From f088fb45537fc74f0fbcbc31a76877266cd5041a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 4 Apr 2024 22:52:42 +0900 Subject: [PATCH 001/192] fix(lane_change): limit prepare and lane changing length (#6734) Signed-off-by: Zulfaqar Azmi --- .../utils/utils.hpp | 17 +++++++++++++++++ .../src/scene.cpp | 11 +++++------ .../src/utils/utils.cpp | 10 ++++++++++ 3 files changed, 32 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index ff5d7bc0773fa..7c8cfdb926a6b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -257,6 +257,23 @@ Polygon2d getEgoCurrentFootprint( bool isWithinIntersection( const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); + +/** + * @brief Calculates the distance required during a lane change operation. + * + * Used for computing prepare or lane change length based on current and maximum velocity, + * acceleration, and duration, returning the lesser of accelerated distance or distance at max + * velocity. + * + * @param velocity The current velocity of the vehicle in meters per second (m/s). + * @param maximum_velocity The maximum velocity the vehicle can reach in meters per second (m/s). + * @param acceleration The acceleration of the vehicle in meters per second squared (m/s^2). + * @param duration The duration of the lane change in seconds (s). + * @return The calculated minimum distance in meters (m). + */ +double calcPhaseLength( + const double velocity, const double maximum_velocity, const double acceleration, + const double time); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index a6d21aede64b6..bc9a366e62b34 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1293,9 +1293,8 @@ bool NormalLaneChange::getLaneChangePaths( (prepare_duration < 1e-3) ? 0.0 : ((prepare_velocity - current_velocity) / prepare_duration); - const double prepare_length = - current_velocity * prepare_duration + - 0.5 * longitudinal_acc_on_prepare * std::pow(prepare_duration, 2); + const auto prepare_length = utils::lane_change::calcPhaseLength( + current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration); auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length); @@ -1347,9 +1346,9 @@ bool NormalLaneChange::getLaneChangePaths( utils::lane_change::calcLaneChangingAcceleration( initial_lane_changing_velocity, max_path_velocity, lane_changing_time, sampled_longitudinal_acc); - const auto lane_changing_length = - initial_lane_changing_velocity * lane_changing_time + - 0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time; + const auto lane_changing_length = utils::lane_change::calcPhaseLength( + initial_lane_changing_velocity, getCommonParam().max_vel, + longitudinal_acc_on_lane_changing, lane_changing_time); const auto terminal_lane_changing_velocity = std::min( initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time, getCommonParam().max_vel); diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 0b4893f94e071..15db6b0055756 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1184,6 +1184,16 @@ bool isWithinIntersection( return boost::geometry::within( polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); } + +double calcPhaseLength( + const double velocity, const double maximum_velocity, const double acceleration, + const double duration) +{ + const auto length_with_acceleration = + velocity * duration + 0.5 * acceleration * std::pow(duration, 2); + const auto length_with_max_velocity = maximum_velocity * duration; + return std::min(length_with_acceleration, length_with_max_velocity); +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug From 7d268799fefe6d326f906315293be1ea150af41f Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 4 Apr 2024 23:23:04 +0900 Subject: [PATCH 002/192] feat(perception_online_evaluator): ignore reversal of orientation from yaw_rate calculation (#6748) Signed-off-by: kosuke55 --- .../src/metrics_calculator.cpp | 13 +++++++++---- .../src/perception_online_evaluator_node.cpp | 1 + 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 20d8c6d570489..4b882bb8b2e68 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -381,12 +381,17 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas if (time_diff < 0.01) { continue; } - const auto current_yaw = + const double current_yaw = tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation); - const auto previous_yaw = + const double previous_yaw = tf2::getYaw(previous_object.kinematics.initial_pose_with_covariance.pose.orientation); - const auto yaw_rate = - std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw) / time_diff); + const double yaw_diff = + std::abs(tier4_autoware_utils::normalizeRadian(current_yaw - previous_yaw)); + // if yaw_diff is close to PI, reversal of orientation is likely occurring, so ignore it + if (std::abs(M_PI - yaw_diff) < 0.1) { + continue; + } + const auto yaw_rate = yaw_diff / time_diff; stat.add(yaw_rate); } metric_stat_map["yaw_rate_" + convertLabelToString(label)] = stat; diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index f3a08bf42797a..ceb304894ad8c 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -214,6 +214,7 @@ rcl_interfaces::msg::SetParametersResult PerceptionOnlineEvaluatorNode::onParame auto & p = parameters_; updateParam(parameters, "smoothing_window_size", p->smoothing_window_size); + updateParam(parameters, "stopped_velocity_threshold", p->stopped_velocity_threshold); // update metrics { From 178841b9cc797bde39a5f47d8074729e0355bc43 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 5 Apr 2024 10:22:46 +0900 Subject: [PATCH 003/192] feat(obstacle_pointcloud_based_validator_node): skip validation when obstacle pointcloud is empty (#6684) * feat: skip validation when obstacle pointcloud is empty Signed-off-by: yoshiri * fix: remove mistakenly unremoved line Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../src/obstacle_pointcloud_based_validator.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp index e39de639a6121..db2e6ec3a7901 100644 --- a/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp +++ b/perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp @@ -327,15 +327,19 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud( // objects_pub_->publish(*input_objects); return; } + bool validation_is_ready = true; if (!validator_->setKdtreeInputCloud(input_obstacle_pointcloud)) { - RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 5, "cannot receive pointcloud"); - return; + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), 5, + "obstacle pointcloud is empty! Can not validate objects."); + validation_is_ready = false; } for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { const auto & transformed_object = transformed_objects.objects.at(i); const auto & object = input_objects->objects.at(i); - const auto validated = validator_->validate_object(transformed_object); + const auto validated = + validation_is_ready ? validator_->validate_object(transformed_object) : false; if (debugger_) { debugger_->addNeighborPointcloud(validator_->getDebugNeighborPointCloud()); debugger_->addPointcloudWithinPolygon(validator_->getDebugPointCloudWithinObject()); From 804600599c546e5947d34666e842d6e29840909a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 5 Apr 2024 10:49:31 +0900 Subject: [PATCH 004/192] feat(lane_change): check prepare phase in turn direction lanes (#6726) * feat(lane_change): check prepare phase in turn direction lanes Signed-off-by: Muhammad Zulfaqar Azmi * Doxygen comment Signed-off-by: Muhammad Zulfaqar Azmi * Add config Signed-off-by: Muhammad Zulfaqar Azmi * fix comments by the reviewer Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_lane_change_module/README.md | 3 ++- .../config/lane_change.param.yaml | 1 + .../utils/data_structs.hpp | 1 + .../utils/utils.hpp | 15 +++++++++++++++ .../src/manager.cpp | 2 ++ .../src/scene.cpp | 10 +++++++++- .../src/utils/utils.cpp | 13 +++++++++++++ 7 files changed, 43 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 17cdc58f5ad47..62f35a053958a 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -554,7 +554,8 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | Name | Unit | Type | Description | Default value | | :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | | `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | -| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | false | +| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true | +| `enable_collision_check_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true | | `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | | `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | | `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | diff --git a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml index 039e8a31ed10f..1ab33514c5f24 100644 --- a/planning/behavior_path_lane_change_module/config/lane_change.param.yaml +++ b/planning/behavior_path_lane_change_module/config/lane_change.param.yaml @@ -92,6 +92,7 @@ enable_collision_check_for_prepare_phase: general_lanes: false intersection: true + turns: true prepare_segment_ignore_object_velocity_thresh: 0.1 # [m/s] check_objects_on_current_lanes: true check_objects_on_other_lanes: true diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp index 0d77135fda242..fdaa15ff9bef9 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/data_structs.hpp @@ -114,6 +114,7 @@ struct LaneChangeParameters // collision check bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; bool enable_collision_check_for_prepare_phase_in_intersection{true}; + bool enable_collision_check_for_prepare_phase_in_turns{true}; double prepare_segment_ignore_object_velocity_thresh{0.1}; bool check_objects_on_current_lanes{true}; bool check_objects_on_other_lanes{true}; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 7c8cfdb926a6b..76331bd98eb9c 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -258,6 +258,21 @@ bool isWithinIntersection( const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); +/** + * @brief Determines if a polygon is within lanes designated for turning. + * + * Checks if a polygon overlaps with lanelets tagged for turning directions (excluding 'straight'). + * It evaluates the lanelet's 'turn_direction' attribute and determines overlap with the lanelet's + * area. + * + * @param lanelet Lanelet representing the road segment whose turn direction is to be evaluated. + * @param polygon The polygon to be checked for its presence within turn direction lanes. + * + * @return bool True if the polygon is within a lane designated for turning, false if it is within a + * straight lane or no turn direction is specified. + */ +bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon); + /** * @brief Calculates the distance required during a lane change operation. * diff --git a/planning/behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_lane_change_module/src/manager.cpp index 7045544df50aa..81d4b86afa094 100644 --- a/planning/behavior_path_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_lane_change_module/src/manager.cpp @@ -72,6 +72,8 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node) *node, parameter("enable_collision_check_for_prepare_phase.general_lanes")); p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter( *node, parameter("enable_collision_check_for_prepare_phase.intersection")); + p.enable_collision_check_for_prepare_phase_in_turns = + getOrDeclareParameter(*node, parameter("enable_collision_check_for_prepare_phase.turns")); p.prepare_segment_ignore_object_velocity_thresh = getOrDeclareParameter( *node, parameter("prepare_segment_ignore_object_velocity_thresh")); p.check_objects_on_current_lanes = diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index bc9a366e62b34..3a4a44ef33edb 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -2142,7 +2142,15 @@ bool NormalLaneChange::check_prepare_phase() const return utils::lane_change::isWithinIntersection(route_handler, current_lane, ego_footprint); }); - return check_in_intersection || check_in_general_lanes; + const auto check_in_turns = std::invoke([&]() { + if (!lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns) { + return false; + } + + return utils::lane_change::isWithinTurnDirectionLanes(current_lane, ego_footprint); + }); + + return check_in_intersection || check_in_turns || check_in_general_lanes; } } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 15db6b0055756..97fcc841a546e 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -37,6 +37,8 @@ #include +#include + #include #include #include @@ -1185,6 +1187,17 @@ bool isWithinIntersection( polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon()))); } +bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Polygon2d & polygon) +{ + const std::string turn_direction = lanelet.attributeOr("turn_direction", "else"); + if (turn_direction == "else" || turn_direction == "straight") { + return false; + } + + return !boost::geometry::disjoint( + polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet.polygon2d().basicPolygon()))); +} + double calcPhaseLength( const double velocity, const double maximum_velocity, const double acceleration, const double duration) From 1eef4c0e102c53e96d30ee701420f388ba29f77d Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 5 Apr 2024 19:05:10 +0900 Subject: [PATCH 005/192] feat(run_out): maintain run out stop wall (#6732) * feat(run_out): maintain run_out stop walls for a given time Signed-off-by: Daniel Sanchez * remove printouts Signed-off-by: Daniel Sanchez * space Signed-off-by: Daniel Sanchez * add stop wall debug markers when maintaining stop points Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../config/run_out.param.yaml | 1 + .../src/manager.cpp | 1 + .../src/scene.cpp | 54 +++++++++++++++---- .../src/scene.hpp | 12 ++++- .../src/utils.hpp | 1 + 5 files changed, 57 insertions(+), 12 deletions(-) diff --git a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml index 628b8725149a2..6d0d9571bf43b 100644 --- a/planning/behavior_velocity_run_out_module/config/run_out.param.yaml +++ b/planning/behavior_velocity_run_out_module/config/run_out.param.yaml @@ -17,6 +17,7 @@ ego_cut_line_length: 3.0 # The width of the ego's cut line ego_footprint_extra_margin: 0.5 # [m] expand the ego vehicles' footprint by this value on all sides when building the ego footprint path keep_obstacle_on_path_time_threshold: 1.0 # [s] How much time a previous run out target obstacle is kept in the run out candidate list if it enters the ego path. + keep_stop_point_time: 1.0 # [s] If a stop point is issued by this module, keep the stop point for this many seconds. Only works if approach is disabled # Parameter to create abstracted dynamic obstacles dynamic_obstacle: diff --git a/planning/behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_run_out_module/src/manager.cpp index e2ce3822bf86d..1c85a22f57bf6 100644 --- a/planning/behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_run_out_module/src/manager.cpp @@ -77,6 +77,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".ego_footprint_extra_margin"); p.keep_obstacle_on_path_time_threshold = getOrDeclareParameter(node, ns + ".keep_obstacle_on_path_time_threshold"); + p.keep_stop_point_time = getOrDeclareParameter(node, ns + ".keep_stop_point_time"); } { diff --git a/planning/behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_run_out_module/src/scene.cpp index 48fbebb8b056d..da826e1cf0cf6 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_run_out_module/src/scene.cpp @@ -144,6 +144,16 @@ bool RunOutModule::modifyPathVelocity( debug_ptr_->setDebugValues( DebugValues::TYPE::CALCULATION_TIME_COLLISION_CHECK, elapsed_collision_check.count() / 1000.0); + // If no new obstacle is detected, we check if the stop point should be maintained for more time. + auto should_maintain_stop_point = [&](const bool is_stopping_point_inserted) -> bool { + if (!stop_point_generation_time_.has_value() || is_stopping_point_inserted) { + return false; + } + const auto now = clock_->now().seconds(); + const double elapsed_time_since_stop_wall_was_generated = + (now - stop_point_generation_time_.value()); + return elapsed_time_since_stop_wall_was_generated < planner_param_.run_out.keep_stop_point_time; + }; // insert stop point for the detected obstacle if (planner_param_.approaching.enable) { // after a certain amount of time has elapsed since the ego stopped, @@ -152,7 +162,23 @@ bool RunOutModule::modifyPathVelocity( dynamic_obstacle, *planner_data_, planner_param_, extended_smoothed_path, *path); } else { // just insert zero velocity for stopping - insertStoppingVelocity(dynamic_obstacle, current_pose, current_vel, current_acc, *path); + std::optional stop_point; + const bool is_stopping_point_inserted = insertStoppingVelocity( + dynamic_obstacle, current_pose, current_vel, current_acc, *path, stop_point); + + stop_point_generation_time_ = (is_stopping_point_inserted) + ? std::make_optional(clock_->now().seconds()) + : stop_point_generation_time_; + last_stop_point_ = (is_stopping_point_inserted) ? stop_point : last_stop_point_; + + const bool is_maintain_stop_point = should_maintain_stop_point(is_stopping_point_inserted); + if (is_maintain_stop_point) { + insertStopPoint(last_stop_point_, *path); + // debug + debug_ptr_->setAccelReason(RunOutDebug::AccelReason::STOP); + debug_ptr_->pushStopPose(tier4_autoware_utils::calcOffsetPose( + *last_stop_point_, planner_param_.vehicle_param.base_to_front, 0, 0)); + } } // apply max jerk limit if the ego can't stop with specified max jerk and acc @@ -230,10 +256,8 @@ std::optional RunOutModule::detectCollision( debug_ptr_->pushCollisionPoints(obstacle_selected->collision_points); debug_ptr_->pushNearestCollisionPoint(obstacle_selected->nearest_collision_point); - return obstacle_selected; } - // no collision detected first_detected_time_.reset(); return {}; @@ -717,14 +741,14 @@ std::optional RunOutModule::calcStopPoint( return stop_point; } -void RunOutModule::insertStopPoint( +bool RunOutModule::insertStopPoint( const std::optional stop_point, autoware_auto_planning_msgs::msg::PathWithLaneId & path) { // no stop point if (!stop_point) { RCLCPP_DEBUG_STREAM(logger_, "already has same point"); - return; + return false; } // find nearest point index behind the stop point @@ -736,15 +760,15 @@ void RunOutModule::insertStopPoint( if ( insert_idx == path.points.size() - 1 && planning_utils::isAheadOf(*stop_point, path.points.at(insert_idx).point.pose)) { - return; + return false; } // to PathPointWithLaneId autoware_auto_planning_msgs::msg::PathPointWithLaneId stop_point_with_lane_id; stop_point_with_lane_id = path.points.at(nearest_seg_idx); stop_point_with_lane_id.point.pose = *stop_point; - planning_utils::insertVelocity(path, stop_point_with_lane_id, 0.0, insert_idx); + return true; } void RunOutModule::insertVelocityForState( @@ -806,14 +830,24 @@ void RunOutModule::insertVelocityForState( } } -void RunOutModule::insertStoppingVelocity( +bool RunOutModule::insertStoppingVelocity( const std::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, PathWithLaneId & output_path) { - const auto stop_point = + std::optional stopping_point; + return insertStoppingVelocity( + dynamic_obstacle, current_pose, current_vel, current_acc, output_path, stopping_point); +} + +bool RunOutModule::insertStoppingVelocity( + const std::optional & dynamic_obstacle, + const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, + PathWithLaneId & output_path, std::optional & stopping_point) +{ + stopping_point = calcStopPoint(dynamic_obstacle, output_path, current_pose, current_vel, current_acc); - insertStopPoint(stop_point, output_path); + return insertStopPoint(stopping_point, output_path); } void RunOutModule::insertApproachingVelocity( diff --git a/planning/behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_run_out_module/src/scene.hpp index c7702ed15337d..3db6051ab36e7 100644 --- a/planning/behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_run_out_module/src/scene.hpp @@ -66,6 +66,9 @@ class RunOutModule : public SceneModuleInterface std::shared_ptr debug_ptr_; std::unique_ptr state_machine_; std::shared_ptr first_detected_time_; + std::optional stop_point_generation_time_; + std::optional last_stop_point_; + std::optional last_stop_obstacle_uuid_; std::unordered_map obstacle_in_ego_path_times_; @@ -119,7 +122,7 @@ class RunOutModule : public SceneModuleInterface const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc) const; - void insertStopPoint( + bool insertStopPoint( const std::optional stop_point, autoware_auto_planning_msgs::msg::PathWithLaneId & path); @@ -128,11 +131,16 @@ class RunOutModule : public SceneModuleInterface const PlannerParam & planner_param, const PathWithLaneId & smoothed_path, PathWithLaneId & output_path); - void insertStoppingVelocity( + bool insertStoppingVelocity( const std::optional & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, PathWithLaneId & output_path); + bool insertStoppingVelocity( + const std::optional & dynamic_obstacle, + const geometry_msgs::msg::Pose & current_pose, const float current_vel, const float current_acc, + PathWithLaneId & output_path, std::optional & stopping_point); + void insertApproachingVelocity( const DynamicObstacle & dynamic_obstacle, const geometry_msgs::msg::Pose & current_pose, const float approaching_vel, const float approach_margin, PathWithLaneId & output_path); diff --git a/planning/behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_run_out_module/src/utils.hpp index 823dc81b2b72b..51b460482458f 100644 --- a/planning/behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_run_out_module/src/utils.hpp @@ -68,6 +68,7 @@ struct RunOutParam double ego_cut_line_length; double ego_footprint_extra_margin; double keep_obstacle_on_path_time_threshold; + double keep_stop_point_time; float detection_distance; float detection_span; float min_vel_ego_kmph; From 35642a6df0a12750256f459b40546e90bcd5c09e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Sebastian=20Z=C4=99derowski?= Date: Sat, 6 Apr 2024 06:55:14 +0200 Subject: [PATCH 006/192] fix(route_handler): exception in route_handler caused by int overflow (#6755) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Remove cast to int which might cause overflow Signed-off-by: Sebastian Zęderowski Co-authored-by: Sebastian Zęderowski --- planning/route_handler/src/route_handler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 8cec5073efb6a..8d143fcf0b87d 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1708,7 +1708,7 @@ PathWithLaneId RouteHandler::getCenterLinePath( // append a point only when having one point so that yaw calculation would work if (reference_path.points.size() == 1) { - const lanelet::Id lane_id = static_cast(reference_path.points.front().lane_ids.front()); + const lanelet::Id lane_id = reference_path.points.front().lane_ids.front(); const auto lanelet = lanelet_map_ptr_->laneletLayer.get(lane_id); const auto point = reference_path.points.front().point.pose.position; const auto lane_yaw = lanelet::utils::getLaneletAngle(lanelet, point); From ad79997a32f331c2ce41ee42e1ccd6ef068ea67e Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 8 Apr 2024 14:22:12 +0900 Subject: [PATCH 007/192] fix(multi_object_tracker): debugger timers checks if the timer is initialized (#6757) fix: debugger timers checks if the timer is initialized Signed-off-by: Taekjin LEE --- .../include/multi_object_tracker/debugger.hpp | 6 ++++ .../multi_object_tracker/src/debugger.cpp | 29 ++++++++++++++++--- .../src/multi_object_tracker_core.cpp | 5 ++++ 3 files changed, 36 insertions(+), 4 deletions(-) diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp index ca1b20d26c25d..858d43dcfc5bd 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp @@ -41,7 +41,10 @@ class TrackerDebugger const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; void startMeasurementTime( const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp); + void endMeasurementTime(const rclcpp::Time & now); + void startPublishTime(const rclcpp::Time & now); void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time); + void setupDiagnostics(); void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); struct DEBUG_SETTINGS @@ -56,12 +59,15 @@ class TrackerDebugger private: void loadParameters(); + bool is_initialized_ = false; rclcpp::Node & node_; rclcpp::Publisher::SharedPtr debug_tentative_objects_pub_; std::unique_ptr processing_time_publisher_; rclcpp::Time last_input_stamp_; rclcpp::Time stamp_process_start_; + rclcpp::Time stamp_process_end_; + rclcpp::Time stamp_publish_start_; rclcpp::Time stamp_publish_output_; }; diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp index e3fc58dd5d692..4304afbe2e055 100644 --- a/perception/multi_object_tracker/src/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -108,16 +108,35 @@ void TrackerDebugger::startMeasurementTime( processing_time_publisher_->publish( "debug/input_latency_ms", input_latency_ms); } + // initialize debug time stamps + if (!is_initialized_) { + stamp_publish_output_ = now; + is_initialized_ = true; + } +} + +void TrackerDebugger::endMeasurementTime(const rclcpp::Time & now) +{ + stamp_process_end_ = now; +} + +void TrackerDebugger::startPublishTime(const rclcpp::Time & now) +{ + stamp_publish_start_ = now; } void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) { const auto current_time = now; - // pipeline latency: time from sensor measurement to publish + // pipeline latency: time from sensor measurement to publish, used for 'checkDelay' pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; - if (debug_settings_.publish_processing_time) { - // processing time: time between input and publish - double processing_time_ms = (current_time - stamp_process_start_).seconds() * 1e3; + if (debug_settings_.publish_processing_time && is_initialized_) { + // processing latency: time between input and publish + double processing_latency_ms = ((current_time - stamp_process_start_).seconds()) * 1e3; + // processing time: only the time spent in the tracking processes + double processing_time_ms = ((current_time - stamp_publish_start_).seconds() + + (stamp_process_end_ - stamp_process_start_).seconds()) * + 1e3; // cycle time: time between two consecutive publish double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; // measurement to tracked-object time: time from the sensor measurement to the publishing object @@ -131,6 +150,8 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim "debug/cyclic_time_ms", cyclic_time_ms); processing_time_publisher_->publish( "debug/processing_time_ms", processing_time_ms); + processing_time_publisher_->publish( + "debug/processing_latency_ms", processing_latency_ms); processing_time_publisher_->publish( "debug/meas_to_tracked_object_ms", measurement_to_object_ms); } diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index b8e19d4ca2df4..aacd37766e8b0 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -190,6 +190,10 @@ void MultiObjectTracker::onMeasurement( if (tracker) list_tracker_.push_back(tracker); } + // debugger time + debugger_->endMeasurementTime(this->now()); + + // Publish objects if the timer is not enabled if (publish_timer_ == nullptr) { publish(measurement_time); } @@ -337,6 +341,7 @@ inline bool MultiObjectTracker::shouldTrackerPublish( void MultiObjectTracker::publish(const rclcpp::Time & time) const { + debugger_->startPublishTime(this->now()); const auto subscriber_count = tracked_objects_pub_->get_subscription_count() + tracked_objects_pub_->get_intra_process_subscription_count(); if (subscriber_count < 1) { From 52bc600edf1b0bba58acf8f3ebc5b73fd992f892 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 8 Apr 2024 14:28:31 +0900 Subject: [PATCH 008/192] docs(mission_planner): update readme for route selector (#6576) Signed-off-by: Takagi, Isamu --- planning/mission_planner/README.md | 67 +- .../media/architecture.drawio.svg | 725 ++++++++++++++++++ .../media/rerouting_interface.svg | 435 ----------- 3 files changed, 759 insertions(+), 468 deletions(-) create mode 100644 planning/mission_planner/media/architecture.drawio.svg delete mode 100644 planning/mission_planner/media/rerouting_interface.svg diff --git a/planning/mission_planner/README.md b/planning/mission_planner/README.md index 3b649168884e6..a9eb488c71377 100644 --- a/planning/mission_planner/README.md +++ b/planning/mission_planner/README.md @@ -7,8 +7,13 @@ The route is made of a sequence of lanes on a static map. Dynamic objects (e.g. pedestrians and other vehicles) and dynamic map information (e.g. road construction which blocks some lanes) are not considered during route planning. Therefore, the output topic is only published when the goal pose or check points are given and will be latched until the new goal pose or check points are given. -The core implementation does not depend on a map format. -In current Autoware.universe, only Lanelet2 map format is supported. +The core implementation does not depend on a map format. Any planning algorithms can be added as plugin modules. +In current Autoware.universe, only the plugin for Lanelet2 map format is supported. + +This package also manages routes for MRM. The `route_selector` node duplicates the `mission_planner` interface and provides it for normal and MRM respectively. +It distributes route requests and planning results according to current MRM operation state. + +![architecture](./media/architecture.drawio.svg) ## Interfaces @@ -28,31 +33,37 @@ In current Autoware.universe, only Lanelet2 map format is supported. ### Services -| Name | Type | Description | -| ------------------------------------------------ | ----------------------------------------- | ------------------------------------------------------------------------------------------- | -| `/planning/mission_planning/clear_route` | autoware_adapi_v1_msgs/srv/ClearRoute | route clear request | -| `/planning/mission_planning/set_route_points` | autoware_adapi_v1_msgs/srv/SetRoutePoints | route request with pose waypoints. Assumed the vehicle is stopped. | -| `/planning/mission_planning/set_route` | autoware_adapi_v1_msgs/srv/SetRoute | route request with lanelet waypoints. Assumed the vehicle is stopped. | -| `/planning/mission_planning/change_route_points` | autoware_adapi_v1_msgs/srv/SetRoutePoints | route change request with pose waypoints. This can be called when the vehicle is moving. | -| `/planning/mission_planning/change_route` | autoware_adapi_v1_msgs/srv/SetRoute | route change request with lanelet waypoints. This can be called when the vehicle is moving. | -| `~/srv/set_mrm_route` | autoware_adapi_v1_msgs/srv/SetRoutePoints | set emergency route. This can be called when the vehicle is moving. | -| `~/srv/clear_mrm_route` | std_srvs/srv/Trigger | clear emergency route. | +| Name | Type | Description | +| ------------------------------------------------------------------- | ---------------------------------------- | ------------------------------------------ | +| `/planning/mission_planning/mission_planner/clear_route` | tier4_planning_msgs/srv/ClearRoute | route clear request | +| `/planning/mission_planning/mission_planner/set_waypoint_route` | tier4_planning_msgs/srv/SetWaypointRoute | route request with lanelet waypoints. | +| `/planning/mission_planning/mission_planner/set_lanelet_route` | tier4_planning_msgs/srv/SetLaneletRoute | route request with pose waypoints. | +| `/planning/mission_planning/route_selector/main/clear_route` | tier4_planning_msgs/srv/ClearRoute | main route clear request | +| `/planning/mission_planning/route_selector/main/set_waypoint_route` | tier4_planning_msgs/srv/SetWaypointRoute | main route request with lanelet waypoints. | +| `/planning/mission_planning/route_selector/main/set_lanelet_route` | tier4_planning_msgs/srv/SetLaneletRoute | main route request with pose waypoints. | +| `/planning/mission_planning/route_selector/mrm/clear_route` | tier4_planning_msgs/srv/ClearRoute | mrm route clear request | +| `/planning/mission_planning/route_selector/mrm/set_waypoint_route` | tier4_planning_msgs/srv/SetWaypointRoute | mrm route request with lanelet waypoints. | +| `/planning/mission_planning/route_selector/mrm/set_lanelet_route` | tier4_planning_msgs/srv/SetLaneletRoute | mrm route request with pose waypoints. | ### Subscriptions -| Name | Type | Description | -| --------------------- | ------------------------------------ | ---------------------- | -| `input/vector_map` | autoware_auto_mapping_msgs/HADMapBin | vector map of Lanelet2 | -| `input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | +| Name | Type | Description | +| ----------------------- | ------------------------------------ | ---------------------- | +| `~/input/vector_map` | autoware_auto_mapping_msgs/HADMapBin | vector map of Lanelet2 | +| `~/input/modified_goal` | geometry_msgs/PoseWithUuidStamped | modified goal pose | ### Publications -| Name | Type | Description | -| ---------------------------------------- | ------------------------------------- | ------------------------ | -| `/planning/mission_planning/route_state` | autoware_adapi_v1_msgs/msg/RouteState | route state | -| `/planning/mission_planning/route` | autoware_planning_msgs/LaneletRoute | route | -| `debug/route_marker` | visualization_msgs/msg/MarkerArray | route marker for debug | -| `debug/goal_footprint` | visualization_msgs/msg/MarkerArray | goal footprint for debug | +| Name | Type | Description | +| ------------------------------------------------------ | ----------------------------------- | ------------------------ | +| `/planning/mission_planning/state` | tier4_planning_msgs/msg/RouteState | route state | +| `/planning/mission_planning/route` | autoware_planning_msgs/LaneletRoute | route | +| `/planning/mission_planning/route_selector/main/state` | tier4_planning_msgs/msg/RouteState | main route state | +| `/planning/mission_planning/route_selector/main/route` | autoware_planning_msgs/LaneletRoute | main route | +| `/planning/mission_planning/route_selector/mrm/state` | tier4_planning_msgs/msg/RouteState | mrm route state | +| `/planning/mission_planning/route_selector/mrm/route` | autoware_planning_msgs/LaneletRoute | mrm route | +| `~/debug/route_marker` | visualization_msgs/msg/MarkerArray | route marker for debug | +| `~/debug/goal_footprint` | visualization_msgs/msg/MarkerArray | goal footprint for debug | ## Route section @@ -168,26 +179,16 @@ And there are three use cases that require reroute. - Emergency route - Goal modification -![rerouting_interface](./media/rerouting_interface.svg) - #### Route change API -- `change_route_points` -- `change_route` - -This is route change that the application makes using the API. It is used when changing the destination while driving or when driving a divided loop route. When the vehicle is driving on a MRM route, normal rerouting by this interface is not allowed. +It is used when changing the destination while driving or when driving a divided loop route. When the vehicle is driving on a MRM route, normal rerouting by this interface is not allowed. #### Emergency route -- `set_mrm_route` -- `clear_mrm_route` - -This interface for the MRM that pulls over the road shoulder. It has to be stopped as soon as possible, so a reroute is required. The MRM route has priority over the normal route. And if MRM route is cleared, try to return to the normal route also with a rerouting safety check. +The interface for the MRM that pulls over the road shoulder. It has to be stopped as soon as possible, so a reroute is required. The MRM route has priority over the normal route. And if MRM route is cleared, try to return to the normal route also with a rerouting safety check. ##### Goal modification -- `modified_goal` - This is a goal change to pull over, avoid parked vehicles, and so on by a planning component. If the modified goal is outside the calculated route, a reroute is required. This goal modification is executed by checking the local environment and path safety as the vehicle actually approaches the destination. And this modification is allowed for both normal_route and mrm_route. The new route generated here is sent to the AD API so that it can also be referenced by the application. Note, however, that the specifications here are subject to change in the future. diff --git a/planning/mission_planner/media/architecture.drawio.svg b/planning/mission_planner/media/architecture.drawio.svg new file mode 100644 index 0000000000000..36be0d683bc06 --- /dev/null +++ b/planning/mission_planner/media/architecture.drawio.svg @@ -0,0 +1,725 @@ + + + + + + + + + + + + + + + +
+
+
+ mission planner +
+ main module +
+
+
+
+ mission planner... +
+
+ + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + +
+
+
+ set waypoint +
+
+
+
+ set waypoint +
+
+ + + + +
+
+
+ clear +
+
+
+
+ clear +
+
+ + + + +
+
+
+ set lanelet +
+
+
+
+ set lanelet +
+
+ + + + +
+
+
+ main route interface +
+
+
+
+ main route interface +
+
+ + + + + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + +
+
+
+ set waypoint +
+
+
+
+ set waypoint +
+
+ + + + +
+
+
+ clear +
+
+
+
+ clear +
+
+ + + + +
+
+
+ set lanelet +
+
+
+
+ set lanelet +
+
+ + + + +
+
+
+ MRM route interface +
+
+
+
+ MRM route interface +
+
+ + + + + + + +
+
+
+ API +
+
+
+
+ API +
+
+ + + + + + + +
+
+
+ fail safe +
+
+
+
+ fail safe +
+
+ + + + + + + + +
+
+
+ route id +
+
+
+
+ route id +
+
+ + + + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ request +
+
+
+
+ request +
+
+ + + + +
+
+
+ route id +
+
+
+
+ route id +
+
+ + + + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + + + +
+
+
+ in mrm +
+
+
+
+ in mrm +
+
+ + + + +
+
+
+ main route data +
+
+
+
+ main route data +
+
+ + + + +
+
+
+ MRM route data +
+
+
+
+ MRM route data +
+
+ + + + + + + + + + +
+
+
+ route +
+
+
+
+ route +
+
+ + + + + + +
+
+
+ state +
+
+
+
+ state +
+
+ + + + +
+
+
+ set waypoint +
+
+
+
+ set waypoint +
+
+ + + + +
+
+
+ clear +
+
+
+
+ clear +
+
+ + + + +
+
+
+ set lanelet +
+
+
+
+ set lanelet +
+
+ + + + +
+
+
+ route interface +
+
+
+
+ route interface +
+
+ + + + +
+
+
+ route selector +
+
+
+
+ route selector +
+
+ + + + + + +
+
+
+ behavior planner +
+
+
+
+ behavior planner +
+
+ + + + + + +
+
+
+ modify goal +
+
+
+
+ modify goal +
+
+ + + + + + + +
+
+
+ mission planner +
+ plugin module +
+
+
+
+ mission planner... +
+
+ + + + +
+
+
+ mission planner +
+
+
+
+ mission planner +
+
+ + + + + + + + + + + + + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/mission_planner/media/rerouting_interface.svg b/planning/mission_planner/media/rerouting_interface.svg deleted file mode 100644 index e19c362611d30..0000000000000 --- a/planning/mission_planner/media/rerouting_interface.svg +++ /dev/null @@ -1,435 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- AD -
- API -
-
-
-
- AD... -
-
- - - - - - - - - - -
-
-
- Mission Planner -
-
-
-
- Mission Planner -
-
- - - - - - -
-
-
- set_route_points -
- (SetRoutePoints.srv) -
-
-
-
- set_route_points... -
-
- - - - - - -
-
-
- set_route -
- (SetRoute.srv) -
-
-
-
- set_route... -
-
- - - - - - -
-
-
- change_route_points -
- (SetRoutePoints.srv) -
-
-
-
- change_route_points... -
-
- - - - - - -
-
-
- change_route -
- (SetRoute.srv) -
-
-
-
- change_route... -
-
- - - - - - -
-
-
- route -
- (Route.msg) -
-
-
-
- route... -
-
- - - - - - -
-
-
- state -
- (RouteState.msg) -
-
-
-
- state... -
-
- - - - - - - - -
-
-
- behavior_path_planner -
-
-
-
- behavior_path_planner -
-
- - - - - - -
-
-
- modified_goal -
- (with uuid) -
-
-
-
- modified_goal... -
-
- - - - -
-
-
- route -
- (with uuid) -
-
-
-
- route... -
-
- - - - - - - - -
-
-
- MRM -
-
-
-
- MRM -
-
- - - - - - -
-
-
- T.B.D. -
- (Request MRM) -
-
-
-
- T.B.D.... -
-
- - - - - - -
-
-
- clear_route -
- (ClearRoute.srv) -
-
-
-
- clear_route... -
-
- - - - - - -
-
-
- clear_mrm_route -
-
-
-
- clear_mrm_route -
-
- - - - -
-
-
- ADAPI -
-
-
-
- ADAPI -
-
- - - - -
-
-
- planning -
-
-
-
- planning -
-
- - - - -
-
-
- system -
-
-
-
- system -
-
- - - - - - -
-
-
- set_mrm_route -
-
-
-
- set_mrm_route -
-
-
- - - - Text is not SVG - cannot display - - -
From 1524bdd813258e5d2b0e342821543da1cdc26092 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 8 Apr 2024 18:17:25 +0900 Subject: [PATCH 009/192] fix(behavior_path_planner): fix behavior_path_planner node to check occupancy_grid before running (#6752) Signed-off-by: Mamoru Sobue --- .../behavior_path_planner/src/behavior_path_planner_node.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index e41061a2ffbd2..1cea9e46cdb7b 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -312,6 +312,10 @@ bool BehaviorPathPlannerNode::isDataReady() return missing("operation_mode"); } + if (!planner_data_->occupancy_grid) { + return missing("occupancy_grid"); + } + return true; } From 86172857ecd6454d682ab38cba06a4230b94c5f5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 8 Apr 2024 19:50:15 +0900 Subject: [PATCH 010/192] fix(avoidance): add update param to use rqt reconfigure (#6759) * fix(avoidance): add update param to use rqt reconfigure Signed-off-by: satoshi-ota * Update planning/behavior_path_avoidance_module/src/manager.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_avoidance_module/src/manager.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --------- Signed-off-by: satoshi-ota Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../parameter_helper.hpp | 4 + .../src/manager.cpp | 98 +++++++++++++++++++ 2 files changed, 102 insertions(+) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index abd0c017a6483..0a62eb5b33e8a 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -313,6 +313,10 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.use_shorten_margin_immediately = getOrDeclareParameter(*node, ns + "use_shorten_margin_immediately"); + if (p.policy_approval != "per_shift_line" && p.policy_approval != "per_avoidance_maneuver") { + throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); + } + if (p.policy_deceleration != "best_effort" && p.policy_deceleration != "reliable") { throw std::domain_error("invalid policy. please select 'best_effort' or 'reliable'."); } diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 692e4260520f3..1f420baf4ae63 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -91,6 +91,76 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorupper_distance_for_polygon_expansion); } + { + const auto set_target_flag = [&](const uint8_t & object_type, const std::string & ns) { + if (p->object_parameters.count(object_type) == 0) { + return; + } + updateParam(parameters, ns, p->object_parameters.at(object_type).is_avoidance_target); + }; + + const std::string ns = "avoidance.target_filtering."; + set_target_flag(ObjectClassification::CAR, ns + "target_type.car"); + set_target_flag(ObjectClassification::TRUCK, ns + "target_type.truck"); + set_target_flag(ObjectClassification::TRAILER, ns + "target_type.trailer"); + set_target_flag(ObjectClassification::BUS, ns + "target_type.bus"); + set_target_flag(ObjectClassification::PEDESTRIAN, ns + "target_type.pedestrian"); + set_target_flag(ObjectClassification::BICYCLE, ns + "target_type.bicycle"); + set_target_flag(ObjectClassification::MOTORCYCLE, ns + "target_type.motorcycle"); + set_target_flag(ObjectClassification::UNKNOWN, ns + "target_type.unknown"); + + updateParam( + parameters, ns + "object_check_goal_distance", p->object_check_goal_distance); + updateParam( + parameters, ns + "object_check_return_pose_distance", p->object_check_return_pose_distance); + updateParam( + parameters, ns + "threshold_distance_object_is_on_center", + p->threshold_distance_object_is_on_center); + updateParam( + parameters, ns + "object_check_shiftable_ratio", p->object_check_shiftable_ratio); + updateParam( + parameters, ns + "object_check_min_road_shoulder_width", + p->object_check_min_road_shoulder_width); + updateParam( + parameters, ns + "object_last_seen_threshold", p->object_last_seen_threshold); + } + + { + const std::string ns = "avoidance.target_filtering.detection_area."; + updateParam(parameters, ns + "static", p->use_static_detection_area); + updateParam( + parameters, ns + "min_forward_distance", p->object_check_min_forward_distance); + updateParam( + parameters, ns + "max_forward_distance", p->object_check_max_forward_distance); + updateParam(parameters, ns + "backward_distance", p->object_check_backward_distance); + } + + { + const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle."; + updateParam(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle); + updateParam( + parameters, ns + "closest_distance_to_wait_and_see", + p->closest_distance_to_wait_and_see_for_ambiguous_vehicle); + updateParam( + parameters, ns + "condition.time_threshold", p->time_threshold_for_ambiguous_vehicle); + updateParam( + parameters, ns + "condition.distance_threshold", p->distance_threshold_for_ambiguous_vehicle); + updateParam( + parameters, ns + "ignore_area.traffic_light.front_distance", + p->object_ignore_section_traffic_light_in_front_distance); + updateParam( + parameters, ns + "ignore_area.crosswalk.front_distance", + p->object_ignore_section_crosswalk_in_front_distance); + updateParam( + parameters, ns + "ignore_area.crosswalk.behind_distance", + p->object_ignore_section_crosswalk_behind_distance); + } + + { + const std::string ns = "avoidance.target_filtering.intersection."; + updateParam(parameters, ns + "yaw_deviation", p->object_check_yaw_deviation); + } + { const std::string ns = "avoidance.avoidance.lateral."; updateParam( @@ -107,6 +177,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "min_prepare_time", p->min_prepare_time); updateParam(parameters, ns + "max_prepare_time", p->max_prepare_time); + updateParam(parameters, ns + "min_prepare_distance", p->min_prepare_distance); updateParam(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed); updateParam(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed); } @@ -117,6 +188,33 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "stop_buffer", p->stop_buffer); } + { + const std::string ns = "avoidance.policy."; + updateParam(parameters, ns + "make_approval_request", p->policy_approval); + updateParam(parameters, ns + "deceleration", p->policy_deceleration); + updateParam(parameters, ns + "lateral_margin", p->policy_lateral_margin); + updateParam( + parameters, ns + "use_shorten_margin_immediately", p->use_shorten_margin_immediately); + + if (p->policy_approval != "per_shift_line" && p->policy_approval != "per_avoidance_maneuver") { + RCLCPP_ERROR( + rclcpp::get_logger(__func__), + "invalid policy. please select 'per_shift_line' or 'per_avoidance_maneuver'."); + } + + if (p->policy_deceleration != "best_effort" && p->policy_deceleration != "reliable") { + RCLCPP_ERROR( + rclcpp::get_logger(__func__), + "invalid deceleration policy. Please select 'best_effort' or 'reliable'."); + } + + if (p->policy_lateral_margin != "best_effort" && p->policy_lateral_margin != "reliable") { + RCLCPP_ERROR( + rclcpp::get_logger(__func__), + "invalid lateral margin policy. Please select 'best_effort' or 'reliable'."); + } + } + { const std::string ns = "avoidance.constrains.lateral."; From b98a21a5ffb71f7e33dc183cfc90c0196240cf7a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 12:13:57 +0900 Subject: [PATCH 011/192] feat(avoidance): limit acceleration during avoidance maneuver (#6698) Signed-off-by: satoshi-ota --- .../config/avoidance.param.yaml | 3 +- .../data_structs.hpp | 3 + .../behavior_path_avoidance_module/helper.hpp | 75 +++++++++++++++++++ .../parameter_helper.hpp | 2 + .../behavior_path_avoidance_module/scene.hpp | 6 ++ .../src/manager.cpp | 13 ++++ .../src/scene.cpp | 47 ++++++++++++ 7 files changed, 148 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index 3c3a086a3514d..b7b8d8434b9c4 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -287,7 +287,8 @@ nominal_jerk: 0.5 # [m/sss] max_deceleration: -1.5 # [m/ss] max_jerk: 1.0 # [m/sss] - max_acceleration: 1.0 # [m/ss] + max_acceleration: 0.5 # [m/ss] + min_velocity_to_limit_max_acceleration: 2.78 # [m/ss] shift_line_pipeline: trim: diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index 686e4023bc7c2..fd841ede37e70 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -143,6 +143,9 @@ struct AvoidanceParameters // To prevent large acceleration while avoidance. double max_acceleration{0.0}; + // To prevent large acceleration while avoidance. + double min_velocity_to_limit_max_acceleration{0.0}; + // upper distance for envelope polygon expansion. double upper_distance_for_polygon_expansion{0.0}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 6d2eb81b328f4..4ff02df97bd89 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -24,6 +24,7 @@ #include #include #include +#include #include namespace behavior_path_planner::helper::avoidance @@ -32,7 +33,10 @@ namespace behavior_path_planner::helper::avoidance using behavior_path_planner::PathShifter; using behavior_path_planner::PlannerData; using motion_utils::calcDecelDistWithJerkAndAccConstraints; +using motion_utils::calcLongitudinalOffsetPose; +using motion_utils::calcSignedArcLength; using motion_utils::findNearestIndex; +using tier4_autoware_utils::getPose; class AvoidanceHelper { @@ -61,6 +65,11 @@ class AvoidanceHelper geometry_msgs::msg::Pose getEgoPose() const { return data_->self_odometry->pose.pose; } + geometry_msgs::msg::Point getEgoPosition() const + { + return data_->self_odometry->pose.pose.position; + } + static size_t getConstraintsMapIndex(const double velocity, const std::vector & values) { const auto itr = std::find_if( @@ -262,6 +271,20 @@ class AvoidanceHelper return *itr; } + std::pair getDistanceToAccelEndPoint(const PathWithLaneId & path) + { + updateAccelEndPoint(path); + + if (!max_v_point_.has_value()) { + return std::make_pair(0.0, std::numeric_limits::max()); + } + + const auto start_idx = data_->findEgoIndex(path.points); + const auto distance = + calcSignedArcLength(path.points, start_idx, max_v_point_.value().first.position); + return std::make_pair(distance, max_v_point_.value().second); + } + double getFeasibleDecelDistance( const double target_velocity, const bool use_hard_constraints = true) const { @@ -367,6 +390,56 @@ class AvoidanceHelper return true; } + void updateAccelEndPoint(const PathWithLaneId & path) + { + const auto & p = parameters_; + const auto & a_now = data_->self_acceleration->accel.accel.linear.x; + if (a_now < 0.0) { + max_v_point_ = std::nullopt; + return; + } + + if (getEgoSpeed() < p->min_velocity_to_limit_max_acceleration) { + max_v_point_ = std::nullopt; + return; + } + + if (max_v_point_.has_value()) { + return; + } + + const auto v0 = getEgoSpeed() + p->buf_slow_down_speed; + + const auto t_neg_jerk = std::max(0.0, a_now - p->max_acceleration) / p->max_jerk; + const auto v_neg_jerk = v0 + a_now * t_neg_jerk + std::pow(t_neg_jerk, 2.0) / 2.0; + const auto x_neg_jerk = v0 * t_neg_jerk + a_now * std::pow(t_neg_jerk, 2.0) / 2.0 + + p->max_jerk * std::pow(t_neg_jerk, 3.0) / 6.0; + + const auto & v_max = data_->parameters.max_vel; + if (v_max < v_neg_jerk) { + max_v_point_ = std::nullopt; + return; + } + + const auto t_max_accel = (v_max - v_neg_jerk) / p->max_acceleration; + const auto x_max_accel = + v_neg_jerk * t_max_accel + p->max_acceleration * std::pow(t_max_accel, 2.0) / 2.0; + + const auto point = + calcLongitudinalOffsetPose(path.points, getEgoPosition(), x_neg_jerk + x_max_accel); + if (point.has_value()) { + max_v_point_ = std::make_pair(point.value(), v_max); + return; + } + + const auto x_end = calcSignedArcLength(path.points, getEgoPosition(), path.points.size() - 1); + const auto t_end = + (std::sqrt(v0 * v0 + 2.0 * p->max_acceleration * x_end) - v0) / p->max_acceleration; + const auto v_end = v0 + p->max_acceleration * t_end; + + max_v_point_ = std::make_pair(getPose(path.points.back()), v_end); + } + void reset() { prev_reference_path_ = PathWithLaneId(); @@ -417,6 +490,8 @@ class AvoidanceHelper ShiftedPath prev_linear_shift_path_; lanelet::ConstLanelets prev_driving_lanes_; + + std::optional> max_v_point_; }; } // namespace behavior_path_planner::helper::avoidance diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index 0a62eb5b33e8a..fbfec58abe4da 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -334,6 +334,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.max_deceleration = getOrDeclareParameter(*node, ns + "max_deceleration"); p.max_jerk = getOrDeclareParameter(*node, ns + "max_jerk"); p.max_acceleration = getOrDeclareParameter(*node, ns + "max_acceleration"); + p.min_velocity_to_limit_max_acceleration = + getOrDeclareParameter(*node, ns + "min_velocity_to_limit_max_acceleration"); } // constraints (lateral) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index 5125191a6e544..899ec99cb0d3b 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -233,6 +233,12 @@ class AvoidanceModule : public SceneModuleInterface */ void insertPrepareVelocity(ShiftedPath & shifted_path) const; + /** + * @brief insert max velocity in output path to limit acceleration. + * @param target path. + */ + void insertAvoidanceVelocity(ShiftedPath & shifted_path) const; + /** * @brief calculate stop distance based on object's overhang. * @param stop distance. diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 1f420baf4ae63..5ce63987621ed 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -244,6 +244,19 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "nominal_deceleration", p->nominal_deceleration); + updateParam(parameters, ns + "nominal_jerk", p->nominal_jerk); + updateParam(parameters, ns + "max_deceleration", p->max_deceleration); + updateParam(parameters, ns + "max_jerk", p->max_jerk); + updateParam(parameters, ns + "max_acceleration", p->max_acceleration); + updateParam( + parameters, ns + "min_velocity_to_limit_max_acceleration", + p->min_velocity_to_limit_max_acceleration); + } + { const std::string ns = "avoidance.shift_line_pipeline."; updateParam( diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 12c59daef93ad..b22a4bf53eab0 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -686,6 +686,7 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif } insertPrepareVelocity(path); + insertAvoidanceVelocity(path); switch (data.state) { case AvoidanceState::NOT_AVOID: { @@ -1725,6 +1726,52 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const shifted_path.path.points, start_idx, distance_to_object); } +void AvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const +{ + const auto & data = avoid_data_; + + // do nothing if no shift line is approved. + if (path_shifter_.getShiftLines().empty()) { + return; + } + + // do nothing if there is no avoidance target. + if (data.target_objects.empty()) { + return; + } + + const auto [distance_to_accel_end_point, v_max] = + helper_->getDistanceToAccelEndPoint(shifted_path.path); + if (distance_to_accel_end_point < 1e-3) { + return; + } + + const auto start_idx = planner_data_->findEgoIndex(shifted_path.path.points); + for (size_t i = start_idx; i < shifted_path.path.points.size(); ++i) { + const auto distance_from_ego = calcSignedArcLength(shifted_path.path.points, start_idx, i); + + // slow down speed is inserted only in front of the object. + const auto accel_distance = distance_to_accel_end_point - distance_from_ego; + if (accel_distance < 0.0) { + break; + } + + const double v_target_square = + v_max * v_max - 2.0 * parameters_->max_acceleration * accel_distance; + if (v_target_square < 1e-3) { + break; + } + + // target speed with nominal jerk limits. + const double v_target = std::max(getEgoSpeed(), std::sqrt(v_target_square)); + const double v_original = shifted_path.path.points.at(i).point.longitudinal_velocity_mps; + shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_target); + } + + slow_pose_ = motion_utils::calcLongitudinalOffsetPose( + shifted_path.path.points, start_idx, distance_to_accel_end_point); +} + std::shared_ptr AvoidanceModule::get_debug_msg_array() const { debug_data_.avoidance_debug_msg_array.header.stamp = clock_->now(); From d6824423c3f6cd75fd451fd6bdef7a53aea77719 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 12:21:08 +0900 Subject: [PATCH 012/192] fix(tier4_autoware_utils): fix `-Werror=unused-parameter` (#6764) fix(tier4_autoware_utils): fix -Werror=unused-parameter Signed-off-by: satoshi-ota --- .../include/tier4_autoware_utils/ros/polling_subscriber.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp index f4d230e15dcf1..f8d5baaf02777 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp @@ -38,7 +38,8 @@ class InterProcessPollingSubscriber noexec_subscription_options.callback_group = noexec_callback_group; subscriber_ = node->create_subscription( - topic_name, rclcpp::QoS{1}, [node](const typename T::ConstSharedPtr msg) { assert(false); }, + topic_name, rclcpp::QoS{1}, + [node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); }, noexec_subscription_options); }; bool updateLatestData() From b09501e78e8cb09d7e91d264389114190255a39e Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 9 Apr 2024 13:01:35 +0900 Subject: [PATCH 013/192] feat(lane_change): use external velocity limit in safety check (#6760) * feat(lane_change): use external velocity limit in safety check Signed-off-by: Muhammad Zulfaqar * style(pre-commit): autofix * Minor refactoring Signed-off-by: Muhammad Zulfaqar * Fix spell check and remove headers Signed-off-by: Muhammad Zulfaqar Azmi * Add warning Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../behavior_path_lane_change_module/scene.hpp | 2 ++ .../src/scene.cpp | 13 ++++++++++++- .../behavior_path_planner_node.hpp | 6 ++++++ .../src/behavior_path_planner_node.cpp | 18 ++++++++++++++++++ .../data_manager.hpp | 3 +++ .../utils/path_safety_checker/safety_check.hpp | 2 +- .../utils/path_safety_checker/safety_check.cpp | 10 ++++++---- 7 files changed, 48 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 0eec0ce75f622..7a76daff4bc55 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -172,6 +172,8 @@ class NormalLaneChange : public LaneChangeBase bool isVehicleStuck( const lanelet::ConstLanelets & current_lanes, const double obstacle_check_distance) const; + double get_max_velocity_for_safety_check() const; + bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const; bool check_prepare_phase() const; diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 3a4a44ef33edb..db96f7c83d72a 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1967,7 +1967,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( for (const auto & obj_path : obj_predicted_paths) { const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons( path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0, - current_debug_data.second); + get_max_velocity_for_safety_check(), current_debug_data.second); if (collided_polygons.empty()) { utils::path_safety_checker::updateCollisionCheckDebugMap( @@ -2062,6 +2062,17 @@ bool NormalLaneChange::isVehicleStuck( return false; } +double NormalLaneChange::get_max_velocity_for_safety_check() const +{ + const auto external_velocity_limit_ptr = planner_data_->external_limit_max_velocity; + if (external_velocity_limit_ptr) { + return std::min( + static_cast(external_velocity_limit_ptr->max_velocity), getCommonParam().max_vel); + } + + return getCommonParam().max_vel; +} + bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const { if (current_lanes.empty()) { diff --git a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp index 99e312f98f100..5a49f4d9ab66e 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/behavior_path_planner_node.hpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include @@ -103,6 +104,8 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr modified_goal_publisher_; rclcpp::Publisher::SharedPtr stop_reason_publisher_; rclcpp::Publisher::SharedPtr reroute_availability_publisher_; + rclcpp::Subscription::SharedPtr + external_limit_max_velocity_subscriber_; rclcpp::TimerBase::SharedPtr timer_; std::map::SharedPtr> path_candidate_publishers_; @@ -142,6 +145,9 @@ class BehaviorPathPlannerNode : public rclcpp::Node void onRoute(const LaneletRoute::ConstSharedPtr route_msg); void onOperationMode(const OperationModeState::ConstSharedPtr msg); void onLateralOffset(const LateralOffset::ConstSharedPtr msg); + void on_external_velocity_limiter( + const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); + SetParametersResult onSetParam(const std::vector & parameters); OnSetParametersCallbackHandle::SharedPtr m_set_param_res; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index 1cea9e46cdb7b..d250fd97c3aec 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -112,6 +112,11 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod current_scenario_ = std::make_shared(*msg); }, createSubscriptionOptions(this)); + external_limit_max_velocity_subscriber_ = + create_subscription( + "/planning/scenario_planning/max_velocity", 1, + std::bind(&BehaviorPathPlannerNode::on_external_velocity_limiter, this, _1), + createSubscriptionOptions(this)); // route_handler vector_map_subscriber_ = create_subscription( @@ -821,6 +826,19 @@ void BehaviorPathPlannerNode::onOperationMode(const OperationModeState::ConstSha const std::lock_guard lock(mutex_pd_); planner_data_->operation_mode = msg; } + +void BehaviorPathPlannerNode::on_external_velocity_limiter( + const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) +{ + // Note: Using this parameter during path planning might cause unexpected deceleration or jerk. + // Therefore, do not use it for anything other than safety checks. + if (!msg) { + return; + } + + const std::lock_guard lock(mutex_pd_); + planner_data_->external_limit_max_velocity = msg; +} void BehaviorPathPlannerNode::onLateralOffset(const LateralOffset::ConstSharedPtr msg) { std::lock_guard lock(mutex_pd_); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp index d196f2bc551bb..09f3c2c66bcd4 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include @@ -65,6 +66,7 @@ using route_handler::RouteHandler; using tier4_planning_msgs::msg::LateralOffset; using PlanResult = PathWithLaneId::SharedPtr; using lanelet::TrafficLight; +using tier4_planning_msgs::msg::VelocityLimit; using unique_identifier_msgs::msg::UUID; struct TrafficSignalStamped @@ -161,6 +163,7 @@ struct PlannerData std::map traffic_light_id_map; BehaviorPathPlannerParameters parameters{}; drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{}; + VelocityLimit::ConstSharedPtr external_limit_max_velocity{}; mutable std::vector drivable_area_expansion_prev_path_poses{}; mutable std::vector drivable_area_expansion_prev_curvatures{}; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 13009d5114439..53c4706e49c10 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -141,7 +141,7 @@ std::vector getCollidedPolygons( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - const double hysteresis_factor, CollisionCheckDebug & debug); + const double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug); bool checkPolygonsIntersects( const std::vector & polys_1, const std::vector & polys_2); diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index e15a3c164bef1..6390c45376b37 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -26,6 +26,8 @@ #include #include +#include + namespace behavior_path_planner::utils::path_safety_checker { @@ -560,7 +562,7 @@ bool checkCollision( { const auto collided_polygons = getCollidedPolygons( planned_path, predicted_ego_path, target_object, target_object_path, common_parameters, - rss_parameters, hysteresis_factor, debug); + rss_parameters, hysteresis_factor, std::numeric_limits::max(), debug); return collided_polygons.empty(); } @@ -570,7 +572,7 @@ std::vector getCollidedPolygons( const ExtendedPredictedObject & target_object, const PredictedPathWithPolygon & target_object_path, const BehaviorPathPlannerParameters & common_parameters, const RSSparams & rss_parameters, - double hysteresis_factor, CollisionCheckDebug & debug) + double hysteresis_factor, const double max_velocity_limit, CollisionCheckDebug & debug) { { debug.ego_predicted_path = predicted_ego_path; @@ -586,7 +588,7 @@ std::vector getCollidedPolygons( // get object information at current time const auto & obj_pose = obj_pose_with_poly.pose; const auto & obj_polygon = obj_pose_with_poly.poly; - const auto & object_velocity = obj_pose_with_poly.velocity; + const auto object_velocity = obj_pose_with_poly.velocity; // get ego information at current time // Note: we can create these polygons in advance. However, it can decrease the readability and @@ -599,7 +601,7 @@ std::vector getCollidedPolygons( } const auto & ego_pose = interpolated_data->pose; const auto & ego_polygon = interpolated_data->poly; - const auto & ego_velocity = interpolated_data->velocity; + const auto ego_velocity = std::min(interpolated_data->velocity, max_velocity_limit); // check overlap if (boost::geometry::overlaps(ego_polygon, obj_polygon)) { From d340d10fbbbb04eb1ba614bb05f3f4d3b110792c Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 9 Apr 2024 15:24:21 +0900 Subject: [PATCH 014/192] fix(multi_object_tracker): mot timer bug fix (#6775) * fix: set object timestamp type to follow node time fix: remove comment Signed-off-by: Taekjin LEE * fix: add initialization checkers Signed-off-by: Taekjin LEE * fix: timestamp initialization Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker/src/debugger.cpp | 40 ++++++++++++------- .../src/multi_object_tracker_core.cpp | 11 +++-- 2 files changed, 32 insertions(+), 19 deletions(-) diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp index 4304afbe2e055..b5632a13e78fc 100644 --- a/perception/multi_object_tracker/src/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -18,12 +18,7 @@ #include -TrackerDebugger::TrackerDebugger(rclcpp::Node & node) -: diagnostic_updater_(&node), - node_(node), - last_input_stamp_(node.now()), - stamp_process_start_(node.now()), - stamp_publish_output_(node.now()) +TrackerDebugger::TrackerDebugger(rclcpp::Node & node) : diagnostic_updater_(&node), node_(node) { // declare debug parameters to decide whether to publish debug topics loadParameters(); @@ -39,7 +34,15 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node) "debug/tentative_objects", rclcpp::QoS{1}); } - // initialize stop watch and diagnostics + // initialize timestamps + const rclcpp::Time now = node_.now(); + last_input_stamp_ = now; + stamp_process_start_ = now; + stamp_process_end_ = now; + stamp_publish_start_ = now; + stamp_publish_output_ = now; + + // setup diagnostics setupDiagnostics(); } @@ -73,7 +76,11 @@ void TrackerDebugger::loadParameters() void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) { - const double delay = pipeline_latency_ms_; // [s] + if (!is_initialized_) { + stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Measurement time is not set."); + return; + } + const double & delay = pipeline_latency_ms_; // [s] if (delay == 0.0) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated."); @@ -127,18 +134,21 @@ void TrackerDebugger::startPublishTime(const rclcpp::Time & now) void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time) { - const auto current_time = now; + // if the measurement time is not set, do not publish debug information + if (!is_initialized_) return; + // pipeline latency: time from sensor measurement to publish, used for 'checkDelay' - pipeline_latency_ms_ = (current_time - last_input_stamp_).seconds() * 1e3; - if (debug_settings_.publish_processing_time && is_initialized_) { + pipeline_latency_ms_ = (now - last_input_stamp_).seconds() * 1e3; + + if (debug_settings_.publish_processing_time) { // processing latency: time between input and publish - double processing_latency_ms = ((current_time - stamp_process_start_).seconds()) * 1e3; + double processing_latency_ms = ((now - stamp_process_start_).seconds()) * 1e3; // processing time: only the time spent in the tracking processes - double processing_time_ms = ((current_time - stamp_publish_start_).seconds() + + double processing_time_ms = ((now - stamp_publish_start_).seconds() + (stamp_process_end_ - stamp_process_start_).seconds()) * 1e3; // cycle time: time between two consecutive publish - double cyclic_time_ms = (current_time - stamp_publish_output_).seconds() * 1e3; + double cyclic_time_ms = (now - stamp_publish_output_).seconds() * 1e3; // measurement to tracked-object time: time from the sensor measurement to the publishing object // time If there is not latency compensation, this value is zero double measurement_to_object_ms = (object_time - last_input_stamp_).seconds() * 1e3; @@ -155,5 +165,5 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim processing_time_publisher_->publish( "debug/meas_to_tracked_object_ms", measurement_to_object_ms); } - stamp_publish_output_ = current_time; + stamp_publish_output_ = now; } diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index aacd37766e8b0..8ff69ffaeaa9a 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -135,10 +135,14 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) void MultiObjectTracker::onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) { + // Get the time of the measurement + const rclcpp::Time measurement_time = + rclcpp::Time(input_objects_msg->header.stamp, this->now().get_clock_type()); + /* keep the latest input stamp and check transform*/ - debugger_->startMeasurementTime(this->now(), rclcpp::Time(input_objects_msg->header.stamp)); - const auto self_transform = getTransformAnonymous( - tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); + debugger_->startMeasurementTime(this->now(), measurement_time); + const auto self_transform = + getTransformAnonymous(tf_buffer_, "base_link", world_frame_id_, measurement_time); if (!self_transform) { return; } @@ -150,7 +154,6 @@ void MultiObjectTracker::onMeasurement( return; } /* tracker prediction */ - const rclcpp::Time measurement_time = input_objects_msg->header.stamp; for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { (*itr)->predict(measurement_time); } From f5c30eb55e52d52412a71369cb44eaab775f8ea4 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 9 Apr 2024 16:15:15 +0900 Subject: [PATCH 015/192] feat(multi_object_tracker): reduce publish delay (#6710) * feat: implement a new publish timer Signed-off-by: Taekjin LEE * chore: add comments for new variables Signed-off-by: Taekjin LEE * fix: variable name was wrong Signed-off-by: Taekjin LEE fix: reduce lower limit of publish interval Signed-off-by: Taekjin LEE fix: enlarge publish range upper limit Signed-off-by: Taekjin LEE fix: set parameter tested and agreed Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker_core.hpp | 10 ++-- .../src/multi_object_tracker_core.cpp | 48 +++++++++++++------ 2 files changed, 41 insertions(+), 17 deletions(-) diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index 94cc7185bd518..fe41f97cb5a77 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -58,7 +58,11 @@ class MultiObjectTracker : public rclcpp::Node tracked_objects_pub_; rclcpp::Subscription::SharedPtr detected_object_sub_; - rclcpp::TimerBase::SharedPtr publish_timer_; // publish timer + + // publish timer + rclcpp::TimerBase::SharedPtr publish_timer_; + rclcpp::Time last_published_time_; + double publisher_period_; // debugger class std::unique_ptr debugger_; @@ -79,14 +83,14 @@ class MultiObjectTracker : public rclcpp::Node std::unique_ptr data_association_; void checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform); + std::list> & list_tracker, const rclcpp::Time & time); void sanitizeTracker( std::list> & list_tracker, const rclcpp::Time & time); std::shared_ptr createNewTracker( const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) const; + void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; }; diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 8ff69ffaeaa9a..785038fb513c9 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -68,6 +68,7 @@ boost::optional getTransformAnonymous( MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), + last_published_time_(this->now()), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { @@ -83,7 +84,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) create_publisher("output", rclcpp::QoS{1}); // Parameters - double publish_rate = declare_parameter("publish_rate"); + double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; @@ -94,11 +95,15 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) this->get_node_base_interface(), this->get_node_timers_interface()); tf_buffer_.setCreateTimerInterface(cti); - // Create ROS time based timer + // Create ROS time based timer. + // If the delay compensation is enabled, the timer is used to publish the output at the correct + // time. if (enable_delay_compensation) { - const auto period_ns = rclcpp::Rate(publish_rate).period(); + publisher_period_ = 1.0 / publish_rate; // [s] + constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check + const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period(); publish_timer_ = rclcpp::create_timer( - this, get_clock(), period_ns, std::bind(&MultiObjectTracker::onTimer, this)); + this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this)); } const auto tmp = this->declare_parameter>("can_assign_matrix"); @@ -179,7 +184,7 @@ void MultiObjectTracker::onMeasurement( } /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, measurement_time, *self_transform); + checkTrackerLifeCycle(list_tracker_, measurement_time); /* sanitize trackers */ sanitizeTracker(list_tracker_, measurement_time); @@ -198,7 +203,14 @@ void MultiObjectTracker::onMeasurement( // Publish objects if the timer is not enabled if (publish_timer_ == nullptr) { + // Publish if the delay compensation is disabled publish(measurement_time); + } else { + // Publish if the next publish time is close + const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period + if ((this->now() - last_published_time_).seconds() > minimum_publish_interval) { + checkAndPublish(this->now()); + } } } @@ -232,24 +244,32 @@ std::shared_ptr MultiObjectTracker::createNewTracker( void MultiObjectTracker::onTimer() { const rclcpp::Time current_time = this->now(); - const auto self_transform = - getTransformAnonymous(tf_buffer_, world_frame_id_, "base_link", current_time); - if (!self_transform) { - return; + // check the publish period + const auto elapsed_time = (current_time - last_published_time_).seconds(); + // if the elapsed time is over the period, publish objects with prediction + constexpr double maximum_latency_ratio = 1.11; // 11% margin + const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio; + if (elapsed_time > maximum_publish_latency) { + checkAndPublish(current_time); } +} +void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time) +{ /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, current_time, *self_transform); + checkTrackerLifeCycle(list_tracker_, time); /* sanitize trackers */ - sanitizeTracker(list_tracker_, current_time); + sanitizeTracker(list_tracker_, time); // Publish - publish(current_time); + publish(time); + + // Update last published time + last_published_time_ = this->now(); } void MultiObjectTracker::checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time, - [[maybe_unused]] const geometry_msgs::msg::Transform & self_transform) + std::list> & list_tracker, const rclcpp::Time & time) { /* params */ constexpr float max_elapsed_time = 1.0; From 094f3e6710f06acec009d3ddad41aafefb000381 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 9 Apr 2024 20:36:43 +0900 Subject: [PATCH 016/192] chore(ground_segmentation): add tuning param (#6753) * chore(ground_segmentation): add tuning param Signed-off-by: badai-nguyen * fix: and param into yaml file Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: typo Signed-off-by: badai-nguyen * chore: refactor Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- .../config/ground_segmentation.param.yaml | 1 + .../config/scan_ground_filter.param.yaml | 1 + .../ground_segmentation/docs/scan-ground-filter.md | 1 + .../scan_ground_filter_nodelet.hpp | 4 +++- .../src/scan_ground_filter_nodelet.cpp | 11 +++++++---- .../test/test_scan_ground_filter.cpp | 3 +++ 6 files changed, 16 insertions(+), 5 deletions(-) diff --git a/perception/ground_segmentation/config/ground_segmentation.param.yaml b/perception/ground_segmentation/config/ground_segmentation.param.yaml index 756882391183e..594ef1fe974b2 100644 --- a/perception/ground_segmentation/config/ground_segmentation.param.yaml +++ b/perception/ground_segmentation/config/ground_segmentation.param.yaml @@ -33,3 +33,4 @@ center_pcl_shift: 0.0 radial_divider_angle_deg: 1.0 use_recheck_ground_cluster: true + use_lowest_point: true diff --git a/perception/ground_segmentation/config/scan_ground_filter.param.yaml b/perception/ground_segmentation/config/scan_ground_filter.param.yaml index bc02a1ab7e6e7..35d494a620b19 100644 --- a/perception/ground_segmentation/config/scan_ground_filter.param.yaml +++ b/perception/ground_segmentation/config/scan_ground_filter.param.yaml @@ -15,3 +15,4 @@ center_pcl_shift: 0.0 radial_divider_angle_deg: 1.0 use_recheck_ground_cluster: true + use_lowest_point: true diff --git a/perception/ground_segmentation/docs/scan-ground-filter.md b/perception/ground_segmentation/docs/scan-ground-filter.md index 21df6fa6ea1b9..d4eb9c6f3addf 100644 --- a/perception/ground_segmentation/docs/scan-ground-filter.md +++ b/perception/ground_segmentation/docs/scan-ground-filter.md @@ -50,6 +50,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref | `low_priority_region_x` | float | -20.0 | The non-zero x threshold in back side from which small objects detection is low priority [m] | | `elevation_grid_mode` | bool | true | Elevation grid scan mode option | | `use_recheck_ground_cluster` | bool | true | Enable recheck ground cluster | +| `use_lowest_point` | bool | true | to select lowest point for reference in recheck ground cluster, otherwise select middle point | ## Assumptions / Known limits diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp index d017d06929702..d97bbaa2118e5 100644 --- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp @@ -194,6 +194,8 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter split_height_distance_; // useful for close points bool use_virtual_ground_point_; bool use_recheck_ground_cluster_; // to enable recheck ground cluster + bool use_lowest_point_; // to select lowest point for reference in recheck ground cluster, + // otherwise select middle point size_t radial_dividers_num_; VehicleInfo vehicle_info_; @@ -258,7 +260,7 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter * @param non_ground_indices Output non-ground PointCloud indices */ void recheckGroundCluster( - PointsCentroid & gnd_cluster, const float non_ground_threshold, + PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point, pcl::PointIndices & non_ground_indices); /*! * Returns the resulting complementary PointCloud, one with the points kept diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 7a0333d95075b..34573b564fa36 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -57,6 +57,7 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & split_height_distance_ = declare_parameter("split_height_distance"); use_virtual_ground_point_ = declare_parameter("use_virtual_ground_point"); use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster"); + use_lowest_point_ = declare_parameter("use_lowest_point"); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo(); @@ -316,14 +317,15 @@ void ScanGroundFilterComponent::checkBreakGndGrid( } void ScanGroundFilterComponent::recheckGroundCluster( - PointsCentroid & gnd_cluster, const float non_ground_threshold, + PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point, pcl::PointIndices & non_ground_indices) { - const float min_gnd_height = gnd_cluster.getMinHeight(); + float reference_height = + use_lowest_point ? gnd_cluster.getMinHeight() : gnd_cluster.getAverageHeight(); const pcl::PointIndices & gnd_indices = gnd_cluster.getIndicesRef(); const std::vector & height_list = gnd_cluster.getHeightListRef(); for (size_t i = 0; i < height_list.size(); ++i) { - if (height_list.at(i) >= min_gnd_height + non_ground_threshold) { + if (height_list.at(i) >= reference_height + non_ground_threshold) { non_ground_indices.indices.push_back(gnd_indices.indices.at(i)); } } @@ -403,7 +405,8 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan( if (p->grid_id > prev_p->grid_id && ground_cluster.getAverageRadius() > 0.0) { // check if the prev grid have ground point cloud if (use_recheck_ground_cluster_) { - recheckGroundCluster(ground_cluster, non_ground_height_threshold_, out_no_ground_indices); + recheckGroundCluster( + ground_cluster, non_ground_height_threshold_, use_lowest_point_, out_no_ground_indices); } curr_gnd_grid.radius = ground_cluster.getAverageRadius(); curr_gnd_grid.avg_height = ground_cluster.getAverageHeight(); diff --git a/perception/ground_segmentation/test/test_scan_ground_filter.cpp b/perception/ground_segmentation/test/test_scan_ground_filter.cpp index 444a38ea44754..e48bd36d8c54e 100644 --- a/perception/ground_segmentation/test/test_scan_ground_filter.cpp +++ b/perception/ground_segmentation/test/test_scan_ground_filter.cpp @@ -83,6 +83,7 @@ class ScanGroundFilterTest : public ::testing::Test rclcpp::Parameter("radial_divider_angle_deg", radial_divider_angle_deg_)); parameters.emplace_back( rclcpp::Parameter("use_recheck_ground_cluster", use_recheck_ground_cluster_)); + parameters.emplace_back(rclcpp::Parameter("use_lowest_point", use_lowest_point_)); options.parameter_overrides(parameters); @@ -157,6 +158,7 @@ class ScanGroundFilterTest : public ::testing::Test center_pcl_shift_ = params["center_pcl_shift"].as(); radial_divider_angle_deg_ = params["radial_divider_angle_deg"].as(); use_recheck_ground_cluster_ = params["use_recheck_ground_cluster"].as(); + use_lowest_point_ = params["use_lowest_point"].as(); } float global_slope_max_angle_deg_ = 0.0; @@ -174,6 +176,7 @@ class ScanGroundFilterTest : public ::testing::Test float center_pcl_shift_; float radial_divider_angle_deg_; bool use_recheck_ground_cluster_; + bool use_lowest_point_; }; TEST_F(ScanGroundFilterTest, TestCase1) From 9cbd02d7dd5c505ec604efca73d6eb61442ee2bd Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 20:59:21 +0900 Subject: [PATCH 017/192] fix(avoidance): bug in the logic to judge whether it's a parked vehicle (#6768) fix(avoidance): adjacent lane check for ambiguous stopped vehicle Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/utils.hpp | 4 -- .../src/scene.cpp | 1 - .../src/utils.cpp | 45 +++---------------- 3 files changed, 5 insertions(+), 45 deletions(-) diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index 9dc23ea4ec80e..3f1d3495e51cb 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -85,10 +85,6 @@ lanelet::ConstLanelets getAdjacentLane( const std::shared_ptr & planner_data, const std::shared_ptr & parameters, const bool is_right_shift); -lanelet::ConstLanelets getTargetLanelets( - const std::shared_ptr & planner_data, lanelet::ConstLanelets & route_lanelets, - const double left_offset, const double right_offset); - lanelet::ConstLanelets getCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data); diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index b22a4bf53eab0..a7430efd1c860 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -318,7 +318,6 @@ void AvoidanceModule::fillAvoidanceTargetObjects( using utils::avoidance::fillAvoidanceNecessity; using utils::avoidance::fillObjectStoppableJudge; using utils::avoidance::filterTargetObjects; - using utils::avoidance::getTargetLanelets; using utils::avoidance::separateObjectsByPath; using utils::avoidance::updateRoadShoulderDistance; using utils::traffic_light::calcDistanceToRedTrafficLight; diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index fdb2b9b71c782..6c2b72db0237d 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -575,9 +575,11 @@ bool isNeverAvoidanceTarget( } if (object.is_on_ego_lane) { - if ( - planner_data->route_handler->getRightLanelet(object.overhang_lanelet).has_value() && - planner_data->route_handler->getLeftLanelet(object.overhang_lanelet).has_value()) { + const auto right_lane = + planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, false); + const auto left_lane = + planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false); + if (right_lane.has_value() && left_lane.has_value()) { object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it."); return true; @@ -1219,43 +1221,6 @@ std::vector generateObstaclePolygonsForDrivableArea( return obstacles_for_drivable_area; } -lanelet::ConstLanelets getTargetLanelets( - const std::shared_ptr & planner_data, lanelet::ConstLanelets & route_lanelets, - const double left_offset, const double right_offset) -{ - const auto & rh = planner_data->route_handler; - - lanelet::ConstLanelets target_lanelets{}; - for (const auto & lane : route_lanelets) { - auto l_offset = 0.0; - auto r_offset = 0.0; - - const auto opt_left_lane = rh->getLeftLanelet(lane); - if (opt_left_lane) { - target_lanelets.push_back(opt_left_lane.value()); - } else { - l_offset = left_offset; - } - - const auto opt_right_lane = rh->getRightLanelet(lane); - if (opt_right_lane) { - target_lanelets.push_back(opt_right_lane.value()); - } else { - r_offset = right_offset; - } - - const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane); - if (!right_opposite_lanes.empty()) { - target_lanelets.push_back(right_opposite_lanes.front()); - } - - const auto expand_lane = lanelet::utils::getExpandedLanelet(lane, l_offset, r_offset); - target_lanelets.push_back(expand_lane); - } - - return target_lanelets; -} - lanelet::ConstLanelets getCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data) { From c3b727f002e0400130e891909a868d3b75ee6d1e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 9 Apr 2024 22:14:00 +0900 Subject: [PATCH 018/192] fix(avoidance): fix margin param inconsistency (#6765) Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/src/scene.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index a7430efd1c860..33f58c6a08dfc 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -641,7 +641,10 @@ void AvoidanceModule::fillDebugData( const auto constant_distance = helper_->getFrontConstantDistance(o_front); const auto & vehicle_width = planner_data_->parameters.vehicle_width; - const auto max_avoid_margin = object_parameter.lateral_hard_margin * o_front.distance_factor + + const auto lateral_hard_margin = o_front.is_parked + ? object_parameter.lateral_hard_margin_for_parked_vehicle + : object_parameter.lateral_hard_margin; + const auto max_avoid_margin = lateral_hard_margin * o_front.distance_factor + object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto avoidance_distance = helper_->getSharpAvoidanceDistance( @@ -1431,7 +1434,10 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto avoid_margin = object_parameter.lateral_hard_margin * object.distance_factor + + const auto lateral_hard_margin = object.is_parked + ? object_parameter.lateral_hard_margin_for_parked_vehicle + : object_parameter.lateral_hard_margin; + const auto avoid_margin = lateral_hard_margin * object.distance_factor + object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto avoidance_distance = helper_->getMinAvoidanceDistance( helper_->getShiftLength(object, utils::avoidance::isOnRight(object), avoid_margin)); @@ -1675,7 +1681,10 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const const auto & vehicle_width = planner_data_->parameters.vehicle_width; const auto object_type = utils::getHighestProbLabel(object.value().object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto avoid_margin = object_parameter.lateral_hard_margin * object.value().distance_factor + + const auto lateral_hard_margin = object.value().is_parked + ? object_parameter.lateral_hard_margin_for_parked_vehicle + : object_parameter.lateral_hard_margin; + const auto avoid_margin = lateral_hard_margin * object.value().distance_factor + object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto shift_length = helper_->getShiftLength( object.value(), utils::avoidance::isOnRight(object.value()), avoid_margin); From fd1a27e053823fb6a3e38522b4c884deb5a9809d Mon Sep 17 00:00:00 2001 From: Aswin <130948783+4swinv@users.noreply.github.com> Date: Wed, 10 Apr 2024 11:35:35 +0900 Subject: [PATCH 019/192] fix(freespace_planning_algorithms): fix issue of astar search planner not reaching goal pose (#6562) fix(freespace_planning_algorithms): fix issue of freespace planner not reaching goal pose --- .../src/astar_search.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/planning/freespace_planning_algorithms/src/astar_search.cpp b/planning/freespace_planning_algorithms/src/astar_search.cpp index 1ab5e9d5df487..3cc3801575116 100644 --- a/planning/freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/freespace_planning_algorithms/src/astar_search.cpp @@ -292,6 +292,17 @@ void AstarSearch::setPath(const AstarNode & goal_node) // From the goal node to the start node const AstarNode * node = &goal_node; + // push exact goal pose first + geometry_msgs::msg::PoseStamped pose; + pose.header = header; + pose.pose = local2global(costmap_, goal_pose_); + + PlannerWaypoint pw; + pw.pose = pose; + pw.is_back = node->is_back; + waypoints_.waypoints.push_back(pw); + + // push astar nodes poses while (node != nullptr) { geometry_msgs::msg::PoseStamped pose; pose.header = header; From 2b48d25ac6d32c7617be8d098b78c76df6101560 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 10 Apr 2024 11:53:01 +0900 Subject: [PATCH 020/192] docs(dynamic_avoidance): fix sentence (#6782) * fix confusing sentence Signed-off-by: Yuki Takagi --- .../README.md | 23 +++++++++---------- 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_dynamic_avoidance_module/README.md b/planning/behavior_path_dynamic_avoidance_module/README.md index 10276db0efab2..89a661d66735e 100644 --- a/planning/behavior_path_dynamic_avoidance_module/README.md +++ b/planning/behavior_path_dynamic_avoidance_module/README.md @@ -4,15 +4,16 @@ This module is under development. ## Purpose / Role -This module provides avoidance functions for vehicles, pedestrians, and obstacles in the vicinity of the ego's path in combination with the obstacle_avoidance module. +This module provides avoidance functions for vehicles, pedestrians, and obstacles in the vicinity of the ego's path in combination with the [obstacle_avoidance_planner](https://autowarefoundation.github.io/autoware.universe/main/planning/obstacle_avoidance_planner/). Each module performs the following roles. -Dynamic Avoidance module: This module cuts off the drivable area according to the position and velocity of the target to be avoided. -Obstacle Avoidance module: This module modifies the path to be followed so that it fits within the drivable area received. +Dynamic Avoidance module cuts off the drivable area according to the position and velocity of the target to be avoided. +Obstacle Avoidance module modifies the path to be followed so that it fits within the received drivable area. -Avoidance functions are also provided by the Avoidance module, which allows avoidance through the outside of own lanes but not against moving objects. +Avoidance functions are also provided by the [Avoidance module](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_avoidance_module/), but these modules have different roles. +The Avoidance module performs avoidance through the outside of own lanes but cannot avoid the moving objects. On the other hand, this module can avoid moving objects. -For this reason, the word "dynamic" is used in its name. -The table below lists the avoidance modules that can be used for each situation. +For this reason, the word "dynamic" is used in the modules's name. +The table below lists the avoidance modules that can handle each situation. | | avoid within the own lane | avoid through the outside of own lanes | | :----------------------- | :------------------------------------------------------------------------: | :------------------------------------: | @@ -23,7 +24,6 @@ The table below lists the avoidance modules that can be used for each situation. Here, we describe the policy of inner algorithms. The inner algorithms can be separated into two parts: The first decide whether to avoid the obstacles and the second cuts off the drivable area against the corresponding obstacle. -If you are interested in more details, please see the code itself. ### Select obstacles to avoid @@ -31,11 +31,10 @@ To decide whether to avoid an object, both the predicted path and the state (pos The type of objects the user wants this module to avoid is also required. Using this information, the module decides to _avoid_ objects that _obstruct the ego's passage_ and _can be avoided_. -The definition of _obstruct own passage_ is implemented as the object that collides within seconds. -This process wastes computational cost by doing it for all objects; thus, filtering by the relative position and speed of the object with respect to the ego's path is also done as an auxiliary process. -The other, _can be avoided_ denotes whether it can be avoided without risk to passengers or other vehicles. -For this purpose, it is judged whether the obstacle can be avoided by satisfying the constraints of lateral acceleration and lateral jerk. -For example, the module decides not to avoid an object that is too close or fast in the lateral direction because it cannot be avoided. +The definition of _obstruct the ego's passage_ is implemented as the object that collides within seconds. +The other, _can be avoided_ denotes whether it can be avoided without risk to the passengers or the other vehicles. +For this purpose, the module judges whether the obstacle can be avoided with satisfying the constraints of lateral acceleration and lateral jerk. +For example, the module decides not to avoid an object that is too close or fast in the lateral direction. ### Cuts off the drivable area against the selected obstacles From 81c432e8110ca54acc5e6fc4a757eff87724c39b Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 10 Apr 2024 13:16:21 +0900 Subject: [PATCH 021/192] chore(multi_object_tracker): change node and glog implementation (#6780) * chore: change node and glog impl Signed-off-by: Taekjin LEE * style(pre-commit): autofix --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> --- .../multi_object_tracker/CMakeLists.txt | 10 +++--- .../src/multi_object_tracker_core.cpp | 4 --- .../src/multi_object_tracker_node.cpp | 34 +++++++++++++++++++ 3 files changed, 40 insertions(+), 8 deletions(-) create mode 100644 perception/multi_object_tracker/src/multi_object_tracker_node.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 8d835fec20a9b..185ca175df2b6 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -47,12 +47,14 @@ ament_auto_add_library(multi_object_tracker_node SHARED target_link_libraries(multi_object_tracker_node Eigen3::Eigen - glog::glog ) -rclcpp_components_register_node(multi_object_tracker_node - PLUGIN "MultiObjectTracker" - EXECUTABLE multi_object_tracker +ament_auto_add_executable(${PROJECT_NAME} + src/multi_object_tracker_node.cpp +) + +target_link_libraries(${PROJECT_NAME} + multi_object_tracker_node glog ) ament_auto_package(INSTALL_TO_SHARE diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 785038fb513c9..220d1104b33ee 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -72,10 +72,6 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { - // glog for debug - google::InitGoogleLogging("multi_object_tracker"); - google::InstallFailureSignalHandler(); - // Create publishers and subscribers detected_object_sub_ = create_subscription( "input", rclcpp::QoS{1}, diff --git a/perception/multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp new file mode 100644 index 0000000000000..f20aedf16efef --- /dev/null +++ b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp @@ -0,0 +1,34 @@ +// Copyright 2024 TIER IV, inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "multi_object_tracker/multi_object_tracker_core.hpp" + +#include + +#include + +int main(int argc, char ** argv) +{ + google::InitGoogleLogging(argv[0]); // NOLINT + google::InstallFailureSignalHandler(); + + rclcpp::init(argc, argv); + rclcpp::NodeOptions options; + auto multi_object_tracker = std::make_shared(options); + rclcpp::executors::SingleThreadedExecutor exec; + exec.add_node(multi_object_tracker); + exec.spin(); + rclcpp::shutdown(); + return 0; +} From 9f915019c9eaa4a1ecd0b20dc77c6c603ceac407 Mon Sep 17 00:00:00 2001 From: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Date: Thu, 11 Apr 2024 09:52:56 +0900 Subject: [PATCH 022/192] feat(fault injection): change for diagnostic graph aggregator (#6750) * feat: change to adapt diagnostic graph aggregator Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * Change the configuration to adapt to both system_error_monitor and diagnostic_graph_aggregator Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * pre-commit fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * spell check fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * clang-tidy fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * pre-commit fix Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * style(pre-commit): autofix * fix datatype Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> * cleanup code Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> --------- Signed-off-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Tomohito ANDO --- simulator/fault_injection/README.md | 4 +- .../config/fault_injection.param.yaml | 64 ++--- .../fault_injection_diag_updater.hpp | 244 ++++++++++++++++++ .../fault_injection/fault_injection_node.hpp | 18 +- .../fault_injection_node.cpp | 43 +-- .../test/config/test_event_diag.param.yaml | 6 +- .../test/test_fault_injection_node.test.py | 6 +- 7 files changed, 298 insertions(+), 87 deletions(-) create mode 100644 simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp diff --git a/simulator/fault_injection/README.md b/simulator/fault_injection/README.md index cbac41ebfb640..cb3d6fea96a7a 100644 --- a/simulator/fault_injection/README.md +++ b/simulator/fault_injection/README.md @@ -27,7 +27,9 @@ launch_test test/test_fault_injection_node.test.py ### Output -None. +| Name | Type | Description | +| -------------- | --------------------------------------- | ----------------- | +| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | Dummy diagnostics | ## Parameters diff --git a/simulator/fault_injection/config/fault_injection.param.yaml b/simulator/fault_injection/config/fault_injection.param.yaml index ac02442d70b4d..e9e90a336348e 100644 --- a/simulator/fault_injection/config/fault_injection.param.yaml +++ b/simulator/fault_injection/config/fault_injection.param.yaml @@ -1,37 +1,37 @@ /**: ros__parameters: event_diag_list: - vehicle_is_out_of_lane: "lane_departure" - trajectory_deviation_is_high: "trajectory_deviation" - localization_matching_score_is_low: "ndt_scan_matcher" - localization_accuracy_is_low: "localization_error_ellipse" - map_version_is_different: "map_version" - trajectory_is_invalid: "trajectory_point_validation" - cpu_temperature_is_high: "CPU Temperature" - cpu_usage_is_high: "CPU Usage" - cpu_is_in_thermal_throttling: "CPU Thermal Throttling" - storage_temperature_is_high: "HDD Temperature" - storage_usage_is_high: "HDD Usage" - network_usage_is_high: "Network Usage" - clock_error_is_large: "NTP Offset" - gpu_temperature_is_high: "GPU Temperature" - gpu_usage_is_high: "GPU Usage" - gpu_memory_usage_is_high: "GPU Memory Usage" - gpu_is_in_thermal_throttling: "GPU Thermal Throttling" - driving_recorder_storage_error: "driving_recorder" - debug_data_logger_storage_error: "bagpacker" - emergency_stop_operation: "emergency_stop_operation" - vehicle_error_occurred: "vehicle_errors" - vehicle_ecu_connection_is_lost: "can_bus_connection" - obstacle_crash_sensor_is_activated: "obstacle_crash" + vehicle_is_out_of_lane: ": lane_departure" + trajectory_deviation_is_high: ": trajectory_deviation" + localization_matching_score_is_low: ": ndt_scan_matcher" + localization_accuracy_is_low: ": localization_error_ellipse" + map_version_is_different: ": map_version" + trajectory_is_invalid: ": trajectory_point_validation" + cpu_temperature_is_high: ": CPU Temperature" + cpu_usage_is_high: ": CPU Usage" + cpu_is_in_thermal_throttling: ": CPU Thermal Throttling" + storage_temperature_is_high: ": HDD Temperature" + storage_usage_is_high: ": HDD Usage" + network_usage_is_high: ": Network Usage" + clock_error_is_large: ": NTP Offset" + gpu_temperature_is_high: ": GPU Temperature" + gpu_usage_is_high: ": GPU Usage" + gpu_memory_usage_is_high: ": GPU Memory Usage" + gpu_is_in_thermal_throttling: ": GPU Thermal Throttling" + driving_recorder_storage_error: ": driving_recorder" + debug_data_logger_storage_error: ": bagpacker" + emergency_stop_operation: ": emergency_stop_operation" + vehicle_error_occurred: ": vehicle_errors" + vehicle_ecu_connection_is_lost: ": can_bus_connection" + obstacle_crash_sensor_is_activated: ": obstacle_crash" /control/command_gate/node_alive_monitoring: "vehicle_cmd_gate: heartbeat" - /control/autonomous_driving/node_alive_monitoring: "control_topic_status" + /control/autonomous_driving/node_alive_monitoring: ": control_topic_status" /control/external_command_selector/node_alive_monitoring: "external_cmd_selector: heartbeat" - /localization/node_alive_monitoring: "localization_topic_status" - /map/node_alive_monitoring: "map_topic_status" - /planning/node_alive_monitoring: "planning_topic_status" - /sensing/lidar/node_alive_monitoring: "lidar_topic_status" - /sensing/imu/node_alive_monitoring: "imu_connection" - /sensing/gnss/node_alive_monitoring: "gnss_connection" - /system/node_alive_monitoring: "system_topic_status" - /vehicle/node_alive_monitoring: "vehicle_topic_status" + /localization/node_alive_monitoring: ": localization_topic_status" + /map/node_alive_monitoring: ": map_topic_status" + /planning/node_alive_monitoring: ": planning_topic_status" + /sensing/lidar/node_alive_monitoring: ": lidar_topic_status" + /sensing/imu/node_alive_monitoring: ": imu_connection" + /sensing/gnss/node_alive_monitoring: ": gnss_connection" + /system/node_alive_monitoring: ": system_topic_status" + /vehicle/node_alive_monitoring: ": vehicle_topic_status" diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp new file mode 100644 index 0000000000000..948c2b45f6615 --- /dev/null +++ b/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp @@ -0,0 +1,244 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#ifndef FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ +#define FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ + +#include + +#include +#include +#include +#include + +namespace fault_injection +{ +class FaultInjectionDiagUpdater : public diagnostic_updater::DiagnosticTaskVector +{ +public: + template + explicit FaultInjectionDiagUpdater(NodeT node, double period = 1.0) + : FaultInjectionDiagUpdater( + node->get_node_base_interface(), node->get_node_clock_interface(), + node->get_node_logging_interface(), node->get_node_timers_interface(), + node->get_node_topics_interface(), period) + { + } + + FaultInjectionDiagUpdater( + const std::shared_ptr & base_interface, + const std::shared_ptr & clock_interface, + const std::shared_ptr & logging_interface, + std::shared_ptr timers_interface, + std::shared_ptr topics_interface, + double period = 1.0) + : base_interface_(base_interface), + timers_interface_(std::move(timers_interface)), + clock_(clock_interface->get_clock()), + period_(rclcpp::Duration::from_nanoseconds(static_cast(period * 1e9))), + publisher_(rclcpp::create_publisher( + topics_interface, "/diagnostics", 1)), + logger_(logging_interface->get_logger()), + node_name_(base_interface->get_name()) + { + reset_timer(); + } + + /** + * \brief Returns the interval between updates. + */ + [[nodiscard]] auto get_period() const { return period_; } + + /** + * \brief Sets the period as a rclcpp::Duration + */ + void set_period(const rclcpp::Duration & period) + { + period_ = period; + reset_timer(); + } + + /** + * \brief Sets the period given a value in seconds + */ + void set_period(double period) + { + set_period(rclcpp::Duration::from_nanoseconds(static_cast(period * 1e9))); + } + + /** + * \brief Forces to send out an update for all known DiagnosticStatus. + */ + void force_update() { update(); } + + /** + * \brief Output a message on all the known DiagnosticStatus. + * + * Useful if something drastic is happening such as shutdown or a + * self-test. + * + * \param lvl Level of the diagnostic being output. + * + * \param msg Status message to output. + */ + void broadcast(int lvl, const std::string & msg) + { + std::vector status_vec; + + const std::vector & tasks = getTasks(); + for (const auto & task : tasks) { + diagnostic_updater::DiagnosticStatusWrapper status; + + status.name = task.getName(); + status.summary(lvl, msg); + + status_vec.push_back(status); + } + + publish(status_vec); + } + + void set_hardware_id_f(const char * format, ...) + { + va_list va; + const int k_buffer_size = 1000; + char buff[1000]; // @todo This could be done more elegantly. + va_start(va, format); + if (vsnprintf(buff, k_buffer_size, format, va) >= k_buffer_size) { + RCLCPP_DEBUG(logger_, "Really long string in diagnostic_updater::setHardwareIDf."); + } + hardware_id_ = std::string(buff); + va_end(va); + } + + void set_hardware_id(const std::string & hardware_id) { hardware_id_ = hardware_id; } + +private: + void reset_timer() + { + update_timer_ = rclcpp::create_timer( + base_interface_, timers_interface_, clock_, period_, + std::bind(&FaultInjectionDiagUpdater::update, this)); + } + + /** + * \brief Causes the diagnostics to update if the inter-update interval + * has been exceeded. + */ + void update() + { + if (rclcpp::ok()) { + std::vector status_vec; + + std::unique_lock lock( + lock_); // Make sure no adds happen while we are processing here. + const std::vector & tasks = getTasks(); + for (const auto & task : tasks) { + diagnostic_updater::DiagnosticStatusWrapper status; + + status.name = task.getName(); + status.level = 2; + status.message = "No message was set"; + status.hardware_id = hardware_id_; + + task.run(status); + + status_vec.push_back(status); + } + + publish(status_vec); + } + } + + /** + * Publishes a single diagnostic status. + */ + void publish(diagnostic_msgs::msg::DiagnosticStatus & stat) + { + std::vector status_vec; + status_vec.push_back(stat); + publish(status_vec); + } + + /** + * Publishes a vector of diagnostic statuses. + */ + void publish(std::vector & status_vec) + { + diagnostic_msgs::msg::DiagnosticArray msg; + msg.status = status_vec; + msg.header.stamp = clock_->now(); + publisher_->publish(msg); + } + + /** + * Causes a placeholder DiagnosticStatus to be published as soon as a + * diagnostic task is added to the Updater. + */ + void addedTaskCallback(DiagnosticTaskInternal & task) override + { + diagnostic_updater::DiagnosticStatusWrapper stat; + stat.name = task.getName(); + stat.summary(0, "Node starting up"); + publish(stat); + } + + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr base_interface_; + rclcpp::node_interfaces::NodeTimersInterface::SharedPtr timers_interface_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Duration period_; + rclcpp::TimerBase::SharedPtr update_timer_; + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Logger logger_; + + std::string hardware_id_; + std::string node_name_; +}; +} // namespace fault_injection + +#endif // FAULT_INJECTION__FAULT_INJECTION_DIAG_UPDATER_HPP_ diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp index 0f578ff343a17..999d18b38c7b0 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp +++ b/simulator/fault_injection/include/fault_injection/fault_injection_node.hpp @@ -16,8 +16,8 @@ #define FAULT_INJECTION__FAULT_INJECTION_NODE_HPP_ #include "fault_injection/diagnostic_storage.hpp" +#include "fault_injection/fault_injection_diag_updater.hpp" -#include #include #include @@ -36,23 +36,15 @@ class FaultInjectionNode : public rclcpp::Node private: // Subscribers - void onSimulationEvents(const SimulationEvents::ConstSharedPtr msg); + void on_simulation_events(const SimulationEvents::ConstSharedPtr msg); rclcpp::Subscription::SharedPtr sub_simulation_events_; - // Parameter Server - rcl_interfaces::msg::SetParametersResult onSetParam( - const std::vector & params); - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - - void updateEventDiag( + void update_event_diag( diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name); - void addDiag( - const diagnostic_msgs::msg::DiagnosticStatus & status, diagnostic_updater::Updater & updater); - - std::vector readEventDiagList(); + std::vector read_event_diag_list(); - diagnostic_updater::Updater updater_; + FaultInjectionDiagUpdater updater_; DiagnosticStorage diagnostic_storage_; }; diff --git a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp index 9b86fa2de4294..7b8f87400beab 100644 --- a/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp +++ b/simulator/fault_injection/src/fault_injection_node/fault_injection_node.cpp @@ -43,30 +43,26 @@ using rosidl_generator_traits::to_yaml; FaultInjectionNode::FaultInjectionNode(rclcpp::NodeOptions node_options) : Node("fault_injection", node_options.automatically_declare_parameters_from_overrides(true)), - updater_(this) + updater_(this, 0.05) { - updater_.setHardwareID("fault_injection"); + updater_.set_hardware_id("fault_injection"); using std::placeholders::_1; - // Parameter Server - set_param_res_ = - this->add_on_set_parameters_callback(std::bind(&FaultInjectionNode::onSetParam, this, _1)); - // Subscriber sub_simulation_events_ = this->create_subscription( "~/input/simulation_events", rclcpp::QoS{rclcpp::KeepLast(10)}, - std::bind(&FaultInjectionNode::onSimulationEvents, this, _1)); + std::bind(&FaultInjectionNode::on_simulation_events, this, _1)); // Load all config - for (const auto & diag : readEventDiagList()) { + for (const auto & diag : read_event_diag_list()) { diagnostic_storage_.registerEvent(diag); updater_.add( - diag.diag_name, std::bind(&FaultInjectionNode::updateEventDiag, this, _1, diag.sim_name)); + diag.diag_name, std::bind(&FaultInjectionNode::update_event_diag, this, _1, diag.sim_name)); } } -void FaultInjectionNode::onSimulationEvents(const SimulationEvents::ConstSharedPtr msg) +void FaultInjectionNode::on_simulation_events(const SimulationEvents::ConstSharedPtr msg) { RCLCPP_DEBUG(this->get_logger(), "Received data: %s", to_yaml(*msg).c_str()); for (const auto & event : msg->fault_injection_events) { @@ -76,7 +72,7 @@ void FaultInjectionNode::onSimulationEvents(const SimulationEvents::ConstSharedP } } -void FaultInjectionNode::updateEventDiag( +void FaultInjectionNode::update_event_diag( diagnostic_updater::DiagnosticStatusWrapper & wrap, const std::string & event_name) { const auto diag = diagnostic_storage_.getDiag(event_name); @@ -86,30 +82,7 @@ void FaultInjectionNode::updateEventDiag( wrap.hardware_id = diag.hardware_id; } -rcl_interfaces::msg::SetParametersResult FaultInjectionNode::onSetParam( - const std::vector & params) -{ - rcl_interfaces::msg::SetParametersResult result; - - RCLCPP_DEBUG(this->get_logger(), "call onSetParam"); - - try { - double value; - if (tier4_autoware_utils::updateParam(params, "diagnostic_updater.period", value)) { - updater_.setPeriod(value); - } - } catch (const rclcpp::exceptions::InvalidParameterTypeException & e) { - result.successful = false; - result.reason = e.what(); - return result; - } - - result.successful = true; - result.reason = "success"; - return result; -} - -std::vector FaultInjectionNode::readEventDiagList() +std::vector FaultInjectionNode::read_event_diag_list() { // Expected parameter name is "event_diag_list.param_name". // In this case, depth is 2. diff --git a/simulator/fault_injection/test/config/test_event_diag.param.yaml b/simulator/fault_injection/test/config/test_event_diag.param.yaml index 83f58fcc455ee..d9006d239b924 100644 --- a/simulator/fault_injection/test/config/test_event_diag.param.yaml +++ b/simulator/fault_injection/test/config/test_event_diag.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: event_diag_list: - cpu_temperature: "CPU Temperature" - cpu_usage: "CPU Usage" - cpu_load_average: "CPU Load Average" + cpu_temperature: ": CPU Temperature" + cpu_usage: ": CPU Usage" + cpu_load_average: ": CPU Load Average" diff --git a/simulator/fault_injection/test/test_fault_injection_node.test.py b/simulator/fault_injection/test/test_fault_injection_node.test.py index 4556aaaca8d80..1437d69b1c91b 100644 --- a/simulator/fault_injection/test/test_fault_injection_node.test.py +++ b/simulator/fault_injection/test/test_fault_injection_node.test.py @@ -167,11 +167,11 @@ def test_receive_multiple_message_simultaneously(self): # Verify the latest message for stat in msg_buffer[-1].status: - if stat.name == "fault_injection: CPU Load Average": + if stat.name == ": CPU Load Average": self.assertEqual(stat.level, DiagnosticStatus.OK) - elif stat.name == "fault_injection: CPU Temperature": + elif stat.name == ": CPU Temperature": self.assertEqual(stat.level, DiagnosticStatus.ERROR) - elif stat.name == "fault_injection: CPU Usage": + elif stat.name == ": CPU Usage": self.assertEqual(stat.level, DiagnosticStatus.ERROR) else: self.fail(f"Unexpected status name: {stat.name}") From c381661ba4a20b1054d28a95467835e95424b30a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 11 Apr 2024 11:56:09 +0900 Subject: [PATCH 023/192] refactor(static_centerline_optimizer): admit I/F for other sources of centerline (#6783) * refactor(static_centerline_optimizer): admit I/F for other sources of centerline Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../static_centerline_optimizer.param.yaml | 1 + .../static_centerline_optimizer_node.hpp | 21 +++-- .../src/static_centerline_optimizer_node.cpp | 84 ++++++++++++------- 3 files changed, 68 insertions(+), 38 deletions(-) diff --git a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml index f62c34496e024..4fdee8a0ca6fc 100644 --- a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml +++ b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml @@ -1,4 +1,5 @@ /**: ros__parameters: + centerline_source: "optimization_trajectory_base" # select from "optimization_trajectory_base" and "bag_ego_trajectory_base" marker_color: ["FF0000", "00FF00", "0000FF"] marker_color_dist_thresh : [0.1, 0.2, 0.3] diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index 3e6aafd3a9954..a920139a94472 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -44,6 +44,11 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node void run(); private: + struct CenterlineWithRoute + { + std::vector centerline{}; + std::vector route_lane_ids{}; + }; // load map void load_map(const std::string & lanelet2_input_file_path); void on_load_map( @@ -56,6 +61,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response); // plan path + CenterlineWithRoute generate_centerline_with_route(); std::vector plan_path(const std::vector & route_lane_ids); std::vector optimize_trajectory(const Path & raw_path) const; void on_plan_path( @@ -65,8 +71,8 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node const std::vector & route_lane_ids, const std::vector & optimized_traj_points); void save_map( - const std::string & lanelet2_output_file_path, const std::vector & route_lane_ids, - const std::vector & optimized_traj_points); + const std::string & lanelet2_output_file_path, + const CenterlineWithRoute & centerline_with_route); lanelet::LaneletMapPtr original_map_ptr_{nullptr}; HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; @@ -75,12 +81,13 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node int traj_start_index_{0}; int traj_end_index_{0}; - struct MetaDataToSaveMap - { - std::vector optimized_traj_points{}; - std::vector route_lane_ids{}; + std::optional centerline_with_route_{std::nullopt}; + + enum class CenterlineSource { + OptimizationTrajectoryBase = 0, + BagEgoTrajectoryBase, }; - std::optional meta_data_to_save_map_{std::nullopt}; + CenterlineSource centerline_source_; // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index ea7e1c302fd68..0feebe8cbceb6 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -240,46 +240,44 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( sub_traj_start_index_ = create_subscription( "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!meta_data_to_save_map_ || traj_end_index_ + 1 < msg.data) { + if (!centerline_with_route_ || traj_end_index_ + 1 < msg.data) { return; } traj_start_index_ = msg.data; - const auto & d = meta_data_to_save_map_; - const auto selected_optimized_traj_points = std::vector( - d->optimized_traj_points.begin() + traj_start_index_, - d->optimized_traj_points.begin() + traj_end_index_ + 1); + const auto & c = *centerline_with_route_; + const auto selected_centerline = std::vector( + c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( - selected_optimized_traj_points, createHeader(this->now()))); + pub_optimized_centerline_->publish( + motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_traj_end_index_ = create_subscription( "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!meta_data_to_save_map_ || msg.data + 1 < traj_start_index_) { + if (!centerline_with_route_ || msg.data + 1 < traj_start_index_) { return; } traj_end_index_ = msg.data; - const auto & d = meta_data_to_save_map_; - const auto selected_optimized_traj_points = std::vector( - d->optimized_traj_points.begin() + traj_start_index_, - d->optimized_traj_points.begin() + traj_end_index_ + 1); + const auto & c = *centerline_with_route_; + const auto selected_centerline = std::vector( + c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - pub_optimized_centerline_->publish(motion_utils::convertToTrajectory( - selected_optimized_traj_points, createHeader(this->now()))); + pub_optimized_centerline_->publish( + motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { const auto lanelet2_output_file_path = tier4_autoware_utils::getOrDeclareParameter( *this, "lanelet2_output_file_path"); - if (!meta_data_to_save_map_ || msg.data) { - const auto & d = meta_data_to_save_map_; - const auto selected_optimized_traj_points = std::vector( - d->optimized_traj_points.begin() + traj_start_index_, - d->optimized_traj_points.begin() + traj_end_index_ + 1); - save_map(lanelet2_output_file_path, d->route_lane_ids, selected_optimized_traj_points); + if (!centerline_with_route_ || msg.data) { + const auto & c = *centerline_with_route_; + const auto selected_centerline = std::vector( + c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); + save_map( + lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); } }); @@ -306,6 +304,17 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( // vehicle info vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + + centerline_source_ = [&]() { + const auto centerline_source_param = declare_parameter("centerline_source"); + if (centerline_source_param == "optimization_trajectory_base") { + return CenterlineSource::OptimizationTrajectoryBase; + } else if (centerline_source_param == "bag_ego_trajectory_base") { + return CenterlineSource::BagEgoTrajectoryBase; + } + throw std::logic_error( + "The centerline source is not supported in static_centerline_optimizer."); + }(); } void StaticCenterlineOptimizerNode::run() @@ -314,18 +323,31 @@ void StaticCenterlineOptimizerNode::run() const auto lanelet2_input_file_path = declare_parameter("lanelet2_input_file_path"); const auto lanelet2_output_file_path = declare_parameter("lanelet2_output_file_path"); - const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); - const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); // process load_map(lanelet2_input_file_path); - const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); - const auto optimized_traj_points = plan_path(route_lane_ids); + const auto centerline_with_route = generate_centerline_with_route(); traj_start_index_ = 0; - traj_end_index_ = optimized_traj_points.size() - 1; - save_map(lanelet2_output_file_path, route_lane_ids, optimized_traj_points); + traj_end_index_ = centerline_with_route.centerline.size() - 1; + save_map(lanelet2_output_file_path, centerline_with_route); + + centerline_with_route_ = centerline_with_route; +} + +StaticCenterlineOptimizerNode::CenterlineWithRoute +StaticCenterlineOptimizerNode::generate_centerline_with_route() +{ + if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { + const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); + const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); + const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + const auto optimized_traj_points = plan_path(route_lane_ids); + return CenterlineWithRoute{optimized_traj_points, route_lane_ids}; + } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { + return CenterlineWithRoute{}; + } - meta_data_to_save_map_ = MetaDataToSaveMap{optimized_traj_points, route_lane_ids}; + throw std::logic_error("The centerline source is not supported in static_centerline_optimizer."); } void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) @@ -741,17 +763,17 @@ void StaticCenterlineOptimizerNode::evaluate( } void StaticCenterlineOptimizerNode::save_map( - const std::string & lanelet2_output_file_path, const std::vector & route_lane_ids, - const std::vector & optimized_traj_points) + const std::string & lanelet2_output_file_path, const CenterlineWithRoute & centerline_with_route) { if (!route_handler_ptr_) { return; } - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto & c = centerline_with_route; + const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); // update centerline in map - utils::update_centerline(*route_handler_ptr_, route_lanelets, optimized_traj_points); + utils::update_centerline(*route_handler_ptr_, route_lanelets, c.centerline); RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line From 5807f7a36835ee3258d524db9683d199a911be88 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 11 Apr 2024 13:21:27 +0900 Subject: [PATCH 024/192] feat(multi_object_tracker): process modulation (#6742) * fix: reduce lower limit of publish interval Signed-off-by: Taekjin LEE * fix: enlarge publish range upper limit Signed-off-by: Taekjin LEE * fix: set parameter tested and agreed Signed-off-by: Taekjin LEE * fix: define functions on each tracking steps Signed-off-by: Taekjin LEE * fix: remove time argument to avoid misuse Signed-off-by: Taekjin LEE * fix: refine function inputs and outputs Signed-off-by: Taekjin LEE * fix: create tracking process class Signed-off-by: Taekjin LEE * chore: clean up Signed-off-by: Taekjin LEE * fix: move processor to subfolder Signed-off-by: Taekjin LEE * fix: output filter is moved to the processor side Signed-off-by: Taekjin LEE * fix: rename tracker management process, process parameter Signed-off-by: Taekjin LEE * chore: revise comments Signed-off-by: Taekjin LEE * fix: remove not-related dependency Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker/CMakeLists.txt | 1 + .../include/multi_object_tracker/debugger.hpp | 1 + .../multi_object_tracker_core.hpp | 36 +-- .../processor/processor.hpp | 79 +++++ perception/multi_object_tracker/package.xml | 1 - .../src/multi_object_tracker_core.cpp | 292 +++++------------- .../src/processor/processor.cpp | 242 +++++++++++++++ 7 files changed, 414 insertions(+), 238 deletions(-) create mode 100644 perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp create mode 100644 perception/multi_object_tracker/src/processor/processor.cpp diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 185ca175df2b6..41d150ef0ba1b 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -23,6 +23,7 @@ include_directories( set(MULTI_OBJECT_TRACKER_SRC src/multi_object_tracker_core.cpp src/debugger.cpp + src/processor/processor.cpp src/data_association/data_association.cpp src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp src/tracker/motion_model/motion_model_base.cpp diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp index 858d43dcfc5bd..90291ae6fec18 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp @@ -56,6 +56,7 @@ class TrackerDebugger } debug_settings_; double pipeline_latency_ms_ = 0.0; diagnostic_updater::Updater diagnostic_updater_; + bool shouldPublishTentativeObjects() const { return debug_settings_.publish_tentative_objects; } private: void loadParameters(); diff --git a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp index fe41f97cb5a77..f788dd3895216 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/multi_object_tracker_core.hpp @@ -21,6 +21,7 @@ #include "multi_object_tracker/data_association/data_association.hpp" #include "multi_object_tracker/debugger.hpp" +#include "multi_object_tracker/processor/processor.hpp" #include "multi_object_tracker/tracker/model/tracker_base.hpp" #include @@ -46,6 +47,7 @@ #include #include #include +#include #include class MultiObjectTracker : public rclcpp::Node @@ -54,42 +56,34 @@ class MultiObjectTracker : public rclcpp::Node explicit MultiObjectTracker(const rclcpp::NodeOptions & node_options); private: + // ROS interface rclcpp::Publisher::SharedPtr tracked_objects_pub_; rclcpp::Subscription::SharedPtr detected_object_sub_; + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + // debugger + std::unique_ptr debugger_; + std::unique_ptr published_time_publisher_; // publish timer rclcpp::TimerBase::SharedPtr publish_timer_; rclcpp::Time last_published_time_; double publisher_period_; - // debugger class - std::unique_ptr debugger_; - - tf2_ros::Buffer tf_buffer_; - tf2_ros::TransformListener tf_listener_; - - std::map tracker_map_; - - std::unique_ptr published_time_publisher_; + // internal states + std::string world_frame_id_; // tracking frame + std::unique_ptr data_association_; + std::unique_ptr processor_; + // callback functions void onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg); void onTimer(); - std::string world_frame_id_; // tracking frame - std::list> list_tracker_; - std::unique_ptr data_association_; - - void checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time); - void sanitizeTracker( - std::list> & list_tracker, const rclcpp::Time & time); - std::shared_ptr createNewTracker( - const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform) const; - + // publish processes void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; diff --git a/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp b/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp new file mode 100644 index 0000000000000..6d6e364d83a41 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp @@ -0,0 +1,79 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#ifndef MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ +#define MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +class TrackerProcessor +{ +public: + explicit TrackerProcessor(const std::map & tracker_map); + + const std::list> & getListTracker() const { return list_tracker_; } + // tracker processes + void predict(const rclcpp::Time & time); + void update( + const autoware_auto_perception_msgs::msg::DetectedObjects & transformed_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & direct_assignment); + void spawn( + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & reverse_assignment); + void prune(const rclcpp::Time & time); + + // output + bool isConfidentTracker(const std::shared_ptr & tracker) const; + void getTrackedObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tracked_objects) const; + void getTentativeObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; + +private: + std::map tracker_map_; + std::list> list_tracker_; + + // parameters + float max_elapsed_time_; // [s] + float min_iou_; // [ratio] + float min_iou_for_unknown_object_; // [ratio] + double distance_threshold_; // [m] + int confident_count_threshold_; // [count] + + void removeOldTracker(const rclcpp::Time & time); + void removeOverlappedTracker(const rclcpp::Time & time); + std::shared_ptr createNewTracker( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) const; +}; + +#endif // MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ diff --git a/perception/multi_object_tracker/package.xml b/perception/multi_object_tracker/package.xml index 699b28222f63f..4033f85eafb8a 100644 --- a/perception/multi_object_tracker/package.xml +++ b/perception/multi_object_tracker/package.xml @@ -25,7 +25,6 @@ tf2 tf2_ros tier4_autoware_utils - tier4_perception_msgs unique_identifier_msgs ament_lint_auto diff --git a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp index 220d1104b33ee..d80a21813b28b 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -31,7 +31,6 @@ #define EIGEN_MPL2_ONLY #include "multi_object_tracker/multi_object_tracker_core.hpp" #include "multi_object_tracker/utils/utils.hpp" -#include "object_recognition_utils/object_recognition_utils.hpp" #include #include @@ -41,18 +40,20 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; namespace { +// Function to get the transform between two frames boost::optional getTransformAnonymous( const tf2_ros::Buffer & tf_buffer, const std::string & source_frame_id, const std::string & target_frame_id, const rclcpp::Time & time) { try { - // check if the frames are ready + // Check if the frames are ready std::string errstr; // This argument prevents error msg from being displayed in the terminal. if (!tf_buffer.canTransform( target_frame_id, source_frame_id, tf2::TimePointZero, tf2::Duration::zero(), &errstr)) { return boost::none; } + // Lookup the transform geometry_msgs::msg::TransformStamped self_transform_stamped; self_transform_stamped = tf_buffer.lookupTransform( /*target*/ target_frame_id, /*src*/ source_frame_id, time, @@ -68,9 +69,9 @@ boost::optional getTransformAnonymous( MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), - last_published_time_(this->now()), tf_buffer_(this->get_clock()), - tf_listener_(tf_buffer_) + tf_listener_(tf_buffer_), + last_published_time_(this->now()) { // Create publishers and subscribers detected_object_sub_ = create_subscription( @@ -79,14 +80,12 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tracked_objects_pub_ = create_publisher("output", rclcpp::QoS{1}); - // Parameters + // Get parameters double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; - // Debug publishers - debugger_ = std::make_unique(*this); - + // Create tf timer auto cti = std::make_shared( this->get_node_base_interface(), this->get_node_timers_interface()); tf_buffer_.setCreateTimerInterface(cti); @@ -102,34 +101,44 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this)); } - const auto tmp = this->declare_parameter>("can_assign_matrix"); - const std::vector can_assign_matrix(tmp.begin(), tmp.end()); - - const auto max_dist_matrix = this->declare_parameter>("max_dist_matrix"); - const auto max_area_matrix = this->declare_parameter>("max_area_matrix"); - const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); - const auto max_rad_matrix = this->declare_parameter>("max_rad_matrix"); - const auto min_iou_matrix = this->declare_parameter>("min_iou_matrix"); - - // tracker map - tracker_map_.insert( - std::make_pair(Label::CAR, this->declare_parameter("car_tracker"))); - tracker_map_.insert( - std::make_pair(Label::TRUCK, this->declare_parameter("truck_tracker"))); - tracker_map_.insert( - std::make_pair(Label::BUS, this->declare_parameter("bus_tracker"))); - tracker_map_.insert( - std::make_pair(Label::TRAILER, this->declare_parameter("trailer_tracker"))); - tracker_map_.insert( - std::make_pair(Label::PEDESTRIAN, this->declare_parameter("pedestrian_tracker"))); - tracker_map_.insert( - std::make_pair(Label::BICYCLE, this->declare_parameter("bicycle_tracker"))); - tracker_map_.insert( - std::make_pair(Label::MOTORCYCLE, this->declare_parameter("motorcycle_tracker"))); - - data_association_ = std::make_unique( - can_assign_matrix, max_dist_matrix, max_area_matrix, min_area_matrix, max_rad_matrix, - min_iou_matrix); + // Initialize processor + { + std::map tracker_map; + tracker_map.insert( + std::make_pair(Label::CAR, this->declare_parameter("car_tracker"))); + tracker_map.insert( + std::make_pair(Label::TRUCK, this->declare_parameter("truck_tracker"))); + tracker_map.insert( + std::make_pair(Label::BUS, this->declare_parameter("bus_tracker"))); + tracker_map.insert( + std::make_pair(Label::TRAILER, this->declare_parameter("trailer_tracker"))); + tracker_map.insert(std::make_pair( + Label::PEDESTRIAN, this->declare_parameter("pedestrian_tracker"))); + tracker_map.insert( + std::make_pair(Label::BICYCLE, this->declare_parameter("bicycle_tracker"))); + tracker_map.insert(std::make_pair( + Label::MOTORCYCLE, this->declare_parameter("motorcycle_tracker"))); + + processor_ = std::make_unique(tracker_map); + } + + // Data association initialization + { + const auto tmp = this->declare_parameter>("can_assign_matrix"); + const std::vector can_assign_matrix(tmp.begin(), tmp.end()); + const auto max_dist_matrix = this->declare_parameter>("max_dist_matrix"); + const auto max_area_matrix = this->declare_parameter>("max_area_matrix"); + const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); + const auto max_rad_matrix = this->declare_parameter>("max_rad_matrix"); + const auto min_iou_matrix = this->declare_parameter>("min_iou_matrix"); + + data_association_ = std::make_unique( + can_assign_matrix, max_dist_matrix, max_area_matrix, min_area_matrix, max_rad_matrix, + min_iou_matrix); + } + + // Debugger + debugger_ = std::make_unique(*this); published_time_publisher_ = std::make_unique(this); } @@ -147,52 +156,33 @@ void MultiObjectTracker::onMeasurement( if (!self_transform) { return; } - /* transform to world coordinate */ autoware_auto_perception_msgs::msg::DetectedObjects transformed_objects; if (!object_recognition_utils::transformObjects( *input_objects_msg, world_frame_id_, tf_buffer_, transformed_objects)) { return; } - /* tracker prediction */ - for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { - (*itr)->predict(measurement_time); - } - /* global nearest neighbor */ + ////// Tracker Process + //// Associate and update + /* prediction */ + processor_->predict(measurement_time); + /* object association */ std::unordered_map direct_assignment, reverse_assignment; - Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix( - transformed_objects, list_tracker_); // row : tracker, col : measurement - data_association_->assign(score_matrix, direct_assignment, reverse_assignment); - - /* tracker measurement update */ - int tracker_idx = 0; - for (auto tracker_itr = list_tracker_.begin(); tracker_itr != list_tracker_.end(); - ++tracker_itr, ++tracker_idx) { - if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found - (*(tracker_itr)) - ->updateWithMeasurement( - transformed_objects.objects.at(direct_assignment.find(tracker_idx)->second), - measurement_time, *self_transform); - } else { // not found - (*(tracker_itr))->updateWithoutMeasurement(); - } - } - - /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, measurement_time); - /* sanitize trackers */ - sanitizeTracker(list_tracker_, measurement_time); - - /* new tracker */ - for (size_t i = 0; i < transformed_objects.objects.size(); ++i) { - if (reverse_assignment.find(i) != reverse_assignment.end()) { // found - continue; - } - std::shared_ptr tracker = - createNewTracker(transformed_objects.objects.at(i), measurement_time, *self_transform); - if (tracker) list_tracker_.push_back(tracker); + { + const auto & list_tracker = processor_->getListTracker(); + const auto & detected_objects = transformed_objects; + // global nearest neighbor + Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix( + detected_objects, list_tracker); // row : tracker, col : measurement + data_association_->assign(score_matrix, direct_assignment, reverse_assignment); } + /* tracker update */ + processor_->update(transformed_objects, *self_transform, direct_assignment); + /* tracker pruning */ + processor_->prune(measurement_time); + /* spawn new tracker */ + processor_->spawn(transformed_objects, *self_transform, reverse_assignment); // debugger time debugger_->endMeasurementTime(this->now()); @@ -210,39 +200,12 @@ void MultiObjectTracker::onMeasurement( } } -std::shared_ptr MultiObjectTracker::createNewTracker( - const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform) const -{ - const std::uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification); - if (tracker_map_.count(label) != 0) { - const auto tracker = tracker_map_.at(label); - - if (tracker == "bicycle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "big_vehicle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "multi_vehicle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "normal_vehicle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "pass_through_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "pedestrian_and_bicycle_tracker") { - return std::make_shared(time, object, self_transform); - } else if (tracker == "pedestrian_tracker") { - return std::make_shared(time, object, self_transform); - } - } - return std::make_shared(time, object, self_transform); -} - void MultiObjectTracker::onTimer() { const rclcpp::Time current_time = this->now(); - // check the publish period + // Check the publish period const auto elapsed_time = (current_time - last_published_time_).seconds(); - // if the elapsed time is over the period, publish objects with prediction + // If the elapsed time is over the period, publish objects with prediction constexpr double maximum_latency_ratio = 1.11; // 11% margin const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio; if (elapsed_time > maximum_publish_latency) { @@ -252,10 +215,8 @@ void MultiObjectTracker::onTimer() void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time) { - /* life cycle check */ - checkTrackerLifeCycle(list_tracker_, time); - /* sanitize trackers */ - sanitizeTracker(list_tracker_, time); + /* tracker pruning*/ + processor_->prune(time); // Publish publish(time); @@ -264,100 +225,6 @@ void MultiObjectTracker::checkAndPublish(const rclcpp::Time & time) last_published_time_ = this->now(); } -void MultiObjectTracker::checkTrackerLifeCycle( - std::list> & list_tracker, const rclcpp::Time & time) -{ - /* params */ - constexpr float max_elapsed_time = 1.0; - - /* delete tracker */ - for (auto itr = list_tracker.begin(); itr != list_tracker.end(); ++itr) { - const bool is_old = max_elapsed_time < (*itr)->getElapsedTimeFromLastUpdate(time); - if (is_old) { - auto erase_itr = itr; - --itr; - list_tracker.erase(erase_itr); - } - } -} - -void MultiObjectTracker::sanitizeTracker( - std::list> & list_tracker, const rclcpp::Time & time) -{ - constexpr float min_iou = 0.1; - constexpr float min_iou_for_unknown_object = 0.001; - constexpr double distance_threshold = 5.0; - /* delete collision tracker */ - for (auto itr1 = list_tracker.begin(); itr1 != list_tracker.end(); ++itr1) { - autoware_auto_perception_msgs::msg::TrackedObject object1; - if (!(*itr1)->getTrackedObject(time, object1)) continue; - for (auto itr2 = std::next(itr1); itr2 != list_tracker.end(); ++itr2) { - autoware_auto_perception_msgs::msg::TrackedObject object2; - if (!(*itr2)->getTrackedObject(time, object2)) continue; - const double distance = std::hypot( - object1.kinematics.pose_with_covariance.pose.position.x - - object2.kinematics.pose_with_covariance.pose.position.x, - object1.kinematics.pose_with_covariance.pose.position.y - - object2.kinematics.pose_with_covariance.pose.position.y); - if (distance_threshold < distance) { - continue; - } - - const double min_union_iou_area = 1e-2; - const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); - const auto & label1 = (*itr1)->getHighestProbLabel(); - const auto & label2 = (*itr2)->getHighestProbLabel(); - bool should_delete_tracker1 = false; - bool should_delete_tracker2 = false; - - // If at least one of them is UNKNOWN, delete the one with lower IOU. Because the UNKNOWN - // objects are not reliable. - if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) { - if (min_iou_for_unknown_object < iou) { - if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) { - if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { - should_delete_tracker1 = true; - } else { - should_delete_tracker2 = true; - } - } else if (label1 == Label::UNKNOWN) { - should_delete_tracker1 = true; - } else if (label2 == Label::UNKNOWN) { - should_delete_tracker2 = true; - } - } - } else { // If neither is UNKNOWN, delete the one with lower IOU. - if (min_iou < iou) { - if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { - should_delete_tracker1 = true; - } else { - should_delete_tracker2 = true; - } - } - } - - if (should_delete_tracker1) { - itr1 = list_tracker.erase(itr1); - --itr1; - break; - } else if (should_delete_tracker2) { - itr2 = list_tracker.erase(itr2); - --itr2; - } - } - } -} - -inline bool MultiObjectTracker::shouldTrackerPublish( - const std::shared_ptr tracker) const -{ - constexpr int measurement_count_threshold = 3; - if (tracker->getTotalMeasurementCount() < measurement_count_threshold) { - return false; - } - return true; -} - void MultiObjectTracker::publish(const rclcpp::Time & time) const { debugger_->startPublishTime(this->now()); @@ -369,28 +236,21 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const // Create output msg autoware_auto_perception_msgs::msg::TrackedObjects output_msg, tentative_objects_msg; output_msg.header.frame_id = world_frame_id_; - output_msg.header.stamp = time; - tentative_objects_msg.header = output_msg.header; - - for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { - if (!shouldTrackerPublish(*itr)) { // for debug purpose - autoware_auto_perception_msgs::msg::TrackedObject object; - if (!(*itr)->getTrackedObject(time, object)) continue; - tentative_objects_msg.objects.push_back(object); - continue; - } - autoware_auto_perception_msgs::msg::TrackedObject object; - if (!(*itr)->getTrackedObject(time, object)) continue; - output_msg.objects.push_back(object); - } + processor_->getTrackedObjects(time, output_msg); // Publish tracked_objects_pub_->publish(output_msg); published_time_publisher_->publish_if_subscribed(tracked_objects_pub_, output_msg.header.stamp); - // Debugger Publish if enabled + // Publish debugger information if enabled debugger_->endPublishTime(this->now(), time); - debugger_->publishTentativeObjects(tentative_objects_msg); + + if (debugger_->shouldPublishTentativeObjects()) { + autoware_auto_perception_msgs::msg::TrackedObjects tentative_objects_msg; + tentative_objects_msg.header.frame_id = world_frame_id_; + processor_->getTentativeObjects(time, tentative_objects_msg); + debugger_->publishTentativeObjects(tentative_objects_msg); + } } RCLCPP_COMPONENTS_REGISTER_NODE(MultiObjectTracker) diff --git a/perception/multi_object_tracker/src/processor/processor.cpp b/perception/multi_object_tracker/src/processor/processor.cpp new file mode 100644 index 0000000000000..0d56e16b431e9 --- /dev/null +++ b/perception/multi_object_tracker/src/processor/processor.cpp @@ -0,0 +1,242 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// + +#include "multi_object_tracker/processor/processor.hpp" + +#include "multi_object_tracker/tracker/tracker.hpp" +#include "object_recognition_utils/object_recognition_utils.hpp" + +#include + +#include + +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + +TrackerProcessor::TrackerProcessor(const std::map & tracker_map) +: tracker_map_(tracker_map) +{ + // Set tracker lifetime parameters + max_elapsed_time_ = 1.0; // [s] + + // Set tracker overlap remover parameters + min_iou_ = 0.1; // [ratio] + min_iou_for_unknown_object_ = 0.001; // [ratio] + distance_threshold_ = 5.0; // [m] + + // Set tracker confidence threshold + confident_count_threshold_ = 3; // [count] +} + +void TrackerProcessor::predict(const rclcpp::Time & time) +{ + for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { + (*itr)->predict(time); + } +} + +void TrackerProcessor::update( + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & direct_assignment) +{ + int tracker_idx = 0; + const auto & time = detected_objects.header.stamp; + for (auto tracker_itr = list_tracker_.begin(); tracker_itr != list_tracker_.end(); + ++tracker_itr, ++tracker_idx) { + if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found + const auto & associated_object = + detected_objects.objects.at(direct_assignment.find(tracker_idx)->second); + (*(tracker_itr))->updateWithMeasurement(associated_object, time, self_transform); + } else { // not found + (*(tracker_itr))->updateWithoutMeasurement(); + } + } +} + +void TrackerProcessor::spawn( + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const geometry_msgs::msg::Transform & self_transform, + const std::unordered_map & reverse_assignment) +{ + const auto & time = detected_objects.header.stamp; + for (size_t i = 0; i < detected_objects.objects.size(); ++i) { + if (reverse_assignment.find(i) != reverse_assignment.end()) { // found + continue; + } + const auto & new_object = detected_objects.objects.at(i); + std::shared_ptr tracker = createNewTracker(new_object, time, self_transform); + if (tracker) list_tracker_.push_back(tracker); + } +} + +std::shared_ptr TrackerProcessor::createNewTracker( + const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, + const geometry_msgs::msg::Transform & self_transform) const +{ + const std::uint8_t label = object_recognition_utils::getHighestProbLabel(object.classification); + if (tracker_map_.count(label) != 0) { + const auto tracker = tracker_map_.at(label); + if (tracker == "bicycle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "big_vehicle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "multi_vehicle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "normal_vehicle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "pass_through_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "pedestrian_and_bicycle_tracker") + return std::make_shared(time, object, self_transform); + if (tracker == "pedestrian_tracker") + return std::make_shared(time, object, self_transform); + } + return std::make_shared(time, object, self_transform); +} + +void TrackerProcessor::prune(const rclcpp::Time & time) +{ + // Check tracker lifetime: if the tracker is old, delete it + removeOldTracker(time); + // Check tracker overlap: if the tracker is overlapped, delete the one with lower IOU + removeOverlappedTracker(time); +} + +void TrackerProcessor::removeOldTracker(const rclcpp::Time & time) +{ + // Check elapsed time from last update + for (auto itr = list_tracker_.begin(); itr != list_tracker_.end(); ++itr) { + const bool is_old = max_elapsed_time_ < (*itr)->getElapsedTimeFromLastUpdate(time); + // If the tracker is old, delete it + if (is_old) { + auto erase_itr = itr; + --itr; + list_tracker_.erase(erase_itr); + } + } +} + +// This function removes overlapped trackers based on distance and IoU criteria +void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time) +{ + // Iterate through the list of trackers + for (auto itr1 = list_tracker_.begin(); itr1 != list_tracker_.end(); ++itr1) { + autoware_auto_perception_msgs::msg::TrackedObject object1; + if (!(*itr1)->getTrackedObject(time, object1)) continue; + + // Compare the current tracker with the remaining trackers + for (auto itr2 = std::next(itr1); itr2 != list_tracker_.end(); ++itr2) { + autoware_auto_perception_msgs::msg::TrackedObject object2; + if (!(*itr2)->getTrackedObject(time, object2)) continue; + + // Calculate the distance between the two objects + const double distance = std::hypot( + object1.kinematics.pose_with_covariance.pose.position.x - + object2.kinematics.pose_with_covariance.pose.position.x, + object1.kinematics.pose_with_covariance.pose.position.y - + object2.kinematics.pose_with_covariance.pose.position.y); + + // If the distance is too large, skip + if (distance > distance_threshold_) { + continue; + } + + // Check the Intersection over Union (IoU) between the two objects + const double min_union_iou_area = 1e-2; + const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area); + const auto & label1 = (*itr1)->getHighestProbLabel(); + const auto & label2 = (*itr2)->getHighestProbLabel(); + bool should_delete_tracker1 = false; + bool should_delete_tracker2 = false; + + // If both trackers are UNKNOWN, delete the younger tracker + // If one side of the tracker is UNKNOWN, delete UNKNOWN objects + if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) { + if (iou > min_iou_for_unknown_object_) { + if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) { + if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { + should_delete_tracker1 = true; + } else { + should_delete_tracker2 = true; + } + } else if (label1 == Label::UNKNOWN) { + should_delete_tracker1 = true; + } else if (label2 == Label::UNKNOWN) { + should_delete_tracker2 = true; + } + } + } else { // If neither object is UNKNOWN, delete the younger tracker + if (iou > min_iou_) { + if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) { + should_delete_tracker1 = true; + } else { + should_delete_tracker2 = true; + } + } + } + + // Delete the tracker + if (should_delete_tracker1) { + itr1 = list_tracker_.erase(itr1); + --itr1; + break; + } + if (should_delete_tracker2) { + itr2 = list_tracker_.erase(itr2); + --itr2; + } + } + } +} + +bool TrackerProcessor::isConfidentTracker(const std::shared_ptr & tracker) const +{ + // Confidence is determined by counting the number of measurements. + // If the number of measurements is equal to or greater than the threshold, the tracker is + // considered confident. + return tracker->getTotalMeasurementCount() >= confident_count_threshold_; +} + +void TrackerProcessor::getTrackedObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tracked_objects) const +{ + tracked_objects.header.stamp = time; + for (const auto & tracker : list_tracker_) { + // Skip if the tracker is not confident + if (!isConfidentTracker(tracker)) continue; + // Get the tracked object, extrapolated to the given time + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + if (tracker->getTrackedObject(time, tracked_object)) { + tracked_objects.objects.push_back(tracked_object); + } + } +} + +void TrackerProcessor::getTentativeObjects( + const rclcpp::Time & time, + autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const +{ + tentative_objects.header.stamp = time; + for (const auto & tracker : list_tracker_) { + if (!isConfidentTracker(tracker)) { + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + if (tracker->getTrackedObject(time, tracked_object)) { + tentative_objects.objects.push_back(tracked_object); + } + } + } +} From 06bb9bdab6398c717f5e5b234c0f35ad268e80c8 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Apr 2024 15:38:54 +0900 Subject: [PATCH 025/192] fix(avoidance): fix invalid road bound distance calculation (#6781) fix(avoidance): fix invalid road shoulder distance calculation Signed-off-by: satoshi-ota --- planning/behavior_path_avoidance_module/src/utils.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 6c2b72db0237d..f0d864f3fed38 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -874,8 +874,7 @@ double getRoadShoulderDistance( } { - const auto p2 = - calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -100.0 : 100.0), 0.0).position; + const auto p2 = calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -1.0 : 1.0), 0.0).position; const auto opt_intersect = tier4_autoware_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); From a06122ce1bdbefae8c4b0bb0a7ce38c2f7edc407 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 11 Apr 2024 19:28:40 +0900 Subject: [PATCH 026/192] refactor(avoidance): rebuild parameter structure (#6786) * refactor(avoidance): unify similar param Signed-off-by: satoshi-ota * refactor(avoidance): rename misreading params Signed-off-by: satoshi-ota * refactor(avoidance): update parameter namespace Signed-off-by: satoshi-ota * refactor(avoidance): use prefix th instead of threshold Signed-off-by: satoshi-ota * refactor(avoidance): rename params Signed-off-by: satoshi-ota * refactor(AbLC): rename params Signed-off-by: satoshi-ota * refactor(avoidance): update yaml Signed-off-by: satoshi-ota * refactor(AbLC): update yaml Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../avoidance_by_lane_change.param.yaml | 52 ++-- .../src/manager.cpp | 24 +- .../config/avoidance.param.yaml | 292 +++++++++--------- .../data_structs.hpp | 20 +- .../behavior_path_avoidance_module/helper.hpp | 7 +- .../parameter_helper.hpp | 78 ++--- .../src/manager.cpp | 64 ++-- .../src/scene.cpp | 8 +- .../src/shift_line_generator.cpp | 8 +- .../src/utils.cpp | 4 +- 10 files changed, 268 insertions(+), 289 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml index ad5fe0b123f1d..384ef7bd285e9 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml +++ b/planning/behavior_path_avoidance_by_lane_change_module/config/avoidance_by_lane_change.param.yaml @@ -8,8 +8,8 @@ target_object: car: execute_num: 2 # [-] - moving_speed_threshold: 1.0 # [m/s] - moving_time_threshold: 1.0 # [s] + th_moving_speed: 1.0 # [m/s] + th_moving_time: 1.0 # [s] max_expand_ratio: 0.0 # [-] envelope_buffer_margin: 0.3 # [m] lateral_margin: @@ -18,8 +18,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] truck: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -28,8 +28,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] bus: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -38,8 +38,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] trailer: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -48,8 +48,8 @@ hard_margin_for_parked_vehicle: 0.0 # [m] unknown: execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 # 1.0km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 lateral_margin: @@ -58,34 +58,34 @@ hard_margin_for_parked_vehicle: 0.0 # [m] bicycle: execute_num: 2 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 # 1.0km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 lateral_margin: soft_margin: 0.0 # [m] - hard_margin: 0.0 # [m] - hard_margin_for_parked_vehicle: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] motorcycle: execute_num: 2 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 # 3.6km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 lateral_margin: soft_margin: 0.0 # [m] - hard_margin: 0.0 # [m] - hard_margin_for_parked_vehicle: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] pedestrian: execute_num: 2 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 # 1.0km/h + th_moving_time: 1.0 max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 lateral_margin: soft_margin: 0.0 # [m] - hard_margin: 0.0 # [m] - hard_margin_for_parked_vehicle: 0.0 # [m] + hard_margin: 1.0 # [m] + hard_margin_for_parked_vehicle: 1.0 # [m] lower_distance_for_polygon_expansion: 0.0 # [m] upper_distance_for_polygon_expansion: 1.0 # [m] @@ -101,11 +101,3 @@ bicycle: false # [-] motorcycle: false # [-] pedestrian: false # [-] - - constraints: - # lateral constraints - lateral: - velocity: [1.0, 1.38, 11.1] # [m/s] - max_accel_values: [0.5, 0.5, 0.5] # [m/ss] - min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 799364437955c..a3b28b4d63d06 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -65,10 +65,8 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.moving_speed_threshold = getOrDeclareParameter(*node, ns + "th_moving_speed"); + param.moving_time_threshold = getOrDeclareParameter(*node, ns + "th_moving_time"); param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); param.envelope_buffer_margin = getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); @@ -121,14 +119,18 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) p.object_check_goal_distance = getOrDeclareParameter(*node, ns + "object_check_goal_distance"); + p.object_last_seen_threshold = + getOrDeclareParameter(*node, ns + "max_compensation_time"); + } + + { + const std::string ns = "avoidance.target_filtering.parked_vehicle."; p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); + getOrDeclareParameter(*node, ns + "th_offset_from_centerline"); p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); + getOrDeclareParameter(*node, ns + "th_shiftable_ratio"); p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); - p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + getOrDeclareParameter(*node, ns + "min_road_shoulder_width"); } { @@ -137,9 +139,9 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node) p.closest_distance_to_wait_and_see_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "closest_distance_to_wait_and_see"); p.time_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.time_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); p.distance_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.distance_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_moving_distance"); p.object_ignore_section_traffic_light_in_front_distance = getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); p.object_ignore_section_crosswalk_in_front_distance = diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index b7b8d8434b9c4..92f533bc63872 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -2,11 +2,11 @@ /**: ros__parameters: avoidance: - resample_interval_for_planning: 0.3 # [m] - resample_interval_for_output: 4.0 # [m] + resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER + resample_interval_for_output: 4.0 # [m] FOR DEVELOPER + # avoidance module common setting enable_bound_clipping: false - enable_cancel_maneuver: true disable_path_update: false # drivable area setting @@ -16,215 +16,203 @@ use_hatched_road_markings: true use_freespace_areas: true - # for debug - publish_debug_marker: false - print_debug_info: false - # avoidance is performed for the object type with true target_object: car: - execute_num: 1 # [-] - moving_speed_threshold: 1.0 # [m/s] - moving_time_threshold: 2.0 # [s] + th_moving_speed: 1.0 # [m/s] + th_moving_time: 2.0 # [s] + longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.3 # [m] - hard_margin_for_parked_vehicle: 0.3 # [m] - max_expand_ratio: 0.0 # [-] - envelope_buffer_margin: 0.5 # [m] - safety_buffer_longitudinal: 0.0 # [m] - use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. + soft_margin: 0.3 # [m] + hard_margin: 0.2 # [m] + hard_margin_for_parked_vehicle: 0.7 # [m] + max_expand_ratio: 0.0 # [-] FOR DEVELOPER + envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER + use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 2.0 + th_moving_speed: 1.0 + th_moving_time: 2.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.9 # [m] - hard_margin: 0.1 # [m] - hard_margin_for_parked_vehicle: 0.1 # [m] + soft_margin: 0.3 + hard_margin: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bus: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 2.0 + th_moving_speed: 1.0 + th_moving_time: 2.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.9 # [m] - hard_margin: 0.1 # [m] - hard_margin_for_parked_vehicle: 0.1 # [m] + soft_margin: 0.3 + hard_margin: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true trailer: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 2.0 + th_moving_speed: 1.0 + th_moving_time: 2.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.9 # [m] - hard_margin: 0.1 # [m] - hard_margin_for_parked_vehicle: 0.1 # [m] + soft_margin: 0.3 + hard_margin: 0.2 + hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true unknown: - execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 + th_moving_time: 1.0 + longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: -0.2 # [m] - hard_margin_for_parked_vehicle: -0.2 # [m] + soft_margin: 0.7 + hard_margin: -0.2 + hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 - safety_buffer_longitudinal: 0.0 use_conservative_buffer_longitudinal: true bicycle: - execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 + th_moving_time: 1.0 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.5 # [m] - hard_margin_for_parked_vehicle: 0.5 # [m] + soft_margin: 0.7 + hard_margin: 0.5 + hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true motorcycle: - execute_num: 1 - moving_speed_threshold: 1.0 # 3.6km/h - moving_time_threshold: 1.0 + th_moving_speed: 1.0 + th_moving_time: 1.0 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.3 # [m] - hard_margin_for_parked_vehicle: 0.3 # [m] + soft_margin: 0.7 + hard_margin: 0.3 + hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true pedestrian: - execute_num: 1 - moving_speed_threshold: 0.28 # 1.0km/h - moving_time_threshold: 1.0 + th_moving_speed: 0.28 + th_moving_time: 1.0 + longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 # [m] - hard_margin: 0.5 # [m] - hard_margin_for_parked_vehicle: 0.5 # [m] + soft_margin: 0.7 + hard_margin: 0.5 + hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - safety_buffer_longitudinal: 1.0 use_conservative_buffer_longitudinal: true - lower_distance_for_polygon_expansion: 30.0 # [m] - upper_distance_for_polygon_expansion: 100.0 # [m] + lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER + upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER # For target object filtering target_filtering: # avoidance target type target_type: - car: true # [-] - truck: true # [-] - bus: true # [-] - trailer: true # [-] - unknown: true # [-] - bicycle: true # [-] - motorcycle: true # [-] - pedestrian: true # [-] + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: true # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # detection range - object_check_goal_distance: 20.0 # [m] - object_check_return_pose_distance: 20.0 # [m] - # filtering parking objects - threshold_distance_object_is_on_center: 1.0 # [m] - object_check_shiftable_ratio: 0.6 # [-] - object_check_min_road_shoulder_width: 0.5 # [m] + object_check_goal_distance: 20.0 # [m] + object_check_return_pose_distance: 20.0 # [m] # lost object compensation - object_last_seen_threshold: 2.0 + max_compensation_time: 2.0 # detection area generation parameters detection_area: - static: false # [-] - min_forward_distance: 50.0 # [m] - max_forward_distance: 150.0 # [m] - backward_distance: 10.0 # [m] + static: false # [-] + min_forward_distance: 50.0 # [m] + max_forward_distance: 150.0 # [m] + backward_distance: 10.0 # [m] + + # filtering parking objects + parked_vehicle: + th_offset_from_centerline: 1.0 # [m] + th_shiftable_ratio: 0.8 # [-] + min_road_shoulder_width: 0.5 # [m] FOR DEVELOPER # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. avoidance_for_ambiguous_vehicle: - enable: false # [-] - closest_distance_to_wait_and_see: 10.0 # [m] + enable: true # [-] + closest_distance_to_wait_and_see: 10.0 # [m] condition: - time_threshold: 1.0 # [s] - distance_threshold: 1.0 # [m] + th_stopped_time: 3.0 # [s] + th_moving_distance: 1.0 # [m] ignore_area: traffic_light: - front_distance: 100.0 # [m] + front_distance: 100.0 # [m] crosswalk: - front_distance: 30.0 # [m] - behind_distance: 30.0 # [m] + front_distance: 30.0 # [m] + behind_distance: 30.0 # [m] # params for filtering objects that are in intersection intersection: - yaw_deviation: 0.349 # [rad] (default 20.0deg) + yaw_deviation: 0.349 # [rad] (default 20.0deg) # For safety check safety_check: # safety check target type target_type: - car: true # [-] - truck: true # [-] - bus: true # [-] - trailer: true # [-] - unknown: false # [-] - bicycle: true # [-] - motorcycle: true # [-] - pedestrian: true # [-] + car: true # [-] + truck: true # [-] + bus: true # [-] + trailer: true # [-] + unknown: false # [-] + bicycle: true # [-] + motorcycle: true # [-] + pedestrian: true # [-] # safety check configuration - enable: true # [-] - check_current_lane: false # [-] - check_shift_side_lane: true # [-] - check_other_side_lane: false # [-] - check_unavoidable_object: false # [-] - check_other_object: true # [-] + enable: true # [-] + check_current_lane: false # [-] + check_shift_side_lane: true # [-] + check_other_side_lane: false # [-] + check_unavoidable_object: false # [-] + check_other_object: true # [-] # collision check parameters - check_all_predicted_path: false # [-] - safety_check_backward_distance: 100.0 # [m] - hysteresis_factor_expand_rate: 1.5 # [-] - hysteresis_factor_safe_count: 10 # [-] + check_all_predicted_path: false # [-] + safety_check_backward_distance: 100.0 # [m] + hysteresis_factor_expand_rate: 1.5 # [-] + hysteresis_factor_safe_count: 3 # [-] # predicted path parameters - min_velocity: 1.38 # [m/s] - max_velocity: 50.0 # [m/s] - time_resolution: 0.5 # [s] - time_horizon_for_front_object: 3.0 # [s] - time_horizon_for_rear_object: 10.0 # [s] - delay_until_departure: 0.0 # [s] + min_velocity: 1.38 # [m/s] + max_velocity: 50.0 # [m/s] + time_resolution: 0.5 # [s] + time_horizon_for_front_object: 3.0 # [s] + time_horizon_for_rear_object: 10.0 # [s] + delay_until_departure: 0.0 # [s] # rss parameters - extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path" - expected_front_deceleration: -1.0 # [m/ss] - expected_rear_deceleration: -1.0 # [m/ss] - rear_vehicle_reaction_time: 2.0 # [s] - rear_vehicle_safety_time_margin: 1.0 # [s] - lateral_distance_max_threshold: 0.75 # [m] - longitudinal_distance_min_threshold: 3.0 # [m] - longitudinal_velocity_delta_time: 0.8 # [s] + extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path" + expected_front_deceleration: -1.0 # [m/ss] + expected_rear_deceleration: -1.0 # [m/ss] + rear_vehicle_reaction_time: 2.0 # [s] + rear_vehicle_safety_time_margin: 1.0 # [s] + lateral_distance_max_threshold: 2.0 # [m] + longitudinal_distance_min_threshold: 3.0 # [m] + longitudinal_velocity_delta_time: 0.0 # [s] # For avoidance maneuver avoidance: # avoidance lateral parameters lateral: - lateral_execution_threshold: 0.09 # [m] - lateral_small_shift_threshold: 0.101 # [m] - lateral_avoid_check_threshold: 0.1 # [m] - soft_road_shoulder_margin: 0.3 # [m] - hard_road_shoulder_margin: 0.3 # [m] - max_right_shift_length: 5.0 - max_left_shift_length: 5.0 - max_deviation_from_lane: 0.5 # [m] + th_avoid_execution: 0.09 # [m] FOR DEVELOPER + th_small_shift_length: 0.101 # [m] FOR DEVELOPER + soft_drivable_bound_margin: 0.3 # [m] + hard_drivable_bound_margin: 0.3 # [m] + max_right_shift_length: 5.0 # [m] FOR DEVELOPER + max_left_shift_length: 5.0 # [m] FOR DEVELOPER + max_deviation_from_lane: 0.2 # [m] # approve the next shift line after reaching this percentage of the current shift line length. - # this parameter should be within range of 0.0 to 1.0. # this parameter is added to allow waiting for the return of shift approval until the occlusion behind the avoid target is clear. - # this feature can be disabled by setting this parameter to 1.0. (in that case, avoidance module creates return shift as soon as possible.) + # this feature can be disabled by setting this parameter to 0.0. ratio_for_return_shift_approval: 0.5 # [-] # avoidance distance parameters longitudinal: @@ -232,17 +220,21 @@ max_prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] - buf_slow_down_speed: 0.56 # [m/s] - nominal_avoidance_speed: 8.33 # [m/s] + buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER + nominal_avoidance_speed: 8.33 # [m/s] FOR DEVELOPER # return dead line return_dead_line: goal: enable: true # [-] - buffer: 30.0 # [m] + buffer: 3.0 # [m] traffic_light: enable: true # [-] buffer: 3.0 # [m] + # For cancel maneuver + cancel: + enable: true # [-] + # For yield maneuver yield: enable: true # [-] @@ -251,7 +243,7 @@ # For stop maneuver stop: max_distance: 20.0 # [m] - stop_buffer: 1.0 # [m] + stop_buffer: 1.0 # [m] FOR DEVELOPER policy: # policy for rtc request. select "per_shift_line" or "per_avoidance_maneuver". @@ -273,6 +265,10 @@ # if true, module doesn't wait deceleration and outputs avoidance path by best effort margin. use_shorten_margin_immediately: true # [-] + # -------------------------------------- + # FOLLOWING PARAMETERS ARE FOR DEVELOPER + # -------------------------------------- + constraints: # lateral constraints lateral: @@ -292,8 +288,12 @@ shift_line_pipeline: trim: - quantize_filter_threshold: 0.1 - same_grad_filter_1_threshold: 0.1 - same_grad_filter_2_threshold: 0.2 - same_grad_filter_3_threshold: 0.5 - sharp_shift_filter_threshold: 0.2 + quantize_size: 0.1 + th_similar_grad_1: 0.1 + th_similar_grad_2: 0.2 + th_similar_grad_3: 0.5 + + # for debug + debug: + marker: false + console: false diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index fd841ede37e70..bc66598d3ee90 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -75,7 +75,7 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; - double safety_buffer_longitudinal{0.0}; + double longitudinal_margin{0.0}; bool use_conservative_buffer_longitudinal{true}; }; @@ -243,11 +243,11 @@ struct AvoidanceParameters // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. - double soft_road_shoulder_margin{1.0}; + double soft_drivable_bound_margin{1.0}; // The margin is configured so that the generated avoidance trajectory does not come near to the // road shoulder. - double hard_road_shoulder_margin{1.0}; + double hard_drivable_bound_margin{1.0}; // Even if the obstacle is very large, it will not avoid more than this length for right direction double max_right_shift_length{0.0}; @@ -276,26 +276,20 @@ struct AvoidanceParameters // line. double lateral_small_shift_threshold{0.0}; - // use for judge if the ego is shifting or not. - double lateral_avoid_check_threshold{0.0}; - // use for return shift approval. double ratio_for_return_shift_approval{0.0}; // For shift line generation process. The continuous shift length is quantized by this value. - double quantize_filter_threshold{0.0}; + double quantize_size{0.0}; // For shift line generation process. Merge small shift lines. (First step) - double same_grad_filter_1_threshold{0.0}; + double th_similar_grad_1{0.0}; // For shift line generation process. Merge small shift lines. (Second step) - double same_grad_filter_2_threshold{0.0}; + double th_similar_grad_2{0.0}; // For shift line generation process. Merge small shift lines. (Third step) - double same_grad_filter_3_threshold{0.0}; - - // For shift line generation process. Remove sharp(=jerky) shift line. - double sharp_shift_filter_threshold{0.0}; + double th_similar_grad_3{0.0}; // policy bool use_shorten_margin_immediately{false}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 4ff02df97bd89..2e481e7c98e44 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -151,15 +151,14 @@ class AvoidanceHelper const auto & additional_buffer_longitudinal = object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front : 0.0; - return object_parameter.safety_buffer_longitudinal + additional_buffer_longitudinal; + return object_parameter.longitudinal_margin + additional_buffer_longitudinal; } double getRearConstantDistance(const ObjectData & object) const { const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - return object_parameter.safety_buffer_longitudinal + data_->parameters.base_link2rear + - object.length; + return object_parameter.longitudinal_margin + data_->parameters.base_link2rear + object.length; } double getEgoShift() const @@ -370,7 +369,7 @@ class AvoidanceHelper bool isShifted() const { - return std::abs(getEgoShift()) > parameters_->lateral_avoid_check_threshold; + return std::abs(getEgoShift()) > parameters_->lateral_execution_threshold; } bool isInitialized() const diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index fbfec58abe4da..5b8963c7ca22d 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -40,10 +40,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.resample_interval_for_output = getOrDeclareParameter(*node, ns + "resample_interval_for_output"); p.enable_bound_clipping = getOrDeclareParameter(*node, ns + "enable_bound_clipping"); - p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable_cancel_maneuver"); p.disable_path_update = getOrDeclareParameter(*node, ns + "disable_path_update"); - p.publish_debug_marker = getOrDeclareParameter(*node, ns + "publish_debug_marker"); - p.print_debug_info = getOrDeclareParameter(*node, ns + "print_debug_info"); } // drivable area @@ -61,11 +58,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) { const auto get_object_param = [&](std::string && ns) { ObjectParameter param{}; - param.execute_num = getOrDeclareParameter(*node, ns + "execute_num"); - param.moving_speed_threshold = - getOrDeclareParameter(*node, ns + "moving_speed_threshold"); - param.moving_time_threshold = - getOrDeclareParameter(*node, ns + "moving_time_threshold"); + param.moving_speed_threshold = getOrDeclareParameter(*node, ns + "th_moving_speed"); + param.moving_time_threshold = getOrDeclareParameter(*node, ns + "th_moving_time"); param.max_expand_ratio = getOrDeclareParameter(*node, ns + "max_expand_ratio"); param.envelope_buffer_margin = getOrDeclareParameter(*node, ns + "envelope_buffer_margin"); @@ -75,8 +69,7 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin"); param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); - param.safety_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "safety_buffer_longitudinal"); + param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); param.use_conservative_buffer_longitudinal = getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); return param; @@ -124,16 +117,20 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "object_check_goal_distance"); p.object_check_return_pose_distance = getOrDeclareParameter(*node, ns + "object_check_return_pose_distance"); - p.threshold_distance_object_is_on_center = - getOrDeclareParameter(*node, ns + "threshold_distance_object_is_on_center"); - p.object_check_shiftable_ratio = - getOrDeclareParameter(*node, ns + "object_check_shiftable_ratio"); - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, ns + "object_check_min_road_shoulder_width"); p.object_check_yaw_deviation = getOrDeclareParameter(*node, ns + "intersection.yaw_deviation"); p.object_last_seen_threshold = - getOrDeclareParameter(*node, ns + "object_last_seen_threshold"); + getOrDeclareParameter(*node, ns + "max_compensation_time"); + } + + { + const std::string ns = "avoidance.target_filtering.parked_vehicle."; + p.threshold_distance_object_is_on_center = + getOrDeclareParameter(*node, ns + "th_offset_from_centerline"); + p.object_check_shiftable_ratio = + getOrDeclareParameter(*node, ns + "th_shiftable_ratio"); + p.object_check_min_road_shoulder_width = + getOrDeclareParameter(*node, ns + "min_road_shoulder_width"); } { @@ -142,9 +139,9 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.closest_distance_to_wait_and_see_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "closest_distance_to_wait_and_see"); p.time_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.time_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_stopped_time"); p.distance_threshold_for_ambiguous_vehicle = - getOrDeclareParameter(*node, ns + "condition.distance_threshold"); + getOrDeclareParameter(*node, ns + "condition.th_moving_distance"); p.object_ignore_section_traffic_light_in_front_distance = getOrDeclareParameter(*node, ns + "ignore_area.traffic_light.front_distance"); p.object_ignore_section_crosswalk_in_front_distance = @@ -244,16 +241,13 @@ AvoidanceParameters getParameter(rclcpp::Node * node) // avoidance maneuver (lateral) { const std::string ns = "avoidance.avoidance.lateral."; - p.soft_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "soft_road_shoulder_margin"); - p.hard_road_shoulder_margin = - getOrDeclareParameter(*node, ns + "hard_road_shoulder_margin"); - p.lateral_execution_threshold = - getOrDeclareParameter(*node, ns + "lateral_execution_threshold"); + p.soft_drivable_bound_margin = + getOrDeclareParameter(*node, ns + "soft_drivable_bound_margin"); + p.hard_drivable_bound_margin = + getOrDeclareParameter(*node, ns + "hard_drivable_bound_margin"); + p.lateral_execution_threshold = getOrDeclareParameter(*node, ns + "th_avoid_execution"); p.lateral_small_shift_threshold = - getOrDeclareParameter(*node, ns + "lateral_small_shift_threshold"); - p.lateral_avoid_check_threshold = - getOrDeclareParameter(*node, ns + "lateral_avoid_check_threshold"); + getOrDeclareParameter(*node, ns + "th_small_shift_length"); p.max_right_shift_length = getOrDeclareParameter(*node, ns + "max_right_shift_length"); p.max_left_shift_length = getOrDeclareParameter(*node, ns + "max_left_shift_length"); p.max_deviation_from_lane = @@ -289,6 +283,12 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "traffic_light.buffer"); } + // cancel + { + const std::string ns = "avoidance.cancel."; + p.enable_cancel_maneuver = getOrDeclareParameter(*node, ns + "enable"); + } + // yield { const std::string ns = "avoidance.yield."; @@ -369,17 +369,19 @@ AvoidanceParameters getParameter(rclcpp::Node * node) // shift line pipeline { const std::string ns = "avoidance.shift_line_pipeline."; - p.quantize_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.quantize_filter_threshold"); - p.same_grad_filter_1_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_1_threshold"); - p.same_grad_filter_2_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_2_threshold"); - p.same_grad_filter_3_threshold = - getOrDeclareParameter(*node, ns + "trim.same_grad_filter_3_threshold"); - p.sharp_shift_filter_threshold = - getOrDeclareParameter(*node, ns + "trim.sharp_shift_filter_threshold"); + p.quantize_size = getOrDeclareParameter(*node, ns + "trim.quantize_size"); + p.th_similar_grad_1 = getOrDeclareParameter(*node, ns + "trim.th_similar_grad_1"); + p.th_similar_grad_2 = getOrDeclareParameter(*node, ns + "trim.th_similar_grad_2"); + p.th_similar_grad_3 = getOrDeclareParameter(*node, ns + "trim.th_similar_grad_3"); } + + // debug + { + const std::string ns = "avoidance.debug."; + p.publish_debug_marker = getOrDeclareParameter(*node, ns + "marker"); + p.print_debug_info = getOrDeclareParameter(*node, ns + "console"); + } + return p; } } // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 5ce63987621ed..3261214d1b9b6 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -46,18 +46,11 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "enable_safety_check", p->enable_safety_check); - updateParam(parameters, ns + "publish_debug_marker", p->publish_debug_marker); - updateParam(parameters, ns + "print_debug_info", p->print_debug_info); - } - const auto update_object_param = [&p, ¶meters]( const auto & semantic, const std::string & ns) { auto & config = p->object_parameters.at(semantic); - updateParam(parameters, ns + "moving_speed_threshold", config.moving_speed_threshold); - updateParam(parameters, ns + "moving_time_threshold", config.moving_time_threshold); + updateParam(parameters, ns + "th_moving_speed", config.moving_speed_threshold); + updateParam(parameters, ns + "th_moving_time", config.moving_time_threshold); updateParam(parameters, ns + "max_expand_ratio", config.max_expand_ratio); updateParam(parameters, ns + "envelope_buffer_margin", config.envelope_buffer_margin); updateParam(parameters, ns + "lateral_margin.soft_margin", config.lateral_soft_margin); @@ -65,8 +58,7 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector( parameters, ns + "lateral_margin.hard_margin_for_parked_vehicle", config.lateral_hard_margin_for_parked_vehicle); - updateParam( - parameters, ns + "safety_buffer_longitudinal", config.safety_buffer_longitudinal); + updateParam(parameters, ns + "longitudinal_margin", config.longitudinal_margin); updateParam( parameters, ns + "use_conservative_buffer_longitudinal", config.use_conservative_buffer_longitudinal); @@ -113,16 +105,16 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorobject_check_goal_distance); updateParam( parameters, ns + "object_check_return_pose_distance", p->object_check_return_pose_distance); + updateParam(parameters, ns + "max_compensation_time", p->object_last_seen_threshold); + } + + { + const std::string ns = "avoidance.target_filtering.parked_vehicle."; updateParam( - parameters, ns + "threshold_distance_object_is_on_center", - p->threshold_distance_object_is_on_center); - updateParam( - parameters, ns + "object_check_shiftable_ratio", p->object_check_shiftable_ratio); - updateParam( - parameters, ns + "object_check_min_road_shoulder_width", - p->object_check_min_road_shoulder_width); + parameters, ns + "th_offset_from_centerline", p->threshold_distance_object_is_on_center); + updateParam(parameters, ns + "th_shiftable_ratio", p->object_check_shiftable_ratio); updateParam( - parameters, ns + "object_last_seen_threshold", p->object_last_seen_threshold); + parameters, ns + "min_road_shoulder_width", p->object_check_min_road_shoulder_width); } { @@ -142,9 +134,9 @@ void AvoidanceModuleManager::updateModuleParams(const std::vectorclosest_distance_to_wait_and_see_for_ambiguous_vehicle); updateParam( - parameters, ns + "condition.time_threshold", p->time_threshold_for_ambiguous_vehicle); + parameters, ns + "condition.th_stopped_time", p->time_threshold_for_ambiguous_vehicle); updateParam( - parameters, ns + "condition.distance_threshold", p->distance_threshold_for_ambiguous_vehicle); + parameters, ns + "condition.th_moving_distance", p->distance_threshold_for_ambiguous_vehicle); updateParam( parameters, ns + "ignore_area.traffic_light.front_distance", p->object_ignore_section_traffic_light_in_front_distance); @@ -163,14 +155,12 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "th_avoid_execution", p->lateral_execution_threshold); + updateParam(parameters, ns + "th_small_shift_length", p->lateral_small_shift_threshold); updateParam( - parameters, ns + "lateral_execution_threshold", p->lateral_execution_threshold); + parameters, ns + "soft_drivable_bound_margin", p->soft_drivable_bound_margin); updateParam( - parameters, ns + "lateral_small_shift_threshold", p->lateral_small_shift_threshold); - updateParam( - parameters, ns + "lateral_avoid_check_threshold", p->lateral_avoid_check_threshold); - updateParam(parameters, ns + "soft_road_shoulder_margin", p->soft_road_shoulder_margin); - updateParam(parameters, ns + "hard_road_shoulder_margin", p->hard_road_shoulder_margin); + parameters, ns + "hard_drivable_bound_margin", p->hard_drivable_bound_margin); } { @@ -259,16 +249,16 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector( - parameters, ns + "trim.quantize_filter_threshold", p->quantize_filter_threshold); - updateParam( - parameters, ns + "trim.same_grad_filter_1_threshold", p->same_grad_filter_1_threshold); - updateParam( - parameters, ns + "trim.same_grad_filter_2_threshold", p->same_grad_filter_2_threshold); - updateParam( - parameters, ns + "trim.same_grad_filter_3_threshold", p->same_grad_filter_3_threshold); - updateParam( - parameters, ns + "trim.sharp_shift_filter_threshold", p->sharp_shift_filter_threshold); + updateParam(parameters, ns + "trim.quantize_size", p->quantize_size); + updateParam(parameters, ns + "trim.th_similar_grad_1", p->th_similar_grad_1); + updateParam(parameters, ns + "trim.th_similar_grad_2", p->th_similar_grad_2); + updateParam(parameters, ns + "trim.th_similar_grad_3", p->th_similar_grad_3); + } + + { + const std::string ns = "avoidance.debug."; + updateParam(parameters, ns + "marker", p->publish_debug_marker); + updateParam(parameters, ns + "console", p->print_debug_info); } std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index 33f58c6a08dfc..b16395f825385 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -162,7 +162,7 @@ bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & const bool has_shift_point = !path_shifter_.getShiftLines().empty(); const bool has_base_offset = - std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_avoid_check_threshold; + std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_execution_threshold; // Nothing to do. -> EXIT. if (!has_shift_point && !has_base_offset) { @@ -734,7 +734,7 @@ bool AvoidanceModule::isSafePath( for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) { const auto length = shifted_path.shift_length.at(i); - if (parameters_->lateral_avoid_check_threshold < length) { + if (parameters_->lateral_execution_threshold < length) { return true; } } @@ -746,7 +746,7 @@ bool AvoidanceModule::isSafePath( for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) { const auto length = shifted_path.shift_length.at(i); - if (parameters_->lateral_avoid_check_threshold < -1.0 * length) { + if (parameters_->lateral_execution_threshold < -1.0 * length) { return true; } } @@ -1222,7 +1222,7 @@ bool AvoidanceModule::isValidShiftLine( // check if the vehicle is in road. (yaw angle is not considered) { const auto minimum_distance = 0.5 * planner_data_->parameters.vehicle_width + - parameters_->hard_road_shoulder_margin - + parameters_->hard_drivable_bound_margin - parameters_->max_deviation_from_lane; const size_t start_idx = shift_lines.front().start_idx; diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp index 5a8fd35f6d618..9137048945fa1 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp @@ -871,7 +871,7 @@ AvoidLineArray ShiftLineGenerator::applyTrimProcess( // - Combine avoid points that have almost same gradient. // this is to remove the noise. { - const auto THRESHOLD = parameters_->same_grad_filter_1_threshold; + const auto THRESHOLD = parameters_->th_similar_grad_1; applySimilarGradFilter(sl_array_trimmed, THRESHOLD); debug.step3_grad_filtered_1st = sl_array_trimmed; } @@ -879,7 +879,7 @@ AvoidLineArray ShiftLineGenerator::applyTrimProcess( // - Quantize the shift length to reduce the shift point noise // This is to remove the noise coming from detection accuracy, interpolation, resampling, etc. { - const auto THRESHOLD = parameters_->quantize_filter_threshold; + const auto THRESHOLD = parameters_->quantize_size; applyQuantizeProcess(sl_array_trimmed, THRESHOLD); debug.step3_quantize_filtered = sl_array_trimmed; } @@ -893,14 +893,14 @@ AvoidLineArray ShiftLineGenerator::applyTrimProcess( // - Combine avoid points that have almost same gradient (again) { - const auto THRESHOLD = parameters_->same_grad_filter_2_threshold; + const auto THRESHOLD = parameters_->th_similar_grad_2; applySimilarGradFilter(sl_array_trimmed, THRESHOLD); debug.step3_grad_filtered_2nd = sl_array_trimmed; } // - Combine avoid points that have almost same gradient (again) { - const auto THRESHOLD = parameters_->same_grad_filter_3_threshold; + const auto THRESHOLD = parameters_->th_similar_grad_3; applySimilarGradFilter(sl_array_trimmed, THRESHOLD); debug.step3_grad_filtered_3rd = sl_array_trimmed; } diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index f0d864f3fed38..bef3976be7e1e 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -814,9 +814,9 @@ std::optional getAvoidMargin( object_parameter.lateral_soft_margin + 0.5 * vehicle_width; const auto min_avoid_margin = lateral_hard_margin + 0.5 * vehicle_width; const auto soft_lateral_distance_limit = - object.to_road_shoulder_distance - parameters->soft_road_shoulder_margin - 0.5 * vehicle_width; + object.to_road_shoulder_distance - parameters->soft_drivable_bound_margin - 0.5 * vehicle_width; const auto hard_lateral_distance_limit = - object.to_road_shoulder_distance - parameters->hard_road_shoulder_margin - 0.5 * vehicle_width; + object.to_road_shoulder_distance - parameters->hard_drivable_bound_margin - 0.5 * vehicle_width; // Step1. check avoidable or not. if (hard_lateral_distance_limit < min_avoid_margin) { From e459f09dada0db9b57ac8108254a844d69e86569 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 12 Apr 2024 03:05:40 +0900 Subject: [PATCH 027/192] feat(static_centerline_optimizer): generate centerline from ego's trajectory in bag (#6788) * implement bag_ego_trajectory_based_centerline Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../include/route_handler/route_handler.hpp | 1 + planning/route_handler/src/route_handler.cpp | 7 + .../CMakeLists.txt | 2 + .../static_centerline_optimizer.param.yaml | 2 +- .../bag_ego_trajectory_based_centerline.hpp | 29 ++ ...timization_trajectory_based_centerline.hpp | 45 +++ .../static_centerline_optimizer_node.hpp | 26 +- .../static_centerline_optimizer/utils.hpp | 3 + .../static_centerline_optimizer.launch.xml | 5 + .../bag_ego_trajectory_based_centerline.sh | 3 + ...ptimization_trajectory_based_centerline.sh | 3 + .../scripts/tmp/run.sh | 3 - .../bag_ego_trajectory_based_centerline.cpp | 82 +++++ ...timization_trajectory_based_centerline.cpp | 192 +++++++++++ .../src/static_centerline_optimizer_node.cpp | 307 ++++++------------ .../static_centerline_optimizer/src/utils.cpp | 11 + .../test/data/bag_ego_trajectory.db3 | Bin 0 -> 2654208 bytes .../test_static_centerline_optimizer.test.py | 1 + 18 files changed, 491 insertions(+), 231 deletions(-) create mode 100644 planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp create mode 100644 planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp create mode 100755 planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh create mode 100755 planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh delete mode 100755 planning/static_centerline_optimizer/scripts/tmp/run.sh create mode 100644 planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp create mode 100644 planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp create mode 100644 planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index 83c814b70f0a5..ac8e472b2f943 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -354,6 +354,7 @@ class RouteHandler const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const; lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; + lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; private: // MUST diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 8d143fcf0b87d..76763821998bd 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -2286,4 +2286,11 @@ bool RouteHandler::findDrivableLanePath( return drivable_lane_path_found; } +lanelet::ConstLanelets RouteHandler::getClosestLanelets( + const geometry_msgs::msg::Pose & target_pose) const +{ + lanelet::ConstLanelets target_lanelets; + lanelet::utils::query::getCurrentLanelets(road_lanelets_, target_pose, &target_lanelets); + return target_lanelets; +} } // namespace route_handler diff --git a/planning/static_centerline_optimizer/CMakeLists.txt b/planning/static_centerline_optimizer/CMakeLists.txt index 829c06c1fba12..cc33f2234a50c 100644 --- a/planning/static_centerline_optimizer/CMakeLists.txt +++ b/planning/static_centerline_optimizer/CMakeLists.txt @@ -22,6 +22,8 @@ autoware_package() ament_auto_add_executable(main src/main.cpp src/static_centerline_optimizer_node.cpp + src/centerline_source/optimization_trajectory_based_centerline.cpp + src/centerline_source/bag_ego_trajectory_based_centerline.cpp src/utils.cpp ) diff --git a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml index 4fdee8a0ca6fc..24a5536949479 100644 --- a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml +++ b/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml @@ -1,5 +1,5 @@ /**: ros__parameters: - centerline_source: "optimization_trajectory_base" # select from "optimization_trajectory_base" and "bag_ego_trajectory_base" marker_color: ["FF0000", "00FF00", "0000FF"] marker_color_dist_thresh : [0.1, 0.2, 0.3] + output_trajectory_interval: 1.0 diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp new file mode 100644 index 0000000000000..db954b6ccbd47 --- /dev/null +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -0,0 +1,29 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ + +#include "rclcpp/rclcpp.hpp" +#include "static_centerline_optimizer/type_alias.hpp" + +#include +#include +#include + +namespace static_centerline_optimizer +{ +std::vector generate_centerline_with_bag(rclcpp::Node & node); +} // namespace static_centerline_optimizer +#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp new file mode 100644 index 0000000000000..6e52ff98d78da --- /dev/null +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp @@ -0,0 +1,45 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT + +#include "rclcpp/rclcpp.hpp" +#include "static_centerline_optimizer/type_alias.hpp" + +#include +#include +#include + +namespace static_centerline_optimizer +{ +class OptimizationTrajectoryBasedCenterline +{ +public: + OptimizationTrajectoryBasedCenterline() = default; + explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node); + std::vector generate_centerline_with_optimization( + rclcpp::Node & node, const RouteHandler & route_handler, + const std::vector & route_lane_ids); + +private: + std::vector optimize_trajectory(const Path & raw_path) const; + + rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; + rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; +}; +} // namespace static_centerline_optimizer +// clang-format off +#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +// clang-format on diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index a920139a94472..242a76ae0d94f 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -16,6 +16,7 @@ #define STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ #include "rclcpp/rclcpp.hpp" +#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" #include "static_centerline_optimizer/srv/load_map.hpp" #include "static_centerline_optimizer/srv/plan_path.hpp" #include "static_centerline_optimizer/srv/plan_route.hpp" @@ -25,6 +26,7 @@ #include #include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" #include @@ -37,6 +39,12 @@ using static_centerline_optimizer::srv::LoadMap; using static_centerline_optimizer::srv::PlanPath; using static_centerline_optimizer::srv::PlanRoute; +struct CenterlineWithRoute +{ + std::vector centerline{}; + std::vector route_lane_ids{}; +}; + class StaticCenterlineOptimizerNode : public rclcpp::Node { public: @@ -44,11 +52,6 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node void run(); private: - struct CenterlineWithRoute - { - std::vector centerline{}; - std::vector route_lane_ids{}; - }; // load map void load_map(const std::string & lanelet2_input_file_path); void on_load_map( @@ -60,13 +63,12 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node void on_plan_route( const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response); - // plan path + // plan centerline CenterlineWithRoute generate_centerline_with_route(); - std::vector plan_path(const std::vector & route_lane_ids); - std::vector optimize_trajectory(const Path & raw_path) const; void on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); + void update_centerline_range(const int traj_start_index, const int traj_end_index); void evaluate( const std::vector & route_lane_ids, const std::vector & optimized_traj_points); @@ -88,19 +90,19 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node BagEgoTrajectoryBase, }; CenterlineSource centerline_source_; + OptimizationTrajectoryBasedCenterline optimization_trajectory_based_centerline_; // publisher rclcpp::Publisher::SharedPtr pub_map_bin_{nullptr}; - rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; - rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; rclcpp::Publisher::SharedPtr pub_debug_unsafe_footprints_{nullptr}; - rclcpp::Publisher::SharedPtr pub_whole_optimized_centerline_{nullptr}; - rclcpp::Publisher::SharedPtr pub_optimized_centerline_{nullptr}; + rclcpp::Publisher::SharedPtr pub_whole_centerline_{nullptr}; + rclcpp::Publisher::SharedPtr pub_centerline_{nullptr}; // subscriber rclcpp::Subscription::SharedPtr sub_traj_start_index_; rclcpp::Subscription::SharedPtr sub_traj_end_index_; rclcpp::Subscription::SharedPtr sub_save_map_; + rclcpp::Subscription::SharedPtr sub_traj_resample_interval_; // service rclcpp::Service::SharedPtr srv_load_map_; diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp index 8c8c346557fce..52dcd171e8658 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp @@ -28,6 +28,9 @@ namespace static_centerline_optimizer { namespace utils { +lanelet::ConstLanelets get_lanelets_from_ids( + const RouteHandler & route_handler, const std::vector & lane_ids); + geometry_msgs::msg::Pose get_center_pose( const RouteHandler & route_handler, const size_t lanelet_id); diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index 2e163e2eb93eb..10718150d1751 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -5,6 +5,9 @@ + + + @@ -78,6 +81,8 @@ + + diff --git a/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..8164b521553c8 --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_optimizer --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..3967c7a4ca523 --- /dev/null +++ b/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/scripts/tmp/run.sh b/planning/static_centerline_optimizer/scripts/tmp/run.sh deleted file mode 100755 index 9e475b9d8759b..0000000000000 --- a/planning/static_centerline_optimizer/scripts/tmp/run.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp new file mode 100644 index 0000000000000..150218b498ae7 --- /dev/null +++ b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -0,0 +1,82 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" + +#include "rclcpp/serialization.hpp" +#include "rosbag2_cpp/reader.hpp" +#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" + +#include + +namespace static_centerline_optimizer +{ +std::vector generate_centerline_with_bag(rclcpp::Node & node) +{ + const auto bag_filename = node.declare_parameter("bag_filename"); + + rosbag2_cpp::Reader bag_reader; + bag_reader.open(bag_filename); + + rclcpp::Serialization bag_serialization; + std::vector centerline_traj_points; + while (bag_reader.has_next()) { + const rosbag2_storage::SerializedBagMessageSharedPtr msg = bag_reader.read_next(); + + if (msg->topic_name != "/localization/kinematic_state") { + continue; + } + + rclcpp::SerializedMessage serialized_msg(*msg->serialized_data); + const auto ros_msg = std::make_shared(); + + bag_serialization.deserialize_message(&serialized_msg, ros_msg.get()); + + if (!centerline_traj_points.empty()) { + constexpr double epsilon = 1e-1; + if ( + std::abs(centerline_traj_points.back().pose.position.x - ros_msg->pose.pose.position.x) < + epsilon && + std::abs(centerline_traj_points.back().pose.position.y - ros_msg->pose.pose.position.y) < + epsilon) { + continue; + } + } + TrajectoryPoint centerline_traj_point; + centerline_traj_point.pose.position = ros_msg->pose.pose.position; + // std::cerr << centerline_traj_point.pose.position.x << " " + // << centerline_traj_point.pose.position.y << std::endl; + centerline_traj_points.push_back(centerline_traj_point); + } + + RCLCPP_INFO(node.get_logger(), "Extracted centerline from the bag."); + + // calculate rough orientation of centerline trajectory points + for (size_t i = 0; i < centerline_traj_points.size(); ++i) { + if (i == centerline_traj_points.size() - 1) { + if (i != 0) { + centerline_traj_points.at(i).pose.orientation = + centerline_traj_points.at(i - 1).pose.orientation; + } + } else { + const double yaw_angle = tier4_autoware_utils::calcAzimuthAngle( + centerline_traj_points.at(i).pose.position, centerline_traj_points.at(i + 1).pose.position); + centerline_traj_points.at(i).pose.orientation = + tier4_autoware_utils::createQuaternionFromYaw(yaw_angle); + } + } + + return centerline_traj_points; +} +} // namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp new file mode 100644 index 0000000000000..5bce91be722ca --- /dev/null +++ b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -0,0 +1,192 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" + +#include "motion_utils/resample/resample.hpp" +#include "motion_utils/trajectory/conversion.hpp" +#include "obstacle_avoidance_planner/node.hpp" +#include "path_smoother/elastic_band_smoother.hpp" +#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_optimizer/utils.hpp" + +namespace static_centerline_optimizer +{ +namespace +{ +rclcpp::NodeOptions create_node_options() +{ + return rclcpp::NodeOptions{}; +} + +rclcpp::QoS create_transient_local_qos() +{ + return rclcpp::QoS{1}.transient_local(); +} +Path convert_to_path(const PathWithLaneId & path_with_lane_id) +{ + Path path; + path.header = path_with_lane_id.header; + path.left_bound = path_with_lane_id.left_bound; + path.right_bound = path_with_lane_id.right_bound; + for (const auto & point : path_with_lane_id.points) { + path.points.push_back(point.point); + } + + return path; +} + +Trajectory convert_to_trajectory(const Path & path) +{ + Trajectory traj; + for (const auto & point : path.points) { + TrajectoryPoint traj_point; + traj_point.pose = point.pose; + traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; + traj_point.lateral_velocity_mps = point.lateral_velocity_mps; + traj_point.heading_rate_rps = point.heading_rate_rps; + + traj.points.push_back(traj_point); + } + return traj; +} +} // namespace + +OptimizationTrajectoryBasedCenterline::OptimizationTrajectoryBasedCenterline(rclcpp::Node & node) +{ + pub_raw_path_with_lane_id_ = + node.create_publisher("input_centerline", create_transient_local_qos()); + pub_raw_path_ = node.create_publisher("debug/raw_centerline", create_transient_local_qos()); +} + +std::vector +OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( + rclcpp::Node & node, const RouteHandler & route_handler, + const std::vector & route_lane_ids) +{ + const auto route_lanelets = utils::get_lanelets_from_ids(route_handler, route_lane_ids); + + // optimize centerline inside the lane + const auto start_center_pose = utils::get_center_pose(route_handler, route_lane_ids.front()); + + // get ego nearest search parameters and resample interval in behavior_path_planner + const double ego_nearest_dist_threshold = + node.has_parameter("ego_nearest_dist_threshold") + ? node.get_parameter("ego_nearest_dist_threshold").as_double() + : node.declare_parameter("ego_nearest_dist_threshold"); + const double ego_nearest_yaw_threshold = + node.has_parameter("ego_nearest_yaw_threshold") + ? node.get_parameter("ego_nearest_yaw_threshold").as_double() + : node.declare_parameter("ego_nearest_yaw_threshold"); + const double behavior_path_interval = node.has_parameter("output_path_interval") + ? node.get_parameter("output_path_interval").as_double() + : node.declare_parameter("output_path_interval"); + const double behavior_vel_interval = + node.has_parameter("behavior_output_path_interval") + ? node.get_parameter("behavior_output_path_interval").as_double() + : node.declare_parameter("behavior_output_path_interval"); + + // extract path with lane id from lanelets + const auto raw_path_with_lane_id = [&]() { + const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( + route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold, + ego_nearest_yaw_threshold); + return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval); + }(); + pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); + RCLCPP_INFO(node.get_logger(), "Calculated raw path with lane id and published."); + + // convert path with lane id to path + const auto raw_path = [&]() { + const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); + return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); + }(); + pub_raw_path_->publish(raw_path); + RCLCPP_INFO(node.get_logger(), "Converted to path and published."); + + // smooth trajectory and road collision avoidance + const auto optimized_traj_points = optimize_trajectory(raw_path); + RCLCPP_INFO( + node.get_logger(), + "Smoothed trajectory and made it collision free with the road and published."); + + return optimized_traj_points; +} + +std::vector OptimizationTrajectoryBasedCenterline::optimize_trajectory( + const Path & raw_path) const +{ + // convert to trajectory points + const auto raw_traj_points = [&]() { + const auto raw_traj = convert_to_trajectory(raw_path); + return motion_utils::convertToTrajectoryPointArray(raw_traj); + }(); + + // create an instance of elastic band and model predictive trajectory. + const auto eb_path_smoother_ptr = + path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); + const auto mpt_optimizer_ptr = + obstacle_avoidance_planner::ObstacleAvoidancePlanner(create_node_options()).getMPTOptimizer(); + + // NOTE: The optimization is executed every valid_optimized_traj_points_num points. + constexpr int valid_optimized_traj_points_num = 10; + const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num; + + // NOTE: num_initial_optimization exists to make the both optimizations stable since they may use + // warm start. + constexpr int num_initial_optimization = 2; + + std::vector whole_optimized_traj_points; + for (int virtual_ego_pose_idx = -num_initial_optimization; + virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) { + // calculate virtual ego pose for the optimization + constexpr int virtual_ego_pose_offset_idx = 1; + const auto virtual_ego_pose = + raw_traj_points + .at( + valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) + + virtual_ego_pose_offset_idx) + .pose; + + // smooth trajectory by elastic band in the path_smoother package + const auto smoothed_traj_points = + eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); + + // road collision avoidance by model predictive trajectory in the obstacle_avoidance_planner + // package + const obstacle_avoidance_planner::PlannerData planner_data{ + raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, + virtual_ego_pose}; + const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); + + // connect the previously and currently optimized trajectory points + for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { + const double dist = tier4_autoware_utils::calcDistance2d( + whole_optimized_traj_points.at(j), optimized_traj_points.front()); + if (dist < 0.5) { + const std::vector extracted_whole_optimized_traj_points{ + whole_optimized_traj_points.begin(), + whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1}; + whole_optimized_traj_points = extracted_whole_optimized_traj_points; + break; + } + } + for (size_t j = 0; j < optimized_traj_points.size(); ++j) { + whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); + } + } + + return whole_optimized_traj_points; +} +} // namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 0feebe8cbceb6..4f729ab5c8c57 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -21,8 +21,7 @@ #include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "obstacle_avoidance_planner/node.hpp" -#include "path_smoother/elastic_band_smoother.hpp" +#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "static_centerline_optimizer/msg/points_with_lane_id.hpp" #include "static_centerline_optimizer/type_alias.hpp" #include "static_centerline_optimizer/utils.hpp" @@ -35,6 +34,7 @@ #include #include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" #include @@ -57,34 +57,6 @@ namespace static_centerline_optimizer { namespace { -Path convert_to_path(const PathWithLaneId & path_with_lane_id) -{ - Path path; - path.header = path_with_lane_id.header; - path.left_bound = path_with_lane_id.left_bound; - path.right_bound = path_with_lane_id.right_bound; - for (const auto & point : path_with_lane_id.points) { - path.points.push_back(point.point); - } - - return path; -} - -Trajectory convert_to_trajectory(const Path & path) -{ - Trajectory traj; - for (const auto & point : path.points) { - TrajectoryPoint traj_point; - traj_point.pose = point.pose; - traj_point.longitudinal_velocity_mps = point.longitudinal_velocity_mps; - traj_point.lateral_velocity_mps = point.lateral_velocity_mps; - traj_point.heading_rate_rps = point.heading_rate_rps; - - traj.points.push_back(traj_point); - } - return traj; -} - [[maybe_unused]] lanelet::ConstLanelets get_lanelets_from_route( const RouteHandler & route_handler, const LaneletRoute & route) { @@ -109,22 +81,6 @@ std::vector get_lane_ids_from_route(const LaneletRoute & route) return lane_ids; } -lanelet::ConstLanelets get_lanelets_from_ids( - const RouteHandler & route_handler, const std::vector & lane_ids) -{ - lanelet::ConstLanelets lanelets; - for (const lanelet::Id lane_id : lane_ids) { - const auto lanelet = route_handler.getLaneletsFromId(lane_id); - lanelets.push_back(lanelet); - } - return lanelets; -} - -rclcpp::NodeOptions create_node_options() -{ - return rclcpp::NodeOptions{}; -} - rclcpp::QoS create_transient_local_qos() { return rclcpp::QoS{1}.transient_local(); @@ -216,6 +172,15 @@ std_msgs::msg::Header createHeader(const rclcpp::Time & now) header.stamp = now; return header; } + +std::vector resampleTrajectoryPoints( + const std::vector & input_traj_points, const double resample_interval) +{ + // resample and calculate trajectory points' orientation + const auto input_traj = motion_utils::convertToTrajectory(input_traj_points); + auto resampled_input_traj = motion_utils::resampleTrajectory(input_traj, resample_interval); + return motion_utils::convertToTrajectoryPointArray(resampled_input_traj); +} } // namespace StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( @@ -224,13 +189,9 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( { // publishers pub_map_bin_ = create_publisher("lanelet2_map_topic", create_transient_local_qos()); - pub_raw_path_with_lane_id_ = - create_publisher("input_centerline", create_transient_local_qos()); - pub_raw_path_ = create_publisher("debug/raw_centerline", create_transient_local_qos()); - pub_whole_optimized_centerline_ = + pub_whole_centerline_ = create_publisher("output_whole_centerline", create_transient_local_qos()); - pub_optimized_centerline_ = - create_publisher("output_centerline", create_transient_local_qos()); + pub_centerline_ = create_publisher("output_centerline", create_transient_local_qos()); // debug publishers pub_debug_unsafe_footprints_ = @@ -240,32 +201,16 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( sub_traj_start_index_ = create_subscription( "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!centerline_with_route_ || traj_end_index_ + 1 < msg.data) { - return; + if (msg.data <= traj_end_index_ + 1) { + update_centerline_range(msg.data, traj_end_index_); } - traj_start_index_ = msg.data; - - const auto & c = *centerline_with_route_; - const auto selected_centerline = std::vector( - c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - - pub_optimized_centerline_->publish( - motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_traj_end_index_ = create_subscription( "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (!centerline_with_route_ || msg.data + 1 < traj_start_index_) { - return; + if (traj_start_index_ <= msg.data + 1) { + update_centerline_range(traj_start_index_, msg.data); } - traj_end_index_ = msg.data; - - const auto & c = *centerline_with_route_; - const auto selected_centerline = std::vector( - c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); - - pub_optimized_centerline_->publish( - motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); }); sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { @@ -280,6 +225,11 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); } }); + sub_traj_resample_interval_ = create_subscription( + "/centerline_updater_helper/traj_resample_interval", rclcpp::QoS{1}, + [this]([[maybe_unused]] const std_msgs::msg::Float32 & msg) { + // TODO(murooka) + }); // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -308,6 +258,7 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( centerline_source_ = [&]() { const auto centerline_source_param = declare_parameter("centerline_source"); if (centerline_source_param == "optimization_trajectory_base") { + optimization_trajectory_based_centerline_ = OptimizationTrajectoryBasedCenterline(*this); return CenterlineSource::OptimizationTrajectoryBase; } else if (centerline_source_param == "bag_ego_trajectory_base") { return CenterlineSource::BagEgoTrajectoryBase; @@ -317,6 +268,24 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( }(); } +void StaticCenterlineOptimizerNode::update_centerline_range( + const int traj_start_index, const int traj_end_index) +{ + if (!centerline_with_route_) { + return; + } + + traj_start_index_ = traj_start_index; + traj_end_index_ = traj_end_index; + + const auto & centerline = centerline_with_route_->centerline; + const auto selected_centerline = std::vector( + centerline.begin() + traj_start_index_, centerline.begin() + traj_end_index_ + 1); + + pub_centerline_->publish( + motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); +} + void StaticCenterlineOptimizerNode::run() { // declare planning setting parameters @@ -334,20 +303,53 @@ void StaticCenterlineOptimizerNode::run() centerline_with_route_ = centerline_with_route; } -StaticCenterlineOptimizerNode::CenterlineWithRoute -StaticCenterlineOptimizerNode::generate_centerline_with_route() +CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_route() { - if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { - const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); - const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); - const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); - const auto optimized_traj_points = plan_path(route_lane_ids); - return CenterlineWithRoute{optimized_traj_points, route_lane_ids}; - } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { + if (!route_handler_ptr_) { + RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); return CenterlineWithRoute{}; } - throw std::logic_error("The centerline source is not supported in static_centerline_optimizer."); + auto centerline_with_route = [&]() { + if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { + const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); + const lanelet::Id end_lanelet_id = declare_parameter("end_lanelet_id"); + const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + const auto optimized_centerline = + optimization_trajectory_based_centerline_.generate_centerline_with_optimization( + *this, *route_handler_ptr_, route_lane_ids); + return CenterlineWithRoute{optimized_centerline, route_lane_ids}; + } else if (centerline_source_ == CenterlineSource::BagEgoTrajectoryBase) { + const auto bag_centerline = generate_centerline_with_bag(*this); + const auto start_lanelets = + route_handler_ptr_->getClosestLanelets(bag_centerline.front().pose); + const auto end_lanelets = route_handler_ptr_->getClosestLanelets(bag_centerline.back().pose); + if (start_lanelets.empty() || end_lanelets.empty()) { + RCLCPP_ERROR(get_logger(), "Nearest lanelets to the bag's centerline are not found."); + return CenterlineWithRoute{}; + } + + const lanelet::Id start_lanelet_id = start_lanelets.front().id(); + const lanelet::Id end_lanelet_id = end_lanelets.front().id(); + const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); + + return CenterlineWithRoute{bag_centerline, route_lane_ids}; + } + throw std::logic_error( + "The centerline source is not supported in static_centerline_optimizer."); + }(); + + const double output_trajectory_interval = declare_parameter("output_trajectory_interval"); + centerline_with_route.centerline = + resampleTrajectoryPoints(centerline_with_route.centerline, output_trajectory_interval); + + pub_whole_centerline_->publish( + motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + + pub_centerline_->publish( + motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + + return centerline_with_route; } void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) @@ -443,7 +445,7 @@ std::vector StaticCenterlineOptimizerNode::plan_route( plugin_loader.createSharedInstance("mission_planner::lanelet2::DefaultPlanner"); // initialize mission_planner - auto node = rclcpp::Node("po"); + auto node = rclcpp::Node("mission_planner"); mission_planner->initialize(&node, map_bin_ptr_); // plan route @@ -472,7 +474,7 @@ void StaticCenterlineOptimizerNode::on_plan_route( // plan route const auto route_lane_ids = plan_route(start_lanelet_id, end_lanelet_id); - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); // extract lane ids std::vector lane_ids; @@ -491,133 +493,6 @@ void StaticCenterlineOptimizerNode::on_plan_route( response->lane_ids = lane_ids; } -std::vector StaticCenterlineOptimizerNode::plan_path( - const std::vector & route_lane_ids) -{ - if (!route_handler_ptr_) { - RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); - return std::vector{}; - } - - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - - // optimize centerline inside the lane - const auto start_center_pose = - utils::get_center_pose(*route_handler_ptr_, route_lane_ids.front()); - - // get ego nearest search parameters and resample interval in behavior_path_planner - const double ego_nearest_dist_threshold = - has_parameter("ego_nearest_dist_threshold") - ? get_parameter("ego_nearest_dist_threshold").as_double() - : declare_parameter("ego_nearest_dist_threshold"); - const double ego_nearest_yaw_threshold = - has_parameter("ego_nearest_yaw_threshold") - ? get_parameter("ego_nearest_yaw_threshold").as_double() - : declare_parameter("ego_nearest_yaw_threshold"); - const double behavior_path_interval = has_parameter("output_path_interval") - ? get_parameter("output_path_interval").as_double() - : declare_parameter("output_path_interval"); - const double behavior_vel_interval = - has_parameter("behavior_output_path_interval") - ? get_parameter("behavior_output_path_interval").as_double() - : declare_parameter("behavior_output_path_interval"); - - // extract path with lane id from lanelets - const auto raw_path_with_lane_id = [&]() { - const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id( - *route_handler_ptr_, route_lanelets, start_center_pose, ego_nearest_dist_threshold, - ego_nearest_yaw_threshold); - return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval); - }(); - pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id); - RCLCPP_INFO(get_logger(), "Calculated raw path with lane id and published."); - - // convert path with lane id to path - const auto raw_path = [&]() { - const auto non_resampled_path = convert_to_path(raw_path_with_lane_id); - return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval); - }(); - pub_raw_path_->publish(raw_path); - RCLCPP_INFO(get_logger(), "Converted to path and published."); - - // smooth trajectory and road collision avoidance - const auto optimized_traj_points = optimize_trajectory(raw_path); - pub_whole_optimized_centerline_->publish( - motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); - pub_optimized_centerline_->publish( - motion_utils::convertToTrajectory(optimized_traj_points, raw_path.header)); - RCLCPP_INFO( - get_logger(), "Smoothed trajectory and made it collision free with the road and published."); - - return optimized_traj_points; -} - -std::vector StaticCenterlineOptimizerNode::optimize_trajectory( - const Path & raw_path) const -{ - // convert to trajectory points - const auto raw_traj_points = [&]() { - const auto raw_traj = convert_to_trajectory(raw_path); - return motion_utils::convertToTrajectoryPointArray(raw_traj); - }(); - - // create an instance of elastic band and model predictive trajectory. - const auto eb_path_smoother_ptr = - path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother(); - const auto mpt_optimizer_ptr = - obstacle_avoidance_planner::ObstacleAvoidancePlanner(create_node_options()).getMPTOptimizer(); - - // NOTE: The optimization is executed every valid_optimized_traj_points_num points. - constexpr int valid_optimized_traj_points_num = 10; - const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num; - - // NOTE: num_initial_optimization exists to make the both optimizations stable since they may use - // warm start. - constexpr int num_initial_optimization = 2; - - std::vector whole_optimized_traj_points; - for (int virtual_ego_pose_idx = -num_initial_optimization; - virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) { - // calculate virtual ego pose for the optimization - constexpr int virtual_ego_pose_offset_idx = 1; - const auto virtual_ego_pose = - raw_traj_points - .at( - valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) + - virtual_ego_pose_offset_idx) - .pose; - - // smooth trajectory by elastic band in the path_smoother package - const auto smoothed_traj_points = - eb_path_smoother_ptr->smoothTrajectory(raw_traj_points, virtual_ego_pose); - - // road collision avoidance by model predictive trajectory in the obstacle_avoidance_planner - // package - const obstacle_avoidance_planner::PlannerData planner_data{ - raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound, - virtual_ego_pose}; - const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data); - - // connect the previously and currently optimized trajectory points - for (size_t j = 0; j < whole_optimized_traj_points.size(); ++j) { - const double dist = tier4_autoware_utils::calcDistance2d( - whole_optimized_traj_points.at(j), optimized_traj_points.front()); - if (dist < 0.5) { - const std::vector extracted_whole_optimized_traj_points{ - whole_optimized_traj_points.begin(), - whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1}; - whole_optimized_traj_points = extracted_whole_optimized_traj_points; - break; - } - } - for (size_t j = 0; j < optimized_traj_points.size(); ++j) { - whole_optimized_traj_points.push_back(optimized_traj_points.at(j)); - } - } - - return whole_optimized_traj_points; -} - void StaticCenterlineOptimizerNode::on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response) { @@ -629,7 +504,7 @@ void StaticCenterlineOptimizerNode::on_plan_path( // get lanelets from route lane ids const auto route_lane_ids = request->route; - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); // check if input route lanelets are connected to each other. const auto unconnected_lane_ids = check_lanelet_connection(*route_handler_ptr_, route_lanelets); @@ -641,7 +516,9 @@ void StaticCenterlineOptimizerNode::on_plan_path( } // plan path - const auto optimized_traj_points = plan_path(route_lane_ids); + const auto optimized_traj_points = + optimization_trajectory_based_centerline_.generate_centerline_with_optimization( + *this, *route_handler_ptr_, route_lane_ids); // check calculation result if (optimized_traj_points.empty()) { @@ -693,7 +570,7 @@ void StaticCenterlineOptimizerNode::evaluate( const std::vector & route_lane_ids, const std::vector & optimized_traj_points) { - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); const auto dist_thresh_vec = has_parameter("marker_color_dist_thresh") ? get_parameter("marker_color_dist_thresh").as_double_array() @@ -770,7 +647,7 @@ void StaticCenterlineOptimizerNode::save_map( } const auto & c = centerline_with_route; - const auto route_lanelets = get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); + const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, c.route_lane_ids); // update centerline in map utils::update_centerline(*route_handler_ptr_, route_lanelets, c.centerline); diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_optimizer/src/utils.cpp index f8cc0953a6dbd..3cc7ed5ca1fda 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_optimizer/src/utils.cpp @@ -45,6 +45,17 @@ lanelet::Point3d createPoint3d(const double x, const double y, const double z = namespace utils { +lanelet::ConstLanelets get_lanelets_from_ids( + const RouteHandler & route_handler, const std::vector & lane_ids) +{ + lanelet::ConstLanelets lanelets; + for (const lanelet::Id lane_id : lane_ids) { + const auto lanelet = route_handler.getLaneletsFromId(lane_id); + lanelets.push_back(lanelet); + } + return lanelets; +} + geometry_msgs::msg::Pose get_center_pose( const RouteHandler & route_handler, const size_t lanelet_id) { diff --git a/planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 b/planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 new file mode 100644 index 0000000000000000000000000000000000000000..0883307acbae0ff5e4a42efa165cba8ae262ae64 GIT binary patch literal 2654208 zcmeEP2YeINAHU9Y&{imWmc2Wx~3IVz62gYxmAhDJqERDX?yc-avr6TT& zhzOq^_AdO0FQfoc04abJKnfrQkOD{nqySO?De&K>KvqCtv#xD?iq$$5J=d(((k8P) zYmlo|bKysmB9Ar&CQlrZlsO_QW!&%)Q=%#ii5fpH$}udeTiIJtNg2uAt&#qcW^LN| zSc}by91ZOl=J+>&`_{~)VW}g^zNDL41%D@V#HbMyqtYj)q$N$98Z~yr)Lv%2L9K*` zDtmL>_{^wrlTuTAmH$!4=gQuSQYp-es9~w&hebK=b+<2q^wBdwCp(VOH3 zqdr%yp-mOPxVzQQ*G|Z(93jmLGBGV}|JSd=V>|BhJ-Fk2c_D2y!BbTxsAI$}Poef< z>1OTCK7>h`PiqzSt8aw|u;1%u|EJPlaptKJrmRw%%trk!e~Q@VJ`tBF_zz!50i*y@ z04abJKnfrQkOD{nqySO?DS#9}3jCKS5bWniwaB+l~MSKzQNyG;c z`y<|r*cq`SVtd4vh{q!yf-L^KBbGSV?O z*I`TnT$30jT!%7K;W~sF57)uWNVpDShQM_o(-*D-m_Bgr&vb-qKc)p-yD?4S+LZ~1 zYZoR2uALcQxOTD@!L_4R2iFePJh-;E&V*}}brM|LSySQK)|w30HrD=dZEcmpwUxCC zTw7Y(z_o=n60Xgy!EkM6g$vbmE?k=E;nJ9fOXM`TG)jj{!x3-^BVX2FFkC|8;1bdu zF2U{K64V4Pl2Bs*`$SxYtM4TCANUDhNCBh(QUED{6hI0f1&{(r0i*y@04abJKnnbK zDBzp9B7%4&8box1tM8JCvk^xk4n({bu{mO01QTJ1m>H28F@SyZzcXo^2~q$lfD}Lq zAO(;DNCBh(QUED{6hI0f1zb|VcXF6tpl`D$!m^+9xv)CK2o`e}?#{Fi0HYR+_#A*c^SC?dlyW258xviEfC&3*~-iHQmQq7&hsMx9HW3<{llpDBb#(Lsw&`-5rJ zj^E`PT4AE)DtIu`cG8_MRTS#gDmm%PNcvmCBPnUQQm-qdb>y4iFXbvUCYs3)kx*s}*@V zy~(Ur!vFjdBw3>{nbf&zS~a}<1Bh=SeCJ6(luW9U@JfS4ZXpebU6S2knMB4Qr3EN$ z^9z(vimD;5)N8d0ol0t=HMG)9tE7c=zFMhqN%+b3A<6cSf}GJBXcclnfD6pR00}i| zPStpaPSH8`JzEYvxIq(f3H=pIj<@Ntkcw10m5t`y`_R zj{DE`Jqb7Q8K2y$$;l<#?Q7gx@-+{`ZD92WAB#8KoTRBoD>WNm)8AYaIlbP0*Q#*-M zB#ADL#;BkNQP~J|mNG);D%2XeNs&uSwMH##`_K-W%i*XSaMTvYl#@EmsI4KD>x;%R zx1oee(>mbn@O-lx3#SE238Y;cnw+6eNNzE~743X6F7kpqB-DuPDoJlND=XOddO+FG-n+(uwh&U$~+&x9? zo~->(Euq2}G`J9YcSzfyEt2SfFChN!2RCoiYsvg}5~_DrJzzv=yCC#L7-yI4)u(WM!Sl4%K;blpLFAw?`B#v_NL(TKnp;Vz6t#o64!10X z@j+LFOf`9~f_QCR%MAO_k?crR5k;wp=9X2G9Xx|@?z1jW1lcpVp-6U;2Px7v(zTFK zvOEXc?FK%$%jH_Vie?>Jt|W>*fDgmdU^J_hqj(V#FY@LRN?MkLsMWKP2-fs*u{ox( z!;r#aB#AA!Sr9eV>f^w)vxzTNlhBWo#V??gINSRv6+Vi*5XB3ssf3zQX81e8q7Dt5 zz}{k#LRK`KTd!edPWd9JGQT3(K9tCtiL?RIi>fbh>WOV=kN@98^8Z_eJ{OW0^oC?u zz;6EmzMuKrbDPY6{4-7zV1{&;Pzln=B|W7%iae+aD4>mG1*q7Vw8^Y0k6#Sa>oxrN zj*f<1-en1e2hAb!RZ&s)Y76pr%PS;qf5k*@H&9vZ_GJ+%PjN^SQk`O#D0UZag`$)s zGL$psiR{MG6v5II8`TwrcR}Qmu~G#~Xvmky%~dPq8g*X2nT>op?wHhhP#;uo6IGQ% z0qHE{(;4hg0i#F|+VwtRKf-hiDqCJITpVJA)oh?**&sI=Xj%nT&Pw=)R`KQOX28%4GI9hr5Vusp zoW=Yo$bGSU!C08zLi_SOy2?s?l2djlYVm?vyxsn9M1?O8YY=*0NY|jJC7lD_@{jgi z>eI-{EUiaBGIQc2)L3?F<2+ANQ@%RaELYJ=wF<29JW#3SO0CKPN}l9|Q80{C=lEB= zkS6Cr8(lwg+itYmy2b`kMb>sipKuVpVz7Z2Fgg?K1d&4lEtDY}r7Akdk|zgM zn@i+$1SYB)OFBv71>WQ^u3y+ad7B*YX!6-)#C|MJ7dtI|0 zd{!2t5qepa-C*6f_C1pOV7U!6g6kmSsBmU$qxDAO#zlq*MT`{DuvdOt!6_g?e`B5DLB~EPnDUsAR_i|*r zI5t@awP{CXGm$j*?UV~}ly9e89HXoV8Z7>rHlQWvQh0JKiX( zDoP>|JJ3*d$@W+@N*J-2@4<(8$dj|M{ncDxKFKkLqj!xlUr+RTd;WhE6<*ZfWa#MN zXM(~5_5NS`CHOo?MG>Rl7CKl$Evg{+!4l(2)8)B(jYeMtrkDm)Nh7oXuz0R2c11z3exebP;Ii5CkK`- zqcnC1hHOP;{I%{6jOooruxhq)RCJ-5RSKlViXvEKdHf=-Z#)V%k%FyxKVVO1PqPPE zq6OjPSX(Ff&xL^*aIH#hqtc&DGU_2y`R&cdcrJr#O zsq9sEyiulvq1%P@9&zq;FOCt!{tuLdQQ_tWr$S4D{|Qo371NT+ecP2wzuQN2Yp zKs)`_CNPim1~>u1ZW&e51XG}MBKv;zqY3qe-1Cwo6wP){bWLvXUqffyITo-`U6LKf zO>_)H>I=kjnAt-mR7QowtxCcMz-~}jOfHC?&c2Pr79h4QL?)q%DoFOK>`jecm!~#c zRBCdZnMnh(UJj)dj?-B%d?s|dnmC)&7CZ!UNZn&bd05PqLkvTiV;{~X95$pkb z^(5b+y1np_JT7|)AbF5HCK?x)%fmd8JV+i#mlXFs^@tus52D9Q=Pcvm!o`J)3m4bF zamM?d>fDllv8mg?N+KlBt*Ip%buMi(D0BndsC+~8#JS2cMDiec`bCq@ z+_<;|kbttsMfxS82hlSi3f=MOjz@RAKu!P}73lM+_dXwz-f2X?PrdW|pi={#8nk=< z8??L7?yBd8MSVR~1yyBKmFvB#jB2v3HmS*Y6o>sN4wTI(o2xIINwL2#^*ZI-0xosy z#bl3=Q1(_*<<%i3xgsyG{MV{_s9~orF`c@uWeyLbpc9n!a+0*1o&xRZkhEe*ixL|p zcJ(DTq6g7~=)sUhZL-CLjxnm|ZbKvwdtN8*T)1=L&Q*JME-?4QiTxi+O`^hgh0Siz zHRRRcK9bJ@r}-c7%kX&wua+LXH#f9>zdS#W55gbb7_tJe7sye98*HhN`{k@3TTZw zU$5s{DplR*1bGrAuB8TJ9w(s`zA(ZT5qNOqBAw}qv_NhL}_ zvg_awNrgtv%Az8*IUf#ZFH{)S>=CS3hCV)ewpvjvO^ zq9#~LN$pao9k?Sv5D51^u}`eF-Bj^FFH_Fx2x(*+9(MX10+n5 z=IRyYePlsQ=b6l^a%yInjc^_mKS6~cSzo%BCXbX*ZOZ70RIGOY{}3Mw6+XAYU!gOD zzYQ86croC9f2r@6a1&qNp#U>|8l0w^M5L)fq15VC(j23rfSlD0XGqJ92D3cIem|~U zDx{J3CK}8!yn-PXB`qgur%aVlQns^h1@b}<=}KhHD2ATK+GMSYwKI5WOJpjR6q;xz zcZ!5chJ$p0lQbGTor!i!M)1-ZF+707@YF0jhRX>} zv{xb=Dv{StTaXQ|F^sfz(00n?TjT?4H;^9lJhVmmAkzC_lS~4Cv>$kVZgD?Y%xaBP zY1A9!Ir_QsT(t(gpS)+F@;id?D90$Vobb(*Q1jekgtAzv0sjzp5G^vnRlgo_p#WRc z3|I~g!6|*qa$vpB<|4JpEYG!=NDziw5;c4Nhh@i@~lIN{zI_2nVv5OmdapZm9F+~Q5P2b^5)R_IMG6jRN~OrI_g%!{jJB{+h4aky;>Zd=o{1;`uAOWs%{uMl~O z{U73!Muk5SHYW6Z$m-x&$rk}i|4`qT;3mG@qX3hm2du*R#brS|$BC{c0}Wo?s>JPN zI$y2S&>3U^?qy>3vdKEIYn`nxvqi|RMZ-%BVJB(rge`N%u!ODB597$1a79=_)wZ5k z2}`sZFlb{UmxnqGFSEWHW>*ZFU7Y^~>quSJkuuW@z|e>Er?Op$b*O^dw8{+#vqusW z>?d!Ci(D~NW&?Sheb!~mCO|r~I?McigpOp`u z0B7yVl&{XM+Q(8R8C>o17!`0t1t#a&DO;vK*(qD4P(b~O9Caj8;7-f62MNpfGZwPE zB7wY%@<1GMiTxk!b0-!4eAu|qKSO#1%?Nza|B~NOxP`CVM*&;kxsWKPVAJ&sv{6YL zNM*QGpEH|Qf^epl`aDu52)9%;)CaOZDK!?*JV-cPs?_V0Y*D8fazzwo1!QFFl=()z zPF;d&mR`-DvBeevY z>OIf9@_KCxIA}z$4S6My-entO4x*UgY756I)|pzX$fHR%F4-7K-gFL|FU_q&wsVaX z-c>?(JmT=cT=oG`{bOU}Tpo%jQfQ7e0W*DWH#2ef^Yre=OfiB3E7{3ESPV&*kYG$# z>0z0wD4GcGp?5`$cV*@r2{q6;=dviDhN?aO@Lv{rAA^6QeF5VPka0E8DdVb8U3E_D zWVOx}WD~FuhAo64_J0sHh6)=HVhDO&;u|o{Z>!H$xZ(E8*2@atWQ}o4Gb^)Z*9Ow!ZU$Pt|t4qCpD1WB-+d!ECYffN|A!y^3KR8lRrl zI!Z^C0MkZfL@t*|%Ux{Z10C2wqL5o}a&HSpOtW&CW>uP83`idAStO&t@wC7}6uU&R zJ^tT}3LoEKTc}U)M9DjW-Te)|JA9hC?Ev^MeZbb-8VsvD*e&bWpjYdlI~QC?OdcH< zY%gSY&X^Y&i0E$(0^a1g6^W?G8!@^cMv?S7FEB5`Dgoxnz05q^M?JldfqTYC}Z7{aJV7;YhI+TRzF}@vd7tl zTad@aTsx~Tu&S9`a<0kO+N3ZLl@8b?{2b z^+1jPQNJ`e{jX1DgWeWqjf6wC*n?NZdT)(-wJDBk^=q-HxijX;ni6lF}OUuvpmA8vpk}4d3bGkG^ozGd+3w)xU;6CH3ZnzuKMhf7Q)H#P|aLk2#s0bP_^LMQdkoI522E% zaASkxp&7yZf|>^A`k(O2@%aXBih0=@S=#`gTU7R+!XdcO*iLSu^R&>#)y~JNPXIz! zsi)a$lUQ3zr~<8Ul`QLFb1PpVlP%M5)GlKYtUwVgGvC?@&YFQU^Pn+|%VKkbkyfeg zy&bd)9c?M3jfHBH1*9N%taMp}?lgrF3T4nmCdx%dSzAh|sdI$sFFGoaZf8_k{XVV% zfi(cNVJ%>jNUOX_xae_fXH&3<%o1-(Z zap0}VDiwL*+**;3jT~2LmDKTBlR8hQ&;T20V|JYWGzS+BlQqqnFy^H5)T44Q{tG!HvkJCdbU$vmvg2Jx&y%h2PN zVGC;qU{lvhY|5$1HP0Ram}k^mbSiYQn7m$HZEIp}56o#-L+0SB@%XCgW{m>IRN?!o zYSmQUdE|PFSp$jzE~4A8h&ox@0k5D4|5iU`O?ZWC%HwOQskJTesl7NpRUIV8dR%X0 z$lC4yd@6hb)c=PE7fB8W_V8cp`?pX2f6})9*Cu6aV3kU!qJmolmBXN{>{D>O!}WUnm3U>`^Sr=wlhfGBc;gGTN6-TMY+3u{l{S3|YvEyv;i zEDz~}Hy|%xN(#mVU7e}wynORSy&9dJqMV(P)*eL2)r>jF7BEyidN52&YjgH9gj?Mq~8AgRK z3u_p9Ur4K<$0cn7Hu-n;eHm`zO9TZNowdJ&nlOn~vos2wjwI6?6y|(##o zoYbk1Vy~e=WrbnYCpl5-RkT7ydSJUFOf~9U+5};3_deq=9&Woa!4z2&CDe?HBvDEq4WZ%XB~rJg^+YfIm83uSXTH6dEglyFoo8536<>z50LU6qkNn&<@59k4ayzQ zx*?dk)>sK87r=a(n@$duQIK&;auIR6jgITf7D?+^zfeE714E3-8Y7`53DCaGwT)!= zkgzdZqa{?90NHau%~ru_ih48B-7|Ez+y6OK_{y+Gq4$S$4ticPIN*K%@xEXA z*OLKS#%LV^%{;1rdAYN_f-4Mh?g^aht%IvpVVtOrDvU>gUT7UuwF*;Ca#UfwkrB;U ztOKi7VXCG)sxbXMV~T0lRP$8xWNXU2SLxfsO(TsN%|UEHOFPl^ePj6{?M9 z=uRt#7Dt*I&>feFo$NM$>quyfX0JVP2(+rmUe*?!%e$*$40H;XrgPsh**;!xv}fH_ zKi9FI=x_l45n|wP?=YlgTQMX2YpjETYj=3nuHABHI=Xf}-I;;4|EalD`1l47g`5oT zB{2lN;CIe90d9HqW$SO91Uf;UcXR?Uh!r_-_5iVQP0|XesliG`1%Xo#Y<;bnz&yom zVP08W0XgRZt7)(`130I@9h@VJuR?|eGSCAI9Aupc4AkCk2BN3QGeHhpKkEeGAALLc zhb|}2re)g_tm(izVizD2L!zzYfNPVyv)t$$OCDMVo;D|Ky{&1$v+>^K85#s06peQKe+%jV_h`uJ z;8+P0@Tq@uUj?v^TA0_RX=@}OLR zM26|WwyZ2~s7z{|!D5Eo6=umhq_XD$AZ|$~tA3&;^gz=q zA;L|Q!`nSb?8v@pb26dXq^RoEAal3L&usocDVso zIj~QCd)bE$HqSWNi2X0|SxSY+H&__7B5-ejzh6B3im%&B0b38N4%QHHnt9VmBc~Fe zj#zUYG1aOKqL?r*+hFHAI&M<^*n4Qt+Gg&88& zJnp$Q-*ZP>^I^{o@baEpF`|pRu2*(ld;CA23QudWH00CZwvwpPbI(7vIt@9>dg9V>}4V>79K;WS*1m=;Vubq+9$hxI6$5~=oZ;l^L;MaY5=x*JJ%Ha zR0cUYsTswkcf_UCss}cDJJ+;~jkxk^yz+?sA4)w>g%5`O|93)q1uYF~8mRZ*gWpW{;iEFe|hMT7~f)fwDO7r7 zgNs*S@miZ$=K(CBlCvhTC}UftU~PpEjypaP+W>0`z=vdzd&lap@MNAc{?Sv)`E2@H zi-CK$DLml`;}JQ>aZYBP3!Jmuo^|KZ{7Gb?orT2y5Ar`nMJU4_3Oy7$Hh4o&c%TJt z;0q~$6hI36Hz;5WVL~L-0wMdN%n&uv8rJrgq8Gp$C4)_vV9*=d3B|@aM^c%gVAAUK z=6rI3DWn`LbkOI^tcNqO^ac{sapm_zZ=cAH1p!Qugfa;&6V~bCICU0Rh&NV9G$Vl( zGRiGZ@cLcL7LZ1*RYTKNlxp56BeMoGf#4p2*pztp2rtW=BOAalX9t9+sHaWF1OR~K zUJSmlmb4?NhM^b874~pHi{Xqvuu$zy7HafGa+SVFXODVd2+b>Up#|dyaskRqJuesR z9&eL_jqb|{V*mU5G@$(R{6l?L!VmTM#mr;EB~(_$*i_lxnX4edK$EmQOSUYupin6c zYI$Kyd0=5O*Q9VH`yn>sjNt`=@B%ZR34;SbE0W)2rfE`$DYuhf>Rj33g8muY$B_Ps zurG;I{--hx0;#DA*HWsQ+Wv+nOsIq^$d24rZuOYymcijCtT*T#dbW5p#!x zk_#}PVn-@m1D;(2B}|0yW?a@)3aRf=>VtvPqry3<)%CV{@PO@@Xf~I|?u;itYt&$x zfFfps!(7SVDgRxrfe;`qS6Pf+@{b@n5FPx73iF{OI-0=NWdr1TwqB4Tw|2-ziXcTC zhm)fmx%IeqqzF<(s7nQ61Tlgb@l>u7>Lc}09|8NnrveHom3ovVC`(Y5M91}Yaz455 zP)3~u-GtC|Oam{##Ms|DKNo?EhY33xsh8#vK@UVBCRm z2gV&3ci`HRiT2;qNl+j0bRPo5NPUd$VO&pK<0G_d(5|Vkb`9A7y*=Mt0rwl+Z!ovj zWWXI5cVJpMAPVzH5^H=?Eoy0~rPWt04K*|nq8>Vy8084c5tJhs#lk2SiDH5M--m5_ zi_-NrcMw1y3HnITM}j^QjCNwQ6K$K@-M+|jl_P_Ms>7a)@ zFz&#(1LF>iJ239R^?3)z-M4mh^hJFH^%2xZP#-~k1oe^nqmO|7AB~laQML4x0n|xQ zCqbPAbrRG`P$#KBItl6{sE?4Usk(3u6l!Rwp`nI`8d_b|(7^tW0a1(gFYY%QbuJAH zSvP=ffX^0%;0}xwsZhL*7`e5aA1Q(qiH(hmbJgGgF@hLDjF1zYopcMqf>T^IxN30K z;Ht?{Yt-gq`^oPrTA@OUc#tAs|Hncb0JQd^qHw>#{Ra0Nl&&6>t|(cf6WQ!;^ek3v z0*QMK?lrjA;9i4!O$7>AjEV}sqqT<=(Won80x9B2ih%tem(UNjG|<#5r4PEvsaxC47~2gco(%{Rl{SGd3f^%2xZP#-~kq{42DJ`&VNs;`fL{U0CK7k6NL z1_b7$VRlVLZzD=ql&;m6t|(a@84xI0QL>_Btw;fstSDJkw85NDS{+1_5?mvV6hVsM z36*$4B7++Pv(R@7TjZ$-To^;XoU zmd2r$<~=P9H8jkTSDVawJZlfn+QYN<>grj0weg%iu>UEnK#Iyo>1tN%btqj?x}tQg z+=>is8?I1SE4q{rxbVx39UEDbwCb2 ze~9fbKc-m_)vABwoxdkbAy%%pn2kyekkw2Za}`S3j^9*$o_JEm+=5y5ch6uphIChQ z9PvSZF303;$0%QN2|N|{e*&q+b;Lq)MA;XB-93-wKysL9lpQ)TaSB{4xL9zp6w|%|g)x1CC~HK9bBI=>Rw+mrT&Gl+X&wA8 zS1HU2xv5yE%s1+F>Jr*0Rna*X2&ES*HEN~Ytk%*HB{!>SW4xSwr#xmpQlnRx`^IOO z6)=Sp>oLPMdM z{kdE$j8hb*PtN3rERr@?p)t|SET)Hq8Y|-`t=yzA%X8IpZ$&N;I749`sh*287D%39 z%uII)l}7W>7-%bpj48bm8fxazdM#}>7MJ5Vvj}R{vef4MWPPE+s8;BdG;Vbw9g!BM zn}nL6tVDMMq=LzdfToa;=OAij%BRC9B>aG=ehKb&24S+8t`aI{RF#CUn$U=8k(kbA zx=5(Fv`VA}DMG8NRFH@1^%^9vNb;JP&Jv2|Pv`CHa04icFpqaYlwfkONV3yRCztkr zU$p-{X8#BI7^(1r(077cN>&H_<8Sai1~>5KB?>UJnZ6QgQi`*{w);Ocbgo%S6hBq5 zj+Pq~$^zPKD*L^xCSWo*B0~wfA74QLIn=R2HZf}%*1v)PTLUHm+)ZIsxSLpV8=*c! z4!P?Z@Famzqk-&o&eLQt>LH7r)Ni1-2|AZ}NU+<2n0VkvfcyMF&mXB^5O++gxJ?#Z zv2i@ESaxlw*rq5X-xkawBdJ${S|z(178i#%%A9S%Oe`=&!nZhFFa%eJr&mX5S0=_T zsg_I1Jhx68wbH0J$aC~_ao70w>UM8ca&E04t0(U8(hf|tgj$dh=?+p+Vt86&R5zo% zo}kp$kdcBwZC1tZCMNQWDu*{z4if(lqGnNH(?XsP?jTtc7~pU5lfVrRy-GVWLnPFq zDnye}otJNxR=ta&Y(m-OT%+y%z5%nD!BsnDj5K7XlsRG0DdUMuX>iI6f}Nl$rwmJO zbjpBYTi&6->*xok%s{)T~9Eq=b#l$x6VrCpejAgKMSF#OGW1CQB{avJ6IZEwd` z+MXF9q2{>-R20)Frf;i-&J-}iB~(@wNkeuwDmth`GmOs& z7hnj=YER2*TR4*h%xG9eAkQw1&__iQ5pJggH-s4q90{%tM{s?3dVQ33V`O$=RoO}9 zBIt?M4_ZIB-TEQ+f3Qz36>e_uQ|Q#-13@zaTl=r@{S$8C%VQLP7{Yk)17eym)v+dwdb{6(7wSr<5Px*_*g+eWa4a`;0z-y) zD!OV5V6r5XrCR*Jd=T1$EeRu-$*?jc)#3!^f_Nio5AvlZxt%Y?Z5@~f0``bU+eC&l znIv4}-uiILUMr;Y)k+PGTZhNCjxZ*}{k`0YBla{xWQfNY63$Gl(GnqNsi3;+*-d?d z`-CEwW4x{rGg=)PK zj$46Yyxsaq0uCm|!r@~^CI=EmZ>2fZMC9s?W>VdNRClK`LtGztCYMo2sAPLOmc2S9 z7m7*XoVQ$B3YfQ7sF1y}NMWSq3YEg3mKVl2RiPNQ1mHC&J*g*&-^^TQ796gpcakY( z@6HGC;%3ghM+ORWcwC+N_G8`zRQO^cE@B=P@(j zVBg{@>CJh`DwEvtM%i&gNpK925df}Bw%1o7`NfeRe3;X#>%&BknTO3B=y012O`hB{ zJvoOmI?Ft3a>BxxR^5exelia)4152-T~VG+SgC9MKh_+9hOp+2j#ra#2F3&6|N zK8b95oE(L-A~ot9BU`X7RVbCTMh?FfK+(OzAa}f1cD5Bcl^wKjm0U#^%JoVm83iYb zmn(ncl}ZbgyDN)F8P%xv38{UyCd_PLNK6eGqSRYRuLN3?D`!t@M#e^<=EyWSArz=xeaCJ+>AAv}hAHItt|#QVGl0pJP?7y3S5E+_xr?#r|5D!w65y)t zj>d;FB+!5;*VU+qAUlD;K~GC4dXkgR%;9@?^ye~I%6oOe&)}-h<5HXGxo~>4PN9*L z_(+-mEZJb0gnNV-2mKsIC80*-IniDZA%E6t1Cpy~HrPs+d*&;}p~gFglLYY^Mx^S= z&STI2pGt)r8ypMG2;LWz82D&_ub;-}2sO1vJ^*GBV*z!xnY0>qIGo3Bu$ZM51DN6v z@wMdT(Izvo$jcVhFuh(=eWk0OL>r;+iJ7o~?Z4!vE2JU|jEW-S1*yP-ks7_i92c8r zfsSiQMx&w_`5_R2v^8Q(z>gMepuKwhAPy_qXw)0!tX#BbaI#0Tm#+j zFh<}?B)jiak1KWt6e=_pkW*^f7!R()97|p$mXxm*WR6JYG-l=ibK2Bk$tW#GBWbf* zwsc%^2>BwCFA~N8d}&gB-yyfTquc49w$cho=6)Ys~yc|A+yOgXh^!Z@Yl65a}Ea?`E(v9d#N3od$&Y zT!?jQtDtdN0S3e{1td9FkwK!Jh;4D$wlGB!Dy=FVUZFHw?6GENfLGFBk{rYANQWzG zFCw%TTVtjWtp1uf^6egD@Vz) z0PoY8Bfe@S1xm960x6%sm7T^mdm?Q7(5We* zln+G(HY%m}T+R#hhi3-I7@XxmQ8@||9MrAW6~NEYi?vNY_+b0c8`>u{Q*K@uI(o~* z^qDWk4gLD^>V$;cblIBuzpTC6XQ?dz^4*i7Tb+B8nN@gthVLgb!*^>!S~Qy{Q>c@b z_iitc@sZ@$&dumg+x#<_=Eh}=?m7PXho|$7Z@7Qa`19t_J$&EyZ{5Gd&7+OL^My=L zyt(zyM!fUmd;Z0R_cV!mXut61@*gaG z<__+4b52;TLw6WAk8uLe_sIw6l*^1F zrK09>#$=jy-}6fV-F{B!9wG_a;6V2Y4du^=Zb_eS-Y4i@^GALGk=<#}Ox-bo$ZqZZ zLo%kP%X+<(zH}d;TXSKop%0)tZs_l;=L5PY?mp7!Y=zR1nvC4uLABkIVVU)>ccjM7_Bsk)m_H{z{p!Z(v?m%}!@Bv>wbT@9f=@EkN zye+$C6LcRLe64UWpu2F|h>J(3rOS$U_1cr-w^X*=$N%x(fbKox?|o=FpnFS;n3w*X zHeWWR?Xkv_uJEJ#P@j?c3upc_cqlh6R{Okc{RMt>@5o&9ch<|bPcu2r&10{?^UeC~ z%%G+n-ADJzU#`xZQ~0j%s(3B2!2HAabzd_{=_hI)v-+==rKJ+t?c;>*fgkxw9q85? zH~8?O`=PG%V+7sr9^T8MJL4h6s%Str^G8XWrL)pyUwzgj$_LPWOD*L*x6JKY9=3(6ZN6d1ROEy1(~xCx{%%e7R+t z;&j=h<-?o3dZkp>tJMN+49KBLtwUx`06CQ0Dy6}}x$|Ua?q7Fkc|-nP*6-e3tJZyf zbMRSiT;lw8$`gM4yKKt0H>@2ZBWj%-3ghOHA@F>=9e+TvXfLA^{ zU^oBt%^|uzv+BGYdS}xOQS<2T*KWlAr9_7ec0%{?ORpbup!=D{%|rRn{p!NclgTdI zZ9=M=pga8Qaf8`W^q zwO`#19Y87_u}spMa|>Xkv{`(ZX-HmkQ2I-_ZOXTpnFlt z$zVQof3RrIy9C`oQaP;spU{YTa3i35+XKNPn;6q&4@E9GdH#B-EZ1`OdxGw~S7wBc z0(5szdg(x6<~-RA|9cWEm@0HFzzkImLeRLoGd;jAFErroN?s}UAZ9d;$=h6Mm)mEbBal9dYYWm#- z-4Z8s4_m)%j04>_TJ8$sL-))d{+vW26TdFlrX{jlw)6eQxq$8`cU?Mur#4;I=wdg& z?bK3P)F+oCV*%YOf~a*#fbKU#Bm6pP=gGeK>bY)D2k>hq(S|O~9=v&Z@HgDJkq>?O z*%yEDqx-HM~q(L4oIc{rP9_9{Yp)=)QDfL#g?55s`@vPyU)WURC$) z|5eY5n@1aC$M!Rjy{2iqt{e*8f|Y9pNO0QWJlTcgUfveo2k^(le#7|o8jq4E1#oV*|G|CWW}&m22jDvMHI*xD21&o;mKL{{4jQ|F_bw9y_sSZ=Kg6U+N@o9yt$e{v+*8V*iIb zp?hqLcP2W}oieOXLq2pLy=0LQbQ{`+DhRp_Lx=aB0qFio+v>~Gl62YfRfQvFoG+DS zPJZk6UV!e0O#43B1nAy>G9xGP(9i}b){x!|$Mnh(D<34X#n()TS zY~Jzf^E9R&huhaWbWi8zalgRx9ahIIRIY2tJ3l@lxh`$d=dWISPw;b#KN)l-y6E#d zk8Wy@xOtqTT5m0kSq|t9b3%8@zPFk>(EY9YXapa+ca8qOn4r5$(`zicdtMrNGX>E7 z+8v{tY?zlW>tQH);5E^h!YY>$BI+c{aX8_Vy*KZSgz&=*pJ+2_N!4H}26UDdS&#o*&&i+r9nUM~B+fI&}Bs=CNDg`HHul$@t?t_t8D&%iI^w z{voVGJ{GE+_=xq^*s68v;62DMHM~S|Iy~P4&6_3^B61eeERTh zU$^hzzGiZH`|#64H;AzRXV2Mw_0hVIZi*2(k1d+O9&Bb}s1v$J%`x2Pkln3D-xrC44Dk* zUiZ~PZI>tK$&@!wc0T1IGx70+dmCN<(0@oCH}2Tc-J4QeWF|)JeD<4n$2G2X=-$lD zBU0e`-q;Xt7#Hn6y4Up$ZRmGeMErkKY4)0beysEMKh=JTsCl#~z_z z(eoJP=~CIjgkwWGfE;=t{nN~;exJzhPJd?d(Wxb}oS$E4^vJLLyX@u7A4I-!zVVP; zZrq)#dYs+%Z{)Zp@3B|^emndH_tAZ^ z$-0d`=S1j`@lEc&Tso%Cqnk=?AZ{M9LuX1^9kP)Vy2n4;_?iRVk01G@2_L#+wkr-0 z3+eNO5lVvY<25s_0y@tn*zG!BhTL1 zu0e_H*{AP(^YTOd=)QJ*MY}Besn+C?j>u(pl-De-Hv%|7I?ni zR}D)|I``3ie9nxAs}6Y z-!uIA#(d~*^vt=b1l?n16tUi|1$RI6zj=V}F}~Z6tk6KVkcHiNI z?leu@=MHoyjw_7hL-){T{g1u_=x$TcN`UKGZ==E1_uG(KBTa~xtp>L+}$K9?i-fmmgtl5w?+_-m}C2hKE zB!Ap(@q)zhy;jve&Ey|$9yWpJYn+z%>O%|MM|a~ZO&zT4y1>!p&o<(DMy$ z@O#GbI|SqSw+gAJ-`x6C!zIGrt;O;#zdY1CvCgA=akC#ziJ8Z^|NZ#EpSy^K)XWLp zlV1P4tp2~t#lx-m(7m(uwNFU?|H6+}vibi7K6ibT0qB12we8cUfOl)iuXp{H13Ki1 zz4PS+-KX_KXIlW>gXl|}dz~wmwP|fVoWGD?b}xFM%|}Z!Lx!~H#@*BZTjP;je%ZZp z#?UW&yxOAHp?f|zkJSRt_l@o4>6bdXFT1d|e1TG;;Y*Y=6FC0n1a^XOiiZWc9< z(6w>1eq2k?-P8%)nU))GIAr(GUpBPlL-&%yJ!cVgE17rM+O0RIzOp(G(EaMg=o3ch zZgKBD=lq9&ck7X!y`~d%@Af-1s0h$~^zKs`J%2Bjeev?I^33`C=zi~`t{b-{-7(~A zZrp3x1&aTv_|d)Kujm_vZ?>y-=zf=*$0C8}`$pYzW3k$Obbr4yC;!n8-WHbmz3*u| z@6#9RJi4hN%f!tiqD{wcto`4_3EdgV_m$;tL5QIRAG&8B4n9R96ZilAHCuPPuuJ%T z44}Jt&XC~`PEMDlof=?x?w3+o+nHfA2)bJgdAdb0p!=2n=JYq$mBP^;|GCoDk+1dYQ0vg`n8$g6=X*D1Q_O3<+(-AYDV>?? zSA{hbO7ni7)>#MZeEfg$)cvC7@ue!)xb;D_|8Lb~Ywz!+*=?QV(9AYI=N-H3?2w+F z_~g(eg*lE`NUtpD$y!KR_jT>bKpxV}mor|U)g@i_!i^De`A|bTu4TX8?LZDqU(_LJ zA;_WGig!i_{Zk?vl=bZoSJ&{%p(~euII!D%X7^BT+@^ZHx)<uhaWBw&i|)^(r=9P+gbN_+02Qe=8-yb%|D%X zlz{$Ahs%#)=zymR|68~D*Z{f!=qI~SkXoymz4t(Jy6jB;$-OT?4yh*Mo_7ek`~1>GPAsJSpiQr(eo-vjJNM^_|0wt^ zq=CjIy(jJcarb_1+_yRH_a02)w~$U28CyO*?9W;!yHmJ%91(cFWncA@b~)v~cdJ_; z^^6@q3)}z9r+-{n_4yNZUUqMP{0C9PER5euQW>EeGbqa(zj_&3$T#ll!HdTe5q8nPBOX`v5>;I{C$Y{ZpVxs z^XY_7ie)nbzf*rVogdxp9vF18`P-lFR&e9i_FQ^y<#2v<7d>|KhfmKOt##;Dar4L! zc)qu;6#P1_yZf5SwB2U^0-K2V|Gt*@wTyqH&ZC<$>|ZBp9*KU1y;=Ler4zcR4ogUK zpgU^#tag0pj*~AvMbMqyN@5`Bo?P_GFe%voXAiF18>>l|J^EYEqaC1j%kbrMa|ybo z_f!20fbOv)G!{?)VJns*4t-Kdd-Fz{es^mz z^T3KRosaO0zpU$stupsoo)ndfM9e;FCkk)9#)8A;_VBT3@sfIiyZ} z>9T%5M}Bc~64}+Tuj1xy zxY>`focVtml_Q8)q~#k2f?O;xV##=!@EL^LR+$`95wN{c>_A z_jlR6%bh;WI3cV<=8WDF{>Nffo!@1fuiP$b9``=FGcs)z(IGoHp*!d69akLa4jyu~ z8y~uF+-&sC0YLXt(|$1#bjKe*aNin0cThN;t%^>UozHvmu9pDa`_``igzU0(j~@mq z0NqQ@zHsBY3&pZuK4Fd~S^3eO7;$hpy^q>+h8y?E1Km#lrshZYp4Lw_RcGH(>(Jeg zo5yZ}=Zn1h=<$BD+(&nhw+wgXEE1tZ79M!|-8Z#$9^F*_x8mlp^slsjtPa`U3Ehf~ z*@+HxD~!9k@}Ya*xpS!m-OB@BoI}uk;n!W$mjSwe)?PcD-XmSsXZ-&rtp{|c&ep{c zbZ0Mob!7pddv2Qz`?437$Q~HF&zjkgUx#eayJ*^h-WPXoTcrQn*HPVeG38ITYnn1^HY6^EG#WhmFLTk?&+_`oY!_cwfhckoG!3)ljyVj z=zeBM@sBU9zg+9={~T@}PY66;|8b3ye?RIzy4A(Qb~o57jPB`EwmvXAbw-`{-M;Yg zGot44iY4bqcb16-;4b+oS-}Dul4N7MD6EiZZ80Ir*~$o zn_8yJ41cAJNdt8Ee|^=dwt()o`O+jSpu0iaXAQq=N@O4OO5a{^lV3CW<*m~1JI+15 z`y+1L&dIwcw)vGG-HpHL_+IBjf7d#6pXcTgF7SK>$F>;t-aMcAB-;NTG9Pcl*OX>=bCN^qOAB{8cG(1Zcr>3J^1W-; zTB1Y#z51w;=#cMx|I$6%Kn}f{KDX_Kap|(-LsJi|hd!i<2fo})Dx^Ptx#w5yKn^8u zD;V{_J5YzT_wbecY5cpax%)?B_grtd=PquXnr?M+=4k#1>66ph} zf#=&Y?@Ev?)cpwQy2saEUA0$4hcutFMWu^N>%JViN8CJAt3&ty@dVK!yE>sef7i6% z9OxdNdAJWBy5G(C^J{|ck)toN_J6~kXD4q3bho|sO#GQK>9Wl4c3w&XbU!e5updG9 z-OpTkxd)&-4^Zm4X#Fd9exQ}klg9kp1%@#)YP1X8k16G``^XSg`N!&cT^y-xV4x1s} z#R=Vci;{kKpgVQUQ@#1n?RR5Yd*Ztdf1(5HyDd4@(6$B8y=%^>4+f1)myPcG%-|oO zL;8&sk4@_c=>F!u2mVX|bYDJCpMA_!B0F__`o>V` zZqd5rx7mPhwe{C+q%%>B?~MDB0Noe*Bxd%WRw8?U#K>+_e&e^0_RlB?(LCR9&qv(2 znUTsSo4(;k_xUBUuUV68pJwt7HxHrbyF0pT!(p$uZy`N9WG&U{4<igM0QiYnrUB z^Y(u)**;P8Q2z1aM|&2M%EV4i=%y1wEe>>do|M*;58Vf{+I>XOt!(y95kdF2XC}W& zG812jS@2fR0qL^!tLA+B1K9tXyV_hOakn-v-2X@#pxgJ@n!n^n_v*W|Yzfb|u63HpI&L1T1fDNu#=!LLXWWnf-?8-c zGdn*Jmfee6EcgF-?Ug#8|4&)&5;c!)6Q*p@twa0&HW=<6`V*zuy`AKc{+E{(4mq@L zw_jgAIdpjC8ix2G4=h>D=8!&+XB_+_$f14XnmwD?2hRT+^W|O7f`!zpci#&{hkW(; zg9m$p9C{%p>&vU-=F1unQt7gP=Raj^VRoSH9X0G{@+cA&71)guof;oPJzjj}T>=O4dJ#&n({lB-t{ii>=x~$Hl zd+3&XM9t&52JN=J3|V%i**%@mtu0=)%Yp9V&Ku+S(Ea%7xf0^t`rWdX%^~fcHTB#x zfbL_Rii-vePnQK9)NlU~&>g(}-Gc<(;|??oZv*Jo?YKDMVE=it|M_%iZ2pWN-G>Vj zzB&AG*q)u-xbIfjGE?^PqkG|=ov$REu6;V>cicP{3q0TT+ zyQSm0IVoGduJh=o7?JZ>-99{;&2H)8gl^5Kvojs&PJBik%ZKhc7e{9hbhjP-1DoA) zx9ZUJ=K$UF_cs`5oR}^P&U>!t7@+&@D@#Un26TUt`SGkF) zx{v#E=-zMCZ@n-@*vtNB><3g=+qychLvE#?6g7{zKl*>xX(_S)W1P@!e&Vm69J}n& zBup zNI-YTVW}-b0_Mr~Xu72u9^%&_*PM=>mihFt-Fvxluf6}?q%$k{b;t?r)v+29e{$7pz{{Xpq;PyVk_W$BW+m;;t-(z(i-Bjo0qULe_`}Thvd5q|g z(N5?#E%;!T1KkJS-q@cH-G8k=bdsQZ!@O`dhxCQ5cOCj3(B19$xX8zQrprp-+W4$5 zSV%kajjs~>KjhOPD@pFw!@ZlY7t@k*0$}R=XN{B9U68(`-PSt z-LHHoiJ#Z!X01c_8g3r13q0Sv7Xo*T+vL7?tIy)aF%61^V@Q)%ZT=`@p`^}7NE-~) zikrtLe|;UnqFd^OZevFAn+|kecw5tt58ax8;%fxm?X&V&bbqo)*I+-Od+wS4U7b|EW*AQI9`S z_t8y_|LNvqV&-vtDni%tNt&?pDk+pZn&|mwmak+tZC&YkA{E zJAP{Z+K_fWd%ohv?J2$1^K|2xyyKr-oicOjtF^B((J_yw1fH))>^(bUs)6qK%y&)& zeszGCE@h_P#?+06zN!0tx2dS%qUK?|GU2U8>oNXc#{XLXLuq!RlN_4&!GNcT93uAr zkCEwtd~#_0xbHg=ITU@cAuERzoyM#=3v#H-vsx29C|&mR*c%&ugZ_WpmhFCm?U2?p z=>X{=eZAowhp$odWYa?LFGzFIA?<_g(5XH%e;n)>w@+m@KDv~DmwoWFFZbVh=8xUA zjof>=dE6)Pd|$MQ`(XVk_jlRcjPERJ9uEc|YJAR0 z?Ek(_=q`EWN47&cLHF+ubqe4^_pr``LJ7J}lb&XE$Q60Um45=d1LH1z{N2EG*_gtQ zf6u>BDtlcTKb>UReROoBYki~pYYvpiR=@qXEMLyAL#{hIH*?+>CkNlfjq{H` zy;7dWkM4iAeMHAkxK!)Vy^5R1Wr62={7CX^Pqua+-4o}}Ki}(nVGD^mtUNm_u}_^x zHhIgyw+ABjBTobmCdSq`i z9KGw_I*;zc)Xk#iu~h4ShyEer-HLZY_uN5e_d3x1@Yj2N`Ow|(uP+Z0bYE%t8tc1# z5YKzGv0;^BeNG4}Vk&DV6J z_|dI=eaEU-xBNKx95-&=Q}1p2DxM$R+hdQs`(x~%wN7?V=jQRW!1MKK)AjMMH@h#p z$6SwXx9m|75z_m|{P@nKHFX}{)DwNh&11u=3GG??Kh6o=MGf1`cA)!N+e#lkbX)1J z&l7atv$;2m?u*anEeiv54_L5ibW#6wS(feNn|g>$JkjCHlO*o8auu`j8l3;P`1wDJ z3l_|iS)>m=wYw>Q-t9|G{!-jH`T5`?ZrrMAH;bjg{CT%e$@UDGDK)FlSGMSNQw$2(WD58%qo$vG?^tDNU2N> zC{xMM^t$=YiBR`P>;UyM+ zw9_rr%XE8Y4tu% z6Q#Rdb_GO-Ax3_e=Dl9=OpbORBC_pkU8{)QA>|o3RF$r?Wq2Rb528*-y{_~#*GRaA zG@_t8D*5U$GTrwqCFY~i9df*=p7af=bPwq(yYqa*YTkhE{DYVD3|8VHUg7KM+v7dZ9X{XzFPmauq&s5Zq?l~dc;yW0gZd@vrI_$e}dZZfC zkb>@m-p5Jb|HHdm3G8EBXmtBEY+!=vj^w?$5B6^3sV^>;fbIYyZ|E-w4_(js(a=8~ z1BJyGyoC2|57^~hh9{&o)|wkE2jBm1x#$=u^)KK5?@%d@EZP00h8(wO^{c0!CeZJY znp{fXJzo0R1Z{=-Z~gN?M8_J8{FX=Wf1ef);oUXMO_R}_j|u8 zs&pu+O!h|S!QO2^L3iZxCvVB#9ry4yCmP)q>-H$Y_y5~gn3C@QUrt;(E(_=`?($oG z(i9J^^ZwMjcP<7x!elrBPe{X8n)M$BbT>uiX6_FrKpFF$RRX!tz5A8d72BDRE)#Ox zPkFt~Tc*(I-q(Nn&BoF9bk`v@Av%08@@r;h*XG_qyLa19f8ujaroy{J%A(@8{y*?_ z%lBK<>3DNPUWMe{`V@3W7$tR+=@z_qkOPhGvofK^@X3T7OAzVY?TWWl!Z6soHLp1# z)eX+w6ov3`Ipe$}K=+fe?Ja@EVbBG4vp|Dq=yacuAKBU;_SS?P z7b$)GIC~v>Wpbz`B>LXnQM#i$4AF4_BfsF^S7QqPgST5-YoNx}+ySeshw;3av4eO>;>VMyFz|-d#|Wknc$F>aIgpkBd?@yIx1RDo0%TL_ zp{~h+?n5a*Mcc*KNfS3Cak<_iE^J@WSJ{KN`If$qQ=_{M=?tPH8Y90aoA<^n9ix2? z36uEg`)^0FYsd|v!#~u0@C;u=p8ZIjj^iiIe^_|IHRK8kx?_*jqdNe zRy86t1=3*V~cd>BhBFsY7+M_9{{h2~p4;N2sU_z|9jDr&0(Y+qgA&ik9>&BR8M+a&5 z?n!C4#O^)V-fgVtEQ#CogyHFaa-KRJT3Xg7hYDctHl?8Zh<@Q$GTome3l^Z!EtVW* z0@EG(_;mzanap^9dzuC4#+Ql(2ZQ(jL{C-k*Zvv<8NQvdgij{+++te|zujUbkTrEy zAM9@7c|XWDqto5+JA3h#5D}t15+_#oh?h`?PIpHpH!*i?3Ek1%i0F8Vk>9%IRkq1X zY4869#h&z!Ha)<;A#L-bDxA>4@O0zCx~bFQvHgfD$-7M`=#HK~Wl5%c?sYg18r}B8 zd*xudiPgJFbbs2JGw%$bTjRJ9n?88E)r+M^&;Y#u*Op6kcWJ#rR&F1U@9-pvPo$0uSANpncWiM+|f} z>2f&iLsb!uB5Q#UHAE&k-(wGh&fR^o$vX|*hX&bB{j_``MI^^bA;! zY>=eC{=W~=(SVWPLYwyV<}0-O(0#=zZUr3n{eRr4%7#4`T^N6r{pCrOjtp+12+kd@ zAy-q-oseL1=x@5GI7HFtcDj8o3Z}cN{vGLd%lDVtubqYIHV%?6PQXKXIGOCb-(#Rb zelt8=L%N8q9CrkCr}g}DuzpQ|*aat#O$DOUJ#nWn%X+&EksMbv_;AW+2RhxKb{#D| zHmgo|HRL#=V-zDlbF)xQjw7_!kQ$AzGm3+->F)iN>!tGIIm6Sfba@3;I+$G>o`kTR z0d$*F&>bHbUqPl@>DUipG`dX-1s=n6$5_gT!`_|VS9T@?&>fq?qwqBz53M*WuvHGw zUDtGZ3EclHg}tls2Xt?bJCz*SN`N?vOkyi`pwm4<+)ebCmnD+pE`8wDyuS&Z?kL?V z6@zLGx}$p-(QybPKhDr!GX+?l;?TGJl5`b>chj%(X z!TG;U|bj_r-``XJNYSZLJT&-fjNu8KD-?-TvUFt5h5wQhw3# zdkoL-?Rln1`d5DVJEjkajZgPIY@clo|^&xdS z9s~=Bg59k@{r`Wbo2UIxjd5B};X}!nvg*h_R4k| zF99E7H<7x-auN?YHg`XH0PZ2Bd&pc>1U~drDfI1I@EuZq?WAvP4*|NQ%gnXpUpl0^ zn?{+ri2}q6NL)^>-^)YW(S7Ka&*Q%9QuOzR)ICH;8Ag65_rDT0iKKm%_1=^HPB{y^ zL&Djs?IfPJXZRWtx15(M9jfU+mz}u`_y3j@bf4b0Z!?*0#q=MNXmkhG9#DaANVl&d zkX}ej8tyW?0O&3=ChEALZ$;Lz+c&IAY}2)Vtv4X;a!)S-x!D zo=fi7Q+7H_cRl$g{EXr0{>W!Vm5z#=&$(Pl(=FFg(4Dl(R+db+UEMAQG`97SWhTNICXGwGn0owjz zMu$Tjo$ig}tkJD%VnkOYuE!{~brl;r-II>fPl*>5=#FknM8^b1etfRK=6Cwj?%j^( zn=PN-qN4v-J~?=EOAo`-jT4KdN=LS3-A1My*t;z#=sv~WX-cNs?C!aRXmsD0QqG3y zt`_tleY<6A#Pu=}&~0b1RP+O&TSIU-h9A)VD#mYsDG1W4`K zWX?iqx)Ql+Yn55 zn|)LW-2d;6Pd|1H(7iL?ci{k_o6YjaeIht_ixi5z49{*^wD8h@J#PM)z)Ql~tLh^XczqVl1LV2P41nT~@m} z=1jJL4k^6nwy71^W#2t)ptJp7cGD8L!i@?_{teXR`EdH0TTUZ`n2*CGp5OGMH+Vf96&HwU3 z`o${SnKCQ-qkFpTFCFJG@-y@ail{tGJKgVjxvvG8W3RHM=L6%9?9#gZKSkMp>)%s& z&z343x|%0tUz6tlSy9k^P6zjqO!v;`HL_@QFR1pDgXxw|w=0_YZYHUCry=>EQc+gRJeFo<2W@5<11^bW~cX0e_J(|jTe z5~pjVZc~?u-XT5U9u{ogwvg`Vwn22%V&u14HEgX)0_}8rx+=83XT{#T#eHwRezo!( z9o}o&I`9is>!6LXa*+4;e%A?RVWbbxa>mZFr_v(b_b?~`cVp2~K-2d|~G2^)m z=++Ht4(9{sZr`m3&W?fIt!Gc8T9p9Z!xc|2wF0{B<=!}}DTG05P8iKxAfnU#JduYf zXOx$?3W;NVefn-oF*@D9cE)z9sY=rw-7ScY?-=E8E?;I)q7=}tK9M3oM%8ryaEqEr5y|Npm2NSgoL7$;i_AG&-(Uy$rW$`!)OXg+j5 zI^F=DL*lnEk~D|p$$3L5c!qSgqh0UU^IIf6BcYuj!6-;+RUh*Dzl~q_>oy`JPS+{O)=hxPFNKG+};~=10W4j^~ zO!rRh`?g$Qm7Q_u3s2b=4y_e=Sa0$joo-h9^Zd`BP1l$saaleh`)eoB>5glfJ|}BN ze{V<)+x?~E2u6Oa(K%k1&1k2)ze}XP?)qcQ|5pU;uFE;_+mzwYkj$FyQKiG;r|eL| zvvffBW(vB~)`vKe=@!u`Qb42oXp#DQxQ2{b-A|g3mg-Do<_B~S5*4Cq9q>@a^}UPa z0p00aL&UWK-Hj&<62t)A(T9aS?Y|SC2Ghmthm+82NQVsRpDqVki4TxC!EW2nwo&Lc zqz>!au64{pbXP;JM|3R5$S+0pQ&}HGdkv}C<8Qb$0lPy|N&0!hM@^aG>HfWDhAJJ( zPxw5)9E0C(v7w;*;+KhLGTpq{kxS9&E^}Y|0j7Hjzl(G;@fGiz1UW!=d2%@Go9%dL z$jTX4IWHD^H1kDC3($R{revccpxaf#JI_do0I_(df82Hl{rms?)rKct?B^u@_WCRC zyz$p`u59%4f8P=Hmabm<+q=Dl=9m zlZB0)ROw(^pPaasbTiSKg6`Cg6lXHsvhOx8L8IGP`*;$(cdO|xMY`SMQCXO52z&R~ z##?86@Q}*-hZFjM?z@LpE?*Alj&;e%(g$>(RE;liHzGiWTz%rWN9c5iuslz+kmMxl zB5@Bm)Yqz3pwm6EIrgT*ar&d%7tt|_kzbScr+{C1w9_qg*R0&3jf&|OqXRYd8kP)y z?uI)(Nu7?k%2eq;_y7OdrqS`QW1Ji*eCTSt&)+kojCB@hp!pE<=H8QVhZOj{-5>6d z2F9|~Hv%8hKKIph4xIn*SibAWZE!*w*JHO;7x<9pf)5toK>uH(98BQ$4THFLLL-GN z=pE9R(6EmC;tNb!k+_a$MX_UF(Q8QQw0IUKk3~d!`$01i{?Z|jkzeWcUTfy7LYSS- zKlOFr*Lele*w`%Se0)0jAsIPP@z(KzGSHw|T^| zFsM9wFe^14o$eL;ik>RS^O#;o;*RJ_+}4Of@Bf`ySex~NCFzcCD@4Z*jQrl#jesF@ zw9{RF%xFp50xE8|?0pyHB9_ANbVvDk?4w49)BAG88~N}Vk^=?ZSBx!xk?HPqC|HI@ zccqC6H%#~ZleMJx|K4?;6c-0{yX_3j`~fDUF|WscndXXxTpvRhVY(xdwO@<@x>HwI zrK}qXgJPu22*O9v>CPXV&Gs7OGL1swPI3FaObbJ&yW;DypO3eQ(;eLvh>j|Z{Aw3! z7rG_WPPf)mwUzU!xZQ#q8~r>a@Pgs##t}b`QKKU$(IqM{6Qg`yTC8 zMWg$m-llu-3u#AY5=k$lXz8wV#7{YkFv&(`3f-eOA@e(qRkirM=POg9JnobM+< z_u_3jL#mwNP+z@KYk4+0-81nzKIh_COnZ>HC8~HOwp4VwOS@G*9uX0wJG$8t{?c(1 zBR@X>&-|b5Y2UkD<0a`HwSkJtL`F6AN{Kk*(=C%hoeo>BbLynZ#EydQjP`+SGTnSu z8&uHfURxPTqWej0NtbA0Sfm4-3!hiG(0y#fKt`@)=o#E z)4e6hRI=DKEcDkQg_kJ(A zf_?uV=l@J%&Dk3aPd9GgUFvigiJ#B%fp51sQ_!6!?ruP)J1HPj3yp52;Dm=T-K`%_ zkZQahKF{wd``UpZb+{;pFE=v=$_k|)%^_6ec^FRns_q-`aOc@ zxaERQ_W|LaMB)-Y(;rCOhmngut?SY0UVC}+n^T-L-O(L^=va@D-&0Ap>csz`hP2!w z6uo}{`wQu|{#FU=L(3Wd{Qqgv4XSiVU#LH2avDDW-$p@q?z=~Szulr1AFv#a?slUCbEWOC zSwWglCT?d+S#FD@!n-HeRnOf}V|co8eq2=P@D6+^&Uy*1Oq?j_&MEumOZM)2ng*I^ zbbE$qH^OvBoWD)FnJ6Kn_Spr{{UUNHZ&xTD>U=ZsEr2Z+dNc2e9=yB7{P>s6ETH>c z%c)Jd`jcAaRoy+c$fy zLSJQDg3Mh57pc(QDm#hjz{*cGPDLx;lJ*Yip+llg@E7bF^2H(M*I5mk4DUk@#S&EM z@Hv>FsdEsnA$L*GUAlg;0C|-)`qpZQM)&2VH9|1mS(;BtC!|>)s=lWKx=*|A&nZpD zL+`siIktic=`Le+b;f}1VEr5Q$$)NV9#ciFBm$%ox|~l-9-Zz_9hHUeYo$z=A#u|4 z^V(1GqSL+hNJ6GNhZ^0{J&Nd9gOOj!cY@ljbF{CrPkYT}%d@DcAv+_)A`6Tdo^ITp ze5!POz1NvnnFiO8J1OWckqi_g)9oFSVSq-rzq5ZF-2We~P4j_wx1b7$Jq6G$H!XLV z2xdq(ICL;=1~a5yT=b2F>Gn#LG(89Cew3dg%yWnUdHD&|-V{Wq+a~UvckXr>Q*R{h z!C5&%?i@+I-*l0z7U=6MAf;8RRJ=l zIaHLQWYB zPd9F>HFY{Jyh@ZOo&RsApu4crRfp`|=fsWl(C8i>=iUI*efjQDcbIPW6`|wsx!aLD zU%V~{;i1->RyN(gz{|vW-rtP?-JBfX&Zh&qEwr0zRMv$-g0{j&mA&Y69~-b3)c7oE zN{;i`$n~(f9lbJHeC73uhmb1W(R~8ZA&-&Y(%*fXbMelahFuXQ@K<&P zrMpOTNM5ENxp*4fvh!+BQMLtdNK5R}c_0M#A*%}~znTIcYG?{-^#VSWX&+f4VIKya z-f?9pYZTpwZvRq{zn#Qlnu5el)~vjp_y*mFzE0NE;3VnqmR%*H11mpe-OtIdm(yND z=5NWF;iYEEPGW$Tz{(KD_aVXos&oWogihQz2iK5Z6m*wsm&uUnJ}_UN4UO(SWkT^V z-O`8J0^wEm)<+lfyMXTSm?`_-y?AJHyPe59aEA0vOZym1x0H3z*1dr4aWx6E(BJbSvdEqwUZf+>clyRtrtDjk8bb8eZ5@a~o;1>LupZ;+;2!h5&1=Ho1A zbWe@B?t$+tK0nJOZ2{hX3NCJv+1&2QLZ{=-d%?rO*=L)Wgi31$;`xYnSp|#}>H=RKLU!bp@51&l1xL3p-26Qj) zI^M)HLx5^l2=DMdfljwPy%^Dfm0u8> zW1BK7H1%-%>-&)Del3JNnbCD-xaVPX;f)NnWPEd$%cw4y^o& zG6MBC2GH)^R{1g;@77_TyW!^AUU3VSG5-AjeIKdPA^&W(QGCUp{-0jE{r@ws7$<)U zAF6RMS0=Br&Hih-(R?VMt&KE?R4k{8)c;St+H@oGy4H$2OE|sL7UQ8~m*QWzfEiM+ z=WIJ6;6qdQT;=V651rQwvEy<8H>BsaT9^-^&mj@qKVh?KsKewE6370mJE-Uh`We#x z<|eT-A$@c=|BtK#D?e|8i~W6(wBNGBB};sap<>F8Uv|psS3S}UUqkAP%~7Qz@jdHR z-HUJyxtoISYKvSZGTkyq)aIknZDJ?g2(Pj~nCnS&XUMn7Uj=mEzR)X@qK1bOXBC2C zz?7Y6omG`E-H*?eopb|82c+boX9bofq+#EPdBbVmpUDW?R5&I zGbBF>x~rJIpONXFpFYBcM)$?Uwq}^_%e@^Wx&z&MzC8zY4=OH}vo*p)?W>O@9|Pb2 z3%|QSJKJ~y@qT!IF(g#a@w9~!z{q`YyE-KEDmW!JTh`(Zdy3-`7(qTCo9AiP6 zkmgH4cV%6>B$@8am)AMb=*Bmmc?8p)C-a6x_ZHbl%pzcSE2{ZPrK2St5{eb8a{;qk zJl2&&z;p|3Tk*gd(5-c9YtQ0a1SshCt+BFyc_DpR&N$1K>x)S+5_dfOU}AzcI^A1^ z_Px?O%S?Cu{|KT3E59JlngZr|w0B6+AJY4TS76`WGM$z${g!CP@cq9+;8Ln|H1F5q z{e2v+OnfNlzMajvm`wNKQ}G;VbUQ?3w8L~8>>nY~ZJ5bcxf{^^=E?h;R@?B9_{gq- zIWTuCVCal1Ot;+k%9QPZZsHntVqpUT>X=<6}np{nog)GqN zwlqECFz?Phx}%${V?9QGrO{?-!nbou(KLB{X@-&~+h$II5+ zYM?UtbN>H-cG~p$Phy;cD17LF>w~9cA9^irCV=KcW#+*t@Ep>G%ABM*r0J)u#yUX_ zx#e|TW4kUMI%ihRbP#+)8a6+u1D=rXJL+kdT_hz=o){GK<%FRS zy+gWcF#DWu8Fme+@pgJ)Y)1#f(=F)#jVc{t#|2ndr@(aYrJ(!n^nzkC-S}sHyl8Z< zlCjc(=`NUzCcXc6=CSmy0zfzGrfm|hl<|z4q!HQsQB zY)T|RU2eT^>t)gD{vPo)B+L0_%?l*Xbf>4b4>vm9>r{?DTv9hgcXUr9IxI2rdz~YF zFDHg}x(99?8cO;^#SLkJ=a<;RpE5k%xZ_W#)6qNNsz}=13ZS67_WrB8WV$O&N*18e zeRhS*Z@5D$w#*^T|6e9>+czH2tzmUU+!&lpjNu0C!6Vg>xzvNT@CoUuEnQ*JfbO@y zI-&9nVUS*=8&~ZBI^D%7hezJ#T&OWX;$&(c^9nvir#m&fLq*0bkM8J>Ms(z1B!*h3+XC`y?YM@-NX}%ACl=# z{JftBjqV@G_aDG?M|j>K_5U}WEVEo;x*f77MHb?r>cgou5@5QeWq-pY-2b0^XVkeF z(0zvM)D0WQFi5sZU-0$>I^A!#gs^SYt2J4S#69)$Hu3L6r+W?mOYN)fZ8bFiwEmZW z!vLaV6-It>6}J{_GNir#H}n&|e(yKzyk1DS3uS1wUBy0@*#(1%yq!;$+*cSu`n(=yKk zy01lFbc_LX*F;zMSb*>UMZ84HVY*BCML9MAx=&~mlD6(8KwD(Hh=MHWbPMW#JyLV! zON|{87rNEzc>gE#^Z%0`*P7YY>2G&S2+@&*k)IBC+|tbjw9|ch2iJ|+IqY5b4IhJ- z6VL5qc)Bm}?W9UaT8zBqk{q~(45pyFeq@6zneK}cFND$PW@r6U4Ab3o-H}v74qxB9 z3O++(4!xXe4(N_`#EHa!@BepM$ghXrklMrk;lN5jca(;_#I0=v2$u)>jDAMH-J*g| zbqWptQNx17;lr6W8h4@79pqD;9Pwm6-R<3~B0BbC!yaa*Qqljr z3FnV&ATT`LIK!zts&w=YK35_2|NANEu4~#zn%xS2-NN$ost_98@$M2D@a`6FtsiN3 zYt4QiXKg@tefqcc-@xq_N2T1@S#baVo}1<%Om~U;nh0G$_pCd2f%5z?D6GKlUP=bK zcV9iov1MO6j(8A>WAl()uW=H+GFhcQCa-41M|X6Sb(mx1$J_oe>}mt;bf2x-)}}E@ z#SQ7RE2<=Re`kEUUrJG>O;;|8oRVH=hM`+e#^CmV>$5Ja&Ci@avWZg>w8VfbPU&t?L`W{Qn!5a|7f4 zW&S^J=Y7yXi_#5QwC`^H%H5`! zWq`fAb;-F=km$RE;ptW}zE717u8PORR|$Xm|Np@T{eSsi72^~^;X{wt_2bDtv`9uv z3eAT&>o;n{HRKw14^oG8HEONWIk3taDjjZ~kikPvyTuKMr(&Q7OY#<|0UvT+)7G2- zd`PE%zV;HsFep;p<3Mve`YOw7Z2l|D;-?8Y?#|M?dC9ftJ~Y_zlyLkkH}QY@heh+h zegUGRA0xkhEn%PL$F%#9z=3dX&!zQsV>YQ_6t zx{v;l@Qeg>-zV(y`qdT&2@Qq+)bU22vfCy6ibpEwr-?8U7d)E~pYMb|Wj8KQSzxl3 z{^%y_IEsYsfGP zx?8{QH7CpH!9%0+l1AtWhcPxmTs17@iWta?wGbp zbwIa<>1fCvK)2l!vs#v>FleG(F^zv0I^D!sXj%KaS(8a5&VQiC-^CW4?!#v^yqGMw z=+3)q5gkz&`Sp!|#m~H|E z-7Og}n8|btFH2mAMz@t@pC?TB{T+))lZi`~EqCn%bjxT|st0@3O2Wa7&l7acb_jl?A%X4CoMhEBIXAB&EU z&u_XrA?-qR_+aFh>*83b^dC$n`oVj!RQ4YB-7VbG+uoO4_A-8D;#NSNj;-(Rq>$cj z38kRBIn$znOm_?4PH{B4M+e79bla!XMt4()RDRBD0yH(>JC7+4z3w(@k8*UdYBrfc z;vU#pyM?)+*WEm(CWZM~-E>E{9-`x$$-n29^=MboJ~`UGdq{X}hqNem|9{fH&EVHD z9K(C}GR^x`>F^u)vOH}+x&P0_@yN|H=Wu6@Wy+Q7IqfcV;%#qeO#t>Sr2J{#wOY~#8Qz7)RYj@Nk>qV=9t(CM0p3g$ zct2xP`TG;nl+R;wXn3y>RXzgaJ*s(wg!e^-EIhoq6|894(!q|0R+NrjW*Luxx~(_e zR04Q6jg+T!1H6ZZ+#XzQB0vhCEk50FM#uX=|Ax-*MPE!5k+`W%X{L4S(D6R=zAM^D zmxb;cq+mn`R(^h_nY$A|(|&}cqAz;wX$uucNImJbc2RK*k2fy+8dW+52W*00wZRS2 zAshwXPhNj_C%gA@vl>}6yi;CFoq+Mi$#s(O4n4l{YZAaaL;J{;OY`s$w`p0H@k9)? z_4S!lWq>zVu6z&kkNiSLa90+er)zw4JNI^LI>uZ@xJ7NiBx<_}MmqDX@Y}Na-Fx@QyKS^{KOj(b_0lL}O?cwC-#Y5%_a@&d~ zV<63pkYg%;vdM7^V;&8Qpws>O zgYir)W3tO#3?z#He|@rO9!p9tRu4(~ZmXrb@@&$PI@I zFTmyG;RMI`=yV@s z!JP;!roZq1^${Hr82L$Bdp<5XM!R<_pCKwP$;Q5!$es|-VLb4j;di$bd-qbMqxHIj zizb-e^4ItOS8+VD^UOGQu^wT%`oG`I{`nJV{0V^ik%Pj6UMW2+Bzw@N>w?N?9+c$C zo&xW%AJ^_D?XZ9Tt#nobcu*==;2Cq!9>xDI(fK_S11$+{b&>}jq&1axL4~CaQp;J? zZF4LX(s1m)`B(`3{;0#sdHcH-{W2lP6>W{a#6RnZ`fYsfw~GCXJbCDDg(d6A!N_lL zT=GjzA?+({mFVx%G6J>-S;n+@_QyLje0%gPsGBMszm`>WoQ)y1N9+`MzhtiY`|^LV z?WiIe-uX(?4`IA3Wb;VJqq@B(iZuY<8&+*L)@H*)2jZKL^nt_wBfHAgmjJvUl)~3Jj zN2_GtP(Z_5kw;(-#{2uCL!`Sch1taL^#E_5!`Av!VDHvnDbLXNYYZgrw}W>n!28Jj zk-Gu_@4+R|{fORB=)^CxfO&h+-FxQ@izcD`s|h(yq-#%!zb*Rh|M$L`()s%I*ZuE6 zbiBjJujTZ;>XiTBeza7_2aRAu?9+c7;lPHNxDm$3TcC|99XDEjb#Y!Jxi>2X-d%~% zW^!?|s5N3K8s5yY+esG_A9(qbE+(4rsg(Ewymd9djS!gekh6Go-Vw05)p6GS2aGoX zmwAj0;O%U^l|T1wD8$^R&>`=Sj<`hRA_mWgzLx1AMh!%Z9>x?CvV#|=*24xW5I zqX6)}ZL^?i8ub78l|#1|g%O~@@Sykqy^C$-1UM&6$Z@sNKGp}P(ed^S?ESnw zmHzN1>+rzHZ-jX1=j~D2i<7Al&Hv8u{Xg!yu-e9XF1m$;6Xb_J_qVVhC<^)p59mHp)aus&AV@`*~n%}j{6XE z;`+l;^ajb=a9@^Ms}S8Su_qB7SotY!ad-u>)9yjy1@(%nGO_O<;cS+?u3r29K!aqV zLY0oWlUAJ?q}$Pl=2PJP_IqIk8E;dKZZ$N#r^A0AgYmwwrjmsBt{~m3O99@&+ZyGq zz~z6hnpTb#0B=oAl~VZhziVo(MF+rpguC&^pm8Wx-A02N8t+xDcZuEzD1EK>fKjU3Y)unB;<9$p(fBk-+X4HKYvS$Xo@wHx8-Oun1 z(({r%ROvXsGUZ*>Nz&z(c@%iRA%f>Dm~c4w`)Hkc`ODDo{>Yzn2*x`~DV2oxxM!fW z9Kajr)tU5G7Hn_rdKRYw@ZNa%tqFX0>qsl}&LMy|M^1TA+m8_FK;Z7%JhA9_H(6Nd zSu3-e1|xCnja-8!J<#!9(PUN0UrK*3w>Bd>AdLKq9%U|Y{SVw*aSze_M>!RjTe4?< zr%aAAJl?oC>U5lSsIvb+nr(52ivsW0S6TkPApNv?zbYEuLcxSk81L;)Atbz?yneAm z65yTDy7QG6I3QJ({gfvN@a|3dTm$$2CtsEBWCs1eM9Ym+3wuJKG7py4ST}UM$IH%2 zWq)8cCC7P(d6}OzN5^~q^Ua(r`vvH(IGI3n%)`jf=A!gdr>C^L_hKDq<O|Zg4H*7z=fAlK`8u)p~Tn;R;{9F6o*8vY=cFQf98X!RT z>(*CDg`)34%C4=RJQT!cdKZb)lqNVTdZ6DyVrKuEk}yGk4H8)gR({*E=e6Z&(e6Qm zHB+134P!5{IJ3KDj*Cnfzk+POLzRxwJ85g0FOg1=_$csxH@k*F#@majQyUHMpn%7x z;U#voV1R^o$-E}rRRHh8)1%7>tHB4PY@N90@B`9EJA~o$e;-o~f&{=j#Z@xbw2A<+ zEgJROwFw>X8>Q=ayWL?kWkKTjUivz_8=>R<{O+nVwYtJ|x5VB=bYSJD_N~TNoSF6$ zq%VX=B)p>z{kW+Q@OGJ9zTv(h9=iU>Z=wWD|BE^gvBCZSrph;WMnM0+M?lDb z$$0{_>`W@Vj|w{8Iy-(`ymb*BSoyV=bO~)* zLA!e=l<&@yp2e;pal1Z@t-oHy@Oa}yK2oLQ+TBeSlBp#3UO<8OK=jhTcW*bo@?MUH z_rtAyq{E4U#k3tx>>asiXOl{RHjK&tPG5$O_h(bZ6%S?DP1hrF2l?L~Y!X9v?;UZn zyhW+>hxaI=11rB1BN<};iL~P_%FEHaKnWY~cBQdt$I)91e?a>6;uKXng1R(cFsG65 z=App5-)`ecvU~S88Ec~9edBIF3GYlL+VJi_Vx0N?dMK2%uJz?L2>t9$Bjep~i$`px zr;xZO2}L6OOVH2%<9S!yQeH=Ycxxg$u=4x7Dp~GX0_}Jg?Jh}{8K7eBR=avz?TcoH z#~W9sN1cvk99pvAa^j!+|8(8?|CJo*|3xS~=<||3(hX8BaDp^9u?vUhK_44_ordoq z>3YtP?jR|=I4d~^W{?h#ri?Oc7}-j9kERtgmc73A9C$ssY;Ht2aRr_7_Z z1V~ABmAQX6x(5}%5uZF)F=e8F#4R?tr`2>H-GjbgWWj``B|- zXm5}{i?iQos>WVoaSJ6q-=5OaX8)v-xxc|T6Rx%4l?21-f5JFgEp$`quj6?z6C++99{{a2J zUDXAtCoBZ$ckBH=Vlq13%{GQ{7m9wG{6ykretkIO9EOg!wubskgE{&e{zulKg^}M8 zn^Jrvrcy<$h13p(CH#hfa;B$-YBjw=&h_}d&E?^6Or_798s>CU~$I^hdwUZV?mbf<%BG*m@Ob0Y9#Ey@%A2s=q2L4w6eofdcn=*& zIYf4EzY#ZmG`xcz>D|sd=4K&g5mfCs#xX5Sv zyWVmS(IJhIA0M04wC*77co#<8l2Ln!eL-56_w}ss>Te9cy>)V6fGQpOe#d(ZCJ)1S z3sB(w@n~EU8E;w7m3nA+uVOJj1LHlja*VWlJKtUQs5QX5_43RHYdbvj!ExKz6)^u_ zYGGfZG{9Rg&iTTAfcHBu*{o)N0>l;De`X02`u0|gSFTi`Jew&e5|_NB@$H5Ybi9eF zcD~Np^mq0ai|D}0PmPU9Z9_2a#ffV8v9F7YsObOQ6jrztU1R+IUqqfd9gyE@zd!x| zKNoxY{59|(2?`JT!XC{5dl20J`%GA|qj`|kf!Uv={y!{>^un%_Ucb^T=>IJr>~d(< z#X|<7C9~93#J_QZL<=Txj>8Q_?%WdR?KSf?UjGQ||j( zk3J!!A*;ou*3{^T@qCiUlE@RmY!yvN9|^~=_$=hJD&TQ9UuqLON5Wg20`KuFD%Z()uU|UDf`<2=tG0tM-aB$kNqDdP zHY_~_@a9WR&c3%C59xlpusDRRHcqkMV-D)Tvg^u_A z0k^zMaTjVLkvM(LpVPjc=y+dxS{)&A=o;POJ%Z@y!^m$>`J#u5)$XKbboX^7y9{sPwa%!G|v#-4M?Ad=y-vVpZ`Za#phYHDW}sCw+i??%SQ+f<(_9cO(rnd*~C?k!4z_vp%lq<6RB+FNM+6cZZW%ZZZpFy2?V z8%b}s`WKsvj{>~ULdZuJGEEt zgDg7Uj~_D`8m5n!=pu0)Id_@(c+m0IFqrgUpPi#SydNPt)G_j7vJVnlJVHC(CcD&2 zTwJm77V_$_iQ!zv@OY2=UbI5gW_au*&-*Ii7$~jFT0<$Jpb~-u2gsdp)*3j^uPF%{J;Lu z#}OUU82OF%7__)+(0=~Ud~>{#nX?7+$U^sy^`09o}4sjx>z?jx>rZEB^=Q|2$oK>4yuk&;M}~ z@*QPAf*2p~-Aky_5j+!AcdwXKK}u2J{p~zHn~b;J?LjUyyq7c8_`rC(@;U}P{GM15 zSz+q-3*a3`sC>J^2@kpY@4SD6D;8qKujz-kx6F?(UK0rLCVq*@U!6^WE>1va^Yqc( zTmAdRP5P^+YtA5XcUk0xAIPKQeI@=tmf0jT5%?RAhk9iCw;zfH%H+;)*NdY z3(@g5_UM(>bDF5hK;rTr*?KKvN5{Lgq-LGZ7>@4nHbQh<$H;H8bFN2e2ki}#mrBor z_IfHlPMnoD62IKX@Oa~HEv8C`+@iej%yN=@OH$zd)zBuNjQ4tv6C7xGw>4OE!FY2z zwUM^B9xL@+fbZU>no5tl>Ej_t`|3${j#%imZ?F#!!274nW$QG6w`o0-=x?ySwRO41 zr5tH=yn9&V6kHldYBnQr+qHU~Sm&eTZCG7+VTr_dy4$^djp#7O$nWYACH4SS+TGj# z{sQHnQ`mU7$5fl&nRv?ZXKztIuTZ6f$%@PT*%9*le}Crx|6dzJdijT-|6fAkLBDy1 z#mFA?InqJ^&4apRZ&bDd59$~%3xk(f{(}d!I)Mk-n0%LoLh;Zp>q#YhP(dy}bZ`jv zAXNwTuG7GS{M}MKt2zmg{=$%=azAtr+H7~-q2QJ;)w1+<)M$Ci;Bq6 z-4aXIftBCht!E+Tm$WajoFl$h=T>7kNY(ekA0KlHVE83=w|WFsI*!Xa@x4AnsvzYl z@cvm7B1Fd9K$(Xh4R61nMsYCSyr(A!Fy5iVI~TtOcyHHGid#znSL}Lq&3XXduCpe~ z;RY#y^O|A=zw&7I^L-XcZ+w) z%g`O(WF1)fy*Tcm#Qz_R*y)yB_1&Eddy5_S%5_!GzyXHG8@FjYRXP;JT{^R_kSfT< z6nOuLuQeg#oz>aJi-tF!-)TD-Z>yh@B)qTsHcq|+c>A2{S$!Z3+}>g`kv#ymw-maI zV)+2x9Az(aJpkUJX`fogzyxVuo-ZyJc+uTkUtA@5N{EN(j>K8ZKhu9dhkpKVsO6A) zc&8-Y;jM@0z{;;9xMb#+1MTiTogpdYZi;<->uYv`-?NcDysTP?}t4TID0cal28yD35F9NWGUz1 zj)erX+_u2y|CXW)e(M6fJ0%)V##@F#EhoeD6bI1pUh-Ia8*dUj@gWj-MQj)nfT(IvqB+ z7IBrrKlA_SrN#f(JV5`i{Qr9po^@i=OR@(Qx9EtWd60@d3j{B*4%zofOKhHRgXL|o z#0E%a-Mj3EhwMM=J$VV1*t{JJE8s15VRoCQ!@z^qhi*BuIwA}Tx+5E#Eb52){~i0Z zotJ9Lg^9jM+!CR7?u%T`sPUhpA6PYLE}=UQBJ22sk)MN)S%e%f?R$`X8Y_b?LfHL3 z?&+fim5-wse~HD{QKdtss?y3EYT?H^T$K6{b#4w0=$XbDuyuL_foH{O#pbuaVw5YYz%|c-7|u@KcFwM zkdFLC*Dw*H0ur~abn5l1F7zd~pJ)Z`JEu}m6ChM@o$gg(SGBdvgwBzlsaB7}HGxqjY z)L!law*V%Ce_hEL;D3x-{yU!<9XDQe<+J`Z|4)GeZzjCm0W#jt=U)**!&|0Qs2p~0 z!wWe*@962qfOK#x`YG7G9S}~@hVkB{Vq=mH@ZQ##Ten{%4C?&2 z*g~Qh9dA*!K7;GFBE(iCPUEd0M_?K{-UZ&jt=_cKpL>&aVC83au-By5mUg_qo@i6^ z^2f&eBP(}d^llf1$9v6=;R0%OJY$y5dVi5roGhil8z-+|Nygi$d5<6(-t~9(yo2$^ z@q34pwzs~upKk|vZ(9%=W*35o7P)C84uI<|TX)YCa09%z+rsVt;@&x~*JTMJ@^t6knTQUo{6gD|K5Ayrj`!J6 z3nA7{?A==&E|r+{{v+e}|HV}5I2~P`3TAKpng7QCOEPGX)G0h@UVlg#*@HH3P?tjU zAh{dwg2|AEg+a68?VZj&=pJMsy2-V}jGs7(#O?R1bY1ueeTkhR_;1tiroRJHvW{7d{07}C zgZ5X_z6bfREp)waK6ZnI)Bnof zUnzuEfC_TAyNz|xzf_R&Dt#KKe(@7Mkhr~fAH6b5N5{KhZg~5?Q?hio#4bj36k_C; zz9aC!y2G?DvF5%dlhM1ex7Y=bo?ow;G|2FHXPi7qm5z%~q6`;x&xv!~( zjJIn?qXZh>%Z)#Z!FUS|FC*bSWSAFw1>ikcQu^wx8y<>gZZgRNc%S_7uxCEN``X61 zlp6qVQ$kI)%@_fiNq*zACKlbjLz~an$UYJvP9kx(>|>6d`_S>;Ab;#MuOt24-U>l< zVCDDnahvXV4ejn79<0?DbRYW$DK3MLNhWlR;qk`xQl}$hCEm&Luj?(U6nJxNn7Bp8 zo2UESLNvUczpF^Vc<=k9MZ)_`9{<;TfcKl}ex6uQJXAE_DDn`%yVehig!_M=P{p)! z0B?&8I3AZF0u(0n_LOWCI^N-|Ck@u!5hU(M;#H`{4=feQr zVQyy(`Nj#*8~q#YlmFu0PjxnXe!L?@>_Xzoo-eHm-j9y=*3UtF-;L<6|0nCf%J1`A z#n`D<+TDA>g=4aZuTs(fYuqN}i{cpGy`vUhr%H#c{^@duKkxrBK=Th$1Qnzw=RmrHFBfNMyOvj-kZkbL%b>4I43UQOz5 zxc`?RRO}iC9+c4+Egv}&4*C1_?l(-_je4HHd1LfQ==^y^A0+OPX?y$QI2Y7-NB1?E zL4M+Nx5Qc_I<{ftXK-e^WA-iWORU&y!kf1iEvP@2zag~WHhF8p_V(YuX4JpYdhvxC z9m4|byVw5J|7%g;&3ixDjg0sFLvwOyc;{3UeunW5E+#HC1_yACcz z+7}&f!8*3w6K)c8hj$aALl`5!S4lcU5v4-dnEnGxx7@D-O)8Htf1k~99==4bQijKS zO^tvEH9DTj6=YOIkt)dL6nHQ2(fPZAd@y!L77g#r2R~+DyoK3rlJGubHonms;N5@1 zK@i%7hft4FQPlV>ku6>82Pyjsn4F7q}{!=f1YAvIP^>9XjZ=uI^IKgH>;5; zUg8WAH{N7m6ylDKH~;2G?+z`OraQbpB02;y@>8_lPkiqsijC<%+?u=?zRhxk`|d>sb;Kfk_?4UD(F?f&wg0PocgNBJt^!yux+TXg19 z^t-oZBEBz#GWdwMk+}D32Qu`<(eK_`3HmH@H>AI_H?odR82QaeY%Uf#Lc4n>1s8t2 zNX6`}C4nCnj5^ygynDwRzobgXoW0NG{y*RU|HBOF^q0Vc3@AKEq*YFayu{u-C#a0( zLAtqWBk&AT6G0c!43ZV!gd4?x2Pp?%57@L83`l>)w%vv|7V4TFmW8+2)#edeF9HvG zx?{V3oMSk&dG(a};2gRKeRe!0T|G2jvk8eyg_e$fnMC)XDZYK#j)&=Q#Ljy}$1FyE zWjYVnHH6UaK{b2&Myy$>IR6ilTk2Ha$M6jjE?u{rJi|IwKpNn$&&@&5XHrD{HIYbBkUEY)e*@R(4gW5?e2uTDjh`hPtN zyoJ2Z{ypAeGi$j58s4&ZU)aNVuevBfn*Z0mgY_efcT_^a>DDcHXpQ!wT_a%kHnqj> z7ks@XGmWsf7U1pl{qvKP3&No}wpWfn3(@i3A*K~n^@*7{gT$3~eNvaWf{wR|_WF3Q zQ2LwR>Wt`sF!IaJi5|Ouh<5k3xs_jf&;t8{H0~XtX*zBj!{dz`3ZqI#$A<*RclSvB zzb*ydg6cYZ$i>N##Rr$7;k~cyDQSA^hg;&L>8*9LiB$^$-gd!7r<|Sfkj2g2LjNCo zXC6*fyEp!|4BNc7LWayF6q1z0UXq~<*%T?t5E6=zVN)SwiVUd`4N6HW(M+O2C7Dub zph8Gep+V`l)_(SVe*2v3UC-Y8{pW1&_4H4Dy6$s5_gA0uUHA7MOHsXT%mZHvpn98M zHFRu6^=>8az7r!DjXa5~i)uWDulKjx)7Q4&B-FIh+eLOi4!d87ueYN1(aj?IoOeL_ zD?JWnCjFDqiBt`L#J=7k1xV`F9Oet8Ty8PPb3av0dA$uc$Fda1Te+8lA9HDX>oe#* zeTmC`ptqc=<19SAO~>9m$Fg^D)jZntR(W0atC^_YK_RS!z3s4bB;S^gMvM!ySHxH2>+PXgdtO+dzh*JL-Qnf|qlt_7dW&y8ztR4v zB*zU-Hqhgk!K8mgrM;@Tvg{8|?q0gGHzJ9J>n-GqY~1ZzFS9%f;M9fzI<_pu@w!ub z&Oh(}aq7R~zxNBR|H%wFNKQKLUsvn~4hYS|%Rw>cUq@nZke(3UN_&GeDj@b6wn6&4 z=E=QlZ77IO&k@7TXbvhrvDOv4|Np7#j%sr>2VI!7dQyKZ8fi((xc1cye~SH{-G!yQ zX2IlUdb_ii(tkW7<4>`lK6uGn;f83M@{|uzd4GfIC5`pUGM;Xg9O#vm_hHE`x@4OPi)}pSK4@bkE+?f!1NwW z{S!z#Vi)&o*$!0i*Q?#%`>&uND~~Vgs6zEVFmjX|yFu#YZ`m#vRPVd1>N{d{qY=N0 zY2Q2y@b&i0&^P~h?5pu+db_I4YT@5?@%0vnv8}nP!Od}cZ>Gn=%cOrR2jlgKlI(wC zH#Dm5@>OJB|DXG^^y!hyBU4^)@wv-cibH3u<8JO$TK#XtptsD1H>yBy#emaVczS0i zD_dZ*w@%wGZ^QIIh%r?;xUDimNlNWbml{)pZG-~W~? z*E1&?v8!3HuDcLl@70~-l!G(7jaSm!MR+F^T+zYT`>RR&%DgR~IPL{0PkJ10ne?yr z+x5?(9_(jtckith@-LYeNHK!7btUTtr@Y=!@?)0bFni!xsD6T$y_YcPEv<0#U&mYY z^|#H%)4MmLvBJn;K)K<@cR=ffQic`Zn{u@s!uQ>DMEc;>c*;5~~qO)7y|iZz-ke z${>3uhp(K2r}rJ2jbWN#>b8kTezQB2hiJ9L%Fw3 zY{aks&khk@I|TM~-2MMb^f+pm^w0Lp!8^*=*w=g0>~h=G5*A)>-Sj$0(ad4W>kU18 z!CD-9Uwqd8r~d!%7oV*304L9pk$RZ+i8W==TWL@70igE`rPc*_dcSLM--?YObDSN5 zu>#3_{nDIssNNNOqBiBDTkL){TwVMYt^Yr^r?g;tC-HhmV|u??({qPFibiH@>T>0u z#n*e`%apC>`$Wm=^mZ>bXTHAmHw&al(5s;NyA(N2Zv%Q9WG4M*OPy`SV~Ukygr|AWp; z{o(!_z4NVW_qptuM&3qmCwgo}x8~pIExN0&pI26i6h&H^Mcd1ieZ%BR>OL3GHTILTI(z3S+gWd{?Ux+~Oj}t-j@$^2zqx84| z)jNd`J*9$X@A-*0M<1ek7k9@r&akH-hVS|K}%ZNc=`7yM;?8P)p>Z};LiD=A3DrbVk~quE=^#GnMb|37fRn>r8G8-7Tb zyB5vfcaHL3?f;wITj9K3VyCwAlR>+Y-n+eGf0MnT&`9$mU6LH9cN9I2$&kPA-%!@4 z`1)<^>s`L>rEu|n7V7_;B-@>m!&6>wXy0Mh;t9CU0nkAR&)8ko^c+k>=|`qKP1nu9Kd&6B^EfxbanTo_h}-XNX5 zQ~VWngVce|Kh9i4b5OL^^3xOVsfeVHWv0t6{3~{XNioKa0M-Y?#-JiE#So-%grbp%eQ<(904%~LnSg8LamS`5Z3r_tJq{V~= zD{)j_Tk9}CiDcUys^G2_WqwLbim9X)!WJWO;%np73s^)8KW5D>wVzO@0q>A zW5&JocJlefS!|C^j9 z2UcZFdA*^N1HV~`BmT5hv;g{o6goIDXV80=#PMOE_w&0x26%cuy)kZv>0Q2~gQj=+ z^{-l|QN5MNlujjuQxLm8jof)?fs~Q`%^TaCC@1SNV20|Agy;91Eu|t>+R+gyCir^m zw(fHc$^T=#g5GYq?ZTl;TKIYonfM%XcuwRvy^ZK`3^M5-SK&JEo>lDYtqQC6?q{L? z&sr849iub#cW;^0FJLJSjYnaHm;ZX4$c#a6l{X^#KyTs~y+wF>KYUw$7h8Kf_O*?6 zyyf;Se)A$Md)EdeulA)N4p;xY&P3PV)L)I%Vbfcshqazz(_3MQ+ekslQOKL|@fu%B2SmI(%YZ@2t$) zf{08O>i@*OM}mHZPyPBoKb^HWUhlcC_D}u)pQRdSGWvXtNT|H z@N&?E|Bn&u6Dw<#Nqd7NG?jP!7n+0O4c%`TqXkmnZpSPFTK~6(-g5XO^XX=n*u&}Z zyiLgOnoDslC#gvL-Yuh7jqpFQ_4lU7Mi+jr2JOOE+iAVf!2iS=#Yc`^oDY*Z?T37g z9)~fL{C=*FG$_FVb=ts zpV-A|MxWN9dN&idI<=t>q$d_%sVf%6*E>~(n5Q z|IeC1@3|{h3j)0lzWvUPr}y$C=bf0|QoPq_@Bcv?E?WUUe6}o#vyb6`~#Z zdQ1K6xIUcK!Et(v(&JEK(!Yi@bFZip_Oo}L{+e~YtgQcg7KJG<-ZS;Hcd`{rah%iK zLVW($`o9%}-g5*uWdgkye5vNb)BE@5K_g7>2g+w@^}m*R=E0Y!-V3>dEOum4kc4~d zD%w%Kvx4^!u?x~%w?F^Ljq1JU&di5voTy0FmO{RHf1~%xW8I;ZPwS0AJG0>3MMh8X z^$yw^67IgXjpJr-_tWF>V$wg$nR#J{N7&c<{0)OtmCwxA{|ltPnW_C6nDTmi7NxNi z$4B$@;Tc)9!O02+y)_0qZGhfsgd!ME?+ZS{V_5ya=0yT+?d`x>*(di=y%UXxye{si zAn}_Vo2pU0t=|zkXxCdL`@MOB*8k6o+q8adr6SAZr55{f;}1?AHXl6@xun$?w3DsY zTqyPlU+-R@jMhc>-*BAXBlI}BnDp_P+i?Ug$|Fesi*&h2pQ2*y{ zV=az^!}i+$)c>4TivG|2LF<19h8(ou@GDD@gAT-43FGCU_r>uaupIPpjR!3UB~FH` zudUEC>0aVzG8sidVj~PfwSFZahuy4oc+pQRsZ&Bj3;o0<{g@58-i|~@(r&E(uo`~^ znJ=01Qs1b*`ZK-VM4$mF)(Afbsp^W^JSzFdaU;kydK|Nu^sgydv8zam{ZDL7&GwP; z-^^E#VvaAn(2?&dM;pt7{JEwq+AT`|< z(MFKH{+;%AsNSL_%d@<8P>}DY9-Fl$6Oi}0KhAQadN*7DJZ6UK%~i1WsY-Grva?mq zc##yo-m?BebVSSWT|OEvRI=t}Tpw<6vGu%~|p?de3&936vML~}BUfoB95)t>atuwh$y-#Hy|LKbAtzghup5_*b z3z?cy8YT*bOebGPV5-;p7-a%1kl@K(*=G! zz26jk*pKPGc(W{R_V(M;qO*Fa-r9C)0w2-sEyS3%rrF$y$mdYqa0u0V>$?@kVW{4R zXXd4q8%HABVkGL?AK>d<{jp$cm(!2xV0t@e%b?|><@kCZ2+H^rdYzx+^sc1Gaga&> z_!o94UvOk!Z|F{agw7Y{^?zvGTg&>ssbBvqS5I5cN*wj(DYv#4(6aYR2EBFOD*kJF zYrph9K0LkU1dX0!dJD$SqpiKQyM5iLfa?8aL7}MbZVJ+Ut*>S!ArT?A5^E;WwKpR_ zYUDmt?+0bu&CCoVk*jq{kkvhWy-Q;obw3q-uLkX|+sAWTpTXDL{Xy8$F@Da|`zSpQ z4<`Nlky?}{SirvC!7KHKEm>LrPrLAW^TgY!pS?BDvKGg>hj&!}ssI1ydYjY!7X8Go zVaP#-3BTupPwbXKlj(Rl==!L_vPWnRx^(ly4(trlj6Dxd?m}}=QsrCUURMedIwBj=!V8yh{zg z{;$kDld|TCFvopjkJ00}#H4@qAuI2bH?p6D&U=MX(m%2=f^7YDpq%o4>hD21@|(3d z>K~cYN03eodM~Ejhy!{@nh8zA(_4yrTmaKscIzM7C)TCg+As>$J8S1EZcp?DsjwWM zbv>xw{1GYcSb@|$ZLca;AXR<%UiD%=6}hss+{*MWzTOm%km>oRW7VKtjGAP9)p>lq z6SD%uWomgiPVW`;IQB5ZFsy=;{`T9T9n&lQ3|9{|s^tEi3;vfp_ z6NxIJjUXKv^fu5c%>a7q@pO^!^oDm)A7UfOyOiIw0?FOTtadx9x0;5Yc?$Y^>qzp` z&@ZUoOEAnxK#(HA{Tcq5B6xb6y`E-_>202Ofwnl|qZ3`~jq06Z z+8UG-LP3NrLzm4!_12Ve55{(H4Nk@+Ek^a0=c%K7zY~ev)Eyz@IpOPl>x%xvkHOEY zYw7KFsi#~($oP5(AGsJ9^px}N|2sjCBZNu+Y$YEZJ^7k_y~`!8ddLP_|GzSA zfc8Mz*=_MnT4)X${>YQ9mQF#;R8*W~coUK9QQoCkfuvp3xR`?Gpxhs4{y4WqAvaRI z1Jt(RpFs-M4!!7?*;9R;-fsK13WWte_-ByTQ2o^d#6~&p6YE8f!<9+@`ZCU!)djPk zgA52N8)FTbk07CL!d2rpu2X&l390e36o*5F@CLuX3M3Z>y%EO-BcONV9xh2dy&vsG zu3>s}lTXo(*j17<#|=@v3wu63E{vxjyXI1ODCi2(GDoEVOz&M@b4wgiy*K<6d6<17 z3h~|kYNMekzTWcEXZdn@e^i5Z)vMpUl3j?eH??k7&6q#uO|j3Q$FYM+{|?>xWLK`w z{uaAYs+E7H`$MJ$lJbqb^4AGZr@Y=d9r-N9(Y#yRI1By6qS<>LgWhCCp@l&27lkbn zczV0pmFZ$5$Wm$sZ3KDoc}$r#s`rhGy*bH|6r}8(M4KU;h_uzd(#G@-J1t6fLG>0` zpjL988ijCCGnl75g*L&#JkhA->X&g7b^`0KbM<)G? zu8#3*_GLeN{}DJNHmb!!_RjasAAH(9<@JV6Ze}Tt!37eOqSLejX)S}^M%^y|TAb)5 z=8NO${epL4C8qb;rNy-AtYMzV=lsPmK?~o!G+{LlKkshZ8f(#BK~ah;y9Yf%G`` zG3noP%DWZj^VrYcHzPBT-M3<%z4JSyb_O1CnDPbE5T6W7aoiR%tQh($dpk4ez2s6w zH^|;n^HXp3vv-Yu>r=hC%r_@4sA_yIB-l3P*WLow zKVm5kH8Im)U3=pZ5w!B?^?TARViMX*Wp6MD?Gh?Lj&dezOvNgLKbkwSfY@L?rQ2n=Ez)Nxkty`#bau zl33#vJ<*3$BsF%PVwfj>4pOTZ4?pHOot!{#*Q(tg_m+a6gUnWGSn>99-VM^T>2WM$ z(m$_-b!V#+M41*k|EW(|ThSH;)c!68DoHddHyPjA;o;rY@s4PS40w>L;`>&%+} z{OA8~vlBfIIVSzflkE_(GGqS}s}PvJyy6*iy?@qB==z3?JXB%zi#ZuUqP}+yx(di%0q6ZxBIZ#YiUax z{t8k@?Q+x4Ibs~A_X>I(Pnh&?;JXt1A(;K_&1-r0PGrwLrddBm{gmbF)|@G?cZ~TB zmf{GYZmN?0>-Clm40@Zsy5I`*&JW9$!P9$#*e`obZ~KG&wC629ZK>5$LiOg?`c)>2 z9&hPVarRP1_3op1Ct`;aCG!Qt6i~fI{Cr7A45-LUgS-P98}aqlPUhadX3@Cub9y_O zmiZ|Pm+|#}?I@9PxSW^c^wy`x@rp_R&X(=Zi#pG~-hUdxLyqS%*BhGuG4b{Ki7Br) zG%#%sD{+W>9%=BnNt@nU&!G3xOCvcz@853z(s+9NA(e+Pz312wY0q0KJunhbM)fWz z3cPkTnS!*`9PA%N_y0Q&yfDVr|23EJH!VQ*b`3w_GonL9{J!s&h^WWcyCUZK`o49o z#=i7+H+!=W{Wy!Sx4KeY(5wN@JOAH8k3*hG|7xX&rmr1gU+>+{&Kk2x%=M1xtk9ZW z;5_B0x1g48mf{$Tl9HH}_fP%*-yWQ^^xsG8e;3hn<)HLl(LU^n z9cO4p05*ag_*}YLAI(AP^6xBQD*A%dbDJ(*^aknjstyuXAYJnhx8p){(82MzE3Y)8 zkYAqbn~vVbFOaHM{LZd@BTxQ8Z+9ekn^j;Heu1<^i=d*ds?Bkq*h};{7BlIe_>FqL z1!?T(ppBA879Z_qVT;{*4UrW!yi@-Zdu|R(ao9jlHC+zUKC#{mdRwp1ma7A+M)OVOFVH)#`Hd&_fCESt^X_R zpLcBJib5(#M_qqw;&&ra|(c85>Sn}<23clWBHa}CXe$U}Jy;soV_{yYz z<#`WevMB7=|CDyZf|4ZBwfT$LUR_ z$MKp;|0WWzo~zo;e)c{-T3KNFk@*TzOg--`gUfMKUhkMVL6+huinu>vewmiNH!|qG zyaS=V-ilpL-1#_J5l`qE3TA1{2By4ZrgS+hOU8%4bDi>m|cTV_|!;#SA4)BCl&`e97(S1LSgt-WbyZmU`~K}D2u420ij<7e-lBkwvq z6=slU(%Xd^rRgQ@#?RjAFXfM>9+<^(diT=f*vq7U4Vy-j9|*HQIEk<_c=oQAg|oM( zNKd2;w@>-?f9U*7*5bG!JN=*g|5>WO|ND*5`rn@+2RUrm5d=n%cUI2O#LGb@B|KW# z9Au)W3vG%$XSn3zQtT7EyQE?Ib_z1Q_-9@@`oxar$zeqrbKjQw3y zWMAB1R$4fI4iY`p8`St!j=Y!N?%d*|AA^1Hb5PFB7WE%Xv^XvY5$SPcG3lS~4vY8| z0qlQb&u+TEQ1Uqo_5Ze_hk9B62hRVe9%3nu+aHp;7Ua`Dv3?AC+iOnHp4i1kki(;I z)baF=jU0W2ePT~@OVAcb4Wf)RO;Ej8iX>k=j@JLAp5BDDsNO@}{o^)FMznMXAyC0`( zLH4elcWySG-rt_y*n{cKv+4q^K-##aa3LAhyY{@9;&zf=RrQKYKyJ^ zkIc#5DUa%X>gcxJl{r*o-svqv4>j@iZW0N9R`gYotV3_tH*&1vu_V6U1s>~uW~OqU z-XM;ACjC3Trqa?ihkd;T?%VOrV&VP2*BVyK(jGQXdA*l+G>yJ%u%}Sp?%K+6oy68{cH1u*}m(t@u#?iI6 z0<)9(*zTt1Iq4kfA?s zarAaSh!p|Wn)o^BWlBcA!B$0%8$qhm6`jFX!QO$R^n))}S;Rx0Zgyz*2yPVd+BI4qg;Z;8icaY&r~`u{|2hDC=8^ZH-# z^S2TI`%}OEH~5&wQXD^Gz6om|q}Bgh8T57>%^m@Ie?DEJg{OD4`8Rb;?`c;z(Qa=s z=hM`~UT@W0A-i?AKLycN@P5*ajv&8ez1@N7{Y@^aZ!4;IvlrrV5#9e^?qnQg`8WIj zTWzzn8dN07XXx#YUP6Y;{$~IGTN@^xP1}5|L@YZ?2PZ|;=~)C`$?GI#e+#H0jS=G%xs4e zeW{4^@Y*Xmzwz}xAzC|L)G(9mNN+dqj?l5_0ern9p6pRpmgl_9iO1=2gfZ!#ah3j~ zkgM$Ltr-^}^_`Xb|2>^wB%W9`^~c`7tXYf0H|**^_y4m}d~-k>wEo}Dkb^eZ70QAf zlzo(EAzlu8_rS~ryC8icd+Sat2Z^bRBs@Y#kU85{Y+Q-n|1YaJV7?t39Ckrkl4yr~q;3>)zEAYT;fMGIlHc|Dm&Wf78-sSnPKCxNZs6DdqnkhXbqP;a zbHGpZ-@34l9>)li{@r~LckAZ=;uAaTmC^XIYUU$I$kA!nx6R{IJ_p5Yq_PwTS?RM? zmscz{#U9F__j;@TV?gh(7e^Q1=^dgbHICgNRkNpwcK?6)=Yg z%&50T@BdS6wHUy*w_H(N6t)4?d)gP3^**zs5W=aj4$E8kdQ0?(U*1tQVa!8s7q>g7 zSfm19?`1#dA{T^(IIch<(&I2;(!ZR0O_GXL?0;gH?$QVn6k>kFE=9!R4BvCFDL;a| zAf3cg9G#Ed2dP3ynBE}_db|91)duvw{-Q_^Pw(APEjuy2yR84ZAYJ0-k=qTZ-UaGM z&&Rt{kd0c?s!yONNSDhQYGHc+7=Nefi|U>6_M3s;^eE)^e)-UpGx&N>b5HDeagm#R zi{7sE`kGyL^6~Zl?XYRh&Ly08{+~#XV}eQlEKPq}ssArdkV-G`Gk8D5!Vc2jH<}jj z2~%Egs4r(8OK~{WY&QJs{l8!az1N+~)dPBaKifPXPj719ehAY$bnh$L{hD_v>;= zU5eu)^U>QWJ)Un~brfIks@dAE9&&S^xjHI*?-l9YInV za*&sw$X@IdD}-*4CcScl@Ny8p+`{=-{U4j!NPGV;x+ro^4f=^ag^Y+=FQFjwrsaLh z|CxaFt=jejdtzsm+lL`j^b`ADUE*Z`DGJd`UD@1l3jY&3z0o7TX2odr0(!fYKaFOi z2k}3##>%rE9e&77=Cq%)EIkf{N&oaFZyJ2wzramf~>LXgG4Yl=g{@WYBvfv1tt$LC#rt+YnE0ipOLaruQ-HUfT4Q&&(T#>rlN- z^he5$FQXuQwqI6#NA>QxwfPICx2ySWp=GGv{Kh@wN54{$;XCI%ZPM`dPG2ovb2ss8 zHE1{K?bvlY3SaLcjmo9gBAlo90eT$AnDp;*!1=4L2iVu!Wp9(w+c(TdkeW{KmBp@G z8nCSshy4#m`cJSF2jNXhmre#v?+6CHJqFXa0=?fRWG=?jJKSEn4%2({m}Cq#d;4@E zIs~i#ZR&QCBWx+i6^U7L-st;(Pxu7~F};W73Uo2O?dI^_9r#E^8W!K*z9kV~Z@q%d z)Z;FnszJN;?Grk;w*QUZ@xjk~4oq^~>n-N=IF2*vpFs5ZR+(1z^>(lxGrG8gg%PC8 zu4Tz9b*8-Dkjz%r;-D1FpYvD!AI_k+dj%;E=&d8;V}Pf(>Df)gJnw>;pzQw!s9xYy;a}+*oEnh zoZX=E7}a}x3~4>Nj)JIj8;TRq=PfE9t1ZR!R=)OL(gxL=SEp*=Ssi+MYxQuLv!y_ zXL@@pWV&Rn<2=tPuQ$XS$66e`dO^k>693%)&tZeh|FJu0{lAML2l*MfJ775otN-Vd z90+(hNXwmMj_n|wb?>kD|AeI7nxZf2nHUPr^P3S%K~9^PsF)2TAdiZPL&9hd3fYld zdJVl|htK=?^sBogk>=4!o(*F7bCB=&lue!$jT^Vp+leTXs4+j*;r@RudA*6y${7TX zn}d8ok0X&u|6~#hjiYNxxbgju|90qKc4q09etN>Z{*O`b-ug~mbn1^F?H;ofN8+c& z-&2m#3Z$J3dT)ljo&mirF39uZ>D`mCaW|&7-NFId{(t0Wte`Eb_xvE2b;m;~Nbz3o z*xU~Z2){v^l@O};i5b7;+EKl4RvUh*TM>z56Yuu?db%0+pVM-BdF$=&e&hZ0c3)pr zMwH*c*V{v(#s8$$caHnS8qni#WzxT{9Icu#arQs46;kfU1z0#idL*dN$R>_D_4U5_ zkfk_&5?|f#+DFrS2ZP?5-kd!O^d`zoaO3H{{26o)(_7DOl6HFQ;sWuTLa5$#siR&Y z=;^Kb6VK`bh7%Aav&LNP^_Jluir&Mh-gA`3&xb2TA`5kkn<~rk^>!O5ds|ytYivMo zce2UQ(I*RE@5_Q-OP{W6<~Y6O>2Z`W>EE16>Xim7_Vqq;SWkXY77O+N#&yp+-tC_H zdMn$o7ROCe$o#+R|7ZrieU4_+7D%zd37k^Pg{Sw1L0(a8{a-FagZ8}TOs^!Fv*-rt z@4t;!$2d?B9hWfs@1GNp=hVy!=!;15oUqV~?@ zz4xwqFTGuNBqiNQ9e;y#V_jSG2dl3fSO1@<$I-&1f7ir9FNptUe{eE0oxlB7I}3*s z1)Ef|G>MDx202sa?}uNp6i1!d&PDxyU2hS^pttuyULlaZ&EM{W@$}Zc+n0msE&h8s z?RiW46BjluMD=ce;zFvkpdilG)+w3e2}qXa^I`0Ii-#kpD6>$#TcmZlq?b~WgAbO6Y8u!PMU*4N_eO`;msUJB*nxV1MSdK}Z3^e;O(xn<8+_Oo~1 zpbF9|%KUI*{oeYHqUm8%UT?P(Pg#oNlju8dC^qMx`hP0qtpt}i9)=tgq&d3}OM$PksgDgAk{PYIcUSL?(1bu)5-7Y?d~S)-0#W3&q2D2kXsjAlsT^c zccaHKk4gWkEe?cGgxSwQ6s7i?8#AkPwE(tqgw@C3j?f$P6;tUfzMPxAB1HJbzcrSpbcW8a@7EEuFQ6%jI>G8AN8%>B=UVhj<}>3zTWC*a;B|YCP@B4Z})oD?!{_0_ zDVcB^L*y}fyOE4vC6mAL^{#pO>XC9KiQ}@jAU%%jO#0XU!*!|qC-(IwAMrnFA%LAIP4DrSYKG@fy*Hd$n=x-51yPMZ8x@EaNIFu7Ziu0J+n(*! zutoL0yxk0rJxE2?6vU-8YU6)mRd&t_FxQtQyU^R|IK0b0ITL@29c1qtSd+wgSL~?L z<6zc5elj`yum$^i531iPRJ+am{6BQV;>0HDol}1Vxlj5eD{&YEm0j~cO{@R;81xRg zr4tFVcgyHg5}w{Yx4i5yy~U8%G`$tl+VUGvy-Q_J_9PoqkbSytehKLG)@l3JsOhNQ za#e0SJyE@nHFqclgi(>B-`6y}7sA&&rb#&Zg0Bp@nBLBEeD0r5-|(|{z6`uZM##7wxEj> z$yNNi(@?$h#;tQAP`&$7pFU{bL`81A>M^FS9O%yh`w-{7|CdOQV>Xli30}(_7Vl-h{;xZGzWx&n^?!=hqT_B{Kc@WH`-t!o zmg2a5>tzWNpMwaZ1#mxiGejCCy(e{&9+7HE7fB~che&CpU8G==H_4e~O(K(YNvb4C zk|6OnafJAe*g?Ecyg@uiJVxA4Od>`Rw-P;wtBICGL!uT@ktjwai2M*466q3Y6}cmF zMdXY~p-84kyhyl+pU8Rf0VzE{~7-S{u}(|{73k+_~ZG* z_W-_6S@hlgxiEmgj0k(LKqpf`Zbk#bR}8<3g0 zRyouK$n@0(SLijMrI$u>pjUuQqKkh+F99Kr4MxxlKx9Rsg-|CTqi&bE&~rdbE>(0x z&j1-F{GJOv1+F`p|7a$`x_uP(2`}J;?{4 zIzWm}9`kA4WOC(8rDG7fMhnjQH5>*l2*9+5V{UX zN@=<>bPdpqMrB3lDjq5SSTA%|DKdgC=1a0+4}xaCZOIQ7F1{-pq@*yr=Sc# z@8Z-hL+OCtI@zW}djY*Me7+A#1JpH9b{R?q^tuM!Ta*Im)d}u;sJGR4mX8%1A3whM?rCb+Ii>5La~5aUrl&J zF~Zyg7|q^xE!U*db^&M(3`*Du;PHyLlpO$?NS@Ns02)WPnMDD3c;p!u6~Kd|%kM=3 zxbNZ@8Udg|uG={rz}*ivN?`!*+_(L@9l-5f%}^+Sdbj$v5CC^ z25|KIarHF-jx@h3b^=he*Fek>K%xKT!>a)twvKRF1t9+7%+XFashPsmi z;NbRGMs@%W=tKQ00pto-C)onXc@$}310cKL*d1#CS)rk;tN>&#b5vRZV4rXYc{zae zmm|KG0QR10t+xP>mS!Al4j?r+^|Bd&6p2B?G5|@vOKeR6?5VmjuoOUIyhyVNfCLwh zB?y3cgR)UFfVgk_tc(G~-nP>;0uYmZB54VLU7M3X8UolkzqM;IfE`ORpBn&(x^H-5 z5ddo8y8{aWM1};Z=>v!`8m?UcAbgsfpB{kiz0aEF0|-6-tw$F?$d3E&^8f^|ioB@< zV4KvI+1daC`zt-P0BpVBS2GvDmdLbga{vTb4sXx|;ICP?Mgzd+v7J}d0r*~9H#8f- zrd>-vssZp>?FY>Q;H@vTT@`?rU_zh@0MCw#Ka>G@6u2x>0^q(~%2N@5+mgBo1ppi5 z;1PKM>xl#fIRGws84|Jp)}2d{p9x^Css2(K0M6ofe@g>!dZk@01;Fuo>j6mstG7?y zm;qqbvi&n8065H^KPV1>(mT^w41nDk@rmgGRvwm}I}LzsfL^O80GmZ07LWi~OW$!I z0$5RZYlaAb<%Mx?g#lP@3)(LPz(U1;QV@XI*!6A!0LyNNzvTyDnwwLGQI8c5ej zWu!vVK2jVhl;nd}|5hX;k~T?^G@Zml94Gb@JBf|N8sd4h_Rk?E5+jIyL|5WU0f_$# ze-D2Le*^zD{xbeT{(by${Gt3l{LcJV{6_rR{EGb3`FZ%p`TF@f`5O6Z_|Eek z2=h+zj_|(aZRfqqdxf`@w}3aDH-87Yo@YD{cy92N z^Bm#H;)&-88JSq>Rp35Cp#q z4hp^$Y!a*$tPm^~%oR)$qzVS0^A!|9Q^5s-YJyUNf&#w;h6TC>S_N(kTta6n@&wWZ zb_xUucnYi*un;g1&=imrAQDZ8^NFg&8AN`OpXkiXYmsJ=I+03|lOhL2QbeLfwu-om zIEa{`^DgQlG9tpllfomyZ-v{1?+RZLE)_076`=p3k4Ef8t`}~H!RW_c*g2*i2BRN) zp=IZ}VKDl!7x;CI2!qj&J^$n7`(ZHpvFE!w#~ucwAA5pJ*#Q`ge(ZToR8?Ux`myH` zRtkkps~^|GvH7_qp#a=d04X+3Ed^e;H zy8?RJow*5i0o2jB?-RTZ(34$a8{oBo+8x9m!Ono%7RklHYXG&3DcQnKfSPN#p1_WP z9;YuhhgSn?@{03-ce#9dQTLY>ecvk^i0ji5i`U$T9bjy5D0A3ELmVeVO*b-39i)SBU z3qaK;?rOs3fNq4nw1dq6U3cGS3NHh6O)py>HU)I0zxoEe6wu|W^g7rC(4{>QMKA)W zYSm{um<*^=HBk^Y22?TrBNa9Rbm88!W_Ssp^T}3DupyvxUQTP_#emA^lk;E$KxM!B zXTpmBow*kq3@-#!da^7D)(3PtVrM$M0MMzq7UHlTpb`Pf2s|IqNm-xIur8qD(#nhQ zJV3`o#Oh%kK*x;v4#L`ij!JsHfwce?y{nl6&jnO?F}oU`1L$z1-yT>KP=QTqI;;UG zUrE;lRtI!wbhQsW`(HHg;|^F2(1AT(a_}rbxo#R|uqvSaNvBA#3ZNWr;d`($psWVF zjj$4+%>DB1up*#+-t+ol1wa`~ofTnuK=`T!C?bJt z0W1V4+(FX;76gRtse=XRWWTmCt^#fV4?D?PL;s2aw~Eee>bl zfL6Ve*#XxBayU~A!F7P_drl6)w*XPR<~YE$fb66m$HF%O*}g4Fg=+xW)QN|~)qt#b z{)mTf0J3uS?}D!bTA|Z<3BCr%^8Gm@_$nZaU;g&+6+q@$NDO=#keOf4Z}<|RWg5;h za1|g^!NFL#5|GKKb`kg@ASCB}5?ld@?0xDRd;yTL?qyZ@JRl5y0lI17-JU6LA{2}p8! zr#`$7ki&?f;|=Bmgl!Ol34pNu6fiF!>|`^{0|+|^ z3UdR(&dtGGfUsjmFboJgl>tM5{IL7c{s5v~Cp8I(cKgn6K(xzBegUH0?Jxm|cFX!t zK(tG#e*mK0;rksB?aI?{fM_>Fjsv2-)iwr*_O#U~AlgenUjfk`PWb|e_Rhp-K(rU% zM*z_t$o>R~_MY%CAlmb*9|6%`s~iI4uwh3K^Z}5)=7cRYD1vIn3!i{Qlmt!rHuA)y zfBfecr~L%bJxJ&l0ho}gYK^V!Vj~`~2PxP~R|;~~n3UxvR2 z$+LIJUUH5KS(DzbaQtu+oQuB)N#@gwke;gf9Jl}9gB}O7{=Jt?d#Lh;{VjI7(H32? zn;+m_GzWBZf0xnrM=@f`Z?P+NWGxQ;r?a=JZO0x+j}u|g8yms{y_4_!nSrPG)@(Bi zOz)Fo2R37R-%Z(aS{&88L9&6oZZ-vh3pSlyfa+Z(!9PO+)jLbk#8VH|JEBSK(aQ&s zh@J6}&vzGmy(iTSUM-)YOs3G=5x>~Z4_tf^@ofVnr?X8el^eRkm_iL1QI;h?!9fTgX9EwCj z+$m3MHSqPeq>`qo4JwjByU(H1UlT;}^$vS*(fLx`JdV@bf*uF6{_&pBy`6oVeZ5JY z6xThI%=OkZQnT{dIXUI^E;O9QQXGF&0~S0#NXyaeEI{wpnFZo_dY1*k7cjlK zo2>mYy;FngUm>X8zxH2yWTi|&mfY!?*4CeZNE}tq!StR{Ho0srs`s)kN9bZeBoZqy zb~t?k|9VSG=r*q_R~5*h-MMt3Bh}sb*INod?7Mp5n>NSky^`k>@RYwGEoKgDaa^esp0>A)mc0cT^u}flf!+#vfns=iKbO1u z5z|{>g;@Zm_n+#_i*BgiGK!xXMHDDVYVA$w&*=3QWt6mMnBEfQ!?Eh9-n)#<*F<|p zA_*N5@d}^u^&YmHlnm_Ki^@^)@zT#xgV*W1%Fhov~E(k_AVyW{`4{|^*jocudlAc-;LAZ*

hgFw$T8${Ep`UU+oPCv|KD73SX>#+L96?hg^ZX`kQ4pR(sAeo>C$~%k@9E` zYM?e|<#IP6-`i6bov)`NK8CI0=l|vn5``x#FY~6$lfCHeMs&V?m;IYJNFMFC9sS+P zc{yk%J&r~u{VU8|uBE0rooOBapDHzcO+1{tfcXd#;?6RE?BF@&N05+g9!qf)^{G@- zN@$f3xPoIv=AOSJiTL#!y+-gm2bz;j@WI0hwsUwdTW28{@H^bkiNF5>Vgld zx1#5da#>VwnZ0Y)R-$^h>drC05l=-P3@K1N54sP4{aNk!&as$1cm-D(2Wdi>B ze_utBn=ev1uRsc-$HA4!r+c!m_YD4EXS-?4^=?-fd9kRhZOZGtZ|_%@;@B=f z5mcH_(|a0&-q^}E&|3w5IulQCuNUfbF}>wCn9b>!+;rupK?}D&7YO7XL5!?HXu4nu4>wibRw5>g{%4BPLyJ>rhLj2nB z>;DZN&mUBZa^CFiDta8u`d9x+3voEkzTP*8o|^ejn4kZL*2#KXroWx?dP9>lSc~Jf zxKF`f2c$(A^v1So0KLn9=E>mcT~Q7{!wRIbo)5J8KiA(gRsz*~YqGnRxIP8huegp^ z8Pz*RR%<{C)jQ*g_S~H)Z`^}x~7f3&U-Z*5*|B&gRCZNtzLe|H7$`?pszNRe2 zvHHlSi0UNT^cIOhZ*1=o&|6wCP#RBfy&j=xOz+@;5Zdgmrjy8 z<%5Rf=;DOR%s{F&Xq$AD^YoUW$HAI(P9u_5Xj?Y8=UE{V&CkgRtF~AP3zI)>OsIL6bqtxUegB=l506E=Zr@)4tpc z%|W83)MbK}6r|>?U)~71g0%DaJz)hj2a)oEq|(t(>`6-f$=%DM5Q~TI)*-L(3#87) zdD2hjijmFe?Tn|{SUq`!Umz_JpVP*Fne*=de@c(TkV*esmu+3Gy@dS{q@_`S{q+{+ z1rp?Hk?-TU?FvUa$WEsO5SHS|dp2+T;#;%=Ns>WtY&$W~+vC)*GM?UN2Ht(e3Z%G% zaGKt7rrREnQN0P<84r0?=@#JMQ_n~^1l;mtXK0OLK@JiyN z{~3I}F_tV?Gq;9->EDvArypO`iJ{?x&xDjM5Jq~95YYuzu$vwfo-kxiY z93JCh{)vr#^!!_2R^OD@`_uYnmg4X{UK$sMUa^B_?->kwWBcQQ-crY^mGJa-8!_m? z^xo02kf!&?EB=ocp?a^>2{+qeMnQH~+glz)^%f{gzl-T@Ib%X63)TC(X>hjJ02SG8 zXDPif7GLitC!2eAYDto}(c8UGlF|(c#MgVJ1|MZjks8P8-A0dtS^qpU7M@%_hkd>4 z7pWf#xXgTk6so;gzN4#m%IgjNtY9gQbzzA!t^b<6m0-{tJMaPYF1@x_5l`=fVbX1w z-d*!XXp0jXMB)i;RPVky(Lr6N6lCF(psck3_c{eR0WBm7hF^>+STrCxq}CRvW&&eh7}<75QB-gC4! zWgV2^yvvDK)8o)&(!VaZ>z7K;u&?*58)GtgD_OXE`-;&*xqA&${{BCx)RMJ0cCFbs z2fcgypZ))wn56!rPv{6zjv)tOXE;F)BD5=O;^m+t{Tkv}{ZH)|+=lHzGC$XQ|NR9$ zleE_xe`NV+2tAdIml+L z_npvjL2^93U6yn1=^Z=pbI_wlrOme|IqwB2D|#Fcne?wHUesuOq(T!>76m3o2GZO z?FYASsNQ*dB-?hO&s&asx#~YMf^LxZbl9wd>TNOh%^TfriWolmIlTE16)CZ{ZLssg z*V~rAz@^GYn0$)fZpkFKW|BR=-V~^Po?YQgjvGN*{Xh2JJe36Cp=ikqSvKbi9Q$ ztfs8K^Ww>I?|$yd2(v}UyT0T7y4NeE=niiILuYHvR*_a!+48R;0<3JLB{*>&p0JCyw7u$^22zKsEm{F{?TQ; zND<)ed>}dCtTh1&UF3KRkPe_Pz~!m!so-$Gc-m`DOZhy|oL`ft8v(@vF+#~Vjmjmk*Hi5Lam@I5GGyoVrrMKru)_HQCRPMrR7fQ0u#kH}Ip zfHz0YMIyf$0easQ=z0Up-n_)JG~wBs!ul&p$pCMD{zS3bCL#nb3M+r$@fW;%Cx0?W zEx?oGmU;`DFZxSy;x7_g>$6af?%cZz(Sem8xAww^&*Et>PC}WsNQ5U-(f=nb5IxuO z;qL#|c`@EUP76_|gHZ5R_22%VG5&tR5-U&PLGVpbWDj~)E3S>^LFKR4*1>O(Hc5OA zf&2d_UQ>d{L4#EK^FZl`00I=p+B!x284s1c+ffB?vCl^0oDKpHa>!&_x(h6^>7R>j zy#KPqPORKr;u1PybR3Bjk!hF7U538IzU5Gf^(vXEptt|%Lx_$xjQrMalihb_oc0Qm z`=^%24nFK97U$;CxpE~x*0xUz4e#wb$=hMP zKPBu9hVjl##5rXFydzY4*a`vOr}_Cm22RC8a~)>Ea0R*E^W@Dv0PizJR$MhPL`Za9 zMbvo_^d+|bq7j$t+G!(kB(B3{Tjot>bi5O5wh1gc%SCrfYz?9#9wWbvhGK(Ww`j+E zNUlTg_hRe;>Crvz`Hty{43GC%=U%FGRP0`@o|!saTptZ#Ye}H##(N4~HJK zXtwY@K*u|L!!emzW)A!#ByMMf*Q9qbx_kF^9&oAg5urQ0LlGUl82L#&j6D0MoOZlt z%TM(EuEXBF#f{zQUuew7@clndk~$q5mFEe?{P}uIngVb5HdQj->rJiH(eQqhD58wvr;MuRF{(t_4a3UwzgY?R<$SIB>Ko>qg=;#F=blm@#h$8Ty z-evi|a=?Q`bw%B}&BCEmEjHHPAJ9F>X<5qiZ&ni(XOKAK=iT8eU!Z%?%evOrQ%~pN z|0jw6H-F6?(b0jG-)zktmyfhxv6I;I%kQWac7ucq`>{{@Wg)|R5N-o?I&5S(w;LGx z!xJPWO1!}Z>14dc_Zloi!~3VXZwHKbZttp4xPsiVIeBylEU|GvkCmGc2~g={r$u`v z;-Q|?2lC(sX?3xBj2XcDl1(PW?aq*|mrc6O8;yI>Khp?xY>>&s%1Rio#U%|B?c}l~byW@80va z`%$HX&rqb;o%BHZA_~0WCoIT#ul3rcgNApJYO+`pz`I$+JPdYkFNfWehXLLL-RqUP z0>SQWqw5{#U*LL+V-8|c0PnF_bDm28@9RQ+cb!_op(9R7`fI$sQ44$ZzG%tD!gm!Z zNZdpxzseyOC)9ZU&K2`j1c&JkZ(~G<1V(VyZwpeQw z;}1xkUQ(qaZxaWPO;ceR9WO;Ll2ub%t zoUAeE?(Nw#!Q$H4WF(8k4VYhzJNcKdxAG6!7?1J1qr2JLazw`|jQox|nY9h7(~h^& z;l@OnGHkq8ExDv28GW1K@vfFGq)JCd{apBykobT5|Np6^ptoNG9;89xLGY_oum|x7 z#Baao=z>G@pkRm1E1!ZTwy^JOB)r7(N1R`99W1eqTb!?5*-e1>JxxUSfeBJa(LH{6 zi#@S&Q>`{wVtbF>U)ljG$Rx2NpJ#5Od(ijl<11bJI4Tbzai?F)$Zp6)uOJ8B>iXQa z6s5ZcX#&wPgpnT`i~sSBCbWCdVkt}h{toOtNc*L8i;ojmF?r~iB) ztxkbA{LC78iLEw%x&jUFQE8_xxPtWf78(KLZJ~JCvl`%it#4}nm=6KUAG;9~0{Z{u zUj&2U?X4+OO*3(TcbCG2Ba7b?A**(W&0_)Rc%KLz-Txt+rP2n8Q!NkXed&sh_f?L5 z7ZLV_bcgpzL`N=0e&$+VQ}+bXzP;6OT|l+d3A_KtO&lAXd$6A2@y2PSQKchzQZbD0 zBx(MyMu9i{ZXg-&83(#vIpH(C*%E`1S@Jo5IFh+_rVWz=j%z$NQY~OR99d`7Aq; zc$9R#g(?N!@I#nnyuSqO(nrJl!QdfY7;oJHNmBoBwyAxB2@EG5qwcK&@E-Qf>KbBhhW0Emb>3b;gq)*Z3<{f|m?w<)DbZ)h<( z-Wr=LRQH6i(H-8e5FOeW`LWC>6^DDZ|~b|vGTXRWJ;hWD}7`T6kfZS=8Z((G-)dGmvE0B>Au#Ov1m1nAaN zPS^Br;Ql|CJtvg`-ZGm_N2dVZuAe@>_6rP$*0Bn4vCc=|-nyv6_l`$&k@fb*|~`Bme|dRj%bYh)>xfn3(2H?iItD^ z-Epb84t4bK&tG{S-$e(JpA5eTiR+|NM@8F%#eYtaYE$41Kh{ph+e1)s9va@a6`YAM z-f^*GB)q?l`yF=!c%O4L4<^PCAYJ<>jT-^pNtMU_;q(7;^C$dw1H7-~>)IYWM}+)O zzPGu&1igYBms%EIv{JCr7l|{ST8gjsbs@mVsU1xe7ejS|NK90FLgQ&XSVj=zeTDb7gOMUIbdNO8Sh^AVHPyJA8dRW z4dWfg$rA;;H|}h2s}GE~NLN)8INq{;*r?z7#&3c+O%$m?^-!J-d!Q%03*j zFBRFLJ&um|uyfS+`MG?RTah>>=is{eAJE;~_G4<9>4pXiX9?eq;N0{{K(!MbAF~4_Z#)L3#BD{K+0P z@YIwC&4bojODux-ATK`j41z1jclo=OwgV4J*5Bf@tAGH_DjK#bf(B{OyQT!*gPd6{ za`P+LgUq?oyY|_)Fi3k!U+P92`Wqy810K8J9n%%$IISP6lHK>9FR`T!Q-*dmTy*C_ zrihLzjQm{slS}3~(e6P>VRo;qmS9(q8-n&PPX8Xr@D-%@$tbFHth9d7{3VOjAT6W7 z`}&pqL^9si`xUs+@LpXJkO1S|Qv8GT{r_UO7isPQ@2sB2qpi6F=+uP%B;5aJxj2Zy z1JaoPn(I^Hqqr?0vS%&UBi#O>TtFaARd9q$kLFyY1N zf^>&>0-~cIBfljTd3>)@X~+B41+7HI5h^OkyquKCff$Cz8z*~(Ivppjn=koOK`y1h zJ2!McX+R3^-dbyY;6%gQH(=8kjQ4>ZIi&OdA2#T_y8yg}TQldf{|Zc-4&{1!j<@KW|FUrac)MDe-XLZYApMg|@C5+x z#}0kB;Rfm5_}dT@fOkY*T-Cs0B4qD-MSFcMI^Hpoc1Y8Zn0xt^0MiOhq1Mc)Ukamr|v}-FfTN zU6G{YEjkok?{@{iDO5@doUjN5yo5T-9ggf#J%|2EOr2IEmo1#%_j*^^J>=G z&j9cHOkTtAaAL1O=&&2W`+AUDd!u_8BrDCStvj|0^{-`Pu>9In?*%KRkht)nd9QZA z+=d!ol_vjcrwjef-YgLvH5mClTizwIQH^%Iy&KCtn|EQ~y%m~vrqq0IFvH{h^5$8p zbbKu3P)%3ZQwAP>3BKt{}$?pOgCkOD?=j z;lP8K?^NgQsU|>E%e&vK0DF+KyzVye5j*uayGjQ@|L2*A5QSfyt4J^}i2D(UfQfcG)I!o@J&dEP2-;S;3zs{8F-8;H<+UZz7& zI?*f0^;Tyr_w#=?;zQz0+?XxW>(ML7c|TPh^Y;9ryHD&^Avz|e{+{36Lw17(#kAuc zS1Y^!?O7`N|AE=}TNdnOc)W2E6V&Noaj97Pr~fyg!271B-BvQ*$=l!0N5gvqr=AXs zx30wn65fZ|``H5k-Z7HXK_5y9P@nSn3Jx$Jo!4Q*3FG~XH){SDfcM33y3aCti4e2& zM)9RYbocJ~!TEM5^Q{pR5*Hh{Gw$&Y^a+wfp^J;#k0H9lyAIKT$H*@?=4kViU9{tE z7Vv3t&>$5Dq^B1Sxxf6*_;^nUP^BZfP<+wk6_R`FQ{Y{ogFi#Y`;*T#J~X_G+r8Cc zyl+XzlJK^2YSq{a@K%~Mz)9UEK&(1a)`tMzn#aX^;NgVfrWxB&fcNV|gmrRniBP`R zkH9oPbi8L9yc#W{YAUWHas8ij?@v3S z`vK{M8tG*^OR=}NIzO=Uy^Yz<@D0+(EHOq#tBTxpxV87hB+j(39EdtO_nd=NU`^+7XHXBK>}2t?xcM8D|Cb3@0wGdvF* zIrv3)c()-sK4au(evA9f2N&AiyG7xgs^A><>@8Z5$acV&iSgZgUN}`cd~SxQPJ`<$ z|9$_DPMXlar2+c?RTLg{_s-E;vIkvm)fGkapx^Dcjo>9V;Q62ae{xD!wHYk2wF;8$ z+iww|YZkn})W8!vFK_z^>wqQJ%O~@-C0JtX&L1)HCJ><$JMLaE=|yjlmKQaDoEDlk zI*G&;uN3V3@C3ahOKi_vt^N5r>;ux#{Hq6} zSOXZ}gHGV7(lIvJ7vO!FR6#-%c$XXuy+Fo0wVOi(4R0;eTcqu+K$kXB1)1t$IQ#(M zz46SJBjUvbXouL3=(k_uq1qest+WB&9}T)E_5i${cTBuqCrE_SpvGUtIp}zcx@ij! zkNq^tK;kr&y{x*E(ebX=(pcPY%}ICLTSADA8jSqT#<<5!?4cd+Hq+k+^<1&>p66dD z{KKM$;qgwgtENha+Se0RchgCD<0{*x=!23h*VeTY=x9p=4mYh#vkW;RKJ8LL9-m6=c zEw}kj8Mz>FR|0!8WS!CRj!n8bW%rJq?(oJVIwCRh`<6_2ESya{-j|AFJ!@*QD@fc# zna@j`FAR@2jc`)DQW=kzOV%AM*wf0{sSRD^TVL18!Qgf zE79@Z{rHvSZHw?x0Aq8;yFyP0e| zUQyxR)2q!7tNSoK-Z&Lws&p`I@9Uem@NfVBx3-&Z{vGK5*HU;;Mb0BNvIni5Q;|mV zpxVOo^I#7;ANZa0g4E~@h~FD{kY}`m;!5y=bP-QhWB|DTFRxwT3fv&Yt?hs30z8OC zO5A_uC72*-+v~pFg}w*5w8n++<|Z7T4TzGe>9<&6}u^cPE z!SyHZZl%3~G;7Mm@m5nYLAoE<-gasu<5!T0)aiJ%FU^4C5~)Elp}_lo@VkE+Bnz{j zl4y885bIn3j?1X zvr7&WyF!ElUcBsMH8nMBif9Zh^8@EcxgT?^HyGI!1oW zxAXOH6r%l!ojv{2i>Al1@n%)j7W)+VgyHe-a9vE5juW5EpFasERgh~a@V@7oYD{)- zj&F?;Xm}6)UMd6QEiSZ`g!kcP$?sDD-n&PBvL884fY#|3^WFmul5^?~!V-Wt`-)3a z_5km2BLjYmC?fRkI~PIwFCR#!c@yI97t9!SB5|AXTw$+&qgRlj{q1L#PxH_n-bWD~ z0T}s(oM>85w}y82=AS3Ftm7hf1sSb8x;yvvD~87#_wx%?I!yPUoBk9>a&Kb_yvudd zrO9~r8)u25;SGg7(uDEOyp~47yRa%o3GV-I-?rM?aFGC2^yU>-fbFeeQInf6-n;g+ z^Vk5q#e0JHZi^s7SL0llF5^dc?*sh1O>SiWHp)ffcCPk#+wl_}Z@r7Dal0qE=??EG zM28MWewuEC8sjM1@eU7{u#U*XKAhMz>a=(5M?;2hkc7WFP^H7%n|uG)+a$bKQ{Y`X zP;sA(w?>AW7#iN8AyuT=+t1&$&ED*#{7$|}Awmf;Eobx>q2v89zcFsc;Mh=G@W>+VPHvR(;(mO~v6vk6+QjeXkk+`+t^6 z>U8*&epCU66aSt6(@mF;o(Smw%_%&nZm_qA>_M9@DJ??tAYZl}>)|D~XgxdW1L>vr zIJ{556{KmRk4QQJG8^8m$Pd0j`pS034Q`MYc+?oVgC+L-#P`FSFB73ki|bkM^w2%% zke9qB*U+p{9TNBYHD{x^Jh}%dJ=znwU@`qQNO6b`8I1f6zdF&~_8&a4`{=f9E3HtLul47E^m+=sYr_+Nk@0@IZ&Dr&Z;mr7Naz29v};Kf zWa0*=)FS}z?zV&0Hb)6iUkU$JJikBfOYDt^vIl$E z8&N+!{Kwbw4%~cvqL}gVUKvM~j!^OR}E$2~bTyiex)D8laD z<{eDJ+bwt{AqL<*;%Tv!Jrx-;S9kT}zQol83M(D7Eb(pCFDMSpk)AUYOd%O0Xi$M4U%ZVPis{l6&%-j#1VzL4?O;)7s*ta7v-t+U>pC?L(LzkO( zv1*i{iNh>-ZbODIPBQq8P^F{6k*HjDAmiWu|DWoVj(-6Cza@nSJ-)gxo9saW zhQexS9&~mv@i=@3X=P3T=?+q!@H;L|z=QlJX4=NV4N{_STv8T;52PQgdKL-aAa!A_ zWVQ;pgT$(LGk#)4IApk*Nmb}2x(981_1v@J(x-~mNL;ImrRHcgx(E4O*K=%LI7xTk zAXy_iA~Etixq|<&2tVx}lta8L?GE_-fB8bSq%D`g4buLOThajDs;`DD z;V(!bxBF*)f+g1c${9xuQz9hSwpHA%1O12{B+jq)#wu>qCEGJ z6=JXG?gQyXhz>kPekT6AM04@9SCBHp4q+yHvA4H&oXd-Qn`y=Hc!yrUM3s*Hzh)g3 z4wEWK3ktmJjfktscq?_6DWl;X6}l=FzCmh2ZB00Qd+V|{pUv(8yc^do_-T5902ylD zw4DbkNG-YJE8!EQ6T0g=8vx!nxF#a{b%{{cA6tMj}WY z*VFq!%73}u;_xGqEbJH2%Q(NT+$Us0(;fBFI1@n*UHrhaS{_UWzGdrcPeB_$Xh zZ*MWKP1NXEV{Xhnney-Xe>(2^|5s|D|F@y=pq8TsYsnt8a}%dFng_|JF>i+VAhQ;U z`NI`t^nm)KLQvjcIG9Tg5poZ1G*XA>dlOYD-W3h$^xpXjdtFGX~iVC45(?4?q~8`?dn zI_tHX%1Z1l_F9&@kf}qJ4DUguXQq~N$E7UKYKowe7cV$Tzxnr+s?)1ZQ^UiobcyuB6T%+sL?@Ln@;tzvB* z5q$RIu`1~=52U~8Q(HeZ_^aYJ5_kIerLx^?(DB}r)>}MeN`KE=^ddTZG4k7&cc+kt zhjzU0*8Y50pF%|iS=4PZRME`vc;iBPsM5j8vB&boj|BJysm&C4Kh4-idO;e#|NqhP zd`&dGadit=;Qqh<*gVn$=~{UPM~493t!FPj)yX12&%d7L^#FJqsUDA10C@Z8oY|od z@Rsoj@x1^(Z~4gXo~E@D-MtUo8+}61nO8ZC#9a$5R@(NL&s!vK|GL{+NPo{;#3MSS zG4cye`R3KRiFUlZBnFQbs$f@;D(Q+D(V>jrAia#UrAmjRQs-V(B58ZeiURK@{^);R zZ^^Zb(Llrd%lGX+VZ5C>e~>OnZ~vI-(GBpfZB-9*y-a{wu3sFv33hLV0#;|k_y0%c zoSJ|iNNef2Wa*hrg!YV`;ONyy$NPoZUe=xi?3I2<9AR%+E=~d6z3qC-?>K!E#{aLX zi#~p8Lv(D#$nT_s?!K2PwBwDN<4YJErQ(2eN%y%Mss9hScfP}Us&tq)_acuI6DaU* zeC5UTPjQ0VppJ(3l)O7fGr+r2Yr_G!_I|*t7W4w(J#HYfR{JUeS}O9c={5NF_UL}@ z2k`TjfqsMhb^!1F;l^_NL&Kp6U+*3X0dLe(N3w-RUZ$S26){NM(#PUb;Y?1b@mJZ7 zIIHFJ(jDH55FIx$^3%C($(r>axc9Gfda7~vuxoGJ)Rz5;KRz)2`TwI^snQXra^Fq; z-|zqF!{f2C02Sm`3J+?FTIfvnpo(v}I%p$tO`zNB~B1V3`3Hy>9y=cdKz(^uEXaKwax3~RR zn3w*X;qiXzOq~wLfESln{Fxwap}_m4o>Vj$@9z`mb_{EXa7jv-8(M!~1LN8%r2(m8(;GVfPlUj{Nit z;O*$O$6W%P-pa8#-smNHi)}{dxVPG zTU%)9;EWODyZ1&}s&rJJf3Y&{>c8`Utk#<@{ypgbohdx%ZG!(Y*n@b%1Zg125r^hM z&Ayv%*8>mo6m{7Nd(io$Q~C-;x~pCh#Eidz0ck+PP}e=+LBW#+j?%z`oUd*qCIb&z z|6)_(GQ)7_-i`dZBdzEjl-mBF^6u_M_=iZGA4m7z&{}j4+NC@()ik0@cOG;U(Xj&~ zKWm+)=v}{P_aLJ=^<1qn>xD5G z@8|2{SPuZakK9w&{2>?)NuHF}u*pZqd%C7h!d_1SuY|D# z4(};MM*&8DBi-71b9%HlNPBZq?k0+1>J)GZ(EEoq z@iG8!j&ePXAb_{!>zi-i&k>=dPnrjApFqc(wJt~?cF36i;nj^{mUGC zBbLw|-rR@|W{ms>Jae9@gwl?;WqX2#K?4;7(y>p^zEu}6Jl;6N@6_qIFg&32=ls6| z1>Wu5$99tO-f8QhkA}CU&wdETn|Sx!F4(U3m3Q)anK zDo(ah;Qgv8b(D;^DxaPn8s2vEwuZoXTj$5@hVkCex-&Wu;QhV%faxfB-s1ixubQju z2~dC4ivk$$wB+lijsR~-D~+UQufidlQq!nbe{{V2@>e}U zU)p8ANrUe2?nQL$#mG;aFP5nTw-EJw16sLiu9a_BK7oxl|B^(n!W|9_@80k9sMB${ zu{mrY;@|K8(YT?jUkCla2Zaaq9Jcxddl20Jr~BEkp?Oe(O4@dK5Ar*Qxex3?7eZ}t zWuQU2QtD(bn@WIs=USUpz!{{+W-X->aD!yJV7451(90Ds+xotOD|WwST}e$uuORKk z4=$dsrhvbR#5r63GP)CpUO@^w^!wM`p}z*n7SXW~BfoD)Tpw4jroDnpzsKotVVH^v zlBo1yfK7$rJqUOG7Yj|(R+ws=T{ex_C4db8Tp{54N`&M-v_z zj$?oSUuk=C*DU)H|wl9A%G}4@e_bkZu%scgdN*A-nhGRvarD-exy4j>34K zDStz%AWaGhnTG)0h7Z489|yO$TC2`1r~-K3;XGOf<83;ywLcf&&C*<;Rb4`a?htqT ze%XMI_rr~&E2Eng@l{CNQ}LRD)aB@S7aq>mmo;BTcX-z#ItnoI+q_2OgSQdw?#-bu zp70GEnF~u4{WzUFV`UB&9e6%GaB9lxeEkgyxWfS zk+!#vdbXr`0lYUpcCB(aL4e+^y=fv1&i}vZ;aDXF@E+ah)t3eEeq%aNsJbT{QgWB* zDPl!$kdm(C&PY2d;kA)C#lD-LTfU*=t)skC*S(eg@IHv>Sd5XMUgL<$!&%yg6O}4n zSA}}17?5@meXLd47{C7yx=NLf7!SvYds!s+cA>!gU5=+98E^le$xLW?M;Y@Ufrk@G zODcB2wRhh(+>imlTXf@ggOyM#`~wY*|C!V@AjPUvu_WCL*pCY zZ}=>Mj(5c4Cj|KrMf`6hE_qHlAcGsd|6j@-dFa)5`YTR|h>j%~`L(m}71;iScK3EN z?%q?Rf!+TL>xHyR`DyCYRp0j?B-7fwo+=$g@wf{w!0oO7-v9p}{73$8{}#~ydr^4M zC+7}4*@GsQtmQ%Tpma$aeYpSU={`<6Vt4D^rjJa;x~ukIXWttdM}S^+Hpy(6h=(#g zJRZXX(lyWQx)Om0B`>rs?duPNmP)ncEek=vK`NQQ{=8$VBz^@Fx3es8ZM`G<4N_hg z8xE@Us?%Ks8H4EXz{pR-?Ttv(9om=JZ5i@jVP~kQAPLbBheoH~e;cp=<9}Xt2%ah( zab{h}Cw4n2@a|XL{}0~vl7if5c)RIbC7mD@hQ5>VcD8!sH4T6nKA}^EyIy@6g76PBgsNIQ{a1-JAW{Hq!2`%HS3EZvbzfv6sKo4-z2u z<-ep8r47j|8@$zds}#_$#@?NE95}K+yCSJI2iASZBIyeJ1Vy?83cHTO7lu2B!SOc zW`{K|0lYuX7+1pETRWVZqOJqHnQ)5Mwh~0>db-E$xB2LJ-SsEMy}%|_x7Z~`@=PZS7f|@m>yH80)*yz$ou`Cfv@ zi9-uxxE=t!AB-t5!+2lHw?9?_@E$A6+14*jgtncCcolvN9q+v==?=`R8g} z(d{SE@lFzaCT!E8O?U3S3(=8)k)KiL$0dAsX~%oQu8k<9iH$d_%ZTntJ8OggS3@1qX5Fi34zV!Lmc<52|o_!*~gLEH?uVrHecaY?)nF~4_ z21Q6IJm*zI_n=iFDopADlK2=TZal5%X)`an2Su}1*knJVzy4nj(Luz>&+fv~6rWLk zn$I8!IpG6#mQd0Emur^{Ox|St{@+~jCRI8lnAp|+RFK{jcn>fB(nrSoPSpGbXn4D= zx9W%SzRd@b=Kt5eMMo?Hc(34mxWvJa0JVJ`5e@|pq(7MZ(IN`)Hc4t8839Xd)0G3i zEk%gXdbL$teb>Aq0=Mzb2z0!w@84&Qn3KS#A#vU3jugweqvM?+DZ8i4mj3WAMRXj+$Zw{w zouzj#?G>ar%g0RC>)3c}t*}|3a=(P(@jlS?f`b|zO|p{D_xySPZ#MOx7P3lZn!~GBfKTyt98ma*hEd^oXr`Jq2hXrhugibT`XsKym4iE+o;hoeIq13{vye}cTwOykVCK| z<6Wv8#fygbmE~V#VZ5u&my(7PHL8KH1OeV7(!2Hj_Y)w_$XrFKAMwzPajHJNd#mI5 zqTw>Yd#i?#M`H;uU4Srt>xhESm;Q9c-tU4 zR59`kKbNZ3_K9}9wY%p&tXYDMcl53dDP=h!hVTDz;wQPO(Lo5zd&7C|-~RtUX~+NT zzX$aH{uCbc&2B>h*@N2l8Hl2J5YOo>8TkHxmI8A>_zaSQ*|gVM;6b97Ru);y5}-9H zS412};vr|{ZT@ioU&Um!mJ{^-j`b@g^?nfS1@XcLiS_V8^^g7L0m?IsOKZ@5lz83Vk>WY#Nm zt|CCX^{Ky~0=!uoj|ahcAKJXVoE_l(LGNj1ObiivYiz{cER2qK_@;dPlM@p7P9#pA zSMP-@4jpf;GwM%6N7d-gy#o*(${6`&M=_m09ZY-wubnPsHzkkV|C_Fpe|C!_pW*S& zy!Ney8XddqR)(2Jk}gQwM}hZf`BKvBEim4=r8;1yX%N7> z|74Xr(Ut&R2<{y!9gBw=gyxgnTluHqG(4Pmw#0SEGG8L3(|=|^8!I~Aexh>&isO>_ zhVB0Q&j`z{Vc3rc1QuzBwoUebX#n@lmTfom}zo{+#;T@0Y;Ks<$A}+a+bDVa( z6MIhBF!N&LJ#y>9uLsI!7{2yCy7=99YIH>1Jr?=#^1uE6f4!IgPyRsA|A$a`&`&7( zp9ZNkN?97sgI=|s)`pi@{(a%3C6+n0*k&78V*MAnzFVk4fXZhMXUPo2L+VG|xdlK4 z`CBD&!%ncoR^nCdpMWQJUT1~!D6ByDAdk&0PRp(>#J@q}O4Nm_?<_*EAcwAV#)~dd zpt}mv3DMDuk>B-=oo<4x@t-4h z!4!B;DWqH@FR@=8eoLa^{U&u~0F1X8Yci=psuOBZ*#hv^Pk0o;!69#@krvHt7UuWXw%DYk+t5;*(6}as;SM#OqGP zP&{NIESf6_@bqDCd6XQ>ira7t7 zQSzw3&E?O4G>`)CAJ_K^lihp%rc`k>yaNoFxZ&YMIm=Jd?rr7xvknV@w{!l@d5RJQ z=<$jI-0#ovkQ{3#n=rtexaYwMd4Tt(ga-q*65&wiqi55h#prmaFYs;RowpF*g~Vmv z{hT(Ig^stTW_`xMG5T}wWJHG&Mt&35t#I+lw7Yj=?Yk;Tp(mJl2b3BZeBl$S@Ds1Q1%8kA$%Yb z=lr_l-kT@r#fe2etMhmQ{XI@}2+^??BfsgeBxSyPw7WOgy+>6KzG4?A+s=;v;MbE3$-q( zZ;(P?VxNle7`8VE;RTU6=R0rCTCk%pvAHKqFP<<_q`M08A)+G-BR>m5`*sTp+Lzeh z50){rzQ?{|C%a^_O_c8d!#7AA_7ha;*q$EICLK;%V#6u$p5^<>PR6@w?z21^-p93% zE5LX^5HTU)&7qX+t^)8rbdAd`dKm#SdSA4?05nL$ZSyte1H3og=$y&`c;Djv=C#EV zY_S`i`dRe>eTfya-P+|dCWI%)70!NZ-}sj$wn(8k(0C91;mwQaxQ>zEgQ69@ykWF2 zv8&Yc?gSjb-rmBwRGAlOBr!bR(I=?W@#;*Mp=vT|{!gU9`}bQd6Efaxl~rdJl0)O6eU#B&dV<`cunjgV_8*Fdo4LrUHo*WnH^eQv32)%;z-t*0DuLu3%t&iyNz{oE_V#R)yBHHnu zyb_YUAq2aEG&`nZ^D=Lg;qh+mqfSRd*>aZI`y{->DDa-Xt4w;m1>W8wW~9ra;oZIE z3oDGbnnVNX{QqOatDoV+i7PlaT5Z%JKn`Ww?)-S2xgH(w2wz8=l_!PpU5I5CVjr-OqG8s3X{ zXnljf-nzClnuIq~!ugMm0Pl@vr}yh=6QD&u8n0@6iidVQl6nH;y?Fg(VFbW?)gjOC z#oa_m+uiQVp%C=iJL%99hbQL+!S$AZ;yCkcGA?_d*WMDc8q1!@(qI1{i|AO0k)L?t zc?seb+VLJPfbvQ?u+RVF1Y4rctKk?Q?=@{y>5%jZU&5XKZ~srvZT~;H#XH0@{Vxx) znzw4vB60<}=(&&@ng`uuw!Z=IK^hHY1i%NR%jB!ub^;ID7B-?WWln%zKn~6`;E3Jt zE0dM*fRv59+TH|s&~$gx7v=yWbnsF0@&tBt4{A|3DKym0gpWt!J{oWTDfbn9iPb5* zcXCnC0=nz}s}LPB82Rbvn@Ac>)879Rn$HXLJ7HIlxB*i_PBG*6|F|qFbtpuL>X4S$ zSR4i3tUPjoWV{Ph##PYp?y#@h2jeZ7agwyf{_T!qfHT0`@l3snju`dc0w{A$8;gkjunkd)ouB<|@Aa8K(JH2252mS{V_e^J`r{yw{1` zH%p2Vp*y_KBRZC1r!tVb+OvSB9nww?#CAJ`(Ivx1Iz{|VN zkQ$^Y3cQ&+I48(>o2@NVM#KBT>+c#c-VU$gNMCP7#3i+D26*3^$2!EamH_R`Gh3bj z&i}il-ppD6@Rn{AKIsMUZk2v?Z52llSu!~aC$V%CbM+zdm< zyES$}oms3D-Qk^q=%~TS@7UO^|LiB)@outXvbubm3ioCXOun#=gW(6HxcmU>baWhu zMQ(51Pk}ennUo7;yuV#IpoE6^=)CriaQ{DT=SZ6W-@MT&XaexghPni8RuiDGC6kxV zfsYf1Z8YNH25Icv-Yek%Z#C)MHlJriC~C)|P^F#d#YyBVD^-Qvlwa56+z)c}j#{3ie-4_C&`!*Nb=Iw?#tuRwQmSGqa2X z0UdARxX9%r+4R@{Uqp2HVdOXPtLMuyoDepq|1?d1e%N>4Wh!+1Ddz9n72vwNJ%ne) z|MuG%?jK#MT&U9VN-xOf#?{P!@Bd?jzhTh-vr%{u_nKQQ|9DUeuQr+ovGEI5!ydF# zwVdQZMujK0gn&Cp11+})TPhKtF1-&$MDT)CzwP2&A>cv$H>*@+fd{2u)9DFbMueg# zIBuslpjVK;&nK`J3QZbCB60FV;r98r&?`u2KGZICn2qi#$PPq@1V(-%Z=K#|+tR+o zZcM)TU^X7RL5h~^FA86p#_$aiPVfU&I&^A$kG33zm)O{O6nJy~zQjkyyUn~?3k~lv z=c-RI-jU~BNEPI6+`-8-fcH7CJ)LRl1gLo3x@U*M6}ugYtQ%mw59OWgQ-bmKXd0Hs z5uvB|ogzOUL&sZa+4^yOU?t z^B4brm)Lp2uyi<9Sx2xX)c)ObT|GcyWyxtmZdv$9+I^H_-T@-(bv(O#hZx9{482N3- zy-8ddNju)+{$Hxiw5b@7e)@hWK{t)z@s8e1osP2_76TTf{y&zP0&g~l{F7w7Pq?g6 zN5gx>n<)s!J6I`?G@OVT!RLyB{{IADx;iV^-nzWMXS@nrP8?cqvk1mJz;jiGA;7yi zM#)pgoe2FpwH<;c(D6RId1p$G@s!ad5~nm4wa32;9d9dR!CL=9cDlnm9MPeHk>92F zvS&uhX~$cnbL)Z7Ane-vZEcwokJ=c+<2}GlosM&kt&cMg|2zL@g!Uf?8YFHC4_crm zv6bvW8;-IqNAsX_9MdB38Kf8E1EeQ*cQG%|Ee1>MRM`hx86g6+YlN5U2^f&BQM23v ze}lwRRAdX^|JTSxoHV{hgaoIp4=u%`??IYHCU7R+;m0pP;#$gy{#vT&dyv7M3x3Tf z$kLq$twMC{#mH~CMSaPo4%$6vqx_QM9Ya*y|2J=wH7kb@rQ$gU0q0JG8f=&^ZrqzuP6ah4-97&21~5T zLeC%Y7o^sNWw-eN-nZ6=vfeTZhZgLXn^@b9j<@X-LH}`x3(tqdxvaYNYUUw2-c?JM zq&&(JqdUA!5FIx#^2;*JdNY_#JKi-f_m$LM#=am8ci3Z%u1YrJ<9$7XDjg3#TyU(; zBW-VSQsB*3ZP-9|Z^;c8bkXqUFOTbh@!ofqiFAV0Cy{vNJiz-SkI|HcBN=wF_dmL$hLAtu%IM~Xg5p#mXT;FMS(MO!&E68MX*7elr z7~&D-%_rUeAIm|3H}Ad7ATr*sxcBLx;a%?6VG8fw?mkpc`n)Cj$VkKyfcO27C(GY~ z%ZXioy*up)wznQzd&t0e=SD3P69;%ZI!xM&iiATIpVqUK-bBZn>qnf^THP6=awM)X z61O7kJUZU<9Ud8*#PZM`-k-kz(J{R3@A(y!)kYpULA!g~?%ds|QH=d@BF?@h&_Yjy z;qk^`a*Z=??#82TtA_8xg z!5+j1zCrTtbi|=~(42F`Og&g)PxVET`u|O_(|-M6iPbq96Bj%moFLtGaJ|@YJcRdB zkcQtNSzuhlb_2XYqIrGChEdsYNPj}<*vm3>56W@e@a*elF}xlUx4-%-^x!JG2fgFy zjTvHBr8^JGM0C8w$gkB;>7lR^?H<&1E?&ei8M}hqoOn;t(uwiU|Ce!5r^Dw>mW}u+ z`1}9Z`4o5y4JO)>msp|sPgkJf{nq#H7>u{#Ju?#C2WL4BbpgB=)yuYmeJ03)psdgc z@a79%*a5#FB`KnQxdz~UC1agscrSX9|KJtC+v~lo_bGk?bjURG z#Zerw@oWEl#_8XSbiUzNw78y*2e+r!>-!h2a~dlSb6( zaCxv?N5Plm-nCrG@e-2@M3=)^# zKk3K01|4seR?gc&G4%KSKOWH`gOT5=$1?8)ZD@CI`3iv|%Mt7WDXwW!!@QcA;qi{P zpiW2PW8&TqAtd+ap}<>UQ}Q7)-f7pg_0aGZVe6`e@xEezh=ljqJf8jc0N&r_$NBIA z1ZY@cT|^%Edh6mc&D-$o?Zb?Y8Y|e|s&OyB`S~>wlC9b8A>@aS_l!fF5=2Tn|2S9GWcR} z;~^C%NFz3H&0I6h@OO~n1nsEPk*%u2^Jo4qNP)M+bE`5k-Y>RF&qKp|{vFSyFy70C zoJe?k9}nfa5AbFcv3i#N&=Q&~+NK=`2Bhz<$(&RKc>l_|L6iU$8$o659 zL4yJM5_@+v_)fqcF}w{D=M(ZxZ2w=Lx3C{!%Px6Fe|X$26kJJxIB=v~l`;oXiVOl@@dC@D#<})j<;!Nmo_qGbr@dzV7xosnU+t(vxkF53G>M%F88+mOK%Qzypvpf$E1$XAKng#jsqC^d8B!BdtIg- z?>^qs#q&m~IGo6R^rb>PEBl*Sg)kvJrp~O40z36y{ZCJml(~th}9zb;XV&oV6yon>rop!vN zPI0}wTY|lNi(|XO0_J|{bv$Su zq+)+c4)&nJEIv{Nx&7sq9{BrzVvW*Ke;fgt-?}S)*ROaey`txu7Vw~D89nt;p#L9g zKjxQTN`ykBIGD;ep?eS$``3+TEy8$m+?oEus>=rG9waKfF38nHiS8yyGi-l!2w>#* zIiA_DuAX)es*D#}`_Kh@{$IdauWFy<%kUoL#rA|M9XZMg{nN3e36dBE-f~TM;>mdP z@`-Vy;eG$yT{Rf*A(N#fyu-&XsYe66J?EmY)_k#q^rM2O9{!An=2lpxXack|+hMPlhV!{c4GV~8ppd9zLn4~CN5TZ95{8J{CZ z$avd3lyIQo-PRHd!S3D3a){*KYZZtGP652{-~CzcTww_<2tAUaJQWY!IGAg!4)B(_ zS|eNz@OHdu%qb0CZ>ihqTT$_s*IU*c^|8BJB!aI+;$nACebfER>n&N=(i*qQ)8FwH zJfh1$*`~Md!#-7?6hP}NNT^(25YWDv?|9>l%Djlt#4j&yLz1|WlOo6ww zo{|I^?-g|i*wOIbrRlQ)#@kN(9trQT3D@0u0B`;CvDcL|EuoX%Or;Xw?yb76Q}fjT z-p|KmyPE;t@2Yi!*gT2QTw&%3ohfwpW>Md;Db-RGKa0fqN3qwg>_K<$H_S)d58tCd zyl2(^=xD{rkM-&6(^nVM?%p{p&bd5$urDWCp_8qzD>TaRvp2yFSEWh-Ad;2sDI^FR> zbHWMTgBoS3F2}y+#FOLJOv#DfF-G^G^d?#6RV(T51L-D2$3cwzT3;t|K5C-9L3%dy za>~yTdxpyLh_3C24!Hf=Z#!kg3K!;6^Q2ykoFAvG%{ zY`kaKBM+Sp<~K#-76^@35tT$`4NZAF%;;4P={QPXZ^8J=TVIZ@oqY{~c+aK@Jr0NPF4~!^!6rpeq+dmRcvH!5`RK&`#1#6g z_r`6qj#KQ4D$At6b0T&i}lF&|H1Fxo)94N zVc~t~qw-D|?}Scu^5sO~Gx36U5Z({R-)v=(CxBm~BadDFoe0|gFj8L#;mvX2(}oZT z@9Sx7tuJOGz>%uyHr;e=ycgfLv%a-V)D(@g67s0G3dY7;qHmGG=1RtUy+sf4F^@`q zf*k7A5qIgY-T;?Jgx(1n=KpzK8V5J}Fg@NlOHZ17l;THx?wz)^Dr)F5R^ z>Nu)FHE1YK{`7mO21WKg$_Ro6q~?y9)@SEo4@i%6$9=Nd1DLKx;&_yK4krJ^u0by+ zil2XEVZ0lp3J@PpsN~0OU)^DTo&Fkhs_<&;%{w&Ipak>tNxiXE|B(S^`j;nY^RZs) zv`hMV@(NOs0&nemetS{8^J0FBV&R?nX_vQxP|5GCmzT`%Ao^F3T-yXUo}=M<3kl-AB=*CzOpo{QV%mIc zD!tsgD22R&RG`3HD`n&?Q&RUR2{*A=@gj3B&MIencSOdx=Y z=X$pra3_I_Jx?0L6C^L!=f2et-h3fW&$BEez?qezK{hXaFc%-a@4e#E{un3Uv{~HnKov#DoJ+|`d zlckXaaE14mpyv?Ymy^eg;rYMA!nnPcAiOo41YXqZMu2?Z%`8}Iu<=&CkYv`V%wmeh z^)6g8QCo@wVgV!R0s7@N#0twf6F*qfC!C zuKOx&KAdtA)c@?>%2D90A^Z8C(_0zByM?jv&Uyiuz<9rz$tL5y@@m^PIS6ml+UJ7L z0|;Q&)_{T-o+NNw^vP=Y^wzt^zTTq{-Vf8V+fP4;09B^e>IXYuFHVFeeqZkQV>3nL zE;~OL?plJqIQb-K`qXtugyD8?g%Ka`sO0D1v7DPTlYYE^R=svJ<);35i+WUy*beQ9~Z zGx!nfJ01pavA1p*8i90Z3-jA#Fhp3+*#WgtG-8Mg&`5&=$wE3{#qpY~6l)QpeqriJniBv0!x694% z(pY$(c*pk{{=^PGHZBy#J9K!odk=*7IioWZx=#t<841Mc2}c)vWC&{=0$uc zP|0t@-RVb@2k7tr8ywCAP3u$N-s-Ll%af7BGyNmB{4{MoIGbJOrzDd5e^m;+^`m4~ zqIlPwdLo5|_b^NAY8Y>=o;LCa(xQCl`R#)6zO9_vA90%i^2e6sJ%sS~^{v z#K$!%`2}Q^`ER~WfAuz9Zu_fvhWhEPnD;O4AK1*w^myam(&pp53h+hq9JzX{P~fe% z22Z}d6&{clNgk2J!n^jX(LuOD3SBcsKAfoACFs5t!rQB4U6RU00(j18W-5p?33`hw z^gTSBFfI)-dI{k@Fuy3yG>-_5v}O6?G_mnc=-gGeppeCM9EsaBmTw;doEX*H>yy_dnik5@!{RunI7*6F4}x#>1(9Tc$4u~ zrodZQwrm$#y$kz1C9v?mY%uRBynD;?gudCEwb5dMhtRjT)_R_d`E7!Yx8%XHq0t>I zrZz|%`^(y%Z>rdM_viR+`aHyV+gs9zk9Sn^v%5P}BY1BO5KDN9@b|S355~CV+x_hx6>9{(t;wYASp{I?&^BKYaeb`>0E1 z@I&Yg(y+|iid(R2PFPgZNOR zk{|mMVf`94`fE^y$~qw-9_kY$T#L@pe#sxF|PKhT-sTKzz7R z$xqGn%Yn*|^sgW%6o+~fxau(n$N&80WA}He#IZ5`3KF-2HXqp@x39&dkXMje6nGmE zEy?%)!wu5S6?f#Z@UA}E(gfo@o~|5DuHMCaEnFbHT{VB<7q$?thiC9O1#(H8WgnO~^p2|A5BNAI?Sl#x zc>Zs{WP`><2yc;UjdSyM5y52e$C0yh*aOlhCBOHxb+M7skT^oV^3oT5*aK45I)$~e zF7p`otha4deL;Wqw$V7fdG93k#Yu~G+R<%-o=lIo-$B}ZXqnl@xaE?o zw+02?hJ3T+ueZY0`v}!Rvt9N2hn)<4Q*_xwB9B1;1g5Vi! zykjJ6MHOEOK-0EFGL;o+bM(*qVN#^hW3D&gvNG`U4 zUrzkn|NpZ*W!zst{r@708f5nEB_H~T?G%vGz^XyAYmTzP6Qto&^?`5=@)@??WeU}x zx(@=s?p!B;PIaMbyV#OIu?yx3@GExK$HRN0p&HZ?u4EIL4PB5{-aFT(f?b0yzw0vp zrq522LgKDGy}6SlfW3kgP@CU(=rZFyV#`n;RPx&u!1+~@i~bt4*HbXl`WOv0=ym9L zb{QA*_y5=YY4hP9wNT|x|F2JhH<(j?0L6QHuv-laZ(Wm@8)3XBLZpLXyn9cMq`-LJ zuF=eOuOfgJJIx%AKzNt6eN}?-c4(S^2*!J(APfGCbR;~ne5+bUBW{e zN8(1Ch)p+&uf@h5-EL@ z`SG5VrpX5ZmmVN@ioAlNO;`}>c?B`O}nipRE3zn zL9&_qK$8!4?nmuT>E!-jmjZ7Sy_-rX-nMQrDp+`D?MoGb`+v(&#XT_IM>$*iVZ7`2 znO>K^O8`HtS$>xbYLJ$y=&QqcS9AG&B42MI`s(b!XCgQ*c5OB}9vknvfv>|cmxM^) zkvPr*<*yI?vGHE&SRi4vLZ0F9evJ44spR)TX5@uaIsMhUc?)l&Bp(e2q_>aUe#{}r z^mya)hG_D^Z7d+3UPi9o3n}n6=Gu{s;(aidpp1q0;VZXeV7$wVK9bMgUMrZ@0U^B0 z6CxWz9}vLnG6Lle5Z<3(L}y4f3Iu<`b&(UDEyW<0!CAwGPlH_a+UxJpUqT_+jIP!dpo` zXfurWB3Tad2~x|&+Rh6hyxmycBJZ6ifa@QxaJGT2w^ZXyIS=DKmvA~7p8xA`__}YE zB7(D@C*IeV{tMpno5~|^zo_|*#N8WyJCvS{jkn@>#@-M1T@3enixuKyAC>$(hjve_ z-AVr=_Tk{w)dufr=>IQhy$xYM&h&WWbXL&hk8BBlRdEUjs*4_aI^koIJ`>{9~Y?PH;?08 zlbbUA{r~oyy3YrssrUcqQ%Wwg_lYungB16?h9(~?%4*Gz|Eb;v6nL*x-z16R{mmyr z3k&awU#f{P-sjtHlkwj4?#qkC5Z-4-Yu=qHC4l`OBy+bwx3>f|G>|VR&bzFkp90~{ zpUit8@L2>nkvi5ivIQIO=UG|Zd&;M3rjR%@qm|E_OtJAM^|G`DDR3}c|KEi8cts_@ zWty^_77p}R@0{wEd)4o$H%Pdu0GV+PS*FJumzznG58s+cc>-6-{r_SLyv@0XVo|*J z_pR5&!h4y!)Cm~x9C!HuczbKw`$;Q&drPlUd3^O10*DhRUmXR#y~P!wQ3ap9bstKz zPJr-!n6#Y5{AmQZ+cEk1txec?FL8MGfMq$J6oABCP~{dlY>bU}Lh{VX)K)=;!`le) zaga)W@dy0^-el2_x7pJ-nXe|OA8&bmo?9&baun0!?R!d>CLdp>FSe}7_}l+eblHsi zOQ`=hp{PMN_eK7>AdNqX)ex%&8FpDMhW8-%n4ThUv0E&9cB2rgK@T5S7_9wF00+{I z7Gy&!$g%C=@8A{WCXeQZET{&ZoxUDjstR3@cBFvU_7-*xx>qGE@Z|BEnte#zhrK2O zYffUMlL*k>c)}Q&mF$Lb%(bEa&BQ~t6aWNL&isJlF;Q{HdOM~PAsd=s5`7{Xcc^_x} z&vg*MdEc6rDL_~3B2}@jprmEZ}FJ_>Sic} zce$T{@zX{E=;`SH?kR+KbncO3Fy7%#$?Fb7c)#vHbYo{65$s={RJ=kI8}DNwZ*9)J z8!#C};^xjhNl*HPUA=ownkv|=`oVB`A3=QFrjlRAqu*vX|BL(odx-aqWYwtSokNiO zb!=f5)8pL}tU{BI?dd)7Pm;)ZFQdSF&BFE@DBe6d!TMNuUx{&Sg&U*^{~27%@tQ>LA$qkzb-_;cnkUAByu6VFU4Di^u!Rs_PyFWZ;D{!Egtiz z%}{N`F*84hnz#K%c0`RyTH?78!s{_1_8cja=+AsP-R zj*X1yuk2=eym1<1wD}P9QP=phI9W=8x8>&Mk3mnLiu;!w^#g21ykn07im>zFj&34*+ zq`eNw{Ih~IqrjWsp=poeeKzCDQY^f;dl=-vc)MIvCgaULW1;^H!rOeqOV@U8J8)-A zPlpeLcgcmGT6luATcRl>7Q%bmn)S-8>XG2+7f|H&J#4&_e!oqLtiqAdxGkyfYzr=9 zS8t`glP69%Fx~_y1@WOxB|qJ?0iBjI`tiu`P@1pL7WV|ib$f=Vcyg!3_yBz>K z&@}Tx{Y?n(%;sy`V7xC#`#pm%C(1MTd^y1%2^#GDbV=c$&dH5_ABQQ`j5AmI+-38NTZJTiJ}! zr)cs4D*4Kv`SW^+xPX!d4yplBN2-rE1BQz8?>o8zu)iu6VzSgTPq)-{Mdd%K@ES=`j~rRF{o zXP&)a40wUPI7wNd6ZCE2oC!r&!4SWEg!s5ZB|nZ1mf}UH=&#<_IRc2`NVOn=(mSfM~{+}WK5>QJ5dc;~%)SykLY{(4~-2XRm+OuQTAem)r z%HTUlp0u2agwG(Yu_MV@S1vNEC{WIi{z(8!8?w84p?8qx9Z<8>gKE%Q!{@wfpc(}1 zV3GZ_lL+4C>i7CFgI$AGg>Th-=?T4qgv6-_kB!-MW7nXHa9{t~4Dc_x~0YcyA;cjlqvt z81EN3s%%(zYk1cOzMQqT&LD0tk;3_4;5%9vH^LU@me zKDM=o@D50kP~W(M2!6>A+8@=5jkl6{VB3NX0;I1<-1?e(PQACV@iwzaYh}r2y!-#O z5g%4m@)K%m{C(;f{dnJ7@=YZspN0w2_)*2gXbYyt8+YLXZ9e)7XW%P#pz6Jv0&k~v zzsT2Hz<6&C16Z-}PPwO|1>?PHQzrQaDJ_E~OO+wKXHq}9G;!I1OWsuGl|XoB2%1a4 zcrTGR8rlls{XR);v0obz^d1%dkT`$i*6W>O zy!-#IBR&MF#{K&`xq7dn zzVvCLUgN=(q zbE3rcUH_k6>iS-{r~58nl$-Hn9Z2I z6HR_OaU})b4n2}lDBd{|X?QHWw@vnB!FcDqD~8_Kc+2m;7iS{OK|*xOOddy$F*=h5kBe%in z&e6a9Keg7IA^v}81!+T3gItPQ2GJU{uXimkRt+M3X?+f_AeY5S?}Hnp&kD6oyP-$y zXO~+hbu4zE=7uN%B0dSk>lgRKkJ#-W*y`P(8sv0~ze;q72zs)rKU@}rU4ycfy_D0! z#YkRA+$8tHgmb&FYfy{u(@R4`DhyYH@(>@dspRJ(TW%E@On(i!VdZi57BBTHc5pm< z+xq}>rmsOUFQRDjp<)@kEbh-2q^v3M-sU@b7sdP188IF#yxn=?T4B7mI2w}iUVnph z%NxSGe^$h79^MX&nVb6%1|)&|uk3Y!8>9sV?hbH+WGoB}_K}F-q8s~a@s8MdtIxZg z{Zv$pv>1sS>u+h^VSIKqDV6-xMY%d_FVT;8fl1f6vpMxg?AHTQ z4{dYHm>zGlC8{*}D7RE{aym$Ekk(S*?QHbW0mb{;)4iY!INN(_hh1H?xJmHZY*3GZ9+UkpeakEHB}2ND@sx!iUzmt*IbaZz~GCH#fvppm@*tL~>x^UDvr`0LDAV_AnW5 zhqdj6n;^Wkgj4eFeTVMR4nXXg{{6jxZk^ zZ}ag-m!l+wNp?t_*O*jW0LwPazYfN-ULywQ6&Mb0OT-6ACBJO1<`U7J^lxto$7DGW zgq~skT+sf`H*CUiQO`=Iuimp+97|~NA=Q1j{X|^O-~0bj02uk7Q2%d7QG+}RhX2`O zf81;~532@Qj+lr&hicF+D=-S~|HZhpLkFNeNTs)GkBZ+D!1go_+hFJh>3FG#G58G9 znLS4h;0w~0#)!%6=Ocnni8cI|C$I;k`>(gJjXoew+JwYCNV*=N6puY1tt__<-cSJ!fr@h*7r==BtYcSi+ZL18xmd}Q6X{~ol0 z+;X1B8$LmL(zTX14Z{1pL}1X|iwMwWRYTu~9oTqp-TJUDLsOiz9*GNo_K;Mw3L9@? zf%Dq3ql}05cEm?CmHgs_ZqD=gKtJA_B>YZVc2dWCQxv-^k4hBN<1Mbb%!3vm7P1*u zS5n9mBwGr+-4;vfqIgdwz8Ap4TW}reC%l4uee?x+1=*jF)Xfd8AaUmgb)yCept`l? z`*EoMPaa>>4dd;VD|jIu!n^5Yo=e!V2=L`I%##iJB6*Bz_5+`kPl@=fG z-{Lh_|M|SddJ4Q|9P@KeiU8-DeIE=7W8-}&XlYPTv>53(68An%U?TGS z7R*L~M=$pC#SzBaz0E^>2vEuIglp}$_2%^Bt+!n~{e?gE?X6y};`*|5ai;J8Sx4o9Qu$GiJhiSeRl8t&e5l1Tf&r^NJl<5tPg z=0h&qUme=L{rmktnmU^QZ4lJ|J5ki2UFUj5&>A#!beT9-4T_AvEZ7LuAc+lNEZqO+ z6+BE0gKCh+&yXzf#{`h8VE^+-sQ>T%)zl1sgLLwXbrt*#Qk6^Gy$Y#B@bV4MMI#Ha zCrE50;&@oa0@76^E<*FIZ#x_I7W)akXKR&zYcX8^&xQCXrjnn?)kQ{J4fNNbT?=%) z1No>wVsT-WX)){GF8SZW_W#50ek(eiCLgauGY$VtkTy`@?PJ?%h2ouJ$0CM>_ezc% z?Qs9^RkT>ozHfd5R6320@kS(SZ8}DOLvd6DEYcd?(w-6siRPs9&eYkbr ze){qDbTa!iz+R8Jvi=9C8{;9;qFzkj|KqI2LTT}l{k6Ta|0a0_=}3XMw^HnP6z_5S zH}kRZmLBvy3F94P>AxSw+vlfqIlO{&x%`7qwwVC#C>^Zd3*lWp^zJQ;_jCbI`WXms z|MLpv5qyzgTItn0L1(b5_cEfL#(Zx{QaTbhIo$E_WEM8wO%?{LOP{DS9Ns2~kC#;P z8{p#{(lDieg7jY8vr&tM`UFXB+n(V*jrUBCchN1aFSPi`zTQA6NFZ--IZ)ue6VSbi z;{7bISOg1i-WMq@Fy8M6+@oQ^N+-2g2KXg@-#loOt%3 zDESzKH~;5VOI4h8x3+Y+(y?i1Uky@;g7aCna( zJ_f1emvYNpeWxG&)jQx*CI8_f>gWG)F2M~ypR_SO-Z<9cMp}GS{{YQ8&XB9OJq6yL zmAjHryd8MGg|YDVaWx~)-ges4H+w4(yt-tDGZIX8%vFAU5*zPJI#K491`?zcB#y&U zTlPyTHr{U@?l+JxWIVhtBR<|y$q#h7(Xm>W{_1VGtYD+b4(f}O*LNOkYrf`Vdc1S8 zT6AdfA+p-8@LSa1`TswQQ%3#;)cH{fXOtT`Fn#EA|A*JTLFZ277IWd&Dk5d{|M*&$^+m?;|(;HOP4< zkCWH|>NUt~{f;%~wY-_W21P9NqRB_c*VFikd`8GJEgp@N_JvzvD-f~ntJ!1@$kkQ|M9VrN`C9Ee-$6r zqkjb{YIBmaIDq>0*89@4|iwX9?NC@v6t3Xp2?~AMWH7B9_{}O%!t@E!FYRon@o{uiU2qF z>Rat{!5)x`TF%r&P0Ns6khp-88I@%#uoovwcAEt3Hf21#r4b({RPx(!^z5XTH2rvg z%TRjri-U%j6A!)%8Cy5P^wk@;Vwxr&pIzRZ_9!6t{~Iar-hH>?HHtS!sFws5-ZqVw zlwiE8Y_rICTkP@|jEC?xbD#Vg2H|~dl}j53^!|TD^DQG7Z{H7m)iB;4Uj0l;dmI6_ zY#ZBm&Iudu%k`<{(_S*9H%Qzs^K&=uEXBq<5^vqL{R-nPPAU)|F;w#7ywvOX)QNt) z*Uv6@V>hFIdaFWT)<)fB?NUZ=18K?4Wq}V(KF+S|d%ZmM@B9C>{7nDnF;M^SN>PKt z{LQk^8dSbcS_!KL0Zt~d@Cs5i>nnMS-SOOUi=|KvN{9s~TdN3Q_Kh6kdqL=mU7LNG z@EN4z3rvFppc-^C=DS<%01@0TY4YLzaR`6& zPyfH20`EOb6t|#wKUzPmfQ5I{hnHC}-h8EMBwLM1=-V-vUEZlnJZyKM`J=fE`eM=WmDiP*6C^-Pa9E>bX#79WZ# z>iNpKT`N)^aG`tS9csW8rPpc%3}|cjxye;~krG_nIw)chSr7Wo9)5(Acqg zCp(0i^)-4|Jx)|*U^cknwKIa+*- zKOa2P6Gg^*8wK9M0~yUI-iIFM%3kKLud z_QsVdZVJxtVg9qXr&Ve4A!yA0q_6gG|NlSl?P*B>>i<0{YS2EPu}f$Ta!?f2z^XwW zT9ujbBNkLwB|l;xpJ9n#2R&kqt*`5Hmk>ZTp#70Lw8dW6%C!%^L8`N`I?)k&#NOU} zE7T-0666qy4N{cFzJui5gyg-Rx1uB-B+ew@*L(#&>^n%R#x{9$tY^G;kU9|`_o(C- zBpT$vbB6vJw6yV=K?yhY`9IFd_*Bv;p^6qH7&=CCIZZxnDrXA!<&am99u#;->X_G} zcz-PKRKvo1@!MAiV7!MG3Xt)3-PxOs=0R#^DFMtm4@@OO1JV$|_0}-nmx-q? zI6-(1Jx_PUZH@%pCeQf39>spdZns`;yK@b6y(JPSdBiWIwgdYS8$bVc!|iIu!`lP# zkxC`MN7g0Dmag<~Z*5nWv|l9t4D%cXifY2ssP?+ukC`6t>d8o&e7H}w`}Q0pA8&D| zz?;Y)`_KIUNy`;gEWCetM8v^(H)($-@7~VxvM+(Rx3Ybd68BvpfUm+x98%En7B0sN zqA=b%T^GAHL3l@{e67y%B!XT&8>SO~U{8>yLVd*UJQpMFM&fqGMqUW`h&@5FXWcja z&4lsZ|DQ#CY^IW*+7{d%`2+M<@7Z}t@>Y}7kGHV-S9ZuBtz>$d#gbC?CLUiB6$3r(2{~lY`h~X1WmSwh?7nsaRCdv^!9zg z#`|vKP2bXwjE8qL;-ijAez{Vs7Yp2{AMeJqB7SbPe7z+-JWc%2DW=C8*Y87{k3Oa2 znt%HL9Ta%)Jy-nC{Qv$r2W2e0cU-Rzf$<)bzeUDd>{hh39)$Onspy45Hwj=<-@~2y zLP=nEJogD0Z(9}XliMJ?N4Kr3xvvrlUUJD-*h#`(oET-@a6aKCLArv(J$BrkI==CT2LF$(i;k^9IG!{H${{DX}i6$R6 z*he#U%KrBM=;D;2{|P-}cTv=!xMQ~e+(B};L{Jy22Dz=+*bLu6QWq{mzJuh<(zX=1 z|BvyxTy^$30jwD5GrTsJ2V|5^mqpev>#j*3tXDk#!)3fV^lKQF#_dQbqn2Cc{t z8$6DiM?&M4OU5OePhme|E893$G#!>_xB;mp;-i{MeoqZwju#}-UxQd1hU*{GaK(5o|MdSp6nMvKcK)-y1zkz6gN64=32yQQY5e&OWV~%8 zl4RFIc=JA~;`{-vAmbFq6T5#Wf_GC)m%(_K)`djtKzMik79PL11$w>Z=WvzJ7wi>e z=JS5pOCiD}{Oq4N;mX2aW3AYD>-f9G$^BxyD|T}bABI%&6D7?yS>B}|Z{a(Y6MeKC zkp8IOD2v~~^mya!Y4j0s)fT>D2dduQ6nMw54Btl^q=4p&+E{p7synH}D@fBlDdg)d zrDINgfbqV+?ab!)Q2)QCxftgQecr-(mbhCV!h2!mX8vUm-n!c+jvwnLg4KD+8#BYP zt9P5Hl$y;C5z<{G?!Zfx+Hg1Q6{Mncx_Utb<6V&6f%wp*lAlZ1`nlmf^y3{Izo;vn zn}!3@13{BNayytG@45h*e6-bWEx+}r|KCZ0cXZvtlPKP&?IX0X@WyE@cP2MTs+-9T zQm4K28~Aujn3-Xq0knI&)BOCjH}w9$oX)~S@CE75Ki%Q7fbh1xR;KZ)g9v`G{x)0@ zij8*$hf&)KDN#}v5~uO~$cE;xZbRF#QE-jWPgDK2D#>cm4PWZ!ZeGqfVE1@3}7h@zxIByO?QoH;%O8*gKiulN@=L##=`u1-Ki<4n z(`iIn?%vYsQOVy>dy}F2Kw6S})J>ZYNx={$XmRrQ{y$oNsQ=>_XayNSQG*UxA9Y7- zQ0k941FRZkHYq3v_y3u^1o9W8!xf9JorG!-QPj^RxrYEse>&gNJCg{Wmy;idYtX)@ z+_4*>8kALDs`Q#A5Eup*S3O0;86+KxAKz#7nSTZO)`%t_{sRvW85WW!Nd6Rf zC#xQ2L-F1t_;N88-lQA7CNSR0@lVNk`-q3^&W7-AJX`H7`wp5QDRYU=`8z(h&-MV)rx>=d$6P*g+?3y!9HM?yhIR zPwe(1K2}i4Z_dP-J6)6h`G1qtt_@#2>Z#8E_X(w`vH?|0k2kwQEKNSn4X_EFOC`_$ z{V4EG{ABEf;@wbmY!MdT{$buOFy1<|>xl3LX^Njq(_$gKCzUTR-td9|ayoj{SwMK- zzjp5t-2aPI>!~h<@a}ne>hf0T^%kWz4F%v|UT;afch({63O7jwiF;hWpfg1a8}EI` z-^_yWan6z@IuW_nn7^O5iuVZ8Yiq9ftz4XzjyglBJMEX6Z3(EQ)w z=m~`;2ycGYL$?=0c!xGVPZ5Xkj?Ai=Iay8w@3Jdg-mn@Q@5e5RzVlK9Nwr8^Wx~w! zv443vasE(5FFkg@CV)S0*7Y<($6HS8883w&u_I^d7Ro|+ z8xs5~!$?H% zCBttl#lrjP=xb<4>9X1Lhk0bYCm)jx+#$TzhrFv7gTCHs`r*gt@!3Q$^VqX)xc}El zpByuQ@ILuU&hT_P5j@q_7O_hX8}Dtue-)m*Jy}zX#0`#I*pK7H#(R3y*7<@iJHz1} zjQ9{A`}h2gq@1;x8=@cYwF-Tf`?IK@|Hlo7xZO2O-6MO=;q5J>jDaQ3ps%-{HaR*r3N=U*&(dPy z-CK`&x$)~Dyl;uzFHtjz1T6=vpD%uejdytA$&E(FGc{|FIPamZkD9gEcuy5=*gwCJ zi{bE2M|_B#`uF_QZLVGG{4YL`COGc@^c{}+?k({F#e4PjMN6>oW~$(o>DBtwRLRsvncsBskR9tSR1)jraEPhgL7tailLu+}0%}I*~2dc)w+9 zeta`afZ_1=Mtn?D$*=e#`}Hz&`nR|C+)+?G&GwAya3Z)N{Pj$kcoieBt7*y2p3jjc zAIr5jsk}@4d;dQzKhytt477rbpr}DPfo~R~{r_<7Zg#91^zz1Hn`clBQhzzL2d+Vx z64EsuPz|b6-L){ioB+mTtu8Z}NCX9lEG%&UudB2$L;|Woarf|zwOb=W*QA%cp%d6O zXm3-O$tA9y8ZRV{UBycg--TU+_yo@;>*tP{{Lg=$|DOcTAU=$#ZV+slrf zg7MzKX1N!}yK#i)qZ5R;?n>#QT9Yo`)H#pU=TFy06&E!V z37&cO_9ojA?CUMO4vij{ogJyUfW-B3oLv*2jD5XD%5eqGz8oCGJ!1DEK2B4~Z>R@n z=XrsCyj|?9_{>9TINl;2U}Acrh57N8_NU3mk9qgppHz~Mx9p|B`%trn5L&&@zZzh{ z!g~1$hK$ytE3!TY)2f1J8W|XcBa~*=wCsGb=g=J3Q=#6l+IaCnp&AM{SDGf_pPDHhn?@*==E{r0cjWo-Un~TTA+Bp z)vE%q@b0T!>jgJRqq}{`!--!lggcrL-X&eUZBEY#V58dCcpd2NtG8%*1kvUrS?5T;%ir_=|NQwg@-LwNKboQj6|A_;ht{Cm6SllqHAv>Ivvxi7h?TC} z5Ck_!OMC6&lb}be=`|L$?O_Cv*YHg>FpvlisQ##g2c$XaO@JD-f-IJkm<;eBg2t&6 zTjZy(Yf!Pj{P^z7ITKSPPSjfO;NE|^V&{et$KdRHUJ|4Is51~Br>NvNOJp^$FQfkv zJ9}0q(De`v{eQ5((47Ncn7;9-}DCY0~KU>k{!z0JF)+U;~g4{=e_mRG`w>P z?JgK^_jUHcaP^MWc5#OXq%))UylqklU?8}xUU)bW^tx{40OS3Eeg8*I2=8wiJ?xDy zh~V^`$BfcWY`nkdZFsrn?x4vW5+~{DaKn&*jrYFrlUIwBr)wCkdf!8Q*ip&v(?V|* ze_8tb|2tONuUWOIZ*MJ{v+U8^J;C&NH;HJ|a{nJmfp^~317A_RS3Dqb zV&NS#t&|DlePUS;8Smrbu0>H0-r=ccacgo3VB3$$AFN*z!KVw(O2K%~$eozbhVZ`f z{GinC8X_p)^J{puJvQD!v3`kGqs=BNNZf9bqAl;1VdFg=$F_D$W+%hpEsFR!MJ2x| z&**V=8~Ura!06d;K3y~%kWOioVZS!c^myZDOKI}4*jF-2?-03q6Djb{4K;?;pR>2) z{RcR(@NO#)oP+UhX}K5*SMR%|k@Eo%-m7|!oIG_Ay57Rkb?b@IM6h#DZU7nY`HyCl zAiO_{|I{3ai3FALW#&rVDH|(eKocH!H!o9H+y3b z{Np3*^}pvQ)ABS%x|V*tw@hRVS#wgyTRL=6k_OI<>G8Iir$dvElbeisRtWt)|IcWv zng5ti;?@KfiW*e3BHIkDLCRlO%)_cdg~j!T@B~SxDVse1SGl17I3B7&tVibvhhqs~ z`Le^7``;&mfh+kRs6&s~^n3OX`rsAh^--6fS0lgxnQ3r`8Fv34FSGji8K2)KXdJJ{ z@`EcCu=gNM!{@B8Xj94WCfk*dVgJSb|EAIdnnUZT_y69@2G~wKV*d00 zHi!CX^0C_}K%6rLe#9mK6nLMMlAlBIR&|{(goXFT3lo#@BUY#(gZzlS$>9vgnc2=am zg2efT&0DPXh57N;r_G1Q>ha|d_mitPjsoxFM?CY;>dl{6%8!LNJ~z)3##_Z|Il2FL ziYJ_hhZE-(*^f1Z62Jn#pVsj`iD2Qi(rNho|H{NCY4GPQG7jDnbKDULwtU~KBsGJL zw*Y5EcM=P$DH?YxeBRKxer&w!#?o#sOJh8|*$^MqRPwX58$JDC1>%dh3M`7pk%)~laQ-rm|zf%h?QV_6jM#z%*>n)KzPr@efNFjPXGy%J9j_sPXsU7mvoSa6H2iLDiGc>_EXt!^NHX~O;d>m zEo{7Ry7RU1<>O6XA#rY3``vs*u<@QrYq`Hghw&CCrHGFaD*2`N3GZ9^U%Y#(w6XrQ z_c!WqZ)q($cc-qRlj&z~AxXZ~y-v`)x-1mr#SmNl}B&X*?mnAPuh| zH=bN7j#YzXY@)Q_8nke+6L~%sDIq>CQ^{|U=hd=bR`fSW5E z@jiNqj^4oFcN2h%Z{dj-vOG*FAO??F^2%J(seS!I}w_xQzNt2KE zr{j@p$pg{^HVV8?=T!utc&k*L7s0~YUvx$U9!``-bCHJ=w-b~#4nufr{j3^p-b(=M z9uyX4wIzZ_yLhr-yw}+6Oyq^|ett3ay2Sbja0{_FPp%ys??V!q;#_s#O*SKO_>aH8 zW!=KYyDxDgYvoGD!+SsC<29B1Zg2B29=t_A-frs>-0eUb4oJrw4nLLpnCYuGuIM0b zJ_PTd*Z8x0%SwUwDfcU%P`qb(Lxi#LHfTH%M1DEZHa-mQ|Lc}7(Sv7i<*J6;&L=?c z-VPUeK5kD0{jc5DhVj;44!jhC@E&}3_6YmO2=JM*;jUzV?6r4%E4wU9>5NG|68D^~ z@8tnI?BPUuQ5piCM&(_QXu_!f9YwITX>&(^^R#77ayq|VEX0HrVfn07}j$9U8MqC!f`us}#qWqkEGkl-(A`#yGmc2{}u?i?7VEh z*hbj8*yuk1-t|{39J<`7SIup6PPE!%0J0Jz~9c_z)#{Y=ReJ# z!=J<-&cBP_nSVWm0P;UR7Ir|an9ttyR;meb097Wb2a|zhR2heEYygr_wOmG*A4o*i z(l6i=AOTfI^{M-TcvLOP^6UiSP-VEe{}>R9Dg!0XF(3w2i+;Mk1@@y#zol6ih(?v( z(R@)L3RSv6aXr93R4p{#M*<>IrNef_93Y}f>($<)Km@8ZkH5YMgriEsH!m94iz@ZK z#BLxARciCsT?h7{N~POo1_(u!^7&tEKnSXolEQ<5U{onu*cJgns8SG?c?krfN^VTB z1PDNtY?Glr;EyVq%n$njKU6IUDk}qgQ6;T({2Z_wRgzOj3xQpzlDOMa3;3W)JXa?l z@J5x`#si(ePE?8NgyjQXsG1KHrU0I(60Wyg2Y8@r-W#0-fIF&$_ADF$+)yRxw&4Y^ z162b2UxffyRPi-!eg|wv6>mr3Gr$E^Jd=m60NYT-9j_b(IHQVdvuh8q6;&Kx>h1tr zP{n@V{4TH=RcxVGQh`mVVqI5l3T#9bi{ke-zzJ3O0WT+D1FCRW9^e5-MA`j5(tZMP zK-I6~JNyBARLyCo-3RPYH7n$&0T56%^Q_Gnutn8$Mr{YM9#ucQwI_gesG3r3mI7>0 zH7QX12CzoeMEmbiU@fY~uZb!GYfv@jX)z91p=xybDsR9NRU@*ECjkpoeeG3C2Uer% zOM~}GU=^x9hwT~yR-$Tn{c=yh992Vn7pj33s2cck<1Ao?s!x~M%>WQp{SnW-0aH}< z5msgZCaCI_;RpkaQPpENyBb)Is;-tXQ(zgYI`dyH0G6WaBf+2!FhW&_-s*$E5>$QQ zzG(*-qUv4Ud1t@?RqdxGyn)52YTJ?L4=h5}+qF)TfIh0;2o{(DdZ>E!T%jG%Mb*m! z^(tT?s#^WL?EoEAwJev<1+-DsJa=p(p!JVpyCDZ?qN+*xU_79Ks^^wDO zd>^VJbG}r z7f|JX!O;OYk1Dqa*=FDzs&<&Ks|U`a%2lTG6>tVsE}y;z1I4J?_ISV!IE^aj6dya_ z6soooKE?t?sM_LXn+u#o)uu1oZGaP~+IXK+0VqV3Q_ApK;5e!_L}%{@j-krY-m~tyhL0kcX=E7GNfji>h_FZ;n6?s;pbfM}Whq zT6=L&6Uau@n$R0pfkUXWGIa|D4x-9ZTXh?dg(?f2M=6krs#TTg=|BdmR_;0S97so% zxq03!kcO%inyW;CR8)ceL)<_LqU_)a7r==scpw09pbFkU1=vvqZ#MyKsDit5fE88n zIaz=ORq(Mw06-Od3Jbua3O=*~;7|q6`0>9{1;1^J|Ai{}2s|0DcBl@SR=wX;i^i9N~YU3ce8rKZPpz0uB5ms^I$u@ZV7d-~5fAKoxvZGJYIY z@V&D5F;v0VaNahTA3+uT{V@DDRKcHH!hb~-{B;`q7gWI?^T2;b75wc3{4lEE zuaM)1a5#Jg+CBXJCo}v6kUu~Bohw-LfRexW|1-g#88rXrqu7Il*Er}Nq+_YN4AvfG zc(8THQ)r95{Idx83{r%BnYPunMP>u#4HGKR1WBQ&)LNt|5$ws?KCA%kL3VG=)7$~= zK^~7%2?(+vf?erfKU{l@y$5+iy#p+r;xI+yWLAhB2_|9hLGrl!8glIvW4JxY62u2P zmHfQ7S;Vx&(Z2_|nyV|HW9}*D;P@W`91*G4=peDR@y>G7^;dO(v8Ab4ueBIt@;sCx5I z;0<@7DBh1dA4*~2eM3#Y7si`YRfmkXg`eP(c@W+(z{iwIqT{wm+Jc zA-tOqULx&S%RlGOhUM7NvW@jDX z0qKxq=t&U>Z~cTKq2a~|uwtX`HeDBNyc=`49haH1m|jKV0#|7-=rhB{n{Z+;i(UOZ zhQs?I;$tn9{0<(wEmO0I{^~8U^U#)i1nSlM_S$7DZgZ?=`t$#5iwtS<;h1n%+arNo zy}2mxhW80kyqi9|OJL!x*`PcO;~l-shKzT0@{X))5Z>NDmqo1HKmZpR8CO|CXK$aX zUG0JoCtmW~uxc7Qd#kTfb=l!@1Q_UTR^{e|jrVOf-+bOKoM`|O=W*2}w%Z6B@74c@ zy*Cf1a&6{dC+o1#|w=7*3R4LqZP%E+35T?N?DpCu}6fkm)L;$IgiFfUNL+H zxlZdeRXSKXm?S$7la^RM3cTUb9~tlVym3i1ynlbocBlh*e?Hx|6UN)#OQvlF!21S& z2+w3R0b1z4+0e8;781~lQ-txZnJM1t4)Eq=>Wh8#g$U{VxYoHX4ju18a8&(rF+W}x zi95>q^jY8@^iS+^S9*TBrY}i%c;_QJPGjV^$28Xeb_wkj(i9VapJD?Df-IDd$Cyyb5%d$K?h8}DHW%{!yx zmJHt@U6rOzhvt$53BD5~ym=__h7V_u@t)g$SON|2@lgwFxIt1l`NR*#JM>BQ;xzzo z7Xg>8F(Cv;kft}`}J1bd6kjL zV`dDGH*O`BIuuPxGJW9ZEn~PT@P){`b3Fo(1iZ*Hb->0V&wPb{@z&SO|-jreBf*GY^VXVW_R%M z^mvwF%J9XBK3^bJI_$4@$y7!Bd;jmhdo{ZJ8FdPgHXdZMybC()i zL6(JRkQ$`5!(OI!U=Pw!?xW@0DFVbP6nen5E*3iaax6pzcu;ds+__s|53=aPk9ku> zA{5yh>DI)J?m=Ds#6eY$W%y_$uCCN&)xvM+dyp#W>4Orb%5=BHzCd(f<=3_P{#O=l z+Lzen%CCRy*TJ43eKU{yG*|PH;XTN|K7lG7Rr{JDvuslTzlZ{F_y92(@3Ke3@@RN# z>}lhN@mA8fPukwuztbK|O-5Y%1P11ptpTU#)J~bz3 z$D5_0_sjVu*mytCVS$)8Z(;ZbY5o9pI);uJN=Snnq(E^ZNP#!}i3b_)efOhe(eQqs zw*EPcx7&$Z+u{D7SuoaX9N_H}_QX0njR2KAW)nXI@a|Yt#tRQfOEY;bctL~2T`>Fe z`HN8K#=gYcXS~qy{%IJsG3=ly{uUCqUc>P1150$gCsswOw6!SFU2*aQ(Sem;@nUAT z%qH6LUNg4kSj;o*%ZYI+CC4*yo(zvS&YemfLpxu~{`vl2fC6v$n zrd|T$-Mv+ugm-(-%?oUx|JTvgsOUaMfNYFKIvoqvZ;=R0|2O}q%YOgAlLAYuD1`^XUu}{- zD5G+@I+_Q`;4_n94-!kr^oEz%;bhZVb+E+B5)>`>f-82mRdIW)0B4X+=V=wg4bs|A zHhuM=f>gWcb}y_n42mAV_o8VH`Wqw%eY1+H-WORb{#RY+X<=Q@$6yy$qFo|St(Pm2EV zmO*r2W#? z^<=!wg-TS=@II#aE?MwQo5(-o|p$2S-ap@%=~~XQXhVJr6qGac;BUMRD|pw?3i+ zE5E>7BK{jjXvcegxagLMaqJtUu1@H!C@bn>c)VZ5>r5Q$BB*d z=y=DNK3>Ung8uN1Ms#51cck(zuZJG(#Yx~Vqcc3|RP_H6EZR=ejf{UlnwNt*9s5@o z2>b|-3hxcAY2UdRB!q4XhuF>w^TQkNYq~Btn-oizguDgcw zVtDt)saa5^qg>?C!(HI@mVe*>|97)Zhd+bsH*!FNBAJ?PNh-`Z#%WU7A303MKT zIpI#4|BDHo@i`AF$j@W%uh$zBpjx}n8U^45srj=v_P|^0LfJt^@Ha?7Nd+Gy^NG+K zgJTPR>!R;LM&5H>Ys9h?KY+wZ=U?(ymq7QRDb~n|qwb1yw+9)9=)lTv+uS$5*4MOq z(37$+Njyuj`~U8oO;>cy_c6Q&MMc?Br9(3GUPWsXssERtz#G2IjEpz`iFPeCy!*SC zGQ)T$qy&>1qyxbzK1bl~t-bF$N>>q}>}xM|+j?W63C^@B7;mZeFY@q!^z6-te)s)} zP`B{aYFlP>ysfYLiJByd;`@-e2e+Or)BA`%LAum4f?wB5e-k7tL`N}3etf4cK5^lr z9q$K$na^T6sObN9h!uu#{$J4l`^!?LW8snCJRN`fe{l-D;oJGhc-v*?tU$v%BPy;I z?*FrHhmy9p0=LU8-45_R@OotF8*2hIJDmUV4S3#iu4hFgJpa#?S8N;tcpv^`aIw^x z2+cHS%{(4OACT_3*->p=xeSkc_9w1trzw+aJ38LXgN=3^oGNtZ-n+;;F!Fn;m6woe zM?2oC>mROg9meke<6=h>Zu`Auc=u+~o}fxcyk6ad-egk$FGhhkeBC4&Z-WO1HPP@6 zB`O?(@jjyINg7Tl7lte}0C-=Y$Z#ofB0z0{u1l+4$3hurB>5Bp-mB9(B>Mo~w~p5w z)pR35)p;8X+{V%IR<0Gf`O{Pk{{)Gf>o;wA)rpR`(kedZbBXkaw=AMV5hK6gg;&bU zPSTEd*E_4ki3BS8e@nrbr6X?`9&em9A9Xrxs|;qglFt7xqre-!Kb4I4z+wXpG`xpC z5#3?Dn<`&>!Lzr=jjDGA0Nw@UXO-YRUPO2^32SBsdf{`LQK*zNzHDS`f9mcoPJ8>C?m z;sfvhjcwk7L-U~3_cp7--yoSynUOxRPPe7O86?kl=5iN6gLLv~^9`%NG)R?m_XWPj@!?M+arU7J0V;oKkXDN2&bEjy zr@IQW9MOT5UtQd`;efNWd(g)gL6K?^?EatKTytTg%Wjfx?Oi{z^aWs&sHVx_%E% zCE+bafj9hU1sU%$9xpvKya(ch3ShkVOA3+jR_ohf48PvG?hKRiNj(A-mRlEd5A5Cw zdwt&v-~TuCqk1nVz}wf>Lc39n2tDBzUl?)~9q)q<(L-HHi}8&}+|7*g@h$1-ct>0l zk5QkKr91ZyMs$Q@M9Dw% ze@P0w;a6D5c)Q-#(nZ7j-j*DH81Gk7x;}7mLg;PQt$^|7<{KK-0pH$E@#SoO8w>sJ zk{E~ae(TN3$pr9D&d=9B`U-q|EAa75YXJIiqV-bo_T<&V_&6kP`V6c7ZWr{~TQW~> z@s2C;M1HW}6QG4(R`tC_JbIyh8&pWHgJQ~9=#**_y2p%SJak(J;?RXna}S(778`qg7a@N;6VUyMGCy(ht; zKR>)@Kfv45L7$xoJa6&f;MaXO!41+{K}@{x0cqUcXZs%kycgBa)E3)?Ld9*{nWEqB zM7^2RBB3NlUvw+;pWK@8|2H zMmSoi=>NCXx!pf%UrrlK^cNjz@Qf-Q^A>FjS#LzbTY&;^_@zKH-py~n&qKqzmzhHz zo*&TYIl&ZV~ zns&Uo_>MS!Y{uTb#kC)OF+28*;qk^XZ|a~%$ISQPjB?Rf*uCW`@P?nhB;!5%sEQd4 z?~`$|tuWrA_e)5}TM~C&cohQhHhnP^_`#6?Da$b{M0UnPZ;Y0Y!>6~bD>$6K1H5a_ zY&g56F%;6~7!471LB~62^Dc?ye0+F)B<{?}8lxY0bi6Bl^mUtxB!Mvf|ABhcRgmnzOlQ2FH8pDAA^*&%f9)9dZlOkpkEF0;Ml@+SAxD8X z{FW;j@11T(nb7dIYG+M=`~O|Gd8Gb-TjKr3Fo5@bvrK~(>j;p6s6)0nnEwkoN?O7F ze^CfNPeQ`Y$y3~`NHfDm3_cigi8CSiz@mG+zx4qR*6{XSfZnCH_ym*EF zZg0Ja=xD&mFT6sjiI7RVdw=&Kj7fD;(f_A7A7!^wXZ-K~FW69}gQ(IdbMy4S{+}Ui z3@owg6dnY>W=-}WS)%0vG!Gh$|JE))7r26)uf){$`Z{=nB>ngqha>{T95|BN z&=U*2d|=)OpFujhOH%wHSYms;C#%0t5TWOGd4lan(DxvN3twIvmy^SHB5^@?-^zX5 zhrS0n#kGH+Ek}p$me?Rf$0SC6_w_0?p6Jo;L2*Z~Rb_QiQ9*W{)l!>xm+|)?KU}6t z$8ZvtnCcNygQP}*H~c(18Sj{l0$gZ#;~rjL1>>FAY2pgwEuFsb%@n}9Q8hK=Wjq0z zI$H>7cgI50aaJoy-~aDEwxkl^z1u~`Ij5QkS-!ZWXt4<$?{NLo*OnH`;H{Ck3VGrZ znU&~xztcBbFi%dK?(jZ<=;+7D@1jPGbkPj$c%KuIzGd|kyMnC2tK{xmqrvbEQcoEV zRXXes$}5PZkt#@43cTC=c5EQy{Y~c+2O8ejU9W}1ct2}Va)a?UJ@;UTAgCbuKXFXv zMiHRpRTD`rUEq03NtX*S-WD-An&K;r9ffgSQJ8$#~ayUD6n02o-{tyy3 zY`&hy!wS8EY&R{}vz=N&cX$sWI@&PuOa9X9z$#BW-ko;B51$oapZ{03R`y$6V9M}# z_xXrXrK2gIbNBl{ySFM7ct1B>o=(PlVbdLUG`xLErS8FayRpe{f$`p7%oJe+@HQWu zvlXf!Z>z(ey+w*CT61j(Vffiwr2A5;bR?HpnL(HT_5Y00|7%ltP|xFwE@TgC&@kdh z^Ps-X!mYJniOsFrxfxz!TLrK9a)Bjw&siJs6W|7EhX{?-Ch-0L7TcAfYG8?dmABzm zG+1J9zT+sBY$QToHqW=?*oy8!MejQgd#WnpCy=<3J+&i(Ytb8|yIxL_Kac9uod;b+ zbYSK8aZ63(CqddhsK8zd|KuYTdyoOV@k&MW^%#Q5zb45?m5vs5$k-6vK?=6Fv?%cI z&J!lxAPpaHG26k%hlaP$dE5&a?^_}vB)kivxqsjQ-g<2dQ>8KpP>mqVoXn$?Ub|Vtz#E_`@LmdpLBwPdVI=yOE`U&p_gy@Wd_&8bq%kNA2YM z+J5QLoqL}|bYSHdeW@>Pa31Y=b1`vk;bX#{2%VQf@T7!=8-3hVf4K&L-hK*qCL}5AdFu6&6iMB|sY!7rwRypSMKB zh9<+?TZv`9Oz`7Gd#>+1Z{|US934JpXHBB_|0%WtONfgU@UBRlcux2jXAe5wAEeVC zT@I%|yps_f?=kX=@xOUugDLHJi+B8RDc8n6y;YvpcldHg2gBoi;Z`qII#LhB1&RMD zPBbX+?&LkWl8kp$RK!9wy!V+dcn9Ncaqlt-Z;!ky+v@?|L(xPnBXIx!t!*rs%HZR~ zq}!3P@a*lrS^l>t0Ppw)ZT)OtBIFgu(yH|r_vX6(CL?95Jl+S1>(yOnGVuW&Z$7_$ zLrl+f>CU~$I(RYiGbv8TZ;7TIZ^5{s_QOA@*xqVyJMho~V*J@#_s~JAbnq{m5eM5_ z|L*_$Ya>G+zX=*70}2m%`+NdV_8@6{-6d!qblttz5cZ(2YKxrU{y#XlglPhJP*CCZ z{FzMzDA>9Ac<1|AsJ!x8zzX0&%9Z`ac;G=ciq99mEg?b?vzom#rsx%5l`FKYGO4C9R(K0(4;bjj*{-vQpt zr~KX=@+3g1XC`cZ4#Yx5EMd1b0p3dZaKc)Ex3SLE>s;%?pcA@Bzs?Sz<82ffr17Lo z5ub^~9c)l2Skj7)w^u4R2gFZ*cpD%(wqfKqGxGTvVPbwX%(Cs-~Hhw)zKCFTsf_k#5%u5$qI zj+I2^#rp`*E3qefzuv_{IX0!=GyvXG)2cfh0p5dWm!#p8!=RL!;cC@dbiAK;l>ZvH zRm7(vaXE%j@$seTcqf)Bq+czgzwNCSM8^?~{35^K4wIOr9q*xK_C0R=4VVX{B|i14 zsInR{{0Y*I({HHKu|+8Omw60ndrOxB?>8E&j*;=cbfQ2I4et(VWx3V0N(bhD!Z3k5h0dEsrH>c=>5Ns z!CZ)=wj!PbiMyk#|17H-y+P7{v3y@$2L0i^1JR*}k>8PX1*hZwhXE;*VkW2E40dr+ zr>|9Ep{d09cu!NOLu>8XCx`yL-l{`^_iN7E|2e%SaX3-{4evKImzrR_yEeI!`v1_6 zL$Bfc|2_yVyxyJ#zTV=CIKC5n|6hEA*;5_hEo0@gU_Zb+wA{4l#wM_PyT6O2ZWtZ! zFB6BVMAj7B=Md*?e49++}34hHWmH9 zL|OH2_F%^E|F==8Lr%9w`d|M~AN@U67NGx!C_HGeWd48lAP;jZh@p9qfdI4#_8<{_ z0;xfg*Zs*a0V>Fr2Yrz{))Jr)z3)G!zQjUJ^8&KrJxH;Jk)%7ogA@`6yWbxmLYFlQ zo2q!xE6Ag>b@<2=iukKYoL~LQy7cep9yGh}c5>|m{drIVqT@S8ez(09itf+xU{-?v z{hxDYsO+U%JoXklu2f)$o8&8oKZArDzV1nljwtn;QXd|W8YDag-XB7n{xknC82u)S zhWFUrw`*X$1H(6w@b2F9Rlx+{ZTs~^V=cftgZ*-Z%;#9>b%E(=ctAQVWgM6d@Rs~) zyk5eN2+4h4>i7Et`V!mP$+7OjXGOdc5;yCRzoxSh9q%xuhS-N|>97B9M0A8;jzCO+Lu^f{{Ve$U+fCfViQMhk@d>*|Nh^D(SAN9)SE+%4wKc|dgh5Fyp1XFeort< zCO1f3^IDdo;Vt~q<x0qLl;*@3q<{in{>b2^_2@ir@>v&>!A~ zhz?VX{C-$ey;IpmJKhonzh$?zJj8bWE3%I*L-ZLQZyavRU8;1XWd1@9NE=b$Js`#w zM8-QTJW~V>?}D$nsxaO*iSHcY?Je&7_eOaD?{ytHGbaJw8Z%MHlRw5nmibTm;r?IW z^vO4SfOqeu)76W+iO~3G4mJ>Pd|dN%+jaWG zI||X^jgeo?>F68M;+ypM9hE0J*n`iL+}n@> z?{^!1t|H@o=*4znG`wTRg2iCGr%cb0@UAKx%NYfD;|yBf3a=+X2Y;XC%J>iqnaTvq zYXQ6$mv!vX1bF-Ko*Et=B0`4wnWcUa=y)rwtX+BsuY|`VaSxtt)MVd@j*XFK-OFu&4V~jXRy}*54!(Kf&eeEaa#}fX#)?EcrO)HI%5Ml zJW|wi8jXcIq_^ILZ;+aBXn0o-JZQ_pW(OhZFi0`4|H#~3bPtNr629`iSOu?!#Cd;t zy79{ebPqb=GO;S=yAj>Z|059{M=|nyIJ&6r>QdUT*daPQ$L$Vpz^ouos8%~2bZKY! z3Nq4`Ivox(vH2%M)8X^~W)ygj1o;e;@veL~Dv5?SD?jfs7;l?3R<M17mIcFjm!^m-H3Ph_J0|++4iKS&`vLDy5Yh2A>xC|8j4R=b zk+=@Q<2>Wr(D7cjA-7h|(va@(h7cXX82R-E5z`&iXkTIvl(zC0ox?u=kK5ms+G!ZW z@Ob089#N$uQn;dAsen{Lno{8X$=cA1jCcI~JIm4VcEsIY_7LFB%9dyc<6SJ)qbLpV z=KQSC*}aSaIgi%A6b8GuIx|;wVZ5_#yNU1%Qd*L!T2oJmkiU~^);U*nyvNSfXgP)| z;`bqOk2ViVthYeNd!$9uNdG1M?cR|^9@D)g*^b(; zoBhu4c&ok+p-RVEPdnM7L!|k?2?gH63k&a&@qRLrD1nCemS?%;Fy0pg=52!U4xjrd zzZl@XGCh@Rza{~4RBd9_8HK*swVM2BodeBaXHx3~F-j&O|pGM0$St$Im2-YQkY@9TT9@m_qu z*z)X(c7~t5@d?IRP@}^pM}YV#A?@G!e@55=01c8Ag$I4Tu}F&SLEZk#6wy3rfmuT| z+#q@TFC{fdBP<uOATW1$Z~{>lDK`NNYJdefbRV{wVr1 z#w>#fz1SPYSF4D=#8xe0Gk#H{j(>^7z20SIt;~;JLE^SZY6Q5_AKqjgb8dgnPhT}K zWL%kcydy6e=2m{g-eSjnj(93}FM;tZNSRcsbi{h5zmEc2?7+QOQ{X*rX#St$Eh?OM zvY=<{oL26s`Zs-Si zr=Fj6aRH~d47>~-4gPX^YthXkisFsxcnFD;%{^2z_YK{>yPYSwV!Y`OZ?cY;82L>f zTxq4Sjdr{vvNOLNQ^UraV`;y4vcwp}@L1<4uvcywKxPexK3tt`C(`?NX;dyvaJAV&n(4 zmMu-mp&jqKh##s;`=~e|J?(F^^ub4l#~UZRn>rn8!b3~93c>EZiURM?1M*4a;$;4J zCmA%n?+Te5hws=b+!h0&se(gr#c~#`~1c>u&h_ z|KHC--)C+NgLrz?))bDQ<6T(R^kh6m4KIkqb;ax5sO>^8PMZC=OBc4_>8|#^faqwz z$WKnPXzIEP?RcNO8Rg2wioJV_Gq~0fU-o~&^_I-k=@^(=tsR;W{jdLLkpADA!h?P! zSHB^9P{RBL>S!J$tKcgNSCC)4Lr4{5ir}`54ZwqpTw6wPH*6r6WjRlj!T0|!#+L(Ht2%Y3yQxc|+?m;|#@(UKYsNv5bank+UETHA+9(1H-r9XoP=lIyv^Y3o zw|@@58(v}u6kXWi3R2?!2Ms8c2n7x=P!(B-j`wE&fiqe`YWPqjF52o{V#8PT3i60* z|Gp2m=?`ybL`N(}e*CL~@1MFtJKhOa0%?PvsHh-?Q<@DPg)%(exQe6H=`aw=RQj{M zwT=Ss?{Y0m$?iR&dqD*a?|VB_Jz%^g-HwyCw`MygDhdJKjTZ+MXY*|!rVT&4^#^02 zuOSzF;QqgzYk|yrfcJ4#mmhgzVNk+0vF!(Mq2sM{?wUy32{n8Q5?AE#s>JFXx_hsE z^zwIWJN@BJ)?tB>-^?;^pZx#f3({$Bwi@CMDvq}lxNtZO&1d)r(r}^F>9AcOugiIk zy1YN-UG~pXK%o8qVwI$EpbD! z&|&_x&G7E+?05UdDS)?U>VY*k`NN=sz1f+j#prk!%JgpR{-B00LgF}2q2p~Z zYCqdA1JPZBMAo5=k>81j=eW0s(SA5lL&YsVEgHK);+q}l+NKl2@OV$izo$yay^9-5 z{i8_7Th>tEJ=y(xoQ!w%xU~`*-uPn28!+Cnvi&5yAIa{D^#yoO#?7l}Nw$HQp_MfP zU^sEH`qxT$_V#h10xKJM|F4dxwd_9l{{NkKNmJEdzW=x0eyG=AtvY@XiCdXEI(PCf z-~U(4>FaN5r9ZrF5FNKL@@r3ib&hKd?ZwIGOG}0(y|6z{d@iR!sH~n~_}SaLa0{w* zT`WNGL9%4u#7~V5--e+|o)l6AX-k3k+$oR$T#&wOtX&HY@9SJHco^^f^M8== zwmoyjAQ|AzJ8>a5{GknW_g;pZIlz0e*!~rK|36=8m3$Jw`_ik;JWJLSA*UA$EZ_H{ zA8*;U_P2&JP95)z#2qe9eZKz@I^L?Y6?kcg{_yrebSPrv*ZEd$RN;SkAboz?ydS+; zRP_H%`i4^vH!wWjxJ^Xrbo`qCS@uu=zkvepUrLEJWcR+SaCQY6-lJ2RAu!(gX>ZrV z?yb9Mhg~kfyD{lv^W*~?NF(g~Z)SjZlfdJJFy0T1TJOQvTljn1m_B?@go>;2-KGc7 z-CH5}L5W_t8vYUzSO4w8_A_4S4bq_^Bhv+znkzX9o;^sFSX?Jfsoadda zVeAv6xC0)N(t+<7A8&s*s&tG9Sk|iMliZs?f%i{7KSeU$gT6tUXm}HMzP}CQ-MGA; zG$1{H-~A(1{#_QoW2QeZ@tJw)PrwtF}r*C=|zBdVeP@7u-8QB+|1YX zC;QOxE@gJk3YS;IpGV>rHMvNSyP)H}>s*9An=k$0eFf369V5R&-@rxg#I z(sZ%6w?z97Z@+NaiQ)VI@H4=&0P3}ER>i=yh@SbUSX+*|*gE3wM4ezZNT7JQJ zPb&Q+9dEH7KbqGG@V4A=Vj!r(25N3_f9(YD{`ADq1%BS5{_C6_{Jh2TY5jbtj|lDO z5MOjE2p#XJ_~f#ZwQBefB(8eb6~32S(D7arF!IYih5qn9gy`VI$ZyYwtKTlIrro`L z<6j*8^b33T7U{8vr|~rt!@GB+vKv)8W{dKgEy3>Xzx)3gU2!tD41;6VvCCTrjdlG9g^zX*8HH2d9o%&%;qs^mtuFW`xtH_7(~ zbb$xybZ&b+!vs7ivn#!K9L)dktWL;2jP5~Sc1GJwe^$rmAaT70l0M4<&^<__rzAi9 zF#R2|8%1=eV&u2r_o9vV1lm1FM2&CPVGb&;*jXy^$l>K~Jq951?W0pHJy$VZ1+$hLi9f4`q>9QA0UEqLpj-swH zc>nLjnQ{pofcLSSmAZ?;5}V+Y-Nsx;gcgi;=2rgY18Mu>ay{pF>iC67+=8CP943GH zKw81OlG*4W{o%b4(IJPCU*%Jq53l2C$D2>;qN0L1_7eMQzvlkTO)nT8@2j$^ROztl z$husZMQV^7DDa*qHT9BQK|Wu4S|1JXnT4yb!FV^x)sXN`ge0TV0p3ekS#v$xY@prB z2ji;24btX3>(|0JNPStAn4kslj=bX^HeL!QNQ0jZL|37^cSK;eM*1^#`~VV{uc7o| zfeN~Nr(8ZbG_sTa@D4|GBx2-eFOd>lSWP?L0Xk|qcNb#s-r~lt280MA zbi7QJPy(O5UAV#SR&S;r~WV{`jTv*ZY zeg(Y^g7LQB@Qj2v;gz@NI)L|@h#FxFLGZ-x%13+RTVo-G@cOkd-lMk9-!uTcyQB|# zoct9EZC=k^W|M+G|97?Q&#>R2j(0@jyo~I2=Ilksd(wWeQ`ZejQe@_G1ks&v@(v5J(mX2N)HrofxS$^9J}Z}a2& zENFOZ2opnLyoK-dknn!<@dthdz}wA{eW~_B0+i=kxpc5C7W&dSI${9ub|~<1Y5{nM z-BUU1*BT0m1!dJO@j%D>ra|47vKV!|C=zFvYgF%GhK~1iSwCNw1pVQC9nmp`k)N$b zRsNA@w7d6bpID``Q7Y#D$>TfbCj1#5Z`{*&ROxWGEX}a9Pl54vrofwR^zmIX-cm2_ zF{9yKACYqa#(NuKn1uK0n?eNmfwa&0Gg7};2vBbG%v4cFEF`poGYZDLnl;7#1;G2| z^oqHtq)^DpOI$ix1Rd|3qQm$0g75z=k+{57yKz#p&Zvz*iM3avng;#horUNq#>j8x z<;*fBY1;e$Fx#~TS^n7DTO;qhj3$M*GCbY|{^3;VNQ{wx{wkZad+S7j_xu{uDl*;) z#4}82c%S~(9znu;%?}dZ-UBCmK7#&#V9nU<*>5&b(N;nK;g_+{`hCLuFy1-AE$g}g z-U+U=Q@2w>q1pPIMIEB(cyGLA(((L)I(`O;V~daujQNF*_g&uAtg@!`hc^MyQI3({ zGD7e*oh`KEtz8Q}z0*v^-CGrfmm(xQ7#?q2Tmf}D-i+^&1iQEY=Kplv`Tt1{EU{ZD zJcut)ZH(+eo1|?Ppm~toquRc=K+xZzbd1wQm_08s4kYil<<_f6Cuq4dbnT{k_#0fcM$-eq%)@0(7Lu zjp;4e-a0+>#RSG%cR_aLnN-QcE)Al zHuNp_^L)~e4X)E4-ld3+GZ^`O`LXBvR0!=2(s6C=H=Jv+`+uCp?yWtyIT(J69XI6? zK#dN|=RYIf+$2?y?i6_QaDV0_<9*KR3kMqB7p&Mc;R-VKdzmGS_Z!=5)-eF@RAIG? z#o&31kH!l}t^&M!_)@>a+gnZxaMCpZZ<8Zw8?BqdAn_#;4kA0z@fI(A<$yN<{XY`- z_$If;-A(9t=d724=I+xU-lB+(42=BL0%AXY`5$g?4X|lZ+ZKeqdn@iySgAVb!SHy? z;`E28(XnvctXU(ObU=Cw1>OsvIrWh7eqVBh9S!fnybYw`#1Wo{qy~xF;l#aL`eLu^ z!=RX`7|{94uuL6042 zcki3=9GzO0RJiw~Pe^6ooGt^D%YRQ%$CN4^raz`){0d3#?M8w3f;Xod$asGkh-O2> zyOrw?-pdx!hPQ%ia_7Y!BINfzu<7z%^x2z5ZahyXnE&rY;?xt$r@WleYwvrN>grFv z)1P~rB09=3^0VXEao%2q_S*Yuz(B5GFt&R?uzYsm08AZ&Rg%Kj_#uPMs6~ z`v1S11%3Q3=>NA_G9}3%M|e+ zkT_n0RR?B{qk9l^KtP9=pZ?w;CF?N2$nPEDH7A!9?H)9>w@9cW344i6Rhwwrd5iJC z|Ifd1sGS-e8_iWOi610Yklqw{FH#N4BIE7&nu`w&@4l4OYw#y_L$7;CUy$0j>&93C zyblNkGZDVpK+-$1Ec?OdEn!Vp_QB`>9}mgg<_CD=t>fRiEg?b!7T@ARi_o{&Z|Vc)p(dVr=v-K&s*L=bSPuwSAOW}aixB4)Cn1y7uv3KSiE>I z_V!lQ%ds!NUTHCWgJij&af})rHxkZ02}>kZkX{sc3o)NQLdJXZk=HzEc;km%e!~6# z*6c~r2~yXQ+NPZVZ}YsB2`(RPARN#4Yc1Weke`ryvL3+u^6BjU3DE!7P4=$a#6*Nf zAFt>cI*yL_@`b8vX6~!vN02yozQnfa{pfff@9g5!XQ96@NF@**Nf`Mh{M_?c%9i#9 zscUGROk^h&6C}Ymp4!TK439TX9Pdq)4xO%8j%Fyx)WfcpIb> zp_Cuv#qJ8|#mVmbx%Syy>iA?NZs_coi5M?>aq`S#_8!5W{u(5IM8{K%{J!a1nG{se z?%s**-%kYyVtY|qrJTo2CPB5`B221Y_{=y=EXT?~wTL4SDfM|2#*$dAKf z<=szbX?O4Ly#f2{Y_LC0%+pIepcWI!@Uu6!R@+Ewbog-$k7*wL_x(RwQA<~UAN2pe z6dtr}@0BZL5Ar#tvjok9GFDGl!EcZzwC>mpPmp?cwp>vF9#kHE^Yx40Hqezs%X5w3 z25HT2t8p5@gSOT39`gnbQhkf0{yuOAiT1CXpB?{l2Z;bv+vAFU5xf=>mt==8t#?EB zAoDdk0<0?)>F$bMvJQQW`~rQV(q^a}D_sd)UeW=VVu5|{Hq z;kfcVbi5msmt=FhYSJCv1Bi~t82QyaDzfzX9|okNibvu~sCd0aP^(Fe_;ukOx~d%h zhhz>cXr)TW-Wnf{3&%-#@1($6xaxT|8SlV-d4gzoGvCw>gz;|LBJ2R;ZMn|-fds(& z!RSc>KRCUmxOK%gWq^0yAq`RZ`~Mf;svPYB-W3XGkGwxbgc|+N{*D$x$2)e;u3OJb z249cFb-Gm^E1X5&-a7yIK5N%IExN-y9?@|YBR@VzjU`$4X>X7Q1Jt9_K2vdftNPF8 z`Fq$I9&cP9>ocl!wD;Up`Ln&Xg97g*>8k%3PI#}_BY=jtr*6&!JbUZt!P&uh`!#E% zE(LhsaQT&$1@K<*J3V|Ce0%E-foK?SzF9#78-O=B)1~_my#M!8=D?;se|i6J*P+od z{G=TI2ND-?MvwTY6WzTP7i<*RwN01q@b*P?$YSKDlBPa0B}O~m7SbUPGpn&{Z(K$1 z%9Nr<4B!9b_WPMoqhrK+>*L3j|N8&`VS)Vr{vQGT|6U3YlCrQlOI~7Ql;p(FJjm%K z&b1DBP=UXR59~pk*S%nK03OtAoBL{=5&9ZjhQQ;Cv3>L6ZLH)ILApK|vA6 zAJi5Tp-|zeJzfy{65AYL>>3q5em@9_3m5+N2L;;6;}kQn`UzXT|lG`GqTRj24c>>GpT<7k;v7Drm+Z^N@Oa~&Qm12WN7>@;T#|eH zQ{XNBOh=Q9_xc4FM9}a)`Fte@jQ5g@*W6*ePyhZUW(e>;a6iK$5L|CzDk71g5Bh&D z{)@L@yj6vK++e(KRD?C9xDp|a%pdaBW9WD<83?Ir;^V`sAaTy~ZdFCTK*xJ*y3^OI zSc2~GUW({=kCC6fwTX@PN80i36$tFf%%-CMUzsF6JI=!Jc;j@b)S=FEP4Q3v??-{R zSjy`IWW2M5{Djf){$epL`Uv1HX*K8q<2{%AHChSaE$F7X*#ykqc*5L%X@ci1L-X?s zVZ0~U4t(7O@XijAD9n@yg96uV5aldKuf1cdjz-rM2;ui5aY@BS2YK?)Yw!D(jeVt( zGIWP`9HQeoMt;+$>(mX_(T?}SwxiChV^rMUa@R$lFISrJYi|};s&uG!RoI@X_}Bmc zy)&ef-v#}D5QPUR1QYwo9<*OrMjFk7PA!uWg8Tn#j~4HQJxI1jCCM6ikm@B@_f}Q{ zBzMwDYT4^pC^hw06#T>vJIhj)Lf}DKb?K?0rlC;qx-T+8%{x&G`!$!mjK^>Sm4Qec z5AUOm=P#q*LE@wotZkPfiKml4)&Hbnf#~qS$S?NPgSz9pX!juQAikaAE>w6BF57vh z3BY$zceC*R6zz(;4Lq-{w5jkC$GjO(eU=%+Ghmg{p<2w65h;5%Q*=E zZ*~2A?bYA|>62lbWr_gaN8Y;2zz?MDou{pJ8sP1y^xokhXDFn=spBV_j*hp?^Ec&U zV*HhINZfgW4{HYZqT_A%c=^x%tIO#QZ%IVQW{ms_hffjs{b}$2dkE3#JlnAG-Un69 zW1Zz?_zLo5>qDw^?0V>0S&~EQ|MyeiE!)3thK#p_P1SNVyg80dZin%{y2g*Rd#kDB zFt7pOEt-A>cT<1>4SwBiy9RvT5^DCd0ml1`RQ5@>icA8gHl@&2+ybr)Qm zRAh}C+X1|}`z8H0i4vdzryt#{y|EA*@j(#$IPs9`VZAtjcLdj$4-pL^(C2w~Mo-wG z;~h0B`AM^ALFFeT4%$Dq@0l7p-qC}F-_n0Br8~Ss5gi#A`30nZYQLIFJKk9jrZzim z#P0t`U&;zx+!V#|cyF*(q)LZG+8N2mIi%twfC6vnxR3xc-UfHJh@;_cwtV6#jCaUy zoG*;`nFWV8ZUT7Qx}UfkDNBGZ%JS9q1H7vZV`Sj|zhSSL8WG@ayK1m*8o0OKs=RvF zt>}0=uNWV7h-R(SM&g#=6ng*pFYdkN=jEnxCLy}Rn}F!phmqgU>U^y|Otcp#1xn6Z z?=)&qdzk+;0kPc2-?=e9-ngGs>e#+}vozS=`gi}|e+Z!8Ux5BUjKYJ|j1E+iJ;+d0 zP!Y|8#*d#$g$JbHW0^<;(%}thH|7HmstLLrND6Jx=<(6`vt4*iV%sl;DthQuZ8SeqNV9({{lVY}y~QziX1NUDeq zWsLmlyEdfV^`+f|f>JMg?q;Q;f;?EckKMwH@%#UG<<#leyf;bp&lWq80&i8;Oj9!6 zm-oDtN5gxqyHF{N_fw7_65c<#M9ldC-gRy}oNT_>K>K8qn&!aqmNEy6$1vW%UR_PB z26&g({|KsLZN`Kp18i zjQnyt9L}E;p&jq74Ko_t%dwBQtlIl9{bWx+!{aT>Tt$_R(CSMDxAI68WGDsR$}fVm z$#_TMZ^@zI?YK^$8OEE?H%Y=f@Voywd_Z~$XR@dMcN<87XG$RtJa38fwcZH7ARVZc z=5`0*oxMH%lQ(Om^; zhUhqik>8$yb!uh*!|Scq>sk%iUtl*#I8IUD@(&{nk2lVJ33WOOo=74Gq(dn1Ryx&D zM84=gDYMLt`xpy!H-ip2% z;bgp()>+D+;l0{Yfi!!o?VxS;R>0-Cv&oPMNfs7eZf!!x`*Dx)g(Zaol@dtYubWJL z%Gc5HZu%L|lAu9$`Wo8tmUZ8tc2cSy6K~m?ZbRN%5e)C%JL=w1 zrDF+C=ZoLI|K9(j-=?1;v)IkCI0_HamS&$Idr-yfe04MrdiVT}Pa{}jM~-$A;U)I= zdZ*j)1nK&*Ep4y(2vC?=O|T94K>CjPz(obH#7?J;r1ya(*41U*ro?=32dQj?vaufe z8KfK8(*Y{$#VdCraXSX;?I3aVGe~n)tKZH)rb>4efT;*d9cv$=kkXb`QgQ&{XjXs&w#wIx1{&gft+Hpul^@ta}$3Z@cc-s%UtxUgl=k z0PyDK_YQ*b-kA4T#vE>tcvL-(aS@9@M|ALEo1Th$Z!h0HJ`T#knzr$x~77L zcT`H6Ts^@1+V%9kFy40)g+FNmydCG66fy_;`3x0z5jo$V5WMff&MDUU_?hBMt&P& zGrm7tPdnajp2;G1Wnuf6arB)5;@@y5*vQKw@d^oRVP-P?l{cxz;5Eh6JRSQ@O1 zhIdxEVIMpoosD%Q4M?j5eh@?f-miQ+thK=QmJzc}h%)#<+NH%H0LEMC+!Fm40Pmf> zmG$m|;Cf3L`MpU6=y)$&>8ZN;7;oh;68F@7*lOl5x_h%MX}IdIOn=8)$U4|C^0R&| zK6wmBJKjQ@MdYgIW8eRWyCri>u4;zy@s3-4lo}mt&-kwYok?=<0~C0x?~VG;>#c*S z=1ORITOQdG0&j15%V&7Q?!BQ#*7X;7|8L00wEkGX4RmqGX?`{E^_GUn?0p#T-B*gl zTLIqg+TlCI7ZV}&aJF)XLUg=)n^G;mZ{@3GMdGsEeE8cE(ebXHXl&q{p+CIII%+ZU zdt1fMrDH%l-oEbTJj@XGaAH{I%#h1z2gb*HI-M#V{l_b6pMvKt|IPm?`fPgrCFuWI zDLlwfOr4v&#P-j}>7aSg?50ak;r{>h)b<0g2U)o)zF!Xa|JyG-o{om}P0TqMr%+Q6D6Dz?~}*&lXj1~R?}Z4sbKhvu*N ziz(OOB{r6Y0&o3MNSBN^2TQXS8s1#|&qiRpt2?Jic(2+d>efNqI zRXQ%7n!n=WVR(Bhb{+-Zdi4nrWW1A><*Y!%+st>GzX{+yC35T_?B0SBCmeMF-Ycu; z882Q$fHZ%{`6z+i+r|#o<8lCR$2%+5&jWZj9`LgCogW50tmJ1qaT*=(#{~+vH_s_l zRwHrJUit-m@#uIPq`fSX@zAF`yz3AhMi}}1{`n#>&6#%hK5(~D(r6L(=PkHZ=i6Uc zOffv(ksqt6(lMSdm=SfJ}qt+#> z0p3{?j&(%_o2 zUnU&`h;|QJqmrtgGlD%JRg64#A?mz0!&i`9{Ml6Lc&dD!?d+c=mV*Ls=)*84d5Jx$ zRcC;PcLDQC!c&0v#Yr81xPoltnp$KD@K#p~Dc=b2*7~|vmlZsaCKud;htK~nzvlY- z8NhqZ-~-m(r@-|VuiX2-DWc;&$Si*>@rq<+2oiVHRN3q(7dqbjS~g{A#+r18_Yk5( z2qQmPU2dtIy|m+P-O8IMolM06X_td?kG=#jJl?qOIO=rlN|MkZ4M=0zDe%VMNiZhk zZS^Bf9}Vx<&x|?Y`Tz53Rnq+5V=4Qcl>qM>MUn@ffd(nHP=DU;SFupw6yH<0f}D$U z-1q_D9n-ri@}4LW>OZimz~u@$-Vet()LeRGE8ih;vR{XnNu{FWJs12iS!@ISHAuCH z4yKU5=Qp%|{0QfA+VM_5S2BF+F%|v)ffoy&#V|2^gM_Q@ph|~#iA6-lIZ}hfMuE3+ z!m)TV-YlbDdT4md=xTMqcz;#dvmbVEdH*6;czerMLatmN;H|nrv&a~n|KERJ+6?ah z7d&!J`~~nXSiZY%>#tB~o~8IE!xVJ9P1mU|eU_kD$%4cUpC6de-HVR*>au`A{4o7( zZiaeU&$NdzC;C!{e=d^DI?5yls^)+Z`b7-p;4M z+i3r$Ml#+NE@rxDc=MKjxd9(eEC`7VCvH9XGMNm969b}>yh-5g?G5op zm*C;V=bgsKguw1?!+!G|tq-A){CRwb*FKThe3YZ~0Q}`9JQ&&>;ci0EWjqGUg*yI-(Lb?F~%$ zH~**0e*eFd0{uS^g$J!xk#mJT2=4!jQZ~*<^PspH;}Q4_Qq|ZY(kFHj!-Cd<@NMs$itxOjB9^~fE6_rQ3 zzuXr?;{15=pVAJY??HCjrsRAV`EC5)^8Ww+*%i^Tc;nymTR%E}vh;uG|BEsQ)wT>_ zFR{2hLuHk~1&rSyt>IRqMu+=RJwh_+1L;_93cM|Fo|nmZtMbdSqTwyGXucr4y~VXy zmURDLd`P(SB*6Rn{a1!L;PaL(XFu&y0vDt$SUjB#zC7ci5nu;)@qVXs}}y z%iJz>ymxaPT-H#Gs~kq+PW?Wr<6?)7_uTXFB0URUx?5uRAUe3){+{2G6#=I-SZSaC z>#%sNWz)i*|F_GQ9%nil$MATE33#PZql4MAGmkr#R6#DJz}vhmDT$2t3jDWuXm~p* z?S){xZKYn4@D}h}pvnm+I4XA|anV<_@nNdyct64`9k+BBraQd75gqLq`SJaVHq=wz$nbPB`cjWd?&phib{Y4G;S%cTB)0R`S>ftgKYyq{mY$Bc%z zh~uO`jJNC5Dbn?pR^AI+WdYt@>}%G$f(A*e%S+ZB?A{)DGrS5OPK1O$O{)ZW_m!Cn zhLsYb=Y<^5HFI>lC4Uz7Khox}>_Fn)y-pVwRYu2qv79^mohS5nIT2Zh7)E{q@fAuc zk+kFOy@%iXyaG1f^$Fj0SFK|F(_7Pt&jP5?aZg#0XqrL7n~MT(Q`3x}WW1ecqnXg~ z?wOD$&EA}t_R}w|%1UnyXJ2SMnfne2qNPHD>5|^M_t; zdZ#Z(ckbEVeieu zV(j1l|EX!;wXY;CinO9_=1SU8Bb6c~S{0QnO^ZsUvL#6rDhico5u#A3w5cdcLXo1y zl91^4y2ds4caHmbU-vchK0e>?XXba@|9N$sZs(K7{d}G0YrBr9{rmpk|90z1-=7cq ze{mWQT7?^Tq9MLAp_7bMM*V zIOuJ8bOpSFRKE6E)eA7inok$5(`X<=J-GgR0vpji$j$#wwal+yggzv0y8dtQZa6D;{6_NX6S=vphc<-t%357QuLHaz<0|E)5j5Tsv3)#g7^Qc z%k~}l435~nG%3czSM1(KM;Y`0ym2CKV$m67sBz!4)km?&Z`Tk#=C=K4WmxmWn@vik5)Fh581Gko*?*q56tC303h*9_xpM3~ z!28s0%~kOI|1DK~4lv${`B=~DKI2OaNK@?OpFc|Q>(kT@8d!mBm{G0I`q<3~FeHnX--5}xSjpY*_v;GC? zs4n_+sG6rebf%sk}?8_K;@6|$kv&AQ{4=2XU zCT3pJbz=Dq(#cf%bPU`ou{KDg6el7ycv}-aLa2DFr^Rxk;a!@xr~$@1o_Cajx83v4 zR-FKEH)oY4kA+B3ng4U#ckp`a+tXx^(nIPj&z8|LODK|LrKy|I5&Lki*wzJE{lGK12{j^PsJ1 z3eVsr_7&-dlqYs(?a6sz3_OTq-3QfN1rlVG9jP!i5eI2ICVz#e*u}D8{r7+e1!=vo z9(4(W_S@?>x_(CYAVuj;!6C63LM#$@bt*dl>kD)bD!HIvX|z^|=_*J`L`Nn@e&WUf zMFeTaJ*aEIDr03A9sU1<#Erp{d@SD};o5oW(otS($F?JrGQ~>M;Jy0M`)^ddtFFzO zg@*UO@YkU*-b**%qU<0I7(Ol`!BgzI`3rYTlOS{Ph}la&$3d^O+e2WyQ)F(ed^<;(uBK>^S{zyT#xC{4hj^ z8%BOsr>uwEdKt&t`I$feQW@<2za!18xz2Jw%j4Y>+}A{p4mau7w3xE(d2)o}&rc=L|Eb95;YV>-Nd zAv%7I{&Rj8NpDL0MHt7s$5$|ATPJq^ALTqAe0Y5<%j1m;Or=Z5)h5j)U;pg?OVZ$N z?{zqUiudc|7lhF8F8@)T4L3;ESF9)vQiSmH$YTKSt-1V0l3;T}zP)Bj^g|rP{^9N} z81E~0_ba~!c)MJvj6Gl!263kMC+j>$$6J^0_Q`qDcp@(n7bHKRDpZAzcfZM)4dDXw zxwj6YqZ1>)b6?%ach)eDci=BmA)XJ|{r}nUD_n;bb+defB%fVKmyXTd9OiGgQ;HJ_ z8occ+p(9kh-FHL_qTy|j*hIm5eH&wVKOpOTj&UMGn>w$4${IpH|F3iKORDK+HsTf} z4*#i7;!z9w@|Ip&-lp5%M3~OKwGbVu82PPHiOEr0%{bnL3E}oGC+X<_4aUCpRgJMc z-nfOM^yx_3c+&9S{{Qc_GINeW|390?gIq>8t)zO;6Mh|OG!HtP5b*-OVz(kBigLwn zLn~MDmts9r>lvfjxm+Y@;FlX)?~gdBsP8!&JjMF?j=qHV|68GxJ?4AJ(4xUE$z}ZL zQ*4|W;nRsnUn;ecxYpuI1>;ZX9u)G!>dq1uJdxS{l8+-g5-{@H%~et{w}kN>q*ps` z1e)~F(f_xGPgxwCVSNuGjnkz=_xshmA{QxBtO5<*YpZ#bsCcU!osmStTX{o!GK_cO zDT|%(6}$0|aHb#v5RRRQ>AQfd>F@#gU(7Fy3SLk6FVzNOtbe<4#+Wp-(+R zcf7mNr&yKF7n|+9dMZC7aXG8Kc^6fo>mjQpN9s@&Wf%=i>5 zwo(0zr5twuztw!nxoR?*Z1Nm zaQ{F0;73KHf4Ki&?@_qeOXDeFKN5H4OV^IcW9WD<$eCaNJ!6pRHb~PD9i7?#oZsps z+ozs6jJtRDBK2&mC)oWzZibL8UKPXgct^FIpi9R@=9WjN|J>e^qruxLGKKQIC44#Y zYV>7sG`wTX*!$tvTlRk469~Jv$Fh*qLICeW`212ac@kvptucBS;4S7ktO;+B)@ojT z3xD2n>on1rC_#pjwf5hAnuqS*Z~7hyUz_+yIEKV29p}^cNkYe4#I`gq?lAKmZ+V93 zn6mlj{MJcK*yO)v9B+NE^8~|D?Eb%ZuAgg;%>c{etqMJ*OGmP&TZvLMr8tqL!P}8A z<3n}tvt6NLXn2#otQWy}M^vW=z<672Dc`*S;4Lt3jlY}{2^zPPd*b>n4zm1^xeLZy z|In$na)9^lE3Z6XJtad6k3IdVxgEXsj%|7%mtF9Upozro)y)5#>Wsd;Wx6-;!Vd4LRr7|KD>fH9qEpu@Z&`PzW>i` z-ROVF2lW5*Xgp}+yRl%Z2PG&joQ>u|Cv;AEz!fCBYGg3%L7bYT5gp(`iblIFt~|Df zM&vj)sC|!v9`$BW_WyggtNenm*h#;hGq}r{3`soySXwlUKE+;>PyHaXil<5niMzHl z!vAqA`V<=wyz#Vlg%s2E|K*5|JsA113G#0{bcFFK_NwrvnUrZdDoCEFMx~r_*7u;N z6?EyCBGjE4__P17M1%K+`k~cSymhy;DWKs!Y;^w+jQ9Jynw0*3)`|~2Y5?!=TpB(1 zdhH<`bS_~Zz`OtW`n7O_q(9>Mr2*hQ-M8-i3pH@W&QYd(;ubpIhc+eNn7+(Y)r`cM z-t%(&at0l5?!*qGH{#Mvhj$91V-`k!Jmkv5CJl_^-MC=PL{k$RZ?eUc(uvQmEMGxR z^YfL_qoXCYnPX)JrGlJGgST6v?_YR#?Qf7n!&|*Js{+PbA$5d;chM3_eHnmv+w|=_ zYu?#IzlNVm4FbF`{cJCRm$!QD?pizscn9rNe`3f_hSq533ZKnH$9sD3j@l3Nc&eO{ zIPbAU(;G(_Sqp!F2B3hv;~Lkzb!-!sz)b#@*XH;f}R*Dfa3uu4_c3 z@bWv>$9uodEP8Zo_bU*;UqW&3IW%~$^Rhod#k=>{78x|WJ2jM*;rIWN&gblcYj4kn z0}IB$=0xfSzE(Fj5@aB?k}wYNR*^sH2tRLWc>a*&Fu*%^_-k8g4H@EmJ^px`D>~ly z?|$vO_jIO`8;M)+)g;Ph89Lr38sw5#DPg9=y9Lo_#9SjOG^ODFG6MRFtN zM~yrR-ajDj{>1XNH{MFNjvgJut12tiBUAtF|Nld~&2&EkQ|x>i5Ax(Mp}ZgsFR=&A zl2u0Ypp8(y4eUV|Idv%?NPq7|?uVDyw~7|#rGP7T%jetrMgNL}c()zs)CC?iKi^@Y z0q~%Vm8SBF3Skh*LBMD3b#xDsKhwrj*~4G88i{M^PiUBZ4&8%BMbo}-)Rkj84^l#O ze8tG`&8S6G;D7PNj(T!SdZ}0wrUzZ?$>w&{Ud!@RtYEo04?Q~apM74~8Bf_DRinXs z%O%G()G1cs&A1X8-mj|2LNMOj7Z52^tmucrslm9!24v$%6c65f^=fho~IfA@CE6sdDFz64ZKxJNZifjFh{aaa8^p z2R&@dTd4)`-tW6FKLp@y`a@Ex<9jHyW#ZC_xoI{yE^4W0*v=WqZDO%3;%X9O9S9N5j1(I=Z!t|lf7X2 z0%(xzUkZe10=yj$?b(wG@IKsBa%f*B89F&fT5X#SdU3K|zDj0tAy-v864x?gHee-< zUYxKuZDSwEW4``>GophZBfs=}nh}9#8OK{F+xAn}J30<0?!R}{WTJ!h@z#2LjUF8i zc{;^~=PB;3OoO-k>{p#symQIx=b+)u)^ghz#yg0omvVYbh$riY5y1On+SM&BP4(d(MfwFR#2}KKHgkbf{zGw|+P*pwxr${=Z!6>4cOX_VQNs!_CTp9j{rw|5wnC zp-abC-2nbe`~L0!nXcFWPYHqkUz5gz{QAUiQawn-U0wstgLsYzn89a|TnH~IXOMbh zJWjF!58^rT-93qi1l935#c}?QgU$<_zXC6@_qUuaf^HVb^XEF$KG#FYr=eAeo#`sbCy0)n82MF;8>YKmWPFNMd^He! zxwQuM@8z$5@{e`Pw~}75ya(Zu!sye{xK~o~PX)P<25;XBVt+l5Zr?aG9}VvmgB#f} z-pej~?|_%sTYA~|umimPk_N6?@R6V)@y%-`0N$s4_Lsp^tg^ZldlA5Um1XDmvGGud zttCA%BMKewahp+HmsPl`ndU!ny7e>qyj##4B+=$grZJt&x5WMx(V>KqpJHHi2d^vR zcrTq>C921V{fXTuU2dm6=Ym+if{a?0=SYu^=u`D~)lX0=$OSZb`&_M*03>zype+-xBOa#|kVvqBmQ3H63YTRjt8>Hu(TlEeCyp=;% zsxPk&g*^CnJ9n){$9v$Vgmdj6SCu;wSL>%0t*VEP_g1~4aC`vxy>J*W-S_Xc<$ zINdV!JvS6m_m#cyQXd^}?yTmvOfi8fH6+f$aP(=k1UlXwMz38y_%h$-gdn1$8za9C z+>N3IO^oAh@2xW!B!azqi!;*P<#X;W%j1pX*&9Naj^mqe>HjHC)M@bc5@uUM#oLtZ zsDg%f#>JE0V7&9IUQp? zzd1dJJ@5J458EL$Y*tK_WeiZM@0G5B=5+^&fj~*RmkGKcS&;0xSzrT7fX8r}} z|8;3RD6qf5mFhtb_vdP(c@Uquv>E(@)bcyklozC?wF3m-fHO#$CPtB>{v@c9Uooo) zy#IG+^KdKtiJbthv=ZEk?}Rii6HUU*<0!Gpoz+nIrmnw{1kg{dpcb@ z`k$?@f1%?QPd%wvX{CR4u(5(d?2_W zaT{e~&DuxMD@e802!}TJDW<#s-;U_u#>nrQ+_^2o1jgO_=>?TR+dew*PTE&AJGGtV z-8(vdJzY9J^Iepa`}4e|77gA3dNAyNK2Drj60#5tZ^!%MKVZCL*OXEoC%*ao^4&>* zcX^3PIsbeTRQTlBb`fyA<+7h!EPQ(_W^qMf4ZyqM^zysHo5;{?&nLn=KBG5CAByg! z9Ui++kVWFU?Ou(aeu|EF`H-M)S#&$o;hl)+Sd5XMH*a=LxIg3Wy>Mu<|7;ZY@)piZ zv#ZnY{|Ed3+eGNnG3Sv;{ncE`>g^&LythpTAE)BI!J4oD4ez_!@0Y=w6G_+l7}|R~ zXrasz6i9{?YYwRzbD+C-V8d%(kA~h#c_fZ7q&n;AFgo7tD__3fDm%h-j}zq}IwV&8 zbAD3EJ8@qxGmiI8{p5*sf9&P0Sl9R!ONJX+e(&wt4_>--M7M6qG&uHe|Icj2`hUy^ z^#4m~JZN`i%U|ChEjrG&1kHoQCKD9kDb`SKF{S@MK7DXyJeXpQayQMXiYGx{i`Cu? zvByIzY@J*vZ;;e;Z@CJl*r?=`2P>1wP_gu)6TQml9%R|7CSbTklz0t^J6n5NJ$m+2ZL3q;3pjQlKQW3QVRFz!LpKfX$GK-g34$SZA{Vo4b9k{EFc-fvHxR=f!CUTFgzNsl2x zkH6pVE*XYIO`KsIZ*#(P-A8P6tlkR0*VJpQWqrIi z(x+o0$p$ZSf#Tl!Gc30B=Rd@{GxS z;BexbGZqS9dF$b2wLutf^{U_#X8_*oPM?d|Di8+Elk(}EIFF9Ej`)n6Bd;J)5s53l zv1!l7!{~U2$G_FS?<&u9cxxg$c46eVstea3w1x5Its$=d*W&ml%nj1dUX~GtW(tNZ zREPY>RPEeW(xqdE;X>o|Xv*b8JsP}&@oycdcrV>ys)L4iw9qvn*uDML#(m(!iCGRN zOJ4!JO$|riJqjm56@AK2<-f#1_v(FP;L}@;-}+Qe0=#RNpVG|~41>J4aWw1aqT{WN z%lv8S%R}6X#8u5vi@JOS9q&gMy$W+XrI-%yg@}#@jQl1CEd+bh8F%mPg{S&gUBEv7 zkGmvr$Y9wcmhb;@f#V11(J^t`;htaqzy1Gz^ay7AA?W{2Xgnyqtei5%ii7+AV!Jlu z&^)MCi=!4kgLI>N7Uc|5n@=qFKHx#l`HO}cGf9v}FOQRvT{?Wu}AHy~!IDfcF83 zM_PD*_r)}kSYz%m$mH!@@#3@Sc-M6cj9e(=BN`%c$v=ggM-HIlE#Y*(*i1~8>89BG zhz%`xNGEm2)jX24QwpUyi&^YcoPT9>C&;1ZA5-=BBg>fqQRT& z%JEnKAARkZAsXI6+kB3~J4jpPl_=L+B2kyl(C}iN3sbCc1Y0 z{Y{EYhxa)|M>0;#LV^wzLK}W@ z$3tsXs?^}iiCmf4@8HXcwfQBj_H)Qk+zG{LVynzZnrF#vpMSD|riZQql1? zioH*_%`DWlF;1Bp~)6HE+^JJ-m$)*nC0=tt*fC=$HGO6 zmH({X8qnaqXDH~eZ*OImYb`~?`(fucMHugq#mgznTRfNMpCJRhl}6UMc_)w{N2Lep z$(->}iu%&G@bQ-Grq5oN0lY&7^pl@IBtzwkQl;89p%*8MuV!46%@-w>A#q6xLAHrj z=*7uWXSD}rhRlbz9->1JBR_|#Cl2R=8OK|9dE(|IE;=qJZcc2^lkHf_Y^@)o`9xjK zpi4)i@dGutw14}5M*n{QSK>kczl_F%V(L#Xg{N4!|4$gR<3jVGb`kO}xPs)ld~Z9v z1{v~v+NuJ0P_mQU$+jINNRQ`ObuO4<3;Gp;=K>E(&gK`OubXF@5!dw2A=zWUuHXzL-KgE>6$kVA4!1&nvcijjI-fOn>Qn$1Qb zGIaJ3=fL1Obi9w6e=rnQA0T8PaowC}FS6}N$6Fv$ZvCb5&rFAR7@}h|;-B-|RChmS zF(>2w|JgYK64wl{m$!Ic9lB|6k;n3Qi>JJ&ONUO)oAE_|4oE{ZctBYxanB?=XJHba<~ubc}ZY zbAC`;;_)&a#@#!{-^)}Khh0J9gl`8Zr(I@wym5+0w$r1dU@dXk`#=3Zkp}O5qRmNE z_g-`NHai;LU)h%JhVg#%tc!C0zwW+iY8Jq|ZgO$9JZO*tpVW>?fz?~V=VPm2ysLOM zS3m&o^(R&h)ZY$;(nQ3(Emol8U1oG^G{U8ua2$zSB78V-)k1W<$1?Tz9;+T=I=l}f zItnrJbJQ8rn)xrz|Ibcne&wl+eK@iCRfeSTDK?hBAbsj$sT4groT_Ju6=YM269Nt1 z5xxrmw?#w6k%9-z zcY7-o(V>iyUx~xUO?UGdcW>OOm@N$>biCdgRo3J$^O5zJw?=UE>EL10oDY__{{8;n z|77Fyf9byk`hQCr4@$@_@}+vv*UPp7Xdbkx(y#z-klb?5QFf4$^zSbH4m?Oh%lqQV z10-l9VFaOIiqI> zC0M_LERQy(OUJ=rOW1<|-WD`?AMknZPsRKDIdOh8yxX2F$${~1UO=Yc9kXSt^e2Ef zF;`^10XYAE(eo$&KDKx${o-Ju6u{fX^7YwCFvZ%)P8sv&lcAD;VV@`neTm)M#!IjG z$}hqdB#z5gVDyA4`VzZ}iNRs}DFLR#dp)8<5+lEf2g)wDJsHPa_RHGS*+Pw&CrELx zHG;uo^{kI~jr>k}bm(X5^J@RO|8Gu%cf84P9TjiC(mq}^ymb%lPKWU}&0kHy`_7vP zEBJYfk^SQmq$m;;9ty==1-G{(gx9gj0=!R)K&p=b-U7}pg}LEmC}flRy6+-xnUH9B)}pgLmAlBFYES;pMIO5#>B+c$2>WJ`CgC zX{buUo3r$=#0!A8ZPU=D$}kedbA(hmiz6QDNi6Y^2Y5qu)1*9r_aZ6nZ#Tf>#Gai_ zghl`GIB~-I*R^W}rU;vnIJSk_O7j2kIPvQ7CGTW*FyHGf5r_^mjQmJZ0mRcJ#@+jF zquF#G4!i%4+!SpU(k;gFc%N5wx28vj%B}4S7dKG)e={1q_dl;ZPj&ChJo~xP@OGZN zD+b29-gA<&_ZIvx-LnVXHj1b*^__x}?e%>$jl8>G%SSN2B-L4$N;!>^F9anR@& zV>4;sLEOiTO1}aRs{W~8qcs%@Evoga$v%kgK{{HSb8OqCh#E-T3X*YG(suL;QcwR8 zd9$e+(|OP$M29v;ew8|JYatzB%u4X@|N7_dZ`%|=#-3tv8!dj!solZ)Ymla&I>H@q^ z#`&xBflurllFw^``~R0Wy^W>;-V@r{()?Xys7*#Y|FJ)MgESTUe(S>r;>2boPJ&oE zXQ>l<|6kC}6&_@z%yf8vLv&oi$nV3Zrpf~c8J}XWCvpW`@@vNa-{SP%kiO70EPsO( z*T07@9r;3?&g-5Yf$_GX!TZqLcWzX?E4mUy(D0Vt&@Tp`AkEH`rJNw$zR!?M0C-O| zEN_cQB0_ZM{cKKLvYH}ye) zn2f|3%%6Vj^9`Q)5#X%=qV)G>d-VLo<5&{74{pJ!++ z`UxDw93)P8pi0;(5*=^nb)Cy|=xHj&~UOMH$5^T?kuXm~$ZT=@p>|C5%uQJ&bj_8?*)9^jqV&~@NzFbOI;Hpp`v;C)tC zYONT+TfwJG-WuSow9Yee{ey7m%TxajXP*Gnf0o%r8Ghqwio}md-2OKFPn``LQRBHB z^)8L;FdyFXhz<^n{3_L_)lS4S-XPhRoxZn#AG`k#xO=%!(BdG=UsK>c1LIxJx0tfL6<;sR9SrcsDc;|*0-XQ9%%w8? z1K|DR7`Ylgy`^yK$>})&?*d}H+pULT&@8DLoj5OlR9p{@?#iyWQ6vf>ang@ZpA~T0 zfEs^e&r?Oy7A>Z8?<7RWb&UMNw(?vx`!7y!5i394RsMjzdMn9|Z+z3Si{^kt7z~}{_wGvinoAMnm8KXl35EWn-e()KQgpAA=lv-J^V5Z>TbH> zr5}Ngckw3NQ0>{-#4aSRB~9PO)E^!1)(V-Rt#34$4(}pFM>9r#m(AVFE5{jckX-8Q zCtnI-b)cG!z@IB_Kn-bb4zLaBHw9rYJO!~5wEa|+&m zLS-Y^*ouohkC8->0(acF_yX{9JRq8}3HWpKXJ))#$qB10k7qVAan)8U+t>2c15BDuL=jrzUl0qj}KVz%7g6J4o!Co=|R(3hC7xO9U09^!@Dh((6gk zgMLFN99Uvcypo#B4=P9-hZ}=6pn^P_^=evs7uZ38Q&aX@NP?J(#QEsj zDFu8)UxOrOcfMI!#e5s2a}gcJ82JsjlcJJrHu!osK7V&Lu8yjpt^0 z55m2uqfbZR%UjZa&i^~o;C(7`;RY(+zK_)u(D2qDn%fI6u}|Feq1^vZ8!UD_3h+)J zw^TfyV3FH`W|!d!7XXx z3=*dkdn=J`6Z#Z;_G-qOzYrIx;Zw)6+aOrt*OC{{N)6m$R%Cb_E%w)}S60 zp33@o*YRo4qhroPnL~5`+#p>;gLk^ownQr4JUWeXXm~3(k;pLKKWDlrCrCFwZq0>P zZ}kIs-z5ONZ=6%*a|6d)G(0B-1pwZ}S1#gr0p7_Hb;Oq~WavPL*i73$e7!Y)urf_z zT8>DKt5=?CS+NQo?-#ceFSo2-z;t+DKy-9t_lU2nFpT$$Mit5ishxc^ zlm+nqDBa9 zf9KfN36{qj=W&-l9T}oQ8~+q1t7-5)@vA<7>fSo>UNUHScf79lfcM^RIBubQoLJsL zdBu5v_wI#;7Qfv|P%KHc`y+V&|4B!3g%H5ote98(1i<^!dG4Fmvm&55HBorOa`ep! z(tgAJWfF=+1tcz(%k`ni74*#sBQsszBi_undTWR1Sb~vX(N4LS)2jak-Y(+Am0onb zy+v~HyPzn<`gpIr?N5&mVoX_u8z@fxz5kEawK37pLI1yw#)Gm_-3_Q7^xb5xGMWdm z-w2-r_y1!Df++p}p(ze?AK*a=UE?X26~Plbcn*inV2X{^yAvx6dyvTc69<3?1>e27 zdJ|t5q_xtoRO25$vD38j{fuWbp11&s(<-@ej{Faw*ojqqer%N!^Bu9PMs)1Q$j>IY zSRyUH@%eg|KOi0GpDRX>4#(ExUnId9B!IUo4c_N0 zzGzeN-cmHGgobzCey=4k-hB((DR}3;E`8|_@E*~~)BL@F1TD9lbCWz72MPXkO@XJ_ zq)AtgG=TT->YjJEkAM%P34J8PCc#8;-C+N|!GQHV6 z<}T&*)><08GanDxQQiB>h5d?Xc;glv^@H)Q@yVy)owxXv7a8FFB(7&|g*6G9v%<-L z`Hwhg$EvVHaQ~mMvGT%ofcL#7d7Lyc40;qh?85#Gz5id`eo3scPl(ur#D$ud5%$%f z_y2?DN(Tq$&1O2htq>jk82JT8dL9`sWV}Jj8`fL%frx#*5a z=&)<%$vV29^1OvJ4c-~ogzc$##|yj8LBktAicf&?-qowT6TX~iXF_}*3-GSUv<_Ph z_TJ>hmVFie83$EvU9lV9oDllys8t8>Zu(WCwJ3`W5$sg6HI|^`ed1ux8Gjp5qA?Pu z>P3+IftM@+C<|)dEsItst0kV%WI%{(0!}3pWrpf!HRUs zCwBbKabLX(JScr_utc;R32N;O4_xsf4ib`?3WEFpfP$GN$-sk}Q$ON=g@!>f!L7{& z66g)mo}JZd$9HoRBayf$m)phf*wHJ;;b=^;s`n_{;iI`T2{+jjAY>jrJcE694` z_t9gwusuk3k+7Vq_yEhVK~7)drAtTprnNPn(kcD_MjE_xm#v|EVi$hiVuovUJ{sQd zzSUX6J4l0@Cn-Bf9A&qC&j7ru@tZ^RWx)$lC331yN8_Ncs}|J5cys<<-JJmNUbnfj z;&DJ2G^a$eY9TK=-ZJ+0#Nu^0h_XoBa^v;$#U|0G*gao;&Q9K7zU3`JM8__S{I2#K zFEDUl^1?r`i|xC#>J}8r$c~CRQt~k(gqs5FUSskqq?_^Xt^31 z-gUp)&ck@`cL$(hO_4bzgXwp`Iw}X?-om%C(H~rI={mDL0LFXc_4*Z| z0Pi`Q_AV6F42Lc#SaNcl%uc|<}%gaE8JKq0l~ya*axJ0e;V_bRJ~+*_vSeJh>so}OJ00>&l6AS|JT#t zo!w}AlIq?b1+FS+c-yCuDR}D?Gln;Jx4GXE@a=8w;JA+(9q9dk;{xXc`Ip#<3z0az z4c>1qRiYOs0jIJbBpQe^oqOLybZo=OuO>nL-p?7v@7@Y5@Uw{K$F99`PKBLWiJw^> zZ=7HNT{>Q9guECm{oIh9i?$SpK@7c9GUk2=NL6!b4b!<%E! z@CA&ws@($0{r~E#4sXu^yvxfs8@KC`ptA9b{wRQVNRR$?81GY-d;E_8ydR1kb}_6C zg$B#x@#~$?@jgAa$3NXkoY;@VJzG(C;`UN>ygxsexbwSv9@F8ShUoZ&k>Btox5o;# zjN>iww(?uE1$O^$Vly-S&^CbO@mA{jMVF3@kD^XWe;OnY8ocv4iY=&km#rz(M8n&0 zWgQ+~z4elKNWptO?*-v}fH&#qnzNajBnba3qF@`q8#pj41Kf;Gejp4=Z$58lvM(C{=A!6=l9JNaGM4CK&m>w`rdB zVHV^4|E5BjHzjiP9FRUePf{f z|Fl{Y#@kAHC*^UX;<_}i8vt+fPa45?sw8MTQLMlL;Jsm6nhcEhuWP|~(*fQ}+~cb? z+sM%D4?3$`z0n(_^V4=ol+&8% z(D2TCGUq&uce{r(<$23%{2N570NxWjPP{%NPl6Ig9yhmUYpJQ#1lxIibmdtRov+3{{<>s?aOYC)jA<~hfuBK6<%|4iBN|1Bxd z|NGK-P>F|E9Mywl=J72-^PrNkogJ_T=|zcB_Wxu0>yEkt4@$Z}GEW*JLC$&nzLo=V z&|?nV5+2||7jz$#339eV$L1=L#PUO-Nz=WKl}6|lq|~CGMjmkq;sg?RxO4PssyuoH zxzi$C>*{glyZQX{WBm&9hzeag z+LC?G3B03Jklr+SUt@QBPsMwK$VELgygfq|%wfEDEo-GTNaM#pOa=hFTi^elpAPW; zK@yIVc^d}}sg#Jq2c(s>GF_Vi-dcR`tjEO35cg4)I+aW4co#o7eR3vBn#h5~-4(hO zcZ#aYH~Lw9zwKHmIB zbm_2KVc5MclCnYSMT2)ywde{e-gOGwbkXp(@2mI>uij=`#88&E?nttYhXcIHr2(=; zfOn2a^txq(anQVVUUT8wTf;gMUY7yhDmCY$BH77MQvLk*M*r|YdRKl&`GqNIVgeGk zp!?H^K`6R=-!}c26yw2sueUr#bW~vEcOLH+OtfMg@B6#F&3CS&<9N&Uv)>*E?qYqs z1qqVH_Y`~wxiJmlgU&-s@q2gT>XRU*V_tz??Q!w70dn71(Z_5*01C9Z__xd=R zHxWosp@H0|9I(8#T36i)KHid&tJD|^@SeiWn)xn4hEl7!%I5#Wx3^cg_e*#dN)eAC zaowpi*5?kR;~gi~x@Uzv^SQSbq9Ya~zvAR}mt#c6S8v-gmF(ZH!NxoJMw?|r2rK;C-tS9KzAJUd&$foC-9({?{4|Vp#Qhl=DneCJ`_s3 z6-a8)L$4rrlo<(g$pnK46uVE{d1Kdp4Ao(LYc4Fi=)i1fE*qZSM zX-<7+_~&-)`~SFR`UK!f)UDc=XwDfY|kY9lnfZ=M&8 zgz;XwbdYj`be~%F%M$?a?PcL__su6kEy3Aa`g`IapWy~xE`ax-$9--CfcJpkP2yZZ zGF0bU`DJq!I^OrP=N>P0;2_o_aaRQr9(Ki|<6Z5Ywy*su^PT^%LUi26$j@2!i%G0J z<9H7oZGEf2iG6}JDzs^z?A#RA$D5~_E*&!3-^OZkDE+@b4c^yBc>n7Echw&=M8o^g zuSLQz-b=a^DF>vL&t2ONpZ~Z1^enn(5eedsyQsnWA`bedv|s^@w_bmknLfaqw`ekN z#YiZ$tTg#;X(T${bp2$iAdaN@JWYN9_V=6KUn7(b5V}z+`AUhVTY05#z&gX z!eqwr4vq+ylrg~GAZ;j0b?BC3{R*-q<^)|j^a5>FxOP$S-bRCW+2gToRQFym=3{_{ z_v4F#Y4G)yQ;|B9>n*#|RzKeX@Lu=&*DC;PaN+X0|Zi`*NFHwE^Cb z8eV7fy$*%e7jL>ScPBdD;qKlCfA5(^bVcHL*2L=iIiurkd{*H?g&^}?kPbt17-8f$ zzwt7kdN1R6OZ}8tiQ~mSoQRVj-7;zZjrHBzVT?W<+Sfjr{3%ZSXz(sg68-CXOX?%t zrD%BL-y6+>@iricQZ6SJ=c=uA0C-DEY3#NDdv6P33%Zi};~;@KwVp8E1MU&476QCS z-mDw`+!qQZHjLl=6o`&@=a0o#6<3H64DZwsExb415`b90J$aVPVg-g=DaaL35c z?V1()cm?Bl2YzfCl$FPJ?=9|CmJemOusq(P33TeHd-dvE^1tW*nX}>lTUMa|-$~;^ zRZjh~@DvO8|2kspxX?UEB42zO_MpH|U6cpX*W}{I7L|e{cEPFd->Q=!uVqBuoo#WD z%t9EMDuk@gOqZdher|Mot{6+X$t!P zL$7t8hqT8*Wg=VxY+#E0QXQ9b4B#Es84)e5O@e-e*|_p^hF+hM%b?JiQ5w^}}`qzMANMML%+ zTni3Jx6HE5J<|~f6>%=tU4?iAj~QTE;* z{%ZDl3h?$g)AVllToM$*{r>jh&NxU@^Kl#p!29;4<5Erl@1-AKTvZ+23(YSwZ`={; zi~7$p@6a`?!mc+2Wh8Fi@jbj1&g)R)x7+%~)1fQXbLD(Kr9s+5 zgLe%#PKSzjj+hib8s3*6w=o#+#{(BAc)Kee<>do-Pn6|NZCMHW|H6X`f;Dka?hoOe zya4Y4nT~J~Fvae{b>8-SM26Ci-#`E2A8wG|-zoCC_s10BFcSB8r1kCL)#!M;zKGGU za^_F%P2S)E%Rah=Pi`!)G@kCY2p1iN(H%_ z2JicC@B2~l4znNUMZW6R%}U~Am}4;kB|7fxqn8- zd+pAs`Yve>rgQIEhz=)={A{d`4bfqXkzeh6Lh+RV#;>=8rbp~PHGz$H zT0qF!BiYd`UwgYg*-4j<2qiZ{Ecm>|zx_WG_4#P2fc`&%#)BGHAEmq?4NtLpf~!T* zJm`k;v?II*SWHpTcSc5upvg<6hauR-E!_h&X6EM<8Q!bK<0r6WpX|L=hHlpUmS8oVEJ z2boc)SfN6(S!j4K=}{0-oJIcyy%zMBl0md`XV3r25{;+4Yp9L%01EJflnefP6#x}i_8Q|^ZY7D{t5 z9p3v99X~MgJ3q5yk766+OYC-bA<+7fcKH>+l3?(Ns!f+6x^fg zIOss`)N?6-cah{tF_o~bYx)Ux9Ls0p$R+V6=YUbf7#vQR!qE4M>d5N9>`^RynUqG>C&;p z$g(lJD+9)xOoMmbiB}R-ymhrM3!&kCedQGy81J2O>nV6Qa6xC<0p9+4rWbaGlOW+f zj$eBB6K%lkbouMW)CIw;^dxn+n#wQzXb zD>5AD#YxNJFKXwKm~V5U64B9&k)NsLkpKB)#@&0Z+_J!9BiO~s1>x`UXObdW9&ZQV zZ*=KM5f2yON~84up)`0u2tE9Yig%u9j364`6~DvSV7%89e4{LH8SB{i@`B9?({FtR zSpg)-jm@>q9_+on*Z#>T3hNMJ`#O1>b|xpyw2;|fN8wa>G^=M6EAxApS*j_VK7@%Gl%q)Q4tVJwd~ zt|yT`9XljftApz;|MvfAO*a$$JZ^nFJBpYJG{gm^)7ci zeE;92cFvdvm}2kf@d;f{B0=v>?`%8Y3O=zLDW0hSJV^I(yY(&5AgvfXu+%M+4CU7y zZrh=UUO`qgRX-Zd{6@$|;?C=8RiBnauOPYYrCtyPnQsT_I--LMBfpHc{to?xjQ9U% z47}SNBk0&ciWK+TByo@Bzd?#)6QWB;Q5EUuz2Eym1sTsqgZHC($0n$Fi_g`ULc_aq zAA2^8_wbV-$_-M^hva#S0p5)t_6b=ZAwlHjH*>n1RFHN}t#W1n?m$dLcH)Q&71I^J44xMIY{#t2)HxJT<34`shY$GggUB2Z2DH`DDPDI+@WVC1)^ z@W;O4M~vfb-7pq(WtfiFTT&B53qI(uJl;6bNcwd2or~7_b3u9^4c^U%msL>lu6E55 zN5k8o$y^L>kZx%%r}Y2jhP_H_0N!=>?Tvd*g2#zo*hjB!h=a_Z_VdGdE7`fp*2Al} zf=-K<^MygKHx-TLFQDVymdd}4WAr`20f`gZ#BHg16umf!9GM2|XDlmyI9i2Ix=Q#fC|3}i`-Q?Q!*Y%c? z<-THQcuywaoM61|zpI5I6HY4pKjElB)`)Sn}JT>oQ=9T~lBcuCs{@S>C;tlQx0A#Ga;h zb7oSEk4Qk`0!tr+O!c5wkmc4pp4jY?VY)TQ6Nrv7jQs9AuI}G`c^2kQ(BJT=R52ysKA_BadbR?lVm!)oe>?i82Ra#AD3D^!8qQW z-npKO2eJGA(75L_rDCi<#nwK3L6?qdSQYR&;|Bz&kVSw&PZS_tvj$xyRMO z@)nNmd+BX-yzh;+oIfheK`cY!9_s9EXv;#!d!BmwmmMdV@Oeu_$6Sp3NIwPd#F{Z) zL4Mwn#dB~U9Xm)Vjvwm1)mgrR#AP_qr^Alxkp`vzkLRGlyCb&cB^B=vgK4s8c*i`b z<%5^EMxO~&9!R^95)eHG@QzAeV@d+YTl{$H4adO!|BX)u6chp8V|o#<4g$Q79widL zHj|+_U*%fVJkcAZqj%kxYv$pIQb^o-v9+>0?a&(}_S4ZCZKfhj=iY}99c&o+ebBfr zd|#Mxy!{L!MVc?uaXInycKJTyRo2J*W)NLEa@eAG6S67pji{G=4Kw(*aIYp$LNie4tRU(Sx7@Oyu8J4p~HP0;JtAB zLB4l=;Qjyho6g7gpyRz``0l%P-qVDGNZc*%K&_3N(eZ9~s9w9ff}iQ|_C<8GVdR&Q z*P0PGz&PIVWxXFCJi^BNK(>l^ z0v`qX1)d1h3EULO7swPi!dJp~fiI0Ofsf4R&$p3}#An8*&!@^K&Bw<(%{#{XinoKe zmbaYu67Ol=L%fl^fxI5Pj=Yw<2D}=)^1MR4IG)cuZ+N>LvugB;H|8aeK86mev6q;SM??B?*{SjVxFgUF%H zp~NB1!G-^he~<6Qx8m;!L#IK`{mi9!>#=BBSOUk$S<6Wqu#k*A2 z;nz|}`pXw`;GL->J&Em~@lMo{&WCYLyd!m_ePfOkehqb`bwzg)??4?bBJH=pucnSP z)jwUrlc=Kwqqpzl?WrS;7PD5o9d)FBL^B1yiaMI_(P4>SNgb&zc+Q4jK^>_~b#&ux zsUzi_xQ{odjui5J z^YP26Bl%sAzTnNMBe~_ooA_nak*xHz58jkIl9?@0h=-^nse+4fcp`NqNglAn6R0Bz z>#oIk6Y5A@NAD=!m^u>u>Ukb-L>PSdQuLi$_ zIuiIikcnSR9r4%RiNx#wHIfV6j@P4(c)J28@Ve9ykJb-6ybg85^_z^tYg0#@pKV6) zTGSCoa&`xP5p{(3%8AR~vF?#U&14eIFkC7}kqI(77G z*Jd;PeClYLU}=a~qmF*gx^M)qN*(>^*5k&jP)FbM2CVVQ)X}#+Lf`Q7sG~{SWBPa{ z>gcPo#dG{z>gdadCpmaU>gaRD(H8t1>gZEm&Sm^;>gc1-#57)kIvQ6}^ux$kmM;(yd-rr_-u_kUV=J$ zo0aVT|FQSx@l@^6|Nn80sS+}iGS8GTC7q2FNjW5$63Q5v!x5nj4N4>prX&?nlm=4+ zNtz>5MWjeYDMh7z?|s_){?6m``0TsSx&M66`8>M+Xx-N1ao5XzKGu7!_j>R5n?%kCsMQnv+nU6WS}%?lc#>wK z)^j15A0$51>h7mllV+e+*SQ!D(sb17%s9(Snub~(9<|R%yr>25x085K3*Me2aibQz zn?vG4Ex7q5aiSL7E09R21)tg@5m5_1(@fT{r-~JJ& zPz(N4iueA%;QJ|vUr`JGoS!(3 zTJYD;#4o4?-$P9Nj9T!ut;8|Zf^WGbenKtyQb6KI)PnC&BaWgL{F)JQ1hwGDUx*)2 z3w|qu_#U<3rv-@bPz%0^oj8nGYeH9FTSD56S|KuhyGXlGD`+Ttij<04Tk0&zNGYfl zn7U}3l#E&dc0S)pNvO41@4`pYPSo=I6u?E=fm*)R?|zaJQOoBP`6(#@wY=TL9+Bcv z%S%Zuo3tIZHj%bukm69w^O5B}QY>nDWQ6`AZ9^^hdfP5i3~FuAzI=&9MJ+ew@mNwc zYPo)2^PCigS}wV1;iO2^a*nxwnY0zPoNQx@NfD^!$p0XU6pmUB{gVEqFw|OmeM2NE z6t(R4_)L&OP;1TdpZcU=)Up%KDkBA<7Ui3n1!)Uv*)+IBk^)g{^|n*vqyW@fb@X&R zX)|hBYnp!|`6HGc{K7TyEo#9J0uzT&3w}S9IEY&CbCbk3s0F{yM|_Q1XLm|j69-VM z)b#Xq;w#iD;jCCj>_@HB&pJJceW-QnlDHi4C2AFK6Q&S*QR}4X8arYSY86QheIvd= zt->~roy6y;b-cwYoA?a13J$t2BzB`#{<6>7#4gmz<2T$z>_n}c)}htJ4%9k!UciRf zj#@{L9!VuWMXe)on(K*esCC$A^Dbg5YGqH~)_s(io{2#m1%P& zh4>J)G8BAv5+9&e`n!+MiT6=!|J^Uq#CxcFu?DrMPMihAYSfCJ<6J|$idvCFA=bnzsI|53{!ij%)QUJGu0_0rTHy`} z1;i@U3RC}fo_GRxWCznSczIe$3A%wD^P1oWNHTSJZc5%X>$|Lq1NWF zp_#;T)bj5Uxk4;MEx#h+y~MMB&;PT2k4FFlQa-vpNVuv&_aMcV$S7j%K~|n!oZkrc zAT<)WT;TKnI;U(C;U{*V`@G@I@}NLcr;Zw%>py!Ce5oj+UbGwAS!%XAd)g*!jX zW8tmOV-|c1;N7~|)eXk`z^Y%~u>kJ}hKrUP`BR`;H*uK`fcN9gI^h}s@8vrtJz4tgE>oct$s<8Ll8gvg<3KFG1zz?{H_v`?5@Ugc)vz;WZ=YS z)Tw(;`v~)Rm(PD+bnz4Z{NLZp@ASC?YuJ8*^r+RJAsvlU#UG?|X%nRBba=ykCyMu$ z^m;igytA6WuW15!b7cMYfbka4*t{za;9Y;?@|u<56lm?k!KXpblOVyZ${Fea@8`Xa z37r7%l|~tFls`s8W@-Iu=Mu5;HhDR4YR?G~vJv9ki6d;ho6IZw)_?e%Ilv7mWAIUy0oD0PiPv++Eb-DNtBeSx@{jgEesww1_??8Y2c%;XF7owtb6F1W zM~IG5ocIO>bEd7xXCCkS%e;E2t@r~{Lhfi^O4tzl<88y3j`XAR_;d4V*_)RRZ+K@A z#e2-tLk0`)pUVc;!>6~7l{nDO-liVO5=;bm_dJ{(>jFMboOmRd`5oY0?R}$M72ur; z^+$aLc#C^BnZ})KJE(bod*J$pa1*MHI1$k#=rk>q4=HR^|B>wUwiX+wlJi_xZp_i(}chG|FJ>$ zPk{UXS#&uFo{gY6NXArJ9V-Xf1g5Ql8>Bf#@7BXhtf}U(AN+}(v`ySz8xwE_=|t7q z;rmIDQ*7<6c_0T3eoT9s3v!U}#1_*Pv#F3vXi7y?Id%mZGk>Rzr=<$n9`O^RgdUH{ zz^)**xJFf0*DPSU92AA?I?EF~SG~6{OqKjGUlTm)U~Je+%*( z#F&n7(Xd5-Do8;(yy0OViZ{o$H>y~8uQ6Fngz@I8&vk|IK78Hwk~Y9QZ^-M4)iMgS zNH$=1061dzaw5hT#`{F&0b(JH_js0_#2G5&l{_`o0AVk&zA}oF89^#!H^fi$byS&) z3icAK?Q~z_Kp*Sj?TzTr!ig`l+hm8WGxK=6T5t7lt-xPm39FNS9{oA<%D<7r7Js+A z;2R@4L|VQ0rk$o$kOFjg!_#XN?~jugRj}|*JYRGM-o3S=>e6;^_s6eK>5p z*h&hdJIWQh4jhnP)7VIY@lKdnw7wYNZF7BggG&k(BBkwlW$b;) z-ZCY!KH~S_p~?~2VeH~W^5cPAs=5Ko6(?4R4so3LN^^G1RrwFuJ1$npsAGVE{$IFf zcYf0qw#S<=t&brcSAy=V`*+c@_e?sx;qyf(-ckN`N?3S*AYblj0C?*LjIE>9-k-AX z!~neK28;CzJ5wOH0mZ9*-ANGFbE`Qp-b<^b%FhA3w50GQD!>(FEtiWqoP#cz%sI7d8puK4 z9%|3X!S4TE4Gnrk?PbZI5WgAY_jaz@j-7+zpT+Ny=x4q8zayd}6eqs3ssnYa0+?@* zCPVvoRc15L|A&k5evuks|Ng(|0}n$wQsU3a|LOll>F|b+45N6Tk$N!?3-9ZjwPj$u zr4v@sCP>0Pxt%ot@0;z1Vg_|7P>SME)g*Y{qH{>r6UMuuiL4G+kYXaXVgY-o&}5Ls zTWLA$B{uNZw;YEZ^5k*EFZb3D$&)~rz5FNZY@%{YyYO{?p^LYFE zpPVF(GEhM}b5C+9#jt<>fBoqMBRaYRgpMz)qE(P0ba=yO;8DCGu@WsTysKT8l)&@< zVDW&BaQ5DKWR2MwfVW%Dyhp(X6iB`$Z1UjkB&g=2#&H;L>Z`{CMF8*nH>DD~e5laY z!P}PAKe4m-(i?YrQ;#W6{G|IqMaQJKCwOC+waU|NXG@C6r1a5@bi|*!gP4UA9bL3`&^6B#KOC{ zahp1f_Yyxh+VPe&)8L+TxH!4!kr1$u0#*5_xkTSdf|9w5dttn*e-?%21H5G;5t_c;2#G;;i(1fcMR`y-$t+yltLM z?~GVWgqzv@mUq^ zF{|CkJl?+RtPB%X@bTW%5;$Aa@HE@k-amgSF{C4(&|f?i{rCPqcIp3T)8!!eJ54kP z4J@3#04oR0+Ltp6ZjgQ&Nz)pn_>IEc=fNJNY|mB0-KrF5jEl?B?MV`JPi#n12jrlK znxb0aAP0GLEUA7A&LG(fz3Tn62)jXQJUnMlVwNb`7V%r^B@l2^7P~>R3x2$KiI5V@ zRgkra4s)FNe4lA~d^2M{2W`5Tek*Yqeh#WuHId|z2xI#t)_=JfLpt7GpZT@nFs(t7 zqQe{h@EFBgMd_J77T%X64x7Sw2Rpx{;XT;4#<3URo!qRWU#CWaP84@eMLkS{TxD}? zv;p3;hQr)<0KDI5^}JscL50j#6PIcH%NF}Jog$8U4ly!>_>JaYlw41ex8F7Fy1fqFL}ciq{O~&!LvaHS?F;|NJ#_W9W-=U3OsLdFM3BJ zTtRvS`b%a4yt^K$yI+=zfqEyWHuhFyXK&6uzCACM#L3SQKaa19Z9_%a**mj6T-Wf3 zGRtM}soj5cB;mvtBL4F21w-cXp2{6tCpx1Acm7ZKsbci~B-d58s3`s|NMpuyq;oti zxK%{U-V$_p!&gI~c<=M_)5XGjTP5E)7;lA_`LyALYVkKK_;F%)X$!GOniS~R+RRt- z;Qs%U$we37{{NH49JdnyZ?DT^{CkCCp!}B$ynN1L>v4YL}nJ;!f=TUwZD6`vKf@$d!oS{p1h+ zuWPZ3lT)21yKEdZSq^VeM8^@F_ze21@3`nNkM~z{$IiH~_{GVKU;Ca`7xuG#|37o- zHimR~9SXkQ4=yME`~CmFErl%dcVLTMmM#auw>`l*NK7cnD{+|{0V@Y>)JQr7AF-R` zZ9qFgDyS={lLH#0qva)By^0h_*|NSN5}ZL=(J)d8e?hAB)iD@c$VT`aD#OE z6}`>>G9Y~|eWFe0`y6sL;&O9Nxn)HsC0thx)I#}uVV6OBYeHZr*__ ztW^-V68xV@v43LrqD67|+gpSPsBgF_gYEGq43HVpar4G)i;)Ag25BxG-tc{VDBjiU zjx55$+h$}%8I1Sobw0ESl1UypCJW$gy(8@aNtpuWz2j?@>r8@%o<%Cb4buI`2E^k4 z@3uh7hsuRiNWz6%k@Frl-iEf021oXblSL6fs;WRJ=Xq?r-zmSnwT_^|a@l(xqT>Zl ze4`&--h>G-pS@>`*T2yX#;+jFBz@fCmwaV=yoWY=Go-_)y}-@#&+hFUI=tZvCQ-Zt zS8iU2g?G;!BQtpZ-?*ZMHvfOj>5`TX@b3PhkbV*1t?IK)`V=_-Z+y{s65ie_@-AzF zcW>(*=5LZ-0CsQlTSI;BVB@Xp_uW_|Ta*kTe(K%r=9|i}@y@JjC)EkF-tMhBq9X|> zzF%hZzbUU~9`CEt1LbLt8F=2(sJDZ6lKqdj5bpIbro)Q719{#;nhtOH##9tcQp3)*1`Fk4Jq-WiI$h_~$86%UYuq*R~mhz_Pgnh(xLed5H+$*PFoV?KWFIp+L4q{CZZ32K+vQ zT|uTd7AtCQXFa^nAUbyA#OLUw#|v#^{u8@{Bi%gyRrq*cRCj7rzc0b|6C|O5bqwjS z8@raiGKIFir9g)_e5*f-_tjhPNLYB2ACuR@cpHoj(ms%$%6{?YCcrzK>Oi?SXahYf zKCt#Wxc|?5VoNmK|C{AL&OZ$B9>^{>QJRc~;;6@@Ztup%+xyh9h+U8ZnTq&Teb~5g zDgYbrtw-JZueY$?=PmAtj$oYl`ginbTs_Nt_SQOL^k&gT1}ey{pT|^N<=Gx@f(v6h z%pLZ;mHv~x<>~N-pQ%9cUbwWHh=sS_xbjLEZzIJz8s75~lmx2*-X)u22tFJXNTYCQ ztvkSbP1B27c=uLl{@tu9fcMDDUIn3^XsE*{6$lRo8|BhLUioLi|=sOh9NEHixZdqI$7(EF)*CqeKw@>C7JE{VZ2132P@w-;r^`X`%Ts6$B6Y0b!^%Mc!PR{51j$CPi*`ZUIt~@hYaj=i zj63P;h1ozeYmzTlf%*UFDgIpsAO|&EcipB0a!_K)_JWf}R7lR>Yw+~HJdnQPw9DLO zVe(`J#82VZ-713$>>T8M&t#PsiS;VTrHBp>ocQts-g~}IXMTw_6Lqc`dx<~)CwQM1 ziMVrw{rmqTjOj4H>e=k|=l*{+I=tbh)KI*gXG+Y#!n+Te_6c5MPjmUw@U9R^=eq&$ zHm_cF`bw+~^tiBCK^!cxHwHaA^a0+PoSJ3Y0PiQyNeAXmMMI+3AN)MK4||F2-{s(} zrl&wg{iKiTov#nZ#(T1?GWB{r>*4(Z(eW84KHqfPx(EvMOKjh8;ki&%{Qh6+?g2Le z1u?c?VqXk0rbFZQ%CzIVY5l({9p3QUfGFOZJo~3%;jOrH@(GOhsQd@o>8(mrnGFp9 z?@dQKhdOrIKvhq>7N-Eb^R{1~3*%k=ebn3-;Jsj)M0!eNG<11w*!gSr*mx&Zt*yDy zt3bYl_;G*f&WbR=#`|Hd+M}gDthc=tkLYN|iLY4Ks7`P@^V$2P$*1}4=n%t+FZemh@KG)Ecn5Q(9+)#7AMd;^0wurS zB(Xi-XLd2BgHyr5nJ0sWw=x~x@awH8-u%CJ@L=JsdNpnzjCX+SQ`&IC@uPw^e7z;X z&%yJ^X&cBs%X`)dfOp#arH6C@-YO#t8tehyr|*xs78FNAD^fncnzsNO@4%&2!MfFo zWDCU4TG%MZSPUC)13k5pBxBaQy~P*NF&`&Bx$x2#n*ZVR7TH=;Tk)$5+`Se2ae=q% zPPWIJaDqV{=|ko4@s_{m|Nlp?&59=I|L6bzIcN?1el?ndbT^p@VdWrqtJtOR8Kh$E z2ec!0dfcQ^NAL}jzNdHp>N7SF|D@`nZ;z9p%X@;1;ct+RJn%J#x7e>Aw`=+OGa4Eh zq^i6BOM~=&DtpD#hhpR}h~Kr28wHF1r9ldm^UYbZjP<@CeTnGUgcDz(qvtgT6Xus# z>o?DQTN$}x=lQR4VNDhG@BhCxF{I;edl1izQrZ$bj}CA6L3R{x4gTq~u<)jQ3K4+u zesq7*9X{T2i?4vk0^lv8|I{%1xDCWTAQP|%T#)WHy}Sh;kZ$=gmUR^1{q2)%*Wrd} zs8uvDqHqoN5-S(M{c*BclH7^-J@340EuoLS#6BssYVy)#z4QMfh>jMV_|m@HYdFU< zkGE-I(mP!Z{0g!@k+gOH6ZSv%4w$qNB2 zybmUhx5K-)9t(wOc<-3wsiOn%KD;-(>g-_~Xx^P8gQegEX_L@TFZg(ix7(5Tad7q~ zWsX%Hi-r#D@mm3|u*UqHW6Sinq1#%e$%hcXp`Y{0S53#pJ6B}7dy*pSeL?Dp=*Yr} z@5Z9!V2K9i@!l6Y%Q)g40~O@RVPRM0{{yGDzC(=Z*mQmFyg#?MYSQ6N)Spa2@owNN z<;TK1Y{kzbFy6K%Qnb%o%+rd(MFHML!3iZx_t`*s0fAqf!TJAy!3uu3L7Fzp*vJ#$ zop>lYIKY$&y^#uXLk0TJ9n}1p5i^XO7OHCSs(G^J3he$ox{dkFU0ZJPh-|Q-trC6 zF&`(s%c4uVb8VR)PW)Qa^<>fZ7R*%;ZTCbrSydV8WUxKnCZ|R(GNQxCvE3~w?(hBo z=>LC~{s}5beYzYpqp>y)%|W^A3?#5}5Z`1|0=x&=zCW9`2l-ZwH(w7dv9-%2Lmm&= zKow1n2d9Jg|IYJ0Re>K!uj4Zjdj@jQYvosqT|8nSCu+$)w;$N&|Bdg63g%ack=+qL zV?p7LU$6h=ik--a9d}e%um9IUbco=@clo(f{&{oebCA;V@0aSD@pF(ihq0}|#01;- z|2Op@hIGh1+MfMCxjoJ9-O>_Z{tIaV)&2X;gH=c)L{oq)m`wNBJ`s0lYcO z9z05WZUcRjEnoi&;Juq_Sp?&4w|bT56M*-Zy5Z8(t7D+xbq`Ay4q@ZH;aEk$kdFvC z67k!)ooln#6KuTKr+P@deW$>3N9^no9cyvo`w+WC)4Z7Z3i8lBwX-4ycX5|kf{9Le zh~`YTUt$T0x(w;K^60*uZ)Pftw=Nyt)7pc-pm_T@+lXP|?SEC#60RW6J2la+w-6f_ zRWOD7|Bo|=mOrq8qMjY)kOJ3R4wa9q!Uv?Usm+{m2jHElcrd0xBnHxZu6-l(Gh;HGetrT1d@HUnVeiKq>1NC5A4w_XRAdluCRlfOiv2u_@m%InO#IAU)MB9TD{9riU2Q0CxZ#FLxlLQZ>b*VTc zfGc(zxTN*r0cpZCo|ICs#Hw;TW!_Sbfi!tCcW$_bor6@WS1xMJn@wJT_(lBC2;XrU zI|r#A%r+o@Q)jsfat@+H7AHPELV&bd1sN7TzL(eH<{}CY3Zd@ZsflMu2 z7w!fxNR8~SD)C;k_t@k08->%Jdgf4rj@ z(-CoooU!!J1j&#NZvp4|{~VA$o8K@S3vd0hZAakkty}(IX}hBa@fOPE@Xg%Z z6lmK-nC#7#BuGp9{s6qaHGJ6FZ%Jz7h z<$E%uq8l(kuc=OBaHK5s>9C}C!3vVBzcgir{yOzt-K9C+gtng?az}x=% zipLS3ZJ^5gTn`t3=Pi~S>X*PDNJ~g4G`|9PPZu2Sb*PPj2&5UI`yH|Iu2@`OCQFbe z^B{iLxGH3Wmto_*-!ar)%Rz(Xijz}_juf2unkOxZX+-85q#LUhWCDLMaJoiO$ZZXNXL`XdMm3FfA9Z8TWps83HpCBT@Dg2J(Yy! zpsm(&idZ?QUGBFhyu=<3=A~7TM>Uf5oWT-XecGw-q6`J1PV3Ej240ZfLNc2HpFz4C z>0ROimRQN^#XPF7sF1#~P>l!`yZ<*<8H-=LRf=qk_)+agH;4So9i&I?HDo_NWxWH^ z`iPDUocJz$HI?&pW`2qNQj>6m%D@#n6Zd9*uU)#6?Q_s^UPXpOLQ$A9SNRY)5zZcHhOEdNVWqT{W;meRZ z>n*XPhz?nt_^zzp-q(1DdA!YYG!>(d<2Oizj9*7qd`xG1ya^X)9c4&ITq;*SxMBxn zZ(};VMJ?M6(Cj@gqgDvew=yq@jw9ckA-bp(Urp$qtC0W7lGn?3vhjM|%W0 zUK3}%`~O=I9l<#99T&gMeXND~3Q{}T-)-Lj{(zJ-YH!KgM)n_&R+OG(NXIz0!s)Jq zwCgPv)8Q?mqqiT$+rB?T77K6LDbWKk-dcgLX~T)@l}=~20K9Kr|8VpHc$}!G*oZ?N z;BCe^YbK1hJ@JxOEWq2G)8I)$0u>5}RwPP_VdH&y?EX1ot2j9p@te6uEl27H_5ta} z&8G6GCqApgd9#mBG5>l?_?Wxs;&=wK_lSk+Kpy+!9e>T6AswfwJo4B7 zJa1`4hqutU*9jDFInsI=EW8(M)?b0~&OW$@cD$vxIplE&z&r2hwL1l}6sSUDMpiDs zdra$^75uyfF-1WD{y6ak=V`*y6*15|9f6vPer&w`!=KAI@k)`uAbuuWV>rw1VP|ip zJ^JGt{aLT}c1Ltb;u zy>8^--~OMa`+hVyP(d!G%RzHW{7TRqbWcP~9V-VVXMfq(0CG^1Xr2T7fppHN_yZQ; z8>Ce24Ckx@8;JaQ-#_~>xpDKJm*D$<;jeSXV7#lSzh&0~ywfk24Hi~|8>CzEJsqsD z@z%Q6U!dbAM}CI-_08roQOCyH=xXCl$#K@ZVpk2(VTco-1$k3jiVXAp|8FhI4~}XE zCP*sdnL5uB*dA{}!Z*froV=2$@n?c$N{9FCrQ|Cp-ky~6Dp+{`-uJ5-#`{h4nsspY zc6@wHI1S(}a*XUZ2A;QAx$Bm~A#i(3$wO>{j_CM;6QB94J%0IJ%xCXM34EdD z`V35vsuNvn6xhE(A`s#k(&7Hte#5#y+1rE;Zz+kNz9`<}qN&PQcn2(A&<5kZtG0%Q zcXGw}NFBiY%C2Wc{G;G`i{r`9-aSZy>UZu~3gew8G}CAez}uRWTpF!Ih2rO@dJ8pT z6kfp@oAQCFZf=-eD-!ISSBQW z86WRUwI^RR{ocj)=l`vB3mMXJrmaDvbPsKN3v9e{aPLuEDSl$+8p*k$XHmSswp0vE^*;4Pw6 zt2#@T3f)<^>WgV5Hs0f*i+R@$%qBlX{34g8FSvdX8}C)?^&Yw|X1(Jr9}peOaN_d_ zzw~Zp2lLsx#DphQqK<*Xi30wj4nn)x9`E>rjOn;k%GX0)E)a}r#!(=yZj z8hrl$&T+$X_ywt5QLm)U7sWsllzXpLpJ4An?))q~=+`JimO}iNc@7*2s=?laJXu`y z&YY9=D#$2AM;=ami&7f|vPjG?u|dAKeqLbYik*`Iy-Bgr?B5`@Z)Qlx;Vtcg?SJn7 zx1hsY-e<>C6z{KtZS%13&VH`c4$uD!e)Z7i{~=NY^Axy(R8+~dueX6lrOph-0le$9 z?5f}`_Lr6u{iy)&cV@*uJEq4#t55V6W6sYTEVR+>MR*8q3u8 z<3g;ry_JCIu)&E>W0LX!y2(7=%a>WX)h4uHeiwnJR>e`S^;es|usz;!YK-X!UH9no zk5pO(xttDfIinp}DBkS{%CxZXR!rIw3gaz3WllT2CAslYV5o%tJ@6+;4sXNyu7(b>J>JCcp$zG` z++&cHc7S$zYZ)EhvRoY+DBi!;M{8o?efTa1H;lL3>J(aobaU|NmW=>!?Jw=(R%dOX zr)`k*9Dw)u?wz#bEiz-fi-WR>~ zq#|s*t&XmKn#h8$w`@anSm4ALGyXuDQ-k^Jov}DO>0CVnA1B7;TP7C0VSBs@>3NLl z_^#b1_hTwY)vF9Db zxnGV`q1@LCl9kf1bI^eoN#!PXBIG>8FX2*?_N8#_98`1U!nA_Rm2bJPhgRc{{mh{tj9NX-$W>s^^pCDBhv= zt@>Da*LPJ#!gvcU45s1zeXL^Z5`g!4Z@q{j(EqEtx*ZY*c-KrDmV&?k*IKbWtODSD z^!Jw^u`N{SO!DdFm)x=Ob}fQdX5SShmm+?4h0Zq(EU@uT5L&pr!9t1Uz96+jbj0Aq z7e#7+CX>K?1^GZLwn=me{sie~Ma?lMzmIH>ch}uZjOp;6`Vf&t>;G5M;jNI-b4XD)H^l0ck5byp_H`=|b^- zTo|T{g}3$w@pu^T+b6SWcprFO;2#F?K1}`{vb_o1-kNjtkPx^aeZA71bQo{>`Nx;Q zmlF+E$$e|gqe2Ak%ab4Uu<;(f(ENK|y(F24_}z7$dC^r88}AB_CPK74>m86DKy;Mg z#P|5h2Hv*+Fr2ut;ebUP1FyFXiJw0eT4>Am1JbC6=NQtFGIzpV`Oo&&3Oc+M??2px z;>}ZRs)L31aj$`$Fy4YM%4m3-kb>-T0p1s9mt0T3YXfDO%u~D#wzu@uo;-%}4)Gru zI|c9#jaEOXc7X~xzt}tQ$PydxuLr(wYm1jAyCQzQHSIdCZ?Wrt?`%8B_UHcz<$a9lkS}h94=4V8|Bt0R|3ATj z{@;!+2hA_j{R-zGaiJtH<&Ow8^Sy$i+QpdF5c-c)V^doL|XpJLw4!V}JcKNb2E;8z;skF(0 z0Ac4KUU^l*$LXRh*C17(I^_O6zSY)^S1*h*UqSi{8P;j=<4=$XX2B~0o4nY*K_c9Z zWlYCsb+P$>w%Bdy@SaE6u?$^eC(bn*Vd1@J>8KTqclqx7wC63OGNkO_{{PFhLs5LE zY#<3cyBr&UckLV*B^dA841>$(0p5~63S93u#y~y4rPudPVdMS2?rPa(^BH8+Ps`?` zyW$Ww-e)gKJ3h>pVmZ8f5FPnA@d+fZC=@JX9&eGzYlh;}@#p`9=lWFJy8iuP zbVx;K)kOTc|Bph4x0c$c((;jQwrf)~cy{81h4{XZj7qPYRUo3G{65e_gQ z4e_}eeHzAlMK1xyo1D6(r4rzMi1*j4I~FmJ&Peg#%syh)E-N z8Pnm(9V?>(UXTLCi47gz8Xs!@8IZm@?YR&O@6(9`*Wd=pTQ8ILf%JiBpGtLr_rzr2 z%&rO>Xzr5pva_BgLAJY7yW!!)9owGI@NmLMrRDH7KPqIvr<{Fa3VZ$^+tJ)IY%WAz zfcQPtO1pKX4}1Q9W|Ng(U_0yG{~w0vIDr%2+syot;&aSrZ~M2~%MHfyixba7n+5yM zu3>w;d0H6LA=~$HX*l>m8sNQ}4sZ4QW)INp9ZEJf#KPNTXKFBvch1#SwEll@xcfqB zfcN=@{bEnAz;ACS&ff>{=KtA9d*0&hRItHifcK6wMwNs(Dzx~T?niea?CibpDc=sV zqA+<0;`ex8)xfu}*mxhT>v4}hFVAw>TMN;#4<|m`LiwtVlg#5C@LkuU=P&~wCmO2m z%Pk#X|NeiL6k|G;`t62~xBTt@*`xnoN0);PB9xrb{{Oldg&QjeNf(rwHG>@F*7MvC z?*F@XM7V7QIY{XBF17QV6iD$Wv8lNy3A%sP%N4#sx@Fq$!WNK&ra~^b0GdZv;$jyeHJ4AcFFJZOc_yI&mK2ChI-n3_#sWYF0 zHh%Q$bBe>CAjLv)GRGgK4f^@vF?g-*XzW&U1W*7Dndt5n^$8KIF%i&!s{71)gwSSMV zRB~FFw;%I(lg5wq?efR3AfIR!#8ym%vif6O z(ijN~Z?8U528{RoifKMD-s%nEbzT5(&R&Bbqu_bV%HdQ(`ST>`v{LCBxIxlWlX0j8 zcvFOrG>~km&~4k#)7K7Q<9)=j@%B2Wp(Ra---)NwI~s3e<6XGf!ceX0TOF%q??6OH zAWnQ+%cWh6N}0!d>xp5}rl$-Xkj|MQ+F2LF_IMMvEMQE>d!ah=pWRz~I=pq>jcTEI zUzWc`#KL=Y!+;iyH*a&07mWAInAT(`fVX*;vCFONHc*TEyBbH(Anm@;*ahQl=6t*s z?*9+i-z4`9Q=#&?Klp|du!|FG-Tb*}TPK&4A%1ft&JU{lVHYRy`}m3uKIdh*21y^$ z;e``ljd7$@(SOL^gU3wHH1ad>f%NScKGgRdY~TOK@BPJ)4x8<>*ZEb^viBM~ytOaO zh@*HnKikWJg}1;Fvup6~?Xkxt8)3Y!-YvRg3Gj}pKg1=TZv#c_5N*8eWMRaQbNMfKJ1REb(FBQt&xZtA z4(~WbM*vQIr_U$`d7o!Kd+QwU?v^#duf0Fcog-jX@5J`mTO?kUAst84G!x`g{+|D5 zwQA;njR)*Oy3*yK#Syaw(HwL@---__2WgfK?Sq%t$^)FV3eqVr>R>p?L7j23>m(E? zkfmV4!0VwT$ob5L%Ss>zZHn5FElYX;@!pR6*0q@m2^S7MdGi~)g4`rk)12o@s24>1 zwhH;aCk|j&ko&V&td{*OK>lAf{y+Se0f>%bocQ(}?D7Usx8G!DVBx*ng{vCITRQOq4e!A> z^CKew-qulmrCi{OUCj!go{?ug+j6@a&~vTG3$;2mP0T;4qq4Lv`kSthm{ z8}B*m)n7dLz)|0g`1Q7YUbl8LHr@>>o|a|_tcSNUqT>Nhd}4}gQ}vfHpS|~Yl{wq3 zz{mS#Xtbr;;A^(W+jv$OLpn;HC_8o^qT%gChqqyO+*}mzGa8q8vG8sVyFMEpPJ||# z(1sJaH&%XuueS*8&)``nL4guRmYg6DBtd>ZpPf?$c+1LteL4mjq!R5D6BWJD(C(k5 z*H#B(<9$fOhGbh$s82!sK7QqW@ScK=_gJXw#?Ov|ESJ6W5gk)F@$Gsuvhm(F=JCG2 z`a-Hm9)5#FxS2yxG8$uhya_+E7}GH~ZO_p^ueUhT;l1F}#sC!Wa?d0lEWB^>`>%oV z{_#@YAMXDj4e>Td1H2CxZF>+dOo5gKlzA!kCqZ96Z@Hxg@a{Bh3G4@WYdxPM7x*9= zvVz>Wa@?@-exPsnqIPt$&I0lK)?Q7xN5;nc!CtE)SM8>;9NztijyE{*?W|fMH&MZS zaq{(DU(i4o{<)Gg8XMke@a`;E{TIZ~?$W&Shi9>Kkp45} zZ+q25SuO{CM|6;J;*%b~r1Z>*`6c%G9^=Q0Z!j=HQaRXuBBYT0&meh!WK74$c^lOK zOpx5^@HWxQ`)5Epeq`n>EWA%=zt{ug{l-~jGmLl22a+fsSYpqw;#<9uj{?>1vzcoK z@LpcD{jDs(`<2C)(O`i0WlCz)hSOBYY^3An*Cp6n>=%M$8j~hD>dA=T?RU2-^A)hS z*rkTo2%p@`dJR$yqC*iUzFH`(QGFKkcuy@pGtoWFKm|Fw+i9Z3i0v!L_;fjEMsygu z{@n2RPyfGx4sU4s$}ed4KJL{ofQ9$;g<=qlw{vkPtwGXEKNYJ4@UHI8{8}qSfjWsB ztAhaENxSMI~-UGD)fry_+vvQY`mX|WL&LzI#t()_%*!PD!X(# zHs05Nb-t38o5^z7dl=F26em8;aL!#qHq7I_pi?PPih(qP!MS!>AD;YaufcK@!6e*2;RA|+Yhq=NE*m(Dmd&Cyjey>}J`004O zv*qW-#=CPG^{SuLbe6;WBcfvjC%)dTkJe=GXCCkRTW!U2t}<{yI^EBDhUrDN$D3fu zpboo)5u`X-Plvbhu|5Kd_o3CHGqLb)^Zqk?JCM%Y>}}PK!V@o?W1zb;)4yH%f{l0W z=EU!(3a0ArAbw7~l(dE(Y`iDa=3S$F;A1(w?;<(`_WgT&8B3NPUALNfypzx0e>JuM zfA&VmoYA~f>i@v`|I8n^8PQQ2c06~i;P3pO;U4_|r6cJ7z3Fn0#kLu<(HykC-ckZ9 z2Oad5Ai+y)h>r^nOmLn&NA#AbYJ08@6Cp9b&C+c##hcVjT+cFXw2=!y_xzvESG}@5FH#F z{yn~D4+=hqX)?bDNj?@jD>Dp#f<%mtIpjdv!S+k+#Fy#28PTDCLUY!QAE1MAN%o?{ zdpV_Q9L4+7J6>@tyj>K!Vqv@mo-}*Icu$Y_HJuCael(%l$}yb+x!b-wIrJ(CT79;l z8Q$KKJ(1gy4DjwK)0x4WMukdy9`etT$Hv=_SbxQmVy5NWnlJ=%3`+1n;=)km=0OB{%u~OFy5Q! z@Lm?aj&?yBe0xj3!D2Biyptx~dSJY}@7d8Bq~el%o>>5I&%*0Lk9a81#t z#BRS_2IH;ST^+v<;2pPLlw7ta2J(00EBc@ufcf3}=Ib46kN5J{dn10frE88k39ZNU ze@fZZanDkM<+67KqN4{VzJ*#Z2s+c4uOLHmUxahrxR3dJ`KK_b%|2GWWacDq{DmZ&HA5c_BP}_DuRXgvGaLUczdfW>M?CVDku1={5Kd*I39Xw zYs5u?Dod3L-NEq|@0u$Ga{=DE`f1Q%fcNv(=DPEeG0;k5%~sh;?ChQY-tp9;jv4jK z5kIp%D#m3;v9tHkqnIe?d9zs#@6(8mF`W2*D6RUO+rvEGo#m|tsfjJPcwd#zSah&r zDcj>cCw&h?It;|*`+`zvhZ8;N@HV?W`OondjhjKjSa>(*Jr}wI@YcHu1;WKiQmOLj zAi(?PfbCT!A_bcN=)%tla5%AXXUVrY0Pm1VUx7k^_q>D|_riRrkZ#e6yGcK=XK#+0 z#?bUWDiBB`5kK^}$c$|1yjX~@wPyCM) zQ=gQsIq-cK+t1!!x>~PgM2Gj7%gd3pzy1F|t2ZnE0W7hb>2lDjqo?E1B{oY}Z7x<0 z%DJFD1>ZpuUU-IfgOm)nrrQ|ELFW?>?7gT-fu?B%juJox*;aW-Tn^+Q&J!m5@PM?g z(|_H5wHU}CsLv+rCiW70kjgpzvo3)=5AiFv7i}mh#a?17C9-5)3Iys|?N^9%Wy*!`4;pd=V$ATXCE_=lGIY`!hE<-xbkZ#!U2hk=-{&aX-Ynp#T z@#gx#GY1Rr<6A~G;7{yMEbyV-|Ch$qQosQkByByy8cszD6uHsIKF0bAR7v}NKyI84GQNq9kX~SjDLv$60FXiRs5@ph@wr`_JF8sm9N6yUu{)$>QQBn1*Xtn0lPY;U=mj*P>* zw_I7h=fVKqgNZthq{bNNq1lczb?(^xzs-jx!;bI6OPUeCPSYbxPprc3|Gj*R3%0HO z&T`-X%OW~f;KWBh5kBL!Ec19r$L;WMp3cAoY4(at(>^Qq-`;xLbbt{ZKix*^EfZ+j z+m{aS6&L4}qj=XBrb}VrEg@cg2*z9Bg#_&b>6{sw;yM6tefKZD`({!g11@`GF)*B1 z?-nr#T3ML=4%<-XK!ui1!2An=%{{R z?@~6D31@E~I=n4Y2a{2}4^G=8iG_FEw7WFCOh+peMwP)`C^8R06(!0)kLSIprcs)`Gmjaj=$&s|0gi4XoDOSOqYY!EdQyG z=AaAHWfZY;(B_=@RJi|7{C$^p2dP>%$#oCt|E)Z?YJ0DwK;)g7pEtivf^@f8aVvl& zmdE>dvNc#@`*bIQLeIrOmB;3EwXVcoV)yHsa(cB0kV_FigTdALs}^D}vEgcW3x;@Q zSgt`zLUaV-#COH|=6T7d%;zANdgBTKJ_d47;?(6iPbS$u2N43Y8PYM{m>9JPoIwJ3 z2hrheC!AG=;%(?UB9Dc)D`6l5#+&QnHyYmc*@ANU0PoX-KDAeuQ=p8dO)t~H3DS>m zmxRCvq?a|l?sfop8&_yQ3_chGwVPQDD`{inJ<>qFx^8eL`61$$*YGCq(`;~7ZP&?u6tsXbh9uI)GiO);@sk9i#?_%NXBsFZjzuz>B&M2Be_C)-+vV(^eMX~XY zpcb66_{n$t=2khM)lc?k(ZA>yb;}*0Md`1e0Tj8Pf5k zZWuWr9Y}|_O@m7$iud);du6fk-gnTg1jajhzB3K);o0|3J_mSv`$z6AF`_^>pKYPq zfcd|u?rLKgZ_#+IV*vo~$P0HzlQwUI`X@UY{rLhh8-m@%ooCh?@RFY+ek*QtF55GO zjrZ+4aaTVb7iYQby&ciffD_-j7n1fy;>_bM+hrFnIun2XPxzu9VAk)!{>90>@0%IX zAs=+`S7#nAdk4_ry?WcJe-0Z9OIKTy!9Mho!RwjNO?R%;SCW+Jf44@w=F50&Vx2b6fVjDSFQK zc-x)c#E=fJ;5kAbk$=DcNB{q`^iR+rMbPCSC)?O!bct2nEuoH;gF+i$yElRy6nlQA zGkgX~^5ons1+c}QJ`xzv3sInn4IC@HK?SMYI{!S}|685gDX|pfAdXd^%dH+!q0@7k z&e{544@h$lY6{7J7bPD@{4#^=cuiMh4@f0A#15v0v)%*gIfxDsocJ^==Ir+P4<|@J zloEyBFhmE(PT-_>YP?+3|_-VIoHGe6Ljkjo5X5+#w3M{w8E{pd%<15B(;}pk9R!R7lw2MZJx(nTSRM+Lh0~cdws({{r_UmJ<3>k zAK=}f0yjvqsf*Xcc$0u;r%{H#XkS!YhA&XcHu_K>SW>S6F=wm<*x&9j;z9dqUFzgzm!@D8EF+kTJF1e(34 z^LQ#@;oW;*Zaa*3>DD6JaALed;a&{DThKdDCcuUQP33HQs6Lzoh1`nDhO_t4LGL|g z0Pou4M^2tu90NtKb6!AxijBA3y}fc3rv=F&h~J65nid`P*u_cuY4T#qQr5$J6{2Gw zPJE|rZfne&%Y1QiDYN8|N(TdXZ+XA(Ry(_e?fZX%)j`H|1jVm|{=Wam(ry1g!GZpt zN|%E+XkWgB=AcSJer>EA)TUEC0#}f`d{)vb$l>=_(q@1L>5FRYncZ_JkW>1s?<(*& zNE@K9a1P?zWW)`D98|F1PGm(U722S$+}Wdwor4xhjo+*ql^{DJewV(rsR71&=Ym{X|Nmu6wU#iz``6-GT>HWE7WLB%3dI55 zp0Oi6Fy2nWJt=VipY2$A^@DN@WcVoYqWE=eyq_M;lXhs7Bx@snx6V%w)H;KWx3+ou z{1z28mczRp(V>YG-?>Cv{^26#@$Os7_q1*a{s~foRGZ<#{{I6Hq&1r_U_{6A;`~Lq z4YUd}iVknr?`xi;cpEM(*TTYE;Ly{9Fy5=ndT6`1(6(hS;1{I*GsKUfS5-*L5xijs}Ye;~cqztiw+1wP(#K~w(2>%Opk|9}5onI9uM3V*)t zE{dgXZ$;AK?UI`oj^b^+FB&}MN+1M!1QVu%pPn9JUK;}ZwrmD}rXJqz0pmR+&rid< zO)f7}4d9*Qy7k=yT?+KpCTzh7nEyZOQZ0k=?sq#}4-Y4n%A8HTJwb)c3k(_`q+{dV zeN=r0>9Qo5jQAzGeJ;2bg^hQ|#>CF+QmltJs-q1jzSD765gk`Nv)$Gmq-F1|ba*?*+`o+C{dN5c4J^C^*UGEGc%S&C>I83Z z5u>zz8v(rgl{ZP&a zUP@}&XbyUw^TPlu2lJHj_disSu@{Cfj3nS6v2)n9(=;#2lkIbmkht%O zZyO6^J-j0k9UM6EJ?*Z~65q@G65FE}uwuF|{shV2#<0Fn&zbG8kO_Hj9`hlRIF^0rDC?@)<#wC$~mx)rK9S9$x)%oX@@F0FJj}}li(tF?v@z&EaJCeYQciQY;3#@ z?%d0ES5iTFpP# zTWq7l+an|N7m9bOm7gva-k%oE?1%9#XcMOmCk#~U9fSbhypIWnJHhjo&V6fb@&Mjn z#(#Iic)PUMYMTPQYhUxLnqHzpzK2^ZE?8q1Cl@NM=bjuDBYPr#+hiWxo6yBBPQFPS zi%~YQ9^Mxb9iMUHJ82|t$h(bsyf@@}KXQJ}!10y{f1b}egY1vDJ&~6Y9qSKtIPA%x zW$zd|yxr?<|GB+&&GHpGSa_Rk*&qhb|NHpf)9_B7Cg#Nj@ZL9H=?n!tZ)xUduDJm0 z-rn*l;)9R3h!U=3E&+IppCp;iZ>B>1JQY3y8?f=tJiW4Th%#-`!pJz>;-b79a;XMY@)!mV!4(g}}!-i?J(6 zF9Wem(kxN(a>Vb+llRk9XJc28gWB8dB@ZaFT>p>i=*Nk#^6CRVM@{A@Nd4dZE`3~y ze?XeLwrk8&+?4H?Sg#My8PYL1qkq7dHbF`u(c$g)Dd3;yEqSlqGs402f-A@rA|2ko)$jhfAbsz&1BSRPCi@+#(RU*w=44QtXDyzI-GFgi@z=w^09z< zyvzJ&*ms!WpWZSh1`Ydey1@2$M;vENhoj-zO%cg7ygBIb_BlmA1*S*fQ)_Gp%$r50Mh4;KH@uM)_dEd*( z(_7=ktop_P?^<>xtqC0>d0rI^^+I42}YCcPH^@DBe-=3kp|5u%uS-@vH%WN&;cSB4(%|#fy|G&J6OQJ28@v?U{q9dD1eCieP#N^BL<1MiB z-h2OX8j6!Dg_bnKx6FU`HvS?_I@lMSPq6~U$>06|e-a$y{s1aSE{YtqN3JUt?f>iK z*0W>fpnWU-=fPL(&i}lDd_lU>QX!|cAO{J)Ty8SQo(Mf7kd&)H{|~*JrJxORP|lah zPCwR0Xu;Q2r>)n6_y6K9*YE#?y~JK|owWNF&1q(W_?^ytS+VvRcK<&xI&J*%3*%j} zlZ)u+rV^i2YtrK0fAK(CRo}bDs8Q-CNO38$nlBX=Gyf8Mer7%`I{aRYdgUJ>SCE_( zc<<^<{e|NFrcZ?p3-8Rcnr9rau z0p6{pqE9XWyfwuhYY8idKy{;L9-<}Kc(1w>XZ-abuUQr17bgAb-tA0my!+YVflr}!uwMDlXviVYk10xjQ5=fH*&~$2brcBuO&jR_kz!U z0C?9vDVG76&afK!w z19^t^t=Gueo1Fr0pCiWP3({b`E&3j_V&Q!xuH_z#w{!9t@&#$~uf$)#c(;#r9oP*% zkam=ol^F+kZxQ0DRD!d2;{ZQDXpm%W#IGM+91JyhH8)H&VB_5FRdz&CCNZA6sr|+GX-nfPc zeVXhN;y_y1$L`q}XLfBnwXqd$6rq4L$+zIp~?7bkh54Y}?_5wlXn@4ces zs-X4Q#mSUOHV*dWW zV>3-UMp_-!lEBA_fBS#NZTtU;3{;T(6geo6|5!JggV=ah@M7hl^mVzb;TNPA+~puY zkZ!+ct$ho~LA;vI-GbnXo$dQwEn>T(p<_G`QglHMGKjyaLIf4$E%V&5h|FN9Z}S`v z77gqiwEn=1Ftn@J^dsVzY$Ikg#f_bVL{C-i>gyP1xF>dqhz?dN@v&{axiM0o{v7ny z($>OeC-n-lr#rk?X_p|=FR{9s+I_U>P|RCi5g$#iAo(cp-q)s1z90>*ApI9g@nGQ% z`LGJXc>hY1af3gx^NF6n=mEf6#Ue1Q11zyd_FX?@!2@X?x7Oc=@y@&T>WdY?Tdgy; zXydM6NceuxWX&(^3i4TBSN^AnZ>9o>Uy-EZjlwtB6(kRS%-W0#&u~j@1EPbKN__Ve zLfzf|#dym)si94}iH0k7k~8PtD3E7*ym8y}Y13iPlV<+-r-WdS}*{o-$OotIa*+yT{hmP3UyFXLLm4Bec z$rZkPoLG2Ie_xsikWLinIy0dl!u0q5aeNx2Nyjg%M-lQ-WW2d4@beEIX2#EzM_reA)*Y2 zw+W(SE|vId<7=|^meG%Qc13#HFe~-i8@Ie$X3zQp=I{SMveBj^VP}@)-~0dmX|Wml z2hjhEP~@QfEHmUUNZ|_dBIi~m@QngnuC%BkRIRtJet zhK5As?sw6U$jmZs4UmJ5%bU$A13Bn^cbBi;?hwd3`RU7B1ne_Nibp#HN@9db9*Ey3 z6E*kBKI|MMDqoaiGE32n(SFyc4sj~+4K=ShFL{jq4bnufo@J56G~}Q%mqo4(O@@s2 z`=L9YQacNpbX>e!ull<|5~jdAw4t;PU1BY?1%s#~>nPq4(~nE5JLL(e5 zg#hnG%63I3cM>77O@o_l0p7Dt2rFm-yj2f4D8~W3XA}zJCvc$1H-}- z4OIWVoIU&2R%dZDeS^dm-%XQ_J~MkGENK3C$SybyQM`PsuwszmPKmjZsWGJ-gE*$gJ3q9TCLK@bJ=*R=zMLpVfCBHJMHxvb-aAwR`LOVI z2x~t8Z%#Z-e@EVX>-cQq(gW~za-5kTu^L=XTt0bE1>h}qXnqY~Y zMUjIJ^04hja}ZH>@hq$yG}k*|Gu$98dKyJ;kZgCU$h-tOs7mC$O9nYZ0Pxp*7eQB>u6f)TtVIQXb-Guu=8-q8r#1 zWM>qouf=w4hN~b^9n|8>TB&HaIh+0l$#r7)?DV%ZY>*Dx6y5CYV*VV|XF{6}j?p=q zzx#g)3cMq$=SiV>51+?LVBvj5P5Ks$x8=s6U2p}N#&yx90^lw4b@sROr-+ck+gT@9 zwnsyU?&^2Kc;BfOIWY>B*x2f5woP|Jq1ChZMLe>@eqz_ZQdqvJUY=x*_+1WR-~JZD zeqy&#dc_{U9gK%Js^ck@_(B(pUnt!`Ki*;H4lI)zG;EO0En3GppZTx1#7Q5fNypYw z!LWhLJM?JD-CUO}$UvJlHHHD~(qmc4G{ zyDK#4c+>6|UcH};w-^Q92OQ)NqIeg`rHf+W9rkPB0F3t$yt+S}y=MlFPDKN}w;$>_ z)EG~M?9a&;gnByLIreSkJVC}lJ^DfN4 zIdOi*o+cf6b~lZG7bl_=c!%5HQbX|$PS`1eiTA5oGTw~`)ab(d_=Ah5Yl=gl7=o|n z$ZG7`+k0de%glKR(m}+}@ts)wHErzLyZ>W!^GPvfhQk}xF-Rr8wMmLc_uA2qwx39USo9XekxyVnGjy-RZJvC1L?f)6G;s1}QK>t6RA_v79`ZWHNgCsR% zv2u{4_32~q4Dz6s(hhium3=epGXj>_DNdZv&Q>Bc6{J(a`YIZFuR6;b{st-hlBbg$ z=>HGfI6ta99Sj{cI~J^{jy;3KpEUf*dPtZQi};P~mm7V?g*}7xb@`=uOqB8V|4|*g zsKh6DMLu%<68cB%%VsH0R>jfK|BvQsIf>{oeFcfbkI|-s--RdLNetdWlA*vmruyC* z6z>cXw%J&CoBvXJ1mk_Hd6bN|S9rnZQGmC1I-l~#Mk2IDvPALi%VfUneKV&$NQM13iEgOp8VpAVdac4;J7$=n3r|F270qSH%+ zw!URO6xkXLO)RSSQ3N??WJmBTSCE6kG8b&m1P#)1n=#_kv)DOE^=lQ!+jIfaQp8Vb zG>U)I9~vaR#7~>D-^emt1*weapcdZ=0pbs$3jIs$3CX4JpxZR`|0bmSnk9+MzyDA8 zK${NP35nk?NW~~n;GIxVuZZGZ^>bJe3-3?Ddn@53cC(H+`GEAtn=jeL0p6__o~tT$ z6QP@p+8xyZ@2U58=V82CjSlKN1H5xfcF3RK9|C0`_+}g@j6GtPyInN@<2Wzr4C1H! z>9AwRIQA0jSP|=Xf29n=;XNDCK`lO(y0{ene)^Bt)nB-AJK!k|6=Y@iV&!*o%-{c4 zb1k7o$8&Gh{r!353R0c|@A%;9e@<_m^}nxxg|`;pWp^0w?sX|%aQ5~dA8XI>5#W9Hr<|jJPYBfGuXXn@3wHKaKIi^0l#`eA z0r3+ZE7tVx!Nyzf<@tGXF47E#H>yLQN_=y>SNrb$7w`Yw{33Jwa|8|d|4CnZB&T(R z>G8(B$)`<6mD@_)-~0cv6nMvpG;pAJ_n%xVhlO_}%K`G2{Gm8m5*#5NZXihNMf^NhdK>6{$Hu!~a6uw>o*cvBjp`Vn5?^KNp5txH=&!x2 zpw7;GGwRv<(|My!oe9ieoTSwk)1>3KjM?!2M^vEySEk58$vxbIXbxIe zDyfE*gN~1`SPUPrlaEyKgDXgXx7X*T!4k`Q;@$bvV2K@adE#LFG#WbY6zHk|mRPxJ z-ebXFiB%meQ~qce3OO$f9oyN2y~KJR|2*YXAWqtX_`MXD&G9Y4K7-`nvhthr93_U! zK^};XJyhar**kM5Po4f8wDabz&d+Mp8zgUz={TY}eS|GwVh=gld2yv5z-dGo+qA{4=%@JqQV8v0`U zJs-xq_sz^Ee}Fe@rXi%M5DK-`kKR!z!N$AlQ~0V-Q8Cgh#80eG>s?X~Hr|ff3%PVp z&1E>eA0s-}QHk$$Nmu_SZ~E~*dO7M`)h8M%$X-a^uLsZk6{PMG+H_>U>NWgbLC&MV z`$R~BFN!ytN0~Af-q&I(@4$GAzxhG_yyg0a)W@;_Z>4D8*tuZ5^)b6oJn(rmv?O`) zD2%t-dg(E5fOqYhY4#kEP{{4@h}fb6Y`hiEZ5hbV79nj%{L&BmvfCzO<9+c#iI=I` z9EQVN0nu@RN_>kC9C@kzFQ&IDzFdRHzX(~B; z&!xcoxY=@h6z?^ALY1)a#*ajL!gy~wa*zCRqIuR0NCDtI9H15bq#x}68x6f*0dG#E zjTyt^t@^z=8{7fjL!OFB-&8`Oy_)-nc^_fpO~_w6Y;#SRCkz#S?zcB zo?9lQVMY0TV{^d0g0qTL@HS%;m2`VK72^tjJ>ODw9Rn@W8C&&ws!meaq)Zm;&S zWbL4S#ZF_q!)IBEV5YAiy=$y#($QC4!}0S7`GGWb3cS-v-~M?)iktLN6ASP8Sr&sZ z-p3|xkoW)9YnDDd4)8Yf@R?lpgb1Z&441tGc;A#{*Mjj*IMjSS65xIK$bj{d*&)#O zaSlJ0B5b^u>>u#&5)>z)ej%D?f;dlLjAb9 z$R=xv$>mgRyybTs8ZNS%MMC||lLmQ3gR$}6TBJ}LUCwx4kjf!CoT$Wi?^4sfCq?w* z?OFDyV7mwP3evo$zUyG}N2bTSbflUl9i8l>)d2})yj3aiPF?CziQ>IM=YR$l-c#|D zyzu6PL;X7P^wuMzaEmp-djvo6%=8%%>hd!1cvB1R|4)hhBQj)X_@iP?r(OLNiyz8_(xi%Lv-sdfTh>jX6@%4VOwE6yp ze!L45R;aSp(r`G@#^ytf{d=az8z)Yq4v9uJr2ki;z&nL&m=nc&X5$KVEW9N(Wy4^+ z&u^Vg{{H{2pKXd1z}sNet~#q%;BaEvl+CGzXh=Tt$}Bj0^PNgOb^zc#cQo49%QX~o zN$$GxYYKb3r6hZMGH>}Tk~8ABCmsJ;s26*@b%lSj^4oRB%ii-49ha!Y=QMfoX!;QS zc-J@d*^N)rQk?i+)frD_`u;z{E|?}AF@fX4dIf*`e`e|bbtrOBc8&8mnuCU_*$uFA zkcdtGMfeR8u5a7OPwWsYwri_`92BnBlfDcrvAY)ca>#=H|Ac4`4fukz%XO)mTp$Nk zjV)c(a4Qtj>gSa_W{Z8r&bEzTqD2nBFVjW*oL>BttTn^FVrR>)ytg`%BMf)Nt|Owu zgi3tGy{Ws}dg$-}7nOC!&oQLo3)1*3|1VdAn16{C%A`rh#v8MCY(7n{Ahjv*K70Lr z8j82aj<5Pycw3wi;)OquW=-NCzyFsCd0w;vc*g}fo4VB#q4$qf#J|@^Lyzv{O~7A} z8u7nhp#|{vIZ9kwni2}_GupKCzAiT24;;LOs>*+q1tEUlA32BX$YSFyaE9y0RwXWm z8?oO*bWCUcIljmbi#;A*rvDQ=^>P=#rFW>~-Jn*Qbjsli)8nmgcAq94TRz=;i#tjl zZ)s8Bea6)z7{zPvw>55(*myryPMw1+^RF-o&3b~c;hVVY0_aV z@6l-b`|}n}3cRxv?q{KRo6K?3#lm|@V&^!Fw{39^`TRd&BfrRffVatUe6!ypA~g10 zI^4NB8q!f1+zK~HGy8@P!VOY{&uS~x*ih(fa!^OzTx`5e+`Ds&ytzo{5Wk->8gF|A zu<_mzG^y_Vd=|suZG`A>q7t9QJH<9}Df+WFx9NgKr!1)BeWUTX_r6n|Oy3|)6vxn{ zV>qxzDdP8dYd!_ur+<3BM)59bGtt4qdwb0g8Sj!2`tY_duC4IR41xSOp;#MT?Ee3$ z=l6@}QUyrX69blQT5* z|M6C1-w5BB9&g-obJ}#MMD?Ba5`*}_a?i$c5yz*%y_91c;Sl)o?>~(88vy(N1{68y z(x`1ToP#96`+u37n{ik<=%(r?$H!oaU6s!71fTymY5(=K4BSCd+wLE5vw;Y4%*O91 zYL14~w%3=#FG!W%5q^IJT(P^%Le2E7R0!mrqSUtOD)xw7oYRo?{!(r;FT^jG?Uvc{ zW7s=LHA`#X8=jXWG1{+J3enL-CB8NXBM*~U`YTA?)$0Uxwo>0g+G`&nku>SU^cCcj zkRY0L-1j;$cINjJy9+4rzL+HZ&kNFPG#X5>@OF?$4Tkal{wtM?_XbDKAMguO%Y)53 zwml_60gH!K^8ns+MO;TU0p6=UzR0HlyeC)rvT%+ELmy0dHF{#O@s^Ga=xc0dGwVhC z0y}rE81%r#+i8?dRm@t9;qaD6bhuNAFU0qvVd5kD@s4KAz^|yFVFzg{^@-EmK&HnV z_bQn-9r#}_4St^>)u+Jw!Zv|J`ICZiePeYorx zX-g9ks(L)xnFH`{b9pWg<6XFIL+g2fccP*oajRbl6t#Zw`xPA6737Aca~liOXG{+x zesw3GJ@gpF##>%`S>Mbneul%_1<|2RCBC3YDOdg=`th#qPq{DFO+y7)AOCQ>HY?NL zAcfOQph<`3*=KqF=g8ArJqo6T*&Km&l;v_lVNN~MHR7F#)&L6I~(68D1Loj&6 z^f2OgRfQ*8;XO9qUT?3P-Q-|pIJ_4kIzp(#r>1IT?0k!Uytz-EygSTB9q)s)UDvU$ zc42zF)3(s2gN5(Zh5eyqymcw?J~w?Y5XC!kJ!FW5cg%$4N_g*0!?tHDoV_>IjIM%j zZ{eLOxs?I%p3frbKK?8kk{McU13zyeb8O+}Zh*IQ!leVp!RIZlIn9;b53#eiKkurb z(-v)}ZHV8@iXU$2fB3wmNI%ZA=UhL-z5jO<(J@9PzTm0J1Ve55`+xl#Jl4efG<@Eo z87@^>+|T^||D7P(bSNHf(*niG-~OM`y3zlSctHQZkRk^a6x<@8L4x~#uYs}%D$NF;ljbR22D*Y)%wd5JZlz&k(SO&vPk@?JKZ z4GZt2<=2AY9i$tAPstmk5O+lIZh*IJh{3K~!9?g%i{5k?xMH_a#cW6&;Jx4zr(7k# zJLz$N#Jk-gkZPIsuWUB#C6=hW{m``#4zu})UzyKL{jq-R3Nrgn&@S~);tYqkJ)+|R zmH58VG9j^sZ*~Ym+o*LYA8I!^ms2_vxO!d+0{BfOHPpSHm1Nk&%5*! ziucu2E&>+bRYIF<;R^E5z8UiAt(%E!_eTP}A2pX;FG(Uo$%Rje>EMF2%`vKOaD!yy zq%u+f@V1=RvJqMz0=1OsEm`yld%V>d#}>|O&TsY#@%tig!k_#U8}E&!Q?tDjXEPk$ z?-3nNRO0JCpP@l)q95;oXT0^%gEUl-OO*%NvX3%7-ndFd+H_Q`N}d0Eyk$gzcdp<7 z9>qIauY?r~?{|CEcwoF0n}=QC2FY74rYRNRefUi>$IE;oBxAJ1$@xVz6t5yQ1dq24 zSGayn26ziTptE;ylhm#N3GVBy`_8)O8Jw>Ga%+ydi0>g?=!8{jQ3soQS~4kzZW>Z!X0##?#N zuEW{@@8K7>M8W{xVgd^YebS+j%9H#9Z;G+;{?Wsy(4@t0rh)h+Sy~j!W?|z!lBJ2u z3SzwM{R`3YgGzjCCFKfAF7)^R)<(`eIuW&)r`phNYoiT8;PH-qOrO0UvrY5UqGKTQ z$!+HY$$$HQ6aYs4U(o+ArpQ4z?!4QM<{+HdDqgG{bY>_=4qjp(MlU7LAdg+>Q@I9m zkhs~MYxaSl|1WR(kPaS5KYTMc8SejA-`lGD3gn<=PIB8<0=QcgiT!28$Dhyz0hgQ3mmPC-4w*mx`2 zxXfVzpQ|__eit6qzJK{;Bj!?~xoh3ozC0F&!&@EEp+_Y?XUzu<+DGWed!6UU%Vx&Z zPmo5CBoENiyZF6`IxRZ*PCPcW`@KPGMuB(HTGfvz-uY`kb7A3qbIcKWBzsEEP@!P1UY713=M}YUc1)}CwOM;

`qk&3%TwfI<;#bp; zcdPCD^ zAv0mD98{XZ!VNb_wj=%I5qs?X#^ykfgW}Gmzgm?^gdA8DE5%<$LksE@XW%zT&33n@ zi-S+>&U3pN^=AY_UZmV%Pc`fY>GT=5y=!*yn|ULC!jE6Rea(s8|1VhT=2&%`@n(?O zhz>(4@txO9c$z9ne}j}L9u~u4NJ9mgX_cRNc?0wJ|DkIOY0`0UXeILg-*O7P@9eGJ ziQ*k+EFpx2_k3SJJ{a#I&IvN!(*3GJ;Q;R^)%-%gQi#yr>MhNs0PjnBdHKo!?}Waz z8E$}g|J_91SKJ{GPATX#e-<|0VGAB5bsXb0V@3S7vGV0xgk$5qZmuY?=)E+<_5Trw z4o52SRcftOvCJ00Y#9G1AN}7y3D1u{cNtIpdQ03wt3mr6gUpY2$HFhP=qTI~VD+_% zTtP0Q!234TIECW9EBTE87T!Ik?m{r$GDe)_>1~+`TYWUZJHq901-`xI%%s!gG^ilc25#>5coPgAZ+r74$Qv7Pkqrj>LPWXEP9lB_?8+=-tg!K} z`(o7T5Wsj}Z;2y18mPo4@>2ZcEnfPwx1aBgjYfBo4Y>S45^V!AV1}SYDSIh{&d&W-yjS;kK-JysX6}gJSg%|8 zxF$Byha?Fx`yf=~dep6jT9q))1sBfoiIrHP~yYLe& zI_jV2P42r!#(N0`-ZwkHHlujQaqZ{B!do?WmlTZmW8?W`yydn;Mq~oKKQ4HB#yOG* zWw*VGa{*^>B^K~E!+5{m(Q2pG2(z)w)Ff{My92X%AY`k4dMt^*N!)m6C`02Nu ztu<4^#yfs=!-7OlVTLPC+z}m#RN_ls*KJZ4Pe0x^#X@JH^VAO~y7K;f|9(K8>HGhr z$;n63oNm#DRL0$Vo4a9gIc*3&cez;z7_W$!z1=RS2)O5 z?C4xAI}MN63zl+}XB;9zKJ|HJtzd}_Gfqf^`~L-TXJ^U44N`xJQDb`u#JyiNNMSGb z8Klp=t&x5!@n$@TU!ChvN!&*4Ge{oLru5^_87~KYMRa&liO)GyX-3J6{uyL(u+Eal zHq@8cr9VE;FBPw3`UWYqql+dT2j1wfxwf0U#IB;iyUg7@2*rEQnL`2#Z`r2q?J(ZZ z_h9n*|LD`3`r!uYO6!b@7N{V*M4w)=26(fr)V~7by|TvSi4?%QEF$>(>%tJo>(U;) zm^n7y5&J{l=8AEdc_V&B3hsBes$=6VTe)Xn#{O9hx5P#vI^?Oux8Gt>rb#gUc)z*3 z(&6E4>Psx{%mxLP_s^IfZ``;AZ929ou0Id1*a6vlB?aE4=A8dz@AAHvVpw<^Z3&o! zE67~o8uI@Cz*FK;VtgnFa_WzmdBMI={+4pj}VRQ)O zJs)?}Lkb&jH$?&69wB}+AH?s*E>iI2Y3vHJzj(=tj7^L;z4btJ3{r`2@s9_#M=sM} zL3)*cPam0~KHl1rSCzEyxh>N-NGIhBY0|M|vE=J5Ehz9V`8f)#-21SF!*?*=>b|XRqo;3ev|s~7K6-YDOs@pQyoSkUr%Wlg}XWI^2|9 z3zpdRTl!~jiz7m=Q|96I@1vo2KUc1UXOIt99MSIsGf0gT1xt_V5XjL=I5;TxPEZ{%okHiX^immY($49mH5&+>Wr5Cix;GWa7B1` z(ORk-t8&&-(2n-SOh1G4vXiDs$7TMMh;NQ3;0DQ>0`H1FovbL{Guv2ZW8rOaginQx z_xMFJ-p8GE-8aG&549Z#fhu;( zw|^1E#yhScVfXPP>;=9>i3CF|q4HB+?Cv7@14pu|I4@j?}!26Ms-6<4ro4_a1Sa{pI#ms~8 zJ}8|=#`{9qEKPTSw^u`j#>&G)D1D{+=G?c@kb|pGAAG#!ta_0aD`=3^|blv*`1&6z0c!zZ6Y6&U8qWzo;WONLCbhmk(Pvpm>MgJ0XRI_q!}# zMHp|9-WW38iGH`w?E`qbZ|LH?d5{SGWL;Zc&;ed=C2i7%@t!XgohShCt}sZ+JS!0j z1xLSXaV^5eyY3oq+N#1~(@?}uTlKW;;xuf$uNADk<}>z-;qZQe=qRQVpLg=5sI$-M z$NOHRsSw9C>UgK`_q8^SWn=o{L_c;XO*(1?mt9WTLmqEgQsDjIYj8J;_rjJPl2~~2 zR!+&ncn7ZtAmd$pVNFdOz}r5{d3JUL5fW1WHD(3&|D~Mu1K{zN=sa%c*#PfF>RmD- z;QRla=wj5EKiKFRxhDl5$0QJ;X;EBtT5mK|SD2Fl zUy!y=EP(I;G)Nq0mvMw!hC-eK!%+u%uyfEZQ}z6guajloh~H;(sfol!>>NZ=j_FKa z$zw)U?|<20C!*s%mH2$rqdNpx>CZt)m)=%2?4rKJ;_`~O&pfhX{tD9J3{5%+S;xP( zmXa$-I|{sOmOkZ2mssNUK1D3N`=1$}g7MZq;zP#!Zlg{!TtNnKJ1Z^%c<=ObJKz5? z8alarn?8)U+s(|mRRC}I6&LhY%Z5TW`rF#{?_lGdX*AMk6)|3Bi})`MI9d4crZvc4bP1Oz95<{Rnz86fFbYq_&^|a`(jwO; zQ;ofYR9>f!8+gUSaCj3C9c5JF3)ogMQPfHQ4pN%YsX&`v>f^0-FO_0aJ`?cF%I~ea$Q)e>X&xcq?Hv_!AcS(GT z0C>-_-Z(J72V8IQ-fb(4w`v%t*b9I+Yj;ZhIJn+&xNr9X=^<>qKaW)xztSBl`-=E! zEa+aT^9&nrc7kxttH>#ao8I;zI#{X1SIupb=<_eeTgP$BGN18L|3ErIFTP<7o9}$wmsz}hlTgH)ts6z-YVgbe~-6Z7o1%M@E$IB z8_o^zj;>9R6zGnIa&IY*!FzAdEH)3omlG8peX;c=ODI(NV8L7nvO_xF!w z)rcRMHQ#rN#4b*H=0dDzy~i02Z#hKAJ1X&s1j>Dh`bmHGRzH0!!#hbv&bANe=rXMhH2x<@n}##?FonI(k)?-Lc@ z8z108p{z(2`N1@7yoah=6;FL-BV{9gZ64gALJ`<_FLRQ*`M_I@;qV?nbS$9~-{o|% zz87}%8**;)jR~Jc$kQoADaw<50wYAU!PHdF0s~5r)HiJ)$FoN_;BB zN0~eRMfOg~YT*p|Oud4Pc)a1rGo>`<$9u|;CLNb=h>4xaC1-C33cTw(DjuMCyUh<% z!ovIPj7~k=Ahn&d@rLn^t*ummzuw9t@<-GHyz7YbzG(M>$BC^Hr{U?Xsza&tU4Xas z%^GO!^-!p;_>g(^8f?66JKC4HZ($`pMf~DEYfU&BW8=N&zQPCHVIhXY+Xm6Gi%NU~ zvQoF|*VCW9Zx4pOvk|3^w}tK5(fD&0n7%kU!F`e@9r|(UmUh8pyw_3SU00R*&-7L= zee*mlya(M>$#|a)rw{LDF#<`X7JQs2d~MBF7wqDMtLf2-@dH-x&{vPeE|XqtSg|(|b&hH|~ilZ93ME z;f?>^|M#!j@&Ee21p0p`iX7D1O5A`hv8k0J+E_VA*ZJmydbt0eIvfTsvD1^yKiI(= zq(-NXo#PAwUyuf`-u)dcv8ujB;zwf;zw-GH5gHf&mF zJ2p9+^bqm0s`=8MZibzMNNb&hlg;NdTn=(Tbd*tv@6FV$@YOo>=b-NF>n$q;srUc5 zI~jZVEjf+;>wNuh|Aqc{Xw%_!L>PG>eG3KNFBWzvqIjpPv}t1D{WH*W4vcqE6(I!1 z+dOCUt0_=H=FDV@L19FQ+wb;zJ%IO~hzCdD3bJ#y!+ZF6i`i}e@i}gx(Eg1T{6#a^ zc$;r;4<3IjK?+0so(RotGw8?0d-;9&*jO87hQoU~qGK7A_$o}=?hp0SKVpw9t^T-L zfcpMFZc^j)4~|sk$6H8`CLK!^LeqBMCs&Z0De!(it>%W}{Uhr9d@Q`vb1nwf0laNh zmj%LjA9}pv$7g`|lb{_d=YkugVnr9~+kpN*Wm&&G-2cCiJd<-9;GIw#oH4p86iRw; zsnhlW8}BPT`*PS`36W60+@_WaCl!vbiAb!Uv%*IJ&}3zXKyD5 zb^j89I;vl9an1hdXywLd{J)({|J#2aTk}_%blmo0^Dzn~A8*-2fp>Fj6#0R4_;F(C zu@DU`ypx7+mec~g+0+*9h4J1w$5P}iz}r`=;n_#sJ4a+jrEi>iapK++_-p;^Z%m)PeV-koNyprtF^x^XUvJ$=fp=47 z&NeiAD|%R|W8pp7w67GN-ge$n-VNhjyWj0^yKZ!Io$bK%!p zn@Vc9E(5$xN}t{MY7z?7m>e~VY{AA`{OR-E4aMA~I>hh6@{2A4W!TxfZ%tLTric{7 z;Vp{j_(&zb(_I0}j%=nsd-JlyeA3ONq5scNm|dFTW%%FDw*TvY-^L{}H0iK{)Ghw@ z|Nra1{{JU`An5&`EkTdUT}ldlaFF4T7S4fDu4Ibg$nbz zq)NoEt~o}0_8)GL;!(@kCR(q@a5)Io!Am7RhXkSSs95@!*r#P~XC(JiAF<;KuR5YFCYM}O3 zy6MPV(q_aDT2)Z4@Cv(vd=q^t;{>lh!{NOE(a}yNzUfnZPBInr<87W_cyly_dIkAp zjgh_vV!>Aj!hS4r;ww^HEU#;#O?;yvkjUJncJ=|z_^VZ5_nPKLtS z+b48G-#37_dG8D3_9!A0UOm@k+fX$0U`gZ9T!43}X6Z>)fOqWAO+oc*LZFGIDjp}h zu<>sCW~Keub1rEN@$+C+GE}I<#`{&;+Lgzkgj#+SV1jgI?{l@(; z-kUZ&-7y33CUHtVHV4z&-Ay8^uMS2-CoCRk!QcN&aUNX@KX0+=l*)*8UkIf7?nYMg z0qh2;=B~Kb&cHb&CB$z~jpd<%J9dLq6)m{#G7ID3jq0ElpRQf;y194h$9wt9WVKQr z8a|MA5wF-=@r3E|j&PH&q(w)vwX)&f^W^O9Oo8{ya~5hS-iBMvbg=LqyjDwW0C=mf zeG?Aj-E&q)MF8x*y$gAgC8s_zS`*F_^y7WH zeBQh*OR3l1PTeU{-sh*7zV`m8KS7g@G|j`V5r6Oh|9{f1|F8d{p#S%v$U*O&3gqA% zBn3w7YFD=4uyWAT(3)594w8dXXAqo&k{%>-JO@jxt!0{9RXP!J(>=nn?JIa#ce&g9=jlm%>uX?IDnE!}7C<6WA4`!&x_CQ-uOa4e=ZN;a*32gIz(U-U+|7 zalH=1<)C$l4r=k4d@j(;`bGZ?QmN*GC1>kKR80e#zMua|QS)tG7b%#I}8_J`vhhi_WCvWf`kDRAST8#MhhgcltbH!d_OV@mM zx_^i9@IHa)D5DbJ@J+|$>Ff04ZLHG}DSnH31sQSb+se__ZOmUmx{lGL!&-d4KuZz1 zf^?_A`|S^bpD5lZn$nE1@FsCMJcaT0{c)R&cj7y9aS^HIgBR+|0PlkLLO)g=Cqe=O`iAoX z-goUa_QH5;?EiT_2jJZ-5m@I8&i`k9&f+oHijB9auWh~Lc_X`Z)#$ll4z z#ui%GGv0U$)saFaz7Go|J{kOr{r|R$T#LM4Q-8fhm$Ov5{cAPT*WSt3jbv!i5q+p- z&z{}M5I4vN@9^a~ff0djfmVSh0wn?k0%ru01fm4?3b+fb7g#N@NI+9SUO-rYz(3C4 z$KS?Z&rjkn;?Lnv=0D6I#P7wwnctdUmwzt5I6o)fPrgrloqW&u9`P0PUE)jQi{lI9 z^W}5lv*laPXTYbzC&kChJI(ur_dRb5Zx!!d-aOt+-bC&j+!wf0xQ}p$aC>t*aTB?h za_e&|anIuB=9=Of=6c7~%vH&Co9hZ!23I^+IM;42S1x-lb1ow;H7*%0el8s62xm8E zE9Vo=63zn7Gn`4BQJi}@-8t8DuI60CsmUqNDa=XW80YBYXyd5oAaN9N6aLziPNhd2i(`%m^y?49h-*dMVMvtMFQV~=AGWA|luVYg*p&Thc2!Y;+m z%QnsSh3!3C3tJW2UA8>7OtwU}2sS^q?Q9NgE7?rgG}vU>1ld>#qlAxySA<$ZDd8F+ zn{a|~h!8;VAZ#R95zGkM1Vw@@i*`n z@G1Bs_z=7|-U&~{FU9NQmGHCh+^kcq!>sREn^`MaZ?j%u&0vjZ4QJiW>dI=*YR+oJ zs>UkA%Ktx$0?Up6`T6fpjQ<+7e7q zYZ<|KfMASTOYTVV6O2%6@rk7p1VhwAGxOITA0JRp4q#q^dqt?Rv3xf%I zsAZCr>`l-`En_F2xda{5GExM)w%Vv=h?k2aXrb1Eri!x!P1MpqW>!R)k6L=J2VWC3 zP)m2=+9w2c)Y6{JdO%P^Ev??=cL=JerFlv9D?tUd=KId`Cn%$qhV?TOf)Z+}&r{q> zn1@=bZMSa`=AxELp^hD44r(a}-H;|IqL$JcmkR_1)S5TX{T@LcwdQm+>k#BnOR-q^ zEAc9(=+oO*Ygi%Xmfnyp$2(^So z4hIkfQA@CGP?;crS^}4NQwjX2#qaYpjlhRme9QMq5_nOISDJebfd{p?ht|3ixKWEM zZ;2^^3$-|pZr?%RL@kcceZvF})M6Je+d*JQEy52qF9I8C;fwP|2n5t(jeJo=z@rw6 z)tm$B&CAO0I^4coBT;YUzwNa#c-{wrz?e#l*f|AJZr1v?Y*pHZv-Vdyk| z7`6IVzMa7jp;oVGzaIV*YV{0lUV$G(t?nDSGWY@1`fvod8sCpv@Vp)0hg$G>65oqj z@H7Yi5w+mv7vFd_9Y_3I)PleL z!*`+<{HYYa1GV5UOYrTe1s}x6zdjf407V-X!gkc!`)k;auno2RtDf-@Tv5v}$73a7 zD{AfWFxp0NL9N}U-@*vasI|+OyN=+5T0TvJ9fU2YbwOlG@G6}Y*<$S83g|HU2oU9+#5s0X@Me6<_m>)*4L@Yb_g=>5*YQYZz<7-e0em@oe1hwGjCh^t(Sm1R&d=+ZlJr$^n ze~emp_SWviSEAN!sBsEkfm*k;zNO+Hq1MgLug&;}sCDDcyY2XL)VdyXQX2mNwTjlN ze#DbdtB^m>3txs>SBKrW@TI6#P;iSAe;>8-1K!l(OHeD%yYv(O9%|(Z4&d>3QR{No z1tS{IXqf8cMS)`e~S&iG=~I&a)Lioc0k=cexk;%}f>!-w$&h-H7^@=;@gH~RmjlfI4N z^HD3!tz7}1hgzviJu30JsFlJs%!$8(TFE`!gZRs+buxG7UHm1~IuVlKi@%6k$IX`8 z<1e6AlDuFn{yb_W4jtgf=b%s)_#_mdi+V$3T-H@!=FH{kmS*e_~WP*99HxOpM+XL zi!ze%$51Pf|5!IZ5w-TUse9oQ{=Wam_&pvD?Em{v%pl>a2A)B}`~OR}*|THKAmv^N z#KA}G?v<92PmtbDU$ssT%pm3U9CcoX6QRKa=NoQ~fE%Q|)*hM#W{~H1JH~wjGf0h3 z5lK-CLZHUkO}NP?*!%x)KM_`($y6XcM*N~8N*~JPWAFbLlN#&@x{S9$+KK46K_$M4 zkOVXPkM!>#^{KU3T0f%U1gRbG^Jj_8Oh1Ff$$xLANymYv0(_lv^W zY*=`Ij6AR%#yjzZ0vYdT$|03j0B-|c!3oDhM2Kap_m6!5@7Q$_sgeNipHeJsT>$Ur zopZCkUkrib<7}$uF2WwMKd&W4?YC1PMInAtf*YLq6|i@ZO4ci0zc9dfN9>vr9rvij z*D0fSP$ivyyq!g4KYs6}VF&3ciA}xSnfZ5+6Hk9^RdZj%q6L z9U6SiG1g2!-fxQvFDG$P$J={x*1GzSkC-0s^%j9N=`decrWKJu#@mYmZ+MV`;=Qx~ z0V@{X#(56>Fy5omt3X@K|CYTT7l zfcN(hkDasPL!h?Ib3Vxm*m!^F*d|>qr9f&z{7$*}2{y1{a@+bQu2)*f7ao_gG~VM@_6_8dZ&rd#-Uz5Z-6&JG?W+K|9@7BQSCLM2A7p-hKL#`nAP~Z)3_Mv#2rb_W(;r)D?^*xMtaPtKD2C0iIw>;Yc-g6_D z2?-$VMRbe>1uOK=&sKiHLU$bB7H2rwbySA6rRxESrb zacY80|3Eq}Z$3>rGSZ}F_Z5({_bv*&;o}%6-VK|tabn^9lV|igjQ8hjmgEL0$|xXb z6yTk-%SvzGW+EiHWx>fIaC-}MJkA83-WF!Qs~Z4#&)n#AQq~TE@Y{pdr&VC%-3lde z%f!i(es25iCwDiDlz$O>bD}f;pzicM#_Ru49UWBS8|*!@tyhWu{=YWCtD!lfmTLBX z!EwCok>(+$$NRiZ98Egf#5SBT{QY{XF9qK4`63kWo$c`)Sa`pC-K`3bw`$@H$kW@O zCmnaPgZ}?eBYXd_ClMNw=luKt+`V=Gex(b%_jXM7*xv5|?;~yb!#$qC(7EgDx`HOK zixb?J@7GR+D3H<+zp|ts(kEVEXK#gz1{WR)GG70W>X4@rUv$l^!@IZApS`ch=B)na zPCa{js4SKd`mu@W@lF&|ph<^ckl6k6S%3Tge~ME^{sHv=ffP9iK4FRGAWIPwVXPdK z9pKyt-$8o+@C^A5(#$>~1747W9D;0oPDm4>Wv0QmOhNyDhckAiILJZC7X2A=1aSYK z%Bc~Z>>z0DRQN?%HS8R8A;ix6?l=qS6XI8M`uR#1R_q+Kt%PsP^{5cTRgk9<9b2iy z*YkRr__}}bf>g6(^VMAq)N>H;!>F&KHv^cyL3(nJHXZ68wSwA@kt@gm3cTSX!zkXG z?E*qrcyHt{V}<*F`D0#t;0EcM#O`}+0PnP`SCcQu6Cvob^OJP|@7+hOmq`G;?`L`~ z765o3*I(=2;1dLutV%Tq8u!4gd|DFrYz%nIMk+-7R!gth>esLV(|>s6Zr%FLjQ9Ru z9in59N_=M{uXp2Z>0e@vPJMs*#)RF zNAd1|^I8B4@0`Y;vM}D~%sc)MduJY2Q}_P=qcqSwkD5#KoaVDhDx!``2o)iX(m%P~$*4iYzYp%Y%@e?#idxKui?o%Q_54MiS?g4o3c7JIFSC9&Cy9mEP1!*WW@LHk^ z?A{i|E%Vrc?%w%5ZgDphII4aY{)wCS#50W(LU->wyME~&jHbUAq_YtnH!<=%v10SF z2i&ydEn*$9ym}+{4N_diww?xQK8CL#aq~Q=(h+Kr8mDuKku9G82KFz z)OF5jqaE)ur|Z`g*I?uQ>1RIk{AtGT|A##asL~NocC56RNcy}*5Cz`wEhRGEZ3ZD+ zXn05NwRVT`mTmn=!uw!aqSQx#_c0>pCoKa4bRmqdzZBptx;xbi-o5Q6wq$exyxFg8 zkr65hg|@lZI=h&o<2^|1V!ItHQ00uoT_}B4@>>WU@6*KXJ0`g0=??FHM8_$N{CrPF zD;x6Bj<-qW>i~x`?Ajam#<4ZsK8oSpJIc$6Djgi1o>n$T|Mvg%-1h&I8|eS{Q+N=3 zPm}CH6|6d8Cvu&D`<39t=o-WF<(! z9%ShE#SNYy6*ZL<2U>?gRhOBaPPC$XklxrLho_q3=4D8n&QG&g7b%Fo@^$;#Yhb=y;bEHF2hH?KEG2#Eokl)SU7|$D7mB z{ETYpU?rVU{ZAS~m;dPC!N`w;t$K%rFzrk1p~+KHtq}GB={&yL#G>{YhQ~YB_W@Np zOnaLaF9uuez`cnSc*8g8$#^$9zZ62lJM&5N5RA8}#0=>J=|@E`=)4DbXO*9d4`U-h z9^3GCOaSlw>Yjyg|9`&nDF-}3D(-VT;M5ul^2ck6Wvw@+}f)$Zn`- zYl4pVMSJ_$+RFpx|8PYoKYWn?qaz0+zbv!f6Qb*A$NN(bM^p$46&2*{$YSFI^BKN^ z#8nScr-Ru(8M(a`Mu9i{Gz1y%3YHu}RJ|zJxCnK z*@N*`|8aWj(#|h)!*lcKu0i_j_eVz_Mt=K!h`AL!wBsFFt+sNbG`4$>ncLi7c!|jH zcptlFL6wfEH5zmJf80Bi0&n=O6Efbpo*@Egc=w0PC&PG~RwwR;@%~LPp8Nsu&hD&! ze_4P4S$^B@_XYI-f+eovFy4({+S2&|-mUTcPfgE-Lg#fX@oFmQc$emj$d8Hqtjt8> zN?$SU_nU|A-eyt*n$6yvbcc5yqQe*?zbb;XL$D+5ct6_SFmSDfis8h?(L_1^eGHE` z?f{iK+S(7mZ*Tv-|4%1n%zvd3w<&SnzaHcSzxG7-poMyhQfMB8ue&nkL{JkC8v0Vst0F3re zIFrh9+56WE%>QrW)Q=mh)(J4Y2iX|RP^CjAU|`;*+HBAuCF1_YoAi7c8Sg_~R*TT^ zu2OJpg7J1NJVnC06Zfch7A&z(zdtI(0lc?Fy{=aUOYHcGF=bhR_W*Zvf)BtO`t)&K zhe{YUGtTnTz7&0l&7BHw$Vp(r|3KoB7cD-#C-i#ir0uOp3cTS5CdqielFbxH z!`tFxdp3;s{BO@lySEu@hD}BQ-Zt`%xVGQ+keBB29!t>w_j61+`LAo2j<&DmKm zVtF+bnqb>!R%D2d_r@(9_?=JY%)cUWcZ8?Uy6~doU1_aT5XjF-cX;nXbYSJDx=Fum zk2vkc$w)!_VD?KY-rlNzeU0r%D8suqZiq@9ZhN?t{`UW9EgOCP9yCa-|9X%U{AM)S zgS4Au70^6r`Q{yOYk>!e&fVPw??DJ5Z%9;}0A(oNcyS9 z6wTjbx(axZRcqOxXb(nFZPxF^XNBL{BtCZ@1CS_c5FJ}E^0SaCvNbtK`xQHOpXP6Eqf~fM^Yp}(PIiVLkm4rCsMFCBUoJ;FAf3oU zfj9gJIvH>1!=xM<-pa@NG~p%oCpQ!6c+2_(*Tp!nz2$EBeAozVvF{c7a>pOwZ6oT- z1miuGzCC6&z*}xMY=N(5I3ylvoz~3ci`us;*qDjeUT4NjAaOgbbZ@^MLC3q6{|4@m zp#a_Ct%K-zj*;K4n)&zko6?TAZ>iR{EJy6)Ex79ga|Vwx7#{Das<%|>$kZ5kT}V3K zk~p6NZ}?SzGTs{ad$MSFGkJ+8z<6)2@FrD|Ns3OlV7!aC`IpLa5TK*c1Z7Ep_oB=% zAK=~Fu>~^Sb^!0e*HRg$)`de4N^pkhW9aVv>G6IU^MZMJa$NAzJr>$s=y*STByt~d*D|*CtPh90 zwcj=jkE7#V*M+~}ZOVlALgF|t_GV_kM#no*h;w1vbNa)(3(;{HBfpv#fj=vaXvdp( zCg$|$!#dO=?_Yr2tnsU38Q#5dcJ5T^_{i;C=W^}u`Tu|a{pt88u*7muco6*MDY6G0 z{vxD`=0TCkr(V^73i1jed^_C#m%8m4;Qx-#{Fc5pVxl6;zNL zR#)=WF};McT!XWhRT7~q?iYRrJE40}g3J#U_W=R?RU~fF^N8JYCg>i-v3Z{lyT3f$ zHAsgM9b6dsb(VRy=KdcZNaO0eAM74PMT3-e@k7~i9me;d%mS)(9JnggdEykQf?P;} zH~c9zGTzyK6Uu0K|9V^e8OFQ+#UKgqjl@mHTmbKn_pHt~>45kDmakop+sf%Kw_?kzWK zW$6y@&xnr882M=iKQX@4O8XXjNryvY_($vp3Fom&=d#op#>d;oo+=&5dhXGx_egjz zpuijcHXs>q@1Mns(eQ3#SLB3uZ-eH!?||KVDNlLb0)Y1nlh|1cO#&npQgd<^;O&s# zx@s}NI|uLPzzX_*Cf(n{Extr3p+;0nk_jE}_aRTk*_?UtiAbE0^(UA1e)I>@l#W7m z0e#YRhj%}sLm4B#dcU1wPxxrBAVbOx9u)q@ZjkIYbuYVN&&==>B-MzwRO#Tb9xX`& zH%LKo!cKuV{IN?i-t97JN@#e;>910U@g6YzK*D==nb~Ui^_J~hLrX+d!TWz}C5NZL z;lu=wNLNLGx5V3f35o#kWzu2S!?qEj{eEiJu~X>p|B33~mXojH#2-N7n144ew2txQ@Yi2gn@qgxy=salI!zdz=4EWCjNwCkmD;<@^eE zZ>=`^EQN;?-+6A&w*h#+VoAQG&K(Y!>`E!xk&o`)(aV1%T;p1ZH$&p|A{Nx>q@vf} zc`MZpPWy?`9o{L3j(m*#cGybB7FyAc_qq>3FT`W9-8;7P(T(5telz^`R<>#>RXR+L z?HnG@`rH50ao7KEYG8@wrSKs5`_*I*3Xf9cOF!R=qSXF9)8)RR6$9`gGXxXpq zlb6*PzCqGlfICNxjty={l|5tO1Ja2+6nMiQWGCZY&i+Od4R2MiA_&IY@umDW7;l{U z&tnS#-pNBHP3N@<(AQ?GYHfhGdb4jkjQ5lqo^S==U0oD0Ph%4ivX@P(?)!pXL7w(i zi2pt$iYFj(F3kBYbIs@#q*d5Y;UGt4y2JY%qQeFwzghyv=2xt=<6Z9VmFs+oivItJ zMi~@p!0>oSMQc)}qjA-=&u`NA{}Q<=@aDP1d6JCxaqS`vG`x9^itT{$W+UDs;l1|R z3orQf)*qq^b<%YSQ0EJM`^^CFCe`?-Fy8BOJms$fye-PV@kXs6LR?2gRPJ`7<8Aj@ zDtcqC2%a40UVWX5P=StjA$Ld3A%VqohqnWw;|fN83n4?VcXqVnZ7j4d;cXsv1!=J} z=%>(b#^2r=+7wKcj`0INTppzF|0Qx!;LYvVkV(e-nn;*B8s2wI=N*CZmUi9h0lRli zRaGN5z#y>&g-aH9l>ZnA=J2gDZe%Y8J-Qm3t(Qy9C6zQU25ab5h{VWf>wy#@jn>r5YOEpK?!^!+0Bd36q8snVk2< z`2pU8(66H7h6G4g{&Pn?!26VAZa$3n@UPYZ81Lp+xTCj!5}~!emg$np$3g2km&@P-fNt)_^^Giz>@+ ziP-g+;rst6*~?VvNLy?${3G{o|Nn23O~*fh21$s*gG6y^hsYjeC(pVB&4W_ZehI)H zRHP9}>i?ssj^F(Z_8=3xzsO$hwTD_q9iK_|#z89vqZ{G*zsgR#l1AV`J35sEFSrmP zaoywRb^fD4>bQSR=Kf6y&HlOxZ5K^Z*59&g6Y{AHnMY727@g(h6 z?7HU_tS(c*A3^m5!;5`W2V|%>M-`@D_f2BY}+fhJ7#f(eSRQ zQRjj2e)rvzg!j9<*|p;UZzssDxq8MPV%epZl@IXV(7ez|4d7j&DSf>b;2pYtZu1^p zA~aO$7Rp(JUO`^oTfuYUr6m3n5+@RKSMXatdIjk`nWuD1n*Q*BlEAu($s z+LzefcOTkJe59g+9D1lw7$?K1+%1_bm z-YrXStmFQI-Tz-%uy;OJ_X&o_`^d#0s&sr^a>TglB5D55Pl31K_PC>DyrqnG>!RVk zD@$`ejCa_y0SWJF=vv7yfVWkE79=M z%14AoE95UWWMFoWU5-}nFMxbG*Y20Tcd!h;r# zEM5XHu@d}oJNOk{acCYSVsq&vyu@0j6_U2tpJ^p-@C8dO&e}BG^`bpAcfaE#9(-a~ zw?+Pe4)7pVk%{_sz=KBHHiXU?6QPiw6+(G0(3jX-3f;SBe8up4khrbStMN(2=u7Ol zF($R=&i5$=y=DgP7d|#7su-(aXz6-_y0&l z$6KTKyVauC^mn`^4$+~7k>6>yq&2T_v@fytkHzdVnyGl+;-hKX#sdKik2lWSh&ml6 z2Y2fIsUSru@Rmqqb0p&(r+?HK4ewti&$hsLD?YeQn*UqlSSzyt-Xrq72gdH$LreNz z&Ut_X(y}%8Wi1Kq6_u`$UW-#6b?^Q{7A28Ods{nX&?u1+w9@#@v z8oi$gU_h$7+XjLgB&cMn@(#dzpY4Y)Sx1P_&xy4QJQUFJZr>76P1qobpF!e8%v56{ z*wOLktFzWyd4>M^{|-cl07iaid)n4ro~9jdQ`Z267An5p@|`bGpmSy&!(VTC-a?&@ z)SKlY@`)t8g(>hBGYpy`;~k!%ZHR`q;9*};81JJm(@Fh*{w9|_!vJqWu1?#D2774J z)*ZTeAL1aHyGID{>}|<-uy-fGo6j!%*@d%2Xd658=XyPKyoUq&D$UPG;p1U+7d-5~=;XR7z_=S<*J=unv8D_K>C)ur@ZkM^RYj50%Z5w%HPcnZ0PuN18 zj)ea6@b#9z{XeS?)>y_;aAF&(1 zK9KJM_8@)tFSt|D4c;L2Y*vH&|C!(N8NR@S!sSH1ER`cdMbg>VG;X6e zNavh+QbwmF@t2UeUGp+OEI)zXAYI7Yr|oD%e*@Aph>nXG`F-lIQ}o+Iy9XIvRI2g5 zOGO2FrOz9mafIP3NLml4CDQa zIl&#qdr$T$B{A5&>!M;~yX~Qn#HGi0K?OOFHBM3&;9d0VPWT3Zw|v`f!o=+`NMKIw zteq7)-Y<7n>ySH_Sj(&{%_IRE<|GSrVymyG_ z&JWJUKD~w8pEcqe{r|xQX@4qp)R{|Xd6NdDk`#E$*xq&~zQ@vFR9$_mRyfhStEv$YNx@OEccLx1|be0#+hulxo-}M%6LVGl^}9CPp9>KMcD{lC^;>U6Ad$!#!7B3(|Dpuk&Nw~(8Rw`^wGJT$zYwhOq! zcyE<^PTJmTS@8PGHGsEhu2lbauzOpwjo0cTxc~2~rn*oM;9b~#a>fGS?e1yO>KqmZ zU6?ZFwq-}hn@>Ae%lV@S{wxwVdn+N{r5_z{PuFJ#&^r3Vn+MV1g^^#R+q0{CtZCog z(t4QP6GP3{TaJ!Y1eruJJl;`jsMEpWaAG{9>_Os2 zD>>0Ts6s551NI<+Ng`>9W#hC;XD$H~B(|iv`QV7%t7_Mp)n!VQp z57G?OxSM~D2$kQAd>dncz6WVxvgGFHG%5UDByN)fZrf2Y^gT$ibf@e0+coI!3=&y~ zBu0Mbkp7N{WZIY5a~pdVI;nXeO)g>A=w?aA@Bh0GQl+CM%ITflpY#9n6nHBa>yQSd z@b=cTUNH_dym#To`rrm>PN|#JAT6A;+&%~zq&7X4G*LkUG~s1yy}L0Eiu%=*16PnS zqNRSD0p59w9`QSc5TTOw$9`)qM8{j>m5dNeq%{5p64%~panX1by+O)xsWUOXuSs`! zt0Ow{F!GZ~XX?E7gm%0~r}eHHabY(|!9^c5^smG*Jl>sZJyhvfFK3&r44&8l?kz`w z_u|l-5@h!ds2W^=hPP<{uW}ggbM_h}yq7Ip_u&b^Tix00ngRGgx?_`i(1}-Z(CUYV znlRpHYYelu0=ymi{c;1h5Ft%7#j6j#qF0dq8=tp1aLVA-khtq7R-~D>pyT~pJYch~ zvliXq?T6@KmiX`dKICN{beu=~3sRbqL3QEfR2+~t`83(pn9T5a<3>JHrz1_0UFXm7 z7Fi0smDafDk?~epU(Sw(x96B@3XHc_^6o#ox35p1%LI65O%zv%vk;(@>ry9Ix5q)F zR>?Qv-P_6m*55k;-aLMXFU}(nq1O5MJ4}7(c>f5R-K@tWgKtLSBo3B3>C~X(y>s73 z`}$4vhxd0xhc`xkVqc=qd)}qpy}uru+AeS&dqBE<;S2VR<+F^Bw|)y%I&|9QC@iI8IRLWjpc(DCNAVjf$h zC5@Lu;y%UJdW8SS^OhHTs*lJA(qD1HiRdW6$j{*uPio8$+VSQ!uzq?=lnVFOHy93Y z{l@t7e-%7+I;5Pn;Oi}a=l}n<*>w98s327+JVNMkf&O30|HAqiWdandSdcaHBo6vn$JSsBme{l{F?A#JUP6Q!qY%q@B4m5^ z;$063^ad%neDN8LBni9?5;rz-_}hhF=u51KilpiKKKdJw<{>)7F!H;$P%%!^hjtHY zi4gm>HHQih3epf1KdZp_OYE#FbvjOa&X)eEAeAZb*1V+hm5g`2-9kPzyzvfG9WdUn z1&c{|Yp5THh5+76{l<@RFD5`6>T*?QYT_UQah|;qz`Ln*`{;a7K_>I|Ci>0~hob8Z ztg_Fb&{W7V}l8yd#H$1K`y4iTf<*5h>Z6NyVpEuc*oront<`% zUoA%3z3s|-Y`FyB?doRQ)TRL5|BtV@t@ktz8uH9e)_Mx}0v+$=t1q51ye@&?kHoQ?@7tU1fsVJgM7nVZJN=y?CF}6R$S>EP^IPV6+VO7J z-r^d56B}=wqFkoe3Ngl?AjwKlr6Ymp{au{&f%HTr3cS_r8coP}C!H(hM#J0HD2McV zOQZV{65i+7jTKb^-r{?mSRgq9w93eED(_hwl>A{<#sJ_Q$-Ur-A;5dc0NT_4ng}rk zCzommqvOpv>ou|)FNyyh^d}DLP?ox}5gqT3EuOE}WY8bpT!@Y#jQonF-u)=cq#bWp zEx%#&UMlczdGs^HaxcTG3(T z2b~u+7De+QEvbr`YT!Yv3skniCrE8>S6(*(9<(~Q`r_#)_E2!*?xbnZ|9`hs%rF5S zq{Fo|_dV$US2#X&PqidM^Fx?^jQXONB%)ki9Wu?M8M6+MScGM+L19;CrXs&se_tb`i>od4IL zz*|2RPx^v1Jpa$Gz=@#Yef7~2S-3%}tEeX7T{IAK%pBl7*xrBBtH&PNx51(88Nj<^ z2}dQ2_ucfwuWta}-;|3y^Q6H1pXYm|{0(%xQ?K7RTvslMzlp@H-?n=+|0p`%9OWNR zjBwH)-bWD~oEZ6;A8q#aAEX^`*F|Pf{yOXl(zdm%RYKZ&48O!)(O5v0j-oro+L?bQ zNa_@L>urnaB)j)|&1NAqyj991Y+=0p{QXH2Br&BDXc@rU1Lc@4)a)DvFcI+O68B%NZW;s5R8-7zujc&IS%hgW6k_ z0&nfvv-in(k1zKTK*M{U)m#ybci#F565fa3eYmt5;NASj^g{voyru1uL{}z&_xS@V z%V4~dYg_iV0=zp#e~hgz0oz+kUJMdfqT}8E<-*#jLlSr#61Tug_<6ksI^J$!{!N;_ z^f#R7Ky@5FG?wY@J9Eb4bw|s^-lBS^^iD& zs}Yy;?a@8x-nf#(yLdUeJ3+b`(NTes-<2)N#sN{Zd(iF8n!zGd*cYUu_T;DG6nYuH z|BsrYPRBE;bA8AET#(kKz}qD4m@gUcoo|0iqT#KQ@LmwcJGj1<^aW|x3CVhHfVXl0 z$JUeM_7Gm6MlKcL9nH0=3C27524T+}SYl=7_C`I)Cqf3(@%R1B(edV%ZCia{P6Tg= z#Dy&2{w^PLG2AKu>jAy+SfhWGhz#XI2%(s}7$qzRJjx8#0N zfOlRhTaM#9d*}i;ORfsQ+ka=YBYb+RM5D$18^AkuRjbqcBqD@w&8+Q}LC3q*tUgr0 zUJ?%>aW(Vv9)4v;$D6mn$)GKl{`&t8L1ckJ`|;`-QiG&Tfwz%dt{&OFdA6pDqv3tG+oAw&kT!q*N@|eqSlX&6 z0lfDI${slT)E@dGeS+sEIKB0w?rb-V_q$gbzlH(c@w@8P4#W~6{@K;)o5j%a7R+O> z6&aMmljAAT5IEc#o0a_^c}5LWuSO>BS7KxxAB9^#4yg zx-=YaGQN8^w^OIX!{u1!pXV*KDDXC9mOf0zn{UWZ3=QvlYpvSh*_&I*sm*Zh?LVJ? zlM%o>&HQQQ9`HEv(o5pv@&NCjJGXknySGVKpIGz)y!FBkzxFspgo3wT<@1z6$NOZL zroNeu6rLRC9{PSdY#zFMm#AI;bec$icW<*09k(#@TU4^qqdAOr_kQ+aKCfjP_VJc$ zxqFozwC^)~?QIl6q)JE0?dj@)0lOx)Gum`cMGQJZ5uGn$vusm>Xw}%FwMHK!9N9?p7j77pHNJR=R*vf+bKYGiB zqCHoLP$%a}_eB=y9%No{eC*fy=E`m)ZuA{LPmLnF2U*WO6OWqcF{hM94?oZ5|IuNB zk)M7Te%aL_+C6AF(@ae+6ZRRT`FX9>ECK&I# z#}bqz0p4deXhvzJeDq2v8!v|Ni!kkYM|KVd-h4|%1?ld0TlIn^!{d!x=tY%|#DUDT6RYFk z3DOb@ydgV@Ph`C92g+s9@LqX??<|bBaV{qbZ`VE0?yCUr%ymNVi@(@I-LmDWc!2ks z_a=)C0p3-tFWQ6w-b#bV7QfyAK5toc+COOoeg3cTK4+(f&7}DV5*On0&Qtp(I^O=f znUd_D%%{8ETYW@F07ic0J!g1S2(;rJbzCEXzXE%L)Z*1?pfpm*@OU5Ve?^s!x`9vO zZ84<&-+%&dyxi6yGTu$4M`h6PPBhaDhVc%Q+35qjw_upT-bR4;`|F=vM1R{uK7LF# z)!=%|qPJ#IFy5&zhg|po-bU}u0u$B|Aq%^dD@vcx@tzjVZ#0o(!doJ7k9e5NDxag{ zZJU#cJ6FO-cX-be`=etuMt((3A*TcX504YwD5%ssyON5_iJStXwsn^n9&cPaKXp2O zoaulcNC)n%Pl31D_^Bi^-uy`$q|xvm8IiPs@y*!_Q0|3Lws(7g=b|Kl2{ z(-EL<$*hw1_x(T0LYZ!V1|DQi;X&5<^BTw=q?RwJisnHPA{)c&fCurh)$W5mXr9z1 z*?6$TmQT)`k>wyj2iWF4HwG2tuhytd@D;m&bKPP3z=QO*k6d_T84ih#HWAg|qI-~_ z=&|WBBfcsLB<}ig<4>_q&^<`Xi>c^llMJ5T{+{^|9a#A#EIZ5Tx8(zqaV>y%sY7Y|N$qfG1B-mP z&ogwq9fOWK#uFA)Z9?LF{qr@6V6ZTK56GEsq`T6$78QNdLM)tOww2iT}_K<1J{o(?|{A9Xwllu%bO2I=WUd z^Hi`e>dnX2mY@|UPT{JKA#q{@Rbr>zwxGtVyPG%PTf$3sc)vt+sAA+NA*xZ<8cI9f zX1m)>FFwJZ|3{6y85OK3Wq7=!A|6qtW3!Fc;k{2u?rlPWw@Oa~vs!^w-_fgGRaJ=R3 z`+xM-jsA~(K>u$+;X!M1e)f@?bX{kegaL2|soe$Ir4N=^_65vGt-unSnVHwa3Mxp;N?w=tAoL|RDd^Uw-JGkf$!)EwP6Y9R!U0M!)Y8%Xln+S|R_Be>u{xe6MaRjC@9g z2NfKtah(cg_zDvDHkmpdEKK`P|2bl}i~{e~k$UxHytm*!YNFvi5i8aYylwG^BFT6wg%xX{;msb%-v#4sw#tKq zw@UY`x*GuRF#>n_V^IPmB5lih9-RNze6DdD#(Vo*zwJ_hw@Fsu=dEYMp-ry&yBmzq z@qX=8T{B=HUFC+v#l$2zt(HT_J8U4M+JdM_cX*R^gk$7K4ELXKQKKDib%9}*p)qXt zj&f7%sq~*@c)W4d3RLNkbavD^{+QGtK@@ne;@19W_crB2m^vEXT)dxOz;aWIk)X#TdW+gh_ z?CE(854y#xOp!Q$xfdmUdgyrTomCOoW}-@Wc(Wop3^4NJTzG4P(QexDX4XviOy|VL zJN{<>#<=H&4BsF<-SVC)9sWHEwZGCyc;hMXwi(#}jqKj35mstwcz@S8q6XvbF?W&( z*WRCE^KnT4Z{Izx10CRb3yzVbswseXPqTtJynDNAuhJ_cfOk}-56A1h;gDO6{--T` z=y;cI+g&lLC|u=%#2pr#aQZxr-v5_Nju=npDAFC?w-FupF!H;Xrr#ZVop!wA_GZpV zR8TRTc#z~h(Dna8|9>}%IvqjTC0c*q|3_=t=_Ajjj?m1GavrOdPh&4V~U zoS%R_=yH4$X^G9f!|ta5&L9b15N{p?{r@mWC_eO29CWU=wNndt(8a)a*~fqfJ@{SQ zxH&Z(%6s)#bgwG92d&5p>RRzYv5Fk`Fl{eevH56 zpQPP`c0G{Y8F&GEiH%x(y)I#r@!uf9<+9aNqeIDP__=E;X^FL>z}sP4*(x&L%v&4u z(eVDJe{>4Q``&>b65bjqTKeJuZ~ajdUM7II{H*{N{>O39p))x~@E4@Mifq^y0r2L- z^ZrZ=4~JUBtYEFr0p9*^zvRN-|NA`d@4Exw zy{b0=Xi@H1>S`D@~&jOWoH6( z(eQ4$-HCev@K!fti-a4beNvsvW$GdOQ@!nPFybRy3P;~)`E1!s%Q>{nG+x}ro^IlK-!+R&9gMg7= zmrVb+O{;0g`>^->i7QkbZ^0#2NW66T$?*L@F5(_lI-2-XMZ*h7?!BA>Z@ahG*8GEa zDWrpjx8|JN57@o!@x3JXR`O~c8U=XQha^p~g8sijIT~*aW^d!q=2^gaKTJ|dSqbpo z7J7|Mnt4BT!nytI?;LczRaTy^lwwk-I)%gq_1%n`N=CDYK z7c9I1D##UcANME%56an^A+?nGCA74#^!?fsL}-jBi5R1Xeg^5DtEscmoLm(-u7j8N z$N_Hj1}WfBQu6yl^f&)6M|5E2XD21JLUNe){$E|`4sQ2HDk{kLV`g01IEMEi++_}P zs&xEzJFNDng0!W;dxNvae)1B_yZNyR8s1Y5#v5R~J9cdfhbu^yt&f*T0lXt;C&h-8 z2++AG(JV`VH?Lon&0>JJ@vn+WS%CMzcm4NEJ&DlgLnS%Zv*DZ^$fZf})s|`9T0PoFo@$D3HMj%qUE7u~%_T^kjR3>2%#ahXG` zPYkQk-Fw9o^@x49=@0J_M8|TB{I0Khz%o%lJKn2A1_#~ju-$uk=tG|LJ&b?6CDebK zDjiZOxVH@j-cD^(|7>rS8!a(J!#l`$lyvs?Q^X@u|G#jAD?}aOjn7lcxGV&U zlj3y~6A$Ac>m~dNngH*sIgVe70N%dqHEeuj!lB#CmgaWeMX$ZR9&lF*S14AI<0{TH zx9FThuf5sR&!}q|)8BA{tb+|BKj*yg z3RLO1zM@F_@BIINw%c^~OVIzXrSKrP<5yb9{lBgI239l=S~&Yf9lrlRnR{w4TtRl< z^jfX~23zbNYfCim$3gpU`mn+cQs7fjKNV0xc16VYv}`3pk`ETuj!dF2 zvBJZflcLhZt3;8wP;I@y%69Z6mfPP)uXRj??)D)05goi3`3-+Lr)YbK_9eD_;Y{g< z1}Z!#OGry%7vsPGk6WNlosQ3Qv$;rzn434(9)T)>V+qgE&ZLuLz_B@P=5HWElXw^q2%PR48)v>Sbi zy`jU@y4_+?l_nCGeI=@-Qj%|(Qz6hKaKX6Rf)E=<8A%;K{PK5 z_7;0o9oI7V>Oh8XkfK&gQKh4O)@i!%&+!&}3cR<7oi8TiJ-TCr84d56v8QP;-YjRd zLt*ze8oCuR4^)t6HrX~D1P7#j(o?jJK?Ql{?K*#W_txTMtEC0N+iRz|>gq>Ch|^l4 zplAa+-U)8a7Vjsds}>@0>gQhhwV0vfUHoC+(-V4Hbcc5gqT>cee)XfLBTJ6cj`xo< zCw06a?9*Fmdwli{?doKByeoc0P^IHr#L4`rNYa4RjsovZ15=J$-Dy_a^p zc@D-JZ{Wr5|8Z@Da_b8_7#?q2<~!PpZ97#A8l>^-x=Oo@2~gTLo1>dSgT$Is z?JZVyY8d+{~z9EU2$E_TeT30gJieIapj=*|F&rt z2sy3Nbmu{D5FK_H`Efo7JTWpwy9aGbwrx$c!ETV)O9q#jct8G1Wc;EK65H1CHXHM%k_~;U#9Oe90 zet`G4O)?WQ0PkDp_8FxBytBD3H9q_r2JP5pSYsQ5j<>l=#^>){d{yp9TvYz|dqLaK z@h+|J`Zc{R5nJ zM!q2BM1i-5i1jjZ1-Z7lcL5sSg|)o>Fy1qF!bo`69PD*@0PuF$G+eX=oZeDzX=SYf zySKt~FH+xV*(?;{ZaPKrF&?1Z?C0wlL>FJUyzoHDu{XQ&sFxn7H~%T-3f>~ z9l9)u@2|v?p0{wMz3ikt-}!k~WbjH{m%(ed_f6l^QW5vqEJ#Kph( z7<8Wr9q;tBES~SA=jQmdY9Q@jMnf3?L55K#iTojG%-cjWeO=p_;7#?q2 zBy~DEW7w__XOoH(2MWC1AOAi>#@qFH92*+mLVZ==VZ7TTt4Me|sk^3i1H74}l~@PB z{NKsBe)~XG97H^MXcFGNEqSA4ZVK?e&U$L)e1Lc9`)EJo|G-=5vuz|-r%2UJBu;rc z^~C)Dz`I|+ul(7{#dPQ1e29(#jQn1WzHP@((vJ76$7;?y0odDH$?b#t4`uo?Jl+Qf zsM8_wt}n^u{NMhcAy#J4|8Ju3AfGo{%gG+}*~*+B&4X~wkM-aucE6;?`@{YJ{bzkw zmV!OVkIto68n+N2-wj>bXYa;AUr!Gf!xiMo@AvnF01wLb{^hTdNrVJM2Of`WpzlHQ zjE`xLXnd>WM&fp^{rb*}4}A~v=%`(F-d$$8^Pst}e{>wj$nRISG~~2__6pLXaRttG zC3gQGmEW`5T1A`j8>G@+s&pLVFe3Elkd{~%3cS7T_r#L%z9%fshlcmP#PK6A-r4NG zcEflNzB<1VK0zv_cwXzVGXc^Txc*YIJPx|o!!{}l@IF*Mw=f#uJ^a37STukLv5Vf{ z{(e3>-mVqqVy}MSs+f>CZ?2N$wFBrCWJt}W*cD{(@w+<T-*W(Uc53x2=CjfQum_D@&1 zLCREh4uaiVXLx&8A83#^hdXkQSQ4OC&5ucgm2r^!Qms|+?(Mb4;EYoMZ_Y`}8_%~8 zA-)7RABn-|muxXm1_b zcW>nv6!iy;Vt&Xdspx~gC*9`>?}vd^DqcXeYrJi6Z#VS^+kiZ=6rU%ITCj&=&j+n zG5QiaE4d;@CP1W$-u}*K5FOJP`IYEzD0e$f`yOPPB%9x>J=hf_PBC9eD&-5qpFzUS zUZ+Zjnij#4XAU_L>*{}0dqn=f;Upy92X8Gawe`_$0UT`=BV)+)cO0p3;z zmVGJ)c&`zE&dYH-4l2BKZ4Zq1$=`$RE^vc%$YoFGfdPO_lTp!Nd7i**9dP_>d*Xq>u z48O$U(ymdZV_a>0{Hlv2yj>~q-fg__pX)8`!mUDRc%KO<5r)4Yo$K@63YL|xq~ zxc|RUcjF=Vv^PjAdk#vU41I+C)tA8# zwYZIU7$5KCz0~Pw`!5mQ-jQm1a(gNIG)7~IyCobD_`UXIt*vXkVZ2=fuUL2kyj%Kg+fm2tk$68JvlcqRdRHQ?!N!m{``*))}Q~KpXTbFar=d6$J_Vd zVDzV0%d$$i$r9-`&Q~TxL`9Hn6{r}Df%>Q>#c+kGgiGL1ATO3!B zLi3=SjNbL|1gYbqC}}`icn4<#4@mb5Wb?9ZCqQ4bp1Mzg{(t6TeFr@Mw^(y$D?I-% zNcni8|3(;;SbRFk$pXEC^zhy!yXWKrd^{58<|lO9SO&dw)_cLDKE$|Y{w##|M z7vR0h!Pzo0HVk@pjVJnr06N~HlM`-k2Hf}>B(8e&i{6nj7t}_e&wu2+%>G4mhqpAM z11rD%CtKc*%+ii`!TB{(qZhF8R!rSmpLo`T;Txpp^&V8|NH>XWI}%5#AU!DX4*vQ1 zp9|7bMNcKr@V=UAvmVA<*6X)7+#so3OIV->@c#9n@pu=&`_lWnx6%RLT-Xm|^LU-Sgty*+!nkhFWd-!w_r1mJBH()sxwz&l&ZZ`J|eeV`_CAH2O) zXq7Yv@7_A%?Yp`?!XTx%NW*pG=y)3(nH*GZ;l;}%aYLRC>!6qDcsu{p+5g>_{_r+N zbYSJz%$hl(lteq;=Wdi_Y#YO#|2sS!D~-X|FuZ#&NS>rhhp>4Gui+um?(J3zyaO-n zvLWL=k+Me&4R6n;76lmZuajasVfPMT{*1E(cxM)?J0Ayl<2qxzSOMNy+Z(yy^Z%8X z%=WDXc;C8CyfJn#3^Fq|&Qat?FHRoh%?L{7bKy;pxGQ~=;?1AY@$Nr!z2noEB;C39 zGek!pMt&{rUCw%MX~#SDS>>&B5>yN)^e1gt9=S1o?fvK%bvi!Jj=*1U`TPF=|8BYI z>bIc(_oncmi1nS)WDnZTEw6y)L1~pM&eZ@9y0~-F1NNXNjWJigf+Kc;E5rGhgD*(G zCTtXY1tv(Vw@pUD@BeA2Cu%4I50ZQ7np)`>25}$E*p@YizQn5VrrXxJ^5Hp^zf`$piOuhLQ7dXRW|&jhzxq(|1!>$o)6h#s4h+A< zM!j84m5%9n!)<0aNK3321>XCUrNYQ~yI=b*hlcmWcf38k#D3WIgtWw-%!)3X26#V` zS;}z(yN-_c(A}Y#2Z3UAx5SPkIz}+^6W%;ONj62BUgFvu@R;Fa4`biCi0vFau| zGUL6GxHOkG&h@$IcqeDM1vI?or#rm+5gjQQ`LTavv01x=cDzmWC1q}Z!ETUnk`6zI zH6JrP-Z+&&>U4a&(CG8$fV3wC-eKk6_LA|Q6h9(^hWAp|m>wAK&|`X}-P_6TcDxNo%q44IV;@d@Zm{4! z>jhngpZ{mB)T2sAk;T};>|-SN-bsOXX#Q_mGTy9@+@#U)b~=0EDLi{CPV5hWYwz!i z7d9vYynnTPG!+4}H~I7ztjT0PhXI{Z?q%he7r4KPZ^LLC2fF z>R`@=r1|*gNSuwkjoS6Q=y-QlR2{YC5~Mr4#StA{82KGqz_cgHn|8cIA9_7@3Z}xn z6MeRszFE)s{ePf8bvjgCWZ`db{q6tJx;8rcJ?Q^;Q+QAe#H&U2AgNk@RWuLU_3`mK zxc_fUuiXZF&_2h3mX*MRSa($%GUXyb;h~uaKNZJ8L1}jC@D;mXMZ6O5`+uu+T6)B6 z!4W&fyl#(o=zEYh4#LZeCuHzmNStrCjhx~`^!fkOrU|1{$=Y=1K`Rj*wHW!$9nKRA zzD0ZgKb(*6&WXfskaT;b4z;=|GkgVk$xx0e9hm~`FEmb&mRNrZybtm|j3?u5?KY^4 zhId=_CJPvE{m@Vn-a4FW`tStFf6#FO4&aT)H?9@F5eI$DmeqroSo@giOEECs1!tHY zxrtDL7t;f&^XPcr|5EO{XM+qrABmIF{{Gk{8XfQ612^ZmhqUMp?+1tuto)eUmX#%Z zp&jqd?{TjsJh3ZCTnOP9lczqzbL?H;N8wUxJ0CGV-WL0*(m@cqzbp9;$-R9k@IH{AWK71}?@5Fb8s6;s zi9#^mAvq7X!o|s+>Lpzj2v59ksWk*J>n^PH*{8;2jxNHbureq+qQg z8s6OT0Y9Gryw^Lrk?>yEC}S}Uh7-X}+MnKX5TJe5tG14T{$E)t`ie5Zd$WCLoglz_ z{Ao&;S6&#j&bU16j6QmC(&WplsWmKwcS7RAq86zy;YTk{Qq7ZBp4_2GcX+oVI*wxG z_rUjKz=s^#-P>D|D=0pUiu3|K9(nqb?sk70~|& zQ+UuJ6Qu)W4`SC`sEy`9MlpMX-~s7Q?RBL4|NRx!LTkYi+n1%wF$58yX6cucD!_x5 zPje3n0}o2^;XhR(_u={k4K#(2n;(PtS+YYbuV|=}n8Ca$n5wc;f^Isna1S zovHU{KpIGacYJf58QHzL+zK_&@Fw0enuZ%Bx6|8pzztHw>~Asn2I=bhGYg-9_y6bH zP1PiT{$Dq5`7UvQH)|Imof+U==q9aq{0s`YLa1r?;AZrtN7)3jl{J|zTEz-61_nx@YpdO*QG{xODtJO5k`L5Zw|0}?WKK*y%cy~wCy9d z2kAa_URQi=1H)I4&&%wn(vg=G@%G`!;nza_wU2X8w< zT4H;jxkzmVc+ZTOMi#3Opp7EOl_Eg}sZbEU8Sej$y8>sF0Nz{5e$;!*5Fw(8>WPUG zbi6Z;`WXwjNZ|J)arc;#1G|r*qy1OZ)Ul0{E=eX@%|NT5iN9( ziX(PETMwL%-OliMK3g5x%t>4A9F39FY*n*N)D}eVsDE0pD6BJlsWpmK^1^9R` z`nYkONuVrA360xzH%j4!0zTf3c>(Wh+E@>7%!f0b{O**tk{z{}Z;+zOZ+!B3O&{+M zR)YcuKX|fz|G#JHJBEA+v{+aUCQ|qRLuv5dpKBd}Rc}Ypg@$-|XRfY2h2UMb*@*hQ z#qcKcb!236vSLSqpEVgi+B`dTK6u_TTuySKB*6Qvi`R5#fVb)S5lx8_3Vf83_W1hW z9B=XP?#-C+k|X7#aR$#L6Z`+>c*`2ob7^}ovfkVq^Rbpre*1IERJ+zNU%j75`%MJx zp})LE@LYRujovx7@Bd@wu4KrEF3GR?&A;#eu}q8qw~2uMKZ>RX9r8Z87O6oq!3L@B zId=kH4J!Ro(2mR?=iNF@ok3dd*Z(XBYLH2G^F*Q*8NMG@HGCd?|Ib`(pENSWif$iV zzXa5vqaDe=7RgdzUj<&-muK)BBHnqe_7&>`yj>2xKg3%S4s$j9K2>Xsk9YEu_B{XXGf7xn)}phvRTB7k z2QQYArCir#x#g`C)WNCCf(GyO60g4wCvIKlZGwk){KHNM1n>QwmDJ4%Z=(@mbAWe@Ra;`c0qFmo zV}qB2{(r&lupnghwj-zbqzb@WVw%Jbl@#Q0;>#pcd3?N`ZYeF7?wCnRMB}uZD*DrZ z;9rndxm&LLS(fzvwGzr5w#KZDGO zkM}PQ1@eLe(qQgQp}{*XcwPiny|;=O&%?u8s%}^b!CQ9bAocwJpx)6!RlW+KVzjDlyQ8~kU)f@BCODDfq?I&gC?qMG9gpf7fg|8XdoLDdLBSrEN+v80T zbzsa#x!iiKfA|0YZl1?FKZ{?J$VF3wj+#&|VEun!jSDwk4cf=?Kpt6xEUucOo*-T6 zfBR}TxPx>z=hpBJ8!~Lir{5|EKC!El8z(IeY7pU&%8qzYgKQQ#>(q^d8D#$B=W+4) zHHd5>5b!Kaiu610Ph333SLuKc{tU9}nB~G zeY&}lig(xX$_E1gZ^6f#k6Z>z>|PvO)-SA$hX>wS@=XJH&q?|j9R~1r-|y_ldoLUw zOW!E>&f{zD!_v6L*et;o-fi&*3{V zgAAJbbN=7u>&3%g0N#sVyVO2i3ikgcO4AnA#KSUP2e~8w-bs>5kT1adTCZU;*_Hy^ zNjx3U`kU8Vu9Q3K>Xb>7tkJmnQR|gm{^s?Ta&7M0z7m=&hj%UN;|!hremSm7ZJWb9 z-f1h6Lq9yB-yjjrs`z=ed}V*UZ5Z=W>Yrb=C5KwQ2{d>g-hJaFhByDFI!-*i)oum# zA$XUQ1*p~g%J*?gZqOi2EO&FcyMzquWw;4VzZwtAQ^>r?2B~_H+7z-uYTY`^t=EzQ zyYT7fBtFBh-j7FWl%ZA`k`o#?*0s81?^XQjyo|NqQW#%Qez`|rKAFJsI{?&L$2 zfBXM`Rzv>Ve+o26yfiiFxTxW2tOm95*a+g)paZev1ubBR%?R=dL9W={QdrBw35Hlm zXjuG|u;Y`u2^3_%&#FC`@Wo8S8yP`VQ)2kWPMzQr{=zHi*#O==`5}_?7U8d9^Zd zgETU@?AxL?_OC&vD^D}xBjNVtQbFqZ|3n@dyz@I#gE73=?pMeYyB8O( z*oxq7`>+f80UD$aRbKawgZuyYIf9$a0N!i+T8{|=ytjwAk8}gPRU*7?MHW-wjj{D3 z-~VO?xemO8{Y8t1Pt*s}SLf_e90zz;5HFTUfdkTO;bhep_2B*g_$^Yx0B^}h^-Z?`-lyWWeqC=s zfmd|A&1-7JpFxI2t$n6^R+O|1jZ1$Kcxr12KHl?`OJ7a5WxcPrgrh!;>Ex$RIOcSz zl=&It3l8|W+#mxpNar`(hVJZVd%OwHh8gn_d0ASYdc7r)NQ3vWkWL;9?=jMOUOc=L zoCLIy_y09KmQp`&Y2Kzm=?8fG)&2k9xGv!1J(R`eotZ2_QbFVHykF91eh43LDL;?XZ$wmCu6mE6J|yYnxAxAC zvB7_EK>9+HLe;A=`u%@xM5o<&H2W`aNlkmtkdJOY&GtU(;lxCU2Jc+gK@x`dv*~+y z@bKna^Gy%goS6CDf_lAW!E~MjPXONB58k@T*^*)L&7oI1!QR`PW4Q)m0PiEyyv8yC z-u+s|yoH9~apD@{$oD3Eyw8T^JXej7Bo(1?Sxy{sd8PPxmxU}#Yo261yem;3^z!pO zK&+dQ!+iBFb}`!VF@u5XZPdTLMr@S*=idBp8T0YI{ifc({r~@L)mT%5{$Gfu29SAznTQ@mS24f=g4ZU@pJDO8P0><2Zd;B4N$TXtmlZujV^fVOy8ZPENi z$O}?DJlu=N!5bvq6P!|6SHT8pAS|)g4!;K3l&n_aBJtN_aqsinI+p0**C3^!J4BzO zG9*^}C0n9CROsY)HQ{Z>tzXR7pxA;kmwjg$*g=w;8+s%7e?k9Geip)z53Q%-xdD>M z{=Xm%-o+0dQNJLCTyNoM6%xb4d&fyfPXzCN$_^^tDel`7vH{+DPv6;Efc^hkg1+32 z)_C~S5m*yBAnhHRsipyj*w#Ev?b5(-*yb&#f66cXPwdQ5ox>r$oLIjMjf0Op{gT#+ zf5c8q^}?sj+Y&5?w?67)8lC)3?tjhsNR@fK7vHd{PyI~)ddu&G%T1T|tz!EI$@hIA zLp~A?-tLdyg`EFS6rjQTM0MACta|GjJr}{l`=I2#bqLxkCpR4*v zSd!tNI?cu=cjDnL{)P$UcuQpNp~iIp@A!RUCE;_z;S(2|o{lu&;~i(EU&?_*2(CoI>o zJ>CS-YkZ9O;0cYo8JA04-r}dhyQqAK`hj$$dK+#m5yr!N&-`&$1n&f$HB`KRl&w{~ z0q|Bmc=(yDIT>!>`78D4E%16vnDrS^fVb3Xf8#8G_gvX%u4LJ8_{@5PM(30GcsD)g z6I#9CV_i8KSA0--a&{a(-nMi1)h%ixupHi3P#??b>^Q*UcLd4yfrS$v% zls!txd6yd49`DQk=aLxl0Xxi4GsvUj%}0ZGq5XL;ta=*@?i0epd$H&lCj{@3Vp}TS z^A6{}N6y|lCdtIk1e+5pQdb)%+>D1C%nvOS0(ig8-j?10@NS&om}Vgr4s*V~d8n@l zA8!ZS0u_NL+2$N*T!xi&ZC(^U-k#grf|E9!s$;de_nGB?eDrMl`}|6)a$7C;Fpqb) zoZ|gpB?kI`multk2iMsiZ-SKuV?K`CJU|X7{`>wPtNlOX|B?@wL5kDVpfg-MoBpan zqsG#BHK;A)%%Z!X2Awq#jX?VUl$kppDS;X^*5fcBI)@BT8+rfkVn;k&((!UGazWbW z{^!}VK@E!L+Zy^dI~>j$=CMS?J zx}rYl<>&UTW9s%M<{Kn?@521OCm5JPhBg+N5WCrb4YJ9RAs^YL6E5pYsY9$74c@2Q z-u$)yuRBPXj)!-wz1K_x?;o{0CgRyRdl}J!5?CeY<3z}HBe(Y zymz5K=;i0>BJ%lWKJ$3HUi~3uT}XchxpSdnT*j0&+YhmU36-&o_{gNp`2Oe!6>m`* zyvxcAPGQwMDXd2l5AP1SkGf7AarT-nVT zu|kFA@ODOh+@zD=6_{V=@nh!kp3M_QDwbtn2HE`~m(PIxm$wM1dl>TpmO6C*?Ej0< z;C;%S(t+Xq;d!nE9^Q*HeeWQ6Z?{#X;;px~GjavM+dfKNDaL{f@0WZ&EDZ2IuIHbO z-2c!2eJeo-;B7V%u(hE+91gnL{JofrKRMad`Y|lsS*$)7jayc}Yh9T>{^TUaQRqs+ zpd!oR?Th-@O((y;c^W#ViOl02ei^(1T1)@*7NJ=3mAYUz+gESGWvd=Wd<=isr+2!V zTD^s7@IGlouE6jX;MhD35AT3ZyBq{>jkq;Ck?MV{j>Fgw;GH4sswxAnw=9ZWwrxc_ z*qk`Yy8*fXzbRiri2(2p@qhQ~-nno%Z+^yRw?+7PQ~WFH?Iwik^U*l>vE)xgC49UM z6Fj=4%xAJ3-rG?hv+3mb!PeM+w1IiN1N#;{__~}v-UlCCDQJ!~W&7(btDjWmGvY(~ z8;CBN5`$E!h(!F+N^4Z79r9fs5(!?oj2 zw}BcIre7z-IURh1WVcV%M=-=XF0|`HKCvT|zq76h?EjC=N!ur7LxFEiy&`Vt#;-w7 zHqCC^a8IJX8I22ZO_=fUI(`k>*(#H8bcHI*)u8*Rj~#UKD;A$-eexgd|8MB^6FPXU zh3?K%Mcrcki4P8JKg8;*EMdsUSZm$QMCvDY6QyYIKHn?)3d8%=Jeiqzc#rXgEl2R? zAJ(NVv8zOy@AC(EUq~Ep)|x?v8>L^X3xodO?y_{=41jmRHZ8Lk0Phv;!!5Dj!(nn} z^1i+U_;?T8l+M?Vm8xHf#u?-H)mt#x^)1r?+xiV!THI-nkKdA(hSH z@FgpoUr$}}@qR^lwNaHvy8bd6xB8d7hWLDZyu0_-kCbfJV7cnuiTa?IpU56hZ@uTt z<8555s~~ZaKHeAFzB*c*ea`lH9~>QL$j6d&t;Fy9sK;9*Xz)Jk9QOgk`+7>IEFRu( zKCZ4q@NOy^r{aB(^NkzQ|7-86Rz08wUT@9Z{lXF89lGft2ht#I<8XqBph2q5X-m^N z5)Qw)Ud%g32OsaWi`)(BzohH2IP&52XgfZ9yz{pSpT6v^$#Qrnp+4y4w_A6eNXl>K zH%LXknPuI$K)*pE99k$qh<(NOc*pEDW5~ygO#Jr_tbDF;|%n!yAtEl)=Nh z&iMNjg7=bNpQ+1RC+;_>BCEG$vmDQ8=#t@Ca^eSeBbyT|e;r3wZ*8ospUePw?^JB& z?L80<`^U^&eDrUgw>;@8+n_EWQ;)^9We4{8OyO@%kT!n$;kuRe@GeAs(916~Q6}Q) zKX|=mUW4766l(_Xu23iXkD0N3|4%rl!jO-O$dp?_;PsY&_y1Y1-Tyx_0{y=nO%1v{ z+MV)O4Z5PFidTa!OlVC-J0QIR^>K+#e!7bb^a8gtKZCrVxBk+b)eJn4_NsZSQ;r(j53z(h#~Jf6`Ao-h zJ@x$m3>v&IU2OepgEarfureOrL7VQbK=7XGQrV8+EtPZDObFn8b+%iwC%8dcuU@}- z3LLTXH+k?}5#U|_HsVbZz4| zNJm1CEpcd$htmo|jwk@USE-0B$^&?tTAnU`l1PD#tvZjKRm8{pRf1RJ-sY$Tcu!?swcyxDf!|xsn)>+ze{%BNYpzM| zb+P&ZG*11hm8N13e)T@Q{r1!4o3w%yr0|^pzghe-Dhs^t?{FwZppj| zxMn|;-tYjwdXEwwJnXZYR*%IQb*ZF)hS6A$l>pA}0Gyc0|YsCdueZ@K#d;4Ny>aG)cI48LiO9P$D0 z|8I8U&PMPax(n^u0Px;K@;K0J76Ip-b=}(Y6n}^nCJ1(~6?j;ekH)p8Jq*&hj*s`C z7v(@~;%jqOs~;`D1*krH>Ex$d)XLvHi+Q}u91QhONVejZ3GDZAd#73L&bt$AKZBGt zWXwlrlW63Y2I>Z>0uA1^kyqof>fL^*LIV%)M&prC1n+^iQ$a}ej&i&x`WfIYzC`R{ zrXLxW4|^*}1TRR1?j8$6@D_UnTloOI9aJ|jtmch?>quMdty z$YCK5aQ^?6-tOxFZ&*v*5y88?(N5eK;QixQ%jn6U6j(D!5#>=G zfo#9L)hx@HkF{2dl=d8?R_~cKcwe3NpdG`T{C>F_9^Pb=oYx56#zMZ-$BEUKHB>DE zcwbl^vgD-`88&HlK3o8vw=5M=(ns(vH);6b2k=&?uimiPngUxI-+xp15`TFMo+j4i zC%{pU#X;vhmyKP+U*0Oc=so%TxG2lvZH)RTrjuWL-H-hB3z)Co7e-V<%H`=_PTV(I zdNk2@8rxUzI)?;?eB|&G&WVA`iU0Qh*z}Zz{}=TC>NGW|vFA-OR)d@tiW}h7pwsi> z?V3Oh@>V+LjtsF*ZxtIBf*GW}y|8a)BpLp6IK0^f?Ek|HF7+Ta=+G#?-WpJYK4{)} zr8j36tg1aPU_<8?+@WEs>(0i9&lE|TXj~Pnl*ilQjvMb@{qV+%Z3gwM_M6^@`dCjV zzl}Gy*QtFJ$MuKjYiNezC)npM{Xf@U+&g>L7~9t%f;MA5M%H|K+Z|1vL8{Tzz?eesHa=YN1+NP^JZsOxzykg^}E0vO@Tr_Th*3YA*XVaHW%<+vXm1?p0FsG5sH$JC@g;-=cGm?w>2H+U>KsFOKbJkYhh$81nIbWO%%> zEf3isRi(kZA#%xIc)#R7I|~o*67ATp2;L8uZ=-%7t@d(n)MkLU^|zvJG6>#r=j}Ve z46^*_k|zk>e!;J@*8#jkrqs{>xD)|*MQ*B|a>8G|eH!)q%A+z~QV$yEAHPq;bm2PO z|BQkqFC}(MNwZw_?m>Ns(8(`vQbTy36Z6&krZva><2>{mq?cYR-;M`{vOV5sa>xw% zXz=PVz7|hykW^^!zTwedgjMg@rQy1Gcn^CezDFKNH||*Jk4#P;Gzs@40lZBz6tnI| zkYRzfqdL~0{~w(b^9aHF-es;%cYwF!y>K_hq6j#my>E4~1wP(SdhEf09 zuT(bb;NzX?s4Nhw%FA+i_n|(r=;ZgoAkC^ip85X2e?`)CYaRN>TL^9kqn5qf#`bu} zm}N5LBTV0XzHUBsa-vLw_jPgO1`Kb#wM%sH@PthBWi1Sd#2510t6gBrA~U#8Ru)S&vWvRB%c?}7*9 zm*gdV!EcaO3O<>!tIUuzg2u&Fd?~8>fZrf}IkO_#4PMA{L#zYpgI<1jewFlEOHRX` zA>+ZrOZf5Rp*{oq{~TvbH}C9Y`x+GU>@-6@j&016*`!7tVzp`TzEe>A8^gP|_Sqaf zybtJbiZ=qh`*X5f5xjMh)=3!xycZ2Vx#*Nah9^l`hP6%cu%P`FS2cjQxrF8#7~uW> zo#)~n(k{4>Z`PnyKR(`-!`GC%|JS0y`?jy%U*G@R z_aJvR9^MK{O)C(*S5;)VA$Tv_yXgXgxAP>tbJbolEFtaaY0wxCd&(a^t_twhZdw~| z2k@Q~o7P!vvI{QDxOe|Y4?fg=f15?BK;yO%6vxgy!pA#S)s@q7u{q1(jrrI^ zCqJhjO3sCe%;Wt&)M?(~ZS;4L2-ZJ4Up=s4d%Ot)zZml&m@cmN=YX^(4c^Vht7c-= z`);nU5gy(gW`{EoypLs-u0imYReO+Z1n?IAAXVH5mbWyUzHe}8h==>``Sv3XlBVGX zq8q^5r*BO}mE|s2dBgB7%Rzj+XKs?5x&M_mNezvwh^CBKzQV_QTw0g2*xZ!m@Wy<6 zqLbeS7qQGD3+D0GeBCiJ^_YJ3zIZ$I$FBoR*?w{&D9M-)gZkqtt7EB?6Ac=?Z;1*N zVt7x?v@yiPyZ6>fD&CZC=I}n36jzbt6bXNb9&>T{ir@d2_A0;+_NkLb&^TB{d#g`B ze*b^H{I-n4@3}08H|FC8o&1j5n*A0eF^@O@nOeVhpBSj#{FJxyGyWHRy+t>iF&}3> ziYS2U{qO!iUf0G#e;>>s4QOgmNAD2zfi!vWiJj+H+z5CzD0cDCDP)L!ZpFVA8Df2& ze)UlYL+pjzifhq3$na3dK$$c6f|QlMwvR3tVkJ*C%iZQ|hpVOs{}>yMfHMWodGn^? z*Pvc_iXd2RL^^`T?bA}7Z54rEgDip*DXEr=Sgr=WMtv-#lOI?0E3aAw=68@hB%aOb zJVn3%kEwmQvb2W%@Bhav8DPjqh^u%YxsW=<>eJwT@1V*iY=|A)e%lle@1viLd=b2V zt(c@XNJ=N)j%Wb9lM|oKa*8IyQnG7rEC+apRxLKs0eFk{iKKM`yqEN4)WtrEfGZuv zW4>;~$NTxJIo~hLm`%Ej#_?3FF->#F$Gfb?aZhV0>*3vr`Z!G|zekR_60_Wy$9u;G zqu7Ne4B#!3wIw$)o$Y6k7ITXj@^Lgcbu6cXinksO-tBA7Ex_=WX-=Duhqq~kr#ynU zp;sGqdFyKCM6VXW`+J?k{?G(6yy=9lt0lm@OhTTZ4e;LiNV#?t;C=L()Ha(Z5pYKT zyPA#=e7wukzOQy%F`JZ)#*Gfn`W)qfk2lAC2c_9BSP${CbaGACgvMeg=6h zG;qU~JO(aEr^xEQeA>_UcoWj)81r%WvoHGo|1283+cbksFudVU-X?f>?>bS~j%-f2 zi0-9sPV60g7px2LmLKt2F+Y?AGT%fja$U0w)TY|KHeiIY-Dy;u^!$(P#^U2+te>|)8;kv)%)OD zx1yX7`VG>R6ZdX&&TwY?<*n0O9x&uXsJl4g5V#->=H9wAc;DsmI)mXIl5RQ=5AT~r zDJ2Nrb<1A4Aan2a@t;V@-kY^m&_#};WO!cGmIbqJ$HTWLYwMA{H$w6vS9O5*i{y{t zEjJ?JAkyh+avSlNw=UZ>u8O>7L<&XY4$RdPyzYX(yw#bn^ssq3>*0L`^+7K`XTFRR zdp(%1-hpe5%IiF3;O(uQyE?x(yRd)tj*Dc>hv6Nk=U)Hz|18wyO63=(_Y-WZ0Qg>EK-O4HCcP z!Z%3&f3o!iXC0V9N_^HmE1OP%our|-7!CX@cCtN>#~dbRk=)R@M;EjUZ}H<_vD4SN zChTp&dOJv%k2!Sm8_(GKy>%1wXOR56c5GS_&%g|l=hr*q0#EjTgJiD!C__GY16HC> z?98FT`*D0gBZl`+UR5F<-d!qR79x1x7}`$7n;cp8egNQoWPgXYDfs^1jMJ;gac%MN zYr`VKEP%JRi(^U+!28{`h`|ws2>3~jZTS5w_;_oF<}99q^+}y*oWJvjt>p#yc)!#z zp0PNV#B$49n2%mM`IXE%uvt=%dAtqFW;Y~WrGLaOrtVzcYr+?{$2&&I>;xk|7AHI0 z=qRAhAZOFy{b=RNa18IU@Q+-0cqei==plIT8djy^{iW74XB^;d663(P8a!`V=ajE< z@oqePIKLCY0qLg=<(B#QcyCx_^IF!?fE0tq&3vMHa8Eow z-h;=QzW(TiSq^V+)W-;&{OpO^Wo0{<$9s!rgn#x22Jo&LcwAQD#r88ui_PN<`S@PD zjl=L16>lRNydTO*|5d&BRMc?d;VtUWEsfya71h2DX^@)zLi>LKye&2@c3!dqOirXv zhc$!u|90H0g%P}ezR}!!8Q^`5tlfAIyfKuB4|iTN8{#?2rWC9 zgpc>m^Q4%FV%9soRfGDV(8=#e*52@V7v>wJvmUnovXb;yZwdS(N3x&>w#S>0Ju8(V zAL;FdNB=xdWJrVe{crnAuBB1~0O%54~aVNvQ zw}sp)TH@iLWiDO_-hm$%f4YcFPKtjoFA|A>XXjK{E;xmccM~7SdfBIjBvUl*=KS`s z`>FVNKd>8r@FIZq&feZaeLSR-pHGadzCsT3%Uf#BKQ}BoMgR2{1J^c(UCQQczr5xB zOnU(%K9aM4ChppG@ZbG^{H~jIeggV`Q<@soRXKbXt3hTO%LMUiP_eYPEpo-qPUQMV zWQa{T|I_R|s6mSp8{{fTWcb}@%VsaI#Qr!V+*J$IpsR%h@gJZDeVCs+O}mW(H&hds z4tV3&Ac}wE4iY$n)QrY$70OnOx52MLM;86gU;2yn&LBmiJ__jM$20U}8h0!6Z;&Xa zS8ojqr+>tbptR#)=EUkttOMRZ%;ffo8b*9r+-`9mJx85E&Zoh<7o;o7IjI+4eS1VgNoNU$NYLHcIlrobV9 z_wZ)_1Bz7?_}SG1k&A5c@s64}PmasgB)vrAWO%mLF4V)v+dMC9-59qC%QZ+bs1Hjz z`NePD@~z+>yddS!K3J-@j{XkPae0pYQqb@SZZ0*@)nsDk`@Dsov>x3|9C6ye$;>m?nYcEuF7>^nF2t)RVGV6gl2f z-l?$QCBVD;ZtI0@=O{2V23zf4ijQ|+{~)LKL2VK*8khGh&||j_KHixo?WfO<&u2Nj z`%xb`bn+{{K9*|j%6$KSyzPBe+(iaaU~_Vc`Wc+a)&eSXPoGagdF-g6C6wyzLEFOqXm} zz;bwFJ{;-f7u1#>KB2%o-rZ%pe{|iWKRJmB*4}cwMUn0M|ClM$Z}|-PsCDhVWb@~6 zqA?BLPrFwNV|X9!r10S3y(Yhzy7#sulDWON#7JZHhdU$S4L8k89!cOIZ<#)yf9hz^ zERr7@x9n4f!SkQ^c&nzCO?K9ru^ir*4{bX6=@&K5@eX7j?_F_sG+X-VPfo}dAC~dG zwPX9u2|wFx7e;)DmG3TrQ~tgG{|`Hy|Lz|H{Xa}ogI?!LhG8|xUJDk-t3eN^UD}Pz zAor#1q0S(+rhadW0&kE$+0tk4>`R7;l)&3WaQ}b#Qte6P43elj$9olU21#s<>^#00 z3jD+Rj^SfT{2?}E`?=JMElQ-{Xx#O&7)PH;{5MEHy$g9A=5EMxH7FGIF-a#s?y0); zc5mj_ATLZvx^Pv|UxOTwyL3(KkkjS=E?ocb|7{bqM;P)^y_C|wGm83x6p04!UcW5r zCw7tk-|Hry7#`kNJ)Tz~cyB%L;Egm$!Am}U^9OkEPf1c6@Fc_G>5o2<0N&*C#zh(c z?_H}GOvnSg6RRI>w=$=|lfJ_rLhj=~v0JTY{ODb~66qHjH+-t*okt};-n$Q*-a6pL zdU#_#_R`6(XzBTx#)p_6Vl7%Ye@?4pU z`;}#TDOSCe*1r+K!`sng%?AYU>Gej`@he~SUYJJ?A$YrP{G?lOAj)&}q%x9{yi z@V;62ElL95y}e-m+n?MN__cn{%ibJ(yrcU~g_UZRNdsuy%s!%QbT~fVZ@0*cYuFmG z+~j08>f=3~{5Ge2akZ9UesVJQX5v+E4*mY0(Bl8}^{E!N$D5$Kk1-!Yvwd>@?Ef#I z!TaUN5iJbw*qR6-JiIl^K5j(tc0Xa{i%d>RE&a5)0p7QRuP54WzG>!D`T`vVk;S4H}j?un}2euWlNmo*?a9 z^8`KyYLFx0@(|}?GAyWKKJVncc=)|n0~c}z$@8J@cjSnj??=^yjm8u>x>2BNO$&Yv zdPm6Sd;d+9v>S~};HxVCS%zPO1TV~+xs5W1;-uDYx(<_wuHmE zRZ2F8*WlwFp{Zrp=%zx-L*s0)ToA!ce3yPm9KSK5AW-!k92zZeb_yrJ-|HP zv+BHp@-8!QIgwnT{QkfUw#S=Lki(b{6Db{?KgU}vXz+eBSR{wxz0n|i8Xn%m5_%*A zZ|B<0UP$#G;%wcP0Px-$KAtr{gbb(lEaqGX&fa!pMw=o1|MaKc(}h6)-ymS##}!C{ z^GrW`x^v<0y=`Bgw=wmD5~%=<^RMrDzoQQy?@5(M92vVg|Z4nkSa{hM)8D5-si_;cdke=MK{w;F< z|LH2N##%7M#%z%@Ge1v(moo5}VK(u27+4EbnE;8dvj^Tdud z4c^0RwEnt5dgsBU93I|x)PiCVyn`EqsK;BP4(t=-0C-2Pc#wY!ydV{;<7;^h;4N7o zGE9BmGDY_#a{u2ZL~ec20Se4({eE7l3O?RGYbpcYg5@oKG;T=ouH!mx{3CXAH6+5L zSa5j@^I=LSKj+Wer1ChJzd<^=%sKzJJOeXGH_a_cTl3f+Z-SI6V?ItdTcOWeETzGF zNPqrGta>+B-JF4k_d>myItboxb;PMN$R~u^w+6rrGPp9}`I&>DK?;g4Sqhf7w1-{4 zAb95}<%}Tr|F=dz-qWrU0k69CLoK`xAMe*Yg*anm)JaZgoT`lF^wA=Gyian^3AV{( zz1v%uk2Cc0ljOTFag+J#t$87O`n5*-`~L(1`=@I(wAgU3BZ5AR6<|2AZKYoTcdb$Kh(@?QUKfOpE4(64pi<3t;y)2s#n-mYE5 zp9tQ1PwXeJ0K78~Iq1EWkAQP?8gGPL#>d;gINNnusX8eijoX))75pF%AMar~ZdH|C>a%;UX2%Ey^-hyLm2X3U58FO6JqyoDchvah(V6GX;E-ikaCxh-;4q+BFVBuyk%Bt&GR$Z8Q=5i=1z z5k(Pk5lDDKctH4t@Ll10;d8=;!Uu)-3hxvS5MC>6FKi^NDl8?;EA(AxNT^$=L#RRM zf>4Q2w$Of|NTEO>4kX}qz#A-o%TSM%EPn(^xKD)Nf+LOc^Z13WKy?()?0 zoZ~6vImok@XD3ep&srXP9t$2L9#tMG9$xP6+(X>m+#TEv+!we@xU;$Ub4PLqa(i$) za4+UI=GNqvUA1jNlX$@PJ&i>saMx?qgpHbHMeXF+R0Q$bxp zc|lP@PJzz?{Q}PfS_EnZDg+7yG6ePrgbDZwxCz(^kOT|_lm#RNxcMjfKk#?)xAR{Y zw&1GdI>D92mB2;e+RWw7Mdn(>HHS-`OPY(HbBc3>^A+a<&PL9QoF_Sta3*s`aRzgG zaXNA?;WXjY=9J?U{?Bp-N9BM1`rp4|{ojBP7dPkhA|a;@@e7X;bui^+*m0bwjVX_b z@{L3-Os#)#Y(G&GQ|@IP=|l}ot=kwlL{!Jr+J)yRL^VvU5$5zJs$$BuJM%D61yid_ zvm1!Ym~z>vai6G!Dd%-(&WfvFXmAq$DJm|Ff_wTdW%DZ8tmBZ$(NS{66HoCsFd|NNG09e3;|N@2=IU!tBU zi79J+hpR*hOf9+lWDRi|rmPO9ni9n^wRi)+8Bq*Vma{DCiK3WVB%>fs6v325+tz%d zFs9&wm)D3wm?Gt_TuT(hl)3S~RYU9{ zru6!=0-@iSnpKlO2>rs8?*6i^&`(V1tQjnTrZA=bSg{8Bfho<=s}0b1OldSFr$XN_ zrJhPS0!?B{&BM|S`id!4y9jA$0#nLAbTXhXm{NKieir(SDaE{!nb0RpDTKz#L*tl| zH@B;SK4NO7aM%iH3{x|nt%9LZOv&c;ia{fok_q})2MuFN+VZX@G=!c^DGz^;W*AEtyGCP>g*ObMM{ zAOO9=lwd;281x!b0=gHbLA{vb=lPTgy}}f4^Kd29gDIX94P{U_rnq;y4?!<6MV#X| z1$AKxB06k?Ix)rB8FCSN@t2aZxeh(Y6k#W~5A+OGj=vXG`an-H^-C`C0rUh@Q_s#c zLXR=^qdI62^axYmx9xoiJ;c;EE15aa158bNmrFtSF*Wh_F(1@{sV~>GmO%F~^?84w zA=HkkPfqK*p*Bp7YyF6V?qcer!1IStE2c(o4{AUym_pXup*xsDmM5Xxm_k-_pk_=V z%`bEdQ%J7>HDL-lwFfm~3OVEi-NY1fCIo806taa5-M|#G;|N{H6ms_ux`rv_suWa@ zDdc7eREH_#AU;%!DdgNTRD&tx1tI7vrjQ3$pevX{-lu>rV+y&>4_(3(a{C#&h$-Y9 zVyGHZ$g{1`1xz8YTtZctLLLQ#Dlvt;p$47D6!JAA=p3eykH0`?F@=091FFCj@@WC+ z45pBm*r9S%IqknJ{G4cqsl<$!tHfoPN>~xyu6>$-!cAXsAKwOBaNN>qS zL<>wsIIiF)!kD6Pe(5KYFtxMi<{hFrrgogQTuU^=RM_qo5^({hLTxjOh^Ckd;om$# zoR6t(U*k21CYaj#XmkT{9;SkKjO!DPF%{(gNt!qpQ-KmkRETphwT0hrDRDNYHeJbF zPBg+)K)TmHq9LaIH;0W74KU@W=$S**$CR(&&M=}LrhNK4b%?Vt<$X9|B~ceuj>s3T zq0^W`J_rnzVG8+vDs&1{$mb@ZlbAxj&IgrZsC?8Wb)?e+RJWO4k_Mja)hN;V= z-6>EmrY>D!f%EnaXm#5j#VN9Lx6@3L|Vd~tm zL{I1trp`LYeSi*Ps$#A(AC!ryGh92HpbSi%ZhI39rDLkB%-|H1hN)BTlny8rQzwnc z6;KMMN;!RhLI+Uglr-?gi?|&7S@DBMVNf!rPE>cThmtT=R6b-4?Z;H1{dq4a5mU!S z4NpS}n9A==4Tkn%Dz8M$7TSxcVfN z0-|6lRfkXxg=6Z#uLYsdPD~}YiOE4bFqM?`H5LlP)c#!S04NkwiKgn&Pza_HWIElU z?U>s8pw$f8hN<|%2R+bMOznw3oe2eFDh?Lahk`H_D|%xu6!`D=|5(4rBY^#Xdzv*! zWLAT%L8^w#RK;6^G*~-L61jtag4r`#9>ul}>&~W{6}THeh}SY4D2$spLKV{eQyV38LMVH1=PEtej%VM*!b( z?RCegOYF;O@J6QT7~W;8zbfP5Eh~12iuY{j0Tu7?anYZbkqy#&*Dmb@*ISYb`vWoo z-fMP$ia?Iol|OcWi+n-K|J|9zH?1jff>d0Tz)O6*E%t=+oJ^QWN=D;2_K%DY)#2kU zdYrFf_G4X^!`l+|Ax$U0^d_eg-U;UM4!V^ok`>qj(<`J8$@0A&*5YixgVdz0!jKO) z1@A>O_fem>u%p2n={qsJ6Q0~q!o$0H`&TO7KkhxG;_VtVpxgrR7S`;PkIDiMq{m24 zzyNP~pTlv;0cq_=vLc_s2I=&%1D@|h!TtXON(oPj@bTWdKxfC8n*wP!8pr4Ku5Wc5 zKHf2hPoCeBtH*M9hoC+Z>E!p~9^d(CI?Us(YUD5N-c0`nDM4c1m8-rp*&c6#8Dlo}b8{y?-JcCfDuS`78k+?^`Rw;(oO%l2)N{6$%F2 zmwoZ^COyk|IqqY?a(FkRJ}l|vr}1UMjGoWT<9#Viw2<7 z;>`f><#UoNk;{o68;|eo0C>+6PuR6?ARM0GW|-|v!N>a?_!70bq%vs%8s|Pqx!AiJ zA8#K^g;DQP);s@y9`zAGC%=f2yWd^)na4YJSU+~~H2wYmm}-h->UbvG<4p);%*XTb z)CrsVf6xEZo3ygT&q4pcilzo3dm~s4YIr$K8?Od!T&Ny~46!~+Yp8FKL1I4^>mekA^#AAH6%kdD2I;NfA*teUI3z#kt>0Yy8pQcBK_U5y z6lo_K=Wry^*+3k>24!(*C5Gy&v)m9%M135gli%nE<8*5w=4(*+ro$aIjtm@-PBRMg z=D*JVFGzP8Fy@1QWv=$0D|QYvcq5yA7~XLBTTMK?yU$H{Ab6V(KvcX(-|zI@3GkLy z_CJyh@NO?My`9<=4;M&R7$bQ5$tmno1b9E+UQXN+6%HTU{Paz`5I){-&B>zQ-c2VR zN8=VeELvOm-VL|UU83^r=>=yEmczRr^`G$~EoGU$Nt_uBn@xq>uNbsf;yW zN01k!qJ>l)5WJVhym%xB@Q$^p*{iT49KN;w!pl|M_;{Cmp%ltV z$&l`%aZh{oxPJ8FRb}A)|GLK+ zW}FMz9&f@*27MH)+phAbdXs7JMvh}(cpEK_R>#BJ_vJMM1n(JpEvR@qLt^6x0p7}r z0k7_Z&52QUgYdcF{{NetjR6SWvAbUiAkSOYb?bd!@--a(6c|9sO2o(8*4szzzP&7I z5{)zX*ytYUhd(*FKRL(ubA=Ym;cbWdctR(?BRS_RQ(rS*z0Y4ZTbHw!fz64@*GFGG zZ(x7C^BMC|W`Ffmej0UoYXuG7$oV1+?-N&+tKs2IY2l)--n#5$Ztv}s@B7DfQWQ9L zm2_XnDSW&G`8hua+07s&pm77?&wRHh;^XbDHkgxKqRn!62cteV(aA5tN%+@}+00jO z_swEyfj=3j-a0Q2cll0df4uMYG33KlPTdR!tGEB||FcAg|My9N{(tp0&$Pjy~ z&*JBFFvPn4w!Zl$CLBKWlk(J66u$;7i!3xWIz63q1dR)*R$e-12!93{bM}@hWd`dt zNXtm2h#Z2Yf>l}h{RH%Np5PNk|)IrgtXzeE`Gq4us>`p*o~2yV#E%-yMLze4mj$AdC z8)73-AC7eLn}T~CvbQmh_jH%tt&{iZ?;sI)BWJAAJk9=id&e;3qjCOL$xq;k9Z`*i`uz@^PZ< z)dt^@j}v8Yo9TsooalFPrbTp9I9$=rm6q#_kN3^qb-MSGBuJHL+`|ip-1O(*<9$QI zgl|%q_3&;&eKgU@FCcoL)-!_n>Ro*dzPGxL{st-Gu5Z{8HAS|^oA8w}ANI$JWHbLf zPUJ{~H*!k}!@Ko{y$&AU>d?tV1n;u&GV11pUBR`-8v)+k8P9dJj*#J+bW2a48}V@5 zsbAj^ygPIgf;0f$NlVyUo|L;-x#k3-MHE!d?-za z7a`3=A$W&+ zOh1M^kUqZbamVc4WcY;ejn8YEX@-~psTA_tg~Mry)gzn{|H zkL>XA-mSrJxlu)yv>A;%zPyp7qK#j@Z`h_Q)bC-v{r^3vkDGMzt607N(9}QJocO)q zeDH;2@)-2N=jf#WXLG`p7H{y@35Iv{4GTj&yx$AeK0%(h{GES= z`n=`+OGiCAz~;p3fl;p;;Oi~^u_giPPvYU#Uq(%k)myiak|5;smKpoQ4llbL4$Je| zte3UH$Ggi#hJ!LJO;SPQQj7x*u2RRx+jyU^mZ~%Bo!;t3eaxeiU+4MLtA721>b))? zp`~|_e*eFL+^&$2BFgsFo15~KAs=F0RddcA`nUgQkq-aw(*XUy7flU9UVB1nkOKHX z`f49H0$vR=OpBl(4btkoL~4WdV|a$4=TAR^)Szb- zU5|J{4e~85wEs3mfo~t_TVHz!{|!>f)x4)9W?wgNLgR9#WpMID;J-myo>zMIPU*e6 zzc>5e|LGCb$LjpQ&+lICMuR|C=68_NZZ4k~SwsJcUBVIlz-`e%Y+r*2d&C*?@vHH9 zXM72D2I)zIH}ZTLHpC9xZ8pWj`;4f|H3V6hhQB@C_K`MoFo=49AxAlB)sJ=ykTcmUw)!p&&J`ixYA?I+d`E4{VX}L&%%p!ce zrQ>HQ{2Xm%IlK>ULVeK5Z`JpAQG$n<$NQAm`lA!I^c$q?!%rjblU}er-X+tT81f-1 zylF}0pA)1WG6`@m|5D1M zs#9I@aFFHaYNY>PcV=<}(*Ga5mO0FEoC4ck^tiis9zNa$7Fi9^mmitipm95nr$0%Q z#mD;$K_^br>@CaT{TlVrNhiOF)|=Bc9x{)2N5vXXv)lA%kOaLT#kBA@Y>zi#PatDH zPIKJiHG!*{?bJa$A;W1L z*LySp-jq&0LuB=~oHR1&0PyxmUE^C97Xgd7q<39c*o=D{>$Aaw+bwb*&9S&o7DKN# z@~*>;*BRdzY+g-Zxz$_9@Q;sqbn<)V4DD=5V;=9yTSMztjkemP+k z6KEVUT%v4;I6mG-#HV?@4VGXzykDa}3h3mQI$@`K_p2m*O#kBb&tG^eZZDR1Xs7$< z7S4z9%=am@L=DuSsl$$?$P&Bb z{Y{%!zN5fze^2W=5RE^B97(eHvRL@0ITp7{%zwJ2H~tJVwQ=IufxHJSH-mIf{^O&Q zPJZ4ET~AAtm>*(=^XmFMY8f~n?Y{0^)^snnuR#RqO$_;1#6Rtj2RMTS@ZLy+H}VKN zhIdw`A`uVolBRn_2;MQtbEtT~JN=_u5Dc--3OCEI1(V^Pq}7XK0N#s;VL?d$f1r8Q zYgvGI`y&Z$v7C+$2{H+U2k5*e4vlFVE4ecyYsr)9`B3SzA@y(_T}EIKJnB8(mphJBd_{n zc!vlKbK&8gXfPIs;9Zw}p1OKFxFFI`7vL@aczC>I2N`y7)!-!pyjy2WSRkvnYp(`@ zSFzjSXL_@HUM5lCohmgky-N6auh=Vj_1CN}^Brj1$K9FLju1ZHc}h3te%mw1a@G3) z>Z6HHey^%SpFRBt_y3pQ^{>pxq`$mHAiJ1VsP?fv-Z8hF81k{R>R78>F|~So)8LJK zrUJuztwIea9^RMYG(8c#H`Xds@qW-9-0B4IzMFCRYZEw}xXFI&yY1ca@Mz9MY2@|R zIiEgG{00xCxh$7+Nr|Jt>RXmXxXa+_5nq7dUAby+0Mh>xMovbj0K6^aWM1t^B*Q#~TH&|A=7iZ= z+wTb8dxL*Aegt^SS`4_a%Amj>{Rd7(YvSWQ$z$U;%j~}S2pU%uI!9Sa0Kaw86@%W2Q?~*+gT%2+{YLDkaCnny6g!A#Cazfm_ZhV zp1+(o#QrsC+JhoSeB7z}rc?fBiG33d-pHraFuZfiB?R#BZqiYcM^2Dx-1+mo#lo3- zd#?e!DcxI+ow6sxgKq{GIsv@pMvM0$cvn@$h9docgX9Grt=e#SVzg35b2&cVyWAE} z=)UG7eMRH0iEN|z{>=$euJUD@eXV3z4(~mv4?a5ine(aUXE!sCcMJDP4*_NRc$c{t z*0kpMuziEH#4_RnBR*zW7Bu8@F~1Lw9dJKOr}g5+B3ieHYOohLNAV=f#)Y|HbRA_}4d*N8ZtJKzh7>xN|6u>G8&W zc6myZj!3pZi$C-K5GuUkk6lvmJ~eZe6AkaLcrG9KdQ0i_EcyQb`k=yfJpgacCP-tc z8v$y%w!vf(*xnlHQ*MKY6VLbBTu=gdrz8YK4adYnzg5lI@SNy)m*4P?J#9Z~PKnFr zd9m^S2>RnhJR=Wvyl;MGxCW^O(IJhI-`h-%^V@srcki$Ufxb8z4oHV)CT@5{{LS=u zSB?GhqD99~qA8)hnC#xcRCvQ*Z>8YvzdC~h4R2%r#lmp^Usd=v1g^cmXc-CK2YAQN z*#GwMAwa~oocAYSyjwM0V7%L;ISn)c-U=rPJX*w9h}6?ul+A^X_du8}YgYS-mR2P0 zl>WjkI-}@#O9_g#mr6F8|KE+p|Nc)p8~^B-n*ZznbDfVxf3JG!N3uEG+8) z9@JfM-WB$s8In`=4DcYF@OrmHCkfE!VyhNDa6$UMDf=l+;6d)Bs+lUV2l;IHyx*hE zL})|E3x8WK^gYOgIZHm46fD9AAaM#S+wO3@N3S5u-x?lm6{tUZ5|r`wa$H)%q*oiAY?IUXuEBJ38Ld1@7u_8yB{zOmEt+(cz15vJaf^)iCMvuo z2Am-Z-VgML=Aq#|u|Yf;#+wW0bSm#sZD8T#oVd?5}aQ>g`puUGJI6*3E+7b$X zAgwMx`^6K0_j$cy4~Zp2XeVhI7uOARyrb}oAK@3u;ggWKdp)ypR@LZubARhhKX!)k zK9IH<(ZP$6U$CEhE{TQy3R08(Hb?tG8Y)OO>E5MpRx>@`xbs@H>EN)|=lj$DM^ND{ zUi?CUg7;g~U#k1>5Z3-TS5p>jPIa*Bsl;7h;^hM z9*{nsGU=QGcwcc)&C?hnLTfjN%9?IRFHWpf(6+i4@jM>S8uHo zX1uSrE=P2@V&r#Wp`pU)HTvDVLClHk;|uK5Te!qrKM(mE%#U}`ZJKoOhxJO|__KQ( zPKEcvO1UKEKFFep5wKt#v8#UJNzBcJi`rs%-R@1?-mu)0h1 zTlpC*#KZ(RuRk8Nlsh~GVw?o~2;D?PEt~jCSz{-z5Qu|Xrk$$|5 zZs!Sy^wZG)f2!yYkr`%wyh$f$(y^lCeJcM+vU^8U;VrXumox?M&);K((C~InHGp8e zOO8seh28s>(np)Q0B`-ebCtX;1c+bOaGw!)z199_n4vbn`?9pj>wN(4u5arC4>l1Y z-!;LPE;yp&?YHw${_hfHygw3$&nHyqEJ4Rxw>T>7^?XBy!<(W*4<8Mrc(ib`~Uy#)}E&SKIs4Bs60rmU-qB* zKdx0%8qI@hia&6|9%LzL>H>R^YKBJ}>_Mr8R(+&11ZWNSyj^{uLGpTU2*GENye4XY zYlHq@-_KMbONj_sPqDrhY(lRf_Xj*Z=iRM}w?X3WHl=cR=A&1TdnEbgG_@G7f;@oe z$i&Fcnzxu3GCLphEs_8HJ57vpm3JDz?*DOj9{Ifeevj!r2nX$4Pm2zxZ>6pA$H+@8 zkqU2>Pfb@SOKe=ilq4G7Q%kzNV7w16IzV1xEepoR*#X{KS@+L(UL-)u3pKuofbFe2 zZX!W2-ko_~YVZ*|){5U55cvL|{D_X<#eL{_Yk!)rY^14*S3=?>`j0xV4MWF!)d5r7 zm0ZTFAaxKO4jB2J`7zm`X- zl#F*Q72e97d-qfD_K&_UfrfWdonRx3_rV-?a{uqu&HoW@kd#ta$`&^hpxb46+#vvO zJ%jW6VZ0lSv>-KrcWlx5BR_{@q15{7uaCE&<1MKg+p-V_}_G4kUX+_$LNjDEZg#%2dfpU}|%A8Oy>v+4@-p1iZ9kPkgy%>pOK1%3#hsN-^)vQ#-KS1IfVjD&;aH9AB<+(OR zJI^v6-V_~W82P1I2pX7i(%=7AOt9rw$zb>YAHF^Kn!oo6)7Rcbaa!MK(a~YCD8VcD zZ~y5J{eP}JUS=impvT&2 z0&8;#5T|0O#GU>W=<>ITGq4A3=6L%WZjeqL2%Q}R{eQ{DZ-?UlrT@>o`8JWGUmahD z#D%#_WoQx z49OrpNu7+RO~;3RW8FU$Lpx`~i@<|>I?{dhg1IC-(a3LA*L9JF33xIdv ztt%Hb!TJ9O0Ubs%;0sbWR1*%sc$=2_vccP18JxFypOq0IxkG%oaAWi(*18I}xUxeX zuYkl&hR5hHmPB7-Ma!R6ZkAv?yq6(5u<~nqwT$offAK)t{hw`V+MP6f-a_K(-qzyu zMtVqM$XLhgH0fCV*3v%t47vYLpu$`8a>;uN-fA}Oa%gzV3rx1bcqdl~knx_Ub~iu| z;9b;yv+q_h_<~f7)8le5L2?=?4Ttf*YTm1@1Mucab5dWIM1;2Gs3uB^qT_wEUnMJe zk2*dEi96$04)Om$ckh$ujwxonG+{XRE$RF-CM|we)mpt(R-rrjg9xJFTDpg z#D8XbyxUmXY0|+{Ab0m^1{v=iRCsG-)hK6l3kSEij8wCi!FX%>+K1@^yg62E7MI%sPH*|HOV9k5%ZdClR|@py z)bScf+{EkQ!z%xBIWei)w(@yAf=^mtnjWzsx$rwf6`MA&>*$ zop3L$ z)$qAU+$uJ48H?BG?p-wC9!I>(c(b>Sh>k*x{Em&kC{Mpl|Mr&bsW*0GlGy#fN^k=U zJNtE}@Bbfkd$7@>!?or3_QABj{Xat%nE#m+=>OTNJjh@k%Lj@F^?VRiL-Qcn-ycfh z3DQ_?3HgYf_Z%LRZNP)3bId(6&l8|QZ&lKGZwe$G809AqJV;q7Tq_iK(7T;Ui%olp zkYQLw&@+E@4>H}$yZS|=3f>rrTe3|=>#Qw$gY;%W)KLiq#@mCmLUdr|$HV)ud9s84 zC3gK&kNHwj-I(VFl=fGRw13>l^cCdoi%KtP(Q!N3?CI2A_<{6HHY&XJpQ(0H@YX6B zRYAl1cEYwO7;l~QLGt{+Okc1e65!1;Px#$#u*626NMyITl>+@X9{Ar zduCC=(jR+?kOIfCaV`aPyzlv0X87Gv#V$ZA_0h?o}yGI_kX~q(6~AZ<)zTh4;c}yh&zMf8;OuQ=fS{Q96H{2uCw)9-%`VCA#oc&x^d1MMz0_TuZleG*I>K`=>ehx zD?g4+7h|8Equ;$#)>IBVe#OSy>HJ|K(N^YfkfNl^Y0`16hC{$%7umg8sPNW{8w;S| zy(1%02@P)xkw|tJ@7ISE$cGavq9Rh(1H6s;lSS(a2@v7(>B_x#Q=p1u_YW}Mou^;2 znFGArOe{`7&P3>I%z-m6U!xyyQDi@vA-PK(KZV2zd}Z~lyN-_cO66qJ%}*E)Z&gGG zR(_Agg%&-3MZbHSx!X5Qm1Fn+iP71vM&jd4@7{@(2WZlfqWFA({f~Rkp~72t#bh4^ zZ-s}e7NOx?eeie}-2b1trbOP}O4X3~;0*94oZH1OmrZ~q+vauG-3PC?NEh6K`~NJ3 zrU4CrH~zjTx9vJ2G^>)sV(=9m?}<=V{tJ!jcox+^acVIgNA3I3@qQ?>!tKg@#v4vd zB02^z@-y+gF7K~GzkAp3_J3nphJ85k$gbB(kE}j1{p^i*?GQ~mt{qm5)ZUZ)_x}HX z_S%g2GiZ>wsXWNcY#bhZ~2#!um^4H^LK>zAe+ynJ52!(suyXv%>@of zukycdW^z3R>Ra=0C;WnR@SJ`n_ynol9fK?KT14pEhPhck+R;7e;+MO7J111}-;p>! z)@2+|kD+_eMxMLb32PazL25yCgkj{z$F}XjnjZR>*ovR!+r}lZD@fwY=NBLHL>n<8 zg7oCX^?8gY9SxN72YO4TAL|&pFBIGg@(7^=-WUT??H}3PB7kSE6skt z0eC;nJ6&7{@IIPb>o@}NUhHm}4==Iz*2NVV0lbr%wCt?AW1(be@4dC2=y-qgf3nW& znF>A~iF0e?`9QC@BbP{`s#VLjD z9^4ee^myacf@srGmd3Lz0G=Raa#G=KTz_wzf_Is8wI&+gW!`Tt!gxnC4w5HG*P~Wj zJ_LA|c}5+IXdpl`oP(p4H&UR0^Ssq?gQOZZSYQM2e*SSD*SZx%s9vnI=EXB~ygl7K zq%Jlq8j$F!p3ZE~~OX+(qZZji1=bYSHd=5q91e+B*S9mi@T`;ny^bN3e4 zK6Nr631>`?Q!-@i>?4|VByUYm+f@Y5|1&wL@HW~q@eke^K|~ESyi>M9JaGRXX=p_5 z{|V~uO>F>g{u0Y%LL&jVzk74%C2&b_ z_F&?@VWQmWhjKL2o_{z$u6QK7jb2LI1)E9Pgm4B6&>#aw+s*8EXKn-6VZW{-|)GupKQ+2@7`h-X>V3n zVbA|@B9YlEJp7p+Z(L5}ep+-C6qHYA9{$_^Gvo^VpGkowb{>@nSuK! z51OvKwL9K04ssTF8Pk0SeS&mzozWETu_@^001p;%@Q;iJuB@i{7Xb z3f@)R_w~{6j#|w{e*fQI%AI_Jw7%eO>u!MewuIJUGZL8pZ+O4;_{|ikyj)2WUSc=0 zx9^Jpco$w(w>dp84$9l~dJ{`EI^NcX`~%tP>i9w=ZgP3`P(l_u-gP6*GxaYRZ-TS} z(SeoU0Xbp8%Ov`j*gTm~d%YLf{eR+N#nOp1N2c%p6FcN-($SI5a*jm4L7K@&g*Q|> z*h;~B$h&ee8s3k?$|c|m@|9%_xj|Yher5N0fcF3|AAfQa0ZMJm)h-7O(z2oG6>$GA zB>LzVJpWI*vu!>%PaJe6*@X>XfsVJ z)KUerCCAb6jy&^g&G{pYhj%riBMKwGPa8Lx>)O#@oV+vNEBGdZh7Y8d-3>J0-N5t* zq;YjawCPy9L4EFe^6o7U72f6sY0eb9w@e!9qTwBS^ecJx_EUg9yzlB?@r-W-+gnjJ zNp-8y@vaR2pdQYvj$ez!1s%GtHD@t8-p8`saEZZ;SDc(gbd+J_7msUN%JE-(-tvz3 zJo{q`*vDIN(Q;}7T2suA_YystbP#(?GSv>m{GI>*XRpnOKZ7M!n974}wVj$^50Vv3 z33wP3f8mhr?{~x|{VYw2hAPX+;k4di}Kxd=f)5;&DKnH)lbC(1a zWOTp|$?Kqklyca@t0Wi)$t=0BxwaPFgFKs#t#l1ofR{kxLg%n7vp<0DLB_r>ql}&{ zVz@2#AVh~LMt*rl_*GWv^e?e>(b}G`G-%j^B#7^^(M@Ff1_>v#kR~0;bu6!oE6Eci zAu7C=-+bUnSz@Q(UN=F*`(XCtAQ*2`oKO&q_YK`)S!ICtE}gFegF(>5$?3lWseeVdGu&ZDH74o9|4I_X$lgnsnr+ zl_VcZCU0*EQsKQUZ@&oz@45GKjnVKvv*oE2jQ9TDkpLL)$hA3bFy4vI$L`dh1-rNV z%H-C76QsBD8=PUh-zUuz>;`!2DyU5@XeL5>3K5Di&ggij$+`u#YRlnuk+=-62bJ#) z(D7D0nDMr)i}Akymxbt9gpr@N;f4pqRQlcfv+>RJgc9ug|G11Jl0Up>m>zH3*+Vqx z@Ro@aPi!Q+w*VF1OZ~XbD0s_t2OFW`J*x8K<~4wKzsC`O7;n|KIXNl-Z=Hyz_l{pC zKx1#E>j%O4e{tJ3Cm8SRuLGrf0N%IesyupfjtGT`^E$JxM8{i;SA}qOog$tRCw2iE zFxNuI`>b$?mha2O4CmhZhz_j$1dkkCf9WRuc(Y}T568=3YGlkw*NZx9_=`DqK@+Be^Y{^EpNnK;tpK|}vPAbBBz=l=(9 zZ+A=3rh})&F&8{|CrxP!5gH)Zztc10}t}6 znV0q$c+lt-bCE|ch*0pBqKef-^d;6)wAm-QbE3r$iR)T&-v71_x(B`a_`oTX*?W z<%bqV!@CmEp@ETKk4r&zKM(zQ>%6=5(r6KO|G%EADu3s>ai+)nwSFZ{Iwo&VS-sC7 z_y3|)c(2?&?m)r&gZ&sQ8s2yE)U{!}XR5s-V7$vVYt7~Yyp0|Up6fkAfUb|}>1+qz z|GOx*?+A?dbc2`i9f0>dIipFlUEl_(FD~C%3?1)QUH;kj*;(^nNSxgMv7wM@^b@29 zEJIFbTh3#+2I(!LBM&3LkNuvui!JGIkUDdkIHE?d-8&JN;Anh-`M0+c+v8}`F;@3s zy-5YRL0UkC_lh;!lPGxC9cyDj!#hWD;^1|F_tc5!8)3XjPG-yQ0=#X1RXoZ9_y1X3 z64L9z_y0_qM8Cs$t9S^mx(V?1^7$a3lR$)QXU%Msh0*aYYMpN`%*KOXhQ!Go){2*z zM8`Y+PHv70IOj{G54^p#Ou|673*ddVai}ZoAQ9r#Nd59c6&>%K^XY;=%?0pWNZc~@ z&vxFt=*0>57I8O&2eJ%@cQK-a7bCyq7wf%;dg*uXRk<(Ni!NfH-oj-K+#SyS#QgLB z2Sc>!@E*#8-`@V)|1(;-{y*dc`hRIE4{{zePNpoesv8}6(LAVL%jY<}#CquKhru4y zEf%gxIJ4Ly;;v5G>j~o4Nc1JP)_zLUe!B?6_5aO?juRO9DMN$`C4KrEq_nhK z_qMgr;6XP%zPR8;nZ7~7WgenU$02=TJ@WhinNn1EJJo9IQ1HI^WC0Hv-e-Ex&cb-# zbUPYOUSeC4cLxK!FFF#=&ejm1mpXMz96zQ&CyIBu!&~fOOVy7b0(eVA)?Te|iG@}u z-LaHkjgGffMAF;JA}-Q0ByOsWEi_029q*~7Wf={>#TX86Lqx|{jQq}}U7ywcLjMxG zVtcH#UM2SV|0`m_J(h7fOpmvk5_h@egjqZrI^Lf|k6-#}EWvPiA3=0{z{oG&W?cA! zA^q+xIU-P>n7V_uyEcwejYe%D({fS$bnt|9a$1$wAxln6ISu1!N<8v)*1PqXZ7 zS0zGMU-k^&Y(dA{+GB1;K`9TZ4T<~pWcjYPqv&{d6v@fjPKq-e-ir|(tr+?F$n>tl z|DxZ$jqXaMr(eaM|Kn8Jiu2N?n123`D{CvEMTf(ruG_so+gsvPc&}F3VoAaKOvHW; zG`u@KW{lz4o5Phd^6c$nW{3C?!24rJy`xV70eYjKG)LxT3iNW}<9+b29qh38jozdoM7bi`hhN9GU#vb(18+2&IU z}UJrkBu2-O@D}#;sfO{suttG=dn;{Z)%Qq% zHyfMc>!}g~w0dQ*@fg6HASG@j2k?&UT|MIu@V?G-P3z}tB6MVVZ|;RebiC`*f(922 zeQY^^#7Q_t`-KLeibF80DXth>mKE{CbXle0BUZ{qEg82WMBQf_=Ot zx6-6E-BXn5E6Ac#YiQE(N>d|;kWO}QSt`8OdY|4+!Mp6`DSkA(UwKB!!@IY!JA^`E z_co2$uiyvpHVXQl`vh!nDda2|bpgYPfs!{C@Z&`HZ1XF&0KBvFYRBy#5+T#wC+{EK zgpPNXox9-3%9$1eB<^rs;Pp4o=y8>oc-@%TVF%!u3Lmg7>fVNIo>Y>wc^v z&))bZ7t=L+i@xWy$QHPF7T+`B>7D3!&nq>(>@LAV%0%KcMa~?r@khrye)i%$iCO`M z!Tb~^gT$zy@E?p4|wscNZb~g zo_gzM^gT%bW8;+@RU{d%|6haX2*Sv3VCb7sXD$6pY=hN3g;hN?Jh9Ukw5y2|$MhbA z)2C5K$Z;O^KNBQnD!hGa<{Y5ltt2lXiiUTXQ^+P5Z;Jq9^8J6FMDsuefcKTR4w5Tk z2++3A6?1w=QXqA~?{0Aa-i3)voE?}Z?WU_abK1^%wm4L z8-IPKMaQKDcUph^PJtgtQ=-D#J1~O$^;Y-RE?|q041C0EtUx^quchZk{$>HP9x?0#3WTwQ) zjAI>NnI7-<^lF-PGz(N1oy{XRNQHGPjRA1g|{a^i$4YL-o7v)G`zQ74&4speJj!258mG5 zxbkpECcqot9wgiazW?Xwy(E(z?A}(_q`!pm{?NNK+8E&djO2`4M~s7(vn|0_FF?Ql zzbCSYbb2lu-U5lURa3H^`HhZuP}b<4XIVlFhj$L5BNQXQ%xfbt`~HjJL}K?Yj|=Cq zcW-fDBbT=YNHRa(SBNy}a8m8j+*bX!|Nqy%n^FEHs30||JSgDR6LpFQ{f<$WM)RQY zCwEuDN9_DQekR`_P5YG6)CxQ(T6n$Mg8kqVJI(i#_J9gUKELWKB?Tx6%*(U;g+*YWCt(f8(TNSvBw--F}k=pMAo&?L~w@+ZR$NV(nq=*Yy# zZ*O7YN$z#@FR?y9gB^~UV>d`QUv2stdwVm}d(hR~NSbsUO7trWv?EuL8dP}u=cPMR z@GctuDT#)6iH;g8jJI=pBl-NlsF9oH0Kj``_lehs(g{%VQi%)PqbX3$A;I0-7_Qe2VNFsF6o~^QUE;`;bQG-b*PO;+akhs;YAD`R2LEpXY{In6j&XDmc zNL=(E9bFjt3BN4O6MaN~|KE8yj(6!Z?Bgx(!Zi9C#>BET^LgEypWZI%1qT{XT zH0^h*N0i~*+Y`~Dgppr_J@2%LDE)X#-46@(+eL$W&)>r$#m)Smw@h4=Nt2Gjims14 zE|QBARVuvKPo4~<;9Ylr{X#UnU2z8|;N4q^2zT=R|9i>jg53b#yUv&v*oK4cEy>ph zJHgvq&hwr+!Lv8LHI@dE0B@6nFSkl=BSQPTrj-SF(cQbYGxer+4>vvoiE~Ox9(+26 zjyK`z{MENr8SiplXOtHIU-JO{zaEtbZM<~wpBJRYm&qxjc~E{tV*-2!Nh$W$W_S-0fA@fr zC-9)uua`8TP6FhQk5CmJ0&kG!-wPB49<+Fp*d_$}f3^?)8S^uV(Dh-l6~|@KJ?NX- zn|(98L0aFnR(e64DE?oy{xAGXiVh!){7P9_KP3L7--C{sa)v8# zVlT0MZi*9}j*(2?|6f?EK$DK)--B|wyU9zeE*0LP2R5Wpme|tRX?ZlfMU@V&gz-Kl z`I~&ju9L-TE(GviQ~W)55WFC*y~9)H+Vd1>p3;4J7;njwWjIlQw_z(sXt*B{s<5v~ z=KFzOK~76g$Sv$u$4Fkm2zDj_44^$Zt@IL)XiS{{COr z)Pcw5G7S@?&*jF4C5TLqH!krQZ91lLKbHKNAn8!y9TK+fBL(kDg%&w9yr1Sp3d490 z1WA(dzO(h^atVO9kHs9jiFyL`-i1@KbvOljUm*Q>0l>S<&BsR^;BD&}{l%3n4!YIz z+3ML*bocfxIsDDAWvZnMiE9xJI%%~V-MuTfxN(oDaxfg;K8TJ|jQr*nwcsN;=*L^H z<>1ROBN`@1Jl#6MciEY~|Ho~(Nt2FMQS>JpL-bXAmWzq0nEfoI{ z-n}(>EFT3ICq@<8&L6<`R-IF?l_>Z)(XX2tCW2u1)?xXhJuu!UJ6j%00lec?&arR( z33hKEZqsYYMaO&b9sUoAks~bxBref)mgi+GI^Ic!L1txN#~JQ=iyERM1|z?mQ;w}R zkLbtS;KYT9@_KB%x4n-EBxP=4dc42?jH5{hk5}dP>#5}JEiEd%gLq@MQSeUr;wFQJ z_XerNTo~{6BlF46TX@?1cwYa-Uj8Bb!K2qH&<(?91~A?SaHZSi0NxS< zTp?*QL`X+}B%uE=I^IJ8oPOPR8_iXaII*c=JGOXqyf@U@pBf0d&Tz9gjle%T$}#f8 z%P-1WDM>%xnxAX#tg6GFz2W>ed4zqN%k;%bqEr-3IzC+~h%l@A+yDPBw43z*Cqe&j zNaaCM_doejJV^Dah#Hy)C5&%8+Y3A>sdXX|UScyk;@k~E1(}_Zm*&Od2<5Q3jC=(R z5|?-v4t_x@`{IeI^I#8h{nq5shl+8KM95}2`&M)hdg}bD)oGDDNeqd*lyO`gDNVMsAAD+Fo z`p@_O45;vq+&->N!JFVcqJoAu%lpS%Fy2-LPy&p%M#Rrf_*fS8ivO;}&$h zPp6w)FLl&lIJ`F@I%+ZUi;6nIx`|B~^O=hO^si(gtD0mQp4f4dN#79={E_MLmcN`v zla9W-nNqLtyqY`td&XDrBg>6MOd-w>K~FTHrUP z#~YVQqmI$rdU=12x9C&h9U)wxK*4)eL!uHI-laA@89e~+VouQ*81KpKsbDXFckaG- zdh*Y}>n)FbZq$GQX{DL~-$H=*RQR&^?*MPYHj6ps?L3FNYIJN7jt8D9bV&-fD=BW{mto5-*88jiae zB-8i*Cu?cbktHu4p|ykD|1YM(JDfY%hJv?4r_&-dyxpzto`QF8C9Jczzf2T{AN2n>H00Dh!P(pMOCn>}dZ4?vYr4pb zgi&77DJ0G;W%&ykJi2?&_wCP?*Oz2CyeT^PG4i`pv;J;g1O2nN9~q4@@h@p`@AW$U zD}J#szkBc2rb&n0rf|W5qQCwBe-^V0`7`MM&8R$R`)O-0iU)~{i0GhsQ0Ckt&*2Kv zQzm~0>_G=7l~mG!2Ynr#=Og@@0NuTR`O_ir1*!8JcMIzP50WCNbi}jtL9sp(8s49Y zP}joQ{fQaq9wf+h?}rJyD(MOmms2{c7Z8E&L0t-0e$my8Y`-mEKI7qCis;D3$d4%B zy={F6{qB8TKCWG^hK36A3ICZo*56EzH}2&;nsi*_iPX9M=YX^^72aF8!zL+sXBuqR zK*Rfi;ha$z@3swBli=cH#mP4s1c0~JgSpGwX2J6oInUiH!1mVe{_=*L@E+A&jthOf6o8?(fjT6!>j|34kdN|O%J_`|M2f4<&gM1^S%axFetO{19*!Hhwp~*E{}@3tPSu!*_M3Tp2ra~h$6D5fa@)zW?RkS>n&ri z6{ku7-bT|(Ug>AS;Y8nqclB4GtC4u{6B6!jXL^Psi=a(iGRQU$B-TW z|D6=*|1GIJXvc|<|IGgbK5`kLc~JP+L;$?RewOdp34734FW>8mz=PO+ur7Igod6XN z7N6(`-ylgEo|=OD|G7GydxJoOlr*sXXKHdRv}2Q>*KuL=1Jbpv#G{;xlu490ji9SX zmwxs@9U#hm>(!of#DL*Es0Ps?jgjB6v>!bA_vqh)tn`c8_+sn|>YvL$f7yqjSC^yagphjbXfB2XK+`e*NG?z5&2{ z@7=+Gyrymzo({VX>W3-PWWS{EOMj(2zI`-c&N z$|Pz%)@xUrmmyhrW_TROU6U$MiTaNVPB zRLT5!8wt>)Lp$^$_xi3R7;lIQ@3=LqxhZ&$rZp@^!#mv7lpDs|JjAufKyR9y0NzqE3$!90#X{#-cQ32kh>myDxh++j zd6h|Lkhq^-hHG}%q2paM##!)HT7TG#GC@72ZUaZ?7nLr-y~`bqapT5r z%-Vb6#p8rpqbQ~?PDB!E)A9L+&cirxyyb8I|4;YDxW52P>~bm(+MUN)4||XtctQF% z>joT}2X&3luZ1hfp$9|c36j&hH&W)ngFXb@T0PW8fI?*wTjanCQdzOPm9>EfacT!o zqyi7R3bCj2tYd6XUc?Hq12N~@sQ{hs;{CkjQ!nElKjIEISb3u9;72dntwm+jR zvBnFpnxNtRLDZ%k#@laR8yRmQpV>2u0p6)08`n;@6QG6o-6jjb_SOZcY8Q;Rc)p%% zBEZ{XL-4*Wi9{&<(|)CW3(%L?my^aEA9g5{C~;fokOVEhqvKsol<9x{k@4^zL3C7M zHOc_*^S_>)HSZum`;O%p7=R1XyaRWKV7wud znV49BH~!;Q=eyg9(2tv*ZmoRic;6=|#U~t4CQ;&=ZnDeRenQ9ll%tf*&pC`&LEb}j z)L`UCT3GGwtxbP}q<>w?VS%!Fh6I{)G>FHQN^p^nw^&o*z4QBu zf3~-L4|*A);a&ei{Q!)2l)^SL-hSQ${{;YV@Qm5kj;jP{P+(0&7I>U^>%&?+Je-g* z2ylr8c(1S>E%wL>5Z>gh2hsc0miCz3|czer=3h#ue zNoPuN(sA9=5Do9F6>?;}=Y8Kw7v85$_nh>ujD<9VZCor2&};7<+H%e*%E}~4+?~%$ z7M2O3en(Fn$_!1SAMfjpyWj7Z!QS555&r!4u(A9<-9mgEDdwn<)MN{xZT`G!Kd%U(ZKA|DSC}g!dp< z3Ei8(fhE@Cgo3u?H3IZ*olD*<=>PkbS#(vw5-YZAq3T<(#LC$Xc&d%YLfelKjGeZl zdyvAVkvg?9dD1o{F0Q<9(fc*%9uyX{U`ex%9>dN5@ATDMH&F1t+ab-4hPScp^-vh^ z;ib*w3(~$WudeX|yf=96E&2i~$oDFPXVU@R4JIoh)BxUG&6?lt1H6wIUo~&3h=tk= zWi z`Ty~yKfiK_U~hgoNkauGF~ueE*p}(>#_@1+)1u>aTJyz_8gl<{M}>EqzTX`R-nBk6 ztY~=akb-Z+c%P~9CJ#u}dKcV;-~X#xoXFz>`v2#w!ePI`@fO$RS&i`ZmR6SZ@2voD z`SV4c(z|1!E5daaUj)(d{^=0dIhC@AM2Wl5;3uH|5&iU5`KNMS94q6UAe}~Zlw#z! z&95-r`UCxVZ4E`I(w7hbST)pRo67h^8|R??CqMb3Glu%@K&h? z;QhhI`-083ScnaOtMCpxI^J2KF5BW0l}PMJ+?V<_i5<_;@s7dQmgGz^9^U&99osPS zldA8U`fNmhapIriti1j{4a13VX;V^FrA&`E?qDu$I-K$fB>oI1Y^d-~nYV%bc?)>< zW>cI$2MuqRqpQhpZ}Irgko$kr8$;`?LVwhhKdl z>;riF;6#ntRESXfFFu#Im(lTVn{!igKtq{y1&O=&vcht0A$oE0)c2-YZwce||E-9Q zM;Q4fF1%sBeKq}fzwszL;5&@n|KDHt?#`R;eN4Z-W&ipFO**1X)_L{b{CofZKZ{w0 z{2BEB1S${OUmSCI0>F}AmOlbL>r zwb0v6la4IMzDDm{a)Y#*3hylYUJnZ1jd)oeG`xrWsy4xRhn1Wr<2@5&b+!`V-A9V^ zmgpluYG+P-F8lyakP41Sz@OOFB-Na>0eBxZ8DG)g8Vi-YuTJB4M92G#zx*R9*M+1a zBu>nt@>R7aI^Mb5B>i*EDh!ABX+%dBMt+M|21R~(MnB$?1}0h@A84o`=O=hb>0~iI z-nbYdZ94Yal&buxAXic0y-(ooJ__E;9u0G$;eFCxF9pV1<0cpRfi$nIh}=s6Z$k4@ zLED=IsD4c9g(LVtx@mc5wIaa#oz%I*+5qn|QN_3)E=1_%RQ&1wcj$O8oLr|`Ge?p% zjKq!UmEP9qLB~7!&b7x}uIdbj_X0#m0!Ds&7W8*d6w;5km3rIY^>f&}x46e_TV8Gu zW&Q)wleFnrpg1=WcZlrX4peyWdGqa`-P?B~mpIYz7X7~9D2#W|;cznESHH~E+=Gjg z_O)Y@-2^CeYtfk!@Id;hV)qqF0B^zL7I_N*-tt9G>{rc*5MJ^DKl>eYyw#5S9Qrvc zO)^K~&bS(-x7MTMT{X%1P|aG4;qX>Qbd+M`H`aY#VEupbfi!{7pgc_L#@zJ{(spe5 zQnZ`t@%GT7O~*3ckBcVK$ioSHD!elr`5#f-`@^+V4m7+EO4>HSc=z-?CgUBrcqkD5 zdaLk_-VZyw!10z_{ci)o;Y8)hC$sSDE%DxaN`8Un(15i&Zz|*@B70Y zPkyq=ktlJ?di56`DMH74yr8ng?WhjJ;e8L$@d+b8qu&i7R{urq-L`A1gUw6q(_1+G zRNU?z*Ob@y74)s z^jDAxUkfX{WwG}laS@Bs`K7a&zd>50NShAbFj37v4bmDaymObkbx`nL@_vB;8s7Xm z3VP%dq|Zjl7o@G0bZV>yc;7dRu0IKu*qw`t^!ld2^OgeHk7NPfFSfbQ2>^J1BzykdQ>EXI_>)o$Ok|=R`sTbb+$NSxd?nsg+tcRTT>n%p2cQ{jD(?T0)C?@zAx z=Aq$zPeQQ^p8s0~Ymw*w@3bDIy8*nDrAa}tHwaLJ&IdM+$rPy3VL=^?w>w|?vtWSt zu{+ii_qGtBPE>dwc$$+$ z!J9YvBtIJ7KNs?mKX0)+&w+e;tA6I^Mt^{J(}QNdoE`#n_52aXDR)_}}z81F}$ z7Y&60yrp7x7OMosLZ(aCZG|R7Q2$zXZfdg`7+@*T@=qtE~Ij18v`rZC>; zEp{L}vN7`Gt}yE2a;4wB4Q}zCjk3iaPH;AVF0s(v$Mks5_Z_22hw^BBX-qxYy&b9W z&ORgGL&4kd%T7Ktyx(Pp-h=yp&)Q|N@a!#hw-x&qfcLW~iI3c1IB|;bVPWk!7)~s; zafk8#u_uu&3gG?VJh3|3B^FxQGSVXU5*_ay?7gZgq9UXfNSserstq>@9q;h0$_o{T z6&cRG;}9J|82OD492^KaN~U+W*~;$7yJfk>OtRKum=SkOZ;I0Jjm=(8eShf zkTw%J+kD_2@lN9z4zLDzzi|$qYX}CU zVjVlf^QKcEqGHfE{6PBeF*9`wfH%*apFPd<;vk20!8JP7=y=DCy%b5ls7SI$;xu=^ zkXFh<$NR$f8J7YheTJ(bV-X$o82RnJQh#yrBKrIPA)mDZeao=t{|{DeKHE2$%=CCC z*wUtBiS<0Yia#GnccsER@4<*K1@EcIQeiZ_?{?&0fbq7kWF_P6>*1ui4B%Z;aBg-j zc%1mjfoBg!!Ei$BYUwOIoY-IJxsd?y=8`JU?*w0OJ%8wX;h`*ayuVz_vtD*cfpiv$ z8*I}E8jVKBn|EBFeX%s--QN0)=-|M}FKxfxA$u?S-CJk1^|A9p*dItwY_RyLAI|)E z<0@#=p}y^RRO&IZd#|O!`|!~_=P7ve9|#sg!~5JdzFZjZ@3Jv;&ECv1pADUyB|_g7 zf>$;iLC4$q<1zQy0D00R5*O?yCA@40I^OxAQFh{!jQ8zrCqzdsMt-eYxpIa7#pT3x zqD_;rtFgDYf=h~ZZZ0P>eeFFrt%xQa3#>M-6hHX){6FJ0`~O2mpg~$kfdZUCMjeQw`Lo*)r5qcp|9603FV6cqK60Ld>}lyAk73N^M6d*BPw zyQj=G8o?PP)s8Ui{tA79baIPUJzF;8 zRghkYj!KODq^-Rgaw6zoVhMJEnX3-b(Epz>+4^dXmFYbQCuK^TjO`_b{dB&kHqn@CS{!3jK0L?c}Edf zHZflRAC2fZfRUfJl;OCaGW~d8<^Q}{c#wu8b{BTF9l4sz{CFqrrb)+B(tI(K266@I zO@(&}+shmZ-h2mcNTA`}888qI4cfF2yZ;aK6O%ZQ&(HMze?i_tnsn5RG>~k! zljr|lRCph~`J|PCx4CYSI2zv4`!{sJcxNwJO78zFlvFqC0=%D_&mQ;gCqQ|)`f~!m zQy@*-=}Gwf|BZ+IqtgIyjs?)1<-J7cnsvt#*#LCBUv3=RXI7_7qQp5Bo9czwqT}r? zP;z{OG~>PhH-hMJ!^m&9p_IOvJpFi|T6!R*X9&ANO6+?!FK5ntrpFtnI7E|9(&1#O9gJ*BJuUE;lH}Q>^CE?lIo1Jm(p*LUMF8)Z0Ob}zu)Xym@WZpy!$e47r`rwwICQ+Dr^Ov_*(sAKak1N0e0<@9 zj`x6BmZVcN20 ze!7A(H||IlqS-fw~a-=E5ZjvpXKP?lJk4ogKe4~o{f{i+*yklT@@t?>MRyEtg`j#3n9uxJJ??f)Avvjce&dKmUL0 z^PZuZtqVyUNSyDhwqv+T^#0$)Y&z@bW5&B6-Hqt5#>j78)%%vmR`h$2nCH?B4|8bf z|6?8t53Cqv{yRtyr)kq+>=KWh|M#Q9yGq6A76os-&u4iwyuB(Fm%>Nv+J#ui_x~He zFWk2Y;Qb)Y@%{nui5=Ao^Z0IpCH82WYbuO)@j?YBk{*@2FA^cahtajo4(Lnl z5B=on6IY~2^N={(*CksBI_OI*aTlj_8J{M@4M@KsI)X9so9itzetdd9>WNx3Uwjo~ zGQ#qdhW>xQ(Za}r?abf*FQQGy++%B^e_S9}kQ=D*uK3m@N5T8awq`jryidJ3Rs-Wb zC31p%gS1uk8jCx?d%4w|%C$)Oc)*S(0D_QW#x=_dus~O;fs+U^y1l*+!p%XyHF-Z zMq3QK|5rUH9W9$Q&h&T}ZJ?Y}0V2jhKytcRxz;C=WI$EM$Vh)@{M zPE#X!bi6$iT%JeXmM4WGac7eBYnvO`MI9@vRCyB{q8*< zzrgX%eeC`p*JiikQ`}dk$2+l)HXZJ|?e%^YWcOZAg?Cws>p!oz?Ah-sgNFBw3fy5B z@0#LB^7sGhdG&q^0=!K`INdeg5TMrJ>kcbeQz4$bwpsY~R=op1L&^c(ME3Uw-yS1E zW~m&+(?;lc%NvBRI{j6FWQxSy`;_c{UmP88-_&nCo8lPnc#ABe!yO~P!r14cX^ZK1 z?-P9!=}WP-H3wu@pgdDMMm^7 z9^UPU4ik+0cCD5Dpm&&l_x4FUwBoclcK=`eljjYe`zxl$+fPoECLO+c7wlwr`GqQmbB0}~-@WUT9adKLWB31wRg=Qo++H$0-nhJPH0k(ys>w1Y zkL=z7RCu4rGRdU4w;8X~A~d{j@mOcWc#jNAZh_tVvw+%({Q&RW=697v&j^rIl`m-+ zTyOc^wx$QhTT%Ar;-dg>TbD-fkgV{aPom`~L#D+_Ue>`&dV#JNk{e$ z`n(rp|1(sl|34=K`u_+j4?4H3;-5E2c5w0Qpm~rPpZj-s57J!q4f*{4Jt(PU z5_r(HqEAs?-w9CkLlb`eu@orZBA6S#V)tuTky;2igVfTp{pYfUySELhY%gb82JgkeZ_&}r~d}2o8_3~FCXkH zc8?^V<|(~q{xe7)?H|&l<6LIG?KrrD1n>^0!uu?j>pusi@23uEq2ayq>5pa@Z>^z8 z@)mnwxU$VBfcIB(JMNjE1n980XEPDtO?u_Z2jBl+<9hWV{Qm#6(Ne#b2qF}^SoDq@ z8#> zv#x7h>$=y4`fbZT*HZo(e~JAXs&>MC4)cxJ`JMeo#~_XP0(Qo(BCcf|Z$FjVq5MkP zJ4nJ=!uhnvtpAA}p_q+69g9*|C-0|>w>U_JcYc?^BWwq`V(jW-JiMd&E&UL@!+6Ii z1Jb-S#J{`&cwfJpD6@oM25)~eL2L$i54D_>L2i)prz&^I0le$CFS$3v&?>xKPosXHe_UDITZoT$Yrgb)g$>MCAPt~8%4o#5>Aw5nau3FLkmv7x zPq-{byZ#UOw0_rF=o`xyNG;|Y>C$n3!=V{Af9n4ORCwn-I4F(by>g|83Lf5RMz#`mVONJ_5j7&vVYjVP$Z7 z+cU_KUxAOe!?79p=Z?)R7f1a#4XkXkQ}OXWuwiIoVwMck)&F*=4l5e*9nrabHixz6TkDa{`D4uk}F+0E{>NT_xjWS-%o{iZmex4hIcq=gEAi8?K8H# zMNV(!LlY?T|K_AfeyRg_KT1)G9OE&A6$oGX(*fRHR$&3i$BC<&US~W9^?%ir!|%xD zKJZoJ+5Oqg_;?riPi4Inm|32Q`rYv<5c+ZbAMh?*+59An`A%>1Q5}{v;!Dxa)HpcE zINqd(zIQU|=>Iq0I8bb#{+Q+Ke;spIx^$=&{km^-@^AhBp9^j#`za`p+^KTVUF%gF zu^e>o^K5Or92EZh=`iw%oi(YF@`>Gw`ZLnMKn}A15Tkqh85zDAv1-Xt@IYFgfa|9@ zAO}6{@5$){ODtiViLFE!xIwBKvtC~czd%YXFWCz7N|hf#{j6@^=}9Eu*Z;MIrLOK9 zneU06XjDfrjri)n80l>AWxPPD4{*Kb^MiJSbkr~;kxMp=<#&*KB_rw5@pJ4LxgwU* zL2{$QyO{HrJcf5*^kYptyi=nq?jv|Vs+>c?yY$Ft-%o%y$L|km+~D(;wCQ_^F#vC; zqhiW)0p1EiOI9=jyyF!@u9=wn!0Qd>?E2V`zr+qMZEIAun^(RD^|MmtJWy7Nzr@bh z-G4Xa2J_AT??ZLWq!C}=aFIbpCgTN?<(B*Fk7UwO|GPpw*>~bt9`68{hb|pY?~cEk zf0c5)b(jk8!pC3#HUFRV1O#t!_dS#eQX_orrxCm-3nCm>fD6*gtd2o9 z0N#R2<{gp*cn9uEpIZpp?7CeyF)%K!m-akB$cHu@@dauCf7naAHK-8d5 zhxNVcMSm_Q9-_kgj#K^#kC&GXBZer4wX$ zN51UsNq~1O*OZtPzYekOO&kkr% z`u_&chs&El4!Zo=P+aFR8TJt?3f}lJ7#`G5Jt+=ykfcqO)da{v=X2(KQCjH>e?O|~ z*7X!W2fc{PUGV+dyz*t`QPwCR3TNyp-_J~p-c~RkA&Z!ZJEwNDsZMt}P$Jx4w zB1^27=Vr}1XRc}tjX2l;csA04}B#CP*4dt!bn z<2y*pb;9JgJdHH*UbW5X_rkaAEI&a?w&5UMI;OVUgvCWtj<-Ci@GdR){?`Z6uB6!I zczF9CZ`_68tq~kaDUe)026XlUyob4s&+U6chV@TQHH!kgpYCRI69&Brxiczi4Keg7|j>LAjHk7IGI ztZpOY*}G+#3ukX8?fyUE^{lSJULKamo1iX2mkyrm=Y{0{G)O(D@Vn*Zpqw^5Fy~}=o`U3Ed z_PpsO4Ceoh?=mU-vm%GUl!j-@D9_cIfURX zJgy=%T<-&KOYJJUx(gp~*X`A(%eP6FZ$|y9xX*maFv8E?{Rdl%?!0Bb&B;MjM>~!9 z^esm`3@aGV-q9R;I`eC3_udF&r`D_u=4buAw`4S3Iy}qkbH0J>{rCR=e=fP1>ZhRo zKSq^i@&{)c(x>zrQ(T=`9WYE@4ICh#@lEt5UGy z{`+89=Z2 z@HHyxm6nH1r%J{&?9F~VJEx^aSTz%t`v6k88Zm3_` zoQOolcznDGO`9rQjO3ZF{=bRp_}ci-@qKGeK3LktINn`hswIb8AJDA-33Yrj_F+ye zk2hf<4}Ch^Hc2b}=^*)1;ayc4JPRBLAd8?VPgR~yiAxI-W13|b}G?{U{a}zTbO!LsuL6V#r?2ega zeY`h+qf5u9n)Fw*{*1Tqp~CxqxW*WU_llwlHaxuR%@ooQymzL0Qt-ZcT5kOZP#|gd zTl1uKk>QX-8$E)+@m7msnkRBO(WNUle-sE|4-b!Ux)PGGN!f%wq5suWx6AmaT(#`ZF|XH z=&aS;axv6zrolb&{qp#DZ+K{-xBE8p-QF@obr{f!?@H2ae^thhw|1I7_>{;;d+$vU zc=RA6f0E_z{}XOJp-)Fu!Zj7JIr&@vGgYPkpMweB9>GSHgBn$>rm-AUW@5vKmxK5X zp?Am(l8o(pDI<1H`P7G}fE^?`S+jOy8W|RjTbH`HFBrD?)fgiUa*)-J9&SI7gWmEV z$XFoZ11}fdD@(}5FOWuhHSaVDe=A#p`Yq#%lIV@ZFOWPw$mwkL<6^o3sT|d@l}3DD z*S)>iBf$6)t8-x@UVjel9VB7IDEIR#=i>hi0So=qb2VK$&PS{6;F=u_me`0HRCw3F z==h4^ZN5gB7Z2~gxP+C+Cw4;FWt0JFkF#W+!~neYS1sH27=O4Y!|ky_n;Sk9RuP*wPP19OaFupF&#=@1zMn-lKc!l$JIK zGacUHsE%G5@$Cy^=l*5NINod?JJu8^(cVGs)4Eb9d*cbq<85|^J{_7~+(IdV$PO}s zK!tbRohf|`Z>3Xjx$*E8UcWL4!Q1?o8fALxN}0Z>lK}6g1f5>RVluq3ZM{s-KrnpM zMaCGxJJg8VEehbheQe#G&|BUx^l_tQmmxmhbuS15k=?xI)1!al=+hd8^ z&0Mv)Oow+as>6Xse6Mzkj66EcINrVUa=vAMq~n6LE2I@}+0OEK6TIlu(Rr3%{m=2% zaVoqYdVej&@Lq5+p9>G~OC;5A2;TR#t0^By2a-z*+yLGK8;&m8TT6zG1J>V{e-jLk zJ-U=IAK>lcuwDBs!25TgQ+t=C51d?h;-&g1KHl3B`m7BkXO%~zeq$CtBvV`P@%|XQ z=i$y==KKEN1l2J_BR-QFziPMtB74g|_jqhnLdW%%l@<@hSFOIwLfer49BMCpI{X&( zE$sdC{+~Y;-nC|XFJgELn+0*=;msbcmEp>2B=XL53 zGK2JnYgZ_;gVg8i+M<<5hHtD+lim+@kp1G^aY+3y-WKZP4RX-4Z?i4gVtruwFKf3q zEW$s7eubdlvoebaG0*}?d42HGmJdQ^2*7V?%@Bw)5H@4lo z)X4`vrMjr>*Dw4fc4=m-#jg9m^iH6Dw%(Bn?S1%5ta8AIlJk%N)8V}X)nP&-K68#^ zN>iH{$2-X-hEMe??IZS7$5}!JZ+%%FZw}c3L3(tUfB81-{0DD{3h$O4hdK;ziR}Y| zczCmY;*&*AZ%JWVZV28z)t)Ai0PpdN`w@F`$neo(`8Yvh-kqa! zCB3$Q>^(8%RrL-Z@5ZY!`>#A1)0>a_8NXQgO1J?ZZ?Ph&i4zA2Oo#V3REHLg_zHCd zOMb;Lj`!`MJ5QIT&{6+e*!iCh4Pbe^3Hs~l(@|oau12ZG>;^%?Udd-c8Hj&cX0b z;dbT6!`tQC=eG#nB|?n#-s(HnpRyJ7g^jDHi>2v#>pKLMaL# z@BYA3`}U7a=rJ4KY^aWlG~#Qw46=}z&v^Y`(VWW{qDA|7t6_6y)6NA}ERT23L;7?$ z4fgsKhy1PoneG3F{}>Ob|M{qLP^X~Q7c2*H)vpl8%Rwee8SW234mw|%YyF z-v*Z0r8RXTw((@xt1cv15u8Di$wEpBU8;9iJIFj##~B*&3GTjfDeW-hIVc-;IB7`F zh#f15m14r&ET4l22Sn)8u`#Ad{?87QmkRHWNB8bwct<%C#qjVxVx-!R;5`y`-x0z4 z%FJ_hwg}!IIiG$zM~3-cXZcwT2EzspH*Dkq-Y-@KRL%xF$e9rtT$+VhNVcze|H zh`QR*#`~z>(6*640?Ri@7dgiks!~FdVbxmFe!y?87ak2pK6+VY1EdbvAx36BXYxjY3 zzCVA|au6SHW3_sN6<#w*X{g^^p}=<=$oP0`d0I#f^2snA-sY%|l{Dh}6nTCAP!8jG z8{fFpId-3p=7eYU+)GKUk2m2mojR%-)|{oh-V(t@h4*8f{C*5?#ghkw@$i0TeoGB$ zPDEH+yC8UXmh$Wm0C?|TZ?-w&CK)yh$uyY&y|)VA841YgtwdFF?@@sF%8Y8Kj81TR zYj08_=ZcTFqj}uMSvUDeQm7w0Z)?Kc&G>ltUnw=)z$VFbcppb~e54Vdd-w0-v;T|P zTh^zmcbuC;yZ%qM%OziLrg!TZ#+TSuxMik*3++2doh_gEV)liwd=9c5tfEWDiQX5X8NtYi zod_W+yq{M;Jc8lfK4U@>5AVF*$8!<9FIxO?MwZxx))LM=$Pyc9am)nN|DQK_-0FD| z3`ZW_n}s~FJIS^3+8u!RRo)M8^f|zIi`0!eVM+LS4;o}WHxipqGC=))Jn>tS?}3lE z?7+u^&UTBL4(|`B4rLngP5p$IXI3)aAm!Q6zQenUjtVf-h%1~qY>YF3!rd)#6?dy}6p-tCl4yZ#TT$PPAKKZoVjUD zWY}ayAM_kY-cmpjYhELs$-ac6FW{UJgo1^Wa1Zq}_vAlme+f zYp`MxzGU*r&d;N5fAn|7ST z&q2;_9&#RQm`U1>`e~^1+duNc&p~TtiZ$o&V7?=EcT@+NMtpZH$(@cljOQTp+2h5p z=@_vSpm<|zPwZ}%FOXzyztE*auD48hbr5BV6{W)aWmS?5hWAE+PqKJ;pD`7dMDVse z|DA&OW*w+;0^mKMu|4$WJ~Hh0&A{MFXE5C8duF``zdZ#Nz7wz5`lxT7Iq z?S)jB2;+yhwvT3@OI-bk-@`T@<^CEg17p> zHcAJnuj5V1IKcbrzL&uXhskh8&VAp|F7Sc$mByE90Pmx-8l~(3-eNsZ{e@k8;E&su zU2SE@?;yGD^^3kGEle6h{T|KmTkQH8AMblGM~3!wS*EN1kD@xNX~cJiY-bS5AToS zKTQz4V>Xpi@Gda_BJl+&kPO)CC61Bd>v4yTBA*4rYEo+*mjb+J9nLND26+F>oRq1)Di~-Z|8YRl-}FE3;i;m0N#Ny-yi3Pli}~9eA_F!gW)sg$uCp^-We6yW^n-T zCW~~P6p{~YHoBj<>Iwel#9dAFxcrCNBoowcmEq6j^|$cx?%C%^xV}rC>G1YJb-bYw zU&FlK2-|YTv$vO8?snHK+Wmh*;*w?8Zy#rQya`+0)1@Os)=_FRxSaTR{@;JBxS8vR zp#Gmrm4n{CJEw)^pnUx~N_aWQqcQ6!l7se-dQoyvV3Xt4ZjghfFNYO-x{=`y^V0@K zV2O=u9_CaBIq3fNrII^A4tjQ2S9gyEcp$CA?qSd;{2k<>U9l_O?DJ8 z@$Vp6kF6Te&11ehNPeh}{WRix>&Cq|E0^&cl;*V6(X5n?9Hbq6XJhRDg86@unRMyU zzmev|nMc_{N>JfFbk(yA!@GB?M*$D-%N^4@5xl2DXHoE;Fwhz71$ZwtEpoi)0wzei zcNMgN0x9H>XeNSpWUcl3tpM+d3zsze<$dAuJnMvkN_@PhD$c#Hs}>{`pni7O*GF__ z;^QrEs{KfwU5e?JSYqWL9ojVF+onNy;p)!#4zk}H+7J~^yFfbiVovtw$8T7^{x4Qv zOqY(H0mU^}PEfA5%%Q@2@c6C87~U`K@)qIYy}rVc<8sI$w^%x_^Tf&p-lF0Fv&C?k+L?a*g=!xd#NnQ9m$dB7j9Ddg#L^_1} z-I5=2{a%E>gLE$RF+Sla&2)HAqB=Zi#3y)Y_mY$>#Omhg9=0<9Ju?ec&~(jgHq_6pgov7CmBl zya}ds>M(ogf}Y-rQQ`esx;PlaTSVV@As*ghwtsqWCT|$)y^YLVSgQ5e2aa@1$QF#i z-<(uMKOV^Gm`Msk{e%t6&3at$Hz#ZbYj1HnF(2Obs19Bl@qO%)KfC5S<9MH)mH*~9 z7wxaN2ud+3A8f~pn5*#nFQVyhpi77Q%+Xq>OMmPC|Kd0N|NTD#>VIjf95niA^fQ)& zKE&}X#mhnO%`JB#caTPNU+hILNT2S1qv->d*jn{|kycwW?CH7P(&0%kO!PfczZ@*F z>n8X|24=Ltdgim;>WqEh9hWONYQMnWL4MHe9oh6=oMemol`lJda(5~I66+$|_}X}j z0@Ljv$59;~G~x?Ycwg9hL5Sv2`TqoDDqx$Zs~a6TXi#s4OydRCUt*h9(xt;rrl_#K z?HF?ZUy2Iv56>-4Fua9{d`s}~=KH`_fZ!c7w32eg?vqpX6Xc2=-~BI~I=jfQ>!K~N zX?rlNmHggR2jIPU)uPwa0Po_V4^@h4KJaVV2S@m8@bOk~*)HU8Sd{b<^-Jrhipa~r z$D0tz*J1RL`8r5TP#v5!;uAfP+QR;falF%qM!%LUqT_h$Xz9_>wAn0w#2%1!k1icA zo-cWv`a2xKdp;H3BmN`e7~ZdRa~I>`z46@K1;_>I(^>?|1?k^ozrV!-ycOcd^yEQ- zw4muZheby)e9=WAOB>*QYYV|&6ck8Jes5MU81aUm1b8m;t#1k`QbB3k5E64 z#LXXfZpX*FqeIVwD9wC3NPbjD4~_WTgGie~<}<#7WZPS|r9_C1>|M>dPH{Ou%i~Q@ zpijqmN#R(*M@s!aj|%Vi22vsz-g`@qsNmu4W>*x8;5~Gq<^Zxe`P#*sn-1`{vDF+d zcOt`AhR-gF0GAV23E%jETuz*pXJ zVV1{xB)N$$9UV}mr5v~*4YIc+72d;A5kVNd|DV+w6WSmLEu_jp<8RvBu^a^DacJY^ATP_| z&$S>2*}af)K$h5NN|O^vfwU&KHt~)Z8FuH8*|n=J7~W}p(iH|dDA7&UDFhTqv;55z zpSAhGmy^@^_B!F8L8eYd*c(pEkT5@&o1GW$t;auu?CX=O$~vvabU7#u)iFRLzLct| z$&ZqZH%NzfZH_*WLVJlN5a+!!6H#FO`oB_=J{^KLXPo~tVn>b&?=M%gT`{~r54LOK z;qB3!!GqNQ7bXHJcyk7=S%Exnu{1|+=sLLGA{Q2}TLbWxIbS0|0(h@7`LO9cz*~Es zpS(hf4}7?oNA-{zKHfuVz8A)nWJs>4-yzY$An#fDc(e5t3#&X}zEA9iQ5_JC_;ycv zb7_zn-$8Pe+qipn(*8iY{H>mAUfXq+$J;-aJ{=<5+mfGzQTqQ2sPO)L+^qw{d&$Fe z4LrP+9vqiL@P5%WLcx36@>$#`0N$1nLETRelHpS-JzJMQ4u%(OTUopk;2kd1Ot=m3 z{w{cY2Eoe*cKFGy=Exn*0WNqbPg4de9^S4Qx6ka`lIeO|v_!gSd?9M!R! zMtqyrbDPx$F@C%i-)iT)$AgaSJ=kz|D|CzH@eatOPe)t7$T@E;h zGyuHEGnH&kdHTS!9h^?H{{!B0)?B+PT05U4iu%=YRnIi|2fP`nOj&Z#6FMbxU-%k7MtrndGrIZH(EMFi==f=~e<6KpX_`+BU-ZE5pkFiC` zV|Y*GFH^(AJF%dP(tCSV+Q(4uEvJ9g@b_pRc;lhCk@@oY**ii%Q2A($BxwWcx3Hk5 zikB0Ab0S{&@`90=3e#opI8=uejrh37JUSZ%8Q+{7OR);nDWv0i%Xm`acV|wP&)x)4 zI(6{fz7@IiZ~f1N)&Bn*5~%-`sB+Nv9ZxBDkQRXV{~Xu7BjDvAar>>ekosRvY5pFh z{tvq~sdxq~v4Njc<(ebN@O}?l-ehpZe)#7)1*AawnNfHr2`sU5*76#i{0ip(6}%TO z`-cJPXD&$h-90Qvl0*HD9#`8{jOQ@bfmyT218P%)YVv!?uMJl|%C9#=eOKgHpoh}~U8V&nO z5xhNDtfAn&w=Y@(X^={rTNT!vBExS8%~wM}gVgA^Sq*}B_aVVi({}X06I=0RaVST(U8tBr|WY2X)&DjmXTY(DisTX_FFucEaaNy!yF+Na@ z;N4iakAk3i3J>n*Dm%3C3)w=z{Q9P$OodDE{ynVn^YfR+=+d#`_Lc8jBF-atFQUTx zt1^ENhPSB9E*-q={qQ?)8-llz<5>#cPo}*DA^_gK-6DarPJrRW1`yl~>i>DS=0W-h z-czF2d;#7YhIctyPy4{O-(=bA;_$QguZn`KR>=h<%&%_ok@SQaaB*dUPD=86EnWPO1Op zsqmiUPs+sb9-6Jb3=i+As#z}(ysdrfD0okJ$8Qe-c=JHzR z1i@P)!^+?=zYx2q7JFT5yF>gk8e_;@R)*ARl!Wl5MHXZ>Kp4qzl#43e-{5){&0Rjeiwc_esg{! zerz*Kq4_D{)J53vd&-K6Ab1ddgMDRl;?h zE0rsTE0F65*Iq75E)%YmT&i5sT(h`1I43#Za&~hzah7xDbEb2~bB1sp<=oF{!?}@D zpHrPvj&n9A7jc?6LhL0zB32Ra5VMG9iQz;)q6^WEXihXDY7-TR5=1`e7c>S9K8YYtNm z630>wSq>2nBKs8kFnbSs3wtGB0G}J*9zF{`V?JFz6~6g=LVRqz++gx7aVUC$gVn_hCQCzJs02 zZosa|F3&E`&cpVDZIrE_?J-+5TOnIETQXZDn?IW?n?2hWwl!=zY)WjBYy$t@o6NZN z??3oCvsrcp0BE^M0U*D-SI`8$c9<=KH}rV z8JM+e{S9y#8nf)=2ZNyBn6=}BychHfvusQ3^`M`aWfSzC7y5x&+bvbgpzoMvEtOIN zO=Fhj`%Tu+H_X~rwKg7_!Yqrk6K9~Wn6=eqOa+?6tSzuy12lnI=94uqpmEGHtBP`h zzF-#lx|RU+8M8LoR^5d@Vb(^Hb}=-DSsMiUxS)@iwZ84!31}3vOs>^!gg#)_x`@>} z&R*7?8 zfZkvhJTjsRy~ZrkFIj8o6=vy09aDq`Fl(hcA|OCob2ZcFam7PIC;L)K6YX3e=5cL%D*Eb$UcQRo3?i8=4G zhpI4Zwq}qDbRV-sek@OdDltpAtL!pVfmySzH2Fd0m^IV!&RnPrvxKzH=R&2JCCKx* z47!I|0&_2DLnWBSmo88P-Nh{45bY_b7_)eccJG9WFpFFHasyO|S)2o11yBKI5sM|b zpgWiao$4e&w=s*u#{Ld;3$xhm$llOR%$o6iXD^hGS%gB{XHXt$ZT%f?y%NgBtY5AJ zW6%xE`l&RB6S|IB-@h&+K-d0df%A6gDrOOPGaxDg|A{Eab})C>67ii}=t5 z%tG!hL+3FInIHtEU=}iP1xm&&WIhFS4zrNY`JuCzg?#-CC1DmahZsu4EM#melz>^t zluIZcvyh>H&>74^W~f1Nn1#G%1jS+&^7soBgIUO18BjE4Ax{fHQJ95HVuwznmPL}t z_8Y{-n3YiB>_}9>toX>p7er;uI%A>ul&FMRaZAeciHevNJ45{wQ311}9}>!li!duH zLh2(?9=3stgyCmSE4Ltow|G=jVOazp&{H3L}|n<#`??rLmZL_y4QJCW5x6u>Ok_GCRGKWc47Ubu!LF$;MR7>d9w z%xdXzsDpwrtJ!0W??uQTvuX^LnxSKu^?%gig z3VC2w$wrtlO(E zH$pC`WpQ??X*p39`+K*zx5Yuun3dlp@CZ7HS$Pi*N<#-QD>v3Q6WWhiH!OEbKu(x- zU0l>3a>T5w6GlPMKFrD~PozFS=0NRdO zDL3ttAZyG@HuUd?tT5}G_;dhdiCIZcU+sdnVOHXWwmXmoW+iwiH$Yo4D}IgT1856o zo#FT<3vI@%*q*o(kU3_>+>~vE%rGnZvh;F@j9F2p&DPMSzxV%{zs4hgBlac#K7+JC zb~VTuB+~!qtJ+A!JA<@*VA+FQu`70aMfpHF{G`s5)NKv@#3hib02r}5%POJv$fIDm z%Oq|0YH$W=?>xs!4xB;Oh%e%btMY+KfxCxxTH&8T<_IX6Xo@Z%tw8KAZDO*&v1{uiXZv6&^;OPKEq z(g&!Hx3uEhEB!+@n(-X;ZN&ae)DZ0@_L1H}n;XipEMFj9+;oU89W4qe2fv3?c90rW zcq7d|4DU6&=kns=ZKSy66oU8K8DW(A|BUzfBoTo3`0h{NVDJTLCHJ090|0NCCB)>l z0B`ZgY!!BZcVt1w+wEt)VTs*t(Y1^4@%||5aXes-G)WBglkNWEnK=U=?@qOB*YmE- zhxY`kV}M3{Vw=1qHr;3Zie1m(%Olm1w2!w4c5+h6+~-&x?|^;Ebm{1Bt)EqKm9m3W zr@|ZQUSoJS_zrU8;hprx;0c1ab5tqi^meRr+3W=X@2OkvJXK&o8uyCgxoet&;rmJx zdyN6!qpP~(CI~HXgoq4>Xs9>b^=XhGI~yPGApKSPyOgC#?WkYrSp&a}kJh+#Zc1l^ zYQP!h!#f<+kx3&yzO5StUa~Qsy(gXg=REbJeY|!4=lLzQZNFF^Z}F#@bm_Pezu`++ zI0bJtD!h^F7#QAensr=wc$fHTFGS}5<@NAU##=&F+vjQnya~IOpA!HB(qvSQ=H3H% zzq^p6yAI%8AgSRy1n>?KJpFc4v^VT9aIyXTe0;pa+Sjqyrb&}_p?-EBUzpfW;o}_; zCiKBZkNKvzM58)_X~Y*@=;v#+mT|mmHUt|gy`$p;>2CKZ5xZ%Y$D3e(ggzZMydmm; zUT*}`sUdiqt%50d|FG!4qzmwN$=G)L<54m!-Ep6@swEgs zpY8Av*_`+}lc#?Iyj^VhCwSiYz{(QZy_fv(>;E+AA*U)Lxc`s(m8PiAAKHOm{|}#& zmYY7ue6zQ%pgKO%h|l1?)#mb0f@pZ5KKf?HkWY#|ZW$2);O9Y0bNYbA63 z&i`lTvj1PPf%<!^qfPWKoagcbRnp~8$MJ2C2jv|{3Z5H%*wfI&1FcD zs9&ca=f1mA_ytk`iLI{d9rG=*?@=AWG~!c;dVg-~L&giF65n}gC6g{AR~57 z$}H;TlE`rRnx-5MfcK2Mlk<@Ne^>LkvJJpnS~bRW`6+L>^LzxKkQhGRawmB<39ptR zwV{67Hb^aA}7`5+~zJ?BHn)d9gt{M(kb+7CnD7 zg5~ihIEK=vLv~ZM+MgZdGAg{0JMb9ZNrhd4cz8#M`hP(1&i=^rXL_s3pl$=eyVAGL zWf|!I6S?1o!Og+2j+odkLx8tLTkPms29weG_H* z4iaHm3|%?`S6vdCPNQURZ7RHxk2)~CAKbeufQL87E6XVa@7;HFD0u71G!6Cxyls|Q zsvJH-h8rG#aoPsze}68|TSfqH(Yrfds{_2N8|o{U^ZUR~ht@QZFXH1JtT&Q!y%mhN zME#bO9F~3Ki;wpWjdSY__cI^fk*JPaG~&yA;;5z_!+7@oGIGCNWlsa{u^+YxO@uQ% z^eaxXJl^8%S#;@`b+oKY%%9Sn(4xW{`AP}HyWGr!9}jQ4H)}bN)7$H>_fzohRG6Ij z4e&NfQQrLnyuEeWq>a}AG$*eAIwg$s-kzJA{gMQD+mysMZ6Nx<()Hy5tIy)&t+?(| zr(T#eNdom7bMIVMdITSDJ(s3+o(q`|@1>{?LmKgkXof6|Z(=-qUp-N<$*Guj?~U*+ zRiotU|AP8IDvd53N6*Bby>jty{g0(Lrv59a|4CFi2>DJE%RwjPG{o_8kmPc%ht(hl z9UWh8gItgv;J1iEI!L44Rh7R$fm9G5B%cSCSk+tdkB|vc>7|FQPJ$dXa{H5$v%e24 zA^XvXUl{)kQr2HOS994yk_hS-^YLTHqR;p_DEZlDUEd<+yMv^F>bOKBzCNDNXUhJJ z=b)@-vGQB#xnie&^Rsvq>-YZ&CiLmB8(AYcqmZ(L)T6>1`S2LS`$j&y7#`lc{EjWJ z0eBN^1$H2KKb9Br765q5ht0WIbDj*Z-N)~u3JN5vPw~wN-u9#H^ANmKb60tIf)}Lu zu6Sz|cH%Fw+Gn==S%)tm5mCR*E|xR*7vSSvbt&`dRT1X9|GyH|QAZ=bqY~-EmsT^r zgPeW&c<_)O?E>kbYwk&b64t*UZE%b}9W$T36{!iL>>yWC;f;JrkKuhZvRM=l?~jUO z1qj|bH+k(4yp10>=6?Y@$o>>nqb=#+^Omn}fmHzSo%JL22;Ld7RWAbp-h{HM-CqQK z-~sQc*6}oayuBRfdPpkEl6p|TI%Vgdd;Ib7Ze093_Hr5Xb&!ssI@)N&M=p_L&*<|?hd&y6(;Plp9<5@L=cW3&IYy@wC=hltyzk9<@ zna6*6p2o-fWud~EN+TJPJ?iJeZnn?W2_Ns+7eTkKGU4g%5UL}IMtsSKH*G)hUmS1E zb9ek54byH;+~O#+K4)~0o#k=2eWECv6J092ky$4g-UY4)h4Jtn%ADFNHmqT^jq!C|2!O>J%A;vc+ zv4eAEI(TT`-XcVj?PhXAtlyj>i>6ep#C?c%0bAqCoBiq++8>y zF9*GI-L~=p$U$tU2eu+htmKB_$eo}-5(p<9xB@6NIAZ_WEnyv9=1=D>& zYJ%#pq7mP)hnjgOk?|b#JkLedabqLRBX;TDXc3O*f-Jwp&MiGnmkznIG>)5p9!N8w z!W$W1hT)y)!Z8mIZ~x)~X9VwLwOk7XZno0hqFc)$C+BOSqe<>t_B2;O>PCys9cc>gf_6>#Pp8P3jaoA(po zeRQC@Z8^YOu%yf79oRvx_@rg9YMVDKa$h#D>a`PY*6Avmecq;0ktBfnIoB;L3@gRQ zd$mN*4!4ENnGWw>REG(T`0iA+f&uW1<2}#0r-$t$9oJg~+!x>e!TR+-!PS*M9db7p zpcka|sqjVyOk#Kk?@W}y!`n*e+;ht2MA6+6!Tarp+dS zF}T?7N8`bfhMtp_lhvT-WGmiIZ8%J{IFWLo?Y|Tj8>|Lz?dW-3n(&@I(4j4+p7RB zC;pxP_wO>BY5xRvkj7Lw2$>m;<)9=7c{#isbm4uXGm?Xj&3$N%Oe~TOtM0?|_0)aZn&>gg!U#arJ@2?{+TMg7EAASMcl=Zqa--*e3wd##T%o`bA^i1!vhq2m)fm4O4d zT>lr`L5k?7PY3jMp7Ngy(rc;kMuwnccvo_a%i`gkbbpyLg7=BMLdp`G-ks)n8sJ?L zp93Gm(#y3TYZ_{47Wftb@f|KSt6;$y|Ff~~5g z^{AiswL@y(Z1In`#ENaA3Pnjwhj%HeV?K@e8sX$RR~^RjE;w+Ob8;3P4N{-*pR-Le zSpSH9^(ne^Ea!0VUz|nhAg!Uo8=2~l;e9WwOa>3{lTRNEAO%vP^=V3hl-7R`4g`1y zy}tRq84O74kWKI0`T$ICc|WfKIlZ-$KlM@y;C;$%v(WuoAK1=qru0Hv{OoEb)bFgnz|5a|_;@$%tITz-V?MkuqdK0@h>x_QtvTo@<9LTWu6?FrO8a#>0E_;u~iWyn{Q9DaTv4<_smf z1HAXE{(Sp1o(w;G{i%*r6ATl(pZXwp|GMW8zX0H^o)((1w$uk+wdBE-edhRhmkZUZ zEl2&{4{);mP{+r6pkzhu%dgCbcNMDREsgkMIWAalzQ;J;^6~`!Eputt|Af9e znI z-WN9D9V(I5!5?qAQsB8)UcM?x7xnvf(qeS^eEjj2)^=|Qyi?4#_tr;s*wKiuGj5gN z4L`>5z8lv&c1*Pa_Z0kJH6KZ#+&C$W^*1M>@^tA?=o^$+18#5qt^fZ;0Q3F<;8u8UHH%|#Y&v*`k!qQ8vWN2TI4s<9|Iv1C~@;PWY@*G_{goezf z??h29NSjjOjXb4>;e9*dg90Aj5uxJQ2;NfcsgxaLm;CNsVgT>*()Q&i!SU9^YZe8w zii6?stz)&i0PoVx9pB#oyi>wz1H!*}!+nQmt{Dl!$9tB;?ro3etB{_eetGbzb@6ui zc&py^PPp#De0YnZIy7m-_dUbx!Q6Tw+DqmCNR*Y+$}75_(=Lz*`EREsdDB@Q?|?nc zbmy`Bnh31i1F+l%hi3CbCPy}q;%hDP0$rymM@U9 zk7?7T<3O7cTlAmlEhbcWBadBTc!!z#%j4mFr9pN+a(b)u;soXN_D#^@j$u&$|8h&} zZ8}MYgS*|OIqreaTcQgMk?SqSUoVXR0C-2Pv|qfU&>Nm_^VWX;8hpG3_BVgL-L6a$ zMg3NKxW6!v#>ZRXwcUW}V&=npCaPmGjrin(x_34hGLCmqQSWwzi*z(d4OWbI1kPf4 zya`Hzbn5Upp!ui%Uq^*E@_H+V_l#p(7UJQ(#&6>;1n+r^6DYkmF(M?@0PwcS(Mv1| zB*UMc3~hW_8Vp~~d+V+P@c!XHCd>_vw-&?^-FUBg!=7?d<(&N1ucLz7y9G^SA#0AA4EmG{FwioGJ$)?^k0vXplp2DP9h0y6jwlro%_mKn_ZkzH#i#1XyCf25b=v z#m_;9H%z!sPAZVZQ9n14xWW#5{2X+(GTiiqoetAANROgA@@T}D*|Bn;{Vv9r*s)lb zlIgj$>wlR!zl9Sg?ODD+GWlg7LXQr%O|q_+|J?sKqrw|`kR8L@C-u219^O92rNJ)BxTqFYrzH0lYI_YpLzK=?&lM zs*=!Og^%~K0{u#=AZzp}*8d&q<3@g|slrc1|89kXRo*_8U9Oog`szd{R!_X35i#dvrxY;jqQ z;QjNwG-U^=HSL%e3-ET_0;zs-Cc}2hV$oILdW-mvh&T;^w<(Wtjs?JbKUWId&j@e$ z@*WArVF`S^kJ>n>a@#1AE}(wW9Y4mQar_&k!~A#J{EL|H^Oj?%j*m3rTcfF)<=4tM z-cvSWb02-Ay@MPa-BUh1GRX3H>n4QKrDNJix_fgR1@BE%c*_r)I%0TxRUTKt!~5a# zVF>U+?tK!aR0ih%!AHV8OUl7`%Y~ZaNdKQa^Zb-5z*}`Z?wN?M zH<<2X_%4APA8(nNAtWg?6%q;cd#>RmzIp&3Z?EOWD;{MrUx6f#>hPlx-~QTRp>iR{ zHz)mrO&<=#(oz3c#>8BnH^K6F6E>fwPexhjC;t;xWHB}n~$?)m2y2;kky{kCsJ z-Uo)xi)@Lyi;uT=u+@UTUKP@hls|qw)*^1+iTIlnx&5!!>#D6}y1lnQszZ@Rd|zeC zAEZBGJbQoaG*x}wMaTTVih_Vk`&hsJC#2k_OGgNSD?1_nZ~f1l1^@qu3e^AGsB+L! zXB~bl2OW$4sfCw=Y_8SiAxkXpwTF}f$zq55LuACRs!5qs`yMhpdYk*_doV#NqI}cE zB_IcRxST#14RX+;m*WS*)6(sNM3W4 zm;JMYw4lO!iD_LFhW82CmzsEZ|M0$%kKld%LNf*LiMy*5KLWgU8dRO50N!3pf1l_B z<1OE`<#-@?r+U8|hy!@@$_t*{?B@+fY}s1Q$&0_lM$Ug6})@lHC-+`<>DQ&qRRtmPGZJF=Al;|G?zVUpe@Aw{awmJj`B5szCkDl-NpUh2ZZX zi%X70r^++m7o<;79c47)+ghBo!y%P%yrumwzYo7b`}CF|bRg`U-w&3@o1kw&myWA- z#ivY8QSjbEg}2HRmunc_^_|Y@czBCE8@h$yy~6A{1#cs%>@#8j?sAF=t_^IUdF#t2S8kI@x z`n|3DJ*(UtA8)TqY3GL|m~XtrZB&OJjrg?3lM?EZ7|-4T>zZ9Ib<$D)Pe>RG+FPy2f*A8RI!f z=yh;{02l27>Cu>raGAaU%kLnK68-4X@iNxC%Vj@h2f3XJZ>?q9E3qZEPpw545AS6? ziq8?e&ChsH@E$AJom&9#t`@Ey={`V)<7dQqJ^|w`A+w=i1n;A>Y@jTF_YvWO`T$TM zy?f1FEqE0l?@Kx>EDyNKlHQO z<9HizpCu+%)6qeSUo4$z^S|JDYd(oS9T7bbjQ@0ytf}zU`1SNAhPURq*yVV5H=LYk zM)1B^p-;h^aEbHv34r%TSH9vwCo=4wc{U>i3`jG4wC5Fqx3Ic#MJmAChS@oxRDcu5|--tqzUdpfc+{NPUf&B^R_A&0A&@b#9*s16Al@kJh}TC>uL zalF&d4|)m7(2>2XCfe9sBUv7Ag83AEI#NV7DE-OamQ;AF#WwuwapIzAg+dVXXH?K7C@-igfV)-=dHgf;#x)E$Wg_wMh!ekt9&RZ2immOT_WVTSSxhN5>^G zU+=96)p3SKe9qU5cG@js9B&7$V>>Q1)9$?mOh&k`cg|SGq!l3jVa>{0Y7gY{gX;-9))&E>MmPEW9w958PKJo_1r0wKxkA z3E8QHM1xYP45eY01`R@zgpd?XNRkE`Wr#`&NtB3+QlUX<@>|dL?DN{MdwDtn@YW6M`#|PhJsY$Djko`T-0$%Ff6F&~BEA17 z*pdAq3GgOVwKXt+7o>OhIITVfR&R~;$~lw(?}LXd@;(6GCCZ!1WQ&N8CAJp*h~4kT{$$`e)E!u~wC3{=7Y$qwBr5 zP_h5d@IupASdad9kXFB>Dvs&Y=}Su(65;H?J~_G{<{dZO zMS8vUgze|p8o>ME-mx>9?gYqQ@W7=$aR1-QX#HKvfcKb(LS_Tto$3=<_x=D8D%7_s zZ&--V`>25_*X{S>cyc?=?RA#l`q3vRWm1-3wh(FWfwbdD92FS-V>l50JJw|WygTl< z4rFLxZ%*V~Uvxk^jEnAh$2f6N702rj&tIQCL7JR6QSjC}9h^$$o#JzX0gd-UhtLst zd28(C3)1pdpZr3%-*EO`>%4c`j{y0sOAHVMyxmjJK3f5Jvu~(-a~trUV2cc>i6%nZ z1(RDR1<`pA-H~GGb(X+8A?@N-@wfI&qVrx?Aj%RmNqfA%A#vDX^zU||ice!17o{$sU9gMSZ(SPzOEWb7(PB6<_uXTVgGS%gdcyU8f|Z<`7|1~*XJ*VhL4nj>`z%=sd?1|@s8=Haa**Fs z|LQPM|1a5AcBl4CDCEMh+i+MN{SML?+e!`ni3NCPq+Q?8l~#Wt^gBoecCyxLk6RNGijbLCdB5SgPOA+9rN?2Vg{Katm}R(kp2rKaS^KG2(I3lv*QYBh;^sn zZ6wHkk<7bGNnjBg@BAOH(qP^Xx0UaLdGD4mXORWG1%z!RV{HkLwu-?*eK5qbMzfuf z0=#qWOhTOi?=NxJGTnkhA-AQ!wVv>!^EU9V3fi5v5KnGrd_1-1&@c1?$^F-OiT<1r z&G9xy;y8fOKOxq_>BDvN=iQkWx}kqb1Lm^W!6d1SI}SZ`&wE@%nyNUazK?~;*`0z5 zq@5JJp}|2FGVk@tpV`rPXWmfX1oK`bbKV2yy}fH`r3&D^(XlA+#0CPSY<4~%4%GiW z#@eAWfcK&HeX<6CwyVPYBOP-9O z^L}P-{p8h<1kLegSoSB5*BJdX;|>t^dOd&MrL5jT(x-tRn(b7@ z0r3OC*s?5;MGYHmb`H_5)>$pre| z8}0;trP%kD)a_XxeJj4bNi=BUf52Sx?`LX!+J_00XZa(@8%pmte3|Y&;5ZlWW zG;sqAv9f8e9%XL}g??O9)3`Q)K7%}1D(aHFyrXIaX=k<1-e{r|eTe1JyXna9GGOqZ z1N`6pC%#A=r*;3ne^ItO!-c_YQ%WLx4`-THCZwD zZh`v$TvJ>G%sV|Gb;B*ddnhC6tA%kWB!X9ny3mQvdp|>~-`Iji19H1uRaUcAwdlMX zhHULeliybT?_&PXzj_K1$D`rD?;p#X+zHwB^XEOOxN5``!X9EDMc+$s^Ngf>-fsT2 zRK+3jGk_?2p2XXWg16bY&0#Wc&vRqkXuK;}M{Ydt}X_=PqbOD$kYpk!dg5Fs$QY3F%l%mBppCg6%-bXPg6SQ=dyUKbm3_Qn(B@blZuwj2^}p(rt+ANRxBd`aKImmA^ugg+jr_j9;jR5nw#fIl z!F!~gR#@Jc?iO_3&t90G*jmCxd%Tf2zG3vwp=RO0p`Y{Tz5A%=)%qUn&55i#YZZ0C z^T+>r`b1y2>N2BcMRm9o>S+| zjbDU7K6~#GC*9E3AcNe3OP34_R+HN?mhdkugwWR@pMU$NWoa*ur?ubmKqQU^jQ)jq z#C-Hontu+mk$f=nW{`?ANIOSpdHpcb5k9 zQZ(N0Jl?-)1iT-5h=#ztdn>~?tOUFRFRXA8x=DbhcVFhp2fVWy*iB&G-nDb7Nr3k& zrfa_zZ6-oY$IE_C4WjebUpH=pH{h=(w^QL6bZ2;q&inY;p9ynyk~GJg97h~R|DGM) z7}Rxp{!8o&--ep$ms2r=4Au{97Y5pW`il6uj3y{}n~%?a9!x z7>&1v7tzg}fcJXo=mRkCRYX=9Zos?kT>rdCEGDeNRg>FE`s}_xdky{e)>y{OP@xQNn&Zum#Nmz6 zzn%K)%nT09KYK^YnU|^iVlQv$ho@fmO+7^Syd|`$i-Wy)N0bz}APvmDeJFUZIcBC! z<~`&Q#*fB(j_12R%zNy6*nXJz*P~6541jm*x-HHOF$AbSV0N<_INowetyl);9b$eZ zE(`G9Q+B2HNOuUNx%fezuRnVBZXC!6+j8oAl?Ku-V3qnMrw!=YyQ^&AWV1Yu=6F9r z;;6;w-`7r$hl8^7&)zq)hF899e1MuJ{;EY5OdiVSiJ*JlxXV<=p}qgjvVYG1|Mj1r zrvC!upaT>+$PSWjAm^aWMAhYJIjC|?%o=!uly%uv(*D0jc-fwCut6I9mME-plmJCV zFIC}bjfKuO1lq#i|4VuIUtt0{=)k#w-;JO^I;d84sb>g12lZ}TFg_b6R2_k|V=LW$ zZ&4F^4iXC*y?$qa_UiwSNF2f#{d+rX9ishTxFFpNRUET745~xA-G| ztZEDT25ELO;Y;}iWttme$B{TLVf63xqZez>a?O8;Re$NC_Gyrc1JV<2Kbm{~4}AZx z<3&{*Rx^8fh{dECq(233oBN4gWZs(+9*Cgv_W5!p1D-)zNlOI4yrn)q7OMfgm+u<% zVM`-G0j49;-OaI3AN!^RX}~*NTyBLK;C&{xf5Y8-MCdN=Vx;wEbl#U8nwxrA#H-2e z4qt7kVAe(FeI!EtO7ohPG{-v=iQ^DP|MF%M69en#&l@)#9xtbfy}V_`d@|+rUO~E_ zL2~t;rz#Gm=AeSqC{q2upMp0be-#&*_YJQr!f3n;#p8Fv%Uf2hhNR`K@zzIE-vMvI zMbfw*xdcemS?{zEc${e9qT?A!zxqvQauUpOn4#QSjd2bpI}ycgd8K5E^f`*6pOdHyNpddF{RNd^m9QZUqrq zxn#6l)E1rhxks7tVP2xu71I!ED8>}22Rkj@~rFx&_yf+1FU(s{RKC;>8X8+$6#77KAcsGEc9|MZQ= z=ThHkAY{MR6TfG+E_}+4q?(2Wc(#d>k;wb1ivAX8Z`+p%6 zyf=T{@Yffl+Ij<$XuL0&TZzI)?D|wbl6b#dJDC;)c*obKT0R3$?AGaWFXRTiMNK_T z;rsv29$Q#60(f^Ci*wrEB|@*wnYtSZ=)4OE$+i2mSgOhG-WJIxZBa+(O;DUYE>^IZ z=6Gi#aadyXPq@>m@LJmZdCNamKi*%3J;dTvXPt}2PSZVa+|&SdacnjjP4Fh&{})Wb z+u^=N3ORdoey))~<6XGP%L?Z0eEA&dfV5hV$dEta{Zu;Rd}=rW8v7}3F!m}In!LFy z0p=ZKoUwEm@E#S9yf&RggeKnk#0ATt^X{AsvX;x>tR}ac4(Y+Ou%YwDFXr9%vVR%P z@oq)pSdGy?*SVp`3U%|JL1swoRT<;QuK$lMcRVwOUrP4{Qn8>3RdF;3F*R-XCe{Bz z6udX3j-Mj)?jB1KN8`=ISQ!fQc39`S8(!YxW6D~%2k=(xOmwY?1h2O)b<=7EytkBo zA>H0ua;0EXKj6(iE+nlKPK4f?dB>>! zBxsIzCK5+7M*j}4E9W`$dH(f(MnvS-r*E*ccck+3#5SwNbk94o_BK^Qn!B-58_hpw3($`x|8FG=aaVDvlqehdRo@H%NeYI0f(RL$X0+-U5dG@@TweLc$YZ-tQ{%Ni#^o+mp5V zfcN$uF9D$w1nA?J&#Vq_V`~L?icsrH58jyJ(^eB@<<9)I(XCus8th9zy|982R zif01er9ruZ_#@y8Qi7hJ#+z8^*3G7Fxc*Q5$}Z9ecyD*rKlEiqD73(UZ>P=^^z2^M}Jw#9V!(H9XI{mbhHYc zx2BDI|ChZVs}hiQ8{bBY-OWVj9r<8E$eW2DG?%^kkT~2i`nS4ny4Z3dANE1#|1i@{ z#I=7ntitA<(B1PsWAj0}=PfJQM^zm0IWgryF{H^!C!7-gp&z88qITJ`^^= zdv87;(@A%4Z(6s!ISlZAs(=5|WC#J8d6ck22W(DQ3%XUndv64m>X2!`+rzNJpaSp~ z@a9Wz{2ShW*9+uKH;z`3+daASu4LwKc=JAy`K;N_NOSeS6A}j#M*q5Y;F>kH=AXS| zY@Ssvx{tm0hO>WkMCrnEx}TijT#KoSBjo6L?<3j&)c^k>8`9?A#yTb}pvXZU+_HbY zAaz`jQxz=-S+0C}0v=-ROR7l)lDmO~RvXAco3;wdYl1b%vm4i6T=gy%l2A7rgmcil z@K)(jkb`<$4wbiT358yKF@CH(jy}Zx-gs*#>#jQ!2 z8)AEqI0zX1lU{bKLfU)&IjBx{yX-+`>@P@hi#K!c%!sG|9AxiIRUBFAnuZ@P!!yVP zCJNp=Csh8rAboB9M-?>Qr<M6P|X=1yb{$L8h1O+8WK?h&l5-^uzaxPZAT|&mgat`BN3g*`R>b zyK(RgGJ%nTx7({xb@B{SuOW8@8t=|mFDqf*y*~p;yoF?BMVkO`@l~D#fdm31U$;x( zQD-cqFlx3EUf$|+y%pF6cr)|_oY!Uug-qA^NbEh2&U^B6c49^RP?ZtV&fnXNvG^c5 zZ!7=I@Ra5mn&aJp#G#7Ozfk|qix1Y#KYO2Ery3iahg~4yikA7U31p{x-nfG0RK z=)C3uW{`k40|jqaqTm>r_fnT&Wi;Nm?gqEPyx&Z8l6V)Md*oXOc!yt;$}2fZfTA6_ zk`Dsjv5$n_z`P4~OkI2lcuVU%2o0SeLLm%R^+8GKyuB*+)fy&$tqMfiSyTn6MERrh zHqJHnO6-}UIo?)C910lyyKmz!QO!R8?5&x+@l>Hsp_?Dvk(^ z_UHFW^?w46g15`s8_UVOjXErp(0D5_r;Wh8O;k6KE+@`+lQyjaycM^|JNc&)p!Fh- z9ddxTI&XhG{CewYt1n(p0B;eOPZ`F5_mFF|KJ+)d&-ztr$=&Fw8bI2))LoKX`!~D= zZ}L{(mLH=z-UpC4ei!_G|Mn{@=Ju|hfA*GN{IV&m7JKgv7rN_Pm-7PppL_3grYepl z+1sLjUHqs1r_F-@KlBO=vFsE%$cO#+Ul*i{STL_f%RvEe)=0sh*o|zq2!xN=`KOE} zRf8PVwrJ%Gg#ZF{Q|WVc+k5cDj@Eb${DPE%%Bm?D@QK|@m5`-!TZvHh4w-(tZ|L9u zZxS`BJY~&ReFtgB>dGOo>lyk6>FcfBQYPg~X>JXYfW*;)(Laq(sayTk=bwWXM8>sx z`%!Vlj_C&VB@VuHpM#Pi0#$Le%e`E1;WTLm$wtB3yI*QAd58^n`KXD;o3}#j1pI-t z(}#Y4nD4 zX1Ws^(RqJ7{oXg|7p{60(r(4xoOiWX(Ro8zjt`HX{pAYahR2#Y#Sw)0q zR^Sf_*rOLn<-%uTV~R(rCXjZ`EHY0ntwt}9?vDD43>wnj4$=)Ij(m*%Eo&}a@OI_= zc~6rdu=IdZQ$8t+HS z9R@IO-qnXmmlLVW{!D2GyxX@_KuqB4t#@V>pA-OZZ%M~1@cVxqGMdj>0dIzfPj_A^ zBSOUeO)K~|pz}WOuF8kE{8)7WY3C^2kQ<_k&RhS>s=O<$w735sfy5z&(LYvsdy$<1 z^XKgu8izMA!aluqJe6;8t%)<;^A_!+E)E0kzKK_VCMV1kymuKsE+zBcl#EwH;~f&u z9R}C`0*!v8y*HuWQU5o9_tAj3%~=rysH{4z&=qV>7?s6tg!kSY^P(7LLH!@6qxAe{ zJrS~grn4>41)X>Jo-@_P$9t>RAno2d9o^?`g3h}p*()iGd7S3ze>WtKY>fVi6ngCH zub4k?J^YX0f`!;~Z=A_fv4agi>Hm2Pqh{*j;Ai?G`_KJ<|Dn*P(Z2=tKNm#~+8>qE z3Fjag@ctiu?^YaI4oYlM{Q%ehJVG|43(_C1W0Bi~q#yL74Aa?^vt)en(&9bNGshQ!f% z4?DK?ZRk{>Io`!c90M5rJD+gQo~S$jA$He$mi>oUVDskbcF^xI@1=X*c1Ng-V?>jC z$m}GkK;od_y(cqxoIHcvUVL5$jkjZ~>l2ta)5pPJczJ98OMzG4zzp&ZacF%6xc`sm z?OCTgU$Z$-&)fh4V+8=?l$U4O&TZclCQHS>3>PP2oyEaFu{Fp#>Fw!oEsmt@# zGxY53vuXF;axQ6_<4r)~@WSYy_!gqeSMB-p7WgrHJb{|mTP}Nvh^*a5_w_$6iMluz z_|1M?{O5SfLJHo#>Wu5jysLMv&_d%Kdc7nc=3UnmOyYe;(}ceQ@SfWs!=k&N03D1e z!5Myth3egel;FKLE@{(ED*9gL`Wz2%|Z=67;Q0d$|e8>F^S z6^EXXM9(pBIFS>Syvz*QI8KR$#;k4&V!&Vi^9QZ{4uJZfpCShZ4R0Z>LBjR_k%e|F zXgR3r8Q}|@gYGtZk_se6|Ck^rP#_5(NSDKd2h!9D`uW}96Fbgz6(!3+4oZAnr&tSe zQ2vL|aGkyoU?Y5ERxtVoX@YCi#Mni#YBr>umd5#Ijdti8r0SJU;zC_2G?#;pB5|l- z^snoS{n*0f`Pcu}yZ!jiQgOu&?sN(Fw&wzLpMxT!3#f{t!_@us)*MoS#7Dt9u;QF7 zd3np-QIZ*rw`*56iFdVw4~h4eVvck6fOk)-FaNzF0<>I}C3eo9mQT^x49E_w2I>p-Sgfz9ZFRkFV=quJxaPkDuI`R_kk44 zBr@*{KgOBRc<=UN?1!^=0^?p1Z|;Jqw`&3KB~F2hYQgKRs}qjb^a9?KdMj+DK=!t? zFT1`G@SbML9BVxq0$K1K+=3H9=dG_#Y_wApt2Rd3t#~Bx>fIRn18G@XWZKkyX^*!S z5=RC`|H3YZ^$W1gzd&;CI}jyE&Fd|DMXR=19H)EUxWpyY#lge;di9_BpNE2XfPG*d znRnyk3Pv>Ew!};lZ^idN9v|JZ}s5#;*6$hj(lpI{A>Hm2P+(&7u;_#FujEEGGCMVn!y#3V} z+sVB7B~LJ*@g8gw8Gy65*{5I_5Jl&iov_`agH_{G&KylZH1a#haM;DfEI7@r? z|5qY$lwkBP-Oqj3*~9bC-W-0ceM%bGUvKRlWEMVlFrMz0x03G93Q-fsmiA>4$0Gl! z|7oq%|Nr&})c=AMIVgN77^aZ@|E#US9B4UcEM^JEGmwKe*oq&5caR=LJ-ZwQ)*ubf zg=d@GB|ww$kr8+LzztFwn$3$r4mx@${HFYZXVA`mKA-Q8L!hVimlizPf}VrI7LLjr zUze?}L)vizIG8c|H=X9uc&TXqysgbz(#7(y z4@l!eWhGrA66wD{icF^}4%<;C-X-qQFz+Q4yhD>ZNyl5@)!Xlzzq6z9c0Yc4Jk*DO;G=vhs!xje2j(k7ezY@0^ZKOsbLI&w~>n7FL5w~T=Dqz z#i0Up-s009O|vf~s}+!T9wB=fLjGn3`CLCgyUxOP^m zq;_`*bTdif`7wWV-tUzglLV8+s;?pKY*w)(r*1&!ZU55{ANPXxR&U91*kJVUThdn( zf2a9pZ_{OFN7jg9*Z;|@e@CeM9-w>Pi5IdXsflCTME*wKBmdO@|KEC>*8U+FVnr!( zP;~D=4><=V1ex=p_6H5aI0BTcdhGUiZ!GjY zqss#xV)=_MiVlMuWN4AS@Wq2rDC&1-fQqXR>cw7B{JLwlw<=VJBJC1*C1ej-Iia@S z_40z6wU!Re4Y83(9G)2cv(G-4miKo4L+nFS+wWq#8&H2=$lNaUT+a6VLjPxw?kdJm z702H0+_<@T(gkVDD0m-wmP0y03eO-vTvO*oDqJ;2pnD<_RNb_{STlVVO zt%2Zq3y4RRTNx~GX&D(C!Ud9T-^H&uP#^{F#>ID@4~5#Qinpt3qw_uyd)uk`m}2#F zq@7M5_gJ79I`7qGD-vA>Xpc8J4y^tSU#k=-`!C!eWtn+Cq==d;c6@e))>ix<_`IbU zqAHHbz{$ReO41IJ2nFw`kP_1KmZbV$sht~*cjo0TZ158xd-$;t&UZ>0=)`U(Kv;F{+^kCUO0)Jfh22UO5`H)pSGl_*lI7Dd{{ zuibYja4|Y>?^it*joi94m%YhxcwzMK%7C&;(bM^7Z`+>uSM3AX8>AeWpEEl0`su#@ zmrO6FDvn%(H@sV-NZDJMf_Ef7r;t23`S3c63yt@Mh>fJp37It#^V*z{F6LElJRJ%h zGd~{Dua3?;RCV9aM?Vy*V~}?5US&+p2%+U60eZ5w-5#I2=U^-zP;U9>CcJAyWUfm z#M`THetU0)=Qzc2H;52}8ARA)ihlloxb#?zMv#2jZ%=U@K^`W|J7OT<2$nBvL*NWJ3=-Sg&%@S-Y?BF|RE!SH|X z|0CC4H2r5#|4UNjpd-)6{#s(+Dy1ffmV=Dg9v*`0|J9?-q%}xYQ?6K3FoP6KNtokx zCP0anKfD75W1(+Rr9PZs28nliv8E8rAm8(zmEIH<3h@L@E?X{yKEyUY@|YUJ$yBo; z?ab4czN!C>o`Xs!Z!b29qP-2$dL)iJ82w9PyZi7v*Zhar?uucTU~TLnHqB{??lQ&g zcWBxo6`gxn5JXiRHJVXBPrHzYSP2T=@maew$umd;i-k+kcw7CLafNw%Cafj#&T>;} z*a3K(<~vV%?Ib|jyiM{61F_Kk{@_twz&mpB!&DEz+l#?Y<-)E|s7ut&=q7)`rUgytyt7-_ z)lS>UR_7t@ggz}+V7!A~AU*iWF8{fH70t~cvyeC*V)W0l;W3BKvibAgrpb`|n-P2U z7H2Bj%wW_*|GWc}sfwe;dN%jSp9|8&D0s&ihLEnefS0$zTdoM8@wPtNC$Drtc^|9aHM^Ua_6j5cB#s1({sr5#<9>XbKkvQI-PJV~ zHDYc~1RL*GzN9rw_XSeRB?GGBxGkV%I(Uqhti>3b=WHNPe%((7Yn*HaB9a#$A ziO0mgk%!oY0Y8?Z@s3&-yA9^uS7%K+Anjih?{O0Fe%M!>UaPkOn%#G~J`eB?VhFQf z0K5Y~K&ruj_gt=WcM*JfYoYDT1;Wunpkr#a}n6CJ0{ocf_b zb3<%55=Syd|EAK{?ESJ~{zI(USB4w2N3jc}^wUGzf;{Hvp7(VQ>f$i>U*PKS=lwq! z3f{+eA8I7?W(#~Gg2vnF_cA4zchGPQ>3EB;gZ`1*fOi&C{a%@@4N&Rn72XbjcVyx9 z{fvOO$o<3VI{|OE-KRpVOo`A}!7l+<-=Lo$ZGE1q-6JMl{RwFocfkBw=^gYFq|kBA z=!9(A2G-Fzj^)L z{V?tEE<)nCiP68;H9Lhl9?qY4dr98#+GkX}-Xbd>XxsIP?s?2*Qmoc)1Kp?09$m{CR)dQMeOg#r}E=S5mw=nr*!7f4|uKZ}xz@pQ<EKA{}6kKovJuI@O{%C{=6WiM8P{H;mkWS?{_vsl4!gW?ME-byjQKz zCk?TUvRh8J0N#0R5^j96R?wy>8*Y5{NIkhEgAk3{JE^%u2E z!_av@-}J~+S5CTm0BNT=^3(d*4s_n#-#MmF<Q~mrged z;-lh<9Vxe&c84=ecmHQ{=D+V(sY}JZp(c)7N@jg;LrFVGiWIz0ZBl3>^IjBuR|1W< zOJmM=nD-#_8B&21^hERODBx|l&V1Bqb}h8*)_Nxuz}r2z;x5d4fs^3Z62SXcdWY2l z@cy46OYrSGfAjv|8zu)W(bY25dPqCh&y%Ba+UUHyR1}3Li)n8L*@ndN38R0fM5DSN zo6kRcZ!R=HyzMvk>8;2lMGwJEY;?~X_fmnXINGmnt?5l8o!(NQ;GMj(`mgii@j*Tg!Eo)?q8PL>)rZ-F0=PTiQ=N%y?tCmvE2N6S!l`>sFd|K%xopJY(~LC)TZ z3tYv}cLCD90M5r zlZrEwk7}KN_HO9T`nZsq*IO=gn;gsgKT!W$3Q!k^|MDnhu)Oup{r~^IiQ>QPCxiN5 zjUoqKDDnU64$`;RmMWsyE=d;|0yD@DgFT}A7a2qEn=P|> zMq?q-p)&<+U=8w_N!(!;kb~}g63Jj$L4=rj+XU|1N8dr(d(KQwQ~`%)K-$@aw%ld9 zjJ|^;w=|U@B8t2EU-tX*FZw|T$Z=rwZ-@Gh#6Z{i7f4T(JNIvTfIYQh);?*+0(eVRp5a~rc)Rj1wQ1}PfwB_TF&BoQ^Oj<|S&%#Oy($A~ zcU$-KE*S@O-tS|6Z@-&@qq+TmQ6vtQ*uU@J%fRks+R5`DVjntPb-A$&`-q)%xM6wfA-FP_4RYmIQH?D zFZ^LLBR8Yzo_A7I2vu>Y=BN}_og(pGLBad1fa47^Z}t}+GHASg-dN{10N#D9)&VeY z&&gM!cL47@yfH8NcUnM1e|fdrp#FciSnDjjyjAMeE^!_3KH0V8IT7$a{mX*I{BL+4 z+u#w56OyP-M%r!TJlJ~fZ+IU$DG7<(qP^=ak0Nm-V)So)iX^_tV*b2?YE*wjoTK9I zZGV-0r5TZQ&l@*KWgKc#8Y=(P|No*2^56VpK>fd(A_ryW5=d{5!sq`}ZnCSQ3-afmgB}JrIc>UvUH?axu&Np|nbLjzAIZc?RUCUN8nv#ckcQY*6udJ63&Y4m zY?{a$6*S&?XO^hJ%Ui6811>P{tqDIDj|1M3OeO7|KDv-wfq)FhbS%_Rb)yxo|ECto z_DX;uR{caIugd3%ZzFYWJ;!tX)aovUm0?2tj{?NDu|w$@pL=6HJ{ zacsospN{(jZsyPP=bbf?fA?H2_6)L1wTlODTS)i3htoe&701@6GdG2^NW3*Ecwbt} z_t*V@ToyN0pz-c}yHOkF{Y;aMw0awSEw%~X|Nri2w9$R7K6K@3*4M~i;Cc(8JS$ef z`+@rLabdvw!IzDPH=YcEaAQ-01Sxdhg70o7E=rfc&yN0S7j&TR>eD&&_y0tn$Gy!| zRiioH0+SOB z3f}4bI=tlUogNmTjK(|3jTwS@59LUac)t$uRUQGnwc}o<<)G&AuJ`322c^Xy*MJKoqYd)IJHQ#F zFLNh*k7%hwMOg}8xaVRawU%4k>_85x3Fq+=!99cG4F#|3n1({n7o^_2^#T11Qcjc6 z`Xd9;_!gv{{qE1K@9NOcAl>A5R3`2}MRPeQ4~YY-fBs5uuSqrYK`EtO*YS>)r;krTrcIuyQKZzRWr78d@24K_WnO^orI))MGf8a#vRqA zDvp5V#+QEGB-Q^q6uh&IN6pE+qXV)u(0E%KRaV~vyx+8*TT9}dplqW9cn7~*k!<%% z6Vf`S$FdFZ#&@%yS_OE&-gQG+7`!08cP{>>>mU*84%<`wIS!q-{;NA)`m?+6T}Zn{ zp-!|0#NJMj-%wR}*h49gtvuR=`T*Hb<>%5k{WRCbM+ zTlh3!wtw{H)*--PRP6+?Nk7~@uxF9;Rn)%I=er{wGpAH z$38qK_M-D%mLIE=F=&GiN7@~5*(Ypdht4~7wnm0M!iDB|ljAsx(LaTaUnG`}^FnhK zTi2u<%*Euo@Y8;o48WUV%Eb#$&Fd|$Rlcu^)aaf!?#mad;Gr z;T4(pTRuHCG~S_VdjsLUH^RB0?J#fh-rMBiY_*P8+7Qn75Vs59J$QTAV>#fx^YNLz z=fVAdg_Tu1R`n90j0IbsT#P{H9UHwQDEG4=J{@V7p417xYDDL4BB*t|F@ivIykn3! zj4}H6S>*fPUln}N6S?qb3tf+6@^-(`a9McNt!B-pCcDf@>~C*>Z@;~;qFa^jCnrbR z%czRO|4g&yj@WO)Q0tzHUiX3#KtS3zR> zA;Y1oy$3%xW9Fc+k3UTa${sa&`xtKQZ=vFfoqGFdw!QpxpM!7%o2ZN9YJ9K!pB*HK zf_J_f50N~?E_(P_7mYV0xqQP7!252^>@>{#=#ar#PB4Sqo9j0!%A^EwCA?3`To4Co zhFrR{51v61p9!eWH9>9_TGF@&M5v@_we=-O^dZ(Q3p%3t>N36@YtFYeyeTa1m z2+%QiFQPf#u1Fl)F!~qW(m&!`#S7gEKETlN^(iKAqQ0E`uicI{m4oS$+&tJz?2!?# zB}%tkp?}_zZ>fsIhT}+|*lp4b5>LVVy3W~AGVk$Mr*zPGhd*gQT?lwDY4K!-XOQxF zS0|+b?++cVdX-Eopte=gZ$B``L2qjuOuPZ_NrM!|8-RDbL(OgHt3>E(tKz8?BXr&w zR^VZ7V zsg1_F^FjX8+kkgfU-A-|H^Vcw923CXd0alCcjrn-p22;r85ak6UM=tR1iW1$+R`5Z z-iK@kW{tCnP+I8RjuQsxycs?Qa(vi(8h-(4Ct1?>I8Y3oH=q0PyOQr&G{>792Uh>2 zYQBAVvxX1y(CYiZXNJ8RyZO>%&m32L&CQAS35P}4r?+rv7mD^((?4$t(wmnT{fOmVsq%6$)P=C;MU%;EE-+Lx(nHuy7r)Rbq z?7cb4ZfkV`yq%738q)jS1kH9i8!m_ng=~96i7m^~@Bh>C5sJU>ort$V+HEFw@NQ;7 zzyI$_wE%}&@kN^Bt&PNi)xXF$W^RgIsRdHDx9aJy_ws!)#F;L=+!MxD9ep`JVEh zeZN5cFPb*3TuX#Zrvm*JZ$=+tt#|_anctP+Es%E01}tJ$>7Wm>p0kBGBb&!GmxId4zW9MNYlIoIzeUDqtR!^Qhq({kdnkGWHD8DbCL35caBQ6_$29Momc-J1n?uYAy1|8}Yg;!^C~xHOdrnNP|~JF1}bzQz^kYOGm; zw?x`Gc7=yu=R)V*A1d!!Q}&SNcwa~2!0O-rzI9S#v%HYAfK}*dEH>}$bH}bNm++{O zV3o))_=-Iw$By6jUQ*D76C2)LXODw|j6=lF1KvE9_eB$@o1k1C?t$Be zq0qqkE5QaG=)6~1`d#b1SA_qHv>WLX-`G@x&fBqQC@OU0eVXG1 z-gyKTi;d4Qv$rFYpw)4`jWu!|<#)BqunQ_2cYbrh9{Rr^4Og8+RUF%w&y?LfOj_PD zrr>>Z=<_l%@2|Oc7}0otcRj&>1@P9ATk-^Xq-LXk>i>U5b^h=F8KC~RqR2sa58fg@ zu>%)K!*9$v&~nhyn%hlLAP3#!?pp)rpi7&Qq->Mj4 zPy=$%K2t|78BqUQKQh{ICXNURXNs^X3Zv(s&&@K?Z8`VxVn{pXCH=FEztD5gq`zn8 zd)*f_mxIW0Okniy`J01Hwf?-2*A6AGExc`*L+mNyQ1PBzQ>gRM;k5iQ>>PCO*W{3u z;&bhPKd682uTWt!N>vFl7-sCt0G5WWlF@8 z{|b}$LF*TJbtg=rqWCnQ59g_<|9MW=HlBM=_q=g_S=7bB!SPA;PyKI6!MjXYV}#5* zWlt|V8t*K}%8{dh_jwJQJuvT|Mf!{G0^T3kOva)emO$CNO|p*y-fj-Vt`7n4gNqv+ zngQ>}#XBM-XNb@%N%Kt2Q|Q^d$?ZKu-2EDS2hxu7o3Fvr1Ly_P<6#$u5%y-9<4umE z4x@iBD_5P>2;_zCtu4=}&2Giy{q*BU@r|!7Ys@Pj?|n$k>n+haVNwF#I{)6>`akf~ zhqI`PL%vO;-8z?)y)7tsm-I<_lX(la6|$l6{`{yc>;&Lly0Rw<=KWf`dtU^cz3=y` zzw8i#BD-&nmjK>lA*)qj-VW}9sV@NUN|p}ibK^v4dK)utECHQ&^6U1^!opQ}oYS9n zr3W%Meepx*-4!^_czo|un&VB5;~hr-MouQGw;J<75*$y9D;4 z?})VPviEgdYlvPTZFF~w)Tnzyb2%smiDLss|6IeLW@SKpP;cG0(J70!m_zKk{$2ad zuo7wl)Q^a^Y{D*(B01Uk`L_$x{SrHFCo5HPjK;sb1yzt{kk%Bus}0Ra@BhKeTN7@J zc+q$>LbI#<0PjJeJHKGw+fF%uxDNB?`SH;3MIZj_Sp(^4z`Jv&Oll6`ZLfMVy9V%n zt9{wOwsG#D7i_0F-bP3qkr@3G z6A(Wv5y1zEy1TE~nfL~icirX#TMjeYLQbNYZ)eo+W48b4{rvbhk8rx@J;UBYRUCqh zH+x3^JdnPgf_Ifblma<>E5CZpjmA6EV!e((;60_G&jrsQ8^&U1o&esFQ#IqZ0h4&| zQx#sn0PkO%i&ho@-lbivYmESJ0t?UfP0B>5e}TMhVI?|mK{>lETBCLNA*9_c-qKLB zbLhOY+B{^c{n}`b_fjN|OpN}8&CRs&g75!#bDo)yZEMHmT9m?Tocwzu#F1mTFw+p5 zH?Amj1s~7h(r)`*xs>Zl==J~Mj%~T3Q>`?|8;`^hgVDbX*T!=HU%XJsxn;bU zlwM=<&bn?VXu@U&C9oW8eJp}q|7R^W%^lAlru*z2XQEG49LD|Mi?zT9(qQhrmV$Tr za$ct24&scHvaZ#}ORZTr*)o%aP>ZHcA)5Ahd~cDoh#zj?2Q&fAQ&u$t@A zOPb?Nj>80_e+lsp8%#BMp=;-N$l*(|_udGjdUv{5&7iQtY4e9~vFm?atMCR-hwb#g zIdOl^nwmJu!=Fpu`KSK>?^fpjGyguwL3R{5=n*kyoScK++|Uz5%|VZc8rFjx^Z?v< z4i`vu7wc88zy;FSZC`t{r8P%R$JgB%j)iQm2NB=`sg~8d={1-^PHiUO)?EvMgtOa9 zEmon=AaCxwu-3QkIbIxTr&BM;9LIw`gN)M(Xl&fkO>;S@5Q!reqkqOCVxnfOd{7jx z6GzUC_n1Sh-Dbu56+gDuB=y!B7hI+y2l=hLV|UAt?uXb&d26cT*i@9JSCUSu|7|IF zKh*F4>wxs;cGjh6yf1V|?Xv~Em&nQ_z`RE*O21x&XOKS@-`!)(U!!b0<8&W9Z~2w2 zTlx~DI7vvQLe1{}Wh#!hjNKg5 zx6h$_-dZt5RK;P-cF{Qg&jV>2DR@5+;))_?Z|Ajd7o+jka9samGvNL1d){T3cbbN; z?pZi{$BNxv$jw>9u={p?I=KIze_Q^7%YgT9b56abfcK}7GW_)Z5QxoHd)2mCFVz2x zOwZTbk7_2K9agPnq9ss{yE-aL&3ZDRZ0?> zH*QV302=R$zAN8s2fTy)+R9G~SQft8{k)-hxtHEiiBC?Yz4W!P$GC zPkWlt$Lgx`@CA>+=PexyyB_BQ-eUEF(OUrT0fA|^w>(71fidt=(j|1>gJQBK3W87Z z+mLoM<>iB4L(zFFnv1C|4eX#f-sCuBG5Tk8+JWf`7eC}#=_~s2DfZr*AM|2wR*6u< z^-|5+$r77)Z~h7c*CYINpS|NYP#1@xy#C4C(f{24M;B=f)c;#3a!})0g-LP_`YN$% zIa&^KU!p&|0^}euzt$0Zkb}lgvGA+`If%!^?$Oyz$~7HEUe)GJv5;}NiXJ?~awR_u zWdJkC9JQ`%EEyrtmp=aO6Y}Ue=*0D2hla0h_+g|Sp(EyrFe`cv61!~hV*9Q>n#)1t zII#Nn+|N#}WgQ<>em~EI?c+zxA@<^M(=I+4of>7%D^K3{Q89xYJg0qc2BP~Mgv&^! zE)J*UqwpJ~fcIt!-VM46#$?_LCYeOhc)wpCzIYYjy(O-T8y;fqRo?1v2E6ZeSveE; zE7W{9oEz+Y5euze^Qi~s{mrO6VFV1ZUCAefx5yKroh+a4))%Amo?3?I*!%hw-WzH6 zKAvgR;WRq$@+bM9O}F&Y9B*Q6!49^FduU3S+BYbYt=+ET}aUTWL~b(5mjI zmxsNBgqxZ1*Vy@#{&~+)7e|h7WA4;7(hSmpf_FXpmcMRqiS2$Ug2vn92LCBNzC@R*BqmwY7aLtC)g22RyE?Nm z7w}H`e)xV1;GHoW2>E;ofo3^2Ul$EP=l!Ibuh`(xOFT2@pLQ*_+hpF@p!0U{wGtPw z{X}!T>ybD%Vf4>}W4fhhAs_TAI_1V(!v{>RsrlmUe(o!3{FfN+WvRiwARSj36!bnt zm+pB}8%Of9WsETwNZH$-f_L2ocGCU-@ZrS7Fb^R#-uUVoSxdnC;dH+f%zJBM#{OKu z8z=A0CwWh}W(~e()8>I#$S!8X@f(158izuoE8tzx^{{`z_Yi1o+o1xJFm&G6{~vpA z8c5|9{{3&$ZJuRlphQxXnGAcGlOz&Rrie)9MpH5+DWQZSNi;|$QBqryRO}{cl4Puq zGSB_jcJ}@J_KW8}_kLbIdq4m4%K3J#7uUBwuC=bU*1gsVZ^yc)Z-|rBxTV%oi!VE2 z8&BS3_JHz2!O!c9Oli%6IuY!H=ML^H|DzRK8e7sFn8>%uy-AL9^`WJPF@$qg6 zRd}FmqQ&%+6QvPFx_mU$-HsQ7)%(Bm|4gs~02?G%ni}-l$-Mv_VsGfm$YIqW&h?7- zd0`FuJf7}N>HmG>Qk}G54RYTlxq4BkCg~y8_%pfY|4ob=j#4cZe1L*|y*1vjaF`ViZ&`^a3}Yz%^VUwbz5`YY?Gnh&~^nqHmyV zZiscE!TXhb*J2cJ6PA8iEWE*XZ#hwjcdBw<90l*N1OrcPi1*3RO@B9H{yo=jl3&$YJ8Z-$eK?Il2=USDB)!wet_CfWTC*VGTPnZv0M# zVdnz*E~dx(a?221KD6Ar7kWR*r7Ukb)8I{>Wz|RVjw*Y&1QT!PTYID+-bx)$aw&Kx zth!XD1M${bFnD2kuNukZFXzUhqIlq3_A~Yz#QWJ>vuDK+@A_K7m$EYlf$2VnF3uy^ zGsxs?}J`p!i<4kK_OsxNx4N}tHh|eEtelQ%~$EZH=@(WdXy<^2u5g=%OZ}`C> z`tct4{bX^iI{xyO^}dF_^q_Z4kGF^%eLnJvjJKI3%=Q1l}$7z^*W zIV!%3A>JzL;64TKc@?gKx)5)bP=2}FcB&-RiBb2|@^}y*J%39c#QRZI%tH@|cj+1) zwSdnDfsu7j>d+2syk&KOyQR)Yq6IZ>`OV0bt>)Mb(!&wy?4yO>84m9yR3CWxak7LK zE7b~v+(TV10qppAH+NTrv2IWSUyh}{+=?UQv?!B*>9&ZAd2wgsAO8*#?|MPmw zRvNq;a@%lXlZ|`p(8ucOG)l*&)9G_N^e(d>TyrVuI zY^5fSW%O9)`mk^?{e)yltX4PY8$rv#O2!MH@PBCmRiF;e~S2Ye+HbgL+nS9`UxT!+rqbo(VotuK z9;`tSZx0&0n`JhSqIk26b}h%kJA~syZXd+^@=mTE3f?Z7QZeMgkndl3`0JT{BgRtW!~@1` zHdkZgeakcTXII;AhQqs=>Z24VKRsZV!onvC@=X?%u)g??i??xy5c%~Id*CiPHP$jn z$Mcqf^9MC5wlF>3gsY3`^I^l8LOme8od)lwp-cTJ-d9s^Dq!LLwltw}7~=h`>I@fU z205$qjDraAzO4SYF)B%$ba8M0jG1RVSa9s8HsyIsi_-=duE7V=$Wq3gXJ3W^6ZzUM zJ7?_b&6@m;7F*;mtzzftTN@UB9%~J`(}F_5H;* zk9%6lUQcDpzfqY0~b zbdU76!hKq#=W-|WFDAg_Ez5joV<~zUXJaM{Cei zH7*sb8k8LWJEH;)u^jTp`6&&OnO#xpCRl?Cp2)5^!l6&9%)LFk>T?`W;C{7Kj?y6M zY0hx5lfl}&ug&Yd!$7jT4cGO4>;~!0^MlT7a=VBpsc}12UK%|76T3m0oca86h0F-U z)u2~Y9}_tFiSL$-=-(m&KCYKg_;alnw+5N%BpzB)Y74?xZNJ2S!asvVIMCuL{K}K* zXOM*ZAL;UO(tEH#?4S4lcGBS8vf$or6z{N+wpCbogBY%l)e!IRda>#hy!*xp<2DfQ z1Fp_*l#l9>q8>-c=KqKTZCgxBS3tZ!c1CSZVm0;stBb%PY z|GJatLygNl^ZQ&%AvWIqCWLnr4#NzGcQw@qUVaVSLMKj3iUKLKZ@2vB;p3exv%m6Q zwj1y>S>W?=DgFkjnvT?`{5@??q?A1{MKAY3f}FXd#9}--mkcg^c2T+NxN1zE1OQnfn7ph^0Xn|w*7uyH(ANR zhU6jK(0dSk+m-NFAs8F)vGW>ab)HUQ7d5V9OvyUM3mb3$!Bdx-T z7=LE2LGq%(`{TVeUs1e2UOA|Qh4-?_w-aw5-nCbnA}M$;R31KH1@X?@Q1V9EMwfI! ztw|_{KOUS_NlY|_c$dg>j5e^4!7Wwcq&=?=g5p~-!e{NV@xGxXlrd)7LA*(g)A#=+ z+V(FSq{9_<<33G;42O3y)dyaFxn~}%Z-mENPRDOk)YQSpJNCBr3|H^a!$yf9?r=7I zyz9jde!fJuX8QiW@XTJid@Q)~Wgh3HIlOn!;Qb+~=Pio&@UwL*vG88EYtN6*5bu)F zz4;Wp4~8R3ly7f;f49*LJF$jj)>s*g0B{90DX9L#MH0Xx{< z+aG(4zxNh>p!B(@^q+@9u5RHXm+AQSwn52=!@!E^@g^uK)90h+Ld~-O`hO;9{$Yx+ z|M#bpLF?H*qv-#et2$(-A#jc`#e7~ig#W9M-42zC&S2#PeHuj z<>#rJ0RZgCAUWTaFIdr_9zyEk}$A) zr}bl9O>DfI0}_ZH+&_rH)VNkz^++uvY`hm7&ffQC&p5;3{g&!uK2CnWL|g9I&5D3F zH*4F+y^Y+u_qhLTSsQCC?|L;eG zciY4PFBEUJ%jeax@V*tlgDVH(J?a>nN5PxJ^aDE|oIz@A4$0lNok-d`pgS-FZ}8n; z;B{^U;=R36X74IaGN?LzIx_NT7*PM3Hq9-Bjd!Z7wnfOg@5D9KIDuoxtMd}rc(eNQ za@@N&#&CG2P<^oA3USoQ^gKG8Y@*yr;p4Ipd-o7+=x1RZugyPNnVT~#l z-VG}rq?JItZ#QIrr{In5z3mz5;sIRxBzCD@G0NVX+V2{hg%IzxAII+|!M(Sd+Z7G- z^20#fp^~plR$y0e1#!E+)VgkBA~i1I%Y;nFzdUc@c8vTiz>x9qmZ$n~#mO&qe$A@U zRuN#cbJfwmr}6O)o9Yy}qp=;B&F;T+@Dv^W|6t<7!;#OKf9`D&PoIzOpQo4q*Z(t3 z{~tnAgMO&xK}8@az&l9P#hnOPHR!<^Rm2I_plj@35;wsbbmMm>zY82x5i4w!}~DR2VQ=Ti<+dyvqS)k z=1qyvu>oAXg$cub)|ih4)KRZ>T@S`@+VK77E^PM#O_xQu_aar}>AIj7UD|!Ez!S z;=qW)tMVfdZ;?o$t%(9;V5_6T@?&EdXiet3_U>OkZ!vX|_xL2)N9>@+?T$<@=Iq1X zLHg7lY&{S-#c(S+7_mShl??UJB4xquiGkHNH ziubxJdfHfcE15V(ABK2~`q-?d;9XY~Iqx0ZoM_j2aCeKRAxS~iy4`DE9O&(5xmW@5 zUgYkz*^ZYCWEcAw5Iw^{+IW6)Ko2(F4Q&Q*Q`3JE&rsuXgep8b#s^-86FHBmUl70_lcd4REnW?B7p zTUdh(bc*J#*jc{wZQg@C6Oy#3hOMJ)9I$Da+M6#mK(fn?z7@KN4E9Y5rEr9XfsKiO z{nia**P#B>=4X|j{3dRq#x;l@>sI@hH%PC({_P{~LLf2B-zzndKB^DA{B&AvcrQi> zgWuoUZ-lS^gWDht_)GC74IKoJ9!fVTPTyN1XeYQ3XaBNaLs$Y+dx7Z0ei$=HKL~d#vubfng*DUrB zo8xnKD0Jj6!_6Q?sXp-XQ~J0*mz^XG{9*^Jnq~3vPRW12?7Qwku=Ko1T!0Eb-dnd8 ziND>vhw1UI*mIdKA4jj>t9@EHhxc9@y!+lc?nLqCyTQVag}0mvtI!&V_pY{e9F+cF z5gB#a0P#*drWf0*Z$e7{%0K=B;{AP5z4S1|d&&3mFUpc+z^2`*AFdn*Bn09fpT3Tb z_o64dw(EWm5EoG6%q6%oa=u{W&68p7yIhI!@LoXmftO!ksFjI6y9l_OY`gS2J3ih? zwY_||wBRc^g10IPf6_67R5!HqMGi7O-h@tL`h1MlmQcPRg_Dy#G8$h4;so{XC`+?_t-&Y81R%W7yrcLA*!Xn?$7uCZxgs%_Nbfap2U}o%)inL1M4@ zo%~@Q87TR-tMa#pfzyvA>Qr}PZ%)WtonH1(d4QNjjdL%O>FUbB-kjLyPVihEILmO= zdnwfiUVe$|7Po(WDhyWCC4e2*@i!-~98f+qxHK5>ZdqbWxP`xZOIT3DyVhWW`SJFu zqsxbP4r#@@{JH8KN`v>$aEY^M^-dN#&Vq&anLfKa))4ROw|BWx@a{vT%K{+Y-M{W2 z0{4tb1@YTUydd7z^A@eufq2gxIucYTN(QUHylT(s3j=I%Ek7(nu<_0wIsJjd?-!Ai z8uwv&)g$8^Y`mqnDMSq3nqfG+GpRoC@@qLTIj)o`0{#jJOR)yv<84!4aA4K0AaJ1J z-G}hV=eToq$Dj5;-mUFr`n|WP`P=C7!D$>y{s3=p{jdLLv~Ki&lMftXBWP;Sh*8zt z8zht=Hl)sh532@sG^yg?G!b{KcaX@50)3 ze<*lw@NAJxf_NJm{_^G8xR%tkao^1cdU0SUNBGzhh&Q>sp8cvk8O$Qzj(LcMgE!*$ z*|f8;hgcq?4x+K!AhC%W=SS*#o;-w&cUr5agExG+n$iBPxT!u;aPqrsdCc*#h6uR* zc<2;2KR(_iV*Qh+l6=9qR+G*q2RdeuK1L~(e@-$z-UN3*myfE&NbZJ=5K4m-MvJ%B zB_kAXlTIfdEWE?khY1nj4DyQO+WC~_t=-|4R)Y}l&0!m+Pi;0QCC?+~XJ|mYJ-QOq zAl@f;vS{bZk%8wkp|8Fs;oyt3N@nsiY`k;HT)Vfg7$knB#;w%!@C;nyf?3r>pEbHU zS1=ylIaD9QIQiLg#I7}6Bnk>M_WwB3fZzY;%UQ`e?h6H}T~_x4NchiN%saOCRaJ(x z9;5yG|DWcwt2LM|ACAJkRzXweD0m;F!TZmV^))Eof{Nu_Sa{Eb#2E5Jyn7pN*--G_ zR`=K^3~rE`vPRzxT46?7^{Zh@MJWypE9=#7gLv;h;BkCv3A~(m#d+lX--BSXyT?Q; z5_@^;MoezJ%JDzM8ERbhk~6Cx*I+Mi6&|hO8I@){yi2G)3UKn{iPqj;e?S=AQ5?+g zX~f4no{INr<4wOlc;WB=zZx=6xVdkP>HB};X%o79{HXn0UYb1D{~w^i`?sg+-2MNQ zxpzi%JSP_3o43f_mV|h#Xn#LM!Tb9?lLzXs{};OOig(8|6Ovo@TXjXadfTG$@j@iT zn{eioe3J|ryxC$RJs|=&Cn7A~o1|jnEpRJPmT$!$A{RBT#^~5V;%jWYlX`Ur;LF<# zH#y;_`Z$V{pT>%voUPTuz(^^7vZw$b@4|x@oF5zv1tJkPMOW(RxSW`EyF}`Z2&V7< z37vHMC@(OV{BQsN|8#KtzY`z7?Klff4VscUIQKvrr3MwGn2TW5ph0Va)7N2xw3xl= z$wpX%9tv;`kCwnEcII!1>Xo%7Meu}VzS|fFID-n$J(e6G4a=U8xwaCX|4;A!CY=)j zCa>g|?O)-KIU~F)S1j6NHbR`B#?nC<@-orQ?N1i>*i@hOScq z@PPEGo&Hv2i1)(GBfT>#$UwRIb!%5l1X!mLFZ^5(8}Hq1XOjn-hKUx`I71|e_f{4* z-UZ2q8|17Q5AOh~j|({Y0ow-k0ufQrvMKUN?_zwsmn3nYRxREFj@gK`#K^zE{dKT7 zaNeeN13%OE|7pItboo$VF?+G{;N1EDLo|4g-~J+v;@yaR62!vW=h2mQPa)n*SZ7yL zmbYY09(IgCye$Sy){6{Vl8*8q%I7TOKv$Lj%C8Xb=chE5_9~LWOSaal#=9dxApbS9 zTjRSi|5?t-T-ep>GfWJi#<9-3&u1BijrWr+e-f{DurXZq&Y}9K!O5?O;M-kmDFWvA z-rVuvCmqXM-fVHlZf*g(=XpaHzM*4zYf-0TTR1n<<4t(nPL~h;%TGQBh0ireQ8aju zg;vF)c(dHUAb^E;Opm^L6T~~`^9C;p-uDfHgeZ7h-qTAl?6x3T4s6_~w>A!>3>8ZZ zK)iSPen0$uIT<`~wb*kkA_Be7qBFCM%wEx`SnTpZ-MD;!jRwCtk4VC;evn z$%*U9=XCj~ZZrB3l`~hpBWds+T_>N3;$6mdfFBF*P0G!Utq||Ow+N}Uc;{{s(>mX2 zL3+Slw$A|K9jUVS`8dQo1-TV%0rCFcejw{vMHpC_I>PC`27C3^BCS?HQ+J4n#&s_~ zXk(F!y*Z)&u_?^*A>-}6p*~b_@|&$ccVK?rv`0dVV@jAYf!g{nj}^Y605nhdnc?x9iyi&TEihWWM$o6Ww^xd z_NkpG)Yz8fn)tK*3S5Ic(0%0WdRT+T%km4N)XCti{D$`TDdFJ3s-lC&V%RgtbonU( z*%f2Nd(=4DbM>2Y>acf^O3h54yCx$HH-kJw^-+S8-!82K?Mruyf^tIltC6q6m@{jX zrO%DJ9xVNPfJJh7qhB-r0cnC-kBvfYKGP4e1Q9xYTu*wPy^FH{f1Klg@OJpyQu4o+ z*w-6zNMPY@8bHq63-MmNSihBmch4`8%qh4*+IMQ<)5`+3q-!%;?JMC9Qq6Scz9342 zG~FC4rAh|B)nfhMI);PWR|VA7TCj&$>x}O#z9pl?o76am4Zpi(;;`}dR{s##DaLqs zZ=(9}#L3SyT`MFp2R^audSZiL06yNqPu6Pgf3Xb==pWrYYlz<xOLj|r7$R8RMZX3@$v2~6yj`q zvJJ%45i`qqp5j(}LVnFrE%B91k2gVsJ|Dg_7iw-6Q2PJlY&3Y!oct||;>{6xRSXO7 zMOS4vr9!;9yZdb@c;D};F!6%GqnOR@2m9Qk|aN#h8Sml{`3G!~v*i;Xu&s{Ht{9^>J?fa-%4C%?ce z?PtyiiGaeMIval;e7qm`7Tf*sbpWQa=RV0B;!jQr7Z;FnN)nhJ?@w75>GI+JF?VlH z^c>!-Gke8ti_VV#4_S zKVfOx`dvy~%s==3{*^u-SC_2(@BV+ZQ)BR-aERsopBl6UnNZh8YtW{&WztwR=mpnC zQ8`$HTs3zmZ-6z(Jp_r?gJ+Or&o9a`J!wN?lW3CI{x%kzdbsy+p2Pqtton}B9U>Xn zoe@vU8HxaZlGNOTqOq6Qebfst&A&83?4!ojjQYJ=AK->LQxbdW>8bjgi{WOF{!||# zIQdQItseffL=@bM6jmyEK7#2JrAa4A$>nUdH~7sTkX0Imzr;?c%zBz5FTwOfETN1( zA7rr~QtOV)4Y52lcym0vl!4-Hb#ihc7T$mOiMFZ`@50V)k12TH5!F5}4)N|3A!!&_ z*^tW4RvIn%77M-_+-e|4#=C0QdXc-KjEDCUs*ig(`3bTFUg-WI3Yy-h%FAEH$Gg-ru~J!oKbYSW zddBnH3*29a1_kT&{?(~Wk9XTr`h2KX-@4olKe2<=o0|r2_R|s$DBhAiPZnU|y?Ief zD-q(|D0^~>f;SuQu?szL^|p-P#^YVT4TiyNwmx6av zNXR35hK>Wtm!yh(c z_y1FC%$(Eij1h&YaYy$4ezlYzyZ>holqa!@G9KQ4sXhoe`7Mci^Rre}6bybl*S$#& zAMdwRyfb>c`DFs|S8ua*&TAi9$oyw-C(Y>dao)6JVMb;g;DOCb8(TF&a8R&QuvxHP zuu`yCFjw%TV2t1%L2p4vK}$h>!Bv8b1w{ne1x5wF3w#o25O^qXQy^d9lt6;O0fAit z&H~l~Y65Zs;sRX!ll*=Bt^BX}Yxv9f3;8qollUX}1NhzfH}RYDYw<7VpU=<7H_P{% zubr=nua567-&MYId?$EHc?x(kcoKQScy{x+^4Rbg^JwraRkDCBntdIm-E+^Al$S=R?k$ocWxmI1@MzaPH!C=CtNCon^x);88RthKD=te07{S(90#Sc6zSSU0npv+A&}U|q;6fOf0|0!!)t{P%zV#rS^% z{A>uT#6|us;Y~pjNI$B=?ra-E`cQT7Ora{$i>d>v6D`P3RPE>SQ$T*8YHw%jeB?W- z_FRmqLV8dYdN{uy=|)wEW1$h!g{t6rIo?Pos)AI%FF`s`6;L{mhqR;0Kg!z$`G%_9 z0b9Q!ZK(27eU*oNMV0U1CvBt^RX%r9yOA%b+L`7uinO50+mpQz`HU*BrTvSLPpI-7 z<=cRKM3u)Qohal3s4phu+J22pLuOuWyEA1aVVo}y}lot`FAhbk*2qdUkGR9W^$ zr6aYdTKCE`7XCb>($8;iK<=VSZ|{gHQh_R6n+gM@ z993(U-=BxvL6vq-ydhGCDy`?QCy?8y(hR$K4k<;IhUxq5$SqW<^N(FeZlX%HPcsp@ zfhv_dq+p~3RjcC@?;zJvwW{%B7E+8VWq*W(Ttk%-=esfFDymjIl(>mpL6u@oh8c1h zRm*otZAOYvr69jc11Ut+viXvB$R$+Cy&oVV1*lqD&?t{wM3t;x?p-7wRZBEf?2!wo zS}f+g6UjrBbcd}ZavoKS?ww6Ta#6K#@9kzJ2UQDnq7smEsG2{on~a=AmE=dM)krp~ zByR88ie#ZmJZknml8LH$>*I;Y8B~cWb3Z~dP$epT>k4ujRl;Sd5y&Z230=+NM$%Cw z=pSf+q@hYcMg13&iYmU}{u#(gRPjFUe2S!?is!_*7;*wt+|D0Ik>jZ1QfIk?B%_M5 z-i{nY6=iu6NkSE6H3vD0DoXQrI=4Jwgp&(Z*J>_IW)u}f3)ts!TN-ql==43%tT9|MSCjnKdn-{)E{-WxnEJ+%f zMb(LKxv9tus*V?tb&zRPB}WgpB2%b3X0zorGKs1r@v7y>1ga9JHs&Mas59ql)q%FtQs}l=o8+KU7hkn?!b@it;)i;)|*;`q}Rh zA5^t0xOW@biKixDC{D>#2nq@YRA|9w}8oJbv zY)94GvMhhZ9aV466>%eOsCw<>UVylw>Xm%gV#Ebi5+ zqUyyN#c{+5RnK)5jS)vwJ>z!TiflpE)929#5C>G%o#lRq*rV!6SlkG*8CA9VKMo>x zsCq0Va2VNysz>imokVO=RegQ0A7XfKw3te-91Kz9819dLVXK z5!ryM`@I*$5i3+xKK*KrtVh+o$Xgc?OH|#pwJS!}p{ioO`XFL~syp3FcOh$0RrYvT z1u;j}?ZlL=h#9I%UHV-RQ&inrmVFR0LDh}^o`r}ps!AHIrVt}kU9afQLkv+>>?st6 z090LDb7lx3qUy@*1!u$nRhR3;6A^t>6`gaiK=e>m7-Bkx=%VV9@sK&P22};Z{3{S0 zR9)mveurqI>Ozst21E;0dHZfgAeyK;zg}c3qJgSh(KW(|I;zeMPK6+9s5*Nm^aG-b zs_f*MB1GlC`~Mif$0NWUBq5qLNXo1RU4zuPw@40a4f6M+tY=^At{Zwj;|;cgYmhgm z{5P4xHOTcR%YSsT+mLQ~jU@Z~#Dcryha!UD4w9vK&st$)GDw$r_GZ>80xWHRq0syV zdkwPFKjwy>{4{Y9H7;gv*Aw$;>@~aG9 z$Ci!ZE}8%NR`OeCegH|FuQtzmIUQ$^rYx@$8!j;a8KiMKeJFLCs?OaYeO!4&O{o5m)$>{3LWuJkTwSgIHf*X!1NoW z-hTA?Fcw~0WIOk~<#7QTyeWMriZ|OS(h@AZty@;fOhLT2utl{~@Lqc;Yxfn1_v;&8 ztDIKbkesu+<5!)G1(Bb2lOiDARw=xd$`J4Lx6f=R7DoUdn-!e>1=x726~OC}7EBR6 zsBx}$yA&m_VdHHy?{rfC7RJL{i|WG=C%t%*_@>9v?7u*d79tt%bJTWsF#mR2lae!SPy=Yy;zw_IcHdCTK`G+zS=Q4QcnW@ix||4RYVj zcz7S6`Y^=FZ*RzR+2&qRaCh_af$y#O`~NEj-q)=u^9B+o5$krG#y^}WbRlSq{8e72 z$NQ!meLj|WWIW_M@ZbIaOwj!kDEt1nJoZQx=U_;McjWRteUi2+QkMN# zd9iDdUbRh_+wNJSFEws+;84g(Z|oXWaPp$lsU!RhH^ibo@^JDKY29d98XyWBwPQ9o z8jj;ONF0hrH90OjKti{7;>}e2Ay(=5uU!txl1yKN2()Q9O-&UW?-VxDiWw=! z!}}A}M>0-+>%9`L@Rx`H>7KFdm2CKUU;V?^U+lO86iV+HiyyDY{dFL$<~jPr_5Xne zX$^foY;zb>0QAT3IRH)Z!4#aqFoLIDf!@e4hTWt8gOd-ov)?=sDH_jri6gyJ88 z`EE8Os|SZxo14UfC%U(0oFLwz30lJ0CS+jn?8*jP=LoQf!!_wFAXz3)(cxZvdHnv_|2I7SpWc-|V^Qh>jDo8y}_&%M?j zSbfjz88^qj-XihSE0YH=&M^oc4uyAHS99bsTO^qzXzO z4t9$G0&&>kq1k55}m;2)4CynJE5`1&cP$2JK#h~)RQA2G1{-f3 zts_WaE933G4N`q*;pC?m$Rpwkm$wRTeYj*`gO7I~zrZ^&r2x`C-mfd>+u?6cXq8TN zrg5ES`n|W968d}uiDZwGhuCa2?cwlGr50J(buFfp5hF9!_EZR9;8Ud=0 z7KBGBVb>tO3qB@^hY6sH8uvZ-%(orSuxn82>RsngvIsHU43d}X11~=zPwS1938KKJ zPN4D8i3!|>=Zv*x$D2Vr&>7i3B;bxegCv}Ava8Z-WcnIJuaEA}$D5*Z=Ncp_8oVh- zhEcq)?rU9zg?F2@D&JO!_m6@~GYZ}g`kCyjAl_TI8wGHMZXzwoe7d-5Q!J>I2KhA* z@8z4f-8R}l1|QuG*ln{TK&Nei*4qR#mBoEk3;}D-@k*rY}j~*$cUAF8vaX^ zrp6^a^g)iqV&fgLHuIMhf${K0eH_5aPxju&{?%!s!1wHwfUYb)-Y@;utU_*hgH74{ z*UU=LvAop~9dVF-1JmP8Xr#}F{^wxUpYR50xH%y~gE!@)4ixWoei2Goct3i>v+)4L z`|JACk12SU$nRah0OG9}F}|WB)RvTYh$q%jKNgI1c;}5mydBJ~^QPC4!G6md6@^(5 zpdlvc)_^!R-Z#q#eon!EiFMStAosxvo@3Z}&)Scqv&9H7T=hnMOycBc5O6tp;;Sey zs+w^cYR6x_-5K(0hUL#L@YFmYuc8~j|JU!kW@n>vmFe-G?5EGi3B6bm?te~iiPPXs z`AP}J+xnU1N-VsGzp-pP0`WGTSjtLS-cp?h9`HfD!(HZ0+Pt(OJ$T4@_lt5YaG&>5 zL=5)-g~8*QOD)J?6MNk^<0lcIFs$T>y%{#%lHQLuZ|k2Wo~OnYuecqdQ-Y26?;{!! zyVw{HZ`4O0PJYHGH?#4mih(QV=WR78#K$`_V&0pIU%Nntj$;#&j*mA%{LF&rrD@DR z_m-s72amla(88)gYfi;p9D8!zaNV8_#TKvz z^*UZ&auMD^T09Zm946pEVmITB{QW)_aGG13O@>3PS>FAdjy7aqq5bsw%9jyfuhH2% ztOnRMs6cz5L|Tp&gi_-cc$n&^i@9U=#qy^O%M#Ot8E%Npr}|imli$_dZa2UG5CIqT zN1i!;o5b{q67{o~XF=CkFzFocwQII5_%$ec$l!ZX$xi04K@Mhg`Pjj2YtsJD2B|a+ z-jolIQM^sm+cdE7-sFF~hYJp|zod1CDR^JYPPzXS;yr6p=%{aOPttnLBD}pK7O?CU z=}&-o=Ol9OZiIMqW)Jvou8ROGKX5LZ@Nq2%;BS5+R8Wk2>Y`pDm`4YME zSU@Q?PT?|7LAf9{-hH>qG(_ex9^RX%K6-KTD?6HV=sb%U@VuwgU=e|jci-z5!Jk|= zlIm`MCU_C(IR78SYV(?t`9E(V1kmZDVOgruKj;4!(%?OHx-t zyf1oZ#ZmB%w1_^o1~y2!cB?CYud*XKh2Ps@=ot&n#CN;rLA*J;HmB~~NCvgJXZsh< zMgSJU;AL5%*m!H)E{)#f$^vEt{)rPhQ8x(YW8)ntIF+@&nejF!P#<{tt>*faY*jA` zq~;sleW{F(H=oR+=Nze4;7!lb-yl zZ^~UKDBcRB!BT%GXAk^9V)9@FDZ$fnar(zEp| zVDs{OM7iyWQiGO@#Cr|qI1#XFkibuS(R|qdYl-BoT?>cUr8gBn zIl>uag4MZN@O3MRuY)Cf3tZxyJpWxc9M&L@Bi@}Ia0cn7sU5XbBLckAJ^Rq$Bz6tz zyZo5UXTb&#jZhHRia0}Toqxs{=b*%!vQD1-2Dj~U+xkCy!oyw(_>Tk zH6?nIwf@ZNEJ`$IqN$e@5n{s^_I>c&A zl6A50_BgkX`!>Wo&fn$49Nyx$fGfm%`R)5xC%-w7R<9IK3k{6}C#%Dr9EW&EY|~!! z1`e@Ld<-R}RU<&fWUqU03O3$>h2`8|McF_pH7>09N#(?CY`h;w@Rd#;U_8A2sXnT4 z@>_Y>j!*xA2#}Ht_c&OKkGFuqW5+}0!KC48<@U!5@$s%KsOIfe^k#azeUh5!@}XnU zGZgTA4sTf+yeaqbp?HIUv^7|GYs|jktc7@o#S-69@P6gwx7iEg{l@9@c=0_)((%;_ z-~8bNX@aK{7E)Gk9Xv-HgkbfybJRywx1yRmu3hYRQU`W z?~k?%eVebb0wHRgvyNac@){d&#ZTdvGv_fL-tVbCmf_@=!l_cytDWzs@vJL}Jlj%zBvfUE8e60Jcxi%tuu6i$~!JBep zDvG!3ejRNrynX6DmUKhBBaOCuQt)nmT)r^@;+;|W)zILf18Iom-TMBaSYXClrk(=v zMz-C#Ed}v@MGiNL1rdM@rV<}t!p8fGyF8b)7b|F_#znFsuFYq$@m71=nDgQ_x$_uWoZG!%$3T>qa-^-+$KpTyR{nwjsyU}F$> zVcMD*%)b|uml91R^z+^zp!Ah=VsSHmgA}cly=_6p1oPLRpILPI@LFpBYUrO&?3UBu zO}PXe#k*{?3I`V6gn4{Rogv;P@hwZuA>MgOQXP~7(h+T)$trHHq_>a8ZU!!o2dNs1 ze7WEdyR~#8;nfy0c**Wp;(RR}lo<4$;2y)q`%2c$Oe-mNP=v-U+p|e^CpO+u1+f7Y zA&iIjWvY)boczYl?h4zjB?6SMpT2%&Y8n@B?X~H%D@)zM+sN4zvtRf#NW1zUmHm6% znZ7})IYpljujzG!hpBTjNCg_aDYyEgcwhT8%Z7z_a)H(xe~7o{lFR-Syc6~t$~3?k zq~eTMhxcI@QrpCkvOPyUa6bJkVkyM?JMrpX6$diV?(_@(eK#Bo*<9BA#fd$Gyy<7~ zGOLpf^ity{&dpSQ`xm^`{Tq%18!{f=H>f^VZpO#Ex_4(rwSX@$XqT7BYNq4!mUYSLUzUY2|KubmlP(`gj{=|a`OQ^t zc^bSa@2;SD|I9wif`#{>N7U3wi1!Ccdje(kc4hhI?9C8wO}`vzxqI74;5E;x3lHMJ zC-qP9z7X$QFZT}j+LA%r?6VjbS9tzk=U89gU2MD`oSVuki(~_N)Hp5G`$cWD*prip z*J_KETN!V8tBUI508V~YTQA+_hW)=yL@%j&K0e+=-AwIXwI4+9@O5H^%J?5AMrU0y zkGC0Rdc4o8l+)$o5J5BYDf~F`zx{u-TVvp#u>W60Q-dfkPoXu)ugQ`Rs|K|foM#=V zy>3_{QnAex)}Y6mx1R8WcaZX)LzH$IyOZ8m>S&nN#{-L&inp<_|G#9h@#Y&hGDwj9 z!6{rG29B9`ugm?h3$qb0*8FAbKFSW_sd3F&@5^@H!oEQ|=k_JdIukL5>;D1O$61{G zPTeVX{Lv!>Kr)9sn7ikC1jO5eH_5`zoeYHDh}rj^3@>?r&q%rTMFi48YjJgK!@wVEN;?lm;9@rmHRa`Cl z9QW6uWvO-Sm#+IvkN2L%^!X6p%i$S3ok96PT8Rd4%G-b_-W!x%c(Cx!Db8{if_NW& zDbYj0TUnE}#dmQ3j+i|7M0#qcN9Uq zMYoI2mbt*&Tc^#RN(+aBg!R9ZF4$tP-j1ZHe@wP#2hr5HF9hF5)7{v3C!A+Vy?B-J z`u`!Sj~JZ%`jbu1sig^nBJ&9M=f(J&6V-(*J0#pqK+_@T_ZPp=(f_ZvN?&JV#`Jg- zCfC#D(|tLIDxZ0|mw|I-l;ijjm>H7l|Ee`oK_w+Ca` zK_NA6;pp_LxN7YFe{@a#z0miJhxb;hk3Ts1l^$iEkhm@a{7>rL2=~OtJ0U~oy=7Do zkn?AMJ}HYo_ZC=oP`!fv57YPm*&Ouw5V9j%&Sd`A|D(McL;r+BtU65%qP$;?)}U(* zYeleX5ZmettI}Zqk5v8mU<_-}-KLa@i?Bgj(juO9g5*ZhaJgc#s4E_5Yn+)r2Wyb< z+w~IK%b- z7E~W{IQeZj{WSD|qA)OclqJ{I`WLt1=^jZs(yZ!7n)vQ3V$4U!2ht@YZ0G)JGW`xx zv;}=W#%fgq*WQ>LV%2EyraZ`w;+-BSD2#>o3thsxOAzm)X&K8+Al_FcdI$0$-n~yc z$07yXNh=yck1t=ab}f+YgPr`xm@#Raq5iW+Nbq z8kaj0wzOOY8}Et!dwLI==P?}K#Z(_7IQcyzr}8`v5C+SIe+cf*!N;4+^W%l1r#(oW zLh%`fMEv6|PI)i<=MhgaJ>KO@=<_kO-&aob+#KGjGS~*fYpd`;dciUI_R?jqBa_eMO80Hr_<9jJmV}#>4wM)rTHVev%8;E?-e0 z47P{A?tU4BkGJ%dSD}ulJV?YpNOuey{_z$i7RDG0mR$I=GSHlZ zerh!@C!+(|<|l}pq9;5SHww+9HPd;TAIocJPrK7t}c z_RhaLSG`x$;H}!HnTX@dXJNa?dw55&98?rDYjSQxmVjqrU_#9rPqbm_JkQQ`pE)VOqUo$gKqyZ<-6 zC(ZM8KjW?5>Qj9fJtwBFTG$pZWP>)KVrV6Y< zx2C=WBUpo`*KLb>2bb9I@@XxWxZpxsW@0)N@-rUfD?X}6z()2J z4F}W9EvK7huxk)&+l$7;AWkqwje8Y!XuICOyg{1Uam)VF1;*?DC%*pU<2X)!)h#mV z2C)Bs`DDw68|Mgy=syqE&qEzYvTt%(f%lC>lT*LwI6*o}_~n+W!TdAGg)H>>IB}VS zI)l`v!CP|hgQwo=P&OxWZ9+URLA>+6yft5`>_+1L%)YB_ARg$R`1~Oo;$3xV z*9T*`yybN)`pr)J2(Z)Pfa=&j?EZi2=gj?PuzGt?hCc91}Pze zJ|CTJ+bg;M>Hjro@Ye2$H$?F+bKWhAh4+HtoeGB_-oMVAI7-1g|0zdp0mNIp^3e2x zAUD!ow$_=SaPHl%)Yp3v;$5oMdG97X-r^n{?D%PU1mH7!tJGnIjkgpb>CjhJPQXcx z+v2OfdAS2N-m9V)`5a)t>McU`u@Wag;;x;AeuKi`L)W^lSPp!=Z*EQFuhaD-ooY-? z`?3aqd289%{_7^=DokI!h4bn2q4Bfbq$u*g{vWG%W2ireGe`rP8f09s=`C7=UgWQm z#;QS^vg^EFKE7^v=rFMuz#0_Uq!73ho_T!XahCMH7Y`K0#Wt*lHE5R` z``b-kWFVMX|6Pa}2A*!6_t#-H_6#ztqVc1^A}&xvjngksx%_Ym_6)M%bzx|psRYAq zkOotIT)@dM$?uxC)q2O)%DCb%R#Jk4L z!l6&lg>*YxvWB}R9xVG9S)>Q?_AXRB8nc582D4He(;tU{^A*NfZysXfePC^g`N}R% zkWG!_a0q|;HV+%`+fL(r?t+YmcOccrO`QA?Rx1V5{X$?7Pu;v_Gx$R+d-;h~?y~Mc zU*Kdz*BBi$NSPsD-|)B0k2iUcE+4Yfs;#+S=XQ|vXz(^PZw^E8KF#@T0T$kBQ&mQz z5by2L;?{-`@6e>4tN$N+cOFhv_cjjvP(tP-Ljz?dDMFdD%qc^rWS-|rLW6S%QyLz1F?f z-fOo*-aXp{Qf~_Aj^lT$I70wIj|J{)pGM~$ zJoDOOyqF#MBI6pR?zP_wK7H{6E;ZY(<*thymwqk^Ot~!6Is(8AIiC1$%+-nhQ2(H2k%?v6C5CKT~St* z9548J3!Bn4!~_E9l&Bs|I*iWS!C|}W(Y@^82{O(=)MSdJgU-8)P2v^qBIEJig5=SO z5#PDh``TNB_<^D8{y`H8Ht)omD;67Gc!Q5A%S0@HWAEO^^z}|jonZdw|6^q7%OmW$ zfyBD=bJbguhWCb-BaKwvpG3SDqwy{{qI+l=S_s4_J>*fXShP<~tlym$25n4BNr2Yjoll`YG$d7t#?I=4g49Gt%`x9iGE zY~G`xmz2&FtYrGdiB$!Cc@#)T;8(?y{(Ju)tBGTTUx)p_0Zk1u%@nAo)*y3f32C$% zbivWxJP@uRyBDXk=)xLQ6Y=MHX&JnObk7NcDL;3zRDb2Nh=cLquB*jfHduocG;Yrm z3!s3G8>L-k&j?_j|N1Po8|YK)H_Cyv-!wTv2r`bRsCs%cKl&b|cfASmv8^b>_5VXi z9v&F+)hz8v?UEG$i+{gwx_%0~|1X#qe5m@K6Pb9IQZ%*>dj%=&s{GdG$U~;DL8ol! z%R^r?{!+s~D@c7B-W#1xRa1FicseAB#yg~98*4P=oxDZWVV3u^BQLv$AaCy7ygP6c zZe%Ox{LAN##siy&@3hz86F+J~?Q2O$4-T6^I{qo!jQjdnW$-2SyRNg+}cO}qx3u>HskP3OP zCUIPu<^5>ouHAa@1}VEXnF(EZ{_mx_c#~OrJQzJlvfzZgEm#zmbU@zGR^d-#q6ol5 ze*D2%FLd6dd(x7Nn>c_jGS1_R@t3-Pxk38O<}<(j`WbI~D-y{g7b8BW0WOoDN&EmO zI@%-=gw1=)uU{%TTi1Z%SK(D0Yp_?4^4e7!o5$BNegE&kOJ5$WjlL^nljnE?8s5f> z?{!mo$B0~9fyR4DV4YPV}b^h$`ZMEu=$EA>W?GC=ZZy&po!>VNRU!RKyh98~T zgdp!;BI{Qk$Xn7jE+S|T0mT2@l(57dop%$SjS!x~0iuv`dWqNBm&Kx2@Au0(_QjPm z9`Acd9=#ax-B=;u-`m0ul9OH?+wO?Xdxad~j#=>Jj^OwSu9 zOJ^P_n;#neb2y<(!`tv#*5AvC$w$4Hqw&@piR!rnc{_gi=rqf_ejt3KKHR;vni*XX zjdvyI$l@G7T#EQ0NLA@7pn6}$QTC?NUlT}|Z(0&t2yYh34#&bzkh$N~pf4q%In zTe!?i{$Ln7@45iR!LPB5$GZ~AgNzYh3~&5(t^|It?e*T`4qa^CJ6Udd)mS-zt2=)6 zCm>8U5$8t~E9lqy5eh_dx#!fgMWF4{NmV`Bku>AX~ zW3UGOA#yAP29dzPyRX!Y5B(XWr@Bc?k_Hw6Eo7Yf_0H;foSvxf#oOjvuPzx|%y9jG zE0TvbMtqB_(sj?a2!N)LWu(I^SoN^}-YiS=s=r1!l69^W`AsgOX@jJ`Yuztk#goSx%tOvBrJmHyxBE#>^L%c1f9eeTkk zm5_HsROPQ(-t5H_8MTmip^u1ri*0*G8n*GE>+@?ddC1%MS@kq4dz9`A=p9$PWub69uurIHaI zke^)ZyFG@zf*ft%cVhonAM!ba>VeNm*t~J#;mfp!Rxmwp+zLALs9Rf-6(ltKdW#Va z@6BJLPg1M*z5Xa!G~O;OX{iA6_7y#By8-fEvoObIKjdA$stcF?(4BmBa^A&sLOhT& z6%to~yq#h%Ja_>gP8_IX@2rI%NLL9i`?+frowp3@4VP-Eg+LJ*CmdJmBG-Y=yEwtA zkWG#8c#9)>T*8RY5?|5jP7nZ2qs|K+v|#f#k>}`~PzxbnI$w9*v>*{~rUVPj1=A z33ejm!aZ}6YqimN^IVV*->+#`L^#r|HY%NnKKCQR;vFKefCu^p9|gHK(aTc6-O!sZ;F3 zUEIoOHR$D3D#(Cig2kwpJI>lKllEj!3|a-<8(MT9Oz$+-v8H(^Q)dy zUdnL&{~;ugI~eiZOxSU``+@*Ccm&^5mx3}%PVM%(SvuDsnbGjJHNKrndi4$7Ak}-Tboo^h_?4TSIRkl@hKdNy52S!56|IUdgGAsc{?2&dG&=7WP6OWc zlU%?S8K<4RrFSVSI&Xs}t-#RnB@D;A6Ujp#BfgqIhh*Uo0-(mBMUFoKn|Iv6gEeU; zisbI!_d7`<*u1$~N?9}9nZH5uETk`w=%dAXS2O2$Z>HgGBV0a1-ac#{S?I~-N$$J3UPP;z1Qy7|_bh}f$kPfk3Yzfgtu~v6 zH`n`#;FbJ-^{{+&-koeOn~qmx{b|31Ct^m_j)G~PQ0!|!!M-pAbpGiP~U=uk?whrIjEZ}uC=c#`GR#I%AwlfXcS zp4TGC`+<#v?jhJ9sodGX(>+QAxh=ALOD?1H?mBMbksZwi(vWds3l1d}j-vDa@nC{e9SY4(Q%){B;vErq-{D7MPagSwVd+qgu3xZcMJ#Sod1$}ww+ImUC>iysM|8R`|AMF3FX=;#D;PfME4LTX{ zM;)yOoiy%#w+hyvZlN3P8n6as+qwkz!gr9!yZJVj=ev_P@Ndd8u_1x)2lna6zy_($ zjHN_pAH4r>$HdKJ(*z)H^y5^-A@n^+?(dnx<6YcfDKakEI!WLS{9-cNAE-#km|sQ% zNFG8M@#*=pt~~~?*lE>aHN887U4sG+c8+XP*agVK(h~_C*bP!l&QGC-!S|WI z2E|;ZFOM>rr$eI0=B8LH8s3hk1*}xw6MF4xXuJa)e(D%N-UnRLR%t@sNrRQ6=wGOPjUyl+glUF$l{ z4Xz^NjyB4E@5@Bzt;X73k(kVQyssg7ti_1$j9B33g6#s}!I&@q&=5B7yp^~kS{wF) zTgub(#J^*&AUA)`=oXJwV)_P&S0t0JJj_dF+4cWfL2jYp?I5p}LFJtnTcL`^+vHJF z%r?k7`W}D6EN}AyJxVO(J+?Jvp+5Zn-{w}KE3Td-fE#@MdJp6sF(F^RFq8s{AF6FV z+DHHjgcXZ6xuElwZX0f#@52pbka3Gux88DzN9X;=Nccm|Hpb(<0?FeyMtq%b^wx!x z34qYRv)}pNVDmO=h~0ZyYcJUUi~r`afQS=5WN70<)(i(0sg^ZK27H``45}o(`Gmit7 z$TA-9OeBwc81dykSvfeiLjY`gva0LbZEW6^ORA48RoxA)@QS@T{f>?U(t|%__3zwZ ze%^`nmn|{LNDM%g-81YH8ebaoh2M_vWOnd__VDqlsS`g6r zb}NXrirF8mfc@_6guQSid*4;2Uwiwh(3i)KZ6tk}nE&qo!!g5uu>ZHGsX-o|GTUZr zkOI6xx^Bc7hgO56FIR-$xmTuF%Kl(t9jrlTPfC5ChEuFldB|$jSQoOQs)3O7E)pn~ z_FiyCaD+UleTwD&0l3Bf>SOAX8w9X9nn$2X9DN0;u{CI)*%KaMij3PA6fX9$9({^U z*HPmyy0VPn4oKCJJWgT6SHYcd2iM0BJg*D#<@(Ii!=lsmB)>K9ge2J|BF^2wH*C3n=eR*66?C16=n44m^((rb-jhUiOvD&o{wa|Ejl=L0#khjc{w5{tQ z@A9~y&K7+1S7s5YCr1yk36BH z|4(dOqU2-3{QbW?eR=q`Y^+_rbFO;Z(C~IHbxNc1zMHAJ9*y_*nqgZJ$h+BKeBUf@ z)lI+l&x5?>b7Z3oE#1kk_7)xL<|HtBJ)n^V_W!}G^G=f@C}7pigDmWZL{Lyu{Jg9Q zoi`VeV7qq_4>*gAd$BLW(%}<2ZwXu^$B#dZ*Z*@Mc`V0>FGhyE^VGBexWiRj+{T5? zyZ7saLio~M;NLE%!^{lC$f0`28{ZZZAhq`#cLJPeOJ8`Z+sTmC!$$Liu3;MZaQ z?@UvJ{JiI1oUK8#{eRc!mIY`v2(O(RunDdp9rlhcQinC@_8F0P%i#*r3yog zJIj9neGf7+i+wN15o5UiUl+*(E50N451ysy;DO^$n?JV2*fpr=X6)5YK@+l(=Q)p$ z1udwJ=3il(CzLun9y5In!gY+(l}Dv`Yo+{!xhd9(hPSWOkQkNs4xz-6jk(vCE| zy}xr?P=Ov0<7(m zmxCa0r-h$gW)4z-o^r|KQuy@N$@lCPa*pULNWA;Z0-_x+NJhr3Y^}YpiU*x{slWQ7 zONxxgn-9qYE54&DI*SA0`TsHT>kn7|FL*D`sm{yT-;Bxo*gbvHi|x#RLAsO$eR&vJ zcxFcs=U$L@pyBOxPa~Sjdurz$Ry5u*&nIplhrF-bZcv*&oKRi;>1PS#U9FnDI#zU-y9OwoBS2z}z=qsR-Ik#XBZ z6+RVyM{ke<4u;-X%f@)T=OKCcW5hRl^ikGVcsOzS$mNQtcA+$^+V9LG)_< z3s33j|0THM(q0=fef7o_FQhAv)#o?<{`JqpiQ8y+d*(|Wq4IvNoyvm78@I70rU3HZ z`+DA~S>7*KlXYj$-rjzivZ~^6As<^;&^2!l30w{JCm)Br5AfCQeHlXmTV=lt$4(M} zrR3YqxPQ6ca@Wb+quTR$fjKhnnG%;s`UE=ftJYFu1#cK{dus=h$7PK8o^F#Y8?O)m zM+-|!x^`ppCQm11<@igHb&5}%Ok9fH|LYkPT^vz2VfwWbiVrAFM%tRudju zx7w4H8e1Gf;RmXgO0pl4hc&2-Qx-3DhyrdEEveNQCjyDzZ}6+vpf^a%eCyBQzwv?P z$hbv3>y0CN(N~bG&A$X0UKeM${$CWyV+}@p4S)JQ53}Myzqah)#)b3su*hh1uGA?j zb|iDC+FI-u$F4!RfV?Ft@7tNa2I2a1>B=KB_RRV8e?GC}PQ!b<%9DI5?~soQTxh&4 z<#-H+A#YjBRcW)l-#&GE>;rjs8FhVZwAe;=R2S#Vdr1P9+g3HKguI)QY>d7pz%BL# z*_V9liJ&R}q+8y6bl!qz#{x%g@PUWOIJ|=&S9CQxZ-qSKmwuuvk8KC!k1Rei z*C4sk@DBX?a_;{B+1*?9$`71qyq{g!FgPEsASJlYPt5YZ;{1lw0`lJ8tjrnpZX4NN z_^mceC+z?0zx1j@-ieaC+yLaArkmDWmqi582`T&ad(ays@lz4n0#SS*5*au1yj|jB z7CP@*ncu~VhK$F18IlK9e7$)=gxsG3z`Mlbj@KYI?<0OY7GA{bl4~t*R#oq#9Cylb@pdHpK0a#}(?9}e?nQ}NK;F{V*N!y7 zv$u{l0n(azL?FPC5LP&Z&ij~|Zd)lgAK*vEjVX9q?u$p~?c1{TXxIzJ+ulk<^6Zwf7-q@!kpxT)pI`inA0fBKHgLutp@3Qmm!{+c1fc9-Uy*$z5cTAvy?K3) z?je4lf{dGLSN0@=wD<*SQ;{eQ0>^7RvLZ^0ukw z7C_^z&}AG#guGSqiPvU%pY&NOEC{Dq%9G8_*I(I@zlNpWeei({{9s=kq$b$T(Ni~lAAR8IC&}|J{$#^fx7$L~pY{L#;LCCvOS%Q7%VG39*y4PLJi3pA_ zGiNz^5S{net&%Pa)cOC8%aUBC_^1HAdcSjZ@bi^qJl-Qn9v?8`D`JT>d%=MR>6{Ca zeKoLo;~t3BNPk*QcI&&g)tHlx>Me3qbD8{o=C9tm^yN|aD)i^X-MRkXlZN-sXg^nK z^`^)Zc+hw|?~+cbg}f~i?{v)aKB2p(Fah$`_HvONaJ45F8eWVqcuxY~G8fI0hP*G` z^k#R3XK#n*Uv#p8@Bb^=fO~@b&<`hm=k&UIE#U{Nka6l!;{qJQUZ`tK!P6I(dyg{S z_SR1%k3|^q^=P_Qy>7>Y-Yl7?6~frOA06N4CVSnHY(WuL4Jv6y{d1uf>CL0ue^QP# zFn#|o9#3B$Dus&;jpF`0|EK=_GxU#eiVdQvLHkvH&V6Ec_5>-dNl_H71~nXGRURdm z=?&KY@>v6GP))+slP6&R?_J%?r_gCb-rVnNs0_E*N7q#DyaXF0e*1OpR>>65KT$4q z@i_t5L@bNcZ9wn;H*dTWH#Er)ERk^yo+^vwZ=+AKIjgqLFECxfaQ**ABoD0kt}1!S zINid7ubCR_AHJV~yk#XK^zVz04lmls#zr~r6-g0~_5f5H3K8q;0onsmJX|HFM;dJXeW zv8O~l=*okurinY|%-jkxfQI*;4?Rn$D@Y~JP9ZejGfe@P#365DW3hrV^DVMDnf+zGz|k6(p{h&OAo#%-8<&{=YvB@9^^n=kEWXt=|0|d5h3^ zxA+!{u7kY&&b~f2%lqsTSM6rVyJk(Bg}^;q@+HpG?|!@{f!K(YHC>SR!~>^%tz#4* zo!4w)oJas&0TX-997125tc;yfkFVwj&yjI&I4<5?yaS!LsJ0z`J3r&`mPPVdj1k|& zVR@$?^Y9?(cMBWaNo?N1GMabnI!wvFYMrSz7IgIgo4ay%PFXU4|4*hbkD@wJ=a`DQ z>g`9vJ1q9x5Vd++D})H5@fP}$t!DvwFK~Q6Jj)yZ+;iC%$h(d6H2=HRc4UX*W4;^V z*;`(;*;GH|Z9F}#EOnFu(l?H-sVX7>vz+hlH?N@c?tI2JEM5Y?hlh;I<+>JC7>dsO zxVQfT8yw^DZbR}&!iX<6Po(>^9UidYo;W*`uzB|%)sOJ0(kF*xwrtH=jJ-HXY|MYU zdL{FJoT&c{eR&LOCb$j3`zQZ<|DT~d|9^sm{r@hS8WgQ!u1u{#?IcBUv>LR+V_Jy_ z`~O{~x_gvh4XOk}cW=WQWN8w0K;OffY)~0;f**bZ@?2u>vS3()9;{m!rgD-3NY7Vr zj9ef9nMUcTjNRxp=uq_w+x;#AKoS|ZZ)B(P`se61Xz`*G3ac+LUJZ&v^1zDkd#ed$ zdK(@r5UISNj%U-ulJjwj+tzr*pG(|kj$0LK& zNeYCy{y&(8cN9LglFEDcnt5Vqyyav4&Za`%(vG=Zv%FpJ2L)Y&ywy)H;<}J$P5vXb z)_5eB1l*#JcaK9UDFMtn=;4AmB$5CC%FFE8*dz~0>HmXJf| z{dCgk;!8CF0FZH+&9!P9Q_*>63^)%t#4sN3CrBQc@pWxaFzylnZHK;QicDayAl+n~ zv~HCfljl8mKBuIJ&AZO!n~IQvz>?w5le)aMk?;SL}2{)X_sl16Qxl7P^ z!?*3-??K+r*lwPlU$>S?bbN0v0B51eAg)SVPqu<_$}qOjEB5$B}jSXo}d7Z z14dWu%n5)k_15Xb|H3;rwyjb|LIAKJ<9y@aiCv9D=N-8r(1a(L@pxw;c@Qz;yYu<> zs(X@nklK24{nRIH-epD$JSTzA zHM|_`n16B7PhTDhCTmVDxcOiIPwl-J`bXIRhtt#`lA+h!_y1p*3V6Fe zI_sk!5foq6vHQ9N{Smw7iv?nX*9AZ!GVT{=uD3b?{TZbDHSw3(elT7QdWhsvhY?@R z@_Xy}hyuVhWUob^Ep~&{Eb@Lh_K*jtuGtmL&5M2hkIM*XXpw7V{u)$IUmgL9EyjY^ z=2nnlG`!uZb$f6}*~Ua%RP_sQTz&nHjWfbTu|q3;A9VXh!M z?80ub%os5J3R09vUmg>s!uRV*bK6^?G`wT$-u~Uaef6PQ0*$vUpG56i$XoJvjQ%Rf zyO!rEaDlulxicFYhONkFM%8MEi6n4mY+;i;weC^|1w1s;upny_K&|Ro&W3+^ zyruWT??S&6c%w2hZp2-6-3l`L3KDnuzNL02sX1upug3JeUGLGChr55Arr{lPo$o8Pdb_G;uR!D7 z;YP%pLEe3P{#=^nJ>zJTm;ia-mp}PNeW5jZWynF@oACYXrxIpmCXjd2yWY)r(rzOpE|ng^b%`BQNo;44rrHLPCyi1LN@yM)G)v5#P41 z$rbY(1;EVL6N}q)v3Xmp7gPIlzy_!{R$ly?QIA=@aZ)`C7bUJ`dfqrWI`cT`s*Lpi zAvC-Xcydipd8dguEJx$rr{uMwC%oDhpyy1y3kW=pl{?N_uWmp%%~$T>^` z>Lus*xI^AcIvyU7Jw*ZGqCAVrJ`jMN+mbBjQuM{i)M8uSMd1R#3K^&V!amiM4SjK9 zZ1+aX;11*Q{*L5<72k)7fn8GYa6(f}LHe*HHtzva_2zZAwvwA`k4X|f&~d$G#-B%j zV*d|(dn=p1Jl6VNcF;QgU;oe0eLpogIK@WL)Sx56)$-IDRJj4a60HVJMkSp+bhk|J z4og*l0<1xk(;Gi_TvpY)kSfqIB4JIoSlo0`(w+qR95uIXhW&q?x}Qn+1qz6;<#A&> zOaSTX4~{Isqt_sNt*z>~}TLYtSX9z+VRH5@c#xjPj!AcBf5;m8@({Ztyf+rk zfsprp8s3M0Z8`Usci|U#G~O-SzpCa#-dDv#+h%#M%p)xAfxJV;UbHOWu_pVToay=Q zL;_-4ANIII-WwFpvqu(CfCTBPzr6XB}v;{oZOuc6wR zcbT3yZh+1_4*aS?R*?H>cptjo_xA+J?PRqa8gGsO>ra)C_chk*S}P&%YW0fN&ye?K zuUr}52`jRL#JwA7@cVxb?WJjvkau;hY{A8I6!3BXmEyN=2w=zA!F81c^y>Xfw!E*p zM*#RC;}UIaCf3-X^R}I;sSy%mJl<1C9$4}9iY?2{mJ|Si-JV%u2e5hHPgF2{wcigs zs-Qg7;G^UIzu4liy-gdLzd<@oUmgNuUfGFP=c@N!8r}&<4yRD7_q>$}vS_@G+-d^b zAa9vm+4Hl!OS)WSenQ@R60={az};JRkJ@}Se-hX-xaxd9#1B0Vyp%yI-~w zz{ca`Sg9~{-r`|--PfK900U&4q30gadVtPbhHFuosvzU>UWVj>6<_%gd8vI|2t1C+(Fg6l8Z!X=c3ua9MU=uQK;m7U8zFO$KPo;K> z4s$XdZw@4nlNj;c6**b-zD5AB3FD*I24eGGE;X#a`#}JxKl(J!oBsj!_Lf$oQ}B&- z%)dCvqce{ep3!Rm-T%iZE$F|;0c%h+O$|zsB#TpPQ0@+XWwaVpEA`!o3)Y~r_oH@l zum(|f9@Tb%caVf_2;1i0U`77aWNVSMh6G|tcdhQ=A0gw#<>rN!!3U(jh*z1x1JbH5 zlkXBPpx2*Z+YAX_XCqd7N8tS^1ww?4oFRC-t5_ zLFHXJ(7hUsH>GFZNomMiMNQ@2EN}OwJL1bAZv%_9yf&|_$nT$w5!Ba_z;oG2nJ8P!paYxtr z34M8dFVGM9cyVq88A-$Ycp*iD%DYy(Knaca(Z+%F4Ul(4s?I8T$h&T-@wM3(q!%ki zef9rlMLumRIy|_61gdJe5066Lzs##^av|^4+I(l#+lXMFpZ1G0|MLAm-qePDQBruY z8yV;Rdhw7eKRRzwAth5yXU5~rjpQMM5#QcY$MmnULcrx}*iP{pY~Gz^de5)s*?^A6 z_Z+@VwW9vBr%v6D^M8J`t*0=3gJiytzC5~;ImGSi=00ypq~U!mW}=76+bAt!6&mmR z_*>%kkoSQK!?ao6=X(%PZ50C}6k7 zXXVm+1hC6O=a#zx`r_p29d{QCK0F9O#%WS z^o}AHQh-%kRf}{T0i--lxSwW<&iit6w#_z9JUEPubNlQ*;NgSLTdDB?rNNN#c$Xr1 ztj36MrYNhio^XKgK&J&7-M7=?WzesWqs16W2Pl8YB@?_x)H6e8n!Fq9Fro zkYmgp1I2PxJ&l;arw`=K$?G-dFX~nz0nLNABDCQOQgA$9TH+Q3L|u~Tygvg^kQ!}v z&bLLcL2iEjM_LQwd*pfvjO_;oclGI=J!&WMpbi-~Q}Fc1a&`0uDe<7BsQf*~ z<6VX1aR?*6nJY`oJRZUGe^;rzFACVaj~rjU%@jBQJuCS&tN5BQ8zkJQrpCv@KIZ4W zQj4xU%rDI-v=+|x|4A$~yiZ;y{C$Fy^-sPk8t=V%b}eMcJ8YdCUKaA+r8KZU4f1aP z8k6|R!IGT$yH8Jk6?}s9Mf`(k$h%9feXysT0uE>`aPiwm1n%qjKFGXA=l$&W(}n8} z;DG}&F0~}9>%AyC@Aa<_?D=?^@pyM2d8lE;C$gF-xHiglZM~e#!e-FGt8uG@`@J=NNI_d}A zDFT4AKexkCw|WJ5 z{%^K=Z6)L#R!4HszCr;4;!pP93nqf622X-dy+P-_)2J+u*8>k8A>$OqiWiGbqp!VF zxiz#Or!pSz?MNOe81Y?bs5qW2f(KazHHASqY~HFPW!%C>RzTR4$4;Xhd+lBRjlNTccoOoDr(v^oGD^c$by!-9H{vWH0V}M_WQ!EEf4a${I_%>UER>JrHmqfea&}z`z z8$acEVGY{BEx1ey)}R<~O;s^C#a8cF)YYM6OkQ(B`eNEj5>Qf}-c-vsLgpa-Rv5cW z0re}sm<_fOz~$_P<|b_DHHhcsyL}BG@Zb_ME^Na~6Bj=8DRyS_86aD`} z;6(DkiZ3x(>}=6`0r2Hv>r4Cn*fl6nAaTgL%$96@Qn~- z6W#0Q^=1n?Z=HzTvA#cyH^qKN^1zC3`iCRC#Si$!tN@Ef4?k?)3m<-1qdH>`v^*|t zBxp5Z_y2-Z4xuM-OuvG}anhFug=4M#m)mpw{{kA`S?5Lnz922GnW>4!J3-@&tUlyT zyzTmJmiL|2<4PwX@8}8l=IT2e$x_d^jcLRF|Kxb)+YgX;j*U{q>1qn#-!zjwwt)zK z=Wkp1;vhQjpZlLyZ*9SYZ^*a~!C#>tRnd9Rh&lPLn_xWN6G$F7@qdrcYysy%$2tLU z?RL8BZ+mRse=0M{wUurlw{M=E`BiM*X%^ca{fgYf^t@&D=*#1WQ&f=Wp}GE_jfQt- zz#BJe_4X<8&_LsTZNeqQ3Gx;`yuwo&^1hrc+cmp;>to(_{*2=$GSR!M&J^z6#`LT0 z`U82B8y4=GsiJ_jKIb(86^LLe&8YNkC_3+G;=VqIdOR3M#@S1Km;Aa6o%hf6+k~Ts z7>_pr$zuv5zJpO0GPnKV2Qdx)&&{@A^FD1P;hFo;4OCq|{wT1Np8j9t2YX5=)ANpb zOJ5!fY*bh!|2dqPPs2OIyy_5@_xkT^)}!&huA_A|4Dy!js%)9%?YXx7yazmcQ+ukR zy=;>i`PvFH&ym$6@Q5s5E(-hq*NLpF?QX-@TSVj}{56Sy{k&Q5szh|&mahWV3Dw{M z4jC8uUVPYL2|Dl3Q)1hRpBRt#W+V@+_@)hH4=vg(04kpYqZ&hO-s@@x_I*3%2fkW} zO`7Y_!Fwi)&DeHYl)Cyd|R7Aibd;QZD`bPBx&Sq@w=IW5O{ z{l5;92UdL9S4(d`3KRgzW6j^>PGQ#|ccCHog+=aUPKi?zr_-_T|4Y7kJotG{EYtV@ zIaT!Kp}2LDt@_H`3X+?KcYag(M=I~}1CnfLy!T#>Jb4N7PEoTCl7PI&)n>}xLf)39 zd{WL8`eX~z=YxktNnl&hWKRy{?XZ(vX9jtz>TIbRT|op|4U*nU|MCQBqvBG~i4z2> z$hh@YMG30{(0M=5lnowQ!FasyBY9xO7gERX)04*!xH1~E1yitjCvIyRIDEmKEKq06 zq27o61Szh5@@?VDqfE~mcbUFCTsGHsj?~We|6DY@&*Z$Rq4IwAVq_i~?|2q>o;t|e zYK{E!S>Cnw5qqWJ3DWSNpe#2p1G3e*-P)dFB#^m|JM0|fZJ%NM?sY8%@YvfczL-x0 zMFBUevhw{j`t@wPznz=|(|*YnxgAOR5l zL?-lMA~tWw;SbX#BM#*4mJMeNq?<6exBgt`T@i4Th3OllV}5HUQGUB{_4$3 zUmnY(H-9^RZmxQB((uk(Yx#xBJEuR11&z1ShL5!qkoWr69am;~+uyO#8Hc>npLaW~ zl{F%_#+0QG!SjEoidfl7$lF49^|L)>3h>-t{yUqU2u^PsTYYRjI`2x+V@1cm;Xx)c zF7=bUDT^jL?}$afwO5q!cvm2K?8k`jli}um&0VCx5V%)gs%OTki!wwqm57 z0tOm&qSM|G!ARR(sn}QOHR$sf;w{S@K`?-f>+`eUTrcH=I+Z-jd3$T?6~?PU)I7Q{ z;;Y?wSv0AaAKcJCUi`Khy9Swk{=Dt*9|ge2a%y=B9arr9D(-pvL*xe2*Pw?a`ts1g z*SZ+OJ4hjK0UF*HD-R!_^7d5|;X>mr^F{TT9OTV^$IWm#ck>uQf&D)Aw;|SMA1(3H${D~~* z1Jr-^e{1Z7&gs3!?l3)XTnC+be5+EC{O9o&ej45vjy__i@-||9$BD*!kqmdW{%rMr z&|ERgdm{VZ%Qm>ZHEFqb$<%gT@*=6XGV$yraLagkS0d!i8Mk;Zv5o@d^2J`+Cqx2& z^QoYt>FC#6#Iz4O=_CpQPh=e4C&q;8IP{J`?? zR*k+J*t}=g0Vml*N0VDH}Ib_nc}DAQ&7{vQ`iUmo}!eu9fm&Q)(d8r}t4 zS8Sm2zW=C%1C6)a@l}tUA@Ayr3aQz{i3Q(s3t}N}HRYAtHL~@{l51|PtKo;26Q>e( zoq)W5KR&x?3hv&Xa;{LyKN$%IYIL~Di_m%7?i&uOj1vSOka0e4IQtrZbl$J8EDsCG zVLaYeNFF^H@rm3tc=NbK0IdI%efZBsY~E%44r&@F?8zLydk_8Kz`ng@Rd8#fdi5yN zACUgpM_(SpUqzod`pj)_@zU@gs#9>_b&eSZoq@2a8h3dbBh za<7&3#%jphapRTPBapYXlmbT(tloK+Y5w`?MDR#c_-J}L`r?G&{mr$5f`Xs{8FzWG zFu9eC-v9G%S~1M8!g#!SkUaP>;;Rox98t>W2Y!pq`-{$C^L}Srl<_6ap8RBzJi4m9 z343w!%;0-Z$b9BsoV=qi4}8Bo-X!q9^Z&n#Q%3#?Y>-4~YEaoA-z2pL8L;T%(Q449 z6IoqH@4zoe?-DIo2B%n)Pn)l;gOAwh@7^cf;{C* zUmlCQ@0u++GB?Ev)9@~RldMPO{kBv_0FC#`EpOLeguJ8PY!?!Pyj33eeHDegQ(7v6 z)S4v8PfV;g4}XmVJ}t6>&5-v(=XUl23I&|gj;N^4fG0>iIKD6fI`6MgRegoqTPr@~Up`^JlDr&jG`~L<2LzS+21g<9cCkC9DlPB}(lcf0 zGw|yzer#u|oI=ofb6k1uw#Zlzcq8NP6|21Q3`6Igt&%fj>BM-v7b1D&V8rLsNGa2D zga@P>v+PYiV)MR!_Sd2^O;6y~`uMKhPVDWi&D*4oi7M7JJ#TkM`tn%zsZrGQ)Lj3+ zh=zBun|2tLx9_oXUNqhb)6xwuAn$7if#b8h#}^p4kRfjkj*_Xd(<)>u4&_arqj8`o zWa(}}*dSRH^i9uirhslghx6lE1R%R`QbX$yI&Z62W>M=61c4+n?#!5_GdUEU_bTxp zmIoaekGBnyhZ077wv;e?7T6$lmwY&OxEGuEK_cZEVVx&$m&uSniw zdfqq#I`i0VR3iP)?yVpV?;^P$WmMiTx9;OXRr8i2^wU!5WfAnaP95lv?JRT@?P~?=Rjct1#t7ki$`)rg4RnGahdiBoAqf_1#gn|E2Z(e=3H z_Q3OWi1P|gI-dW3A9}X=nHlr<|5xeDV_rbk>Vp~o_5Xhtr;Pj)xPn|pQ-dlxpFg42 zpa!?KqG&aUOHaCj4c4H-vM)YMU=2FQy`*mgY>+&j@&^9!kOV%W#XIeVNkAg#-uPXf z5wcNv_L$2X3gBDOMtYGE2?E6GzikLauR)dZSC>A1BM5wvaV<0QbqBto*PvTI!jDBi zFCX)P*m4qgcnG~TYB_Pxs??+BLa&RO2Qq{u(|kT=dO z>Pc*>FkoNLVlc{00xbjiQUj28Mu?thX*UIYxA>xVo)ii6xUR+R_?HXP&D7%ZihBfs zE;25Sr$agPEjn)z)qYQY2IOslUqrqVI8GG~Nqh z8kVa=-kW}Ns4RuN?{6R8vT>F-`vu}Ds~@_#ODf5qS>Wp}*Lrs^g#AB0!%?~9B?XLK z895w&H4?})^ocDdp;zzL#fcKxe*}RPGR}yHC+Nd3bl#a953+{Yq{xi+*Yg<3BMT$G zoQutOemL=i`I{ZxEoZP-kSByPqR&9y@rQ##P6cE0##!~~-6{=YdfqrY`tksGiC&vp zGG}=&rr~{6GuD>M8>g4K2#t4Aj*gTA$h%x~ zo%iavZ{<84jJG)HqvnAT-)o}Z@Ha&PkehshCGQtDZ=)5F+V>0h0-$?d@3dDlX7%PK zbsKNLQOooVlJs%<@>m|dXDL2*?r=hshWC|#)C4MT9mQxtG~Rv#Z@=z_ym2aL)n?D$ zsJw9x<6X1TxX5xI263~z_Z$ zPg85qM?pn#v>G%|a`o<*sxrOPt4C!;VGSB?Y;H?{Q!IzY@uhkE8vv`|u9Gb$B+#8m zte1ifl9XDq_*6dykaXBS4?HITlFMSdti$LvC@N3eJUB`a97M+b?C;tsycB(k71+M~ z)UP=M66N}!)}naa9YY(>Hg5weS9=y>Ld0ElC0OVamoFw zn7;oH;G!=N{u^Fu3*a3jkoO82-j#(jLR8*2KTIw|<1KrppeY;jwm-v?ImHFQ?DS}`K8FzQIa2MZp^y*E1tE2xugYkG%^T3Ml>>t^th(2Dh zZz+M}fgm<-!{3@=MKeJ__GEjwcNKPngxloizxMMprmx;Hru60ULD7H5WM#@MZ*dyl zH_gxdeK@g}J#z_K^-er2#L)(MFWG%2W-;VltK-*V2YDZ6+qd$#k1BZ6bvAUqGQ7Q2 zcf~b-$h+vmmDdd)D1fuHcJS76BDf$@={nMjUcIkeSB!AmCkP6Vaqn)HPOp|h=bdhN zXv8m;@pxZF^1zC(m-Wl3P49pf8W6^N&~iB+o5Q#AtZm5Dhs(U7RG|-o6-(cMboh{a+yOIP>@8v%KrQhA(JA z-d1le9oZHo55907xifp7kX%QGSGxS#^f#$E~-Y>H~%|A7d~*OV4kT|}?mQ#$j9 z#oq~ntH?NZ5ntD=9CY41lPcr-{fx)^7m^27d>WfLl^$sEgL5|t^M?emdHesq{P@)_ zZ!o01W$T1W1NP!1c(al1{Qm=slL9*P_-OiMDSW);zx)6Gr-qxs{y#Xy%F@&za=qw6 zY7Hv$lafZOLGy;@Y5l%kruT5G=CBZ~LGtamS0k_ni7q)Zm@Kdn+)OCC-sI7pPqBKw?n8CT z+)O{k;1RGtJ{O3_L9I@(ve+XAa9*})oVNkDIn*=rRzWOk>LGO_xB+;(0N~a z^di=+Ul6=Q#)+5nmfvJU=ban?LUTSc9`7O~k0gxvey^No^H7i%j5_7Ib1cW^ZD*IW zU(;NYY!XnTIwp(F8~4h0PxyyG=I8C_Nmm|07dY-6-V!?7AW75kuKBI~jLKVLOc9m0 z|CUVzCCK}zr^WqQ-iq;?lB*zZhg}Qyw&WTBp60;uBIuexgk;>}7q4Sn|ky)3{x(HlF#+_K0oc~=8oj2#R%-bq6jK^CZ$%6wUK9XhE z<vD18F*zVwaobH^S4xDFTwZ#O4_ z>-VlKSPXev2?$4?`%D2>hUz1&TO&c~gPb)≈e?NKFN*MhyspB4ixpZIz&oGdgb$ zt*^o4&y2@g8p#7Iz8_sa8Mz#MAZC$o)FyFk-o_=#sXgf$!0ikGD+w*eyrn{iL%@)erK%UTk}lmUl|uld65; z0F-NQY@OvjI&ovEFyzfSZ<%KsEhZDv~9`P9Qh4`@zQP}yxn0Fd^-T&h3ZSuOyfkIa7>n+@xR;r|N zC^LQa*4|5B9$%&Uiw5A=TmI|+8LZd;pTdDFNJW|&^x#uMDRqjyrn_V%S`C^GM z{(m^`W}P6MVntcClB(epYqdLUKqJ-~yb$3$`KN*e!i#dd0%3#H)*}#ZHbDVLMTmUM z9z=p4PkOq)yP!|8Q%35dQ}7Wx>Nu$r23BQf(5KjpkJ?vr?lImJ`xD6{3nRWiM{NsY z!uWuxj9XaxBJ3$P*CD@C(ZC)Eg(z%#t%O~Jx^KJ1g%&ga1?e;O-gM=Wx+OrTDShq{ zyOlJ&>no(psJxy12ISFrr(ey}OoP0o^av`8AaB?0tn6)&_t&nQHPPl)K=1QMwkvQ3 zFP1(e9s_x|SY^r%ex-o(!?!_m2N9Gy4aWgb^eNV0DpTNbi{RgJ0%zUt#Pgx^zG7O{ zu&IIZcvJJZiV!?4!00$^F`l z1LxV%c{jxrUjOxo@pyY9c{F3hCzvE$^A7NW3C{bU$s*X*`&YeiMY5VbuuVQvVR*eB zbyxfEgdIMacUJKKv3IBORBdtNz>jg8heJXoNugAxkYb54L`X76nL>&*nM24tSCk}$ z2uUg-r%|Yo4269!q~Kt^DT&X;~`X_fPbeqP)G`!j@z44iPmpsV7fPmKXDqHz!6%Z+h-?M^%`7(!b)(zN`lUul{~v(tj+(%#s-S+%6T^LNl6?@CG@c>Vhn(YXHP4PId7Rg#uM!_!;&Q^(#p7Of`L z${gtUE!Tk0ThgjsveS?8d0SY}l*bl1UGeIFE+>|u;(d3Vl% zSf8)zL#iGVHt)9TefpX`LV%aju5afUm+vNQ-V4@E4+_1cKi(abJn;JGQFN^_SeYN} zDZj#EB#mFar4_g535O^E|NIy`iyVC3tS<*wM=YITc;4}z{WRr~)85UV?f>8U|L^Ec z&p*KRzXDYadQvr1fex`Z-ta15)gYb?4+MTzmS}$fi_!#P4Qfo!t80UIkocXsdu{1r zE8rfv(<0<%1ZaN$u6%-fgj9KEP$6}u33z?l-JL`V1oeaV&yj!m21!&~ayKhU2t1** zTPoqnv2`tW4VrpcAKOw+e>EtQk_TS@W*#59-loe3POaz)TSmh>NOGH=w1>FwBt`!e z*9mH*;fkHrF{=WCI2gVL5l%ku;>Vp*;E0&o3n0%_(Vn^pCL z!06{ACfgdZ7f7J0?$noiLf|{4-LH^4m%sXB^Nt#5zMg%P{&;Iq@;HIhzlbbN>lH=3 z;Q2({%`MFMLu}N~-ErYPioog0@X04E_#335OV^GK_NOvD@6a+8n)2ZNtSH;+^k@CQ znu>RW^-3v}w?R$GDlFb_JU{$e1$l4Y&wPl?+won(Gd;+Af7|(erF|B_`HGnO>Z%BE z;8~-N2;_aObf!P>M-#YnV5NVUUJw{RWD;ue6r1;%4GKaAbwc0=rQPIwnY~p9uzA0V zu{z#UO@F*IDS33^^zU70dQi_oK5)fz`v?aYKJOhZ_YA{4O#pF7bKX6ZI@|@)=cM68 z)|OF*=Pe*bTOLL6;|nfa`@?$`74Lfempv%&`(feoSiBFg%vl>i-XL7&6PdS#ahS(> z$lH1(w%yKqJLporn2}r)0p9W18LfuA_b)6wGdtA;LJhC_KC=k|W1jK{Q{Q9rW){+~ z&1;0!o6>IidattFL)g4cPqvrI(Bb9;6D1Eboc=95et3CJIv;pZ&CFcFjnCWOJf_t? z*#y+cJ^JM?{0Nsf;m5)K#onO|fB!#W;4p1@C{=S)9&gE0@vfV?c?9Jx`oeT27VkNC zt>3#L?^>pE3-aFE^aXeCV#s@P;8Dwt7<1s&p8Go;PEL+$&D_$1yude zC)|gEK+w5GBC7v#drQE_Q%58lgg^+ToyLl1X&fYM-uX+*`YP|zU-kB<=EqP%Yj<-Cs`#K&h$ne#hVCFzm9vKsbv1Rb= z_ka8U^t|w=^bM~6*HYD>=jHN$U$N`{&8CV~gO+qZtrQXMR|N`m2Xt`N8%7 za*Zu7S`zJm`13t64R8nP=inl)+i?BwaJ*@u;qN98E?%!4tsVqqk8)>ZU&bC{%fH!j zMArxbc}hFm3$JcytB+)Azn|I;CBN`!)_Z+32_^Vf`&%?2K8#it~yP}x>co$IeFv97d z;c!a%f}>HptUvjN;dv8`Y0IP1;~U5C zOMezf%2d3Y?YQPp-hA%om9cp91)0hfldJcGyo~~o_cGsUzDUShFM7q3#Md@p!&l^n z-_-~psC*-&9`Y8*HGXOid51rj3%2120+q+kM427K=52V|T+Q~55U8fK8~Uz2uI-1- z+x?elhF~fE@z$s0f!DwC4fzN87V(3<-C^<_-|>0Z&1B!mEaV4cVRp02^_}et$5+6?v@Jr<2_EvLjk9M3NbIk_8jB|;`VVIBNO<%2}e$) zmRECwJrCwT$quf=UH^whq-FUjr7`^aKa`oaJRXMGrcT2Tq{F$lA{FnaQ?iaI@8uUZ zC}Q#6v|w_)7xM1y5s)J9y#cAx;S$JO@?6^^4rXicH0X>J$BhVZzU<4-uaI{};z@O$ z*(R{=t!&iD+dyz|u~@&X6*lkrVWBHa?h1h;ly;ZzAMx2}hRs`7twwmqb^7BiLdio1 zr+*T}=5hO1yx_#}LSvV4eBK88IZ1i}J4s%h6ZKE_Kf>odGbWWY@tfg!2Q8;9kARYQ zlU{lMt^e`XaCGtaum)*R)u7HM(N=N|S_yBEI`hndfK`L`2Hv{=<5r2bgud}QURZ-F zZd?!`z)$Q}z3tIq`{e+}veCJ!x|*CGetB8 z`-+{!VP_Jvkq|gcX=e~wCO;>HU4ukJ!8SJy`l~^)lsx9+^sn<|d0<8hH>mvb&hN(q z{2Fw*Wd2TXX9sYWH>fDT3V(x?(5RO;cq@bP7f9c9Y04vMSA&9T;-4XQ9To46bvBVs8eTL+uf&@QU3E?>jz+ov?X7yWXF10Dj)`CZ!!O-@(UDQ`oQASu=+_9o|TP zyc;Na;Pubo^m$H=^*lhym9*?a13qu%$j<~W8wWttM5cGy;`0vmeX{NPN&>?#kO&zK zH02TA;#(Fl;7^`Gs#Ec9k2xxW@_y6#avc`$>CGEdRzTjw@^)@M$a_8_^EL|d4o%G6 z@rvjGxcALlcQ-QveEt%wZ4G(v%v-g>nyne!PuR>NKOP7+7Z-fqM@_}$b;8onUqnRI^#+XqV! zvKe`JY|m5N86-h3Okns^FXQv3F%Ra(GrDG*63M*PsCc(6mfwT&EY@=+HK}~ zkoVZew~=JtNw(^(1CV$AlMrvUkexu0RO;ji&tGRWdoUk{ymhU=J&k2)2J4c(J?AY7 z1VN8%K=?vz-e)f*^|n|Efn$_*r5XZ8w+yj)?@2j+_qZYb@y?*+f!Dtig=eSqW%$83 z`voJ9xA@iDt5q+vkz@p}^BPB0{>I;&s41y5R~=|zc-~)%Y0JYsh4{2T@XzBdRVv=C zBuegL^FF%uc>f+c ze0uwWk_TS@TF;zwWFF!L8+h6eRD8hay*xG1ttH(EL~Jx!n3vmtU%fL{R~=G!VEnmv zIBj_dq}4C4h5r8A|EG%;{=atu4zYl$2E9&B+Cr{DXFh*%7E;_sXVls9OI#>HU#*df&hFB&_9$7g3``q&@N<@|$ z*gx@Ac~pvDgP7Y_Ie%E}0ls*yyZ-Vx{t!z@etuETP>$h;SV9kNc{FM5j_Zy5v;Nnj z;@#usEsye6Nt0s3;{D+L*8CL6dtqUPKbdz&d7)1zE*efqWP z(<8`RNI4_<5MMLMeId~B>laktz~@ao=oHu4<3QnQ?jnZ!=h4dNlU&SOB=n_p$cHX6(mXtZqD# z3pNRXa!NbWB1d6kL2TaF`;QDJD9|5o0-6U-{{p%XO%FtKgS>?cRBZnbyz9?%o$8Ip zpFvLkC~xd;E@61yFSlQ(DG!^`;j|yKDP-OosCd7ci48}24?G|-WAXl+)aFnJdEZ%b z#*PQ_u1QtUDuKLT7KA;5F zWu1CKz~;@F9Hir?E(Bgt+P%CQubSG0{q%OswXpmBa{A-VM#?;8*XDOZaVfbT|Y3Qu{$yH5#tBxVz=xt6zDHzd-7xF^}r`jVu0nIdMG|@0T43 zuTkDiC*zo~cu%Z+WBwNMj^6pak<5GCR$yKWU{4#{mKKLVz%0&J`RyJy?@j4%W%4!)0ai*oSskt6WDV@4}1K{*8zht-t@#F>rXKh_})3Eo(&7rCOmFED6Ql2{4_lt(ji56YyrSdWi&pUL@ zMw;>vYszpM{%`&N@9S=Q`CB-|ZlbC|?_+^6O~MEh5L&3g`5 zgUa9h+(?5q4#m&ks zT(CwX9Hr6tLu_%l_@3{Qmf)P*38gbC_%letTeHPll0O)}1`(QQ%Y!(}%QX7W0cl+- z-tSz`ile-vkBV|*@iq&%l_Lm;*vH?NY~zHy`?Uu0>mcs{|JbDmavi`?(KB6K@Oq1h zy@jl{kayP&{-R~`nt|R5pF;&sf#5aE+ANJ**t}1iTCFMkiwNFQ+Hp4D*v#pL&3o-- zi;1bv^v64jl7|XT{~E*%*Cs^qfLqGGUT2QYo*CDX$42(XZCZnZb$Egdfc+J&0IEVn1KJ)A+7MqZ3px`xera6*ht zUPuUBqqN(*^7Q@+cWmC?8$Ghqe$gNAFO)p+`lmV6V9WWP3v65>_L}K5KJPCzM+l>3 z4xntDy>I1KeBOk-OJ(2QCNey4!bRHh80O1d^K*LwnfFF2-n|na{w|Pa%5QRD@h&!Z z`mhP|<~!oJh70oMYm+Nk3>Qe!S{KyqL>$5C!L+H|US;)`raUs0=8eDq z=l(x!D&B8;t?r@KdwpdDg2g*spU=Yq^6nnv&L;DAW?uf<1@c}Vk#zmcE=Ry`X`MY@ z5CIUs6F<*G-aiE9K0gy^1_9m$laZS6?kxlBOx|>C-f1tVOrI}+cW+VJiDZ`C&DO)_ zZGUamyfK9S*8fSAJn;G#FT#IwPct`2mX8xnzJ$;Fu9e8j*pF5qQ%rpGw8kS`-h|>b zjm~t&znqBhiN-t%m;&d+$6NpH|D&rwI{p(5v4&JNXyBx`3R;7T)%1y2HR#sD!r?%; z{!e!9t7nHbC|m2ry*N07tnCOM>gU}Fy5|Y{Jc3v3Snd!gQ-C$-nnqV-_55bAWS97N zLzh61u(E9QSQ&N=dhQeZl-N!L$&_|q-gakij>E1&`66mx&(_f25Zg@2BM+y41AVp6 z*pqnRH(E8{>u<-eL6Y0U43&;qkSx08tG))&@Q6L9)C~jABk7Ix!UcPhXjmW-rn-4z zA2B{}X4>+Q6ibNfNemz_ko2i|e>SPUgz{b+C?tTzyP*E1&lSj9?}z^>GVi8#8?6M$ z+be89Fg0x_AUZ`QXF%R^PJ}CKA@7$h-z7XDZ<2kPSAcjBP$^hz(dvuMdp?jX&iG6O z>Xde}$lQSi!`Qqxev%QWXr@2j^C)>}8f&8G_3s2cR@U7?koRcT5^Xied%EgczA5A# zTEx7U9lpJla{Y#Rk|FlwCc>R+y z%uV7F#6eL(K3dw-eNT7VHvUC$S?5E;l#~U zyg$^;zDIe#Yz^ea;$0N*V0$m*tvknbl+2s|^!m0W$os?3tlt~9I)J^}u}^IwZ+~S; zj`ff?;q-WuAmn}MT}R($kwCD$f3!{PUtUgJxF_qj=`a!OptO7Zvbgo65jO7~wcB`9 zU(z3MaY`N*IQ_e)n6@#_pBs=0{oB-!;PbxhBc0=6Y)eX$)Yqw~qG9em9BbL!=EV4W zZ+$f8@qXt^mH*cNj4?>VA=ZSd28}e2&Y(3YC?`@Bs|Jl}M>x;jDA8v3iOFY$H7HLp2Y>(eb2f|*5LC#o0^gKrp%2bJMma<yKkB1Ska>GM%Pz`-ytONr7`mRY2dkSu zY&s9WAT``4b4C{O_IUKz&<66hwRw3-AUhBcHwTld2e5f>zP;IT!!sh7M`^dpd*EY7 z6*lj(gY3UO%IS|cn#Wa~{@qW$qkXoW7hIW9+;M&bKJUIgUCVsk_K*w;cXVuR#(%t( zp&gq1LZXS`d53D!mWNQ<%*$i5e~z~pQSlxe>FY#!S19BOWAXO5#(8H8BL=EyD7O6bAHZl-28;&keevZw1 z|2zrjq9!6}rL}xIQ@HdLfbk8UQV={x%b4BEpdj-qvKa!HQ}%S35zz6B;PwSJZ}P^Esw8V9+khLKUlrDQ1Sk9Rk#x6Exc}@ z5Ek#rGq2V;L*AVptPbS8wwbIFmvH^h|AVQCJojFg>!AM= zuK#Z|?6?(@83;{1w|nl(vhFowDIg% z7mcpUI%5UYTJx^{7R7%-T7XYypVjR?hJOZG-LsLVJSL7tGQE%cbH$E174M0SkE>DM z{>sdYuz2_Ls3%>3yf+5?N{g6Y`#C zyw=}!K{I$;u+!A}7<|O;{dxN9eQe&MN3}2URT6;-rQN}@`U|QgY~C-Yt5}mW>5sP< zC66|o{<)_e%vvYG16rGkWxa>+d5a2mH2TF@0om@v!^>*%7f6J3u5|_FgAC7`u!*)j ze(t#xzZzc953Bb!D&FHliBTx;4&x^auy_wS78u`#yyb711(12`zDeHN2YKhls#l%b zZV#3pjasz8J_3Z@PP-xqXONHN9{CQ5HG|SG5^oLm1cGzXp7}~e*u3w{%UGmU5kUr} zo!H?>sgEVtytf{RM($+MA8#~|Ejaya2zz!nFNzmL`)z;jIE~M{LGiS=)F~a3h;&r+ zsRaDnTLhSuHZH#4#PBo7MfVhG%H!S%m!zJkKh@ieiuboZuU#l_9iLO;SiBF7y&q_S zyoD$4ye0E)Ww}+<0C{J)?|UqzXAd6n{&>F2IRc!U7!wkQybS~*&pAQfY2F(KW~>6i zb3L)Ri~q7YA<{Sv0!I1pT$WwM%z1JZ}O*TOJ(ZGMT~f`xCHw zn^N%}y}s)2>n&0z_laTgPBsq<>xaCRT*UOrdv9uOp_>aK@2-7APM1~ff&S3?2|lj~ zu=(_s11ll#$3A|~_2J{KW5gl<@x6f{TF^)(?_bW|de_GtwrU`PC`!ATa+{;i3$b~B zIr!IMebXF)Oq4m5SVCDU8WMmWpZa19n>xK)YYo7~>cPwfKZW*WZ z+9m@)!dT)l!4=pu$gX*2Vq40HAdb>*9LL6n ze0hL#-I+#*v-mT}vkM>mOxD^>Qb>=Vj<2TS43brDAp45D3}1snEosXmbgPHqCyPJl z|E;Ka|J<*59_4N3y<#aA@7MQ*HpxKVM~ANcCi6}LR<4K%hj5xqGr2oA<9}8w6%<5P<@vU6iKlgGVjcyaRT~ zhCNB6Ki+5_hjIGHJG)$SYZ@=ue#E=7sRW<*53d!~-UhZLrW;-x9WLNM-rBh=Aoavj z62l*mUPxmeh+w}Q-)51%1##UPQybolhvsc~16LvbJ&98=2d`Gn1T+3&%7 zPAx<*KxxM>k-Ta68#eC*#j~HL=x_$PoRUX0PX7!O#JiY^dBEX>V13`~_`Hkd54Z(y zv?l5C@y})~#y|fbI=mw`U+pQw^LD2(kM`lmrl#zF&j0VA;yu-(JBjiR5sa6_;_YK| z%*+<@7VdiSn#}vC#!mN-khh<_yMNMZdl0A}qWKi^)^pd19EQAIgX3D|Aa8lE&K+{| z0)c(Pw!ByqY~K5`QkTS)5`hh+onbqVYC$|U@AJNUwr@(Lzv}Hx$>R)8|8!roo9cz$A$EAf5Nt8Zv3aW zgzDv{Q+h6pzc~>_TOLgXquY4k^{W59|4$DKe4IYO8RX9YsX^9EhtB-@#16Rz{k*NR z0;>is$?uuSs3_5XV!k7NZtk0Q{;!;26*$ChDj1z^%eDc7ud|M221S5Fm7;f_!y1&4 z**5SRE|B6BW=}j+4gm8Ox$(+b?ZK=mLwdo5esM$~L}}N5we8)jCD=o3uk-zc);;uB zgT7Mo=)vh<-7(!uJ>CfxWTPA+MCMU@p-RmjRge}Gvg{uZ|u=EZ`XuNj^NQl zu6Id~A#Ve27RTR^x54?%&Q_3jH2h%NteY+1)@ckF*b@O%lDkzqAn!BxMe{E}-tsSc zPwZY02vla{c=SxM7f3SCg%3+-5rHzL9qB;y<}10_ytR(M_pI=vKi+5_>u~y)J0()H z-j)YUOHPCd9>eF|8Ef*)*U62<_u+PTPAUxtq*LWToFdsX{sM`{JRHhD?3P~^Mdocw z#rqd&!AG=uJ2eF^$Kri&*9XStcbBdyoD(-eN<=dp0g-Kg#=&*VbiNyr{~nKre|sXr1CH)bWL^A!;H|{#670)? zU%l&Hm7`*IGyd0GI5cR><9uzq(Zuop*8hJer}X>-9AcgRrv_Og_V54R|G!sZkpfl? z3j3}|kcKsAsR7T)SvbV5w*AF3Q>?6QawN1nyUYscs0UP7-h&6ElbPHrU=6a`KJQ-a z;%2Z#cRIbfDgflY)GrKg$6g@C9WMB&25ZnoN;|XDU03V>Po*F_b(i zaQc@#`F$5jkOvHY_kVw!h(E+S228L2e8!37#Ug(*;L9W21(M$zxAlYlHVnT&de=!? z9?DCUUEMDHS^w{*;?2J5MhrT{mhpUAjm7&L(~(u{A#aVvIx}S6@?X_u*x?X6J*#s0 zgtRsIaazXIzbpbQK5ton5Ar^hcX$~|q8acNyt`9a7ytz4a`ku~VDo;X$x(s81JeAI zc7s=3LR-UJG5;Ci19tAiDfGwtH6@Q0oc>L&K9egD$OBBe(jvD?;PX~j_o%)BdDjp( z$P^!^;do2(dYMa7%VzcUEsooi9D3XAviHN`8<$-Fyi zcKw39v*q935{A4#E&Z@%xY!yDl#8rAmlXkiI^R0n0(n0?q2~1#&L9^(JX*I@I}nV% zX&buZj6H+gv2wCk{0R{ZQ`$+@KI3ohz~)^dHQLFWOMkpAD0vj&^zZIe+?gf4++aUH z@$d!>eBNBLgpXUboJj7G?dtud^_c(L|D8A}UT?PK`@s0TSJ9ToCEYl;+wk+MaB|{E z#hax}-vQ+yo z_qz}Bekxll-2wOi1AQO83f>k7s=Z`Ry+4f2J9u-l!ok->P)TW*FzTS!`7gJ(K0TgZ z+IOA)cn4APXu#>;k7ADpw{3X=XRfs6fB`;l(&9wR#7Q@j!}8Zc6P@_HjlQnr5w;mu z|I3|0fAAfoEsp{IsJ$TQ&-&kiiZ^rVqyozOo2}JKEZ&FYN>#%k?=UX8RpiYHl(%Qz z@Y`w=8z3DZ67m`HKDIRM7I|}`XW*4^6|COzLXYw-cLji$yQDmxDD24zd%NShiAZ?< zpVChBlih|YP3-DzwRrbsq7(h`W~1a`fzv-}C9M!HEpDK|a=3HQ44-%HxlPV`-`q%D zU6Tt1kKwQXL)GuJZvV{A@YOq1jkY|RgujlJ=Ki<-XNW2WhuA$-HHg=|W-nTUZg#M# zV$~o;V&P2L^%8CWda3N6um-U&F%douhuB=LQQ|UBOVFPiYSTCs0hn{Q>V1MW=#IL^ zauYbjCae)z`O`2Eoc1V*7x2LzVhx|(ChGVS!AVNH*41xqTmR+#|EVEe2Z9m()gXOJ z9(euR@MK--;*~r=Q8TjnO&zN?o}KGm5jmro;iL!IYX=879^=m-p9DA?9@@+BHHdJZ zwmjY}yQc08Z!m+r-Kco;@W#ADdFLs$s$lV!-+uYaW61l^jW(tk$lE_T+h`x;y}ZeP z?Sf=W@F20?ef4MrNS%uueh7K*y3E7A2d@9C3g0N{tOx``Cw;>jwqo-Z$osg{H<$?ozeTTexlPw#_yg7TdwFcqlMA;R)h4ZH@L8@h*saH<~P*m+d zSpa!w`F-D|FWC%g&h*?-`xppVa=*H<^NF=K$5#HWPTzoOT_7^^H`D*r*Dark$B4$!R9TN=)q;t&Uwfa6W z{Q948mbN@5UsqP;U;Z;Wai-$Uk;?h^?XB*ab&6QLeUqbVc;NcK-aTS9d2?b_b)m@^ zU;!|4RsMd7OC0KH(Oe{@?k3yhR*6{5>3Ey{KxC&_;_})uF|a@I%5eI5}AT8s73-VY)bsw?rMmQ!mSwW8gxlxk;Fk+`Ws@U zD0vj%^iTBLhFP1nLO^Hk_PL`W_(QCBI#_vhTLNjTitmd@T1~h!NQZX+m@Bio41dH< zyn(hnE~^V(5Y|6WoAZu+NYGCo+csHnY2jo4Sl_>NB z^1kUWCol+ke>qcKtrTPlDqH!4BV{8&=B*aUA*=w^<-gVAT z)?x8JIl__a33XL&?Jj zr+?Y+j}JT~@&LZ>8!MgT@vFD|X2Ywt#tEcfuc{wNDc9rjCYW(&tomTU@VrCk(Uyme zgKBAjXB@eDdr~84JW5;Q_%fH9ewp@p*gv7U*=_6-{b-H@q`t z|07)98Le`8=T|*v`1Swi4%+faTy^yRs*FGDe|IY0d`F!%QQk$&Dr#7~3umiz&p_Ua z=KI!@_uiiS`%m41yffrF3{qR^hWyQZAHl=8>fF~`{ZuCeZd2I z&ii{=l;HE0Oq*TfwlkXKY`AznYcmZmC%XIBlz6^oc-{mb8uM5eGe*ANf(y>h-m=^! z@Q?9-;P2qC=da=~=FjF&<`3sT#P7y$&A)|z1OIA%Nq!8j;76S)>PIA)+4O$thTJitXixJ ztWvDPtn4h)EMHi9SejVw@`UpE^0@F=@)+=F@W}H>@CfiQb5C%8;(p29$X&x-%ALcV z${oRdgxj6lmfM(Hi(7$Pid&eQookxw3s(+WnpI~FPft{oQ@++XcYA_y%KqbMv*0(iO5qliU_-W7Xje<`+V?iFFQIOoB7~~-u1q^8TBM;EX zzij;nKyILs z2d7E`Qh`Q$UeCrN*U`xBii;{zjz+E_X$0gN8oB80K82K_ku%SSa^xx+?d~csK}ykR z*H`Vl;9v80|!^pwZ5yEapfN8rgkK6h#Wr$hLM*4RRTcY;rU?kODNa z-fkU$0eo6h-9FV-eKJX$Z0g%yk(;qate($iI#3cPNI>{`$Tsn9gQ~DX&pn-&`A5pM{y(- zjeyA|c_ammv{p>6LXy#F!>3ELND>;YuiGt+B%+ZC(sAND5{*X6EZWj`QMl#VOB1kYA zE#DoMhXkR~GGUo*NFW+59lOeb1fY>rm7g`@k48(5Cu~Lh&`8qKFbp}0MvLv{F(F6L zXwjt2TjcQHDE{zQ6yNn|e?k)P%uo@hi~{30G`L|!W(?r20lwTJ9M zBl009#0`zeXF?EHG$L=IBQ9t}-f={n(TM!+AL4{Y{-Vva`SZ)G6c(1`qL0mKZA$TzVgrj*F~ zstw0hWCV>$56t{RhS8{aW@H)}LZd4KJORj8G%6}Sl!FYSQK2{2O5_U~T?Vh~kO4F* z5Zow)^rKPUD|t2KGa6mGVqSrKLZgfR;(W+QG|JT=u0=ke(S?<=_mTH#bpG{}5b_R< zvah__i}azDk0ry zbSf<8HPVGfC)X}Nio8OjwAl=Kz94OA zlt{=eMqZ#%{No67q!o?gN?G%f=V%nWue=LsL8F-UK5a-dC9)!a;TkbPBk~7PI{{#hG^7p;C&4-K%>tl)t3-`H2TCPT#x9X(TAGZ z_sC{6dLR2M1=)l~?_AG{Bf4nR=X_2P(Ltl$i4U)ljcD|y*XkakjYhANleQoLje6X? zaO1{fM}x8tC`qvWCI$#>_~WxtVg5HCecprrfwcV+Mt8?q+7KBuB0Uu4LYAXZ?fG0MWEmRWnO)z3NTX4W zreYhi6pgB;3%4UuXmtDOuV2U#G^#B4Jr9xm8#!8zA&b%Irt$e{L;{U&i2B4Li_qwL zduI!>5RJ;~e`z2K{zi(=oe^;~Dq9z}9T7vLtL~{$h$tGBeC3};=A%(@Z<015f<{*& zM{gkW(5T2^{Xs++jS6L^N)RD5Di}*Sju6o(zcTt5BKY6^fAqh`Bfv-O2dJJwl4mvK zXOQIm|GWZIcC2TRCu)8Uw3fp!NSPS+Ou}c7Ix~D4Z{RaX>FDw-X=f`C8fC5Ytt=7@ z?~{D+67K&m4kCTXn{5Ja9rw&$?+yeJ_M!@BGO!=9SEm>7B7K4&iqfubBCG3uJN7e3 z3E_gA$-9yydi#yvrsN@w)4%h|&7z~C0^r;&X1@=b_|G6Oudz6LK0_PHPOc30_H zKLvSLM-JP)hrIRty^2q4vI4)>ozK30E)tx4GhR>udGDIb@|c`!0?UW2CPt+KfsVw} zPwOnPc|Thcmni~yZ=$qw*x)d)tsI;8Pi<{hdgT3tlE-hH{_RP97f^ME59ATs8x3^u zd3TJ>q%HXpK|1VHqG+o@!|N?Z>HKfaGgSm z!|7jXTssfXPd<>~^DSt=0H6293}utD!V{$4us+!g5q#bfKJ1~<6IU3XckUtD@_0Qn zlHJJp=l;L_RJ_R#Qc&Kk?e)x9yo+!41`ELr((Mu^-^sj%1fP174=1{e@2z*7wgd}o zxzYx`B7sh%$u4)u`;GoQrCt{Jd5fd=tIAme!LMyc+5J_qdF!v7|7%;nAoxvbSDDi5 zEPDyNddIa-4?TKJf4nzS@<_tzpSM)S`XX0;P!;{umw7urZ}-*A1$kFakV1GkrM>Pw z!rlKTV_qFx@PI}`#O;zH`}I98}hb4eADePdozewu6wxrToCB`Rd~I= z3;XPC?#lZ=uNx9UH>I7=yw$lam$1*?D*6d?8ZBKycXRI?N*-%*`uAR6CiS#5Ke&HZ z(E<7!Vx=j0T*c|%_X`2{TKV~a%J1OC^Oob+pd&YO#}?#G8ytFMi5-0w0q@arSf$XHg9msWAj~a`s2+-$wLpPe?O%wmXbX9 zz+>BOE8i`}=dDwS{5*RxoMdCDv4T?tpEqHbTE^zkYKG@ch@vfzO1~`@tRHrhA8#F^ z<_&kRQQny+Pjg}M&dPayIu`Oa+_mijnRmcDWuJBM4N|V~0$EW9E6~y>^6qtCB+xyd z7;XxAo2E=o5x+Nq+#!#Y#L56LofVvTasaz}bCxb!SbISb{G_y#UKbjv?TXFYRNQM1 z5=DQ!xhZ+su!43zij(n=02-W%V%9WQ{qcT0*$k~b%w^2xr- zhP+2v65t0{tN_Q#c%G4$ksx-e)=CKSUfAP!0RNA@e@6`OWZBxc>h%=alEX&kA%*^PJw<6bVvtyPpif^*_7ggO6aQ30#bl zl2}p}08;O;J#_ej%{$jE^^QZhAUH{BXL?a7livordUq@f*{keMf4p-jd359SPkcsW z&^VY6Y`wHC-d+`-ce6S zMroIH;Ly(73fRveFWo%e=RHAxHAs+>M=?(SHgQ$_uDZh$cBkaA8mE6MiE(nR ziu|Bjzaj(|E9VALS#n{E6YDw6MMulr(7g zDEmhTK5xC5p&sJbj||WI-r5nG^6(MfXnQK^&+RQosd$s$QbKuuP(Q+p#XB

I!4X zyTWKJotigae{yKLg%!9xHkG6Sd7pDLS#$;Ro_d+$xMidXd`zm@TJx#O*<*TcRV$~p-cBX`2xc(nKXTI>+mDWVM~fTi*{?PP1rI_V!0Tsa5zx zEMaQ9*sVvdxBpiIjPxJ-Y0Ja5CY8`h`ZI$(M#Y=_;xWqmLfkJAEZz>kR>Y=5-c|L@ z$H=^WZ|sVB0D0H4SF^fX?Et$e+BoMatmrtD*QeNLR8=whMc9GCc2PBj0JtV=jl~$!yr48Dt0*Z}OY; zC~q@~)_GXGYZ8yFyaIU-5PJH^yvM&Ri+c}wPnTCH{dl|ss5zT`JI53SS|%446hPif zj|rZ2>umzM>m7{-PX+>{lkX(+hx-j55{wLa z_P4V{0S@+?T``b%#QQWh-M%I;UYS{ER}lzgr*7TO{Fe*T{SJlrzF{T;8A>~ipP^X? zxv;Buzr*?nnGf{GJCKscC{F*FHz$mp>f-|w3W|jrtnsV&`n=rf&#-#?xIWvcf1id6 z(nb${(p#m%_!p#E_|ulh;w974|2(}7qT)@y>jdQ;NC*|e;@vvAXu&JUd%^P01!UeV z>gN|MfxKsZm}?dvg1l|m<=A2MCOU_>IYHie65otT@0&p9NfY;j^MXKo^yH=K4cL>D zSYDTJR@`v!jneMH%NJko>0t9d6S?AW?jZf~PN3wGi_^cCpJoJ~>+yj@?e;_kBYfVU z7Ii;d;t)ZS;Rwwv`cj8my$Mrg4$HKkGCuFKH)+aa^DmC}pi}>?{~2Og1=s& zRt@AEA^DVgkF98J0zx6r6EYtJ0M_jz>-%0|pFtX3n(uzuRuC{#+8G<2;Gg)HGe~{JC$k80QRq$ocO+*5pue)S+L*BBJ!uOuOXaYN8LeCkN2Y~H0v$5|U zWAi@!l3O>_Nf2zKwCg^~ndr0~dx69xPqf!Gr$63jDS2?=^lwG@Gu@&Oyr8%2(Fy5u z_`Dl0cs}-kyeBL7s+33J^Cpa{sJS+8V|d<#lQiaWG~m-AH}VJ4l31vClkek0d9Nu~ zSct`Y%AZ4dE#$p*q3b&`Z!aI|jvC0DPbBbQ%CI?Tk+J7_IT;B8l7DSAhPX8o+zwXH zx5(p!r?<}eZi<$Ly!Q@jSX*^AffW)fQr`#!f=c)3Y+nUz-rN^kqRZU{K?SAVE$J$g zl2~lsp=H@x8J6_No1c=+Bql1}#jtqmD@L4fgS=00)>o2w zpY&hBngMycI8~q2F0=q&v`S|m%|?QxB;&k=koOCwrw)QIn}Fnv(MhgXf#7Rz#`ZUp z*t`>;*19^p5Cj91cHK@qF0%8m*Z(q2pS4DA(;x3tN*-%)`e(qDQralS56TzkJzf`x z&pV!NZI)a`C~4)l%#*f*5AoOkYkzU5#J;NhmuW3y{ME-<+VVJeqIxBKy!GGxe+=-? z3Wr!Osv1PTGa9WyOkv{EST*SOd*pR`S&6p!>QhQXum-8!NVk%OGsvg=7j4~r$pnlE zU*3tp7o>C6@7XEA55NECVRB{UaT8F{c;LD!I2i1&efpW}k|*Z>JC@$}f^MA^{M&9* zpzCkqFm??(@oV(-@p$^HLAI1Ul5zT{Bm8MweWDQ9ts`aI-hy9)9x@#`*mE?D)c0}O z@}`0o%-?qM->aKw1a< zi9x`$;d*f3a_mR!x&xf53o`|Q38kItaLTCXGHl)l4C{-Q#n2yb14Jz)-%g1mz&T>=d9%m87&&cK1;NN{vviSGcMK@OPL zD1awT;H6L2gK_B~kl5B6Dyfdmd&{A((H*x0K?0@SZ|^PKI;z;b348@CUU~G#+l-P2 zCrRlQ9Wv-!IrZ?(wPyM`g}c>?KQ7eU@CXKboeL$?9t zmKK(YZ;@cKa>0d%khe>3PyniNShB%iCf+|WoR?YN0 z(fQcCV-}wo*?6A*coP!;$s-k~e}{+%Q{(_YC_c2(sP{HL?_{6*rF;CtNLTj`s87z; z<5us)?NJWHp(KVs-ZEAiNmCv<>pERSPLNM;C9zZSCVzJY<$d|xuEkiq`$KmZjX~ad z?`9rQ^M0E;vTb+JHlW@ktVtM)1QIvCr)EOlhLz){x-Ct>?6(!MZ8`wNp1-x-O#plS z?;cvbeyg=0h^DmjELa+oa0L7D78jdZ7_x=_c<-a+A%xSv1HtF5BNIZ*WlK0(R| zjk`7>B>U(B_7WR)I;yny81wNiLhCq(lV6rWd-lj3A^?xUtWsrs-W!U3G`?9yLbl|T z{G66+#9d;OgeT`v+PPSMK+;(DouN7=i*$}f$ItNQrQ=O~Hz197%=;=?EZ#S(2S1uX z-WINPzo@+D&b3XBguJzd`m35_w}LaL)0zvrNZ{Lsv4X>p_jSn|k@odu;JHMqa^*%p z&~762)5Hjyx9+%DsxCYr?L^}u!Toz@W3YLL*a=M^wPQZs`e+?zaPs?U5?om_Mg(=9 z+>M^g@Od8=pIq0sl7#HG`s9)9&cF@QcOF08JjBQHya@^IjMY&z@5=I-8>C}-=y+3K zc1h!1mm9tui?=d&`P4zk`&;h*L&K1_IOik3eUSH^NB8+11dIU%Su*?jOA;6!)KWBs zynCLBKlt822GPFTiU<4sfu`h>#?E=zhZFIi9@{AH5&+t0oX3mFdpG^D=YP-IssuAr z=Hs1&*5QkjpB5$1{7L~4{OTh--17&2K$=$QthlQYifr!QtVI%L;P#eQ)z6w4NvzMC zM}?s}cB{vyKD#l~z30*KroO$E#+$&meHj*S-KCRv0wC}8r90cHy!&{sSgwM+8xrPu zIbJXU?*_R{``?j3#(44^O~|{g#zKgri40l-&CU)b1%b`>f67IkxnM4;V`Ig4I35cC zeKgK_tJ%pE5$tYn&|5gw$%OCT`i|DI9Vb6kTc5Esk_6E85P4YeKb*bUx_bY7uKEP? zbENIz+sKvV1J=GQ&)eZUV|8RayBx2|pYz}OKMepg|AYgQ5M2+VzQ3B*gDRbQm9Tn{ z+M=Ik+1HD-OMgYne1tvdSpeD0Jb$gWl4><&?lwbkJw2c~x{n05I9i&T@lz1tyGvi@ zmyv-`;D?xk8@}LO#ojq0W!N`JE4^9!nYU2@P|&!7ZZ{n*P-!Q(_weRK$oqWB@@Oh==i>X8fsl9W7-_xlaYMjm zJu9;w?jTdUii}o4-lO?Xa*4OdKt8elOtP{c==WL`a2#MSnK>%9XX>*Bz$Y~BYo*cL zT^`uH<&#|oe3v zEn%YP8FrfGmsmoKF++6>xYxUf|J^|n>3C}&9~7nW-l~0B0gHFgGUJ>s$or=Ci*YLN zv988PWsrB@_CzVoTtjfOb8GSe>I2g2P5S0R-UDD~8CxY8T%%OmpJVp}?2|6T0{?P? zt|6Xfm2BRBm6@-`0fk4SuJ2o$&F-!^+f0_zNYFTH^S z($w$WXG^NdKo&{kI<(3cm~w@MO)6q{2D&ZSl(v zF&}Ruw2n%g{Dz(ghxB?8LC$D$*{}bBcWKR&S;^}gF+Ud?neQ)4*eE}~v3&P_=Eztb zZ#ob8QsQRje||dNTC2V*(0F_Gn#f`CR*+t^a5kL(DO{xuRNkk_wWT|#m$%%niT{=` z0^}p}3wN}U0Oxk%i(8QQA+_?+T{UE2D-n0aTFw_JW<$f|9jYjwsFW^_J>QX$NWtW`I%e5?JsN6w!9{R9?R0Jiv=ji(oy1gS{@nP zn=4qqvEL5_T-W?~vKf0o8v0oz-c(8iVQAd3b}sKLf3SCuJ>v!Xb90s;%=TfAqIC@7 zCd&{-ehO{Nt;qDU^EZ&?AVj`O$?-L)3{i(b?^TKu>g}ggs#Vgn(3;;RI zPCFg)?p?oX^Dj6cSuA@}b^9tANIX8|lN9U^4hC=B$bA(14pO1P7$8Edh4H)}i0*#mh$v|jgt z%6sFN@y7=s@2KxuUGgOcpxk^-9vi%RYm;{G`*X-U$LOcVw`*jOxLEbfO@Dt78=**i z?}5#Gm!fBC0py*G##y8)czn0S=6z{4kE1FR^4^2iQGk=5PLKKp?Lt8y)|U<5+{5S1 z!>;$o;x-AHWhU0VX)XTct#__^-^2K%siA5h-)=|Mj8b?=909qu^! zxdm)~$2CO+Z7XFDncl|dEple%^|D(egGh4jzVm%t~b@SBMVDWZY(U^1=^5$)KtfuGff6#6H*4>7{a9%wz6!IQT zy0|e6@>V{(aE1L1GI;q-+3HrB9}r);DDq1R_TKx?wy>|e01+%h@4XF4 zn{qa+Wj@~QW`FD0fs^0%TD?_blSJ@S+bA_NAD{P!)U@`si%H0zKfLTAvQ4M4y>_Lm^dXVW0<1lIuQXrBJa(%TYVD+GY zr8Wx+is3cLg)7Gf;1X-S)Jrx6?jRSc?Oo2{qX!nJ|1NvgN&?cwEuag||C{t~>|c11 z49HtNAG(M80U7^GBW;JVdr-jC^Vp+XiC`rfw@uGRyYmKi4>IA^KfBwA`Faout-}l_ zzq=-_3R`%Ipk2(Q@`mAT?f>)t72O}U2p;VjdwLo%3Dod^Zj9f9R-JQ+KBFPS@;gX^ z8)J2Fwcffonm#iiNzm~&$#|1aTVhL-n>S$b=GI*nQxADxNs+P}guIm=YcDttdFN{> zI)r@E0|fuM-*$G8K+@AEw{sxx<6^<)i!PDj(wZg8YwHKDO6ad^(8lIHT4q@MPL~LZ z(YVV}#=C9Ouz7Puh^G#1Vm{tK(K>i=^1BkTO=Hn+A_y%nOB36G&)el$cFOhc(@4m~ z{>q078*!Idg8ufD_1r3~&s&ATI#LZqE&g8K5~t&Be17deueZp2iKt`ozLdI4?Iq;R zY1qM8R=MIe##a z7r&u@5%z#Y8T+8J)rbf_p>cL8ceZxV#~zTrmURz5&}Tm06KEZiIQgZ9PUrpDKm?lM za$C6t@p)@@?`Y&b6oIT=>Ud!PIR5!R;bO`Ksqz-q=bgk@9nF8SA5)n z`FOLb{;fj+CqDz9wUOo`g5b-}HDPCd;}1y5CpYB}<%S{ZJ4qIA7H*z>vSs^;a(mgzl_33?OficFX^C4jFiVdAaTjyFaMg#r`$_J@)2gi~B-r zgWE*VjK&oyg;b^rV0Ui`jnU57Ys|;n6s==9PJX5r4IKH4h+y|_m)NlXh4*uj^RnL> zaW^Libe{>9OqjF${C`n_u{xH7~yK-ezN4BG`h)71_ss=S#$1VnY@!yjkzSd_Bk=ts@L4 zzkT^z8V0ijz}47|^&9i>caTQ&7TS2Jl8~G8qNh8?@q3VO^2Y9M2kKeA2aTO)td4!f z1NTNEX6AosI^Gs3g2go6;p{7BVe#f{ZkW)8ygh#J*L(|kS5=)}?f`k~83-14h;0I= zyB&D$QAl99wN~{O$XiqLs-L+?eAi}=-XNna-*34r9uV+ zx3~04rr%jYW_jKOM(fDG=ce>`{$E1J+kD^V-!$Im$-^92yx%xyB-udT$dSGRDsRoh z?{Bz6-ux9$NngHf0*Sx2v?~pgz_G}ccUD2(+GXiYY3Ip+f5OxI>O4QdckK`N@Jnpo z1B2h=vdoD<2#sqHmI!fh#peCF;9TG0oy^DkGg`+8PJZc~D<$q1!W+Wl?dh5BEk(zB`!-Qo8gKrE zt?XF5xpL!XpMbm-hpR-WhZA>sHBN>=-VMhN>NS7V0fI;R$M3+ew>TQE$Pj|Oe|PDG z&PySK0>%2RyXO0WHMRR5&v}c@dt;kSO1T*ksG@Nq`Ko=J+_8BN$CmMY+s=HvbLj30KwK_`I#t=1z)AlaK`Vn0`I}`?%dZ zcuLFevq35AZ%!UCR!8V7^~d{D|C|4rcj%|f49@>6=z7qen!|T!J&4`bmd(hABlj&!?n6C$ILF>TFueggn z=Gb01|9`yySnwTw4|<{|cCV-96mo7?*sCEA{5wbqjytklj=y649%RZ`9nX*)8TO|$ z@Bfpf<876x$wlKmM@@bn7H^WVaNRw~d-ZZ*;Wv=C*^aemlpybgg3}L1x334fEuwRN zE(iw)UzYMULf&%}e@GTZ!55^FIyni|@D{t(yuxmQ*h{SE#N}z1!$cr~#@VOIe5h&1 z=I!w0M{vCd^YQjY>o|aupL~d9dWa$s+zB^_#?LEgT|SRK|$s)0^~^V9><<#fDvTkQ6w@jfxw&yB@f@BI+}E6BTe@HC0a z`@KW=@OsEQ@@Dz1eHrTTd;ifp8~MY5V6>M{5#;@8;_ReS3>io->$nz1@&jGXX3OQa zV)M4&)ZXf0PXy1wKHiRK9X2@msmQJ757id{JA|t>?zZCd zwza=qwi@yt4HjKRdDe`(gCrcvx~Y-8o8@^E4l`DVStH?-@P(QAe;FO`U9#)#XuN|j zmvLe7?r05r{vGnZE!O#!%6p4g!o^LH_esNtOVV~~03&}>yW`y9;G3?>uVl!(X3?&- ziLqob+$8@=E7%WQ$hZ|bWq{55r_MP?WFHY+MB~_x?D?cujLlmtL9X)}6Y}QJ{aeRk zoc!XghmYur62ZXSo}gv5_`Dq=+us|+1tWSts@*Ry#^0Q*)+JoKv8;*ZdE4tTR!5%m z$rFR8XU_kZ((&H;^GYj?_rcDHIas_!Y93tVhx5NTLCk@A_GZv~=Cvv0Z5Ew69ef^u z?v0eZDgxY`oB-RyAa66@lb|o{qO&NXE?LEvR2_*_%Zaz~Ze`a8q6z^4@5xJwW9x6KntB6s9c1&k0BlRtOD89>-1= z8Qfvu1gXI_Dme822j~CI4Ay}-u}l9wL6W26ZEG;{l-9ksh`!*%;;oEy6zqY#FWXpK zzJ|QP=9^1zK;9)|1};^n6~Hr~=GLhm4!V6EwuwRB!v%-`EQ}z7 zMDcm=ndDR44zG+8cq~p2y}|F^1aJAD1}(c-zIzi+Fj&X(uB^M4s#ms z(IX}Ev3L`@gDKvS_g9UK`&8b_ws&2QL*DjrRUOXLN}xsYkW-*yICwjFos$dl7Th8! zWgSTdg$u$THfq7kTVWOBePh_XFaKG*eG}yU6pecxZeike7Q1^Rze;nb{g{vURkRMg z{Jy80Z5Q1v01B)6eZqL~d3PiS78v9OBa@qZM^>=o^Io&mqP$AJoaK2pE@P~Y%(olv z9gUjdy^@Z%^>EBW8t;SFe!N(`t#d6G#6sTpmiVbr&))WxR?J!sdGlAlzg(QV7OeLT za2t~f2P>9%uAQbHPAroDx%4y{BIZ7}x(MXT$y#O7ho|1EZ2>Ea&n%ZX^*fc3M% zrt{dmM>(RBJeZL8W3&#u{EqF^r}!oafc@1b+V9!$c^{VLAMwo(Mjkqax9eYL;O4}p zDh2ml#wp_RE9Z;q9AkW8Y3$c1o+wmBy z%)%n=-;=vHyo5bS#G_%h5}f}DoR;4rwIsmlxgp(Q$>E^bkt2d2L_vbwzrWphk_>!( zU*C4x>j$iZG@NFQV=u95tX6oPj3k0xXxyrorMjJ&*gZ({S>&BX8O*oDu1D)wf|H*b z?+VBB!TdlxMRZao48I4(Y<=*3`eZob7JWyt_BZ|#OYqdb8tc@}@;xZno3T3L-wV4M zkY<+HHFUfW1|||{yhn|=MX-2(+y82LHRP>QAy!D`T^*@URDitg_01#|)=Glsy5a8H zXTm{g|Cfi);SN&a*4OO2zGUEFFuJaGjURXg)^zB$V)H)Q>SoviFK<0Z<36;qIl4q* z^S-GSveGk|`FNi|>nO*`Pv-O-6LK9th#89ioalqkn}fqi>wFpssZzTzo}rGqQEWd+fb78EGCzfm1i(Q%FtwhKBfd0PoG~V;Fo(N;{&Ydh2?1sEAPaa?V3i1wI zk+6LwmG_rf{c-hDpq3(?`^YyO>^^+2svPoWcMvfZ4j_a58X0S*Mf|{re4gC-<=DLW zz1nBr3Lt_(G;VF{@9F>_Y~IDE+*@|UGaqkZw2l&-{5Fb71ai$509IFAo+-NG^Y)Bi zSC$HS*Ra3Y+5dxq9c07Tnz&khmgh})$Y32)(Fc_OUfxEZ&O` zZe2MFdB0hm5Kra3AeZmpQpmf*rjBdD3TaTEq0qNIf0o7(0nQASKL_HQ)<`cWST@>pVAwny zIDF5I@r1lhKgmy=4uPAK*9s|NJ$^uL9SGhOiOsv~*p&^BgW$8b&^Sd-DMN_??CyQn zjVN`833>ORb=2VGcUC@CC;65DxcEusSNZ>N_NEtbc08a0|LH9;UeihnZ0lK`clZg$ z>iAlB>Uhj}(tqp|Vps}^JRAT^)zo`rCUwbwX4^&Ivf z&ZPO2@;o^I2TGN+=CFZQhZC#gYQn*+y>Hp-;r!qF`Dswa5i-yRLq~Xo`~myxfOlq> zv3t-7zSxvq$?$pjy?^6W@}#vsa~;CGQ&OnyEMIpi^DVJ~XdS{h`LUN3M~bZ%09W`& zoetc^Ut+J0?>L?MnS@B$+3n^H#J@qh)ILA2&9su`d(hND#_G6e@MG|<%{l7%zbYN? zBe!*h{|x4HJmo3FTl?$d?aH7mn`cVatR z7UUhVC*@g}D;Z23-5?dH;s-|R>IlWRu?M8~A&+79EFu^}<4Sg{IUJaPy~Or^@SlEP z&3wGO(K-fj^3%9|G~V?DKTrwhDjvAQIPcEW+a#_lHDms@r*$_~)9&_e@!KrV+tPxu zI?A4A+fR|Asl3(piCfq^lj0qlvyq(#f#C-H11H=1Kz5b)VVCTp(KNDYU-ZvK<{FV_#1ZHU5 zi>B;FXB@G4n|XU*|Cz&lysOYUEO7FZI?-)fR>Kb#_&A;6F30D+BdK_!DeT@}wYEZm z$qdZ@(kol#?fY2%>Mda-gLOPK;a&Q7{#T*n?ZmATP2;VanIekCduz_tW6qFwa!b}{hFSI@v^3Dv^IWQh83`7lc#qM2$H%N1xYS{{TZ&@yAVDAMVkpA4H!~B9DP>k}U zh$v!jPU1f{>^L1w1gp@v9ht(P7dK$@ZXyh}M=&Ap6ts>9IQgk~@vpxG4=3(zujX-2 z!{_b$X`ubR4SYEGhA}ro@Vs@S+$osI}#%3yS5u5i;%5eVIcAhe;P7(vrHoC*}u7rcHY7bRcK;A8{ zegjnyUsK+mV@l6r|Ji{N4a-GN>?g*wI1s1N;6I7%GHd z?;x}62h#1+iNFqx%k|Ri*%*S|gPImZEp$ehuLtF#bu{DT=l^G7MPM2q5b}Qdb<-j) zZ9Fs0T^EOCeNQ7F(tqa0$uY2ltlcbAdv`v|_aH(agLU||Oi29QL2jhu?RngEJB>Hb zdV&lV@41SPO^P6Icu=bH4D#M_jPtrEHS-bt)l&a$lA%2pPblBtbQ1~j>tv$fHX9Yj2yh>dJmiT_ME)Jt~<=f+Ze6G z0w=#$7qW@`Jbd7quglT=Df}gN?bQ`(18!%K@*ZG>+TD zEb7m{e1p^~Xvc#zCcM05h}L0^lV5bI-qDk1_&|qYzr@fGK5usunI`v+vxrh@=VSFW z26)ddnNzIJ!TJNzT*m4k8Xh5Us+t*))aiJ;FJ{xB@pcF=kiy~}`it+hPjl-j+Mkv`HvGB_t$pzP!12Xv42>u0~m z=I!e6_NFl0oB%Yg;m;AD2SwQ3Teya^kb?<%d!uzMz{yXr^Z;3S4nNq;UER3)Ek1AM zg_&`-jc1XtZ+$Pt7vl2{POlGJd!6;4-a@#-SRJ)7`PuhF1Hz$YZ^+{g5Lo4l{|W2Hwp60tnIEyV!;{GTxP-pxZsmG!Y>plOt2eE z`S1CEcq1Hh{Chb6Z=&l#Cr>#U(|V9lA8{2{4~k4{{x%2ppc9*?0=r-jQazdZ<7O^A zLE`XGAB0QYaMviu9nEmC-RoNN^#v5fab#RL&X^27ckR|%cE}%;IQ$WctH$m@<=lzA zv2z4LF&a0W^C+5q7j_Ra{^TZkS56vXjt}+!&EghXhY3!8A%|5qk{tN~5|ip4yAyx@ z*EhOcVysO?y?quWi99=+*llha4%8#0r$Qm`w#8x( zw{0VXE!p~OeKz<5>E+w@*Ct@|4oI($xy&U9q|i9ddKtr)TG+fx7r7>DGa+xdbDOE7 z3@5+0mp0ccEAxTXgX*MlV|?BRMPB&lQiCa8*a&B@!mT}JOn`AzHYw{cSGLEzTYLEL*Dj^y{VmzqKN(8 z^?bei!ofS&sSj3=_sLM1+OONmU~$peRiaA%VE5)*Y35Pbyh~oI_=(ID1eR!=q4hF7 zA$4rtzV9-A@X0e@_bx^2@W;uoHf>Ecu;m9@yVrP?0({;r8G^sWjlvNjw(K=s6ZpJa zoYzKPte9eX-tTrWR>vP+ZP|CeGu>N@j`uOCj+->z3Yq@Pv3P$|F_pK5yc;YOUs8Fy z>*de-4tdwgr&9VB3L`Njb(xJm;XwIUowGdTZS6OCvvmghQ~@_c~e-fmA^htJ#i zxKH^(lW>IJJzV=nK@)!W-sT$9{v-PK|GRBs(ceNCtHYvxSZ5-6rh9AB@%HMdpF`sv z?`^RRi?>IO#+&1iciASDZPc?j8t=^PyshsXg^~SN!oI0P-jhOAhrh$iTfcHhDmuH# zfaBW|KP>}4KokuWR4v24yyf?Dk=OieBH%;gmV_lqzrKWhd27<`(UAOo<~y7SMCWfOqjYeGFY+B>VQs3EFzI)Hv%UB(^ zlRvDRzWU$u|5&1l!TDdGt_KB1+uWx0AYzY@5>^k|fy|onD}d+!gphSlU=JdX2uy#3 zODy4gdm8UIIb_Fe9V_cm5-|PxHrY%Bo*;dY+*VUd}h-NaaleYyT>l z;jKr<+kd6^X&P_23)d8|ct^RK9xsEuLp%Jl)zMhK za4@#v6`K&`t@|O`L0g{;rWbWNaZdz*B`0++Ih#0R?tFImN<0LHfsmb-tu*JK;C1Ti0PS{;=*`CYbp;g@__0>tcTx*qdC98N44 z=*wMd`55zaq-~HLIr=4Ht5R8hb29Pg4MTMd@Pb7#OIZFq>fywWnC(0AAa8zUz7a7O8KkAhNX2(`ILH^cVb}vNZ#joO`Q2(r z1{xEZO0Vt*fFEbthsT#;ckkKe+c_K;2!cs8E)4O}*|`9_dmEha{2H^7`FL}obr|C0 zht$6uPuM2}rm_cl{+F}2g6k6MooCx|dAF4+ev{x&V0qq$t}|ALbS!&iJd*L>_y1}A zjhTPK9<-IN2Ze>?AEWgkOZnNVSUo7ZMfb_)t8j@O|M8{+_8^z0!X)bb|CyKj4rNi+ zAktMpYiAn?T>LucE#E>4q9&qnQdn)Yol5`E5ckG;?4`Oo6$J-LE124aA89lEr zNC|;~Y4!fA_4vGh{M6FcD?f!;?m}jtID>zCOHX@z(hCc02hgA!=bq28y~! z;J)n5iQABOK0n#{(MB>@*qIw-y2KyMFJCbGi!pZhKJuGmf!A9>Kt$ul2($W+Xkhbx zV?U-4#KU~NozOb)^2@y>_q5JP5R`gf<_Y>Ac%RBHi1Bm5@7|i8$2*^lvi=RyFWnid zBVzrd_^p4x-eN$?=9H8`*`ozD^R4FZgawp)`6FwNucMNc6b<5dT`9Zt{T649~(OP+`sG;k`-Q3 zbgF}ax3@g{y?ztl71lrhA7`+Ri606p{(d=e3mxyEs-B%R-k~I|HCViTU-Q1TgS-Rx zYSdDB|9Lm3ViL~(1mi;EyGsf39)l!crN5%f3-bPzX6V0On+z7EyX+*S`h(GT z;S0_^!RCE!^$p3;96>OS#)XH3|Gst-n|I0ZqIOan^YJb~>%hxzv^j83;(9^gDEQ&k zo_u`Xwkx$ZPpO0;4y*F!n$NqBxyk!y7V&Gl@z{DT>+ikO8LMM;TUY9b^#9KP|M~yV z%)h|--;AyYopCLFLG3|`@C9joKlc)_dXQFrl8gyi}-?S8!n^g53zfSr?pzvfnGsy z7mXWxIk-pG{UGMwwddtQOV$Z9-wyI9TE|nI{8r{7&$38FVD)HB2}p8lv(0<11C|!`V>;Sw63G&`X$NTg~k51YWo3Q`> z1}xsw4HZ(pkoUJb`yW)^&nJcA7C_$iL(2~*u9ioJ%$Hip_mO~-gd$% zB?C$DAZb^sFSsJAVz}TcHt*ivcNw)W1VJtuw3jZ~XB8)3GURRLE9un^c~@HLp6P@GQr`zZ1=nds#Jj1* zX6))> zgw1D$I6M|QC9HFR4#npIXQ>U=c&dcM?M*^x>$`r{|7gF zFRw_JW_jMhY{wX?BQN}tQRCk)NSn~{4u6*P&&`RSjykDf@$OYA{&^GfRtp^;rt;?G z+w&;^@*bJ^(O)XL2HAIe&)4Y=5^y)YQ0E4DUpoGXUq%UjLE3MftwxkDP{?ChtO+5pp3?;>3D58Xok&ufBtxhDnIjeZ(1D=IQgw#)o;}zA_%mSzOT7Dg+Cyr zDw;U#{uYh6foQKoy7&(#T5|TX&!BBE%kw_=n6Wy3&RZkA_wUPzjOlojiZ&Bz-TU4C z4ePOZuX*D&+5vg1@V$1Vp1rjP?HH#XPH2BfeQV;Uj6~@83-Pp&K%w(0S$)V`{82Zh zL75E3MRs(&I^qWwtu9X#2tJItXRK0TYicwQ0*leO>8a|oif^%bUkamallNji-n2T> zaq{~n@IAn_Ob{$ke^-5c44-#d|HYpPqtQt09*tuQW$s~qj{oevjUU-0hPtx;-rJVJ zI-HGL*1*eKyzm2<#g;?hT{2f^&VJ4?`0IcFFxw{p2c(^JJt)q8dgePw)cOBa>dx6% zJ!p1Vk$7u3#dMjtH%0z8-W2 zt-~HCKUwXknQq=haB$&|g*R>ScaRIF{btYGl7;jZWI8_`!(U>5%La>?=55J zCnC*XN$zTpcfi2Iq)(z0#4^n*j&lwfJRnA;*>Cg%yojTU|o{3kBc zZoIqoCiW6*Kkd8f+H&UOO{>EeC%@TOID-2&!3V-0l{5@A#pm6XWB$tGbvhEQu_gG( z00TEjU$6VjHnD@{caVe|jMZW85@*#p9ZKbGLB~6WkX18}E9kawWatPTp~ooQ6;e9%=CG2!U<)q}i;gb1oukaw_Q{uUR0GH@}k|H8J!4`i+M zlH!%Z=KT;+bE_H<1Xs|w9trcQq#SJC9pQd=ES4}IZ(1E>ocv_D66-6)1i|x`8%`s#oQ`+Y{V;PH zZzb`&>{z@HnFarlhP+$m@!5<>DtvhQ6Rexk{w=U(WLv77DMJej^BOp>Z{?3p6#Av3Z{ok`6jA&V0OS zbp+$&cjoljm|1&>fVjin=EDELyN2zPuG7Ot+yUuiNdC4re&sCBTQiKYI=W_kR@Vrd zIh@!|$NOwCXD*Gmb#^iv7Vr5rqz?e{-mTfmNj;oMf9VzN4S7q|oax~SlSO`2T;9G9 z^4_!Nk7^R+o$`EE>oN)I<1O_Iw%Ygt(L`sv5BAu5@A7hqZe@7)mKYj$WuL$3Sq*I7 zTT&cOmWweT?+Ubz%{ckZ8W-5IqKpVK-US{M+koG_!!#Bv9GRbtqzo-vX=Bg8-g`%~ zh#xnR_4nS+4A#-3_DGaab?Wy=RXC(E;KITTT~kIFAqr1 z>lGh3yqWoUx1)7r&8ez;68=AAH_%$wvaK+VYVtx2GhMM)A-83HO92 zs|`n3o;RV2u{stz=G+y#GqZ!-O~*TNIz^twTaD)(Hx}<-9GMcwA@2soA2n3oMsJP# zim1F#7G97D>#Ye=k&;{VjRXRtBT6eID9Ef`cRu+(YXeU<+a0>i;|FvmPZFv>WA7k2 zTP|+x{w@f%pmF_6s~3-?VR!Fg5%C4NTFl3r9j)UdPJXA!kIEF{h~R>X%S+&l&)c!= zw?ME^E>d@FT<)?O{^hO3TR(_7A3w7S?({e=fYdMX2zyi?{tylfLWLF#8Azv^40L4~tWfq`m1S z1%qv%c&9|E=?7oX+j4zx9T}T9|DHUj-xGqMAB`&t)8U9Xjm^6%Wx!iVllgehN9(wS zlV4~%*Zgyx0$|zR6Tb}|@p&KUDp{YzpNlBh%LfRv-N&8(gFV+;3G?h{dEUVX8LMM+ zLhg6tzmK=Dq~jf*A-|W#JN4$NIas`ps7B1b4tZ~6Z@Eh4Z6qOM8A&~y&{y`EyfIR< ztl-08DLDVT`ZgVthP>B@F0pDIYXgE^nd@TT`-1L6LHcb^uzBx^^w&BIHzzO9IM>7i z*&qMH+d=ku#k2RV#_$_KWj#Tn^&%w))K`{m38-;Yokr-Lc$q^XCoIzH|el5~f>|2zNxzejGS`cpXn+tKx)i!R_Ptp}Bz+e*ah zLA=C0TG#T5v^%y9hu?=iX#D5^SfMfwIJQnv5GsY4Rs;G(r|!>=AWaL3|mxa>ZEUfl-$_b2+=%z$J|$2(2>T?LIdC%1qA7Vog>X0K+*J6T+1n#%jc?BYfu+T2bZ>ca`N>a##|co<_hlHEejuS zfyQ-Q+H;d_88&bGoJF6sLYa@ZHd==rPJW5*BbVMg3j)HrJlmgX_`DaNFaMaZrWgro zthkspiO)Oxz^VBb5l2{l2l-Nhu{xGWE59-gn;DR7=y<0N=VsG*-(UBF4~w^=X#1H# z$a_iAUe9L8drBjoPn$ zM*P5!KEcR@>)5<09jdBs5<=h?8u!q%l;SoIn|ILg%3`x)%*T5Ot-~KDznA;j#0Bz+ zz;$WQd7D&x-cs-0o(NPdMr51|zg-i;zq}Q^WkAvUyeG@^CJ-5`gJSvqkzdM8_ufm# zJEfvv5skMEU%`AV-bW?*!`b10bl{EKJ1TE-_7Uy5)XQ6+=bD}K{#v8^Xx^%wbHc%q z;i9(4B@{$`bBvN>N*n0mF0T%F;RkZqZ;d>-jLmzo)Fs{#At7)Ljq|CnC>dtQ=55g^ z!1vpc`FM+=b(rDgSJ~$J{^d6!_-3oL`^Y(b-V(K0gYxUIAqSc}tZon7$6N(z8{wLH z9q!B5x3fHNsjzm2>UjE`==$d`Z)-Z<$qC%bG~QW!e!N(`H^23Wl7zgc%>P(Z&)$L} z`!hJGyjQQi9+LG&YkX^>oy;#1IGdwl86ibM>}<69c3o`)Iy_tFUwP&S-u-sAWXs3q zJ*?7m%9B?J45M)-Ck(;}v#@y!U+s;0WW#*CKcaOIaq^1{X6s$OSr8oJ_%b;WgU?(1 z_T>|ns@ISOQQh;RndvAXR>-ZFzmFE24{r|M~#?(LI{C|M12W4#_ zuA}v!u4hUMv3gLgWQDm1+(B+&WOItzfCWlXD(-0Jz!IN`CE*J^%ZdNrW$WEd*|%aly)i8V4?8_n=vt z=f8c~xfEfx&)N&EV-8M!#u-sxW21=RZZr2L>1O;MB%Ank`HpQjkW~qRfsSwRcaQ`D z?g5@#Z&<$v&1bBRZ26aG?V@LPko)O)UzS^OkH)*+evt?kZ_TcC-&G**1Mf8psk~?L zDj(E>yo1AHwl45qf{3-b?RlOW4z6?da$H)fSc@p6!_pmTU0m|4g~ED(+@Wmft~sl4Y!p*}u2$8IPZt{~hRfUwSnmNaMYq zyImNI_wr!1Ds#wNSXFds6Xabb8mz2H<$W#aknI;SMAK#uDQkZ?$mnO|^jbkdnx#I? zdngUB-kL=P$~5}}{(X_kZ}qWxw_4BER(mW2M9{c2b{q9aXR&$n2_}q)YBC@1CbSNI zocsznofiK|A_Ak^${$p#@p;SK^}J*Oc^8~F%=kUpggYP+rYK9F=~%El@8DmI)v>64 zphEfY>n--t@y@vR{0NQrnUZuNEZ()Xl_xwPZ|-jf7pc7KwDma_Lf-b}Cnj$y3nCAR zv)TKk;p;8Uuecb=!ne0x-mTWG+6HF1*lyHn_XmIC>u!WwVe^*f4!N1%E(B&L{EhoQ zYDqqL4x9Jo@{exqD$K`Q7Of)_C%^cv*FUG<5W#_C{SgHv_`I#G?N(XqmLM4(%h}3= z@p*@f$XC=|+sg8r6XRAnhUyUOjkA|NKeIWpr{kR-dM|{=d)&!O5R12x1m9FNyy|2rQz|2xt3 zpnUMEiPnRH=gBR`>OnthvIc^3i?om16?fl*J!qFrjl7?lY3?NzQpfAJHPk5m{VPbd^AX+eD7vp z{+|vbT#}Dv{T}pt;?Mt)b55(q32?FefYi#)SRIGttK?V3&CLIY>3HWnmtRlo z-i5Cph+*-5nx36`2l5^;Ue-+IZFNxfnGWP#TP~un>L!cWW_eeN2SosJsr!`kiWEft z#1k{#+pXZzefdS+4Sv9<)P`fJAU1Ey!Iy-1dm#{n#(mR&x=`XiHgD7Oys}>@%*T5> zT89}8JqI3Mx8#w<<39D}q zw_AY_&O{2>m_z_jF-OBdfr2#VJgo00w}P&&FE@`Pen4%~Wjsy{oA;9YmdiXGg@7g+ zcY<_;t*I58_XAI^wE;}ny~WTv9^&NpCuVg&n-UQ$A>(CkA2kCfU@e!R*<8ATLc@Y+GFm^2H2jqR@ zm0%5(xA7PD6FVU9%)=q3lg`VLG0C7q;goQY$Zoq^P@aN>X-A~a9cYD{716>25&j_5 z(XH`u(R_7w8~6t#GuCW}N&Ur)BZaY9oTz zI=i}7J;LYxQebaE^5#Ew-`Js z^knDGj0A>{gVdVUD9G(FJLg**tsrHVj`Us~KTw^|f8&EHc2BWzVxRr}t{}LB#@$dR z<_SwN= z8F8T1q z?+?*kOR#wNnbnIdgS_wm;&iKny!YfO#9xKH35Lex$BI*0nj+qV9gdM8y1%Zpc^w6* zJ9`vaq23DWZ|u(abJGv(Dix2dtHb8K_rpV{P4ES2d(b$cKqc|3&e*&s3)iG`pJG1V z)@U75IQi|;wc$~QkGHHm@oRm+TYTONGlmwPbuLGgg=Iq8yYZj@S3CDtr(Yt4O$TZ3JCA0ye0jb^8w@?ygyh- zc>nL37h5l!u+@(Q!j>vGG*l?ax$^-+$vaxXk7gU|=6qiuKluLB><(%9cyv&dp7u4scxqL;6+roWeqUSJFDl|>T4s7 zn4b%6FWkqwal_k=5SHhyHHWb}1P^qVG+daO|DEZ0Uv-}=N8=sgWhaTndv9fZ)IP|2 z`Cywh_3Z8IYVU$F>hu3(?H-fgiXd?g8WA-Tk)W(vU#Cf#f=FGK=<;%F1%W$D)>dTu zf~reX=(xIe^SPMgBsX_OovV_iiAt-irni?d$(x;KXF+p zw&#(+dizB48*K{G)BYkS#PcE8cY6t!Mvg!5=OPZwUwjyIX>chX4!E2s1Om~xE4AEm z+h1b$EVjAQ96J-3?;4~tS_eB$e)G;BEArA70J)Bd0aZWnd(gwK%J%mXl}O_(!u(JE zO_-nKKlnCI4(obHvi$rXtj<^+*8Kt;Tvuk6*rRm3OGnzz(|9Wei30g-GPJZ!cQ=jiXEdbbW zm`yC4!sp#9F6WZ9`8G0C`_up0Vf-CrzM}j+a?Tf)=UphrSREN^FEh%LXLx(k@xF22 z_$-b03Afv_SiGzACH-R|Z@sM8)d=Lhf^%^N1@cZ&to`g{wgy;oW>Jn+L;@~xeya>k z3i3j0{hFtR4?(4;=FhXI`~mkx?{j)G*u0us0>sDMQG~S&a2FtK`cdz!n`VjIih@LA< zfA+>7aVezpr4;Br+p6#r@?L6x`-Q^>3UZVZah>=5Lr_>VSJGb1A6VvSNjY<4^A5HP z%@^7z1a_lwMk4{PG5_*%B3{?Sn;Q6-k9QDS2R}}Jy&B^JztROjz1J<{LI%2b;q>mx zF?jZtVENJE;v#(BIx35L_te#~Jn!2IjMec>Q`gz^;(yQo`)BrI=3n3vdy=jPRY^N! z(R$G6doCrc9(3-KqQ;%O%d4i7jZAxV%jklZk8$~SMgO8gIzks|)4mAW&dH+~;{*@lQL0ama zZ?BG*5jYt5%0zfH64=|GnZC7!f;jpsj9mWO0yL_cJojY!frUO>BTf3SxeC3Xey03U z5Qw62DcNE2m2BAY<6;SSWyF||HxaF40w+JA?(^yH1N>mF=nC`FulT$_0%YVmQiXh) z$9XOIeIxGWEy`g}TaSnAEPsi87K3%%)1pXUJ3X_5JWj{^R%QMV8t+}Z3KXz-|Fq=3 zHVJu?l%9N{@-8u&zvCX{ZST3|ct)53=nd{NNQAr#efAZ7-wfX%ojP~Ra-oNyV`!x4 zB*_n)Tk>K-bq_XI_cNg-6=Q-R8I8L?pHlgi6Fa`C)MIbH2=noFMeDeali!!i-sG57 z0^q>xhL(Bb_`JVWEvYbuyuD>+{ahZ&K=)=Z85v^|90bfHcRY!u~Ggecp_H_z*lGttI?8`E$EI_|dxOFvnOV7+bcb zN?nhFOcWE}uTgmjaxUd6d_3j{MDH#yYJP*wm232u)C583pSTaZ;{)n=vEv_%eLb{& z5%ck$jn>hElV2V|PF{AH9}Jx>U$KILn-kNUoQ6FKRfzoj@*-`+M%?aQ_44}DUB1Uy zzI%Uv##kL6s9FnXKz|B!s2u&$kh?qb(Q81!B-L8?j&u0KuO^zl^0^~y*+Q0 zUEOe22#lg}Hy<9o=y?U3xB8d)dNJpikGDHo$3~p|exzUC?-M8hcFOS!l`+73dU7l0 z^q)$^vdUeCJC=c~w@ar3N>)wXX67-Fq1>bytV8h^=i>j){~7v7|343c^M3$c52{_{ zkxT1AJsI;&Jmg*n^aht^U%Ny;j?0yQkE8#25@kOnX=MMgpmp zS(S4vD2Rnv!%d~dEkJtzhR#dfen4zYWA)h>?4A;PC17CW61>qGjZ5uw?g^{Fz6a@d zuX^1=S?23OXVE(F@^c-iO=|Dq2PTg{#Xf7q-$All9N!my06}=Kzg^am#=s6TjXT-C z{}jt#gCtyFu#O8SH>mvGLHg72uAx{hr15s=d!>TK`(xs)CpwUKx{K@fD#$x_U*m=4 zIq>n8p*fd49vg$RD^F46`Xhn*X1Q7Ow^NYclHlHxJ)^2vwl-WOHhB@0 zARv-NM2SjJDL`^oGKh)<0Z~v9PC20@u46=_=oc!8CxJw#R37}x`rp#F?K9JTFIWt(uej65C z{;GUnjEd_m+@eZU?(!`986+K*K9aB1XG~Q7nL(bQz`L=&G6ThXd3crz7T(Ku9+YxL z@E%=m4U_QRsqlMQD1x_oiUxz!Z!;iSlIJ6g%ph4jkIO8zB*GhtD?$RjJHanMqak0# zAY^Aquxx?@8*gs=Yue5Yd|*2{&WO&#acmA7?-ma3v&}1M4{vs|k5-)gILjk)ba(TB zu(gr(<3sq>dxz4s2f{*)@VD&nt7fYBpSPSEks2HtI<@HW_My_p`qbCfJ%3+sJx+o5 zt$_Rm6mNPXZ)GgJ_a9C=7mDD$uwb|DCW3cIj<3=;1n=$g4m+()%t67~k5k#B(Lf=z zcDJ%Q5f0UpT)yHAf;Ypx-N$)?z@8^R&Rav+cu#%eXJR?Y|Er!M=SCg#6vD>aoO4p~!D`yWTb%5}5+^^Uo$WnWh6!Nex_YSJ7(U*2>VoA~ zRNRDD+1ShLNaN#uq0c6B{e_@KKlcuLMxBqrgJbFkk-NA4egE%&y}QRxAj&zBo}vcb zV~ge_4Y3NmQ65je+R$OupxLAsF~_j-pr z`%Y=>8pOIZuQE7?_G*wW*#};JCG<8Cx7~RFaJ4?0RDfTDvew)kJkfgx_A{!g9X`>C zJH#q$ol&dLVq5e>Y%!HSD&(0B9fC*~q$Mt)z`N!B#6L4ggU3%bvG6uXhf_-tyuYyt zYBV5tKh7GFY(VgS`LW3J;3*SOlc0FH{8KdWP(3SX*bUO1XoUdJT-w8XIoStZe)PFIeoaXKFZ8zY z$KL+}Z>3YEErBkrxOk5`)~&E!H@E1ASQ97ee56jC*w`3Cnn5PgQQ+MS0~54C$`>rx zz`|QCq2Nacg0~gB?-df>YZQ3Xs}Q_{2IUPD8cf0Vg~=!E@1j8?-`CC!jzrk=`^=1c zK?hhp6xFeCAP6YNysgN5gpK!!eU_UZj3aoH<95ls*HFVsF$D58?AFGylZ2r4? z8%lw9lRu{vig(Q>S9L7BE5d%-jv#oico;$;ZBBd+lg=+f@V=tP5%*2U9Gr0dqQLVa z8hoxlSte;ugx9UYLruf_*rPfnmj&|%NS4_L@?9Krkz>-4ez z9A5jxcubbj9^Oo3A9(rAzrO^1zDxk8z0TgxxQ37S=+NHP@@jYB%&X9)6NC5-QrJMh z0OM`?MUQt_A9X%nho4&Ced|yEA3}lm-Hp?pDBgYL3Tjw*n+y#oUFD)SZ_&Xl7b1MOfUN20c6{sdqQ?_V}@6}zTXZVi2S@f$CI$Z;LqaU++1xM4N|3QZN3^)$E! zSw;4-4ktgg$qTPj-3Z{?K%|1}Ui=!g@N&}5K%yBA(k=N}-cH2~a!5v}VIgMG*C4vL zRQk}~6}Rfo3^I|K0`JbYG)EL~?=Rv^n0W87^W#TmkW()t*VQ9)M_Wu)^DDdtm82o4T_Wb@S1}wZ|)?`=yzPRt-XNK)EeIkVRcz)Gor)H>c6(EH@XIXZVD%&=B4FsrK_u*_9e z3+n^{bt%U>ixt>-Z#jHy3yUBh*hG$dbS{g}Zxc4&!wyjl@-&FI9@)nSocuzbpXEQX zod8Ou$^^cJ;p43=<`=9k+5{`Hy&^ix;^Q5ZTNay73|{nj*IuU12Xp=&jpW!r%Ug^T zc(R<#1v!D}wjjvf^i{vWCFng^$r7a}3BC zZZU3iCBmXmPIJUuJ7}`|?P9nt2qXmDeWt$#8}D5={5ACD`M^1H+^d^h;JX<%-u1Eq zhQ2g7IoV0}ftMenVO)+Y(*IwMjjfl9!N=QO5V|ue(geTi*czn#sReV=_RsWJHm|#K z_whxKH=PufKB`XLll?n6VW7af&E@?;6z_%)`Ae|yel~odYd?bb+@mM%q`kMfNGs?r zvb;6h@^GK*2O}`@Ypjo9DjH1eD%+5?lL%M$-dowXsss3eOS!65!C-dZcjn0d;j!V? zsS@Vz$my+LS~yvqHz|Np1F(ee*S|Ia~DgL+2y zO`|m^ahpB|Rt>T}HpIW2m5M}8gxo!rOb1rLGtaJK5e6J0DRvo5sb28K+~L2 zmU#dXzCXCnu;4@+;HjY7u^XvD>)t+AWe>uxDXPPDEjjVLK#3f8{^xzpdT#6?HY4Qo zWnFpNYmnBHec*(Dg5ygj%_m*=@<85j1^A-=X54`*g_g~`N_=^BETN7sT?eX#65}$SH z>r^wGqb}^-whaG*bP@Bk5<}_4MUVGsDt$zca82!w{d2s9jRNnk1Yvm;Z$GxmY?Y1M}{@0mS+y=?!?ZzGA{EPpB^fD@a2uoSYF1h%pdb3jC{m8L3 z0>!)MXf=d|_qg@FFV_*gPds&8LfV`FC!`v8Ab2M(WSzanV*rG-=R_K;V!+v6i%lB) zh_KPCyDH5*?SSKF&mLyOAn;A%Hk(upHr{JL^XDXV@`4$1T)))VyNB%&lW+ z0Q3Vbo+io1fK4}p-G+ULaNd|Hr;ctr5FO2|*^aERru{LN)V;xrKj0K`1XoLEvjfibI+bb`2`KG4-jElNZdAU@5$C|Hxk~1-66+45WM4mUB3%o(g9O1 zg1_(m6$8p!g(N0}iSP+84-LuUd!Smm(?g;%2rSK0w)(Le8}A?HmK(*Td4VuFPDRX8 zB6%w|-Whdz)xX4PZ-|{E`$)&hZ>S}-;QD3)AgbxwB#GnW{i04($qT_dByGD?X-_k5 zgG3iSGs)G#vG`|@)cTOPGpYD@2FXo<_tVJYEEMk%)mPkDcwbpNex3=LK~`>}gGqR= zn_YUX0m0ksgVtE~V_guuENA<*;TXVhQDH~W2_n33p=8t6*Y|)=lk?UBm0+Nu#`?3r z8XNDs)h5JDZC(J#aWl8}F|W9Yjko@D<;EQ}_=0*uD~+t)j>q5GJmaYcps;pXyGJpAQOLxN`xp_< zj>u9@;YT(nPLu^zi3WqsPZ_nPTCnj(W+t1TxbOlUa$LG(Jm1<A8%RTJf?nD^4p@v8?;d8 zW6P-98qKgjlM_w~yq`#}7eK4G{MqB2Sa{21uFup)@NQEbu$tvD00==*=VGgSJJ-k7`=nVkIl{r^8*Htqg^^#98!YS7?F;Z?K-y*a)? z5UU0~yz0xRhBQdqh^wrxA~ncPeV5NGEM!)0}uv{!>< z$v*DmLcYz^UjAt=$?6mY75p>%}71TlAMq?L6BGbf*JX^|^-tfhPCq=l8MkRvsRZv*F_f z%gJ#z&&CKA$FcE#CS-TvWGe09y`Jm?FTaiFmvwxz=K*}|$F!ck#mC#IQJCU3DuL{|Qp7Sn7P_>^hl!@!TK0`6=*z5ge z4j_2z?s!U9h2Z@%ruObp1n)bw6%ezVCNOxJ$NXD87E}OesOvNlj+9beS=!zT-b1(D zZkdMwt?C=~=iXxD9T2>lVM?AC=#%5vZO+(UzJQJQ*4!JrJ8AHNw4-DnxcU9CRD>__ zfUDa_54Miu<1M6|n|TVs`$BD}GV^8p28oU?-E~|raM3qNbn|J{`M6EUO!FbV|Ch)| zf%kx&@;MZ5MZrvdEWC~5uW6h`@GjLFaUkLCaNmkJiQw%Od~`~!QX6ng4ajPW!~zYS z6>@e_MEI+~E4If=?tz0=9hG#tAt2xQbn?vqaG#&>2&3T=3tmu0j?1@e(fL+`jrUpj zmqAn-?Nx74vJbrc{DIBh4NnNb!Pqfa@i#u+K51~F*v@-!Uv>5u^Vj&dw_ZvgtY)=X z{0&knl|H62TuvqYx!y97mjdtpWv=`v-t0U5`LOUF`#!@_j^O>1slJjD@9Z-g9{BvZ8T~1Mh-VJ!Wqcte7N=6K; z2AOgeEX~U<*RDwbl@-Vk`_b!i+}Au6?S@%GwY0A?oak;KAleWM2BR5-)U{_=UhDh#8o~#m3`M?H)bQy=>1Jg4ba{Y+fMdz z8z;ZXnAnER6$IcsUCVtx8-IxP&*c9V!O{V{J5=56{76L&vifCEbK}P1uR)g7`DjuP zj^zCF#BQQ61>SEsVaZ zz_OgW<4zT^;7woArTkIqcp7ydBgu8p4xt+1`_RIg~{9T#{oF&I) zMEL8}?7_zS7ROIEeKp#{`w-bjBTjy?q8}|yJ`q5P<;DQNQhdC@z^>~BVeRmfX$wY1 z4t%^{+;v~tW+}Dk8>G}b)cH8{&G3$A@}K@+hyw37fj@quc-zOcFUP{0!_6c06@vHo zL_zevamSm@ZOfmU8DcsYHZD06`byY~Bq_~f>L_3N1*$9n{W zxsS@LF8>d!vCG$Zw0mmtfCX~gvezlapMtRQe#GG|aGC~Bkgg#6=)%eGD|@)_a^&^a z@Fm-s?pEXDT@qLG${N9&>&DCSr8inIN40}4V@fJY} zyoa_ul0fkmhHpzu6vg`_#{$2N zcgBm)5#fY$awD9tTfn9-JC6(*2ZN}6_30Bq*wx!<={nz~&OG2WIWA5m_(xzeHs0=s z*SwXY!3)w{$UZ!9@_QWjX6VTf0US^53beY7kM~Wn2Mp5Sr=R+yq>2=TFj}rwb@O~|9p^oD1r|T_*g?HNV$;U!S|NlG1Zk~jg5Ce` zaJ6;1`kn_QkmHn0%{lyJvHu)S3X0yAxR6R$0jC!I+?%d~N*^3)f@}WW|Nm$3rs*G${$HG;27P)i zDT&sg*#oPjuxik^$&;c4WQgTT>5?f&YS89ahVkCW5<8)lsPe(l1h(f&Km5Hr7EGty zR13=|!o2Noh--(NK=PF#IRS}apqn&Sdx8yn$h<6{rKrJ20NUiZn|dM5R~=k2XG$w) zn6u@cO2V}EyUr&2ki^Lke)Uu3{9R;-bsa9{K89a|EUd0N8a(fSb={gBYDcN4LCw9l z?==c7`XQDMrqW00-65&JGsqPbc#ovm>_PEXn4gfq!h1zqdfZwB?~nAA2T6FJNx5&a z3BjB9w!(7FXd~G7tfL3pqgZg}t(_Wg9ub})(9gV(X$I^^i&dAE2ZIODzJA3s*m$S6 zd3P?8CxH9pxE;oap64fFGIT}1V;nZ#BU8NfM-2%7#2q~OVKh4z8*f7eElcHg+Qa)3*@rPseo8ab zX=0msz%F-{vF12@yq)T^1NR;2fPd)k-TO5P|Mr%9bzc@jRHSdx+UWM*<^$DG=c7`{ z{(@TKpX)6|DexXvD7cB@?UE2Jj)k{kS&5q$g7+={GEUOw#HYrc>q(CjZD<=)c=6DObdO(X?Fs+N{-7; z-g9nyEjHd`%~R=OZM28CEZN5dPJV>V@vGPQ6Tqc`c{`4C_;~Az?S7+z;Js;+$7e?> z_W$V;MPH`cuUYhXQ|n{*5oc&k$)D9*5emFN2$uSxc=xpUtiZzi*E5p`Q3&2zE8Dh{ z@P7KcbYdrh_gfaL3+}4guH8fqic|c(F&lQ_4 z;o~i)50(+24*1SDd&6o8{K-j^0k`pEv(!b8_Yjpn4kZu1UK?`Z-~Ippc6j{Xh)4Q= zX^I*|?3&g^Ymm#Bm>gCO61wBhcl>g>wn)(R`ck9@4bk7(ejfRPG=kUd;r9&|@LO?l zvz&LafZsYl*euvL}jcLNJDZyp~CSA$g;0HNQ#cyfl zTM_JdYoBy++by)W1{q5Bu?;7`0?ky%vfBh8L2qK9Xp3Ki1n$;$@8Z4>Cp@dw2~DG- z|9`bJ>D}x6#lHqQM5T{6BP>dP`+q44yeDI2-=KJBhrE}?!dp_G{$~n;w_T?HJPGf( zA?`po1n+9US1$`A%;DYwo_F1^W5LW)A^K&NM0mZA`M}4)yWmnuv5aLz2yl5bYHq2I zJ;WO19k7$^=LXK?xEgNfFR6Cecz?@0X2e5-cpH&@;N@3tG|QxYoB&J6Qna;CrIF`1^lR>U`*i*sq^0_%nl)q`-T^?IEK6zTUd| zbImF&yw3`){9T9OU3@CZunfVwBy~Dp2En^M=;GnJcr)1Z);agw7qMVNsi93(84-?n z{=L?AWfQQO4)pi34goJ$v5uwMVdHIddgRk7ZUT5gj$@PF79!(^jrZwE@KZ{U_Nuor z*#};Jps*t(ONR%nXxV&J%oiW;lZVOIn?-CQw%7yHa;;2$+x!VE?oq8}H$OJ+eg`2w;pH zSF|alcU>Gd-uufdQ*%sc5ATm;AAUIbrMJh9g`FUPzKbipG!Nk8tzsXP^-7=<-lHM< zGwc`s=`A|0ukq2mMT@?Ahw)J7V@Hii`o_Q4Tdt(QdvrX05Ut+D^hVNHcn@zA5&MeZ z-M;GdAPH}D@2#`D)%3v$V|aL0SLjhsEI4;lkA1R`2zw}cjpbiy0&Dhss;E{90nOaU zSNG*&<6V-?#xb*#0Pd3GhCei>X;xw5z1LIw!QeL9!@HF1V;@d_heo?NF5~Kzln>`vJf!skVUR$1H^1~D! zEJ`%J^(z(>I?``cZY08tcGIn}#vO2sar4%!vQQ8`W*gY|0lTK?-af+bKE(yX$#Fji z9xBw$@50>wm+Z4YaP0=|)gaV|I8J`@ZYRPrTL~aOdqszbE`ALX7L~90eft4S7x7Ed zNC&?LvBFVv2>iD3n7B_fEj$>r@Td6CI9q)0th-KnB?ct63aKp(@tD(BomYD}g z&#aBRZGew=NY!fLGYH=6zIIIK^WvW%rAwOA&rMjm=<%jYq|(Rl!`H#z1s_TfG}r<0Shnje4vpDyo*^>WX} ze?XcphdLj9#`lc3_WY^dt0?gP%Gb9Q#d~#wk31IM>LpJkwGh0S<(1ZwR&N{A+Bt6^ z%Uh7#jr~_U%;6B@^0_r5vEUk8`BCwDB7DBBHo=$YE{OCneIhCs27*G*CFy*`#yju+ zx|I0$+#rw~mn*-F!7>&b?-f(^V;U{Ahj%X7hX_u70u54x(CQcv`V>d08=fsY$egFAEml5sZjryp@$&XP~2~s#o z_^c+*t>VwS^N<-NeZKguDKBHV|J=zCPSZH>Br77esGSJ!FFgEX zM|dO9yJDoT{y79(^0v*++OZ3>pTGafvX8Hf1Dq$vg&gc0V42v78J~1;KzOGn?bRUE z$61{GatdvJ8V?|Ekg^xVDhc8bu}!tp;~zIXf}M}-nDu#uzd;&Sq$4DxBDv@rB&`DK zd?ZyD_N+SnXNX-#f%ng-Q{gDyY<4eIvG6`RxGnS`g7-Dcc7GDyOt)stA0T*J8s7We z!C?a5b2zIYvN;Z{@;g@Ndyfd0aLxMs6uu24Z^*7n%LxJdcZl>Adtu|f5MeZRX@&#r zA;%rqnBFwOjvX&Je(6gX4dRXZSc;S1_UnGePgx0IvR*y=vj{%kkHcbCMk08h>kQX? zABn%bMHiIyxUf@x(c?`QNSzN=OV*Nwnm-NFS_-^>7_8<-@pjmlrGkaGdpv9FSp@Gp zAuVMjye9@!sumEuhd>>Q6?p=@DKKvPE*N^>NthPyu9&erR)cLqnUDbL&@ekhe6nM|d zi@Zbe{;&|HjD@#XRn=4(g7?;%_D>|dA5Pm7wji4m;bR_!Lqeu-Dq~*VHsLsM-Pdh@ z|6L+%nwQ#n$OHynMVA=md_usjA2}S}HQ2Z|?v@l>eUTH?k>gCYzufdS!j8A#*uxs6 zMSFOoK1^})6L@#ZQ!$nRzW=grNtMILJDa}YusMP^u>lgXb*yS zzn{Poq0Odnt_-YqjV=x(bSU;^g->W?QByypBfDU`_iq@#P;tdh=i_h| zr!Rtweg=8`DRn-&`HuK|U-~nHRH49|Ztnw4bOveiqg4|NZ<~BbcL>4z@EUh}65g{h z4$TS(-cEsWJjWc3;2Sd6SR@g=i=LRQa_%9*Pa{69@F3g-m$ox1?!FfSGQ^|43=U%B z`fKfo_nL$3Ab}j`obg>d|1oyFUQ_rvO+(tl`zP6l4o-f{`lI-}Ja~ZZs%h!!CHQ!6 zFqG&XkLZFUP8IDd6`FXE&@)n&Vl|KB%Pm^bm%KyRJVL|ucXB6)@lNU9x z@a9!%3;m7Y%|@qshJ^P^$(Jom2;N!ajAofRMsT8z$Co*~II!hTy zR|<^|!p2+cW5V$bH2C#aKG}yRPJWa2i9$C$dB87*w=Cz_@$p{PpAg<3^9c6IOJAj{ zkB|56A3SgS8rc^82hvx6QRkx|`AMQv$RE5FDe#_q@u3H;-qFSiYFK#FYo@$XBlZ6? zW^*LGgH_A~A`rayT?!7Tzkf4h6d| zobmSAiH)}!!{!6ad^vyGb;t~onNDj>AyR{))F=0>FILgk?O%x9*QyK0 zi^bNym`1+;FaN@sJV=B?^+H9Ql&=AKOOGjULMZ4dc|PyJ0!W zay54^{2ipG!Y54(-xq)XFJ45Qk0F@@tLAe446*7IcrynHDxr8^d91{Qg?FcGS(+Jw z_h6Ze6A5qTQ*-0|2;P>uf{#8;Zh_h408bed2X1bg7RY`n198kg`|plv4XY(En5GW8;zcq$hTf>a9kBHxqD) zMDbpEjL3k6_p0?1>OKhGrEbZwB)s27MOKa>{lDQ)zsK4_`tX{zrdwCU;y_39^_c8_ zW@5^U1 zTQl?x;QE{N)tA-dz?fu-ddhPmd_#O!ezM$kkaG2PY=l)Pm{@!I1{VQ)HP-L*b$hWG zHt?1lH*Pb&ykRYN{Lu^PK0=PPhxb0RkHa|mC0ZwNI?3|@#fsTN(;0lciC3?=@({Y= zd9L;4ne6y@zdS!MWOiZk_y3F+sq^v1>;t6#_x}I&6nN8j23w$b&o7T%f`zxH^-1r1 z1aG;9fk_hHo`HnOy$Ie+9YeFp2Mu8j!KGUtA^m??N19K}Qz9(fX;8N1(RCnoSx5%9 z4+V$P;tj@=uyK|DV$B@+jt%S~$C*ER$F3KM9Y3}4RpM6%+QWMd*~eF${I;F2eSYQu z4`?3CR$KoQAMd5BDq2UlyWy6AyM@uzyxw9HSRU5(f1v-jqtb`&u3x0PxBl(_@wzw~ z_~*zBQj4MnaYk=#L~9UqNuL9&1}T4QdYzI{u015a!J+`EL5yYw{)I?`vG6Y7_$^kC z;C(dy`B4(y6$Y!fUPAC**R(y+_MrxxKXV}!(u@V3;gQT7ABeD!`nFu&;9Bs)M!O2m z4+Tr<%%8fjI%DF^(6*~=uOx(&$iH!}L2sY=9LC05Y_2-whAZviy>RcZj}E>zKQRjs5ss-KE~=6 zptk7orkkYF2PgO{@ppM^BL&{9zamee)qDT>1_%r9tJ$yNuL$1s_m6gw@OF~_@X`;# zTaHgU)Z!z68_pQ=s^-Q5{}rpPJl_!Ej!Z&Y%0L}pSaPeYZB-bEnkFtUiNVIzyumP7 z|1AVU$Z^|si%Si8v6r{(W6jg7y=bp`8`WYCz=&e7sAuwzds^ z>V~_#3{hbX7#+2ju;~;a|^#UK8Ou^Aau2n0nB0 z%vnKWbr`6sQs2nTkB#e1K86@E6IM_{jx*k{XRqvb?D#gFq-{$6w1;;C*~dMc{0?|H z`?0no$6F%IW~%;+y|=o|l)Z1Lc)evf<;I5Erz;md-rA|u`M8|8ho3e6-~0b*pu5LU z0qOs@P}Cs4kkxz98q`pz$%|EkI6Ga9=hMrziG5Vj*v3LR8Uxp5zVi0yOj+cJH(2fmiZ z$ypk87xVY{4*&^z(%gHuFaG|&iAo<10fMT3XOOxSc=PUGZHVGswNi!$3vaK0-fj_O z2Kg(=x0;0a=Fz*1VF=zqvf09XnThy`tVv6aNHhSh09s58>sa$2;s5bv}YOZTYG8=}-T! zLxDGs)KL=@Z~x;1+*o**3T^J(h~Vx0AmTX*@BYlWUGWIssujO;wso$C&vSlT5ic48 z?2R`_!ed1ERoa48e|;6;y+8=;i3$bp+($cGeq!TozHuz*TRt;*NsfCoTdvT292@V} z;0YB?JKC$>Mr0rNaPs?n`1zFEO9J@hKYX&H3m@7VKG_ zy7-s3=nhcnqd<#U@o)7;P8cp>j*~JK$m4V*EKysI;{7nYk_!v(9i>}@oDjT+A`O3& z@cxwfB`pKN`*Xf`X{Ws++#7p6cXdz9aUi1ypUJ2@aD83Ya8)_UyI=uxb@aDR0 z;e+D6P<)&d3-1w;D;JL;c(0V3kS6v2-Q@U@d>O>51R$#jy zJVJyy>9<$~F0TQ4QfuSJh)$Og@>9F_Swu>H;PYYlHY2-M2-z|f`=dkgXOgC^? z>rQ)kJCJ=y- zCv?>M_^s$E`S1S!Kdl!{|A5pWBZ?X%6yfZI)*uZRO+l<0R36o?ya(z3_nGwnzJk;s z+f|yKD@s(f)myUNTu(}Xm;2&-pZ-1ts{Fi{1xzDvkgyEsPFfd(f`+;yebJ$yO38Y& zUyCi~5Ie`bZKZn*BPb%rJ^bD3P~e4Kvs7FC6mDP{C}#@b=x-Ecl+qvdBtaGD(VMe_RYk44ycZ?aptzN3Nm z@U9{IP{+w{oeH<4qX_aK+`+85xi);fMKpth-8VmmnUm&;bFcAdkaYY`FX}a4EPA}d zxT*7T{lG7Y+Pi=He*+4<1$aKvp?Ld$d$<$}??+xb>+=x2Q_a3BlkonfbsxHg;4QAh zIvjV10jMUh{~B*U4YaIS2ETkI!kbusKTj|y0}+z%Zt~3_-~aRQED_+xUcD`F{6@U4OFbtIQIu{eG0snz8ct$;(Y;1;m5-Jh}~ZE zy9nOnQr9j2EN|)c?ca~!Jycj8k>L9M_HPX-V+ONm;IL_?B;^Yc?mGPbD0^c$;A6kj zumlPNXQyknuc*hyo99byN=+vdI7N>8e02YQ=T+DZl0BCh@&PsN;mt|*VS|(3vD%*9 zHigLQt;^nLQdHm_I+rBCg5XV`kWiAkqX}~q{AXeumz0|y)!y)rUaUVfQ0c?Mu!j6N zu^t89{8uHDP`vYJ{Q0o(cDpQj`Za?0nRJ_dlz4}wx(_Nya>C}XL$jw$qd~r!T(ib! zU0%KYS1Oq?K#)M4pQy z_5aTv-f$wF|IeUPxM7*03U2P*wts*p3V^SB?kD_2z94N=4ca%H1DbA@TITqj1ZoCH z4vkvaU=9t>?6f4>BI$twIWF36cl(cE>?L{5$?-PJBHF7#kI6pRaPr$?>$c5xlpjRN z$ZayYhF^nfa$K!F(;vfCb9n~)S-LTQk0^vDX4_QXu!e;PgKO)*Gw2hlPuYM_?s~R@m3UVy%#h>VbCpqr!i35Scx!8DD zx-nPJXVD(sa%3N6IQjKU=`6j4TyJqKxi%p1zrcI$y5(cKZ}<vyl%KhIm3Qs6Brc&He~`)qH=axA>}k00H{iOeAN=F{s*cpv+jlFNy#-WE)6 zj6BSv1imWP@x{D}0>^J_3g4I|!rCu93@rw)0OL*X(xD|`pn3C^4Bj2scylh?cmHn3 z0B(@uPI3>vjCzEPclGb#13WeKG`avz6&k@qdALWYVf5SDxT6 zZ}|pVTsFC(vFP#Ef~oUys7dAv{ok**OepYP{z4i?@gDt}CX9*q(&v0@5WLMk>pddj zo%)V*jSGTzclZ6)vP0{D*KJ>kj6J8oi)y8=n(xT-7BPti{SF0S@=I``8B-WIe%bw; z^lxmu9fqf;SGO~O1LU~y<+%lwY}gHw@TE&?pRdv$-qvIv0yz17yC{0mdoKZ~^QFF= zYQUeIjHSI=WsOWu!b>ch&wAi5Z_z#W(u}U}T>SliH@)s_jT$zAQM#-#8y$ehOS=9=Mn>Lxd9> zyOV^U7XscjR;{sv$YvG?AJzVZ*5uVMtR$Z?Oxj5f%qVdL$5to2Sa4dR_g z_Thk&-)Yx!j~a0TV41b^tGR)Xw`j`m@JqW>IF5Vp+xlG5=&9XMV-p&D_LX%Ur;m${foa#Jrz*7xOk|J?0I}vdqHF z98B{}pPAk=^)lUKYG5j1%3w-h3S&CR|^X?yv10- zn9Z2P7|D2q(TmZE(Tq`xQIS!Ck)M&7VU}T(;U&W(hC3W#90xhvIqW!$I5aurIm9>! z9Q5o{?8EGR?49hl*elqx*^}5K*^jV$u{*Jwv1_p_vP-b@voo{JvW>F6WP8MRhfABG zn&ApVGD9@OaRy(89Sl|sx(uoeG7N$YZ1i*Vlk`LMkLg?J>*q}uRq=rXFp z__owSS*Qx>y`~3cqAECpcO#U6s-PfGUnm__Cp2|!p)^z-XRHf>E}<&$*#;gc6;(&G zf9gRgs5%mO_$ic(s>3>GN1%(S3gCGv238AAurKwe$JxV<-YuJ2H8% zK;fuzIlpQvbP`qDRX=h)t2ZB8PHx-=|TquARkm|50z*^-lziUJ{gb~s9jH={moSE0P^FZ6Y69AhDndwlVb_HNsFKs$X$;w+YBizO46;Sls^&FOkPWJ2F81<5)~J$pgC(JDsFG6pZ3%5fl_bYR zEo6nNm9N@$Axl(=r@!0|S)huv-VT|ginKflnW2ibngf}liq!lE7 zBUF(NIYEY~BAp3=3{XYdLWlHGMcQ$M^iW0m_7B>ED$=J?kS?l7UzR{Rs3IN2hqO^e zI=75mWkMb;NH+*UTBzbcE?j{&ql$Dt1+)oOq|f=Gji@4h{S0ZMigXV#q=72ZwXKjk zsz|q7LTacYT?zN34&Bh-MZ%)1Mc&^1(LB*!K}^{7gBuf71)p(;&- zVJ%dPs!PlBgPOiMS4FK zT8k>ubCZxfsz|T%L2FPo-B26`$)RfMyreU<8dcxyyeA-8RDI>^+X}5h)#opBE|3hW zh+WgVkTj|$V`bk!QmC46d&mq)qH0{WV;Yh`)#!NqAhZ%ypPoxfLgJ_zNwL`jtw7aB zuck^!3{}Gl1vep4RDBRE^@BuE^=`o19a@g6wSb9V6SNdnFM?zBA%0X1*eRcb_)yiq%#|PFMb-03wKRx_tQ>E3 z*)Typ=s$aQdoBSYpz3L4aTdgls$R=$6%ZGyo=C12fH+arGrDgY;y_h*>xtD6JF2=8 zgykVNR6TNRjeuBD^-yWl27*xafJfB@VnJ1BTbd)pjH-@;K~9JXRqdyLRzQrXYIAvi z5Mn^pJ+^30h#plf?Z59N zS*B4{=bQsrrchNY^;L%D8>*^5cO|oY{rCPq+VAn`kPXsp6l;*ASq-`dSrjWOg|!B` zVWr!ajmQS6&HH2}(i&tkCws&=atCSO*~lkt=9>V!9HCmFEF83K7rZt9n+S^)&Y5)P zUI017cjDhX!+>VI&w!$)73RKmx2p~PMu-lqC&!%>J03;HiT%ZCvlC15Dr?$XVt+vP z(S(ym^q zSMK3^j41-FTKZix0KxkiDC?=LOaZTXt!}uhg#q#XWhR;B*m#dAU3hZIiw-O&$Ek@} zcZH~6<2_ofk?f>Pdw72&`@qYuEICAbbU82JC*GVKqXKXBFWFvC=%2tgJQ2Ii-r(OL z742b5@8Y?9(Z3*d%9A=D8Q*2rW+nXD|F@#Ro78urcrOvSwGs>O6$R6 zTKwvb;_bV$@{(LD{s!s25&y4_Hk^wd@7_<;`IyRKf9m@8{Xa_zyh#fwDBfmC=f$z` zo~IXnb`il_wIyXY3GeuYU0*d3yoVIL4@EVpfnJ?xIfaiAKxtp-d07N+9o+-Mr*38f z*MKauNNwc)|5F78Y5`j@Cnw_fmK)G*SOPwh9{*+(Hx zesX-Zu3E7?;HZRlh%ytRWJS76~?UFDEdgW#RG$2^dPw>n?g=|}|c+E;3HX&xKE5rvqW4R9oQ z;xo0|{TC4?>}oRp<&q7UpK`e$>J0R-kdOSPJ8Gu}^Q+ zd{_`?E~P!Z`N=-6;^bHK;BJ*f1>UDJW>xl#K8E`xL^3#;+cAHS|8#%H z)A<`~dl&uwKV3C-J{}i36wM;9xBT1x|3d)n{(v+{_7pXUv^Rp*pp}-qa#%IUkw`4b zyHu|Ioc$p?sRns36ZU$E^#5L==MJ=o>H;B4XLnWSaG;Q)VV$%L-BSGdMS&AcTncOg}VseVS6gLDe<1n<0-7uTx}gn`QToCVQ$C&Aw1Z6+fxu<>@Qf8leaVL{7<9CzY#^1d}MuxF6x zHp_187N$MCoyb1$@;i3OA3m+a2l}2Tk4;c_y?rpKbE>R z*6&&LLoBsEX04^JFFW-IZ(9nyNxRo5-nRCwtFZ7c?#*=>Lh#P-;9p9K_h~zgw=Ct_ zfPOeR;v0f@5{Iz19D=tWQ=0p?8^~=griZTY+e-#_=)29y@lxHnyHId_H z^k0g}M`Pp7!svSLb2M_eo5ubZLiT}|A8#v{-)Aj8a9bx&wZ0y|dJn&fzsQW>T|z&w zG+PC~|EJq_`H|;9(4xniY9GXoF7o|LNVBuXMG1NAX;C+Yw=W~b%`8TBTC0|NCO*hK8x25-+t0wgLH@N124aD<}~HE^}N8Io}0&tiq+esK*_gm zj!)pbmn*i45~ElF0olDB!$BC^e@FtxvLh+Wfw2;QaJE>G` znJ8)X7B-in#M}7L!8E=0&7fxE_til=!h!Yt&GknRyh~0F)$G1_4y1U2Q%osgAbCPr zg!v*i-o>@bnm_Cov|`9{CT@`jghsLN3z%Rv-M@Js?ctq6_A!o=-wpF8^9;4Tz`Y=~ z!;1>M>y}5sJQ+`GZ!+%IvpUgkZKUj<+1B=zKVA0a~rvSTWvV;8CQWN zcQ9P3)h%keKm<{fCBq*wPJv5RkP9FxmB;;&Fbs~WKNrjYh z$P5$j-3@t)uZ(|d*^=Y*9a1hA`eWn0e#xHZZKbq_w-eciDo%c{a@H;vf6oV|zr~Nt z7vba0b+%hX!53NHV)U&;TG&*;{ulECL8@EA-WEHOIueCWg;k`M|su3pwuOjOQ||3T(X3M_M-tchDZ* zrDPxHaPm7G-7mYnn;*DFRox?&;o~iR+~CI-_g>h^$b6ISx(ArQM|8*@5lJwAD3!D5 z@y-{e&WCOk@Sw(X!i7T(rrS`vE@ysw*QLX-`Xvtx8{z;-=& zq}cezM#pftyKP3J7{OZ^oIZU1hCS$~vzEJ15&^uH9+~f6f_=P2vbsX7X<$KX7dZ}U z*0O@)YrXG!_kP#;{&V`CbFI#G>2t38zMlIT)@*Y; zZ9(&g6Lb{T(O}v>`Zas$>a8gmZ{kx*B;IEZXm3X2-Dn=|8Uyn_AMLw}oHzS)${>gP zPT<+}*;3m)3jAQnkS>C+-u~wA+A#3Z5}1E3V^rXY23#`qhGUHAy!BqCg(bfDqsffK z;q(WK`(n{~YZues*bS(Uw+>Q=7Dj$!mG3U99pM3uVkV)VC^-L5$k*xbh0or^R=*bn zi`cx?3A_?wo&7Y=`v!$|(EoYpTnN9M=-=~y()vxse}$J=JF*@`d`^?pgQ5pkY)9)s zJa;ai2+kGe#h+4@)J-wi=hAbZvqI4^k7-( zlLbcF#8#^nM}q?r-KxyDbWnFb8^a-CR;gJ{O(d?RHT`?|AM{J?oB7!w0{2FU+J4f) zNFA~m`8kSg&$1Zj1E>4awrCb$FR^hwI%QJAcxcP(Nmbt<3I?RG*^dF&*VF#|PiY-4 z@%@ILOY^@i8E@i)$0Xj#i9JeaypLVsbG-=j4qY9xfykRPEn)vQnD@q(@I@gj01b-y zf15oU1nsEPh)!A{fUj3#UfoyD0HYrFn&TUyL7{d+<(_C=RNkv3Mb@+B3sj&I`dP^HJ-oz*ANxbiuUQ$Hk{YlK$t_tQo z{+yGK$a^Bg`J^Iz_12W}$Hi}qTF}++D`wnJgg{5XTwf4eB!KHJvfV~g@Z$z=-a%Dr z(ZFr?{>7%u-Kc*o)wfl)s#g5ev_RtCU3(YocmSPub2{Ca#zyMnU4himf{|bK$99**FdtSi@qmR}viF$9M|pE#}dWx~A6BRbD?SEYb; zf2Py>a-zVef|)G`rqOwOK00CktM8{~FA^ubN&no*@93KoWqy$d@fWCXKstuhp@NZL ziPw%+2Ul*eX7B2j5ej&#R!x1n0(Wo6PaItp1r*$zn2;>f@Od@OcW=5x%IXL%rB^?E zVQK!iBI8Yb*9nRDn>KBEG~O=`#$1_%c^`Tk#7yKZy}MsD5boY?*Pn=toB&Y8E4z(r zuZBXL)6=&WVcr8W7v#LYoddd&ca_60MFA~oV^{Uay{O%Ld$!kpzNvXlMI^4uLr!iz zAA0xJKXgdDD}(xYZ$awVkCES#yKXI;?{b5~e%!eX6r8=qyIifl0iV4&9PfYg^(OYs ziFDRehT}}(G|$_E!a6SP!1FR$NB=wjlXj=n{8xDXcP8sW#J4>WdyqU=jMLaj8#=Te zq%>6?J8-c?Yw>!L2eAi@e0wRN3O|D+D&rqM!mkaz&D}j^;Oh;|ge7(Q&k+F6l{5RZ z-xq+cHfiY+&nR#*W6f`da7EM}R2~;v9e(herZW;Z?N$|`$d10m+UVn4p4_9p9#n+X zft6nfm)V^$UtZ9TGhZoJf;}LetGWKO@}ntMhi!d=H|u4t1I_j>>y?L6Y35&`C`{B<{oO zE4l2#=)9G5OXVDHP#gPE`B_-~cD8@S3qG7a*?GSho3}#T=|_eJcxc9RTFGV{ zdx;HdNqiA!cZ246zipF`^ji+$Z|?1?diCyooQEB=Np7 zW2=J3yE*c_uLjJ!Kz~e|$lG|rGr0}Ez2)XiwO>x0CKTQztCZL14+UlatakcE04-r= zw`6}@1?~-wZk*TQ*Iq1N9!q~#6P0&V)p%WF?X>2XWq;%R3kEE3kI{LD>@{q#QlP%e zTOmjtp&0pXaadhepv?!iw|h6L-@xwPnJNlQ@1^lj*j2+A`Y!CtTXc#}j9j=|G=F)E zPJyyIR-}kOGlp-FhWFm~WW0%QOeOKoKB%gU#yhnv+1&!>-S^_F5|Q`nu|KoNVBX~% ziEsFBYC;8-()TJ_10a3Al6^|>+1o21lMz~W864lpbIIyjG+0@lZMYhhq6@W)R;z}2xk9QE&$xF@5rA-2&8^U|TVR>=p$6fKNKjKd&>rk8 zg8Ii2y`6Q(j=3StbW$9*`Tj!#=)ChD9WL0ug8F#-BXwZqw+3hLV5Y|hiXPrQF?k7_ zcSFAP6#WN06yj&Q*T)EZK*9;fZWQ`dLHoQnP*#UYKH##lL@xa@Ht#Dzv6mBX;vpWAL*j&u z${h4&(Rm;C=rA_=M18#bkvg#Q%Qh*u$^Xs=M6)wK8c}dSx}qRM{}jxd?!@~5Wq{3_ z?rl%L{PHr|pa1(QtfMJ4^U~j!6CWevP5kZ(iT7{Z1$s2z4_E?5n_%7+Dhc64-hcXk zOMAh*r=JjJIV!Xv{O-y%-ut~EOL}{T{j&rhDEZdP{M2=@+oPh@=~NVGjrpYzy+;m} zH>6`sUw(K(vjT}z%Prd~&4@n#Uyl2%bg7m4c$Xt}VCA=h{&D|xc|K5gG$v~_K2nD(Mt;j481asx67Vq0_d|ySt3SgChj6ZmmgQutf!s)H@yhT{jY(=U;y} z>Gc{^-hDo20^>D%HJ>AK&AY#~vG$|$_BDhW&qz@p?}tboJ{b8mm1#%2p5z5rKDfVm zdIpfowQ6ezG7FO<_Hq!A9^sq^&L9zYk$nA9d=M3 z?;xa(T#WoUFER%WP4j}LlE6|Z37dD@tYq%;N<6e+uzpeh3ijk=1j5qOPmn7c8t(8n@y!%h%4OhbhlFzO+Ohn!vE^<4G!@PfZ&AMq! z?1n^rrWHGWIzmnwrmiO@2tX=(H{oY>IfxLqS1AjL1Rld|ho!UoHUC*W|G!`K=Ey2} zM}5#V{qi?1DWLmU&j)ng92&cLd=06OcLP!fR(@Jt>MM8o@d4J}nJu4Fuz3$}v|P0s z<}LVRB|e`Y`|2&-JbRtM+C19doXk;JhrJXN@_I`TGTy|mw~~10U5s0a#ydX7LSF{v z?Y&8DoH+mAVqJfO2j;!0_jk9C)^4c&UF5f9;0zt2OC?BtBY+|{dbWohW#H7k4pA$o zNHBl!o789?E9#!{`crY97U7SY-bfq-EN!;;q4U;$IJ7El8};$dMC!oGPtPp=MY<9n zs6ShAelG=QZ^IJ2cQ(OiZ}<Rgm zNqUfx%cR+EO#_JT!-^|d=2R1xbF-ZVlS~fA=_7p zZg}W%{V`55^b zvC_2%JYNG$R5c#jSzz-PtiEvY6wLeQ`J?L&y}@2$=??v@3t9X>aC^%E3hUthqc&*2 z^m+?FGT!>{Q!`1tg>&Dsqw!WVz+JY4dD|y%gowO<*Kav&2lK{FDsJMA+y_}Ux~YBV zG=@4&+7h}y5`fbQ?lQ*NbswE)ydPb3aGrFYP888dY-Gfs^M>(oZG^0 z+yC(N)(G2{j;Ma><1LBQ@f9P#?1G!`tDdX@4XfDJ3;AI4)|u^+%P_`6nuoH?-7>LH zkmwTaR+JZ)(0uo%J4aa^r*0&yCkQTeZ(lOr`!8IwBk_)WcY8G&Z;RWBizi^-#oZ5c zh`dKr&OK*?dHb^78zZ#sg<9H$n$O|Qpd(6NI^%=z?JbHW`#jt3fZ>Bm!9yn_fz0^p zRO268PMmN2-o2UmHyV0V;oVy*NF7WV`MJJvuVldUg2l}* z&yR;=^F9@Dx9E>49unHi5x|ku2C#O%9fN`NbN32qe*UlcL|Gl5-`F2BXbF=6R3* zrmT(yXv;-S_~FEV-~Wfz_^9BY!}EU#Sr0n8^LIR{2RSw=twrlWW33ip85c^l-ek~s z6X$>9TlN<9rHWb(zZ6#8{bd0CSfsDb#<4)s)iD_gT?F9y=K2OMqgt?+nZ2WN4-UkH zds)fK>7XvLd+8$9uiX8%As&fiw~x`_6+~ZR^%l==TN5CO`uqKF{iMy1I`(1Y7q6mm z{^}cU@TN&dgn1426028`b}R?JLHbNHVFkksb`R1$S+j3WhW6k8#}iIj9aaWHW{;DX zc96kjyp6tsKoW0FA4Wbj-c4%aGk0L#xG2v8BJUH7wt_)0?YJdkQSWR8KyAGRoRK;nbD==@S?}-(KmnfM3yTwyC z2T0NWfYd`_9fyoe760De5=6$^uzCYMiMQ^?-Zf~vU4E(ibiur5o_L24dGFYvvPBr? zEzdMDC!lx;$~pb|teMDmsNom=z?~NaFn-8R=wfj-$T*uH=_ZB)ZE0M;?PoMldAE1R zyKGj*H#|q;HjJ(1N&OFxw>-Ijq(wE4`gp%X>S)EtPtnV2`#KRG5L>tCq$!EbJEHMe z&Co|Ylr+VY=69qSx z@u2Z;%P?Fu0rP$y`^kXFyZxw8&#e+gt-8Vsmw!1OfaE{kzXAVk$oV4stD~<8;LMnr zqwmZ6Al~UXU%Mm@e8&0I|Kiwz$~#0{%jXH(^M-LGZuw2A%s=hu-MdljRa`YheZ0>h zbv(ex&t%ftXKNA8XjrV00pI@q|yniJP9i?+>ZV*P| z8=y+;MEYAYsE-_=`@TdN@Ddx>Wd~h{d(c!Tr(e)*MJ6p z0=WF%ogvx-0%|=gFGa7zf$Y;;fB|72Y7g?LGP*Q8`lTTUiQB}qU70=%y$7k~zc!mb zMtxt9_C@MY#mLX8(YWa8O)e0jA#|%~aD^7upJ9CV?(ynuJY>*%;`AX_>~E0bYz5N7 z=+tO`iM6M!j>e$u#^2YLc97v@yv>=@FOzuZ2h9tj@ou%r?~sIf+tzPBN927Wbxqh7 zn75I!dG|g>3uvRIt^P6Vy&&yj-NEgT2_XNJy18j~15nbbuS}ke05|H-2lH;_mFQ9qeSLZ3Kqx5^FQU2e{TPMkQn---ly+N8dAf4a( zWE~oBhcOZPoiOhwA`a$6-eQi%gzj>f_aWYV^=)PlG&Je~&FlojkL?SMS_zz#e46@r*C2H~ z$H%(l^v@R-d_H6#4s?8r8G>|wZg;M#+ zdGz^TU%PHo$Ytu|&4<*nA0t2C?40|}irm2SqUk+VI_v>Su))hcd=w8Azhv!Alf~}d zYM!5FCUPWc{`D5iyeO+;-`3Tg1EavQ&F?lfB_No79CjrD(7O2om)Pc8Obv=I+M1W#r z@k^XhJ5hOesCwgA51NUrJ%&3Ee_~fFptlI_L2L0f3T$u>Dw?=eG$ZB&^;f)e zzFBJlwA^>z;kiu!Pm*3G+veq5H))CW@t6`tz`T!%9y{MD>j){@E!&cE*9@4N5BXiYLjb#W)2pQ(ZUlS^ zR%3^qF1?kKu-`}Nq-m59BgHhM{$7nS1 z4$>3`GTzoXT=^v4PH*c((0CiHG)uV$^B%}6xy+>8-9Wm=1ot=+bT`!Fp0N+>N#OF-X6(C+k0T%9``p$6L}A( zweA#z=l`NzLPJ;T?V$G=)@_8gBOrGy*(tD=02=*G`IuuKfWCRRPD`T*(7-Rl$g+Pw zD(~Gp--v>y(S~{?ZXzdNH@^U#cfMLnb-Wz)@jigmk%y6AyamIJxBgsU*&XxO1s&MD z4-$F~+;ql6&u^bjdFh3Hc}qZDKAdSC?a%)@6xJ~!!@N@d{1R_EGTxR-U;cUamNC$L z0~&Ang$KhEFmLmWp(*0!txoAvqGd2|tN4n6y)w4YiifYw-qjukht7MvZ)qTa2={M> z1fd6D`gfZ6TB`_9C=w9o^cv!8BS@?0__ph;S=aY<3m)J*} zs!iCw&os;-aSt|}+%r~Y4$z8rOBWEz)1>l)N za<`Z1A|BfRef^#zr?GdCxFKMkme5V}_aISP$A=e&E3=pGAWdN+en|iM?DTZQpX$GHIR*iFPPfr{i}R;)BZSHf zDm$7uAgv_h?Ra(ZAKp*3YNgP4<5}+J%EG*pjvYxN^0wLVa+Cw+tvK~cg5TH$s+K%_ zM(VpgP(8u@w5fmqEG-fgtG_jY`hBYREP`-gZ}e%l_Gv@Z?!8IC%K6>gRKqSLZZ2Oz zXOkZ~@5DUy{3#3S<1LHSk${n3`=cK*k&Haxl8!!IRt7fj*#{!B%aicXvcBc%Rdd+9 zV;27ycpEg+JnujX>)>2q$Xj5&K;*rGjJJbV*)LM}ZvPV_iN?E^r_FyK%=_7uSOX&O znB^DD*kRstdY@DaJ~%^NdQb!F&euE=6dMz50DqfoZmy_|f-^xBi;yrg~ zuLK(J*E5z^9AVysAsQf%IIGqJU7@Y$Qk-fb#>_G0r^YS~=%>fAb-=k3-;SsmLf54QY* z-`@J~`9IpUN=1JkUSe01^&pR5D_)X%P*XOu99j<=yIQl~8=n7Legs$-!#!x<^KHV{ z;3r5EM{0aR(!C%}gQ+j~B0NFA*fo8ZI09Hc+jnfZZXCFz>*HHkZ-Ux` zKI}`sZ_qH`a2|={XPRD|*0DsL|JCRkzl49HzVrWnqz{xFmFhXUNWQG6Y8GXl^v{p9PIwd!T$Ul0caAcGm6H*!#H(;OGjZh3iB~4295WH1?SmDn0K#o zQ4*0ip?JrJ5tw(Btelp2rw4R?*{X_tf^OjZo$K6=7YN|DlSjah)JGs&`IF5C5t#Ro z>1r7vblzVNZ*x5OdA8v`5*L~1%ITts&Rb&0yzaFC_3<7>>cGlxV1!-LMx6`T$4jdoz>qc9B^$B6aW2 z!}~U)@y>W(zyBS~+bX&10Fk%7n?Mio>@EDB=q`>xcc`P=$KjZW3kZFDAmIEZ0>FQ% z_@cM@5onlM?me!61FURT*NlRXpmy)(unjvlkN;?3LgJ33f8G3b5&iO(%*VLXbxPF7 zyA7#B79+o{4DmX}NnD_)M<<%!d((ZT ztPY7SPjJ%r{+<7+Xv#-V1)l%8$$F3WA~sbra9}$y?E$8A77$*5cUr8yhh#8uzVYuUt%*UtV7xQ+C~Dy(g_k58E;=M z*PA5X-FhofdB+9tKVXEH*aFLnL?Z71#uvZ)VBYEqmFI$keW3m>`hpF6e87o}rb&RaI@%-)tn z>f>F6)Pa?sY@FK`^UIvT_gaeOT?%+77~#Zt_rb5&8S&q@q89u9e;l4yd+3@E&GV+T zj&stprv#(U5)Vi@$#{F8AuJ>D<~x+Dh}OM7|M=d!0p^`&<*rWT?Y#1P(i52X*7C@S z7(pK>_@dpr)qUQ8&;I?>>JS1rHz`wj`d2fMx~Ak4d@BN++85fG_sSHNH%qPOo6e|( zhHxbALSm-z#kc5JZqy*W&+a&^&KzTgvKKGa9tQHhpP8;vnPgWpL^YiFZJ%p8^_hzXr}Y zHJJCQ-6`LQS8v7N?<%i=d0)KQWiEKr8}gVw;BwyD8x;E5Bv?fd0O5<8CI5wHpu=$T z=wNLGxN}Zj=cyDr@Agg*dE?UWhB72hzaZ%H>$B**xz?O4%)3v0ygQIOI5F~jE1y4c zP!GQU|LZpvP6uq>264~7B*VPdze=C>oul9Z>AXhqa(_db=S`PSVI7W>j+>TVZ;`@I z#@lnf$5RsT{H;J9jrWQ1XWNg$yeFj03yHjIkNX&>!MtCy%P9;Ac|(i0-CEdkyg=n! zu7iYV0&rCtyluaw890?(DA2IOf#ls9S4*nUc^{J!TxU}CtKlpXSKLwEx4G~?@D?|G z_VzXP@peJ#;KayJq|8tC+6FH0RBgHBeh+NkIqQPBVlU#M52Iszt}n6o-gIyEXSTcz zqW$^*J!N%#pIJ7&sGcKY803 zp8t*0@0=)wd(c|pD_gqZ7o=qgl`LBB_k$Q*Jk33?`+{asalzxJ1W;?~lxo}X1e|M+ z%(P&}fyP@GrQDWTqwXM^Z|bXXh%i9aNZiN+(G9$}ZBXa`6~zoWZ4uPhgB~MwVCBcS z_^Rym8BVbG$np!~ZrD9&IBnojizOba3fh=>RQsr1^ctI?I0=9k#~HA$w$Wf#MOCS(h{55)ue{TyP%|>GZN;#YPXdrk@qf~x6cNc_uV1&V%AAtNL>4= zOVSBnVCBC5%q1%VkneIx`(XM6c)e*zQ(?jZ7pa86G*v59-g__BlnfNpL$*lV&QP|e zOuNu|=e`W*DNUn3-g}Tbu=0DKwdP1;Hzx?*_C#RF37fanmuTA?Fz=d@{Fc+-DcC_8 z{1DK8Dn#?V>5foXM^fD)@fAC8_vR(z9T*hQOX9uv#syV0-ur(Zvde;bPk6oUEP;6| zLr&k7;3r7^ZXORzkM@PwPG?88>G%S^+a(G4_5>g#@5Oy|x)ngKuSNE;;(+1PED>Cg zB`WU>-JNTe?VyMBkhrGQn1o&Ltx>!8srxo(MoXxVH>nP+{Oacf0^Bm-?j5wcezOfW z@2{)4|3r!6p$8mU;wsCrySL|Iad-DRMtjK>HOHAvi=Z>!$uf796VyC-GZ(n90^g`(JL2+JRV1Lrdi&+DH2Z3ia{cj@0oBBfr`~o-2KloFFIb;8(6xY~Bx-8|{1p^FF$k z<86Nr1+Un7+|povV-wBurh7zT9oOT6{(k>2WgQvsurOy267Q$W#~9IgYb+M9tc7=w zef;dcxOysvVV5_KCCMXsG z2u3#CEHUW3SDLt#yeC^ zXX*QY#O{51posyEck6D8T?#O7xvj}!MBZbWc3XGBy!p1Tu~U5H50wfw*G1&|g2vyu z+RqLU!1b`NPYdJQfGF?N{58rEK>z$6w#B#ThZ9P1O45TB4A5>QZr8-@pOq`oc?SmS z=ht;nA8$FN4y^oUTrO7dDZ{t7v>Au9QgHu&iSE<3^QZ6-i(-j|zb^LWEfWP6w{QV2 zntwrBn>=N8s|qJ|Z*%cvdNkhB)q;llFz*#|C7r~>iP6#T z1nUY#ty3oQaoOp9(D&!j-4;E*fM;NBo|F**Ge<=vNjDt<_0yQ#8(zf7xFV0N|L1NO-$k|{Y(2$uw7`&MP4AjgE z0;f7awm_9SOHer2ASaNaSeLA1)aB7@rbzm0qWy@0jUEk zzug}N?%x#S0&+h;Tzy-O&HD`t1H8Y64@k=+>OSRQ4@h(y6->Sl-lTcn6xShJNl15F zy1ius8ShBtA$t<G`ME!PC zn+xk@y2oQyhGwW+jMRv8t3|iRpH%|P|Sq6*y=)B8P9<~geq(0t0NFAjZ`R#opn&Owk0VZ8H z70nc2ckhgaF0>x>ZQ|>nH_0Vh*Pk9#z619lh|4V77rukka|OSm!-4qS3U!eH{MGol%E8-f--?dzwA+$*hCTj5a$O>&^08k zJpw7YcgNR+V3p7yl2u|6i7}I@DO-89Nm&&Hs{QyyMR>o0E78=QDGn@xEX!vik?j zTTOQGNhQpCL88318s_aiWb*3KY#7A*!F@fazc(22gT2JkzbS~((!fK6iGuQQCT!lCZQOGT0qQhAAjP#%R!4tj^2W5-CEgNbyyK3v z|MT?LI;Pj`XuPFAM8%KsP@lFsZuxL2neCU*8$-Xmm34pm#Ya)<<9!3EBL^ctPlY3u32^r|iVDxl{*29=S4)6b+6oU{ z?k}8R%X^HvX(R1z!*_VqWIw)5^SpCZDXYVCPi1g$?o#&_BjX)2V-`W;%^?%QhQ?d+ z#`$f#VBT8~cbz5jW-)mzAPXN(#P@AEW%x1#+Wtjp$cEbo3~L@qGv|lDy;akDBVW7| zZ0vooEo=THcyZ`Mkzo}&Z+h>=+ut6pfbd9M6V#R}UX9K>JHq|&Lq+Q2{mbib9hWik z`xL8m!|Nj_P+$Gy$LqJ)yd88Fr8QyRK@w4SQurz8-jWI)p29b1e*UMEqOcCF=h-s< zp8u1&8+HE`p8sXYdQftSS1PFo#kFi(i`Ii4Jn+*ofd{00DYrxJ!ae9cVXaaT{D|H0 zT0<`*UL3SxOO}O{pBLD{klbb3KLMa!TQAE#eGb~H%IsGQhk?5R=2qTG4yg0LK3Lo6 zUc?O5AaOlmQblSB4ya2BhjM%ugP|zu@Atp;hp-E&gA*e^v7Zudp{ATb_ua>=en;&2 z|2bYvJAOI*25G6b4OwFp^dJF#v$4*tG{3~st);Mz!DC;y{@p=tCgYtHa%~@pw?g6{ zUNqjOoP#fYVBU-=rVK>h1hz%p7clR&vEdbu-bFy=uEJ;7qrAX=vk}7V&;-!?z!jm9 z{Tu{6Q7E&7!a(VfM@McAq4S;`GgTdxVTLM@xF*L8>3zBAy#4ty<||F8kM{^tM*v2C zFPB-G%yV%9x-%l?)(5e9KVUDpV|=Rz68m=Q7JC&1kJxeNG!zmZ&^~W2%IdJyek++? zw6ueiCgYu`Y4n4{dsAEM8Z_Q65pVs@!Mtl!%g$E8yhpa_A0U1p&EEgsMxn?EXuGtt zXHvEo$Ow8Z={G(BtP2_wAGkjUAI;*X)NY3XSslyUdqUB9cf9Yf*<8K~+KR-*ZYBIF z)I5@htj}xpo!gqJ85;pHC`huoQcY7eWoxJOHA}RQK z%K=_H{@ZFae}i@nVl0z#+(@z z{V(v=)4j|WVvjxl%Uq4g)p;pH^Ss@zP*#WOa@o4Tq^0h?k&O4*`Iki`-j3%2xY2ko zOPZ5tgn8E`jTI2j-W)zIcHf108*E;w5Re=WnQskE4_WjA^D|HCRpuwa;zNu4B3&;RmdJt+O1#&J>)@}Jza9<2wBYm0UCCY5M?xyJwQKHP(Nc>f$TyQ!#U z7}42|FULXiMh(~5&wGL^Z!hH#>L$SbBd<;Do^*lr%#RLUJ`f55>UJ6B1v;Y6>%9j; z<+z4fAyV9!diq!Ka!1tpU;E`S0~0g#^`K`+9RMT08){u#nkzZMY+Awli*eXJNVz+H zc`s8hME}-|=X(YP^S{`+8$KD0w0{j!gu*%kcvVII&i`^`yf1|I{PX<(fk{RoG~SZJ z)u{xScN;I>hRC~%sYUn|%)5A@{qf;!9OP@Dwdce&PoSXmxcBg*36Qg|M~)@E3mkfB zw*Q-aD0t2C<3-ya^Z{wNDBGu6Usk9OiQ`FieBZGjoj2W$tKbC}_3_q1>iARipY!AI z;bedFfCJQy#{AZez~+6gQ|j)89z4_(QI%!xguR2b-o?1%Vu~is&;OToD62!{_vn#h zUQ0X3tz^8<@9zIZ>fTD}?d#BZkM-5mo{|o^{F?=uMB)n5 zR`f~DqtE}<1mlTJA?oA(5UJxnMt*x9HBU`4asqi5!%E$g*u2HQj2y9nc|*lzVe!u? z*g3gM{&XuKmLFYAfHym?ADxe<8} z$pr0Jzon=pyY7C0rZWyYBX(?~;Ac;e_}lsLt?mg>_5J-vXSpu$#b!2E`)Mf1#kbih z{X*x>#v}BdIe`VrL*jbW^&5Ja(YyD|``(Bq8S3M`5~*VvBfo3QbDq0Aw&h3TEp)#0hz87CBYXEG@o-}J)dF6-L{aNS`?>)K9UP=HG=GUj*b96YzxnaX z>j|L3F)`Yj5Kn2?f(SqlBx~=)5)OrEXqX#{$hFasIl8tYROdcW+TH*J>S2 z>f^19)Pa?s@326zG%F|ABH?Lo=Yq|9x65$XJ^1X6&$v3laU(YGQY`@`vEOnuKmU6I z%IfG3)=zyB_3!=v|Fk!1{slb$ZztTk51nv2IltQAL`*}FVJ@mJsUf%FNmPOv)vR%rdol zt45#yKR#{j7?fj&NOA6mU(t`oI-xEl!gSGY%uhs6uP6L({SmxD>JY-nujEsun@JM~ zU?0zIpRB>|L6whAkG!~zhmQGg@RKmYp8rSuC$6^m%hLQ3yDWgRIvT>W3gS|hme_4% zyt5oD&Xbnd`RQ>{G~Vl@HN}s^ye-!L8LokO7X|*>l>+m2OufHTCj|!`(o)zKRqY9+ zw`ql4xI6&_uQ3)WrFVnvJ1#m%FAD*L3EL;PZP0ngnFct-Rjh_4khtU00lPh9(Rn|5 z`ub^dC-w1;MCxe7$nQm1gViBAPGI;$K3}^6o44ZeQTj!g_w7uf=e*mRQ2(?4=RfPR z!asMLRcM|!T{(qy{P7Es|2rTlk@3z{Wt1iH4%qQP1dX@vOu5u)n0K&qgd>r+g~PK3 z#v=IcE%D;7^%*#*AYGPkbD<}=_HAvtcHsm_=k(z+bLa-CUa|`Z*+M|QM?j()H#+b8 zuFX)F`f8{aiF;(g-<$jveLzx>8_Zkvn)-O(M(Ws#kzZNorruxG9N_2Gme0EjuzCO3 z)+RUn8xL7)T4%jUX~g9HAkX`h?`#Fl^LELntd5Lf5gyTtOWj+MjQ6E=1z{xKnNtbE zXuM_4b?D^6ykF;^?XQM;D{gEMzX0>raL#iIzKVmm+=ecQWq5)tV{QCU$pna)j&$LW z>jn%2+(Pr|5TMy`ced{!I`6^XN2gyjvq9=eoKKyBUegD3-iy~abg+J=KHl$;I(}i~ zC+n2*Q+I&_wFj1;)^IQ?)?_cr%Y$8m4)%>l>m>pcNFa>b<;>v{kf z>wDxW9}GBK`AX{oolxiXI~#Y2Zm;2h*pRp~Td!NcTAfkeU> z{6-y9fBcB$02>BYJ04|X(!v5GWxG#vTW1gSzE5G{aTj(Ey4f3HsC!F{=9gHRmz34f zx;A!YV9wGGQjLsvuGxhE(h|$jIJgmw_sx%XGovtXm0qzc^)PQby7(#&nD^>sJk}vW z@DB31@Cw^fZ;%+KCb=zW0!ZeTNpha+0h(Q6^End1AX)#+fhZ1i-hLJbyH160KRPAC2(4*FrqSzqVs4WQZS$j=cIAjP!GX27Bch;CvqIaL%4&aj{8 z%5_5Ly(fNjq)CedI*r6hzZ<++<&DnUyw<2IE`$1b>mqfSVdVFn_Z0@`dQ$h6 z!$nA<@jg}0n6&}s-PFr`st)Ge7p16YAc3+v`;Iq$=v;{RF8)5hFjQTT#q+LpeaGne36XZP>gMm=c`)VBR5T zb6N(P9;5zT{@KHy`ItHxtU&X;ac3#31Ml!h{BYL4^Z!48{?z;nc>dQS>p?{q9slV; zjw^WN(0b5U*?lfY;Q?t)LEXwmxCa51M7o!759)rz-N1C(L_9)86j^%$qy6 zLnRI7eJ+bTD2W*!29lSe;v0(9Q@ zwjB`6nB|20k+?Rs<3&;-=)4_0-v*4;P#^C~qz*fb{EUaIQ|F#?0MA`K+P_t?c{A;J zndSoXF1qOzNXLWyfHYm7)Lfg^Et=;|X&p?q`sRxx(ZnxEX_E0SRFrik@ebQuE{n!{ zP%r0oEX@1n)w+)m%v*KdUP1%r{X28US?W0sI{T`=maxwk{Nz&|aW|a++#d3hgadeB z9bhfC)guI)$Kh2gr;nj_Z<|^B=P3{;l!U|unyszj=0)eN-P|*0)JA>0Es#1iG4h*e zdB<9Ki4&ZU?@DUhgv~puJeR$V9uH|H%x&TJ!tUO3x(*%X7PS9@bc0=#)lo3@dcF1V zQuo#%H#nbnh{zlFSYUexe0ggw;F?5c9u8U~vCK~3 zjt`LPeCM5II{|Lw1+lWU1%uDdKEYeAJEQWhJj8tRYYZpUkHnR1Ns{pS zc?@+CzVP`zH}4zj<6Vx_k%o~UKBMaLKr;tejo&A__+Q|Cms3%?T(BAS=R(??Tn#Y6 z@r|(3{D5@i1Z8#P9N5r$I&SImmO2^lye|^RNWAUEbT*^$cIj8rt%iBm)xU(u&)$Me zQ~M5j;2=DQ^0kzeK7davdRcABP^Z7P9@1JTHd8Y`}$9o%6$1FyE?wc8Ig>Y~Jmj1B^MD|7n_?LT{KNMRjm>nxSv+gtuU|0gv#D*h|HgWN^dgGwWEnMplp zQjl>wS`P}SigkaTP@>g&UU=mrc!{00-(|2Jz6Yt9u%+N9OBCc}_iXvxT7TfM>jmzK z&;;$RKP&@CFg=f*&0}_6u`0VTK zi!?tVX;N6nt`g4A{eeq6NL@1CB|&4pB;JLFFO<-Dvs7COeusJAV90TQ2=i`NXrC#A z?;xFA?wK9Y5ebDio8!xW`++Pr-FI%16X09j^txEDUhs2pIjg+SAEaJ~5;i&5km2N;Auk+9wso41;M zz1^ZQ9x^TCbxR{)pCHjODBWf&zD)DHDXpVpmu&0#zfX|vB;$Qc@No%=_l+G{ifFup zT&!4G;2k6@q5OFh%$w0vI`t3yc*|7fyypR2BqY!?8mcwm2O{ZKj5BSW0NW-%TzIG1 z3*HSbuA8zA0jRxa(-ascQDg?BsY~s(8MduyZ{$_ZbiyL}?#N8d!n+Uk) zhTgq1BIQKbMNwCS|E=wzKT^jmMt%u_Z$nE9;byNEcx9`U0 zUAr$RrcDA53GB0RG?c>Ld(#aWBy8iCp#9Cs7s~2LUG|`p<@Uel|Npc%YW@X0|Lc+U zpgWz>g~T4D$Q9$n>*7R*)`O%uHl4792c+I_hvi$~9^`Lj!m$^A#ZD4`NcWB>(GVBM zUbe`OK0wgt`|sq*aS+gQ$7wq01z?TnbS|3;0^ed-oMd;P&;Ku*;^%KB^FX6WoagUM zWBskiQJ0eSp9P1$t5RPN!XtI?V&oU6A9MCi5eEof?=O*-i`|2EH5r6^+4VrpwdN5E zK~GVCE+l$yZE6MeAMc|19VD+EWpx}BDYfV>&mavRMB|H#oaod1oJ*oTKxVo%=@^O(3B_4JLy9E$Nd`7(7;%`#Fb88 zu#o>#tAP=|y@mJwkBluZfXSG9p;KKDI4;j(ds+*92g#Rdi4&*ifn1O{`WM$v^fRDe zz3r2TTQFCrKHfY?9e9lVczY5)ZcF0;9n!eNo|mwBAH8(TFOJXyjXMo{@7#lZKq_}2 z@r=4Q?cd&#c#yI>(vI4O{rR?ZK)Q#F_wCg;)k)pkRd!Oh1<9W|{KEL}P*4?_huZwTjUe{i0?-L0A@K(C;{z@zS_SR<8LIyAz z0euLO7v}Ns0rj!|yMmZzftG54rtI%`VAHLkWuM+aVA~-ZYRiPoTUKL7@N@$wWQm)X zVVJgFDj)gw)}b+wY;%1%=p0~cAiaHW+OFMnG-}K^2?Te1XlT@|RfdSztY!%dFY<4hW3)-03|K3`DK1 z?j8t3UYx{uQ~9NRQqRcW*IUCNdvy6(N7#YQ*KS+(O+tUjJ|ZkMF%m`YXJG zJV;Q39!51?#P|Pu)2wKbYS4in=TpZL;TNRs*&h4~u0eHO8*i(@E6AgM92Z|$L_tr_ zX!;)a@C4ZveT;ja&j2&Ym8l%pPH;hc|E-jw5Rjpp$leg?0U`ZtZYphx`c}mY;pfR= z9+)h6dLcFf^Mbbver1y0E%p*z9#bgsO>wQyY%1Ue->hzKvu;PPK{S$`m{g57(2;`~ z=bD(B5PvTCpD%}d?P1y*r^vnr(G!`+6{q~+v+-*?NCpJFA6VSkh3BnxMwteQHy?A! ztzR&2>l~r>moV?)yMq>)@a?VdgU(SNGm#J*%S~IEVJ}eg#N9Hzbq1UXRA&P_JHhQ$ zyK?v85a8H;ujY{pGH(gVs=f+yUg$V(UcRSLmMlQ#edyPxVT$vl$6E}ShdxSt&Vm(h zzIJng!NHY}zn`P?PEB#VO|AI`>TjZY6j6bGi4D`-=NHVzN%p+M)QHQ2e()ZHVbxlL zbbx^O{a>xe@VsCC9;ZU$?K~Cb!VRw=DRR$A5%PYJJ)SVX7zuIRzZy*6-~~7@AKHrT zngJ)fTep;RcY^D!+UkkwA>jEXgSqa*?ugYpCUEk`sbC)HDQ;e8-ZJmQ5>Lb`6@K90 zp0^^T$2%IAM-WPUfu;ugc{;fOx8N^cl?Uj&gI`rVpDK9+h4k*#mh?v7L6SE$=sbTZ zmh5@c8WNX>!raG>3t?-#_Y?50>X>+g=grdgkP?aa7e!Y#1(>%HHa_?TLG|XT*w>u6 z5((MsQ$5;N8)ZS^H|EPDfOlKbN5!CfcL$N4o!I8uNW3NLz76hz zdAFZE-u`Fr4Zk>1-)ObGjERD3$7#1S#(RN#Rb49!lQZB;ZGM;k>xRfXe{=TtXMJ2yJZ_#&(sAldv>u4nyCnHzjkP-I_5W9Jc@&_;S3A(qV(Z8a zL~5JP8vZx--dc8V8GESTj`(xIuf16f)D((k_LBYPMEXJE@~9PD7dPu)@bCG5JOEPu z3fCYLf*Mp;b!P1aX@BF&dq$PJPnUul^p3BEx(9G8bKN_?i;)-?M)xIu~4mBSbctQHy>hg}%##+i2L zEd4W=100R0H3)N@>BsLpd$M0aVjdBhN2+z@`oFi>jR|-|Tctbjm)O>`V(@#oFqo5e zo)`xB>oGf@<2G*2?ym6nmsHbT<6+(@ihJ4q@OB9{lTyxC(GqevHLZI#2CAubKajk` z0q`D=oD(gY0S|T=)atT#f&DK>o_TBw2Dh>0A-vC#`~TXG&r=~DQ zh`+|2k$e1HJ4o*mTZ7AEJ4$>PjSnv?$#a8`T-GwZ^XMx`-4n}E+g944@*H*1X>Rle z2_y2Rz54zf`SX55TpoI!m!yJn)*7Tk1iWjRAMeBS{uMrpMdF>G9&_yq%=<1^o_jOQ zTd-wd@z3im*|Kk5&Mc3Hlmlg~JI0-WSszvR(efD}$4USB(qtz%Ga;=xBNPITOTBgq z+3pD;RVnI>-w&Qe@Im-_A^W8J3gP22Nb{-2q$XdfkzW5#iOb{HhyNU((6x@5(i_~s zV{5`d(MNRNpz)P1EzcXMR&>C;QEz} zm;QQONqW3RaCvB;#CLgRAd%mUA2{Br45ArD=k3ZOBF_)=?#-mL5lA4Sdb@375BZ5D z|LW~TWFECY_8xZU{=?glfcK+I!cXzMQ+9^aA@LTrnW}Grd21vcl>Eb6Q&R4;8hpH^ zciX*SlgcP)XnaU<;*2}sZCiObUONM#3Ysi_XLf={iuci{!a_lHd!IsI9Ww82%g@26 zJRfu)H*a_EWK&8IGVh~}+a2BVNsqS%E)O%5_)aV-zF*Gf2b>bv8%F<)y*JJSIz?{W zZHQMj{MD{It~<(ab2{1cen(^;6eiB??;0=v+yCPMkn&f!23Zi)plAA)!T1_fvTGX$ zQVn8AxN(FMu0h8Q3S`>h8boRMb?n#`6|GAaJ=^c@ii1i_8-8FyY(YwsSmGw184z=$ zB2SjK8||+rM0Ni}cL606F--G;OTC>e*mLI~;tNng6RO>u)|8MWn)seZK^cti^ zTpl(k@wwOW)ysr(gLU?*wO4h}`+tfe#jBa2?a-)#n1`P_`Uj+O`L{9%vmGJ(8uU4m zxIC1?6Z3B-tgRr;33xY(X0_pYZ_Q_5N8(-6-DJxT^G@47@RGs7^;zZe_ncY!E-0+@qUTRV+tj{T3HIgj4o~f?8F|$siO0qbPx5bfO#`U zPfOVvp!3E^oZYoG+llOXW0Z)@W7o!Qxh`ufNHYT7PnSy9J|OMS-CIuGAyy>b3g5q8 zQ-XPqsGWG!3iEE2OZ46Y^A_#)VW*gih1l3`40b2m0=HYLHd;|LfWqT$hWWiNpv!dF zTtg@j9QG;B)tEu%eL`CKIp2PM$QU>Q)~UKctGAC$ktZ-B*Lm zyV%m*u-}gKc&p;_C`5_R)PjfiMKl*UU3Oc!o&}w^-KgE-6wEv7`I5Z|6A{n<|ETDt z_n9So-WbMPMCIYU^7Fh;-rC~iFahuS{Eeb`-qs=^%t*Y2G@Ki(VcyT&TJ2uLytkk2 zes2QvW=W1PKPnRo9U8Zd$eFhTQgLJ5l9@9gBm1MbibEIRZs>b1rxOIipymUQUm@?k zwJ<#8Wzpw{PUGgaCz@o+Q6cyLuak`I?~all?zM9|0m_P|DV|4{{JXJ z4QkejUVH!lpB3aQnN561HK_K=zF#Q`Wm*cf(=Xq`HOP~(#r+n%f*iG;EpM)jhpO}* ze4AN13IeFdqpSDK0PhC}7azXv2ER@#HZs2O1COe)#dTj?5qFR#5;P3g9TbG{^E{k6 z>IG(zFR}Z79G>(3CWiR;{gdzi@Hb<)Jocc(#}ysOM4Qb8>KP7a&BUSCAhX`g3gxr# z{y)XK`JO9{s5R)=m&)j!-4kU04$^XW;_~Q{cRLi8x^{`RCg9z~9XE=<#OhuB&4a{S z``Jg2>oD)j4G)f%*T_$Z$^=M+q&2;tJ4ZX_<4J--nV>Ehs^uZ47N>*lJqXIHn==;P~vN& zH~rD}g$r!v@DJ-hgU&md{dA8E%scA(m!c2>BAy_P?5i;Tv_ST}F;qn65i6sn^!Ip+ z6#?&;L!SfjyfaU>a3k?9{(frZG0dAae(F#M%=;zfNqsK(?(O~~f!-?e@sRfJ(#D`n z8_?Y9T71}I2JCj7<1;(m4d(WhC9n(mgVQF|PpSU{@1;2IJ?sqv5PqJK!7JYN7m;~a zWIW9rV<$b{i?}>)pv33T;uIPBh6_YGyWFq$Lg)Qx=IW$TKs)qnjJbJp4mxk9GpzG^ zQ_f_+f?O?RAu10p+V**a?6vBBgn;)8=$9v+H&5twE+pPU&-1h1!n}R1+&cdT=53HK zclapG`+$fUR<9!t@)2iO=H{^l?9PQFG{xt!*=dlQg(ZwqfUZIdKD-rI0_sH4O;2yVpAYH)*_nm<3-IivFy z332?i7v|0UBKlWC77=%EmD68*4ESGg_f{;8xIA_j(8&C)-j)QspGU}b;(0%obK^wf z-E~jnU zACS&Hn&mHiBLOme7$oVo=?K`Rr8gZXI0H^-RaI-H_W+aOBNfIceF4WwiO$PT$PH3; z&U@#l%YqO)Zr(QWX1@hD}-h1+wE>yuvpkI%ytCBAsm=r`s$oWL}B;1Wv{dJXy& zH5NlP*9I-W>bYEh9eoE0Grd(OUt5dpSCE(~;_~p^z*=|*{tQx>_b~$A?F_nhc;2TE zeicIEZRs-fQ3d9GNHKh%6Xvbryv!v9^X8VdIHd2I0B!c3EQ#|y0xIP#*>t34z=Y1M z&Z1in@O-(aVN0Mdh<)wVwQ~b9?=!p17AI~BLil;CZWpcFrIC53{BnKWXFz(q@p&Ym z#Aop)j6>xl7s%l;?l6Ch&O21`%kJ;G?NHf@9;crt`U%qRRQKCSS8B+fw^bT(c?7S& zG}V>3_Ie9D0^Y5?LiTvxZi>$Zk$C6Yf2!4kdCRhM@crT4`Sw%SgFF>2n)^-FK@tg2 z@T;LW3Y|xQl9kk)y21>&A(#8wW_J&WV}D9>UD_AC5e>0DBaZwADNY9wC!XVi&|BO* zpr7m#0l%3-CJGe z!xOi%?vOq2GeqVgqV0Zc%isRrmVo!`;)6qY-s5pu0!X|wTev>h!MtxK>KeU=dB+dN zK2nBx*G0=QV_VKbFMiYNx;t8df>n81VYL~+_I`bQi*OGJaQ`~-%g7ga$I*`3OCs|Y zyqD);D=G;2;pTnaHorCX05b0kBX)_8Hl)X!AD72Dl=y^F51A>`a)EKH3uEzj(5ttv z*_jajJ?)Tc@y_1|3ZA0!#-!a7j{I6p_PmMCW6y&I*}wh24FT_#FlHG%?`m&nek9&s z8?BE7!MtZ)iJyH3^LAamEf@~>|1!f?%cmXBLZ9sIw*OGF1|Kv}8dHE7kkI{h;QN1klxAceSnt8(l&^T_Mhi~N8--*b)4{_>?& zjQY-xpk7WO-Vyy%JqMjP79jk{zSw9pjj z?(h+anQMh&BWx)I+|XB$JiERHc#86q{UugvH*tAfRHqEwUbxo(I}-5jq*~y{^FDp> zvjh_FF1k}iPhsAgb4TCz!n}D3g}a(y-dD4)_9(R{LUB8pi_3N!10H>;tHsOH!0TmS zDKpcs;_Ktb+9+)?y!6Mxs-lx6!9XG=bQl{2uq50`VNGtNWvSZv~ zFyCBz0#M9=Z+@KH*=c$~S^B{d(G9+!ybJv7@c#C(JCw_)`3+?pS)&uk2Rkx|+ zG0fZOn^;qYP$Fde6?_RbGzWBLa=|0m8PI&n+GF<~^Vj zP*TPt3{l|bmD5TxPCZ2Cy(&I^xb7n9@$Sdvv5XSmR+SqY-K#jk>aOvm=y~)83F`By zSITaK{4-SSMdZ+V7hTNix7x-;_6?H!CF1fplQPb>FKdmr0|D<2?-&2{|8mThqDZ_M zbeDPQ;Qn9d3%hqW%p1S=MoX;}*m^wy@(pEN7-&2K0#*tvb2w(eWzIYKdmr|IFz#Bq zoMd0HaZizee+n{h4No%+#f%W7h?|!e$J<$(hs=AEj-T17d!)yED=v=>DDl~Of8;$b z3g6!HmU`VchR%C$B!%Zun78elixLSF4d}PGm|e!{gRhbQ{y!6uc`%ky$-|2iX1Ix= zp}2-&7H80=v!{-Nzy0?=r1lel`~Q;!HE2Le;357J%NNNZhg5?~QoX!)!k5^D+jjSc z;2Naxky7_Uwu+WZS?-dJMG_QNAJ=o~mJA5}yzy>z!!)>JwG_%g)dxBSdQNgH`T!4! z8=a9^$Tetu<9czLa1rPvZXWfQC>?VaU&McFd2`--zI+pfNbScviOVA!CBA@xtlq>0 z4zP^*pfkN6eFb?@#UMVSq!oHiqo8NUir)WYc-(&O{4GfSD@bDVpc-7S{I@}JBjDYS zVGhFc9=bUpgTxyv?Ym?O^WK+kIXnpSe*D7caYv4dR?3{Sh=O?%ly~S!`<5zIP?CA* z!ReN1z`LA0I5N-+?)3)mdZp$ACP%ZH&X^(dmR+lD#Zu-*rex7e%; z=OPp7U1H^Mc?hD!cQoynd=bO}ZtkV{GQJ6&cY5ukua!J)(9%nGy|9hwD@YOTubjJO zvdEry;x6LyD7LLr();@asVf2R-scvMc;38Cx7Q=_&Po+H<_7aFnzUg1!@F$Pi|2M1 zRJ87l=VhvxB|)}SC2yxfwSa3M#YKbn(_pJtYp&VDUf_Q?NJaCY4{)$QVXUly%saN} zeb7+}5y%cVZ{<;H{HIuC-tN0iBTtBu9&dae&M5IUhB~$$<>dtFf~pxlis-y0sEr!3 zVcu6SW!v4EB4P!3*@$gI?h@Ja#^e#1$7YpV(toSB3jyz*)D7qGyce#7OC#}?s7)9T zhk0kV*JusEyk*QIzqsbAXcgp&mPD8)K`+c+44kvr1NuIld%H3)4c>=`nXb#~1zQ&y zmZad%1r(DMYsbnW^XBBqF=hHG42j_8x!swLPBcO0UC(4xRj)>Ryg6`rJVJ@jcjwnq z> z|D6eVciVGI;dzhI9$bgSn|8r6CL89xvY_wX5A%NX?lY%4ygAV*#}K3p^VZ5gpx57Y z5GZ6Vwj@kU1Dk&AMmg_Za5E!c^-h5g5D(GStky#2t=x3?a>#pONEA1(^R`^WPjzJ8 zA{#mG(;Jc=Z+sqnDDl0FU49UAfD;5~rd97FV()Dydx%gL%sYgAxY}O(J!&ZE*I`iro4uH!(HZ;_MxBue{ycrZMc6c*{>k4CKH#3tBa`Rk(9Lq z(q06-M?R(h^YNBvmfkBO@#Yn{eR&$@y+ucYwqj@o`4aoWTG4&)W>F{$H}64*{@x=~ z$hWsdEHMM?tx1n}GcFGq20K0o z1|ON+tVMgS=(Qp9{1(Phe}D0 z_Y^J=!owdVBT>rk0lJlyrk| zOVKFg`+gLecL*iV6zdS_@s7jg;e!(2_veo{1{ZJuUyR$aQEPPG65T@8+u^;p=j$lv zwjMyQ-rxMaj-}|akv;E>0OImU@{7+ftp4}>|Np(=Cb9n(?*9V_YS1U~*Z;i#k1?M@ z4XFnG(2pE(Ur;Xj-1BG;f(9}eF>Aua}S;pS;RYF#+=47vYbR`+wTjuaue z{r@mr9!n_kRoW@F>$q|N>I3z>R|Ofh(3I?LD8Cf>;T6OZ9Q`C-2)+Lwkg$n+5l;U7 zzkwKWd6YjMbNCpu*8lqx@SYsMUx>fNI=^e%jKo{fe|TdA%-d<+(|Ho+ZRc?>rVr+A zbHK5#TC`5~!#}MGyL%kE3x50bwtJBX(k9P(xkG&}Ijj~K0 z-28}T@Ae92SH;3J7f}qX4^UO==4bsmRC$7XCaItN71kP z15m7(qQtBCX}~`ALZJI|ABgzPp_H!d4b=RmTxI{m<1N zcovHbq7W5so_Bm5bABo^?;;hIw+RxY*Z<4l^0Ic zn}t7Xh7NVK7hV4R0&!3BpEdj~6-hd_TJqojze8LeIl1?O_29d=|DONIKBZQ6dKn9e zsoZ(c(`5tAzyI=5asM>XzwduPW3V6i{IJw$Df0wDK00mXrpOOSOSkFPm5GT#0l0a} z>G@CQs*!6@^?^Jw)o(&1*Z<4n@~A?IuktaQ<6gKyQoO0>t)7V9An`YBTGU$C1m&|> zM4Jns_y0P}A7!pCsFD38R`MHhc??JouV_ZC_5UFRyk`fKRq&Tsqw*&jNW6o--JRxv zd1rTz&QHU<1-5v4N5Z`CJKGqXT#bc3H_EYrk)u%Uc{wvqlW7p_B(j=Z-w$M$ek8KAO;QN<{bHas5lPK}E`)*EH z8DRrh4)5H=Gw8f`eN?JC4fFo4o|GopiQfNXu4l~GD3E{uk0~N9kA6S*N5B4_{|_eM zJySZgi04helCl+vcYc`wwLHvwUVf484{zP``zd2!-k(gIedaXdptjMsHeai)p}b!f z)l)~NL9%nvvDCtTU~y1`M(eRBNbTKeo4V+X$Z=f$lt9BrQ78pB@4k=Tqjm{o-VD46 z=NeT>kM}e#4|&(4s>lV=a|AMI^&v&L} zWM92UJ`tBkt8_suSNdB2A4I@=I{3#wFDI(hJ-!8rcf_^q%{yV9Z-0IU5&eG-XG5aM|n?J$4A@DUO3FfW;K6@&#I}XatxYoGgyd`uv@b&o!*J;oq`$9X^u^;f4 zpUQIC8#SK~dj%yp^En;uB%=RMmn%t~P$m1vTQEfCF+#t=CH%s_ z{Xgk8{RELkA4#Jis6k(;W)I-|{|0{(TBI7}z|qNkA+Agd`o1}F0j@#sTHl>gfKQN0 zKiKhP5X3^ICjF&~KaWFP3^y)YNKb>jmqAzeog9FlkUYLg(#sQ6abz3MT|urv&xWEl zDa?vNcX0Du><#Bd$zBy#~vMlaa{0-3y+vroR(|cH!o+T`+IzID^bv^hSqQgbeBN_QvHQ zgc6@jgSyeVKz7g+5YiU=0iE~M^nS<4fEQ48aj-~B2oWnt{}%IROL?;AjqxEe4+r0M z!#3Q1KHlOC0q?~tj%$y%{JDE;Cp1Te#QViJD$}Ph@4`DFrJrHmwTsgNn_=Egw5?j5 zfw9nq;neMl&h}7H#Idbio2P+B_?CDF^#QPHi!lA}VNc*dnYnf45c2+ikwNw9x_U9_ z7;c`^C*|OjkI1|m+1q{H_LCm(o47olpv32NPRJnLh#goJhO=FGhR)kYMsMs?@=K@@ zgf3g_px?d4oXGnb(O*UWyotl3I$mKfAhfhCZonLwx2I~?lj2KakN|F8IIrLK_GDz< z4zIlhX5n{r68c(t18Wm28rnZ zqx-H=w%j5A{r@Q9^2qCvt&4d4Z~sp!{|^3R9B_j~OHhM;GM@CtUt+yV^qG)q&;}Fz zi)wHU8r&D8`wgx^;rml4YTtVLsgd5uaIkyxqPy(fSd$$9yc#{)9EF1w?M>8$uyg(lHM5U)gVh;9+N2X znOe@ZZvDjuL=4Zl3~pu8`j5Xe_z&C5Px$mCG(xlXnir|*h4;pp(Sq zkxK1z>i)I0{-1_`_ezV#+DGjExx~hdi7+DZHdDN|R}bd>a^cS5uQ2Z^lQVUn;1y&o zze61TcnmaDZn;COz!}Oaod535I1L80dohA-1E8X$hU;{PC+MH&I5*UZ%v*hAuI{ja z1oR#^uSG@Gs&+RrZ?7K%4BI(K?*!>qTplM;;#=3`(7UY54h9mw76mAw^R60h3{pGS z2)+B6es^Fi`u=~I_a!O&Y!0$-kitBP%R{4S(1g2ejW;y`@9*i7*YMTb-hK#+#5;K- z9qUn;cXLYa@h>p%by{}oW8k~D{5xXjyA@-huXjdYTbG`IhWeF1cd$=`rPDsyPpbz& zk;1ew{2A;ZYc61$7A5itQX}1Cw>=pppj6yEQyv*FMipely|45MF z;jiI;?%q-n@Lo=?$;0zzfBT9ai8oeoo24hr`}e(+h$RBvVdh*iTFK&20&db4+(VM81G8^ zP<4K?=Z$eEGLPK->$4sH+`UbsB;fr`RqLO#w^Jvh>5zCEoo|ndhIv1v6*;{~!29{9 zxLdbmW1-axw+3Y}j?nCd3geri(}1c@Smayu0FW9g9#wYr1e9sdfoL6DX=u9Rqbms2zC$D1}#7K0JKf+D>Bl^m)L`QXzWL^6438gf9IVl?tz2{ zkXMkgH`N|k8k1fPGQ{N(g%aOw?E0QsJ2qhaO!OW{GJEMdDSuah9f>zpRQ>2U%vD1=G9>%{U!2H1qA#&jJ0|^kyd@3$U%V}TXBa=n z^R9K6U`66BxhE3y1Ll3&<*e8W%)4^e4#nJaDq88~?HpI?qoE(`ICTtEyrEl7=`CIh zQ(&Mm*2hb35Om3;wq2ux&;S3zepcZ{=A9W+4|U9mL-DwICL!}>OMb|_S5BKy+`d72 zyt8n5d_{>bT~;cG-Wh%(D6uwr(jJ|6B!_QwAIw|p*7PYaZS=dh7_W4?`Kt%Wo;Svu zxIFBlnQZOy*KTjo6YyR=+FOk0%}a5E1&O!MjZLN}XhiidL4{ z?~bbnVj%nG18-8NJfNG0tnTevo&tI_rYFyE4}uA+>a%CEJ%P6FpcNAa`S#Y)6CoKE zh7yn_Zr*oUVT|NFGVh0lZHJk1Nw5F6#pO|j5})fjslDRg*}yBq+xu#b(RmyDaet>; z-v}M>zkV}28@)k#p!(bFx0edpFHSBh6PE{8=7R72oHgEb1iXLA4j#kvey!!tjKupx z;v7a2=6zFEZObyuyM5!%lrETej)6hnY(Nb3^yZnUOET_|>sF(Rg4HP?Y7@;8zd8UW zv;2=W7kYxC9UE+#hmfnc_pu*U5gHOu9&Vnd0qt)3Qe@t5e(dx8^@#L%`{MF=jS`=A z-h;#6wy}fxep&ao`_Os2sO~%wqXbI z;r?IBy=wEjlYph_$MmC1$h@K4dfu2f;t(BfUUkmkZhlK--cfc2<^?OH$GaYvMZ{d=R{5wdTPILe93Lu*}+ zW6$6IpM`)oO|-Zwp7#lcHf|)|ylF-8SupQ!G2?W<;T2@=mm%jVnD@Sk?CKb76yz;v z87<};06}x*8S3w+K=X2Z`pmgOAhD@!PXFUcz|VR?t0^3rH&3~peOIG6#DSZ)A|~c! z#E;B7@cM1rA7X+eSH1agdHAEm_d1~LQ14|{@GzwEs#*&=@BHV@nhneK(4+3+n+v@} zRPX*wQ}GNtvgeKIB`y!9YX6XLg=-BGGXZaE{|#z*-eHJ;cz1vc>VbFhUD0*8)$>DTz&!34LM z&7mY@-eGj}<0l@%Z@I(G`=LYCw&NS}2C3Fo5fG|Rdb}fWdF()mPk(QU7b6cFn8}lu zxcvZ~chg<-D-Ik_q5ig~cS4qlXpnphL{3LSWY4?Glej$mSkweDp=-RE2zXN|ROjP) zv+eWaMB;re>SlC zFb`g>pmiPuhYwk>s>*l(>Ikh`{VN9K#9-mj!KwDAsf(Fpt~@B1D*G2pGB=3Fz*ZFYM+*hh&bL-)TQPTr$_#4 z@2f=Sv3ljnzx_WEy*DXLf%|`Mf*Qo!l`4m?K@*9xB1km|!^-iT39dn=Vy*17aDx=t z_cl;58b1F&I=ud#Uj(H2UU#(pa3I8Z=8@yx+fyKs-9ZCOKLl=L)K(Sv-9V)OXK(6L zPKY%_lma?uOe+DM!Odf@T<2nFgIt3ox_DGx_wytEegD6H)Ka)S#8Kkob$nZ+@5=@# zH}x~=>}A$Mi?{z~+(pa@c$e+cI=#b1M64k75}yPmb&!1x3L`R)iUUsVoj2Alv0Mba znFDDRr@^xq50-t zO;@U>K(a%4VCt_yAoJ;Mf&!l#5Se)2k$w=FcbqOne3C6h67Xh>j92_{fRz>E$k@hxK z-E(mW;O6x&76XHB`5+fW&)Ikn6-A znD?)DKdGo--cLR`EF6x3Urx-;X8d(L0$Ms;JYZQ82weyd;n`O|1!CCM&ii)3n-fLR zESL&6aO&RC*og^b-c7PKN$%z1P!Mk3@_ELxCSBy}Exi5OfhJ1QyL;P;%L6UGvwnsT zQ}WmVo&BM-F>Z9;`O-k{i;T!PohL*bZ_y0(4-a`u_PoQ0%tPvap{!}iTJ>fp z;Em-|a=`P(%Aepz;vGG|i}MJ~o1Rgaf)eI^N6EeJ3(ULD>zGB1U?kL6=efkz6bL!T zxAZ4Hn*xUKIHqZy4T5dP3YQw+xdFA}JSEyWWZw2lkB{|dibI=l^D5e~bmt_Id8eCo zd>7*HJEJka9vJ%9Swr6D%(J@sd}2@N`L`?I!c*6`ljrwB?0aVvD*R`(@0c2y~p z{rmr35Sd5eLZOcme0%HP^Z#gF90~k6-2V#@)F94hTj%jLC{>473aJL&x$tnTGzLCF znyjPB2-hH|;hc;0a1ELcEx*=*iGU2-`_hw&{2^?wC(nlLDNuJ}BxQ8-5SU;$jw^C; z10`ENYTrDAe2ZP%dv#&kkOXucH}C8xkpn%LV1V=!+cuJsoy<*oHAn}S2U>j5{t6vw zob2Gx$nE^0^XN55x>`ZIqPPwc@%3b0c>D_S=Ys!vUA>qQF!^zo?E8NMBJ;4!7<_CW zy>>vFpMW<|g^w1VdFv{~NsT>UY@b=ArlhpWi9l{A?d3 zd)^I1=0W{@+N^u+1?g#g1iaZ@W%cm9hacC7Bk@-DQCi;t^X`2;DvgDC$DRHVstEHw zmgF0kt{efm<))TQng>8kqZ9RZ`BQ)^PfycLatQ2>o2Z*-aRZenv2DUp$h_Abd{v-Y zApzaS&2zjWH(A|@yn@`u7FuhqL3+GpaCxA`*VI%NZxg}>eqWU{ZB0P0-cNTrh<}8u zH~dk#k9P?W(f>OfJ+RrGO^)nh|pKuK#&(Yq=@u@&16zqYfp$Z`5Dh zf>hbS-XC|eIi1jXAJ2XNoRO~{TDU=%)K-PwAYnFzmX7T{N%s9ev3XcA=}I#EeK`>i z0dH1Xc4vI`?wvCdMdJNpm>;tO^Zpd=#!CnD#_zrH-^w^iSMONZJlfY8(5l%S~W06=Y7&?!>@+p_0U7p(_Y>BMDX6ITzW*omh7u{ z7?F8Ij?Ne9z#mTZZ~u?)zDW2h-2aOb)FA%;q+R$L#5^r7hg5^sB~;ws57!{!ErkJW za1FZfH8O1sUP01UPy2oj4Tq@DNuLfs=Lc=C_?ddJ5~Kt#K!TTywwiyO$*wPeGS4W6PZWD%xLei zwe$ZX1ibmuH1^~ak=4CAvj*4wU zzQi6pS3ec>lk|8S;_@&=iH~NV)$7SfR&Z@r&fj?$optdf?z4e0z6lNMdoD!qUWDnz(`T@&F6K|NJPad==@rf4EVq$dJz{7QWocmkQc~>f~>w8xA7|I!4-L-y&h}&Bu{3buI*pfYO z%n*@zur6Q19d8jN;LXkYOc2joyuxT55^t>4Ez$EZZ+SH~Ehd1V?hO8(G-rlIwVGGn?nO4Z+^LlQ$2CWadZQKbz|9@j+&OR5xaHzxh$i~kp{*dEQrO9RY zDImAus9ize5J=xUBKSzk1!(h@r9MtazQnTb{>{uHEeUPM&C7erwtcl0xdx@*%5B{c zM|uqsJ1&n5l=x(4C5?in*g&LO+lEv%7A-U|`Yqbm%Ff=0qOfY;xpmR+LFSpB*>xOR zNA@*nvpI2jJl#G?Hy*dvAW0JN7O6b&&ntG?kFP2s@orZ>rHp|uv0g#ix4B^69(z)x zFT=d0l&zT_%7jA;@#V9ZPx?bFT&oXbyr;mPS04iJc@KfCKvnxYLM~uWPt{TT6Ue;T zW7T3ysU#sC+&qCTNlTA>k$H>lWN!KyOM1LHaCu0e#HThEk;*K^4o=nQsr_D$&O1w5Rep0|Jnae3Uhpx9^> zvvzt*oPf8G4E=pP?~9%x@<_bzYt&gu!@Rp?$J01q-tp|?uD@d8x3^ePOiSp8L+Zcz zjgN8oL+WikZg+yFz`}`ppYNX-0@VBH&?elx=kL-z zUVcID|1~}v#VnSR9&dkK9-1iewN+!;^Zz%9%p*GWg@6?NaN@uHKUx<@0)Gzo z|FQ%%Xx)9z&G<`fVhNoZQVp8ZdwBUA-2bm+XetQ8HAwb*>rPkr4N_$j>%N4234_jO z`%ZcX2SPPXhcC5RPXVKcR1{2^L!j!@en}4j7qGWZSD~*IxdzF3l~RBIDG6!g<}s}_ z8ES?hpZ~uuswy4ZLV7i511=A=_-qs}IAyuAf!FTS>Nm2`YtYT$q`soQdyqi9{FMXn z=SZVTV%fgs30HU%*>8|;Ng^%}<+x)D+R1DEzYGCysjzdlc;3uM-)=_Ytz6-LDIexN z5Xi(M0Q2s7ZQ*MS^ESK%e9M1^K~b)^_umo>g!c6>h)deRZ;*x(-lQZCfsxBzvUf#X zfM4mhY~O5T-p1VL9#4!(LY}yJy0OXp-TKJ9&#|WHeds1V-iL8{B%#FDgR#GoT>?KK zeN3g?D+--=E=x{D8_c_a^3@=d9uYf8-%x_ zFa<7_)ReKD9RgSLRCg<%a{)7!`{^Wfk#~^zcUYc!|5g(Eh@02BOMld%1(|pCTxzNC zEa~wU#N}}xCB8!H>bNQg`02P1WZ7d3$TU z^i?|-ws2_g=Zl{-WCEa>bH^-RJ5GVx-mHbQT1xRd9+)?N?=AlFQ6D;yaA>LS5Hm%*Kh&U6byeDR3VgKr&A57c2;@kO?2m^} zZyi5mAa@}QnfJ-YxZ&GXl8_y49)-l48=Vi4d0(BXnp-bHdb~Ywd7#CYeB9$;lOH?S zR_4ngun(R0L9G>6Bl+YoDd-t) zp5rzX5fi%*#6I^&>HMpjLeg77j^Oe@i?62jQtk;eb`W)IMr*1My#_gMbg(E^xeJM@ zKH5}Thkl6-Gn!k^+eQ8lNMquN%OipR(XYkZYyH0h0dG0)zVG-;tU^J91`=;ql}TY8 zm^YNUO|fI z8@7DDOnSWWd7#Bdccv_}=oLG-`8YGbr~#dK1m=o=EX@1Nwe5;ccZk>^WlL%;9yB3) z-WWY1^T-*s%Km%2Wdi|k8MdTkJnv13wp$Q+XW6}Tf_bZ6D?K6%^LC~<$m;?hZ#h0+ zdTs7w7_>L1i^aw+2-@QEiT9Y<6nJX)RA}h<$`1V$AYVzaExiIKXVOhUWb09Ry&pVr8IR#vgv+c9FFa#1d zKay3HZ~;NTMbnkvAy;qBXO>&#xuqa)+`JJjdh?`4WZprL|52I-(&N1imj_yW!W&KG zjw!*s@72esUqk1;o1s#VTjL(2J=&u^a1XtDhecmyi?aM*@ce%zae18E6-sp(e*XW@ zNufciIt=Rq>j&2NtS?v}vX-)5W=&y@VD)7^!D`N`$GVMGkyVV9gO!@)E6XHH4@)yk zEz2#I0+tMx7?wa57ZxiP0~Tc#DHa|Udgc}8Y32duHs&YHmCQxVIm~C7Lz&%~ZJ7@- z?_ySCmSGlPW@1`p`ph)K^p@!vQ#I2Krd+0T40jl=GGsBtF$6QXF&t$uWYA{V%plFc z$H0L7iJip`Vc%dIuvOS%>;-Hh_B7TLdkkxW)x~bX%3+1DELaTv0{sX2_w+C5AJUi7 zU#3r?kD&LZKS6I!uSdU)UXfmmo`as6?kn9ST@PI|T`k=$x&pckx){1ZIu|-CIs-Z_ zI%PU3IvzTD+7;Sq+5y@&+9$M?v_-Tzv}b8UY29gUX%ErvqE(}np%tKIqFJT+Ofy3B zmgX5vHO&p0T$*z?iGn5k$fc?+2>^ZY)(z^33wSN0@UVw3Ts%bVZ1V9()4xpSJH*d+YuV#|UCHW5F% zknuYbn}8pk*FU=+dlo;+sZeFX#^Xm>(+6s>arjZ@!^;?KEPj-6;gTgb20u#ATxdt@hx2w}PvA!&lC6SabZyDrrUmYla^kG3ijp zn&L;6lEdGyhw&rxg&h-E6a2_*^u!|87(X&inX|?o!jBF+{tU+&;YTKx>s7FZ_>nRF zVh#2neq{82*t_#^D!2Y&;JZXN86!hv-o}zysN0l8q$CQNZDW}$b2N%%PDmQ0A}JM8 zE1Hyuj--+ZQIayH6z|&3zR$Ja_j>Q=-oL+|y?@s^|2)2@b)D9?KF{}F>t5?#t2c2o z(Hf0x%7=~-tpMwXwDTg3HfWO3PyKr~0A^&!XZ z5!a!S`BvL0q8S>kd)4P5H-zA1yLN0D4+8a#n6cI^)qoP z8d1(6CW@jF<=9rD2pUmNxg-js5#>-oq7WKU&QK#RK_kj-Mnpk0qFnw$6hI@&T^Yp1 zXhgYMfXI(Vl#|$rd}#EzV_1n;fkuxqZd(wqqR~U2fTP56Gu7ABrUqgzYceiP54(TzbF4&oU!s=TXvgII({*E7AFh^Nu$nk&a0 zVj&t;IK+J>ox#B4Mw_I-GUn1x2?wchR^W}?wK?s;Lv3^Y3P_M{6j9gT|4 zzLq7Xp%LYVYa%ZiQ7!}~@}Lpr{!}728d0vBByyn<<#s;eA~c#e?V>>BL?c4O(`!Ty zYP4-O)Aliuh(4=qCz;(RokWcg}EoQFo^@4KCe1T-2eBuM#H7uW9+}s=u6~uKKoBJ8uB^Y&OU`kpQV~**ngnW;Ky5M*(cFx zpr+yp`ve+&%<-;dA4j8pC(lIoF*NF1<2=ni3dhL*%pM5;Wc1;4Mjrcjv}MoT9&`3@ zXw-dZa)NyXjoyb;*sy;^qb^y|8uno{dPm^e%l-w8-ag(&W*+S z1Nalf{uYfMCn&vQe}hJkEVoCpzeb~n64@>69cXlayfm8q6&lqKUG-ycN29tTRSEW& zXmsypTsV6h8i7@$zu5o!cmF>V%<|y+zXr`aNXn>&@(z-+{;$Eli4E%=gDk$Ec+BLiH|BYLt97^)T6W6t3fM&~wCYB68qya3a(1L5d$- zLsuU8hTRP&MRV)_>NLD5!*rDQ5)K(wEZ!}p=9PVrca!>2q8#MC@|%-!#y$apkEld}Yy6EeJ4}a=9YHrh_1$j7EPY=mPn8cMeEpHV$sTOpeFGJD^IT-X zVrsim_TPxQKQ`|rv*Bt3ZyAsG2WlQdIQ`4ZStQz(&Woh>*iEhA#pfOSo}l%d$hBsy2iSm|9{KA68TjQg-*AK{B zshjhg4CKB0$I~X81P#Lu)O{Yv+ zwGT2Dm84ol#^(L>mer+A=CWXz+HS?T;|_lWoA>ye(nm8N7?1Z8Y913f{o8jy`E9cU zA98B9WiN>XpSNlF=`VqD6~N7l827D)j?Y^@MdW*aGiUk*Qo?6C^N{afNj)HKB@J)N zixiaiCdUW!v3LhZ>56l}1ya$krmv(S@3&VUlZ_HJ3~!$GUeI404@RvVG(rTUfRK6a zL9g{g$g3>X@%=ZuktaU7$mcsgNYj-a1+3e!dAFSOH(jF+Hz!it%@{^4N)o{4{rU0G zI?iFnFR!n?Qfg}dypbt7Rns*Z1d>4PX{^{ILKWAo1Ltp4CC zE(>I+?f4Ym1sr6@=6xCrUDW)=c)Za(@cMUzthf%@&W8*eX&!$tj?epfd5y%Aj0$kF zs)htc{>G$nCcIBCHye zZXO>J21k%d$%Kc>umjfeq*c+q|vqnqCE@iwuNYAKw z9Kq?|q^0^~4*bMU<0CI=I0%0Pxj#iGR7dtQnA)D!6v0l%H%I|(hjx`bW&R1$%wP27 zv39qS*54mU>(KC~EcT(iXQl->v3SdQ>q{SkynO<*&nrRR9oHQzNbvO*@2W}jk%w{M zaLS%t=8}=1wZJg{vF;G^FsXMYx3wGj^xh(~(#99Dw9wu>b`X1uon`s^+;{SFU@h9N zdB?@mtkIaCw=8;88}FdVc)ZtB^WetmU)j>YYI|>9q~9!}MsFKF?`!TajvWyz1t(K& zWj%i3?;s^?U2VUo-jV4?kc3JDy7G`!Ws?c5oEt%E)9|LOUZcD}7xojec-yTy^(Yte z&JcWkND=bB=dQ)O9r6yjBC>yoGakr*!6m=_BSG}!<&?8}L&$X2lld9V-N>u=idA8D zzR1JiD}e^l*u2#`74-c@<-k2^J6W=t*1`AK)mt~Iy|Mu3^ziRp_qhB&T?-339@^G@B;duOMZiBQI z4R6YJ43szN$aYNL76yGMFGJpE-wfwUKXJGK@^-cR;j_{p9$0jgS4%&P1RY3V zQk}sN5>@@&UZSxZNlh``Ss&z!kX_m~?>UamJE8iomnR@^H)^{xX4)r;JF$7^SFYDg zwr4!v@zgv{;q-5#r|*Y-M|qKk$49sBS&h&8lCGtDA>_Tj)Aua77N0la^VtJY-5;5r zH(}-sU3o}OW~MpbOrl(Gp-ID=vcCxBJrx(Z5UYA?>sYq~$U9|eg^4`mjjp{#w_P!9 z4vz;bt)2?~P>ljN8`TrHB0~tb{sphWN8N~fRd#(>m@l%$Z1nJgBiOuG-CHWKh$siF zsqMTnw!HJchRu6H?Zfv1evHRkmzoC~PXAQxHwJKd@gd@J4{fbh;PW;+RU;GgryOvM zHSa08fj>Ag9UL62Toc6fWABw@`tlfzJKimnnECJde~dB1|IfXEHE1VVoFB0`=5(ix&A-Et!hOoFILfFVTE^ zhVg39Pih_`IQ`qYTTeT~krx?|w%y2b9=`_J^gmcOnO_V9&HwC@PsINQi7*^_>DYW5 zrmsPSuk_`S_*^1c^Y0U+3}|>$whW`ZgAQu)Ve!7{J1wjXc^8q()~$rRgLI_HJ#YjW zt>|eN*%1qL7nkcEk=YCOmG}7bsSY8IwJ+~&>FGx7Qw257zxG9>E|LlhUSso~Uia=* zYzPU6Q`@->uwPv`jLlnivO>*aDdQcn^NX5?JWl_D*Ho~2oaaT7D`%xRa`1VJJU_W` zo6H5!?td`HHVFUqmZwWz??c-%rsuuKjlMj752u7Hz)$R8_1351P1ysF^5zTg;KAY@ z5c0WoHRK)nI8j~|^4{2~dhQ*3d#gGB%^DSpIB?ll_1BsL_<{5rveL^-s*KKd91~ z$7CogWd#ZH)}!G~`KSZs9pZO}8;kernw_sVLf&V(<^h4?|?CLGU)~G{zF9(9C?KYURyq~>* z&HHktfkSi&;|)&GJj!tTCnMF)Ar!!iH2rxOQ5BER`!Xl#1z+ez;3aWq(_Jq7-CG2W zKe}$A9`wR~{F3nRRafbJcql4R6X8%mZ-LK- zYFjMizIeR+{56MA(I_TuwCMe_Q2 zQ|2<@y7z_GS`UBh&DIjfd9LUV)ANqrORetBU_1lV%mCbx(D z5c1(>VBxdjZe+A_q@44B5Avc_V>-MLy9V8>-kEs3SPnE(+m&f^53eU-KVns?S#0$a z8E+5LU1}b9{S*DNz*y%ZAJXAreCkdIehpe;nI(LB-x&}eUnbLY3;!Kt~-l z!_&kwK%BdQgsj zb!PSG^H3jzyd`AyD{t)Tox9(2n{2Ec@S?UmDmMR*TRk@Kl97+8SC23r?`&!wmvH*m zV9W#FiSQxOomSaWcky|Lwl;24J9!RVUKd){Z-LKy#%IH0ujnGC=e^gDzC5B5xOXhb zo0}jZG`uNCL!i6^&t4F~;_avDUNs7Nv#x49uK{_F^~v0M0Y7h9l^lF9|6mMYuW0Zc zdb1lu*Zww|r#ys|Ph@=mI?#>W|MpH@pTif4_r4`*!h${j*H)GOQ!^|FVyNw!Z^W7L zZ^a&*^!ls`9Fu3f36dr?kA9r~4V6AxXIH?7^wcR!8&u)*KJ>kEcOT^KHn{%YH+pVw zy=SN0y}Xd=c@ygC%wuBXg51B4w_HQRn{w6(%6pAj*kUZ+`TpBVSmFF%^-^JyI^^9s z)3!|&@>Ym64Be?13wT4Ho;2~^10Li~>awW}Aql4fJ54^q>n)}w#VAwjMX7_>i-!dn=N! z;PW=$7Wu#ruDw~e@hY$B#=pHqxQh7tP7(9J-s-BRFOS`RoJuo?{$2lPmihlWni@no z?Fp?xx|~YOFl&&9w6rsP#BLGzbl(8hpd0GMyK3+oB)5Y8C5wilz?RSPs`8-`fW2^Q zS-A8NvMqoexiQg=G|gMnYNG3dC_4w~5LRH1AfHOz{XNW10!q|&l>v7)e-^}k#9qrd z*r~OL@kWr3sd-$->EFzc0psi_KEywpTuOXhDhH`Rnmj>WsJ&1+~E%E07b`Z4yoC4vjn00tyS@OQ zcfW$`Bd0_8fP4Cq;-x%?d`a)k3@VS|JZlEt%X&FnX9-nGLDg}dMaX$H0325rmdKmNlCQk0q4d|n2u-qqAR z@cKvWOc;?E;6->`$|GFn;q!K}R?yN@IStN;eTV9Jobo=lUbJ zEw&iDde0|EyB>>Xyz0G{ng?G0>fA;}gXH-T0r5-ME=}W4kfuhT-dwo+G*~nkrn2}p z9Un+1tz0F!Esg1U6OPcChm`yh)xWp5n9%U1oS2I8o~|T|VDVP8xSw4Dc{ki%rJxIW zH;W(aEr-1M1Axj()@ZQhXSww{eS!6NM6 zj6L?Q>%UqNTqg&LsqGZ`E6ue0u*cq2H##+f4l^EaK+OZMf3a8G_e}NkBIR~@H>C#f zc`KEixFmI}2uQuzWbCDbKlUb^N=R7Obe-wf{|Tq*%R~5&bkqHl|E~XI4gMMG-^2C) z4Ky`~a%MDIgCv8cWwB}y-|HvQvk7H}t;P;%#;^v(zCRc97`}t7`}F>0R9h5iy$)2YsP@F1Aej!{-I(P^0=#Iuj_<>I zU$D<0IafMy(S`vhNJi8=&g1kifUHrp`7$5kv_@uQunhhPa&NV<#*5P_K%eEriNurm zk66vb3#R#O!c6~&-F%q7Ja)b1pNjtb{69+?-jqYoQQpxFQ_@(xC-*E@;)jpeLml;G zBgh*$Rma5wAF;7+roaBYiUM0}b}m4YBfx3LXLV~N;Q?uU?`sjrd)kaQq-`e|+3V+< zXLcEzx3Yby$)GI>L{QsB`90KoFjdwOCWEq z&&B!KQ{BkP3%aN6i^+&ngZjKtA?yhf@>pe)gDDAYqqZy7_1ss#9D9Ov;XrBrwQ$Dc zZ9vTfuYcwPx&?iee2DA2Mm<>(eBK&&QlF#qQl8-kG-_R{o_$0xr~c zYB8_Ro2X;+=F*Nb8;oK+-f7f4xN-WIG=9kbJb@qK0y*050{Fal5t1exv~$24X*Dhb zb^Pib-yoM>EKa=rPc>)KAG)5>mxuo88LJh^bG*%IcvJ3OL3y8dcap&3eYSA@S_{a# zep%F))sXim>mGh1`1ZDvJ#<)j0It1V5-XJRivYr6iEo}k-V<-!Pu!pEMg-rzsbFRI zK_31*oyq>d zs3=RgSo7lZ&aa8nRnyG@$3=g?mo>%bO?dQnZ2W5$^Uwe3&Er>6NIu-&!Ug|t%sTHp zflG?Rc%jFF{qVxe_`RV0A6v-R_sw<-<01`V=LTVCJAcs1x8H4nW08I}aKM>+E$qrS^O{iTIp zgVJv<8EpEV0Cq?k-j0c+;~gabC1tTm5#}F3^3a#ZwYZ(r*Z-dX+tBc)T&0Hc?qwNN zz~cQ&+-_whI8Z72pJjNyl+x>7<>L7k$p7h(^(Qg+jae{a4~Si=KV3C;e>=AE;O%S_!#m|Yph*t26>;pOX9f*d6yxsf;lBo;5QKA zFmZ|iDtwEJ-63yVjljYp$osq9BNNxXWJG0mL-s%;HgAC|7j&0rkpS9m!uVd%R%LA7 zT!@0@Ie*6E%}31xuYX-CCIyq`_PVqoO2T-YZ~5^%Pvvg(b|VeSiIE|Wr|)y-pM;9znDVa3q6k~bHT-l zzVXu7g}0-C6Jq!L^_~bIzskQO8S;+iPnLIvy!UbGo|26tBM}a@3tqNj^R}|Se6lc! z1j4E9IE{2e+hwqMO9{Hj?F?Z&-WJq6q;dMU{P6eOrz`o9-~KODO_t;H{v#&#=kuZi zVBXRnoOcTFc}JF&ceUJR{`tQqoq4EU`TE0;Zi}xG3qUT>A zZ?O)`+a{2A+|or?b0F_O@=x|}Y=yjSA~&wgivVrTW-qQn-o3S_yrd!T@~|^&wGWYz zrpe;fobRxCD;h4`ZInO)jnsCg-oj^;B(Zs4z5B7ciUGH`kf?c7;Ph`QV^CVimk-f6 zVJ*B|5uf+L6jO^wf(L+!HSem+WB7*?5nOklcRN$c{PTZr`tsOS^eIK>)W7Thj5gK( z|MmyY|F_cAAjfM@u>_}oc_LSYzJ2FKYMYd1SU2I9Sv{Fh3qKrOZ(rhz~UXrvz65j^8WQk zNX`oK78ww_P2s&Uz*s~L9<4k6<;M3-Y2kqHPt=EG$h&{*1^VzMk0~3TqiY6G z-cEX@%dvO|9XKKC19@+Allx%_dGGJx$fxkG*AH#Du{H`k*gfxtZB;l(jmVi-4tXbC zz3li1@@^mmd^_bvMp8s%>VosId9VKtY+_nTAc@*8Z^(4|v<^0JCoP^vDJRC`ZBESt zuYaUs{*QbI`H+Hoj}hW}eBQdpo2&~UZ}&68N7dNq7(p6lc{N%~GXMM^p)(KnfkySe zH%Qyk@V4*u9z%KW7LHWG;;rTP%svY8ws}r`Yyo*+=vos>;k`ukU96L96gc-}+vN6- z;b5(6-lZnU`+QtYQwHSCQFGAaL=734`u=t0NgM3NiH}6l_D#=8V3OJ{-JB~5F1%vy zQd+!fbC7`#_$aWfdVxoVI6QlcFR5r0@-|(a-?0_)4saJFiPn*k&7!K$fde*g&ZsuY zZIJgSYP-BEK3nysCnS^uY2P9$vQ=T#CA_`r=~7G@9N^-sO{ep zz~dNME5A?pixaUEWtL+^Zl>pb<~x0P98$W>awFm2@Bjb5^KC}^mvH{?NK=E{cAWZW z1Sv{hsEt*FVlJDV?%7vns2JE|yam=E{Zoxj9hU;de!0f5c&? zuR(-q`tr~|7tedAVD1sSorbroq`4OQi0x2#sfopV+|I3i9P;j1dug#PM^Yw0myw|xcCgwoiZ`r~E`QAqY|I)nY(r3az;)Q5G1oGarZsops z$eSzak7wJq#APqacILdqK+Oqw_X09&c`H9xOQh zt9|S6^6d(Kgu`UXQHAaJyn{Xe`dR)p0jPKOf3zNJ#N|ymxLtbQHx8!fO>Z6n+s$Lz z&&^eD2O8eam3aXuZ_h{{bu8W%cUSIT3VENrpnuH<^1fWgHdzaKZQSQeQr}IPoC9-HCmB zGcND%NpI7PQWKe;cR!tZOv_|>7uTJlTyJ4d!`mrkcsa`ZccOtB7Vo=?&t9y6ye$@7 zN!SQ^8)fScQ0D*AOBV>3a7F>6Kl_$~&EY`Cyti@<<{b;B8^Uwdm*pf8UL!{aMM{=NV2|9xsOW(;ePD@_d| zTR8SpYLGVn0k1owZUn3vly9+{KLJjVv<*~Mw!<2vZ5q)|*&r>uy6y_=)krWi=4+tQ z8v;58&rD8>4>~8q}KOZO$@CMjSIF*Gwg1*PsPq+Iuf1%7bmxcJE(0vsI>H zpFv_x{JyW50S`!@Pt9WkPXBVJd>)Cm@FDA;L=aXu;6GwZSBQU}cQFAR^*<=Ma4-G} zQu8arPAeTE)6f4qUecFG1IJaRTPNm5kS;X5z4=U6ppRJ9yeE2Cydypu2xURu^IqG{ zI6&St`gWzwU?9`e?_^iW_Ljv(7P??^1Jhy?K=V~IVsp}=lK-yvzpyJ^$? zz8jFY=l2afjsiZ&&7j!lkA|^%=aeQ8j_r^K*Qo7SOcH;mjbQT@)4O{Y31d9oS=2m4 zaQgRnc8&P$zxWUx$?W(rI^N#4yqw*=(L5IH_St@Fr3xLpx7v#jNay}9I3WEceR*gP zEU4I=GFQEwX?Y8za-+O0m-*;o@vg9YVsIPs{;Q(5Xe;E+^}a1e%vj0V3RxurM6Qmbb8tS z9-Ft>v71Xn81VEKerg^jIQb?7{?~x zB)sa#eAmeQ8>9*C^yR@OexYX7-nmDtCk^ia?yc68M=XW6nXfb}7ViNLuLs(Ycgv~1 zS34l@C!hKE4a51r-r9tadXXrQG~(tcc`5{yII}Fc4|$v9D1Wnty!$0`WSigwsb46o z?#^>;-lgN}NoS79gI;R8l5o#^IaAn=Sk5(vc!e175qp`M2N9=#jgtq1o8T6^CB=_k zOxxkV-m*60Tw%R99;AvpKRzFXzrE#neL|HDJM(}4FL{r?Jgy!2E5^QHZvEebhPU7A zNIR5wJK-w}7VmGH#*VCqyuY@jlsQA*Q9tV*ynwv55v>Zj-;uyr=V@}|xe(AB5O}B+ z@|Iq-%}W>ZCe>cGs+{M8j9Hq4H>KFT#n$BX*FxUksqOO5J<@Dx#^zmJygg=`0e6s! zQuDZl)4$(!QV#O|d`PGjhn|}~K5sWA&yySi@u2EnQ0|f{{12oF3&bpwCQmZ`1c~r_ zDP4KYm(gB!uwt%yyVLOYt$ZSi^1iNEJ0FX;|LRxkoFH$L!A1L>An)a8V#~`RZ?sS?j6df8hOqcYc9*nmjl` zZ6^{@Jh7(%oA;E1=-#>n#v7c}Q}dX>>7PCSgvw@9eq`Cxq(6tZ;qzwqVl_Szy$>WC z2*yg#aY5R%V*~HpFERi3{}Bi1%cDI(rpYXRu6n!C@b(E&n>%}(GB|0OO`3AI`rQvk#cfaNBJ;g8zDp@Xea{!HWXspZ^cjm&cvALK)xS=Pm!v z|NpO~f<}OI5)SwK+Y7tfq`tqqZ@^O5bVN-H#ofoV@E)vEv3*r2q zy?va#uR997NC`MocrO$fw*=mLLm5G?2$@(0YtZ8<70Uy`WTe+Lw{ZJs>@P^Uf0X#> zOpyTE&X3cp(S;Mc207}N^T$;z!Q8U<-}=MnqUPa%(?5F~Su^fqyh#1WKqD6u{6}p5 zrqJutKX!qNs4|7pBXo=)ZGX-#@ET?Q8e~sj9#u;ZPP*~WjUat#cn8l0{)LVpt&+t# zv3MV=C@6jndAFR|bjlO*4orG^j2-f}_@pn~`7{dnuT{@<$O;AI@6BdUA@Atvl}Gd- z@4aWQXPG*XkvOm|iLDl!cS)oFu*4V%#8cZnT)pDA`77)#b~)!)=r%AQ?+esCGI9F% zD@v<(z9t_cdi9;Mni)QCr^4iWo<6%l*NJJ76)*95i_Pmk!nZYq=_g1vEOh1(q5hz} zA)T^=)Q5(5&~x3n1JWqfdog!E5sUY0wQ8F$koWbp*$@xNTVO@OCJxAZU&0BwClyiP zvhqCJD;}ZXn4&u&AShImN+s(0voCALfZou zW}d?4-E#X;qpfD32PEB!WIy$3QU)hJ#jAZ}A@5tPWB8t8|UgsRW(zWCWg|{~i@16UEI#Ay4 zt8*7(@!oi>N1YGO|IZu7$htw^!Tde@cpz^l9i_hIAyGg@ZeMtIe+Ur&(>U)7es*Q96X#zWFhD77#n=vQgzl2isO;sbB?uvT{j)Kw``Q-Jy`s|;Cf4X^N97G;s1C2 z|Gzcm{Ga{4um{bo$U5#B<7sAFBqDqZ4%e;UhLlf75Y)Sc7bMTPIh-8gxn2 z#{K%CXwb7Tw61Vp7^tXkogIfYXqkDs@GxZu>5Mqv{s@wY6C}d#z7`e1Z_Gdcr!$YvnXBbL&d$yMchd0QJ^Fhba)kr?%7em-!HGg3bF>nf43rI>zIT=5Z3Ie`a5~3q}v| zA@*-I2FCU9c}I0i=?ja6fZ?sTv-)`Px3|3UUu%a5c{BY8GA@9=JaqhP{drU7R*(W| zct<>VJ9qv+W&WQO`<@4jcfir0^y84XqEs&83wifESnMMLdB50Gp|V#x8f<>8C-R;% z49t?IADw`_RkwVXH~@Kjmn!xESGYjxoFcvI9yae4ns=f*g zZFQP0jK>?z;}}l=^e=68i+aS1OzH(?f7Zw6UCX}D$O`h-waBOwxlhOZ|JdMQ|0_?X z=S@hZFAuG)hDGj$bJaV5hIjZup4Djec4#=ujm4W#G-Y)b@-Cl!y2JD?-~T~f0Yp*T znO(MjWbz-X_dV`>tIQ9K$6Jk>$6cKMxipE4d=cbBbop7;wyehIy_BVcpuRB#NGzMU zv!V@ugLDmBsZ{%ZQ>GuB{KY|E9=?aQ&n-PP$J?KVcUY^-MwIv6{3tFg-b6(XuN#oJ z)`pc|ylHsf?2C=M1$hrF9@=ONd0!M>tXT?q_Zr5l`$FDIzpOG?9>MD^^xYj3xv+WH zReSRy8S(&aw_bHuVaX=!wKv6%LyKRpV?5sXsCmfa^v@uuS;KxYA5z=uz%{)FpZ5k4 zv8@wUA>fzRO-oV$9rJ(fT~+xk+nAm=L7&b%ScSs7-2dJG|390E|Cd_B`F|Kq4T@W8 zEr8Y_Rec>{tQs_BB%QL2F#)&->DWYY>OF}VQ1~jl)yFg(6!*I7 zIKVqd?&n5{UV(Rz+)~W253ut=q;3ZW*q_3#K{Aiz5*GiE2a?ow8*kjn;8=z|f^11N zOv~KQcr{3xn#VJo{+;bf{+&*DqsArrepqpb2mHt z>qO?SLFeep<9LVm)9rts{})QbJ7)9{8RZ?-PZYx9eV%yxs}$r-_+Gv=2=Y#jzIcst zyhX~ptLGv)Vt}RK^A#+laIk89eaj2@iCs(9xh?zQ5xWcbdGYhvO~A z0*^lz{UZ;WsqMxZpRN2rz~=p@CnWV(3ght}rRMPyr+?EU{8cfcd`PoG?WH%O_>WjK zJ|6D!r}|(|SJqyEA$;B)Z#^qNtop_Dyu0qwm&fER>!?>-24w{)gobzYRqMIiTPX8? zjhrSyEZ*5qk!VfG`}m#N@tu(Ou#164E#!T?%tdkJTQnHV-F52e{BRI*Bhx({^3M4A zJo5|W9r((lZi}H0^7zX-(&|v`>b)b~c;h#s0(eAir+41x-I}l1BS_&Sqt%Y57>~Cz zH4g!t{%zP%b^fOhFCz0P?+@EDeBMJBMfA4sn%IR-Y-{{G&sV=3AOTd;Z?Rih|rr${p&KYc_SATv;&tZ06}WI z-x+@H$~@TBd#rp)HtQzi@m@pCV+5yv>05a~#0_5LF$Hv>P{?K;==I^ub zkS+0fugQ3J{7rY{fHkIi9T#Df&xK{UK0-Bv6?c@LKbFUH~x3eBH7K;E3o zM=Ap#@7k9hgjJBYyNHWIQF%0YoLsV6{c0Ex99McyIlX0hoH+3e{={HIJV-{kvD~Fzr9ZiyXPX z#feh^pZ7Z5bJ>A3`S%|4S44|KV>7 zYtUYr8gxKJ{+};MGjA#`!>U2k_4d)%(P?h$!=sq<<5d@N@PS~Ci?L^1MEFW%OjJQGqiqv-8 zZKA+)H})Q+T{eClFVz`u50V%)j{uzhRfT0-BTMoi&J$q3wSmVF?{9HUww6P6-5x~C zlKX}3H2x!&aOnKQs)eb{UxSX*mq+Byk>9z0uORKA;hos8>4iRG(+p?Duy~(dbminj z$Xglldln9PkFke&rb6B?1l$(OU5o)W{D(?7@4-iG;>}GSkT=p$Ht6%C8*wmH*DvKH zBO*7wYVzh`^S-(8gs^%U383xLgW_k!S7Gzs`!wj>0S(6ET}jO&0;hlFf{n*4Px2rO zi=Q=Dzr^S5Y`luC{LWrvs_OF;rxHHz2fdfpi{51Z`M=~>`ttaqrk$yGGVe1dI3Q z`K?cWL*CxQH{3!XZ*4V6HywEX-^XBqq^%obK=^DttICRSFkb&KYznTunLd!REBo1v z6yK^ec;HG#COLC;k~FXfCpNF{iz!&hgK=uR!#x?u+QZn@`~5|$cAj>|7zC~J5OwXI3NoO9nhHlCJ zJO9UX<&!x7{> z{@tHEvSWa7PwYyKbs->=v@R}DW(djju$Si^??#B4e}r~PkdY6I>6a^zW(+EE92FmN@^a4IQ@%!Qt@@Rj2kg^$yA98z<Y)bY3>mlL&N*Xi_EJi@4V|H(pbFR z_1nw*A#YByfln0VeQQaqR3hZfo&C(9<75nYV6g1%&zumTZ^aU@4)Q)b>hU4~@|Kr< ze6xW-M%+FvQy%+_J%apm<@@hS$lI0LZqc5~*8`H+ye(VL*m*5vJl?;ld6?t$PjK-W zkM*)V$aA^Yck^QLdG`u?yM1x+Ms9oVdB8i4KZ3lbcr|?YlX0f!-6l<69*(!ym+d<` z$2*#a_u;Y|Cs5u6iBF`kcnd_BpNN6HcR6mdh=jarwuVPWL*7=ILTb{dV?ehX$2GAZ zA%HXS^3R{rL&&+k$^paWZ(5`1NHZ?d4Cmc|IwC20%*I*=49O~6W9}^ zZx62XKI33K-ow;9hH?7W!fC1CcA5wAiQoQN@hCp;MZ2$!7w_;!?i3%IXLOQ|5hRP% zC9NC+^N%3s)0xMXV0ZPu=l@YOybtBv??QQ-e9Mu<;$62vBOn#>*65sAz8CVoreD+$ z3VG`Zs?LNK#{d!kdtlHf6g;W?z5Wd3ZDtZE9z4;Flo|SQTB?ze*_h>z*le%|CmnB| zjY?*a0NRdY(NSlsBiPm3Q9`@KLxAykzoO>hfYZOgZ#ysWi|`=(y(51smg4gkux0TV zs|Z5=h$yeI8N}bcMOgHxCh*x&=I6~uUmiONQS0n3&sFb88r}yt+K>-P%?OIn`cm_mb^X3hRK2MNjJl?|8Jh*WBx9tu|TFH(V z$uqxna}~hn9XZPV@%p_z$ZHel_^OroA15xzGM&6~;}_HOUXV;*9-Qj?B`?Qj{(Jr( zW6bdXb1x1!X0XuIpfvGi(P$02WhAbIRfDYEqJ!tb8l>`|ha&;jpzkK^%?R8zLV)ENQ4$T^Wb~Owrp+$nK7S+cj{lP#wc&n@lOg^yg$~S zndXPQGsxp(@sRf+4@1@$@D;o0>#=Xv%VL47vV2^JbueJ>V|7i1yoC+Sj=7C?BPZWo z)aUFbBO_aEM1U^#7CW)C-#_;g<-uoaJLg4F#L53~y`}i(N72Un7?1ZdY932*`ZuO- zGyh>3FH$HWqP|WMpZ8QyM`A^@C!(iPeqN#eG3LtJKef&1wM+TnALi#RMPDBIpD$e_ zB~eC@8S`j(A4~ss66M`KR4$LjJ5sr~To&>UaYl7r^y12Jk)( zNBYx)!P=?%Btyts=J{gq9`b&+0Gu&zB_o$*x+pH6 z?0z%70WR|RN!t2$*5fZu5V&(Y6!$YfZ^Ew=^yLvXqL$|;NZJ1%N5eaLdFMrx_sCld zIV|4NWWz1ykoN~Y!E-T?H@f!L$A3`A7OuU0-t$n~8m_$!HaJeFL*74nvz#X&@6Mux zBO#FYoy+g)b}qo?-M?3V;V*u9P)lvM`J|^wnHzTX_R3{hubRSm)w_?HhZ|1+N^1Vp z*}x+Y!qvJLm$>5dzGd2Z%VT6K^84b28wQ~NU#$K)LCRr*xDu-d{ZMOrbuqTg@P2Sa#35LN^u8A<7xxQBy&nhR>>Nqx=x^WkE>v*l;&uvHQBjF8GOEo^|n5pOQD`4$`QN zuF{P{@*s=aZgi5D?Oh!9Cw8Z78-EuhGhPjfq2__tKcO`ruXVNXB1La@r?S^@8{(1K z9aWWi_COr+AuQE3SPcJyG=fyU!}!$!rmsPSwe;oTZSitf;oSOv#zGq2Sv9Br*&u!4 zMf(aY-jA=d8Qq4wKfd_jeh~70VgJ>s8}fehF!UCoD;8`|G>gz04+6@zM6r6(5K=gu z-tg*cH*#^>Bh*CS2U&eyGTY-9_9OOC9#^;=uRPGEwp+7s$*LP0v3YN+E?T2_fbn=A zrsm;*)4$r+yC3}3y{%t6nR5PL1{)3U%##J%(GjFu%=zV5yax&fYo9^hETtOO2Ow|BYVPJ{$U8jj zUV&b9EI7MS_t(*pAmF+~(9i<%zA(C-FL$IHF%*;b?v(XGyhPos4>V%)4$Wzw=;f9N z&eV2W`6lO=NMZA4AGcK%VZgVyVbna>aQZj6a8~1f9WU~9Y$j6d9X@Z;F6EfypuLEl zSk`ls4*U@$p;SMQ|3(1QuOJcX>B~cuP?z$fXm0+`O2a!NOFjhU-DeP_g2lT&nnk4x z@{SG((%TPt|8=P0`Yp=fgq3A+R!S^55+8Cw=5r8O6@ELcQEmuXb@}rtuW#MR!*4(C zH%a&)w{6Z`=(>Z=Tjl!er`xPP?hIJHms9h&htt1?_~hk- zl+#;fuf9|o$LGCBVg8*2uLvYGbHjC40O;`oK*33JtZ z0S)hTl@I^S|GD3qDP!>#+!+3B1oD2Tb5+KB! z%^P0N*g@VgR`UX7;M$vgaHqnxdt^j$O&!O7w?<*8xi9P?< zk6K$b&4BZNG!I>z{;gDr?mAM-i|l+Mvh?`>fOl=^`=a0H@HZ!Jamq2Vxa7w4WAD<< z^yN`qv?;wCew@e!Co!z^&J(z#IE)v1EZ7f!{P!P5`xAg8NG_Thls}>$gg#=wu9~Nf zRfG1DmR+}nHE6Tp#oA<8gSG^3AN>Jq5dTi%QsKHdkW%E0uL7@L>(k&xte(4DO036!#HuwX9=&PfkCdd1t4IXn*C5GJ>q}yX>X^O; zC48nYk2JQ3{;hd)BgjQGyz`ny^-$h2?r$`)cz?TD``Hunb_n}WdKB^&-diOy1$pa# z>^nT~VjR$Y*1X;QKrmRnda1n`S z<*rMu_i^X{1cH>Z--{Ne=S}z}NnalN+ixrVy}gB#hWE+L*+i7LAa|h#7H__5Y=j8N zyLGEyVG`us`zF+a!aJ8^qc<4| z|H#TS*oMvf{F8K^08bJKpthU$*62^-6gKZoA+8F&?--9ang?G0qANvv)wOw%ZKX9c z&SChxo5p#k*pBT%u3UO`)Q<;${Xf2CeyQz%8`Dpa2#xgR(dOPL@a*DT_2!`AooksS zkMjO029EG|)q;2AemD_k~x_P7*jyZ5OiXU>9XtXP}+~ryWMj~%9-lj$kX>{c>LGmum7hn5{`|HY-D=g=UC~> z<4t5@@<7%cZz2uv6XjamC~p~CV>K+^N2JFRPC(w00?XqLL*9h#$*(EAyF4tuoG^<6 zGlvtlnaKx(d3J}>X5iY}ubxdF9gz2j{ijRiA@6Oi-3lMBWAo%E0&V!``ub%KCf^wWr-!t%ek1Ah1a`Vn^q%wuKWt`nMA{3+%5bEfA_7^E|gDWZ(jzu*7=x2Bx`v)>oa|M_WZ(3!U zRfD{?e^Z)?fmiHi^Uq6%HOSw-uht9Jpx#Bv7ZX0jgJXY6vb3f{K$U6AmU^Wjgwy`V z^oGH1#P<+i=R`RCK)N?Q?(-t-SL{FLuS>lt0k7Dlw#)T4{nES?`yFIk`|Q=4LdL5> zqtra``d1^oqsOS32TA!UwLpD_%MkA`F|UT_!6F$eBwFZWx7d3+KCyeYN$#+0*($vM zF2n!&T^qXc2mzuW@0ZR!V)$6;mC!!JMrL6rM=0Mh7fR6@l)e*$UDl;`(7dB&6~D<-;Ql$#MS3xjdoKJ%E0T#J!1@lswyF)H8xB0v5kwqf$4 zzeKV*qTH!^rCSnzfpqoe3;u%NrSuq{FHQ$-1&Zm)W6#I4s~!Jd|L3LQeLDP81InB8 zN!ltb-W57>>m?!Y+dJz%rb6CL_g*?3g}l=|`88gr$AhYMQ*w`vg#gWvUz=SZZ)1A zTx{MuPizSGtYkdiR@6KKar(FJ(T8&#a=gf`1F@2PEAV;eYu~bXXY7V}SH^YT`GG${ z8q7Ideyq9agPcw$REuy@i zra<1BcKi_ykhekJp58)IJP@1TJzO#!3|NHp)B54!L}#f+1c1C#yG@OC^~lImTQx$$ zf8c#TCyCT#N&@$(?S^dvS40Q#ZF!%LAa1FSr?!8 z%RE{3rRHu(>W$eI&-3W`_V&`d=ocV|>3I{f>CA&wMN#?R`9IE3k3oJJ&i{pIYEVfl zF`rU{DD(fjE}Ph}YLM48uiKa4{QpdBvR)3XK@W*DkELJ@YHm1E$5XWrta)W|L1Q8m zD3U(Q>{lK_a=spQU>WE}jxF#hW@{rOO6r|q4|ZYC{{xD`4>$zCGf1fIB)`e>`K4gb z|BHuSx4DckUJdf1=7HBg(-l^PHILyDJKr7kgp%;*|6QZ1&n6ql$P(2Hn{zwqnE$K# z^t}1z%KYOmOWeN4tehwJNL&OZn68mI9BC{F*fg$ zOC-&@!${x@wOxy5*()^?Y94s~tGI2{WPFhqDFF6Ud`0-Y<$rm^ zIX`eg+#JNFIhWzj|9yTog}1kMFg@>V@n*X6kh#Cqb>#2)zaS0oV&8{nP~OSoUs$ks z-#xW^@iWM~Ch(D57UUg%-!M}T^4_R+Mena2`+%;z*UJORp@8@EdPgb9TTx2x#YM>b zceN6yQw15(as9#BAdbyDwA}ghOd<(rP}{ktjCh$CVe|GKNY_kTz<8gx1W@z9>)&L_ z)^pr<;Pn2+6T61$`BkZ zLc!^q^Cc(Y{Qp|>UEy)a+n{%!Mfr6ylEAS=D@PQYx6GbEj_ynnh^4mM^XARhO~%-~ zPqnT$kzl~{|HP?z6yo&np0z>|mn<)0aycg5(KF2*T4CQSdnLH1RcWA6h!7$`qtSrx+0ePcq zZ+Y`Yc16Lpw=*Ujl}|%y7297^nkYdrTg&it<%Q68`ZFRe_pz} z)}#cEy{YY9t>*Y_w*#B^|6%VwgQD2Fg#iyiRDzO&ft<6FgEXRmBozTAiR7dp83aUv zVgeJOq9g?c5m2In%2q*8BpS#HCbEc1FaUlV?0N6}>C-c~WAz)tzvur`$b65N2Au!bko2IUCp3$%*e%Tefz_Ltv3gKnOCYy3 z>_Jz{j#;L`9z>yUkTU419q>9G3sO!UuB|%~1oD_RncS5fMf~2G-=_W4kK~tK zH;|O`K(sc$lx(|)eT#kcZTx!vt71S6jT`$TVk?)8eGihi&&PeO0_6=z185!GIQebA z-06SjH!E^vVud3ATKpcgPo>c$Y;qeyPiMGy4v?{eObZ=XAM>LA9@I!?9o%&SDT_z! zB&{alU6^vKop_1O*u}ww#d~j5`EgIkoB!nLZI>bM&NQ8Ek&w6P38nOl!LdMRTYMHn zXb_;&xN+zlZ!#0w%EMa zO&_^ZBTsp}521A^;N<5U>Dy^0&5Ddmmo6Dn!{>c*Kh2+O0xpR3(W<&9-1zhVc`N?6P1CaMlHyWc$khjye z&O<4Xw>rXDT>+vpi%Hw?&tphK=mgwWZ^eR^%$|kk>KlJcs^=ZO)R(L}EWVz11&NCT5+4cgo66_yh`g`p6feW# z&Ctbv`8eeLtabgSRLEPi&g@`0{H-xC9~Xx!{nU~&TsHgB;L-`lzMDUY`YS_fW!v|bLC zA2e1X>^DZ*EiLeQYajP+ytKjxsR)}YVwuLD|2x0+DBa6&p!)g0dtEPCb!^Nz-{n}e z$eWjhcRtIdz)E&@|EuZ{CewFgI7C7+>zF8+NsC+uz7DP+0*c+K@2paasC|EfujGw z`-;F0$NU|X$6Fh%11~@EC$V*d4_6{zfgop#Gd}Ndp07;3Og>2L!*-uNXULfUEkT|8 zH5;nuO*l_x9R}4pg8%OS<4xX_@jIOVg-Ci(S+#mOu?Ov<*}#s~gEstrU`G#okn$dh zkSnkUxvZ+|9F0`cWgdUt(e@%1Ofcz`Zn_f)PS`%6dkZhIgiRmUJ^9#=WNJSg+rsLB zu*@#yx^W%52k{5oX-iEO1B_^#js4!kKmOqxBrXmFPG(8U>p^^I9Zop;wIg$7c|xp6 zhjhD_Yz4C}9**;VsvLrs4}#r0e{MNaM#c(~W!rb}^k%AGK@!x-t7GXKM@{|g#Y?Op z3GdQm_a-9m+v#jH;g`wn8)@>oq>_oE^)L zww?SSHwds(tg4A4nxG!NF)$=B(l352w4{zGv<1P3}co$nA8X@xDzw7l1EZz*> z{i{_V?}Q&(2QnaUA({q{0QiBlk1MuvwB3#cZ*}*WB?tt8)jPiNazWlPxp7N;AaA;q z!DEN?JdnBJB`26ZWAhG*T$MYOEe3v~amm&vIrUnwd2`dW*%c^J9&bOi4o;l>W-ewv zVGUtLR4>;&shPs(eSYim;2*ziK$?nySLF2{of|}KT$t#5%TJop4>7R^6|vN z>8)!?c;A{m_>Rc?(9>WREZ$z-yUYwB@5wVkcIl9}Q z-+dY4?d_s^-j_lr$f`p)Vnvg{nSam!!<*qK;&<4C#7TNkRk1Zcu?MXSRpG_zK~_~~ z5=tWrb$#ds!mq;~bf3Y_@IG8Y+BfgibDoI>`>mI>uk8u|JP!;%pN97!RmSMs``|su z>P@Mk?Qc8~>y-@*uV=BJL5jL}qf+db7_dR(^p^Go7rn=R2B}aYegD}rl-Gm8&^q#Q z@@vm7$m`K#Lvk#QoQkaQFR|J7ne6davB2Hi%D90M|A2HInbRsB9m7;V|1U$xtK-C( zb|0amiyNe3B)lt+AL1nPUOT>w2aES|l2t}?1B3^_-6yamxZ?%?F-xwEH(-k%luJ-9p|#vPxxp*C$|nPn`X4Z7wvU4XxW zB$VWPhs}SddftS4^(=KRt?1hmH6Z$TGc>c|7u)(HC#b%`E$+p58NPKGhp(dtK0**;vmjl zd>OlYBgf~BTxi4rF-~cc>6ceLHt*co3WwSh%Hyqp){%pgpTa6vwOz_=h?DBEp}A;$ z-Xqsa51y!r1|!W?F1mjB2c+BU_D{uzc~kugQg|R z$%hP1EZ$e+Iq5z^-fll`Mr1?YX5hN!|%5v-^PN@t|Qwo_yvMrJ#k-mK;D-3Mv=_ozy*z~d&NF-YCksb`3(aVae#5uRnTVfUaVZ{N0e!bj|K(74**iLl4-vF|~?=}t10+eLXR$hkLv>*&SF zZ_9_PQQhzsyO=A3w8#S{UA%ubt}8osY%Goga&~2BUbd2PK)Uj7oq(2IRNsRLqGZ<5 z%}p!!cLzzDgf|Fdog(tCJpOA97VjOZ;c~%{cfpxJt9;12euI9cA>>VSw3F9NA`S@e zj~-Ck7XXUuA13aDykFeBe7*#}VyCFumA5Lv1KDsrEQa+6Ht%;by?RPd#egmvm#7ly zJZ6i1iG9t)sd3kt@_2Wnb-cvMFZGDB-E#POi((PQRNFy(-W9KBIz1Q;gR&Vzr%WdN zTkM2OE%smLKT$pJ==0>&aeVc~4cGG)SCCR9ysNhtXb^cP*FRZ}#XCPWv*P zGK<6N3NrR<&%XxPY-K)elJV66DqKI{()3zT=C$B}sTc5b$#$ z@)k}?U4_Lv(n(J{8S<`tp6QhbdCzlA1T2HR^)`tJyl066PIm3qy%z$&$6F`#nc>}A zhu*UJ68QfAjh%}5YR5c~L_xitI2UZ*?;kxE7#|P=r_s1-yO!xy*Wz7tmRQh2M&i%mlCo}%jTZEg1Un2{QsGc|B z8kuz<^IzrvE>0v!c;6dhqa*VEzS@Hii+9RO+oWvB`}lVG&|Jv-DEnKp4tRU(e^zTV34;s$eRGUf4>MeCr$$5rFy-P z>7PG9^_SQgMe^!6#U&h)8J)B6h@Aon?0ApS@6@P@L8!*26AVqn+z0o?XaPp(Mpk=eSloQd9jaJt9Z}5() zQ4hN}--OFs3`Vv2?=gstrygE`|nRhfj%~;?qPr|!ahko%3(hH}zNSjp)VewY+ z*&wS1dGkIkmo9?5z3(1-+6xDyk8)Bxm#yP~z5EjmJ7ai2diTvlKggSfzT9i!>#Y`= zHy!ux@<3iKS+$zc40}MbeOM#$1M()u>APFGf8xX*kVfSz-xg9JZ*#PcVVwNR>VCIW zRKW+Nul`=Q^}oUU`raQ0lsoZvkSZ${9@)6sfNuPv@s^V$P@!yXk4BBKu!)VHt*lxv>Yq6DX)81 zpmqGj$!}jLS7!dlm59s}7LVaG_=^+HeIegzH%EcNOV9XXkKo_linj5+>lNTg^}M53 zkyl54w#eM~JBzosWJ!2GmT>$J@1K3v0$9AgzFCFtguHVbDzpnAZ&gOQ3SY>Zp>b8G zsAe1p7z~WL2tRM(7kM}3Ipm!idSy=;lbHTm0C^Ibq z4j=s6TN4l0eLc!(O7-)<=oRwnP<+EVVFOQZVS&TP5}IoS79mExr7rY`;s5^oAEo^b zz)P$ONe^ngBqv9_#6HX9kjCmk#y`HVZHj;^$e^FM%U}=s)OXkG3>=V-_1tmFI2H#U zOT4i*nhyZ_?gp(X@DscAJ-3#p!!Jnl8-IxWXzPK{O&Kwqyn)?=ZhJd4`3{SLC1{-6 zD>GUvN9;?i&dbX>dyZ0G54w)lp^cN@WTgf(uR15v__KxON-?7@9uvVW-nIMLgTPEy zZX_MR??DMB7aF&C=urJ7R+EdoI%)=ccelGOUSgF=ct783GDhSrz&I+2#e28riIE=2 zyOZGkv=s7wc;DP42J-gHSK457Bo63&_L`LJ2>=>zn+&c&-W783>_;H)5yF?j=Vl(r znd)P<{c+g5_loVBoqjC_&Y^J=3Yl{{+St7NnEY$_f+&x-Gg`+Roctuck|*AWaw2X+ z{QLc$;q!i{<>%AN5d=;Y`krC7A>##U!#?fR_FJf)H$jxlI{E@uX#CwlQX=8qpgj^v zcoHy8dv&ov()X^*t|E6TzHg5fp>53 zp>-fQ`5`o?esw5wBKP)tvxpP$SCGtAC(`=wg#g{st3o0O{`^m9a@J`HentJfpOaTd z?Z<6Vd(SR*@AV|SpDmdSB=Y9k94C&&+w!hR^3R3t-9$H240&tZTQ*_|c~?8$=;(`# z1LA)sf31uS0M>*sI{^kW>4AKC>f6Y&5}WtHl%vbpN-^*ijk{sQ zAHTB&n|IQ@&E@A5_;6wmTE|(O{65iZmgmxNA$+-=$ziMUd7D+gS(DFv5a<#f3vtWf z^PZqHK2r5%lNR2hhthwqC6HIgq1)9wk*61LZ>=NYUEldxn#lW9nUxq8Z#ozG@MUoR zpDDh=vcOxI9{8+>yboGz=l2Ya1C#IS;xe`b0Egd8F7-j)rTXnt(vY{G2eWlKmnS0e z*1le80-N{J2elVXO2mL98n^jPYkJEa?9GWT`TJA5w^QEYWcL2wIy!LjYsWLRKA5TjbY&&;NJ+r}TEU zm>-<~HA#BVi}+%DVh@UQSgwfGgHDb=w~d3B*s1jJ?Uk?xUGNy&Jr3_d2H18!HaZjs z(th}*YL*9r<2NtPPf3g-9p08>m&W>$?;VqJl|`P2|BjiV$m<@M`~SyNO&DoiB|tD5 zw?y+uLV8LR=0>2@x5gCp-<0F)DoSQURj`Wnl<>;4va zgt178uUs`54@h^Ye)(}vnd(=N(XHgwu~x?IyzJle|1?N=w^@rlC-UCj&?}F{`@3um z(>chy?a*5HyO4L>o~9l(c!@o)H=sCrI1a48uWp>MKM<@eeD`}byu=d3t=k+R?<3on zG`_v%iG&xpHu0uo^N!Qy`2F5g0z{#4EZn^Us;97dPkYiT#eSqb-eG7RQ#kp3QJnKn z@8Ci@l-r^4m`dYp;?!xCimh#SK3cbHykWwe% z-73Fp8Z`0Y$oo>nGlttI<3L5xr*ghEfk3vj zfkqSZwoppHssMTG3#sS|J@7>2F2tYjzk$tLJ8b=*0W}Grh{l}{oIXFBj?MeP;rBl} zTPTmWB3efnPJYSL8YfNpxRGzKUWXL9;Pdv4bZ?Sw_6IvA&O61G<8P1>rsvd6vJ|L( z2Z?Z>%sO;ME?)lo^%gY}-px~MI*7dYKMj<{;?4fd;LI(^JI6xfL#H}6h<-~vY|Eb^(0G$63k{;A~VYr6a zgEkynqKegnST4S<)`C4~JL~-?4`2^U%WIu%f$t!B=op-Ax)2BG)0)NFCxgK~j(1hx z#YYkGASq|r@qWYvVP89D;(>U7v`Xw=f_;g7_4=ynh?Y1AK;yi0-b9RD$L>MrO!WDm zcTiprYC!8ai<93N&%LF6)|`lcOvTIY*yXx-a;`>({M>Ok6olK0yry}Ce~X<^Rwbm* zP(<}Th;Y4U7E$$%cknrxXYV9QQ?hNfv#^MdincIyZ?;jGS@9#t2YqKO+ z`XO&$bph?#({UiWYWBkJykJ1X9it)xZ*RGOx>qg9mcTc30L|H})kq zII(BqroK2xLE}CLJlQ;O5Sur<)Qg?j?>v63uLK&{@=ntULBWC+#lvSySRefK*GD-)#xmd_l53K zB`n_Jxu5y0A#W}1>Dhab_nEwGry0n*)ymhT3O?R)F+aid*_L2n=HwOS2YEZ6ETi#) zycPGa)~i$UK-g!5Us+UO^VW+svf;532YhH;YV+woMRwS{ua&QhnVXUl@sBCn3_mruLS z-d^n9+9bSRFRd&g^0w3sU5~|^_tcsr?vVHIZ?Sv}yn{GDpIWHtbDjhrCxtx9d*A<1J4+`B?NJ*o%`NPnYrk?h^;eXxvv_*ZS{E zu;>5m(_Rmv4p83wKaSRM1t-6y$ZF;dN?ge2OPR}7_u=!7llY|PWEc!=ug^8`XW~Dc zsP1s*)3u|QsGj#SZSv~ixmHip7{AC{i-h;f=M}4oy!XxOt;6DN8&~ot2=YFA|Ex+C z)&zOqHGZVj1Ml8SZtWa!boNBDK8G`! zabn-Seg3#OpW&bcxQ51ocRzNm`Gd`Shu+NFY7QREy*#|N?Elv9kI*{Iaq_!TMV}G) zjtc>QcIBk~!sp$%M(fiXgJ2M}wqEJhS~4C^96a)erZSiM*WQg}))5obB?});{CEEU z-;(`5_~*j;e=|uBdK(*mc%cWW!#7AL{9OrHJt)Ck1I#{WVud?HfDwa4%L%bj(F`pP2ukY(wj(lzcDjbAzotF zoo~>@;(a1aMUNg{V$U%z(|ZJY%id95p9Oh)@<>qLhOpkoU)t z?C;HA`Vpn1f=N#Y59CAkGn&hO*el5Aqec%0zlnh%G|tiYg!5Mh>`QFe&KdD5rzmeg zdW6;yjFVs0nSrmvJse08?FWJ^0sj)~|Mf_C_cD9EB=UZsd`1I{_e+s0^K6het*yMZ*VLOIe!aEC z_Vn6iWpSYW!{H$J^C7@4Xo)4BvU&`;7`>Y;uB5KFY3U7+z^RB%5-adFL z0)$+yGnHI||MixJ8KH|Gjz>{FZ)tyFvg-KrB72VY(Bkc_jU>Fg`}dg>dEY8Q zSXH%(6S=_Z*srt^pLY=-pQ_0B2$1;VwJv=Q{{BCqc6iOTn0-_~{}T*`$f~3E$mt}R z^NaJpE-7zqM^++lc~=EBEZ#QywAt6 zdDEU$qWRH6dAxsk{;h)sC%>>yIl^*`T!@B>$Tyn3_`J*Z^;;f~4Fww_M6#HC@E0d} zsV(0Ig43yf{;#;*OjaGCTzk)C!S4O<{ExTVqk!Mx{BK0kgFgDOSuOOSh50{Ta~lIz z4>~CGQm7Qp|7tA8R&}rkaobLJUO%9un@{8R>0ojk$QKl!Se6z7CIyeJY!n$qs%E|Y z)xN_WBpKRE?;pA&7k&$QFU!K7|Mzze+pP5$1L%B85zp*Mq## zIuM-vwwt96mY1?4>V>~7O2qN!fA1iJLz`k^faUu#&GBgb9i-^fr;abVVo3G#e{>mn zb%aaDyG&hOyu@xH;r(H=ZW@vIn^iJPuy~ufFFpMb^0qh>5%mP}u9WZc?SZ_xt+Njq z!AtB8@MWufK?o4pciVX|R&f|SR*7_DO+PJTNlSIVzv=0MiI=(!N7kIx&duwFU-D;5xH z+fO%;am3CNi&@s&oW)en+dY!JI$T}{6Wss4AZwaLr`$_7^@hB4 z%)75kxMK6(8ggczLAn^&jKXgTO3tGn%PJStFa!+=6aUk<_ zG9q=h_`JW?`rWDj9Sb%zeQ^jP=j$zoLiaa3Eu(tggllBh;m_6}{rB#z0SWK^9=#$W zZ{Og1v{<~^M8aZvAny;$=UZwZZ+%OF!BEIsp2Ox?;hi{e>1Gj6(d!V9`>OP473959 z@_kMD*M3Cn-HNlj89k8XElEN5fBge*y+Xlp`2K$?8uwQ7)Q*)$uoov|dpYm$TTvcw z1GJ7|ocvgXhU*y&I1sfIw^f8Q_`F~0RGeOubr=|gx~kSL$A5c^&=sS5u3CxeZ*LLY zW67#xrA46bx{Srei9QMMzTEUjMBb{xr)jWwTP2SP4MX0|r!Pz|?7bbXWGMd*d2?$e z)t-DB2fm9|{hpi%0WHAJn-y+O{0ObrOC^8IAhvE+u6QY>7Y{5$_szp5Jm+SjQm-oY1&z?fpd>cd;+A41vaa z$u~JE?ir+dw2nUk|D4|e$B}XkQBLI4`{?D!)up<4|7^#(8V21;4uCz|4MGFT@o%yJ z@HZcy4sN3Q9z-v;ovb=mMeJc;8NaxLWJbb!SaIWHB5y~39wsc_G0U?G4np2)g_b}`+t+`a~Q0;f`OBcTPqE`y>-!zlkO$gr=LH z&5H?}w~S);=#-!sphx3)`WcgCqOf@v_f4GmSV?)jCDA%=;^gPZpwrHN&pVz__m8F4(<57*Ap~aKGq%t1M#O%b!@@s9q>9SyVOOC>IbB7)pKOk zvH6Qr#q{5|w@gTQ4?MS9e7$91b3#F_bQu=!HNQ?+T!g%zt%xTq@SbItu^NZGWtGQ` zgy7d(jDN^pDKrQHW8=^NSVG=U)0de3hMN<`s|vn$HoGI1j(K}bKVkEx^RG=#(-Q+W zXx#5l@qFSA*u1T^mdYjcQXcPlzrS@@;NJ`CMzy_*coFuPUM^+u5&aaD+J^b(f zKi&*S5x>Lv--4tEP3*jGO6)=3eKpy!deFwf-%k}_57OcnifM*D=oG_D(ck37|#C(*;e&%P4y!g7Ow9FQ``}iO(X9=a$pZgE1EtW++HdQ zRM9wkb{39Z0oa$=-IpI$r5I6O4`N2^u*Au4YqQCjS1cSzd`4RzhvLFa3qlT}AQi{`6N*n=SN9VEQJsG9#G@^-w+!-mB> z_xIBvZOFUPaI~Tc@^&-uV~{`UzO3!Z{%^`amKjazkhX=b_(HgCz;H7&1pQy%Z7XdQw$`OPup zvCNyXBL(BuTUF`sSC9$0A76iqa08pTMzr?l;txoKI~Fm;Eu&P=o4^-FRvk@w#`$fU zM;3USlkoohop6N6JL_T3N-W-Wx6a+TEi2@xo?pGd5r|UmF zy*1^bDRsb)@_64x>lnw$uT#Z0zc`&8*>Xyc;fVx3?-(xiflc2eGi|7Jx zF2V45TgZE_^BtGT*Reo{&*8&e*I;nfXN2b&b!6xD5RL`5RiOf36XJya1aV_xPM#6hEO`ey?`+DaA z7A)SzMQKJZkav=Bhskru`?Bccp{H=~?GhWWh!cEhPWaSr*QdvWfyo-3-cHDSd5GMW zCdfOcbeqSIX?Mh?>1Fu*5$v`1wFhcJtC_@rJsQViC^IxUh0R+#+gtF}Rm$Ui6|F-V zC%^bg0!#6B4n(|d*g`)BpZCLu&hJcm_Je@@o$AAy_-k*1XzI5|f#%e|I0?B(RvlL* z%MU&&`gi}IBIbL%Bw!D+Ch0-bX7)>nJxE_cg%_&_sjs@k@a;gM?p4=K&M#mOl3H!q z?F64ea@R=}9t(&CJN?5R_7Z}@Nx=59Ux4R>4C+{0yoWj1u zUbDVx7H1#|TG2Sk(eCEY|1coM>OVfUriX*#_W!fdIu79E*E+>%JwD2g)G2o-uUBHg zo&VQ;1S>yF1p@X^KeN@>@Gr5|>vA>}j>J%X5AqvIC#w#IvjuFY+!r@UcaiX(lHFTQ zImdLaZ;pFDKHio*Yu2P&;)}ujZ(ZJkoOX) z9E(uM+k7<#^3~8C(N&fGnb?fY+fv=^+-+M?fS_@PN$=J#U5$N-bt`Jf$oN8eymz2= z*yH3^D3tQLOP2!~lR37w#t@(PSi;Y3U&SDAK4(6S^<*5e(?0Ow&BGnyP!+TLNZx8kgQbRFXr8Gbk5aYt5%>6!> zV)MTI_A~pZrIfdVR7dMb!pU!FqvJ^$4i1FF>UvyS3_frAbLBy=r`*Ahf!REhJ~D1^ zHSah1B2WFtTSV`3A*+r9^S_>26)tvfD-zz{{v`ZoapKL9&WXi4Yj4(hZpeFek1W>$ z@9F);kzMfaZBA>A8B|LS3-a!~^eR>f@)moy;kI3-JJMNsZK=RN z9B<)wA?q$fq9`E7rIj357gT`Fdy;jOF+!N~c<)E+7{$r2Fot82%Z~%8J$|aWBM+bV z?qtoaM-<&a=rK^pbqt@kL=K;gqig`x&;PM3jAYeu(Q0h$(ckm`EJ=8Oz1Vh)*u9&) zgE+8wYtPv&5rMqlmeQHEK;ASALv|-1@1vS2d0CKmOYEujsCk2v9ZU4}{?=-gT`Ex@QY((QyR`7ChJiz8{5k&j01fe|M zA_^X&aRS~=hxayO_aN_cB8>juDQ`gfGy1mtYAmFL{uL4MlHde|M&Zg z9(nOA1l$%ZC^DGDpZ^Izwmpx18A<&ElIV7_>QJ1w&hBblTtV8C@cyl(n@Qwtd7ox2 z7H?sV0ItW7w_rz^$Lobl?8MKe+wlB9{Q}wt!B^o9QU?5nrFk&e3nCSRAa93w8}5~m zcfs&(E59LkB#B}8Zo3fn5xbvmslJK~5e4VaIKjsiZXDs*=l^LtKlkFIzyaw4T89!& zeq-mpui15i0~wA~^mVSq=WRyQeIi#V zkX`Zj@fJH0-oI!SQ;EFqHTSH>;%(JiJ>CR)TZ^vGe+79zaIZF2fV^`=a{F2mV!_rV zSN^rK!Qgq+^wrCdx67V-l^4_f$hUUKhc?6T?rp5fVId}L-l=yDc)CuD0%F{U?N95h zJg|9B<#{<)3sT++@&a1NC{BJZ2OOizTG)}hUG;~ey775`X`pRp_6`N>yE5C7>+zo; zC2Wp~9?+bmdfo&+^6DtCyXBcxvDm$BNqGOreJ4TW{f7C>DlFd3{h+Z6@}B8W9D50Q z`&|@xc@W;-$}6cxX5i*T`Ik!M#GfG0abh6uF66D7XmtHL?p>_xaaO*X{gish;K&deD*`nFR-7532WFUDO3Hv1>-TAIQKJ zd`g@QXnRV1PPfPvXAax?)O~aICOXS_S_p2}# zZ}Xl`n&Xgn>6YM`PRRRu$jdc-#Kzjr>pdR$BI02#a^k!{y$|khjI13S@!zZ6k(X#S6E$td`6ha>fBc z+FFs>-|!1ZeES+dLEf&ky1|3+_Eyx`k(%RyZpamTJ%#my*t`P`O>cFd6#>LJlUMh5 zEL)1r`xHC#<3SP1F6MV?5V|-+G-QVuLhlKb1{hd3A-Meq+ML{gyzsDmpGa+xLA={H3 zkhj9UWyM@@b3$&7#COB#STL;I8rl9b7-$RVZ(xD*|9-QWZ8sNqgX-F*hi*vsg{B|u zKG=(skqgPY2XBdhE;KG=Y<2FY6l~r}3aL_jdX&d|5Ut}RPJYGLbDe@s*^!v|Hf=_A z{Q2Lh@fI9=NdXNugh=l`HRvU*JYl*c;* ztz$1vegk5a_dkSkAg4Yn8y#}M=Y5Ka-{cb9dz-RS&>ugEKmUVuJ!;>c`%!)OP9?LB zBG#++hX20*k9$$4hyd7wJpQW(*)3DZ`p*%&Nj$vLSUqTIqtGrx*n@-$4A;JaJxD2t zf3GHd28lLS@lnFrIFL3V)y5ef0!)1AzUK&xB2M4CYI=Y6BLeR}iurDELqyF?nl%Km zFR{a)47Y6P7X~6|+{bXwKMF$Fm)H)QOVJ~KlsEr>MC)k5$#3^;YNzxEHiWlfV({fW z9q#wYcx*`*sw@$~}IO$`Q$J-sPLj@9`;D2w0^NUdMIBw77J!Q3hhp7b949VCL)bxVfK&D6hwv>>mJ&4ssK z2&ONtAl*oKFM0bkmdM*C_KpM=@B1kXXYCWH{v>)$_JZC$Ekj9S)n7jxC ziO+kMp<(~WrV!v&`$Mz67k@w^j9M-UXRM@p-h@H&>iFY+@?Bi&V)u3-;Z2uevxmsr zZ@Ik~7VpQhQ8odP_q*^1uHBF~U+58!S;*U@Af!QKXB;qKUbTMOA_P2jGkp;bd0!l- zr%Qmm`Jx=zD^9}2$^O;0;ttrn4;I&mgqn$fIyA0WZ=+;?AU1D9;XO;L-cla#aI_8t zCqFf$v1E{g9hu0Rk=DPA&-+V)X1EXBdn@PqetKdKe{*7MZCUpL8Z)Y2d+XgGuZ|~M z9b}eW_;>%GBIbL%B;fqNkE92!kgSR%_Mmnh7DcQcR1%=($PRnZM+QF6e%OOD2~FCO z@Q58j;4LW#KajT9JSzRskr2>1-2%AbfW&cy=UMfye#EA^$VzJ56ej{~;+iZ|yEhXD1Tdkn-N zZyD{iS-FsRBCXtO`BqoN?d8Nv``_3bq&=b^6hF}m17aLMxWE0>%W%w%K)-XLtsxgE zk9Rv-hbK;c$Cs%oj8C#6N?SRSQ;*>DPCRj8%gQ@GVEr-e^ICKGE6C_a(mK`$2dVxN z8~vWVI%e6wg>wAeLGmWy&Gh8cIU?_@y6bXSyt}2?Z6zRY-e>Q57kJx-D@~?D-ogpY zUN(^T-Mc*mZpeG(t0AlPkoPH*+?I2YcX_X+x$i?)1QB|%V`D8gZ)0zcZDD-EfEcHv zu&-`?CN}So-rOer0?Om9kJjOflb;t$rb(qH8{#{zl@eHt&%5aI{wHOGaKPgEeaEO2 zK5yM?u_Y}N=2Sl*=~k0h$FJ%={J%~w4oF@kycrXwjuUz3Fa^tE@uus{=UxwaN7#D% zyoJ0!&Jr${L*55%mHe90;0Mw}In?yy;0Myr#i-gt-q)RW{@4b2yQuA&9j+r95A@TR|7Eco1%e~C$h`bMc zFp|OIEyhvuLL2gC4-B&#=?LYw;XXis_Kf(n_VW*ZTt=8@lHqUV8qGK zarnXQD@JU{hWI~ctUuxNw!NC#HPaam80lJE%s=DL|FbI|_o~v?Q9W-p8S?6odBI!P z9P{t||Gza;{*V5-aQ^ov=|P;LJWRwMRJ?&s6{`m+J!GnV8wS7sH@ETX2iSwa%(1G= z@C?%RJZ$Yt_Q!#9`)Ut8h4a7Urp|3O{G-S-CcgcKzx$CXV`Mbrj2q&8cSXrpfc*^8 zv0vjM$t#4xUNp{#W0hTRI`%V2OI}vkRi#m04?2w2LBPq6PB@>pOPw8IPrT5UUrnov z_ivn9=j=^?*b5YVVzLRbC*u*j82G)T*%#D5AVrZ^$3TgPXZPO^r1_EXW}o)ILgX!E z(yWZd`&+N$w;{-T-IN7kf%o-9^)~?WHu5z7C=EAAb@N|;Erh)9?d3oJ6!NxdO|{d3 zyob(Nct=OOA-#-UUqg;!^RBKhc#ykB7`#E__K)22+w6(W+bW3Zo77Fp<6VW;u?;7` z?Y9%II>8On4;@)?9DVq_ZwIq^@*edAd_3)L`Va62q*o3vdQDesp!!SffE{^t?3Q_Dp4j$oqXtjuIB{VEI_J?~r#&71!?fkoTLz2k(D|ym<@fe$>atfp_bw zYqKEl(C1xl?U48G9HA2ukau&PX~aaB8zM3oFdz62CrEw2!|-gUEPQ$kjgyEwd$98# z4oLrW-C14v9_8_#Km_{+BJXq^zx7zWt2J0nsu;2gR zps5f75Mgiujq|ln3!jq1e*gc)(hpe!&6LMm1FfSGCqGSx5Sg}kc4U>0`uYbO@CT#} zZQlF#vVP!N_wQ`^FV8XWYX4`E^Fk|K$d394Btk2Bb+m^DN^55=-rn*d)htlAZ*o)%lrSgy|>;sri3ST8UMcj|DXOw!T$s2{}7TMv}$?X;xkAZ z@Dsb)dNu^C9%N##mskidvCpbbRt~@(MELIJ#se?0(d+!y9F&X$<2kjrxP3!_@hFRr zHta!L+W2>f&h{hqrP7kuP2G^^e~c2m3b6;Ia4lmR^&%nAh{j1ornRR2!}tIC_E-sR z)uOx}6o%IE7AHR${?$z$@cDn`k)t%O?D#9l)ffANwuA)&_04ZICf?u=NYO$Oipm_+ z|AKThBYAb?5Q4k)t}R|-gGqSvb~|zqFR}HPYBjNVKhPR6xdVAC@tLhz;Js|n_}M%h zkgh+_dUj4Z4%{Exo%;+v|3A9V?tvrZ-JCM)G7MLc8vb58hjiVLAZ^*0#|N=_pLsdd zo(6>){6s;Zl%?#VIg4E#D{=*$a~^K4_g7`9ngvl z4(hle9WuxWs}nZwwr%~F?!FKL#JH5I?HkU@Ve>A{QJmIxq&(g&XdSn4@=IUY*X`@e zj>Nsvj;7s$&wFw=_wgI{K|qCmdG@kgGB!vHYYOTA=utgy!Xq;4XbNuO`aAyzlJMq^ z3bi2eR@~#Jj>TJ=#k{fs@?MQdfA|P_hsRl*uYkOl?KF_lvVhP3S5-3{hzbEEat$~DKP^*&dTI}8dB)qwtjy4f_4+iR~Ve#IwGveqg$UCE3M}L90W7g03D9GEmPrr)O zBMvxrj?Q<%`QLUfd-HwB+uO1cv4Fhkjcd2xy5)xOpYu%|fV7FuCIjGL95 z4&nNS%{%&GhS170l*fA+T1O;Ke&bii-Y#FpflQ{ly!xGo&wJaR%Z0L$UZA|L*y(f} zKJTk;30H~(1T!V{$8XN~mU ze2WFlNiuvhkoQ*Kgf=0_yO#b;{tn2S^K0=^=I^e^AAbLo?bg`5*~F5fUKj}hg23On zHq+@3Zy2z7ADWoE-qcQcyjP%g;N|zt`}x7#M{LMpRn0$-;_!I~g2S|9YEx)#SduyS4>oUyKVex)8$xeF~ z^6uYp{qPXvz4b!omn6tLjayo4Xg(HnRaM5U^9ljK1;ecPAn#AByLaz_ygA0EORA<^ z5xvbeuP<%J<{f0_>aXo01oY9k_Ne5c@)_*6x8#4NuTq+zJl+9l9eDXId$3IF;0ku+ zvfq<_qcnWpe)jxdm(*DROB%a38K=pZ{~ODsR>V>N+gpTH<>b|2Jsvsly!e6iFcRKt zVlsw^-8-W02`v`y;MgZdmlg&j^V?qrA#X`z*G3P>JLiVsZZ?)UFdQ%AlmL0Zp827< zzXD>G-DW;J1)E{i#w3azr2=b8VHQG-cdV& z;Lra9sZo8BBh)|tzjh_B4)YHKKF90+o&WJ>IEwiFh+Q&)qz8%po_j{@LAI_2%ve20 z({_8)cG!b5PxqW3gFT4jt-Ovm>_OjV8TNdC77H5sSRy9jQ*sQgvjxhq2i-Y4eO4Xz zpjg6th?pyQk8Weu4L;wJVsSAn&aP^B1_AV?pz$ssskD z5b%*9iGCyGZ9lcqcH!}s56asgp1k6UoX(MW-7164JFVF4{pr%j~}4^Hx})dfo7XDTqm`Z;|+dKmR))DBb#l zuaWBK{}2)K>Sz?WxufgU;tDc~gty3riVZ~GB3lNQWAT>m`O)SKd0(j)_8Wz~QyNSa zFF@Y%o;+K}Uc>?!+RG-d3`2m2N^qkA<2@ zG6iS-PHww#mW=s7%f`X}J@vo6MQ|pwj*Yh&6#sVbgCx9#ouzLQc`MTvFT>(pXI@#n z7xJ!K&D1vndGmh_m%j^nXKgK)&*_W>388oDUhWJ5meRqBn;~!8rC(>)Lf*R+rZp?) zU6GoU>05*izbvFE7ZL|LGl6`kz@*|NMVzH(7OfGg>~h%UktDo@ z3{$d*yqQ-XU5dqfq$2fk5ahkzsM&adcWCFwJ)a-^yq$U-qKn&S`s%X zk9Q|8Gon_mio2r256l z@-p)3a9c05_GRS1^FKw*_jpOb`F{yX50YhhAWrN-PABx)v3gMd%ALicum^<+$T)w2 zJ&1WocEwZJg9@ewHI(27(%YogbMrq52F!V^9ot|JVoI&xWrsazK^&hSsJVe6oi7|Mi>h zN9p1ZNcK`IPsx5=2l@^6HLSBHV+9%B&qMz{o9cTIA(+fM;tOW&oECPFlIcl!OFxym zNaWq+v4RbY_j2uT;c}2S!iY=DG4bHtb8RmT~t@TQfn>fyT8veEi;U9GkayzDIn<9m?ZP ztYaTee)mo1<@E*Fkfg5(aS9IjyyMIY+sp>dK|Eh+p~4S*-rW_yH8S^zQ2h!rrI@@r zw(YF0Iq4d+z?+VgH|xPvE3ROGAK0&;4@?n-kaMcrI!}-jm;7Pa$w~;-t&+KCV;P zyvtrit6zx|1jo?0UH)uyUpcV{q?#3Mv+-<{Hz1Xxb>QW9D>L8Onwbr`<5JVzcNL#^ zt7YAA*1c80-ifP!#R~kxiK17sH%UwEpnBfq)?sXMum9`7!u+31L&96a()j|B_lcrN z7A)Q)H-}ysLf$uevZNMxf4XRd*h1c>-(_|<*2MxpCJVmJ;vrz)XP?D~6R#u-3+!50 zoO~+D)c~#tmzjC}?F-nvi^4*!II;u*2O75|qD|RU6r1<^x&ynb}^zuZ{=IX%~Zek77Zn@4v9~aT2KEy z{~vGiri|ZV4`L+gLF-1H|MQ65nTyK2SUo87vFh}X&_dm#oj=!pgFWboy6(Q8@C#DY zpROOclNbwbI18V%%?$>|J&|s|;3c;DTVWL)dP4N^ND@eYsLaAw8s_#LBj!yFGNV{kJ_XMfr5bGw}RB z_U=5arZs#V{@%Mit+l60nu(HgUb%h~H({j<*6zw7Bc=UyWf@4Z=C2bge(eY}NR z&;-0Mt#>Ni54`O@9M{Hk#aOF z>tN5hWc=s)e*v!pZ_{xD?vcC)m9A2u;=OJAxPIM$x9-w?v7dmq+u2p_x1d4dPSmW? zEQ-fh&e(GF?!iU)LGF|((}B0f4Tl{q!25(<)w8wmaH6*0x$RXS>IbARC=Ky;T+|EK zl#SCEXx3-*BWm7j*A6|qf!X;Qq>HjT*3rz*%X*9Q4J{?CS!cTbyl(Uj(ho)HeB^;H z7QD$eGP;7kL1N@Bibyxm>GG>LW3GI4ddo!I+hnEyC3)9=o7;_w_tH~6 zK4}5((M_K}64%~H-oo4ASG9n*?)cFLw}5xn%bd!oz`If9xZ`i&y>MrC&f2Iz?D^7~ zkKO*`el`!3& zKKn9F=y@;k*~WWx%>w`aG~lz(S^CY%*sm5>&!^^fdEWgW%U4H_*!B-I|GxjfbM*Ig zvw;3z(qRp6QmKVjeAn9L0*+V_g;biKj7uM-Cto1Du3N#um`?Ds=e_*Qj9bn zf20?6;PAdhxYqS9F((;Ggr^`{bvU$?!epn5dS-Qh#eN#qD{s7 z?u?Y>w}JPP8eI)F zvD;@jd%Mn-w>lDdhYv7$JOp@aIVRa`-57|KEwCKjYXCLxLE0k3n5>R5H1jjqJ!Zl-6}UlK_wMEApXqsDST=QJSd2ARaCJmLiX7kn zi%6KEGBUTg%k$ovC|?~jo@UKb&;P?)*n#)JiK@{g?{CxdHK};ddeoHp3V1Ktp=d$y z9{Dz8#B|{OxnxD7U2;6Gj3i!LxM>mIw65a1JMf;Vlejq=cyBx9e6#U*Aa-)BS;mtI z)V%Y}#1UVA>)n$s_3MGEZz3}a_aiP`&)_sbm=54c}-^D%- zosV~wtPVSx`9-Z>ke8#TgdLjIw{_rHdfvOY)Qu<^H5U72dhu)C2m1d1eeR}!_9Uw= zzxSTtBVQd?mkc|x3EsWMVKA61R0RLmGTkIClJAlx$vep_$ur4A$sNgc$z{oT$r%YQ zsgxX&?3L`4lt?y7iX^Kfd6G;?ibN_|CW(^FmxM`zB)*c#k_i%5$tcM%$smc9#7xpp zq9^GgQIjZ11QL$8UHnu0Mf_g;O8iuOUwl)1MSNa-T3jVQBHkz7Dc&Y77OxTKi!;T^ z;yCeA@gi}!I7A#Eo+h3ob{CHoj}&8KJMjRqiP%8gTdXDSE|!Q9v4W^g)GTTeHHuz} z9*gdZu8S^-YDCqdW1>T%J)#|=Eu!_JRia!`x+qb!LbO=4P&7vrESe#jBJvcC6O9oK z7Yz~Fh%7|?MfxHgk%p+7NF?Hkn8Fs}H{nO&8{u=|L*Z@VRbid*tPmGg2oDH%3rmHY zgzJQb!fauxP%2y|j1tZlh6#g&zQW1E2|`!lDB&>SAfc7eOxRDTC+s0q6DkP>LXMza z@Kf+b@Lupr@KkVLa8qzaa9(g)P$f7b*eBR2*d{0ztP$i3G6l(kIKfiEB0;zyL=YgD zCYU5}7mO8*6kq~7!2p4Yz(CMjpe5)okO&Zg0@{W)qfKZd`VxJN-bJsYm(Uut8a;*{ zLieCM&@JeCbQPM5rlX1I3Uo2L5S@btqchMcs3$rO9fJ->hoCm71==6gM|DsQv>Pfy zc_wXAvB!Kn@_gky2z6vJNRkvXN9oiY!B-koia$5`_37 zlaUFCD>4chh73Zi5HqA7qKEWA)DR^^fN=Qj{Ga?U{P+A<{HOf;{G0qM{PXVnHPdWEFH#t{0=Q*c2Rh%Q7eVm<~ZJc7x8cseZ zlatJe<1FPY;)HWTI02k#oJkya&REV!4#u(L4B(h>3^=_xTAc122?yaQu-n+p>?U?2 z`z8A^`!4%B`x3i`UClnmKE&R`-of6&Ue8{|&Sj^w6WJ@+i`fg=bJ)S`8SE)+Pxd(W z81``X5Vj55g5963&(>jUu)E0)-ke{Z{wV%;f`5Mke}4jhe*%Ah0{>Tk0!-I56t;pc zX~e#8Y#RK#na-(8A&yCngg82NKEzR}vmrXA216W~>JM>5>NJSMQ@tTNrcQu3EY%Gn zmO2LF(9{tShor&@bLQYwdx(QltsvT`nnScp?GMp5wJ$`Q)ZP%SQ?(&lrK&+3n5qnM zKq~A|nU<-1h!&{|5Y1DTLo`cS4AC?t0-{MuI7H)=P>B6gf*=~D_(ANKG6kYxiWfwK z6nBVyQ(PeGr;LKwC&dw>Udj-Nx+%60d#4P5*ek^pqE1Rbh&@yKKBrSpXD`^qLpGor|{zwXg*qk&I;`gK(5Wgi& zh4?jT62vb_9uPk#xk7A88V&JN(r}0$lZHb4kYoq(ebPXP?~=?QHYOQCe4C^X@l8@M zh_92hAihdch1ig!1o35(5aRPB9>ix!EQn7NmqC1z7!C1p;zEdz66ZpEm>2@_L1G}p z`-#2~?iQ40PU z#ZvIk*dPV}jP+9R&nS|Df5ti~_-Cw@f`7&uDfnlsmV$rADk=D9tdxR(Mxhk^GYX{O zpOGIA{uz1k;GdBj5B?cB@!+449S{B)S@8i7GvmQOBO@OCGt%S1KO-$3{4-MH!9OD< zek8=?cn63{@!+447!Up#3Gv{cA&m$BjQDs1h;i}YpAj1m{uwLc!9QbpJmG&?JmG&y zJmG(FJmEh&j_@B9NBED7Bm6IlBm76i5&jp(5&jp%5&q}L5&q}J5&pyD2>)~A2>)~9 z2>-L=hC>XCBm9TP5&lEs2>-L<2>-!xg#Vdw`VfQSdO-|~Bm4)%5&r$-2>&zU2>*U@ zgn!>S!vA!F|1?7XR097L!oCkde=;H8n}9!waPLL1_axL$B+ySF%zF%j;7*7iPkQ{v;|!{WW-GVxaN2Jvcfo;X9C zB#sp?5l4vUif4)a#Z$#z;_+f<@d)uyv8~urY%K08?j_a~tBA#7zL+Iy6@3?d61^3@ z5Iqvz5nU5q6rB^D6jh22ipoXXMVm!MqLrc?QJN@0v|JP|S|FM&nkn)V`G_Wp+(e^A zj-tULYmvFgNYqEvQ=~3Z770aM5kvS(_*M8p_*(c(_&|6|STDRFJR>|IJSyBT+$Ag# zZWOK+76`M1DZ+SRj4)C-PZ%l;6iyd<3q6D`LMNev&|WxDXeu-m>I$`mszOB}Dr5_O z3w{Vb3*HGD1WyF_1UCei1+{`xg5!e2g1v$=!B)Wr!D>OCAVZKOh!rdmL}QbLr0^I=wQ?uHAjumK4?!=9aTn! zC>LcQzmTuU2jn&K40(XuLh6wV$Qk4WaunH*>_SSAjmTQ00Lem9ka#2piA3fhp-3Py z9q~py5EsM=aX{>mfru$$i0C5Ph$^Cppa`4)oBxCVng5R8@CO+<`}^zfPvGxQ;O|f1 z?@!?GPvHNLp8zYl5H^0Sq(a#Eu@VbmK9D1?n4 zYk47T{8-BhVdKY&DTIw5YiS{D{8&p0VdKYITnHOKR&*h3{8&+iu<>I>7Q)7lwWts_ zeyoT>*!Zy)7WRU;pb$2Gtoeno@ng*^gpD67ybv~itht4-@ng*?gpD6-b^+}CSYZXQ z^<#w=z}}A)QUIGj)~o{9{jq`zVEf0KSpfS#R!{+K09k;qZT3ScA1npyxmLDrN4*b1_I3SckDnp^;zL6&y`>;_qr z3Sc|Pnot1yL6%1WYzSHI1+XDxjW2+|7}mJ_r4ZfnBO$ux&xh!eKO5rM{9uUA`Th{c zrR85QpVkL3GGBhlu6(hd4C9FT^4F zy&(?H*M>MKUk##tzA{9+d=W(3d_F{*dIdFfRh)fV^;smU*ENE%JgO zn&m?TZjgE10d?>nL_N7*AJpz zULT0Mc{&h#=V?OhmDe4jPM#vfo_PX@J@U8^wey$|wQ^%1YUV~k)W}@`Q9XAKM77*m z5LI&nAa>844pAj{GQ@7V6Co<+j)SO_>kLsbcO*nft^-7I?jVSwTx*EJTnmVTTw{o6 zt^q_OR~I5bw+BRCt~x|+Za0XWTros;E&@>@mkp7XL-=Rr5dIlC;Gfx^1OA!6bHG2d zEeHHFTXVoavn2=oGk@iPf9B5|@Xu_{0sqYJIpCl9EeHHFzvh5{=9e7s&-|P-5Momf z_-B5~0sqX8IpCl9A*UC__c`F7`7Q_iGaGZ1Aim83|I9Zz;Gg+A2mCW%WrKfaLpJzl zzRX?-@kKWHXFksc|IBCE;Gg+48~ih$WP^X^<81KHe3T9TnGdtUKl4F0_-EeF2LH@^ z+2EgfHyivj?_`62=Iw0o&%Bil{+Tzk!9VjxHuz^=&j$a@YuPFguV#aPW_>pJXI{w$ z|IEwT42YMqz(4b17Wik@WzC0pJ`4OaYqP*VvnC7tGtXs#f9BaN@XtJxH38!3Ebz}f zl?DEp)mh-5c`^(9Gx03&&peR@{+U%-;GcOs3;Z*WWr2TYWfu5nR%C&H=Fu$h&peU^ z{+Wlfz(4a)7Wii#%mV++1DW8Txjz&9GxueJf9BrIaEN;{!9TM+6Z|uGXM%s`u1xUH z+?fgfnPr*o5O-vPf9Cc~@XsvG1pmyEOz_X#mI?luTQdhh+>&VuadRg4XKu;_|ICe< z;GbEX3I3TIGQmG{eJ1#4uFC}f%(a=|pSdOz{4-Z)fPdzy4DiofnF0Qpg&E+VS&#w# znfV#upP82d{+YQM;Gdb30sfiU8RH;kWq^NXW(N3YW@LbWW_kwrXQpL4g8K>4g6!>4g8q>4g92bi#jBI^jPuo$$XXo$w!#PWWG#PWWGtPWYdnPWYdfPWTT` zH-k7Qo$x<9o$w!)PWTT^C;W$`6aHtV6aItK3I8+G3I9Rqg#W-a!hb*-;om=v@INDM zE=0dH!oP1C;eUD>;eT2h;eTox;eSdR;om2X@IN_?@b8^Q_@9(U`1eX9{ClPm{wJmp z{wJgn{yowN|L$po|M6*r|8Z$5D0-5CE1YCVK1*Ie&tD5y`gch-NOGXZkC4oS-riX< z7<&3%5@qP+zl&c(4}Vd70($q&;sWT|qs5`ntGkIEphxc`Ru%I_zeMk#C$ATsf?m8t zv>JNw7|~qly*)%DpyxIeX^Mox-@;GOW8V;-gWkGKSR~9s_oG{(V@*MqK&Lt#9S@%aK5?FLZg9?Vj&jO4 zMVu^7EN1~HkmJP}&9Ubgb9!9b_4qk`vUtoyPUm|oySgKN3v(Jeb_GSp=@)u zE?b4oRrsOsR^frdWrdUf?|yp1Sm6RV6X7Ks4QC*Xg+1ZS155A~&N$o=T!1qT<${fH zh9N-^31=331TJt!!CasVXA-#R4>*JH0KE(Z{{6+=|L-6F{-F!}1Vjp4mf9B4lwG&W zKcVxGIA+wT``5(~P|7OTs6Euv>w)+1N zqoHKB#s1M;G=$7H{is-o&LXpo^;bWl!DLpvu16_4lgu{E)v8B>$ZWmUJX17~%!*X+ zTcH7Dw)RSX8|qJHYwo_fiOwLi)$`f}s2`cFvOlpF^(C{FT(@L&I++#Rw)%ojBeVQd zr+v|>WR{n)=OQ|V%yOq1l%YOkmSZI`MJJP4*5ls`QExKK++8*to%CwXm-LuN7EUaUb!li89o z=TdYOnJo@)JcK%tS+t#I7CMs5qBv*E(Gg@8$#Drrhm%>v&c%tSBbhBMxY>#hBeMk_ zX+2N}GMlgDw+zL|Y#u}15*v`T*v>%yyR#cxs4asccVy~5`0hvu0-eW4-m&`nLYpB$HYh$)8C51TdzU?ts1ljksrV?MieyGS zZ-+|AjCec=6_Xk9GzTgoGvelVR7hsTy~3z~%!s%4peUIUFF8RGG9%szf%3_Wc!VD1 zks0yCG0G(~;@!U}hs=mqrK0SAGkCKksz7GMi}+9$nGx?TLz!eod_f3hkQwp86{MZa zi0@M%zsZbvoj=k>X2jdikybJzzC(<(kQwpWR^%6%5ns7Pev%pSQ9$GenGxSmLz>A< z6FKLLd?z#Ydw$)JZ)B!+pn5s-mCRI^M@>M!kQwnMcH}ecVlQ`r!}Q-N%JmZ<|87{qRQEfc(lFZoac0Wg6keR}U z$-c;QGGjU9>LJg_j43GcL7vJopY{haddL$p`+eNY19|*!W*#^Yc|>Ndb9X;Q9+Fwh zActb)0h#?`nXf_ali82brv}J9GHXue9YF4q*>~5e9OMp}eKQU_gxn^xFYh0jBDcuw zb9)8{xk+YCtFNXYH^}UhSBVR9oyzgg7HK1e;8H5QqwBUi}m z?R54-GJ7#c$rCwGX3s}B6d|=_ z_Kb6H5K=>CPwqRGBj?EMaq0SM+S7-YP!1Mnq9iBlVb~WT9cB_P@ec&V)W6q3u3>1F% zpRq8=cXr5JIJL$2IAD=hDLjK@FIjEY49_6#G)=aSg=dh=Cy&m%vNawrXuo{O^~WMy z>40?UGk69G-L>mvCOrS|WIL5x|2hC;+|`WJ5gOv*MBdkH$s#9izC@_kefCls6aG0&k_k zF;QRZ1F+1(_YKn~QuE%tv1Y>1`#ta!**Na5#ddp_QuCf?aqVZ0f~eE+-YKgil4gFE zJI+jXa#6&dPCnXp^fW#1hSA#P84f=9@7|-c-EJvjfA90Pl^5IK~8TRi&BZ*8%U>%R&Q9;QfCo6A#}j zdbkMB8MWEzGVtD~&n(;nyfclk+6FoOJ0I^?vO0ok<~Q~!XW(v$5_aWszuya*>3QcMn6-|BKmM@kE@#&>dfu-a z%6_fO58J@k8S(h7sU`bwTwH{EjzZfm0PhLj?w1b%Z}$7KJ64_wz{a)Th?sy< zuimaYx~W$O^u))?#))_LkKSib&0Dh0)78SK^YQkQ)zOV+ekb!cLJoNL>F3+10DqkHh(<}4l{rUc1fno>V#F;^o zx8Eus9V*^-KQHa60p5Xq7Mc*e*9R|uRRz2w3$L|rj*rL1%}XxNJ+ufv;quyGC-9zp zZQQLlzEgVgA-1`*dr$Tet7h?)`A8WeJM`NmjSgCt)r ztoaFR(52nReRjYawDBq?^8Fl-zy7&!|IheHT<^?K<>|c|u>lwA_$PnB`~MmTc!W9! zU>{~49oF_Uh_az6n=z%R#Y!80CmRLwt} z`Sqz?G4HCDBKAX5_0h|Nt(0|=b!@owD(k}r8*D;R{g zDjqj~nLB>gyh!}o>fvi$f%p6g1ETH&?_h(#FGO z<8FQk*kQ4cn)h&iSm3_Y&c}O{td7w%^LzE<#plRLirB9i8+*iFr{{gV`i-_QXB}&<7+C)E1}U`;yosyVByZ()XAG!#|9IG3mJPhq z-RGD50N!iDW1bNG|1XtQ*$NNh@meHvgYlF|e8$2-v5vr7@NDLi55W85EnA&WX#rTu z*|?>PJgFO`#Xbhyr~1E5lb__(7T88SEwsu zSL_zG?$)92|L+9O*!5d+3~qRCNkhgc`m?u;s*I;sJ`V5t4N|szb@U2R+j9SCB5`_4 zwF7VBb_|lYb-uJO74MAT%+;%aca)b-UxN344+SS2Bk^Cw zYqgz$cSGLEn&-fqUo|Gza%li|X?MM%S#N6I;Yf>QSgAICUN&xu)&>1k18UySy;&1i z-0pn5qh)oxp_$*?XqL@{M~c|YFpc6_F7&)L)m8Og_4CG3-d*|Gq)8Zd;6NhfE z71VEQ5#6fDjaou}o^=;_R6xm0y|-VALy>sUK}uG_l5{Xf~Ob?V>Y5ZklE8bsV- zNv=VNmy$Wv8dO$oW9b8HP{dm!ZY!)oJqu5rm;r0h#>aCdE@CNOw1u%;@;wp{&bT+` zCagjC^hRp5H9x`fH*I+Fq$L1DjSM!wpF;hL-ETIZ&bC%-<9yjTi-~WaCr+h42RZ6$ zP((~q=R3r<$?9;SnV*wK|9J&%ikOds-@*JREwpP&Q;gB&%2lq|{?s<**oX92kQ@t7 z>$Y9%`rja7*~wQ&WB=`Gmy`b-VtaJpP24g}@^;_!(v*sKt9`etGl(6e!@i6b;9VE- zs_#PJ{h?I)ES4+9RkLFYpWTEnNI$t3ybpNyW?AgDfgPmx+v0sK?*p)x=ii>3YDCRj z*I~+4)3@3d2@=oe*ZsMzB&y0g`sOJ|D4{^?!cS42cF~|_i%>^ z74NfNYet6v?*`{9-3i_$zUkjmfp^NrRnZ=8@pz`fij%5)BXI@AH+~tw`=KT}J_2|b zA1HX6JAsl{Q}f=_Sf%hbG+4sCmJ2J3;7C%t*Q;XvsdyJFx}1sz-bIgxYIWqTU0An$BJei< z{jOXac&B_Su9^e9U&kA@l>qOcUMX#NE(BmI+!+r~J)l0lwY{%rxa62N-c2@cSQB3% z`zdw*AF%i1$qjEi-`;zVtd0b{?x9Q6Ns9o8V?IZbj6`s~ZLrdorJ zEVI351#8f+)Sjb%!yz_6fAYN@@QK~L6Jd5-3n|?BSzL5$X%s$w*NXj?y&JKkrmpk- zq5n^M_;Eu0u>ef#;GKe&2r!GY;2b3I*6qNXc<`9yZ9o6gKq}satkBJL5%9jSQ#ocH@IGmNL+G(H02|VtKV~OJ&D-PV%OuP7 zTDYBT-0f|rrmfMU=Dq9H)ep08c0S%dvO4zA%x~1$v<74l4SbE;Ccexbp*yx1EP8M8Sdqj>MWSW0Pw^<*%{0@@QBS5Y?Opkq; z_G!*-o&dRNZt<)FSn%PUDnK=Jr;OJ9hH6{E>3uynclD$c*ph{HR4%sDc%|r z(p)+`3ZI#`!c+{rkECqVDhA%09hs?fHUwbP&rTn6u$8(&3ZMIZ__iln_!QYVLHPXP zhyJ5MGTwn&Y*X!g4N|nM4s)9MIZtgfP@bfOg$1%jf@So)y-we_8x%JZ@A<>>dGTm^ z-bbglerb-I)#XobHAKo+NA9qb>}A=1cY>UDmtzdg{%I^Y;LA*PES>_gPsT<7nomtG_RPNV)wxU0uK-fQ9)WaFwm zZf3{pQm;Ydo1R8o>)-iykgc*hCeqCB!ewdqr>RPq@btkqUv~VY?f)ICQt}ndXJY5> znU7e|O^zF+m)Q#22M}-8?c%>;t%a^}w!1qPr?}vHJi3i@%XR!f~fp==3(2X(o0GfsDg7eh84Z~7aD~;@Yym!dzFs7N`%%w#i$74#^ z{ohaa3RLM&Z!w;jo7Bx3kF|W;f3H|wjvJ(X9vSDdd)Rkz-0&gI-iPxJdEAla5-(mqg)f z9M;$S1MkOY`CFA?2brA6zE*K909(KQ@|29n)T?(&H(hnUo)*4JHtyD($4#+i)Vwv+ zYK|uPc0S(OvO0Ru%F2G((*7j-WOMip3OIZ1Y zCe7R~&wFm5e0Ah$Ty+ah6yKEd0rJ$VyD;sy>K&y1x@uidp?a{Hfju*vtKHfiMb&RE%Ury?V<#WxIFdvoE_Nvq9dH;~{ zc3}QO+!6W)Y4n7-)BLY5?DD)PkCm^E5%$=zYgvC*?>-%P6K_l(rsy?N=`93yzQ20fcwHBgE_zcAD6SZWj=U~tG}81Q~MrTwTg@ZM;!uC5^} z0P}PlFx}-pPH!RJuKN2zwD9q=aR>G|enT%(^RD`Saqx*PosYMYtd5g3^Sd}a_xaHI zN?65EQ`XOPdfwyLj_Hwf3dODu;F|TSI79ir{lA+L;kh=$r=Q?E2wnWw*z@w$v9(XT z0qnj1KL6hZ{=T9AH|ekj5$}v9)*zz)XBAH1QmsLQ9uFG#C33fe^8VpVSkNG4{22F; z3#Ztz8%riETqDH;V_dO!!f5>KeDU{1x{cVgGrKE1zCFS8*0kO11JD0!R!99f>qfnU zbeeQOL(x(bSCx%>dS#E9*C*;V=qsNY6%mC{HeCNxe-mS6bu`n=FQxhCwuxhvu;hka zQzmEspj}hOE9s4i>*tGoh^ZduQzXY4G-TMBqYVSPe*a%8XB`(ECz}7${~LGUO}qr1 znHI_|()s07HW2>b=yY=FOV7x#^OZCeD_P^K9!mAoL_P?~@X7#O1Y}k2had z$7!1RRoJXB_{vto`i{E(cxgR7@AZO;RST4YFuO%H_U3cwPj3x53d8>F{fM?@3#%W4%Y2?Gnh@yTcL8qlj3EX_+Ht# z;Fz94Ys;y5yH+qRo1N@@yb)O)<7wuXGV++9+h`?hs_o&{?CSrUZ4s?0m3?n(~=o@`Z?Vr`#r~_}}GZiH7-m{LesCYlle&@*r-l-ww zBMIK9&Z9xZ&57zhAJ?pokm63=`yKjqFA6VvJoyI$c+WR!DN%y6x1(M+1uRJq!1VTp z#Cor#=55zE-k@}cCf-vvPSR^)@>ngA ziSMqEyro&$Oe)^ILjl!7;BDra^^mwYk$);Pi|GGnmLeXx0aEOT_lWt81-f_+j-yGKkU`H})r%x@R<{i~+A$oUP6W=czH&=7wXlFla-YUDlZ5*rC z`TGADSsm&$^Ly5RWR(I0g3EVP>68y)N*6z|PFbJ1NB#H#e1a z8ybzfj_9#>9q`7M8O>1!-q%^!W1q+Vn1AV)Z)P86z~1HtA^K3bJuwNt-U+8b;0A==qsfpXYQw-Y;c!n9MP$n#6<}^cxFk7#)@saAvj@s^7&n!}DhAJOF-q#&Mrb@VbhA+C%0vwE9#;7xq& zlH~0$Zy%qE_wj=|!dJlC_GaIq1n-@j{2Z47@0FO2SitzHJ(f=QWNRu?u(` zKi_Kb6L^>MGNUil_+tYNZ>DTtL(O~1B^QM&P8ztSY@GJ}4`&^9sCgG=Ec~%Kzw_~4 zE~{fL&HUmHCN%oRDPkVsb$8Ah((_iBpxGCx_rTTWMd_ctPv0Oh0-N$z_jK;^ykkw} ztK;?O-|DY6{#m_EJMbpH-b(VGy)~Cd#e2@7Gh^NZZ{vmwcZrJ=4L=8DNR@4nBY!B zT-HzeixcIA7j)`omvnjFU)|)ZL$rRh=dAUA`~Ux=KKy@bFzg_0I;=s&_p8Y@Xw7X` zWvVqOxc)`NAy|VZnN0TL!WyK4EKlG@4RBa?>GRI`cT&9jiq9oW+@kT);x$ieVGU9! z^+`GhhgieQdR1Qj{+Q|lZbSVv>NO~9aGcPguR7jMHg4VhS&<1xmr(Y_cMX$viI?*_ zUH_jgtK%Wf{A`0x-LBc9h_zk`A9HE^cgi|RCi{2j+<7*|53{SC-n76|wu@?7SMw=y@C6P}dme z>x%EXGNIVFU5*`OiPz(yhNrteZ&&&1m}M4!uGgVIJ4mYzyn_sWnvlHxkKK__@m3fZ zP*e@Pvzyxs2;S>Q+?+lNc$d929Gv|`iXZP^vI89(jjuoG*i;0(hptno6TuGBYW|qo z_Zj|}@g8>6lN@T^D~c`8=g(5d`^m=X*m=Ev_?>$7Hn~((_n@lt@s5?%VM#N;Cb*D1 ztWXi#ypO+R_Y->F+2W;GjgmcXJA==(GNk7n-)y08|IE0{?;!ma%2&q&$zsObls~)& zcHkX|Y;`1gpMAVrOvQVdQ&d9@@HXx9&Ya-A`2N245x{$dTibKZyHY&CW@qEK(b2eX zaLesv;63DBslGYz4!eRUk4*E&1{qhVlt)wZE_zUXXHtebZYLY(shGUR_Bl20u*J4h zMm_0#yw}U>2&b8!^zgzjN;ed-^8t^)&E(LZy`8mH(e`JAJ-%qeyqRa;$Z>Px)FrIs zE0$fJH$zX(I^tr3_5azN4Cuf+pvbe92OS%?I}a z??A1wlb!0NxY-b&%yOq_{Pvg|6>-43J*#DtJ@9TbJkx7$qd(^HHI}#EB$#rqY&Poj z-Qfq-@$s^8(oL6^_1#Q;dMh&Ect9n$^Y#DcvO1Q~%ugruTaI$BBDO7-p(~zA&s$nQ zXqO8s4EI&Nby0H<{n=Z_n8ky!QwO^~ZzuWc*f89q_eQwA9!MQzun-VmlORh zc4sDBE1zAoy~{U9vl_3;Rfp!OCHk+E|LhKaFW;vhaJtsh@M#Y<%px?Y6cxMcn zQO^V3CaM+13BWsHOUAl6EmGWj`=M5IxV`1^Gjnw(;N7i<71jp4tqwn${NScPrc$k8 zY8Xb%yKb5P0u?oNTuC-Ab9A-($y3yaSf|HhVy@5Ye7wmz#?s8M{)FiFd!{m`Sif{s zXaPO%B+JRxIZvFh1xJjfYQ^*o62oihy>O%d1vf~0$XUmr`y-0r6+5tc+jrm{X71-k z@-~UP*`12Fef+i~TY&dG`|t>Ycl8eM!CQfM3~SHbq0LhKu+Y(=_o!%m$FLa(jexgT zXm8JcaC+-VaqX?@^Zr;+k6kSSrjeaicJJC)Z_m_O&1~?xwdJO&l+|!@$ZwB7e&JFkbc-J4}r$4iG zv8UdgoUzzHP>`#Rvt{E7r}Qw|wvn3mo?egGRt=qx_gPsT2WjTFc*{$FzY;}kZ^iyF zrYZf|+f6zN*oawv*!NbO@BSh5*Z+@ZjQ`=|pws2|-nx47)zJgd-&y*%|L??2e}}2T z4suwBHE3bM%~o;^dgeT^C)FAh`{ZqN46H$uNJSjdf2AkClxJ zEt!|NEr$9Tqk&t0RJDetkL9liY48VJ@!SEH2u8rS1Q7{EoEM1^MAA zaZ&pvV){cY`hKnFsP7xP{2HWQDPJ9ttJolDE@EW)CXfX+=*w z=L!q!MmMfBh_p1dS_5|<2gUW-Z0`Ig3D%dbV0`8_D?D@+e8gEv5_#_N? zZ_gZRcM^D4c$xJ#o)>^gFT5E0wuYKF$Ea4nm%ch4CmUB%sh>Qs=Q7Gw?cL#C=ljHV zKHe-@9Up1txAgS0w)h)LnAH&eQqcu^-p_v3zCP~fh#z@><5}@QIj$ge%kyws-M8yE zNQiuO>_6FS?25EMtM||jyyr30ElJ+K<8m~qcqcZbKga;yJ#GA-q{n{0q`&X%XXGAnzN_10) zx4--|Zu^yWJ06=*^XAVCaQa%>`FN+w>JZY*@9?qVoMpwz*g2$c!Zn1x|9|0~!@v68 z71wUxVn3pip7$AT#>?8(hFyO3&M9brAx|9+79~{&{&_fYNC)0?Yuay+yvq*-X;ASV z*k@5e9`JrpGB>Fs@2NYl^e_S5rbaz8X8`XkyRu+n?|tyjo)2e%w^4c6($~NIF~4=K zBctyJQ|`S7?|Zq>_qiHAT{iB-dSQNLf9lQ2v~d|lGqBFb+g?`344U~(+dC=jLzWU2 z-;%m1&77Y15G&VdN=IDrcoxHkb(sFz8{@}2$E9EG)}0a;w1?%AGP<$F2If zIZE%QleqVQ!!J8k9xZ(pakrWL@O z{n;vQ#3_Hw#UeSjdkgg;Hhti{m+E&_adOo6XU=Hw}@p1h<6nHP>Yc;=s1}XaVN5?T{3AlUj zsCeZgQTTI{o$-;t+w*-YXAkhM$+)9&tkNHQSK81g=`J;Its(E0cmJe{ljBwvZ_Yo# zq2|5dTkMXNo}G`kx~z^Un)&suHfSF6QyCl5WFhU5N6-67oW;n+hXe4&J=ZU#6TH4-1wmB=|g(n z-q&plej8856@S?2Kj=x{|Fgb)9MEH4S(jhEecs7e$0e)T!we(-+}`5Yfp^5t#s9v0 z+gX2_4i)c+D@PAU0dGCahc*Onld|Dk0)e+vzz6$hJri(Moeftee~ZFDw)f8s2Hrb& z%&$8KyjQa?8dvKEU^c%lpJ|&xz4xwkwm5d-h#EdnHcri_yFIgndiAdK+xSgEt@HK& zM`U%JpqXEj=6)`7jS{9=U(`ETf&T36x;>5F4+c)g`<)fg_fmDbQnJm*0Cc zl;o>pQ0rP_JnwJ+Pxfk^`giF6$97nQR)h`y_Z7Rg6)HwlYf$Z(@7iNw4f5Z%L_q{= zkaE(fFYd4grCX#fvm26tzb&|aB|bO`KQ$q=v=6L7)(4KAu!MV%xbvA_+b#VuWgXw5 zOaJlxzd?)>u2*uqN%tKK5nAz|6iQe2>txU2M=7f)!ns*{ti-x-WTU+?f(T2NcWeoj=V1k!l%3cTtRZ~ zzQefj1*=Lm0eb zx9{o=`oKGGT3c@m;H^G_7o@B0kEN)5EmY}Cy@L!GadWfwzV3L2Y}|;otS2K3sChf9 z7!0+zcZ=3) zS5I~5@;k^$8uHa~=LJIJn>~kb6XI>N@vb05cDDZAP;Q0mt-pcQc(?a<0f;6Kv&W*;Il&kGT z;oW@)Z*<3PW#c?X%?Nh*ME!vDlOsK+?;qazc)QE$cu6zAbw1nAvVSRI50@O$|22u8 zcWX6j>uMf?tC+X6n3l@1gH(F(uMMmLL!{mNm!28!n}7;|exQPBHIM^KN(*HoA9k=i_}(R!1Yv z{G!?}mzH75*y_>Q*F#s)^H%;C!WmW*iihdoMT@r3-yq#8L{`LC?dkHo>+R&L!)nm> zh+&0)c#rD9dr6sdDam`lPA`2b-q){thD`_FwZAvl5*H`7)Q&&V47`88_N&Smlz?lW zpS1XAOcd_Q!^1+^R z+??pO&F%idU0t3x!$rISK4xXJ5RL)nx&(*LQy z34K`|Uuotyq+(doL_=llcvzMf_Irq>x;#}Thru4 z-Esc}oPqfJpZAW!`?amHP=G`1pv2Kvh$l$hZ*3Y?=HQP>j;#z7)KT-kp`)=Xs!;_e z$89?MqTH~8n)f^7O&SjVosai5Ssfo~=4XFE`)h845|%etZ%^qpdfrpC=J+M`n1ye+ zqS^Z*m;Un>4FAxAqEB7F|7T2*ua4ip-nWe_`Lly`>%cp{O;b$rE_2ysLd9Es$nNAJ zz&k>6^d52ccJQNb(F=jMPQL$uB~udc@6SUAmQIPnm!z0)5diPR+;KJDz}tqob-Fj4 zy|pi2F!$DfyuGE&+UC?6#qKyc?wS7Z8?Kquy!p1Z1|~_JkN0+29VpHGwr>5Xg6&hr z5?kFp`smT0y~RK39*jy0#i!Qgt@J|cXjl6?`D_--KGx-TkV{hKt7B@@@+<4o{+!-& z?Z7+ko%sWj_n>Rh##Fq;IX$_Kzjj0|6s}cM<=f;IO_w7UN(4`e``z>fILNk-5^YJHAXdu18D7^+*44aU!i) zsrSv@osV~mtd2~Y`F$=o)Oyyage~;88B*j;&wJILupwKdp?ItHpn$+q`s@D;`*HnB zTC2M}Z-%9Ob+BF?$Qo1nXZ3dJz&m!8xjD%@k~ykB74H>8(^ohFZ{NDLE(Gu7OD#oy zz}s*|)ECj11bpRQK`T2T3LkUsqPsEht`u18)d${(*XHE=_4CIHH$R#%_&=__CFb8+ z5gpJSUo9IqbyvAh>2&JV+k02o{0X-@A8)Cwj;S>BOVAy%zT0tS?C6Hp_WE7)yj7Ho zuO5HpgGW4%>KPwKzd5;L>h}5kJ@Y~TQ$5K4t^e+!zVg+v@A}mn$nt`}{r~^1AN>E9 z{~qZ7Jv*#H>F&Jg>gH&q=_i z_h6LX;Y8ur#Y0xcLjQlnquRs@-a-2AxzX&{?*7<a-3`R zN;9SZc!N|4+o)UM4TVnE|69uH*iJJ)zV5q~F-b~T{n_^(5jF2=cZ4&VN+g#u7vNFK znhT8L>8~Kg9{;xD$fc28zyEiaua4jU4|{hWPSw9Qj(?LvhRide$(SNSSSUj!C5;-k zDM~VAR%9koNfeo)G^tdQl)Z#RQWViZGDW7$MEu^1wa<4y=l877+Meq?*R}U^b^bY@ zI`?ticfCIM`+cwX8nis6eKKa2*c}wSBPBc-$h@=nzgvUF`|#5AN6P?jc1NyV2=8v4 zc|vCa@33&oExr*U@U9IN1)ls~u%!flehT2-6c@8J* z;5%3)VSF$-uK2-~?Je%uOYG-sMPdRBw70~vqIG=5$!}eUn4{nuZYU|#vr5#s7nisC zGLe#_UM_Id^DI#xXZ*`s3oq>cy}cou?s?a4p{|bQ4^t(oQfGLZQ}8~`aaotlTS4`@ z3Knl=7gaA=z*~bOL*j>zrAe98u!cZ=30;z}jjB6IP|>(mij2ER}WeiCBow zUcKE;!8`otJ0mjh9VRZySiIltJN!oh@P6=Spc%P(dzN!eW+>pT*tl2um`4a4P#L6> zqvZvwoA<^eA17M=A^1%Z;Jv5n*O>M`Ybc?8Ir}F8>>H%xR&uxmcksc9Xq=JOsXbl{ z*f&TwK6B3RCDI=6i)bB9IQc~fmE{22B^HnGV8wrW zDgq5J-&r3TJJY?*D0qjRIn_nxO%zaDjm6u2Uis@)fcLTR#!Sky zx04Px<}U|lZ*~^4?tMGG;L5e-A+><_mB&~8?g8F^ZkS#=aMT+59d>GO@ltHw=`Ppv zjm7w3a-6gFzTKeM( zID1R2y%Scx0e|n^WVbB*1Drtj-Md?rx;i-S7`LZ^&s+XI|Nq|{-2X#A8_fR}6g?}4kjhxnr;{rYC^|yxWTwsZHYYlrv@=(#0y)b>YCnW^lRHOT6 zN1P`-W!(FWAM_yT&lci$Fd&VoR+XEqvxb_Jel0)Yh~0zQkJn4T^5%t`(7076sy6Yc zV)r039R)u4HzWKX`cwIj{TOl`+i~(+Un1GTWXcO=MxK^+hJWHNu@6}Tm@BJ}z%@$q zOHVz`6kkj(lgRMp`$Soy0UY~}=MF9q-Os*6^Vm)K;N22Cv9+eFPi z@dDny6Sb}gZ}qdXqfLPKtCm=nt;r#9N856ffSaB$+ZsP#8Nhq2K3B9D@E&X`5$jlP z4M|wDoqMl@&AWzZv&=7p7beFokyK8ECa?#jO*z+!jhE8iuTJt|| zp*`N@I*M@e+m~dS)K|s>buChX4zBOUJ%?DR@WUy}h2yo2iqij>Y@xk%P}f0Ph9m;!FtdO?5fj3;^%e z{%ySL5<=iHzbTH#T)fceo;``lIrzLS7j3B>tvw2V z)q9$JBn5v!B5adNy6j2+ya_^7*1@>V?egsFEx^aK85W#bx>+!TV_!63zUL#j;okv18#RA@Upvyn5#D~D2eqAzLH|7cF$wpqb0=)084mxWG zc$YtYv-qNtHDpj#P<)vMoA=!(9!x#*eDDS|F6#BVohSaGdyi$Ek!-k0d%W+Vb^ON3 zPgwtytLs)C=ycsPxm;)bvp4tpB8|~=$Ki(1Q-0N7@E=Z0i+-78^;3iH_ugeKB~;ZB z(4h9K>(t-#|Nqz!`M>#t!2D07=s}k>Nr^}gLgs({HCq>8^&kbi;xtCkg9e?AL%2Z? z^8OrE84U&``7i2S?qG@CuYK@nd6x&g>9+;zZK*Cuk(hWoW~2$a9+$MqXv_*~kr0>s zqmSK#x;fV^GK}GY$#J(8)tV!Ru$R~$*LXNBg=ug8??LOp%g=*VvE?@_FSIu1){dYR zKX7-D->0Ha@vc7%ulUf*ePB8M{Ga!5NHA{Ub-M3CQ4+&c)nOX*v~IRC{=*X6|FyX449o+Q<17@mKRNImo3{nGX8CbL+T%Td z)`6E_B-c9|b!{Ff;9gT##~FOy0_-hf?+gyZy-oTzySwmrkO9NNt|GbgfBqk^HiW7= zw#C}byOTRJARVCKeX&k;kj$Hdp?e+{Z_$9wk}QCCacYB+pJjH{2K6n!>4;= zyiLR+&fMV;r2F~5-if+8ey&U4TLQiy1vV%9DR{>g6%)z4zixZUh{gL(Q1$3S!21Wg z{4_HETPIFzzXEt4Wbb^W1P&*RYu_m-?C^wjhE$3h0B^ZC$8B1GcWdcYv#;$|5J%FY zg@ zw?DrCp8tQT*!AE^TPJS!?%mq+L)O^^Hu^;@zp9SE_a?}^O!l_WqWir!L9K+UI?|<_ zOv1stxBs61|8EZN|Dm4^mRMVg9+a%=GIKzR%>UjyH?m{(ps`Ia9*lV0)m5?Bt-%9& z(8G-5qzcf3-jozrs>X)EE{Tpl{p(SgI+l1%0;_@Clz0yDCf-~%X=ZtpmVk&l!Z;t6a zJeWcEya_iQsjEXW)E#}jg*655#CNfO$h@1gzq4ZT*3r~cm;k)fG{lFI`Tt4C36W=j zw=yXx<;g|xg0!7lTR0p&;Kd&n5VHaA4Tb63A^~qJxxOIPvsRFE)?42;5;pH(MU^kl zBe-ElG)~z;)|I#yyL(Swt

uWT3h39g5cR2PePSQ)2@XEj*BPy~npAbn04c*WG0TxnJ)xqHPR?!yRK?*h}RusGwKK-aA^L`?d z%Ywywn{`zBAHe&jpTj$Z_ceyb!}kI2$Mf#{+=~M*Nc*Hu%!u%SSBJb&%>%qOxrj^r z0PkMeAC-)!tsvO|<&_p!v3bjw*(CNqB3&J+i9&b6cjtZRo z4r)6`pIyZZZ6CBaU-bo_H{s%mO9L$SaFi>z@01Nb?=gwRm-CON&^>R@RpM0D5p4hD zio@*Y#FB#dWtTr}WZp^oq0Csk+5JB262SZ~m8^0D;XUtt{Gv3#+gE+F;zw})pOfCb zN$a);oJ@F{^c3)BU68-T7w}Fd42d~|F9WXeVIl3kgw0!M^7GXBU)-u(S`jQ z*t{PwOFnyhlJRCF>yk<{3ZZ|&Acy5HqY7fihw&u3J!oPY; zX#afspz2k+=S|@JLS-GccM`$vEq~|#|JWG$zxRW{5_^QA2W4nBI+1%&CPU9d;NsxDzPktA;nu+yU#&q8D)0IgGk>%R z+T0u5*yd#g?dZ}uX~u_r4f4bhm6mvMF4!E6)9sR!agN3AK`BjTH-0%xlm7Sqp#En+ z*&nSV9VfqbW`zhIPaf!+(ep{Ui%qyasH0%7>A0s0Y`^_(>3k~g|0f)ff0JSw@brIH z1r7bb*2_>;$A*nh-!844*+Cwr;C*%M>C6q%$mOl$H#xYmc)vasFWU=vi>pXIM|f|~ zS8jd>cqiTObNZee0;~L9P`Z1{9ai`8o(e$*Bo14xcVLOFV-Tp5va*79Ya1u4eZXE~ zzYtifbxgV7ooHN38`JWl9oW2E(zdmKEvG%+jc6S|aPqtOP5a;v9bPEZw6gKpf$zAy z?SdxOFVnMvP2U#R+;YNy#ZKP&UDn2GLv+u(Qp%jFI@;64Dk6er9&fRy;GI@g-AC@; z4B`!ouy_l{JyQJzcxNqqm4xu#6eBx76Y$n&<$XPIKLmE{Yv9RP=mB5qxilRLcvpJ- z_*n^fZy`;KTrshNcv<)Hp8SW`TQsape0n*M3+6`SmJ=>7N)o~5Z8vUzgGrF~E^jrV zbsWaYuj=?Me=Q##$Z^MTTYMcp@58+%{JRaT;1;3j4(%8CcaRdicO|XU>Y;ny1nK=$ z)$v|zkDJi!1JZUByi>1;&%7WV>E4q4S)5qBk1Wa69ssn~(>bR5>po0PvRYc3`Umyicia?k)mXZ$$$_IX?Jccki(8r!PKx%moXf zaYh~AFW53*^XBC(oBwSi?eUI4>)^x5FY!R)>O3P}$eGjGDLu9sw|oD*cQjDW>wZHk zNL3QU}{Na&vNEi>K z#ALu3H;T`@t+03G`fl)Xq5^~4dKpyA|2bFJP4W5BJ#RuHb#+vv>>V~p{(JsULsJuW zDq#M1qUb@ll$h3%dr*9!rVv&S3S7zeqZRa^Ov&S$c|i|)7ZK^Q2Yeu1@I3e1wf!OR z(B5JF$F1%#)AZXN!;;_y>9J)K*E>nZ9i)1LdY7dQC!B!BLCd%QshWq)n>A1!j!B_C-a2RGCr=dFcx-?XC3dXao@4w@I^FXwb2v;@9T&Re|EPVQ zxxD2_!8@}swwKIXq5nNU7Vp|iSq(n`ZzT&;afJ8L4=PjIfVbGLIOh4^L*UGpIlH%a zy2E!mxbqhS-q-t^ESv!E%BO=$VGFIGlCeMPkB?&WJ|++>CsfM`7olu54CM{kfmO39nmNs-L^`s*Yree z9`GLgt{F1;F$9iC%oAVM?G6Vm{cNBLc&8Uhq?!QUD@Pj|>+P+e&Djd94MNz56Q<`r zJQv=$2;PLo{r>d27CwjFy&b|=+xA7$LZRBm2pK?+oE?03O zzdE5S&Tyq+n7;fx{HwQwmImFbg=_M$cd2ypzr6oSRUHy?W;fMmzuw|N!TXx^7$=#x zANMg{EZ$pH25$TWyxDdy9+RL|a>0vWIW*2Q-d#ld3^wmu;pW|S{j|qB1g+yf zPJTvuTjS#7d797Z=WPpKyVNZoD?kX2Sn^OXhOze!+eQ>5c8?)d9CBXl@7j4z1$@PJU+&i8Jxs=Z88U4L?`% zsl{DlcQAY&_$1^6f6`gCM$NGjH$L83Hs$LJZo2P5>sC=$$A@<%ft|uh$ozktg7-a! z{%A69nfF5CSiBEN99`N3czc%IibHstJ>B@^I^b&F_ z@jj2%u?{D{;{|W)Pn_g|xHuD%bGClO<+^LjWR{?a6P#8vnfP=Re~As~xc9y*U7GHB z2P9HgN6yPSX4yrt2ya&k-dT0`evx@cbhe0M@fIN-W&I9#KP@qeKzJ`$#?o^E@P0Ry zq>;)V3Ue6o-62)C0U%O{Ly`@xTi52zmcliWQr;WZUkxXT}_` z3mUhT@X_DK4V!mkgyn>PB<=BDhSt%BlVA9r!aMaYgI_37)@9PPB*vevZZ|^{(?Oi^Cp}9=kf+7$DHz)!Ub79nWy`ORZb>wsk2F zWM9vB`c546ygO2Ed1Z*>A5QRXEJ`Zg5=HmCHCMi%s*Zu+q4fv$pFwy#Q}DjMe+~H6 z?7O$3lN^MxcyExKxZeVJ$NW4-M0k_W-bzN95@ z`oa9qw`Z-F3gGSj`SH@tqS(B7$F3iP)Hz`nG_J{8FM~fEoA>9Yt`#Qkw8vWnt)mGi zKf#Pg+)N%kQ0gl8ZQOqKxZPW8nsYSqo-_R3VRuo+n_}E}!r|x3UcE`p!(V^1wF`{q6a+|-tSB9K^8o+OR;)TU&V(PUqBDKxh(WE(u0E6 z=KqNROKia51CAoALgC3fuHp=fJYazrnym9c58C_C`O?bqCMfV^!#3k?aD(*M$%kt7 z*gMEi)-{|*E!ki*G|ugL@9~vtewhER`Sc!qee&*anj4TB&^iKf^7EZqzwZ;cL3-#% zWPEV}{ybl1%K7pSc*Jg4=MjBmwyTT6{tNb!$SWjNL^Icp(en&X7&|3UKG3^ zHRSy3{{J+)U(#5-S57$1{|b0-SQGXU;eENM-6jq2&UUNNJEIT^`!DrQt;{N1u9e-wYM<8G!-UtH|vf&VF>SLql<45-V*GO zju!&nw`6aB+#(YSJAAmNCN|*?>qjojl>)rCq@F)F1qP%oOalh2`>mn8E`uY!m$7;8 zTr0znX2A|WK;zg|dOB{*^T+&aKlXab<)>F^kGBO{hX+o6mSd>{leN4MvFA*p>f>t6 zI>}wYY}a&o;0^~^Yy+ohQ7As|%UiV7ssj4yeg|2(jJi6q%j*J9&c40XgM#;ibDQeO zyjzH8B(ZpZ``miA0r398dAWd+x1n17)3tzim2|kh2jE@Kz2l?-;4Qv1#QG)R{q|=Y zoBww!X!?oZ9otmw&57d@I}SEkc6bbpTPqga@RAX`d-sRz$_RF)J>ITp9pgCp4e~*T z@ufTvhn?k$Q+wXy^4|W?SHxty1DyZsTHXU^{P~}-Iy(79D-+#!?*Ins>e#!HpS@!C z)~yXH)X7>6Ocn0=(l-zxI0zcwbo=wDt(# zeZ`r-rO zI(2n$P7dCBQ6Btv{wFW@wEW*-{`aHkLC+R<%8+|dql=InRu8gX7Ih!lLB8Vp`V#3u zAH-j!PJ(BUc71Q3A|UfW_kz~k{T{IAk|6e$#a)nUM4z%H7?Av5O!kzfTS5X$1zIy6 zVc$X8_Pkayyp zqp}W7pPdP_UywRM!8@;TyIvAUG@YCU}s!|qM0F7(^ zbSnN~F*fftCo+wfFCC+~?j45Kp@oxQ?#1R)w|??K0x^nD2~zkEJil6^(ls$?4L^#X z2s|W>KmS{l38deQSD^a?(p`_Kt7Ge!)Sc+?nFpkODR@7*RQ#{=|C-0q%dvPXsWapv zya#x^J|Vp8RF*bv2D}}j>m37CLgD3uRtXXc9`K#~fnO7#dym>J7uEp01u`$1#~ibQ z1|3{wNbJ}HlKb774DCu*xCf0hKdh`>y9fLBmZ+5+of1pOX^yuyT1OmCe&@d)m%DL@ z2jc!ck2Uf=K3DIp2in!gtYJpmwY!&p!+&~<@bJso1FS3Po;Sgjx;og7EFSB)GP61H zq2QgnIf9woz4^cFUWUc{?ecg7g!jcea?J?u3a4=yFTlGg@9}#nz?+H1bmY2#2V7`Z z!Z84NU%D8uXCvTkSd~=H*J}mYcN5vrQfWpSNk>VT;lW zjC8*_*`j}hsyb{2hd)FI|9$?SmdE~oOt=onO;M# zK^E>0Nkw`P%XP@I1H6M&F5HWKiBKrKdd;12*I4k1-R8<-BG^F&ZoPLS0bGN;?Q?Wx zg0&@NVzO+jPAK;Lf0bz&k3{f%*bt4o9k}VsnJ|Jm>N22=CHz)_q*y^43UZP=KmfC~QY+ zTsa--0Z)AAe`pAJb8aWbz5u*6HgTpn@3n+i_ED_-c(auL$&fg8BI3EzY&+BP&4bl*-tuO~vq z?Jb;V7^2_P|K%+LH??-4Ic{urT40i9@F2xHieE2!@@w0ol zyc2X%&TbXkPkLr1btw5FK5woDOHZ8|F1jC(Hh-h8j!!;j90oJp`{F4I-US|q?~-}< zA33Ff#oHuNFcaaOuAKP@;caSIGd~LOPKr3NdTMzn{5bK2$31rsSW@#=2shx(bYfIa z01QZ?4y#u#wy}h=&wW2=W{%C9Ur^sQZ+HQG2aS_73y&B&fz6xKJpSO;gCjK8y#>%Z z_;K>vzhL+<`%zv<_?G^)T@ep)c@wmkWT$dClGHZ6`K)}AimSIFEXjAZIOv`?;VhMP z+#A-Bn7ujCpMv*uUCX6p-oKx2lE>oxdIgaI;e9#&Sf~$!`M)4}NPIououqYX`{%osP^L}Ifu~=vdEeD+Z&~2Z45y)SQPtz3 z18mq=Z}WxE#>af3J>K`xI$q%9x1@x~r=!9P9j$3QqP5}~F7JTF1z?J~A+W+?j@7F^dB6pBKaP!pCDz${Y{gCR z4AQbR3DW%Y;QU`KXFOIJ`vfUvdBV9v>*m3HXx!mXeZD`|WA`8raq&0y&jx62iM@)} z;fa%-Y(o|HtIV>j3Y=%T_-e_p^j9DDSz-Hif;!R=&Fl>)f6PpF`s+ zNM6q_aAWiK-D>6pv_w6UE45a9O2Wj!?7FBiZY!LC3i9`-a-AsT1Q9NKrJ1$#i+FXeA#bBXqNFGuSj;^bGzaWr%C z0}u4>=d~D;#YJ4+1nYepqpRLMpBH{F>2o3e{Q?B*o*s$q%jups;TUywnW*)#Ot32&XCSJSU|omJTVHm2 z^@oMDcQ|nbt-}x}zm_*EVEI&DsIX)#`N-NtT;87=bo?3uO$$on3!je-;PbArbs8S; zjHP?t@{ZKi@$|aQCi$7Kx5Uk(;9cYz?MUW*>EMagSiH6JH}@ll6F~alsBJ?1yhAc*#O-$(1Xh?8Gb-MppCzw$s@edZ*uo2j_G1N6fc z*IOSfXiVkJN=?B(|0fuv_qLiZrTh6mU;%Y?@R*jA#$Eb5|I_l=|F7J@63b4}gWmM? z%=92F@QIzECL#f=2OZb?G>E)G3La+OiS(dK`|ArlKo9E4x6)E-41p8tSS${zdBOyP zkunLRV}6?;FgPhb91TA}oJ8tjH27f5_i(ycU~x@~`=299|6YD>TmL z<_XoOU$J>F39i_&hOwXKc&DLtNa5rc9nsi1kUMwYiw`xba;V_%AOkMme0%H>{m=h| zHtOn#Nr>$>%9xjn5&*tp8u-o(b=G?uDgaz9B*s0*HA3m1@MfjpU2gL%jm+DAg^fBEZ`)tGGq1Ni@xuS`%zzaBD=z@>cBv8D zFx?XZCs{B{H~sN|85VA-Qv$qStzwll1-u1MyZar_wuBy^8kE=+i_P2EkbyUH4)^QOhzl|*-e9v~zo%j1kE&Im2V8kBa}yun9oX8s#24`Xyt9323g8{g$;d*H&@&{u`ne@O9A_rpH=zd7-3C3STiud(*HbpG%A|Nq?$P5v6p|J)Qk=zZhY zl}Hal=6|k@<_oZTkR;2l1IR0OGh#)Jksid6knkh~^q_)oNs|mQA@IqgoVI)up77-T z5rzTKgDkHsJuVCeq<|I6cC3493H4_lXtU+Teg>)CEn9lE))Z*~jnib>-?WMu`w=_8 z$FjH0U3zG4KuHx{nMKmV_}UVY=~1NwjeKTj)lb=)~s zILjxODZ@P5C#=v^S-Efl%*i*#xTyiM)* z>GyS>u!`ckoG*a4{-OsJT7Y-8*XnJ2sg{uU&*yIns<4+>hAMWWlA$S*4;p8;-(=qE zQtTy`&nEf#rlq|!$D0+cV6yQybCST z%vp;=V6KGpe#qYw7R!ErBn$AaIAw7m9Pl2E*C5@Av4n&rIA7gL#O~f<(wr%KbO^8r z8fWpvdjIu*c>lk(Th{ke>3uZUy(7^&_Tc2l^=JjOpkeO3-*oYBd-H~h!-=B;KhE6@ zq z^SAlu5V$`pWY@9{p0MlP@8+?9_rhaqMDGLM8VPFlDRGuiTN`n&TpTuU=inpD+%gF; zIc_uO@72+<*xlQwlU=YvjrPvo+|W8aaPn)|Za5%zbMCwi8hZA;EX9BJcGZ&mYMTo~ z>Hh3(&28%H;NDi4dG_+(^M9J0_y0X9F#iis^q~4WV-mRsrPmm+WA&iYigirLH%Nx| zRj4C9=+WYmuVSDF*$Ngd|FAFwcC|B)d^PC>pSzp&cAsa|I_zHtsG)53qUHEs||C-Zw$YLE}2~8|K@sP+0 za`(Pl{hbwycVblQbA&gaCohEXUK-DlxE}C68CNA-q74p68>fewlD*(Nz9m*FfcN2O zle9;Gx0|1g?Y*Ox(Cw|EZpjJQysIY9FD~bpB$4B`nO5y=IfdQ5M?~k3k8bUvIo|bX z9o;zjX)f~@o#2~$_qNfJU-kAo{tnW?zc({!4gFue&j@1>5Htph{;mu3IyVizn z<^}0U_g=ZShy{yxSt?&F!h7C^bbW;P!5tl(mdJo)ze$PjUtD4)R8OLyrW09tQ9SrBu$}li79NS9))7_wj$mn#Lw@h zIo@$-9lLSzD@d_!xqfW!yg${+9@un;iupfV=6W_85B<;oIaJmWpOfJ_JOA@g@UD?G z|3vQIPvwJ|v3O^`>$X97>rF=)BE0hp4sjvp|H8(B%L+q6;PapF72Of`f|n_{`!WOG zg&MakM*(kH<*&mdHQ?UcvgP6Yd$G^nxZn2}W=H-ZnW1r(-+DE6Z^k}*>tkSXGAyP& z-oj`d?Kt_>J6 zVuT3nCD!QB$c>%9+i7lz{esq^hm+q8d`<$UOb?F zR{`+;Iv_VP2?xVBS8qEqeAyfR@UAK565uVta(bR1*g>vzGWu@1))LzI_zL%f!`Qs# z@(fQnmX49gaV7NxqO>+PZ!z|2m{+2M=6EZib@1clS7_*Zf*3q^-aDol=kMyppa1O= zMYmd4Y`dR{jB_EsSZ-d_|;`pDf|JpMK(7VlD>8cl@v1zSrMg!jb> zNJ$d#E{Q6Uds!b0cUC*F%Gh|r+r1{Q1Owj1mxcDL0p6bLY;RuGvV{8XSQZ=o1MkEH z+pvN|<0Nw2qpa%8NeG*F{p;(hMo(#vcPd&(HBNrH*OjY2)XtqZeDI68!g(s@{|$bw zRZulrlZyg@Mg_e->?ht_LIL*;RtR{T*X&vb$$i*{LjPaAw0tN zo1}!s-TG)BmHZF)-e#KW99X-L_Rijf&^l6Z@=LPt>Q%Wpciu5;R$Ni6r(*v1Iq1Hu zSCamDn^0FryxEzXtoeWEf0~^4|2-)%|4UNzpw^0=+sHjACSP3$s|U?{*?FrC^q_mc zHZmYR=sb7gIzM+6-H3bk-Z%FL!y&i09Z#P2fdl;CM9D4bf^4^SSu278sqId^O5hbD zG?b+@7tb@6RM-zk`IgsMPgQcMHw!Aitw^EW*i;l}IqP z)17+{64%u5Ac*46|2KU<5J)?GHU9mtpWc3bA?ZC;by)UhKm8UlGygB9;N21~w42P^ zV*RuL7Vqmk>$W1iSF)^UL3mr8d^!~icn9Q!c{;c*~J1|62M&k-MS1wz&6PtJJB!6g}O)Jgu-h|e1 z7AHTq$h|zryt(Im{{Os^d5n#k`Jb@tYpX*r-SZ}xEv2dsLk&$~vGkewUxI>n^Fg6f zGVjH5ANjF(&v$>`)e3mW6jUujcn=k4tix>C)tgC>{+uJIDU+o+1@qU8V z;f9l6SKOjUqww5$OP|nAK1Id+UnQuqD9o{g?s+TkRi~;BZO__k(Cq#H;uO5UuTah+ z^PX6d&WFXDqaE@`cqhg#5JGtW*#R%C0laVUpR)RMJQ%jiIyDty;scXPx(bHDfYfA` zP!I@s>vj&_{jiz{X@->sD_UUl*4-vwXg)klQbpqizh$5LB8bh~IM>v#me@vf-P-`I zV?9oO89(;iKVE8Co($n!(K5+Pkgy+qGcho5k z-Za3Q=sdh#`4bUZyg1is%LF#>lxu98TKz{zqG;Ti(1%4E3bA>A>|XbysEzh`UqkDt z#>ua9^chLAX71g)hhfCg_X8F4fA&gwrMnw7>20t5|I2r3HC1&a@@U+%iugPK|Ns8{ zXz@3|{J)H%2mO3du1fAfA|?tFSUqTm)b5MOfW#e8FwFyc(7|w>Rw1y&il3>qb2JKu zcdRAFZmjl!eGIHgR$vD?4lVsuGuQ;_D-)t_F?Jm~m$-!gJnixBN9#C;lV5n=0_Ig+bLVaU$ylkhlZq20l?8>K zS>ANdn@~HSx;no449d*zAeT_^?l5JtB=fGgP$7!Nd(*43RD`$jsM`$h_b_XSHsD?O zw*1?+ZQ%A69ia;vk9^=y>|Yg)0Ph_K6y2u*@8-7+2VL|np=RC8sZ$-;ydekYMyrrP z(ib$&cH?-+P#SjkzV`Lh{g`Rm<86S}k%p6>;_<-4Z1?8QyF5$Ayeu34>Mh}XeN9p- zBmM6nv#6`%WQfBa$F!O5Elt7uhxDe~WZuCa6GgCi-!@>mj_@A8`FVzSZ*`~L9>6<> z&HmG`ox!ksGV{hYX+CgYXtcBj;9b9}Wr80JNJk2?R^&q91?dkgBNu+c=3V9B8JjvW zNZNwNc^U7#z4#xV-qMy9F}UPLdxsNsXdN0j`8AbP8AkZceg2ne9cH}khyV4K!wVc# zEK`orJ@0M<>grgd@NVsB=*;1S6b0|L&IdhY-Wy7Y!kE0DkIkID`A-`Em$SF^_h--E z%x=t{y+!)Xp1t*(&7Qrvwr&x$*RzDG4o25TzQ^WWFJjH{#%qZ58jWLJ?P(Hm9=m%B zE9X5uOoL}{-_Sbvaq<&5I(_w9!Q8v|#~+n@pMRoa{!huvNQoX+r^WGaPC0cxp{kDU zZ#X;7fv>l4fFC}e;W~jsYN0-}4O0mC$G`ufwLbwcAjwhmpkFsn{OkRH0ShIUV)dZU zq%#`rV2M>J*)@pF|52UWc#6RiE4kN1wm>=_%iGsK^g^A3l(FRT4`2uG~a(ymQey z(s1$<%&_0Jym9Wl*X`YLteXvg2kF54$)x5758dw|3lCCPhy5SRQ;!NSAeXmfD0ufK z3eSAr0=fVH@Sl7sEZ&hnET@nG>F(KcqX_Sg!0j#ZPeN?x`NE>Y zPNtE7w`+xW{6)Y!%am~GfHM&aY~Q|LXg)UYNv7XF1)2Iu-e_F2m!5k@Cidkmc?PCK zIp=AQH^cndI^=NjQ!cY+3e=lB@3i;!nFrFT*g;yatlR%kg6??}f~cz_>{WkDvwR@J zdj%!$FwYa@0jVwht|S)kE&~r*VY$B2mv*#{qA~%impzD#0+rk9C2s#(dz- zTkZu00^VP}Q+(3_?>>HRDv49hY(PlapMbf1YRV^FQ+kV;gn_{O-*&aL-;c?JC{#F6*VP4%z2&4fEXN z5#Gxwcz69g_=?PX{(I}iSiCJF-JT%4ht@|=BD@ueOuLK#?qbs2l28Tnc(n zT{rW3Mc!bT#LXyRCgTgQc7Ao|5$HjBdAm28gC11ydwlXnpe0m&dFRulci7J$L0rK* z7?1Rl%Fwv>Z&vrpoUq?PLX>XS_;#g%=6cX(w2p%~`L*8E%{=r zmwDFuxabgQ&oWQxt(Z>W4vppEIDwO&-8Emm4Tf{yLGF3HvGl7V{^hNq z)#+QW?H;3h-t79+)p15v$n56nnG+;M3f@DTvJzaJ#Rt@b#=f8;$h2sGw1&b6ubx5zSJi3zE^x=ITr8Z7F%WxC%lR+{>$M6 z>%Q5;iHo0S4<}-pW)CNBN6#KkESU;~WI^|i<_H-Nx`NGn%$zVB1`a1e(733^KEXge zY~E0Q`$$?g?Hx``p>=5EgrGs zws^ZWa)!4&1@HdhW&UK|q5*rCVex*cwSI>8(j)u+3-4PNv%K$pndQy-eU^7~)GTks zgQ?}pOqNiISDOG&4))dC3)0m`69MmMXq=Nt?(~rz*k^C4msgjU(jf24XdTHo`Tgn4 zaqxOEciwL+_i)O+qvGa7yVxGX{wccWO^~=qT^(OoR29I@iGR=k|J#Y1wtf@L|7$3E z&}4$=VR8@Z+{(QQs|TeW_;wE2K|Y_B#qdl`(`AAubtSLuaMuQ-EY3*uSQZ%tp= z^ISgh8`wb}ir%2e0d|mUlIz)3K@W_qH&j+rR%MtuzQf! zpT;T2-cK|)AdR7Q=;GuTd_|_B^WxkGBtBk&$fzRxC6@4JG{EX%2>tIMv#6}&QsCXh z*-z}MQ1G7cIP{Lpd-Lj!l~}yx*)FCcysO7dW_a)EIB%Q_c*{p#$TtSO#Ugy$`89mu zlGY1>^?P!8 z%vqa&&osyT2wKNNocx?ODogDvo%<3i4pp;e3ggfJWu=WjiIS{ze~DfFCUtc^^9z>%-kFu(cfZUbLUoU#!({&91?erSP-tU56XpVO;T1Ny}f!EZ%2_OJ5+oNgJeQcynmhm&1Vf%66**On`UO(7A70 z*Z9Kjda2XpfVXF+dbSeatv7Zx)$=hC60>eGb&tjF-Xm{PZX9#(Ch?(hr5=Wvs!OnW z^VJhmH6PO+Z^lZr4xIc-9F$nr=*+!)|FAK0iyFj#y`@WHLYQ8%Bi-|Uex15H;Ae}@ zti3QZ|F5FpJzCRLOy;fEVLf=dq@-WX5*3`n~pr} zz~(Kx_C&DW=vSKS-j!$_GC29Yda0n^S3Gy#52lZV>s_K^{y%T9*raig{^$P$D(ev5 z7$^I8{->=uA1fO$|7-le9<-k^GVxz8NI&qLK@F=18J$*7L3+?r;;}Yl2YGwcOYSD< zLAj?7uXg|glA+n#ME+gAu-j4XN6bsRAY)>}Sj9jS#1@=#(c?K0;;z~)-V8_j+{jC;^|NN)Uhi$# zj`03M%JIJic*{&kzPtcw8wi0t-~89zgS0x-e!@xU*6Jn%o3H$ zz~4dsQtMjqZplTu=j|FrT^+0^_0@%AXLzrr;7w3+U?KCiU4Byqi+8<2O$@@@ItqB#wSClT2fVHINAq(ch|uK7&1;O8 zuz5=)$fzdtbdW~TxP1#axrKzVc}wfnuFo^7r@8JegVwPeCqK*DshG2S=g!;Od{f~^ z2`YAwjwA9*;6%FTO-Q1$j<@UXA}2_od#n9F-utG->|T(0=L|S1WAWw-<&Q*o7fY|4 z8IZP|;IJ-+uKSA&0p4B9*;>s6ETL=%moJTK z*aH&j_50JKCpt-4Xk0t@ql&d8Y~IZU`QLco(;n|Kw2pS1{A%>~Kxg^q&ij6g*91e+ zEBwo1TSV_Z?G&f``Jb?hx;pwF?zAwT{d$Wk1@AxQ9+70;*)ck+v3Or|8VNvnCvIHd ziEK{l>`k4Kx3}uDWW7`c^Z&^6ewV9SzVK+GIiVf!7T%HJ&j{v!osb5V2NGcZ-&54u z3t{u_kzpLJSoD)Ly?ZupZ|M)V!E$Wg?o+!fbF66Z>}?dS!y6|*-`s$~>OFJk?X#8r z+|Yh}-ig(b#GFT7bl<&?&p$&|9T(T|E&3Do_x^vZk(;J|A1tvt|E~w_XF0>6j`SdH zpr@vPtN~-a#hX=JgIuwUTpbq47%?@iYutA!!-KH)ull* z2c+5*yqPyy^N^R=)I%kjSiJo+$4n94yb`()9*RJ68nk7_R?!S2)5iEXIew_ zg}coZmTeoK$os=+tr-o0z<91DwzsCd1_n7sMJq}6oKoA8IaIvivQ z=PBNqxq7Qf!JBEFxC5E@fvaoRV)4Ew)?b6n|FG)ECWQA^$@jHRfcFi-bzRxa!Ei); z+d{$pzVMe#&}%`!dxT>&{2}1Yx?5fK850pIUiqB!pb|Fk;2)wtNDb|z0yJ)|o7Hgk zHEiBr$IZ4}H~dI*-8&ksqZubZt%?)YnvQet-fxS93+E5v^S)^J%Fxs=jqZ7S9Hp*~ z;Aek68-tq@|K9&kQ3xWLB#Q#Y3qR?IAC$!P>+ExEWCPG-A2%ZKCtbww*@_jt4AvQl`#=At?jD4 zk&WGhl74^77FgLrGC||=wWq>d1hEIC{2%s8>mIzPxgK;4tpmo%k8_P{L&VtJm)OET zmM7XOi*e_F!j7AlQUn?4e?W4fvW|kO@FlY+Nct4KIZOw?k$G#MlADjk`|~Ym6xl)U zfAIb_!uxV|9D^|6t?*XpE8k!ce9`RnS21uv`b=|hy#e5TB&6!>QNX)XhcFfd6QKuI z9~=gyu`jVFK78~n^GXZpJ{qTb>ExTJv)H_o3rlUvML*CS?{u_|be#NLB=2`?=gysX z<+UU0pR(d#Vkf{Y>N^NA^v}DEx;o?<`HlBx%haL+s}-T^Is zZxP-)uCFQ)-Uo%mT(|*mbL}A07QowSuVTP5aC?i)ygPxqfOn@T@9*P)_w?%5^}Fv7 zA;;XrE(T_7-g}sDWw>#)l8&Hp>3_J51l+NCXWZEn>=H?PyoqQXw{Y^iI(@b-=l9%s zyLfE4#Q@>oy%qA2OZTMH2;KAE#>7ok9c!}6UR8z6@Ybc^z3}_>9CG(gsCmJN#hW8K z_A0`AOp~D+;oWI}DTo>H=K1)hr*lhy$VpJm$Ic&QNQ4%|9Ri>MbFgi%qXx zg6_LFL5#XOjM?r^YhV3){{P<(+%)#PVE#9z=s|ooGBfueAv?%bzl_+idJwze+B#&3 zUCw-^99d$0iGj?!z!EESW$cB`&mfpku}z#&$rmQ}eA{*$EU}Y?x3iamCD#1f1yTig zK|1qkD-DU&*geR(`c%xc!gtaFG>+5p6?^(We1qg*x?RnBQWeb&NbYDIRyg@Z?^~;< zl{fbtq^`nRm3k_^|9948i+?PaFWvVb&Mp(G>ZpLmln%^(LE4CdH?Q7i9r6-e-z~w0 z#rttaOfSOQ&EJ1_tyj7W>)n7ilY(T3Dd4SC zmI=h`u5Y~Bg3@qX}k+T*|n%};_@qs=clMT#*3pEM z-|Y;!Z{`1ky|;(N{Pcul_?NewI-IzD2=xE`zt9Hi>L_E9I%xyGz5Vz6pT=hW|1KRc z|8Jq_K_V{VFUdW~$#ydjRu9^8#(pC*AT5+|dxP{KLZ^{RIk^A-&;IDo?;8HU_Rc&S zt1sUFPmDf84o zippGu-#$9$uIJu$&-Xm;TKBH!`K|ir`+c`Q>-+t@pY>Xwy+3>Jv$r3j*A!h<0&b8l zQ`s*N32IPlvav|#k2d(U{)5Ky7!$arcIK7nWfyCqkc&UvXjj{@<~PJ|E{| zubfM~IW>dSp}~8Bocz=SY3TA+L@_TvA>LvBrYPRuK8sD^U2^ugWCOsPJ!$1;r&d2? z@1~Ch{YyL$`EB=FuL8V7lYKkB0=(}#7aw@#WCFkFtoM2=OpJGlxo)m2(n8J0;_8I< zm=4$y)VdDQYW#vvdzaT z!Ul=)wzn+y(~5h=aMgP)=EIpJKd9Dl7njWR@%9`M*O%=hKS4?nw!Ut;=l_HLUx7X! zWx{TKGFemATbl;&c`rkj;dq}nc)&}9cPw>72#U8#k=Yd9j}?UrIYEQOGcpMIb^0MW zrtAhL%RCTGw+FdF0B@t;-+X6)2C3((li2Vl6IdWMvPiSZWkEf(sU-A2XZHVPMg ztF9-;`*6WTVV7YQ!{IH4`LH3$Pb1{)Xi5L{@$TkO8hNNhzPu${b$eXaERgB@f7w3z ze0&*}ErbK6`hP7NyyxC!*@@$=^l=q{!EWI zWet5k3eFtTZv%I4{q6t%yM~*={top21~fHjsqV@Ds6o+%^7Dym&@RiNPV^h3ZH9Ya zp)<($k`f z)wxIi@`4m!a&pAXutw@NEH3Hb@Mo@e;x))X$NejF+RGSjh!w(oTp-EsaF~Q#uFCY6 z*q=qrh`W(Pen8si^{=z7w#@(jpN}zpK2Gt?`O@Y+HG|Zr!CPeMnQVNBg$}U_5#fC& zrr>NEf&&a(_!VQA4n}O{r@lq%(=}E{H$g6zN*daCl$Ae3X#n_a;*| zLfmWmcv}b-Jm@zk$9tqv{y{FwH>U6Z!?fx1u_HW1uPZ#^2k7mx8i!0~nys-8=P zH|qiaIp_>>?VU4IcrOyOP3Qr5r<$0Y%msLBq$B&c3xVq`R=imj2k`DNk+iASmtn3M9r`jpgCez*NS=+aL3xNs`}pt6}@d zf$29$UpCz9A6-J;|8uM`&svakl<6BJX-WEga4eE=@BFj>uS+4_h0Oq)c4BH9Bk`^UiOf z4q$NxaDP?Mzr4M5HF#&d8UyaV>0mx0N%9jDH8|J)Kj{BeUb$QTcu!uveV&F+?v|Uu z{MEadJ|Es<*Ber9{O$i4tkeJR(*gbeKAIXNX}RYaUW1-Z$}b_RK}Tcn>Y@!&M9pv= z+W!kwZF&uZHOQ9Onyq~~eu&@6)IIaT6FX)nSzcv3vJCU#PLkiUl0)(l9Mhjc zJ`e3F&7|jwowHVEI{QvDe+>$t&xd5ElZ|A`RD-ma25$+$*Mm6T(ei_fi15DExa0_m zw{fWS+o|I%ryOshCrF3x>^R+)?}rqJ|4?!UPwdpY@UTAvc<&b}dG!?F9hTIZb=ANW z)_SZz;<=s}Z{7eOfsAeSRDCQ?$2|CS&?#cPcdAuK3dA!W-a?oUJ(B!7M#V-Q%BPPv zd%{MEt3Sv$NNu)kK0$dk!t{9a(&?k%yv6Vf|EV3MJv4ZW54TKRkcJ*_*~L@0kO=SG zagiVt@4dfP)uMQ>9pvqj0eCMu>yckt>W5ssIVt;G!UNHMTq2bL@Sagxvp5IfZJXom zZMfPL=2?Am_htcNytQ_0dRtvvPo0Csv5QGPmD^8@_sT%~yUq%w3|GDNF&_#f`TgQq za^UI2^c$o_vFRpHqUe}G<~}~;qCsK$28lwak4~lQKGARw1*h)LNCD{4utXW-i7%nCCN`w z&dID(ZTi(ak#d(yKZ5*lqS5kuUe=|?OpkZI6n#E6C(mndFrJ#67}DS^8pXFCpPZzu zI=+Ai@3OMFl_=gtY>88QZ^8mYL2Ll;)U{&w?}NR!hZif0> z(El6J)F4?^b1u9F?J8cnjHm`3kbdC%5!9er9KBO_kUsd8@?a5IVrTU<-t^wW56ODt z-#o|11JNm~mnZ`@==f@zb+eQioG5Zy zVp%Kk8Kl{f`x=rrzht}_B<6#kB)`?Way<4toc;__Mtk7N_Icz(EX6-J`ffP$zd=Gt zqtl0yi07L_Q!hvzq``ZId!8tc_mCYdPK3AdGB^gsTkz`5R_qn~r)&qK`uvMzCm!=W%5c@&-+wV!`I_fbj zE_-cSdg*oIA@=)cSu@VZjEDC(%m-P1g68JewtG$=Zx2|yZqk_ic?-&Am$7CWKBk{R zQr4cJ%g4m-j3Fh#0Q7;h12lNcu=04|c!zwf5hcQVh(kFa#an57b_!^}g+?gMzpJf~*#{2wE(ZOEHB8IEpNtlldB>4^NuGNnD9~^J7i|txpoKZn~d#ho| zjHOqNFEKsd!R_?9hp$-)9JH3yZP`vjY zQ`vnR;4LtGNz5(84_SUG7O4Xlq(4>U;wk`mYmB!>KLmIyr>)t}r)dgTJv8Q8vXvO` zSZ9U3mD2C1byys0J3@6jLyY&GjqLu{A{YlKjMZ8xvb|reD3+*i=yOHC2-0 zO=;-X@HigF^mtR6=<}g5lk4b#?8_+L`)Tl&Iuq@S;~igbDnf*J=?*V0wEtIAel+!Z zi`ASl$xi_9K(`GM+wS-w4c&I1x^z5{uqDS;UjV#Ii~K%ajFeb@wi^QXTuh9QN|9?+X zwB{K3^%jYI2@-6A{Y;PdZeIF)tjx}FeR}@y{r?Qr=MyCZYS1B?8njwrLc+@8Hax(U>vSXq@H zXFv_Q*sfk+t7ZmwT=aT;>Cq8{D6Q%jj=MEY-%z`-xIpo_=OjN9U$GPG-Z=9~djZ4M zpm&%LvizP0tXp%;X!VR_6+tzoOWpWynO0`IK^cf z)d9SNK3y-n0PueNRZ)E?)f6sNUi?9_ns^48C@Pe_t@aJI0*m8MZ`Cn@i1D_T`?2z| zK_SE8{RH!2Lz16Q$_jDE@afMWt!CH#wof8o-l~{cP?Vl=i0Sc;-cFy7?JGHT%1-;E zGe}b!yye#{pMm3@|Di~V2=AO69zzswS)<4f6mQNjb309dch-dsU+?PqA#Ft$*)5~N z>g`;Aqt^g$wZjKHuL8WiFB|by0=%zo>Yru^r6 zOA{KrZ}s*b=EIdFzoq55 zZv~R4k9YRRH&x#Q$iLpAc#A*PVgJtj8>F}B^I;q*+njQ0YW3Eb2Je+eSN%uzb{p1` zAi`T=Q}h(x12_Kj-di1pwJ;Bw;e>fDLqfBE)Sldp4x9pKGc z^C!-b<)vb0CGql>mE2gvC0&-?Nb+00Sykfaqv_+F-le?r>2~tdTRZB?#H}`% zGkx`*_(h)&lW;r5j_|+d|A~5AhWdLjgS4WlLCP|h-0&fm^EM<;RD<;5mzQ*c8Dy6A zKZEEDvLyF8wFAr`GY@*o4D|XUyt6(>hZ}ezn=8ejJ}`qc>gF%A0yD_>l`H*gx0%An z&P9mszd$^LT-mmShuT?9b;jZvZ}TGWpApxfHLcgLUvN0khY+~Td6eD498n5 z=HW^ryiK@AR->!8V!FzGDBiAAN(y>=>z9)c)5j@($dY$=&iO6(L>@JBuj&DKAG#D! zX%Fz;d!}ho6ptw!-|4?I_FpzgyK?WIe4bE4eT>Da=_zcAb0)?+*ksk$qwDh-u6lpP ze4Hc6&-mtyA4Z#}U%g$8lO+zzk_&xdUAa+mlkQwOBYY4BcC z=w^ZAt>oz=ON93cSvv<5@0{HkJt*EWFC~SZ0=&a>H|{yf?S~w{pPX&X=ZSQCDam&O zydPaJ?{oloe|g{Pac!O{tn)eAPhN|-dT(P7*%LLlmTG{-B~{H)Z+0if+dU^b?Q#s` z;jM%DAj?nXLEq8Jfa&8cKhNPnAU&_Qy#6{T3+iHeyeX}8`na)xRp!s~)?pgF6f@xLw0(bDRHY&?D9MLWRz zydd{Ko&fKYS;ya$8JfZOwG3l_y(3=Uij=+lD6X%TnuNtc9#=)i1-%Ie?~@)93Ii^T zxA%4z^Ffwh|9w#&o{;I|-My;JI2Xqv!ohvF-T?h&6s%9I=*O>=xr^}ym* zoozSST}XWXU+K#HG;f|43^#+!#(b4CSQkF7GbT$A<~hS==fSD#CE zv6;XIc3X3cOo;J@wv6W%Sih$3!QxW0(pbB^i1C&VfAshqE92qKhxw2p$?y5hxpu!V z&4!P3&bhQdg#r4ACckTydOdlAL>Vf!EPn6B^mtPimC)s*aNu(T+n?tx zY-#Y`Sgw(P<9+>7j3N=<0Y0;R+X3E55=R!GcrX5BcLTj3O>q7b_YXzB$Ut)(bzh<< z;aq6j6^w`XV$6p$Nq$fE%zo`(F&l=ujxTJ}iY3LnXiJdfDjjn~?CybT{t@!yEf&p^ z*ORY&VtTw)#_03mliz0V5>p>PK)j(3!o<7y(j+spZNI{@A+!4cdj-uw1F zVQ&X`Z%l{QvA_0377u-B9=z^}ymb1#pcCNzP0MAq2f+L6rI39yYK`Gf32#n#h!Ep_ zvwp3)Zux6!7Zz7v<#ka2CdRwT&r)NLCF9|J8}rdZlHZ$n_NAVj{IJXJq7tVM*Gcgf zFyo0`tZt4xoArBQ6FslD1nc`N7xywf-jp;teQaEzD*31Xx2C~+z2(+=9B+z*x&jg2 zG5dEcL^mhY^9m-X`u}kq-;V(Ay{qyrZ~u??Y7G5P(EmHq)F2JP zp-pHFQUy0ieO5E35Y?dHMhBegKn)5Ad0vDLvArG!9zx&_60a+-a=RjYk>JiNi=Fws zkXzl4vbTd86m>S_=W*}`Nl@jxiQY^TIBhZ`@x@BwCH9X)YW<;7wbTqO?)d?+B=LWF zgY=1p^uUe`##>_V!F`bA=YCOVi5qwz{lFUz_8iMsq(iJ~RM@`uOfw|Ef^A!44EYR_ zt=mgrW!he*A7UdS>GN^EWYRV0%+w6hfd+5&Z_*Teh%I(4-#~L0ID z9K?A0$3OY!r%??R!Q$pRRNKK4#5+jhoJJ>P`xtNkKN#~NL6RS9&(YS$YXo3*x54Bu zo)x5c%bS($x%AWw;jXwTDy|M`CkuLFHP+)TpID|SHjK1PH0=ES)> zaJ;#q!`2hwZOwoEp9X+;rnONpinq}Fll~Ndw;A`7)idtF#866UM_k z4)ftglHc0|_o(1reptL(YV4~Q`Eivws@!=6T!)dU>%sFL=aI)#1V$AW_%Q$T78C{g zd~n1^w+!Ezs@_Lw@K*B|%Ej?+X|_-%!kfi$NTdni-B~H*fZ{!LP$><4-qIyy;f|fj zzKGyCwxih{p2%ALj}E8M>V0OEx)9(!dieu2N758#^^>$e8b*xw7HY`yas6s42Nt)+ zaP`9WG-A9z@BH=UYd7OHNZT+U-6Z*i^PBj{$qT?UyB5yeYD-5o_M>##JhMQM%@Ni= zjLGp1J}{CV|9uD3H%LAn^!Zrh%WJeWWD0M48oXhHMN}N`jx1Ud&PlZp8Zz-PuA1m(=Zx?R^Zv`)vH-+~u?-kwvUU%Lj zyhgmbylT9wd6)6d+}?V?1U&20R)(Yk8!3gn78R zC%C_JcW}SqF5-U1{fIk~JA~VZ+lkwPdoTBP?hV|s+)KD;bF**_aDC!>&sD~i!n4c7rK9WGTac`h-oIb3Ye2=oPNf?h!{pfo5Bx&{S79*{j`0_j2O&>Bb* znh!yoW1PL5ZJafng`An34>@mgUf?{%>BxDQb2q0Zr!uDu=ORvCP723Qjt?Al93>oC z9Elv!9AO-O94;JI9Q!%6IaE00IF^E+=10&?K&Q=LcCq6Sy)=KHC6| zEA)^P^aWSwnGmQOSLhZx)P*Z_#}WFBEA-nx=o7Bc zPoc<2hZ^)ASLka-&^uhAkH0{5xI*8`fZpN? zeOdr|gDdnVcBmFt=$pt;4X)59WT9$Yp)YPiuW^MwPzY7w3VqKFdW9=t$Hgz9N?a|F zlQ)Mda3wT883vW(YTnC`Wl$Ne&{yH1Qe4e3mkx$Xa3#2ThbmNzD*+A}cc=(gv#YxE zp_jPgyQ^sk72=Bbxa%FL09QP^{jE?wuDAtal%PCZLGAa_p%=K~O!qwtA-Li=&!Y@c zamB8ESOCh!6`R1_Pf!l7X3Y$nfU!DzfV|JK~He?YuzacC=FMm`xnlJQgJo>rmX-< z!PU^s@<`}0t_JOuC!u6q4QQ)Spd?)NuY0)(O2pNVL5WjP02+qmj5nO_7&7(_~4O}&@EbN0KaMi#od=0vetM~7=Q=x0PdUxBI7rKh8I!j?G=nAgh znsaT2!g2LxsbM{I8CNweO>)pBTvaDauZ6;J_1blYG!%-fDxE{(PzbJGEht+7UBp$z zw{P~)1zeRQndZ=WT$TB69)*H&Rcf9c1D(TFiHC3;6ojjyNy>UC5LYj=E%;ym0mG#gGl;iL0mA3${ZZxXRoS#15UrRmK7%56B%?Pny%6 zAvav5#ng#IuDD7K)qV$^z*WkXE1Mw~Ts?LeFoc}{-v7@8Q#r7Mbb@9L5}nncYmn&v zzt5;H8_^o1ugb`_3a|#bu|L>$4p@VXvg=Zk221R@A~#hYU-d=04l2tgJ9r^&TUcd= z#e3k{hxK>=1WW9K>ggqS{7m4NQtDgZ&m&%g{MgNRGxGR5Y8e)1et_j??F!;G$XnM| z-G2Cq@vhkI!F)uM|CGz8 z3>qSt|NcKpI(;M*5~#0B;M`YAqD+c1qwA z4S+XKf&Hivz&rT8hU!~$FXZ5${02_2#6CHqp7R#qt(9CbFsf|=>jm6C^6@?K5jz#f zUGqFG>!^FMIF8;M^&bCn#4fbJJ~6G0@otb($9!BO$xk+Muj!z^0NiG=+H>{J8dAJ% zg!lVM3LQe&P4;ohIg(#*$!))a(%aU<^v7FdBIxt+_|BUB*5Ha=P`#aL@J9Pi9Pd(_ z!I?yOKNYuH@fzU0$~{sB#d}4G=zulAyF&0p@Aws8q`EL+meO7?MBZ>$=n{Z;xw6W@ z6M%R7xAP@jbHV2=(ruc_k;Hg^eBzTIV*8f54~t8Gw#eXn3h@b2P4BWF{$CjH{=Xi~ z$99tZl9!H|$N2EWW4SjJwmzvQ#oJ)d%_MfgLr7}N*xunhI!=%_AG;JfFv#?HQ|3C* z-#&D3L z+9?%#V!VGu2xVnO)>6-7ak2Y^vtxaU@wPg!H-b-^@xK2b#(db27cC}KU@{w z=M*hYj`tVYs67?O3=qrxF{>}e(y{;F)bZ}HjUChDP5D8e59;Au)!K)D&;K()_fMgK z8KehI4MO)u@EX+Bt;J1LgT|4Nb@`wMxwENo&jmF|Oxo=s`u)EI$5!_j;QYU%?AzwO zfnLbdc#dPoLI0ncx#muBe;ceLn;v+z-UN=_p*?fU8RGsw!(UxW?qoCdAr|K=Hmhgr zzdVq3>2+mvb7=*`egB_}`M6AypIV~z2;$EVJAFHUMA@^Bbco%(sqmy+=3!*9!QihU zPVysml#?fPHYp4;{~4r9E_C@ga)o2ti+fWu$dfd9qnmv=-pyA8xrp%Q%^clb2=I>M z5cz`6Ah(9{Xy*XDwM7nc$O63Moo(-C`FSDHW)32O0B;E|6TW)@?|tj+{N2(`V2;|6 zN~?dl|1Wo9A+>E=6O|W>8}7|h-C|F?ycOHHZ%^y(a)!hECFUcJBtJFY8TxPuKU~uI zievW2x1@L*DD-^(48EV3(XlnvQk8s&En6m)XP?CU7o=aG-S!FURi9u6%yVKx} z?q1_~bNYYeB*I&L-3;p@fVbieY6*(><(Jm#5diNQH6iMr*L@LAEw=eK-d;%Lt<&1~ z(CYnZ_D>gpcia80P~N*H@P^e5ZSiWv)qC>=m;4~1MyeVX=fjr1xMepn-V(ZJ^AK0Y zdqG+Y^C3x+-;q{x8obft7&zYhA7*e6;q9b)GqwcaJyLN$4#nHno%^>9zdKl zRle%FJidtd{{NiTu%LSDQiiME?U)ZLNq%P}qP1A~@(@XuAVZRkp z`rb^bn1y`xmZE!E@X-tAU%jPth0^6?X~CUm%Pvn6*@^JpvND=l z2Jki;%k)F>#`oUV^GSEU0GktfB+%!hki|&xaPZ&v|Cpu! zKTT7E&=Zz;4Vp0z79grY)hwYhnV<$u>YS)T`+p(v{!TvE+&HRvAZLxm*2#0fW{8-e_A`i>A?<0TEGL+nvAZrc&q99itMnSI`O zIzGwsw>tD9R+;H*5ak4&K6)Vsr9U4?pQ6DVJu-~red8CzPlR`JCiLVPz?-^M^FE3< z=gJAaCjjrEgovM+mwl0Zi6SFvqZguIDj32FhFGZe(QFrhx2v*(6RgZ zds4iw_Qi}0>scYHHWG@zpV4u=S)nhL8J4(}tF z53>BiHBwG^vkAbNo{P&OC*P6cEgBl(;%j&W5jh@^WO+4c_QS9XQ^-F86tf@aE>pkje#k7b^D|qj>AK)##wlTkQC!_l^Z< zkZ#}6QC7?HLLMqSblM2;HZ33hvIyYqYhl-I>1GV;%%T?Wk|Lg*?6BRM+ojV=)x+Xg z-Q*3n$P-Ua8uw?ouf6<=;qcbOd^C~dr~Zm}&A6d5usdx6r?+k?iC6EvK#q5o z&lmQWwF+SFjh_E!Wj#yb5rx#*&B4F? z{qy%1`1=d|{RRFHe*yo4*JjcTvFL}#_z*kGfFeXR#GZ@FzMKGtSjnCguX$jI4cFz3 z+5v{x*M&!GzFhQ0hVu3txuxQb9CWVecmS5Sgcm)X$2Qmouk4xkCP>5t-coil>{UPU z4Dy%$0%7efAE+8wT%6W+4%ucN zJ_X<%Aig+y1T;vwqV3lAMvUQvN{4m6#l(1LQ3q?TpYNn5VsSsDhVSotO^i3U(S3h= z@SxiN&TslZ|F7m?J|L3(t~fp%6))q5pE$0Ra9Ghqinm)}Se%dQf!5sTl585K0$tZi*l*xSP+6RJ>HakHgx$IExT#6@*28&dyPVaH+t6z zjYE*7yf9`dSh5Wf6MtYm;e9( literal 0 HcmV?d00001 diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py index 36bdfc732ed79..9f0a5df7f3fcc 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py @@ -39,6 +39,7 @@ def generate_test_description(): {"lanelet2_map_path": lanelet2_map_path}, {"run_background": False}, {"rviz": False}, + {"centerline_source": "optimization_trajectory_base"}, {"lanelet2_input_file_path": lanelet2_map_path}, {"lanelet2_output_file_path": "/tmp/lanelet2_map.osm"}, {"start_lanelet_id": 215}, From 957e55346df22260c30d6edeb655679d2035fed3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 12 Apr 2024 10:10:46 +0900 Subject: [PATCH 028/192] refactor(static_centerline_optimizer): clean up the code (#6794) * refactor(static_centerline_optimizer): clean up the code Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../bag_ego_trajectory_based_centerline.hpp | 2 - ...timization_trajectory_based_centerline.hpp | 2 - .../static_centerline_optimizer_node.hpp | 4 +- .../static_centerline_optimizer/utils.hpp | 2 + .../static_centerline_optimizer.launch.xml | 3 +- .../bag_ego_trajectory_based_centerline.cpp | 4 +- ...timization_trajectory_based_centerline.cpp | 27 ++---- .../src/static_centerline_optimizer_node.cpp | 89 +++++++------------ .../static_centerline_optimizer/src/utils.cpp | 5 ++ 9 files changed, 55 insertions(+), 83 deletions(-) diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp index db954b6ccbd47..b29f222b068cc 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -18,8 +18,6 @@ #include "rclcpp/rclcpp.hpp" #include "static_centerline_optimizer/type_alias.hpp" -#include -#include #include namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp index 6e52ff98d78da..8c7c1e69e9ce6 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp @@ -18,8 +18,6 @@ #include "rclcpp/rclcpp.hpp" #include "static_centerline_optimizer/type_alias.hpp" -#include -#include #include namespace static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp index 242a76ae0d94f..5d9530a469012 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -31,6 +31,7 @@ #include #include +#include #include namespace static_centerline_optimizer @@ -81,8 +82,7 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node std::shared_ptr route_handler_ptr_{nullptr}; std::unique_ptr map_projector_{nullptr}; - int traj_start_index_{0}; - int traj_end_index_{0}; + std::pair traj_range_indices_{0, 0}; std::optional centerline_with_route_{std::nullopt}; enum class CenterlineSource { diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp index 52dcd171e8658..04f2268aa972f 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp @@ -28,6 +28,8 @@ namespace static_centerline_optimizer { namespace utils { +rclcpp::QoS create_transient_local_qos(); + lanelet::ConstLanelets get_lanelets_from_ids( const RouteHandler & route_handler, const std::vector & lane_ids); diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml index 10718150d1751..ed137367f3ba4 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml @@ -5,8 +5,7 @@ - - + diff --git a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index 150218b498ae7..571e98cdbe1c3 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -26,9 +26,11 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) { const auto bag_filename = node.declare_parameter("bag_filename"); + // open rosbag rosbag2_cpp::Reader bag_reader; bag_reader.open(bag_filename); + // extract 2D position of ego's trajectory from rosbag rclcpp::Serialization bag_serialization; std::vector centerline_traj_points; while (bag_reader.has_next()) { @@ -55,8 +57,6 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) } TrajectoryPoint centerline_traj_point; centerline_traj_point.pose.position = ros_msg->pose.pose.position; - // std::cerr << centerline_traj_point.pose.position.x << " " - // << centerline_traj_point.pose.position.y << std::endl; centerline_traj_points.push_back(centerline_traj_point); } diff --git a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp index 5bce91be722ca..20b2027f39d54 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -20,6 +20,7 @@ #include "path_smoother/elastic_band_smoother.hpp" #include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" #include "static_centerline_optimizer/utils.hpp" +#include "tier4_autoware_utils/ros/parameter.hpp" namespace static_centerline_optimizer { @@ -30,10 +31,6 @@ rclcpp::NodeOptions create_node_options() return rclcpp::NodeOptions{}; } -rclcpp::QoS create_transient_local_qos() -{ - return rclcpp::QoS{1}.transient_local(); -} Path convert_to_path(const PathWithLaneId & path_with_lane_id) { Path path; @@ -66,8 +63,9 @@ Trajectory convert_to_trajectory(const Path & path) OptimizationTrajectoryBasedCenterline::OptimizationTrajectoryBasedCenterline(rclcpp::Node & node) { pub_raw_path_with_lane_id_ = - node.create_publisher("input_centerline", create_transient_local_qos()); - pub_raw_path_ = node.create_publisher("debug/raw_centerline", create_transient_local_qos()); + node.create_publisher("input_centerline", utils::create_transient_local_qos()); + pub_raw_path_ = + node.create_publisher("debug/raw_centerline", utils::create_transient_local_qos()); } std::vector @@ -82,20 +80,13 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization( // get ego nearest search parameters and resample interval in behavior_path_planner const double ego_nearest_dist_threshold = - node.has_parameter("ego_nearest_dist_threshold") - ? node.get_parameter("ego_nearest_dist_threshold").as_double() - : node.declare_parameter("ego_nearest_dist_threshold"); + tier4_autoware_utils::getOrDeclareParameter(node, "ego_nearest_dist_threshold"); const double ego_nearest_yaw_threshold = - node.has_parameter("ego_nearest_yaw_threshold") - ? node.get_parameter("ego_nearest_yaw_threshold").as_double() - : node.declare_parameter("ego_nearest_yaw_threshold"); - const double behavior_path_interval = node.has_parameter("output_path_interval") - ? node.get_parameter("output_path_interval").as_double() - : node.declare_parameter("output_path_interval"); + tier4_autoware_utils::getOrDeclareParameter(node, "ego_nearest_yaw_threshold"); + const double behavior_path_interval = + tier4_autoware_utils::getOrDeclareParameter(node, "output_path_interval"); const double behavior_vel_interval = - node.has_parameter("behavior_output_path_interval") - ? node.get_parameter("behavior_output_path_interval").as_double() - : node.declare_parameter("behavior_output_path_interval"); + tier4_autoware_utils::getOrDeclareParameter(node, "behavior_output_path_interval"); // extract path with lane id from lanelets const auto raw_path_with_lane_id = [&]() { diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 4f729ab5c8c57..073d30f5b5a39 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -57,19 +57,6 @@ namespace static_centerline_optimizer { namespace { -[[maybe_unused]] lanelet::ConstLanelets get_lanelets_from_route( - const RouteHandler & route_handler, const LaneletRoute & route) -{ - lanelet::ConstLanelets lanelets; - for (const auto & segment : route.segments) { - const auto & target_lanelet_id = segment.preferred_primitive.id; - const auto target_lanelet = route_handler.getLaneletsFromId(target_lanelet_id); - lanelets.push_back(target_lanelet); - } - - return lanelets; -} - std::vector get_lane_ids_from_route(const LaneletRoute & route) { std::vector lane_ids; @@ -81,12 +68,7 @@ std::vector get_lane_ids_from_route(const LaneletRoute & route) return lane_ids; } -rclcpp::QoS create_transient_local_qos() -{ - return rclcpp::QoS{1}.transient_local(); -} - -lanelet::BasicPoint2d convertToLaneletPoint(const geometry_msgs::msg::Point & geom_point) +lanelet::BasicPoint2d convert_to_lanelet_point(const geometry_msgs::msg::Point & geom_point) { lanelet::BasicPoint2d point(geom_point.x, geom_point.y); return point; @@ -131,7 +113,7 @@ geometry_msgs::msg::Pose get_text_pose( return tier4_autoware_utils::calcOffsetPose(pose, x_front, y_left, 0.0); } -std::array convertHexStringToDecimal(const std::string & hex_str_color) +std::array convert_hex_string_to_decimal(const std::string & hex_str_color) { unsigned int hex_int_color; std::istringstream iss(hex_str_color); @@ -165,7 +147,7 @@ std::vector check_lanelet_connection( return unconnected_lane_ids; } -std_msgs::msg::Header createHeader(const rclcpp::Time & now) +std_msgs::msg::Header create_header(const rclcpp::Time & now) { std_msgs::msg::Header header; header.frame_id = "map"; @@ -173,7 +155,7 @@ std_msgs::msg::Header createHeader(const rclcpp::Time & now) return header; } -std::vector resampleTrajectoryPoints( +std::vector resample_trajectory_points( const std::vector & input_traj_points, const double resample_interval) { // resample and calculate trajectory points' orientation @@ -188,29 +170,27 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( : Node("static_centerline_optimizer", node_options) { // publishers - pub_map_bin_ = create_publisher("lanelet2_map_topic", create_transient_local_qos()); + pub_map_bin_ = + create_publisher("lanelet2_map_topic", utils::create_transient_local_qos()); pub_whole_centerline_ = - create_publisher("output_whole_centerline", create_transient_local_qos()); - pub_centerline_ = create_publisher("output_centerline", create_transient_local_qos()); + create_publisher("output_whole_centerline", utils::create_transient_local_qos()); + pub_centerline_ = + create_publisher("output_centerline", utils::create_transient_local_qos()); // debug publishers pub_debug_unsafe_footprints_ = - create_publisher("debug/unsafe_footprints", create_transient_local_qos()); + create_publisher("debug/unsafe_footprints", utils::create_transient_local_qos()); // subscribers sub_traj_start_index_ = create_subscription( "/centerline_updater_helper/traj_start_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (msg.data <= traj_end_index_ + 1) { - update_centerline_range(msg.data, traj_end_index_); - } + update_centerline_range(msg.data, traj_range_indices_.second); }); sub_traj_end_index_ = create_subscription( "/centerline_updater_helper/traj_end_index", rclcpp::QoS{1}, [this](const std_msgs::msg::Int32 & msg) { - if (traj_start_index_ <= msg.data + 1) { - update_centerline_range(traj_start_index_, msg.data); - } + update_centerline_range(traj_range_indices_.first, msg.data); }); sub_save_map_ = create_subscription( "/centerline_updater_helper/save_map", rclcpp::QoS{1}, [this](const std_msgs::msg::Bool & msg) { @@ -220,7 +200,8 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( if (!centerline_with_route_ || msg.data) { const auto & c = *centerline_with_route_; const auto selected_centerline = std::vector( - c.centerline.begin() + traj_start_index_, c.centerline.begin() + traj_end_index_ + 1); + c.centerline.begin() + traj_range_indices_.first, + c.centerline.begin() + traj_range_indices_.second + 1); save_map( lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); } @@ -271,19 +252,19 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( void StaticCenterlineOptimizerNode::update_centerline_range( const int traj_start_index, const int traj_end_index) { - if (!centerline_with_route_) { + if (!centerline_with_route_ || traj_range_indices_.second + 1 < traj_start_index) { return; } - traj_start_index_ = traj_start_index; - traj_end_index_ = traj_end_index; + traj_range_indices_ = std::make_pair(traj_start_index, traj_end_index); const auto & centerline = centerline_with_route_->centerline; const auto selected_centerline = std::vector( - centerline.begin() + traj_start_index_, centerline.begin() + traj_end_index_ + 1); + centerline.begin() + traj_range_indices_.first, + centerline.begin() + traj_range_indices_.second + 1); pub_centerline_->publish( - motion_utils::convertToTrajectory(selected_centerline, createHeader(this->now()))); + motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); } void StaticCenterlineOptimizerNode::run() @@ -296,8 +277,7 @@ void StaticCenterlineOptimizerNode::run() // process load_map(lanelet2_input_file_path); const auto centerline_with_route = generate_centerline_with_route(); - traj_start_index_ = 0; - traj_end_index_ = centerline_with_route.centerline.size() - 1; + traj_range_indices_ = std::make_pair(0, centerline_with_route.centerline.size() - 1); save_map(lanelet2_output_file_path, centerline_with_route); centerline_with_route_ = centerline_with_route; @@ -310,6 +290,7 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout return CenterlineWithRoute{}; } + // generate centerline with route auto centerline_with_route = [&]() { if (centerline_source_ == CenterlineSource::OptimizationTrajectoryBase) { const lanelet::Id start_lanelet_id = declare_parameter("start_lanelet_id"); @@ -339,15 +320,16 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout "The centerline source is not supported in static_centerline_optimizer."); }(); + // resample const double output_trajectory_interval = declare_parameter("output_trajectory_interval"); centerline_with_route.centerline = - resampleTrajectoryPoints(centerline_with_route.centerline, output_trajectory_interval); + resample_trajectory_points(centerline_with_route.centerline, output_trajectory_interval); - pub_whole_centerline_->publish( - motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + pub_whole_centerline_->publish(motion_utils::convertToTrajectory( + centerline_with_route.centerline, create_header(this->now()))); - pub_centerline_->publish( - motion_utils::convertToTrajectory(centerline_with_route.centerline, createHeader(this->now()))); + pub_centerline_->publish(motion_utils::convertToTrajectory( + centerline_with_route.centerline, create_header(this->now()))); return centerline_with_route; } @@ -537,8 +519,8 @@ void StaticCenterlineOptimizerNode::on_plan_path( std::vector current_lanelet_points; // check if target point is inside the lanelet - while ( - lanelet::geometry::inside(lanelet, convertToLaneletPoint(target_traj_point->pose.position))) { + while (lanelet::geometry::inside( + lanelet, convert_to_lanelet_point(target_traj_point->pose.position))) { // memorize points inside the lanelet current_lanelet_points.push_back(target_traj_point->pose.position); target_traj_point++; @@ -571,18 +553,15 @@ void StaticCenterlineOptimizerNode::evaluate( const std::vector & optimized_traj_points) { const auto route_lanelets = utils::get_lanelets_from_ids(*route_handler_ptr_, route_lane_ids); - const auto dist_thresh_vec = - has_parameter("marker_color_dist_thresh") - ? get_parameter("marker_color_dist_thresh").as_double_array() - : declare_parameter>("marker_color_dist_thresh"); - const auto marker_color_vec = has_parameter("marker_color") - ? get_parameter("marker_color").as_string_array() - : declare_parameter>("marker_color"); + const auto dist_thresh_vec = tier4_autoware_utils::getOrDeclareParameter>( + *this, "marker_color_dist_thresh"); + const auto marker_color_vec = + tier4_autoware_utils::getOrDeclareParameter>(*this, "marker_color"); const auto get_marker_color = [&](const double dist) -> boost::optional> { for (size_t i = 0; i < dist_thresh_vec.size(); ++i) { const double dist_thresh = dist_thresh_vec.at(i); if (dist < dist_thresh) { - return convertHexStringToDecimal(marker_color_vec.at(i)); + return convert_hex_string_to_decimal(marker_color_vec.at(i)); } } return boost::none; diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_optimizer/src/utils.cpp index 3cc7ed5ca1fda..9448677d1bbae 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_optimizer/src/utils.cpp @@ -45,6 +45,11 @@ lanelet::Point3d createPoint3d(const double x, const double y, const double z = namespace utils { +rclcpp::QoS create_transient_local_qos() +{ + return rclcpp::QoS{1}.transient_local(); +} + lanelet::ConstLanelets get_lanelets_from_ids( const RouteHandler & route_handler, const std::vector & lane_ids) { From 879358434705a6f8fa512c0b438583fd696cccf1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 12 Apr 2024 10:50:09 +0900 Subject: [PATCH 029/192] docs(avoidance): use json schema (#6789) docs(avoidance): json schema Signed-off-by: satoshi-ota --- .../behavior_path_avoidance_module/README.md | 171 +- .../schema/avoidance.schema.json | 1465 +++++++++++++++++ 2 files changed, 1466 insertions(+), 170 deletions(-) create mode 100644 planning/behavior_path_avoidance_module/schema/avoidance.schema.json diff --git a/planning/behavior_path_avoidance_module/README.md b/planning/behavior_path_avoidance_module/README.md index dc6ab0ec4b6e1..aa7a3a42efdb4 100644 --- a/planning/behavior_path_avoidance_module/README.md +++ b/planning/behavior_path_avoidance_module/README.md @@ -760,176 +760,7 @@ WIP The avoidance specific parameter configuration file can be located at `src/autoware/launcher/planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml`. -### General parameters - -namespace: `avoidance.` - -| Name | Unit | Type | Description | Default value | -| :------------------------------------ | :--- | :----- | :---------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| resample_interval_for_planning | [m] | double | Path resample interval for avoidance planning path. | 0.3 | -| resample_interval_for_output | [m] | double | Path resample interval for output path. Too short interval increases computational cost for latter modules. | 4.0 | -| detection_area_right_expand_dist | [m] | double | Lanelet expand length for right side to find avoidance target vehicles. | 0.0 | -| detection_area_left_expand_dist | [m] | double | Lanelet expand length for left side to find avoidance target vehicles. | 1.0 | -| enable_cancel_maneuver | [-] | bool | Reset trajectory when avoided objects are gone. If false, shifted path points remain same even though the avoided objects are gone. | false | -| enable_yield_maneuver | [-] | bool | Flag to enable yield maneuver. | false | -| enable_yield_maneuver_during_shifting | [-] | bool | Flag to enable yield maneuver during shifting. | false | - -| Name | Unit | Type | Description | Default value | -| :------------------------ | ---- | ---- | ----------------------------------------------------------------------------------------------------------------------- | ------------- | -| enable_bound_clipping | [-] | bool | Enable clipping left and right bound of drivable area when obstacles are in the drivable area | false | -| use_adjacent_lane | [-] | bool | Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane. | true | -| use_opposite_lane | [-] | bool | Extend avoidance trajectory to opposite direction lane. `use_adjacent_lane` must be `true` to take effects | true | -| use_intersection_areas | [-] | bool | Extend drivable to intersection area. | false | -| use_hatched_road_markings | [-] | bool | Extend drivable to hatched road marking area. | false | - -| Name | Unit | Type | Description | Default value | -| :------------------ | ---- | ---- | --------------------------------------------------------------------------------------- | ------------- | -| output_debug_marker | [-] | bool | Flag to publish debug marker (set `false` as default since it takes considerable cost). | false | -| output_debug_info | [-] | bool | Flag to print debug info (set `false` as default since it takes considerable cost). | false | - -### Avoidance target filtering parameters - -namespace: `avoidance.target_object.` - -This module supports all object classes, and it can set following parameters independently. - -```yaml -car: - is_target: true # [-] - moving_speed_threshold: 1.0 # [m/s] - moving_time_threshold: 1.0 # [s] - max_expand_ratio: 0.0 # [-] - envelope_buffer_margin: 0.3 # [m] - avoid_margin_lateral: 1.0 # [m] - safety_buffer_lateral: 0.7 # [m] - safety_buffer_longitudinal: 0.0 # [m] -``` - -| Name | Unit | Type | Description | Default value | -| :------------------------- | ----- | ------ | ------------------------------------------------------------------------------------------------------------------------- | ------------- | -| is_target | [-] | bool | By setting this flag `true`, this module avoid those class objects. | false | -| moving_speed_threshold | [m/s] | double | Objects with speed greater than this will be judged as moving ones. | 1.0 | -| moving_time_threshold | [s] | double | Objects keep moving longer duration than this will be excluded from avoidance target. | 1.0 | -| envelope_buffer_margin | [m] | double | The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation. | 0.3 | -| avoid_margin_lateral | [m] | double | The lateral distance between ego and avoidance targets. | 1.0 | -| safety_buffer_lateral | [m] | double | Creates an additional lateral gap that will prevent the vehicle from getting to near to the obstacle. | 0.5 | -| safety_buffer_longitudinal | [m] | double | Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle. | 0.0 | - -Parameters for the logic to compensate perception noise of the far objects. - -| Name | Unit | Type | Description | Default value | -| :----------------------------------- | ---- | ------ | ------------------------------------------------------------------------------------------------------------ | ------------- | -| max_expand_ratio | [-] | double | This value will be applied `envelope_buffer_margin` according to the distance between the ego and object. | 0.0 | -| lower_distance_for_polygon_expansion | [-] | double | If the distance between the ego and object is less than this, the expand ratio will be zero. | 30.0 | -| upper_distance_for_polygon_expansion | [-] | double | If the distance between the ego and object is larger than this, the expand ratio will be `max_expand_ratio`. | 100.0 | - -namespace: `avoidance.target_filtering.` - -| Name | Unit | Type | Description | Default value | -| :---------------------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| threshold_distance_object_is_on_center | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 1.0 | -| object_ignore_section_traffic_light_in_front_distance | [m] | double | If the distance between traffic light and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_ignore_section_crosswalk_in_front_distance | [m] | double | If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_ignore_section_crosswalk_behind_distance | [m] | double | If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it. | 30.0 | -| object_check_forward_distance | [m] | double | Forward distance to search the avoidance target. | 150.0 | -| object_check_backward_distance | [m] | double | Backward distance to search the avoidance target. | 2.0 | -| object_check_goal_distance | [m] | double | If the distance between object and goal position is less than this parameter, the module do not return center line. | 20.0 | -| object_check_return_pose_distance | [m] | double | If the distance between object and return position is less than this parameter, the module do not return center line. | 20.0 | -| object_check_shiftable_ratio | [m] | double | Vehicles around the center line within this distance will be excluded from avoidance target. | 0.6 | -| object_check_min_road_shoulder_width | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder target. | 0.5 | -| object_last_seen_threshold | [s] | double | For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit. | 2.0 | - -### Safety check parameters - -namespace: `avoidance.safety_check.` - -| Name | Unit | Type | Description | Default value | -| :----------------------------- | ---- | ------ | ---------------------------------------------------------------------------------------------------------- | ------------- | -| enable | [-] | bool | Enable to use safety check feature. | true | -| check_current_lane | [-] | bool | Check objects on current driving lane. | false | -| check_shift_side_lane | [-] | bool | Check objects on shift side lane. | true | -| check_other_side_lane | [-] | bool | Check objects on other side lane. | false | -| check_unavoidable_object | [-] | bool | Check collision between ego and unavoidable objects. | false | -| check_other_object | [-] | bool | Check collision between ego and non avoidance target objects. | false | -| check_all_predicted_path | [-] | bool | Check all prediction path of safety check target objects. | false | -| time_horizon | [s] | double | Time horizon to check lateral/longitudinal margin is enough or not. | 10.0 | -| time_resolution | [s] | double | Time resolution to check lateral/longitudinal margin is enough or not. | 0.5 | -| safety_check_backward_distance | [m] | double | Backward distance to search the dynamic objects. | 50.0 | -| safety_check_hysteresis_factor | [-] | double | Hysteresis factor that be used for chattering prevention. | 2.0 | -| safety_check_ego_offset | [m] | double | Output new avoidance path **only when** the offset between ego and previous output path is less than this. | 1.0 | - -### Avoidance maneuver parameters - -namespace: `avoidance.avoidance.lateral.` - -| Name | Unit | Type | Description | Default value | -| :---------------------------- | :--- | :----- | :-------------------------------------------------------------------------------------------------------------------------- | :------------ | -| road_shoulder_safety_margin | [m] | double | Prevents the generated path to come too close to the road shoulders. | 0.0 | -| lateral_execution_threshold | [m] | double | The lateral distance deviation threshold between the current path and suggested avoidance point to execute avoidance. (\*2) | 0.499 | -| lateral_small_shift_threshold | [m] | double | The shift lines whose lateral offset is less than this will be applied with other ones. | 0.501 | -| max_right_shift_length | [m] | double | Maximum shift length for right direction | 5.0 | -| max_left_shift_length | [m] | double | Maximum shift length for left direction | 5.0 | - -namespace: `avoidance.avoidance.longitudinal.` - -| Name | Unit | Type | Description | Default value | -| :----------------------------------- | :---- | :----- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------- | -| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 | -| longitudinal_collision_safety_buffer | [s] | double | Longitudinal collision buffer between target object and shift line. | 0.0 | -| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 | -| min_avoidance_distance | [m] | double | Minimum distance of avoidance path (i.e. this distance is needed even if its lateral jerk is very low) | 10.0 | -| min_nominal_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a nominal situation (\*1). | 7.0 | -| min_sharp_avoidance_speed | [m/s] | double | Minimum speed for jerk calculation in a sharp situation (\*1). | 1.0 | -| min_slow_down_speed | [m/s] | double | Minimum slow speed for avoidance prepare section. | 1.38 (5km/h) | -| buf_slow_down_speed | [m/s] | double | Buffer for controller tracking error. Basically, vehicle always cannot follow velocity profile precisely. Therefore, the module inserts lower speed than target speed that satisfies conditions to avoid object within accel/jerk constraints so that the avoidance path always can be output even if the current speed is a little bit higher than target speed. | 0.57 (2.0km/h) | - -### Yield maneuver parameters - -namespace: `avoidance.yield.` - -| Name | Unit | Type | Description | Default value | -| :------------- | :---- | :----- | :------------------------------------------------------------ | :------------ | -| yield_velocity | [m/s] | double | The ego will decelerate yield velocity in the yield maneuver. | 2.78 | - -### Stop maneuver parameters - -namespace: `avoidance.stop.` - -| Name | Unit | Type | Description | Default value | -| :----------- | :--- | :----- | :---------------------------------------------------------------------------------------------------- | :------------ | -| min_distance | [m] | double | Minimum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 10.0 | -| max_distance | [m] | double | Maximum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 20.0 | -| stop_buffer | [m] | double | Buffer distance in the situation where avoidance maneuver is not approved or in yield maneuver. | 1.0 | - -### Constraints parameters - -namespace: `avoidance.constraints.` - -| Name | Unit | Type | Description | Default value | -| :------------------------ | :--- | :--- | :--------------------------------------------------------------------------------------- | :------------ | -| use_constraints_for_decel | [-] | bool | Flag to decel under longitudinal constraints. `TRUE: allow to control breaking mildness` | false | - -namespace: `avoidance.constraints.lateral.` - -| a Name | Unit | Type | Description | Default value | -| :----------------------- | :----- | :----- | :-------------------------------------------------------------------------------------------- | :------------ | -| prepare_time | [s] | double | Avoidance shift starts from point ahead of this time x ego_speed to avoid sudden path change. | 2.0 | -| min_prepare_distance | [m] | double | Minimum distance for "prepare_time" x "ego_speed". | 1.0 | -| nominal_lateral_jerk | [m/s3] | double | Avoidance path is generated with this jerk when there is enough distance from ego. | 0.2 | -| max_lateral_jerk | [m/s3] | double | Avoidance path gets sharp up to this jerk limit when there is not enough distance from ego. | 1.0 | -| max_lateral_acceleration | [m/s3] | double | Avoidance path gets sharp up to this accel limit when there is not enough distance from ego. | 0.5 | - -namespace: `avoidance.constraints.longitudinal.` - -| Name | Unit | Type | Description | Default value | -| :------------------- | :------ | :----- | :------------------------------------- | :------------ | -| nominal_deceleration | [m/ss] | double | Nominal deceleration limit. | -1.0 | -| nominal_jerk | [m/sss] | double | Nominal jerk limit. | 0.5 | -| max_deceleration | [m/ss] | double | Max decelerate limit. | -2.0 | -| max_jerk | [m/sss] | double | Max jerk limit. | 1.0 | -| max_acceleration | [m/ss] | double | Maximum acceleration during avoidance. | 1.0 | - -(\*2) If there are multiple vehicles in a row to be avoided, no new avoidance path will be generated unless their lateral margin difference exceeds this value. +{{ json_to_markdown("planning/behavior_path_avoidance_module/schema/avoidance.schema.json") }} ## Future extensions / Unimplemented parts diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json new file mode 100644 index 0000000000000..cd3e29b8ec0b8 --- /dev/null +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -0,0 +1,1465 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for behavior_path_avoidance_module", + "type": "object", + "definitions": { + "behavior_path_avoidance_module": { + "type": "object", + "properties": { + "resample_interval_for_planning": { + "type": "number", + "description": "Path resample interval for avoidance planning path.", + "default": "0.3" + }, + "resample_interval_for_output": { + "type": "number", + "description": "Path resample interval for output path. Too short interval increases computational cost for latter modules.", + "default": "4.0" + }, + "enable_bound_clipping": { + "type": "boolean", + "description": "Enable clipping left and right bound of drivable area when obstacles are in the drivable area.", + "default": "false" + }, + "disable_path_update": { + "type": "boolean", + "description": "Disable path update.", + "default": "false" + }, + "use_adjacent_lane": { + "type": "boolean", + "description": "Extend avoidance trajectory to adjacent lanes that has same direction. If false, avoidance only happen in current lane.", + "default": "true" + }, + "use_opposite_lane": { + "type": "boolean", + "description": "Extend avoidance trajectory to opposite direction lane. `use_adjacent_lane` must be `true` to take effects.", + "default": "true" + }, + "use_hatched_road_markings": { + "type": "boolean", + "description": "Extend drivable to hatched road marking area.", + "default": "true" + }, + "use_intersection_areas": { + "type": "boolean", + "description": "Extend drivable to intersection area.", + "default": "true" + }, + "use_freespace_areas": { + "type": "boolean", + "description": "Extend drivable to freespace area.", + "default": "true" + }, + "target_object": { + "type": "object", + "properties": { + "car": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "truck": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "bus": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "trailer": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "unknown": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": -0.2 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": -0.2 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.1 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "motorcycle": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "bicycle": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.3 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "pedestrian": { + "type": "object", + "properties": { + "th_moving_speed": { + "type": "number", + "description": "Objects with speed greater than this will be judged as moving ones.", + "default": 1.0, + "minimum": 0.0 + }, + "th_moving_time": { + "type": "number", + "description": "Objects keep moving longer duration than this will be excluded from avoidance target.", + "default": 1.0 + }, + "longitudinal_margin": { + "type": "number", + "description": "Creates an additional longitudinal gap that will prevent the vehicle from getting to near to the obstacle.", + "default": 0.0 + }, + "lateral_margin": { + "type": "object", + "properties": { + "soft_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.7 + }, + "hard_margin": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + }, + "hard_margin_for_parked_vehicle": { + "type": "number", + "description": "Lateral distance between ego and avoidance targets.", + "default": 0.5 + } + }, + "required": ["soft_margin", "hard_margin", "hard_margin_for_parked_vehicle"], + "additionalProperties": false + }, + "envelope_buffer_margin": { + "type": "number", + "description": "The buffer between raw boundary box of detected objects and enveloped polygon that is used for avoidance path generation.", + "default": 0.5 + }, + "max_expand_ratio": { + "type": "number", + "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", + "default": 0.0 + }, + "use_conservative_buffer_longitudinal": { + "type": "boolean", + "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", + "default": "true" + } + }, + "required": [ + "th_moving_speed", + "th_moving_time", + "longitudinal_margin", + "lateral_margin", + "envelope_buffer_margin", + "max_expand_ratio" + ], + "additionalProperties": false + }, + "lower_distance_for_polygon_expansion": { + "type": "number", + "description": "If the distance between the ego and object is less than this, the expand ratio will be zero.", + "default": 30.0 + }, + "upper_distance_for_polygon_expansion": { + "type": "number", + "description": "If the distance between the ego and object is larger than this, the expand ratio will be max_expand_ratio.", + "default": 100.0 + } + }, + "required": [ + "car", + "truck", + "bus", + "trailer", + "unknown", + "bicycle", + "motorcycle", + "pedestrian", + "lower_distance_for_polygon_expansion", + "upper_distance_for_polygon_expansion" + ], + "additionalProperties": false + }, + "target_filtering": { + "type": "object", + "properties": { + "target_type": { + "type": "object", + "properties": { + "car": { + "type": "boolean", + "description": "Enable avoidance maneuver for CAR.", + "default": "true" + }, + "truck": { + "type": "boolean", + "description": "Enable avoidance maneuver for TRUCK.", + "default": "true" + }, + "bus": { + "type": "boolean", + "description": "Enable avoidance maneuver for BUS.", + "default": "true" + }, + "trailer": { + "type": "boolean", + "description": "Enable avoidance maneuver for TRAILER.", + "default": "true" + }, + "unknown": { + "type": "boolean", + "description": "Enable avoidance maneuver for UNKNOWN.", + "default": "true" + }, + "bicycle": { + "type": "boolean", + "description": "Enable avoidance maneuver for BICYCLE.", + "default": "true" + }, + "motorcycle": { + "type": "boolean", + "description": "Enable avoidance maneuver for MOTORCYCLE.", + "default": "true" + }, + "pedestrian": { + "type": "boolean", + "description": "Enable avoidance maneuver for PEDESTRIAN.", + "default": "true" + } + }, + "required": [ + "car", + "truck", + "bus", + "trailer", + "unknown", + "bicycle", + "motorcycle", + "pedestrian" + ], + "additionalProperties": false + }, + "object_check_goal_distance": { + "type": "number", + "description": "If the distance between object and goal position is less than this parameter, the module do not return center line.", + "default": 20.0 + }, + "object_check_return_pose_distance": { + "type": "number", + "description": "If the distance between object and return position is less than this parameter, the module do not return center line.", + "default": 20.0 + }, + "max_compensation_time": { + "type": "number", + "description": "For the compensation of the detection lost. The object is registered once it is observed as an avoidance target. When the detection loses, the timer will start and the object will be un-registered when the time exceeds this limit.", + "default": 2.0 + }, + "detection_area": { + "type": "object", + "properties": { + "static": { + "type": "boolean", + "description": "If true, the detection area longitudinal range is calculated based on current ego speed.", + "default": "false" + }, + "min_forward_distance": { + "type": "number", + "description": "Minimum forward distance to search the avoidance target.", + "default": 50.0 + }, + "max_forward_distance": { + "type": "number", + "description": "Maximum forward distance to search the avoidance target.", + "default": 150.0 + }, + "backward_distance": { + "type": "number", + "description": "Backward distance to search the avoidance target.", + "default": 10.0 + } + }, + "required": [ + "static", + "min_forward_distance", + "max_forward_distance", + "backward_distance" + ], + "additionalProperties": false + }, + "parked_vehicle": { + "type": "object", + "properties": { + "th_offset_from_centerline": { + "type": "number", + "description": "Vehicles around the center line within this distance will be excluded from avoidance target.", + "default": 1.0 + }, + "th_shiftable_ratio": { + "type": "number", + "description": "Vehicles around the center line within this distance will be excluded from avoidance target.", + "default": 0.8, + "minimum": 0.0, + "maximum": 1.0 + }, + "min_road_shoulder_width": { + "type": "number", + "description": "Width considered as a road shoulder if the lane does not have a road shoulder target.", + "default": 0.5 + } + }, + "required": [ + "th_offset_from_centerline", + "th_shiftable_ratio", + "min_road_shoulder_width" + ], + "additionalProperties": false + }, + "avoidance_for_ambiguous_vehicle": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Enable avoidance maneuver for ambiguous vehicles.", + "default": "true" + }, + "closest_distance_to_wait_and_see": { + "type": "number", + "description": "Start avoidance maneuver after the distance to ambiguous vehicle is less than this param.", + "default": 10.0 + }, + "condition": { + "type": "object", + "properties": { + "th_stopped_time": { + "type": "number", + "description": "Never avoid object whose stopped time is less than this param.", + "default": 3.0 + }, + "th_moving_distance": { + "type": "number", + "description": "Never avoid object which moves more than this param.", + "default": 1.0 + } + }, + "required": ["th_stopped_time", "th_moving_distance"], + "additionalProperties": false + }, + "ignore_area": { + "type": "object", + "properties": { + "traffic_light": { + "type": "object", + "properties": { + "front_distance": { + "type": "number", + "description": "If the distance between traffic light and vehicle is less than this parameter, this module will ignore it.", + "default": 100.0 + } + }, + "required": ["front_distance"], + "additionalProperties": false + }, + "crosswalk": { + "type": "object", + "properties": { + "front_distance": { + "type": "number", + "description": "If the front distance between crosswalk and vehicle is less than this parameter, this module will ignore it.", + "default": 30.0 + }, + "behind_distance": { + "type": "number", + "description": "If the back distance between crosswalk and vehicle is less than this parameter, this module will ignore it.", + "default": 30.0 + } + }, + "required": ["front_distance", "behind_distance"], + "additionalProperties": false + } + }, + "required": ["traffic_light", "crosswalk"], + "additionalProperties": false + } + }, + "required": [ + "enable", + "closest_distance_to_wait_and_see", + "condition", + "ignore_area" + ], + "additionalProperties": false + }, + "intersection": { + "type": "object", + "properties": { + "yaw_deviation": { + "type": "number", + "description": "Yaw deviation threshold param to judge if the object is not merging or deviating vehicle.", + "default": 0.349 + } + }, + "required": ["yaw_deviation"], + "additionalProperties": false + } + }, + "required": [ + "target_type", + "object_check_goal_distance", + "object_check_return_pose_distance", + "max_compensation_time", + "detection_area", + "parked_vehicle", + "avoidance_for_ambiguous_vehicle", + "intersection" + ], + "additionalProperties": false + }, + "safety_check": { + "type": "object", + "properties": { + "target_type": { + "type": "object", + "properties": { + "car": { + "type": "boolean", + "description": "Enable safety_check for CAR.", + "default": "true" + }, + "truck": { + "type": "boolean", + "description": "Enable safety_check for TRUCK.", + "default": "true" + }, + "bus": { + "type": "boolean", + "description": "Enable safety_check for BUS.", + "default": "true" + }, + "trailer": { + "type": "boolean", + "description": "Enable safety_check for TRAILER.", + "default": "true" + }, + "unknown": { + "type": "boolean", + "description": "Enable safety_check for UNKNOWN.", + "default": "false" + }, + "bicycle": { + "type": "boolean", + "description": "Enable safety_check for BICYCLE.", + "default": "true" + }, + "motorcycle": { + "type": "boolean", + "description": "Enable safety_check for MOTORCYCLE.", + "default": "true" + }, + "pedestrian": { + "type": "boolean", + "description": "Enable safety_check for PEDESTRIAN.", + "default": "true" + } + }, + "required": [ + "car", + "truck", + "bus", + "trailer", + "unknown", + "bicycle", + "motorcycle", + "pedestrian" + ], + "additionalProperties": false + }, + "enable": { + "type": "boolean", + "description": "Enable to use safety check feature.", + "default": "true" + }, + "check_current_lane": { + "type": "boolean", + "description": "Check objects on current driving lane.", + "default": "true" + }, + "check_shift_side_lane": { + "type": "boolean", + "description": "Check objects on shift side lane.", + "default": "true" + }, + "check_other_side_lane": { + "type": "boolean", + "description": "Check objects on other side lane.", + "default": "true" + }, + "check_unavoidable_object": { + "type": "boolean", + "description": "Check collision between ego and unavoidable objects.", + "default": "true" + }, + "check_other_object": { + "type": "boolean", + "description": "Check collision between ego and non avoidance target objects.", + "default": "true" + }, + "check_all_predicted_path": { + "type": "boolean", + "description": "Check all prediction path of safety check target objects.", + "default": "true" + }, + "safety_check_backward_distance": { + "type": "number", + "description": "Backward distance to search the dynamic objects.", + "default": 100.0 + }, + "hysteresis_factor_expand_rate": { + "type": "number", + "description": "Hysteresis factor that be used for chattering prevention.", + "default": 2.0 + }, + "hysteresis_factor_safe_count": { + "type": "integer", + "description": "Hysteresis count that be used for chattering prevention.", + "default": 10 + }, + "min_velocity": { + "type": "number", + "description": "Minimum velocity of the ego vehicle's predicted path.", + "default": 1.38 + }, + "max_velocity": { + "type": "number", + "description": "Maximum velocity of the ego vehicle's predicted path.", + "default": 50.0 + }, + "time_resolution": { + "type": "number", + "description": "Time resolution for the ego vehicle's predicted path.", + "default": 0.5 + }, + "time_horizon_for_front_object": { + "type": "number", + "description": "Time horizon for predicting front objects.", + "default": 3.0 + }, + "time_horizon_for_rear_object": { + "type": "number", + "description": "Time horizon for predicting rear objects.", + "default": 10.0 + }, + "delay_until_departure": { + "type": "number", + "description": "Delay until the ego vehicle departs.", + "default": 1.0 + }, + "extended_polygon_policy": { + "type": "string", + "enum": ["rectangle", "along_path"], + "description": "See https://github.com/autowarefoundation/autoware.universe/pull/6336.", + "default": "along_path" + }, + "expected_front_deceleration": { + "type": "number", + "description": "The front object's maximum deceleration when the front vehicle perform sudden braking.", + "default": -1.0 + }, + "expected_rear_deceleration": { + "type": "number", + "description": "The rear object's maximum deceleration when the rear vehicle perform sudden braking.", + "default": -1.0 + }, + "rear_vehicle_reaction_time": { + "type": "number", + "description": "The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake.", + "default": 2.0 + }, + "rear_vehicle_safety_time_margin": { + "type": "number", + "description": "The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking.", + "default": 1.0 + }, + "lateral_distance_max_threshold": { + "type": "number", + "description": "The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe.", + "default": 2.0 + }, + "longitudinal_distance_min_threshold": { + "type": "number", + "description": "The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe.", + "default": 3.0 + }, + "longitudinal_velocity_delta_time": { + "type": "number", + "description": "The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance)", + "default": 0.0 + } + }, + "required": [ + "target_type", + "enable", + "check_current_lane", + "check_shift_side_lane", + "check_other_side_lane", + "check_unavoidable_object", + "check_other_object", + "check_all_predicted_path", + "safety_check_backward_distance", + "hysteresis_factor_expand_rate", + "hysteresis_factor_safe_count", + "min_velocity", + "max_velocity", + "time_resolution", + "time_horizon_for_front_object", + "time_horizon_for_rear_object", + "delay_until_departure", + "extended_polygon_policy", + "expected_front_deceleration", + "expected_rear_deceleration", + "rear_vehicle_reaction_time", + "rear_vehicle_safety_time_margin", + "lateral_distance_max_threshold", + "longitudinal_distance_min_threshold", + "longitudinal_velocity_delta_time" + ], + "additionalProperties": false + }, + "avoidance": { + "type": "object", + "properties": { + "lateral": { + "type": "object", + "properties": { + "th_avoid_execution": { + "type": "number", + "description": "The lateral distance deviation threshold between the current path and suggested avoidance point to execute avoidance.", + "default": 0.09 + }, + "th_small_shift_length": { + "type": "number", + "description": "The shift lines whose lateral offset is less than this will be applied with other ones.", + "default": 0.101 + }, + "soft_drivable_bound_margin": { + "type": "number", + "description": "Keep distance to drivable bound.", + "default": 0.3 + }, + "hard_drivable_bound_margin": { + "type": "number", + "description": "Keep distance to drivable bound.", + "default": 0.3 + }, + "max_right_shift_length": { + "type": "number", + "description": "Maximum shift length for right direction", + "default": 5.0 + }, + "max_left_shift_length": { + "type": "number", + "description": "Maximum shift length for left direction.", + "default": 5.0 + }, + "max_deviation_from_lane": { + "type": "number", + "description": "Use in validation phase to check if the avoidance path is in drivable area.", + "default": 0.2 + }, + "ratio_for_return_shift_approval": { + "type": "number", + "description": "This parameter is added to allow waiting for the return of shift approval until the occlusion behind the avoid target is clear.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + } + }, + "required": [ + "th_avoid_execution", + "th_small_shift_length", + "soft_drivable_bound_margin", + "hard_drivable_bound_margin", + "max_deviation_from_lane", + "ratio_for_return_shift_approval" + ], + "additionalProperties": false + }, + "longitudinal": { + "type": "object", + "properties": { + "min_prepare_time": { + "type": "number", + "description": "Avoidance shift starts from point ahead of this time x ego speed at least.", + "default": 1.0 + }, + "max_prepare_time": { + "type": "number", + "description": "Avoidance shift starts from point ahead of this time x ego speed if possible.", + "default": 2.0 + }, + "min_prepare_distance": { + "type": "number", + "description": "Minimum prepare distance.", + "default": 1.0 + }, + "min_slow_down_speed": { + "type": "number", + "description": "Minimum slow speed for avoidance prepare section.", + "default": 1.38 + }, + "buf_slow_down_speed": { + "type": "number", + "description": "Buffer for controller tracking error. Basically, vehicle always cannot follow velocity profile precisely. Therefore, the module inserts lower speed than target speed that satisfies conditions to avoid object within accel/jerk constraints so that the avoidance path always can be output even if the current speed is a little bit higher than target speed.", + "default": 0.56 + }, + "nominal_avoidance_speed": { + "type": "number", + "description": "Nominal avoidance speed.", + "default": 8.33 + } + }, + "required": [ + "min_prepare_time", + "max_prepare_time", + "min_prepare_distance", + "min_slow_down_speed", + "buf_slow_down_speed", + "nominal_avoidance_speed" + ], + "additionalProperties": false + }, + "return_dead_line": { + "type": "object", + "properties": { + "goal": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Insert stop point in order to return original lane before reaching goal.", + "default": "true" + }, + "buffer": { + "type": "number", + "description": "Buffer distance to return original lane before reaching goal.", + "default": 3.0 + } + }, + "required": ["enable", "buffer"], + "additionalProperties": false + }, + "traffic_light": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Insert stop point in order to return original lane before reaching traffic light.", + "default": "true" + }, + "buffer": { + "type": "number", + "description": "Buffer distance to return original lane before reaching traffic light.", + "default": 3.0 + } + }, + "required": ["enable", "buffer"], + "additionalProperties": false + } + }, + "required": ["goal", "traffic_light"], + "additionalProperties": false + } + }, + "required": ["lateral", "longitudinal", "return_dead_line"], + "additionalProperties": false + }, + "stop": { + "type": "object", + "properties": { + "max_distance": { + "type": "number", + "description": "Maximum stop distance in the situation where avoidance maneuver is not approved or in yield maneuver.", + "default": 20.0 + }, + "stop_buffer": { + "type": "number", + "description": "Buffer distance in the situation where avoidance maneuver is not approved or in yield maneuver.", + "default": 1.0 + } + }, + "required": ["max_distance", "stop_buffer"], + "additionalProperties": false + }, + "yield": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Flag to enable yield maneuver.", + "default": "true" + }, + "enable_during_shifting": { + "type": "boolean", + "description": "Flag to enable yield maneuver during shifting.", + "default": "false" + } + }, + "required": ["enable", "enable_during_shifting"], + "additionalProperties": false + }, + "cancel": { + "type": "object", + "properties": { + "enable": { + "type": "boolean", + "description": "Flag to enable cancel maneuver.", + "default": "true" + } + }, + "required": ["enable"], + "additionalProperties": false + }, + "policy": { + "type": "object", + "properties": { + "make_approval_request": { + "type": "string", + "enum": ["per_shift_line", "per_avoidance_maneuver"], + "description": "policy for rtc request. select `per_shift_line` or `per_avoidance_maneuver`. `per_shift_line`: request approval for each shift line. `per_avoidance_maneuver`: request approval for avoidance maneuver (avoid + return).", + "default": "per_shift_line" + }, + "deceleration": { + "type": "string", + "enum": ["reliable", "best_effort"], + "description": "policy for vehicle slow down behavior. select `best_effort` or `reliable`. `best_effort`: slow down deceleration & jerk are limited by constraints but there is a possibility that the vehicle can't stop in front of the vehicle. `reliable`: insert stop or slow down point with ignoring decel/jerk constraints. make it possible to increase chance to avoid but uncomfortable deceleration maybe happen.", + "default": "best_effort" + }, + "lateral_margin": { + "type": "string", + "enum": ["reliable", "best_effort"], + "description": "policy for voidance lateral margin. select `best_effort` or `reliable`. `best_effort`: output avoidance path with shorten lateral margin when there is no enough longitudinal margin to avoid. `reliable`: module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid with expected lateral margin.", + "default": "best_effort" + }, + "use_shorten_margin_immediately": { + "type": "boolean", + "description": "if true, module doesn't wait deceleration and outputs avoidance path by best effort margin.", + "default": "true" + } + }, + "required": ["make_approval_request"], + "additionalProperties": false + }, + "constraints": { + "type": "object", + "properties": { + "lateral": { + "type": "object", + "properties": { + "velocity": { + "type": "array", + "description": "Velocity array to decide current lateral accel/jerk limit.", + "default": [1.0, 1.38, 11.1] + }, + "max_accel_values": { + "type": "array", + "description": "Avoidance path gets sharp up to this accel limit when there is not enough distance from ego.", + "default": [0.5, 0.5, 0.5] + }, + "min_jerk_values": { + "type": "array", + "description": "Avoidance path is generated with this jerk when there is enough distance from ego.", + "default": [0.2, 0.2, 0.2] + }, + "max_jerk_values": { + "type": "array", + "description": "Avoidance path gets sharp up to this jerk limit when there is not enough distance from ego.", + "default": [1.0, 1.0, 1.0] + } + }, + "required": ["velocity", "max_accel_values", "min_jerk_values", "max_jerk_values"], + "additionalProperties": false + }, + "longitudinal": { + "type": "object", + "properties": { + "nominal_deceleration": { + "type": "number", + "description": "Nominal deceleration limit.", + "default": -1.0 + }, + "nominal_jerk": { + "type": "number", + "description": "Nominal jerk limit.", + "default": 0.5 + }, + "max_deceleration": { + "type": "number", + "description": "Max deceleration limit.", + "default": -1.5 + }, + "max_jerk": { + "type": "number", + "description": "Max jerk limit.", + "default": 1.0 + }, + "max_acceleration": { + "type": "number", + "description": "Maximum acceleration during avoidance.", + "default": 0.5 + }, + "min_velocity_to_limit_max_acceleration": { + "type": "number", + "description": "If the ego speed is faster than this param, the module applies acceleration limit `max_acceleration`.", + "default": 2.78 + } + }, + "required": [ + "nominal_deceleration", + "nominal_jerk", + "max_deceleration", + "max_jerk", + "max_acceleration", + "min_velocity_to_limit_max_acceleration" + ], + "additionalProperties": false + } + }, + "required": ["lateral", "longitudinal"], + "additionalProperties": false + }, + "shift_line_pipeline": { + "type": "object", + "properties": { + "trim": { + "type": "object", + "properties": { + "quantize_size": { + "type": "number", + "description": "Lateral shift length quantize size.", + "default": 0.1 + }, + "th_similar_grad_1": { + "type": "number", + "description": "Lateral shift length threshold to merge similar gradient shift lines.", + "default": 0.1 + }, + "th_similar_grad_2": { + "type": "number", + "description": "Lateral shift length threshold to merge similar gradient shift lines.", + "default": 0.2 + }, + "th_similar_grad_3": { + "type": "number", + "description": "Lateral shift length threshold to merge similar gradient shift lines.", + "default": 0.5 + } + }, + "required": [ + "quantize_size", + "th_similar_grad_1", + "th_similar_grad_2", + "th_similar_grad_3" + ], + "additionalProperties": false + } + }, + "required": ["trim"], + "additionalProperties": false + }, + "debug": { + "type": "object", + "properties": { + "marker": { + "type": "boolean", + "description": "Publish debug marker.", + "default": "false" + }, + "console": { + "type": "boolean", + "description": "Output debug info on console.", + "default": "false" + } + }, + "required": ["marker", "console"], + "additionalProperties": false + } + }, + "required": [ + "resample_interval_for_planning", + "resample_interval_for_output", + "enable_bound_clipping", + "use_adjacent_lane", + "use_opposite_lane", + "use_hatched_road_markings", + "use_intersection_areas", + "use_freespace_areas", + "target_object", + "target_filtering", + "safety_check", + "avoidance", + "stop", + "yield", + "cancel", + "policy", + "constraints", + "shift_line_pipeline", + "debug" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "properties": { + "ros__parameters": { + "type": "object", + "properties": { + "avoidance": { + "$ref": "#/definitions/behavior_path_avoidance_module" + } + }, + "required": ["avoidance"], + "additionalProperties": false + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 682a814961e100c2c49a1be3b8995f366c038276 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 12 Apr 2024 15:36:25 +0900 Subject: [PATCH 030/192] refactor(avoidance): unify redundant parameters (#6798) * refactor(avoidance): unify redundant parameters Signed-off-by: satoshi-ota * refactor(avoidance): remove unused parameters Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/avoidance.param.yaml | 10 +--- .../data_structs.hpp | 13 ++--- .../behavior_path_avoidance_module/helper.hpp | 11 ++-- .../parameter_helper.hpp | 4 +- .../schema/avoidance.schema.json | 54 +++++-------------- .../src/manager.cpp | 5 +- 6 files changed, 29 insertions(+), 68 deletions(-) diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index 92f533bc63872..5d6044df64b2f 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -28,7 +28,6 @@ hard_margin_for_parked_vehicle: 0.7 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.5 # [m] FOR DEVELOPER - use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -39,7 +38,6 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true bus: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -50,7 +48,6 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true trailer: th_moving_speed: 1.0 th_moving_time: 2.0 @@ -61,7 +58,6 @@ hard_margin_for_parked_vehicle: 0.7 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true unknown: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -72,7 +68,6 @@ hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 - use_conservative_buffer_longitudinal: true bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -83,7 +78,6 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 @@ -94,7 +88,6 @@ hard_margin_for_parked_vehicle: 0.3 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 @@ -105,7 +98,6 @@ hard_margin_for_parked_vehicle: 0.5 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 - use_conservative_buffer_longitudinal: true lower_distance_for_polygon_expansion: 30.0 # [m] FOR DEVELOPER upper_distance_for_polygon_expansion: 100.0 # [m] FOR DEVELOPER @@ -222,6 +214,8 @@ min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER nominal_avoidance_speed: 8.33 # [m/s] FOR DEVELOPER + consider_front_overhang: true # [-] + consider_rear_overhang: true # [-] # return dead line return_dead_line: goal: diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index bc66598d3ee90..e74b546f31fc4 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -76,8 +76,6 @@ struct ObjectParameter double lateral_hard_margin_for_parked_vehicle{1.0}; double longitudinal_margin{0.0}; - - bool use_conservative_buffer_longitudinal{true}; }; struct AvoidanceParameters @@ -191,14 +189,6 @@ struct AvoidanceParameters double time_threshold_for_ambiguous_vehicle{0.0}; double distance_threshold_for_ambiguous_vehicle{0.0}; - // when complete avoidance motion, there is a distance margin with the object - // for longitudinal direction - double longitudinal_collision_margin_min_distance{0.0}; - - // when complete avoidance motion, there is a time margin with the object - // for longitudinal direction - double longitudinal_collision_margin_time{0.0}; - // parameters for safety check area bool enable_safety_check{false}; bool check_current_lane{false}; @@ -219,6 +209,9 @@ struct AvoidanceParameters size_t hysteresis_factor_safe_count; double hysteresis_factor_expand_rate{0.0}; + bool consider_front_overhang{true}; + bool consider_rear_overhang{true}; + // maximum stop distance double stop_max_distance{0.0}; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp index 2e481e7c98e44..8d95e724045ba 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp @@ -148,16 +148,19 @@ class AvoidanceHelper { const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto & additional_buffer_longitudinal = - object_parameter.use_conservative_buffer_longitudinal ? data_->parameters.base_link2front - : 0.0; - return object_parameter.longitudinal_margin + additional_buffer_longitudinal; + if (!parameters_->consider_front_overhang) { + return object_parameter.longitudinal_margin; + } + return object_parameter.longitudinal_margin + data_->parameters.base_link2front; } double getRearConstantDistance(const ObjectData & object) const { const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); + if (!parameters_->consider_rear_overhang) { + return object_parameter.longitudinal_margin; + } return object_parameter.longitudinal_margin + data_->parameters.base_link2rear + object.length; } diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index 5b8963c7ca22d..6dbf52c0425fb 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -70,8 +70,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node) param.lateral_hard_margin_for_parked_vehicle = getOrDeclareParameter(*node, ns + "lateral_margin.hard_margin_for_parked_vehicle"); param.longitudinal_margin = getOrDeclareParameter(*node, ns + "longitudinal_margin"); - param.use_conservative_buffer_longitudinal = - getOrDeclareParameter(*node, ns + "use_conservative_buffer_longitudinal"); return param; }; @@ -270,6 +268,8 @@ AvoidanceParameters getParameter(rclcpp::Node * node) p.buf_slow_down_speed = getOrDeclareParameter(*node, ns + "buf_slow_down_speed"); p.nominal_avoidance_speed = getOrDeclareParameter(*node, ns + "nominal_avoidance_speed"); + p.consider_front_overhang = getOrDeclareParameter(*node, ns + "consider_front_overhang"); + p.consider_rear_overhang = getOrDeclareParameter(*node, ns + "consider_rear_overhang"); } // avoidance maneuver (return shift dead line) diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json index cd3e29b8ec0b8..79882beb805f8 100644 --- a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -104,11 +104,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -171,11 +166,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -238,11 +228,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -305,11 +290,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -372,11 +352,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -439,11 +414,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -506,11 +476,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -573,11 +538,6 @@ "type": "number", "description": "This value will be applied envelope_buffer_margin according to the distance between the ego and object.", "default": 0.0 - }, - "use_conservative_buffer_longitudinal": { - "type": "boolean", - "description": "When set to true, the base_link2front is added to the longitudinal buffer before avoidance.", - "default": "true" } }, "required": [ @@ -1150,6 +1110,16 @@ "type": "number", "description": "Nominal avoidance speed.", "default": 8.33 + }, + "consider_front_overhang": { + "type": "boolean", + "description": "Flag to consider vehicle front overhang in shift line generation logic.", + "default": true + }, + "consider_rear_overhang": { + "type": "boolean", + "description": "Flag to consider vehicle rear overhang in shift line generation logic.", + "default": true } }, "required": [ @@ -1158,7 +1128,9 @@ "min_prepare_distance", "min_slow_down_speed", "buf_slow_down_speed", - "nominal_avoidance_speed" + "nominal_avoidance_speed", + "consider_front_overhang", + "consider_rear_overhang" ], "additionalProperties": false }, diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index 3261214d1b9b6..e3391f251e55f 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -59,9 +59,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "longitudinal_margin", config.longitudinal_margin); - updateParam( - parameters, ns + "use_conservative_buffer_longitudinal", - config.use_conservative_buffer_longitudinal); }; { @@ -170,6 +167,8 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "min_prepare_distance", p->min_prepare_distance); updateParam(parameters, ns + "min_slow_down_speed", p->min_slow_down_speed); updateParam(parameters, ns + "buf_slow_down_speed", p->buf_slow_down_speed); + updateParam(parameters, ns + "consider_front_overhang", p->consider_front_overhang); + updateParam(parameters, ns + "consider_rear_overhang", p->consider_rear_overhang); } { From fd032e86926cbd191f8fdca3b154f46cadad3fd8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 12 Apr 2024 16:59:34 +0900 Subject: [PATCH 031/192] refactor(static_centerline_generator): change the package name from static_centerline_optimizer (#6795) static_centerline_optimizer -> static_centerline_generator Signed-off-by: Takayuki Murooka --- .github/CODEOWNERS | 2 +- ...load_local_cartesian_utm_from_yaml.test.py | 2 +- .../test_node_load_local_from_yaml.test.py | 2 +- .../test_node_load_mgrs_from_yaml.test.py | 2 +- ...load_transverse_mercator_from_yaml.test.py | 2 +- planning/.pages | 2 +- .../obstacle_avoidance_planner/node.hpp | 4 +- .../path_smoother/elastic_band_smoother.hpp | 2 +- .../include/path_sampler/node.hpp | 2 +- .../CMakeLists.txt | 12 ++-- .../README.md | 6 +- .../config/common.param.yaml | 0 .../config/nearest_search.param.yaml | 0 .../static_centerline_generator.param.yaml} | 0 .../config/vehicle_info.param.yaml | 0 .../bag_ego_trajectory_based_centerline.hpp | 12 ++-- ...timization_trajectory_based_centerline.hpp | 12 ++-- .../static_centerline_generator_node.hpp} | 30 +++++----- .../type_alias.hpp | 10 ++-- .../static_centerline_generator}/utils.hpp | 12 ++-- .../launch/run_planning_server.launch.xml | 4 +- .../static_centerline_generator.launch.xml} | 6 +- .../media/rviz.png | Bin .../media/unsafe_footprints.png | Bin .../msg/PointsWithLaneId.msg | 0 .../package.xml | 4 +- .../rviz/static_centerline_generator.rviz} | 8 +-- .../scripts/app.py | 14 ++--- .../scripts/centerline_updater_helper.py | 2 +- .../bag_ego_trajectory_based_centerline.sh | 3 + ...ptimization_trajectory_based_centerline.sh | 2 +- .../bag_ego_trajectory_based_centerline.cpp | 8 +-- ...timization_trajectory_based_centerline.cpp | 10 ++-- .../src/main.cpp | 4 +- .../src/static_centerline_generator_node.cpp} | 56 +++++++++--------- .../src/utils.cpp | 6 +- .../srv/LoadMap.srv | 0 .../srv/PlanPath.srv | 2 +- .../srv/PlanRoute.srv | 0 .../test/data/bag_ego_trajectory.db3 | Bin .../test/data/lanelet2_map.osm | 0 .../test_static_centerline_generator.test.py} | 20 +++---- .../bag_ego_trajectory_based_centerline.sh | 3 - 43 files changed, 133 insertions(+), 133 deletions(-) rename planning/{static_centerline_optimizer => static_centerline_generator}/CMakeLists.txt (80%) rename planning/{static_centerline_optimizer => static_centerline_generator}/README.md (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/config/common.param.yaml (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/config/nearest_search.param.yaml (100%) rename planning/{static_centerline_optimizer/config/static_centerline_optimizer.param.yaml => static_centerline_generator/config/static_centerline_generator.param.yaml} (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/config/vehicle_info.param.yaml (100%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/centerline_source/bag_ego_trajectory_based_centerline.hpp (71%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/centerline_source/optimization_trajectory_based_centerline.hpp (81%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp => static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp} (81%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/type_alias.hpp (87%) rename planning/{static_centerline_optimizer/include/static_centerline_optimizer => static_centerline_generator/include/static_centerline_generator}/utils.hpp (86%) rename planning/{static_centerline_optimizer => static_centerline_generator}/launch/run_planning_server.launch.xml (54%) rename planning/{static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml => static_centerline_generator/launch/static_centerline_generator.launch.xml} (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/media/rviz.png (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/media/unsafe_footprints.png (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/msg/PointsWithLaneId.msg (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/package.xml (94%) rename planning/{static_centerline_optimizer/rviz/static_centerline_optimizer.rviz => static_centerline_generator/rviz/static_centerline_generator.rviz} (98%) rename planning/{static_centerline_optimizer => static_centerline_generator}/scripts/app.py (92%) rename planning/{static_centerline_optimizer => static_centerline_generator}/scripts/centerline_updater_helper.py (99%) create mode 100755 planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh rename planning/{static_centerline_optimizer => static_centerline_generator}/scripts/tmp/optimization_trajectory_based_centerline.sh (57%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/centerline_source/bag_ego_trajectory_based_centerline.cpp (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/centerline_source/optimization_trajectory_based_centerline.cpp (96%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/main.cpp (86%) rename planning/{static_centerline_optimizer/src/static_centerline_optimizer_node.cpp => static_centerline_generator/src/static_centerline_generator_node.cpp} (93%) rename planning/{static_centerline_optimizer => static_centerline_generator}/src/utils.cpp (98%) rename planning/{static_centerline_optimizer => static_centerline_generator}/srv/LoadMap.srv (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/srv/PlanPath.srv (55%) rename planning/{static_centerline_optimizer => static_centerline_generator}/srv/PlanRoute.srv (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/test/data/bag_ego_trajectory.db3 (100%) rename planning/{static_centerline_optimizer => static_centerline_generator}/test/data/lanelet2_map.osm (100%) rename planning/{static_centerline_optimizer/test/test_static_centerline_optimizer.test.py => static_centerline_generator/test/test_static_centerline_generator.test.py} (84%) delete mode 100755 planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 256b617116432..a6cdc58f03e94 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -205,7 +205,7 @@ planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp +planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp diff --git a/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py index ec13df010c8c3..b8540550ce9da 100644 --- a/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py index ccec68486b79c..c7697038cc253 100644 --- a/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py index 200504d0ea18f..f75beddc6827c 100644 --- a/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py b/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py index 7883ae6aa3c99..765f3cde04679 100644 --- a/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py +++ b/map/map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py @@ -61,7 +61,7 @@ def generate_test_description(): LaunchDescription( [ map_projection_loader_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/planning/.pages b/planning/.pages index 1b5608f7ded57..942a5a0b32158 100644 --- a/planning/.pages +++ b/planning/.pages @@ -67,7 +67,7 @@ nav: - 'About Motion Velocity Smoother': planning/motion_velocity_smoother - 'About Motion Velocity Smoother (Japanese)': planning/motion_velocity_smoother/README.ja - 'Scenario Selector': planning/scenario_selector - - 'Static Centerline Optimizer': planning/static_centerline_optimizer + - 'Static Centerline Generator': planning/static_centerline_generator - 'API and Library': - 'Costmap Generator': planning/costmap_generator - 'External Velocity Limit Selector': planning/external_velocity_limit_selector diff --git a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index 2dbefffe67738..3677e6c5fb075 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -39,12 +39,12 @@ class ObstacleAvoidancePlanner : public rclcpp::Node public: explicit ObstacleAvoidancePlanner(const rclcpp::NodeOptions & node_options); - // NOTE: This is for the static_centerline_optimizer package which utilizes the following + // NOTE: This is for the static_centerline_generator package which utilizes the following // instance. std::shared_ptr getMPTOptimizer() const { return mpt_optimizer_ptr_; } // private: -protected: // for the static_centerline_optimizer package +protected: // for the static_centerline_generator package // TODO(murooka) move this node to common class DrivingDirectionChecker { diff --git a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index eb2d651cc967d..e0bdb326adb33 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -38,7 +38,7 @@ class ElasticBandSmoother : public rclcpp::Node public: explicit ElasticBandSmoother(const rclcpp::NodeOptions & node_options); - // NOTE: This is for the static_centerline_optimizer package which utilizes the following + // NOTE: This is for the static_centerline_generator package which utilizes the following // instance. std::shared_ptr getElasticBandSmoother() const { return eb_path_smoother_ptr_; } diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp b/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp index a9002c8cf8a9f..50464f12114b0 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp +++ b/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp @@ -37,7 +37,7 @@ class PathSampler : public rclcpp::Node public: explicit PathSampler(const rclcpp::NodeOptions & node_options); -protected: // for the static_centerline_optimizer package +protected: // for the static_centerline_generator package // argument variables vehicle_info_util::VehicleInfo vehicle_info_{}; mutable DebugData debug_data_{}; diff --git a/planning/static_centerline_optimizer/CMakeLists.txt b/planning/static_centerline_generator/CMakeLists.txt similarity index 80% rename from planning/static_centerline_optimizer/CMakeLists.txt rename to planning/static_centerline_generator/CMakeLists.txt index cc33f2234a50c..991d12097cc08 100644 --- a/planning/static_centerline_optimizer/CMakeLists.txt +++ b/planning/static_centerline_generator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(static_centerline_optimizer) +project(static_centerline_generator) find_package(autoware_cmake REQUIRED) @@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) rosidl_generate_interfaces( - static_centerline_optimizer + static_centerline_generator "srv/LoadMap.srv" "srv/PlanRoute.srv" "srv/PlanPath.srv" @@ -21,7 +21,7 @@ autoware_package() ament_auto_add_executable(main src/main.cpp - src/static_centerline_optimizer_node.cpp + src/static_centerline_generator_node.cpp src/centerline_source/optimization_trajectory_based_centerline.cpp src/centerline_source/bag_ego_trajectory_based_centerline.cpp src/utils.cpp @@ -29,10 +29,10 @@ ament_auto_add_executable(main if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) rosidl_target_interfaces(main - static_centerline_optimizer "rosidl_typesupport_cpp") + static_centerline_generator "rosidl_typesupport_cpp") else() rosidl_get_typesupport_target( - cpp_typesupport_target static_centerline_optimizer "rosidl_typesupport_cpp") + cpp_typesupport_target static_centerline_generator "rosidl_typesupport_cpp") target_link_libraries(main "${cpp_typesupport_target}") endif() @@ -45,7 +45,7 @@ ament_auto_package( if(BUILD_TESTING) add_launch_test( - test/test_static_centerline_optimizer.test.py + test/test_static_centerline_generator.test.py TIMEOUT "30" ) install(DIRECTORY diff --git a/planning/static_centerline_optimizer/README.md b/planning/static_centerline_generator/README.md similarity index 93% rename from planning/static_centerline_optimizer/README.md rename to planning/static_centerline_generator/README.md index fd5a58ef816df..00572b754645c 100644 --- a/planning/static_centerline_optimizer/README.md +++ b/planning/static_centerline_generator/README.md @@ -1,4 +1,4 @@ -# Static Centerline Optimizer +# Static Centerline Generator ## Purpose @@ -34,7 +34,7 @@ We can run with the following command by designating `` ```sh -ros2 launch static_centerline_optimizer run_planning_server.launch.xml vehicle_model:= +ros2 launch static_centerline_generator run_planning_server.launch.xml vehicle_model:= ``` FYI, port ID of the http server is 4010 by default. @@ -50,7 +50,7 @@ The optimized centerline can be generated from the command line interface by des - `` ```sh -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= +ros2 launch static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= ``` The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`. diff --git a/planning/static_centerline_optimizer/config/common.param.yaml b/planning/static_centerline_generator/config/common.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/common.param.yaml rename to planning/static_centerline_generator/config/common.param.yaml diff --git a/planning/static_centerline_optimizer/config/nearest_search.param.yaml b/planning/static_centerline_generator/config/nearest_search.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/nearest_search.param.yaml rename to planning/static_centerline_generator/config/nearest_search.param.yaml diff --git a/planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml b/planning/static_centerline_generator/config/static_centerline_generator.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/static_centerline_optimizer.param.yaml rename to planning/static_centerline_generator/config/static_centerline_generator.param.yaml diff --git a/planning/static_centerline_optimizer/config/vehicle_info.param.yaml b/planning/static_centerline_generator/config/vehicle_info.param.yaml similarity index 100% rename from planning/static_centerline_optimizer/config/vehicle_info.param.yaml rename to planning/static_centerline_generator/config/vehicle_info.param.yaml diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp similarity index 71% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp index b29f222b068cc..30b2e55c36bba 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ #include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/type_alias.hpp" #include -namespace static_centerline_optimizer +namespace static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node); -} // namespace static_centerline_optimizer -#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +} // namespace static_centerline_generator +#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp similarity index 81% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp index 8c7c1e69e9ce6..7e7cdea31e9f1 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT -#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT #include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/type_alias.hpp" #include -namespace static_centerline_optimizer +namespace static_centerline_generator { class OptimizationTrajectoryBasedCenterline { @@ -37,7 +37,7 @@ class OptimizationTrajectoryBasedCenterline rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; }; -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator // clang-format off -#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT // clang-format on diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp similarity index 81% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp index 5d9530a469012..c1d92c06a8e05 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +#define STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ #include "rclcpp/rclcpp.hpp" -#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" -#include "static_centerline_optimizer/srv/load_map.hpp" -#include "static_centerline_optimizer/srv/plan_path.hpp" -#include "static_centerline_optimizer/srv/plan_route.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" +#include "static_centerline_generator/srv/load_map.hpp" +#include "static_centerline_generator/srv/plan_path.hpp" +#include "static_centerline_generator/srv/plan_route.hpp" +#include "static_centerline_generator/type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -34,11 +34,11 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { -using static_centerline_optimizer::srv::LoadMap; -using static_centerline_optimizer::srv::PlanPath; -using static_centerline_optimizer::srv::PlanRoute; +using static_centerline_generator::srv::LoadMap; +using static_centerline_generator::srv::PlanPath; +using static_centerline_generator::srv::PlanRoute; struct CenterlineWithRoute { @@ -46,10 +46,10 @@ struct CenterlineWithRoute std::vector route_lane_ids{}; }; -class StaticCenterlineOptimizerNode : public rclcpp::Node +class StaticCenterlineGeneratorNode : public rclcpp::Node { public: - explicit StaticCenterlineOptimizerNode(const rclcpp::NodeOptions & node_options); + explicit StaticCenterlineGeneratorNode(const rclcpp::NodeOptions & node_options); void run(); private: @@ -115,5 +115,5 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node // vehicle info vehicle_info_util::VehicleInfo vehicle_info_; }; -} // namespace static_centerline_optimizer -#endif // STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ +} // namespace static_centerline_generator +#endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp b/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp similarity index 87% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp index 1a700d36deaaf..2dcb9cbbd099f 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/type_alias.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp @@ -11,8 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__TYPE_ALIAS_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__TYPE_ALIAS_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ +#define STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ #include "route_handler/route_handler.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -26,7 +26,7 @@ #include "autoware_planning_msgs/msg/lanelet_route.hpp" #include "visualization_msgs/msg/marker_array.hpp" -namespace static_centerline_optimizer +namespace static_centerline_generator { using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObjects; @@ -41,6 +41,6 @@ using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; using visualization_msgs::msg::MarkerArray; -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator -#endif // STATIC_CENTERLINE_OPTIMIZER__TYPE_ALIAS_HPP_ +#endif // STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ diff --git a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp b/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp similarity index 86% rename from planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp rename to planning/static_centerline_generator/include/static_centerline_generator/utils.hpp index 04f2268aa972f..c8cf8f8b90590 100644 --- a/planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_OPTIMIZER__UTILS_HPP_ -#define STATIC_CENTERLINE_OPTIMIZER__UTILS_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ +#define STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ #include "route_handler/route_handler.hpp" -#include "static_centerline_optimizer/type_alias.hpp" +#include "static_centerline_generator/type_alias.hpp" #include @@ -24,7 +24,7 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace utils { @@ -53,6 +53,6 @@ MarkerArray create_distance_text_marker( const geometry_msgs::msg::Pose & pose, const double dist, const std::array & marker_color, const rclcpp::Time & now, const size_t idx); } // namespace utils -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator -#endif // STATIC_CENTERLINE_OPTIMIZER__UTILS_HPP_ +#endif // STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ diff --git a/planning/static_centerline_optimizer/launch/run_planning_server.launch.xml b/planning/static_centerline_generator/launch/run_planning_server.launch.xml similarity index 54% rename from planning/static_centerline_optimizer/launch/run_planning_server.launch.xml rename to planning/static_centerline_generator/launch/run_planning_server.launch.xml index 3a8b88a021dc0..1493078317458 100644 --- a/planning/static_centerline_optimizer/launch/run_planning_server.launch.xml +++ b/planning/static_centerline_generator/launch/run_planning_server.launch.xml @@ -2,11 +2,11 @@ - + - + diff --git a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml b/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml similarity index 93% rename from planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml rename to planning/static_centerline_generator/launch/static_centerline_generator.launch.xml index ed137367f3ba4..ae71b0ae6e925 100644 --- a/planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml +++ b/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -55,7 +55,7 @@ - + @@ -79,11 +79,11 @@ - + - + diff --git a/planning/static_centerline_optimizer/media/rviz.png b/planning/static_centerline_generator/media/rviz.png similarity index 100% rename from planning/static_centerline_optimizer/media/rviz.png rename to planning/static_centerline_generator/media/rviz.png diff --git a/planning/static_centerline_optimizer/media/unsafe_footprints.png b/planning/static_centerline_generator/media/unsafe_footprints.png similarity index 100% rename from planning/static_centerline_optimizer/media/unsafe_footprints.png rename to planning/static_centerline_generator/media/unsafe_footprints.png diff --git a/planning/static_centerline_optimizer/msg/PointsWithLaneId.msg b/planning/static_centerline_generator/msg/PointsWithLaneId.msg similarity index 100% rename from planning/static_centerline_optimizer/msg/PointsWithLaneId.msg rename to planning/static_centerline_generator/msg/PointsWithLaneId.msg diff --git a/planning/static_centerline_optimizer/package.xml b/planning/static_centerline_generator/package.xml similarity index 94% rename from planning/static_centerline_optimizer/package.xml rename to planning/static_centerline_generator/package.xml index eef133581622f..6573f6e439c43 100644 --- a/planning/static_centerline_optimizer/package.xml +++ b/planning/static_centerline_generator/package.xml @@ -1,9 +1,9 @@ - static_centerline_optimizer + static_centerline_generator 0.1.0 - The static_centerline_optimizer package + The static_centerline_generator package Takayuki Murooka Kosuke Takeuchi Apache License 2.0 diff --git a/planning/static_centerline_optimizer/rviz/static_centerline_optimizer.rviz b/planning/static_centerline_generator/rviz/static_centerline_generator.rviz similarity index 98% rename from planning/static_centerline_optimizer/rviz/static_centerline_optimizer.rviz rename to planning/static_centerline_generator/rviz/static_centerline_generator.rviz index 1e7573d561ba1..62b4c9b75ec87 100644 --- a/planning/static_centerline_optimizer/rviz/static_centerline_optimizer.rviz +++ b/planning/static_centerline_generator/rviz/static_centerline_generator.rviz @@ -130,7 +130,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/input_centerline + Value: /static_centerline_generator/input_centerline Value: true View Drivable Area: Alpha: 0.9990000128746033 @@ -179,7 +179,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/output_centerline + Value: /static_centerline_generator/output_centerline Value: true View Footprint: Alpha: 1 @@ -222,7 +222,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/debug/raw_centerline + Value: /static_centerline_generator/debug/raw_centerline Value: false View Drivable Area: Alpha: 0.9990000128746033 @@ -268,7 +268,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_optimizer/debug/unsafe_footprints + Value: /static_centerline_generator/debug/unsafe_footprints Value: true Enabled: false Name: debug diff --git a/planning/static_centerline_optimizer/scripts/app.py b/planning/static_centerline_generator/scripts/app.py similarity index 92% rename from planning/static_centerline_optimizer/scripts/app.py rename to planning/static_centerline_generator/scripts/app.py index 90610755e828a..c1cb0473da040 100755 --- a/planning/static_centerline_optimizer/scripts/app.py +++ b/planning/static_centerline_generator/scripts/app.py @@ -23,12 +23,12 @@ from flask_cors import CORS import rclpy from rclpy.node import Node -from static_centerline_optimizer.srv import LoadMap -from static_centerline_optimizer.srv import PlanPath -from static_centerline_optimizer.srv import PlanRoute +from static_centerline_generator.srv import LoadMap +from static_centerline_generator.srv import PlanPath +from static_centerline_generator.srv import PlanRoute rclpy.init() -node = Node("static_centerline_optimizer_http_server") +node = Node("static_centerline_generator_http_server") app = Flask(__name__) CORS(app) @@ -51,7 +51,7 @@ def get_map(): map_id = map_uuid # create client - cli = create_client(LoadMap, "/planning/static_centerline_optimizer/load_map") + cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map") # request map loading req = LoadMap.Request(map=data["map"]) @@ -85,7 +85,7 @@ def post_planned_route(): print("map_id is not correct.") # create client - cli = create_client(PlanRoute, "/planning/static_centerline_optimizer/plan_route") + cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route") # request route planning req = PlanRoute.Request( @@ -123,7 +123,7 @@ def post_planned_path(): print("map_id is not correct.") # create client - cli = create_client(PlanPath, "/planning/static_centerline_optimizer/plan_path") + cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path") # request path planning route_lane_ids = [eval(i) for i in request.args.getlist("route[]")] diff --git a/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py b/planning/static_centerline_generator/scripts/centerline_updater_helper.py similarity index 99% rename from planning/static_centerline_optimizer/scripts/centerline_updater_helper.py rename to planning/static_centerline_generator/scripts/centerline_updater_helper.py index 00a646406f14f..fec3d21d20bec 100755 --- a/planning/static_centerline_optimizer/scripts/centerline_updater_helper.py +++ b/planning/static_centerline_generator/scripts/centerline_updater_helper.py @@ -155,7 +155,7 @@ def __init__(self): transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) self.sub_whole_centerline = self.create_subscription( Trajectory, - "/static_centerline_optimizer/output_whole_centerline", + "/static_centerline_generator/output_whole_centerline", self.onWholeCenterline, transient_local_qos, ) diff --git a/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..30ed667dd3732 --- /dev/null +++ b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh similarity index 57% rename from planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh rename to planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh index 3967c7a4ca523..809bbb46a179e 100755 --- a/planning/static_centerline_optimizer/scripts/tmp/optimization_trajectory_based_centerline.sh +++ b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh @@ -1,3 +1,3 @@ #!/bin/bash -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus +ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp similarity index 93% rename from planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp rename to planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index 571e98cdbe1c3..4e541b1aff527 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" +#include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "rclcpp/serialization.hpp" #include "rosbag2_cpp/reader.hpp" -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" #include -namespace static_centerline_optimizer +namespace static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node) { @@ -79,4 +79,4 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) return centerline_traj_points; } -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp similarity index 96% rename from planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp rename to planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 20b2027f39d54..7980ae4e8d2d7 100644 --- a/planning/static_centerline_optimizer/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" +#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "obstacle_avoidance_planner/node.hpp" #include "path_smoother/elastic_band_smoother.hpp" -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" -#include "static_centerline_optimizer/utils.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" +#include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace { @@ -180,4 +180,4 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra return whole_optimized_traj_points; } -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/src/main.cpp b/planning/static_centerline_generator/src/main.cpp similarity index 86% rename from planning/static_centerline_optimizer/src/main.cpp rename to planning/static_centerline_generator/src/main.cpp index 96c139fd7ff93..981cf54fc9274 100644 --- a/planning/static_centerline_optimizer/src/main.cpp +++ b/planning/static_centerline_generator/src/main.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" int main(int argc, char * argv[]) { @@ -21,7 +21,7 @@ int main(int argc, char * argv[]) // initialize node rclcpp::NodeOptions node_options; auto node = - std::make_shared(node_options); + std::make_shared(node_options); // get ros parameter const bool run_background = node->declare_parameter("run_background"); diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp similarity index 93% rename from planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp rename to planning/static_centerline_generator/src/static_centerline_generator_node.cpp index 073d30f5b5a39..ec7d6278e346d 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp" +#include "static_centerline_generator/static_centerline_generator_node.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" #include "lanelet2_extension/utility/query.hpp" @@ -21,10 +21,10 @@ #include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp" -#include "static_centerline_optimizer/msg/points_with_lane_id.hpp" -#include "static_centerline_optimizer/type_alias.hpp" -#include "static_centerline_optimizer/utils.hpp" +#include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" +#include "static_centerline_generator/msg/points_with_lane_id.hpp" +#include "static_centerline_generator/type_alias.hpp" +#include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" @@ -53,7 +53,7 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace { @@ -165,9 +165,9 @@ std::vector resample_trajectory_points( } } // namespace -StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( +StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( const rclcpp::NodeOptions & node_options) -: Node("static_centerline_optimizer", node_options) +: Node("static_centerline_generator", node_options) { // publishers pub_map_bin_ = @@ -215,21 +215,21 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( - "/planning/static_centerline_optimizer/load_map", + "/planning/static_centerline_generator/load_map", std::bind( - &StaticCenterlineOptimizerNode::on_load_map, this, std::placeholders::_1, + &StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_route_ = create_service( - "/planning/static_centerline_optimizer/plan_route", + "/planning/static_centerline_generator/plan_route", std::bind( - &StaticCenterlineOptimizerNode::on_plan_route, this, std::placeholders::_1, + &StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_path_ = create_service( - "/planning/static_centerline_optimizer/plan_path", + "/planning/static_centerline_generator/plan_path", std::bind( - &StaticCenterlineOptimizerNode::on_plan_path, this, std::placeholders::_1, + &StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); @@ -245,11 +245,11 @@ StaticCenterlineOptimizerNode::StaticCenterlineOptimizerNode( return CenterlineSource::BagEgoTrajectoryBase; } throw std::logic_error( - "The centerline source is not supported in static_centerline_optimizer."); + "The centerline source is not supported in static_centerline_generator."); }(); } -void StaticCenterlineOptimizerNode::update_centerline_range( +void StaticCenterlineGeneratorNode::update_centerline_range( const int traj_start_index, const int traj_end_index) { if (!centerline_with_route_ || traj_range_indices_.second + 1 < traj_start_index) { @@ -267,7 +267,7 @@ void StaticCenterlineOptimizerNode::update_centerline_range( motion_utils::convertToTrajectory(selected_centerline, create_header(this->now()))); } -void StaticCenterlineOptimizerNode::run() +void StaticCenterlineGeneratorNode::run() { // declare planning setting parameters const auto lanelet2_input_file_path = declare_parameter("lanelet2_input_file_path"); @@ -283,7 +283,7 @@ void StaticCenterlineOptimizerNode::run() centerline_with_route_ = centerline_with_route; } -CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_route() +CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_route() { if (!route_handler_ptr_) { RCLCPP_ERROR(get_logger(), "Route handler is not ready. Return empty trajectory."); @@ -317,7 +317,7 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout return CenterlineWithRoute{bag_centerline, route_lane_ids}; } throw std::logic_error( - "The centerline source is not supported in static_centerline_optimizer."); + "The centerline source is not supported in static_centerline_generator."); }(); // resample @@ -334,7 +334,7 @@ CenterlineWithRoute StaticCenterlineOptimizerNode::generate_centerline_with_rout return centerline_with_route; } -void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_file_path) +void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) { // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { @@ -381,7 +381,7 @@ void StaticCenterlineOptimizerNode::load_map(const std::string & lanelet2_input_ route_handler_ptr_->setMap(*map_bin_ptr_); } -void StaticCenterlineOptimizerNode::on_load_map( +void StaticCenterlineGeneratorNode::on_load_map( const LoadMap::Request::SharedPtr request, const LoadMap::Response::SharedPtr response) { const std::string tmp_lanelet2_input_file_path = "/tmp/input_lanelet2_map.osm"; @@ -402,7 +402,7 @@ void StaticCenterlineOptimizerNode::on_load_map( response->message = "InvalidMapFormat"; } -std::vector StaticCenterlineOptimizerNode::plan_route( +std::vector StaticCenterlineGeneratorNode::plan_route( const lanelet::Id start_lanelet_id, const lanelet::Id end_lanelet_id) { if (!map_bin_ptr_ || !route_handler_ptr_) { @@ -442,7 +442,7 @@ std::vector StaticCenterlineOptimizerNode::plan_route( return route_lane_ids; } -void StaticCenterlineOptimizerNode::on_plan_route( +void StaticCenterlineGeneratorNode::on_plan_route( const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response) { if (!map_bin_ptr_ || !route_handler_ptr_) { @@ -475,7 +475,7 @@ void StaticCenterlineOptimizerNode::on_plan_route( response->lane_ids = lane_ids; } -void StaticCenterlineOptimizerNode::on_plan_path( +void StaticCenterlineGeneratorNode::on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response) { if (!route_handler_ptr_) { @@ -533,7 +533,7 @@ void StaticCenterlineOptimizerNode::on_plan_path( if (!current_lanelet_points.empty()) { // register points with lane_id - static_centerline_optimizer::msg::PointsWithLaneId points_with_lane_id; + static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; points_with_lane_id.lane_id = lanelet.id(); points_with_lane_id.points = current_lanelet_points; response->points_with_lane_ids.push_back(points_with_lane_id); @@ -548,7 +548,7 @@ void StaticCenterlineOptimizerNode::on_plan_path( response->message = ""; } -void StaticCenterlineOptimizerNode::evaluate( +void StaticCenterlineGeneratorNode::evaluate( const std::vector & route_lane_ids, const std::vector & optimized_traj_points) { @@ -618,7 +618,7 @@ void StaticCenterlineOptimizerNode::evaluate( RCLCPP_INFO(get_logger(), "Minimum distance to road is %f [m]", min_dist); } -void StaticCenterlineOptimizerNode::save_map( +void StaticCenterlineGeneratorNode::save_map( const std::string & lanelet2_output_file_path, const CenterlineWithRoute & centerline_with_route) { if (!route_handler_ptr_) { @@ -636,4 +636,4 @@ void StaticCenterlineOptimizerNode::save_map( lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector_); RCLCPP_INFO(get_logger(), "Saved map."); } -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/src/utils.cpp b/planning/static_centerline_generator/src/utils.cpp similarity index 98% rename from planning/static_centerline_optimizer/src/utils.cpp rename to planning/static_centerline_generator/src/utils.cpp index 9448677d1bbae..ddfd3e11036ce 100644 --- a/planning/static_centerline_optimizer/src/utils.cpp +++ b/planning/static_centerline_generator/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_optimizer/utils.hpp" +#include "static_centerline_generator/utils.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" @@ -21,7 +21,7 @@ #include #include -namespace static_centerline_optimizer +namespace static_centerline_generator { namespace { @@ -228,4 +228,4 @@ MarkerArray create_distance_text_marker( return marker_array; } } // namespace utils -} // namespace static_centerline_optimizer +} // namespace static_centerline_generator diff --git a/planning/static_centerline_optimizer/srv/LoadMap.srv b/planning/static_centerline_generator/srv/LoadMap.srv similarity index 100% rename from planning/static_centerline_optimizer/srv/LoadMap.srv rename to planning/static_centerline_generator/srv/LoadMap.srv diff --git a/planning/static_centerline_optimizer/srv/PlanPath.srv b/planning/static_centerline_generator/srv/PlanPath.srv similarity index 55% rename from planning/static_centerline_optimizer/srv/PlanPath.srv rename to planning/static_centerline_generator/srv/PlanPath.srv index 644a4ea013557..7d823b4eccbf9 100644 --- a/planning/static_centerline_optimizer/srv/PlanPath.srv +++ b/planning/static_centerline_generator/srv/PlanPath.srv @@ -1,6 +1,6 @@ uint32 map_id int64[] route --- -static_centerline_optimizer/PointsWithLaneId[] points_with_lane_ids +static_centerline_generator/PointsWithLaneId[] points_with_lane_ids string message int64[] unconnected_lane_ids diff --git a/planning/static_centerline_optimizer/srv/PlanRoute.srv b/planning/static_centerline_generator/srv/PlanRoute.srv similarity index 100% rename from planning/static_centerline_optimizer/srv/PlanRoute.srv rename to planning/static_centerline_generator/srv/PlanRoute.srv diff --git a/planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 b/planning/static_centerline_generator/test/data/bag_ego_trajectory.db3 similarity index 100% rename from planning/static_centerline_optimizer/test/data/bag_ego_trajectory.db3 rename to planning/static_centerline_generator/test/data/bag_ego_trajectory.db3 diff --git a/planning/static_centerline_optimizer/test/data/lanelet2_map.osm b/planning/static_centerline_generator/test/data/lanelet2_map.osm similarity index 100% rename from planning/static_centerline_optimizer/test/data/lanelet2_map.osm rename to planning/static_centerline_generator/test/data/lanelet2_map.osm diff --git a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py b/planning/static_centerline_generator/test/test_static_centerline_generator.test.py similarity index 84% rename from planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py rename to planning/static_centerline_generator/test/test_static_centerline_generator.test.py index 9f0a5df7f3fcc..29ee49a11e3b3 100644 --- a/planning/static_centerline_optimizer/test/test_static_centerline_optimizer.test.py +++ b/planning/static_centerline_generator/test/test_static_centerline_generator.test.py @@ -28,11 +28,11 @@ @pytest.mark.launch_test def generate_test_description(): lanelet2_map_path = os.path.join( - get_package_share_directory("static_centerline_optimizer"), "test/data/lanelet2_map.osm" + get_package_share_directory("static_centerline_generator"), "test/data/lanelet2_map.osm" ) - static_centerline_optimizer_node = Node( - package="static_centerline_optimizer", + static_centerline_generator_node = Node( + package="static_centerline_generator", executable="main", output="screen", parameters=[ @@ -50,8 +50,8 @@ def generate_test_description(): "mission_planner.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), - "config/static_centerline_optimizer.param.yaml", + get_package_share_directory("static_centerline_generator"), + "config/static_centerline_generator.param.yaml", ), os.path.join( get_package_share_directory("behavior_path_planner"), @@ -74,15 +74,15 @@ def generate_test_description(): "config/lanelet2_map_loader.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), + get_package_share_directory("static_centerline_generator"), "config/common.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), + get_package_share_directory("static_centerline_generator"), "config/nearest_search.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_optimizer"), + get_package_share_directory("static_centerline_generator"), "config/vehicle_info.param.yaml", ), ], @@ -93,8 +93,8 @@ def generate_test_description(): return ( LaunchDescription( [ - static_centerline_optimizer_node, - # Start test after 1s - gives time for the static_centerline_optimizer to finish initialization + static_centerline_generator_node, + # Start test after 1s - gives time for the static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh deleted file mode 100755 index 8164b521553c8..0000000000000 --- a/planning/static_centerline_optimizer/scripts/tmp/bag_ego_trajectory_based_centerline.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_optimizer --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus From 453d41c2f75091c32c21f48f497d11e2f99a48a0 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Fri, 12 Apr 2024 17:26:33 +0900 Subject: [PATCH 032/192] fix(ground_segmentation launch): fix topic name conflict in additional_lidars option (#6801) fix(ground_segmentation launch): fix topic name conflict when using additional lidars Signed-off-by: badai-nguyen --- .../ground_segmentation/ground_segmentation.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index f502aef017979..a307b192d7caa 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -281,7 +281,7 @@ def create_single_frame_obstacle_segmentation_components(self, input_topic, outp use_additional = bool(additional_lidars) relay_topic = "all_lidars/pointcloud" common_pipeline_output = ( - "single_frame/pointcloud" if use_additional or use_ransac else output_topic + "common/pointcloud" if use_additional or use_ransac else output_topic ) components = self.create_common_pipeline( From 9f3633d3c15f6e32d5d3bafbfef31ff7109f5d2c Mon Sep 17 00:00:00 2001 From: Dmitrii Koldaev <39071246+dkoldaev@users.noreply.github.com> Date: Fri, 12 Apr 2024 17:33:12 +0900 Subject: [PATCH 033/192] fix(map_based_prediction): use object_buffer_time_length_ (#6772) fix: use object_buffer_time_length_ Signed-off-by: Dmitrii Koldaev Co-authored-by: Dmitrii Koldaev --- .../map_based_prediction/src/map_based_prediction_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index e12b7c54c3a9f..56dc1c2293583 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -1360,7 +1360,7 @@ void MapBasedPredictionNode::removeOldObjectsHistory( const double latest_object_time = rclcpp::Time(object_data.back().header.stamp).seconds(); // Delete Old Objects - if (current_time - latest_object_time > 2.0) { + if (current_time - latest_object_time > object_buffer_time_length_) { invalid_object_id.push_back(object_id); continue; } @@ -1368,7 +1368,7 @@ void MapBasedPredictionNode::removeOldObjectsHistory( // Delete old information while (!object_data.empty()) { const double post_object_time = rclcpp::Time(object_data.front().header.stamp).seconds(); - if (current_time - post_object_time > 2.0) { + if (current_time - post_object_time > object_buffer_time_length_) { // Delete Old Position object_data.pop_front(); } else { From fae0f78d8b48a798b13e7d2beb69e6088d2c7c75 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 12 Apr 2024 19:20:47 +0900 Subject: [PATCH 034/192] feat(start_planner): fix non-thread-safe access (#6779) Signed-off-by: Mamoru Sobue --- .../pull_out_planner_base.hpp | 2 +- .../start_planner_module.hpp | 23 ++- .../src/start_planner_module.cpp | 162 ++++++++++++++---- 3 files changed, 148 insertions(+), 39 deletions(-) diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp index 0126ab47d1ae6..3089134a16500 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/pull_out_planner_base.hpp @@ -51,7 +51,7 @@ class PullOutPlannerBase } virtual ~PullOutPlannerBase() = default; - void setPlannerData(std::shared_ptr & planner_data) + void setPlannerData(const std::shared_ptr & planner_data) { planner_data_ = planner_data; } diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index 2d661cf41855f..c05b7a8f94716 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -155,6 +155,24 @@ class StartPlannerModule : public SceneModuleInterface bool isFreespacePlanning() const { return status_.planner_type == PlannerType::FREESPACE; } private: + struct StartPlannerData + { + StartPlannerParameters parameters; + PlannerData planner_data; + ModuleStatus current_status; + PullOutStatus main_thread_pull_out_status; + bool is_stopped; + + StartPlannerData clone() const; + void update( + const StartPlannerParameters & parameters, const PlannerData & planner_data, + const ModuleStatus & current_status, const PullOutStatus & pull_out_status, + const bool is_stopped); + }; + std::optional freespace_thread_status_{std::nullopt}; + std::optional start_planner_data_{std::nullopt}; + std::mutex start_planner_data_mutex_; + // Flag class for managing whether a certain callback is running in multi-threading class ScopedFlag { @@ -290,7 +308,6 @@ class StartPlannerModule : public SceneModuleInterface bool hasFinishedBackwardDriving() const; bool hasCollisionWithDynamicObjects() const; bool isStopped(); - bool isStuck(); bool hasFinishedCurrentPath(); void updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, @@ -307,7 +324,9 @@ class StartPlannerModule : public SceneModuleInterface SafetyCheckParams createSafetyCheckParams() const; // freespace planner void onFreespacePlannerTimer(); - bool planFreespacePath(); + std::optional planFreespacePath( + const StartPlannerParameters & parameters, + const std::shared_ptr & planner_data, const PullOutStatus & pull_out_status); void setDebugData(); void logPullOutStatus(rclcpp::Logger::Level log_level = rclcpp::Logger::Level::Info) const; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 0e6e5fae84fb8..4433020605056 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -93,26 +93,56 @@ void StartPlannerModule::onFreespacePlannerTimer() { const ScopedFlag flag(is_freespace_planner_cb_running_); - if (getCurrentStatus() == ModuleStatus::IDLE) { + std::shared_ptr local_planner_data{nullptr}; + std::optional current_status_opt{std::nullopt}; + std::optional parameters_opt{std::nullopt}; + std::optional pull_out_status_opt{std::nullopt}; + bool is_stopped; + + // making a local copy of thread sensitive data + { + std::lock_guard guard(start_planner_data_mutex_); + if (start_planner_data_) { + const auto & start_planner_data = start_planner_data_.value(); + local_planner_data = std::make_shared(start_planner_data.planner_data); + current_status_opt = start_planner_data.current_status; + parameters_opt = start_planner_data.parameters; + pull_out_status_opt = start_planner_data.main_thread_pull_out_status; + is_stopped = start_planner_data.is_stopped; + } + } + // finish copying thread sensitive data + if (!local_planner_data || !current_status_opt || !parameters_opt || !pull_out_status_opt) { return; } - if (!planner_data_) { + const auto & current_status = current_status_opt.value(); + const auto & parameters = parameters_opt.value(); + const auto & pull_out_status = pull_out_status_opt.value(); + + if (current_status == ModuleStatus::IDLE) { return; } - if (!planner_data_->costmap) { + if (!local_planner_data->costmap) { return; } const bool is_new_costmap = - (clock_->now() - planner_data_->costmap->header.stamp).seconds() < 1.0; + (clock_->now() - local_planner_data->costmap->header.stamp).seconds() < 1.0; if (!is_new_costmap) { return; } - if (isStuck()) { - planFreespacePath(); + const bool is_stuck = is_stopped && pull_out_status.planner_type == PlannerType::STOP && + !pull_out_status.found_pull_out_path; + if (is_stuck) { + const auto free_space_status = + planFreespacePath(parameters, local_planner_data, pull_out_status); + if (free_space_status) { + std::lock_guard guard(start_planner_data_mutex_); + freespace_thread_status_ = free_space_status; + } } } @@ -172,6 +202,38 @@ void StartPlannerModule::updateObjectsFilteringParams( void StartPlannerModule::updateData() { + // The method PlannerManager::run() calls SceneModuleInterface::setData and + // SceneModuleInterface::setPreviousModuleOutput() before this module's run() method is called + // with module_ptr->run(). Then module_ptr->run() invokes StartPlannerModule::updateData and, + // finally, the planWaitingApproval()/plan() methods are called by run(). So we can copy the + // latest current_status to start_planner_data_ here for later usage. + + // NOTE: onFreespacePlannerTimer copies start_planner_data to its thread local variable, so we + // need to lock start_planner_data_ here to avoid data race. But the following clone process is + // lightweight because most of the member variables of PlannerData/RouteHandler is + // shared_ptrs/bool + // making a local copy of thread sensitive data + { + std::lock_guard guard(start_planner_data_mutex_); + if (!start_planner_data_) { + start_planner_data_ = StartPlannerData(); + } + start_planner_data_.value().update( + *parameters_, *planner_data_, getCurrentStatus(), status_, isStopped()); + if (freespace_thread_status_) { + // if freespace solution is available, copy it to status_ on main thread + const auto & freespace_status = freespace_thread_status_.value(); + status_.pull_out_path = freespace_status.pull_out_path; + status_.pull_out_start_pose = freespace_status.pull_out_start_pose; + status_.planner_type = freespace_status.planner_type; + status_.found_pull_out_path = freespace_status.found_pull_out_path; + status_.driving_forward = freespace_status.driving_forward; + // and then reset it + freespace_thread_status_ = std::nullopt; + } + } + // finish copying thread sensitive data + if (receivedNewRoute()) { resetStatus(); DEBUG_PRINT("StartPlannerModule::updateData() received new route, reset status"); @@ -1128,19 +1190,6 @@ bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward() const return elapsed < parameters_->prepare_time_before_start; } -bool StartPlannerModule::isStuck() -{ - if (!isStopped()) { - return false; - } - - if (status_.planner_type == PlannerType::STOP || !status_.found_pull_out_path) { - return true; - } - - return false; -} - bool StartPlannerModule::hasFinishedCurrentPath() { const auto current_path = getCurrentPath(); @@ -1336,19 +1385,21 @@ BehaviorModuleOutput StartPlannerModule::generateStopOutput() return output; } -bool StartPlannerModule::planFreespacePath() +std::optional StartPlannerModule::planFreespacePath( + const StartPlannerParameters & parameters, + const std::shared_ptr & planner_data, const PullOutStatus & pull_out_status) { - const Pose & current_pose = planner_data_->self_odometry->pose.pose; - const auto & route_handler = planner_data_->route_handler; + const Pose & current_pose = planner_data->self_odometry->pose.pose; + const auto & route_handler = planner_data->route_handler; - const double end_pose_search_start_distance = parameters_->end_pose_search_start_distance; - const double end_pose_search_end_distance = parameters_->end_pose_search_end_distance; - const double end_pose_search_interval = parameters_->end_pose_search_interval; + const double end_pose_search_start_distance = parameters.end_pose_search_start_distance; + const double end_pose_search_end_distance = parameters.end_pose_search_end_distance; + const double end_pose_search_interval = parameters.end_pose_search_interval; const double backward_path_length = - planner_data_->parameters.backward_path_length + parameters_->max_back_distance; + planner_data->parameters.backward_path_length + parameters.max_back_distance; const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_path_length, std::numeric_limits::max(), + planner_data, backward_path_length, std::numeric_limits::max(), /*forward_only_in_route*/ true); const auto current_arc_coords = lanelet::utils::getArcCoordinates(current_lanes, current_pose); @@ -1361,23 +1412,23 @@ bool StartPlannerModule::planFreespacePath() for (const auto & p : center_line_path.points) { const Pose end_pose = p.point.pose; - freespace_planner_->setPlannerData(planner_data_); + freespace_planner_->setPlannerData(planner_data); auto freespace_path = freespace_planner_->plan(current_pose, end_pose); if (!freespace_path) { continue; } - const std::lock_guard lock(mutex_); - status_.pull_out_path = *freespace_path; - status_.pull_out_start_pose = current_pose; - status_.planner_type = freespace_planner_->getPlannerType(); - status_.found_pull_out_path = true; - status_.driving_forward = true; - return true; + auto status = pull_out_status; + status.pull_out_path = *freespace_path; + status.pull_out_start_pose = current_pose; + status.planner_type = freespace_planner_->getPlannerType(); + status.found_pull_out_path = true; + status.driving_forward = true; + return std::make_optional(status); } - return false; + return std::nullopt; } void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const @@ -1665,4 +1716,43 @@ void StartPlannerModule::logPullOutStatus(rclcpp::Logger::Level log_level) const logFunc("======================================="); } + +StartPlannerModule::StartPlannerData StartPlannerModule::StartPlannerData::clone() const +{ + StartPlannerData start_planner_data; + start_planner_data.update( + parameters, planner_data, current_status, main_thread_pull_out_status, is_stopped); + return start_planner_data; +} + +void StartPlannerModule::StartPlannerData::update( + const StartPlannerParameters & parameters_, const PlannerData & planner_data_, + const ModuleStatus & current_status_, const PullOutStatus & pull_out_status_, + const bool is_stopped_) +{ + parameters = parameters_; + planner_data = planner_data_; + // TODO(Mamoru Sobue): in the future we will add planner_data->is_route_handler_updated flag to + // avoid the copy overhead of lanelet objects inside the RouteHandler. behavior_path_planner can + // tell us the flag if map/route changed, so we can skip route_handler update if it + // is false in the following way + /* + auto route_handler_self = planner_data.route_handler; + planner_data = planner_data_; // sync planer_data to planner_data_, planner_data.route_handler + is once re-pointed + + if (!planner_data_->is_route_handler_updated && route_handler_self != nullptr) { + // we do not need to sync planner_data.route_handler with that of planner_data_ + // re-point to the original again + planner_data.route_handler = route_handler_self; + } else { + // this is actually heavy if the lanelet_map is HUGE + planner_data.route_handler = std::make_shared(*(planner_data_.route_handler)); + } + */ + planner_data.route_handler = std::make_shared(*(planner_data_.route_handler)); + current_status = current_status_; + main_thread_pull_out_status = pull_out_status_; + is_stopped = is_stopped_; +} } // namespace behavior_path_planner From 4ff93b2ff57e4ff59486a2412ebdf40d5501cc0c Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 15 Apr 2024 09:26:01 +0900 Subject: [PATCH 035/192] revert(lane_change): disable terminal path (#6800) Signed-off-by: Zulfaqar Azmi --- planning/behavior_path_lane_change_module/src/interface.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index 523a5349aaef6..af2ccb807d989 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -136,8 +136,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() { *prev_approved_path_ = getPreviousModuleOutput().path; - BehaviorModuleOutput out; - out = module_type_->getTerminalLaneChangePath(); + BehaviorModuleOutput out = getPreviousModuleOutput(); module_type_->insertStopPoint(module_type_->getLaneChangeStatus().current_lanes, out.path); out.turn_signal_info = getCurrentTurnSignalInfo(out.path, getPreviousModuleOutput().turn_signal_info); From 165e79d9e98c1b989d7eac76c895a0a2556adc43 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 15 Apr 2024 11:57:22 +0900 Subject: [PATCH 036/192] feat(goal_planner): fix non-thread-safe access in goal_planner (#6740) Signed-off-by: Mamoru Sobue --- .../geometric_pull_over.hpp | 6 +- .../goal_planner_module.hpp | 190 +++-- .../goal_searcher.hpp | 36 +- .../goal_searcher_base.hpp | 25 +- .../shift_pull_over.hpp | 6 +- .../src/geometric_pull_over.cpp | 5 +- .../src/goal_planner_module.cpp | 698 ++++++++++++------ .../src/goal_searcher.cpp | 108 +-- .../src/shift_pull_over.cpp | 4 +- 9 files changed, 714 insertions(+), 364 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index 6de1a726d4d4e..e67d458874d17 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include @@ -34,9 +33,7 @@ class GeometricPullOver : public PullOverPlannerBase public: GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr occupancy_grid_map, - const bool is_forward); + const LaneDepartureChecker & lane_departure_checker, const bool is_forward); PullOverPlannerType getPlannerType() const override { @@ -61,7 +58,6 @@ class GeometricPullOver : public PullOverPlannerBase protected: ParallelParkingParameters parallel_parking_parameters_; LaneDepartureChecker lane_departure_checker_{}; - std::shared_ptr occupancy_grid_map_; bool is_forward_{true}; bool left_side_parking_{true}; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 21ea06531c2f4..818aa7ff79edb 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -91,6 +91,33 @@ public: \ DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) +enum class DecidingPathStatus { + NOT_DECIDED, + DECIDING, + DECIDED, +}; +using DecidingPathStatusWithStamp = std::pair; + +struct PreviousPullOverData +{ + struct SafetyStatus + { + std::optional safe_start_time{}; + bool is_safe{false}; + }; + + void reset() + { + found_path = false; + safety_status = SafetyStatus{}; + deciding_path_status = DecidingPathStatusWithStamp{}; + } + + bool found_path{false}; + SafetyStatus safety_status{}; + DecidingPathStatusWithStamp deciding_path_status{}; +}; + class ThreadSafeData { public: @@ -145,6 +172,9 @@ class ThreadSafeData void set(const std::shared_ptr & arg) { set_pull_over_path(arg); } void set(const PullOverPath & arg) { set_pull_over_path(arg); } void set(const GoalCandidate & arg) { set_modified_goal_pose(arg); } + void set(const BehaviorModuleOutput & arg) { set_last_previous_module_output(arg); } + void set(const PreviousPullOverData & arg) { set_prev_data(arg); } + void set(const CollisionCheckDebugMap & arg) { set_collision_check(arg); } void clearPullOverPath() { @@ -182,6 +212,8 @@ class ThreadSafeData last_path_update_time_ = std::nullopt; last_path_idx_increment_time_ = std::nullopt; closest_start_pose_ = std::nullopt; + last_previous_module_output_ = std::nullopt; + prev_data_.reset(); } DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) @@ -193,6 +225,9 @@ class ThreadSafeData DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates) DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, closest_start_pose) + DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, last_previous_module_output) + DEFINE_SETTER_GETTER_WITH_MUTEX(PreviousPullOverData, prev_data) + DEFINE_SETTER_GETTER_WITH_MUTEX(CollisionCheckDebugMap, collision_check) private: std::shared_ptr pull_over_path_{nullptr}; @@ -203,6 +238,9 @@ class ThreadSafeData std::optional last_path_update_time_; std::optional last_path_idx_increment_time_; std::optional closest_start_pose_{}; + std::optional last_previous_module_output_{}; + PreviousPullOverData prev_data_{}; + CollisionCheckDebugMap collision_check_{}; std::recursive_mutex & mutex_; rclcpp::Clock::SharedPtr clock_; @@ -234,33 +272,6 @@ struct LastApprovalData Pose pose{}; }; -enum class DecidingPathStatus { - NOT_DECIDED, - DECIDING, - DECIDED, -}; -using DecidingPathStatusWithStamp = std::pair; - -struct PreviousPullOverData -{ - struct SafetyStatus - { - std::optional safe_start_time{}; - bool is_safe{false}; - }; - - void reset() - { - found_path = false; - safety_status = SafetyStatus{}; - deciding_path_status = DecidingPathStatusWithStamp{}; - } - - bool found_path{false}; - SafetyStatus safety_status{}; - DecidingPathStatusWithStamp deciding_path_status{}; -}; - // store stop_pose_ pointer with reason string struct PoseWithString { @@ -363,6 +374,50 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: + /** + * @brief shared data for onTimer(onTimer/onFreespaceParkingTimer just read this) + */ + struct GoalPlannerData + { + GoalPlannerData(const PlannerData & planner_data, const GoalPlannerParameters & parameters) + { + initializeOccupancyGridMap(planner_data, parameters); + }; + GoalPlannerParameters parameters; + std::shared_ptr ego_predicted_path_params; + std::shared_ptr objects_filtering_params; + std::shared_ptr safety_check_params; + tier4_autoware_utils::LinearRing2d vehicle_footprint; + + PlannerData planner_data; + ModuleStatus current_status; + BehaviorModuleOutput previous_module_output; + // collision detector + // need to be shared_ptr to be used in planner and goal searcher + std::shared_ptr occupancy_grid_map; + std::shared_ptr goal_searcher; + + const BehaviorModuleOutput & getPreviousModuleOutput() const { return previous_module_output; } + const ModuleStatus & getCurrentStatus() const { return current_status; } + void updateOccupancyGrid(); + GoalPlannerData clone() const; + void update( + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params_, + const std::shared_ptr & objects_filtering_params_, + const std::shared_ptr & safety_check_params_, + const PlannerData & planner_data, const ModuleStatus & current_status, + const BehaviorModuleOutput & previous_module_output, + const std::shared_ptr goal_searcher_, + const tier4_autoware_utils::LinearRing2d & vehicle_footprint); + + private: + void initializeOccupancyGridMap( + const PlannerData & planner_data, const GoalPlannerParameters & parameters); + }; + std::optional gp_planner_data_{std::nullopt}; + std::mutex gp_planner_data_mutex_; + // Flag class for managing whether a certain callback is running in multi-threading class ScopedFlag { @@ -420,9 +475,10 @@ class GoalPlannerModule : public SceneModuleInterface // goal searcher std::shared_ptr goal_searcher_; - // collision detector - // need to be shared_ptr to be used in planner and goal searcher - std::shared_ptr occupancy_grid_map_; + // NOTE: this is latest occupancy_grid_map pointer which the local planner_data on + // onFreespaceParkingTimer thread storage may point to while calculation. + // onTimer/onFreespaceParkingTimer and their callees MUST NOT use this + std::shared_ptr occupancy_grid_map_{nullptr}; // check stopped and stuck state std::deque odometry_buffer_stopped_; @@ -431,10 +487,10 @@ class GoalPlannerModule : public SceneModuleInterface tier4_autoware_utils::LinearRing2d vehicle_footprint_; std::recursive_mutex mutex_; - ThreadSafeData thread_safe_data_; + // TODO(Mamoru Sobue): isSafePath() modifies ThreadSafeData::check_collision, avoid this mutable + mutable ThreadSafeData thread_safe_data_; std::unique_ptr last_approval_data_{nullptr}; - PreviousPullOverData prev_data_{}; // approximate distance from the start point to the end point of pull_over. // this is used as an assumed value to decelerate, etc., before generating the actual path. @@ -460,11 +516,12 @@ class GoalPlannerModule : public SceneModuleInterface mutable PoseWithString debug_stop_pose_with_info_; // collision check - void initializeOccupancyGridMap(); - void updateOccupancyGrid(); - bool checkOccupancyGridCollision(const PathWithLaneId & path) const; + bool checkOccupancyGridCollision( + const PathWithLaneId & path, + const std::shared_ptr occupancy_grid_map) const; bool checkObjectsCollision( - const PathWithLaneId & path, const double collision_check_margin, + const PathWithLaneId & path, const std::shared_ptr planner_data, + const GoalPlannerParameters & parameters, const double collision_check_margin, const bool extract_static_objects, const bool update_debug_data = false) const; // goal seach @@ -487,13 +544,39 @@ class GoalPlannerModule : public SceneModuleInterface bool isStopped( std::deque & odometry_buffer, const double time); bool hasFinishedCurrentPath(); - bool isOnModifiedGoal() const; + bool isOnModifiedGoal(const Pose & current_pose, const GoalPlannerParameters & parameters) const; double calcModuleRequestLength() const; - bool needPathUpdate(const double path_update_duration) const; - bool isStuck(); - bool hasDecidedPath() const; - bool hasNotDecidedPath() const; - DecidingPathStatusWithStamp checkDecidingPathStatus() const; + bool needPathUpdate( + const Pose & current_pose, const double path_update_duration, + const GoalPlannerParameters & parameters) const; + bool isStuck( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters); + bool hasDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const; + bool hasNotDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const; + DecidingPathStatusWithStamp checkDecidingPathStatus( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const; void decideVelocity(); bool foundPullOverPath() const; void updateStatus(const BehaviorModuleOutput & output); @@ -508,7 +591,10 @@ class GoalPlannerModule : public SceneModuleInterface bool hasEnoughTimePassedSincePathUpdate(const double duration) const; // freespace parking - bool planFreespacePath(); + bool planFreespacePath( + std::shared_ptr planner_data, + const std::shared_ptr goal_searcher, + const std::shared_ptr occupancy_grid_map); bool canReturnToLaneParking(); // plan pull over path @@ -537,10 +623,12 @@ class GoalPlannerModule : public SceneModuleInterface TurnSignalInfo calcTurnSignalInfo(); std::optional ignore_signal_{std::nullopt}; - std::optional last_previous_module_output_{}; - bool hasPreviousModulePathShapeChanged() const; - bool hasDeviatedFromLastPreviousModulePath() const; - bool hasDeviatedFromCurrentPreviousModulePath() const; + bool hasPreviousModulePathShapeChanged(const BehaviorModuleOutput & previous_module_output) const; + bool hasDeviatedFromLastPreviousModulePath( + const std::shared_ptr planner_data) const; + bool hasDeviatedFromCurrentPreviousModulePath( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output) const; // timer for generating pull over path candidates in a separate thread void onTimer(); @@ -556,16 +644,22 @@ class GoalPlannerModule : public SceneModuleInterface // safety check void initializeSafetyCheckParameters(); SafetyCheckParams createSafetyCheckParams() const; + /* void updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const; + */ /** * @brief Checks if the current path is safe. * @return std::pair * first: If the path is safe for a certain period of time, true. * second: If the path is safe in the current state, true. */ - std::pair isSafePath() const; + std::pair isSafePath( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params) const; // debug void setDebugData(); diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index f228ecc378c28..89f4086874183 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -29,33 +29,45 @@ using BasicPolygons2d = std::vector; class GoalSearcher : public GoalSearcherBase { public: - GoalSearcher( - const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint, - const std::shared_ptr & occupancy_grid_map); + GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint); - GoalCandidates search() override; - void update(GoalCandidates & goal_candidates) const override; + GoalCandidates search( + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) override; + void update( + GoalCandidates & goal_candidates, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const override; // todo(kosuke55): Functions for this specific use should not be in the interface, // so it is better to consider interface design when we implement other goal searchers. GoalCandidate getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates) const override; + const GoalCandidates & goal_candidates, + const std::shared_ptr & planner_data) const override; bool isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor) const override; + const GoalCandidate & goal_candidate, const double margin_scale_factor, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const override; private: void countObjectsToAvoid( - GoalCandidates & goal_candidates, const PredictedObjects & objects) const; - void createAreaPolygons(std::vector original_search_poses); - bool checkCollision(const Pose & pose, const PredictedObjects & objects) const; + GoalCandidates & goal_candidates, const PredictedObjects & objects, + const std::shared_ptr & planner_data) const; + void createAreaPolygons( + std::vector original_search_poses, + const std::shared_ptr & planner_data); + bool checkCollision( + const Pose & pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map) const; bool checkCollisionWithLongitudinalDistance( - const Pose & ego_pose, const PredictedObjects & objects) const; + const Pose & ego_pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const; BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const; BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const; bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const; LinearRing2d vehicle_footprint_{}; - std::shared_ptr occupancy_grid_map_{}; bool left_side_parking_{true}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp index 2ddacc0aac46d..f5d879358cd38 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -17,6 +17,7 @@ #include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -49,23 +50,29 @@ class GoalSearcherBase { reference_goal_pose_ = reference_goal_pose; } + const Pose & getReferenceGoal() const { return reference_goal_pose_; } - void setPlannerData(const std::shared_ptr & planner_data) + MultiPolygon2d getAreaPolygons() const { return area_polygons_; } + virtual GoalCandidates search( + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) = 0; + virtual void update( + [[maybe_unused]] GoalCandidates & goal_candidates, + [[maybe_unused]] const std::shared_ptr occupancy_grid_map, + [[maybe_unused]] const std::shared_ptr & planner_data) const { - planner_data_ = planner_data; + return; } - - MultiPolygon2d getAreaPolygons() { return area_polygons_; } - virtual GoalCandidates search() = 0; - virtual void update([[maybe_unused]] GoalCandidates & goal_candidates) const { return; } virtual GoalCandidate getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates) const = 0; + const GoalCandidates & goal_candidates, + const std::shared_ptr & planner_data) const = 0; virtual bool isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor) const = 0; + const GoalCandidate & goal_candidate, const double margin_scale_factor, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const = 0; protected: GoalPlannerParameters parameters_{}; - std::shared_ptr planner_data_{nullptr}; Pose reference_goal_pose_{}; MultiPolygon2d area_polygons_{}; }; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index 892ef7d5dd303..d0b0aee83e20c 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -34,9 +33,7 @@ class ShiftPullOver : public PullOverPlannerBase public: ShiftPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr & occupancy_grid_map); - + const LaneDepartureChecker & lane_departure_checker); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::SHIFT; }; std::optional plan(const Pose & goal_pose) override; @@ -57,7 +54,6 @@ class ShiftPullOver : public PullOverPlannerBase const Pose & start_pose, const Pose & end_pose, const double resample_interval); LaneDepartureChecker lane_departure_checker_{}; - std::shared_ptr occupancy_grid_map_{}; bool left_side_parking_{true}; }; diff --git a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp index b7d1c240d032a..0779002690f8f 100644 --- a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -27,13 +27,10 @@ namespace behavior_path_planner { GeometricPullOver::GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr occupancy_grid_map, - const bool is_forward) + const LaneDepartureChecker & lane_departure_checker, const bool is_forward) : PullOverPlannerBase{node, parameters}, parallel_parking_parameters_{parameters.parallel_parking_parameters}, lane_departure_checker_{lane_departure_checker}, - occupancy_grid_map_{occupancy_grid_map}, is_forward_{is_forward}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index a890cfc21ed13..14fc48b4aeba9 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -78,14 +78,14 @@ GoalPlannerModule::GoalPlannerModule( for (const std::string & planner_type : parameters_->efficient_path_order) { if (planner_type == "SHIFT" && parameters_->enable_shift_parking) { - pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, occupancy_grid_map_)); + pull_over_planners_.push_back( + std::make_shared(node, *parameters, lane_departure_checker)); } else if (planner_type == "ARC_FORWARD" && parameters_->enable_arc_forward_parking) { pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, occupancy_grid_map_, /*is_forward*/ true)); + node, *parameters, lane_departure_checker, /*is_forward*/ true)); } else if (planner_type == "ARC_BACKWARD" && parameters_->enable_arc_backward_parking) { pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, occupancy_grid_map_, /*is_forward*/ false)); + node, *parameters, lane_departure_checker, /*is_forward*/ false)); } } @@ -97,8 +97,7 @@ GoalPlannerModule::GoalPlannerModule( // currently there is only one goal_searcher_type const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); vehicle_footprint_ = vehicle_info.createFootprint(); - goal_searcher_ = - std::make_shared(*parameters, vehicle_footprint_, occupancy_grid_map_); + goal_searcher_ = std::make_shared(*parameters, vehicle_footprint_); // timer callback for generating lane parking candidate paths const auto lane_parking_period_ns = rclcpp::Rate(1.0).period(); @@ -123,51 +122,44 @@ GoalPlannerModule::GoalPlannerModule( // Initialize safety checker if (parameters_->safety_check_params.enable_safety_check) { initializeSafetyCheckParameters(); - utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); } - - prev_data_.reset(); -} - -// This function is needed for waiting for planner_data_ -void GoalPlannerModule::updateOccupancyGrid() -{ - if (!planner_data_->occupancy_grid) { - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "occupancy_grid is not ready"); - return; - } - occupancy_grid_map_->setMap(*(planner_data_->occupancy_grid)); } -bool GoalPlannerModule::hasPreviousModulePathShapeChanged() const +bool GoalPlannerModule::hasPreviousModulePathShapeChanged( + const BehaviorModuleOutput & previous_module_output) const { - if (!last_previous_module_output_) { + const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); + if (!last_previous_module_output) { return true; } - const auto current_path = getPreviousModuleOutput().path; + const auto current_path = previous_module_output.path; // the terminal distance is far return calcDistance2d( - last_previous_module_output_->path.points.back().point, + last_previous_module_output->path.points.back().point, current_path.points.back().point) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath() const +bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath( + const std::shared_ptr planner_data) const { - if (!last_previous_module_output_) { + const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); + if (!last_previous_module_output) { return true; } return std::abs(motion_utils::calcLateralOffset( - last_previous_module_output_->path.points, - planner_data_->self_odometry->pose.pose.position)) > 0.3; + last_previous_module_output->path.points, + planner_data->self_odometry->pose.pose.position)) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath() const +bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output) const { return std::abs(motion_utils::calcLateralOffset( - getPreviousModuleOutput().path.points, - planner_data_->self_odometry->pose.pose.position)) > 0.3; + previous_module_output.path.points, planner_data->self_odometry->pose.pose.position)) > + 0.3; } // generate pull over candidate paths @@ -175,7 +167,50 @@ void GoalPlannerModule::onTimer() { const ScopedFlag flag(is_lane_parking_cb_running_); - if (getCurrentStatus() == ModuleStatus::IDLE) { + std::shared_ptr local_planner_data{nullptr}; + std::optional current_status_opt{std::nullopt}; + std::optional previous_module_output_opt{std::nullopt}; + std::shared_ptr occupancy_grid_map{nullptr}; + std::optional parameters_opt{std::nullopt}; + std::shared_ptr ego_predicted_path_params{nullptr}; + std::shared_ptr objects_filtering_params{nullptr}; + std::shared_ptr safety_check_params{nullptr}; + std::shared_ptr goal_searcher{nullptr}; + + // begin of critical section + { + std::lock_guard guard(gp_planner_data_mutex_); + if (gp_planner_data_) { + const auto & gp_planner_data = gp_planner_data_.value(); + local_planner_data = std::make_shared(gp_planner_data.planner_data); + current_status_opt = gp_planner_data.current_status; + previous_module_output_opt = gp_planner_data.previous_module_output; + occupancy_grid_map = gp_planner_data.occupancy_grid_map; + parameters_opt = gp_planner_data.parameters; + ego_predicted_path_params = gp_planner_data.ego_predicted_path_params; + objects_filtering_params = gp_planner_data.objects_filtering_params; + safety_check_params = gp_planner_data.safety_check_params; + goal_searcher = gp_planner_data.goal_searcher; + } + } + // end of critical section + if ( + !local_planner_data || !current_status_opt || !previous_module_output_opt || + !occupancy_grid_map || !parameters_opt || !ego_predicted_path_params || + !objects_filtering_params || !safety_check_params || !goal_searcher) { + RCLCPP_ERROR( + getLogger(), + "failed to get valid " + "local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt/" + "ego_predicted_path_params/objects_filtering_params/safety_check_params/goal_searcher in " + "onTimer"); + return; + } + const auto & current_status = current_status_opt.value(); + const auto & previous_module_output = previous_module_output_opt.value(); + const auto & parameters = parameters_opt.value(); + + if (current_status == ModuleStatus::IDLE) { return; } @@ -184,27 +219,31 @@ void GoalPlannerModule::onTimer() return; } - if (!planner_data_ || !utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(local_planner_data->route_handler)) { return; } // check if new pull over path candidates are needed to be generated const bool need_update = std::invoke([&]() { - if (isOnModifiedGoal()) { + if (isOnModifiedGoal(local_planner_data->self_odometry->pose.pose, parameters)) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath()) { + if (hasDeviatedFromCurrentPreviousModulePath(local_planner_data, previous_module_output)) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return true; } - if (hasPreviousModulePathShapeChanged()) { + if (hasPreviousModulePathShapeChanged(previous_module_output)) { RCLCPP_DEBUG(getLogger(), "has previous module path shape changed"); return true; } - if (hasDeviatedFromLastPreviousModulePath() && !hasDecidedPath()) { + if ( + hasDeviatedFromLastPreviousModulePath(local_planner_data) && + !hasDecidedPath( + local_planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params, goal_searcher)) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; } @@ -214,13 +253,12 @@ void GoalPlannerModule::onTimer() return; } - const auto previous_module_output = getPreviousModuleOutput(); const auto goal_candidates = thread_safe_data_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, + local_planner_data, parameters.backward_goal_search_length, + parameters.forward_goal_search_length, /*forward_only_in_route*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; @@ -228,7 +266,7 @@ void GoalPlannerModule::onTimer() const auto planCandidatePaths = [&]( const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { - planner->setPlannerData(planner_data_); + planner->setPlannerData(local_planner_data); planner->setPreviousModuleOutput(previous_module_output); auto pull_over_path = planner->plan(goal_candidate.goal_pose); if (pull_over_path) { @@ -254,7 +292,7 @@ void GoalPlannerModule::onTimer() is_center_line_input_path); // plan candidate paths and set them to the member variable - if (parameters_->path_priority == "efficient_path") { + if (parameters.path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line if (!is_center_line_input_path && planner->getPlannerType() != PullOverPlannerType::SHIFT) { @@ -264,7 +302,7 @@ void GoalPlannerModule::onTimer() planCandidatePaths(planner, goal_candidate); } } - } else if (parameters_->path_priority == "close_goal") { + } else if (parameters.path_priority == "close_goal") { for (const auto & goal_candidate : goal_candidates) { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line @@ -277,49 +315,76 @@ void GoalPlannerModule::onTimer() } else { RCLCPP_ERROR( getLogger(), "path_priority should be efficient_path or close_goal, but %s is given.", - parameters_->path_priority.c_str()); + parameters.path_priority.c_str()); throw std::domain_error("[pull_over] invalid path_priority"); } // set member variables - { - const std::lock_guard lock(mutex_); - thread_safe_data_.set_pull_over_path_candidates(path_candidates); - thread_safe_data_.set_closest_start_pose(closest_start_pose); - RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); - } + thread_safe_data_.set_pull_over_path_candidates(path_candidates); + thread_safe_data_.set_closest_start_pose(closest_start_pose); + RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); - last_previous_module_output_ = previous_module_output; + thread_safe_data_.set_last_previous_module_output(previous_module_output); } void GoalPlannerModule::onFreespaceParkingTimer() { const ScopedFlag flag(is_freespace_parking_cb_running_); - if (getCurrentStatus() == ModuleStatus::IDLE) { + std::shared_ptr local_planner_data{nullptr}; + std::optional current_status_opt{std::nullopt}; + std::shared_ptr occupancy_grid_map{nullptr}; + std::optional parameters_opt{std::nullopt}; + std::shared_ptr goal_searcher{nullptr}; + + // begin of critical section + { + std::lock_guard guard(gp_planner_data_mutex_); + if (gp_planner_data_) { + const auto & gp_planner_data = gp_planner_data_.value(); + local_planner_data = std::make_shared(gp_planner_data.planner_data); + current_status_opt = gp_planner_data.current_status; + occupancy_grid_map = gp_planner_data.occupancy_grid_map; + parameters_opt = gp_planner_data.parameters; + goal_searcher = gp_planner_data.goal_searcher; + } + } + // end of critical section + if (!local_planner_data || !current_status_opt || !parameters_opt || !goal_searcher) { + RCLCPP_ERROR( + getLogger(), + "failed to get valid planner_data/current_status/parameters/goal_searcher in " + "onFreespaceParkingTimer"); return; } - if (!planner_data_) { + const auto & current_status = current_status_opt.value(); + const auto & parameters = parameters_opt.value(); + + if (current_status == ModuleStatus::IDLE) { return; } - if (!planner_data_->costmap) { + + if (!local_planner_data->costmap) { return; } // fixed goal planner do not use freespace planner - if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(local_planner_data->route_handler)) { return; } - if (isOnModifiedGoal()) { + if (isOnModifiedGoal(local_planner_data->self_odometry->pose.pose, parameters)) { return; } const bool is_new_costmap = - (clock_->now() - planner_data_->costmap->header.stamp).seconds() < 1.0; + (clock_->now() - local_planner_data->costmap->header.stamp).seconds() < 1.0; constexpr double path_update_duration = 1.0; - if (isStuck() && is_new_costmap && needPathUpdate(path_update_duration)) { - planFreespacePath(); + if ( + isStuck(local_planner_data, occupancy_grid_map, parameters) && is_new_costmap && + needPathUpdate( + local_planner_data->self_odometry->pose.pose, path_update_duration, parameters)) { + planFreespacePath(local_planner_data, goal_searcher, occupancy_grid_map); } } @@ -349,28 +414,64 @@ void GoalPlannerModule::updateObjectsFilteringParams( void GoalPlannerModule::updateData() { + // In PlannerManager::run(), it calls SceneModuleInterface::setData and + // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). + // Then module_ptr->run() invokes GoalPlannerModule::updateData and then + // planWaitingApproval()/plan(), so we can copy latest current_status/previous_module_output to + // gp_planner_data_ here + + // NOTE: onTimer/onFreespaceParkingTimer copies gp_planner_data_ to their local clone, so we need + // to lock gp_planner_data_ here to avoid data race. But the following clone process is + // lightweight because most of the member variables of PlannerData/RouteHandler is + // shared_ptrs/bool + // begin of critical section + { + std::lock_guard guard(gp_planner_data_mutex_); + if (!gp_planner_data_) { + gp_planner_data_ = GoalPlannerData(*planner_data_, *parameters_); + } + auto & gp_planner_data = gp_planner_data_.value(); + // NOTE: for the above reasons, PlannerManager/behavior_path_planner_node ensure that + // planner_data_ is not nullptr, so it is OK to copy as value + // By copying PlannerData as value, the internal shared member variables are also copied + // (reference count is incremented), so `gp_planner_data_.foo` is now thread-safe from the + // **re-pointing** by `planner_data_->foo = msg` in behavior_path_planner::onCallbackFor(msg) + // and if these two coincided, only the reference count is affected + gp_planner_data.update( + *parameters_, ego_predicted_path_params_, objects_filtering_params_, safety_check_params_, + *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), goal_searcher_, + vehicle_footprint_); + // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as + // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since + // behavior_path_planner::run() updates + // planner_data_->route_handler->lanelet_map_ptr_/routing_graph_ptr_ especially, we also have + // to copy route_handler as value to use lanelet_map_ptr_/routing_graph_ptr_ thread-safely in + // onTimer/onFreespaceParkingTimer + // TODO(Mamoru Sobue): If the copy of RouteHandler.road_lanelets/shoulder_lanelets is not + // lightweight, we should update gp_planner_data_.route_handler only when + // `planner_data_.is_route_handler_updated` variable is set true by behavior_path_planner + // (although this flag is not implemented yet). In that case, gp_planner_data members except + // for route_handler should be copied from planner_data_ + + // GoalPlannerModule::occupancy_grid_map_ and gp_planner_data.occupancy_grid_map share the + // ownership, and gp_planner_data.occupancy_grid_map maybe also shared by the local + // planner_data on onFreespaceParkingTimer thread local memory space. So following operation + // is thread-safe because gp_planner_data.occupancy_grid_map is only re-pointed here and its + // prior resource is still owned by the onFreespaceParkingTimer thread locally. + occupancy_grid_map_ = gp_planner_data.occupancy_grid_map; + } + // end of critical section + if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { return; } - // Initialize Occupancy Grid Map - // This operation requires waiting for `planner_data_`, hence it is executed here instead of in - // the constructor. Ideally, this operation should only need to be performed once. - if ( - parameters_->use_occupancy_grid_for_goal_search || - parameters_->use_occupancy_grid_for_path_collision_check) { - initializeOccupancyGridMap(); - } - resetPathCandidate(); resetPathReference(); path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); - updateOccupancyGrid(); - // update goal searcher and generate goal candidates if (thread_safe_data_.get_goal_candidates().empty()) { - goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal( calcRefinedGoal(planner_data_->route_handler->getOriginalGoalPose())); thread_safe_data_.set_goal_candidates(generateGoalCandidates()); @@ -391,21 +492,6 @@ void GoalPlannerModule::updateData() } } -void GoalPlannerModule::initializeOccupancyGridMap() -{ - OccupancyGridMapParam occupancy_grid_map_param{}; - const double margin = parameters_->occupancy_grid_collision_check_margin; - occupancy_grid_map_param.vehicle_shape.length = - planner_data_->parameters.vehicle_length + 2 * margin; - occupancy_grid_map_param.vehicle_shape.width = - planner_data_->parameters.vehicle_width + 2 * margin; - occupancy_grid_map_param.vehicle_shape.base2back = - planner_data_->parameters.base_link2rear + margin; - occupancy_grid_map_param.theta_size = parameters_->theta_size; - occupancy_grid_map_param.obstacle_threshold = parameters_->obstacle_threshold; - occupancy_grid_map_->setParam(occupancy_grid_map_param); -} - void GoalPlannerModule::initializeSafetyCheckParameters() { updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); @@ -418,7 +504,7 @@ void GoalPlannerModule::processOnExit() resetPathCandidate(); resetPathReference(); debug_marker_.markers.clear(); - prev_data_.reset(); + thread_safe_data_.reset(); last_approval_data_.reset(); } @@ -501,7 +587,10 @@ bool GoalPlannerModule::isExecutionRequested() const bool GoalPlannerModule::isExecutionReady() const { if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) { - if (!isSafePath().first) { + if (!isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_) + .first) { RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects"); return false; } @@ -584,18 +673,17 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } -bool GoalPlannerModule::planFreespacePath() +bool GoalPlannerModule::planFreespacePath( + std::shared_ptr planner_data, + const std::shared_ptr goal_searcher, + const std::shared_ptr occupancy_grid_map) { GoalCandidates goal_candidates{}; - { - const std::lock_guard lock(mutex_); - goal_searcher_->setPlannerData(planner_data_); - goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); - thread_safe_data_.set_goal_candidates(goal_candidates); - debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); - debug_data_.freespace_planner.is_planning = true; - } + goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data); + thread_safe_data_.set_goal_candidates(goal_candidates); + debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); + debug_data_.freespace_planner.is_planning = true; for (size_t i = 0; i < goal_candidates.size(); i++) { const auto goal_candidate = goal_candidates.at(i); @@ -607,7 +695,7 @@ bool GoalPlannerModule::planFreespacePath() if (!goal_candidate.is_safe) { continue; } - freespace_planner_->setPlannerData(planner_data_); + freespace_planner_->setPlannerData(planner_data); auto freespace_path = freespace_planner_->plan(goal_candidate.goal_pose); freespace_path->goal_id = goal_candidate.id; if (!freespace_path) { @@ -645,13 +733,15 @@ bool GoalPlannerModule::canReturnToLaneParking() if ( parameters_->use_object_recognition && checkObjectsCollision( - path, parameters_->object_recognition_collision_check_hard_margins.back(), + path, planner_data_, *parameters_, + parameters_->object_recognition_collision_check_hard_margins.back(), /*extract_static_objects=*/false)) { return false; } if ( - parameters_->use_occupancy_grid_for_path_collision_check && checkOccupancyGridCollision(path)) { + parameters_->use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision(path, occupancy_grid_map_)) { return false; } @@ -671,7 +761,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const // calculate goal candidates const auto & route_handler = planner_data_->route_handler; if (utils::isAllowedGoalModification(route_handler)) { - return goal_searcher_->search(); + return goal_searcher_->search(occupancy_grid_map_, planner_data_); } // NOTE: @@ -778,7 +868,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); for (const auto & margin : margins) { if (!checkObjectsCollision( - resampled_path, margin, + resampled_path, planner_data_, *parameters_, margin, /*extract_static_objects=*/true)) { return margin; } @@ -865,16 +955,17 @@ std::optional> GoalPlannerModule::selectP const auto resampled_path = utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); if ( - parameters_->use_object_recognition && checkObjectsCollision( - resampled_path, collision_check_margin, - /*extract_static_objects=*/true, - /*update_debug_data=*/true)) { + parameters_->use_object_recognition && + checkObjectsCollision( + resampled_path, planner_data_, *parameters_, collision_check_margin, + /*extract_static_objects=*/true, + /*update_debug_data=*/true)) { continue; } if ( parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(resampled_path)) { + checkOccupancyGridCollision(resampled_path, occupancy_grid_map_)) { continue; } @@ -910,7 +1001,12 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) } if ( - parameters_->safety_check_params.enable_safety_check && !isSafePath().first && isActivated()) { + parameters_->safety_check_params.enable_safety_check && + !isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_) + .first && + isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -933,7 +1029,11 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) setDrivableAreaInfo(output); // set hazard and turn signal - if (hasDecidedPath() && isActivated()) { + if ( + hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_) && + isActivated()) { setTurnSignalInfo(output); } } @@ -997,20 +1097,47 @@ void GoalPlannerModule::updateSteeringFactor( pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); } -bool GoalPlannerModule::hasDecidedPath() const -{ - return checkDecidingPathStatus().first == DecidingPathStatus::DECIDED; -} - -bool GoalPlannerModule::hasNotDecidedPath() const -{ - return checkDecidingPathStatus().first == DecidingPathStatus::NOT_DECIDED; -} - -DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const -{ - const auto & prev_status = prev_data_.deciding_path_status; - const bool enable_safety_check = parameters_->safety_check_params.enable_safety_check; +bool GoalPlannerModule::hasDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const +{ + return checkDecidingPathStatus( + planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params, goal_searcher) + .first == DecidingPathStatus::DECIDED; +} + +bool GoalPlannerModule::hasNotDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const +{ + return checkDecidingPathStatus( + planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params, goal_searcher) + .first == DecidingPathStatus::NOT_DECIDED; +} + +DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const +{ + const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; + const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; // Once this function returns true, it will continue to return true thereafter if (prev_status.first == DecidingPathStatus::DECIDED) { @@ -1024,7 +1151,13 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const // If it is dangerous against dynamic objects before approval, do not determine the path. // This eliminates a unsafe path to be approved - if (enable_safety_check && !isSafePath().first && !isActivated()) { + if ( + enable_safety_check && + !isSafePath( + planner_data, parameters, ego_predicted_path_params, objects_filtering_params, + safety_check_params) + .first && + !isActivated()) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before " @@ -1040,11 +1173,11 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const const double hysteresis_factor = 0.9; // check goal pose collision - goal_searcher_->setPlannerData(planner_data_); const auto modified_goal_opt = thread_safe_data_.get_modified_goal_pose(); if ( - modified_goal_opt && !goal_searcher_->isSafeGoalWithMarginScaleFactor( - modified_goal_opt.value(), hysteresis_factor)) { + modified_goal_opt && + !goal_searcher->isSafeGoalWithMarginScaleFactor( + modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, planner_data)) { RCLCPP_DEBUG(getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } @@ -1052,15 +1185,20 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const // check current parking path collision const auto parking_path = utils::resamplePathWithSpline(pull_over_path->getParkingPath(), 0.5); const double margin = - parameters_->object_recognition_collision_check_hard_margins.back() * hysteresis_factor; - if (checkObjectsCollision(parking_path, margin, /*extract_static_objects=*/false)) { + parameters.object_recognition_collision_check_hard_margins.back() * hysteresis_factor; + if (checkObjectsCollision( + parking_path, planner_data, parameters, margin, /*extract_static_objects=*/false)) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } - if (enable_safety_check && !isSafePath().first) { + if ( + enable_safety_check && !isSafePath( + planner_data, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params) + .first) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects"); @@ -1084,7 +1222,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const } // if ego is sufficiently close to the start of the nearest candidate path, the path is decided - const auto & current_pose = planner_data_->self_odometry->pose.pose; + const auto & current_pose = planner_data->self_odometry->pose.pose; const size_t ego_segment_idx = motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); @@ -1093,13 +1231,13 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const const double dist_to_parking_start_pose = calcSignedArcLength( current_path.points, current_pose.position, ego_segment_idx, pull_over_path->start_pose.position, start_pose_segment_idx); - if (dist_to_parking_start_pose > parameters_->decide_path_distance) { + if (dist_to_parking_start_pose > parameters.decide_path_distance) { return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } // if object recognition for path collision check is enabled, transition to DECIDING to check // collision for a certain period of time. Otherwise, transition to DECIDED directly. - if (parameters_->use_object_recognition) { + if (parameters.use_object_recognition) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain " @@ -1124,7 +1262,9 @@ void GoalPlannerModule::decideVelocity() BehaviorModuleOutput GoalPlannerModule::planPullOver() { - if (!hasDecidedPath()) { + if (!hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_)) { return planPullOverAsCandidate(); } @@ -1168,7 +1308,12 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() return getPreviousModuleOutput(); } - if (hasNotDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { + if ( + hasNotDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_) && + needPathUpdate( + planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, *parameters_)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_ @@ -1177,9 +1322,8 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() thread_safe_data_.clearPullOverPath(); // update goal candidates - goal_searcher_->setPlannerData(planner_data_); auto goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); + goal_searcher_->update(goal_candidates, occupancy_grid_map_, planner_data_); // update pull over path candidates const auto pull_over_path_candidates = sortPullOverPathCandidatesByGoalPriority( @@ -1240,9 +1384,14 @@ void GoalPlannerModule::postProcess() return; } - const bool has_decided_path = hasDecidedPath(); const auto distance_to_path_change = calcDistanceToPathChange(); + // TODO(Mamoru Sobue): repetitive call to checkDecidingPathStatus() in the main thread is a + // waste of time because it gives same result throughout the main thread. + const bool has_decided_path = hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_); + if (has_decided_path) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } @@ -1260,27 +1409,35 @@ void GoalPlannerModule::updatePreviousData() { // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. - prev_data_.found_path = thread_safe_data_.foundPullOverPath(); + // TODO(Mamoru Sobue): put prev_data_ out of ThreadSafeData + auto prev_data = thread_safe_data_.get_prev_data(); + prev_data.found_path = thread_safe_data_.foundPullOverPath(); - prev_data_.deciding_path_status = checkDecidingPathStatus(); + prev_data.deciding_path_status = checkDecidingPathStatus( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_); // This is related to safety check, so if it is disabled, return here. if (!parameters_->safety_check_params.enable_safety_check) { - prev_data_.safety_status.is_safe = true; - return; - } - - // Even if the current path is safe, it will not be safe unless it stands for a certain period of - // time. Record the time when the current path has become safe - const auto [is_safe, current_is_safe] = isSafePath(); - if (current_is_safe) { - if (!prev_data_.safety_status.safe_start_time) { - prev_data_.safety_status.safe_start_time = clock_->now(); - } + prev_data.safety_status.is_safe = true; } else { - prev_data_.safety_status.safe_start_time = std::nullopt; + // Even if the current path is safe, it will not be safe unless it stands for a certain period + // of time. Record the time when the current path has become safe + const auto [is_safe, current_is_safe] = isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_); + if (current_is_safe) { + if (!prev_data.safety_status.safe_start_time) { + prev_data.safety_status.safe_start_time = clock_->now(); + } + } else { + prev_data.safety_status.safe_start_time = std::nullopt; + } + prev_data.safety_status.is_safe = is_safe; } - prev_data_.safety_status.is_safe = is_safe; + + // commit the change + thread_safe_data_.set_prev_data(prev_data); } BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() @@ -1357,8 +1514,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible // stop point is found, stop at this position. - const auto closest_goal_candidate = - goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); + const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( + thread_safe_data_.get_goal_candidates(), planner_data_); const auto decel_pose = calcLongitudinalOffsetPose( extended_prev_path.points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -1486,10 +1643,13 @@ bool GoalPlannerModule::isStopped() return isStopped(odometry_buffer_stopped_, parameters_->th_stopped_time); } -bool GoalPlannerModule::isStuck() +bool GoalPlannerModule::isStuck( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters) { const std::lock_guard lock(mutex_); - if (isOnModifiedGoal()) { + if (isOnModifiedGoal(planner_data->self_odometry->pose.pose, parameters)) { return false; } @@ -1509,17 +1669,18 @@ bool GoalPlannerModule::isStuck() } if ( - parameters_->use_object_recognition && + parameters.use_object_recognition && checkObjectsCollision( - thread_safe_data_.get_pull_over_path()->getCurrentPath(), + thread_safe_data_.get_pull_over_path()->getCurrentPath(), planner_data, parameters, /*extract_static_objects=*/false, - parameters_->object_recognition_collision_check_hard_margins.back())) { + parameters.object_recognition_collision_check_hard_margins.back())) { return true; } if ( - parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath())) { + parameters.use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision( + thread_safe_data_.get_pull_over_path()->getCurrentPath(), occupancy_grid_map)) { return true; } @@ -1565,15 +1726,15 @@ bool GoalPlannerModule::hasFinishedCurrentPath() parameters_->th_arrived_distance; } -bool GoalPlannerModule::isOnModifiedGoal() const +bool GoalPlannerModule::isOnModifiedGoal( + const Pose & current_pose, const GoalPlannerParameters & parameters) const { if (!thread_safe_data_.get_modified_goal_pose()) { return false; } - const Pose current_pose = planner_data_->self_odometry->pose.pose; return calcDistance2d(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose) < - parameters_->th_arrived_distance; + parameters.th_arrived_distance; } TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() @@ -1642,31 +1803,34 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() return new_signal; } -bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const +bool GoalPlannerModule::checkOccupancyGridCollision( + const PathWithLaneId & path, + const std::shared_ptr occupancy_grid_map) const { - if (!occupancy_grid_map_) { + if (!occupancy_grid_map) { return false; } const bool check_out_of_range = false; - return occupancy_grid_map_->hasObstacleOnPath(path, check_out_of_range); + return occupancy_grid_map->hasObstacleOnPath(path, check_out_of_range); } bool GoalPlannerModule::checkObjectsCollision( - const PathWithLaneId & path, const double collision_check_margin, + const PathWithLaneId & path, const std::shared_ptr planner_data, + const GoalPlannerParameters & parameters, const double collision_check_margin, const bool extract_static_objects, const bool update_debug_data) const { const auto target_objects = std::invoke([&]() { - const auto & p = parameters_; - const auto & rh = *(planner_data_->route_handler); - const auto objects = *(planner_data_->dynamic_object); + const auto & p = parameters; + const auto & rh = *(planner_data->route_handler); + const auto objects = *(planner_data->dynamic_object); if (extract_static_objects) { return goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects, p->th_moving_object_velocity); + rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, + p.detection_bound_offset, objects, p.th_moving_object_velocity); } return goal_planner_utils::extractObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects); + rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, + p.detection_bound_offset, objects); }); std::vector obj_polygons; @@ -1685,8 +1849,8 @@ bool GoalPlannerModule::checkObjectsCollision( const auto p = path.points.at(i); const double extra_stopping_margin = std::min( - std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters_->maximum_deceleration, - parameters_->object_recognition_collision_check_max_extra_stopping_margin); + std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters.maximum_deceleration, + parameters.object_recognition_collision_check_max_extra_stopping_margin); // The square is meant to imply centrifugal force, but it is not a very well-founded formula. // TODO(kosuke55): It is needed to consider better way because there is an inherently different @@ -1697,9 +1861,9 @@ bool GoalPlannerModule::checkObjectsCollision( const auto ego_polygon = tier4_autoware_utils::toFootprint( p.point.pose, - planner_data_->parameters.base_link2front + collision_check_margin + extra_stopping_margin, - planner_data_->parameters.base_link2rear + collision_check_margin, - planner_data_->parameters.vehicle_width + collision_check_margin * 2.0 + + planner_data->parameters.base_link2front + collision_check_margin + extra_stopping_margin, + planner_data->parameters.base_link2rear + collision_check_margin, + planner_data->parameters.vehicle_width + collision_check_margin * 2.0 + extra_lateral_margin * 2.0); ego_polygons_expanded.push_back(ego_polygon); } @@ -1782,8 +1946,8 @@ double GoalPlannerModule::calcSignedArcLengthFromEgo( void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const { // decelerate before the search area start - const auto closest_goal_candidate = - goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); + const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( + thread_safe_data_.get_goal_candidates(), planner_data_); const auto decel_pose = calcLongitudinalOffsetPose( pull_over_path.getFullPath().points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -1964,6 +2128,7 @@ bool GoalPlannerModule::isCrossingPossible(const PullOverPath & pull_over_path) return isCrossingPossible(start_pose, end_pose, lanes); } +/* void GoalPlannerModule::updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const @@ -1972,6 +2137,7 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData( goal_planner_data_.target_objects_on_lane = target_objects_on_lane; goal_planner_data_.ego_predicted_path = ego_predicted_path; } +*/ static std::vector filterObjectsByWithinPolicy( const std::shared_ptr & objects, @@ -2017,26 +2183,29 @@ static std::vector filterOb return refined_filtered_objects; } -std::pair GoalPlannerModule::isSafePath() const +std::pair GoalPlannerModule::isSafePath( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params) const { if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); - const auto & current_pose = planner_data_->self_odometry->pose.pose; + const auto & current_pose = planner_data->self_odometry->pose.pose; const double current_velocity = std::hypot( - planner_data_->self_odometry->twist.twist.linear.x, - planner_data_->self_odometry->twist.twist.linear.y); - const auto & dynamic_object = planner_data_->dynamic_object; - const auto & route_handler = planner_data_->route_handler; + planner_data->self_odometry->twist.twist.linear.x, + planner_data->self_odometry->twist.twist.linear.y); + const auto & dynamic_object = planner_data->dynamic_object; + const auto & route_handler = planner_data->route_handler; const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, + planner_data, parameters.backward_goal_search_length, parameters.forward_goal_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( - *route_handler, left_side_parking_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length); - const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); + *route_handler, left_side_parking_, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + const size_t ego_seg_idx = planner_data->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = utils::parking_departure::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, @@ -2044,15 +2213,15 @@ std::pair GoalPlannerModule::isSafePath() const RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - utils::parking_departure::updatePathProperty( - ego_predicted_path_params_, terminal_velocity_and_accel); + auto temp_param = std::make_shared(*ego_predicted_path_params); + utils::parking_departure::updatePathProperty(temp_param, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; const bool limit_to_max_velocity = true; const auto ego_predicted_path = behavior_path_planner::utils::path_safety_checker::createPredictedPath( - ego_predicted_path_params_, pull_over_path.points, current_pose, current_velocity, - ego_seg_idx, is_object_front, limit_to_max_velocity); + ego_predicted_path_params, pull_over_path.points, current_pose, current_velocity, ego_seg_idx, + is_object_front, limit_to_max_velocity); // ========================================================================================== // if ego is before the entry of pull_over_lanes, the beginning of the safety check area @@ -2094,36 +2263,38 @@ std::pair GoalPlannerModule::isSafePath() const const auto expanded_pull_over_lanes_between_ego = goal_planner_utils::generateBetweenEgoAndExpandedPullOverLanes( pull_over_lanes, left_side_parking_, ego_pose_for_expand, - planner_data_->parameters.vehicle_info, parameters_->outer_road_detection_offset, - parameters_->inner_road_detection_offset); + planner_data->parameters.vehicle_info, parameters.outer_road_detection_offset, + parameters.inner_road_detection_offset); const auto merged_expanded_pull_over_lanes = lanelet::utils::combineLaneletsShape(expanded_pull_over_lanes_between_ego); debug_data_.expanded_pull_over_lane_between_ego = merged_expanded_pull_over_lanes; const auto filtered_objects = filterObjectsByWithinPolicy( - dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params_); + dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params); + const auto prev_data = thread_safe_data_.get_prev_data(); const double hysteresis_factor = - prev_data_.safety_status.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; + prev_data.safety_status.is_safe ? 1.0 : parameters.hysteresis_factor_expand_rate; + CollisionCheckDebugMap collision_check{}; const bool current_is_safe = std::invoke([&]() { - if (parameters_->safety_check_params.method == "RSS") { + if (parameters.safety_check_params.method == "RSS") { return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( - pull_over_path, ego_predicted_path, filtered_objects, goal_planner_data_.collision_check, - planner_data_->parameters, safety_check_params_->rss_params, - objects_filtering_params_->use_all_predicted_path, hysteresis_factor); - } else if (parameters_->safety_check_params.method == "integral_predicted_polygon") { + pull_over_path, ego_predicted_path, filtered_objects, collision_check, + planner_data->parameters, safety_check_params->rss_params, + objects_filtering_params->use_all_predicted_path, hysteresis_factor); + } else if (parameters.safety_check_params.method == "integral_predicted_polygon") { return utils::path_safety_checker::checkSafetyWithIntegralPredictedPolygon( ego_predicted_path, vehicle_info_, filtered_objects, - objects_filtering_params_->check_all_predicted_path, - parameters_->safety_check_params.integral_predicted_polygon_params, - goal_planner_data_.collision_check); + objects_filtering_params->check_all_predicted_path, + parameters.safety_check_params.integral_predicted_polygon_params, collision_check); } RCLCPP_ERROR( getLogger(), " [pull_over] invalid safety check method: %s", - parameters_->safety_check_params.method.c_str()); + parameters.safety_check_params.method.c_str()); throw std::domain_error("[pull_over] invalid safety check method"); }); + thread_safe_data_.set_collision_check(collision_check); /* * ==== is_safe @@ -2140,9 +2311,9 @@ std::pair GoalPlannerModule::isSafePath() const */ if (current_is_safe) { if ( - prev_data_.safety_status.safe_start_time && - (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds() > - parameters_->safety_check_params.keep_unsafe_time) { + prev_data.safety_status.safe_start_time && + (clock_->now() - prev_data.safety_status.safe_start_time.value()).seconds() > + parameters.safety_check_params.keep_unsafe_time) { return {true /*is_safe*/, true /*current_is_safe*/}; } } @@ -2176,8 +2347,12 @@ void GoalPlannerModule::setDebugData() }; if (utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas - const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow - : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green + const auto color = + hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_) + ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow + : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green const double z = planner_data_->route_handler->getGoalPose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); @@ -2190,9 +2365,11 @@ void GoalPlannerModule::setDebugData() // Visualize previous module output add(createPathMarkerArray( getPreviousModuleOutput().path, "previous_module_path", 0, 1.0, 0.0, 0.0)); - if (last_previous_module_output_.has_value()) { + + const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); + if (last_previous_module_output.has_value()) { add(createPathMarkerArray( - last_previous_module_output_.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); + last_previous_module_output.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); } // Visualize path and related pose @@ -2249,6 +2426,7 @@ void GoalPlannerModule::setDebugData() } } + auto collision_check = thread_safe_data_.get_collision_check(); // safety check if (parameters_->safety_check_params.enable_safety_check) { if (goal_planner_data_.ego_predicted_path.size() > 0) { @@ -2263,33 +2441,35 @@ void GoalPlannerModule::setDebugData() } if (parameters_->safety_check_params.method == "RSS") { - add(showSafetyCheckInfo(goal_planner_data_.collision_check, "object_debug_info")); + add(showSafetyCheckInfo(collision_check, "object_debug_info")); } - add(showPredictedPath(goal_planner_data_.collision_check, "ego_predicted_path")); - add(showPolygon(goal_planner_data_.collision_check, "ego_and_target_polygon_relation")); + add(showPredictedPath(collision_check, "ego_predicted_path")); + add(showPolygon(collision_check, "ego_and_target_polygon_relation")); // set objects of interest - for (const auto & [uuid, data] : goal_planner_data_.collision_check) { + for (const auto & [uuid, data] : collision_check) { const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); } - utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); + // TODO(Mamoru Sobue): it is not clear where ThreadSafeData::collision_check should be cleared + utils::parking_departure::initializeCollisionCheckDebugMap(collision_check); // visualize safety status maker { + const auto prev_data = thread_safe_data_.get_prev_data(); visualization_msgs::msg::MarkerArray marker_array{}; - const auto color = prev_data_.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) - : createMarkerColor(1.0, 0.0, 0.0, 0.99); + const auto color = prev_data.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "safety_status", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); marker.pose = planner_data_->self_odometry->pose.pose; - marker.text += "is_safe: " + std::to_string(prev_data_.safety_status.is_safe) + "\n"; - if (prev_data_.safety_status.safe_start_time) { + marker.text += "is_safe: " + std::to_string(prev_data.safety_status.is_safe) + "\n"; + if (prev_data.safety_status.safe_start_time) { const double elapsed_time_from_safe_start = - (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds(); + (clock_->now() - prev_data.safety_status.safe_start_time.value()).seconds(); marker.text += "elapsed_time_from_safe_start: " + std::to_string(elapsed_time_from_safe_start) + "\n"; } @@ -2317,7 +2497,7 @@ void GoalPlannerModule::setDebugData() std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); } - if (isStuck()) { + if (isStuck(planner_data_, occupancy_grid_map_, *parameters_)) { marker.text += " stuck"; } else if (isStopped()) { marker.text += " stopped"; @@ -2367,9 +2547,12 @@ void GoalPlannerModule::printParkingPositionError() const distance_from_real_shoulder); } -bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const +bool GoalPlannerModule::needPathUpdate( + const Pose & current_pose, const double path_update_duration, + const GoalPlannerParameters & parameters) const { - return !isOnModifiedGoal() && hasEnoughTimePassedSincePathUpdate(path_update_duration); + return !isOnModifiedGoal(current_pose, parameters) && + hasEnoughTimePassedSincePathUpdate(path_update_duration); } bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const @@ -2380,4 +2563,57 @@ bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration return (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > duration; } + +void GoalPlannerModule::GoalPlannerData::initializeOccupancyGridMap( + const PlannerData & planner_data, const GoalPlannerParameters & parameters) +{ + OccupancyGridMapParam occupancy_grid_map_param{}; + const double margin = parameters.occupancy_grid_collision_check_margin; + occupancy_grid_map_param.vehicle_shape.length = + planner_data.parameters.vehicle_length + 2 * margin; + occupancy_grid_map_param.vehicle_shape.width = planner_data.parameters.vehicle_width + 2 * margin; + occupancy_grid_map_param.vehicle_shape.base2back = + planner_data.parameters.base_link2rear + margin; + occupancy_grid_map_param.theta_size = parameters.theta_size; + occupancy_grid_map_param.obstacle_threshold = parameters.obstacle_threshold; + occupancy_grid_map->setParam(occupancy_grid_map_param); +} + +GoalPlannerModule::GoalPlannerData GoalPlannerModule::GoalPlannerData::clone() const +{ + GoalPlannerModule::GoalPlannerData gp_planner_data(planner_data, parameters); + gp_planner_data.update( + parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, + planner_data, current_status, previous_module_output, goal_searcher, vehicle_footprint); + return gp_planner_data; +} + +void GoalPlannerModule::GoalPlannerData::update( + const GoalPlannerParameters & parameters_, + const std::shared_ptr & ego_predicted_path_params_, + const std::shared_ptr & objects_filtering_params_, + const std::shared_ptr & safety_check_params_, + const PlannerData & planner_data_, const ModuleStatus & current_status_, + const BehaviorModuleOutput & previous_module_output_, + const std::shared_ptr goal_searcher_, + const tier4_autoware_utils::LinearRing2d & vehicle_footprint_) +{ + parameters = parameters_; + ego_predicted_path_params = ego_predicted_path_params_; + objects_filtering_params = objects_filtering_params_; + safety_check_params = safety_check_params_; + vehicle_footprint = vehicle_footprint_; + + planner_data = planner_data_; + planner_data.route_handler = std::make_shared(*(planner_data_.route_handler)); + current_status = current_status_; + previous_module_output = previous_module_output_; + occupancy_grid_map->setMap(*(planner_data.occupancy_grid)); + // to create a deepcopy of GoalPlanner(not GoalPlannerBase), goal_searcher_ is not enough, so + // recreate it here + goal_searcher = std::make_shared(parameters, vehicle_footprint); + // and then copy the reference goal + goal_searcher->setReferenceGoal(goal_searcher_->getReferenceGoal()); +} + } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index bd19871c482fc..df91687622349 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -90,35 +90,35 @@ struct SortByWeightedDistance }; GoalSearcher::GoalSearcher( - const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint, - const std::shared_ptr & occupancy_grid_map) + const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint) : GoalSearcherBase{parameters}, vehicle_footprint_{vehicle_footprint}, - occupancy_grid_map_{occupancy_grid_map}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } -GoalCandidates GoalSearcher::search() +GoalCandidates GoalSearcher::search( + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) { GoalCandidates goal_candidates{}; - const auto & route_handler = planner_data_->route_handler; + const auto & route_handler = planner_data->route_handler; const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; const double margin_from_boundary = parameters_.margin_from_boundary; const double lateral_offset_interval = parameters_.lateral_offset_interval; const double max_lateral_offset = parameters_.max_lateral_offset; const double ignore_distance_from_lane_start = parameters_.ignore_distance_from_lane_start; - const double vehicle_width = planner_data_->parameters.vehicle_width; - const double base_link2front = planner_data_->parameters.base_link2front; - const double base_link2rear = planner_data_->parameters.base_link2rear; + const double vehicle_width = planner_data->parameters.vehicle_width; + const double base_link2front = planner_data->parameters.base_link2front; + const double base_link2rear = planner_data->parameters.base_link2rear; const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); auto lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_length, forward_length, + planner_data, backward_length, forward_length, /*forward_only_in_route*/ false); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); @@ -193,17 +193,18 @@ GoalCandidates GoalSearcher::search() goal_candidates.push_back(goal_candidate); } } - createAreaPolygons(original_search_poses); + createAreaPolygons(original_search_poses, planner_data); - update(goal_candidates); + update(goal_candidates, occupancy_grid_map, planner_data); return goal_candidates; } void GoalSearcher::countObjectsToAvoid( - GoalCandidates & goal_candidates, const PredictedObjects & objects) const + GoalCandidates & goal_candidates, const PredictedObjects & objects, + const std::shared_ptr & planner_data) const { - const auto & route_handler = planner_data_->route_handler; + const auto & route_handler = planner_data->route_handler; const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; @@ -225,7 +226,7 @@ void GoalSearcher::countObjectsToAvoid( // generate current lane center line path to check collision with objects const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); const auto current_center_line_path = std::invoke([&]() -> PathWithLaneId { const double s_start = @@ -264,16 +265,19 @@ void GoalSearcher::countObjectsToAvoid( } } -void GoalSearcher::update(GoalCandidates & goal_candidates) const +void GoalSearcher::update( + GoalCandidates & goal_candidates, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const { const auto pull_over_lane_stop_objects = goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); + *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); if (parameters_.prioritize_goals_before_objects) { - countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects); + countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects, planner_data); } if (parameters_.goal_priority == "minimum_weighted_distance") { @@ -293,7 +297,7 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const const Pose goal_pose = goal_candidate.goal_pose; // check collision with footprint - if (checkCollision(goal_pose, pull_over_lane_stop_objects)) { + if (checkCollision(goal_pose, pull_over_lane_stop_objects, occupancy_grid_map)) { goal_candidate.is_safe = false; continue; } @@ -301,9 +305,10 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects, + goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, parameters_.object_recognition_collision_check_hard_margins.back(), filter_inside); - if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) { + if (checkCollisionWithLongitudinalDistance( + goal_pose, target_objects, occupancy_grid_map, planner_data)) { goal_candidate.is_safe = false; continue; } @@ -316,7 +321,9 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const // current planner_data_ and margin scale factor. // And is_safe is not updated in this function. bool GoalSearcher::isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor) const + const GoalCandidate & goal_candidate, const double margin_scale_factor, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const { if (!parameters_.use_object_recognition) { return true; @@ -326,9 +333,9 @@ bool GoalSearcher::isSafeGoalWithMarginScaleFactor( const auto pull_over_lane_stop_objects = goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); + *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); const double margin = parameters_.object_recognition_collision_check_hard_margins.back() * margin_scale_factor; @@ -341,23 +348,26 @@ bool GoalSearcher::isSafeGoalWithMarginScaleFactor( // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects, margin, + goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, margin, filter_inside); - if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) { + if (checkCollisionWithLongitudinalDistance( + goal_pose, target_objects, occupancy_grid_map, planner_data)) { return false; } return true; } -bool GoalSearcher::checkCollision(const Pose & pose, const PredictedObjects & objects) const +bool GoalSearcher::checkCollision( + const Pose & pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map) const { if (parameters_.use_occupancy_grid_for_goal_search) { - const Pose pose_grid_coords = global2local(occupancy_grid_map_->getMap(), pose); + const Pose pose_grid_coords = global2local(occupancy_grid_map->getMap(), pose); const auto idx = pose2index( - occupancy_grid_map_->getMap(), pose_grid_coords, occupancy_grid_map_->getParam().theta_size); + occupancy_grid_map->getMap(), pose_grid_coords, occupancy_grid_map->getParam().theta_size); const bool check_out_of_range = false; - if (occupancy_grid_map_->detectCollision(idx, check_out_of_range)) { + if (occupancy_grid_map->detectCollision(idx, check_out_of_range)) { return true; } } @@ -373,7 +383,9 @@ bool GoalSearcher::checkCollision(const Pose & pose, const PredictedObjects & ob } bool GoalSearcher::checkCollisionWithLongitudinalDistance( - const Pose & ego_pose, const PredictedObjects & objects) const + const Pose & ego_pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const { if ( parameters_.use_occupancy_grid_for_goal_search && @@ -385,22 +397,22 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( // check forward collision const Pose ego_pose_moved_forward = calcOffsetPose(ego_pose, offset, 0, 0); const Pose forward_pose_grid_coords = - global2local(occupancy_grid_map_->getMap(), ego_pose_moved_forward); + global2local(occupancy_grid_map->getMap(), ego_pose_moved_forward); const auto forward_idx = pose2index( - occupancy_grid_map_->getMap(), forward_pose_grid_coords, - occupancy_grid_map_->getParam().theta_size); - if (occupancy_grid_map_->detectCollision(forward_idx, check_out_of_range)) { + occupancy_grid_map->getMap(), forward_pose_grid_coords, + occupancy_grid_map->getParam().theta_size); + if (occupancy_grid_map->detectCollision(forward_idx, check_out_of_range)) { return true; } // check backward collision const Pose ego_pose_moved_backward = calcOffsetPose(ego_pose, -offset, 0, 0); const Pose backward_pose_grid_coords = - global2local(occupancy_grid_map_->getMap(), ego_pose_moved_backward); + global2local(occupancy_grid_map->getMap(), ego_pose_moved_backward); const auto backward_idx = pose2index( - occupancy_grid_map_->getMap(), backward_pose_grid_coords, - occupancy_grid_map_->getParam().theta_size); - if (occupancy_grid_map_->detectCollision(backward_idx, check_out_of_range)) { + occupancy_grid_map->getMap(), backward_pose_grid_coords, + occupancy_grid_map->getParam().theta_size); + if (occupancy_grid_map->detectCollision(backward_idx, check_out_of_range)) { return true; } } @@ -408,23 +420,24 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( if (parameters_.use_object_recognition) { if ( utils::calcLongitudinalDistanceFromEgoToObjects( - ego_pose, planner_data_->parameters.base_link2front, - planner_data_->parameters.base_link2rear, objects) < parameters_.longitudinal_margin) { + ego_pose, planner_data->parameters.base_link2front, planner_data->parameters.base_link2rear, + objects) < parameters_.longitudinal_margin) { return true; } } return false; } -void GoalSearcher::createAreaPolygons(std::vector original_search_poses) +void GoalSearcher::createAreaPolygons( + std::vector original_search_poses, const std::shared_ptr & planner_data) { using tier4_autoware_utils::MultiPolygon2d; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; - const double vehicle_width = planner_data_->parameters.vehicle_width; - const double base_link2front = planner_data_->parameters.base_link2front; - const double base_link2rear = planner_data_->parameters.base_link2rear; + const double vehicle_width = planner_data->parameters.vehicle_width; + const double base_link2front = planner_data->parameters.base_link2front; + const double base_link2rear = planner_data->parameters.base_link2rear; const double max_lateral_offset = parameters_.max_lateral_offset; const auto appendPointToPolygon = @@ -506,10 +519,11 @@ bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons } GoalCandidate GoalSearcher::getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates) const + const GoalCandidates & goal_candidates, + const std::shared_ptr & planner_data) const { const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); // Define a lambda function to compute the arc length for a given goal candidate. diff --git a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp index b168da61e6239..33d1eb78e14f6 100644 --- a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -28,11 +28,9 @@ namespace behavior_path_planner { ShiftPullOver::ShiftPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr & occupancy_grid_map) + const LaneDepartureChecker & lane_departure_checker) : PullOverPlannerBase{node, parameters}, lane_departure_checker_{lane_departure_checker}, - occupancy_grid_map_{occupancy_grid_map}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } From de21d1a504978df4f2fa380768f2cd83dfa8f4a4 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 15 Apr 2024 14:28:30 +0900 Subject: [PATCH 037/192] revert(goal_planner): fix non-thread-safe access in goal_planner (#6740) (#6809) Signed-off-by: Mamoru Sobue --- .../geometric_pull_over.hpp | 6 +- .../goal_planner_module.hpp | 190 ++--- .../goal_searcher.hpp | 36 +- .../goal_searcher_base.hpp | 25 +- .../shift_pull_over.hpp | 6 +- .../src/geometric_pull_over.cpp | 5 +- .../src/goal_planner_module.cpp | 698 ++++++------------ .../src/goal_searcher.cpp | 108 ++- .../src/shift_pull_over.cpp | 4 +- 9 files changed, 364 insertions(+), 714 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index e67d458874d17..6de1a726d4d4e 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include @@ -33,7 +34,9 @@ class GeometricPullOver : public PullOverPlannerBase public: GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, const bool is_forward); + const LaneDepartureChecker & lane_departure_checker, + const std::shared_ptr occupancy_grid_map, + const bool is_forward); PullOverPlannerType getPlannerType() const override { @@ -58,6 +61,7 @@ class GeometricPullOver : public PullOverPlannerBase protected: ParallelParkingParameters parallel_parking_parameters_; LaneDepartureChecker lane_departure_checker_{}; + std::shared_ptr occupancy_grid_map_; bool is_forward_{true}; bool left_side_parking_{true}; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 818aa7ff79edb..21ea06531c2f4 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -91,33 +91,6 @@ public: \ DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) -enum class DecidingPathStatus { - NOT_DECIDED, - DECIDING, - DECIDED, -}; -using DecidingPathStatusWithStamp = std::pair; - -struct PreviousPullOverData -{ - struct SafetyStatus - { - std::optional safe_start_time{}; - bool is_safe{false}; - }; - - void reset() - { - found_path = false; - safety_status = SafetyStatus{}; - deciding_path_status = DecidingPathStatusWithStamp{}; - } - - bool found_path{false}; - SafetyStatus safety_status{}; - DecidingPathStatusWithStamp deciding_path_status{}; -}; - class ThreadSafeData { public: @@ -172,9 +145,6 @@ class ThreadSafeData void set(const std::shared_ptr & arg) { set_pull_over_path(arg); } void set(const PullOverPath & arg) { set_pull_over_path(arg); } void set(const GoalCandidate & arg) { set_modified_goal_pose(arg); } - void set(const BehaviorModuleOutput & arg) { set_last_previous_module_output(arg); } - void set(const PreviousPullOverData & arg) { set_prev_data(arg); } - void set(const CollisionCheckDebugMap & arg) { set_collision_check(arg); } void clearPullOverPath() { @@ -212,8 +182,6 @@ class ThreadSafeData last_path_update_time_ = std::nullopt; last_path_idx_increment_time_ = std::nullopt; closest_start_pose_ = std::nullopt; - last_previous_module_output_ = std::nullopt; - prev_data_.reset(); } DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) @@ -225,9 +193,6 @@ class ThreadSafeData DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates) DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, closest_start_pose) - DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, last_previous_module_output) - DEFINE_SETTER_GETTER_WITH_MUTEX(PreviousPullOverData, prev_data) - DEFINE_SETTER_GETTER_WITH_MUTEX(CollisionCheckDebugMap, collision_check) private: std::shared_ptr pull_over_path_{nullptr}; @@ -238,9 +203,6 @@ class ThreadSafeData std::optional last_path_update_time_; std::optional last_path_idx_increment_time_; std::optional closest_start_pose_{}; - std::optional last_previous_module_output_{}; - PreviousPullOverData prev_data_{}; - CollisionCheckDebugMap collision_check_{}; std::recursive_mutex & mutex_; rclcpp::Clock::SharedPtr clock_; @@ -272,6 +234,33 @@ struct LastApprovalData Pose pose{}; }; +enum class DecidingPathStatus { + NOT_DECIDED, + DECIDING, + DECIDED, +}; +using DecidingPathStatusWithStamp = std::pair; + +struct PreviousPullOverData +{ + struct SafetyStatus + { + std::optional safe_start_time{}; + bool is_safe{false}; + }; + + void reset() + { + found_path = false; + safety_status = SafetyStatus{}; + deciding_path_status = DecidingPathStatusWithStamp{}; + } + + bool found_path{false}; + SafetyStatus safety_status{}; + DecidingPathStatusWithStamp deciding_path_status{}; +}; + // store stop_pose_ pointer with reason string struct PoseWithString { @@ -374,50 +363,6 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: - /** - * @brief shared data for onTimer(onTimer/onFreespaceParkingTimer just read this) - */ - struct GoalPlannerData - { - GoalPlannerData(const PlannerData & planner_data, const GoalPlannerParameters & parameters) - { - initializeOccupancyGridMap(planner_data, parameters); - }; - GoalPlannerParameters parameters; - std::shared_ptr ego_predicted_path_params; - std::shared_ptr objects_filtering_params; - std::shared_ptr safety_check_params; - tier4_autoware_utils::LinearRing2d vehicle_footprint; - - PlannerData planner_data; - ModuleStatus current_status; - BehaviorModuleOutput previous_module_output; - // collision detector - // need to be shared_ptr to be used in planner and goal searcher - std::shared_ptr occupancy_grid_map; - std::shared_ptr goal_searcher; - - const BehaviorModuleOutput & getPreviousModuleOutput() const { return previous_module_output; } - const ModuleStatus & getCurrentStatus() const { return current_status; } - void updateOccupancyGrid(); - GoalPlannerData clone() const; - void update( - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params_, - const std::shared_ptr & objects_filtering_params_, - const std::shared_ptr & safety_check_params_, - const PlannerData & planner_data, const ModuleStatus & current_status, - const BehaviorModuleOutput & previous_module_output, - const std::shared_ptr goal_searcher_, - const tier4_autoware_utils::LinearRing2d & vehicle_footprint); - - private: - void initializeOccupancyGridMap( - const PlannerData & planner_data, const GoalPlannerParameters & parameters); - }; - std::optional gp_planner_data_{std::nullopt}; - std::mutex gp_planner_data_mutex_; - // Flag class for managing whether a certain callback is running in multi-threading class ScopedFlag { @@ -475,10 +420,9 @@ class GoalPlannerModule : public SceneModuleInterface // goal searcher std::shared_ptr goal_searcher_; - // NOTE: this is latest occupancy_grid_map pointer which the local planner_data on - // onFreespaceParkingTimer thread storage may point to while calculation. - // onTimer/onFreespaceParkingTimer and their callees MUST NOT use this - std::shared_ptr occupancy_grid_map_{nullptr}; + // collision detector + // need to be shared_ptr to be used in planner and goal searcher + std::shared_ptr occupancy_grid_map_; // check stopped and stuck state std::deque odometry_buffer_stopped_; @@ -487,10 +431,10 @@ class GoalPlannerModule : public SceneModuleInterface tier4_autoware_utils::LinearRing2d vehicle_footprint_; std::recursive_mutex mutex_; - // TODO(Mamoru Sobue): isSafePath() modifies ThreadSafeData::check_collision, avoid this mutable - mutable ThreadSafeData thread_safe_data_; + ThreadSafeData thread_safe_data_; std::unique_ptr last_approval_data_{nullptr}; + PreviousPullOverData prev_data_{}; // approximate distance from the start point to the end point of pull_over. // this is used as an assumed value to decelerate, etc., before generating the actual path. @@ -516,12 +460,11 @@ class GoalPlannerModule : public SceneModuleInterface mutable PoseWithString debug_stop_pose_with_info_; // collision check - bool checkOccupancyGridCollision( - const PathWithLaneId & path, - const std::shared_ptr occupancy_grid_map) const; + void initializeOccupancyGridMap(); + void updateOccupancyGrid(); + bool checkOccupancyGridCollision(const PathWithLaneId & path) const; bool checkObjectsCollision( - const PathWithLaneId & path, const std::shared_ptr planner_data, - const GoalPlannerParameters & parameters, const double collision_check_margin, + const PathWithLaneId & path, const double collision_check_margin, const bool extract_static_objects, const bool update_debug_data = false) const; // goal seach @@ -544,39 +487,13 @@ class GoalPlannerModule : public SceneModuleInterface bool isStopped( std::deque & odometry_buffer, const double time); bool hasFinishedCurrentPath(); - bool isOnModifiedGoal(const Pose & current_pose, const GoalPlannerParameters & parameters) const; + bool isOnModifiedGoal() const; double calcModuleRequestLength() const; - bool needPathUpdate( - const Pose & current_pose, const double path_update_duration, - const GoalPlannerParameters & parameters) const; - bool isStuck( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters); - bool hasDecidedPath( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, - const std::shared_ptr goal_searcher) const; - bool hasNotDecidedPath( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, - const std::shared_ptr goal_searcher) const; - DecidingPathStatusWithStamp checkDecidingPathStatus( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, - const std::shared_ptr goal_searcher) const; + bool needPathUpdate(const double path_update_duration) const; + bool isStuck(); + bool hasDecidedPath() const; + bool hasNotDecidedPath() const; + DecidingPathStatusWithStamp checkDecidingPathStatus() const; void decideVelocity(); bool foundPullOverPath() const; void updateStatus(const BehaviorModuleOutput & output); @@ -591,10 +508,7 @@ class GoalPlannerModule : public SceneModuleInterface bool hasEnoughTimePassedSincePathUpdate(const double duration) const; // freespace parking - bool planFreespacePath( - std::shared_ptr planner_data, - const std::shared_ptr goal_searcher, - const std::shared_ptr occupancy_grid_map); + bool planFreespacePath(); bool canReturnToLaneParking(); // plan pull over path @@ -623,12 +537,10 @@ class GoalPlannerModule : public SceneModuleInterface TurnSignalInfo calcTurnSignalInfo(); std::optional ignore_signal_{std::nullopt}; - bool hasPreviousModulePathShapeChanged(const BehaviorModuleOutput & previous_module_output) const; - bool hasDeviatedFromLastPreviousModulePath( - const std::shared_ptr planner_data) const; - bool hasDeviatedFromCurrentPreviousModulePath( - const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) const; + std::optional last_previous_module_output_{}; + bool hasPreviousModulePathShapeChanged() const; + bool hasDeviatedFromLastPreviousModulePath() const; + bool hasDeviatedFromCurrentPreviousModulePath() const; // timer for generating pull over path candidates in a separate thread void onTimer(); @@ -644,22 +556,16 @@ class GoalPlannerModule : public SceneModuleInterface // safety check void initializeSafetyCheckParameters(); SafetyCheckParams createSafetyCheckParams() const; - /* void updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const; - */ /** * @brief Checks if the current path is safe. * @return std::pair * first: If the path is safe for a certain period of time, true. * second: If the path is safe in the current state, true. */ - std::pair isSafePath( - const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params) const; + std::pair isSafePath() const; // debug void setDebugData(); diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index 89f4086874183..f228ecc378c28 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -29,45 +29,33 @@ using BasicPolygons2d = std::vector; class GoalSearcher : public GoalSearcherBase { public: - GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint); + GoalSearcher( + const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint, + const std::shared_ptr & occupancy_grid_map); - GoalCandidates search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) override; - void update( - GoalCandidates & goal_candidates, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const override; + GoalCandidates search() override; + void update(GoalCandidates & goal_candidates) const override; // todo(kosuke55): Functions for this specific use should not be in the interface, // so it is better to consider interface design when we implement other goal searchers. GoalCandidate getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates, - const std::shared_ptr & planner_data) const override; + const GoalCandidates & goal_candidates) const override; bool isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const override; + const GoalCandidate & goal_candidate, const double margin_scale_factor) const override; private: void countObjectsToAvoid( - GoalCandidates & goal_candidates, const PredictedObjects & objects, - const std::shared_ptr & planner_data) const; - void createAreaPolygons( - std::vector original_search_poses, - const std::shared_ptr & planner_data); - bool checkCollision( - const Pose & pose, const PredictedObjects & objects, - const std::shared_ptr occupancy_grid_map) const; + GoalCandidates & goal_candidates, const PredictedObjects & objects) const; + void createAreaPolygons(std::vector original_search_poses); + bool checkCollision(const Pose & pose, const PredictedObjects & objects) const; bool checkCollisionWithLongitudinalDistance( - const Pose & ego_pose, const PredictedObjects & objects, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const; + const Pose & ego_pose, const PredictedObjects & objects) const; BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const; BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const; bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const; LinearRing2d vehicle_footprint_{}; + std::shared_ptr occupancy_grid_map_{}; bool left_side_parking_{true}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp index f5d879358cd38..2ddacc0aac46d 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -17,7 +17,6 @@ #include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" -#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -50,29 +49,23 @@ class GoalSearcherBase { reference_goal_pose_ = reference_goal_pose; } - const Pose & getReferenceGoal() const { return reference_goal_pose_; } - MultiPolygon2d getAreaPolygons() const { return area_polygons_; } - virtual GoalCandidates search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) = 0; - virtual void update( - [[maybe_unused]] GoalCandidates & goal_candidates, - [[maybe_unused]] const std::shared_ptr occupancy_grid_map, - [[maybe_unused]] const std::shared_ptr & planner_data) const + void setPlannerData(const std::shared_ptr & planner_data) { - return; + planner_data_ = planner_data; } + + MultiPolygon2d getAreaPolygons() { return area_polygons_; } + virtual GoalCandidates search() = 0; + virtual void update([[maybe_unused]] GoalCandidates & goal_candidates) const { return; } virtual GoalCandidate getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates, - const std::shared_ptr & planner_data) const = 0; + const GoalCandidates & goal_candidates) const = 0; virtual bool isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const = 0; + const GoalCandidate & goal_candidate, const double margin_scale_factor) const = 0; protected: GoalPlannerParameters parameters_{}; + std::shared_ptr planner_data_{nullptr}; Pose reference_goal_pose_{}; MultiPolygon2d area_polygons_{}; }; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index d0b0aee83e20c..892ef7d5dd303 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -33,7 +34,9 @@ class ShiftPullOver : public PullOverPlannerBase public: ShiftPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker); + const LaneDepartureChecker & lane_departure_checker, + const std::shared_ptr & occupancy_grid_map); + PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::SHIFT; }; std::optional plan(const Pose & goal_pose) override; @@ -54,6 +57,7 @@ class ShiftPullOver : public PullOverPlannerBase const Pose & start_pose, const Pose & end_pose, const double resample_interval); LaneDepartureChecker lane_departure_checker_{}; + std::shared_ptr occupancy_grid_map_{}; bool left_side_parking_{true}; }; diff --git a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp index 0779002690f8f..b7d1c240d032a 100644 --- a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -27,10 +27,13 @@ namespace behavior_path_planner { GeometricPullOver::GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, const bool is_forward) + const LaneDepartureChecker & lane_departure_checker, + const std::shared_ptr occupancy_grid_map, + const bool is_forward) : PullOverPlannerBase{node, parameters}, parallel_parking_parameters_{parameters.parallel_parking_parameters}, lane_departure_checker_{lane_departure_checker}, + occupancy_grid_map_{occupancy_grid_map}, is_forward_{is_forward}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 14fc48b4aeba9..a890cfc21ed13 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -78,14 +78,14 @@ GoalPlannerModule::GoalPlannerModule( for (const std::string & planner_type : parameters_->efficient_path_order) { if (planner_type == "SHIFT" && parameters_->enable_shift_parking) { - pull_over_planners_.push_back( - std::make_shared(node, *parameters, lane_departure_checker)); + pull_over_planners_.push_back(std::make_shared( + node, *parameters, lane_departure_checker, occupancy_grid_map_)); } else if (planner_type == "ARC_FORWARD" && parameters_->enable_arc_forward_parking) { pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, /*is_forward*/ true)); + node, *parameters, lane_departure_checker, occupancy_grid_map_, /*is_forward*/ true)); } else if (planner_type == "ARC_BACKWARD" && parameters_->enable_arc_backward_parking) { pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, /*is_forward*/ false)); + node, *parameters, lane_departure_checker, occupancy_grid_map_, /*is_forward*/ false)); } } @@ -97,7 +97,8 @@ GoalPlannerModule::GoalPlannerModule( // currently there is only one goal_searcher_type const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); vehicle_footprint_ = vehicle_info.createFootprint(); - goal_searcher_ = std::make_shared(*parameters, vehicle_footprint_); + goal_searcher_ = + std::make_shared(*parameters, vehicle_footprint_, occupancy_grid_map_); // timer callback for generating lane parking candidate paths const auto lane_parking_period_ns = rclcpp::Rate(1.0).period(); @@ -122,44 +123,51 @@ GoalPlannerModule::GoalPlannerModule( // Initialize safety checker if (parameters_->safety_check_params.enable_safety_check) { initializeSafetyCheckParameters(); + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); } + + prev_data_.reset(); +} + +// This function is needed for waiting for planner_data_ +void GoalPlannerModule::updateOccupancyGrid() +{ + if (!planner_data_->occupancy_grid) { + RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "occupancy_grid is not ready"); + return; + } + occupancy_grid_map_->setMap(*(planner_data_->occupancy_grid)); } -bool GoalPlannerModule::hasPreviousModulePathShapeChanged( - const BehaviorModuleOutput & previous_module_output) const +bool GoalPlannerModule::hasPreviousModulePathShapeChanged() const { - const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); - if (!last_previous_module_output) { + if (!last_previous_module_output_) { return true; } - const auto current_path = previous_module_output.path; + const auto current_path = getPreviousModuleOutput().path; // the terminal distance is far return calcDistance2d( - last_previous_module_output->path.points.back().point, + last_previous_module_output_->path.points.back().point, current_path.points.back().point) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath( - const std::shared_ptr planner_data) const +bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath() const { - const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); - if (!last_previous_module_output) { + if (!last_previous_module_output_) { return true; } return std::abs(motion_utils::calcLateralOffset( - last_previous_module_output->path.points, - planner_data->self_odometry->pose.pose.position)) > 0.3; + last_previous_module_output_->path.points, + planner_data_->self_odometry->pose.pose.position)) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath( - const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) const +bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath() const { return std::abs(motion_utils::calcLateralOffset( - previous_module_output.path.points, planner_data->self_odometry->pose.pose.position)) > - 0.3; + getPreviousModuleOutput().path.points, + planner_data_->self_odometry->pose.pose.position)) > 0.3; } // generate pull over candidate paths @@ -167,50 +175,7 @@ void GoalPlannerModule::onTimer() { const ScopedFlag flag(is_lane_parking_cb_running_); - std::shared_ptr local_planner_data{nullptr}; - std::optional current_status_opt{std::nullopt}; - std::optional previous_module_output_opt{std::nullopt}; - std::shared_ptr occupancy_grid_map{nullptr}; - std::optional parameters_opt{std::nullopt}; - std::shared_ptr ego_predicted_path_params{nullptr}; - std::shared_ptr objects_filtering_params{nullptr}; - std::shared_ptr safety_check_params{nullptr}; - std::shared_ptr goal_searcher{nullptr}; - - // begin of critical section - { - std::lock_guard guard(gp_planner_data_mutex_); - if (gp_planner_data_) { - const auto & gp_planner_data = gp_planner_data_.value(); - local_planner_data = std::make_shared(gp_planner_data.planner_data); - current_status_opt = gp_planner_data.current_status; - previous_module_output_opt = gp_planner_data.previous_module_output; - occupancy_grid_map = gp_planner_data.occupancy_grid_map; - parameters_opt = gp_planner_data.parameters; - ego_predicted_path_params = gp_planner_data.ego_predicted_path_params; - objects_filtering_params = gp_planner_data.objects_filtering_params; - safety_check_params = gp_planner_data.safety_check_params; - goal_searcher = gp_planner_data.goal_searcher; - } - } - // end of critical section - if ( - !local_planner_data || !current_status_opt || !previous_module_output_opt || - !occupancy_grid_map || !parameters_opt || !ego_predicted_path_params || - !objects_filtering_params || !safety_check_params || !goal_searcher) { - RCLCPP_ERROR( - getLogger(), - "failed to get valid " - "local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt/" - "ego_predicted_path_params/objects_filtering_params/safety_check_params/goal_searcher in " - "onTimer"); - return; - } - const auto & current_status = current_status_opt.value(); - const auto & previous_module_output = previous_module_output_opt.value(); - const auto & parameters = parameters_opt.value(); - - if (current_status == ModuleStatus::IDLE) { + if (getCurrentStatus() == ModuleStatus::IDLE) { return; } @@ -219,31 +184,27 @@ void GoalPlannerModule::onTimer() return; } - if (!utils::isAllowedGoalModification(local_planner_data->route_handler)) { + if (!planner_data_ || !utils::isAllowedGoalModification(planner_data_->route_handler)) { return; } // check if new pull over path candidates are needed to be generated const bool need_update = std::invoke([&]() { - if (isOnModifiedGoal(local_planner_data->self_odometry->pose.pose, parameters)) { + if (isOnModifiedGoal()) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath(local_planner_data, previous_module_output)) { + if (hasDeviatedFromCurrentPreviousModulePath()) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return true; } - if (hasPreviousModulePathShapeChanged(previous_module_output)) { + if (hasPreviousModulePathShapeChanged()) { RCLCPP_DEBUG(getLogger(), "has previous module path shape changed"); return true; } - if ( - hasDeviatedFromLastPreviousModulePath(local_planner_data) && - !hasDecidedPath( - local_planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params, goal_searcher)) { + if (hasDeviatedFromLastPreviousModulePath() && !hasDecidedPath()) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; } @@ -253,12 +214,13 @@ void GoalPlannerModule::onTimer() return; } + const auto previous_module_output = getPreviousModuleOutput(); const auto goal_candidates = thread_safe_data_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( - local_planner_data, parameters.backward_goal_search_length, - parameters.forward_goal_search_length, + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, /*forward_only_in_route*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; @@ -266,7 +228,7 @@ void GoalPlannerModule::onTimer() const auto planCandidatePaths = [&]( const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { - planner->setPlannerData(local_planner_data); + planner->setPlannerData(planner_data_); planner->setPreviousModuleOutput(previous_module_output); auto pull_over_path = planner->plan(goal_candidate.goal_pose); if (pull_over_path) { @@ -292,7 +254,7 @@ void GoalPlannerModule::onTimer() is_center_line_input_path); // plan candidate paths and set them to the member variable - if (parameters.path_priority == "efficient_path") { + if (parameters_->path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line if (!is_center_line_input_path && planner->getPlannerType() != PullOverPlannerType::SHIFT) { @@ -302,7 +264,7 @@ void GoalPlannerModule::onTimer() planCandidatePaths(planner, goal_candidate); } } - } else if (parameters.path_priority == "close_goal") { + } else if (parameters_->path_priority == "close_goal") { for (const auto & goal_candidate : goal_candidates) { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line @@ -315,76 +277,49 @@ void GoalPlannerModule::onTimer() } else { RCLCPP_ERROR( getLogger(), "path_priority should be efficient_path or close_goal, but %s is given.", - parameters.path_priority.c_str()); + parameters_->path_priority.c_str()); throw std::domain_error("[pull_over] invalid path_priority"); } // set member variables - thread_safe_data_.set_pull_over_path_candidates(path_candidates); - thread_safe_data_.set_closest_start_pose(closest_start_pose); - RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); + { + const std::lock_guard lock(mutex_); + thread_safe_data_.set_pull_over_path_candidates(path_candidates); + thread_safe_data_.set_closest_start_pose(closest_start_pose); + RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); + } - thread_safe_data_.set_last_previous_module_output(previous_module_output); + last_previous_module_output_ = previous_module_output; } void GoalPlannerModule::onFreespaceParkingTimer() { const ScopedFlag flag(is_freespace_parking_cb_running_); - std::shared_ptr local_planner_data{nullptr}; - std::optional current_status_opt{std::nullopt}; - std::shared_ptr occupancy_grid_map{nullptr}; - std::optional parameters_opt{std::nullopt}; - std::shared_ptr goal_searcher{nullptr}; - - // begin of critical section - { - std::lock_guard guard(gp_planner_data_mutex_); - if (gp_planner_data_) { - const auto & gp_planner_data = gp_planner_data_.value(); - local_planner_data = std::make_shared(gp_planner_data.planner_data); - current_status_opt = gp_planner_data.current_status; - occupancy_grid_map = gp_planner_data.occupancy_grid_map; - parameters_opt = gp_planner_data.parameters; - goal_searcher = gp_planner_data.goal_searcher; - } - } - // end of critical section - if (!local_planner_data || !current_status_opt || !parameters_opt || !goal_searcher) { - RCLCPP_ERROR( - getLogger(), - "failed to get valid planner_data/current_status/parameters/goal_searcher in " - "onFreespaceParkingTimer"); + if (getCurrentStatus() == ModuleStatus::IDLE) { return; } - const auto & current_status = current_status_opt.value(); - const auto & parameters = parameters_opt.value(); - - if (current_status == ModuleStatus::IDLE) { + if (!planner_data_) { return; } - - if (!local_planner_data->costmap) { + if (!planner_data_->costmap) { return; } // fixed goal planner do not use freespace planner - if (!utils::isAllowedGoalModification(local_planner_data->route_handler)) { + if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { return; } - if (isOnModifiedGoal(local_planner_data->self_odometry->pose.pose, parameters)) { + if (isOnModifiedGoal()) { return; } const bool is_new_costmap = - (clock_->now() - local_planner_data->costmap->header.stamp).seconds() < 1.0; + (clock_->now() - planner_data_->costmap->header.stamp).seconds() < 1.0; constexpr double path_update_duration = 1.0; - if ( - isStuck(local_planner_data, occupancy_grid_map, parameters) && is_new_costmap && - needPathUpdate( - local_planner_data->self_odometry->pose.pose, path_update_duration, parameters)) { - planFreespacePath(local_planner_data, goal_searcher, occupancy_grid_map); + if (isStuck() && is_new_costmap && needPathUpdate(path_update_duration)) { + planFreespacePath(); } } @@ -414,64 +349,28 @@ void GoalPlannerModule::updateObjectsFilteringParams( void GoalPlannerModule::updateData() { - // In PlannerManager::run(), it calls SceneModuleInterface::setData and - // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). - // Then module_ptr->run() invokes GoalPlannerModule::updateData and then - // planWaitingApproval()/plan(), so we can copy latest current_status/previous_module_output to - // gp_planner_data_ here - - // NOTE: onTimer/onFreespaceParkingTimer copies gp_planner_data_ to their local clone, so we need - // to lock gp_planner_data_ here to avoid data race. But the following clone process is - // lightweight because most of the member variables of PlannerData/RouteHandler is - // shared_ptrs/bool - // begin of critical section - { - std::lock_guard guard(gp_planner_data_mutex_); - if (!gp_planner_data_) { - gp_planner_data_ = GoalPlannerData(*planner_data_, *parameters_); - } - auto & gp_planner_data = gp_planner_data_.value(); - // NOTE: for the above reasons, PlannerManager/behavior_path_planner_node ensure that - // planner_data_ is not nullptr, so it is OK to copy as value - // By copying PlannerData as value, the internal shared member variables are also copied - // (reference count is incremented), so `gp_planner_data_.foo` is now thread-safe from the - // **re-pointing** by `planner_data_->foo = msg` in behavior_path_planner::onCallbackFor(msg) - // and if these two coincided, only the reference count is affected - gp_planner_data.update( - *parameters_, ego_predicted_path_params_, objects_filtering_params_, safety_check_params_, - *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), goal_searcher_, - vehicle_footprint_); - // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as - // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since - // behavior_path_planner::run() updates - // planner_data_->route_handler->lanelet_map_ptr_/routing_graph_ptr_ especially, we also have - // to copy route_handler as value to use lanelet_map_ptr_/routing_graph_ptr_ thread-safely in - // onTimer/onFreespaceParkingTimer - // TODO(Mamoru Sobue): If the copy of RouteHandler.road_lanelets/shoulder_lanelets is not - // lightweight, we should update gp_planner_data_.route_handler only when - // `planner_data_.is_route_handler_updated` variable is set true by behavior_path_planner - // (although this flag is not implemented yet). In that case, gp_planner_data members except - // for route_handler should be copied from planner_data_ - - // GoalPlannerModule::occupancy_grid_map_ and gp_planner_data.occupancy_grid_map share the - // ownership, and gp_planner_data.occupancy_grid_map maybe also shared by the local - // planner_data on onFreespaceParkingTimer thread local memory space. So following operation - // is thread-safe because gp_planner_data.occupancy_grid_map is only re-pointed here and its - // prior resource is still owned by the onFreespaceParkingTimer thread locally. - occupancy_grid_map_ = gp_planner_data.occupancy_grid_map; - } - // end of critical section - if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { return; } + // Initialize Occupancy Grid Map + // This operation requires waiting for `planner_data_`, hence it is executed here instead of in + // the constructor. Ideally, this operation should only need to be performed once. + if ( + parameters_->use_occupancy_grid_for_goal_search || + parameters_->use_occupancy_grid_for_path_collision_check) { + initializeOccupancyGridMap(); + } + resetPathCandidate(); resetPathReference(); path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); + updateOccupancyGrid(); + // update goal searcher and generate goal candidates if (thread_safe_data_.get_goal_candidates().empty()) { + goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal( calcRefinedGoal(planner_data_->route_handler->getOriginalGoalPose())); thread_safe_data_.set_goal_candidates(generateGoalCandidates()); @@ -492,6 +391,21 @@ void GoalPlannerModule::updateData() } } +void GoalPlannerModule::initializeOccupancyGridMap() +{ + OccupancyGridMapParam occupancy_grid_map_param{}; + const double margin = parameters_->occupancy_grid_collision_check_margin; + occupancy_grid_map_param.vehicle_shape.length = + planner_data_->parameters.vehicle_length + 2 * margin; + occupancy_grid_map_param.vehicle_shape.width = + planner_data_->parameters.vehicle_width + 2 * margin; + occupancy_grid_map_param.vehicle_shape.base2back = + planner_data_->parameters.base_link2rear + margin; + occupancy_grid_map_param.theta_size = parameters_->theta_size; + occupancy_grid_map_param.obstacle_threshold = parameters_->obstacle_threshold; + occupancy_grid_map_->setParam(occupancy_grid_map_param); +} + void GoalPlannerModule::initializeSafetyCheckParameters() { updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); @@ -504,7 +418,7 @@ void GoalPlannerModule::processOnExit() resetPathCandidate(); resetPathReference(); debug_marker_.markers.clear(); - thread_safe_data_.reset(); + prev_data_.reset(); last_approval_data_.reset(); } @@ -587,10 +501,7 @@ bool GoalPlannerModule::isExecutionRequested() const bool GoalPlannerModule::isExecutionReady() const { if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) { - if (!isSafePath( - planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, - safety_check_params_) - .first) { + if (!isSafePath().first) { RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects"); return false; } @@ -673,17 +584,18 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } -bool GoalPlannerModule::planFreespacePath( - std::shared_ptr planner_data, - const std::shared_ptr goal_searcher, - const std::shared_ptr occupancy_grid_map) +bool GoalPlannerModule::planFreespacePath() { GoalCandidates goal_candidates{}; - goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data); - thread_safe_data_.set_goal_candidates(goal_candidates); - debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); - debug_data_.freespace_planner.is_planning = true; + { + const std::lock_guard lock(mutex_); + goal_searcher_->setPlannerData(planner_data_); + goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher_->update(goal_candidates); + thread_safe_data_.set_goal_candidates(goal_candidates); + debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); + debug_data_.freespace_planner.is_planning = true; + } for (size_t i = 0; i < goal_candidates.size(); i++) { const auto goal_candidate = goal_candidates.at(i); @@ -695,7 +607,7 @@ bool GoalPlannerModule::planFreespacePath( if (!goal_candidate.is_safe) { continue; } - freespace_planner_->setPlannerData(planner_data); + freespace_planner_->setPlannerData(planner_data_); auto freespace_path = freespace_planner_->plan(goal_candidate.goal_pose); freespace_path->goal_id = goal_candidate.id; if (!freespace_path) { @@ -733,15 +645,13 @@ bool GoalPlannerModule::canReturnToLaneParking() if ( parameters_->use_object_recognition && checkObjectsCollision( - path, planner_data_, *parameters_, - parameters_->object_recognition_collision_check_hard_margins.back(), + path, parameters_->object_recognition_collision_check_hard_margins.back(), /*extract_static_objects=*/false)) { return false; } if ( - parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(path, occupancy_grid_map_)) { + parameters_->use_occupancy_grid_for_path_collision_check && checkOccupancyGridCollision(path)) { return false; } @@ -761,7 +671,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const // calculate goal candidates const auto & route_handler = planner_data_->route_handler; if (utils::isAllowedGoalModification(route_handler)) { - return goal_searcher_->search(occupancy_grid_map_, planner_data_); + return goal_searcher_->search(); } // NOTE: @@ -868,7 +778,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); for (const auto & margin : margins) { if (!checkObjectsCollision( - resampled_path, planner_data_, *parameters_, margin, + resampled_path, margin, /*extract_static_objects=*/true)) { return margin; } @@ -955,17 +865,16 @@ std::optional> GoalPlannerModule::selectP const auto resampled_path = utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); if ( - parameters_->use_object_recognition && - checkObjectsCollision( - resampled_path, planner_data_, *parameters_, collision_check_margin, - /*extract_static_objects=*/true, - /*update_debug_data=*/true)) { + parameters_->use_object_recognition && checkObjectsCollision( + resampled_path, collision_check_margin, + /*extract_static_objects=*/true, + /*update_debug_data=*/true)) { continue; } if ( parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(resampled_path, occupancy_grid_map_)) { + checkOccupancyGridCollision(resampled_path)) { continue; } @@ -1001,12 +910,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) } if ( - parameters_->safety_check_params.enable_safety_check && - !isSafePath( - planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, - safety_check_params_) - .first && - isActivated()) { + parameters_->safety_check_params.enable_safety_check && !isSafePath().first && isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -1029,11 +933,7 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) setDrivableAreaInfo(output); // set hazard and turn signal - if ( - hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_) && - isActivated()) { + if (hasDecidedPath() && isActivated()) { setTurnSignalInfo(output); } } @@ -1097,47 +997,20 @@ void GoalPlannerModule::updateSteeringFactor( pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); } -bool GoalPlannerModule::hasDecidedPath( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, - const std::shared_ptr goal_searcher) const -{ - return checkDecidingPathStatus( - planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params, goal_searcher) - .first == DecidingPathStatus::DECIDED; -} - -bool GoalPlannerModule::hasNotDecidedPath( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, - const std::shared_ptr goal_searcher) const -{ - return checkDecidingPathStatus( - planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params, goal_searcher) - .first == DecidingPathStatus::NOT_DECIDED; -} - -DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params, - const std::shared_ptr goal_searcher) const -{ - const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; - const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; +bool GoalPlannerModule::hasDecidedPath() const +{ + return checkDecidingPathStatus().first == DecidingPathStatus::DECIDED; +} + +bool GoalPlannerModule::hasNotDecidedPath() const +{ + return checkDecidingPathStatus().first == DecidingPathStatus::NOT_DECIDED; +} + +DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const +{ + const auto & prev_status = prev_data_.deciding_path_status; + const bool enable_safety_check = parameters_->safety_check_params.enable_safety_check; // Once this function returns true, it will continue to return true thereafter if (prev_status.first == DecidingPathStatus::DECIDED) { @@ -1151,13 +1024,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( // If it is dangerous against dynamic objects before approval, do not determine the path. // This eliminates a unsafe path to be approved - if ( - enable_safety_check && - !isSafePath( - planner_data, parameters, ego_predicted_path_params, objects_filtering_params, - safety_check_params) - .first && - !isActivated()) { + if (enable_safety_check && !isSafePath().first && !isActivated()) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before " @@ -1173,11 +1040,11 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const double hysteresis_factor = 0.9; // check goal pose collision + goal_searcher_->setPlannerData(planner_data_); const auto modified_goal_opt = thread_safe_data_.get_modified_goal_pose(); if ( - modified_goal_opt && - !goal_searcher->isSafeGoalWithMarginScaleFactor( - modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, planner_data)) { + modified_goal_opt && !goal_searcher_->isSafeGoalWithMarginScaleFactor( + modified_goal_opt.value(), hysteresis_factor)) { RCLCPP_DEBUG(getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } @@ -1185,20 +1052,15 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( // check current parking path collision const auto parking_path = utils::resamplePathWithSpline(pull_over_path->getParkingPath(), 0.5); const double margin = - parameters.object_recognition_collision_check_hard_margins.back() * hysteresis_factor; - if (checkObjectsCollision( - parking_path, planner_data, parameters, margin, /*extract_static_objects=*/false)) { + parameters_->object_recognition_collision_check_hard_margins.back() * hysteresis_factor; + if (checkObjectsCollision(parking_path, margin, /*extract_static_objects=*/false)) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } - if ( - enable_safety_check && !isSafePath( - planner_data, parameters, ego_predicted_path_params, - objects_filtering_params, safety_check_params) - .first) { + if (enable_safety_check && !isSafePath().first) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects"); @@ -1222,7 +1084,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( } // if ego is sufficiently close to the start of the nearest candidate path, the path is decided - const auto & current_pose = planner_data->self_odometry->pose.pose; + const auto & current_pose = planner_data_->self_odometry->pose.pose; const size_t ego_segment_idx = motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); @@ -1231,13 +1093,13 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( const double dist_to_parking_start_pose = calcSignedArcLength( current_path.points, current_pose.position, ego_segment_idx, pull_over_path->start_pose.position, start_pose_segment_idx); - if (dist_to_parking_start_pose > parameters.decide_path_distance) { + if (dist_to_parking_start_pose > parameters_->decide_path_distance) { return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } // if object recognition for path collision check is enabled, transition to DECIDING to check // collision for a certain period of time. Otherwise, transition to DECIDED directly. - if (parameters.use_object_recognition) { + if (parameters_->use_object_recognition) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain " @@ -1262,9 +1124,7 @@ void GoalPlannerModule::decideVelocity() BehaviorModuleOutput GoalPlannerModule::planPullOver() { - if (!hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_)) { + if (!hasDecidedPath()) { return planPullOverAsCandidate(); } @@ -1308,12 +1168,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() return getPreviousModuleOutput(); } - if ( - hasNotDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_) && - needPathUpdate( - planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, *parameters_)) { + if (hasNotDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_ @@ -1322,8 +1177,9 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() thread_safe_data_.clearPullOverPath(); // update goal candidates + goal_searcher_->setPlannerData(planner_data_); auto goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates, occupancy_grid_map_, planner_data_); + goal_searcher_->update(goal_candidates); // update pull over path candidates const auto pull_over_path_candidates = sortPullOverPathCandidatesByGoalPriority( @@ -1384,14 +1240,9 @@ void GoalPlannerModule::postProcess() return; } + const bool has_decided_path = hasDecidedPath(); const auto distance_to_path_change = calcDistanceToPathChange(); - // TODO(Mamoru Sobue): repetitive call to checkDecidingPathStatus() in the main thread is a - // waste of time because it gives same result throughout the main thread. - const bool has_decided_path = hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_); - if (has_decided_path) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } @@ -1409,35 +1260,27 @@ void GoalPlannerModule::updatePreviousData() { // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. - // TODO(Mamoru Sobue): put prev_data_ out of ThreadSafeData - auto prev_data = thread_safe_data_.get_prev_data(); - prev_data.found_path = thread_safe_data_.foundPullOverPath(); + prev_data_.found_path = thread_safe_data_.foundPullOverPath(); - prev_data.deciding_path_status = checkDecidingPathStatus( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_); + prev_data_.deciding_path_status = checkDecidingPathStatus(); // This is related to safety check, so if it is disabled, return here. if (!parameters_->safety_check_params.enable_safety_check) { - prev_data.safety_status.is_safe = true; - } else { - // Even if the current path is safe, it will not be safe unless it stands for a certain period - // of time. Record the time when the current path has become safe - const auto [is_safe, current_is_safe] = isSafePath( - planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, - safety_check_params_); - if (current_is_safe) { - if (!prev_data.safety_status.safe_start_time) { - prev_data.safety_status.safe_start_time = clock_->now(); - } - } else { - prev_data.safety_status.safe_start_time = std::nullopt; - } - prev_data.safety_status.is_safe = is_safe; + prev_data_.safety_status.is_safe = true; + return; } - // commit the change - thread_safe_data_.set_prev_data(prev_data); + // Even if the current path is safe, it will not be safe unless it stands for a certain period of + // time. Record the time when the current path has become safe + const auto [is_safe, current_is_safe] = isSafePath(); + if (current_is_safe) { + if (!prev_data_.safety_status.safe_start_time) { + prev_data_.safety_status.safe_start_time = clock_->now(); + } + } else { + prev_data_.safety_status.safe_start_time = std::nullopt; + } + prev_data_.safety_status.is_safe = is_safe; } BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() @@ -1514,8 +1357,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible // stop point is found, stop at this position. - const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( - thread_safe_data_.get_goal_candidates(), planner_data_); + const auto closest_goal_candidate = + goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); const auto decel_pose = calcLongitudinalOffsetPose( extended_prev_path.points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -1643,13 +1486,10 @@ bool GoalPlannerModule::isStopped() return isStopped(odometry_buffer_stopped_, parameters_->th_stopped_time); } -bool GoalPlannerModule::isStuck( - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const GoalPlannerParameters & parameters) +bool GoalPlannerModule::isStuck() { const std::lock_guard lock(mutex_); - if (isOnModifiedGoal(planner_data->self_odometry->pose.pose, parameters)) { + if (isOnModifiedGoal()) { return false; } @@ -1669,18 +1509,17 @@ bool GoalPlannerModule::isStuck( } if ( - parameters.use_object_recognition && + parameters_->use_object_recognition && checkObjectsCollision( - thread_safe_data_.get_pull_over_path()->getCurrentPath(), planner_data, parameters, + thread_safe_data_.get_pull_over_path()->getCurrentPath(), /*extract_static_objects=*/false, - parameters.object_recognition_collision_check_hard_margins.back())) { + parameters_->object_recognition_collision_check_hard_margins.back())) { return true; } if ( - parameters.use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision( - thread_safe_data_.get_pull_over_path()->getCurrentPath(), occupancy_grid_map)) { + parameters_->use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath())) { return true; } @@ -1726,15 +1565,15 @@ bool GoalPlannerModule::hasFinishedCurrentPath() parameters_->th_arrived_distance; } -bool GoalPlannerModule::isOnModifiedGoal( - const Pose & current_pose, const GoalPlannerParameters & parameters) const +bool GoalPlannerModule::isOnModifiedGoal() const { if (!thread_safe_data_.get_modified_goal_pose()) { return false; } + const Pose current_pose = planner_data_->self_odometry->pose.pose; return calcDistance2d(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose) < - parameters.th_arrived_distance; + parameters_->th_arrived_distance; } TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() @@ -1803,34 +1642,31 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() return new_signal; } -bool GoalPlannerModule::checkOccupancyGridCollision( - const PathWithLaneId & path, - const std::shared_ptr occupancy_grid_map) const +bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const { - if (!occupancy_grid_map) { + if (!occupancy_grid_map_) { return false; } const bool check_out_of_range = false; - return occupancy_grid_map->hasObstacleOnPath(path, check_out_of_range); + return occupancy_grid_map_->hasObstacleOnPath(path, check_out_of_range); } bool GoalPlannerModule::checkObjectsCollision( - const PathWithLaneId & path, const std::shared_ptr planner_data, - const GoalPlannerParameters & parameters, const double collision_check_margin, + const PathWithLaneId & path, const double collision_check_margin, const bool extract_static_objects, const bool update_debug_data) const { const auto target_objects = std::invoke([&]() { - const auto & p = parameters; - const auto & rh = *(planner_data->route_handler); - const auto objects = *(planner_data->dynamic_object); + const auto & p = parameters_; + const auto & rh = *(planner_data_->route_handler); + const auto objects = *(planner_data_->dynamic_object); if (extract_static_objects) { return goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, - p.detection_bound_offset, objects, p.th_moving_object_velocity); + rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, + p->detection_bound_offset, objects, p->th_moving_object_velocity); } return goal_planner_utils::extractObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, - p.detection_bound_offset, objects); + rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, + p->detection_bound_offset, objects); }); std::vector obj_polygons; @@ -1849,8 +1685,8 @@ bool GoalPlannerModule::checkObjectsCollision( const auto p = path.points.at(i); const double extra_stopping_margin = std::min( - std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters.maximum_deceleration, - parameters.object_recognition_collision_check_max_extra_stopping_margin); + std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters_->maximum_deceleration, + parameters_->object_recognition_collision_check_max_extra_stopping_margin); // The square is meant to imply centrifugal force, but it is not a very well-founded formula. // TODO(kosuke55): It is needed to consider better way because there is an inherently different @@ -1861,9 +1697,9 @@ bool GoalPlannerModule::checkObjectsCollision( const auto ego_polygon = tier4_autoware_utils::toFootprint( p.point.pose, - planner_data->parameters.base_link2front + collision_check_margin + extra_stopping_margin, - planner_data->parameters.base_link2rear + collision_check_margin, - planner_data->parameters.vehicle_width + collision_check_margin * 2.0 + + planner_data_->parameters.base_link2front + collision_check_margin + extra_stopping_margin, + planner_data_->parameters.base_link2rear + collision_check_margin, + planner_data_->parameters.vehicle_width + collision_check_margin * 2.0 + extra_lateral_margin * 2.0); ego_polygons_expanded.push_back(ego_polygon); } @@ -1946,8 +1782,8 @@ double GoalPlannerModule::calcSignedArcLengthFromEgo( void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const { // decelerate before the search area start - const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( - thread_safe_data_.get_goal_candidates(), planner_data_); + const auto closest_goal_candidate = + goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); const auto decel_pose = calcLongitudinalOffsetPose( pull_over_path.getFullPath().points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -2128,7 +1964,6 @@ bool GoalPlannerModule::isCrossingPossible(const PullOverPath & pull_over_path) return isCrossingPossible(start_pose, end_pose, lanes); } -/* void GoalPlannerModule::updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const @@ -2137,7 +1972,6 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData( goal_planner_data_.target_objects_on_lane = target_objects_on_lane; goal_planner_data_.ego_predicted_path = ego_predicted_path; } -*/ static std::vector filterObjectsByWithinPolicy( const std::shared_ptr & objects, @@ -2183,29 +2017,26 @@ static std::vector filterOb return refined_filtered_objects; } -std::pair GoalPlannerModule::isSafePath( - const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, - const std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & objects_filtering_params, - const std::shared_ptr & safety_check_params) const +std::pair GoalPlannerModule::isSafePath() const { if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); - const auto & current_pose = planner_data->self_odometry->pose.pose; + const auto & current_pose = planner_data_->self_odometry->pose.pose; const double current_velocity = std::hypot( - planner_data->self_odometry->twist.twist.linear.x, - planner_data->self_odometry->twist.twist.linear.y); - const auto & dynamic_object = planner_data->dynamic_object; - const auto & route_handler = planner_data->route_handler; + planner_data_->self_odometry->twist.twist.linear.x, + planner_data_->self_odometry->twist.twist.linear.y); + const auto & dynamic_object = planner_data_->dynamic_object; + const auto & route_handler = planner_data_->route_handler; const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( - planner_data, parameters.backward_goal_search_length, parameters.forward_goal_search_length, + planner_data_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( - *route_handler, left_side_parking_, parameters.backward_goal_search_length, - parameters.forward_goal_search_length); - const size_t ego_seg_idx = planner_data->findEgoSegmentIndex(pull_over_path.points); + *route_handler, left_side_parking_, parameters_->backward_goal_search_length, + parameters_->forward_goal_search_length); + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = utils::parking_departure::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, @@ -2213,15 +2044,15 @@ std::pair GoalPlannerModule::isSafePath( RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - auto temp_param = std::make_shared(*ego_predicted_path_params); - utils::parking_departure::updatePathProperty(temp_param, terminal_velocity_and_accel); + utils::parking_departure::updatePathProperty( + ego_predicted_path_params_, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; const bool limit_to_max_velocity = true; const auto ego_predicted_path = behavior_path_planner::utils::path_safety_checker::createPredictedPath( - ego_predicted_path_params, pull_over_path.points, current_pose, current_velocity, ego_seg_idx, - is_object_front, limit_to_max_velocity); + ego_predicted_path_params_, pull_over_path.points, current_pose, current_velocity, + ego_seg_idx, is_object_front, limit_to_max_velocity); // ========================================================================================== // if ego is before the entry of pull_over_lanes, the beginning of the safety check area @@ -2263,38 +2094,36 @@ std::pair GoalPlannerModule::isSafePath( const auto expanded_pull_over_lanes_between_ego = goal_planner_utils::generateBetweenEgoAndExpandedPullOverLanes( pull_over_lanes, left_side_parking_, ego_pose_for_expand, - planner_data->parameters.vehicle_info, parameters.outer_road_detection_offset, - parameters.inner_road_detection_offset); + planner_data_->parameters.vehicle_info, parameters_->outer_road_detection_offset, + parameters_->inner_road_detection_offset); const auto merged_expanded_pull_over_lanes = lanelet::utils::combineLaneletsShape(expanded_pull_over_lanes_between_ego); debug_data_.expanded_pull_over_lane_between_ego = merged_expanded_pull_over_lanes; const auto filtered_objects = filterObjectsByWithinPolicy( - dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params); + dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params_); - const auto prev_data = thread_safe_data_.get_prev_data(); const double hysteresis_factor = - prev_data.safety_status.is_safe ? 1.0 : parameters.hysteresis_factor_expand_rate; + prev_data_.safety_status.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; - CollisionCheckDebugMap collision_check{}; const bool current_is_safe = std::invoke([&]() { - if (parameters.safety_check_params.method == "RSS") { + if (parameters_->safety_check_params.method == "RSS") { return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( - pull_over_path, ego_predicted_path, filtered_objects, collision_check, - planner_data->parameters, safety_check_params->rss_params, - objects_filtering_params->use_all_predicted_path, hysteresis_factor); - } else if (parameters.safety_check_params.method == "integral_predicted_polygon") { + pull_over_path, ego_predicted_path, filtered_objects, goal_planner_data_.collision_check, + planner_data_->parameters, safety_check_params_->rss_params, + objects_filtering_params_->use_all_predicted_path, hysteresis_factor); + } else if (parameters_->safety_check_params.method == "integral_predicted_polygon") { return utils::path_safety_checker::checkSafetyWithIntegralPredictedPolygon( ego_predicted_path, vehicle_info_, filtered_objects, - objects_filtering_params->check_all_predicted_path, - parameters.safety_check_params.integral_predicted_polygon_params, collision_check); + objects_filtering_params_->check_all_predicted_path, + parameters_->safety_check_params.integral_predicted_polygon_params, + goal_planner_data_.collision_check); } RCLCPP_ERROR( getLogger(), " [pull_over] invalid safety check method: %s", - parameters.safety_check_params.method.c_str()); + parameters_->safety_check_params.method.c_str()); throw std::domain_error("[pull_over] invalid safety check method"); }); - thread_safe_data_.set_collision_check(collision_check); /* * ==== is_safe @@ -2311,9 +2140,9 @@ std::pair GoalPlannerModule::isSafePath( */ if (current_is_safe) { if ( - prev_data.safety_status.safe_start_time && - (clock_->now() - prev_data.safety_status.safe_start_time.value()).seconds() > - parameters.safety_check_params.keep_unsafe_time) { + prev_data_.safety_status.safe_start_time && + (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds() > + parameters_->safety_check_params.keep_unsafe_time) { return {true /*is_safe*/, true /*current_is_safe*/}; } } @@ -2347,12 +2176,8 @@ void GoalPlannerModule::setDebugData() }; if (utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas - const auto color = - hasDecidedPath( - planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, - objects_filtering_params_, safety_check_params_, goal_searcher_) - ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow - : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green + const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow + : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green const double z = planner_data_->route_handler->getGoalPose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); @@ -2365,11 +2190,9 @@ void GoalPlannerModule::setDebugData() // Visualize previous module output add(createPathMarkerArray( getPreviousModuleOutput().path, "previous_module_path", 0, 1.0, 0.0, 0.0)); - - const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); - if (last_previous_module_output.has_value()) { + if (last_previous_module_output_.has_value()) { add(createPathMarkerArray( - last_previous_module_output.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); + last_previous_module_output_.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); } // Visualize path and related pose @@ -2426,7 +2249,6 @@ void GoalPlannerModule::setDebugData() } } - auto collision_check = thread_safe_data_.get_collision_check(); // safety check if (parameters_->safety_check_params.enable_safety_check) { if (goal_planner_data_.ego_predicted_path.size() > 0) { @@ -2441,35 +2263,33 @@ void GoalPlannerModule::setDebugData() } if (parameters_->safety_check_params.method == "RSS") { - add(showSafetyCheckInfo(collision_check, "object_debug_info")); + add(showSafetyCheckInfo(goal_planner_data_.collision_check, "object_debug_info")); } - add(showPredictedPath(collision_check, "ego_predicted_path")); - add(showPolygon(collision_check, "ego_and_target_polygon_relation")); + add(showPredictedPath(goal_planner_data_.collision_check, "ego_predicted_path")); + add(showPolygon(goal_planner_data_.collision_check, "ego_and_target_polygon_relation")); // set objects of interest - for (const auto & [uuid, data] : collision_check) { + for (const auto & [uuid, data] : goal_planner_data_.collision_check) { const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); } - // TODO(Mamoru Sobue): it is not clear where ThreadSafeData::collision_check should be cleared - utils::parking_departure::initializeCollisionCheckDebugMap(collision_check); + utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); // visualize safety status maker { - const auto prev_data = thread_safe_data_.get_prev_data(); visualization_msgs::msg::MarkerArray marker_array{}; - const auto color = prev_data.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) - : createMarkerColor(1.0, 0.0, 0.0, 0.99); + const auto color = prev_data_.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "safety_status", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); marker.pose = planner_data_->self_odometry->pose.pose; - marker.text += "is_safe: " + std::to_string(prev_data.safety_status.is_safe) + "\n"; - if (prev_data.safety_status.safe_start_time) { + marker.text += "is_safe: " + std::to_string(prev_data_.safety_status.is_safe) + "\n"; + if (prev_data_.safety_status.safe_start_time) { const double elapsed_time_from_safe_start = - (clock_->now() - prev_data.safety_status.safe_start_time.value()).seconds(); + (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds(); marker.text += "elapsed_time_from_safe_start: " + std::to_string(elapsed_time_from_safe_start) + "\n"; } @@ -2497,7 +2317,7 @@ void GoalPlannerModule::setDebugData() std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); } - if (isStuck(planner_data_, occupancy_grid_map_, *parameters_)) { + if (isStuck()) { marker.text += " stuck"; } else if (isStopped()) { marker.text += " stopped"; @@ -2547,12 +2367,9 @@ void GoalPlannerModule::printParkingPositionError() const distance_from_real_shoulder); } -bool GoalPlannerModule::needPathUpdate( - const Pose & current_pose, const double path_update_duration, - const GoalPlannerParameters & parameters) const +bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const { - return !isOnModifiedGoal(current_pose, parameters) && - hasEnoughTimePassedSincePathUpdate(path_update_duration); + return !isOnModifiedGoal() && hasEnoughTimePassedSincePathUpdate(path_update_duration); } bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const @@ -2563,57 +2380,4 @@ bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration return (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > duration; } - -void GoalPlannerModule::GoalPlannerData::initializeOccupancyGridMap( - const PlannerData & planner_data, const GoalPlannerParameters & parameters) -{ - OccupancyGridMapParam occupancy_grid_map_param{}; - const double margin = parameters.occupancy_grid_collision_check_margin; - occupancy_grid_map_param.vehicle_shape.length = - planner_data.parameters.vehicle_length + 2 * margin; - occupancy_grid_map_param.vehicle_shape.width = planner_data.parameters.vehicle_width + 2 * margin; - occupancy_grid_map_param.vehicle_shape.base2back = - planner_data.parameters.base_link2rear + margin; - occupancy_grid_map_param.theta_size = parameters.theta_size; - occupancy_grid_map_param.obstacle_threshold = parameters.obstacle_threshold; - occupancy_grid_map->setParam(occupancy_grid_map_param); -} - -GoalPlannerModule::GoalPlannerData GoalPlannerModule::GoalPlannerData::clone() const -{ - GoalPlannerModule::GoalPlannerData gp_planner_data(planner_data, parameters); - gp_planner_data.update( - parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, - planner_data, current_status, previous_module_output, goal_searcher, vehicle_footprint); - return gp_planner_data; -} - -void GoalPlannerModule::GoalPlannerData::update( - const GoalPlannerParameters & parameters_, - const std::shared_ptr & ego_predicted_path_params_, - const std::shared_ptr & objects_filtering_params_, - const std::shared_ptr & safety_check_params_, - const PlannerData & planner_data_, const ModuleStatus & current_status_, - const BehaviorModuleOutput & previous_module_output_, - const std::shared_ptr goal_searcher_, - const tier4_autoware_utils::LinearRing2d & vehicle_footprint_) -{ - parameters = parameters_; - ego_predicted_path_params = ego_predicted_path_params_; - objects_filtering_params = objects_filtering_params_; - safety_check_params = safety_check_params_; - vehicle_footprint = vehicle_footprint_; - - planner_data = planner_data_; - planner_data.route_handler = std::make_shared(*(planner_data_.route_handler)); - current_status = current_status_; - previous_module_output = previous_module_output_; - occupancy_grid_map->setMap(*(planner_data.occupancy_grid)); - // to create a deepcopy of GoalPlanner(not GoalPlannerBase), goal_searcher_ is not enough, so - // recreate it here - goal_searcher = std::make_shared(parameters, vehicle_footprint); - // and then copy the reference goal - goal_searcher->setReferenceGoal(goal_searcher_->getReferenceGoal()); -} - } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index df91687622349..bd19871c482fc 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -90,35 +90,35 @@ struct SortByWeightedDistance }; GoalSearcher::GoalSearcher( - const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint) + const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint, + const std::shared_ptr & occupancy_grid_map) : GoalSearcherBase{parameters}, vehicle_footprint_{vehicle_footprint}, + occupancy_grid_map_{occupancy_grid_map}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } -GoalCandidates GoalSearcher::search( - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) +GoalCandidates GoalSearcher::search() { GoalCandidates goal_candidates{}; - const auto & route_handler = planner_data->route_handler; + const auto & route_handler = planner_data_->route_handler; const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; const double margin_from_boundary = parameters_.margin_from_boundary; const double lateral_offset_interval = parameters_.lateral_offset_interval; const double max_lateral_offset = parameters_.max_lateral_offset; const double ignore_distance_from_lane_start = parameters_.ignore_distance_from_lane_start; - const double vehicle_width = planner_data->parameters.vehicle_width; - const double base_link2front = planner_data->parameters.base_link2front; - const double base_link2rear = planner_data->parameters.base_link2rear; + const double vehicle_width = planner_data_->parameters.vehicle_width; + const double base_link2front = planner_data_->parameters.base_link2front; + const double base_link2rear = planner_data_->parameters.base_link2rear; const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); auto lanes = utils::getExtendedCurrentLanes( - planner_data, backward_length, forward_length, + planner_data_, backward_length, forward_length, /*forward_only_in_route*/ false); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); @@ -193,18 +193,17 @@ GoalCandidates GoalSearcher::search( goal_candidates.push_back(goal_candidate); } } - createAreaPolygons(original_search_poses, planner_data); + createAreaPolygons(original_search_poses); - update(goal_candidates, occupancy_grid_map, planner_data); + update(goal_candidates); return goal_candidates; } void GoalSearcher::countObjectsToAvoid( - GoalCandidates & goal_candidates, const PredictedObjects & objects, - const std::shared_ptr & planner_data) const + GoalCandidates & goal_candidates, const PredictedObjects & objects) const { - const auto & route_handler = planner_data->route_handler; + const auto & route_handler = planner_data_->route_handler; const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; @@ -226,7 +225,7 @@ void GoalSearcher::countObjectsToAvoid( // generate current lane center line path to check collision with objects const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); const auto current_center_line_path = std::invoke([&]() -> PathWithLaneId { const double s_start = @@ -265,19 +264,16 @@ void GoalSearcher::countObjectsToAvoid( } } -void GoalSearcher::update( - GoalCandidates & goal_candidates, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const +void GoalSearcher::update(GoalCandidates & goal_candidates) const { const auto pull_over_lane_stop_objects = goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); + *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); if (parameters_.prioritize_goals_before_objects) { - countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects, planner_data); + countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects); } if (parameters_.goal_priority == "minimum_weighted_distance") { @@ -297,7 +293,7 @@ void GoalSearcher::update( const Pose goal_pose = goal_candidate.goal_pose; // check collision with footprint - if (checkCollision(goal_pose, pull_over_lane_stop_objects, occupancy_grid_map)) { + if (checkCollision(goal_pose, pull_over_lane_stop_objects)) { goal_candidate.is_safe = false; continue; } @@ -305,10 +301,9 @@ void GoalSearcher::update( // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, + goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects, parameters_.object_recognition_collision_check_hard_margins.back(), filter_inside); - if (checkCollisionWithLongitudinalDistance( - goal_pose, target_objects, occupancy_grid_map, planner_data)) { + if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) { goal_candidate.is_safe = false; continue; } @@ -321,9 +316,7 @@ void GoalSearcher::update( // current planner_data_ and margin scale factor. // And is_safe is not updated in this function. bool GoalSearcher::isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const + const GoalCandidate & goal_candidate, const double margin_scale_factor) const { if (!parameters_.use_object_recognition) { return true; @@ -333,9 +326,9 @@ bool GoalSearcher::isSafeGoalWithMarginScaleFactor( const auto pull_over_lane_stop_objects = goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); + *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); const double margin = parameters_.object_recognition_collision_check_hard_margins.back() * margin_scale_factor; @@ -348,26 +341,23 @@ bool GoalSearcher::isSafeGoalWithMarginScaleFactor( // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, margin, + goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects, margin, filter_inside); - if (checkCollisionWithLongitudinalDistance( - goal_pose, target_objects, occupancy_grid_map, planner_data)) { + if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) { return false; } return true; } -bool GoalSearcher::checkCollision( - const Pose & pose, const PredictedObjects & objects, - const std::shared_ptr occupancy_grid_map) const +bool GoalSearcher::checkCollision(const Pose & pose, const PredictedObjects & objects) const { if (parameters_.use_occupancy_grid_for_goal_search) { - const Pose pose_grid_coords = global2local(occupancy_grid_map->getMap(), pose); + const Pose pose_grid_coords = global2local(occupancy_grid_map_->getMap(), pose); const auto idx = pose2index( - occupancy_grid_map->getMap(), pose_grid_coords, occupancy_grid_map->getParam().theta_size); + occupancy_grid_map_->getMap(), pose_grid_coords, occupancy_grid_map_->getParam().theta_size); const bool check_out_of_range = false; - if (occupancy_grid_map->detectCollision(idx, check_out_of_range)) { + if (occupancy_grid_map_->detectCollision(idx, check_out_of_range)) { return true; } } @@ -383,9 +373,7 @@ bool GoalSearcher::checkCollision( } bool GoalSearcher::checkCollisionWithLongitudinalDistance( - const Pose & ego_pose, const PredictedObjects & objects, - const std::shared_ptr occupancy_grid_map, - const std::shared_ptr & planner_data) const + const Pose & ego_pose, const PredictedObjects & objects) const { if ( parameters_.use_occupancy_grid_for_goal_search && @@ -397,22 +385,22 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( // check forward collision const Pose ego_pose_moved_forward = calcOffsetPose(ego_pose, offset, 0, 0); const Pose forward_pose_grid_coords = - global2local(occupancy_grid_map->getMap(), ego_pose_moved_forward); + global2local(occupancy_grid_map_->getMap(), ego_pose_moved_forward); const auto forward_idx = pose2index( - occupancy_grid_map->getMap(), forward_pose_grid_coords, - occupancy_grid_map->getParam().theta_size); - if (occupancy_grid_map->detectCollision(forward_idx, check_out_of_range)) { + occupancy_grid_map_->getMap(), forward_pose_grid_coords, + occupancy_grid_map_->getParam().theta_size); + if (occupancy_grid_map_->detectCollision(forward_idx, check_out_of_range)) { return true; } // check backward collision const Pose ego_pose_moved_backward = calcOffsetPose(ego_pose, -offset, 0, 0); const Pose backward_pose_grid_coords = - global2local(occupancy_grid_map->getMap(), ego_pose_moved_backward); + global2local(occupancy_grid_map_->getMap(), ego_pose_moved_backward); const auto backward_idx = pose2index( - occupancy_grid_map->getMap(), backward_pose_grid_coords, - occupancy_grid_map->getParam().theta_size); - if (occupancy_grid_map->detectCollision(backward_idx, check_out_of_range)) { + occupancy_grid_map_->getMap(), backward_pose_grid_coords, + occupancy_grid_map_->getParam().theta_size); + if (occupancy_grid_map_->detectCollision(backward_idx, check_out_of_range)) { return true; } } @@ -420,24 +408,23 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( if (parameters_.use_object_recognition) { if ( utils::calcLongitudinalDistanceFromEgoToObjects( - ego_pose, planner_data->parameters.base_link2front, planner_data->parameters.base_link2rear, - objects) < parameters_.longitudinal_margin) { + ego_pose, planner_data_->parameters.base_link2front, + planner_data_->parameters.base_link2rear, objects) < parameters_.longitudinal_margin) { return true; } } return false; } -void GoalSearcher::createAreaPolygons( - std::vector original_search_poses, const std::shared_ptr & planner_data) +void GoalSearcher::createAreaPolygons(std::vector original_search_poses) { using tier4_autoware_utils::MultiPolygon2d; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; - const double vehicle_width = planner_data->parameters.vehicle_width; - const double base_link2front = planner_data->parameters.base_link2front; - const double base_link2rear = planner_data->parameters.base_link2rear; + const double vehicle_width = planner_data_->parameters.vehicle_width; + const double base_link2front = planner_data_->parameters.base_link2front; + const double base_link2rear = planner_data_->parameters.base_link2rear; const double max_lateral_offset = parameters_.max_lateral_offset; const auto appendPointToPolygon = @@ -519,11 +506,10 @@ bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons } GoalCandidate GoalSearcher::getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates, - const std::shared_ptr & planner_data) const + const GoalCandidates & goal_candidates) const { const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); // Define a lambda function to compute the arc length for a given goal candidate. diff --git a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp index 33d1eb78e14f6..b168da61e6239 100644 --- a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -28,9 +28,11 @@ namespace behavior_path_planner { ShiftPullOver::ShiftPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker) + const LaneDepartureChecker & lane_departure_checker, + const std::shared_ptr & occupancy_grid_map) : PullOverPlannerBase{node, parameters}, lane_departure_checker_{lane_departure_checker}, + occupancy_grid_map_{occupancy_grid_map}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } From 9544e9c82c07a315daf75ec0d5e470fe15931fe0 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 15 Apr 2024 16:51:34 +0900 Subject: [PATCH 038/192] fix(intersection): detect stuck vehicle by position on detect area (#6689) Signed-off-by: Mamoru Sobue --- .../src/scene_intersection_stuck.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp index 6c9254919cac7..b26f960ec28f9 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp @@ -296,7 +296,10 @@ bool IntersectionModule::checkStuckVehicleInIntersection( // check if the footprint is in the stuck detect area const auto obj_footprint = tier4_autoware_utils::toPolygon2d(object); - const bool is_in_stuck_area = !bg::disjoint(obj_footprint, stuck_vehicle_detect_area); + // NOTE: in order not to stop too much + const bool is_in_stuck_area = bg::within( + to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), + stuck_vehicle_detect_area); if (is_in_stuck_area) { debug_data_.stuck_targets.objects.push_back(object); return true; From d5e07a8f1496c564565722774089981bd808bd8b Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 16 Apr 2024 09:52:10 +0900 Subject: [PATCH 039/192] fix(compare_map_segmentation): add intensity field (#6807) * fix(comare_map_segmentation): add intensity field Signed-off-by: badai-nguyen * fix: add intensity other compare map filter Signed-off-by: badai-nguyen --------- Signed-off-by: badai-nguyen --- ...tance_based_compare_map_filter_nodelet.cpp | 33 +++++++++++++------ ...approximate_compare_map_filter_nodelet.cpp | 32 +++++++++++++----- ...voxel_based_compare_map_filter_nodelet.cpp | 30 ++++++++++++----- ...tance_based_compare_map_filter_nodelet.cpp | 32 +++++++++++++----- 4 files changed, 91 insertions(+), 36 deletions(-) diff --git a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp index 519afa4145bcf..0f870d37c0de1 100644 --- a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp @@ -137,20 +137,33 @@ void DistanceBasedCompareMapFilterComponent::filter( std::scoped_lock lock(mutex_); stop_watch_ptr_->toc("processing_time", true); - pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - pcl::fromROSMsg(*input, *pcl_input); - pcl_output->points.reserve(pcl_input->points.size()); - - for (size_t i = 0; i < pcl_input->points.size(); ++i) { - if (distance_based_map_loader_->is_close_to_map(pcl_input->points.at(i), distance_threshold_)) { + int point_step = input->point_step; + int offset_x = input->fields[pcl::getFieldIndex(*input, "x")].offset; + int offset_y = input->fields[pcl::getFieldIndex(*input, "y")].offset; + int offset_z = input->fields[pcl::getFieldIndex(*input, "z")].offset; + + output.data.resize(input->data.size()); + output.point_step = point_step; + size_t output_size = 0; + for (size_t global_offset = 0; global_offset < input->data.size(); global_offset += point_step) { + pcl::PointXYZ point{}; + std::memcpy(&point.x, &input->data[global_offset + offset_x], sizeof(float)); + std::memcpy(&point.y, &input->data[global_offset + offset_y], sizeof(float)); + std::memcpy(&point.z, &input->data[global_offset + offset_z], sizeof(float)); + if (distance_based_map_loader_->is_close_to_map(point, distance_threshold_)) { continue; } - pcl_output->points.push_back(pcl_input->points.at(i)); + std::memcpy(&output.data[output_size], &input->data[global_offset], point_step); + output_size += point_step; } - - pcl::toROSMsg(*pcl_output, output); output.header = input->header; + output.fields = input->fields; + output.data.resize(output_size); + output.height = input->height; + output.width = output_size / point_step / output.height; + output.row_step = output_size / output.height; + output.is_bigendian = input->is_bigendian; + output.is_dense = input->is_dense; // add processing time for debug if (debug_publisher_) { diff --git a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp index 34a0f17bdb389..7ad479a6e74bd 100644 --- a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp @@ -106,19 +106,33 @@ void VoxelBasedApproximateCompareMapFilterComponent::filter( { std::scoped_lock lock(mutex_); stop_watch_ptr_->toc("processing_time", true); - pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - pcl::fromROSMsg(*input, *pcl_input); - pcl_output->points.reserve(pcl_input->points.size()); - for (size_t i = 0; i < pcl_input->points.size(); ++i) { - if (voxel_based_approximate_map_loader_->is_close_to_map( - pcl_input->points.at(i), distance_threshold_)) { + int point_step = input->point_step; + int offset_x = input->fields[pcl::getFieldIndex(*input, "x")].offset; + int offset_y = input->fields[pcl::getFieldIndex(*input, "y")].offset; + int offset_z = input->fields[pcl::getFieldIndex(*input, "z")].offset; + + output.data.resize(input->data.size()); + output.point_step = point_step; + size_t output_size = 0; + for (size_t global_offset = 0; global_offset < input->data.size(); global_offset += point_step) { + pcl::PointXYZ point{}; + std::memcpy(&point.x, &input->data[global_offset + offset_x], sizeof(float)); + std::memcpy(&point.y, &input->data[global_offset + offset_y], sizeof(float)); + std::memcpy(&point.z, &input->data[global_offset + offset_z], sizeof(float)); + if (voxel_based_approximate_map_loader_->is_close_to_map(point, distance_threshold_)) { continue; } - pcl_output->points.push_back(pcl_input->points.at(i)); + std::memcpy(&output.data[output_size], &input->data[global_offset], point_step); + output_size += point_step; } - pcl::toROSMsg(*pcl_output, output); output.header = input->header; + output.fields = input->fields; + output.data.resize(output_size); + output.height = input->height; + output.width = output_size / point_step / output.height; + output.row_step = output_size / output.height; + output.is_bigendian = input->is_bigendian; + output.is_dense = input->is_dense; // add processing time for debug if (debug_publisher_) { diff --git a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp index 82c3576dd951c..595336145dabd 100644 --- a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp @@ -67,19 +67,33 @@ void VoxelBasedCompareMapFilterComponent::filter( { std::scoped_lock lock(mutex_); stop_watch_ptr_->toc("processing_time", true); - pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - pcl::fromROSMsg(*input, *pcl_input); - pcl_output->points.reserve(pcl_input->points.size()); - for (size_t i = 0; i < pcl_input->points.size(); ++i) { - const pcl::PointXYZ point = pcl_input->points.at(i); + int point_step = input->point_step; + int offset_x = input->fields[pcl::getFieldIndex(*input, "x")].offset; + int offset_y = input->fields[pcl::getFieldIndex(*input, "y")].offset; + int offset_z = input->fields[pcl::getFieldIndex(*input, "z")].offset; + + output.data.resize(input->data.size()); + output.point_step = point_step; + size_t output_size = 0; + for (size_t global_offset = 0; global_offset < input->data.size(); global_offset += point_step) { + pcl::PointXYZ point{}; + std::memcpy(&point.x, &input->data[global_offset + offset_x], sizeof(float)); + std::memcpy(&point.y, &input->data[global_offset + offset_y], sizeof(float)); + std::memcpy(&point.z, &input->data[global_offset + offset_z], sizeof(float)); if (voxel_grid_map_loader_->is_close_to_map(point, distance_threshold_)) { continue; } - pcl_output->points.push_back(point); + std::memcpy(&output.data[output_size], &input->data[global_offset], point_step); + output_size += point_step; } - pcl::toROSMsg(*pcl_output, output); output.header = input->header; + output.fields = input->fields; + output.data.resize(output_size); + output.height = input->height; + output.width = output_size / point_step / output.height; + output.row_step = output_size / output.height; + output.is_bigendian = input->is_bigendian; + output.is_dense = input->is_dense; // add processing time for debug if (debug_publisher_) { diff --git a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp index 32e5367fbcc38..f169e2069aee7 100644 --- a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp @@ -135,20 +135,34 @@ void VoxelDistanceBasedCompareMapFilterComponent::filter( { std::scoped_lock lock(mutex_); stop_watch_ptr_->toc("processing_time", true); - pcl::PointCloud::Ptr pcl_input(new pcl::PointCloud); - pcl::PointCloud::Ptr pcl_output(new pcl::PointCloud); - pcl::fromROSMsg(*input, *pcl_input); - pcl_output->points.reserve(pcl_input->points.size()); - for (size_t i = 0; i < pcl_input->points.size(); ++i) { - if (voxel_distance_based_map_loader_->is_close_to_map( - pcl_input->points.at(i), distance_threshold_)) { + int point_step = input->point_step; + int offset_x = input->fields[pcl::getFieldIndex(*input, "x")].offset; + int offset_y = input->fields[pcl::getFieldIndex(*input, "y")].offset; + int offset_z = input->fields[pcl::getFieldIndex(*input, "z")].offset; + + output.data.resize(input->data.size()); + output.point_step = point_step; + size_t output_size = 0; + for (size_t global_offset = 0; global_offset < input->data.size(); global_offset += point_step) { + pcl::PointXYZ point{}; + std::memcpy(&point.x, &input->data[global_offset + offset_x], sizeof(float)); + std::memcpy(&point.y, &input->data[global_offset + offset_y], sizeof(float)); + std::memcpy(&point.z, &input->data[global_offset + offset_z], sizeof(float)); + if (voxel_distance_based_map_loader_->is_close_to_map(point, distance_threshold_)) { continue; } - pcl_output->points.push_back(pcl_input->points.at(i)); + std::memcpy(&output.data[output_size], &input->data[global_offset], point_step); + output_size += point_step; } - pcl::toROSMsg(*pcl_output, output); output.header = input->header; + output.fields = input->fields; + output.data.resize(output_size); + output.height = input->height; + output.width = output_size / point_step / output.height; + output.row_step = output_size / output.height; + output.is_bigendian = input->is_bigendian; + output.is_dense = input->is_dense; // add processing time for debug if (debug_publisher_) { From 729cbc6d80a1d76869e5111377db529c256b8539 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 16 Apr 2024 10:51:02 +0900 Subject: [PATCH 040/192] fix(obstacle_avoidance_planner): fix mathjax visualization error (#6813) * fix(obstacle_avoidance_planner): fix mathjax visualization error Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../obstacle_avoidance_planner/docs/mpt.md | 226 +++++++++--------- 1 file changed, 113 insertions(+), 113 deletions(-) diff --git a/planning/obstacle_avoidance_planner/docs/mpt.md b/planning/obstacle_avoidance_planner/docs/mpt.md index f8441783bf1d2..4b35fd0e36ab5 100644 --- a/planning/obstacle_avoidance_planner/docs/mpt.md +++ b/planning/obstacle_avoidance_planner/docs/mpt.md @@ -51,8 +51,8 @@ We also assume that the steer angle $\delta_k$ is first-order lag to the command $$ \begin{align} -y_{k+1} & = y_{k} + v \sin \theta_k dt \\ -\theta_{k+1} & = \theta_k + \frac{v \tan \delta_k}{L}dt - \kappa_k v \cos \theta_k dt \\ +y_{k+1} & = y_{k} + v \sin \theta_k dt \\\ +\theta_{k+1} & = \theta_k + \frac{v \tan \delta_k}{L}dt - \kappa_k v \cos \theta_k dt \\\ \delta_{k+1} & = \delta_k - \frac{\delta_k - \delta_{des,k}}{\tau}dt \end{align} $$ @@ -72,8 +72,8 @@ Therefore, we have to apply the steer angle limitation to $\delta_{\mathrm{ref}, $$ \begin{align} -\delta_{\mathrm{ref}, k} & = \mathrm{clamp}(\arctan(L \kappa_k), -\delta_{\max}, \delta_{\max}) \\ -\delta_k & = \delta_{\mathrm{ref}, k} + \Delta \delta_k, \ \Delta \delta_k \ll 1 \\ +\delta_{\mathrm{ref}, k} & = \mathrm{clamp}(\arctan(L \kappa_k), -\delta_{\max}, \delta_{\max}) \\\ +\delta_k & = \delta_{\mathrm{ref}, k} + \Delta \delta_k, \ \Delta \delta_k \ll 1 \\\ \end{align} $$ @@ -83,8 +83,8 @@ Using this $\delta_{\mathrm{ref}, k}$, $\tan \delta_k$ is linearized as follows. $$ \begin{align} -\tan \delta_k & \approx \tan \delta_{\mathrm{ref}, k} + \left.\frac{d \tan \delta}{d \delta}\right|_{\delta = \delta_{\mathrm{ref}, k}} \Delta \delta_k \\ -& = \tan \delta_{\mathrm{ref}, k} + \left.\frac{d \tan \delta}{d \delta}\right|_{\delta = \delta_{\mathrm{ref}, k}} (\delta_{\mathrm{ref}, k} - \delta_k) \\ +\tan \delta_k & \approx \tan \delta_{\mathrm{ref}, k} + \lbrace\frac{d \tan \delta}{d \delta}\rbrace|_{\delta = \delta_{\mathrm{ref}, k}} \Delta \delta_k \\\ +& = \tan \delta_{\mathrm{ref}, k} + \lbrace\frac{d \tan \delta}{d \delta}\rbrace|_{\delta = \delta_{\mathrm{ref}, k}} (\delta_{\mathrm{ref}, k} - \delta_k) \\\ & = \tan \delta_{\mathrm{ref}, k} - \frac{\delta_{\mathrm{ref}, k}}{\cos^2 \delta_{\mathrm{ref}, k}} + \frac{1}{\cos^2 \delta_{\mathrm{ref}, k}} \delta_k \end{align} $$ @@ -96,37 +96,37 @@ Based on the linearization, the error kinematics is formulated with the followin $$ \begin{align} \begin{pmatrix} - y_{k+1} \\ + y_{k+1} \\\ \theta_{k+1} \end{pmatrix} = \begin{pmatrix} - 1 & v dt \\ - 0 & 1 \\ + 1 & v dt \\\ + 0 & 1 \end{pmatrix} \begin{pmatrix} - y_k \\ - \theta_k \\ + y_k \\\ + \theta_k \end{pmatrix} + \begin{pmatrix} - 0 \\ - \frac{v dt}{L \cos^{2} \delta_{\mathrm{ref}, k}} \\ + 0 \\\ + \frac{v dt}{L \cos^{2} \delta_{\mathrm{ref}, k}} \end{pmatrix} \delta_{k} + \begin{pmatrix} - 0 \\ - \frac{v \tan(\delta_{\mathrm{ref}, k}) dt}{L} - \frac{v \delta_{\mathrm{ref}, k} dt}{L \cos^{2} \delta_{\mathrm{ref}, k}} - \kappa_k v dt\\ + 0 \\\ + \frac{v \tan(\delta_{\mathrm{ref}, k}) dt}{L} - \frac{v \delta_{\mathrm{ref}, k} dt}{L \cos^{2} \delta_{\mathrm{ref}, k}} - \kappa_k v dt \end{pmatrix} \end{align} $$ -which can be formulated as follows with the state $\boldsymbol{x}$, control input $u$ and some matrices, where $\boldsymbol{x} = (y_k, \theta_k)$ +which can be formulated as follows with the state $\mathbf{x}$, control input $u$ and some matrices, where $\mathbf{x} = (y_k, \theta_k)$ $$ \begin{align} - \boldsymbol{x}_{k+1} = A_k \boldsymbol{x}_k + \boldsymbol{b}_k u_k + \boldsymbol{w}_k + \mathbf{x}_{k+1} = A_k \mathbf{x}_k + \mathbf{b}_k u_k + \mathbf{w}_k \end{align} $$ @@ -136,7 +136,7 @@ Then, we formulate time-series state equation by concatenating states, control i $$ \begin{align} - \boldsymbol{x} = A \boldsymbol{x}_0 + B \boldsymbol{u} + \boldsymbol{w} + \mathbf{x} = A \mathbf{x}_0 + B \mathbf{u} + \mathbf{w} \end{align} $$ @@ -144,9 +144,9 @@ where $$ \begin{align} -\boldsymbol{x} = (\boldsymbol{x}^T_1, \boldsymbol{x}^T_2, \boldsymbol{x}^T_3, \dots, \boldsymbol{x}^T_{n-1})^T \\ -\boldsymbol{u} = (u_0, u_1, u_2, \dots, u_{n-2})^T \\ -\boldsymbol{w} = (\boldsymbol{w}^T_0, \boldsymbol{w}^T_1, \boldsymbol{w}^T_2, \dots, \boldsymbol{w}^T_{n-1})^T. \\ +\mathbf{x} = (\mathbf{x}^T_1, \mathbf{x}^T_2, \mathbf{x}^T_3, \dots, \mathbf{x}^T_{n-1})^T \\\ +\mathbf{u} = (u_0, u_1, u_2, \dots, u_{n-2})^T \\\ +\mathbf{w} = (\mathbf{w}^T_0, \mathbf{w}^T_1, \mathbf{w}^T_2, \dots, \mathbf{w}^T_{n-1})^T. \\\ \end{align} $$ @@ -155,63 +155,63 @@ In detail, each matrices are constructed as follows. $$ \begin{align} \begin{pmatrix} - \boldsymbol{x}_1 \\ - \boldsymbol{x}_2 \\ - \boldsymbol{x}_3 \\ - \vdots \\ - \boldsymbol{x}_{n-1} + \mathbf{x}_1 \\\ + \mathbf{x}_2 \\\ + \mathbf{x}_3 \\\ + \vdots \\\ + \mathbf{x}_{n-1} \end{pmatrix} = \begin{pmatrix} - A_0 \\ - A_1 A_0 \\ - A_2 A_1 A_0\\ - \vdots \\ + A_0 \\\ + A_1 A_0 \\\ + A_2 A_1 A_0\\\ + \vdots \\\ \prod\limits_{k=0}^{n-1} A_{k} \end{pmatrix} - \boldsymbol{x}_0 + \mathbf{x}_0 + \begin{pmatrix} - B_0 & 0 & & \dots & 0 \\ - A_0 B_0 & B_1 & 0 & \dots & 0 \\ - A_1 A_0 B_0 & A_0 B_1 & B_2 & \dots & 0 \\ - \vdots & \vdots & & \ddots & 0 \\ + B_0 & 0 & & \dots & 0 \\\ + A_0 B_0 & B_1 & 0 & \dots & 0 \\\ + A_1 A_0 B_0 & A_0 B_1 & B_2 & \dots & 0 \\\ + \vdots & \vdots & & \ddots & 0 \\\ \prod\limits_{k=0}^{n-3} A_k B_0 & \prod\limits_{k=0}^{n-4} A_k B_1 & \dots & A_0 B_{n-3} & B_{n-2} \end{pmatrix} \begin{pmatrix} - u_0 \\ - u_1 \\ - u_2 \\ - \vdots \\ + u_0 \\\ + u_1 \\\ + u_2 \\\ + \vdots \\\ u_{n-2} \end{pmatrix} + \begin{pmatrix} - I & 0 & & \dots & 0 \\ - A_0 & I & 0 & \dots & 0 \\ - A_1 A_0 & A_0 & I & \dots & 0 \\ - \vdots & \vdots & & \ddots & 0 \\ + I & 0 & & \dots & 0 \\\ + A_0 & I & 0 & \dots & 0 \\\ + A_1 A_0 & A_0 & I & \dots & 0 \\\ + \vdots & \vdots & & \ddots & 0 \\\ \prod\limits_{k=0}^{n-3} A_k & \prod\limits_{k=0}^{n-4} A_k & \dots & A_0 & I \end{pmatrix} \begin{pmatrix} - \boldsymbol{w}_0 \\ - \boldsymbol{w}_1 \\ - \boldsymbol{w}_2 \\ - \vdots \\ - \boldsymbol{w}_{n-2} + \mathbf{w}_0 \\\ + \mathbf{w}_1 \\\ + \mathbf{w}_2 \\\ + \vdots \\\ + \mathbf{w}_{n-2} \end{pmatrix} \end{align} $$ ### Free-boundary-conditioned time-series state equation -For path planning which does not start from the current ego pose, $\boldsymbol{x}_0$ should be the design variable of optimization. -Therefore, we make $\boldsymbol{u}'$ by concatenating $\boldsymbol{x}_0$ and $\boldsymbol{u}$, and redefine $\boldsymbol{x}$ as follows. +For path planning which does not start from the current ego pose, $\mathbf{x}_0$ should be the design variable of optimization. +Therefore, we make $\mathbf{u}'$ by concatenating $\mathbf{x}_0$ and $\mathbf{u}$, and redefine $\mathbf{x}$ as follows. $$ \begin{align} - \boldsymbol{u}' & = (\boldsymbol{x}^T_0, \boldsymbol{u}^T)^T \\ - \boldsymbol{x} & = (\boldsymbol{x}^T_0, \boldsymbol{x}^T_1, \boldsymbol{x}^T_2, \dots, \boldsymbol{x}^T_{n-1})^T + \mathbf{u}' & = (\mathbf{x}^T_0, \mathbf{u}^T)^T \\\ + \mathbf{x} & = (\mathbf{x}^T_0, \mathbf{x}^T_1, \mathbf{x}^T_2, \dots, \mathbf{x}^T_{n-1})^T \end{align} $$ @@ -219,7 +219,7 @@ Then we get the following state equation $$ \begin{align} - \boldsymbol{x}' = B \boldsymbol{u}' + \boldsymbol{w}, + \mathbf{x}' = B \mathbf{u}' + \mathbf{w}, \end{align} $$ @@ -228,45 +228,45 @@ which is in detail $$ \begin{align} \begin{pmatrix} - \boldsymbol{x}_0 \\ - \boldsymbol{x}_1 \\ - \boldsymbol{x}_2 \\ - \boldsymbol{x}_3 \\ - \vdots \\ - \boldsymbol{x}_{n-1} + \mathbf{x}_0 \\\ + \mathbf{x}_1 \\\ + \mathbf{x}_2 \\\ + \mathbf{x}_3 \\\ + \vdots \\\ + \mathbf{x}_{n-1} \end{pmatrix} = \begin{pmatrix} - I & 0 & \dots & & & 0 \\ - A_0 & B_0 & 0 & & \dots & 0 \\ - A_1 A_0 & A_0 B_0 & B_1 & 0 & \dots & 0 \\ - A_2 A_1 A_0 & A_1 A_0 B_0 & A_0 B_1 & B_2 & \dots & 0 \\ - \vdots & \vdots & \vdots & & \ddots & 0 \\ + I & 0 & \dots & & & 0 \\\ + A_0 & B_0 & 0 & & \dots & 0 \\\ + A_1 A_0 & A_0 B_0 & B_1 & 0 & \dots & 0 \\\ + A_2 A_1 A_0 & A_1 A_0 B_0 & A_0 B_1 & B_2 & \dots & 0 \\\ + \vdots & \vdots & \vdots & & \ddots & 0 \\\ \prod\limits_{k=0}^{n-1} A_k & \prod\limits_{k=0}^{n-3} A_k B_0 & \prod\limits_{k=0}^{n-4} A_k B_1 & \dots & A_0 B_{n-3} & B_{n-2} \end{pmatrix} \begin{pmatrix} - \boldsymbol{x}_0 \\ - u_0 \\ - u_1 \\ - u_2 \\ - \vdots \\ + \mathbf{x}_0 \\\ + u_0 \\\ + u_1 \\\ + u_2 \\\ + \vdots \\\ u_{n-2} \end{pmatrix} + \begin{pmatrix} - 0 & \dots & & & 0 \\ - I & 0 & & \dots & 0 \\ - A_0 & I & 0 & \dots & 0 \\ - A_1 A_0 & A_0 & I & \dots & 0 \\ - \vdots & \vdots & & \ddots & 0 \\ + 0 & \dots & & & 0 \\\ + I & 0 & & \dots & 0 \\\ + A_0 & I & 0 & \dots & 0 \\\ + A_1 A_0 & A_0 & I & \dots & 0 \\\ + \vdots & \vdots & & \ddots & 0 \\\ \prod\limits_{k=0}^{n-3} A_k & \prod\limits_{k=0}^{n-4} A_k & \dots & A_0 & I \end{pmatrix} \begin{pmatrix} - \boldsymbol{w}_0 \\ - \boldsymbol{w}_1 \\ - \boldsymbol{w}_2 \\ - \vdots \\ - \boldsymbol{w}_{n-2} + \mathbf{w}_0 \\\ + \mathbf{w}_1 \\\ + \mathbf{w}_2 \\\ + \vdots \\\ + \mathbf{w}_{n-2} \end{pmatrix}. \end{align} $$ @@ -277,9 +277,9 @@ The objective function for smoothing and tracking is shown as follows, which can $$ \begin{align} -J_1 (\boldsymbol{x}', \boldsymbol{u}') & = w_y \sum_{k} y_k^2 + w_{\theta} \sum_{k} \theta_k^2 + w_{\delta} \sum_k \delta_k^2 + w_{\dot{\delta}} \sum_k \dot{\delta}_k^2 + w_{\ddot{\delta}} \sum_k \ddot{\delta}_k^2 \\ -& = \boldsymbol{x}'^T Q \boldsymbol{x}' + \boldsymbol{u}'^T R \boldsymbol{u}' \\ -& = \boldsymbol{u}'^T H \boldsymbol{u}' + \boldsymbol{u}'^T \boldsymbol{f} +J_1 (\mathbf{x}', \mathbf{u}') & = w_y \sum_{k} y_k^2 + w_{\theta} \sum_{k} \theta_k^2 + w_{\delta} \sum_k \delta_k^2 + w_{\dot \delta} \sum_k \dot \delta_k^2 + w_{\ddot \delta} \sum_k \ddot \delta_k^2 \\\ +& = \mathbf{x}'^T Q \mathbf{x}' + \mathbf{u}'^T R \mathbf{u}' \\\ +& = \mathbf{u}'^T H \mathbf{u}' + \mathbf{u}'^T \mathbf{f} \end{align} $$ @@ -287,11 +287,11 @@ As mentioned before, the constraints to be collision free with obstacles and roa Assuming that the lateral distance to the road boundaries or obstacles from the back wheel center, front wheel center, and the point between them are $y_{\mathrm{base}, k}, y_{\mathrm{top}, k}, y_{\mathrm{mid}, k}$ respectively, and slack variables for each point are $\lambda_{\mathrm{base}}, \lambda_{\mathrm{top}}, \lambda_{\mathrm{mid}}$, the soft constraints can be formulated as follows. $$ -y_{\mathrm{base}, k, \min} - \lambda_{\mathrm{base}, k} \leq y_{\mathrm{base}, k} (y_k) \leq y_{\mathrm{base}, k, \max} + \lambda_{\mathrm{base}, k}\\ -y_{\mathrm{top}, k, \min} - \lambda_{\mathrm{top}, k} \leq y_{\mathrm{top}, k} (y_k) \leq y_{\mathrm{top}, k, \max} + \lambda_{\mathrm{top}, k}\\ -y_{\mathrm{mid}, k, \min} - \lambda_{\mathrm{mid}, k} \leq y_{\mathrm{mid}, k} (y_k) \leq y_{\mathrm{mid}, k, \max} + \lambda_{\mathrm{mid}, k} \\ -0 \leq \lambda_{\mathrm{base}, k} \\ -0 \leq \lambda_{\mathrm{top}, k} \\ +y_{\mathrm{base}, k, \min} - \lambda_{\mathrm{base}, k} \leq y_{\mathrm{base}, k} (y_k) \leq y_{\mathrm{base}, k, \max} + \lambda_{\mathrm{base}, k}\\\ +y_{\mathrm{top}, k, \min} - \lambda_{\mathrm{top}, k} \leq y_{\mathrm{top}, k} (y_k) \leq y_{\mathrm{top}, k, \max} + \lambda_{\mathrm{top}, k}\\\ +y_{\mathrm{mid}, k, \min} - \lambda_{\mathrm{mid}, k} \leq y_{\mathrm{mid}, k} (y_k) \leq y_{\mathrm{mid}, k, \max} + \lambda_{\mathrm{mid}, k} \\\ +0 \leq \lambda_{\mathrm{base}, k} \\\ +0 \leq \lambda_{\mathrm{top}, k} \\\ 0 \leq \lambda_{\mathrm{mid}, k} $$ @@ -299,19 +299,19 @@ Since $y_{\mathrm{base}, k}, y_{\mathrm{top}, k}, y_{\mathrm{mid}, k}$ is formul $$ \begin{align} -J_2 & (\boldsymbol{\lambda}_\mathrm{base}, \boldsymbol{\lambda}_\mathrm{top}, \boldsymbol {\lambda}_\mathrm{mid})\\ +J_2 & (\mathbf{\lambda}_\mathrm{base}, \mathbf{\lambda}_\mathrm{top}, \mathbf {\lambda}_\mathrm{mid})\\\ & = w_{\mathrm{base}} \sum_{k} \lambda_{\mathrm{base}, k} + w_{\mathrm{mid}} \sum_k \lambda_{\mathrm{mid}, k} + w_{\mathrm{top}} \sum_k \lambda_{\mathrm{top}, k} \end{align} $$ Slack variables are also design variables for optimization. -We define a vector $\boldsymbol{v}$, that concatenates all the design variables. +We define a vector $\mathbf{v}$, that concatenates all the design variables. $$ \begin{align} -\boldsymbol{v} = +\mathbf{v} = \begin{pmatrix} - \boldsymbol{u}'^T & \boldsymbol{\lambda}_\mathrm{base}^T & \boldsymbol{\lambda}_\mathrm{top}^T & \boldsymbol{\lambda}_\mathrm{mid}^T + \mathbf{u}'^T & \mathbf{\lambda}_\mathrm{base}^T & \mathbf{\lambda}_\mathrm{top}^T & \mathbf{\lambda}_\mathrm{mid}^T \end{pmatrix}^T \end{align} $$ @@ -320,7 +320,7 @@ The summation of these two objective functions is the objective function for the $$ \begin{align} -\min_{\boldsymbol{v}} J (\boldsymbol{v}) = \min_{\boldsymbol{v}} J_1 (\boldsymbol{u}') + J_2 (\boldsymbol{\lambda}_\mathrm{base}, \boldsymbol{\lambda}_\mathrm{top}, \boldsymbol{\lambda}_\mathrm{mid}) +\min_{\mathbf{v}} J (\mathbf{v}) = \min_{\mathbf{v}} J_1 (\mathbf{u}') + J_2 (\mathbf{\lambda}_\mathrm{base}, \mathbf{\lambda}_\mathrm{top}, \mathbf{\lambda}_\mathrm{mid}) \end{align} $$ @@ -337,8 +337,8 @@ Finally we transform those objective functions to the following QP problem, and $$ \begin{align} -\min_{\boldsymbol{v}} \ & \frac{1}{2} \boldsymbol{v}^T \boldsymbol{H} \boldsymbol{v} + \boldsymbol{f} \boldsymbol{v} \\ -\mathrm{s.t.} \ & \boldsymbol{b}_{lower} \leq \boldsymbol{A} \boldsymbol{v} \leq \boldsymbol{b}_{upper} +\min_{\mathbf{v}} \ & \frac{1}{2} \mathbf{v}^T \mathbf{H} \mathbf{v} + \mathbf{f} \mathbf{v} \\\ +\mathrm{s.t.} \ & \mathbf{b}_{lower} \leq \mathbf{A} \mathbf{v} \leq \mathbf{b}_{upper} \end{align} $$ @@ -382,8 +382,8 @@ Based on the following figure, $y'$ can be formulated as follows. $$ \begin{align} -y' & = L \sin(\theta + \beta) + y \cos \beta - l \sin(\gamma - \phi_a) \\ -& = L \sin \theta \cos \beta + L \cos \theta \sin \beta + y \cos \beta - l \sin(\gamma - \phi_a) \\ +y' & = L \sin(\theta + \beta) + y \cos \beta - l \sin(\gamma - \phi_a) \\\ +& = L \sin \theta \cos \beta + L \cos \theta \sin \beta + y \cos \beta - l \sin(\gamma - \phi_a) \\\ & \approx L \theta \cos \beta + L \sin \beta + y \cos \beta - l \sin(\gamma - \phi_a) \end{align} $$ @@ -394,9 +394,9 @@ $$ $$ \begin{align} -y' & = C_1 \boldsymbol{x} + C_2 \\ -& = C_1 (B \boldsymbol{v} + \boldsymbol{w}) + C_2 \\ -& = C_1 B \boldsymbol{v} + \boldsymbol{w} + C_2 +y' & = C_1 \mathbf{x} + C_2 \\\ +& = C_1 (B \mathbf{v} + \mathbf{w}) + C_2 \\\ +& = C_1 B \mathbf{v} + \mathbf{w} + C_2 \end{align} $$ @@ -408,20 +408,20 @@ $$ \begin{align} A_{blk} & = \begin{pmatrix} - C_1 B & O & \dots & O & I_{N_{ref} \times N_{ref}} & O \dots & O\\ - -C_1 B & O & \dots & O & I & O \dots & O\\ + C_1 B & O & \dots & O & I_{N_{ref} \times N_{ref}} & O \dots & O\\\ + -C_1 B & O & \dots & O & I & O \dots & O\\\ O & O & \dots & O & I & O \dots & O \end{pmatrix} - \in \boldsymbol{R}^{3 N_{ref} \times D_v + N_{circle} N_{ref}} \\ - \boldsymbol{b}_{lower, blk} & = + \in \mathbf{R}^{3 N_{ref} \times D_v + N_{circle} N_{ref}} \\\ + \mathbf{b}_{lower, blk} & = \begin{pmatrix} - \boldsymbol{b}_{lower} - C_1 \boldsymbol{w} - C_2 \\ - -\boldsymbol{b}_{upper} + C_1 \boldsymbol{w} + C_2 \\ + \mathbf{b}_{lower} - C_1 \mathbf{w} - C_2 \\\ + -\mathbf{b}_{upper} + C_1 \mathbf{w} + C_2 \\\ O \end{pmatrix} - \in \boldsymbol{R}^{3 N_{ref}} \\ - \boldsymbol{b}_{upper, blk} & = \boldsymbol{\infty} - \in \boldsymbol{R}^{3 N_{ref}} + \in \mathbf{R}^{3 N_{ref}} \\\ + \mathbf{b}_{upper, blk} & = \mathbf{\infty} + \in \mathbf{R}^{3 N_{ref}} \end{align} $$ @@ -436,11 +436,11 @@ $$ \begin{align} A_{blk} = \begin{pmatrix} - C_1 B & I_{N_{ref} \times N_{ref}} \\ - -C_1 B & I \\ + C_1 B & I_{N_{ref} \times N_{ref}} \\\ + -C_1 B & I \\\ O & I \end{pmatrix} -\in \boldsymbol{R}^{3N_{ref} \times D_v + N_{ref}} +\in \mathbf{R}^{3N_{ref} \times D_v + N_{ref}} \end{align} $$ @@ -476,8 +476,8 @@ Assume that $v_{ego}$ is the ego velocity, and $t_{fix}$ is the time to fix the $$ \begin{align} -r & = \mathrm{lerp}(w^{\mathrm{steer}}_{\mathrm{normal}}, w^{\mathrm{steer}}_{\mathrm{avoidance}}, c) \\ -w^{\mathrm{lat}} & = \mathrm{lerp}(w^{\mathrm{lat}}_{\mathrm{normal}}, w^{\mathrm{lat}}_{\mathrm{avoidance}}, r) \\ +r & = \mathrm{lerp}(w^{\mathrm{steer}}_{\mathrm{normal}}, w^{\mathrm{steer}}_{\mathrm{avoidance}}, c) \\\ +w^{\mathrm{lat}} & = \mathrm{lerp}(w^{\mathrm{lat}}_{\mathrm{normal}}, w^{\mathrm{lat}}_{\mathrm{avoidance}}, r) \\\ w^{\mathrm{yaw}} & = \mathrm{lerp}(w^{\mathrm{yaw}}_{\mathrm{normal}}, w^{\mathrm{yaw}}_{\mathrm{avoidance}}, r) \end{align} $$ From cf5a2ed247cb216fbd3f65453a673866b5f5e5c2 Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Tue, 16 Apr 2024 11:31:28 +0900 Subject: [PATCH 041/192] feat(lidar_centerpoint): output the covariance of pose and twist (#6573) * feat: postprocess variance Signed-off-by: tzhong518 * feat: output variance Signed-off-by: tzhong518 * feat: add has_variance to config Signed-off-by: tzhong518 * fix: single_inference node Signed-off-by: tzhong518 * style(pre-commit): autofix * fix: add to pointpainting param Signed-off-by: tzhong518 * Update perception/lidar_centerpoint/src/node.cpp Co-authored-by: Yoshi Ri * Update perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp Co-authored-by: Yoshi Ri * Update perception/lidar_centerpoint/src/node.cpp Co-authored-by: Yoshi Ri * fix: add options Signed-off-by: tzhong518 * fix: avoid powf Signed-off-by: tzhong518 * Update launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml Co-authored-by: Taekjin LEE --------- Signed-off-by: tzhong518 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yoshi Ri Co-authored-by: Taekjin LEE --- .../detector/lidar_dnn_detector.launch.xml | 2 +- .../launch/perception.launch.xml | 2 +- .../config/pointpainting.param.yaml | 1 + .../pointpainting_fusion/node.hpp | 1 + .../schema/pointpainting.schema.json | 5 +++ .../src/pointpainting_fusion/node.cpp | 5 +-- .../config/centerpoint.param.yaml | 1 + .../config/centerpoint_sigma.param.yaml | 27 ++++++++++++++++ .../config/centerpoint_tiny.param.yaml | 1 + .../lidar_centerpoint/centerpoint_config.hpp | 22 +++++++++---- .../include/lidar_centerpoint/node.hpp | 1 + .../include/lidar_centerpoint/ros_utils.hpp | 6 +++- .../include/lidar_centerpoint/utils.hpp | 11 +++++++ .../lib/postprocess/postprocess_kernel.cu | 32 +++++++++++++++++-- .../lidar_centerpoint/lib/ros_utils.cpp | 30 ++++++++++++++++- perception/lidar_centerpoint/src/node.cpp | 7 ++-- 16 files changed, 137 insertions(+), 17 deletions(-) create mode 100644 perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index f9b65fd5c30eb..ab89da7112b66 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index c6213ee313c2b..d9e18e76bc4c4 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -36,7 +36,7 @@ - + diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index 3abaffb243d96..53ac6f4cafc28 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -16,6 +16,7 @@ downsample_factor: 1 encoder_in_feature_size: 12 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_variance: false has_twist: false densification_params: world_frame_id: "map" diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp index 78ae152141a00..c39dd7ac8bc33 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -60,6 +60,7 @@ class PointPaintingFusionNode std::map class_index_; std::map> isClassTable_; std::vector pointcloud_range; + bool has_variance_{false}; bool has_twist_{false}; centerpoint::NonMaximumSuppression iou_bev_nms_; diff --git a/perception/image_projection_based_fusion/schema/pointpainting.schema.json b/perception/image_projection_based_fusion/schema/pointpainting.schema.json index 036628d72e70a..bc8f0512263b6 100644 --- a/perception/image_projection_based_fusion/schema/pointpainting.schema.json +++ b/perception/image_projection_based_fusion/schema/pointpainting.schema.json @@ -60,6 +60,11 @@ "minimum": 0.0, "maximum": 1.0 }, + "has_variance": { + "type": "boolean", + "description": "Indicates whether the model outputs variance value.", + "default": false + }, "has_twist": { "type": "boolean", "description": "Indicates whether the model outputs twist value.", diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 14783a46ba8b4..c4c5941be5fec 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -140,6 +140,7 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt isClassTable_.erase(cls); } } + has_variance_ = this->declare_parameter("has_variance"); has_twist_ = this->declare_parameter("model_params.has_twist"); const std::size_t point_feature_size = static_cast( this->declare_parameter("model_params.point_feature_size")); @@ -189,7 +190,7 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt centerpoint::CenterPointConfig config( class_names_.size(), point_feature_size, max_voxel_size, pointcloud_range, voxel_size, downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold, - yaw_norm_thresholds); + yaw_norm_thresholds, has_variance_); // create detector detector_ptr_ = std::make_unique( @@ -401,7 +402,7 @@ void PointPaintingFusionNode::postprocess(sensor_msgs::msg::PointCloud2 & painte raw_objects.reserve(det_boxes3d.size()); for (const auto & box3d : det_boxes3d) { autoware_auto_perception_msgs::msg::DetectedObject obj; - box3DToDetectedObject(box3d, class_names_, has_twist_, obj); + box3DToDetectedObject(box3d, class_names_, has_twist_, has_variance_, obj); raw_objects.emplace_back(obj); } diff --git a/perception/lidar_centerpoint/config/centerpoint.param.yaml b/perception/lidar_centerpoint/config/centerpoint.param.yaml index a9c3174846d0d..38c57285e552d 100644 --- a/perception/lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint.param.yaml @@ -14,6 +14,7 @@ iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] score_threshold: 0.35 + has_variance: false has_twist: false trt_precision: fp16 densification_num_past_frames: 1 diff --git a/perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml b/perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml new file mode 100644 index 0000000000000..c217f6321381a --- /dev/null +++ b/perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml @@ -0,0 +1,27 @@ +/**: + ros__parameters: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 4 + max_voxel_size: 40000 + point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] + voxel_size: [0.32, 0.32, 10.0] + downsample_factor: 1 + encoder_in_feature_size: 9 + # post-process params + circle_nms_dist_threshold: 0.5 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + score_threshold: 0.35 + has_variance: true + has_twist: true + trt_precision: fp16 + densification_num_past_frames: 1 + densification_world_frame_id: map + + # weight files + encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx" + encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine" + head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx" + head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine" diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml index 474d0e2b695ac..35e11e61e9634 100644 --- a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -14,6 +14,7 @@ iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] score_threshold: 0.35 + has_variance: false has_twist: false trt_precision: fp16 densification_num_past_frames: 1 diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_config.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_config.hpp index 363184ecacfa9..19fdbe7a8b9c2 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_config.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_config.hpp @@ -28,7 +28,7 @@ class CenterPointConfig const std::vector & point_cloud_range, const std::vector & voxel_size, const std::size_t downsample_factor, const std::size_t encoder_in_feature_size, const float score_threshold, const float circle_nms_dist_threshold, - const std::vector yaw_norm_thresholds) + const std::vector yaw_norm_thresholds, const bool has_variance) { class_size_ = class_size; point_feature_size_ = point_feature_size; @@ -49,6 +49,15 @@ class CenterPointConfig downsample_factor_ = downsample_factor; encoder_in_feature_size_ = encoder_in_feature_size; + if (has_variance) { + has_variance_ = true; + head_out_offset_size_ = 4; + head_out_z_size_ = 2; + head_out_dim_size_ = 6; + head_out_rot_size_ = 4; + head_out_vel_size_ = 4; + } + if (score_threshold > 0 && score_threshold < 1) { score_threshold_ = score_threshold; } @@ -97,11 +106,12 @@ class CenterPointConfig std::size_t encoder_in_feature_size_{9}; const std::size_t encoder_out_feature_size_{32}; const std::size_t head_out_size_{6}; - const std::size_t head_out_offset_size_{2}; - const std::size_t head_out_z_size_{1}; - const std::size_t head_out_dim_size_{3}; - const std::size_t head_out_rot_size_{2}; - const std::size_t head_out_vel_size_{2}; + bool has_variance_{false}; + std::size_t head_out_offset_size_{2}; + std::size_t head_out_z_size_{1}; + std::size_t head_out_dim_size_{3}; + std::size_t head_out_rot_size_{2}; + std::size_t head_out_vel_size_{2}; // post-process params float score_threshold_{0.35f}; diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp index 963579e5763c2..d9740df515db2 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp @@ -53,6 +53,7 @@ class LidarCenterPointNode : public rclcpp::Node float score_threshold_{0.0}; std::vector class_names_; + bool has_variance_{false}; bool has_twist_{false}; NonMaximumSuppression iou_bev_nms_; diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp index 69b75b614498e..4eb4318c4f3f9 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/ros_utils.hpp @@ -32,10 +32,14 @@ namespace centerpoint void box3DToDetectedObject( const Box3D & box3d, const std::vector & class_names, const bool has_twist, - autoware_auto_perception_msgs::msg::DetectedObject & obj); + const bool has_variance, autoware_auto_perception_msgs::msg::DetectedObject & obj); uint8_t getSemanticType(const std::string & class_name); +std::array convertPoseCovarianceMatrix(const Box3D & box3d); + +std::array convertTwistCovarianceMatrix(const Box3D & box3d); + bool isCarLikeVehicleLabel(const uint8_t label); } // namespace centerpoint diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/utils.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/utils.hpp index 84462bc9657ac..f3dd30f754989 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/utils.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/utils.hpp @@ -33,6 +33,17 @@ struct Box3D float yaw; float vel_x; float vel_y; + + // variance + float x_variance; + float y_variance; + float z_variance; + float length_variance; + float width_variance; + float height_variance; + float yaw_variance; + float vel_x_variance; + float vel_y_variance; }; // cspell: ignore divup diff --git a/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu b/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu index ea2111862759a..34bbd2811041c 100644 --- a/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/postprocess/postprocess_kernel.cu @@ -58,7 +58,7 @@ __global__ void generateBoxes3D_kernel( const float * out_rot, const float * out_vel, const float voxel_size_x, const float voxel_size_y, const float range_min_x, const float range_min_y, const std::size_t down_grid_size_x, const std::size_t down_grid_size_y, const std::size_t downsample_factor, const int class_size, - const float * yaw_norm_thresholds, Box3D * det_boxes3d) + const bool has_variance, const float * yaw_norm_thresholds, Box3D * det_boxes3d) { // generate boxes3d from the outputs of the network. // shape of out_*: (N, DOWN_GRID_SIZE_Y, DOWN_GRID_SIZE_X) @@ -107,6 +107,34 @@ __global__ void generateBoxes3D_kernel( det_boxes3d[idx].yaw = atan2f(yaw_sin, yaw_cos); det_boxes3d[idx].vel_x = vel_x; det_boxes3d[idx].vel_y = vel_y; + + if (has_variance) { + const float offset_x_variance = out_offset[down_grid_size * 2 + idx]; + const float offset_y_variance = out_offset[down_grid_size * 3 + idx]; + const float z_variance = out_z[down_grid_size * 1 + idx]; + const float w_variance = out_dim[down_grid_size * 3 + idx]; + const float l_variance = out_dim[down_grid_size * 4 + idx]; + const float h_variance = out_dim[down_grid_size * 5 + idx]; + const float yaw_sin_log_variance = out_rot[down_grid_size * 2 + idx]; + const float yaw_cos_log_variance = out_rot[down_grid_size * 3 + idx]; + const float vel_x_variance = out_vel[down_grid_size * 2 + idx]; + const float vel_y_variance = out_vel[down_grid_size * 3 + idx]; + + det_boxes3d[idx].x_variance = voxel_size_x * downsample_factor * expf(offset_x_variance); + det_boxes3d[idx].y_variance = voxel_size_x * downsample_factor * expf(offset_y_variance); + det_boxes3d[idx].z_variance = expf(z_variance); + det_boxes3d[idx].length_variance = expf(l_variance); + det_boxes3d[idx].width_variance = expf(w_variance); + det_boxes3d[idx].height_variance = expf(h_variance); + const float yaw_sin_sq = yaw_sin * yaw_sin; + const float yaw_cos_sq = yaw_cos * yaw_cos; + const float yaw_norm_sq = (yaw_sin_sq + yaw_cos_sq) * (yaw_sin_sq + yaw_cos_sq); + det_boxes3d[idx].yaw_variance = + (yaw_cos_sq * expf(yaw_sin_log_variance) + yaw_sin_sq * expf(yaw_cos_log_variance)) / + yaw_norm_sq; + det_boxes3d[idx].vel_x_variance = expf(vel_x_variance); + det_boxes3d[idx].vel_y_variance = expf(vel_y_variance); + } } PostProcessCUDA::PostProcessCUDA(const CenterPointConfig & config) : config_(config) @@ -131,7 +159,7 @@ cudaError_t PostProcessCUDA::generateDetectedBoxes3D_launch( out_heatmap, out_offset, out_z, out_dim, out_rot, out_vel, config_.voxel_size_x_, config_.voxel_size_y_, config_.range_min_x_, config_.range_min_y_, config_.down_grid_size_x_, config_.down_grid_size_y_, config_.downsample_factor_, config_.class_size_, - thrust::raw_pointer_cast(yaw_norm_thresholds_d_.data()), + config_.has_variance_, thrust::raw_pointer_cast(yaw_norm_thresholds_d_.data()), thrust::raw_pointer_cast(boxes3d_d_.data())); // suppress by score diff --git a/perception/lidar_centerpoint/lib/ros_utils.cpp b/perception/lidar_centerpoint/lib/ros_utils.cpp index 6bb788ec097b5..c4fb4abd8d753 100644 --- a/perception/lidar_centerpoint/lib/ros_utils.cpp +++ b/perception/lidar_centerpoint/lib/ros_utils.cpp @@ -25,7 +25,7 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; void box3DToDetectedObject( const Box3D & box3d, const std::vector & class_names, const bool has_twist, - autoware_auto_perception_msgs::msg::DetectedObject & obj) + const bool has_variance, autoware_auto_perception_msgs::msg::DetectedObject & obj) { // TODO(yukke42): the value of classification confidence of DNN, not probability. obj.existence_probability = box3d.score; @@ -58,6 +58,10 @@ void box3DToDetectedObject( obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; obj.shape.dimensions = tier4_autoware_utils::createTranslation(box3d.length, box3d.width, box3d.height); + if (has_variance) { + obj.kinematics.has_position_covariance = has_variance; + obj.kinematics.pose_with_covariance.covariance = convertPoseCovarianceMatrix(box3d); + } // twist if (has_twist) { @@ -68,6 +72,10 @@ void box3DToDetectedObject( twist.angular.z = 2 * (std::atan2(vel_y, vel_x) - yaw); obj.kinematics.twist_with_covariance.twist = twist; obj.kinematics.has_twist = has_twist; + if (has_variance) { + obj.kinematics.has_twist_covariance = has_variance; + obj.kinematics.twist_with_covariance.covariance = convertTwistCovarianceMatrix(box3d); + } } } @@ -92,4 +100,24 @@ uint8_t getSemanticType(const std::string & class_name) } } +std::array convertPoseCovarianceMatrix(const Box3D & box3d) +{ + using POSE_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + std::array pose_covariance{}; + pose_covariance[POSE_IDX::X_X] = box3d.x_variance; + pose_covariance[POSE_IDX::Y_Y] = box3d.y_variance; + pose_covariance[POSE_IDX::Z_Z] = box3d.z_variance; + pose_covariance[POSE_IDX::YAW_YAW] = box3d.yaw_variance; + return pose_covariance; +} + +std::array convertTwistCovarianceMatrix(const Box3D & box3d) +{ + using POSE_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; + std::array twist_covariance{}; + twist_covariance[POSE_IDX::X_X] = box3d.vel_x_variance; + twist_covariance[POSE_IDX::Y_Y] = box3d.vel_y_variance; + return twist_covariance; +} + } // namespace centerpoint diff --git a/perception/lidar_centerpoint/src/node.cpp b/perception/lidar_centerpoint/src/node.cpp index 65bdafe94fe7d..0606a2ec55c9e 100644 --- a/perception/lidar_centerpoint/src/node.cpp +++ b/perception/lidar_centerpoint/src/node.cpp @@ -55,7 +55,8 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti const std::string head_onnx_path = this->declare_parameter("head_onnx_path"); const std::string head_engine_path = this->declare_parameter("head_engine_path"); class_names_ = this->declare_parameter>("class_names"); - has_twist_ = this->declare_parameter("has_twist", false); + has_variance_ = this->declare_parameter("has_variance"); + has_twist_ = this->declare_parameter("has_twist"); const std::size_t point_feature_size = static_cast(this->declare_parameter("point_feature_size")); const std::size_t max_voxel_size = @@ -102,7 +103,7 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti CenterPointConfig config( class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size, downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold, - yaw_norm_thresholds); + yaw_norm_thresholds, has_variance_); detector_ptr_ = std::make_unique(encoder_param, head_param, densification_param, config); @@ -152,7 +153,7 @@ void LidarCenterPointNode::pointCloudCallback( raw_objects.reserve(det_boxes3d.size()); for (const auto & box3d : det_boxes3d) { autoware_auto_perception_msgs::msg::DetectedObject obj; - box3DToDetectedObject(box3d, class_names_, has_twist_, obj); + box3DToDetectedObject(box3d, class_names_, has_twist_, has_variance_, obj); raw_objects.emplace_back(obj); } From 5ef57580d2d35e47f172653f47b6c66f10a80a63 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 16 Apr 2024 16:16:29 +0900 Subject: [PATCH 042/192] feat(perception_online_evaluator): add predicted path variance (#6793) * feat(perception_online_evaluator): add predicted path variance Signed-off-by: kosuke55 * add unit test Signed-off-by: kosuke55 * update readme Signed-off-by: kosuke55 * pre commit Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../CMakeLists.txt | 1 + .../perception_online_evaluator/README.md | 51 + .../images/path_deviation.drawio.svg | 534 ++++++++ .../path_deviation_each_object.drawio.svg | 1208 +++++++++++++++++ .../metrics/metric.hpp | 6 + .../metrics_calculator.hpp | 2 +- .../src/metrics_calculator.cpp | 82 +- .../src/utils/marker_utils.cpp | 2 +- .../test_perception_online_evaluator_node.cpp | 141 +- 9 files changed, 1995 insertions(+), 32 deletions(-) create mode 100644 evaluator/perception_online_evaluator/images/path_deviation.drawio.svg create mode 100644 evaluator/perception_online_evaluator/images/path_deviation_each_object.drawio.svg diff --git a/evaluator/perception_online_evaluator/CMakeLists.txt b/evaluator/perception_online_evaluator/CMakeLists.txt index f9cc0f4fa256c..e1cd0546ea94a 100644 --- a/evaluator/perception_online_evaluator/CMakeLists.txt +++ b/evaluator/perception_online_evaluator/CMakeLists.txt @@ -31,6 +31,7 @@ target_link_libraries(${PROJECT_NAME}_node glog::glog) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_perception_online_evaluator_node.cpp + TIMEOUT 180 ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}_node diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index 7c2179239221e..4fcd4fdf9cc84 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -13,6 +13,57 @@ This module allows for the evaluation of how accurately perception results are g - Calculates yaw deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of yaw recognition. - Calculates yaw rate based on the yaw of the object received in the previous cycle to evaluate the stability of the yaw rate recognition. +### Predicted Path Deviation / Predicted Path Deviation Variance + +Compare the predicted path of past objects with their actual traveled path to determine the deviation. For each object, calculate the mean distance between the predicted path points and the corresponding points on the actual path, up to the specified time step. In other words, this calculates the Average Displacement Error (ADE). The target object to be evaluated is the object from $T_N$ seconds ago, where $T_N$ is the maximum value of the prediction time horizon $[T_1, T_2, ..., T_N]$. + +![path_deviation_each_object](./images/path_deviation_each_object.drawio.svg) + +$$ +\begin{align} +n_{points} = T / dt \\ +ADE = \Sigma_{i=1}^{n_{points}} d_i / n_{points} \\ +Var = \Sigma_{i=1}^{n_{points}} (d_i - ADE)^2 / n_{points} +\end{align} +$$ + +- $n_{points}$ : Number of points in the predicted path +- $T$ : Time horizon for prediction evaluation. +- $dt$ : Time interval of the predicted path +- $d_i$ : Distance between the predicted path and the actual traveled path at path point $i$ +- $ADE$ : Mean deviation of the predicted path for the target object. +- $Var$ : Variance of the predicted path deviation for the target object. + +The final predicted path deviation metrics are calculated by averaging the mean deviation of the predicted path for all objects of the same class, and then calculating the mean, maximum, and minimum values of the mean deviation. + +![path_deviation](./images/path_deviation.drawio.svg) + +$$ +\begin{align} +ADE_{mean} = \Sigma_{j=1}^{n_{objects}} ADE_j / n_{objects} \\ +ADE_{max} = max(ADE_j) \\ +ADE_{min} = min(ADE_j) +\end{align} +$$ + +$$ +\begin{align} +Var_{mean} = \Sigma_{j=1}^{n_{objects}} Var_j / n_{objects} \\ +Var_{max} = max(Var_j) \\ +Var_{min} = min(Var_j) +\end{align} +$$ + +- $n_{objects}$ : Number of objects +- $ADE_{mean}$ : Mean deviation of the predicted path through all objects +- $ADE_{max}$ : Maximum deviation of the predicted path through all objects +- $ADE_{min}$ : Minimum deviation of the predicted path through all objects +- $Var_{mean}$ : Mean variance of the predicted path deviation through all objects +- $Var_{max}$ : Maximum variance of the predicted path deviation through all objects +- $Var_{min}$ : Minimum variance of the predicted path deviation through all objects + +The actual metric name is determined by the object class and time horizon. For example, `predicted_path_deviation_variance_CAR_5.00` + ## Inputs / Outputs | Name | Type | Description | diff --git a/evaluator/perception_online_evaluator/images/path_deviation.drawio.svg b/evaluator/perception_online_evaluator/images/path_deviation.drawio.svg new file mode 100644 index 0000000000000..0ff07f2808ea4 --- /dev/null +++ b/evaluator/perception_online_evaluator/images/path_deviation.drawio.svg @@ -0,0 +1,534 @@ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `\object_1` +
+
+ + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `\object_2` +
+
+ + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `\object_j` +
+
+ + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `ADE_1` +
+
+ + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `ADE_2` +
+
+ + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `ADE_j` +
+
+ + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/evaluator/perception_online_evaluator/images/path_deviation_each_object.drawio.svg b/evaluator/perception_online_evaluator/images/path_deviation_each_object.drawio.svg new file mode 100644 index 0000000000000..39a69b5f198e9 --- /dev/null +++ b/evaluator/perception_online_evaluator/images/path_deviation_each_object.drawio.svg @@ -0,0 +1,1208 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ past predicted path +
+
+
+
+ past predicted path +
+
+
+ + + + + + + +
+
+
+ dt +
+
+
+
+ dt +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + = dt * k +
+
+
+
+ `T_k` = dt... +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + = dt * n +
+
+
+
+ `T_n` = dt... +
+
+
+ + + + + + + + + + + + + +
+
+
+ actual traveled path +
+
+
+
+ actual traveled path +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `d_1` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `d_k` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `d_n` +
+
+
+ + + + + + + +
+
+
+ object at + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ object at `T_{now} - T_N` +
+
+
+ + + + + + + +
+
+
+ object at + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ object at `T_{now}` +
+
+
+ + + + + + + +
+
+
+ prediction_time_horizons = + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ s.t. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ prediction_time_horizons = `[T_1, T_2, ... , T... +
+
+
+ + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `ADE_{T_k} = 1/k \Sigma_1^k d_i` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `ADE_{T_n} = 1/n \Sigma_1^n d_i` +
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ dt * 2 +
+
+
+
+ dt * 2 +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `d_2` +
+
+
+
+
diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp index f5dee74828424..e11ae89e48106 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp @@ -37,6 +37,12 @@ enum class Metric { using MetricStatMap = std::unordered_map>; +struct PredictedPathDeviationMetrics +{ + Stat mean; + Stat variance; +}; + static const std::unordered_map str_to_metric = { {"lateral_deviation", Metric::lateral_deviation}, {"yaw_deviation", Metric::yaw_deviation}, diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp index f6566326ba979..ee0a1eac73762 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp @@ -126,7 +126,7 @@ class MetricsCalculator MetricStatMap calcLateralDeviationMetrics(const ClassObjectsMap & class_objects_map) const; MetricStatMap calcYawDeviationMetrics(const ClassObjectsMap & class_objects_map) const; MetricStatMap calcPredictedPathDeviationMetrics(const ClassObjectsMap & class_objects_map) const; - Stat calcPredictedPathDeviationMetrics( + PredictedPathDeviationMetrics calcPredictedPathDeviationMetrics( const PredictedObjects & objects, const double time_horizon) const; MetricStatMap calcYawRateMetrics(const ClassObjectsMap & class_objects_map) const; diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index 4b882bb8b2e68..c31a7f22d16c4 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -152,11 +152,17 @@ std::optional MetricsCalculator::getClosestObjectIterato std::optional MetricsCalculator::getObjectByStamp( const std::string uuid, const rclcpp::Time stamp) const { + constexpr double eps = 0.01; + constexpr double close_time_threshold = 0.1; + const auto obj_it_opt = getClosestObjectIterator(uuid, stamp); if (obj_it_opt.has_value()) { const auto it = obj_it_opt.value(); - if (it->first == getClosestStamp(stamp)) { - return it->second; + if (std::abs((it->first - getClosestStamp(stamp)).seconds()) < eps) { + const double time_diff = std::abs((it->first - stamp).seconds()); + if (time_diff < close_time_threshold) { + return it->second; + } } } return std::nullopt; @@ -256,31 +262,34 @@ MetricStatMap MetricsCalculator::calcPredictedPathDeviationMetrics( MetricStatMap metric_stat_map{}; for (const auto & [label, objects] : class_objects_map) { for (const double time_horizon : time_horizons) { - const auto stat = calcPredictedPathDeviationMetrics(objects, time_horizon); + const auto metrics = calcPredictedPathDeviationMetrics(objects, time_horizon); std::ostringstream stream; stream << std::fixed << std::setprecision(2) << time_horizon; std::string time_horizon_str = stream.str(); metric_stat_map - ["predicted_path_deviation_" + convertLabelToString(label) + "_" + time_horizon_str] = stat; + ["predicted_path_deviation_" + convertLabelToString(label) + "_" + time_horizon_str] = + metrics.mean; + metric_stat_map + ["predicted_path_deviation_variance_" + convertLabelToString(label) + "_" + + time_horizon_str] = metrics.variance; } } return metric_stat_map; } -Stat MetricsCalculator::calcPredictedPathDeviationMetrics( +PredictedPathDeviationMetrics MetricsCalculator::calcPredictedPathDeviationMetrics( const PredictedObjects & objects, const double time_horizon) const { - // For each object, select the predicted path that is closest to the history path and store the - // distance to the history path + // Step 1: For each object and its predicted paths, calculate the deviation between each predicted + // path pose and the corresponding historical path pose. Store the deviations in + // deviation_map_for_paths. std::unordered_map>> deviation_map_for_paths; - // For debugging. Save the pairs of predicted path pose and history path pose. - // Visualize the correspondence in rviz from the node. + + // For debugging: Save the pairs of predicted path pose and history path pose. std::unordered_map>> debug_predicted_path_pairs_map; - // Find the corresponding pose in the history path for each pose of the predicted path of each - // object, and record the distances const auto stamp = objects.header.stamp; for (const auto & object : objects.objects) { const auto uuid = tier4_autoware_utils::toHexString(object.object_id); @@ -309,30 +318,36 @@ Stat MetricsCalculator::calcPredictedPathDeviationMetrics( const double distance = tier4_autoware_utils::calcDistance2d(p.position, history_pose.position); deviation_map_for_paths[uuid][i].push_back(distance); - // debug + + // Save debug information debug_predicted_path_pairs_map[path_id].push_back(std::make_pair(p, history_pose)); } } } - // Select the predicted path with the smallest deviation for each object + // Step 2: For each object, select the predicted path with the smallest mean deviation. + // Store the selected path's deviations in deviation_map_for_objects. std::unordered_map> deviation_map_for_objects; for (const auto & [uuid, deviation_map] : deviation_map_for_paths) { - size_t min_deviation_index = 0; - double min_sum_deviation = std::numeric_limits::max(); + std::optional> min_deviation; for (const auto & [i, deviations] : deviation_map) { if (deviations.empty()) { continue; } const double sum = std::accumulate(deviations.begin(), deviations.end(), 0.0); - if (sum < min_sum_deviation) { - min_sum_deviation = sum; - min_deviation_index = i; + const double mean = sum / deviations.size(); + if (!min_deviation.has_value() || mean < min_deviation.value().second) { + min_deviation = std::make_pair(i, mean); } } - deviation_map_for_objects[uuid] = deviation_map.at(min_deviation_index); - // debug: save the delayed target object and the corresponding predicted path + if (!min_deviation.has_value()) { + continue; + } + + // Save the delayed target object and the corresponding predicted path for debugging + const auto [min_deviation_index, min_mean_deviation] = min_deviation.value(); + deviation_map_for_objects[uuid] = deviation_map.at(min_deviation_index); const auto path_id = uuid + "_" + std::to_string(min_deviation_index); const auto target_stamp_object = getObjectByStamp(uuid, stamp); if (target_stamp_object.has_value()) { @@ -343,17 +358,26 @@ Stat MetricsCalculator::calcPredictedPathDeviationMetrics( } } - // Store the deviation as a metric - Stat stat; - for (const auto & [uuid, deviations] : deviation_map_for_objects) { - if (deviations.empty()) { - continue; - } - for (const auto & deviation : deviations) { - stat.add(deviation); + // Step 3: Calculate the mean and variance of the deviations for each object's selected predicted + // path. Store the results in the PredictedPathDeviationMetrics structure. + PredictedPathDeviationMetrics metrics; + for (const auto & [object_id, object_path_deviations] : deviation_map_for_objects) { + if (!object_path_deviations.empty()) { + const double sum_of_deviations = + std::accumulate(object_path_deviations.begin(), object_path_deviations.end(), 0.0); + const double mean_deviation = sum_of_deviations / object_path_deviations.size(); + metrics.mean.add(mean_deviation); + double sum_of_squared_deviations = 0.0; + for (const auto path_point_deviation : object_path_deviations) { + sum_of_squared_deviations += std::pow(path_point_deviation - mean_deviation, 2); + } + const double variance_deviation = sum_of_squared_deviations / object_path_deviations.size(); + + metrics.variance.add(variance_deviation); } } - return stat; + + return metrics; } MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & class_objects_map) const diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp index a29e1a468e983..523e11883e755 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp @@ -119,7 +119,7 @@ MarkerArray createDeviationLines( for (size_t i = 0; i < max_idx; ++i) { auto marker = createDefaultMarker( "map", rclcpp::Clock{RCL_ROS_TIME}.now(), ns, first_id + i, Marker::LINE_STRIP, - createMarkerScale(0.005, 0.0, 0.0), createMarkerColor(r, g, b, 0.5)); + createMarkerScale(0.01, 0.0, 0.0), createMarkerColor(r, g, b, 0.5)); marker.points.push_back(poses1.at(i).position); marker.points.push_back(poses2.at(i).position); msg.markers.push_back(marker); diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index dabd17b9db46a..8f8cd4ac896fe 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -497,7 +497,7 @@ TEST_F(EvalTest, testYawDeviation_deviation0_PEDESTRIAN) } // ========================================================================================== -// predicted path deviation{ +// predicted path deviation TEST_F(EvalTest, testPredictedPathDeviation_deviation0) { waitForDummyNode(); @@ -585,6 +585,145 @@ TEST_F(EvalTest, testPredictedPathDeviation_deviation0_PEDESTRIAN) } // ========================================================================================== +// ========================================================================================== +// predicted path deviation variance +TEST_F(EvalTest, testPredictedPathDeviationVariance_deviation0) +{ + waitForDummyNode(); + + setTargetMetric("predicted_path_deviation_variance_CAR_5.00"); + + const auto init_objects = makeStraightPredictedObjects(0); + publishObjects(init_objects); + + const double deviation = 0.0; + for (double time = time_step_; time < time_delay_; time += time_step_) { + const auto objects = makeDeviatedStraightPredictedObjects(time, deviation); + publishObjects(objects); + } + const auto last_objects = makeDeviatedStraightPredictedObjects(time_delay_, deviation); + + EXPECT_NEAR(publishObjectsAndGetMetric(last_objects), 0.0, epsilon); +} + +TEST_F(EvalTest, testPredictedPathDeviationVariance_deviation1) +{ + waitForDummyNode(); + + setTargetMetric("predicted_path_deviation_variance_CAR_5.00"); + + const auto init_objects = makeStraightPredictedObjects(0); + publishObjects(init_objects); + + const double deviation = 1.0; + for (double time = time_step_; time < time_delay_; time += time_step_) { + const auto objects = makeDeviatedStraightPredictedObjects(time, deviation); + publishObjects(objects); + } + const auto last_objects = makeDeviatedStraightPredictedObjects(time_delay_, deviation); + + const double num_points = time_delay_ / time_step_ + 1; + // deviations + // All - 11 points (num_points) + // 0.0[m] - 1 points + // 1.0[m] - 10 points + const double mean_deviation = deviation * (num_points - 1) / num_points; + const double variance = + (pow(0.0 - mean_deviation, 2) + 10 * pow(1.0 - mean_deviation, 2)) / num_points; + + EXPECT_NEAR(publishObjectsAndGetMetric(last_objects), variance, epsilon); +} + +TEST_F(EvalTest, testPredictedPathDeviationVariance_deviationIncreasing) +{ + waitForDummyNode(); + + setTargetMetric("predicted_path_deviation_variance_CAR_5.00"); + + const auto init_objects = makeStraightPredictedObjects(0); + publishObjects(init_objects); + + const double deviation_step = 0.1; + double deviation = deviation_step; + for (double time = time_step_; time < time_delay_; time += time_step_) { + const auto objects = makeDeviatedStraightPredictedObjects(time, deviation); + publishObjects(objects); + deviation += deviation_step; + } + const auto last_objects = makeDeviatedStraightPredictedObjects(time_delay_, deviation); + + const double num_points = time_delay_ / time_step_ + 1; + // deviations + // All - 11 points (num_points) + // 0.0[m] - 1 points + // 0.1[m] - 1 points + // 0.2[m] - 1 points + // : + // 0.9[m] - 1 points + // 1.0[m] - 1 points + const double mean_deviation = std::invoke([&]() { + double sum = 0.0; + for (size_t i = 0; i < num_points; ++i) { + sum += static_cast(i) * deviation_step; + } + return sum / num_points; + }); + double sum_squared_deviations = 0.0; + for (size_t i = 0; i < num_points; ++i) { + const double deviation = static_cast(i) * deviation_step; + sum_squared_deviations += pow(deviation - mean_deviation, 2); + } + const double variance = sum_squared_deviations / num_points; + + EXPECT_NEAR(publishObjectsAndGetMetric(last_objects), variance, epsilon); +} + +TEST_F(EvalTest, testPredictedPathDeviationVariance_deviationOscillating) +{ + waitForDummyNode(); + + setTargetMetric("predicted_path_deviation_variance_CAR_5.00"); + + const auto init_objects = makeStraightPredictedObjects(0); + publishObjects(init_objects); + + const std::vector deviations = {-0.1, -0.2, -0.1, 0.0, 0.1, 0.2, 0.1, 0.0, -0.1, -0.2}; + for (size_t i = 0; i < deviations.size() - 1; ++i) { + const double time = static_cast(i + 1) * time_step_; + const auto objects = makeDeviatedStraightPredictedObjects(time, deviations[i]); + publishObjects(objects); + } + + const double num_points = deviations.size() + 1; + // deviations + // All - 11 points (num_points) + // 0.0[m] - 1 points + // -0.1[m] - 1 points + // -0.2[m] - 1 points + // -0.1[m] - 1 points + // -0.0[m] - 1 points + // 0.1[m] - 1 points + // 0.2[m] - 1 points + // 0.1[m] - 1 points + // 0.0[m] - 1 points + // -0.1[m] - 1 points + // -0.2[m] - 1 points + const double mean_deviation = + std::accumulate( + deviations.begin(), deviations.end(), 0.0, + [](double sum, double deviation) { return sum + std::abs(deviation); }) / + num_points; + + double sum_squared_deviations = pow(0 - mean_deviation, 2); + for (const auto deviation : deviations) { + sum_squared_deviations += pow(std::abs(deviation) - mean_deviation, 2); + } + const double variance = sum_squared_deviations / num_points; + const auto last_objects = makeDeviatedStraightPredictedObjects(time_delay_, deviations.back()); + EXPECT_NEAR(publishObjectsAndGetMetric(last_objects), variance, epsilon); +} +// ========================================================================================== + // ========================================================================================== // yaw rate TEST_F(EvalTest, testYawRate_0) From f6a734f3d48907b4d30ceb3d86cf3143a46eb297 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 16 Apr 2024 19:22:34 +0900 Subject: [PATCH 043/192] fix(path_smoother): fix mathjax visualization error (#6821) Signed-off-by: Takayuki Murooka --- planning/path_smoother/docs/eb.md | 100 +++++++++++++++--------------- 1 file changed, 50 insertions(+), 50 deletions(-) diff --git a/planning/path_smoother/docs/eb.md b/planning/path_smoother/docs/eb.md index 2c232cfa4de81..d62a6de5e3f54 100644 --- a/planning/path_smoother/docs/eb.md +++ b/planning/path_smoother/docs/eb.md @@ -78,65 +78,65 @@ We formulate a quadratic problem minimizing the diagonal length of the rhombus o ![eb](../media/eb.svg){: style="width:600px"} -Assuming that $k$'th point is $\boldsymbol{p}_k = (x_k, y_k)$, the objective function is as follows. +Assuming that $k$'th point is $\mathbf{p}_k = (x_k, y_k)$, the objective function is as follows. $$ \begin{align} -\ J & = \min \sum_{k=1}^{n-2} ||(\boldsymbol{p}_{k+1} - \boldsymbol{p}_{k}) - (\boldsymbol{p}_{k} - \boldsymbol{p}_{k-1})||^2 \\ -\ & = \min \sum_{k=1}^{n-2} ||\boldsymbol{p}_{k+1} - 2 \boldsymbol{p}_{k} + \boldsymbol{p}_{k-1}||^2 \\ -\ & = \min \sum_{k=1}^{n-2} \{(x_{k+1} - x_k + x_{k-1})^2 + (y_{k+1} - y_k + y_{k-1})^2\} \\ +\ J & = \min \sum_{k=1}^{n-2} ||(\mathbf{p}_{k+1} - \mathbf{p}_{k}) - (\mathbf{p}_{k} - \mathbf{p}_{k-1})||^2 \\\ +\ & = \min \sum_{k=1}^{n-2} ||\mathbf{p}_{k+1} - 2 \mathbf{p}_{k} + \mathbf{p}_{k-1}||^2 \\\ +\ & = \min \sum_{k=1}^{n-2} \{(x_{k+1} - x_k + x_{k-1})^2 + (y_{k+1} - y_k + y_{k-1})^2\} \\\ \ & = \min \begin{pmatrix} - \ x_0 \\ - \ x_1 \\ - \ x_2 \\ - \vdots \\ - \ x_{n-3}\\ - \ x_{n-2} \\ - \ x_{n-1} \\ - \ y_0 \\ - \ y_1 \\ - \ y_2 \\ - \vdots \\ - \ y_{n-3}\\ - \ y_{n-2} \\ - \ y_{n-1} \\ + \ x_0 \\\ + \ x_1 \\\ + \ x_2 \\\ + \vdots \\\ + \ x_{n-3}\\\ + \ x_{n-2} \\\ + \ x_{n-1} \\\ + \ y_0 \\\ + \ y_1 \\\ + \ y_2 \\\ + \vdots \\\ + \ y_{n-3}\\\ + \ y_{n-2} \\\ + \ y_{n-1} \\\ \end{pmatrix}^T \begin{pmatrix} - 1 & -2 & 1 & 0 & \dots& \\ - -2 & 5 & -4 & 1 & 0 &\dots \\ - 1 & -4 & 6 & -4 & 1 & \\ - 0 & 1 & -4 & 6 & -4 & \\ - \vdots & 0 & \ddots&\ddots& \ddots \\ - & \vdots & & & \\ - & & & 1 & -4 & 6 & -4 & 1 \\ - & & & & 1 & -4 & 5 & -2 \\ - & & & & & 1 & -2 & 1& \\ - & & & & & & & &1 & -2 & 1 & 0 & \dots& \\ - & & & & & & & &-2 & 5 & -4 & 1 & 0 &\dots \\ - & & & & & & & &1 & -4 & 6 & -4 & 1 & \\ - & & & & & & & &0 & 1 & -4 & 6 & -4 & \\ - & & & & & & & &\vdots & 0 & \ddots&\ddots& \ddots \\ - & & & & & & & & & \vdots & & & \\ - & & & & & & & & & & & 1 & -4 & 6 & -4 & 1 \\ - & & & & & & & & & & & & 1 & -4 & 5 & -2 \\ - & & & & & & & & & & & & & 1 & -2 & 1& \\ + 1 & -2 & 1 & 0 & \dots& \\\ + -2 & 5 & -4 & 1 & 0 &\dots \\\ + 1 & -4 & 6 & -4 & 1 & \\\ + 0 & 1 & -4 & 6 & -4 & \\\ + \vdots & 0 & \ddots&\ddots& \ddots \\\ + & \vdots & & & \\\ + & & & 1 & -4 & 6 & -4 & 1 \\\ + & & & & 1 & -4 & 5 & -2 \\\ + & & & & & 1 & -2 & 1& \\\ + & & & & & & & &1 & -2 & 1 & 0 & \dots& \\\ + & & & & & & & &-2 & 5 & -4 & 1 & 0 &\dots \\\ + & & & & & & & &1 & -4 & 6 & -4 & 1 & \\\ + & & & & & & & &0 & 1 & -4 & 6 & -4 & \\\ + & & & & & & & &\vdots & 0 & \ddots&\ddots& \ddots \\\ + & & & & & & & & & \vdots & & & \\\ + & & & & & & & & & & & 1 & -4 & 6 & -4 & 1 \\\ + & & & & & & & & & & & & 1 & -4 & 5 & -2 \\\ + & & & & & & & & & & & & & 1 & -2 & 1& \\\ \end{pmatrix} \begin{pmatrix} - \ x_0 \\ - \ x_1 \\ - \ x_2 \\ - \vdots \\ - \ x_{n-3}\\ - \ x_{n-2} \\ - \ x_{n-1} \\ - \ y_0 \\ - \ y_1 \\ - \ y_2 \\ - \vdots \\ - \ y_{n-3}\\ - \ y_{n-2} \\ - \ y_{n-1} \\ + \ x_0 \\\ + \ x_1 \\\ + \ x_2 \\\ + \vdots \\\ + \ x_{n-3}\\\ + \ x_{n-2} \\\ + \ x_{n-1} \\\ + \ y_0 \\\ + \ y_1 \\\ + \ y_2 \\\ + \vdots \\\ + \ y_{n-3}\\\ + \ y_{n-2} \\\ + \ y_{n-1} \\\ \end{pmatrix} \end{align} $$ From c40da9f1d312d88b13bf4a88124ac688df6d1c90 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 16 Apr 2024 20:55:46 +0900 Subject: [PATCH 044/192] feat(static_centerline_generator): add script to show diff of lanelet2 maps (#6804) * feat(static_centerline_generator): add script to show diff of lanelet2 maps Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix typo Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../scripts/show_lanelet2_map_diff.py | 139 ++++++++++++++++++ .../src/static_centerline_generator_node.cpp | 15 ++ 2 files changed, 154 insertions(+) create mode 100755 planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py diff --git a/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py b/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py new file mode 100755 index 0000000000000..912226511f1d9 --- /dev/null +++ b/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py @@ -0,0 +1,139 @@ +#!/bin/env python3 + +# Copyright 2024 TIER IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import argparse +from decimal import Decimal +import os +import subprocess +import xml.etree.ElementTree as ET + + +def sort_attributes(root): + for shallow_element in root: + # sort nodes + attrib = shallow_element.attrib + if len(attrib) > 1: + attributes = sorted(attrib.items()) + attrib.clear() + attrib.update(attributes) + if shallow_element.tag == "relation": + pass + + # sort the element in the tag + for deep_element in shallow_element: + attrib = deep_element.attrib + if len(attrib) > 1: + # adjust attribute order, e.g. by sorting + attributes = sorted(attrib.items()) + attrib.clear() + attrib.update(attributes) + + # sort tags + sorted_shallow_element = sorted(shallow_element, key=lambda x: x.items()) + if len(shallow_element) != 0: + # NOTE: This "tail" is related to the indent of the next tag + first_tail = shallow_element[0].tail + last_tail = shallow_element[-1].tail + for idx, val_shallow_element in enumerate(sorted_shallow_element): + shallow_element[idx] = val_shallow_element + if idx == len(shallow_element) - 1: + shallow_element[idx].tail = last_tail + else: + shallow_element[idx].tail = first_tail + + +def remove_diff_to_ignore(osm_root): + decimal_precision = 11 # for lat/lon values + + # remove attributes of the osm tag + osm_root.attrib.clear() + + # remove the MetaInfo tag generated by Vector Map Builder + if osm_root[0].tag == "MetaInfo": + osm_root.remove(osm_root[0]) + + # remove unnecessary attributes for diff + for osm_child in osm_root: + if osm_child.tag == "osm": + osm_child.attrib.pop("osm") + if "visible" in osm_child.attrib and osm_child.attrib["visible"]: + osm_child.attrib.pop("visible") + if "version" in osm_child.attrib and osm_child.attrib["version"]: + osm_child.attrib.pop("version") + if "action" in osm_child.attrib and osm_child.attrib["action"] == "modify": + osm_child.attrib.pop("action") + if "lat" in osm_child.attrib: + osm_child.attrib["lat"] = str( + Decimal(float(osm_child.attrib["lat"])).quantize(Decimal(f"1e-{decimal_precision}")) + ) + if "lon" in osm_child.attrib: + osm_child.attrib["lon"] = str( + Decimal(float(osm_child.attrib["lon"])).quantize(Decimal(f"1e-{decimal_precision}")) + ) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "-s", "--sort-attributes", action="store_true", help="Sort attributes of LL2 maps" + ) + parser.add_argument( + "-i", + "--ignore-minor-attributes", + action="store_true", + help="Ignore minor attributes of LL2 maps which does not change the map's behavior", + ) + args = parser.parse_args() + + original_osm_file_name = "/tmp/static_centerline_generator/input/lanelet2_map.osm" + modified_osm_file_name = "/tmp/static_centerline_generator/output/lanelet2_map.osm" + + # load LL2 maps + original_osm_tree = ET.parse(original_osm_file_name) + original_osm_root = original_osm_tree.getroot() + modified_osm_tree = ET.parse(modified_osm_file_name) + modified_osm_root = modified_osm_tree.getroot() + + # sort attributes + if args.sort_attributes: + sort_attributes(modified_osm_root) + sort_attributes(original_osm_root) + + # ignore minor attributes + if args.ignore_minor_attributes: + remove_diff_to_ignore(original_osm_root) + remove_diff_to_ignore(modified_osm_root) + + # write LL2 maps + output_dir_path = "/tmp/static_centerline_generator/show_lanelet2_map_diff/" + os.makedirs(output_dir_path + "original/", exist_ok=True) + os.makedirs(output_dir_path + "modified/", exist_ok=True) + + original_osm_tree.write(output_dir_path + "original/lanelet2_map.osm") + modified_osm_tree.write(output_dir_path + "modified/lanelet2_map.osm") + + # show diff + print("[INFO] Show diff of following LL2 maps") + print(f" {output_dir_path + 'original/lanelet2_map.osm'}") + print(f" {output_dir_path + 'modified/lanelet2_map.osm'}") + subprocess.run( + [ + "diff", + output_dir_path + "original/lanelet2_map.osm", + output_dir_path + "modified/lanelet2_map.osm", + "--color", + ] + ) diff --git a/planning/static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp index ec7d6278e346d..750b2e68b16b0 100644 --- a/planning/static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/static_centerline_generator/src/static_centerline_generator_node.cpp @@ -47,6 +47,7 @@ #include #include +#include #include #include #include @@ -336,6 +337,13 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) { + // copy the input LL2 map to the temporary file for debugging + const std::string debug_input_file_dir{"/tmp/static_centerline_generator/input/"}; + std::filesystem::create_directories(debug_input_file_dir); + std::filesystem::copy( + lanelet2_input_file_path, debug_input_file_dir + "lanelet2_map.osm", + std::filesystem::copy_options::overwrite_existing); + // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { // load map @@ -635,5 +643,12 @@ void StaticCenterlineGeneratorNode::save_map( // save map with modified center line lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector_); RCLCPP_INFO(get_logger(), "Saved map."); + + // copy the output LL2 map to the temporary file for debugging + const std::string debug_output_file_dir{"/tmp/static_centerline_generator/output/"}; + std::filesystem::create_directories(debug_output_file_dir); + std::filesystem::copy( + lanelet2_output_file_path, debug_output_file_dir + "lanelet2_map.osm", + std::filesystem::copy_options::overwrite_existing); } } // namespace static_centerline_generator From 51efa6d06420f3dd72d7d8f6f650b3e1097552fb Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 17 Apr 2024 09:55:46 +0900 Subject: [PATCH 045/192] feat(perception_online_evaluator): better waitForDummyNode (#6827) --- .../test/test_perception_online_evaluator_node.cpp | 13 ++----------- 1 file changed, 2 insertions(+), 11 deletions(-) diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index 8f8cd4ac896fe..e64411a66f521 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -77,11 +77,6 @@ class EvalTest : public ::testing::Test objects_pub_ = rclcpp::create_publisher( dummy_node, "/perception_online_evaluator/input/objects", 1); - marker_sub_ = rclcpp::create_subscription( - eval_node, "perception_online_evaluator/markers", 10, - [this]([[maybe_unused]] const MarkerArray::ConstSharedPtr msg) { - has_received_marker_ = true; - }); uuid_ = generateUUID(); } @@ -229,12 +224,10 @@ class EvalTest : public ::testing::Test void waitForDummyNode() { - // wait for the marker to be published - publishObjects(makeStraightPredictedObjects(0)); - while (!has_received_marker_) { + // Wait until the publisher is connected to the dummy node + while (objects_pub_->get_subscription_count() == 0) { rclcpp::spin_some(dummy_node); rclcpp::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(eval_node); } } @@ -248,8 +241,6 @@ class EvalTest : public ::testing::Test // Pub/Sub rclcpp::Publisher::SharedPtr objects_pub_; rclcpp::Subscription::SharedPtr metric_sub_; - rclcpp::Subscription::SharedPtr marker_sub_; - bool has_received_marker_{false}; double time_delay_ = 5.0; double time_step_ = 0.5; From 859776d8c7250037afcf2481c728ef95a3f3a597 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 17 Apr 2024 15:02:01 +0900 Subject: [PATCH 046/192] feat(intersection): resurrect debug ego-object ttc visualizer (#6829) Signed-off-by: Mamoru Sobue --- .cspell.json | 7 +- .../scripts/ttc.py | 16 +- .../src/scene_intersection.cpp | 13 +- .../src/scene_intersection.hpp | 3 +- .../src/scene_intersection_collision.cpp | 353 ++++-------------- 5 files changed, 112 insertions(+), 280 deletions(-) diff --git a/.cspell.json b/.cspell.json index c3afe17698a6f..94b509370e688 100644 --- a/.cspell.json +++ b/.cspell.json @@ -1,5 +1,8 @@ { - "ignorePaths": ["perception/bytetrack/lib/**"], + "ignorePaths": [ + "perception/bytetrack/lib/**", + "planning/behavior_velocity_intersection_module/scripts/**" + ], "ignoreRegExpList": [], - "words": ["dltype", "tvmgen"] + "words": ["dltype", "tvmgen", "fromarray"] } diff --git a/planning/behavior_velocity_intersection_module/scripts/ttc.py b/planning/behavior_velocity_intersection_module/scripts/ttc.py index 6d1593d95f055..1eb6ae1ffafc1 100755 --- a/planning/behavior_velocity_intersection_module/scripts/ttc.py +++ b/planning/behavior_velocity_intersection_module/scripts/ttc.py @@ -21,6 +21,7 @@ from threading import Lock import time +from PIL import Image import imageio import matplotlib import matplotlib.pyplot as plt @@ -218,7 +219,19 @@ def plot_world(self): def cleanup(self): if self.args.save: kwargs_write = {"fps": self.args.fps, "quantizer": "nq"} - imageio.mimsave("./" + self.args.gif + ".gif", self.images, **kwargs_write) + max_size_total = 0 + max_size = None + for image in self.images: + (w, h) = image.size + if w * h > max_size_total: + max_size = image.size + max_size_total = w * h + reshaped = [] + for image in self.images: + reshaped.append(image.resize(max_size)) + + imageio.mimsave("./" + self.args.gif + ".gif", reshaped, **kwargs_write) + print("saved fig") rclpy.shutdown() def on_plot_timer(self): @@ -241,6 +254,7 @@ def on_plot_timer(self): if self.args.save: image = np.frombuffer(self.fig.canvas.tostring_rgb(), dtype="uint8") image = image.reshape(self.fig.canvas.get_width_height()[::-1] + (3,)) + image = Image.fromarray(image.astype(np.uint8)) self.images.append(image) def on_ego_ttc(self, msg): diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 2103ef25c6cfc..9d0c0c8e1defb 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -239,9 +239,20 @@ intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail( // passed each pass judge line for the first time, save current collision status for late // diagnosis // ========================================================================================== + tier4_debug_msgs::msg::Float64MultiArrayStamped object_ttc_time_array; updateObjectInfoManagerCollision( path_lanelets, time_distance_array, traffic_prioritized_level, safely_passed_1st_judge_line, - safely_passed_2nd_judge_line); + safely_passed_2nd_judge_line, &object_ttc_time_array); + { + const auto & debug = planner_param_.debug.ttc; + if ( + std::find(debug.begin(), debug.end(), lane_id_) != debug.end() || + std::find(debug.begin(), debug.end(), -1) != debug.end()) { + ego_ttc_pub_->publish(ego_ttc_time_array); + object_ttc_pub_->publish(object_ttc_time_array); + } + } + for (const auto & object_info : object_info_manager_.attentionObjects()) { if (!object_info->unsafe_info()) { continue; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 73736c804fb02..8c8874156f07b 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -754,7 +754,8 @@ class IntersectionModule : public SceneModuleInterface void updateObjectInfoManagerCollision( const intersection::PathLanelets & path_lanelets, const TimeDistanceArray & time_distance_array, const TrafficPrioritizedLevel & traffic_prioritized_level, - const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time); + const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time, + tier4_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array); void cutPredictPathWithinDuration( const builtin_interfaces::msg::Time & object_stamp, const double time_thr, diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 0eff4cea63581..8388bc15492a3 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -144,7 +144,8 @@ void IntersectionModule::updateObjectInfoManagerCollision( const intersection::PathLanelets & path_lanelets, const IntersectionModule::TimeDistanceArray & time_distance_array, const IntersectionModule::TrafficPrioritizedLevel & traffic_prioritized_level, - const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time) + const bool passed_1st_judge_line_first_time, const bool passed_2nd_judge_line_first_time, + tier4_debug_msgs::msg::Float64MultiArrayStamped * object_ttc_time_array) { const auto & intersection_lanelets = intersection_lanelets_.value(); @@ -183,6 +184,25 @@ void IntersectionModule::updateObjectInfoManagerCollision( planner_param_.collision_detection.not_prioritized.collision_end_margin_time); }(); + constexpr size_t object_debug_size = 57; + { + object_ttc_time_array->stamp = clock_->now(); + object_ttc_time_array->layout.dim.resize(3); + object_ttc_time_array->layout.dim.at(0).label = "objects"; + object_ttc_time_array->layout.dim.at(0).size = + 1; // incremented in the loop, first row is lane_id + object_ttc_time_array->layout.dim.at(1).label = + "[x, y, th, length, width, speed, dangerous, ref_obj_enter_time, ref_obj_exit_time, " + "start_time, start_dist, " + "end_time, end_dist, first_collision_x, first_collision_y, last_collision_x, " + "last_collision_y, " + "prd_x[0], ... pred_x[19], pred_y[0], ... pred_y[19]]"; + object_ttc_time_array->layout.dim.at(1).size = object_debug_size; + for (unsigned i = 0; i < object_debug_size; ++i) { + object_ttc_time_array->data.push_back(lane_id_); + } + } + for (auto & object_info : object_info_manager_.attentionObjects()) { const auto & predicted_object = object_info->predicted_object(); bool safe_under_traffic_control = false; @@ -226,6 +246,7 @@ void IntersectionModule::updateObjectInfoManagerCollision( // ========================================================================================== std::optional unsafe_interval{std::nullopt}; std::optional safe_interval{std::nullopt}; + std::optional> object_debug_info{std::nullopt}; for (const auto & predicted_path_ptr : sorted_predicted_paths) { auto predicted_path = *predicted_path_ptr; @@ -296,10 +317,39 @@ void IntersectionModule::updateObjectInfoManagerCollision( break; } } + auto get_object_info = [&]() { + // debug info + const auto & pose = predicted_object.kinematics.initial_pose_with_covariance.pose; + const auto & shape = predicted_object.shape; + const auto [object_start_itr, object_end_itr] = object_passage_interval.interval_position; + const auto & object_start_pos = object_passage_interval.path.at(object_start_itr).position; + const auto & object_end_pos = object_passage_interval.path.at(object_end_itr).position; + std::vector debug; + debug.reserve(object_debug_size); + + debug.insert( + debug.end(), + {pose.position.x, pose.position.y, tf2::getYaw(pose.orientation), shape.dimensions.x, + shape.dimensions.y, + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, + 1.0 * static_cast(collision_detected), object_enter_time, object_exit_time, + ego_start_itr->first, ego_start_itr->second, ego_end_itr->first, ego_end_itr->second, + object_start_pos.x, object_start_pos.y, object_end_pos.x, object_end_pos.y}); + for (unsigned i = 0; i < 20; ++i) { + const auto & pos = object_passage_interval.path + .at(std::min(i, object_passage_interval.path.size() - 1)) + .position; + debug.push_back(pos.x); + debug.push_back(pos.y); + } + return debug; + }; + if (collision_detected) { // if judged as UNSAFE, return safe_interval = std::nullopt; unsafe_interval = object_passage_interval; + object_debug_info = get_object_info(); break; } if (!safe_interval) { @@ -308,6 +358,7 @@ void IntersectionModule::updateObjectInfoManagerCollision( // judged UNSAFE during the iteration // ========================================================================================== safe_interval = object_passage_interval; + object_debug_info = get_object_info(); } } object_info->update_safety(unsafe_interval, safe_interval, safe_under_traffic_control); @@ -337,6 +388,13 @@ void IntersectionModule::updateObjectInfoManagerCollision( .x // observed_velocity }); } + + // debug + if (object_debug_info) { + const auto & data = object_debug_info.value(); + object_ttc_time_array->layout.dim.at(0).size++; + std::copy(data.begin(), data.end(), std::back_inserter(object_ttc_time_array->data)); + } } } @@ -714,257 +772,6 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision( return {false, intersection::CollisionInterval::ELSE, too_late_detect_objects, misjudge_objects}; } -/* -bool IntersectionModule::checkCollision( - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, TargetObjects * target_objects, - const intersection::PathLanelets & path_lanelets, const size_t closest_idx, - const size_t last_intersection_stopline_candidate_idx, const double time_delay, - const TrafficPrioritizedLevel & traffic_prioritized_level) -{ - using lanelet::utils::getArcCoordinates; - using lanelet::utils::getPolygonFromArcLength; - - // check collision between target_objects predicted path and ego lane - // cut the predicted path at passing_time - tier4_debug_msgs::msg::Float64MultiArrayStamped ego_ttc_time_array; - const auto time_distance_array = calcIntersectionPassingTime( - path, closest_idx, last_intersection_stopline_candidate_idx, time_delay, &ego_ttc_time_array); - - if ( - std::find(planner_param_.debug.ttc.begin(), planner_param_.debug.ttc.end(), lane_id_) != - planner_param_.debug.ttc.end()) { - ego_ttc_time_array.stamp = path.header.stamp; - ego_ttc_pub_->publish(ego_ttc_time_array); - } - - const double passing_time = time_distance_array.back().first; - cutPredictPathWithDuration(target_objects, passing_time); - - const auto & concat_lanelets = path_lanelets.all; - const auto closest_arc_coords = getArcCoordinates( - concat_lanelets, tier4_autoware_utils::getPose(path.points.at(closest_idx).point)); - const auto & ego_lane = path_lanelets.ego_or_entry2exit; - debug_data_.ego_lane = ego_lane.polygon3d(); - const auto ego_poly = ego_lane.polygon2d().basicPolygon(); - - // change TTC margin based on ego traffic light color - const auto [collision_start_margin_time, collision_end_margin_time] = [&]() { - if (traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED) { - return std::make_pair( - planner_param_.collision_detection.fully_prioritized.collision_start_margin_time, - planner_param_.collision_detection.fully_prioritized.collision_end_margin_time); - } - if (traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) { - return std::make_pair( - planner_param_.collision_detection.partially_prioritized.collision_start_margin_time, - planner_param_.collision_detection.partially_prioritized.collision_end_margin_time); - } - return std::make_pair( - planner_param_.collision_detection.not_prioritized.collision_start_margin_time, - planner_param_.collision_detection.not_prioritized.collision_end_margin_time); - }(); - const auto expectedToStopBeforeStopLine = [&](const TargetObject & target_object) { - if (!target_object.dist_to_stopline) { - return false; - } - const double dist_to_stopline = target_object.dist_to_stopline.value(); - if (dist_to_stopline < 0) { - return false; - } - const double v = target_object.object.kinematics.initial_twist_with_covariance.twist.linear.x; - const double braking_distance = - v * v / - (2.0 * std::fabs(planner_param_.collision_detection.ignore_on_amber_traffic_light - .object_expected_deceleration)); - return dist_to_stopline > braking_distance; - }; - const auto isTolerableOvershoot = [&](const TargetObject & target_object) { - if ( - !target_object.attention_lanelet || !target_object.dist_to_stopline || - !target_object.stopline) { - return false; - } - const double dist_to_stopline = target_object.dist_to_stopline.value(); - const double v = target_object.object.kinematics.initial_twist_with_covariance.twist.linear.x; - const double braking_distance = - v * v / - (2.0 * std::fabs(planner_param_.collision_detection.ignore_on_amber_traffic_light - .object_expected_deceleration)); - if (dist_to_stopline > braking_distance) { - return false; - } - const auto stopline_front = target_object.stopline.value().front(); - const auto stopline_back = target_object.stopline.value().back(); - tier4_autoware_utils::LineString2d object_line; - object_line.emplace_back( - (stopline_front.x() + stopline_back.x()) / 2.0, - (stopline_front.y() + stopline_back.y()) / 2.0); - const auto stopline_mid = object_line.front(); - const auto endpoint = target_object.attention_lanelet.value().centerline().back(); - object_line.emplace_back(endpoint.x(), endpoint.y()); - std::vector intersections; - bg::intersection(object_line, ego_lane.centerline2d().basicLineString(), intersections); - if (intersections.empty()) { - return false; - } - const auto collision_point = intersections.front(); - // distance from object expected stop position to collision point - const double stopline_to_object = -1.0 * dist_to_stopline + braking_distance; - const double stopline_to_collision = - std::hypot(collision_point.x() - stopline_mid.x(), collision_point.y() - stopline_mid.y()); - const double object2collision = stopline_to_collision - stopline_to_object; - const double margin = - planner_param_.collision_detection.ignore_on_red_traffic_light.object_margin_to_path; - return (object2collision > margin) || (object2collision < 0); - }; - // check collision between predicted_path and ego_area - tier4_debug_msgs::msg::Float64MultiArrayStamped object_ttc_time_array; - object_ttc_time_array.layout.dim.resize(3); - object_ttc_time_array.layout.dim.at(0).label = "objects"; - object_ttc_time_array.layout.dim.at(0).size = 1; // incremented in the loop, first row is lane_id - object_ttc_time_array.layout.dim.at(1).label = - "[x, y, th, length, width, speed, dangerous, ref_obj_enter_time, ref_obj_exit_time, " - "start_time, start_dist, " - "end_time, end_dist, first_collision_x, first_collision_y, last_collision_x, last_collision_y, " - "prd_x[0], ... pred_x[19], pred_y[0], ... pred_y[19]]"; - object_ttc_time_array.layout.dim.at(1).size = 57; - for (unsigned i = 0; i < object_ttc_time_array.layout.dim.at(1).size; ++i) { - object_ttc_time_array.data.push_back(lane_id_); - } - bool collision_detected = false; - for (const auto & target_object : target_objects->all_attention_objects) { - const auto & object = target_object.object; - // If the vehicle is expected to stop before their stopline, ignore - const bool expected_to_stop_before_stopline = expectedToStopBeforeStopLine(target_object); - if ( - traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED && - expected_to_stop_before_stopline) { - debug_data_.amber_ignore_targets.objects.push_back(object); - continue; - } - const bool is_tolerable_overshoot = isTolerableOvershoot(target_object); - if ( - traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED && - !expected_to_stop_before_stopline && is_tolerable_overshoot) { - debug_data_.red_overshoot_ignore_targets.objects.push_back(object); - continue; - } - for (const auto & predicted_path : object.kinematics.predicted_paths) { - if ( - predicted_path.confidence < - planner_param_.collision_detection.min_predicted_path_confidence) { - // ignore the predicted path with too low confidence - continue; - } - - // collision point - const auto first_itr = std::adjacent_find( - predicted_path.path.cbegin(), predicted_path.path.cend(), - [&ego_poly, &object](const auto & a, const auto & b) { - return bg::intersects(ego_poly, ::createOneStepPolygon(a, b, object.shape)); - }); - if (first_itr == predicted_path.path.cend()) continue; - const auto last_itr = std::adjacent_find( - predicted_path.path.crbegin(), predicted_path.path.crend(), - [&ego_poly, &object](const auto & a, const auto & b) { - return bg::intersects(ego_poly, ::createOneStepPolygon(a, b, object.shape)); - }); - if (last_itr == predicted_path.path.crend()) continue; - - // possible collision time interval - const double ref_object_enter_time = - static_cast(first_itr - predicted_path.path.begin()) * - rclcpp::Duration(predicted_path.time_step).seconds(); - auto start_time_distance_itr = time_distance_array.begin(); - if (ref_object_enter_time - collision_start_margin_time > 0) { - // start of possible ego position in the intersection - start_time_distance_itr = std::lower_bound( - time_distance_array.begin(), time_distance_array.end(), - ref_object_enter_time - collision_start_margin_time, - [](const auto & a, const double b) { return a.first < b; }); - if (start_time_distance_itr == time_distance_array.end()) { - // ego is already at the exit of intersection when npc is at collision point even if npc - // accelerates so ego's position interval is empty - continue; - } - } - const double ref_object_exit_time = - static_cast(last_itr.base() - predicted_path.path.begin()) * - rclcpp::Duration(predicted_path.time_step).seconds(); - auto end_time_distance_itr = std::lower_bound( - time_distance_array.begin(), time_distance_array.end(), - ref_object_exit_time + collision_end_margin_time, - [](const auto & a, const double b) { return a.first < b; }); - if (end_time_distance_itr == time_distance_array.end()) { - // ego is already passing the intersection, when npc is is at collision point - // so ego's position interval is up to the end of intersection lane - end_time_distance_itr = time_distance_array.end() - 1; - } - const double start_arc_length = std::max( - 0.0, closest_arc_coords.length + (*start_time_distance_itr).second - - planner_data_->vehicle_info_.rear_overhang_m); - const double end_arc_length = std::min( - closest_arc_coords.length + (*end_time_distance_itr).second + - planner_data_->vehicle_info_.max_longitudinal_offset_m, - lanelet::utils::getLaneletLength2d(concat_lanelets)); - - const auto trimmed_ego_polygon = - getPolygonFromArcLength(concat_lanelets, start_arc_length, end_arc_length); - - if (trimmed_ego_polygon.empty()) { - continue; - } - - Polygon2d polygon{}; - for (const auto & p : trimmed_ego_polygon) { - polygon.outer().emplace_back(p.x(), p.y()); - } - bg::correct(polygon); - debug_data_.candidate_collision_ego_lane_polygon = toGeomPoly(polygon); - - for (auto itr = first_itr; itr != last_itr.base(); ++itr) { - const auto footprint_polygon = tier4_autoware_utils::toPolygon2d(*itr, object.shape); - if (bg::intersects(polygon, footprint_polygon)) { - collision_detected = true; - break; - } - } - object_ttc_time_array.layout.dim.at(0).size++; - const auto & pos = object..position; - const auto & shape = object.shape; - object_ttc_time_array.data.insert( - object_ttc_time_array.data.end(), - {pos.x, pos.y, tf2::getYaw(object.kinematics.initial_pose_with_covariance.pose.orientation), - shape.dimensions.x, shape.dimensions.y, - object.kinematics.initial_twist_with_covariance.twist.linear.x, - 1.0 * static_cast(collision_detected), ref_object_enter_time, ref_object_exit_time, - start_time_distance_itr->first, start_time_distance_itr->second, - end_time_distance_itr->first, end_time_distance_itr->second, first_itr->position.x, - first_itr->position.y, last_itr->position.x, last_itr->position.y}); - for (unsigned i = 0; i < 20; i++) { - const auto & pos = - predicted_path.path.at(std::min(i, predicted_path.path.size() - 1)).position; - object_ttc_time_array.data.push_back(pos.x); - object_ttc_time_array.data.push_back(pos.y); - } - if (collision_detected) { - debug_data_.conflicting_targets.objects.push_back(object); - break; - } - } - } - - if ( - std::find(planner_param_.debug.ttc.begin(), planner_param_.debug.ttc.end(), lane_id_) != - planner_param_.debug.ttc.end()) { - object_ttc_time_array.stamp = path.header.stamp; - object_ttc_pub_->publish(object_ttc_time_array); - } - - return collision_detected; -} -*/ - std::optional IntersectionModule::checkAngleForTargetLanelets( const geometry_msgs::msg::Pose & pose, const lanelet::ConstLanelets & target_lanelets, @@ -1006,7 +813,7 @@ std::optional IntersectionModule::checkAngleForTargetLanelets( IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassingTime( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const bool is_prioritized, const intersection::IntersectionStopLines & intersection_stoplines, - tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) const + tier4_debug_msgs::msg::Float64MultiArrayStamped * ego_ttc_array) const { const double intersection_velocity = planner_param_.collision_detection.velocity_profile.default_velocity; @@ -1053,12 +860,12 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin second_attention_stopline_idx ? second_attention_stopline_idx.value() : std::max(occlusion_stopline_idx, first_attention_stopline_idx); - int assigned_lane_found = false; + bool assigned_lane_found = false; // crop intersection part of the path, and set the reference velocity to intersection_velocity // for ego's ttc PathWithLaneId reference_path; std::optional upstream_stopline{std::nullopt}; - for (size_t i = 0; i < path.points.size() - 1; ++i) { + for (size_t i = 0; i + 1 < path.points.size(); ++i) { auto reference_point = path.points.at(i); // assume backward velocity is current ego velocity if (i < closest_idx) { @@ -1085,12 +892,6 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin return {{0.0, 0.0}}; // has already passed the intersection. } - std::vector> original_path_xy; - for (size_t i = 0; i < reference_path.points.size(); ++i) { - const auto & p = reference_path.points.at(i).point.pose.position; - original_path_xy.emplace_back(p.x, p.y); - } - // apply smoother to reference velocity PathWithLaneId smoothed_reference_path = reference_path; if (!smoothPath(reference_path, smoothed_reference_path, planner_data_)) { @@ -1111,7 +912,8 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin const std::optional upstream_stopline_idx_opt = [&]() -> std::optional { if (upstream_stopline) { - const auto upstream_stopline_point = path.points.at(upstream_stopline.value()).point.pose; + const auto upstream_stopline_point = + reference_path.points.at(upstream_stopline.value()).point.pose; return motion_utils::findFirstNearestIndexWithSoftConstraints( smoothed_reference_path.points, upstream_stopline_point, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); @@ -1120,7 +922,7 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin } }(); - for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { + for (size_t i = smoothed_path_closest_idx; i + 1 < smoothed_reference_path.points.size(); ++i) { const auto & p1 = smoothed_reference_path.points.at(i); const auto & p2 = smoothed_reference_path.points.at(i + 1); @@ -1144,29 +946,30 @@ IntersectionModule::TimeDistanceArray IntersectionModule::calcIntersectionPassin time_distance_array.emplace_back(passing_time, dist_sum); } - debug_ttc_array->layout.dim.resize(3); - debug_ttc_array->layout.dim.at(0).label = "lane_id_@[0][0], ttc_time, ttc_dist, path_x, path_y"; - debug_ttc_array->layout.dim.at(0).size = 5; - debug_ttc_array->layout.dim.at(1).label = "values"; - debug_ttc_array->layout.dim.at(1).size = time_distance_array.size(); - debug_ttc_array->data.reserve( - time_distance_array.size() * debug_ttc_array->layout.dim.at(0).size); + ego_ttc_array->stamp = clock_->now(); + ego_ttc_array->layout.dim.resize(3); + ego_ttc_array->layout.dim.at(0).label = "lane_id_@[0][0], ttc_time, ttc_dist, path_x, path_y"; + constexpr size_t ego_debug_size = 5; + ego_ttc_array->layout.dim.at(0).size = ego_debug_size; + ego_ttc_array->layout.dim.at(1).label = "values"; + ego_ttc_array->layout.dim.at(1).size = time_distance_array.size(); + ego_ttc_array->data.reserve(time_distance_array.size() * ego_debug_size); for (unsigned i = 0; i < time_distance_array.size(); ++i) { - debug_ttc_array->data.push_back(lane_id_); + ego_ttc_array->data.push_back(lane_id_); } for (const auto & [t, d] : time_distance_array) { - debug_ttc_array->data.push_back(t); + ego_ttc_array->data.push_back(t); } for (const auto & [t, d] : time_distance_array) { - debug_ttc_array->data.push_back(d); + ego_ttc_array->data.push_back(d); } for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { const auto & p = smoothed_reference_path.points.at(i).point.pose.position; - debug_ttc_array->data.push_back(p.x); + ego_ttc_array->data.push_back(p.x); } for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size(); ++i) { const auto & p = smoothed_reference_path.points.at(i).point.pose.position; - debug_ttc_array->data.push_back(p.y); + ego_ttc_array->data.push_back(p.y); } return time_distance_array; } From 8319209b35d5c77736c6e6d2657824320fd5fbec Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 17 Apr 2024 17:43:37 +0900 Subject: [PATCH 047/192] docs(perception_online_evaluator): update metrics explanation (#6819) Signed-off-by: kosuke55 --- .../perception_online_evaluator/README.md | 35 +- .../images/lateral_deviation.drawio.svg | 296 +++++++++++++++++ .../images/yaw_deviation.drawio.svg | 302 ++++++++++++++++++ .../images/yaw_rate.drawio.svg | 247 ++++++++++++++ 4 files changed, 875 insertions(+), 5 deletions(-) create mode 100644 evaluator/perception_online_evaluator/images/lateral_deviation.drawio.svg create mode 100644 evaluator/perception_online_evaluator/images/yaw_deviation.drawio.svg create mode 100644 evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index 4fcd4fdf9cc84..fd8aee9766308 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -8,14 +8,20 @@ This module allows for the evaluation of how accurately perception results are g ## Inner-workings / Algorithms -- Calculates lateral deviation between the predicted path and the actual traveled trajectory. -- Calculates lateral deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of lateral position recognition. -- Calculates yaw deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of yaw recognition. -- Calculates yaw rate based on the yaw of the object received in the previous cycle to evaluate the stability of the yaw rate recognition. +The evaluated metrics are as follows: + +- predicted_path_deviation +- predicted_path_deviation_variance +- lateral_deviation +- yaw_deviation +- yaw_rate ### Predicted Path Deviation / Predicted Path Deviation Variance -Compare the predicted path of past objects with their actual traveled path to determine the deviation. For each object, calculate the mean distance between the predicted path points and the corresponding points on the actual path, up to the specified time step. In other words, this calculates the Average Displacement Error (ADE). The target object to be evaluated is the object from $T_N$ seconds ago, where $T_N$ is the maximum value of the prediction time horizon $[T_1, T_2, ..., T_N]$. +Compare the predicted path of past objects with their actual traveled path to determine the deviation for **MOVING OBJECTS**. For each object, calculate the mean distance between the predicted path points and the corresponding points on the actual path, up to the specified time step. In other words, this calculates the Average Displacement Error (ADE). The target object to be evaluated is the object from $T_N$ seconds ago, where $T_N$ is the maximum value of the prediction time horizon $[T_1, T_2, ..., T_N]$. + +> [!NOTE] +> The object from $T_N$ seconds ago is the target object for all metrics. This is to unify the time of the target object across metrics. ![path_deviation_each_object](./images/path_deviation_each_object.drawio.svg) @@ -64,6 +70,25 @@ $$ The actual metric name is determined by the object class and time horizon. For example, `predicted_path_deviation_variance_CAR_5.00` +### Lateral Deviation + +Calculates lateral deviation between the smoothed traveled trajectory and the perceived position to evaluate the stability of lateral position recognition for **MOVING OBJECTS**. The smoothed traveled trajectory is calculated by applying a centered moving average filter whose window size is specified by the parameter `smoothing_window_size`. The lateral deviation is calculated by comparing the smoothed traveled trajectory with the perceived position of the past object whose timestamp is $T=T_n$ seconds ago. For stopped objects, the smoothed traveled trajectory is unstable, so this metric is not calculated. + +![lateral_deviation](./images/lateral_deviation.drawio.svg) + +### Yaw Deviation + +Calculates the deviation between the recognized yaw angle of an past object and the yaw azimuth angle of the smoothed traveled trajectory for **MOVING OBJECTS**. The smoothed traveled trajectory is calculated by applying a centered moving average filter whose window size is specified by the parameter `smoothing_window_size`. The yaw deviation is calculated by comparing the yaw azimuth angle of smoothed traveled trajectory with the perceived orientation of the past object whose timestamp is $T=T_n$ seconds ago. +For stopped objects, the smoothed traveled trajectory is unstable, so this metric is not calculated. + +![yaw_deviation](./images/yaw_deviation.drawio.svg) + +### Yaw Rate + +Calculates the yaw rate of an object based on the change in yaw angle from the previous time step. It is evaluated for **STATIONARY OBJECTS** and assesses the stability of yaw rate recognition. The yaw rate is calculated by comparing the yaw angle of the past object with the yaw angle of the object received in the previous cycle. Here, t2 is the timestamp that is $T_n$ seconds ago. + +![yaw_rate](./images/yaw_rate.drawio.svg) + ## Inputs / Outputs | Name | Type | Description | diff --git a/evaluator/perception_online_evaluator/images/lateral_deviation.drawio.svg b/evaluator/perception_online_evaluator/images/lateral_deviation.drawio.svg new file mode 100644 index 0000000000000..5d7b34323db9a --- /dev/null +++ b/evaluator/perception_online_evaluator/images/lateral_deviation.drawio.svg @@ -0,0 +1,296 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ recognized object +
+
+
+
+ recognized object +
+
+
+ + + + + + + +
+
+
+ smoothed traveled trajectory +
+
+
+
+ smoothed traveled trajectory +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lateral deviation +
+
+
+
+ lateral deviation +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - T +
+
+
+
+ `T_{now}`... +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `T_{now}` +
+
+
+
+
diff --git a/evaluator/perception_online_evaluator/images/yaw_deviation.drawio.svg b/evaluator/perception_online_evaluator/images/yaw_deviation.drawio.svg new file mode 100644 index 0000000000000..f0319e9a38b7c --- /dev/null +++ b/evaluator/perception_online_evaluator/images/yaw_deviation.drawio.svg @@ -0,0 +1,302 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ recognized object +
+
+
+
+ recognized object +
+
+
+ + + + + + + +
+
+
+ smoothed traveled trajectory +
+
+
+
+ smoothed traveled trajectory +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ yaw deviation +
+
+
+
+ yaw deviation +
+
+
+ + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - T +
+
+
+
+ `T_{now}`... +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `T_{now}` +
+
+
+
+
diff --git a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg new file mode 100644 index 0000000000000..20587ec30d683 --- /dev/null +++ b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg @@ -0,0 +1,247 @@ + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `t_2` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `t_1` +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `\Deltayaw` +
+
+
+ + + +
+
From 51b5f830780eb69bd1a7dfe60e295773f394fd8e Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 18 Apr 2024 08:41:30 +0900 Subject: [PATCH 048/192] feat(logger_level_configure): make it possible to change level of container logger (#6823) * feat(launch): add logging_demo::LoggerConfig into container Signed-off-by: satoshi-ota * fix(logger_level_reconfigure_plugin): fix yaml Signed-off-by: satoshi-ota * feat(logging_level_configure): add composable node Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- common/tier4_autoware_utils/CMakeLists.txt | 5 ++++ .../ros/logger_level_configure.hpp | 5 ++++ common/tier4_autoware_utils/package.xml | 1 + .../src/ros/logger_level_configure.cpp | 7 +++++ .../config/logger_config.yaml | 30 ++++++++----------- .../launch/control.launch.py | 6 ++++ launch/tier4_control_launch/package.xml | 2 ++ .../behavior_planning.launch.xml | 1 + .../motion_planning.launch.xml | 4 +++ .../scenario_planning.launch.xml | 1 + launch/tier4_planning_launch/package.xml | 1 + .../launch/mission_planner.launch.xml | 1 + 12 files changed, 46 insertions(+), 18 deletions(-) diff --git a/common/tier4_autoware_utils/CMakeLists.txt b/common/tier4_autoware_utils/CMakeLists.txt index 9cb54e52362a5..f9bc00f891879 100644 --- a/common/tier4_autoware_utils/CMakeLists.txt +++ b/common/tier4_autoware_utils/CMakeLists.txt @@ -18,6 +18,11 @@ ament_auto_add_library(tier4_autoware_utils SHARED src/system/backtrace.cpp ) +rclcpp_components_register_node(tier4_autoware_utils + PLUGIN "tier4_autoware_utils::LoggerLevelConfigureNode" + EXECUTABLE logger_level_configure_node +) + if(BUILD_TESTING) find_package(ament_cmake_ros REQUIRED) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp index 5aee3a251dad2..9aca59e4fa514 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp @@ -64,5 +64,10 @@ class LoggerLevelConfigure const ConfigLogger::Response::SharedPtr response); }; +class LoggerLevelConfigureNode : public rclcpp::Node, public LoggerLevelConfigure +{ +public: + explicit LoggerLevelConfigureNode(const rclcpp::NodeOptions & node_options); +}; } // namespace tier4_autoware_utils #endif // TIER4_AUTOWARE_UTILS__ROS__LOGGER_LEVEL_CONFIGURE_HPP_ diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index c34d3b5fdfdd0..8cac2809a13b3 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -23,6 +23,7 @@ pcl_conversions pcl_ros rclcpp + rclcpp_components tf2 tf2_geometry_msgs tier4_debug_msgs diff --git a/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp b/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp index d764299290d05..39950d806a9f6 100644 --- a/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp +++ b/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp @@ -58,4 +58,11 @@ void LoggerLevelConfigure::onLoggerConfigService( return; } +LoggerLevelConfigureNode::LoggerLevelConfigureNode(const rclcpp::NodeOptions & node_options) +: Node("logger_level_configure_node", node_options), LoggerLevelConfigure(this) +{ +} + } // namespace tier4_autoware_utils +#include +RCLCPP_COMPONENTS_REGISTER_NODE(tier4_autoware_utils::LoggerLevelConfigureNode) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index a298967a31af9..c7bc1cc835ebc 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -31,12 +31,14 @@ Planning: behavior_path_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/container_logger_configure logger_name: tier4_autoware_utils behavior_path_planner_avoidance: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance + - node_name: /planning/scenario_planning/lane_driving/behavior_planning + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils behavior_path_planner_goal_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner @@ -57,7 +59,7 @@ Planning: behavior_velocity_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/container_logger_configure logger_name: tier4_autoware_utils behavior_velocity_planner_intersection: @@ -67,13 +69,13 @@ Planning: motion_obstacle_avoidance: - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner logger_name: planning.scenario_planning.lane_driving.motion_planning.obstacle_avoidance_planner - - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + - node_name: /planning/scenario_planning/lane_driving/motion_planning/container_logger_configure logger_name: tier4_autoware_utils motion_velocity_smoother: - node_name: /planning/scenario_planning/motion_velocity_smoother logger_name: planning.scenario_planning.motion_velocity_smoother - - node_name: /planning/scenario_planning/motion_velocity_smoother + - node_name: /planning/scenario_planning/lane_driving/motion_planning/container_logger_configure logger_name: tier4_autoware_utils # ============================================================ @@ -83,19 +85,19 @@ Control: lateral_controller: - node_name: /control/trajectory_follower/controller_node_exe logger_name: control.trajectory_follower.controller_node_exe.lateral_controller - - node_name: /control/trajectory_follower/controller_node_exe + - node_name: /control/container_logger_configure logger_name: tier4_autoware_utils longitudinal_controller: - node_name: /control/trajectory_follower/controller_node_exe logger_name: control.trajectory_follower.controller_node_exe.longitudinal_controller - - node_name: /control/trajectory_follower/controller_node_exe + - node_name: /control/container_logger_configure logger_name: tier4_autoware_utils vehicle_cmd_gate: - node_name: /control/vehicle_cmd_gate logger_name: control.vehicle_cmd_gate - - node_name: /control/vehicle_cmd_gate + - node_name: /control/container_logger_configure logger_name: tier4_autoware_utils # ============================================================ @@ -104,17 +106,9 @@ Control: Common: tier4_autoware_utils: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/container_logger_configure logger_name: tier4_autoware_utils - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner + - node_name: /planning/scenario_planning/lane_driving/motion_planning/container_logger_configure logger_name: tier4_autoware_utils - - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner - logger_name: tier4_autoware_utils - - node_name: /planning/scenario_planning/lane_driving/motion_planning/path_smoother - logger_name: tier4_autoware_utils - - node_name: /planning/scenario_planning/motion_velocity_smoother - logger_name: tier4_autoware_utils - - node_name: /control/trajectory_follower/controller_node_exe - logger_name: tier4_autoware_utils - - node_name: /control/vehicle_cmd_gate + - node_name: /control/container_logger_configure logger_name: tier4_autoware_utils diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a63e7f547fef1..4e58e7898b6bb 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -381,6 +381,12 @@ def launch_setup(context, *args, **kwargs): package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ + ComposableNode( + package="tier4_autoware_utils", + plugin="tier4_autoware_utils::LoggerLevelConfigureNode", + name="container_logger_configure", + namespace="control_validator_container", + ), control_validator_component, ComposableNode( package="glog_component", diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index 4bfefa4d93747..0f18c6e07d705 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -13,8 +13,10 @@ external_cmd_converter external_cmd_selector + glog_component lane_departure_checker shift_decider + tier4_autoware_utils trajectory_follower_node vehicle_cmd_gate diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index aa649710836da..9ef1a80595b27 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -182,6 +182,7 @@ + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 18de04fd9e317..4b904ff48c7cd 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -6,6 +6,10 @@ + + + + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 0a30204ca3c99..f4b2e13b082e2 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -27,6 +27,7 @@ + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 950ef67865a85..62c200eab5070 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -74,6 +74,7 @@ planning_validator scenario_selector surround_obstacle_checker + tier4_autoware_utils ament_lint_auto autoware_lint_common diff --git a/planning/mission_planner/launch/mission_planner.launch.xml b/planning/mission_planner/launch/mission_planner.launch.xml index eca6d05bb9463..8df1198ab3fe0 100644 --- a/planning/mission_planner/launch/mission_planner.launch.xml +++ b/planning/mission_planner/launch/mission_planner.launch.xml @@ -5,6 +5,7 @@ + From 774e6883db8bdf49438ced4d7837cd6c305fd1f4 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 18 Apr 2024 13:01:43 +0900 Subject: [PATCH 049/192] feat(crosswalk): restricts to enter the IGNORE status (#6834) Signed-off-by: Yuki Takagi --- .../src/scene_crosswalk.cpp | 2 +- .../src/scene_crosswalk.hpp | 19 ++++++++++++++----- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 7caf8651d8b33..86038c721604d 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -1075,7 +1075,7 @@ void CrosswalkModule::updateObjectState( object_info_manager_.update( obj_uuid, obj_pos, std::hypot(obj_vel.x, obj_vel.y), clock_->now(), is_ego_yielding, has_traffic_light, collision_point, object.classification.front().label, planner_param_, - crosswalk_.polygon2d().basicPolygon()); + crosswalk_.polygon2d().basicPolygon(), attention_area); const auto collision_state = object_info_manager_.getCollisionState(obj_uuid); if (collision_point) { diff --git a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index d2468e7f31aa7..bc89936fe883a 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -180,7 +180,8 @@ class CrosswalkModule : public SceneModuleInterface void transitState( const rclcpp::Time & now, const geometry_msgs::msg::Point & position, const double vel, const bool is_ego_yielding, const std::optional & collision_point, - const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon) + const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon, + const bool is_object_on_ego_path) { const bool is_stopped = vel < planner_param.stop_object_velocity; @@ -200,7 +201,7 @@ class CrosswalkModule : public SceneModuleInterface planner_param.timeout_set_for_no_intention_to_walk, distance_to_crosswalk); const bool intent_to_cross = (now - *time_to_start_stopped).seconds() < timeout_no_intention_to_walk; - if (is_ego_yielding && !intent_to_cross) { + if (is_ego_yielding && !intent_to_cross && !is_object_on_ego_path) { collision_state = CollisionState::IGNORE; return; } @@ -253,14 +254,21 @@ class CrosswalkModule : public SceneModuleInterface const std::string & uuid, const geometry_msgs::msg::Point & position, const double vel, const rclcpp::Time & now, const bool is_ego_yielding, const bool has_traffic_light, const std::optional & collision_point, const uint8_t classification, - const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon) + const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon, + const Polygon2d & attention_area) { // update current uuids current_uuids_.push_back(uuid); + const bool is_object_on_ego_path = + boost::geometry::distance(tier4_autoware_utils::fromMsg(position).to_2d(), attention_area) < + 0.5; + // add new object if (objects.count(uuid) == 0) { - if (has_traffic_light && planner_param.disable_yield_for_new_stopped_object) { + if ( + has_traffic_light && planner_param.disable_yield_for_new_stopped_object && + !is_object_on_ego_path) { objects.emplace(uuid, ObjectInfo{CollisionState::IGNORE}); } else { objects.emplace(uuid, ObjectInfo{CollisionState::YIELD}); @@ -269,7 +277,8 @@ class CrosswalkModule : public SceneModuleInterface // update object state objects.at(uuid).transitState( - now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon); + now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon, + is_object_on_ego_path); objects.at(uuid).collision_point = collision_point; objects.at(uuid).position = position; objects.at(uuid).classification = classification; From a336fa8e8a1053753442ac8d2faf491f4a8f58fb Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Thu, 18 Apr 2024 13:03:00 +0900 Subject: [PATCH 050/192] feat(obstacle_cruise): ignore right beside objects (#6754) * ignore near beside objects * change a magic num Signed-off-by: Yuki Takagi --- .../config/obstacle_cruise_planner.param.yaml | 2 +- planning/obstacle_cruise_planner/src/node.cpp | 66 +++++++++++++------ .../src/polygon_utils.cpp | 44 ------------- 3 files changed, 48 insertions(+), 64 deletions(-) diff --git a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index 5b634823302c0..bd9c5750af78f 100644 --- a/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml +++ b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml @@ -87,7 +87,7 @@ obstacle_traj_angle_threshold : 1.22 # [rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop stop: - max_lat_margin: 0.2 # lateral margin between obstacle and trajectory band with ego's width + max_lat_margin: 0.3 # lateral margin between obstacle and trajectory band with ego's width crossing_obstacle: collision_time_margin : 4.0 # time threshold of collision between obstacle adn ego for cruise or stop [s] diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index a069b4b6f9395..43400acb86bd9 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -552,9 +552,10 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin) const { const auto & p = behavior_determination_param_; - const bool is_enable_current_pose_consideration = p.enable_to_consider_current_pose; - const double step_length = p.decimate_trajectory_step_length; - const double time_to_convergence = p.time_to_convergence; + + const double front_length = vehicle_info.max_longitudinal_offset_m; + const double rear_length = vehicle_info.rear_overhang_m; + const double vehicle_width = vehicle_info.vehicle_width_m; const size_t nearest_idx = motion_utils::findNearestSegmentIndex(traj_points, current_ego_pose.position); @@ -563,41 +564,68 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( tier4_autoware_utils::inverseTransformPose(current_ego_pose, nearest_pose); const double current_ego_lat_error = current_ego_pose_error.position.y; const double current_ego_yaw_error = tf2::getYaw(current_ego_pose_error.orientation); - double time_elapsed = 0.0; - - std::vector polygons; - std::vector last_poses = {traj_points.at(0).pose}; - if (is_enable_current_pose_consideration) { - last_poses.push_back(current_ego_pose); - } + double time_elapsed{0.0}; + std::vector output_polygons; + Polygon2d tmp_polys{}; for (size_t i = 0; i < traj_points.size(); ++i) { std::vector current_poses = {traj_points.at(i).pose}; // estimate the future ego pose with assuming that the pose error against the reference path // will decrease to zero by the time_to_convergence - if (is_enable_current_pose_consideration && time_elapsed < time_to_convergence) { - const double rem_ratio = (time_to_convergence - time_elapsed) / time_to_convergence; + if (p.enable_to_consider_current_pose && time_elapsed < p.time_to_convergence) { + const double rem_ratio = (p.time_to_convergence - time_elapsed) / p.time_to_convergence; geometry_msgs::msg::Pose indexed_pose_err; indexed_pose_err.set__orientation( tier4_autoware_utils::createQuaternionFromYaw(current_ego_yaw_error * rem_ratio)); indexed_pose_err.set__position( tier4_autoware_utils::createPoint(0.0, current_ego_lat_error * rem_ratio, 0.0)); - current_poses.push_back( tier4_autoware_utils::transformPose(indexed_pose_err, traj_points.at(i).pose)); - if (traj_points.at(i).longitudinal_velocity_mps != 0.0) { - time_elapsed += step_length / std::abs(traj_points.at(i).longitudinal_velocity_mps); + time_elapsed += + p.decimate_trajectory_step_length / std::abs(traj_points.at(i).longitudinal_velocity_mps); } else { time_elapsed = std::numeric_limits::max(); } } - polygons.push_back( - polygon_utils::createOneStepPolygon(last_poses, current_poses, vehicle_info, lat_margin)); - last_poses = current_poses; + + Polygon2d idx_poly{}; + for (const auto & pose : current_poses) { + if (i == 0 && traj_points.at(i).longitudinal_velocity_mps > 1e-3) { + boost::geometry::append( + idx_poly, + tier4_autoware_utils::toFootprint(pose, front_length, rear_length, vehicle_width) + .outer()); + boost::geometry::append( + idx_poly, + tier4_autoware_utils::fromMsg(tier4_autoware_utils::calcOffsetPose( + pose, front_length, vehicle_width * 0.5 + lat_margin, 0.0) + .position) + .to_2d()); + boost::geometry::append( + idx_poly, tier4_autoware_utils::fromMsg( + tier4_autoware_utils::calcOffsetPose( + pose, front_length, -vehicle_width * 0.5 - lat_margin, 0.0) + .position) + .to_2d()); + } else { + boost::geometry::append( + idx_poly, tier4_autoware_utils::toFootprint( + pose, front_length, rear_length, vehicle_width + lat_margin * 2.0) + .outer()); + } + } + + boost::geometry::append(tmp_polys, idx_poly.outer()); + Polygon2d hull_polygon; + boost::geometry::convex_hull(tmp_polys, hull_polygon); + boost::geometry::correct(hull_polygon); + + output_polygons.push_back(hull_polygon); + tmp_polys = std::move(idx_poly); } - return polygons; + return output_polygons; } std::vector ObstacleCruisePlannerNode::convertToObstacles( diff --git a/planning/obstacle_cruise_planner/src/polygon_utils.cpp b/planning/obstacle_cruise_planner/src/polygon_utils.cpp index 6b422fbda5118..fa5a96b934f7a 100644 --- a/planning/obstacle_cruise_planner/src/polygon_utils.cpp +++ b/planning/obstacle_cruise_planner/src/polygon_utils.cpp @@ -20,18 +20,6 @@ namespace { -void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) -{ - Point2d point(geom_point.x, geom_point.y); - bg::append(polygon.outer(), point); -} - -geometry_msgs::msg::Point calcOffsetPosition( - const geometry_msgs::msg::Pose & pose, const double offset_x, const double offset_y) -{ - return tier4_autoware_utils::calcOffsetPose(pose, offset_x, offset_y, 0.0).position; -} - PointWithStamp calcNearestCollisionPoint( const size_t first_within_idx, const std::vector & collision_points, const std::vector & decimated_traj_points, const bool is_driving_forward) @@ -104,38 +92,6 @@ std::optional>> getCollisionIndex( namespace polygon_utils { -Polygon2d createOneStepPolygon( - const std::vector & last_poses, - const std::vector & current_poses, - const vehicle_info_util::VehicleInfo & vehicle_info, const double lat_margin) -{ - Polygon2d polygon; - - const double base_to_front = vehicle_info.max_longitudinal_offset_m; - const double width = vehicle_info.vehicle_width_m / 2.0 + lat_margin; - const double base_to_rear = vehicle_info.rear_overhang_m; - - for (auto & pose : last_poses) { - appendPointToPolygon(polygon, calcOffsetPosition(pose, base_to_front, width)); - appendPointToPolygon(polygon, calcOffsetPosition(pose, base_to_front, -width)); - appendPointToPolygon(polygon, calcOffsetPosition(pose, -base_to_rear, -width)); - appendPointToPolygon(polygon, calcOffsetPosition(pose, -base_to_rear, width)); - } - for (auto & pose : current_poses) { - appendPointToPolygon(polygon, calcOffsetPosition(pose, base_to_front, width)); - appendPointToPolygon(polygon, calcOffsetPosition(pose, base_to_front, -width)); - appendPointToPolygon(polygon, calcOffsetPosition(pose, -base_to_rear, -width)); - appendPointToPolygon(polygon, calcOffsetPosition(pose, -base_to_rear, width)); - } - - bg::correct(polygon); - - Polygon2d hull_polygon; - bg::convex_hull(polygon, hull_polygon); - - return hull_polygon; -} - std::optional> getCollisionPoint( const std::vector & traj_points, const std::vector & traj_polygons, const Obstacle & obstacle, const bool is_driving_forward, From 52c8df5ea70f5ba85a0f48c38356e6d60388b66c Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 18 Apr 2024 15:46:45 +0900 Subject: [PATCH 051/192] feat(behavior_path_planner_common): add safety target object located on shoulder lane (#6839) feat(behavior_path_planner_common): add target object located on shoulder lane Signed-off-by: kyoichi-sugahara --- .../path_safety_checker/objects_filtering.cpp | 20 ++++++++++++++++--- .../src/start_planner_module.cpp | 16 ++++++++++++--- 2 files changed, 30 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index ea9872f268678..91d743df11ca2 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -330,8 +330,9 @@ TargetObjectsOnLane createTargetObjectsOnLane( lanelet::ConstLanelets all_left_lanelets; lanelet::ConstLanelets all_right_lanelets; + // TODO(sugahara): consider right side parking and define right shoulder lanelets + lanelet::ConstLanelets all_left_shoulder_lanelets; - // Define lambda functions to update left and right lanelets const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) { const auto left_lanelets = route_handler->getAllLeftSharedLinestringLanelets( target_lane, include_opposite, invert_opposite); @@ -345,13 +346,23 @@ TargetObjectsOnLane createTargetObjectsOnLane( all_right_lanelets.end(), right_lanelets.begin(), right_lanelets.end()); }; - // Update left and right lanelets for each current lane + const auto update_left_shoulder_lanelet = [&](const lanelet::ConstLanelet & target_lane) { + lanelet::ConstLanelet neighbor_shoulder_lane{}; + const bool shoulder_lane_is_found = + route_handler->getLeftShoulderLanelet(target_lane, &neighbor_shoulder_lane); + if (shoulder_lane_is_found) { + all_left_shoulder_lanelets.insert(all_left_shoulder_lanelets.end(), neighbor_shoulder_lane); + } + }; + for (const auto & current_lane : current_lanes) { update_left_lanelets(current_lane); update_right_lanelets(current_lane); + update_left_shoulder_lanelet(current_lane); } TargetObjectsOnLane target_objects_on_lane{}; + const auto append_objects_on_lane = [&](auto & lane_objects, const auto & check_lanes) { std::for_each( filtered_objects.objects.begin(), filtered_objects.objects.end(), [&](const auto & object) { @@ -362,7 +373,7 @@ TargetObjectsOnLane createTargetObjectsOnLane( }); }; - // TODO(Sugahara): Consider shoulder and other lane objects + // TODO(Sugahara): Consider other lane objects if (object_lane_configuration.check_current_lane && !current_lanes.empty()) { append_objects_on_lane(target_objects_on_lane.on_current_lane, current_lanes); } @@ -372,6 +383,9 @@ TargetObjectsOnLane createTargetObjectsOnLane( if (object_lane_configuration.check_right_lane && !all_right_lanelets.empty()) { append_objects_on_lane(target_objects_on_lane.on_right_lane, all_right_lanelets); } + if (object_lane_configuration.check_shoulder_lane && !all_left_shoulder_lanelets.empty()) { + append_objects_on_lane(target_objects_on_lane.on_shoulder_lane, all_left_shoulder_lanelets); + } return target_objects_on_lane; } diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index 4433020605056..be6b6acef64bd 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -16,6 +16,7 @@ #include "behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" +#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_start_planner_module/debug.hpp" #include "behavior_path_start_planner_module/util.hpp" @@ -39,6 +40,7 @@ #include using behavior_path_planner::utils::parking_departure::initializeCollisionCheckDebugMap; +using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; using motion_utils::calcLateralOffset; using motion_utils::calcLongitudinalOffsetPose; using tier4_autoware_utils::calcOffsetPose; @@ -1324,10 +1326,18 @@ bool StartPlannerModule::isSafePath() const debug_data_.target_objects_on_lane = target_objects_on_lane; debug_data_.ego_predicted_path = ego_predicted_path; } - + std::vector merged_target_object; + merged_target_object.reserve( + target_objects_on_lane.on_current_lane.size() + target_objects_on_lane.on_shoulder_lane.size()); + merged_target_object.insert( + merged_target_object.end(), target_objects_on_lane.on_current_lane.begin(), + target_objects_on_lane.on_current_lane.end()); + merged_target_object.insert( + merged_target_object.end(), target_objects_on_lane.on_shoulder_lane.begin(), + target_objects_on_lane.on_shoulder_lane.end()); return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( - pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane, - debug_data_.collision_check, planner_data_->parameters, safety_check_params_->rss_params, + pull_out_path, ego_predicted_path, merged_target_object, debug_data_.collision_check, + planner_data_->parameters, safety_check_params_->rss_params, objects_filtering_params_->use_all_predicted_path, hysteresis_factor); } From fac57c955c46e63ed3f33e9b3d11f11fe22715c5 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 18 Apr 2024 17:00:37 +0900 Subject: [PATCH 052/192] revert: "feat(logger_level_configure): make it possible to change level of container logger (#6823)" (#6842) This reverts commit 51b5f830780eb69bd1a7dfe60e295773f394fd8e. --- common/tier4_autoware_utils/CMakeLists.txt | 5 ---- .../ros/logger_level_configure.hpp | 5 ---- common/tier4_autoware_utils/package.xml | 1 - .../src/ros/logger_level_configure.cpp | 7 ----- .../config/logger_config.yaml | 30 +++++++++++-------- .../launch/control.launch.py | 6 ---- launch/tier4_control_launch/package.xml | 2 -- .../behavior_planning.launch.xml | 1 - .../motion_planning.launch.xml | 4 --- .../scenario_planning.launch.xml | 1 - launch/tier4_planning_launch/package.xml | 1 - .../launch/mission_planner.launch.xml | 1 - 12 files changed, 18 insertions(+), 46 deletions(-) diff --git a/common/tier4_autoware_utils/CMakeLists.txt b/common/tier4_autoware_utils/CMakeLists.txt index f9bc00f891879..9cb54e52362a5 100644 --- a/common/tier4_autoware_utils/CMakeLists.txt +++ b/common/tier4_autoware_utils/CMakeLists.txt @@ -18,11 +18,6 @@ ament_auto_add_library(tier4_autoware_utils SHARED src/system/backtrace.cpp ) -rclcpp_components_register_node(tier4_autoware_utils - PLUGIN "tier4_autoware_utils::LoggerLevelConfigureNode" - EXECUTABLE logger_level_configure_node -) - if(BUILD_TESTING) find_package(ament_cmake_ros REQUIRED) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp index 9aca59e4fa514..5aee3a251dad2 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp @@ -64,10 +64,5 @@ class LoggerLevelConfigure const ConfigLogger::Response::SharedPtr response); }; -class LoggerLevelConfigureNode : public rclcpp::Node, public LoggerLevelConfigure -{ -public: - explicit LoggerLevelConfigureNode(const rclcpp::NodeOptions & node_options); -}; } // namespace tier4_autoware_utils #endif // TIER4_AUTOWARE_UTILS__ROS__LOGGER_LEVEL_CONFIGURE_HPP_ diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index 8cac2809a13b3..c34d3b5fdfdd0 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -23,7 +23,6 @@ pcl_conversions pcl_ros rclcpp - rclcpp_components tf2 tf2_geometry_msgs tier4_debug_msgs diff --git a/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp b/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp index 39950d806a9f6..d764299290d05 100644 --- a/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp +++ b/common/tier4_autoware_utils/src/ros/logger_level_configure.cpp @@ -58,11 +58,4 @@ void LoggerLevelConfigure::onLoggerConfigService( return; } -LoggerLevelConfigureNode::LoggerLevelConfigureNode(const rclcpp::NodeOptions & node_options) -: Node("logger_level_configure_node", node_options), LoggerLevelConfigure(this) -{ -} - } // namespace tier4_autoware_utils -#include -RCLCPP_COMPONENTS_REGISTER_NODE(tier4_autoware_utils::LoggerLevelConfigureNode) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index c7bc1cc835ebc..a298967a31af9 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -31,14 +31,12 @@ Planning: behavior_path_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/container_logger_configure + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: tier4_autoware_utils behavior_path_planner_avoidance: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance - - node_name: /planning/scenario_planning/lane_driving/behavior_planning - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils behavior_path_planner_goal_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner @@ -59,7 +57,7 @@ Planning: behavior_velocity_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/container_logger_configure + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner logger_name: tier4_autoware_utils behavior_velocity_planner_intersection: @@ -69,13 +67,13 @@ Planning: motion_obstacle_avoidance: - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner logger_name: planning.scenario_planning.lane_driving.motion_planning.obstacle_avoidance_planner - - node_name: /planning/scenario_planning/lane_driving/motion_planning/container_logger_configure + - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner logger_name: tier4_autoware_utils motion_velocity_smoother: - node_name: /planning/scenario_planning/motion_velocity_smoother logger_name: planning.scenario_planning.motion_velocity_smoother - - node_name: /planning/scenario_planning/lane_driving/motion_planning/container_logger_configure + - node_name: /planning/scenario_planning/motion_velocity_smoother logger_name: tier4_autoware_utils # ============================================================ @@ -85,19 +83,19 @@ Control: lateral_controller: - node_name: /control/trajectory_follower/controller_node_exe logger_name: control.trajectory_follower.controller_node_exe.lateral_controller - - node_name: /control/container_logger_configure + - node_name: /control/trajectory_follower/controller_node_exe logger_name: tier4_autoware_utils longitudinal_controller: - node_name: /control/trajectory_follower/controller_node_exe logger_name: control.trajectory_follower.controller_node_exe.longitudinal_controller - - node_name: /control/container_logger_configure + - node_name: /control/trajectory_follower/controller_node_exe logger_name: tier4_autoware_utils vehicle_cmd_gate: - node_name: /control/vehicle_cmd_gate logger_name: control.vehicle_cmd_gate - - node_name: /control/container_logger_configure + - node_name: /control/vehicle_cmd_gate logger_name: tier4_autoware_utils # ============================================================ @@ -106,9 +104,17 @@ Control: Common: tier4_autoware_utils: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/container_logger_configure + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: tier4_autoware_utils - - node_name: /planning/scenario_planning/lane_driving/motion_planning/container_logger_configure + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner logger_name: tier4_autoware_utils - - node_name: /control/container_logger_configure + - node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner + logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/lane_driving/motion_planning/path_smoother + logger_name: tier4_autoware_utils + - node_name: /planning/scenario_planning/motion_velocity_smoother + logger_name: tier4_autoware_utils + - node_name: /control/trajectory_follower/controller_node_exe + logger_name: tier4_autoware_utils + - node_name: /control/vehicle_cmd_gate logger_name: tier4_autoware_utils diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 4e58e7898b6bb..a63e7f547fef1 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -381,12 +381,6 @@ def launch_setup(context, *args, **kwargs): package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ - ComposableNode( - package="tier4_autoware_utils", - plugin="tier4_autoware_utils::LoggerLevelConfigureNode", - name="container_logger_configure", - namespace="control_validator_container", - ), control_validator_component, ComposableNode( package="glog_component", diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index 0f18c6e07d705..4bfefa4d93747 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -13,10 +13,8 @@ external_cmd_converter external_cmd_selector - glog_component lane_departure_checker shift_decider - tier4_autoware_utils trajectory_follower_node vehicle_cmd_gate diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 9ef1a80595b27..aa649710836da 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -182,7 +182,6 @@ - diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index 4b904ff48c7cd..18de04fd9e317 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -6,10 +6,6 @@ - - - - diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index f4b2e13b082e2..0a30204ca3c99 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -27,7 +27,6 @@ - diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 62c200eab5070..950ef67865a85 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -74,7 +74,6 @@ planning_validator scenario_selector surround_obstacle_checker - tier4_autoware_utils ament_lint_auto autoware_lint_common diff --git a/planning/mission_planner/launch/mission_planner.launch.xml b/planning/mission_planner/launch/mission_planner.launch.xml index 8df1198ab3fe0..eca6d05bb9463 100644 --- a/planning/mission_planner/launch/mission_planner.launch.xml +++ b/planning/mission_planner/launch/mission_planner.launch.xml @@ -5,7 +5,6 @@ - From 3adffc3c33e5381349ad4f4f6e827b0e2bf24ca3 Mon Sep 17 00:00:00 2001 From: Kento Yabuuchi Date: Thu, 18 Apr 2024 17:01:55 +0900 Subject: [PATCH 053/192] perf(pointcloud_preprocessor): prevent excessive log and speed up a bit (#6843) * provide only one warning Signed-off-by: Kento Yabuuchi * associate only one time Signed-off-by: Kento Yabuuchi * Revert "associate only one time" This reverts commit 984d028ea46e05f75df7b28e8dd8bd9693df1cc6. * remove redundant for loop and rclcpp::Time instantiation Signed-off-by: Kento Yabuuchi --------- Signed-off-by: Kento Yabuuchi --- .../distortion_corrector.cpp | 40 ++++++++++++------- 1 file changed, 25 insertions(+), 15 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index d1d91ed7ec439..b90a64dc47c91 100644 --- a/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -242,6 +242,16 @@ bool DistortionCorrectorComponent::undistortPointCloud( // For performance, avoid transform computation if unnecessary bool need_transform = points.header.frame_id != base_link_frame_; + // For performance, do not instantiate `rclcpp::Time` inside of the for-loop + double imu_stamp{0.0}; + if (use_imu_ && !angular_velocity_queue_.empty()) { + imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds(); + } + + // If there is a point that cannot be associated, record it to issue a warning + bool twist_time_stamp_is_too_late = false; + bool imu_time_stamp_is_too_late = false; + for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_time_stamp) { while (twist_it != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) { ++twist_it; @@ -252,32 +262,19 @@ bool DistortionCorrectorComponent::undistortPointCloud( float w{static_cast(twist_it->twist.angular.z)}; if (std::abs(*it_time_stamp - twist_stamp) > 0.1) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), 10000 /* ms */, - "twist time_stamp is too late. Could not interpolate."); + twist_time_stamp_is_too_late = true; v = 0.0f; w = 0.0f; } if (use_imu_ && !angular_velocity_queue_.empty()) { - // For performance, do not instantiate `rclcpp::Time` inside of the for-loop - double imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds(); - - for (; - (imu_it != std::end(angular_velocity_queue_) - 1 && - *it_time_stamp > rclcpp::Time(imu_it->header.stamp).seconds()); - ++imu_it) { - } - while (imu_it != std::end(angular_velocity_queue_) - 1 && *it_time_stamp > imu_stamp) { ++imu_it; imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds(); } if (std::abs(*it_time_stamp - imu_stamp) > 0.1) { - RCLCPP_WARN_STREAM_THROTTLE( - get_logger(), *get_clock(), 10000 /* ms */, - "imu time_stamp is too late. Could not interpolate."); + imu_time_stamp_is_too_late = true; } else { w = static_cast(imu_it->vector.z); } @@ -314,6 +311,19 @@ bool DistortionCorrectorComponent::undistortPointCloud( prev_time_stamp_sec = *it_time_stamp; } + + if (twist_time_stamp_is_too_late) { + RCLCPP_WARN_STREAM_THROTTLE( + get_logger(), *get_clock(), 10000 /* ms */, + "twist time_stamp is too late. Could not interpolate."); + } + + if (imu_time_stamp_is_too_late) { + RCLCPP_WARN_STREAM_THROTTLE( + get_logger(), *get_clock(), 10000 /* ms */, + "imu time_stamp is too late. Could not interpolate."); + } + return true; } From b34e5202ed7f4f8fc6c31a23626a18e3fa561b89 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Fri, 19 Apr 2024 11:50:25 +0900 Subject: [PATCH 054/192] chore: added sensing members to sensing related packages (#6751) Signed-off-by: Kenzo Lobos-Tsunekawa --- sensing/image_transport_decompressor/package.xml | 1 + sensing/livox/livox_tag_filter/package.xml | 1 + sensing/pointcloud_preprocessor/package.xml | 2 ++ 3 files changed, 4 insertions(+) diff --git a/sensing/image_transport_decompressor/package.xml b/sensing/image_transport_decompressor/package.xml index 264a8f249da3f..ed7ae7ae060b5 100644 --- a/sensing/image_transport_decompressor/package.xml +++ b/sensing/image_transport_decompressor/package.xml @@ -5,6 +5,7 @@ 0.0.0 The image_transport_decompressor package Yukihiro Saito + Kenzo Lobos-Tsunekawa Apache License 2.0 diff --git a/sensing/livox/livox_tag_filter/package.xml b/sensing/livox/livox_tag_filter/package.xml index 4fe994766027b..2b3d429480ef7 100644 --- a/sensing/livox/livox_tag_filter/package.xml +++ b/sensing/livox/livox_tag_filter/package.xml @@ -5,6 +5,7 @@ 0.1.0 The livox_tag_filter package Ryohsuke Mitsudome + Kenzo Lobos-Tsunekawa Apache License 2.0 ament_cmake_auto diff --git a/sensing/pointcloud_preprocessor/package.xml b/sensing/pointcloud_preprocessor/package.xml index 73f40cc4b44b0..d12181f498dea 100644 --- a/sensing/pointcloud_preprocessor/package.xml +++ b/sensing/pointcloud_preprocessor/package.xml @@ -9,6 +9,8 @@ Shunsuke Miura Kyoichi Sugahara Dai Nguyen + Kenzo Lobos-Tsunekawa + Yihsiang Fang Apache License 2.0 From e11b1f4555af55ac246a140905fd6adc2e823680 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 19 Apr 2024 16:14:00 +0900 Subject: [PATCH 055/192] refactor(lane_change): make return previous output a common function (#6784) * refactor(lane_change): make return previous output a common function Signed-off-by: Zulfaqar Azmi * Replace all prev module's variable Signed-off-by: Zulfaqar Azmi * fix build error in ablc Signed-off-by: Zulfaqar Azmi * slight refactoring Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../src/scene.cpp | 2 +- .../utils/base_class.hpp | 25 +------ .../src/interface.cpp | 5 +- .../src/scene.cpp | 66 +++++++------------ 4 files changed, 29 insertions(+), 69 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 27c6713adfead..63965bc15986f 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -125,7 +125,7 @@ AvoidancePlanningData AvoidanceByLaneChange::calcAvoidancePlanningData( // reference pose data.reference_pose = getEgoPose(); - data.reference_path_rough = prev_module_path_; + data.reference_path_rough = prev_module_output_.path; const auto resample_interval = avoidance_parameters_->resample_interval_for_planning; data.reference_path = utils::resamplePathWithSpline(data.reference_path_rough, resample_interval); diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index 3efc0c9dd61dc..e1d7725f93259 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -111,25 +111,9 @@ class LaneChangeBase virtual bool specialExpiredCheck() const { return false; } - virtual void setPreviousModulePaths( - const PathWithLaneId & prev_module_reference_path, const PathWithLaneId & prev_module_path) + void setPreviousModuleOutput(const BehaviorModuleOutput & prev_module_output) { - if (!prev_module_reference_path.points.empty()) { - prev_module_reference_path_ = prev_module_reference_path; - } - if (!prev_module_path.points.empty()) { - prev_module_path_ = prev_module_path; - } - }; - - virtual void setPreviousDrivableAreaInfo(const DrivableAreaInfo & prev_drivable_area_info) - { - prev_drivable_area_info_ = prev_drivable_area_info; - } - - virtual void setPreviousTurnSignalInfo(const TurnSignalInfo & prev_turn_signal_info) - { - prev_turn_signal_info_ = prev_turn_signal_info; + prev_module_output_ = prev_module_output; } virtual void updateSpecialData() {} @@ -233,10 +217,7 @@ class LaneChangeBase std::shared_ptr lane_change_parameters_{}; std::shared_ptr abort_path_{}; std::shared_ptr planner_data_{}; - PathWithLaneId prev_module_reference_path_{}; - PathWithLaneId prev_module_path_{}; - DrivableAreaInfo prev_drivable_area_info_{}; - TurnSignalInfo prev_turn_signal_info_{}; + BehaviorModuleOutput prev_module_output_{}; std::optional lane_change_stop_pose_{std::nullopt}; PathWithLaneId prev_approved_path_{}; diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index af2ccb807d989..d3ad4fb284f77 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -76,10 +76,7 @@ bool LaneChangeInterface::isExecutionReady() const void LaneChangeInterface::updateData() { - module_type_->setPreviousModulePaths( - getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path); - module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info); - module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info); + module_type_->setPreviousModuleOutput(getPreviousModuleOutput()); module_type_->updateSpecialData(); if (isWaitingApproval()) { diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index db96f7c83d72a..d0e48be72e2cb 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -140,52 +140,41 @@ LaneChangePath NormalLaneChange::getLaneChangePath() const BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const { - BehaviorModuleOutput output; + auto output = prev_module_output_; if (isAbortState() && abort_path_) { output.path = abort_path_->path; - output.reference_path = prev_module_reference_path_; - output.turn_signal_info = prev_turn_signal_info_; extendOutputDrivableArea(output); const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, - planner_data_->parameters.ego_nearest_dist_threshold, + output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info, + output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); return output; } const auto current_lanes = getCurrentLanes(); if (current_lanes.empty()) { - RCLCPP_WARN(logger_, "Current lanes not found!!! Something wrong."); - output.path = prev_module_path_; - output.reference_path = prev_module_reference_path_; - output.drivable_area_info = prev_drivable_area_info_; - output.turn_signal_info = prev_turn_signal_info_; - return output; + RCLCPP_DEBUG(logger_, "Current lanes not found. Returning previous module's path as output."); + return prev_module_output_; } const auto terminal_path = calcTerminalLaneChangePath(current_lanes, getLaneChangeLanes(current_lanes, direction_)); if (!terminal_path) { - RCLCPP_DEBUG(logger_, "Terminal path not found!!!"); - output.path = prev_module_path_; - output.reference_path = prev_module_reference_path_; - output.drivable_area_info = prev_drivable_area_info_; - output.turn_signal_info = prev_turn_signal_info_; - return output; + RCLCPP_DEBUG(logger_, "Terminal path not found. Returning previous module's path as output."); + return prev_module_output_; } output.path = terminal_path->path; - output.reference_path = prev_module_reference_path_; output.turn_signal_info = updateOutputTurnSignal(); extendOutputDrivableArea(output); const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, - planner_data_->parameters.ego_nearest_dist_threshold, + output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info, + output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); return output; @@ -193,20 +182,14 @@ BehaviorModuleOutput NormalLaneChange::getTerminalLaneChangePath() const BehaviorModuleOutput NormalLaneChange::generateOutput() { - BehaviorModuleOutput output; - if (!status_.is_valid_path) { - output.path = prev_module_path_; - output.reference_path = prev_module_reference_path_; - output.drivable_area_info = prev_drivable_area_info_; - output.turn_signal_info = prev_turn_signal_info_; - return output; + RCLCPP_DEBUG(logger_, "No valid path found. Returning previous module's path as output."); + return prev_module_output_; } + auto output = prev_module_output_; if (isAbortState() && abort_path_) { output.path = abort_path_->path; - output.reference_path = prev_module_reference_path_; - output.turn_signal_info = prev_turn_signal_info_; insertStopPoint(status_.current_lanes, output.path); } else { output.path = getLaneChangePath().path; @@ -235,8 +218,8 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.use_prior_turn_signal( - output.path, getEgoPose(), current_seg_idx, prev_turn_signal_info_, output.turn_signal_info, - planner_data_->parameters.ego_nearest_dist_threshold, + output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info, + output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); return output; @@ -256,8 +239,8 @@ void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) c // for new architecture DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = expanded_lanes; - output.drivable_area_info = - utils::combineDrivableAreaInfo(current_drivable_area_info, prev_drivable_area_info_); + output.drivable_area_info = utils::combineDrivableAreaInfo( + current_drivable_area_info, prev_module_output_.drivable_area_info); } void NormalLaneChange::insertStopPoint( @@ -506,7 +489,7 @@ TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const lanelet::ConstLanelets NormalLaneChange::getCurrentLanes() const { - return utils::getCurrentLanesFromPath(prev_module_path_, planner_data_); + return utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_); } lanelet::ConstLanelets NormalLaneChange::getLaneChangeLanes( @@ -738,10 +721,10 @@ std::pair NormalLaneChange::calcCurrentMinMaxAcceleration() cons const auto vehicle_max_acc = std::min(p.max_acc, lane_change_parameters_->max_longitudinal_acc); const auto ego_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - prev_module_path_.points, getEgoPose(), p.ego_nearest_dist_threshold, + prev_module_output_.path.points, getEgoPose(), p.ego_nearest_dist_threshold, p.ego_nearest_yaw_threshold); const auto max_path_velocity = - prev_module_path_.points.at(ego_seg_idx).point.longitudinal_velocity_mps; + prev_module_output_.path.points.at(ego_seg_idx).point.longitudinal_velocity_mps; // calculate minimum and maximum acceleration const auto min_acc = utils::lane_change::calcMinimumAcceleration( @@ -765,7 +748,7 @@ double NormalLaneChange::calcMaximumLaneChangeLength( std::vector NormalLaneChange::sampleLongitudinalAccValues( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const { - if (prev_module_path_.points.empty()) { + if (prev_module_output_.path.points.empty()) { return {}; } @@ -852,7 +835,7 @@ PathWithLaneId NormalLaneChange::getPrepareSegment( return PathWithLaneId(); } - auto prepare_segment = prev_module_path_; + auto prepare_segment = prev_module_output_.path; const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( prepare_segment.points, getEgoPose(), 3.0, 1.0); utils::clipPathLength(prepare_segment, current_seg_idx, prepare_length, backward_path_length); @@ -1570,7 +1553,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( } const auto lane_changing_start_pose = motion_utils::calcLongitudinalOffsetPose( - prev_module_path_.points, current_lane_terminal_point, + prev_module_output_.path.points, current_lane_terminal_point, -(lane_change_buffer + next_lane_change_buffer + distance_to_terminal_from_goal)); if (!lane_changing_start_pose) { @@ -1653,7 +1636,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( lane_changing_start_pose.value(), target_segment.points.front().point.pose, target_lane_reference_path, shift_length); - auto reference_segment = prev_module_path_; + auto reference_segment = prev_module_output_.path; const double length_to_lane_changing_start = motion_utils::calcSignedArcLength( reference_segment.points, reference_segment.points.front().point.pose.position, lane_changing_start_pose->position); @@ -1877,7 +1860,7 @@ bool NormalLaneChange::calcAbortPath() RCLCPP_ERROR(logger_, "failed to generate abort shifted path."); } - PathWithLaneId reference_lane_segment = prev_module_path_; + auto reference_lane_segment = prev_module_output_.path; { const auto terminal_path = calcTerminalLaneChangePath(reference_lanelets, selected_path.info.target_lanes); @@ -2163,5 +2146,4 @@ bool NormalLaneChange::check_prepare_phase() const return check_in_intersection || check_in_turns || check_in_general_lanes; } - } // namespace behavior_path_planner From e5b3f608a9a75f9c918b3b1237dd23b94bb6de5b Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 19 Apr 2024 19:42:34 +0900 Subject: [PATCH 056/192] feat(dynamic_avoidance): avoid pedestrians (#6553) new feature: avoid against the pedestrians Signed-off-by: Yuki Takagi --- .../README.md | 30 +- .../config/dynamic_avoidance.param.yaml | 19 +- .../image/2024-04-18_15-13-01.png | Bin 0 -> 180084 bytes .../image/2024-04-18_15-32-03.png | Bin 0 -> 223740 bytes .../scene.hpp | 63 ++- .../src/manager.cpp | 17 + .../src/scene.cpp | 474 ++++++++++++++++-- 7 files changed, 547 insertions(+), 56 deletions(-) create mode 100644 planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-13-01.png create mode 100644 planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-32-03.png diff --git a/planning/behavior_path_dynamic_avoidance_module/README.md b/planning/behavior_path_dynamic_avoidance_module/README.md index 89a661d66735e..b8af767afd9a5 100644 --- a/planning/behavior_path_dynamic_avoidance_module/README.md +++ b/planning/behavior_path_dynamic_avoidance_module/README.md @@ -12,7 +12,7 @@ Obstacle Avoidance module modifies the path to be followed so that it fits withi Avoidance functions are also provided by the [Avoidance module](https://autowarefoundation.github.io/autoware.universe/main/planning/behavior_path_avoidance_module/), but these modules have different roles. The Avoidance module performs avoidance through the outside of own lanes but cannot avoid the moving objects. On the other hand, this module can avoid moving objects. -For this reason, the word "dynamic" is used in the modules's name. +For this reason, the word "dynamic" is used in the module's name. The table below lists the avoidance modules that can handle each situation. | | avoid within the own lane | avoid through the outside of own lanes | @@ -23,7 +23,7 @@ The table below lists the avoidance modules that can handle each situation. ## Policy of algorithms Here, we describe the policy of inner algorithms. -The inner algorithms can be separated into two parts: The first decide whether to avoid the obstacles and the second cuts off the drivable area against the corresponding obstacle. +The inner algorithms can be separated into two parts: The first decides whether to avoid the obstacles and the second cuts off the drivable area against the corresponding obstacle. ### Select obstacles to avoid @@ -36,7 +36,7 @@ The other, _can be avoided_ denotes whether it can be avoided without risk to th For this purpose, the module judges whether the obstacle can be avoided with satisfying the constraints of lateral acceleration and lateral jerk. For example, the module decides not to avoid an object that is too close or fast in the lateral direction. -### Cuts off the drivable area against the selected obstacles +### Cuts off the drivable area against the selected vehicles For the selected obstacles to be avoided, the module cuts off the drivable area. As inputs to decide the shapes of cut-off polygons, poses of the obstacles are mainly used, assuming they move in parallel to the ego's path, instead of its predicted path. @@ -45,7 +45,7 @@ Furthermore, the output drivable area shape is designed as a rectangular cutout #### Determination of lateral dimension -Lateral dimensions of the polygon is calculated as follows. +The lateral dimensions of the polygon are calculated as follows. The polygon's width to extract from the drivable area is the obstacle width and `drivable_area_generation.lat_offset_from_obstacle`. We can limit the lateral shift length by `drivable_area_generation.max_lat_offset_to_avoid`. @@ -55,7 +55,7 @@ We can limit the lateral shift length by `drivable_area_generation.max_lat_offse Then, extracting the same directional and opposite directional obstacles from the drivable area will work as follows considering TTC (time to collision). -Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g. The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.). +Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g., The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.). Same directional obstacles (Parameter names may differ from implementation) ![same_directional_object](./image/same_directional_object.svg) @@ -63,6 +63,26 @@ Same directional obstacles (Parameter names may differ from implementation) Opposite directional obstacles (Parameter names may differ from implementation) ![opposite_directional_object](./image/opposite_directional_object.svg) +### Cuts off the drivable area against the selected pedestrians + +Then, we describe the logic to generate the drivable areas against pedestrians to be avoided. +Objects of this type are considered to have priority right of way over the ego's vehicle while ensuring a minimum safety of the ego's vehicle. +In other words, the module assigns a drivable area to an obstacle with a specific margin based on the predicted paths with specific confidences for a specific time interval, as shown in the following figure. + +

+ +
Restriction areas are generated from each pedestrian's predicted paths
+
+ +Apart from polygons for objects, the module also generates another polygon to ensure the ego's safety, i.e., to avoid abrupt steering or significant changes from the path. +This is similar to avoidance against the vehicles and takes precedence over keeping a safe distance from the object to be avoided. +As a result, as shown in the figure below, the polygons around the objects reduced by the secured polygon of the ego are subtracted from the ego's drivable area. + +
+ +
Ego's minimum requirements are prioritized against object margin
+
+ ## Example
diff --git a/planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml b/planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml index 371f7da2fadf5..c1f4646ef7736 100644 --- a/planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml +++ b/planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml @@ -12,9 +12,9 @@ bus: true trailer: true unknown: false - bicycle: false + bicycle: true motorcycle: true - pedestrian: false + pedestrian: true max_obstacle_vel: 100.0 # [m/s] min_obstacle_vel: 0.0 # [m/s] @@ -38,8 +38,9 @@ crossing_object: min_overtaking_object_vel: 1.0 max_overtaking_object_angle: 1.05 - min_oncoming_object_vel: 0.0 + min_oncoming_object_vel: 1.0 max_oncoming_object_angle: 0.523 + max_pedestrian_crossing_vel: 0.8 front_object: max_object_angle: 0.785 @@ -54,7 +55,11 @@ object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] - lat_offset_from_obstacle: 0.8 # [m] + lat_offset_from_obstacle: 1.0 # [m] + margin_distance_around_pedestrian: 2.0 # [m] + predicted_path: + end_time_to_consider: 3.0 # [s] + threshold_confidence: 0.0 # [] not probability max_lat_offset_to_avoid: 0.5 # [m] max_time_for_object_lat_shift: 0.0 # [s] lpf_gain_for_lat_avoid_to_offset: 0.9 # [-] @@ -66,12 +71,12 @@ # for same directional object overtaking_object: max_time_to_collision: 40.0 # [s] - start_duration_to_avoid: 2.0 # [s] - end_duration_to_avoid: 4.0 # [s] + start_duration_to_avoid: 1.0 # [s] + end_duration_to_avoid: 1.0 # [s] duration_to_hold_avoidance: 3.0 # [s] # for opposite directional object oncoming_object: max_time_to_collision: 40.0 # [s] This value should be the same as overtaking_object's one to suppress chattering of this value for parked vehicles - start_duration_to_avoid: 12.0 # [s] + start_duration_to_avoid: 1.0 # [s] end_duration_to_avoid: 0.0 # [s] diff --git a/planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-13-01.png b/planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-13-01.png new file mode 100644 index 0000000000000000000000000000000000000000..719636ed295c04ef92641ffa872cb8767962bd24 GIT binary patch literal 180084 zcmY&=1yq#V_x6B-bazNdHwXwwhax2n(kVzYgh)yZjWno$l+@5I(k(*^NJ)1|mmqv+ zy!Zar|C=>yDYM===e#?fz4x>CI}z$?PjRuRupkf!?lVPsO$Y=H7XrCMgMkh{`8^+; z0sgt`Ci_eq1H61Otir+HlYh0X_jidcKEZ{13(W`03SE>6Ns!z3W*8 zAP{=UGkFx4`Y5dQPhU@&TcqDe?dSn%eS@CgnC_pb%b?hT2| z&&_dn*o7lvdshP03W$9u<>lpdn48C7U^6UdD=Yb3<|NwC&^HwZrFWt%gbvMr>n6>KY4)Nxo&3r{z2p1yOx%glJb+Y)6--x z1+cKZHa2P?#59YAk&y!>bC~sv2!SQnsi0q~dvbohF-~StKdW59_}`18COezqm%Ye6 zxlXPU-5m!H^RlUYmAe;z`~`)DBb#v;8FS!Er{1IE<4k7);J9`{qqZbInAXAB*^sos zIy25A*{LhFS|?v$8uVb9U27l;otVl>{&v6G2ypBQa9CeSy6TK#3aX)aI8Ti}mvT#} zNqN}dOU^|&Snr>gQdIVmPJa=PicO_H*j}iAP@)Y>VMnra4!*N`uASp;y)+( zidf`2Ep*89`)!T{kV?}KRx3zsZ34$m#xP7uwBr%1ncY(;<{9t|kgx68KhLeK)cAW> z$csmbCRA)~YYj#h7EF&+KLa(*CKatm$HsP=@rD0$*miR^pn|-_naPSD#n)>VyjfEv zx}0Ad8x{N#Cg$dFQ~Q}`{(xf=YOE>a$}Jr$0Rb-`U;0|`%DC$oztSI&VZ9vLIjxv> z$SDgfOcKA3?=F@x)ldJ=Js1%Eve(bcHZMZYSPdRaD*ACZSmyoU%gR(4pmre<9AHp| zHPKIUr<4hFCSaj!n#OD)&yW6-G9q(qD`a@1c#EsRPPP+T!lTkFY>iylfCEpC0USgV z9ywBxUW`3fsrtbVwy^)y(lYn&-f)hhzxSo>Tia4@t`HWgTTJ@r&mU`JW46yJ%7#Ur z|DOz&|37;f+bY@e!{ro43U+g62Ux$TYvbJU{N&E5FYGy+6nPIh%*wTFk2BON zQ#GNaTCemmgVi*FAJE|SI+$TdAJC=FIq|Mlg)8w;;B+_$NByI%c&gBjGE(quj=D$; zT+UY`5wm+eZEey|NVEIbWa$aszm9%>fjlCc>DDki(xAOGuc&@lL_uGKg(jOAzjrb- zqhHbIzR7)nJVM?I9|`#9`_W&0l2}ty>B@Oz6NGj0@B1~I;HM4hmgEseApVb4>5%@F zJV)txOK5HWu571WF^>xCc)r75KhSygf88n>T!VCPu_w7205FVRz(PG6n=Rnjw0KX4 zCSY43p*a<*ACRYol49Jw$ax5iEJ7qh?ZUU^W4{xEQLx6KbaQ{dJiLOB0K@F|=8rNK zww4hO`A?_wCQApce7n^{udK1HE)#U5tpjVXs;#SwYz|2v5)xFYWjsGUjcABY|7;Ks z3;n>=y|_pZjGyKI8lX;-iSwY&W8g~>uWW5GaB*<~4t|!$#x3?3c_s<`8k}BUnO|6# z<%|fN(k>F1MuQ)&@_j1ZtE@y{D|@Y%wG7CexkEbD!39d?KhA`>UfBXSR*?;~Vy>|# zUi<%qNBghv0EC^KoP;+=C$K+5UJVnac^7R7gkyF7Tw7&jWrdFd=P!&Rg%f_Helij_ z0gG~LFrt*x`1e@Yu3{NN6N~^rnd-(JA`LDt4Qr5BT`sAUz;*A(-V@7E`yUQy+>a!p zn%O&xEaGt&p~=w(a3W07{jxfuhB2oD^Z%eW+=T)eKei^mw}hhM;+E=i{=T~6T<%k* zCuqC*bESZfy+K7oGhnM#r_be}1rVE&QHCZ|7AV;O#0jLHt&`+sWIMGvq0B0ORBIXW zad5($No4-L7HPPql9}Z!RaBQyUbE_H4vPg@deKe!0Y7ZFC1}IQ__*M{&qq5gp7UB_ z>y`7X(Wxnn*xm=oC|4N0YdkHq|K~LSB}BS$p2^F<_(#R!=@XV~$Xhp*{iYSxrc{^3 z<*huP>XN+B>?Eyo9B?Pxn_F9iT-R_GWjy5F09@nDC!OAM*BwYKYHyc$uaf^}!7!>j zsIsy$@{%fior;d`sf|s+Ul1Y8L+yCXwFBY058+YR{}h zECOlX;)9#P-#j$ z!4umXJU?&p7d{o#hfvJR*3l!RYWtp0FCMMS7m0mZ=3x+243ANQ_;g|E@j z3kwMyiZTKbVou0L9pz-3kHWEa;PyJ9MfLsKTOgj%;5~iP9|2Hmc54`UzqFbtOWs-! zXHN5T?uKjyE30|&4*ENY`rr;3`yik#q1xg4WhfSQNCP8GR^zT=kig)9eO z#8)H1zwqn$QC5PIfT7=JbB*n(`L^YidivtX8Z^7Hky^Jnc^DIE(xn`jZ-xqhYoq5Lkq;$WvZ<|p$aaS!Q&3;uvyjfEX-nL} zK^$B+J`oX&#J(c_-JMKa0RWo+>UuXe;}Jpdnl-#e&FT9b0Maj$o6MF+KRFG%@KZW zLG9V4rFV8z2WgU!sBaE0RcPP?%4O0v7D=rtd&i9sC9>1{@i!q%7gv>+Ph!R6$kt?g z*1BS^O4K97*qK+A{ zcbNUCa?%GAY#LR^RlOYtj7C6PIjU;TX}J139|>xXhIDS<)ezE;CP#ioj~;Ivw`3Z0 z15uFpx6;ML#5g=>$w^qrBI0;@kLOcQU{nFQ?xeYw1G13x&JL2XNYXdFr6~8w6d}KO>YeKT1}59?hkGo@$M^Q;=H^ZB-&j8J z4t)LNXY@QSZNmN(q(vX;zT!r>6=QE0%+n`vUD2%1My3zK-{FCZ3o1ebGM}pTL$8t9 zSx!(#6v`$;)iLkL5-D@w7}-rQgk>YsnPN?Yq*7h`CzIPo{h6QA$!OLEHktHJ4IE|4 zw3LzPK>s(ZbTgG>G*D+pPj*S*Pp&pHOnKn}07u(|BU@qmWp%qnC70LGk(?X^14eM* zO{iCtV*H<$mFWdZx-BaC1eq9fs(NIYT`)ZOi&%Pp;HgNvU17s^?wG63b;@a z*&4J^c%a~`OBr)mDA2=LhVQvCgiX=K)}Yd2da_VQ))DcOBn{DiaUml1_;EK#KuJ+p zDT$MNEV%oPA8KCvpPyb3OYValn@gV+c2jUM?>@@rc*ZBT!xw`a>{FSdj#17ioC z2IS2~qbFtB(naS%JA#bB-nyV%-hEYdA7BPV5M-xFtB@95bB~m z*A$shOLZSVW?K7T8GIc8B(7~?QOm}Qyy0}&&hCU>Sh|DFJK@S->vo*m9b&bCyMf2L*ei_M1%=6wK$!1p7)ny|A(qYNYWtROMwupocc~ISZdwWOz$VpfBSkiph5fiD2*UO7ic7b9uv9LZn$J~q^g1j`}ICeA0d=KKJ@K9W5wF)R6!Pa2-|xpejXl{Le--blA_bh|~mF;9LQhzltw<3^-@X0h2-g&tlJN z*~pdnfzv14=`QCXfu4=Chp@1i&3)l7Kw-y%<=icX`%lj#Q6iHyGCU539HS%QL(TDaxUwM zp5O>vt6@upe|6z$m?C`%9MQS;%s?$MS(Q^a$yR5A+c2$a!fx#*R9o|Z8RlU7+qiJ7 zR}Kz1b8~Z$gwk(UkoLucd-VZS!!*>ZE2tpRjOQv)Xh;G<);i;pkzIqD?s`iojNxA= z$?JaBBd_hilWITj*5c6401>Zf@9D(?YG8b!6a}^${O0tXv^w~UgRGp{AyQ&N+z7N~ zXoCR4K$HX|W?w`KL&CcVFz&8mxM7cxC>~&n2>Q z^tUMNHSTxr+yMn>=Ia5AN;3zCXwookqW>aFKD-OaNqYz>aPi8OU(vn!x}_*cmxY7m z6}W5}PkQk#SV)u}4KiT=!wN@{zf`}SYz-CKI7jJs2vA&;@_)sKf$%RmMftUXol`8y z)_yXYnHjN))LAM3<)lAlxe*OGV(bdQm#itNP^VcrIZ3bx^>qBIaFNl7FrE)RL|*$< zPfw4Tz=yk1XPbt+i$JboD;KmW9=?DOW8^^1CR^)9&w%6=gF`vU$nj)zlCMq;{W0bnRZEB9Kel2?eAgPpMBP+=bC; zHpoNKQla)a5BY@QEqzr@8}SwL5GvJYID*5Y041TNMLe7IjO0Hv(43xXtSYwE3BkdL zP~_U`R9{z;V8KKS`?-L0&k9X$#OnpWN839)bVAatROFMH3|(x2?MuFG2c@`1AfOFx1*sh7zLGwDM?)z7bO5Zv!6JBf z9beHr3c6$sYIa-2?k-FOQ;Mt(36xHj5q=khkx`z6JLJzTn~Nyx>fXKS6{SEjQ+%2} z8E>4{92 zSWoh!dlm7XfT&{d^`sfQ*@Tw`xU|3rkPM(O6=U~v`xJc{Ay7mQD>{h7vUhRedmuQz zbNb@EjRBlW85axGnI-g0Iq-@pzN7{dXy)o)(W50e3LIS?Z&Z4p+I^Y(Rb{I{rWv2j zK$_aQ^vz4N4d;M@tynUHY@Tt~^QuXO+1PI6 z855BV;GEOdY%ujwAHUGj8cXdqxtpBnCH}6iuI^1QpnUTS3YLy9T5$zg z*UHJ(PuW&-iGq=Z2KJQ;)xkZlQ8)NVKM1dIFX1#?kQoOl{j9IY)9brye6&6axVUAVlB<04bJ# zmEmI7F%%fYwYplw?e&66??=gtJ4M=&*yKE`*P_nRZ(Ow8e0o;6kt-LbyeQRmSZJZ; z=H`AejCmJT#QTKp9qr?k({!kl1~6)Dz~YVA)$&or9KW-#ok>6MWI({WEdnQZtZfye zW*V!o11eY4O1@K8f9kA=3s=+^zaKX3Fm&}Mor~S4W0H!N z$jBgmI#flzhA*`r2Dttvsr|O@v7p#?WPHvsNZ6T&0bG4!e2z%w1ndlZBbjy46m}MZ z{sjMZ%Afx5NlLy0uPS?umw60pDs0?3eM zM-ejZK;}cK&2m<@Yf$mk#i}FL<{j=bC~B0O1Q>H>l1pa}@cO?Jm4^Vtx!CpeQJa9l zroK7?LJ~A)`dic(fOj?lKaaLlo+b|qw`C~uTy;PX8?GY#5N;b`#50*-dLiL*C!Lh)~sDz z)Lp)o4yOD`^~o{H5OqV($jAV-qkLVt4XcAAZ4jNM2LqvoIfg`L|HO)%vxQYhrfd2H z2m#t#|MXvkVSt#|bD9Xn!DV-z{)f{|*#W774KB_LV?}vw5rD5Rl5s%NjO=aXDAi46 z5oa9$h5=y53tV|~Tg5kk=n8T~tZB@@VVFmlXg}yH*aFpL-{DFK;@U z2<^YuebM_2sc(J%u3J-Y(cs+!EPXdQ)XgpiDrI~pJwA7Fg8St@^rCrL{pQ8+tiB_t(vn|RZg&79 z&V3r&vE-8EWjzTT6Ui!@IDS)-Ge`*x42-t)ZvHfu6k#g^(1wSC0y>3BsBzd}RA#+r zk6~3VY~*Zb^1}mw78ZBvc83MNSf7p^edH8Uldq;jzQ3+xAJcTDP&%ERtbVu?VucQr zo(Guvlt1aJwh7S2`I-`YKv|F`%sH952te8IWvp%we0YdtTs?4+OBnH_E{S=|Mc z^0*M6;O8I$s>qzlofnRZ%0H&2*v^Ow+bAeNCd`{{Cx<5w0xW+X9J`vm7exEN9lXp! zv==zIMfAucEJng^f{Co%)(0plaL@sHiq_Q@7hWiy2j@t+l69^_T2qc@HR#?Lf=z90 z701b}LqoOsK=}xak|t7CdltFZ1UlHO4z%nvidI22{ZC868hnLkVuD?_mO)OAgDqRw z8c!kH7b!G-Ha;2}$$sQcI3yOPa*&|dEe8#NfSRCJhK(nNk|1Yv4;@|U3%rA%dL|CU zZ*7oH{QK=SLoPnR7Y}~t0sQ}6pfR+7KE%CyIRu0n>_9Z2$5a_`dsF4CFx0c<9w|%! z17A;9PpdL1w@DLN>)tD&|WE75a+RCCPI z1h^+bg%XynUD(Xo_*bM^`T6p^fBnDc-^OX)~Yjk#&*e6GWpS z|1WZ%%;%MkGAPz&li2mz&D3|9)$dpBS$;#VAwXhh`j3tnruWW10$@s|3fDx~b$-Oa zwLGNAe=vr@5W<%87N@V=2wk38BZPC{A(Sv#zMMABO7zff!d#>$vQzdS$i$X_kR&`Q2s9`T1#hKN zjy^w4b5P9T$rVASXAQ82t-t-*2#M^AbU-Z!b_%_QIyufG0NH8W1p8!)T+02xQZt1=_D%)nikr>flRFOG-?R zQYchyppes8#kzC=-A3ySBC3r1tn+8u#UV2Z_rivkLAt%}X571=Ai&C}o3_3Q<3>|_r_lVt23LS8x5(Et>BI(5?Y>J@4PNL+{~ z&?V;?1{tWiAXSvV6u9x1-^lK>tT)A&;!+pcf__O)W+~Ce5z`d_ME99m$ zO9rt`=)k)fZRalGOc^L!<>hMu0T0uP3}hoEr(z-Em(Lvw?=2vVK?m=6#SlW`_ugEI z2>RImK#GLG#R+x3m6YH5yE7Xaha_;-H$|X1ljNa<)EDWIwP_SqY^ORxxvtJiml7am z7-)3`nZzP@xeM`Z%$R_oX(KlxrRrHR?^@A{Q_4lY`%xNbAhHnI@ZN{Pa(UVxaPC+t zqK6dKAJ&}bLWtgCm56Yn0nX*JhP?nig9|j5sB3ix;c__&7-*r8VjyR@0>in`-KiWE zdF>rAQ2_c*7E+YEI?+Y|>q@Wo@?!H_AstIZ)@G|=>niJ{A4>{#+SOR@~J zhHJ$v+(64X>aS-ubf(zsy` zfD{}n?qb*m4Q;@+a%K{CvWUT~L(=1dG0fai{TjPY(4-F}`25|96S`fh;<=Y1_Q~6n z5!2d8hFwdRby6l-U4~Ro=6fnfQGo3d11xT)hKI@SW?j>Se zcW6R2?^o$ie!})rZXyEdfFLrMz;S8ZHN7P>@k>hq5$_2L3GGu?XYBJ&yK;qu_gV%` zY9Nx-m6Fx_C%`*Srl*~i5%DAc=j5c`hzx6gJCI$QIooo-@O6j|2<{WCr%^QjITBsnPXi#sR|!AuLQLO6QqFaIxlN#Ya%MB%mI$fCM$G-{Sms>AfcHk z9=W2*uV=eshSVO+(!=}>+mFBBbxT$>@}Z7>=ujfalZxGL#<%jNHkXf^AJzqzgA0`i zFfqbaLHWAF8>o!LxSZ|w?T#bO5<58!*-kGm^e&5VwdW7SBx3YMqHRUEyvnpWbk(OnrM^C^u z)e;IpN(hbu%J(r)(qWl6>K~2pk>Ney7lL(-ldO)ifwxsQ0aG>s6Qc_X|j@oi<3Mo@j_2d^YV8gN?^!KvfyJ?}SKgm^8QMJAs zrdfm&5kgbc*=MHyUOp$ti04<0u|c|0X^=tj5QY2E&EYv`zN)A~sZRBFMFSIX6%LdhG{L>gPV1XJZ5=ojI&GLVl%0M)joATro#O5k(R5t*j-( zC()$2J3n7Q(llHBLA*Kx4LTzsJxz-zHY~w8SA&!Z_|h7ej&Wg0|IPWTSlT7MR+%G$ z-9e8h=Aq3{o0%E47CUAwOEm(7Z%-0$Q@OWDXiDy~tIcU`4H(s31&J(Cd2|SgH@(sp z2d*50VmuCZ9%}u#>*a)@ySLa1k!BGQQ3U#1tjhP-c8{xQ4!_W77NHAJ-syy92}T2o*26n?0&dr!r)ZS65r~3 zQ{(rabXm>soYV<1OQ=|h`02CPj-xs*QIp%1^L+5x zIvLH?nbgW!CmzJ?t^N|2yEyhAs!;e4t_b)fQb6irJ1H-DHj0uq42Xi!lbPCL`biE| zTQ85GXK;GH_|AeZh7MaB4vJ)h+Qk-F1I2yX(Av(A8jfGUxd1+(poeuY{~h@FHd66z z>Z6K$cLEmnY+54Wl0uijP{ULUD!$}}ScFP9gS?5aGkYYkiivwM$&y2js> z2$YBeZT0m6*C!YE?>wW%g8s440$~4ei(W5WbKEc)@E#!5xeKi3xfgFl1rZ~h41eCP zH_G&es%89^64Ew#9)M4Mv*_k^(0-3!OzflUjb7{TiD=7M@l&Q>zmMoFJL!D!c+nyPrs{7gpG%%7j!r&@c_8~Sfo$o>APH1T3c7~vZE-&2x}U&=kf5L-*OeGECT^Yp zED<*R>MKo}Kusd`>m>+@q7gIdYUo#J0KcG0?4 zl6g^J<)Tjy*s&rJAgp1uCdQJGaCmznzC;l3X#n~LPt3~@7(2ey^}%i?o$rB6`;S$J z`){_N>C&bEYQn%Jwm5H*1mvi$6<;faKcnYxJ?*Q*O=3^(<2%^Cnug<9LYO#6R}ss1 z)wT7z;XEoE08OOx#ABulk1~Nm)Wr22S?`j zkgBke*f(7Gt=m%xsL1Gd@33?k@|DZQd=GT5s(z?;fcd+UA05rM{m3Zt9Yml#Hu+lf zz69(dmC!Frun+1ON=##j2I54J3q`m#qz9U##c{5J%pmGMSw2oIUT$_a%DT>RasNQ^ zz!&J6k^;_?XYqa3>h=>D!y%$f))D^@Wx$#gzt47xKw#l1%Y9+@WqjPQTUu^?f&eG- zy%?L$XP4i1y~3$FxW~X;sO!Nz}pzg=v?bh1wQt$?C_h`^Pyj9@B95U{XvKT zV@**89v#S2FE3iH&bY53NC6cvfF6FCKz20I(fuu1snA`FNt+|YwUk>Fm7XD0E@xD_ zOgGg*qDBy8-%McVd8r$J9gxmd7{A#9CJ$o51d*L83nO9@C{V!A{7ce-)6S35i;G?< zya;(z@Xj3#zuIr5JOAm1FL^aRyv%8OiPds7w~zJf^?SIj?_s~G;n}3jG3daPUVlWU zD;$y_*)9vdhu>i<$kQ;RJ_8bwMdme^0wrb=G1|{!v{|Fl`C~G0UAYcFoPGm6J#u#z zSPY*57XOiPs; zH4r_Q`s3asYPxVMQS+$YC7=^kdCwkMmgXSZnz1n%Fd6_Nq+;_*5FAyUCmSqQ|9Z=l#$5v$|eUd*>lBWj_mhm!d15!{4;=8zSZVM<>0- z%lxcqkk zwmEvTkz#$z6Hv_SQ?(+(G!r9{Wg-jAmb|o3d1Q>c5NObfr#rvp5vH z_-g?*8mo%&mfhEb&Ys^8Z}dDt+t=a((_@?Gf3wOpzz|`F!a#|B=gv<=E*S_X1g(E&TVp_!ZkkQX zlRna!)2w6HTHD;-?%4Bj>IHl=3R7o8U5c>Aq_*SVoQH+c;1j9$otx$A%-(?8Rhx?W zpYIk21i1!FFPvKsUtPyuNk)-bcIHf~vy*(;&!0V*#P>sKd~^op2xM|Kmu?LA+ZH5G z&>VJ5q*q4FZ9Fz~O#Ed_skbci#uURs4v@fSPI~YfJ_p0%N=xlqICd1%s1XZ?UX}_Tu-( zEhN@|_mNp)d1f;&kPon9iW-A1Vpk?6=?sC(Y6XTwIaAYEmSB_~Z*HnnbPB=KFR$cy z{rAgaWy*`fWLchy6NcR-Qe@Wr_F2<*!tQ+yustHcQ-VK%l`#=vDl$nMu3)*>)W|X> zOY@}4@FbeE(1gk}25NJ_R9NJ=2%iex57sRW%*!M7jzM3ty<3`(UNSP&W9jxr`BLVzT-X4pqYSRaM1`35#+00?aJ7r{r1sC4^-e!c!{_HH?IveJm1opf;# ziqe})Ts1ebjQ$yQV=$~A5st;0x-ARl*4iq1xN2uy&ORtsJ`&1D2-JV&%c$+-@K(s& zDZx&A%zQY{}iZI_%+=!|mP6)I0vyW6Dx8T=zSJ=~}RRhZ{%jjf1yb zC|Ym#%2ztp_`iJ?a4>Adi}gKufTIDei&UxK zS|!G{ROCFd<_lvBJ($CyCkBlK5l;?R+8-f3v#y7Q#%o_SJ^jGKP7U_5c<60x$!tgr zck$w(&*4x7wUqbTMm1gQ#wQ;LWX~M)V@_M(In4z^>JKes01Tj}!%@tyDt&pj#x>z8XS zpNb*4aEUk9bGVCSdJ8Qe&cE(YbRd2x^v9bEcW@7oJfiC-UddR;7q*~He?)GYQ4&)td=6 zsH}vQ-x4`zilHRS1{w-G_jx;sebA1)a{7v!tw=H4;!p4nUoEHJ4RV^Rz_x&$}c#g)_xG3%oMi_Td(e^dP$ludd)!E@9`)i2!f0`&c!Do(9wW=F~7p~`ZKb_SW;LqZXk3nYV@{uMaJ2= ze5${YW6yi6>3l38@BxR-Ao>G z#qU3u=M)k0mG!S1nYXF1{Hu=D2d z?vVpAq)QNIbWVgFRA%=bvh=Fb&sg3PDajN$s?pRPY`6y{np zJIw94{$A#r7dey!fOh6I8?p1a(RJM8iA#Vou#?P|hvCMPj$ODC)Q3O%RK2z)oo(iL zD|OQkOb}Cgso;^bdVP=V*}ZjbE7S@=Kt`v&#cqCzsS`^3*mH5^++V!hleqGnfCg0G z8?rC$?ck~nR4$pFF!02Ly1C2B8@QFXs)X()E=3De^g-c=h!9uN#iyv4`e}MRE~JcYCtWgk%+#%&C6W8UgO_2 zYDEdS8X-RbiRJatrup?m^+GT4uvFBO43s_9(&HIF6zTG^ry{@_(tnQ32M+Hw5If>> z^6@{6X&Yx6ipE({=w&FeGeS9?_=62vIKE5IjBtFGu#7wQ4C|L#d?cflG3cqHmUcH4 zK-?0fR+;)f4ci*2B`?&*67?+EkrAN^RN?4;OebPqGAUc6PEQsk$MLLAAmGo_+jr%+ zn+x%XuO0Cip}o8-hqo86#m|3~gFJ~|6un0{#o*wqi}9G! zxAkBT>?+1%Lw(pwIC`8h;( zC@cP<+RwI=l*ZY0FaY&Q7Hi|{3-TLVuFxJd6B?~=RwG41;qtlfm5P1uyjA3i?E65u zIc}#I*ZiF?UQs&8O2aU1q~tCjj|4$cU9-cC`odnZs7+;jt4^NG>l|QInvQ zB(H*bldwd66N#%y-S<=n_2i|&f}{wC4JVxAXw#kswi;pICR%ASrZv#+IWE^f?v z$C3RZN#=oGw$?-tj~^$KfSHyaIT2BtlxQGJFs8w2E!nhcirV|_+7Y`9>3v9&h}lxn>_{_?t4 zmCv?jo+oDCkWoN9Viy&3!zjQUM`%{^%f zxb}A|IcGNTV{b;yjpsNfm4JBcD08*M{>jgsoh+r<=%C-tt4cCD;9@ zf@Hz6Wo;I3bWz(@2XM5-(C$xJ_DZ!}h_}2x*tl3T^}nN)O_~06v%Tz;`rsa21NrR& zeruRUCOI{C1|?~qur=T~a$we^=d zC&*-Iw(pMNLPw_f?=T2Nu9@skz>NsetJ)}Ve^?)ASb5WXZ@t#pRR&aey-guzAdD4L zr5%jD#v82bdTPlpqL$H>VOYO1Py1*&^(ns1pKIW)dhcj@hEAzR0#-^z+>b=maP@|U ztHD!`*M5QFh3*c*vq4(%cLE`xHBOiIN(PX$Mg~c1|4yZslR-a1Pq#s>I8$q%J!bt& zsD{KM%&jxG)7IAZ?VE{f;R)!}>&g)k;}4P6&9D6JX~MG9nV->9VzI=Pkda`WfbhUX z#GctKt|+do$j#b(DI_XID2Z(ux@!LGk_wykKnV1 z0EI4V<~;*L1J~ZuS^9X$?XhWQ&uoF3g`Cg5A00el1@|ymBSmO8)Su}{B4d1>c{^SOM#9G`u+Rs>WyEr`%-K{EV&zPg;CpwX1NVZUD zCd-_1kuVYSzzO61L|#Il0mvcLzPi8|N9MdSp zYS9C3mtznA=mo^Pnduj(TU>p;Uox_DI5VPALqYvgN_hKtxoRPHj@pORTKnw3S%6Uo zzU734)Kjrvl^Wtw7w9(^k0fKB@6Nl=|vxRN;T?*Lp-LXjv!Sxb@ce8 z%&sS$tH~fDk*rb5!bB4RqT|ZNW%V(-I}=gcR=l~2%5%9q^{i*k0~bHFF-Rlj`R?On zP1pjKN6z*o6;=a{^W*0h9D>1QiI{YCj=?5HJ*19i?agGw5g}&XCSC&3V#ZMTN%Lc; zAWfEDYS#JQ;RU~Ym0mcRO@}Y<78GP9^k?hB0ThEbK~!%disOC9F2i~!QWNU8TB%Q6 zeI`99GC#IO4drgWGJzRBZmhJnemrE<5Y0K(amN8-W@mSp8G-T&HQ;PO>p+dEUMT)q z-WNY*x|@vxse8&=*xE|gL)lAW$96{bGoZqYyghfjWqu%^qLheo?ALg{*td~6=$!#7 zgvr>}*x=sz&fdC(x2E^~$oCtEG4R}rNO>EcF9+gI)+s5~vVm##9E0v{Sq}7nMmZGZ z=x$}oV4;J5hy|wMRo+|?b~0zlpe1YXs|g5e@#<18ucCrcJQ2+wv9aVH%r;w;1Tz+_x8 z3C7APheFa=)+%%(*(*tdnc3_(M3xS`Leoat&!EwZ=B*05oL>~xQ2zsw{o@>&(m-f@ zx&6_${I0eKLtKe44J~bVp0Xw6EotTDPDJ;L*G6!n*V;GppG}qIk4)E;{M&boG0_ix8kTob<1CNH`lIH1 z8>`*6bfwHp#g|4QW#G26ZHnOw||NsAy%%YdIf$ zt`@BC`2I5pKa_W|O3G))kCCu9>-ergG)sxG^(WfjD3HC`!7n?Oj~EC(1erbzHoTeS z=3A(+Yv*{pFn%}a;n-$vSv%IB>#fywQcknNNedR5p0%1xW1@(=#+-U6Z4R|7?-!zg z08ob4_;Iei2~yURFLvh}&FuIWr}vve3efS|B*dydFEPxB2?^J*1TcJvm*=DW7`UPh zrSJZ#Q*8cydocrJNY_AZaDYBVG1MU2_HLz@%E4EG4}z8w_2pabwA8}OJ-Sw)I*+y6#r?-tQ!SF3ynD zkE)37$=l+FaZ~incRd9^cVe90cbP^N{XyCOcIayhRH=&zPGmiN-OtH8*ywjoF4djJ zI{y?DVviiBnl^fTrNV1lcx}^`x;A>KX}p_Eldi%FAODLA*}78|*7ixnR;g0*e1>9dm`I&`T|9&qhH#}A;NuOa zi{1%tuegY)$!fTIiqeL;&m6BSTO;^j-nHqt{aMX>s)HhG=ZsR7hvSngWu>!~b%W7# zbl!fR&pQDVeLWF;OKRFwK*!x~}m*=Bfy1=_=dL(5NNH$6-4{ zx=n7^OeX$ks!d00dIU`(C=qw{YyC)noR>c>F7=rI_)?Yuur9`cYCLE>Yp%W`Py*H8 zx~fl>F2~{a)xNcgU6~e}`71k=xSzKKin`1_#F)GD<5ARQv*G7+HZF$4VP=&4S!&tx ze#UbN`TGcK0Z?iJ9u!cXg*qHKF<%MO)#|RCwm0P&Z&;d$-3QcWU&DzGpveL0ume zqv)}o3Sqe@DBu@*gXY-VGorl^I)P67v&B_~tAd;vf`gC0f;5HAO}4j}q+!?*tVCYt z1ME%E6FyMa9~##CdW{aha<*&#A+&QabdQyPn|L0<5U;q%>fDM3hSD4Bf9Y2^(m*;! z*;)b)tkWqed%%2r&&N8QsIpv|&)}C21VPaI2Tt>h;J6#7X5cqq1ciiLKSE(zMLN}Y z9!I$? zk!s9e$`6of{kwJDCg>`k|Ka@OYVLNbWGuREBkbn<`yL2;sfQVz8;840h9&Nv%9({L}`MBVTm8GOM9*otv9vI126uk0aIH z9*oghx;-WT?feC8_D5NmEYH(mwbff0!nv-ba$tK zqzWo2-QC^YDcvPq(nxoAcXvpabbTA2d*APl;U94fIp^%X*P3h2xz?5uGaQ@BZsq|M z|87+wB^oS&;E6bWRNKt4eNZo&lhOV1jkE|=@(*!4^>+%S3H@5F9{8Lp#eh-*+!9EJ zbIldlg3qC?;;&(;^=v?OScQjAoX`*cg*fWdSjO0fizJuFWwqt&wnM_Gqpu7Alig^| z`5OCyy;)MDz;0jsLEgbU?CtYi3e3l>f*2Y=IK+5o%lk_8n|rARpc@8gtCjdnj|KHx z;k?PkbDgyefa)i(A!YS1>2dgkKP&u8ext(=*)mPgw-6+q)yE}wJXIAHKdESl7T9%c zDJnyQ(}zs1a^2-OfHQ&jaG3LU6yTx$0Z>B74ZB>*S(q!|rj(Nx#EnjK$Tlg<5Una)a>|Wpi-yfzm;Y zs5Kg2$aWXAxpKUyOci-cP{z&cU}BgS2&lIExBMs?241*Y2B%k#shzguTFe*tUc@}e zKX>m_A9UIO98@G`f5=UZH2wRPQa(r+MYLMvH#}_aOZ%0kCJ~|gUzt>X*Ld5M;s}14 zJhl4rV`0X2l(mQxiO==Dv69W4^@UtBv#AGG1_t7llvW#zcG}|dq!;ZJ4@A$Kt(%q} ze_27tOL)Gr&}w-d;+%FrgS8Ikt}eI{F`Sd28tOuPd8W~>^k zr@OZ|la^144-Y%gW}>78vnFR=`9y<7MNYS~tz83myrd~9%+p+LlY63?3Gl99c+bLu zPrSC41#`yu7=*7yK2czYUicjuAPXlw2hWUXdAm@nx@E@ z^=!@snUkU|`Uz!2?z1NI#3AE)CW59hDn2n^%`ho%_ zQxe%2NlkIP6krb=5z3xnb!w%>oca(rxVV{?6RiHD>V4fY5rQ-qCN;|*xpo8&N_+|OE5mj^I)mPmSE~=ZlqhW>{E~#gvL!cEt zT0T%57jON<+{L{j=ElUZ{~3OH9 z+4b~ux$ZgQTh7tNIsCI%S^6E4hT9PW0x!SD!^Cs=Pb9vp=keCp5CnoA?{|}r@t3^a zv$@V3Sss_GmsZ2q^iU3J>-}r?_Kce@M)-_nwr+2oANJCpjL)AB-IHq3Czt_X%gv?e z-!-v*w78qmCvq`A|oN(Es5t~q|9DQ^^g`j zLX``{)DM+Y-MWoNS-Jhh^TP-Fq@_(wO+Vt}vCt6V zyC!2bVnvUUgg={UsJ3?`Oa-AL*s>g@h$qw*ZSBU%s{`;fHsFO z^XMC&* z45kV|nDIL}y*gU-+24Tmp++{-z;9?$hZzpks!5J{eiMRy7?RoC`mT)sI=P^?K;FKb zgKIOBA5safZ0*-G<&K+eIXA;8f~#n{ly3{+TL)(p71i#!A&mGA?G`o#{Q#cfs1J=}m8R-J3Jq`P9SeEX^^w zsDy9)+an!T?~d%198{!NWz#7M1TLrKK#ux+y~Z~B-j~U39sZ`M^^R_3^E5a~)Eb#mP*!oi&1sQB16j6#zFyCi!F=bZ$Q!;!edA$Mtc}Tz^B-=9#m>FkPua@JKfFj;W zt{Md|7Azav-t0@kB-U^LvznOT^(VN&X-0wxHIcnUB?Bt@v5 zsna;$taWl<&+sTmM1{KTDob``Cd=rW>z7PPM)@Zt;V#*Z@`K)hoFJQ5c1bA`%}`kb z+J+C?DHjQ}E)}n{=H|Wp+j^Y3Lo80DG3mb|--`|CZf<{0== z&eFEI&SLte4L0w(lc=4L=>z}#`FHL=J1Uco_W~2iRy7*Fa&y2I<#*+;$k4>)V>(-l%P^X#R zJ_vAT$$S|)Yeet-t*w-bH8SsG#-8%%sCAC?y3SYgadXip{9P*C4kkH#JKN!BUVgdH zX6EZV8^SBS>37|u%nwn$Rz{;*E8JGClYaM{GuF1Geg{0FA`nVHmBrm9`AdJchJdsE z{$hyDc$>P-86nSTVAkdg9OF zA)!d1YLs%MwM|F30>|8_>(gzzcd98`l>&3FbFiC5nym=z$PJO+th^_{5Tlc4r9AUz703ZpK|sPR{9i*)isM)!1|`Rku$} zi_*)BCsM(!W0z6ywkMb=t7texuJtBqY#SY#m4$_5vASI=FyW7Z_*a>EZZx?3WB&e2v%^Ghx6_+jra%3-n;wBDI-f5?nl{nGO-tlf+w;bEyx zROo6|eWjFLI}#JJcl5{Rjw;urs1Qw>cgwDOv;dd?i2cykA6w7Y5I5ttnu86NCMIx` zlaqfOlgHR`QOI$=Nl9(~75pjAjECV?y2^dly+toV`$6VSsVOwgS_rA&`Vzxn1&j}I zPTRqy4(QNpvfh%W_KS)_4Ix9r`GzBl; zy~Lm!us8-{zSq?ZZG4Im_>zbpkjAa_^`U{C@)hXYf(YVMRAA0gsr3Uj=FDd>a505=E7+VTVO%Sj)jfgFH48o=;D~U zxSU35Ml&v4ESgejnqRb~lNxzZOtFpvu^)E%ooyHVO8)`rpk%MK%ifW0U9z%5rvQHA z@$b1QLG$98G>I3(?Hg5XY=<=a?{5s?Yn&G{OsCpeE!XMa(HQ2qSS;Kxo-NpxeXc3R z*5vcOcX6@4X?b+o8IztkGQ3zgRSHFlVR}IE)Z^TIx<7df!Omfh%?jF{LGLug2U&V3 zuQHFzA_%X92PX5A=T7GUHB|kY2R|qg{iMXiKGzC0>Li8%hyt-B;-E?$BO_|VaoAx- za$49Kb7~d#)WpO!v&X1xhLRZoJCF#t+ZNCHUUp)@>in&8okN2jlUUUK`*V^ijs^m# zZxq^w1`57bpD>Ws{o=TOYD>vd)Av&9KvZ&{f!(>Cwwi#aj=712;Nlz2OBNU4ZUKjh zlp8`}c;4Om_{QV!((LK>y3}UNPmPxl;VpQ|-f???e5y+H#E`_B9T_pz5wn+&cShxT zPnEjJZ)*h8N#u;6Zm#g~;CA)iLfAt%69r7jseXYPY+H1^ulm$K$rBb@h+Klk@1N)w zYk=kq5C2ozNE%wJqD{}DZvky~pQWVdRb5FgIf4&gAG5naG{{C=i zxJW@YN`Tjq5GWY74SsM<^s}e+`N@%75SvsG_*%jAtU3>M7nYN#8b+MzyRGLi75;C_ z)XQ(jp@gP5LF{{rOy~y&oGepfz^(t?o6Lzp!Td}b^+8iJ-Dw<*ZUpYu4xNgeWs3@> z@|KoxE$Ies+3M_~+4TyMi1zvIAsVd;(1f^C9@6@8f%{QP-c<)C9le zY5(lo7ZeqVyvJg?v=Pl7Hv(f3MYA$Lu`+cr(%*e%rxyuH&FpxZQThHwrt} zwh3As(s(2Dz8s%2ANEI-&>Yb>IDdz-cY{y*^!EuYxBEGVSvwIcmzgISnEbn=ZR5xr!X zOA3ZruC}=2yn7etwz}{1`nqa<(jptV9>#|n8jP6%)fG?K`bTkbW>(=+$1IzA_j}Iw zgb_~TC=kFd4Z7xLQo4-T2hRI-s@siloSHS9ke#4|{prD;cS$1zdw71Prm`V=)?X3) zsC3JsGj1C5kNsV$EtS^-29me=tTqK)V5T$-7&>sX=8G)R92>G>w9ANw$W!iYURk#d zr++f(8j6*%h1Sd3PlZ?6k)c#etZTsRVDe*1zW~&V4QoL-|plb!${pARMu0{N|GD^fBiRlVvEnp z^5!i5`+Mo#j@IX8&oEb4m$QotvYR2#2U{K~Z$sU#p!=gq`!g!q5OWT2(1W7NTym!5U7Oe&O7O%4^0oJaGI!^Up~VKR}SUIgvV(4 z(Cv=I)5A~heJ@u#EUB7WNY8sjx6Ll>aoyE$dQXsn`fq*Jx+yeoI^o)RY)X8L0&Pt7%6;-z_L-64kVaqDAPfINMq%}_>*$o-tb~Bq-q-5 zP9vPdR?n9e9>0%n%n>nC{!|g`i$Wz&%n*o{Ae%95nmKJ+L8$T3j7?#G8wGCN*rcd% z{XA(yp_EeR_jD>oQ!JX!d$1-uBGH6WaMtvSdqFLqBm67;lg&vvRfm;VMXCpavyt3r zvD$C0%U%&R+$&p0n)3*_tzHF=C1~Ef{lYY4ctlp6wY?UAHwoc!w#;?*ZIhmVR3GMF z$o&fV%MsQ&`GP-w1qN_fh_BjqFER@YgBM~i%8MMa8gafOy zbHYVfUeh#wErAV$khU!TXh)`kTH1-vWzlxz5HlHxB5Hze%@{>}DUdSzCUi1OX|a^x z^;D`Q5&$<%79xzbT1En~SC)+0(iYg+sTc=cdSV(n_xEcRSnql?>wXyWFxJSX`M<<2 zcm8GwFGAP5x5Y=3i>N06tl|FrY>nX}l^6O^^!5Y80F;nC z*7{n^5zX+8+VdggH|6h`uy9$Bh68Eu_?3pGMZva^=mB8F{!2__WC3Of79vevDq^-a zSn;znDnZ5r>t7^!V0`%MHB$?d5^;(By7X`X>T*!LxtgilD|0F3SbgnT3Y_WF{+~SL+RI?y%nvJT^AR6?mM@Wr_09v%{=kRdD}{7^FQYf z6ln=+6;~=dT{3UOzcQ^IMQO3d({mKlRV}UhR>O$J!uk}5`iVyMtACop6AKN1=#G^e zpFW5VFOG|g3yHXZ|7bYe9FPwn4X?e{yIuVoec+>{#2;F?yFC>!Eu#1A_F?8g&}O` zQAKu8)bGXVsbuTh0E;q@5h^c{DOu=Tmk%2(=m9xeQ#10#?|((aP?528zf{I9A-MFqu- z**)7Qi0Ib`NOTr=mIF1O6eA+}lR{;ax+LYqi!6R^_CG=UQ`zG=$3H-_H*pN`wSL91 zY^K2!fN7lBDY+UFcxO%o7Pa`GcmaPA8#6WO;WxjkS_GL{4WSmSE8oi7#@TTFXV&<~ z!MeMN?@;2906L53>7_sc7qyu-E;)!g@JA6oAffs6jXI|2ke&qLiUI-knd zII6B{b#$FYW_AU_x$nZS+fOdAn<82^-9cGKcf~Jk6?50Z$@A6d$a3551O(SM-P+?d zS2mWWe1(g{ue=>k%!eAT<0pc`E@12?;D4wF?Y($^_T4pC1N?Ay8lBTi0+ZEn=F$uX zk`FfYNa}+E$8hv#i3z_iu?m|EcG^u+>UGWn=6D{u^=HL{1nd$m7q3PTLW4ZiQ|WaEjrIB zFrp2SXkN|_^_$G&4mQIsOgmIj4$?v+nA6_a?L=c)2?R=!ZxzgOCc)PsH1IUBHbFGD z%^JlS{nrFj4OTF*ifTy%(p@q0;>s|t0yQ7)Dqt2xhekqT_?~DC?=5~gks8!!(Z~qv z;qr0387+Ui60@>(yUS|?emXraQf^Ef3pp3N|9*zVW!z7#wqT7sc*x5Pt z#G-6v7|vDzsu&3>js0WCTU=7At#2<@qr2sMa>~%qzbqvXZ1lv`D|s8K&Z8PynB3nRIcSCKvHYfNUC@x-uYoQL#m;$ zs}e;iQr!w1%u0BRGo|;t$SO480*E??&E(?VzPGan-EhBWsmeAN!c5sWBj0jl2b5|A zioOSsMW)gojCC)NryUv{O)x`@6U{R!C@t!YFc3ibt5moHH9!)sPb$j3mBR2x;7~lf zIm)(1OOMRQh&vfWr3=ot9_GHYAJ;}U$c?iM(Y$fdYCQ#;Tq%va!V0Z2W@JMj_y!w7FO1*(*c;QhbS?2s2ah&gFk;h zHGa*X{H{j>r#T+16pONi@J6INAq(O>p%KRW;8Ft90907#aDm(9PqNwLCKCI+KYBO8 z9w__8icu5fg;}n|A_+%QxVi+_xM$JCNe~9pa2j2yBpNIX>F}&(A#_Fe9Rp(@i+v$% zO!aRi&vg#1>Z^f#B|l7*`Q7TN1CryGbSlj>j0c>Q*#JR19OlQ8L8lqBc(pAoxcdv= z$6F(tGeGrOkn}v(^r!aw%|D@tqLCa6)AEu8E%i}?Y5!l6 z?6FO%@IGHDGO*}VsKsm(${9cl39L)!PexeX(6k!tTPCDG-RxOus>;81 z9g5jxV($(AU}V?<|1C5J^$Ccs;u?|1fC(IB3SKOqqtvOe5ULjw(OL|y-_>(cTa$=Fg~$zsq{0+RtU}S4tm(YdKoqo0EbjnRYQ8>L^4r; z6%+LD#^K7HBe<>!9D-U16i)**I-pAWT#H3VjAcWzWNI?fa5_MRhsD<$iA-W4(lYOJ zyW|t59tNNgol%VzV=M|{=MyvM3@04c_gp)FwCRuFWR6E&qJMnHy`$OHoj$zr5w{g` zGl&jN&OlHp>FVpIZ-U?lT}86e7P~mxMR`Y4Eq1RJslQp{(**@&l?r=%dqR?up<5RJ z1cxZtdU#l26+KKuZ*%Xlmm1TcLTP|A@6e_mCF~=GEw)X&Vh#z#G|CG=q49HL(f9J} zbOTv9x+{*Z9^s|Zu|7846@^tT_UeN()?xJP?UclEIQiPhpxISa-TM9SAsb0zDy12{ zrB#T}tpWUwExZG=Jy|7cl-qC`vN>15AcH{pxD=-e4f*SV5ZbVC@urK}lfDLlELQDz z1v)LBf=}{X9$b|HXD6DSzX?3y{T{XFS1b$5eMlDj-hEU%9c@)51Ku6c8QNe`VXSeK zJ_meR00>R60ZR4z%WOmRAI7GURNFr~Vray>cuVL6ffNV{zzosvi{F*+3>`eMO4Aq< zzfjJHgIVcg+DDO>?-~CIDcQxlUd}YQEMegI#1oLsL?D*0tgNI4 z!~-t&#_jJlicpZ4Lq19Q;~uFZjYNG{tU4n$q0`!{!?_AbFV>1V01-;#63@Rr4;L%( z%r14OJf$=teE~NNob!ZjL*Of}{ID4Cpbrx#D?k9R5f?Tn`U}RGX(5^--<&vehHKPx8(!6%#eA@=No3PRT?P^N!I)AlFWPw;)_eI`ZQax86qO~TJXd)C&JR8+Z+g)2}r@tm{{8qZFXLUjhG1asQ5VW=l zD@g-t+_XJ68=J4|aed%Li#(NrkpNWa#W9Y*?1-D`iDj?pXftJhi|_>r$lN}ohP+j= zJM4$7T(B+#398KYh;8cFay&zmDgVgNAQy`p>KRO0itW=SwCU0RzYJYJ(I=3Jj!+Y% z>uz|P`;heElno3I1h+aUUp>YY7TqK~u53M<_lOgip7hYw=0u19?vD@@qKB)kg1ejm z`3G&th_XWsFy$Ryy8IR$l8+7QrbRu;O{}y#O`}T4_}r1n92-Ojw9Sm)ztP#)*nCJ+ z0BJGsDqMJkGAOZSib2*YoL^l_K36b?dM%M!&cLn(%sPvk(Ulzf3oa2?w=>wQsV zO)`33$x*PvCK$GOuX7`4c5Sf@US2DAL1u2sgv<$JWSzg9AbGBrtum2OU<4COnMa@VH8{c~n1;@paCe0_kc!Atw&oFX zaaYD9D(v8LfWj!+iaOOrw|UDJDGV7eQ{y`}y&2|$s2W_I0X&%9R%KV)X2wCrPBef^ zMhMCLP)BuCqlT?^XiK(Dz|47GG-b=bn<7aVN|!t$kUu5*MV<}3APA$3;I4JBCvG@o!44WKhh#u-4DkDqX+&s8TUD!ln7JyiBGOtV-zoA?kX>TmO| z`sAQ_oU3>f_;D)?>=x%&-s2xuaI6iQ4mz@k0M=VMdK3@@bY3(+SMHAo1Mx}Kd)4up z#<1j|;AG<2`O+!6>N0ahU4xXjFZB z^>?7m$@0-I+rEYI7v^@qV;2M4Lma~q@AW`eY`1untq_a;y1Zn)q(E0s?5j1PUpAF7 z@gPl(?^jE+nE-vcqEL7 zg+K94NGXFR)?HWLo_w~PxxWGN^Qu`eEIkwj;gxa9TBtwZ2?EuKnB_nw{RK%fdk)qf zMxQ!(@_#ARc*rp$cC5?(?8Gc|mMxp8&)vdWufQkHQj5Bc+<0H*!oR`dLGlrHHfP$T zyBdF1k6&D%PJ=1!Tkjqo!5o{HI)9_haRfo&9su!1Rmnc;fq;2t23`w5DvM_efho^G ze1g-E`o}Q~n|hkA$VRD^TeQpPXY?Bj&qAsj9b1UA6MSueR(4d~Pe7^Fq7^3iQTR7S zRhvsW`Wbs;LMt8rTD!Jj!dt!|IFVRFir|dh5Qwt-JtyKb%ukP|Svvi|Dbo?Up5>vi zBU~_vf}$8C{7vNLMiNlB0Uttiqi@guV3{yD8JH{^6dML9kUpg2qk{vy{<7$o&4#wL z2+WIefo&xo3Jv~L7{w}bt0}9?kmso(y;f~Wv9a$U)%NZ>okK4rZeP31u+c) z0Ra%lA&o|WPB@3t^%o6-%zh=xNg5Q8jl;)5X^dW>G+v%GzW$Tb_569=NOY`QL5sbd z!2@fK^Xu0xC>a-4L4sS&pLSVi2bOD&Dyq;YBEiTIT|oibo;VI=>SHj_Xoztlr9rHb z{01U_PFQ@1B_vx+Z-E3Eip`{>=l7&R4nsln`F)buuSC{=G}-vl5`8ag3^i&f!!DLi zcDIj9HY$V`a|-J6+}d)D%7FTL`?X8GLj#=0JDOjqi1>;cs>*auM09j?FEa&cvxYh_ zNdO-=@x;I>Os_bZ56Z|^86>kF@%F{aZj!*Ce1574mNMupLh{6BGz0ykh`_iUO0~EM zEy!t4@0SV~*DSb1zi?@0)!{7%1(X*r%qti=hP32lpV5zEc2F{K68r2>ArUkO`}Sk_ zf29lMzoUmX@3jUKIz|-t0>ekvh)B_Fr_twN`d`yL%K;y58!2;r4lXD5?8JC9`mGbg zByxR9HK_XR`?gC%dpE5bmwiYF3Q;#^o@Ur^0t));2`Q)6O4>FQ+Rgq@4A3J;3O8AuNj#d%mG` z=x-$eXzrnikpxPCq2^qU6uc{U*QLtUfpFXIlXc)Mklb~^=!HO9t4=tK7FCt3iQL8Kn+kio9GwKR6uz$bv3C;vK4?xj3$hRx;85pnnoz=UAOL2XOy8!h7 znI0m>{N#RoMgh{`!2a$I09%PAJ6oyBBzhK$+eaN$mMZ(XsIOuDg{|syp7Fy?J=W1j zmZOORiDA|O)B|8j{}MNcm4m|{j7Wny<|Kv@_81UnhiaSm)8kA5Ek$W|*l^mQ5Mq1U z7(}vZj}PwqTsTTreM62N=B$EgxNBHZNm>Rk9Xv}G|OXk>MEvZbh@S966VHafqtd-ptoHrBLJ(^o@2@YyOW^#4 zUksC#=swgU1EfEPIJ(`th@_zB5$J$)*KLw?|TFeo-#8!3N$5V1+?ILeTkm zfTSD|6Z|bdyMPrr$yz^qIjCmYJc#TkmQc$>^Wfa(9O$^ErZ+LYSOD0MhLw8tupY5gGxeMX3G=i@Fs-uj16Z(s6zL*~3cl+0~xoDqx_pn3e`BIG4q%O-Y7 z6qup>s%Zvgu%d&}$^w56(llz_Jau1dGvict>7;!NBy^POH{^~d`(GtJcqEW_{Ev~S zh$JLP_Y(#d)wQ)$yLchFCr+BB8A;yruLvzOMi#>~$poB_L{t z_MjI00&-P$VJ$3eGu*+&K_y`k_^^Lm3gAPtL+fsiLO}pk{@Mk)qmGV_lonlTDrwpMcS3A z7g{M()LV$3KrVKZm>sh7uKD+yx+L`=Da3#eUF*lu@NWs<;e*x>I0O$y?vsGE#BL21Z`UfG5tpz zc!+@Z5)BS8qxsB(5n7JjW!Csx4N$mZ*eXymkPlD2%SsO^7nmHq($w0X+_!OX_=XBP zQ&3Sv6l4PsVT;5tJpW#YNS_R^QjCgr+JOr`fm*Jhs7yttLITFZr3A@aYu)pcan(ZV zKjIAn!`hRU!_?;QzL6MA;IXa+`z0qyB|-aE1Qm;?hrm}HH9XCZhuhm6uRpgrZx<*T z;(NM1TPu*nd&!WBhf1~1dt;RFG$r^5`F5EJ;IhHCn)r?e=g-W{Ol(rRzLI~fv*mx7 zm1h#bSOt@H#{>3P;I8k@k95zfPaJ4hf$IW?l(pKpFZ6JMnO`0JKRKTDMd~SFmRR|@ zw7d-F!MLHBP`U>oY1&%lH>1CsIZO(ym;TkPc-YXD)#Z%y_tL7W8oM^)z0X=MU4ouq zgm8;gm(6jBZRIf$1Ten#>z?r&9&+Y(xep<_|0d+psP|qxSsiJ73{$jNQ`Ef2gwQ&* z_4SFEWS#SAA4Tl&Xba!o({FlqJlTE!Q=zPT|80>He6jZG?lpy_rn0gSxTX|sb=gKGqqk%Ug>3rxZSDM`1aVZ;N`2-u#fvIAFlR@P`#hGj% z>1$W@TxtLINJf1ClnlSTExj_#Ker5Nt#;CfmyiCws}3H>j%pI5cn;voi?%1oxr$8- zNCr)Be|b=5>Qwkwy$=-&uB+}g`gN07DNDg2(H#qvwQ>}tHTRWbg`&gV6j(Z(6{l_S z_It1sd^SYOPhqfnFk&^%&R309K$S za1q#R?`~~X`s=YXI;uNcp`Iuxm~Mxee6-`E=3fuWBjA8ZbT)kRHJEZpGc|A~bK8tG zFZ5H!3vW)-{55R}7fNP6rzhHzeDh>g!V6SC&_J*ky#*FytF6AMCNZj);&)$&WgJ{h zyy5+pu#X1ijHi>9Ay17VmwMO$zB?9L8g5pP2PV)r9lvX0OIApXQjL8Mf6TV{ZLrd7 z-PL!4w6alXVG58R^C4?3S9`)VS0kH)>tu}$?3AMzZ46OFx6fV2sgIw#N|VDW@;e$3 zfiDMnF6jL3u3_t#8~|d`GtfsO0Lmh(t3zc#Zi-@}@}3tzWPyu%J0OwYd)3r%3N2oM zhoZ?VegTYi9NDsDRVsCfq~v+Ue)n?Vi_y&L?GFvf!o7q8QN?Vr?r87E-*6@O#Y#<; zL8A0Be+B$2tHFhs$DqL=bLfmV>g*J)o((1|s^|ScAl2ZP@S*;wMnZxJMb20q~ zanWB|oZ>h01ObJ9o!SV0k+p1G&{D>~&PON~f*=}4iT8SI1XvPD?FoyPO#}OlB}PoX zzR-d{Vf?M{!o-^LDaRuz4v{=i8Xteo{Oe z%(NhHoq-OSjrV_5)Maw1g>?obVjJZpzwpRCfby<=VIL3ZG&8Our3Tx1E0m(~WLe$( zHA|wa1-n0p@r&O;NCQF*!ZZaFc)!M-FhDK<17Jc3YNOXe?4tO5i6!7Qtz%YqKLTbR z)E`x4qqF8~8H+x9mg+r5K*Mp;@dj_2zzXL)**!&+jiY9v)#a~tK#Yytt5ch1RW^7 z5LQ=ohAg`&=nr)tJBm)5tPxvWAk8#V)CP-;=5}L#rk`tpyQiC*m#`USb=f#+Z3uh{ zpg?fHI$0ex6$eNgz)HOR9(j3ts-)7oPM*>0le|`kjXgYHPxJ19n=O$mmgvxFMDQ^#U0G5!eaXjUlA} z%BX$VsOyvFE5V1@xz2od^;g^69C7`$M(*QqL1xh`398hKf>jxA6Zo>LU9JS0vB{Wz z1i1|TAC4IForpyPLF8h&8{jvxY>BcPB@NdY{~vtSCv9b|O1(D_nhWvB5|4 zvjNQae{B}avx`3eG#&#sQ2u}xmFRFW(swra@kBOth?@2G{Db_@ezvt+y(B>r-b(;P zyDr@wwGJIHK1`g$G$__`g!!a`Z!RRF3#l-xD7k~Mnc}VZNz$Ua>Kd^1vQ;#umv^aP z3W}^OS#2oC>d=r|c&83Q0`23~E@EN$hiewDRAgSUMtC`6!7&Z#b_o_R$r8ACt!ydp z>oa%)9j*7jmZ#7g*G7Rxi>*M+Tj16Wc3Jv=b*AI;w8OsPP)Q5sAGm-=UJ-X<9pq2g2Xl2MZ*<0}V4rO7&>2>#xS=9L?|6KjR=_R$I zAYnKMcDuDj`k;6B+jKff2{`2hr8qua+{ZSDrjI6$+B7?a$zL8Wc&l9)5GWyW5VO}p1|puB?}~~S`+$mj zKDn~05vkSJ6U_!B#B3mPPoMt^;aMeExDS<-N10$|so*DC*p7a(+)e+YKHL!Ik$_qa z^|EErmQPA6miew^1WLq}u*FZ{_H6Ia=1?dG&!|!? zxB_3{40CeUa)68PE7MGrlSja0NYn`qwsX{1Hu#uwm0Am=123jR(f7X>0=G*HnPI4HYGawFY zAcWeqJZi9q+zVE~hkDu)j@qc91UzcbH9OegpJ%LQzSY(HQ%?g4F5=O%#+MCcl_>&E zdc-CX{}X979M?1FSbwV2`z@PhH{JIgyu@6U=6J^xS>Dc@B{l!5Em_wxs|LO_v6Ie; z_{EBXF6X|ZCwi(`J&+ne?8-__VDM#NRtW<`_m!HPRjL}t0NTr7XB1(Xa%p5u;PVCL znXrbB+y>*)@iQV7n(jra4~eAF&u5WF6)JAbFSa_sW$>c1{HYfKg^|%trVmg==p5*6 zM$o6jQ5@F`%xitn!v7*pq~(;ZV@&T)3TrcDF9GG+4hmIL074UiTj3~|y^BoBu; za~E85jmn1oWp}k%l0|E2ioTotsp17QPb-b&M!2x0;bL7Z)f%JTiEOG!Rtygu9(MHq zj;XtAE-F9%O^OwPd58i|ws(t+=EOv-nk^#Rf1)=?#n1{08dmjeUPsP>mW%^}8{Whw zVZbK^lwTN!<}@HH2!>j2Oeufe9?aFK(#+_%$tSmGbMo z=CPBp$wQGOnFg`jj;wTWcz%flHCll?e1Ojet~3NxM5z0WhjVMKPa36`ov!A-PP0ba zSctfYknX;OcqQUf8xok^Tj&V`9RGtjQ1HP;!hgq1I6z0LFntRH#xGn-Lz)3$txQ@8 zlUOH97|ecn%>OO*jKWl!E*|(kM=@hXw1d*&_TmD%sxm~ zDzt&lRwE-Fm_$g0M#`d3M{Doe7jf02hGq}CcOo;IRG=VG$ zaN@Mr&jj0iniKw8ZVqonnSXkhM1dD#jct(C^`2hr>3PpghLjmNkd(#p_ zm)ApCpls>q%#D1db>?Yx?%U1&s-yYafbfq5pj^>1R-4QJTMSdrUQd3*ViRpyN`eiF zlP?w`KGH}m8$b8ck=Ghem^S2zTj7&MJIw&~XjW>z(ZR(;%#7z{Kb9c^kW0Iw7(9`l+MU(6u!aAsbK zKD?xa0bdPG=ZT)z-kpf8XXp?+!MrP=c^g?_;t6Dq$p zgFtkJZXHd(KGUh8=pr!`t)HFxf~udjuLYv0^f)Y_EHcSPH|}CI*D&Eguk^e?T@p=&dahmG4lMjnlY+uM;b57(|IFWDZG)7A%}(JN?2>jMA}f{T`dg* zrZMCEK>X~eO=)lcOHUNHk4R2|d_~oZ?mN9iY9I~^ui|f;iztJ`!^L3L7F8Vgq}H!A zak*!?TZ(d)=mZhmTFZuFzRj;nnoB-sT0K29Z7}rTGUI+Vs$>tw0(Oyg5aLBhf4&&Z zwe7dNot$7hkDHZiUm6i}#DeO2DV#o6tg7e$hX~8LaKk3$A#(P$ZgZlWJL}0Nu(SX} zB+$*kdP4wSj8sr~**}3vQ{f+)@{XiF2VqyhbvNHRyDxw7+BU?Wem{+$FP)A&BsJ9L z2MsowAke3+<}P0DCrtVxT_iuZH1|PW{oNG7H<7qsNGU0fWb$B9CE^-`7)DV;Q+G3K z3Nx1r#X7}(jacsTo(*i&O;YgkL@3Qx7P{^h4~%q@;cU7qk2}FK_j@L!NGHPa&03k8 zf0Y;I!3_pqI;b)?JNF!Tx>|)#>`*{}?Y^8X zvlYO;d*{L|Ey213%WhBvpWRZFd)TZgCznPcwcCpDJ0?0 zZw_T=&nsJ@r1=vlYJQu4H9suRPv5FlgzgB#W`>lp#2?K0cX>SD@sZ{YQMl&g$iM$4+x{AlxI2@m2>dhYRUT3!RL2P8kcQm3))` z%e8_UctnDacZjIeS{FWy?kP{2NM2?Q(HEbBGBHOLbGJrh5oC@oJ{6-v7{s$=}xRniDDgt0=6u2c)49r4! zIjZ83MSsX+0@g^2Pntt|96cc*&VvJT?E*gI$}w*L5C`r{D>mG(N}8Iz;^d1A;HC+1 zNM#fi14ZfIaCGX4#d@Cy(Ihn9v&m8aPz%?xH9=QhXXwJ-m`h#oy9>t?PeI+e9|mDa zZy0;XkAb(I#{oU_H%X#=Ua`4}5I4PDsW#<*q^YTCk;&!&5N%&x>h;jl zVsX$G{TIu9Wq0(rIuz{{IH8UO*m8#XIZBjgBrjpO@ukL@Mf=AA2p2S#M`p#yt5~Xi z7-V`T+}~F1Uj#-m?+M<{oF6obBCbpsOYfW8-g)$bh8xKSML7Z3kM)A^ z&X(-&7a}Pz&fEQPzBI9T?_Er$c9XX)ztJs`2?e<}@o~HOkHNM{2N;n!IPQPI71ByA z1N1H;MGsr+fZv~!vecnS-W@hI4b7R7Y-pBJTa;*5;b+$VxoBYTj!y;tD5bY0?2FPm zFKo-=KR6R=^o&x9^o%Ra@UCg`(;g$c+O6`8yUEF`6I&bJC5b(RqAFlzvk(C$>g@5; z21K^`klqTnT_lhRqQeG1IR9g{ywzI82V9la`;8Cugpwne02N8b zNaEZdD=jn$kqi&mgf8V06Ciai7>Lnh(a~n5N>um8)hEaH=L(@rMB}J&6|?iz!`!sK1#$Jr1xn5Z z{)AKQxI=!5i0`gqm$v%G+g}PMmK9JjN6ivlB`GP%)}}x2@fm^Z!sl}Od$GSTkPCyv zvVk_kfi8!2w=#xk2A>lpi7In1;18@^@>kn3QJDGHxJF7CI!Id_{~EA0 zCUJQ1p%e8q^L6J2@^x#fG*;cQpnq!^V9emN`v-2|O8U!JBS?aUE_r;bhfMztOYLR{ zx;|df8U_>b)tQ9|8sfH4e~=9~9?5tlHU0}&tM-o-quNcrk&K?pLSHtsz;3+@ruymh z?YK^xCQaL|w??HT%dgYK_ypPy{(H9;i>ggetn!oz2dBUf(vMu6ATNI!5t!P){7xi? zbq-$VPa8X%l4oQ2j`me^g_Z6r^}vR;yCC=r?A_l>{%$#(bonKc`M%TtA6;)9RAtmf zjU&<>m+roo1_==aq`O7BTST}tA|i0_kHL4elx!r zhf)0JdCqgr-fOS5_C8J}U+Uo8bl}jzG+l3gu=}95iH~pmOGbk7+c~CQ&(w2+boZ^Hw zDW>Z==50qAE9l@GX)@T4BE#7>6aSA-Ut3_+=uxx-7Rui?G-7aqhqWY^BcX9&Y5ZGr zSza_(1S~4ue`(17Jop!=?f)M9?y`3sOqe2`ujmbz6>Rk@KoG_Rg;4Ht1H647OH>u% zuk`gMN%(Oh7KcCC7jY4|YG3ZqQSUwrx%tFUz!ztA@}#ovwDQzy^-bNnLy>D;MMa{& zW=6l=QQeCV3KGe;D?bLM)lth}Tt;MDcMY)OMPnqImt2*AHpaGPAxmpt78tqC0=ATu zyzKWbtXOE01C#+SpL_@C#ZX+pK+yZG=f4^611K0!5PwC1J1Pyh^^qC}2@w1g*E*Ph zX51jvcW>wNR?A!Z`95Kc!rf3yA|vdT8D3!|cdAb0uukh*=IDcJ^v=Y8c|vRKBT;~G zGj?0E+TYY(p9)Ajpv(gr3&Fw~`^ftb%}m z&@RD(Jpf$Ft=%O8)bwn(HGTW1wU&xol%sML_mra<-H3Cp`K)QHb6%XV$vR7o9dC<@ z=<5yOj4W;C=MKXD(n*)qQ@60Ts=B7dYBjfw2^}a<9Glm#x5s5&*x5N)r_)@d!$R-k zPf-5)_It7cA!yY!cwXnRLSlD$IZ&?g;vH+}dos|9JT%tJ;m6evdeiM@Pt57h46yZO zh{j}JylN<3BxROzZxRC?i7xqS7e$~mwWmJDej*rA-g7_ysa4{Kd z$J=kmgXKn{bBk9AoguzI4;gnw!mN7Fwz6|qqnY`}YZn?!7Egav>hjti&X`v2x7v5usy7IxGr8&OTLl)Nq53qc$hLw%kw# zw*Pl%U-r1Dua7EiNWv438?Uc!CiHcaa=bJt9PlPnnWbh%*mJS z#1s-A<7ejF=SMY)rTHQf^P^H=DM3AzNQuNKceD;E8XYPQhQS$Z5YlY ztS~vKE$B%At;~-2qvti=3|{sT(YMlJeQCE8FJdAT6u&BnTjt0ZV&tKdRvrT$8Xzgg zj*5|a2)?S}B_o^vK$(9hIm>8C$>+z}T5J>`s5@0tKYjXCe!DqyCU@)99(XCL*I9EL z_(>~Aq6?>0u{2Zht>%`QJZwBh_?=AMEe2SqDPt>Ifb2aFB+;FV&a<|4W+5}<2+(!wFEay^QJ}JJ{}7Y0E)=7N106d^^jm1=^G@I z)Pt5+JjAaiRa`AB@Ern?P#m1JJmxmFdAdLRL*hFu@y=OT^ zxo+*JW}5JMww!vY=cmX=E5I~ZF7;$-FIc(OCr}-tc9lOOlKH0;TO5pagHcF!dl#4M zf0QVwO=Emb!+;njJ{r}ffOe5HiFqR);8y}s=nfY|`SUFbiUSQXAci`(F7$o?Fp}#+1-Yn}f zL;}QA+y*V^oFPZI>CFB=&4=Mm z%;pd(l%^_)pj)DCM@FC9=C^RM?z3MbWZ7-v#{?MuZJF+*Wi3g!|qm zB4j@okFz{8U7lhL$8!)dJ8!`W-=f&$#Jgw%W&~F1R3Z`N*QO@k`gJgW1*sJR$-afr zA21(jFIQvJ5;om=DS6n3VlijDJ={@?9SzgMtAKSB^zpw1%bNaTvUzsNro1JUGV0(}ht)de(H zE%JcsQif=emzIjErK=0;7Mm=;TQqgzr6@lxb9I=o|MvY1f)|NFQ!9ufMxzT;oYMOV4}Y`iyj^ z(*facIn=5+6Fwtuqs`g8e}zmHbqViin+7U-hrd$S-6As$nN#aIrG0 zcqqvVuTB#^;AAH}ohhmmc-RLutWMG@QEHl{vP3iUPuFot2t4mTVEsud7Nwi)da)A8 zwdwJtBAP2Jnq9~+vquGdH@?q(Pa+pbv-Vc490Tr<$kpGL{o4`K5Y^Appw)9RJZZX2 z?q6?Fmrgj?LNZwAGYF6*Z9*g=%;8RXjNXYC9w_219bh68Ev@G4MpkCc%qJq~AZnjOkrSK>&@dtE3?Xu;dMh*Py{(K_v zSvC?zI;QqPt8U9&LuA`dWWNHH+1lo|#SNId^G8)Va6)+Gm})II;wx`o5{&|Myn`yo zcNTFA7E%alEsxvjQ44#J-#x*fiwX@5t-8qMQNRC6dE!?P zyfb;}=Y9RSFt@c0af8_g9u0s6?wre`7p|g`lj>p|;D!OpPQ&hRJm#cE{Si6rlx37y zANa|@p(g8A(FDBW>Pxj%U%+-aqFPz;BtUR+9S!wmqBYpkHp|{D_N?3==TB0J;5zI` z2EBNCg5YZbQq7Usa)M!iBw>QxOkY}Jul{b`nI?s@^9R?(vzy5m4QnDh;;Ep19j0j>4B2kX_Q7pJ4R7RmD>$BnFad#F!Z~sEC z+zwUb%d2Nd^rPUlb4l*6m1ZP-yG*=kswtD9tVp$Ddmw0n+XzV;`IvWPP#;Mt#W3@& zgfuhe^(myA>Zfm!qe$m#N!z%+x1@PDGD#t@vKYZka||_Dshs3a)#P4UNIeMtnPQ_A()RIUnkS(&?XKnG93vk0 z$KBG!o?qq(Y}YX*(U!ZL5BsunWsgL)kI5CavYol3#!jDf|0)kN;3n_u@3(yU(scML zFow~kZ8o*vwyIjCwW~W9!!TXN-e952;!pR)z@9&=rl2g;+2ws3 zSDjgF0}e+3h{FT?`Rw+R`RtTDM6E+ zw|QgWI`@6~Qv7@*shETI4)U>DhBeV*Pm6RJ-x{@uwGfqMwXwD(7f{R^&0-ma)NAWR zm0&oQM1~g)!V;JLvW7vH%T{P8t~W~;&}H1Wub*I|X<#VH)rYYrDXVE}egq+nxu;FN z0ZAGNEJkP#^W}!I*La1D)W0^rBARWjH5dPNQ1>Ps&Pb%iTBO#Tqj*r7#Iw`t_WTGFwG%m2>qM|*)7&ZDz zjrn-Z(ahWOAzf6cA8;~byTE5XZy&Vkv_>}SaL?~+IKy{v7kk3s8riRAh`^NJk4PLa zxlUvTuc0#tuDzFY+)f-r9qN4`>JcS_3HiYLz^%4tiY-A!L@hb1B~pt+1@^^ z&F|SDcy8M4pa@pT{_*|QUpX8a)ptU{gXY)>Mj*Ov?)CoH3xGiHm<{zehbNqJzLW)9 zsMR$;q=A10YmxAEnt;>iZ~BhU2_hNj=g%&!RADMm%GR~!W=_Z1>||uwBl13{JKfD1 z%r8Y))_Fg@vmPcI(o{24a!uO&OiDs<(b)Ke)2Ji4UI$XRMhy>-82*{07$;yZK)2nH zS%PfU16E$V3`MHGD@}KxRxjtJWn}m(#c(~XuX&X5bRrrwlXpAIR2ywK)KzG~a3Wx& zf3k;+u-wM#0vRypoE9 zXhIUM0u&M(%5px-$x1T_*b0olHSx}lcb({^icvw@!Xk}`ZKcm7-js?Z+u0yMn6ze^Oath36&GtqU*LH0Y*0cuS5vB$9O z`8tqyBe0K&+CwOo|m8Hwrz_(eTlSQOGwfW-VP^N!oUxW~D%M1Bhl9V_>~7dEzLT_ix@$ zivAA@?{=TQGV{roB(Km6|&_7ChV$%ZGQUmYDbkp%frc9du{Nb_@{QaP2 z#>KnWEkz;f5Gxv;e}^Hg!wTFX{v_a4;mM6Rjq2*jg8x{=fhASFrhDG*kij1d<>ThC ziA`PDz+siRWB0%gLBR3zW|FUSMXkDLExA`H9GY)NeQblnI_zGzZLc2-QlG8a6Yfi7 zIr(reQ@1pb@*O+KqXkvS@hZg6sV|)$pZt12ijlQ8o@;IQtZ2NK(n&;A)a|lvkMTtz zR=t9r6viV{03=;k`>3?2v0mk413R8F<1L@d>Z*E- zY<@fe+gP)-w>FiAYMSbVHgfg!kw}YbA+9fKDPM;9T9D}P&R&# zIz{GVdPToe+s@o)r_T9yht8_IDgN>`4h|0;5idIk{_x_j(vKYY_o%n%2{P4Y={{^N zttp=SsFQ5>wmoI+jpzM`!Z9|2VnawK#paHbELH8gPLSpDf5o#G$M65I;;|9Iy`}BkH=bxAMu4I?>5%#n_@&X{tD#CCW{pn?pwyqN4S+D9~ zhWAHh=7(k4#}*}Kcx&0MJbZ+?RfU8?qg|U2l-O$s~gEd;?2RU*S@pqeK#XM9z}$IzKU#4$*H2RGNK++q&`pOcosGE%XR?;GOd;O|+_>9b4KCpSD= zS6mk#>G@>Sf^CHkz_xP%%1Q0S#Oc7Khb=GA0myn2dcp!iHrz1QB5pdK_Vw~Y zfr$?_HAp53d69EtTN2y_;ER2m5W2c_UU2($kOdzj+FP z1-Uj!#Saa8a}O65@1nlur~FUyz>P$p>=les81&4N0wXGJZX4OJH_qOc_u$q&{w}g& z0xKD%_O6G0{Wa6wkF@_K!eRk^rK;r+9s%M4vrA?H+YJXd`c=n!5@du>g*uw>DCV@B z6zNxwRN-tt0Vr^!-c17#(ac{nag+Z(J({r{+4(L59vWuAXC?-_sQR_fZT-$jwxX?y z2_?0Rp(p7k>^}C5K}bypo{;)O_eAUN+mwP57_NL*1Nl(3wxvv1xK}B z>Mw%xi8u17NG5HXtA`$d?>sMJZR}0-<&rS5qt$P@J(-Yzz{k2rXEwAzQ$hQ_{hPAj( z-_hIIdC9P+wTw*Yjulu%HUJ)Vx^dZB=T*UQjSm2 zc6)cM`6bzt>+8rME>;J83gzbWIMIX{TT6HbD;d(p+EAil9}n#BcDG`FCkT?(J1#LC z&hQu7?G0@L+-~D8*6kt-BBqTScJ9sfhqp_K0c#h5>CVLIbUS!vQR=cAcbx(VDTtSLaxMF6*GrzMw zv|kG{Hc}^Ojuu@fhIJ(;l8TN?-b<1C6sg7Gj#t0d4O3$};^Rs2n{Ii!3ulagW>Z$pt8s!Qc!{vC)L) zYF*@$Vm}hnI3Vm?l;&o;D8hOqK50;+?+gw~ZMcHYx}F2;5rs@^X*|p0a66{Vp@&X& z_{wti&5XA|--nX*HUg+>n-Flwv}i4T@dL9=9t(|rILptq?wO(P2x&Wx@l>}H`Y=0( zoA<7gz2Ws-A+ZEq`}><7Qh(<(z~V50h44 z;mPOeGQ)6o4^6?0_KlHuWPo!33;O!+f-X#AO0{V$Z%NnVW+muG9x#6CpwUg$jYP_+ z89oLQ>4$~d3nX>H?&R_~*cI6-QJYkA%( zSaD&*qDP0Wh=s~q99<9XL!%Iw{Fs&(tFu(nEp^aN>1qY1;Z?6lC_h-ibk*LCyo-R zB##QGI+K9yGwmOq>HT&B4}~8>h*$jlh@Y?v*vd3l{<-E1xM;qqVLutYag`zFfP{{> zDs|{goULHEC2jbnOMToncr<(?s_W61dxC^=p1WVI&J&y%J{V` zFrr?}M?q1WH)T(Pdi(eX7EbH`PtwC*MLzU+sJ~Ba5zd+@ah! zK+pm7v{a?P8-E74Ns8ORd9rkImuk1<-FPK?;kSBR9$s8zu0r|YBtc+7dd0o15D)7~0Y$#4rv4AjE*Ab~j;At~ zTYk}XogN`vTS3EC&Rjd)5m5K|@Ctabc6cj=HoLjQdt5gP0?{{FLlk&cLX;u)9uW4! zC^wy~T9;#2Pqe~>zrpny9vH=JzTc1SQeX!$#4EAx!41Qu>r9T(y{9Wh#cH2UY1B7D z8U;IyNcEqN!VUwie;rnC^YSwRu`tmF+>KcU+!t2&?)-9NC~CeJ^Pv%EFkEp|*a43! zE;Dr&f`T<50Ffcw(c}UC_ZYo#O8}IJ2eEeR@kc-<7R}D`$%~8A89hZs{&>lB_Sg50 z^Rdv*+r0X8Dka@@k%<`RI10R9|I?@7{dnZ=04yY=(tv-?+%w56D<_-6xYN22JgDv< zm_-vJ6T6K`sKjl^fd?OsFsX`#c^gGqy~)h@)6ICl?QI@Hiw!siqbhN-Yln=0QuSeT zZAhklTU5ZP%d|_;>fY{luRGEemvHv|R0~9T3VdG~+I6S)K5D{GHvlO4K#KOE2 z6KS5$Zs42=JFGpZx*mQo;7w;=X~>;x@V$*^WlzLkjx@7_xyzLia)^N>pDE34xZsTA*Oiisb@$Fh`43B zQ5wtf@IqoN3=8=eR~!L8-!?^(Np*LsARYIG?;VroHD_DGhu)q&`bNbrWURgZ^)~2U z|1!Y>ATfZXK=Y~}ruHUN`e+1-Y>up{!$stIJGSq%&#U`bmK$48-)kW+Z&?-{3u*na zl=$`>u{|J5xHI@D3g)ilNp~Qh8vJ^Gs9)Gw;bWa(?#JMnJYv6&kFPE`KVM#@nDGS< zS--s{rD~ao@l)*m{HP)FOyo&BXAtXqSq^S3Nqm*b!F9ODakQdL3=xeFC0-mUtvn_f zwM(Bt&~}i@vtExdxm=y|ys7t9_~GvI3XJs$*!J&T(y{KzPDPH&$>!a>vCIZv3>{0n zEyRusC)=A3(H0N`8*eyMyF;pWC#g7Cb4vomL!XtlC-LFzuBW*>D&)9Xmc87l11J*@ z$qPGsun_(0EmvaU0xNz~^#refB9pnqwx##;*79chhdF>CKf8S%gDhs>^FL;kYiND_lIEJnK{EUWWAmA-x z>+8k9O)Xzb8upSjC7G-iP?*Nm9m*#xgfi#7;#xQ9f;+4*+m^LC8`Eht(b`(x)g2Is z@Ln5ef$`}Kg-zddc5;AP^N+RxVSgm|67rL7rHT7D!aLHqzg4Yei$`TCX6HzR zlV$4vrhyQ0yE)G@Nz3wDUK;Q%)^I)8fB=wSBosqvq;|d>kz`mKMcWrfb{@4$_c4-C?avkPQ3TMvO z6V2~m4Vm6XbS_<3D?`EE-|@YLPSfNEz7n$&LyJOKoc|xlKCO@-l_4=A5-9=S)ER%e zLoU+Ae9VxfbmjYHmDkx4EfLUug-{e%{{Zcjba<2lR(yJeUOSp-{!OUW+AP;X*%O(R zlD>cB`d0`bCMNZI-0v%20p{xng+!HICo!YSK&RKv3L2cm3s zFCBQ$vc?r=K5-_fv6q*XMPiQlfraEirb=C3wX4 zmOPt#CB)PfIoh{t?hv?dtoH~+yBza+SuPqoe89Xq86^)7ERaEdp3xfV} z_Cw^RRxt$8o{a7E$f_HSX>rr7ulXULufC;7YRB)3kKxzsJr@@%xV>*vjBUZ#anQF3 zai=*EMD}5a*nOnZZ+NW5xEzdxsz>&nIXr>4f{N}+wK8jH$HQxxy~?0ZI6pqvmaEII zvde~m=A`^;{tl&4_Ju@{AKuep<&z64H*ZT)S_+2e zFALY*utNUjF=9AYP}ehsnwV(|c!rVO_pT1CbXr-kSFFno_(etE88Ahr65A$CwsR3t zt1D=~*1{_2E_MV4iht5i4AWh(SK>hMMCAh`L`5wdwYpj=$ZP~1S(9SSTRBcnT+0gl z6QlEZb!HKMoDVF)#xPf^_M|xYVXO9E0;B5X(L`#MGMok{5)4ww5BpKf!|AY+nG7O} z_go_pK{bh+eUo@Fj_D)Ej}7-jma6WimZ7Iuq1V3}97F3et79LN<|Doih=i$nQi$mC zE$(!j8kqnJk~ldb2;5pwZV=MB^oXC5cAed^P+RrBGq3!eSSu?~=xQZ`FYN=rieROn zvb^8@y~1_y3mcICHr)XE?LtHqk@Z-76e_pi-t2wBrr#)Sz;JIzj}amhm0ppoU^B18 z{q@BuuN%b)c6J^1GZBtA1H?X!)<_o_rpONF9~-h|&h;mhFi9$j@CL2S|KUrxn(yi+ z)r^F@t_O|wu+}ZaH%U?fx7*NThcR2R%WG2}##ssqVWU9#ODKX~jmGWCQ5H05&oQh; zl0McY`yTc^c3i0*X0XZweaORf(@@}33A?mvvMlX2O_sS`2dI3)Chu~=xkRRE7#Nb= zwE~BdM^!)jZJZk626sr^ z-O~+?es`&_!|SKNU?ZRqN?Q6Iq=CO%t};kGOaJPlPrr9s-#<;`hj0FvZ@|qOdQdd; z86vMIgm$ERIizZz9?#FR^0k_r01?6&iF9>7p)`ANLIS8(e!O5C&IqUKsj~jQQM^^V zwRw;GVEEy@R|8EzUxD4_&drsn;+kANjFKB85Pjk_lFn@EncZ=j+SV@jJUGn(|SKPAh?Rr-2#Z0NgC+e zCVD9Kf0-km&9HOQf3ctSIS=D&vk?9!zQN|AAEW(+NM1wE&`CQY6-uX@%0dp`X?<}z zHTaX+K~^NA{cIGnyPNDvdZ5jj60gCb1zmQEBW`gmQ+l=AJikDAU72Tqg(9W$@^#_N zLv8Pc>OC=&{r-qAxbLLS9S1vPq^Z1__^7`pPp2TO$ncMKE{C3io*;gfQKuX z3r!*A!ivRAP~%vDe~DLO2Y;yLfEhe|zufKq7JgTw85%U6C- zRjIvySOxe%zuP%GK;{+qYgm*g=2Ag!n=+dW5I|O zHOc&id?}qc_8vi5821EPl#^lJ{X*2djVFGNOrVrKfAeZv!mg!a+3#+J4eA z-=NwOU8C6YQ(1^R-p#VozAWl$P=99JGsH|Sk{f2UzA%MyM5-(4yJ+*I5_g)3eKGbg zMd=ENlZ3$)ZO*iCp9ze=ObD49U1GZ6>o}0i00{<|*KxG07;_g!uZKUG*If_Sfl!7L zZy@+ctZv+B%kNW*c6y90jU5e1)&B|{ju|-d(jWFE2UrxYE-@uu;6hxc%D2__=56^D z^E#C-AdKDibAc+M&TR<;1Uf4EIEIBiR6F~$`NJ3%BCHli@77f>=py@afgUGQS}#+Q zn6r=nMax}&p^~$GtR8`Ac@F1z`5hDT`rTDMHwqD!cMx1c04zx3|2_LYgdL%?wl!q?)dR+0?)Pp%{1JPsNk67Hu`NBKK%i1rCB>( z*f<$68Uad;?1Lm1E_&eiLHmAJmW!T~_{m%!`>o{i8bARsdq<-F`t9o0BB|YP^lZS4 z3GA0(%SpwM5QpVqa~mv*Y%!&%po1*)jHTyT{rfTT(klDX_)AjP40C@Bw~UfH2+gPP z!qN1DsVVBzv^2I?t19nC&X$uj!wn`ld?W&*V?&9s)U3U{uow2W7_2)9CY(hmV-)lz zaquwiMw2HkcG^$kP!@%^wJEF_{H>+MBN^iIXaSm-CC@%800qG8r!PCL?90hWtd3-s zDAlve(yL$M1WHF{VTISb;Hi zCdBtd$p-R(@FCV?BT&fH86IzC_Ssb$NR~(YOPXgrtE2dpKcVvVzg~c+jz+6(OZ#|@ zKE)xfU27u#Vnp9NjmX~Mq2Qjt3B zmrcW&N)AHQ#x?d)wv;7yS_-yH$3p5XDUrdp=9F?u`^vBGMeno%N6x{k#F0MJF4eSu z6-)V2dIk6G8HZHfo^k7*K(BiQS%?o_$oyBMgdpXBG(1sB31~1S`yXY~+aUdbX;)>9 z<@kDcvid_o;%WD?qBN%tTQVll62Y0g$$177b_^49R`AuFNGJ{?w~}U1UjoUc(L){M z?jzQu?o=7bXGgrJSd zX+ubYahl%_?{cKZdiB>;P;dZ=V(EXzpSa!_*e?n9%9CbbWomR`(vLI~Z~GDhyE}y) zb}W;U?$A}it@9p|v-_}fXO8#Bh7kOm_D6=$Ix2o?CvMs>V!{ir5RSb9KX<^GvB6S9 zJo0=OxhT6oiICC5NvZiP_ppj+ldb3zB7B-_+~yx;Eit?Ls-&BkFwA!@e*8ruHej60!#NKx7dM&lqY6))JK%wHF%@_W0d_HHv zH{4Ki)NgS*<`yt-%^}k+`GnH5kQ;nA_EUkYZp|0GSdS;9%`aa?O$f9^KvN?vD2rAU zn!iEj>GrMKg;7V|V80+dotIotnD<9HqQ`e1z?1Dj34U}PXnOdGYAfIZ*O#*0p>XJ} zqlqmsg|w!e2{_Oh8&ncAB)Kti?Xs2=g1GF1c_vO$gL+sxk%C|MB3|jtyR+L_8%CEz zw*Z-rDJ<^+w*ip*MdyXtnq(;v$;oK4&WOZA(IwTre^_#_LPY~* zk#|e6Vv>8tMHD1AgBrA`jyna~IVi<)Y8j=l`uM@6jqmdjzx@=QAm=g%?()bkmRerV z##NX1-W2qgdu4p>tr%aTVdB{ub+j51;W!PC#GI9lOCW_T;LH`p%i`Lnrv@3{lUe*Y zgY^L@M4d}5!6leTq^0ySS*x=hVj zYsy9H6V*_s#6xK*;(&*db(7BIEz(55L&ApSu2Nv8ZwegvVX^*`kA4}9;PWzcPOq+a z^L*7XZAh!SC%%a4P!c zxjMs9_<@Zp$vcgl*1n_YPlLcaJ@KoI+xX&>A=GBxU9+B*hsgBf{$cim^CBO{V9-N zP1Mr?A1`0FGoXDrq9!LBG!?J(Rp_k%2Ipdg{8mN~Jsv7g*uY z^xB_q(e3M}D=d5a{XZ`+%@E5eO*8&>3Y3Is^dH9}C9*q;NI`V70@4LvVAi>gQ zBM2prTP4+jAgtfTGST7$3s;=^T|Jd(xWaSiSmk%2R4mkaB$=yNZ6trm9}7}jy87zL zrkEpomIa%9(&n%#uE5&0UXocg5tlNbNz(Qzb!3Y$&%1jY`9y^EP0 zgj`)KFBtr77!(DuM{;d3mum;H0}1pK@aU~SM>d+N{2F?kRIb*uB1ld_9>$BDi7`-` zK?KW-WOaZ+kSGr1x_19f-J*v7Qg=nHx)vcgK$_l641h!hEJ*3j!`21KU_DOEk7FVG zZn>Y*57v{0cjRPsE*a?r#+Mm8ZpYR~E3j~;^dwZew&MbB(3v+%rydO~kK4_Ca9ib; zi1-YzD7m?5d;0|12Q@PDSI5F$3_C${1p*}WuYdgxn_dVVb3*iP$nX<|bZ)=yX1!ju zCCJj|@i2RXL{OHbT(}Qe_ke_C6#o0z-Qb_|p*H&|wB5|Vl%2lj;`yL359ar~cRA?E zapfU!bop6Czq1|bTZnCVJQwxnt66IL>s3o*OiKYl39*1NArw zQeO&u%!K3~5&lP=Q@Y?luVvb4y_RuO%iuBkwv1mk=?vQX!#hp{9@53r>FxlFyV8Cz zZF`R?23wJ{V5S8>ZR4K58H2whgFlO8drpTIH+e$u8u+>3_JSYGnxB^=((j4%V2*jd z^D6l2EI^&{el&gSiymCnu^{bTs6RaetrzAA;mM;BA(PKPMfrpKQF>JJGd~8Ydjz;` zvdw)=s}BTz%kii>_$oCH6Gw%F(qjG;$dP9%+GYeH`};qiWYXs5(ZSmr|FTNKz~hO$ zU?cj1$SQb$IvEO&QmK+r2F^nC*lM}ti;ibL2kpvl0#-Z}Pw@dGKf#YTq7`Yyuf?A= zJ*f2YU5`F%J$_UNGrV312SLHh%S?HKX#(-(fa|-`yx(aB28wUiSx;QE{;>->=5@Fm zRd>H2zm~U zp5zRbWD2r;#V8#4HMxOfop%}8^~B#jsFP~?OYqRjt99J+c>Id4>|W;6S=t}=_wKIo zI@|p!Cj_>WVU7Zx=8qK$$+$6o@hujC06TN0e5}XM)_BKSo6r2;;sqP~9-O5ZxVgcU zGUH($U~xaHtsB67Nr=ne&|kM7CmKK7k2K+p!a;LJbhHHDrS*3|S~5Lo^`61J zsGtMR3MfNz%Z#;_pN@?1c%y+qoLRfWL%FkK65UlZU6(W(VB#Pij<=5Q)u{qCzB@=< zY(;>4I11Bq`=51V@ph$x(4#V{GhTbpa1PtdJZ0x#UpV};x8>_C`sHdA+1JlQ%RsZc zex9L*0Vs8!vSXA&tLJmQ*geB0kv|;O>UFGqt$PY}us1xAkNCNl4}HE2|FV_#vrmuG zfWOL=U2QNN>cnX@OSE!EuK{iq=N6E4_8V)yL4efV-_PN*l2R}ZeD8lPAnR@r;QY9i zM+{&%xs;5eL7a-kf*@JbR(^x%)9f#DGV$|V{*efQ&C@IQ4P{KJtuSL0kW?%FCxq%6+`x3<`>-a`6yVD z4&)`1{LDWNA%zWvWH>%gc+$X&aVFFXHJ@6Z%}AR!jW`F7i$r_%srFAmZHwUsw+u){ z1puojnAXUW)EkI|g6^EMl@_lJqF6iEkHmlBAUh!qnk>r1S5MUhPtph0U@?vsd6x@e zMJ5B&T9z?ivnsf8-?d?*+?P=MY1Ol>q74D}@PHSOOxI##VJkqGK{wK%7fvEm&Z3-XCSzWNL7|leaR0dx%e5s zbTG4xwW+NDeKkY2#gA%I0L!ZEyZRthvsCH%6f_)!UL!~2JFQX$JsHf5uDNtJneoYGo$2g)o^u5ze}ZZfMHzKdpFdK ze)P#!&xV;mGV-Y&pZvnVskp-D9Viu%P_XLxlbHGLWWlcujjTn43tvoUxJdS;`&0Bf|uZ1a3OIJUO-c9(@abN-Y6B zZSGW8pNVyT)vfIX3&rdUxuE;)rp16ny%jS0wm*Nn{Q6Qx7h1%vABhCFOgOmT`y952 zDV>!Lca^{ztd#)nn{~eROf9HFW1vISgq9^I&tQ2@Rcn)#qHSqV+b`P1{l?D3pQG4v z(W$X!%$H74b%7$EyW#KgKK6f5k*m*WJj=1!C(`2kG82U)t^Zr_R0M>Z#_fv?dXcDN zJRqgUMk^$O(}ez%aYdL$MnnYb=^@EXm{fSvHm9C-QD`?obX{tU8x1D5*ZQ_6L_V7} zPn}enB}XV!18l7gm{-2Q7wEN*c9la$-~ zh2;`GSRXH`p)6x8rgG0Yx+TF|X{t%G$hkU`UvejSWJ4knCN=i}PWdyx&H-z^ld1@q z6hw=-MT4BKN$<7dS`L|e*kP9PlTE}l%0?!F+T8ZKIj4zHL|WOuzTg>=}K6W8X)0?`7Htoo!_;xTNB zyb5J6ts6@1dx($J8>ffJylzcFtxqlATERe#WAO47S&bWw8gJ6_IE)yp@Sd0e_Dyl~ z)7k~MFbc~xr8aAoK4Co_Zcy*iD=?@85P(Gr0~|nDSeO#~iDlVWEt+tP;)nl9yIHj= zFn=E(ssgr!!AqDT5kvpi;s0u)`azZ+6z~v2ioGB9y%sUtpX9lsQ4jGp!Aa?~x_D;Y z^C3Lc&n?uENv|6)Y%zHXb5Ry+H`5yi^Y86G0=@-i5%jVn_D3ZN*gF`f`Q$+~5vMA$ zd@H^W_oS)*Q;}w8^bH1CAys05@qMuSEp#Js5F=a(L%eXV>1Ond0M|TpiLS{jP6!=%? z&}j0@WEibdllQRsC-~0|UnfIwU$b~G^h?cbtv5xsCm-Kw;}@=FVgz$1R0@gWq}oP0 zY4{Df%fz!m<$On{pi8y>MbO3kzic~wqzmy)pGAC2u<$u}V()a5C0q`~V)UXw;=$oG zLxfDeek7>N^uaxIM+?QMRc`8_wMfPX6u96(-MBSI+>~FGnJ|FUa!&-j6qCMqw zWg)%T_+z6Q;0dE@qK`a_A9xh*eoKFa7hxlF99}_myvTG~l1Qo3(e?-qSn&+?z3<7& zu*iUUtLz=a+ARb4KXG`KlEklP>Q@O9nd-vajXNRBJ(h_xwpVXbNQr7ootO5mnNqJi z+0H1g@@gHKiM*5_WPe|7w;4x3{oV0nFoL)0L*ebMYV5&Q<zQbda0R$FyNsV) zdC)!*?+pQm&U=%mYW1Jh4TXo}AyP_;YOb3?MG`kV5|Q=HHP`3sakKBgwe|CI`Num(Jlk zKY2D@Lqoi^=MwiNP06c!-&?yPVeVjfvB1jUt5?-E*-qfHMo6!Gw4b7-NY>bc5MJ8H zfpxb=jN4^G8AX$oZu+Jx)xiHk4A(0TeWl1E>TCM*t{3!g5e6iUitwIIs$qLGb)Jt8 zSljunIy5FF8JO?Bq(aRX2gNg3F#>{<{iFAAgd`dmiqsGv@Q~0hl*-8)*nKHA=H8H9 zHiEvkmoSx=YUiNWil^vPq=N&Hw;w#f0a6)guhITh{3Faknh=!V2Chjox+ip}OvkKa z2ip~TuRG5}N!gpR5&bg3mGQIImKoLIk)eLXA3`5R>*J81DaWF9i718O$ip>tF9pn-cG$J5Jw#R1FX*zqRunS1Wv6F(W8 zTyX!Bh&cL?&E(R}zx5D}TD}4OdW+c4^QugmCt0W>0ry!FAcekVqOe^H|4(mC{!_l*LB-uLk1m%pa-O}GFobZhQK|V{HQH#qBx&VjfyUsR}H4KF? zV$?NbS+PT4Pk?OvY0H_Hu90#j$ zngiir8eTWaYiwMP7%G|t`$o@bW&XLyFbNwqViADw;N+jLWK4pglO#n;>~`H2e|sev z$H8D8JzPvyg5g)PAFmd|00J??BP*1-YSGa$;C=)fh$)1Q5UK)=UPY@(;d(fdLHwXb|S-F*`WS?gCT( zFSkMf&;Ns~U5*F^cD)g_;K_G|0Qp4!){K?#0^&3f$w-(6Yp3=nx!{Eq$ z;MBC@)NI7_osB8$b@%Qu_}lP3AxvL@6K*`=P01Q`0PMCigN*u}5XmU35=2W#E(ND9 zxcGwEWc0pi0SxS?r|#6WM*XC0>Ng8!85tR=`b)3Yw9lVIz;5FwC6~L*`)BFHe4)R~ z$;e4{MxvGxLvtwoq^CnU=q7Rts#g7IiSHyqlWspFvPb|u`jm$^MAuW6T;`M%JBq&0 z=1t;#Eb{q3m?EPQb)F2BlGD63Vbp@e1fV@|nWLfI-IBC8-u(PCe~wYY5!s?za0Qqf zM)eBuM1@;o#y=j3$P8ik$a34)#!|;GG)|APUv7%(+dz`hS>rPfNoX5b-Dp7ci9WFMFu;N&@`*>d7&;_#^5&EiRHZ<)j&l zhDKL7%}&6Fp5MIkq{3v$o1`xAWRP?sAZ%w-g<@^GF2lFD(eJq-mT56VP_Br(Y8o?u zG9hFAjSY}dfQWj`zosDGVLqZ4I$$xltbrOQZ31{;s=*k-<$Yg z9ZQwPvhS{hziDK7CZkneqM6jH?TGh0pLA9NdS6go(4;Gt`h9Sbs8W%ldW&T%6W43v zadkumf=AW9B-36}(UW6HxTGgT(RgW76n{o}1**s=RcQdBtNHhsqp!xmt?}iSuC|z@ zesvI+{`mKXu*}H!x!n+%(6>ArxTv>_1~b)|02+P{aCEe8mnl-^gm4Xa<9ccO`#m<& zEohR37T;J``}m^o`*GbprXqdt$li}}R7|6WcT)|5t)Vng+Mj%WfM!Fe&Ks)K0?m6& zrU2)6*IM<;)}tqGe7hgZyege6PuaVP+#eGp2%NgewN1Q}eo9~HWC)|B8y4+=kZq=n zcj|{ElWn>*+b1}^l#36BECe=FAHsHJLq`E8$qP#&P zJ^VpVN^)}rMb)YCGc9%~?y{D0S;zWu2PRG5F}3Sv05)G@#l5{~6;{I5)$PeaD(jEk zkSFUlcnL)T8#Ao{L5XMvA_CxQ@SzS{NaF(2CryCdH7`xY{NE)ySEW6WSDaQoC!tx) zxj7?Vwn?(1?(d9}U5Qx5ZW8gpr0cC8mp}B+b^WZF{!rp~H=rk;8e2wpqKzFPLRDp2 zoD2|c`qaw`J#sL}3d1ANG$~H-01glW9-9g*qcoj0wd_LDIxj6WuUb)Au}hBVc(1Wi zNVWvo6Cnj*91F&d`kjr0AF=n`QR6#cGMmo1Z`!>jr&|aeO#lJ`%Gm$cEe9Y*7zR3U zN;66iZaPDbNk19)ncT)gsXD~CW1I<@LdoS-VLpT~Rh_OlyXbt=BDE!>Oq4fTn?k;d zyT$Tk5BksGV1F&6TdHC%;(6x1#eBWiMJd$%cRbog4U=Jjlu4f|&tsMx;%>eUobkl-fbHnfjl*^dE&#V%E^ z7I_vPZp-m(sjHd=UcHkLtrCaN~e+dcm^pc1x2NSol7BC3f+anUcVEfz;PS0H1${s<~;K{db zlsCkFMBC9IfHtjo+N2i83R|6gGVI_c!l_DovS6W*ybX#=H?H84UV%rqcd@qqt-`C8 zItU9qUMpEK0B8>2U*i0`&zn9drbmPgeN-;y6yVfhmipq3j}W|;L*&C@lJYWNCAX79 z_T7T7=M|dXS#(JaUO&aQ;+`xxi?qJhRV*zdhxh^S!=cm|iruLeV<;vjdvsLj|FbuR z1uO98$^n$4-^+&Dh)`*W)r(?S6fdY_wzx|BgqN-lG9eVFr_o`f5}H*S@aDOA_!txE zwSPIyMfgi$96MtVuYMm{ol|3cgno?C zZ69wn=PKr8$Z8O{pE6=@UsG;$W4ln^Swn={aUY=dM2wu9k#FgNEinvb&C&B{i^Se! zL5z(F&w?v`?vN`Tt^7mzI(ol$_pL*#)y&v&vBr30vMFQa^e!EzIqYh@9IK!Xuv{)6 z{_}(5E)?ZNDZ>Q(tDOPS!29`j^HOus-&rvo7e$E|A-NF^PBS!6kZFh&4<&+y?KnE@ z)$XWAm4-0!lKuMIDj{)9KwE`?3Rdd1w4#!dvHhXdqV+ox>t@vX@z*Ym6bs>RFY5uER)AM1 zwqh~}YU3rgke})qPcU9IHGr`KmI{qe=U>e-ynar<;M`*}bb2@j2lM?w#{+{vocO%( z1;C7Pad8Ye=~Y)VYiyNv=19JvZo>Z65OO1u+nG2wvWRXhUp zYr8(36lu{MAUpljg!TL>tO4kl4HN}V#Nof^qKA&crg@{4&RQ$sLAiMdmJMu4-n}Py zs*Xu5NeAu)i)TF1O1aC3TBH9hNY|un^0RX({cnq*CJy7~|1@X_UA_bVI@MPCS_0s; z4G?N?m;k~}9;x9M>xPLligGvA_16MV+I(;9h5O=Wd3I;3G&E%sHw%JjcGmABjJ312 zN4NJ8{d%ZrfAtbB*SyhlR1GhcI?Vm5D1PiP{7UjuS_s{KClvn#2VPDfKSd2#6f~hW zvkLy9cL#o93kyiW15@mRbzB3gwDuxD>SLH7u?+9$zOC!#hSm$lZ1P)#@t-fo76e)U zG-5*ax}a2)KHP>3czDswNnkMXRS44~qu5i|SMXhpW0@~M#Pr44wVI1<6lUJ<;3k5WXII*Pc@3i}pcHaOaQ9s%csl>~bw!Kfk zVn#X%)kV+wim~o_m}cwbJjCxmOT_ng-;$eiK(J6k0a`IWDnNg**yi0__`ES&43#u^ z*cK#w1T7xCnzikjUU6Sy*k_xhj$%OoBEGO#V^=~aY5HC{Y(z0(S`%ZEWH!;kun7jQ zG=w}3Q!(3_B8Reo^ol~?NLp~ncJZytj|tFnn!le!)qEmJ+M1Ex%mnWgs|w#;h6jBZ z`pl3#qiA$H#EX+DJ32J6oL(-i`((#j`9n!=FC6xDN5Zvcj`|f-Z?0f>#&`|n8;^Br zGa3}KNUDmE?5#AeLyR_h7TR1%1`<#)DMa^d{--ZsMx@7M1M4B@0gsUM4AjA0ympd4 zt>eA8jgV(areKX^(P~}|Ahs&dcnHq$QvJI7e3NzpOnnSnQBY}*5ShR0{rf0NFagF8 z;Ne?XZittS2V*Sy_pfR?IIj$7fF=m|33!-Tp?PW`KIXXQ9q1mqDv$PpbBqC5=jy&X zS*HMLbp28Rl6%Kr+i5oTKn+#pIW`tTyitW3+}AE!B#cFXX8_1WI#O)K{3^d$F}QJ; zCp%~xp_DeGdyBmJ0pS9h`KP%+5x$tDLL7^?p(tVocmD%1VkC{Ugh zHBOfRwgB#l&<-`2FWM+1?F+B=ywE`23$#75YlF-9?*bk$NQZm>j;;E{2?PH0;iboB zh%yyy9!~+@XP)lfOk6?m`&%VNrbNMC>e78>z*C@FNuWj|&Y1r4hL| zq>Dg?a`3~977u)necvY>jP-Cw#jqF6bFxCUY<^D)k$E6- z&hi(L|I%3OB|GZBC9?#*MdjVwVSW#ffd5?aEvoAvR|z0R|M|kD9;kyhCd{I56Mp8P zIVCw(#1$S6C5?wg7P?z_QJsWh%Ky-za8MYz z2(sSzDEA1x7Fg+so;~_(RZ`omQl?S(){Kkj?xyA)ux2Dj-SdftzS=?fzqh3eyis?9 z8|i_O)WG5RdOVV+D;(A1PmQ_GkHp;ZSMd5P{C+qef6H65+u0*Yf5mNLhz!Is*;wc z^mD4tH{}dcAxwXE@JJ{f%)N1( zXb#`{`5upp%F;uCtu?_XBZPkE8EVQ1_nze6%$VKhUE;P}2Z-Rwq@d;5;>lRZ5X%e$ zi5+MssDZc^Z1eOiwCuZj`pWAM;QZ(w`d2(Q6HL|Ve*3u8UpT_Zk~$20Rz3MUG@Yi? z(H_H+(|ODr<&O{lxk#xVaw{h6;xQSZQgk*5ELUPEgCg+?{6F0i*RyOBsQ zgnXDmv8@BpGy(d2HZ;{@wxSu}_A6rj*aTJK$~_xX4}h8e#2pqi znk>QpWBoD{3CATq^!K4)(Hg2qCEpJ}OQdn{k;YIgm3``wl14YmJraC)K>Tn$Z(WF|u#uLnSdM>h8Q{$U# z8V)So^Hdh*thk_ES}wPR^v3*<-%wnjU5Ptwzem;Px;vDebs#=o|8ab^i5S&@Og9du zs{_SpLF2oo4_f4tYRT8`+s|P19({NQG~!nJ=t-Sa&61Ykp8`+}ZT3|5gasoR`SLYe zQUU&&CyiQVIAj32zGp*`<38Btxue25Sx;4v!sRLmHPZk5?t{mOc~znsUSt{2n_!TW z4a5;nqs9V1J@0Y?K-9#oFsSIUa1vF#K@qJgUYV30;gvTp@Pt%A_xpW-7a)Yb`(=Gz zT10(2wy`itWv)y=%XpZhN!;ZhK%8_pNGjBzTDJYv&^r+5#uD z>HJ^RP}kaM#$gZ#_C83D&lv+%@fkqOl*838oC~30D)^u!YJNOh)01eFz;EvFBB;vi z(l8RR2>f3j$4a~&nx;~yp{Nt>QDGRu)Y|akT;%}TYa`FdnGww}!Lzu=YbzRW>`eGQ z|LuWfMvqvzFu+{^kFFnAbKPy89GoPYFIXT3W|U4h*u@{;3klKg`fn2qviDReaRlYB>$YK=S_}iA9Dm;*qV3{+lhUW_ zvC0E^y}+(>Uh#V{{C%X=rYPP&e%>$T(VFPr@wWXRCE&14=s_o3Jo;qZRoRf36=7+$g@K5F6Xzit^JEdYpU8oEsS%qt5veY)mZHKP_~)gv$Q% zPB{+1q(D*jFS#U&`Os*6E&h401k9D{UsRUO1K_8r2>r1dWv~3xV8&k6Y|KDA1`jNO zLIZ448!pQ3jQiec6S@%C)_;02vv`>?f5k5|ZD zNG_1syg9`J-g&Zje#>F0oE^@!7bJ|8b#}Q0`>A<|i;=jVB=fGE;;> z;42!T#~E_Obz;C5BhcHvuGzNP-zKz@J^TS_Pz*0%MiRnV%4;idv2iV9E7y+|7`YHOKfqb6hJi*b)$b4qfo+ z{$=`Sxgio+Q-broz*>rhgeFHxsgNQ&fHvIx!Glj@1rd*esiD)G!1Tf+lT0Dz7xPB! z9&gZ0Ee{`qFRKYt;F%+ElKZu{OTTJqY9A$0e__|H1?XrUC>7r$hnE0T(;_ffVWW#@ z#2~NH^5Uj>xI)cil-pHp1hX>|r`#4|<|O`y_i5tn`vfonA)#o?AKA!)hZ}%~0e-)y zZp{xwDh~oD^NJ`!<4ysDacw0$oB<&M)nkT%l$oa|S%?4xc=D}h@i1R{D|*^`mVMaB z*D0w6B82M<_1c{tE}KL;;_tYnS13F;oJDA)$c@%fc299hFX8#3N43C|5HZ7b+M*bz zMzrwmz~zUF`UdwmSKWwtLK{t(f%(%|^ps9)QqjFZW?X|L>VE%`&|h3p;37%KD-Bp0 zvyJi4UngAZV_qMZ8v2#|m>Fr;s@1*HBt2=~r<3(4J@Qe=$uhyp5`VXM~ zuTWR}4@?MW3|Kl2Z4e}pVFDNF{Px-|?;l!l!*OE`3$_Z77ehCb`;-58k&o=VnL7F4 z@Yykn@ki00*q6CkHbZaiW$Qt|w(9bi(AcGU5pslS4K`(4 zc8D1bJh-uzg}il{7pwoJH8a02$30}(jEkg;bN_c&o5)xG%Ah!(|<%J3_F<0Kw_tDZ2fz!vubaosw! zTQ6t1E9uST<)&Wjmu~f@1D6ox@K;JIMikX@%RdjJRg_CU;tWkj=*b{y!g`^E%OKmy zL;%p+XV^Go#m&Z%{7szF-;1k&2WmEzObA)53@0#QgoZx<%cn*tHM1KbZnMK;_OJU3EFNlZM-dthF00r)Re~C;f$} zZIb-cbiOBzrrx*@mwwu(PS)t#+X+OkgI#N8uD$Tmvla6RzX(*pV0GnxqWV>|Vev!h zOl&#cm*Vj2J05szA;?>1(y^uN-n=Tw(o`k%{&=$f>o-4aZqnKqDPZ4h=i5v_{2{)n zxkq;ndyQ;v-OEZ7!W0M$g>Q;wQ?rsu>g{&e{Qd#~$LMATi#rhkcYAe+uefLUTM-D= zn!JEl;nQB^UxHaVSZqcLl>iKL;x%iKA;@+zGB(bWdIfaiQ6}3IMu_Ypg86$6{2kRS zhGb$E;@5h9?&_pGq(bG%q$KmDeaj(I(M5;+lS~0y*{k$u)9Cqe;$xE;A zSa7522Wt8O)G|y-!j8R#gYx_Zi5^MQ*o!imy6q9}T#B$tyh^NVGToo5}cE7;%eB{O0#`~~vU>+=LJ zzn5!TEZE$jqK1f|sKsbww(3SizYlXFeDlVfwwSb4K^11lFbZ}cdVDG)5eU9k&%LT@ zYYVoiaWvGHI#^y%7Io5u{7N$N{uzd(z0tG)fj}7WzQDr}zpLCNH6ko?Olcp)(zF##S&t5ZbdAJ)q`4hlb%D|$>FzIL*%FqyxU12|pbTfY z5t<5Nx-B3R?hc+WxmRMTCs!Nesas3Ik^S_0hl-Tf2Gvo(!Z6;NO)^m91zbioG~b|o zjfN)UTkq03z`&gN<7l9HgNy`NL}B8*na`zF<>ubkb_a@VnMCr-lKP*p8X1@ z8|yQGY)95Fm~h9hGf_=AF+0mh)H}&kWGmHDPx>vi+amH(tD9lkjCD7!$D9F6smB!r zf3vO`Hn||DvKgr1DbZnXZb60n?tYqg`<0^`jKy{Ney*g3CBW9mMq(ns0s%a$r`Ni? zeWaNEtK@F^meArAhP})K$-_=V{rg!>&3Mgd?r}N(l;Qr5k>I>yG~wJd3FL5L385*D z>sUSv&vcq56(GPx9;KA|ls{>}-(FI_P`dEp%6f$oaNcwC^Wv&_1c`lIBUDk0t}4WX zcF~MA>1ZXk1Rn-aLpHneHpky&Z+D&umr3z!#HhKi9`>+(Pi|I;pe_#oWt43RM$l=o zn2Wg+Wq@R*7L`JHfmJa2kouE+`jD!$0E6OPCwvJn%Da}!=UQTFqO{tI4mEG)IzKqO zHljr*Mw2RhkbMbNp#h0P53WUzoL(T&3&(N)gImkxl6UEI zN*q-?!>(11D-B}AMNtrA4kF$%im-#=QmOp82JGtdzkdB%XgZ=-qle@xppjPrG zf9U~?Jy&a}zT2vq&$8D$iq)(n4I#DE6>sp~MGYPcznU-`%Y%(^B18Zc%l44YL<1`K zI#GcP5eTTAjNJkQY5b3alO3$;bV1puw2p=wrA)1W?eJciD~?6Fam6BMXYt;-|q(&6>5j$VItDts^@&>K%fU~2cA(8S|KjAR9wgppvtj+e%i zVwY}KWNg5;Cs^lSF^X3Fa1YNK3=X1nLj2k(v@-D*-|dDKj>3u#2K#nUd-I{%1xvDJ z!_{|EH77rcEh-SQ(v5;mz? z)x~)^+|4+mp<@82nW=*V*6Hb%o($`%Ho*r{MCOwqD$TQ+s~}l1XP5^4xSnKlj$a1+ zR~MH`Gz2IIU3=MRj)cFv+1v>U@}sRvq>qC&YPg20SNO~G#wypKxOqf65sY8Sm{^fC ze~U8Pij$;8pYzRrqM_G#4fftz3O02)sqRbWOzD_%LYgHK`Q`Px2DIlHFN;3EHcyZ* z_#5>L#0s98Zh8ohlQ7)nYk`>Zi6y#Jy6nVvSp8`eZj{HWL^>L(5X6oq!|ByuAp{NAK_p6AurFUtAEq zrq{~DGvfOFkv%ryhrQ#E?Xin?h}|4Y{=XD4M3bKNp5{{Rv%#O3ojMoekPG)mW+s#9$jPga&Cd zj08rGNON3uQEJD16Z}yL5ij{GG#fstFYjjgO{)|b&gWIXHJFE}Jm2^c5hW6?<&2>R zELsH91*5Aa05i;BE@Ejwt$F{!M257V3J(Rl-Z+ViFy3fpRi?w>=H^_;;Hr0Mo6Z@l za4u~V3px^nTQ$275#H_yX@5BMk3CX^h~SFsr03f}#!h<9s#H2yXhq9KImQ%h&m(g|{(?n*67RK{7%#q}%y>y$( z5}is7o~|`T_e(M~FXZs^3s1}WFFuc29LJ2pDL{FYG(OmdlJf*NtDvP0Pl5Oj-cL*o zXkR14I%vidw#CycJ)09XqN(Bjx0)$ z-;WT4H-YkX1@u$U%TuLmnB1eZr3k|PaktpimSmgh3S(CTpRKixE83vI+|p%6&`1S< z#>SP^^rcA^#0@G09Y(P_&EU2c8T0otoZe2j$+Ui5x8F*y{dgLGxQJMs?|6t#$Ki-z zn=<7P834o&DhwgOaR2_M0p9d_mHVA!&ak@E;>cg>2kQ$y=w(iJHbO#E;WbCNTy7s|Cnuv_D(>6Ev|8m_Ug|G|=0? z(0HFBR-f-Zro{Ic3lgbh;T_zq#jPDa)pmi!aMicH7RKP4B(~C2&ntdiC-}1Mwa6J^ z`vNuY2gQKcD}qPN7?IBW&8qYihDA#QU0trJ%k-2=G`I|NR62%UN3%du6{H$Vm`WI{ ztoY!}(2*WS;WRH~?26j=YkGsv_Y?-&9|(QI9m*BFD9S(|v^2kMtk;((`080L|3_LAUk91V|W8&IRwP`_%~6^#<6q}c57}E$ZSz-KiZNd z2M1XW1XsQ7H#(hrCBVRcuMB=-vdN`EkySMX0fczZjpgou=m_s5(Qg(`^XA1kE0(C< zLh14SLTT|R)!n@M`O5L~*O}dk6u)Bb94tFo%Tm7WBO!Qs?dpzMPyUS=E8vpr``A=_ zlNjM-qe8BZ5D?Ieiq>t!W+*TQrsUC(Vt|whpy8s-94(FFBs7)bGpWN#^59>NAk9Yp z$|TDvG^ z03>vM8OxlP2(seM6JHl5$kRUk#KsrmGWps zB%R_z4(bT6QZTMzW@(8amUEhk8unKWHi-Pd^k3&-yTAH)@WWKbBaWWaJcz-13#(K* zf(Z3n-*Ae#_67EPAiftj)tyz0>nJf4SOn z&hE-yLx7~Z0qXfZBn1mX9GCu+If|B)38APjb@)pbHB?EAb&Gy~Fxx`1X+!{Yk=y*f z67$sZ*!n#+0T{mg%9`!@fuCV+8DCckJk8qgZ#e1%YpqU+VP1ybfKni3U0(k#yD9q} zibFeR(LEXHxM(_b=yzl{b!(gqo{adTX$3nB^``w)& z%ny}nTD7xt3G#(UxVF|OcWON*oGdJCJAQjm0y@=W>ssIu9yT+2U5skZu(?bid}3lu z5YTHEUKrQ7I;wp3wZhc=jB#-O-N=CvlR$WR%vo9zSusU@%dJEIYGTWqqb?nFFaa{a zGh5t;dVGb>+9?X(D~ML>P5pMP1+yQPewakGqiinRMK0NQO_FN&ngKTR&JPZt9OUmK z&0WCTF>EsHsKL8%L$A!Za+ z^;$Y`7w2%-Of7_NJ}qsv?z8CUcll{tlm}cJ?}@d-8<@+d1{FVdWpOV{PV!NDQqUcA zp$2X{ED2HnVcTo;#`isZ9MDiT%i96Nw{`=h5^TDNNm1Iyt@7kq0Wx%xb0GU8kUWGv ztmWn@0otuybDRPq<`fE1Acfxl^WG4EnShMcLX+4hck8YDH zEKrr?Ye6Q1OafIP<4){8m;ePS4WXi2Gi2p7=Z*-Qf@fq6fwRosoT!9;IEqh~Y(u5+;G?>AI&gc-xY;*jZ1} z7JpE7#n`ALqa$3R=z(vlub2RpjnJ~=%^+LHai z7)8L-6}xlpr4Z5sx`D2f5hn%w%t^R@r`&lf6%9}J7oCa_Mzr#fxAGSTL)%y>s3GTj z!A$s~@O^j}#>;+wdJoeZ7v+&HvO~ zN!q-K0R~<=@R$8r&v-Uu9Xe%)_-0~-5v6iI@H?+IS)74Dx61qR!Ok8fa8yJok9o_| z9-8(&anzF_q@;|*#)07q;ioWmA1Iapoml2aE1Hv^kstNu)PdB2vN@U6k+5$$emE+$ z7qW`RE#Z)aJ6;f?P{(PWA6okKUVfm*D=5ML9-|$v1^gO@n5_m$A6!Vv2vETwmBg4n zk~KD#FsWp{a4#UVlCtN6Qqn3bDjJ=Mkv-2UG{&4q9qVyYb>su4msnY>=do^R1T+!B ze_Wcn#I;#1^qGSi_yj~Fmqc1W-b#)LPT)a}U-su{9Y}OC7Ec;zk1&_q>HCV2i2M7C zfobM{b=fE%1#gb>F_q{E{;smI6lk;fW(4P!*#6daC80gJ`X$Qfkn?}m0p*HnpKiobYW+VL)FI@}tHZFL^>+|DT%Z9Q7Na84- z$k$%r`rFDWAo}Gig!PZ9)Rx^;qg{Iom|aqq&yXU6BzpFZIWANK%82`xybrQQY6 zpNG@HY4NPX@N=B)U1z_LGp4_o=@T5tXwt zSLGZnFfRON)|Mv^PlYuQ9S9>2FW#Z8s`3g8ag-8G9(;nxT(O9dTgUmW$<;5V!(TM` zd0^>An{~5hrlFf}}ec#`k4z4Ddz1zPt)L#2Rx&S6EuAYDIqZ7Ax}< zI0xV)^6ybt7&owSi|8l7WozPOE{0tC=ehwg>rugvB8#nEH9q**DS0n9*?Hv?+|_9N z+k-9!!i6$lEq;s**1^bVWQR)um(M#e^KY9S80Z_`2NH!afirHjiR3urBTi|^InI0- zh{~yGIg47$QlR;rui3MsyR>dS?j(|ulA_pNLloT$5}>N8p$6{}@;F;+c;i#UF|``d zL9T=q%D7656IE3P$++lyS+BeY9fNOdOcrWHwas&Y=t3{lhKKJ7?a*y^H?2x5TAl?9 z8l|c<@Wf*kz?`ql!GStZk&2i%y16pVDU}MwC#J=!xuz!g;lU4#mFVrtOW7@XDbs{H zOhis@*Yx92cf}JFg$Q`P&~L2l5YaaDm1`akawTR`;#Ic2nWd1+3(uJp_UYCZ-Og(P z+TxQOAllGI1cr3vpyrh5n+|Rw9cy$Nq#4Sk_7uQVaXPY5oid#4 zg@M#v<$w&i5bO#@7>~>Q_PuGu;k&ykhG{T6ouYPn)P#$NSHMxU9UJ%V_Z~>)ws}U%V>>gYsPF0HF|d;{5s*hS5>nY< zQ;y=Ov$@~Brius%;I(@tlITSIJ%fWGEIFZD-~5DrpOZqY_cMhWYBbQb8ae(oedz>@h) zDf2cY`6I(g^eoxunG`YOw)L}h+eg*G`OzJ=ktgnRD>EVTAM#Mi)&ss$gdqC!Gqy^V zza=PH7{->KvYI^9E`sonRAS_QCs;HXf2_~raLHT+&;u7&(URt_HJT4%-IQSG8ZctD zF&U=|v}&Vls(+t1xcpJ;CX=xia9o2wSZY-O1!{;k6@jOxcS&nsHz4o6=PITXf+-@ORmP}BYgBqRmR9j8&LReiAcm;C5tFD0F*ny0_462Fy+fGe=u;?hAHk-?@C`&!7eDoMa*>scD#riH}2bH-=SW zt#&d`0KNhPgHp)oB=klXWX*H#o5vC?WPtcNsglyS{5->6lM4C0R^LiCTgPKK2|$l1 zqI`My)qw6S;J8JMQ>7gI&9(SAftH-N;lv9h8`OH`uO)kB@wU z$A<;y$%*wUa-fN%r^CABS~(R5W3#QsS6$R2O!#@A3VUbeoO@Hst*qBRB4gwWLiMEr zTP=5EnkeODYTFv`Rd3Mc#~P9<4K^c8RO+58OGMK>)|~jo`)`3sEe18!iPH37w{ZR7 zj(9U!A--n~Ab2*wl0;+2(xXCvc!{fv|GeK5o8E_0pPGYLaOo?4tRdzXxvv?ndop@lAZJ)Mo5_UuK77b*H;B9(;x&v+F1 zSqM;4EmJs8rwb30s<=%dLfl$dSkKR}&;t9b-Z5UvHI{&a@fnX>Hnli0HLSG)tAz56 zjBYKK%7M`Bf3g4+PV+~q_R^1C)*3=oUkek8>aR9s^?F^^f~ZvH{`>yX%B89;qh+=D zE+pu@!vuEQ9f9kogv{p8odQO!4|eRBO_G~AJXXuT^hkgTFv2M@0V(WdJ~$j>$|kTl z!t+ZrCVuj5b_c%2F!FUXII%4T(^R#TB|BQ;nCd2R)V2O?ZvyrB-JdMj4_+MI-ukEo z4{;KT=4NJ6E^f1W_N|4xPVdnp8R}p7JMPS)tYUGrL8P%zr=()~$6{7jz64*L(dYce zQ{aUa*MOH_jOs;_$bUrx-*3e;mn>0?gN;QgkxM>Fvmu8M%QVYQ__NF0%4{4txBaT{ zw>bj`4^PM&OVQpblDDpU-*v4J-1BBE6Pq

^S5_EIkw zi4FQdRI=Uph0s~Qjy|H4hpg%B=0iWULpm3W?_1!Xo&uYhEI4vCNG<&^3jrZD&0ce4 z=hJKB%KB#D%aXvlBZvN-kSW!BtKI(n1`D+!!#ThZgbf!tMDZc{T3&5{gDBiPTaEq~ zduMl+1rYZKY;F{}Jd*L*U;vsGbyi%TEXF!61L<}p1ItV^C@zVH`v?~7`=C>ykE9JF zWn)G%`1q|+x?Cbh@P(q?v8&fpxjcj_A|_E5Bb=yDd5YW$sro`^r-m~OC!uU;Z zp4291s?q5)yJMx=yqEXl=6ArJo**DUqaD7f_rCd28for2)X@OVhguCh2l3}ZJ!63> z+Ec;tL?@fosLz0u88*L#EG9=lbv9Pk47gp;}Xn9kR%ZdLN+e8xB>-qE3M&D z@2}%MY=EsoJd^f{C{&368sw2NW?$~IyE9J~g`)0txl<8vjhPt_b$0D>{lO9VdTc4c z5nRzIfIS0{fkp{C^`pmD2BfgctF|oC;B8)%nUB5GC2&*$67z1s?UyXw0N{2%;7Z^@ zmXNAfQTJ?r_qXQCsE&fNv*r&c>aM&utD(B8NmjUT;syp>jhnnupVI;MT>5@Bue%WZ zs`e5S#EOy<^;mrXulhBG_?5e?QJ&`N!)WB=m*mD0RsL1}x^zQ0&vu+(XG^r{qz633 zM9s}6iCNg0+udhWWpBM*+;R?2ge|0>Uvl+*9Aqh#a^oquNZ`dLH;6q+Z^+hgBACk( zFBPDrwir@f^5L<~)FRixS2nb{5AVr;d}MM$sExb2OpUFxV)L+`kZ{bpVVCU#J-rT~ zk<>IY$Y;Z2(@w^O;QpEx-Eo>jf(`~2E*$62iEe?tsm|9+27g8>^XSusz#KYZr;66r z>(aD?(VqYp`KwcE+z?cZ``p`jpFRng#nrD~2U9UfXe&ej(t^-)eJ)$x)!CHi^xcoB zGHBYwp)0iLMZ|rCAmd3A$XP&;^TVH9#aw*TZ?x!p^G%(X#IRn; zwo^g+N-tVpXzTK16}D21#H=;IG`_3EkVNAddeKX8{@F5px&IFp^qO4({crYBUwpH? zxbGWBXD(k%6&F)8F+n1oKj1QaM?dR+-7~h_|){vpZuMgZbQlvw);pSsw zbRQR@O8ZfxK1Wl3NKsu&UsWKxFA7hQypS3yLnC4F1D$F@pt0HiAd(Oyiw8%Ccm5g3 zU;CXcMF4?h%D@-}|IZj@{|v+3aH4< zzW(aK$fa+o=m>$%*jNG1ag)Q~TA(!rqG=SfEvm`GdJ(jc?;wCbi{&8glaLpG6lW+y zt2bz^XJjn>Rg>}K?ozXp`+DXs1X1+3r`anzFBgP<@B z-6;$`bjN$~Joj_|{>SltpHJ89z1LdjIzu=C(0KhLNAdyp{m(u0K#WkPgxs_KV{-zzwjT!}YLCgi|QM=Wd1Rx`IBS$wAWY810(M=gZe z|LrRN-FqDSWEbQj7b*GD<9-*d#@R9}m7-~VB03vFc%f}`Q3g>gMRa#vW3KZs>oMDF zlJb}XP`T>G40*)rW^>QA$)=6@_hBCZnD#f+w3ey%_lGHoND}P(D;H089#>`x6${!Y zYmw{yRiq62+g#4iBAEWsl&-8HiJ8xKIOmy~K#X|J6O~7k7ZcOGOfa`9aE!%I=`83t z>_hFbMItB6Fbrr&5ucS@6q*LZkeGGIzgdWX3BzpiQ6K?#380vL=QMU$^$wJ2>6bA| z?{(pX`0?-oSh>FzMw|UcEAl}+wNV^zgV^W($no`KR@Efqqae+4Z`ozs_7J9lSK0^S z@m92dI#DIa0O8s0{%&nkQzVyw=t8P57=u)}TFlkdPd!4rYd0z(WkWijiR6lDW|aK( z52dfLP>|`tI7sX5;RgzVHk8J9&$_k36hU0{JwLvpNEH2n&uSX>0Alg%n_uY*UV-^; z!*r|AOt+50ZL(OscY2>0jEEJ!jVGi3!o#XXMXfE2H#mFK8Q*@?eJ~jOlE3X}FgxPq zM{hri8BHrWupp{>!&T46yj<^P#=JLV@_(@x?4Hc#zCM}3I389Do!wnzI|HPzt;^07> zpm_Ypny5OIh>r5eKj$T`hElL+j$u8$(5%(_IZggw?+L5b_Hd(>!ykf@{c^{k%1##s4FUgJXAFw1zjoiKR;nU-7HdNg@5 zs!7q9B4Npz-^aAYxTGS1;Dk|(rDIeDEmF!77wN17J4bViY5H71ZA43Pl7HtVMT%WUCBS`uO;&nYu_jXbd4AJ?;^7n20GLNlSCXM^RXEm9Ij0+wq zmgYLuyGyf=3!(*$9;l}LQao2}^M4frHrn$(h&h2UeO6e_Py*fjJ0EotvWTd#Jxa@^ zld1y`{+RR2Tf267D@HB`S7fVTdu|dNn`FUHb#o13NUZ$ z?%0@yGe8ac^zBLIA0HyR-%lt)08Vi?zxbZpeV0U5HXgUfqTv7_)L0HsCmAt)7mX1OY3PQU zfxUyX;4;A};Db{`PHmbHt03yJ+I%FfP*T_@MbVP=6%w z7_UgN*Fu*t%YQpSq*bET>5E0Bjk#0^ibR)1^lz*|+V^FQqOZ<>IRZjbQL%wfdE^BX z$>N(nJHDH*?S$T>f}9+(b%g2nE~~1l>)dv5>iGq?J#swkO5iFf&#{|bP?y`Ta6!zQ zNy3$H^#PvL#|F0F$^1MOJ;oc9Qu0)ZyjVbI`32Z9Pt7MSUF6=!O(X{5=wu`Db8WQa zG=Zi)w!6;x|BeuYJddr>e|m+|f!f_KPvE?Fp~l=%ZLT>Ka2MDm0?<2+&Aucb&Yz+N zU|VyO`pMMBcRZ>WX*fIM#m@`h-QYiY^| z+P}QBzS;FaXWArQhJCTKliC5}B%wGd3%Ux*wI>Oq_*66dZ*SEfMcAGrs0OrDIDK{w z;9f>7X=Ztrfwz_imG6?ZxbSZcFjG#3fy8Tbz+}5S9A#!5`M{_&))p}#Yr1arx2lxe zY_gxwpkU1-t6!YN}?$1oHZA7o}TU+&kf~>80OWqO-3+4^IvMLE67gN|qs5aDx8Y z2c@|@3MopSkNOFxQTjmmXM?EOeIdmRDZ}YN;A{B&N4n>o%jf;~c~2>(skvF)z#<5F}-vU8wo~d%1+toEtJ0I^8(Fb+( zhlAB*d3q?313(ziP9#;`xIMTc$1a#3YzjO@7e%c{JA_Eoq?X|MaCvs~j#BHn-)Ort zlnKX@v5)oM2}5Lx;cpRl_@Tv*XTdKzzIBjhmTe-+ap^0d+Aw?&_?5j zG^)zO{rSeo{}Wg90r}040g5;NUHkhtDL941S+M^Y;64(EcqiC@jasQxAS3{Z6+M{6 zb-TLny7b2z;^E~&$vHmM#B3H2r!EK+Ghof3nac(x1-rSSjas4qbe$39rQY9tXXk`& zRX{%Z3nvtD=?G@`4GsBD{-d$+lS|K7wVe&(O)XNK;?yUg^o&MmI65!s{OM*voAbOS zE&TIo@b*%EPEr&V-<7gk0b+P14;Pg{&$P&7i?@7a*dvHb)FFSc&4=%xPq?)YJ(VBBN} zbqt@jdI@i5le|3fR%Hu^qtj$NeeWRFAGYX=#_{cDyKj|VWn|3(UvN0s(Bf(SgHm}m#e7rB@c7uCWc7;~EK0h?p{*#`p4LH(rq41s zoVe(&7vQUIWdGt}g{$-BQc4hM zPNZrYlQS!dfp!Vl21DSyP$MNq{%YU3ofBwJoe^w5AYG zx?%~^3D`#m2S0Jx0F0NekLgsX_WlO)%&GcO!oq^t_NizGy~PLRbnCRmTm+g-FzC#F z=_`I}Au zJkpcT{)$yT93QSCdSNusMIRNha1xi;eqp&A?l2!I zjbSgIEl>XR!385*uHN%V)K2zA2!q4~7h^dC?}kVv0vz-iCE%utJa$6hmQ07@k)v{i zQfpoJ3NN$BbjgIB0m63wZ|f{My0Aj+-3u?sY5u|TASNZOCym)C8I(UIM2#2GQ{i0L zK+aPIpKjGSzQfyf4(6lQbm#A1=;Rls)Wmu34v16xwF%8FI%57^*a$0zZ7LPB#tfns z3r)_32c)kn^=R+2K_EEgBRuDl2^meW*YqbkAAnJHAGFsP|N15~0zO2fhtvhRDGIrcj{w+1ELr~p2G}f}=pOy5=!Fl^NAbb4v;93-%*~Idf zS@RGt`i#CRcl9R}S9$&4rQY4=F0G!u?9d?BMSN6eD`G7Qat>}t7gVzo%+k~9E_zCR zI@9KnwsB|H<{KIaAueio0iXg~cr8w@`tLcI>}As-!W3obE8?%uK|qs~G_|p0KLJOr zJiLL>IIN@4nJ)hn34ojY^TYxD=oMUfER{8e_4nnlTyQNXc1YhBaCfDeQ92HfuDC`_ z5h33dGn7f9p8m6tKKU6{OK`03U3ikQ_5V*3;WBEh=HfK+OWTx;p?fTR~54C-kzP*}Jh;VWztbw}cBgGEqfL-q_^!eQc%&7HB;I(+?OKOBq0hvnEU{T??F^ilBh95;NM~9qMkDqF1nF&R$AtmdbC6=%p_ec6}si6e>X{3YKjKqCS_7aBAso6 zx1Q_mhHCqRFdRRA4B`K46rmL2ioPsmgxl|JU-ziq^`Y$AypHx_kcV}^syIZAL%Z5r zkbbmdd|ZmK>JN)ME!PvPFbR{3q?D)xPEer(*Nt&+R~J!nPk`~zi-q%`NU^0G58X<+ zbZgtNRdJYBUca*wK^bXR!S5-ld!_ASZhK>FBvgR%X=4nK-&sGY#~$TYpB&=wymT{7 z{#3O1UD(q$PVo;wNSqK5*bQv%55ky~T?a)35(6Rkar%r{1P?Cq*+a)-Pk01RTVpxK zdX9juou1a*Y_{Y46#3cg@{X}amCziWy5U8Thuzj*5VT=OOt{@O=ekOlS&@VEldXNV ze*kR{AKB1~X^9fO!SG|#)6sL zY_IDxDw_k${efQYSKTm@!sPYMbEGHb@ z0NP?^TVA}md0Bm9ENQwO^WaorZWTd|G{cOf@|Y{DI|Ri?RRljRJ1%O#mY$%*YZYMF z>Lm#{3-Q<#OP(KT9_fC;cw-#wXGK>++A*y86Jv1MM^C<=FL5aBXXA}DnRByu|I$8$=PrF&OKV@NZJ-oSyw+{K~RyJ39&6(LVgtcq_dG-B=L9dSf zcyLW!Hkln5aLq?yU19;@|Cn6O0Zh(l7UUK$o9?qZH+q#-(h+ta>|RtpSiRQ6y@w0M z^A~#LR+(hhMdsq8)OajLoN;mDT|h3>FsZzdgGWb#W^h+3Ksg8Wuq$kUu(bopO6b!N_3dXYQ?ZazXCBvG&^IcbJ<)*`0@IBr}ob zMQX>yQt%Yjm%b)`Z+zSkba8HaSt*6StS#~M0R#m&=+4rF5dbBKnuXL_W>aObwqVPZ zyMbohp8!Fd;Y$^efED-hp5fEewoY*_gZh7B;Dr@w;TnnnCR*3YCkPc`Q6Ha5LgbQg zac>&X>-=SM$e?J<$P5R<+7{KX{U?7me{VmBURMPkA@l6wLk_h0$I&SKS3@P|ED6?~ z>NA>~S0EhGE@!&KNmOuKp70I7 zEsc@p_Iz1MW$A0PcuYHr|MBjM{%9FY@Tx~t-$8uImbCvwk@4pOcgBmCi9Ec(w0ND7 ze^B}6j%3>cvxIaqom8RgOeMCRsh=F(=Q9wD17!E5Dtz+5U!r_L?GbS+38jpK|5f;u zk#^#cun_pi*CDs?odOOIk;ZQ_u76Z?2}WjS>ko36#oylFfGA3Nt@`g0Ft_A)KPZ{n zvcxqoT`MO59-BjOkhkAAj;n{siF+6g8RzNEV!@$hv5^2Q}M$qZff@(tUWra{MV9HKQsb|-$B`|aVtB%!BZD`{=p zs}D+9_uz&ck`L-9=&zHi=(!N)Va|G!8mVMi3%sq66)CTv2EZ_v1fYz2=?{!$`s&v7 zj=RY8Y9+5ms%b`u|K=mru|jZq8nf!(xniC;-p|~w1&BOjwsE;lI~i7lEe7PJQR}?Nx73JEa0c`r4gtxg$-S@_goG*+!Y3oru40pbqT{?&*;W zw08g12f4pLz%&zwIeU*QTuO4sYgyvSd3-J)QrLx384(Lm<4#YTvi#n?j zUEpT@KKT~h_nRw}aNjG^biTQ>3;xMp1BVAsqv!tx!*1PywI^##IyvB>n=qAVO9qha zS2E`px!TOp4wrv0ioU;0O2BW{%6@Y}_y8qR3yk9~O_);RjttQzFH?R?*Ik|52K!=Ty z*dLKu2yDG3;FaC#nkQIj*jRc+(@=cWTT{XHwKZL3bb+YlZcIW-n6VX}wZJ17{Zy`I z8YS2*wfYl3B_x79qO4y-3N{z`8r7HI^P~DnTgMg_wL{wcKCQaXbaSLaF^ka%&Z5+q z46|Z}fV!*LSPr0?XhCp<{%sq$k z4KFDC^H;K9@iG~z92ql6zzDuN^l!dv73E(e90Q%ZM4^Kl=Zaj zq#OcXGyA4yTiy?4 zUj(uiR#hUoKIn~)a71A$O?cO!|71TZi@Dgs8TlRaD39^^Si2Wzff$0d2Y)!0l~ZSA2-c5m!H<(Wx)P)^iDG3kT!7^Lk?LYH{ zbDX@JzYwrSdIne`)92X$L^>SfT4=b>#lkhPR^t38_$-qrbp>+sbYtTK<%yr;n>&oc z47%2$2JPk_r#_j&`o=^HA8SU{${0j#&}Wnf-Lsz8&sP4mmo3(^P38bMbQ_3dQsY0K zRqFQ>u7TFCU6KASdbx3$J7wGUA%|Jt&9%rD!KR&a#MYh!s0(g_tG-WbQS4!|+G?>( z9<;dSMsH|W(T zOH<8KzDd!+A`6Ldnx$O}?R@^GzY3CGfLj*BQM1v%IcRZMaE<&TR;&;du!o1k9&Ifr zW6a;iKU1jSQyrHsRdOI9ER*4laq~eI_^^YD+tDeFD!+l7+mRk@UI0g0{yfjK%MCdg z{b6fo8nVf{JsBNIu{C0`==-hi=?+xqVLUv06~5bmw81eo|Qe3d7y&A%F+w%Lh))UVHJdGeq4 z(7#XoHQ@Kj>#bNxl=o62nS{$|q`UY4h`5wu)2C>B@Vw{TfJuHFS>$bNNq0lULYB|k z7k@BPV*>LIA0@b}Yw~PeTT@zKRh+3P|*O zn*~4yWSS-S%Mz@Fs{=0lY!`o0N{J)LZGiAVlQ|RClIA!15swfRnM5B{`5{m|nq}w@ z#&>L`zcdxPCZW&gPLodkd&5ulfarz@#)!~oDxcI9s{)S2ZU(QB@JV2RYxDY$j|5|6 zPN;mR2+N4>ANU{L2W^EaiD^I^l^^EDW_poz(9BT#P6j7Y&V8*6t+;O=l0ErwzV>c4 ze1Hx)u(?(lIdy*#{h*p=7K@+{Y=nB%q_UFc-|Vu`;#U-f`*KRs2tJADi|7>QHoFt` zb^Pox2HjlSwdxej@j#nBw6J~H;C+M)nsRe_a(G-60pEx|JL!nG6T*#CQzDem6U@hx zlT)uo!vY~1gkf#hXD0p!U?)Cmd}aNn1Z3*<{%vNwQ*~0A2Fp)X!aTCXl>e&%0)VRe z2g!RMdYMcGV1b^Z4Y`gj*#p=VkNlmzJ?yU+ry%FQ9EigVP(8T*y3ricAW4~SO>TDA z-e?=@G{jr+i^JqZ0FO}5)}b_28o;P0J?x6XqiUN z#KgCUsJcBNROKt^4A|4;Ayd|=07+!OT__UM(b3WMuv>xqqZ1tB7HW6=h`owWaN^u| zZNp=+0i&AKRx;40l`?f*Mj3R`rUl zsnA(6WAKaSZ~mLn**S7d(w z;{u#>xRbblP$BgcAQ+ArJ~kajG#5S29uPb0BA7B&IV5gw#Id@Sy$-9d+M0=`19-wp}=jM!gv~*sAwZNgC zcHVN4sJ3*zU_f%ZyWwSIdAgsGeyc%4>_`3r4zdymmC+o>pg6xjy?ST2TJ>Hd_qDp2OXjv_4E_xFHWEBD-QXvQRKBG|yQa{gAO7@zhu8Nh+Q=Yax zxf#$9t#`;;@_AVT2}&{X+UKLySGY~Bkhj*zX6Knb#tIGI`;9DsM#Fh0-o@UPm87L2Z{#IC z=XkcpABqD51JbMVkDUn}mIIxF)&Y=e6=D19IL^1dE8EF*WfUsfvjRvX0j#7)R4LEa zJ1_D$fZ9iP!7k=EQXdY|%0<$%?)rv6KIUz@VRhGSXqm!S{~NQ38Vm+=H8wT%5#8bf z&UT)y?cargRZvN4FJD`?9T;ZnObAdQ^sJH>wGG^-sJ2-}eFM9yj3t@AIsHI#btJtl z^5|~OmrOf-(yiK~c??DGKW`*COMHUw%Qxs$J6d6R5?x-N+HDl;%A7}$RK{kXHB8}w znqx&tF+WR{RD#U`7F94GDW5u&pog7rjX%c6$N%A7KTGH8aKPF{&f+#ilF0IL&-(3A z$Su_PEy)n_Wvf$21FMO)3FMVgdRRjebQYtR@mEE2qBZv>@bKGk2`x!QH)%g{8d<*u zbZ-6(6enRCis<(GErojIR!6vNdQuQ^7+W3gl0d3Yf?IkKXXUOPrc2Jz-g(Es_MnP~ zZ8oAXCZ~$k$i$3Uoj8U;iA|wWOX>9IUm58liP~EUKoT{*ux?iZ4g9_0(Np53jtykY z^!zMZ=QQ~5u@m8?j!)k}>vw6>EGIX|doFda{NT=y0}B~u3F`Rof*Oy!QR?+d_wL|1 zy~Br)1O8){`yY?-CH*;yy_#Wn`vLosLs8A4xOIp$Jc zBih>;KL%V7*Kz{c=lY0^%JEohNJI_6N&XWlW)xGK9RGZFOHp#y;8z?|jT7 zRWnVU5^o4#XQ3v?nI8LqZ|X$f8kA^LsZ1DmpX+mMhH|xZXIF@G^?j*q<~=;FXf41T zqO>!XKYBHjNF@&zumYv!p9}c9#CVVo(&j>&4diJgR6wGQXT?82&G_lKa(SnpCO0b3inY3}i zd!4mliC7iua-yQkiXW^GFE&JnDy0HfJ%A(Gr+F;qWaHTQ#Q4)1g_m~RQPehGk+Eh= zA)Q@Gg}-G1tICaWtR-?&zRH8JANzcNvCPk1nlS8Lg?gD*kGEu=Yg(}|?qPkGot$ng zFEwcQd}jV<6uo?^LbRt3GYIC&NvlEe+Fb|miRR(gh==LDiWX^bI=p_}4mvG>qe4U> z%I`g{oZ1udhRNL$fEcCxtJj5y&3!!T{Cg5nD%2#Oi9@`YOE0&a{=Lz)JKnxoVg&7C zfq{ZsTwQhmp^pzM|srQ;TY#MzDz~3toZU-P*^_r!gMO$E z@JVBe#ttO}lbZ8A#g%jaqWkDusEkvTt$5sv>7s%KM@uEl-KBQ)1a=N%n1BBt(P9>S z$DIuvSRMEFz=gFD+-)gxYJ*v3aB0Xd zs49U|-qU2^ZrSSXp8&bJlX@+HjyTplc@%Du+S5d?|59@xc*&W=n=2ghEIIeU_2E0Z z$m2YWAt+IdS3a7g=m4Fi!94S^A*n)|5Nm>w3}GHa>935RMM#l+RdyELW8|#ee@8i5 zDdTqO;-wyUq{JcMWNBSA<#gcSbmHwm_i>-Ce(5QPgJace?tNWugLtS>B($h43iEvb zXvS8mjPuDOsa|gku;3?pi#9?sPb?4Y;T69LpHJFZyjTgb43ilaS)k4pcGS|#FaCeX%WPWzGlA<&pUSOaeVV`f4V9n z0$-)}xy_aRFz@8S6!F_?2C6}3Gl7CR*QH??sNeqN9G<5k#W6EKYvWfEkMB^Ru2gBb zER*B%1GJo4#HqUdqO5Ade)9cSdt)-LlK@?#@8m+8WcYL2on4RT%Qc1^T)UvA_cqd= zw}2rL77r<+rD&ap`aiU&FvKeWi7|LbZczUeOM?a=Lk(e0Wt?4hzaVe?|6?%YH#70U zt&w=&4_3mTwadJ|-wdW{qDM)?1=F&E`Ji$fJ-2@6TYc%g}wjPZF+md>zsh&EAoxPdBph5tgYP&qBvxMsmCa? zfm}kAOI8Df(p7*n{6jnOVtLSd(ge@_v!$cYkrtgHLbEyxIc%B8^@aoum5=%-CQ6li z1*eNGm&~}deg99mU?aD{k%J&Lm-~4zfv4clk%O+azIZIaTmhhx{j*d;=_R^t`v+Zh z0HTetx^?=Ii)DuG@>{UPs4daDak6%5Wb$~^^!Y|2%mMFpy}I}LSXrYDaD|eXIt# z8DgP34I{&>c#KcoO_0HMN&m4>B{2A8bd*?u$dWR7 z<5HM|`YIIF1EzUFG;qgle~(3Wu9fT2s5=Z>Vs&A}lM}%tH3y{wr|zZEKjk`wX<)P{ z90drbpaLrrhD}9ZExh6UaDV*PMN2lA0KbO&!~a-hpQo6ycm#qxIhK|DIF^^2ATL(O zcFbZH5?g$4xkK-gR(Llyz$T{GN2);G0x5)HEdKP5W{o+3Qsf_Nue=T|Z|_?_eGaXm zi)|YQOw*=a8V}{A>>* z2=e`x9rQ84{b{%l+_<=eN7b@^x5oBKpdct2Y}{^XWW{E;HHXzb%!j)H^23atYeqi>(?Ju-k`&b%`0!26dM z(#C(Bz}YGPjuvoHs{8ZrE)K;-Udm|{AVWHGlYLFo_Fk-d^9tAnAMz;^>?ysA?+ZEp zg>E{2%oy^|9>hev!?Aj-?P`t1yz*(=>zha#BFJt0vkxjSLWrcK3`^EZ=6|~7bE@_m zjdZzm$t;~~%@Q_D3QtQhU@>r;PAh&17V~3#VvDsyhtkH-B>)PXmKRf{?FT}51gU8S zsqtb2Ed^<7Yki2M%C*wTB{*mW>LfHW^Y(4at_{K|tazx!KEVciV58`GX(;XdyQ8nK zY;#7ua$!U8Ui1%ztQD{A95h-ASQu(Sc$z(n(Q{M@W^f;K+NF}x+!9{zR7MNtQ z|7sIZfc-}i;XgjxUye8#L?1Ro#>Cz?vxC8>5gW7B8%mJf&jbY6JxL7{dg3sPR3$>) zAJo+0_{Q?5_@^Uli(OHn<}nB=zrpYDx}SIOWESU8bdd__3uBUSp^pnc z)zWRM93AzD=&I37{!kPn*5!E|+$+zLoZbJZe{ff^ zD!l9FA=R*JuK^5+qP^c$xFo(D>2n<99@p-uN;2M``4;@%WkBT2#mt;!?_!AlJ1nba zaQ|p(I&aH3G)`fP{*P06i}QcE=FWlg{dQQI%8W9@?lxxm>=R>q;NhoC{5jAfHF9&~nQv+Q)_vWTJ2v^YNAh`8=eQ=TyAOk8 znX+u&x?a!@kdR^8Qa^N;OB3h27KOi)?;)Y_gkqRnFf64xers>5W0FYSbaIXFFztL3 za$iY0boONph)d7@atmLesSiAB@{Wwf$>Cz)J3VGL;8L5 zR8QUEwSQNEP%hCi@chIdJx z{fF&{wt~L8xmkWy?27sy_sEA5@!$1E_}>2^HY@F4TTdiB1MedfTg7F(?JrjlG|L5M zI{x6am1`mKC$*OJ*4xup=uZ|p$3V;xkn78U+Ac}a@?tYRQcaF{q#s(v-{HVG+2V$8 zIn9%wz*n@p^tyahlPfU*=~!q|Os)EEmmVc5i-UCW;=UipH6LLktAR6;^AYD5m(o_| zesGm@Q;QZh6k>jxeQ&EweiCLBej^`jzJtsk2*GGp>a<2_wp*s8Ho{xZJqf7X$ke;7)I;i!nF2T#4Om$2cyqOrUZHQIuDr6*18rYwML}^ zmpTbpePs&Zi+#4C-tl@~+zxe#I1zJeUV0kbT3Z$;F1 zF8&(~e*YcYmLz*o#cBHBDi}Z-rX@DyHEq)sql(EYl%XDU>f#g8u>RUowzG1$H|KMV)^jA$1!~U` zAURSidO7T-1S0|~0Y2!zgD&3;#jgNFl#_k{^ds_J4Uv?JuzFGM>w}Bgsg9q|toKP; zj9a#RteF@vO&pmNoo@ykYoeG3Z|$!ny1injaL<4{M~za$&fy#G1;5@|$NT2Chdxf# zzOXml%W>5eAUoufz<-MSm=@nkkQ-K^k@H;eJyDM@pqaK`$Bx$d8rbft0Qvl&lhNke ziAjG8ga`o3G?W9tApqrIJ>!ieA`OdV`}9f{Q3t><6(;iNEBCg@;kTS>$m@=ve8j@i zIj2WOMdeT5-2E>rxC-&CI-r=M=dYtEvFv+35uxD|Q>sg&MO3>pt}9AgJVHggV0e+l zaovs0!1^*I^i{1IF@`+Xi>X3kQjzNucMYcrGgX6$nWa-7*TX!~1_L3HcJ+Iy-mMDJ z9TPo?9)bH~F$jc^ASUHZ-PDw_*lwps$H$US+{LAkWQd3pa@(0;6veWrITeeO{n+Lv zS!=^tEPrJfob9eeR!zUM_0vXf?ui$F)C=gU_UeV&`~cS2;iH%$24_0zz}yb5*xKrl zOkE${v}XwnOzDjB=?1{ep{trZg=B(oE$|ii}kFx_vncK`1m;SnzvUzt5jEynT$?0N~!vGvMI6s z<}1KfAg8E)b62J79%Vb+v^ZmAdLdiex3K|uzi1`23QuJE>VIQhz)-;yp6&B6HQig) z(*AaJ8C-*_*jnX?&lX>o;#j?Va_pWniX4>fetF2O68}$F>s&m(S}6^ zv~!@}P6nMy@!7%XE{l0geYo9Q+`lQgZZ za_q?>zad>l$J!)x8ZAu;B9V*1;<=tOPGtoFOG+GlT}1WWr>0rTp{!MJoE@0>O8Ie> z80X!^=|n>-=$(!l^kbM3cKimkIY;vBH7dn8mwhBBx``Det0v5JyfY*OOqUK*Kngd(rvs#o65lyUv?mQk%7F1u$ zBM-zK`N3QzvE$ZxgR~t2NIP?5eyG)+2sDVU_{o%jXtdH^7`9uRo-8LMxB z1IbSvA7w0Xdem(uXY2P1vBMMa$szyxsE}=Q&-Q7&vlE?0Zpa<#{sy}eL0*&8KAkk| z^kwGWlGqVq+RHz1erQu4LucZ#oylL}cD2`^k>8fTPwwy8C1l&_6i$8A!M%3;@PQu` z?`%pTbpSUmey(g&Qp$mOD4wA>`V=>0Kx-GIX+qn-GT(9x?7UV>i?@DMZ1I{DHx#Y- zO`9z_QHG7l*Lw;M!k2yjTyQIBE&sI=1(VZ=W-e|7-QA^sE$Y*;6(i#cwR`xaQ7qH9 zy6z{}k!9h)30)JmcPZ3$$2vT|hMwXZ+6hOzaj4=K^LtV$K6>{&^9fk6$7L7{j*FMU zAIHI_>n~(iJ!)Il)xLML<(fB~DXLe`eVg|+gN)jmY)066WJk{E{CNh{88Bc>iAiwq z$gj^2rkQM7FzDyYtI-+ZfVKNCU$e5XOwG2lZOUY9h&d4ko-7932m>*SCZjUZVAXhCGa$@fS;n|E=UX~XtV9Wr3fp7h{~)UVG5=dL}@ibqQW783a* z$Gp%aYMeZ!Km@tU)Z<;hc90Q7m1>VO{3h4LN?9ScOdYX+{PoXOR`!x2qYE{2LXyfx zVRp^6DOjBrTh%ZEFW`-ThX>5oN3$#`V;)bEjyQoo+lm=;Oke2Rl zq#Nm!k{r50x=~S(hM~K=bC4QJy1Tn1zaP)@yx+ObIsEN)Idjjx_g;Igb??plq=z^T z6paupm0&KVcqM5C>2R!d(}?m8keM_DRAgPWi?yERxVW!)z-lzs(8RT3qS~}*v;-c| zI2VGTntxA5AYr9=R~kM(U-YKo=J*@e{1psd-?WLMOkm2Cv!Y-o-Rm9yhVbJ3{kTEm zj25SF1KmqEE2eCOI9yir5AbL)J1ou{ygoaG3?5C1apf19rer4^01q6 zBKZS{?uK#~Jmt)UWJ@c#D@Rb9lABd9gxtW8A8fYu7uOWdWe0KY3KMwfq}jiEPgcI6 zXe*fioQjs4z?c1v>(rp3U7>E0y)EFj^*;CK`r+J#>&bFHy+W;fez5hyouJlY!e#v# z+_8nlWw3DkQ)A&_9NVt&)0KBX zHt6wKxb&KC2x%lEZpSr^WA`STL(@W9SIeON zL8y=3{OFDwMqbqNG0AvizT(lBVOK%)4wdDhAYf?th)Hw?YNCP;!Pa&jYALcPsnyH} zb0F&D?jHANuYj%H;>ZJ#LK13 z@8!$lwxK)sEzMaT1zC8h(vzUo^at+KiyF@!*kg4GU#~Qc6rYw8A)RV-ktTA5Qs4DdC z6V`hm$>M#22P;k$3anJ;OAhGz z{n9wBgo;D<@x#MO!1zaSSL0Zg*WQ^3c z@O~Ciyj9W|>nE(Q4!Wvcb$9H{;u4Jf1TzDvwPcvU4(4rF7+>iIkqSY96_k6kCiA~z z)ZxX&a>hGvmZ;;EirNZ}LR<}xs%`{elox?#scQJ|=K6`t@?5TNkT<==wUTWHylouF z8eF278j^@g-*bu@P|M-eYRrHNn-CW5e0M?i1z-yRwdwsY&og|_-;0b!efNSk2$hR> z`5Zu$X$Iq<1Jvi$9T8f}49k_qmV_vW6tap>C!7f(^tf8OU5zU9ZQ%!vyEVD?QfuYUUIkWLlt{)Qpm_uu7GBD%br9pn&j`(oSi2P(eAM)SwH{cj{Lv2q$Yod<}!VJ3!c9>Zz#cR8^fOt7{Brb2UZxKQZRSPC_ z=SrJ)yo`=Icxx!q+%mY|k59hXI-=*O%IbjjW{}O)b<6(lq(iqL3uq6<6Uc+-$;jbQ zWOP9Kwh^;WhZ`^Mc$aP-%d zohFu`afj?sU@0-vFSI{g)RO|j)SGZDzkRAlU9g91l5N_&+pk-`Ls`s-43}w%^KA>y zf3|a+IJg_~bq7J7Axa41ChX)pDAYqd7N<~JWJ~d*IDEXG?3bm@;Ofki!tvAj4nsE~ zFx~7tt;pv)S&kYQOH}pZs*W*)PvfTqutB&RRBy*5=?M z`r?v@7kMLs8G0s+nYYgvf3{7#A5a0<295MnCi6P7jn%V(!W_6ZGI zL2yanE3!*JRhF~DP1l zT>t4a#3OcczffXy+( z7=JOd)Uw%pApaU5oU zVuLJ@>!h`a7&S~U(6|q~JR|Dz$rM$Td3k+)32h83CN$0IqRi0k4V!Jy=5&2sZgI>y zAE!Y$vV*Q1U{}}a0E4Q(auG|JdRh;9dK~qa=LnyB3-;KCUcDNmPtMQtvuGN#akli2 zqmP=MU(BVCviW{@JcyFdKjcxdn42dLC_x0nfWhR{fB-Q2U1W9}w|T8YA4+CqzDMD! zAjtjGZ~uhdQsgfn8AYP5#QGHz7V7gGXHb(5g&EkpbP5c@2UW&J z^WY5yG+Dt=5jgrS3aV6chHl++1fDI81rx$Y6(tLvtX+iQQIs$!}=LprPX)6-gRUV zBF_+J1E}ti;D|-kDsiclt<8oCQ$#~w2&JmxWdA+VfH>CIUb!Va;X039--(Rw^r1hO zIVm*Y=xZT)8v{t6n;{G9`|7Durs#D(@XQhD;QD={GHa0fBH8ArakQVmbs~hp#U|`a z@Oe(P`Jygio|gEJHRR)jj$}RtWu{sMU{=k-lCHBAAn?ASfkS~R#C|o%R8d)7O%=Rb z5CQZYlw{m=M{4e)s$StA?R*!b;;0mz!2Cg54dk=zsAn|y%k-<{^}Gds<8tkhGa^G# zpT80y3{D6CUNZ^Yxo?a^mEX`r(6Z^A7qBUL**MwLg&J{R^+q-4bR;MEiAP3X}GvFWsIUGb3qEe~&Pn z^{ikB;+US=54@bh*KtGEE^mBx1O^EWX8LLnp~r6n^_>ip_@d%{K~I&qm&;#j1)Tm~ zgBbEu_0;OORUL!_-G!5yn!HB2%r7r}#ys00J}2!E#RAESl^tRw2TYmPF^tzkX-#Va z->T^;GKG8g|Ef%SKg%*3J*VE^{q;ZA9wZkg&v}J#FzUA?6CtZq%>PotDKpdoTodAH zFz@JhKRcuXR3;nH+T9jZ9=OH%z72w+q*5AP>w^n4rV;83!Vnbb4N<%XP>B$+LteKV z-=GW1Paa&WY6GK$`nwkjjMwL_0^Yd4Cs`yr*0a^sH>SJxE3G3mzXdMhj{jv+qv!)C zU_~XLz2PZjcHF^mbd1}L>nAj4``NY4uj~jnf!+U04gs|)g-eBlpj8J?C4#t{-`j!s=K|HZY%=QM~>;g78O@XI590U)6+vh9`r&;4c+v^KC=P9 z<-KR$S9e_}Zh>IN3xT(rqh-&dg zS+>wlGeEdX6jpfaZZ-Uq^cTR%?`u!A_179Au2R0h44J%SKa>~uSw7}}C_f3fXZLs% zIvyG|lV}ZewuC*JPM?|wAxFm$u!_olI)~$3*msv(55c3OjTYqF`qktt#<92=!;+tT z;IM;6z2$s&MDA4Y;VgRTFd2oRYe1i&`foqc`vVP}X+)>x3K;69&n@{VdxI}POacNM z+yD?XOL7@pYZWZ+V8e>%LAD%qp0Qsw+qVeSOUNVYCw#>UbF}({KcC|hCu(WhJ#HH( z6kC?EXB^p0RJb>4?ZsPyxwHgDSTW5;jjK5R;QxJ;T0WrYI zNox)=Z@J(jE!gymyN1)8qIjOFa6Z{G&a;M&om{ETXV2N0RW9o5iYsN%>DX3@X=$ZB zuVr5BHMI9kPvh$*nkpH_o-Kx=!d%|B-Iwp~65#PFgrC^uwl=YwxUltV;{9ZwrIL;J z-c=*l-<%|lJKFdX42;qLY|<0ryg_#3f0;Sp&>FwN*XSS|5?7p7Ip}mW8hr}1S|7f9 zzuqWsS@^qneCMfy4q5v{BG^!jG(_t#Eolwu8Yc!ivnt=aZhoqrO4E8OS(iG&eDb<8 za7bQnALqM^<7@7Hqg|gQe*{ODpK}Z3Bu~NZm{uR1{dcAbeHiXTPb4G4rT+yMzx4F< zz;kxaSNne;e)Q`*KP-TktsApnY5@XILdaTqUeX8K%UQ8649N4K6>sV8oz~@ARsk-A zXp8=z+g`58D(7`CxwJrX{S zo{tl-vqk~6;mz2B8wrn%DOe^wBm*s5*w*v!gD#l*8gAQ~CoMw1Cx*k$xoE9wSI^Qg zHWLF>N(p50`9q>tWoI2XN_uY_Fgj}PUH#j#0!Fvw*Ay7_gw+1+#UhG!G6TrO5XV*6 zS8fiTZv~}v6aPuN zb6CqTOlVlm{nG7pA>1w%L{65^3&m2s ztIBVFMFV~HZnp8ux#VS`iq}1LeR)8{dvybk??D;YW`~bnO>qi9D+an&{(_0|^G{V0 zdE?XdX>xk;*J9ytbg;1GE+gq#cc@E(KwK~i*U6-~7`;uH+9D6!XL!0myJ6 zo_uN5eD0t%?la4mOn2XT=oWrWYZ^U9?6t%Mj-;qlo^Qi=YP|Vl?VvTOxg)S zZrl85VH}@1g#5mh&H-GecQ7mn_sazRk%?kxA23Z)jbwvf+Vy}qwjtodLgFq}ML4hm zW1V)(I`; zNH%}eDy&l;KCrN3Z|qpmqRZeOw%Fp(+EOxq2b<3hmk~dWVl{y(Jo6dkV44xv;eniS zPnk^cJqeEqo=|jkX-jLHv~MU9ydhY4jQH6FAux6l%300kb0GX3Gazgb(lKkC=BL+F ztSrq-sv}BO{=S!*_Fqm|@i)cY9xrjMb)6o-uK$R_0Lp|rz;{v~ys&mRYf)}|;XPi0 zDcY`ucD?FfPp9XS_A>Rru8Yk9b9#zerlpjZ!Z8z#J@8(gsZ+RAZZ`YhPa{cf60r_`M2`gF26unqGEYu=_sEWnYce?N*)!+wA>`;8r*r zCsf{nNPtqjX5^240}*kbBl8Fep#)s1@N>flhgMmD{lxS|M!#C`uDDis!6StKX^5J* z(gw}0k-RIu7a;PeTf&#;gJ5$40szJW^e|r$u?mio zmD4*e^$;ZEd%yO3kLR~{BlyRQBzso}vxd*)6?HO9(uo$H84BOyb@kf&Ckmr?ygqq_ zfsJ-~Nzgu&y^F$eP0q3J)8YSGpwl@7S?rp+iX0yic zuC4=8zH+(u;S)aJ#}teC6dRY23^B8X&H4W9RbqMVR?qq%`w#FXuceQ`8s$jiLVP_h z@R{BkJ{>n|R;mi$1(f`)LayJAhQ_5Vm`D0W7a4)&G(pDk>^73(FwI z-5X%++&@H~I)Ln4%OqpKWtb<`n9*xh(WtQJH5D(NJuPmf{KY+Jv)m-Vc&7_cIW~5IXO68&+2H`Zyr+xt{z-VP3VjlMymqU?&8@WGl=Z0|B zWq3ReYCOOWK{tZSPsr(*cdgEUsV=@mFOzp%OKP_vdT>Zi*?|L78yu>ZkIw$iMQ~Py z?>m@;372kUmwbQfc458=6M9~YC*Q{+rZpT#6(M*10bJVn^j2J|e=qHi{GxxF&gcY2 z0e^!&06O@tU3KHtmdQX?YL`Vkir&52u$5 z7e-xO`PltH%maAi(lVq9{Uw%kWh4zPU`wQok=grQs-D>O=D2QR;<-TJ8Hb}wLN0f3 z6+SrRQ@*5bVrh99`ylEpAcT>jQ9vV*3@_*Hr?ycTSGVW4Kd+rVN=fK9Y(^dfl zVMCch_hP;v3Sf@+;eOCE$b`baAV5*nVJ7&n0{P34jjQnSw0!o@e7g~~zF0XF?;WlM zyK^R1zo^~H*Lpc4#VeZ*rmxotXF!e4TPTlf5i6~g1JOswf0nZ7ovRx|6XN$qGpy<= z4cf1r62@BmuI7c_<4-4Gy}$b|%gN6$ zY=h|u(U3mrMoptY7v%U#ew%pSyUe%%`?o1hG57qJMZbvLUYXXBOkUs$#^>S6+uC8N z4yQ>p9cRGS+M@65?C{Oly!jObM{F-r4f|LLK#2U>#0LLsPJ@}Pj|75g4I6t{&F8Py z%kU2-K_>T2l@J8P;;`TOokX;COVsWwR zw3%V1D_1U8m^QANB6rc|2O_j^U`su&%;lZ1Ob&LLWkPLBWCB-#;dpl0K=3aPC(5;m?z zhyxjChbq+5O$y$0T&T7{7krv53a-sPxMk;3`ee{+=Tn2~bqAxNhM%Uju5KEjvnq|- z9+jq2o7PdxTO%IJ()v9W!?bCWeHoOlwO&cCXZ**sE@^Go_#^Sld`}(^Sc)xRID`Wv zjco}blyhT}e{{c0lN*ik@sk_!HSE`v8F)tx?S6+_zybPtU-XzecKH9T0m4fJo2C8Q zqW%18WoKe1;IX|tV0+a5X_WklN#wc0KZ$_nShWdunwa@YFr5u={-SB-pvKoRr@Wvu zXu>*AS6{z^;LV*#YB08kwl>2M4wN|NEuj1|qvBJM+m6&qdU?MZ6pvrtC!Jtk(LHZa zQTqW1?d-(B?kOaw8{Le?0{7TLz^XUPNG@RCm-U@Vd@RB8z|1Px`&`#hzcEJ1g>rzf zSre@T1s29ly9tNqa98b|?N_u)ME9(y)zAIf@Sg3u5T=^R<|RDc)^}ttVKPdO=0BPH zjU|wZksaN{>AC|2?N4j1V;Xlh-lk-F8R+L;^YpJl_nu7jJeB0ypP{&_X(j+XEs0!c5o4+ras#b+{Y33^6 zDtu*)x8rGL@^AbzCQN4Y-x=51K5L}IPnx!9G7N|tKN>1lKH0K~F-T+G650|Km}}2W zI|Y3Oy5*&};GVCbifDH(EnT%u1Q2^M!JX3GkCI|AJ&Iz9q!u3E2!@)clapPU1s}=y zk%Jmh@J^HUPUQ~eRUjXlS)|3OtZor!lGC6V??v`!$2U+-O+BYGuQ{0W0 zP{pBIIAmGRo2>obK1K8|=FOSDzi0dH=vM$r9OfNXk%fD@%W;RlkYf4M)6=&TN$tG{ z6`~orVV;e?D-c4LU5kGb7hx_~GNQ-O_h`s>>*i_iH#fqIN7V5Cl)N>Rsvi?`OJG$&^V*P9^w|W^U8ZDqw+Wih^X)@`<@-2(Y z$Myi@j)QP}y>WI|Q+nuqZ_c}a5&q%Xeo4g(awue0&@03D^1rP_0^CYi>uWDGBIyB0 z1`mG!v>}SOB+VmLwm|y-X`)25Dak@#V$N$Vx?<_(s^ak!>0ztm)~eNQL!jc@?FIb6F}l zeZSabwshNO$2@dZ4&H_L{|Fi3u~Ht%5hl;$Y91~KUUjH|cp6xJF@*MvdqYP%mlR$n zvZ5*0Td2Q3SST$ipbK9E=m+JmW!`FIw8 z{hYRu-}>5%Eso`MHP2mtyu9Yiv@UTt<6rjGse6yYILjixdO(je486K5YDqH~xoi zr>X7*IwZ7SzDQZfXE8eZ`Z;q#0$y6U2sSAq-PAY|La2ZfiA!5l;93BPwG0FT<9m+h zrH+S=C!EoAvcWP{3@PmwTMdu9mZ8Px#^? zZg7<-c1y31_%O?mI5$v-o^0RLqxx&A!ws=a?M@KnLac_)5*H55>#UJ zVfS8e2>GXsZTOsJLeeM;h|!f&^x-e`eMMjYFi!cwm>rF#Rv)m1K+@6gXCBRJUvHja z486Dhr+Lcb^6VPyw#g)-+8v$S64AbntC}|fGx76);Vny79_Z3HX|P{p<_KXL?8o2Q zT7LlO4(zvn0rX!knmtrXcllWG-UDQ&08+dpgmND0lY(w@43H|gAh86*KZ zza&kvSpUKuWD4_;}&wrEg(yak=)rySBnGXvqi;9t5Of_IDe6o1YrLms>9a+%cL#sriGQ~=GIFP$zU~%PyWvfkoi3C zcsBU)c^L|9VxjA}UqC_}Yti);kv-}B8#!|Jh*%Pf(O0Qrq^Y?_sPU6Nk8PTb@Det3 zIwkDHxgHybDSD&Xvt2fTFKgy#-BxzC=C7@CI zo9nEeFNUK2wJW_fc59RhRSeSuQhA)?mGJ}0D_su!|zZv|v0K5U& zTC0Oo{pi~I!#%#O4dC+W`ub+thd;JI-5cCJRIJ?Cw?BsmbT+g<`Oq1i=-)ECc&3k7 z&G?5I>gPFz& zjb>6uQ30gB)%@?=M~OelTXL~suNWaYXy!1$OR=^m7-qhC%1CoCAj<3c-3vUnUV!ea zg=f+-8eCH0lJ~p`kB~IWbQPz5HPpb&E+xmVdOAcb~yl> z7J#zxOVHGy_Uj($?7NvNN(t|Q!q0Na^kkJR!raN*M|?$ zF0wt?5X$z$mz*VzYgG~i$wv67;@$v{NJO8`;?GKgLI-v<(BowSf_?dNCsI6Z5w!4Q zMgzji3Bc{oJ8A7#ypZSh47SXcpXahr2$uc}whH+dTU9}rDq6b-2cyuyqHER62`|i+ zIY?bvHniuv$ekh4|DR`wo;?l{d7K!!aeF*o5`5TSSN(i_>6<+2i8RZmk^0!u~ zUW+)0MM$g8WpfF6d@vFCef!;n4fLoQ4wKeNkGtU3?2$`~!r^yVzz_z|aWwux#Yx zl~g4)*l)CFvUV=;BmRz`T@twwa%SCoPwp!Ql(?GMuS4jW(g_lYz&M+(!syg%hV9Xb zbW!N(ofgZ(X*{SOGJ`1md$fY!<>tiv7f#`TnnwChYBB)4L5=2ZK+C7BXFv}WH#ILH zDL#7BgtM@~H<}>US}C*t5|ykW1mng`q6NAN<&#`{KK)stP>s4M5O523)dFnzuX7^i zl#z;2=-#SjvE?gESHz&y+j6LDfLwR6Sb8nC99_#pj0saCmoUjqr{qKNnjfG+H zF`{&a1}=i9h)a?&6`9>ca;DYd5{(THd%vpIyEdbE;1Opg*KS1xPBX?F4W41FEE>8_ z%LUc7azRaZBbl-m&Yeh!tu64?uX*ea$v(`$*_U}Bj!&Wo-6M`^nIpd8RgH^w-@l8! z%jvPJ`JJaxlcpR*ZOa$t^}Be+q^9k|mTWCCyEq{SS-jUtPf2NMDcgpPQF^RyHG?Hr zN`6+Gomhq|VY=V9W$pOT%!fZ3`hB2Z7Y7KB2$`4y@_;ce`+qk==l>;hVG9(!_~rly z@Q9ob9Se(4IXH*YNU$E9gZw7VI?m+p5t93`MCXQz_=(k7yrQ%Zp+Jw)Zra)%JslU3 z+;^wn+)~nE$@(-*@{Fvx4NYB(c8}}IT3VZ4U5eD%+=41b+JH{Xj>ie={hXrGoZg@@ zF6cK3n1d)N7+nAhVB7&Pv1pTH_SiGSz(*jkJYn)a5$BGwey*!m>BoW61hmCFOaDDf zCjW>TbvI|YXguuf6zt75t2)hlFtECZ3b2s(l+4_o-nmVzeTCLaicDU9n1Izy0biVP zAs7y)TXS$IAoVEAmV^yTJV(HS2RD9%;^~4Ump8rxLyfEuS=Ma*0V2jRI69 zG3%HEPlUa+L5$N-jGb+?ki&Wt*%x&?_m*0HrBZfWV6|i-4M@TgFP|B>^D~$)utlM? zu0;lt0AEus%A27QW9sLZZdnrvm;)|dR}C;Tugc})Z0L}*rgA@zND$5dj3S7n;P{I> zSIr1*5|sH5AZ-cfhxM4YRf#q5hjZhV(RAJThV{TYK5Wv()co**uDPT~xJ=@@inHyn zSx7R9f_=6TrepIjj-Hc3f8LNiu%5miC)Q5G#9a|C06I${uK!&VHC)i%#JgqRi;)*8 z6nn5bW^PXR{NZ$ya%ztr`1XJv`s7LRVph1x1@fXG3tpSO+}q^~J@|Sm=6;yl`jAqJ zXq+_5=uS=7dp`kA`$}Lgzj&8oP2`m?;WZ(_I~UIP)8RHtz)%YBmJ~^*QiL*GZ9zV@ zUQgTL;^GhMo+^+1wQ=U>(ar_E20-`-;O8h^0Pa+~*oKXPq=*cOHpLnP<5_eXpe_s}8Xytk8=GSyY zH)j?gPhg6d7xXj@NzHSWHJ>lLyC;qBr!TX4#}3qa@@us?g(5Cp-7g4v+&)aav~{HO z?~oufYdQG4q8AM7MEGVn!l#K)A}o17E~GU*AvW_p0GJs(6J}vJP6>Fm zu>ND#eFiA*=Cl&ul>u%J&3`3qG`jaMLf9Ff&>oQ1kLmE1oI8oGoD_eXJW&mToX**s zJHEu~X|{(a)cykDyO6YCD2kIXy`NlRj+Al6%8P#4_ZkTJglWXy_QGCTPHj6lM{y{g z8Yof6ISI#a33@c19}DgZSuk8TEygtB+P02pRaeg^1dUojooeb5f*dYCk{z<{F^myw zzvxc?H#}`^ZGHC?jMuMbi~|gG|S*CPFG7)%nb zZX?jH;K4=__a=rtckdS)8i*t*YrN9~VBW%+^PGiLv+9DE$z+(u67H|TA!=%72AHBY zfg9jIpZ2o!F*6MzeKld%ha~AVX6&!|mmJpTP>P*zhu1z*pgO(;F4Hp*{{2d9sif z!n@*OS+wm0*7fF?^l8&0;JykY%cCVzldH4UT&JE4;IGf9OAkzQ;HMLbYPTbN$xF?u z=1eTigZbjBra6ETAA~$pHaUcv4N0Di?)^bO6MlxZ@drxH^;x|v+leHpxOm_qhyo2{ z*dXG?B9b^aibgxc*HJq#=N_C`AF{m6b(|qyOU@CeR~kZkya$6Mxq06U8gBEs@!U!G zAhcUFr@Ztm$9CpF`^5<$YX|18LIt*CiEjxRKFKZVoWE}T2m5B8->Y36Vq`VE6nEzT zvKB0B>*=d$J%B$WyUC7#Pz-SZ10RYp$gczcIfyub(JoK^nv}lwEeX(oZ~5vq#%^o{ zfx%u)E5LV;fwPq{5BIAalQ+}!N%XZ31>g)HK1|rDhP^uBG@nJNw z&`0D%{H0kReqfF)Nq+4oFDiw{U(Z}QpI405XWgmTqIBr<@O-qSZ)b4hM|XPCWV}5b z`|*tG_m5;9y%`?uDm(}_F5&F^(h&s$w)rFqu~6x3x(?UOhiY$*uSxI&3FPy*Y!4F@ z(L7?meI{@&A+&hJw0msKRNo|a6>zlp}bf@$J;_{={A zr6yW^xD{MkITgdV>hE{@Yz-r))vv<{D~Utg?}!YOwI2}!|9KiF@zrYtVRU*FSLq-J z!dZH|b)YpU#Gh`!$EK}?pj&5aiY;MMHez9%Ax<6wniSHFG(rZ?k5qr}Kti=@J}I0&EVGs6yD zfBrI#MKxwu+ov_J)BwP@ZO0O*l|LK8qM1NBdQ_K4g6YNBiSPN@;9F zbOgFLv@%@S&H9q6g;})nffSN8(O-p-%9EunR^jE{2qH0`V4>yb43RRl&MYiReyzNF zVzXZZNm9pa1JWXBsi?rD89vASo6h{oQa9`}u2^afhrD3(>IbZ6fzz_tij%$9%F=HF z+gPa&>lk+Fjw~4kV96t>en?#mSNbZD}bq6$m*J zu)xT5P6s~0&P_4&uO^CcVZ?5mBbkxAr;WjZ^ihHI5?Hri@eqRO!K(BWsUzzLsqJf` zPm~dXX{;uaV-$OcXgwi2J~{>ly*+)>e09Xt>LJfuzaD}SYmJvfmk|9OJmAQP2PsO zBj9n@Xhncq=TEm~8k)3_rRh4ET?q|t&+lkb*xj2jts~qK4(Q5NFk4exzG^UsjELNC z)Ck2d>@|asx152|i`{H!KbY{Wjh_Scuv*B>VHnwR>3kIsrz#R|ntYa6ZlY2mXB^J{C2QD$$-p}SacVCNka-m77!OyX&YA5`v;Pc#-X-s7`^Qs9# zil0`ykf7;9CXm&*U5*Id3yGcz#;Bcz6!^Z@t;f#KT~)vpS`HpZLNNm$s}Y8}bR$z7QKr@;Q61oVFPAS$rFg4t5+2AhE`+et~$Tu9h6@{nhWi82Z<)|Zp;ce znlR(PIV+R4O)7S<&=pNC*8GrRXjL*K23;t{I#nkm2xSOszw0n2s$%2%UORGDGNaac zlNQ5Bfzjw0sielLgFRP^PT}EFEKMc!&(SR^NFb0lLy2xa_cQ& zUqxjL!j!ivq|vamm>YhmOia`T|7o5haps(Umnf?;E;bLTv&eBHxnNZ6iUipoXg^Jb z62yO3u2OY7xg%#6gLPaec4^5RaMjSLN|XE|WDu)AO6nnlIC8|?d9oB=2Z*g!EwRB@bcoMPcNCP?HhiAq#=>z zR96bS4`RxI&D#~8JtY`83u5oRyd;wap7X!HFWJv@fd>&0akV)%RoIkJ0t+6fc50BK zIuvSwLi@)=gr&G88CRGD#*!8Q(R4gIO z6QlP^3)yxEi!rq@io;+eWbH?`HZL|Y1Fo#Hxr-By1Wotd0{e$up{xQ3*NIC~XA zTlz>i9c+ZsJY^FpJkwuq>4%}+2KxPr!%CVx$j(&3n?;ZfZA0`MP$Y%1&@gX%;dp83}1PkUglcQu?QgHQL}3R4dV z|31)8^#vUCE=abVUO*K*H~!+X5j!!axW{HFMC8WttHL1*4p)qPz9Tg8vGIsEBmy zJVm#4ygtI|Y>gv~rxwWH$8xp=pd)qIILXUtj?K;ze*aB#yt1-@gfFnHI2m$sj}9dq z7ned3cb3P(gL44O^&(OW+>P!y z&Mbcx41q(cShhL++aJ7eCB&fJJ z0*nZTZkrb->5_0jK7@qS5v}YDJk7Y3k@xXC|6nDZ5Talz}US* zZZ%wStv`~bQ4x1vHhlnt@o1>PsQej!dFjGm4iy7r<0LJP|*b>_%oR2Z8Jw$@OrG_^yli&?{_QL3MLmr%m7Ldtcx@xh<*#6jU`_`Zx=J@!i;2^ITdCe&dxfMP zh%v$uiQ$Hw_8_Z!k-k=gCtH;MVf@9wKz6=F46E;0S#&bPAfx7N`GO+^9pE5}-v3ko zvBxvmz`+sC79H56tgLed?N_-HN8@n0Tgy;9OAc9EAosNNSz`cE_L)8tx-pTb(CBqx z`I1NbUjRm;Ha6)9KEbO_&9+4@a1NJOA~vaT;1DuqzwFp)f%U^wr+=goDfnZ!_Hfst zPEb{Qgr)_$dKq$&b_fefSqCyHQI1i>jWPr9-`KBZV*L}%1Q3u3q0C{^j@PN*GZqsS z*uN5Q{EXt-mr}D5OQ&jQ0r)S0%I#ONrG{kC=#0nuybH0H1r0AX#@$r3{icuOdBme_ zF_eJ5ac|9{vsaOp)wps+J|2ZeUFErBmwK^z|`byo055bSml5&m8fM%S} zD7w%vEh^vrOa%$(N3oCeMKT?mepIR#k*IS^O{olTt?&wGqQ9wn={^-wFO*JL(;lBP z_Q7pyxR+~p=+#RsU*f(%G{&JHU#B)a{)$r%%|pL>YG?uHpP4Mu6U ztu%?qCe$fF0H**RjGo(D&xWBa>TVE;b;|TPF%?)@0qQ$;`JinA#_eZS68_jYbNK=Z zI)$&&h5yKufl!)T`0$j{*}g4&7L!fDU?cA6O}Tsf_T^&Z+Io2r0nNn{OK{v*=cYwx z5M}DPlq(iT4R2}&CphQE38k4AC

u&Rz$m@TSlmv_-UQ%uVpNtP}X&x%d3JU|?DKRV$ z@kamWlTB%6t9I5vMHY@Yc9H*YM~eBNIC%kFsA$&b-{rRZ9~U&nj^;Ch@{d2vopE@5&-xkC44zL-r6_gprLrj#=Ikg$s%i*fycAAJ`81!PAGTQ zKro2(ssg{axrqAtJe@s0dNV++&nyCpEx4#Z%#Z~a0S42 z3o-)fVF&%9|EH*H4`*@>;5v4Wdo_(UwZ({#jpWo>QpxCITZQIPVM%qQSSAm}O3^5n zsDm}sYI2({v^1IPS}rv^I_e>fq*h{d+1xwtH=c98zrMe|=X<{I_x^70_q{J01zX_j zBC_!Cs6u8b8&J8djf>1_-j|tnA*F#&0kNmNtv9<6t(+8vxsvBY_hR9-@S(~1*bNgW z>FDfRIvk*<$MGuZ3GIN#oP54D)zQM`5gfZ0us^@93IB6IT(Zt4dMW655a~iOP z(KL{5*S|djzHnq0J$#bPD((y*GT!L7gN(=r%X8(&-n?r`fbKho`F%i8c>_ufQ?K40 zGW`y(7bo$F8v;ABF?gK!WP7Uh9Cj3uSKC6Zvd1!xMbRzbXhhV6nj}5aG~Obu%5UO5 zpD2PFDJCTv9m+{`n+3spBY5Q?-BqQbGy>}DRw&`^%!&N=;W@-+9OYDIC<>^uVbkkl z2;#X_Cj%2%1h11jAm&2U_QyJ91-ow!2xGrq|>MX4Nx8Co;>h z+yOG*ug}oCxj-k=(fapUTJDJ76;r?Vp}g@a{uY0Ag|g;FV6&}a*2N&jM^@8No}P@M z5RYMlJr|n}@| z*2y$;-FKTVfIRD$#`G>=9mQM8j}c62jcwQ4`-Moe&t1Z2h1~ymN(D0>G`{_=RrLAG zubjl9)}^sTaR3baa_UIJ%y~C5QN2=wqGDcN9_mo#^yrp+ zF{HnyA+wc0a)AU300a0Uk)l(>4o{|Ut+0&8CVZZ{4m=oVfC8N0`<*< zsFV{qvTqPE1>w51v}C@uZPz+z^OPVg@?Y(axX#?!s(ItUu3s-;_DS$7VP~U~PLrg_ zpxNvLuU?Yw;6_%>i=N=)C)%Xr)?aIl0P#lZz#B)>J~rdcShM7)Yt5Mq(>;K7A7($ zrs|sVgMNNKYk%uju&J>%6eyrE{-(uc(IDKUayx{i(U@EaNpbGAfe{3g;aCh3X}nuv zn?&@_z%&=&FX)^8Vy|*N{xJZDTU|RonXuzau>rMWBn;L6CT(cH=e7;g2wSj!nD!m+ zz8cp@KeUYisC4E)<>2h>{Os_=Dr+(!01og|~y4mF4DW#;93N2)_IQ(g*>aW`VA9G~9>7Az%w0 ztX^?4)PwP6*oM1RUApa(-G?9J;)}hP71f}DDX5v=s@VI0uPI?7n5rcRBxZRyjd7b! zw}@^9PowTkH>_Q^@!)hPo$-BsY{exHtk+Gv0Xz|ZZwS=xa`yO#6HI!64us8+r9?)g pK6{}V5OE*CCWV*eNOv!Jowg^%V%OJ}eH1NlY$uXED%^t;{{?`bd<_5q literal 0 HcmV?d00001 diff --git a/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp b/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp index bdcd1d7424d37..353a5fab92032 100644 --- a/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp +++ b/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ #include "behavior_path_planner_common/interface/scene_module_interface.hpp" +#include "tier4_autoware_utils/system/stop_watch.hpp" #include #include @@ -54,12 +55,21 @@ std::vector getAllKeys(const std::unordered_map & map) namespace behavior_path_planner { using autoware_auto_perception_msgs::msg::PredictedPath; +using autoware_auto_planning_msgs::msg::PathWithLaneId; using tier4_autoware_utils::Polygon2d; struct MinMaxValue { double min_value{0.0}; double max_value{0.0}; + MinMaxValue operator+(const double scalar) const + { + MinMaxValue ret; + ret.min_value = min_value + scalar; + ret.max_value = max_value + scalar; + return ret; + }; + void swap() { std::swap(min_value, max_value); } }; enum class PolygonGenerationMethod { @@ -67,6 +77,16 @@ enum class PolygonGenerationMethod { OBJECT_PATH_BASE, }; +enum class ObjectType { + OUT_OF_SCOPE = 0, // The module do not care about this type of objects. + REGULATED, // The module assumes this type of objects move in parallel against lanes. Drivable + // areas are divided proportionately with the ego. Typically, cars, bus and trucks + // are classified to this type. + UNREGULATED, // The module does not assume the objects move in parallel against lanes and + // assigns drivable area with priority to ego. Typically, pedestrians should be + // classified to this type. +}; + struct DynamicAvoidanceParameters { // common @@ -103,12 +123,18 @@ struct DynamicAvoidanceParameters double max_overtaking_crossing_object_angle{0.0}; double min_oncoming_crossing_object_vel{0.0}; double max_oncoming_crossing_object_angle{0.0}; + double max_pedestrian_crossing_vel{0.0}; double max_stopped_object_vel{0.0}; // drivable area generation PolygonGenerationMethod polygon_generation_method{}; double min_obj_path_based_lon_polygon_margin{0.0}; double lat_offset_from_obstacle{0.0}; + double margin_distance_around_pedestrian{0.0}; + + double end_time_to_consider{0.0}; + double threshold_confidence{0.0}; + double max_lat_offset_to_avoid{0.0}; double max_time_for_lat_shift{0.0}; double lpf_gain_for_lat_avoid_to_offset{0.0}; @@ -148,6 +174,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface const bool arg_is_object_on_ego_path, const std::optional & arg_latest_time_inside_ego_path) : uuid(tier4_autoware_utils::toHexString(predicted_object.object_id)), + label(predicted_object.classification.front().label), pose(predicted_object.kinematics.initial_pose_with_covariance.pose), shape(predicted_object.shape), vel(arg_vel), @@ -161,6 +188,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface } std::string uuid{}; + uint8_t label{}; geometry_msgs::msg::Pose pose{}; autoware_auto_perception_msgs::msg::Shape shape; double vel{0.0}; @@ -178,6 +206,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::vector ref_path_points_for_obj_poly; LatFeasiblePaths ego_lat_feasible_paths; + // add additional information (not update to the latest data) void update( const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid, const bool arg_is_collision_left, const bool arg_should_be_avoided, @@ -216,7 +245,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface // increase counter if (counter_map_.count(uuid) != 0) { - counter_map_.at(uuid) = std::min(max_count_ + 1, std::max(1, counter_map_.at(uuid) + 1)); + counter_map_.at(uuid) = std::min(max_count_, std::max(1, counter_map_.at(uuid) + 1)); } else { counter_map_.emplace(uuid, 1); } @@ -236,7 +265,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface } for (const auto & uuid : not_updated_uuids) { if (counter_map_.count(uuid) != 0) { - counter_map_.at(uuid) = std::max(min_count_ - 1, std::min(-1, counter_map_.at(uuid) - 1)); + counter_map_.at(uuid) = std::max(0, counter_map_.at(uuid) - 1); } else { counter_map_.emplace(uuid, -1); } @@ -253,7 +282,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::remove_if( valid_object_uuids_.begin(), valid_object_uuids_.end(), [&](const auto & uuid) { - return counter_map_.count(uuid) == 0 || counter_map_.at(uuid) < max_count_; + return counter_map_.count(uuid) == 0 || counter_map_.at(uuid) < min_count_; }), valid_object_uuids_.end()); @@ -340,13 +369,23 @@ class DynamicAvoidanceModule : public SceneModuleInterface const double max_lon_offset; const double min_lon_offset; }; + struct EgoPathReservePoly + { + const tier4_autoware_utils::Polygon2d left_avoid; + const tier4_autoware_utils::Polygon2d right_avoid; + }; bool canTransitSuccessState() override; bool canTransitFailureState() override { return false; } - bool isLabelTargetObstacle(const uint8_t label) const; - void updateTargetObjects(); + ObjectType getObjectType(const uint8_t label) const; + void registerRegulatedObjects(const std::vector & prev_objects); + void registerUnregulatedObjects(const std::vector & prev_objects); + void determineWhetherToAvoidAgainstRegulatedObjects( + const std::vector & prev_objects); + void determineWhetherToAvoidAgainstUnregulatedObjects( + const std::vector & prev_objects); LatFeasiblePaths generateLateralFeasiblePaths( const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const; void updateRefPathBeforeLaneChange(const std::vector & ego_ref_path_points); @@ -378,18 +417,24 @@ class DynamicAvoidanceModule : public SceneModuleInterface const geometry_msgs::msg::Pose & obj_pose, const Polygon2d & obj_points, const double obj_vel, const PredictedPath & obj_path, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const TimeWhileCollision & time_while_collision) const; - std::optional calcMinMaxLateralOffsetToAvoid( + std::optional calcMinMaxLateralOffsetToAvoidRegulatedObject( const std::vector & ref_path_points_for_obj_poly, const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel, const bool is_collision_left, const double obj_normal_vel, const std::optional & prev_object) const; - + std::optional calcMinMaxLateralOffsetToAvoidUnregulatedObject( + const std::vector & ref_path_points_for_obj_poly, + const std::optional & prev_object, + const DynamicAvoidanceObject & object) const; std::pair getAdjacentLanes( const double forward_distance, const double backward_distance) const; std::optional calcEgoPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; std::optional calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const; + std::optional calcPredictedPathBasedDynamicObstaclePolygon( + const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const; + EgoPathReservePoly calcEgoPathReservePoly(const PathWithLaneId & ego_path) const; void printIgnoreReason(const std::string & obj_uuid, const std::string & reason) { @@ -406,6 +451,10 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters_; TargetObjectsManager target_objects_manager_; + + mutable tier4_autoware_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp b/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp index 569c6a17b5b32..baa1c631df8da 100644 --- a/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp @@ -99,6 +99,8 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) node->declare_parameter(ns + "crossing_object.min_oncoming_object_vel"); p.max_oncoming_crossing_object_angle = node->declare_parameter(ns + "crossing_object.max_oncoming_object_angle"); + p.max_pedestrian_crossing_vel = + node->declare_parameter(ns + "crossing_object.max_pedestrian_crossing_vel"); p.max_stopped_object_vel = node->declare_parameter(ns + "stopped_object.max_object_vel"); @@ -111,6 +113,12 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) p.min_obj_path_based_lon_polygon_margin = node->declare_parameter(ns + "object_path_base.min_longitudinal_polygon_margin"); p.lat_offset_from_obstacle = node->declare_parameter(ns + "lat_offset_from_obstacle"); + p.margin_distance_around_pedestrian = + node->declare_parameter(ns + "margin_distance_around_pedestrian"); + p.end_time_to_consider = + node->declare_parameter(ns + "predicted_path.end_time_to_consider"); + p.threshold_confidence = + node->declare_parameter(ns + "predicted_path.threshold_confidence"); p.max_lat_offset_to_avoid = node->declare_parameter(ns + "max_lat_offset_to_avoid"); p.max_time_for_lat_shift = node->declare_parameter(ns + "max_time_for_object_lat_shift"); @@ -214,6 +222,9 @@ void DynamicAvoidanceModuleManager::updateModuleParams( updateParam( parameters, ns + "crossing_object.max_oncoming_object_angle", p->max_oncoming_crossing_object_angle); + updateParam( + parameters, ns + "crossing_object.max_pedestrian_crossing_vel", + p->max_pedestrian_crossing_vel); updateParam( parameters, ns + "stopped_object.max_object_vel", p->max_stopped_object_vel); @@ -231,6 +242,12 @@ void DynamicAvoidanceModuleManager::updateModuleParams( parameters, ns + "object_path_base.min_longitudinal_polygon_margin", p->min_obj_path_based_lon_polygon_margin); updateParam(parameters, ns + "lat_offset_from_obstacle", p->lat_offset_from_obstacle); + updateParam( + parameters, ns + "margin_distance_around_pedestrian", p->margin_distance_around_pedestrian); + updateParam( + parameters, ns + "predicted_path.end_time_to_consider", p->end_time_to_consider); + updateParam( + parameters, ns + "predicted_path.threshold_confidence", p->threshold_confidence); updateParam(parameters, ns + "max_lat_offset_to_avoid", p->max_lat_offset_to_avoid); updateParam( parameters, ns + "max_time_for_object_lat_shift", p->max_time_for_lat_shift); diff --git a/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp b/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp index c6b7b2e0e8031..84871ed756e81 100644 --- a/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp @@ -18,12 +18,15 @@ #include "behavior_path_planner_common/utils/utils.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" #include "signal_processing/lowpass_filter_1d.hpp" +#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" -#include #include -#include +#include +#include #include +#include +#include #include #include @@ -55,6 +58,11 @@ MinMaxValue getMinMaxValues(const std::vector & vec) return MinMaxValue{vec.at(min_idx), vec.at(max_idx)}; } +MinMaxValue combineMinMaxValues(const MinMaxValue & r1, const MinMaxValue & r2) +{ + return MinMaxValue{std::min(r1.min_value, r2.min_value), std::max(r1.max_value, r2.max_value)}; +} + void appendObjectMarker(MarkerArray & marker_array, const geometry_msgs::msg::Pose & obj_pose) { auto marker = tier4_autoware_utils::createDefaultMarker( @@ -339,11 +347,24 @@ bool DynamicAvoidanceModule::isExecutionReady() const void DynamicAvoidanceModule::updateData() { + // stop_watch_.tic(std::string(__func__)); + info_marker_.markers.clear(); debug_marker_.markers.clear(); - // calculate target objects - updateTargetObjects(); + const auto prev_objects = target_objects_manager_.getValidObjects(); + target_objects_manager_.initialize(); + + // 1. Rough filtering of target objects with small computing cost + registerRegulatedObjects(prev_objects); + registerUnregulatedObjects(prev_objects); + + const auto & ego_lat_feasible_paths = generateLateralFeasiblePaths(getEgoPose(), getEgoSpeed()); + target_objects_manager_.finalize(ego_lat_feasible_paths); + + // 2. Precise filtering of target objects and check if they should be avoided + determineWhetherToAvoidAgainstRegulatedObjects(prev_objects); + determineWhetherToAvoidAgainstUnregulatedObjects(prev_objects); const auto target_objects_candidate = target_objects_manager_.getValidObjects(); target_objects_.clear(); @@ -352,6 +373,11 @@ void DynamicAvoidanceModule::updateData() target_objects_.push_back(target_object_candidate); } } + + // const double calculation_time = stop_watch_.toc(std::string(__func__)); + // RCLCPP_INFO_STREAM_EXPRESSION( + // getLogger(), parameters_->enable_debug_info, __func__ << ":=" << calculation_time << " + // [ms]"); } bool DynamicAvoidanceModule::canTransitSuccessState() @@ -361,12 +387,23 @@ bool DynamicAvoidanceModule::canTransitSuccessState() BehaviorModuleOutput DynamicAvoidanceModule::plan() { + // stop_watch_.tic(std::string(__func__)); + const auto & input_path = getPreviousModuleOutput().path; + if (input_path.points.empty()) { + throw std::runtime_error("input path is empty"); + } + + const auto ego_path_reserve_poly = calcEgoPathReservePoly(input_path); // create obstacles to avoid (= extract from the drivable area) std::vector obstacles_for_drivable_area; for (const auto & object : target_objects_) { const auto obstacle_poly = [&]() { + if (getObjectType(object.label) == ObjectType::UNREGULATED) { + return calcPredictedPathBasedDynamicObstaclePolygon(object, ego_path_reserve_poly); + } + if (parameters_->polygon_generation_method == PolygonGenerationMethod::EGO_PATH_BASE) { return calcEgoPathBasedDynamicObstaclePolygon(object); } @@ -399,6 +436,11 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() output.turn_signal_info = getPreviousModuleOutput().turn_signal_info; output.modified_goal = getPreviousModuleOutput().modified_goal; + // const double calculation_time = stop_watch_.toc(std::string(__func__)); + // RCLCPP_INFO_STREAM_EXPRESSION( + // getLogger(), parameters_->enable_debug_info, __func__ << ":=" << calculation_time << " + // [ms]"); + return output; } @@ -414,53 +456,43 @@ BehaviorModuleOutput DynamicAvoidanceModule::planWaitingApproval() return out; } -bool DynamicAvoidanceModule::isLabelTargetObstacle(const uint8_t label) const +ObjectType DynamicAvoidanceModule::getObjectType(const uint8_t label) const { using autoware_auto_perception_msgs::msg::ObjectClassification; if (label == ObjectClassification::CAR && parameters_->avoid_car) { - return true; + return ObjectType::REGULATED; } if (label == ObjectClassification::TRUCK && parameters_->avoid_truck) { - return true; + return ObjectType::REGULATED; } if (label == ObjectClassification::BUS && parameters_->avoid_bus) { - return true; + return ObjectType::REGULATED; } if (label == ObjectClassification::TRAILER && parameters_->avoid_trailer) { - return true; + return ObjectType::REGULATED; } if (label == ObjectClassification::UNKNOWN && parameters_->avoid_unknown) { - return true; + return ObjectType::UNREGULATED; } if (label == ObjectClassification::BICYCLE && parameters_->avoid_bicycle) { - return true; + return ObjectType::UNREGULATED; } if (label == ObjectClassification::MOTORCYCLE && parameters_->avoid_motorcycle) { - return true; + return ObjectType::REGULATED; } if (label == ObjectClassification::PEDESTRIAN && parameters_->avoid_pedestrian) { - return true; + return ObjectType::UNREGULATED; } - return false; + return ObjectType::OUT_OF_SCOPE; } -void DynamicAvoidanceModule::updateTargetObjects() +void DynamicAvoidanceModule::registerRegulatedObjects( + const std::vector & prev_objects) { const auto input_path = getPreviousModuleOutput().path; const auto & predicted_objects = planner_data_->dynamic_object->objects; - const auto input_ref_path_points = getPreviousModuleOutput().reference_path.points; - const auto prev_objects = target_objects_manager_.getValidObjects(); - - updateRefPathBeforeLaneChange(input_ref_path_points); - - const auto & ego_pose = getEgoPose(); - const double ego_vel = getEgoSpeed(); - const auto ego_lat_feasible_paths = generateLateralFeasiblePaths(ego_pose, ego_vel); - - // 1. Rough filtering of target objects - target_objects_manager_.initialize(); for (const auto & predicted_object : predicted_objects) { const auto obj_uuid = tier4_autoware_utils::toHexString(predicted_object.object_id); const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; @@ -474,9 +506,7 @@ void DynamicAvoidanceModule::updateTargetObjects() [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); // 1.a. check label - const bool is_label_target_obstacle = - isLabelTargetObstacle(predicted_object.classification.front().label); - if (!is_label_target_obstacle) { + if (getObjectType(predicted_object.classification.front().label) != ObjectType::REGULATED) { continue; } @@ -543,10 +573,92 @@ void DynamicAvoidanceModule::updateTargetObjects() latest_time_inside_ego_path); target_objects_manager_.updateObject(obj_uuid, target_object); } - target_objects_manager_.finalize(ego_lat_feasible_paths); +} + +void DynamicAvoidanceModule::registerUnregulatedObjects( + const std::vector & prev_objects) +{ + const auto input_path = getPreviousModuleOutput().path; + const auto & predicted_objects = planner_data_->dynamic_object->objects; + + for (const auto & predicted_object : predicted_objects) { + const auto obj_uuid = tier4_autoware_utils::toHexString(predicted_object.object_id); + const auto & obj_pose = predicted_object.kinematics.initial_pose_with_covariance.pose; + const double obj_vel_norm = std::hypot( + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x, + predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y); + const auto prev_object = getObstacleFromUuid(prev_objects, obj_uuid); + const auto obj_path = *std::max_element( + predicted_object.kinematics.predicted_paths.begin(), + predicted_object.kinematics.predicted_paths.end(), + [](const PredictedPath & a, const PredictedPath & b) { return a.confidence < b.confidence; }); + + // 1.a. Check if the obstacle is labeled as pedestrians, bicycle or similar. + if (getObjectType(predicted_object.classification.front().label) != ObjectType::UNREGULATED) { + continue; + } + + // 1.b. Check if the object's velocity is within the module's coverage range. + const auto [obj_tangent_vel, obj_normal_vel] = + projectObstacleVelocityToTrajectory(input_path.points, predicted_object); + if ( + obj_vel_norm < parameters_->min_obstacle_vel || + obj_vel_norm > parameters_->max_obstacle_vel) { + continue; + } + + // 1.c. Check if object' lateral velocity is small enough to be avoid. + if (std::abs(obj_normal_vel) > parameters_->max_pedestrian_crossing_vel) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since it crosses the ego's path with its normal " + "vel (%5.2f) m/s.", + obj_uuid.c_str(), obj_normal_vel); + continue; + } + + // Blocks for compatibility with existing code + // 1.e. check if object lateral distance to ego's path is small enough + // 1.f. calculate the object is on ego's path or not + + const double dist_obj_center_to_path = + std::abs(motion_utils::calcLateralOffset(input_path.points, obj_pose.position)); + const bool is_object_on_ego_path = + dist_obj_center_to_path < + planner_data_->parameters.vehicle_width / 2.0 + parameters_->min_obj_lat_offset_to_ego_path; + + // 1.g. calculate last time inside ego's path + const auto latest_time_inside_ego_path = [&]() -> std::optional { + if (!prev_object || !prev_object->latest_time_inside_ego_path) { + if (is_object_on_ego_path) { + return clock_->now(); + } + return std::nullopt; + } + if (is_object_on_ego_path) { + return clock_->now(); + } + return *prev_object->latest_time_inside_ego_path; + }(); + + // register the object + const auto target_object = DynamicAvoidanceObject( + predicted_object, obj_tangent_vel, obj_normal_vel, is_object_on_ego_path, + latest_time_inside_ego_path); + target_objects_manager_.updateObject(obj_uuid, target_object); + } +} + +void DynamicAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObjects( + const std::vector & prev_objects) +{ + const auto & input_path = getPreviousModuleOutput().path; - // 2. Precise filtering of target objects and check if they should be avoided for (const auto & object : target_objects_manager_.getValidObjects()) { + if (getObjectType(object.label) != ObjectType::REGULATED) { + continue; + } + const auto obj_uuid = object.uuid; const auto prev_object = getObstacleFromUuid(prev_objects, obj_uuid); const auto obj_path = *std::max_element( @@ -651,7 +763,7 @@ void DynamicAvoidanceModule::updateTargetObjects() const double signed_dist_ego_to_obj = [&]() { const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); const double lon_offset_ego_to_obj = motion_utils::calcSignedArcLength( - input_path.points, ego_pose.position, ego_seg_idx, lat_lon_offset.nearest_idx); + input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); if (0 < lon_offset_ego_to_obj) { return std::max( 0.0, lon_offset_ego_to_obj - planner_data_->parameters.front_overhang + @@ -676,9 +788,10 @@ void DynamicAvoidanceModule::updateTargetObjects() const auto lon_offset_to_avoid = calcMinMaxLongitudinalOffsetToAvoid( ref_path_points_for_obj_poly, object.pose, obj_points, object.vel, obj_path, object.shape, time_while_collision); - const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoid( + const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoidRegulatedObject( ref_path_points_for_obj_poly, obj_points, object.pose.position, object.vel, is_collision_left, object.lat_vel, prev_object); + if (!lat_offset_to_avoid) { RCLCPP_INFO_EXPRESSION( getLogger(), parameters_->enable_debug_info, @@ -693,8 +806,68 @@ void DynamicAvoidanceModule::updateTargetObjects() obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, ref_path_points_for_obj_poly); } + // prev_input_ref_path_points_ = input_ref_path_points; +} + +void DynamicAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedObjects( + const std::vector & prev_objects) +{ + const auto & input_path = getPreviousModuleOutput().path; + + for (const auto & object : target_objects_manager_.getValidObjects()) { + if (getObjectType(object.label) != ObjectType::UNREGULATED) { + continue; + } + + const auto obj_uuid = object.uuid; + const auto & ref_path_points_for_obj_poly = input_path.points; + + // 2.g. check if the ego is not ahead of the object. + const auto lat_lon_offset = + getLateralLongitudinalOffset(input_path.points, object.pose, object.shape); + const double signed_dist_ego_to_obj = [&]() { + const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(input_path.points); + const double lon_offset_ego_to_obj = motion_utils::calcSignedArcLength( + input_path.points, getEgoPose().position, ego_seg_idx, lat_lon_offset.nearest_idx); + if (0 < lon_offset_ego_to_obj) { + return std::max( + 0.0, lon_offset_ego_to_obj - planner_data_->parameters.front_overhang + + lat_lon_offset.min_lon_offset); + } + return std::min( + 0.0, lon_offset_ego_to_obj + planner_data_->parameters.rear_overhang + + lat_lon_offset.max_lon_offset); + }(); + if (signed_dist_ego_to_obj < 0) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since distance from ego to object (%f) is less " + "than 0.", + obj_uuid.c_str(), signed_dist_ego_to_obj); + continue; + } + + // 2.h. calculate longitudinal and lateral offset to avoid to generate object polygon by + // "ego_path_base" + const auto lat_offset_to_avoid = calcMinMaxLateralOffsetToAvoidUnregulatedObject( + ref_path_points_for_obj_poly, getObstacleFromUuid(prev_objects, obj_uuid), object); + if (!lat_offset_to_avoid) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) since the object will intersects the ego's path " + "enough", + obj_uuid.c_str()); + continue; + } - prev_input_ref_path_points_ = input_ref_path_points; + const bool is_collision_left = (lat_offset_to_avoid.value().max_value > 0.0); + const auto lon_offset_to_avoid = MinMaxValue{0.0, 1.0}; // not used. dummy value + + const bool should_be_avoided = true; + target_objects_manager_.updateObjectVariables( + obj_uuid, lon_offset_to_avoid, *lat_offset_to_avoid, is_collision_left, should_be_avoided, + ref_path_points_for_obj_poly); + } } LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( @@ -706,6 +879,7 @@ LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( LatFeasiblePaths ego_lat_feasible_paths; for (double t = 0; t < 10.0; t += 1.0) { + // maybe this equation does not have physical meaning (takagi) const double feasible_lat_offset = lat_acc * std::pow(std::max(t - delay_time, 0.0), 2) / 2.0 + lat_jerk * std::pow(std::max(t - delay_time, 0.0), 3) / 6.0 - planner_data_->parameters.vehicle_width / 2.0; @@ -733,7 +907,7 @@ LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( return ego_lat_feasible_paths; } -void DynamicAvoidanceModule::updateRefPathBeforeLaneChange( +[[maybe_unused]] void DynamicAvoidanceModule::updateRefPathBeforeLaneChange( const std::vector & ego_ref_path_points) { if (ref_path_before_lane_change_) { @@ -1204,7 +1378,8 @@ double DynamicAvoidanceModule::calcValidLengthToAvoid( return motion_utils::calcSignedArcLength(obj_path.path, 0, valid_obj_path_end_idx); } -std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoid( +// min value denotes near side, max value denotes far side +std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( const std::vector & ref_path_points_for_obj_poly, const Polygon2d & obj_points, const geometry_msgs::msg::Point & obj_pos, const double obj_vel, const bool is_collision_left, const double obj_normal_vel, @@ -1297,6 +1472,89 @@ std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoi return MinMaxValue{filtered_min_bound_lat_offset, max_bound_lat_offset}; } +// min value denotes near side, max value denotes far side +std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( + const std::vector & ref_path_points_for_obj_poly, + const std::optional & prev_object, + const DynamicAvoidanceObject & object) const +{ + const bool enable_lowpass_filter = [&]() { + if ( + !prev_object || prev_object->ref_path_points_for_obj_poly.size() < 2 || + ref_path_points_for_obj_poly.size() < 2) { + return true; + } + const size_t obj_point_idx = + motion_utils::findNearestIndex(ref_path_points_for_obj_poly, object.pose.position); + const double paths_lat_diff = std::abs(motion_utils::calcLateralOffset( + prev_object->ref_path_points_for_obj_poly, + ref_path_points_for_obj_poly.at(obj_point_idx).point.pose.position)); + + constexpr double min_paths_lat_diff = 0.3; + if (paths_lat_diff < min_paths_lat_diff) { + return true; + } + // NOTE: When the input reference path laterally changes, the low-pass filter is disabled not to + // shift the obstacle polygon suddenly. + return false; + }(); + + const auto obj_occupancy_region = [&]() { + const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); + std::vector lat_pos_vec; + for (size_t i = 0; i < obj_points.outer().size(); ++i) { + const auto geom_obj_point = toGeometryPoint(obj_points.outer().at(i)); + const double obj_point_lat_offset = motion_utils::calcLateralOffset( + ref_path_points_for_obj_poly, geom_obj_point, + motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, geom_obj_point)); + lat_pos_vec.push_back(obj_point_lat_offset); + } + const auto current_pos_area = getMinMaxValues(lat_pos_vec); + return combineMinMaxValues(current_pos_area, current_pos_area + object.lat_vel * 3.0); + }(); + + if ( + obj_occupancy_region.min_value * obj_occupancy_region.max_value < 0.0 || + obj_occupancy_region.max_value - obj_occupancy_region.min_value < 1e-3) { + return std::nullopt; + } + + // calculate bound pos + const auto bound_pos = [&]() { + auto temp_bound_pos = obj_occupancy_region; + temp_bound_pos.max_value += parameters_->lat_offset_from_obstacle; + temp_bound_pos.min_value -= parameters_->lat_offset_from_obstacle; + if (std::abs(temp_bound_pos.max_value) < std::abs(temp_bound_pos.min_value)) { + temp_bound_pos.swap(); // From here, min denotes near bound, max denotes far bound. + } + + const double near_bound_limit = + planner_data_->parameters.vehicle_width / 2.0 - parameters_->max_lat_offset_to_avoid; + if (temp_bound_pos.max_value > 0.0) { + temp_bound_pos.min_value = std::max(temp_bound_pos.min_value, near_bound_limit); + } else { + temp_bound_pos.min_value = std::min(temp_bound_pos.min_value, -near_bound_limit); + } + return temp_bound_pos; + }(); + + // low pass filter for min_bound + const auto prev_min_lat_avoid_to_offset = [&]() -> std::optional { + if (!prev_object || !prev_object->lat_offset_to_avoid) { + return std::nullopt; + } + return prev_object->lat_offset_to_avoid->min_value; + }(); + const double filtered_min_bound_pos = + (prev_min_lat_avoid_to_offset.has_value() & enable_lowpass_filter) + ? signal_processing::lowpassFilter( + bound_pos.min_value, *prev_min_lat_avoid_to_offset, + parameters_->lpf_gain_for_lat_avoid_to_offset) + : bound_pos.min_value; + + return MinMaxValue{filtered_min_bound_pos, bound_pos.max_value}; +} + // NOTE: object does not have const only to update min_bound_lat_offset. std::optional DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( @@ -1310,7 +1568,7 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( const size_t obj_seg_idx = motion_utils::findNearestSegmentIndex(ref_path_points_for_obj_poly, object.pose.position); - const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); + // const auto obj_points = tier4_autoware_utils::toPolygon2d(object.pose, object.shape); const auto lon_bound_start_idx_opt = motion_utils::insertTargetPoint( obj_seg_idx, object.lon_offset_to_avoid->min_value, ref_path_points_for_obj_poly); @@ -1403,6 +1661,7 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( return obj_poly; } +// should be replace by the function calcPredictedPathBasedDynamicObstaclePolygon() (takagi) std::optional DynamicAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const @@ -1458,4 +1717,145 @@ DynamicAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( boost::geometry::correct(obj_poly); return obj_poly; } + +// Calculate polygons according to predicted_path with certain confidence, +// except for the area required for ego safety. +// input: an object, the minimum area required for ego safety, and some global params +std::optional +DynamicAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( + const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const +{ + std::vector obj_poses; + for (const auto & predicted_path : object.predicted_paths) { + if (predicted_path.confidence < parameters_->threshold_confidence) continue; + + double time_count = 0.0; + for (const auto & pose : predicted_path.path) { + obj_poses.push_back(pose); + time_count += predicted_path.time_step.sec + predicted_path.time_step.nanosec * 1e-9; + if (time_count > parameters_->end_time_to_consider + 1e-3) break; + } + } + + tier4_autoware_utils::Polygon2d obj_points_as_poly; + for (const auto pose : obj_poses) { + boost::geometry::append( + obj_points_as_poly, tier4_autoware_utils::toFootprint( + pose, object.shape.dimensions.x * 0.5, object.shape.dimensions.x * 0.5, + object.shape.dimensions.y * 0.5) + .outer()); + } + boost::geometry::correct(obj_points_as_poly); + Polygon2d obj_poly; + boost::geometry::convex_hull(obj_points_as_poly, obj_poly); + + tier4_autoware_utils::MultiPolygon2d expanded_poly; + namespace strategy = boost::geometry::strategy::buffer; + boost::geometry::buffer( + obj_poly, expanded_poly, + strategy::distance_symmetric(parameters_->margin_distance_around_pedestrian), + strategy::side_straight(), strategy::join_round(), strategy::end_flat(), + strategy::point_circle()); + if (expanded_poly.empty()) return {}; + + tier4_autoware_utils::MultiPolygon2d output_poly; + boost::geometry::difference( + expanded_poly[0], + object.is_collision_left ? ego_path_poly.right_avoid : ego_path_poly.left_avoid, output_poly); + + if (output_poly.empty()) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) because it stay inside the ego's path.", + object.uuid.c_str()); + return {}; + } else if (output_poly.size() >= 2) { + RCLCPP_INFO_EXPRESSION( + getLogger(), parameters_->enable_debug_info, + "[DynamicAvoidance] Ignore obstacle (%s) because it covers the ego's path.", + object.uuid.c_str()); + return {}; + } + + return output_poly[0]; +} + +// Calculate the driving area required to ensure the safety of the own vehicle. +// It is assumed that this area will not be clipped. +// input: ego's reference path, ego's pose, ego's speed, and some global params +DynamicAvoidanceModule::EgoPathReservePoly DynamicAvoidanceModule::calcEgoPathReservePoly( + const PathWithLaneId & ego_path) const +{ + // This function require almost 0.5 ms. Should be refactored in the future + // double calculation_time; + // stop_watch_.tic(std::string(__func__)); + + namespace strategy = boost::geometry::strategy::buffer; + + assert(!ego_path.points.empty()); + + tier4_autoware_utils::LineString2d ego_path_lines; + for (const auto & path_point : ego_path.points) { + ego_path_lines.push_back(tier4_autoware_utils::fromMsg(path_point.point.pose.position).to_2d()); + } + + auto calcReservePoly = + [&ego_path_lines]( + strategy::distance_asymmetric path_expand_strategy, + strategy::distance_asymmetric steer_expand_strategy, + std::vector outer_body_path) -> tier4_autoware_utils::Polygon2d { + // reserve area based on the reference path + tier4_autoware_utils::MultiPolygon2d path_poly; + boost::geometry::buffer( + ego_path_lines, path_poly, path_expand_strategy, strategy::side_straight(), + strategy::join_round(), strategy::end_flat(), strategy::point_circle()); + + // reserve area steer to the avoidance path + tier4_autoware_utils::LineString2d steer_lines; + for (const auto & point : outer_body_path) { + const auto bg_point = tier4_autoware_utils::fromMsg(point).to_2d(); + if (boost::geometry::within(bg_point, path_poly)) { + if (steer_lines.size() != 0) { + ; + // boost::geometry::append(steer_lines, bg_point); + } + break; + } + // boost::geometry::append(steer_lines, bg_point); + } + tier4_autoware_utils::MultiPolygon2d steer_poly; + boost::geometry::buffer( + steer_lines, steer_poly, steer_expand_strategy, strategy::side_straight(), + strategy::join_round(), strategy::end_flat(), strategy::point_circle()); + + tier4_autoware_utils::MultiPolygon2d output_poly; + boost::geometry::union_(path_poly, steer_poly, output_poly); + if (output_poly.size() != 1) { + assert(false); + } + return output_poly[0]; + }; + + const auto motion_saturated_outer_paths = + generateLateralFeasiblePaths(getEgoPose(), getEgoSpeed()); + + const double vehicle_half_width = planner_data_->parameters.vehicle_width * 0.5; + const double reserve_width_obj_side = vehicle_half_width - parameters_->max_lat_offset_to_avoid; + + const tier4_autoware_utils::Polygon2d left_avoid_poly = calcReservePoly( + strategy::distance_asymmetric(vehicle_half_width, reserve_width_obj_side), + strategy::distance_asymmetric(vehicle_half_width, 0.0), + motion_saturated_outer_paths.right_path); + const tier4_autoware_utils::Polygon2d right_avoid_poly = calcReservePoly( + strategy::distance_asymmetric(reserve_width_obj_side, vehicle_half_width), + strategy::distance_asymmetric(0.0, vehicle_half_width), + motion_saturated_outer_paths.left_path); + + // calculation_time = stop_watch_.toc(std::string(__func__)); + // RCLCPP_INFO_STREAM_EXPRESSION( + // getLogger(), parameters_->enable_debug_info, __func__ << ":=" << calculation_time << "[ms]"); + + return {left_avoid_poly, right_avoid_poly}; +} + } // namespace behavior_path_planner From c93648cf24c0ddaac9cba9145931d5d0acf4f334 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 19 Apr 2024 22:07:46 +0000 Subject: [PATCH 057/192] chore: update CODEOWNERS (#6603) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index a6cdc58f03e94..82d07651b867c 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -113,12 +113,12 @@ map/map_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@ti map/map_projection_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp map/map_tf_generator/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp map/util/lanelet2_map_preprocessor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -perception/bytetrack/** manato.hirabayashi@tier4.jp +perception/bytetrack/** manato.hirabayashi@tier4.jp yoshi.ri@tier4.jp perception/cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp perception/compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yukihiro.saito@tier4.jp perception/crosswalk_traffic_light_estimator/** satoshi.ota@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/detected_object_feature_remover/** tomoya.kimura@tier4.jp -perception/detected_object_validation/** dai.nguyen@tier4.jp shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/detected_object_validation/** dai.nguyen@tier4.jp shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/detection_by_tracker/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/elevation_map_loader/** kosuke.takeuchi@tier4.jp shintaro.tomie@tier4.jp taichi.higashide@tier4.jp perception/euclidean_cluster/** dai.nguyen@tier4.jp yukihiro.saito@tier4.jp @@ -222,6 +222,7 @@ sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai system/bluetooth_monitor/** fumihito.ito@tier4.jp system/component_state_monitor/** isamu.takagi@tier4.jp From 7b287028cee2473c84466b759350ed0809b72c2b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 19 Apr 2024 22:16:21 +0000 Subject: [PATCH 058/192] build(deps): bump actions/checkout from 3 to 4 (#4890) Bumps [actions/checkout](https://github.com/actions/checkout) from 3 to 4. - [Release notes](https://github.com/actions/checkout/releases) - [Changelog](https://github.com/actions/checkout/blob/main/CHANGELOG.md) - [Commits](https://github.com/actions/checkout/compare/v3...v4) --- updated-dependencies: - dependency-name: actions/checkout dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/build-and-test-arm64.yaml | 2 +- .github/workflows/build-and-test-differential-arm64.yaml | 2 +- .github/workflows/build-and-test-differential.yaml | 4 ++-- .github/workflows/build-and-test.yaml | 2 +- .github/workflows/check-build-depends.yaml | 2 +- .github/workflows/clang-tidy-pr-comments-manually.yaml | 4 ++-- .github/workflows/clang-tidy-pr-comments.yaml | 4 ++-- .github/workflows/delete-closed-pr-docs.yaml | 2 +- .github/workflows/deploy-docs.yaml | 2 +- .github/workflows/json-schema-check.yaml | 4 ++-- 10 files changed, 14 insertions(+), 14 deletions(-) diff --git a/.github/workflows/build-and-test-arm64.yaml b/.github/workflows/build-and-test-arm64.yaml index 932c15d27b05f..a5e00496cc50a 100644 --- a/.github/workflows/build-and-test-arm64.yaml +++ b/.github/workflows/build-and-test-arm64.yaml @@ -23,7 +23,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Show disk space before the tasks run: df -h diff --git a/.github/workflows/build-and-test-differential-arm64.yaml b/.github/workflows/build-and-test-differential-arm64.yaml index f742dedcf0b89..bd422af46bc4d 100644 --- a/.github/workflows/build-and-test-differential-arm64.yaml +++ b/.github/workflows/build-and-test-differential-arm64.yaml @@ -33,7 +33,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 0e759fe47630b..3ad7b6d434f33 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -32,7 +32,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 @@ -80,7 +80,7 @@ jobs: container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt-cuda steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 49e1c979928ad..520c2cb9983b0 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -25,7 +25,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Show disk space before the tasks run: df -h diff --git a/.github/workflows/check-build-depends.yaml b/.github/workflows/check-build-depends.yaml index 81618a1db0eea..c790c2132d71e 100644 --- a/.github/workflows/check-build-depends.yaml +++ b/.github/workflows/check-build-depends.yaml @@ -20,7 +20,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 diff --git a/.github/workflows/clang-tidy-pr-comments-manually.yaml b/.github/workflows/clang-tidy-pr-comments-manually.yaml index 9bccd972becde..87f939fe8b72f 100644 --- a/.github/workflows/clang-tidy-pr-comments-manually.yaml +++ b/.github/workflows/clang-tidy-pr-comments-manually.yaml @@ -11,7 +11,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Download analysis results run: | @@ -36,7 +36,7 @@ jobs: - name: Check out PR head if: ${{ steps.check-fixes-yaml-existence.outputs.exists == 'true' }} - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: repository: ${{ steps.set-variables.outputs.pr-head-repo }} ref: ${{ steps.set-variables.outputs.pr-head-ref }} diff --git a/.github/workflows/clang-tidy-pr-comments.yaml b/.github/workflows/clang-tidy-pr-comments.yaml index baaa0fb8e7744..0f6db69dfedd4 100644 --- a/.github/workflows/clang-tidy-pr-comments.yaml +++ b/.github/workflows/clang-tidy-pr-comments.yaml @@ -13,7 +13,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Download analysis results run: | @@ -37,7 +37,7 @@ jobs: - name: Check out PR head if: ${{ steps.check-fixes-yaml-existence.outputs.exists == 'true' }} - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: repository: ${{ steps.set-variables.outputs.pr-head-repo }} ref: ${{ steps.set-variables.outputs.pr-head-ref }} diff --git a/.github/workflows/delete-closed-pr-docs.yaml b/.github/workflows/delete-closed-pr-docs.yaml index b7b009fb00263..eb211766c49dd 100644 --- a/.github/workflows/delete-closed-pr-docs.yaml +++ b/.github/workflows/delete-closed-pr-docs.yaml @@ -10,7 +10,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 diff --git a/.github/workflows/deploy-docs.yaml b/.github/workflows/deploy-docs.yaml index b48d70dbacb0c..e5967b0d50c67 100644 --- a/.github/workflows/deploy-docs.yaml +++ b/.github/workflows/deploy-docs.yaml @@ -30,7 +30,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: fetch-depth: 0 ref: ${{ github.event.pull_request.head.sha }} diff --git a/.github/workflows/json-schema-check.yaml b/.github/workflows/json-schema-check.yaml index 77ce4576b4952..5c223edf1eec2 100644 --- a/.github/workflows/json-schema-check.yaml +++ b/.github/workflows/json-schema-check.yaml @@ -10,7 +10,7 @@ jobs: outputs: run-check: ${{ steps.paths_filter.outputs.json_or_yaml }} steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - uses: dorny/paths-filter@v3 id: paths_filter with: @@ -25,7 +25,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Run json-schema-check uses: autowarefoundation/autoware-github-actions/json-schema-check@v1 From fb5b20fde61c533e87032026a561e99428d9d8bb Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 20 Apr 2024 00:23:19 +0000 Subject: [PATCH 059/192] chore: update CODEOWNERS (#6856) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 82d07651b867c..b283c95c28a9b 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -209,10 +209,10 @@ planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murook planning/surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp -sensing/image_transport_decompressor/** yukihiro.saito@tier4.jp +sensing/image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp sensing/imu_corrector/** koji.minoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -sensing/livox/livox_tag_filter/** ryohsuke.mitsudome@tier4.jp -sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +sensing/livox/livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp +sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yukihiro.saito@tier4.jp sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp From 6a787748f6bb60f01f18ad5e4be01f8430bbe416 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Mon, 22 Apr 2024 11:33:33 +0900 Subject: [PATCH 060/192] feat(probabilistic_occupancy_grid_map): enable to create partial occupancy grid map without filter obstacle pointcloud (#6857) * feat: crop ogm creation range by raw pointcloud Signed-off-by: yoshiri * feat: add same filtering method to projective based ogm creation mode Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- .../occupancy_grid_map_fixed.cpp | 38 +++++++++---------- .../occupancy_grid_map_projective.cpp | 34 ++++++++--------- 2 files changed, 33 insertions(+), 39 deletions(-) diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp index 00b3e42fdf392..2722f2ef98249 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_fixed.cpp @@ -71,7 +71,7 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( utils::transformPointcloud(map_raw_pointcloud, scan2map_pose, scan_raw_pointcloud); utils::transformPointcloud(map_obstacle_pointcloud, scan2map_pose, scan_obstacle_pointcloud); - // Create angle bins + // Create angle bins and sort by distance struct BinInfo { BinInfo() = default; @@ -96,45 +96,43 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud( raw_pointcloud_angle_bins.at(angle_bin_index) .push_back(BinInfo(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy)); } + for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { + std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { + return a.range < b.range; + }); + } + // create and sort bin for obstacle pointcloud for (PointCloud2ConstIterator iter_x(scan_obstacle_pointcloud, "x"), iter_y(scan_obstacle_pointcloud, "y"), iter_wx(map_obstacle_pointcloud, "x"), iter_wy(map_obstacle_pointcloud, "y"); iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_wx, ++iter_wy) { const double angle = atan2(*iter_y, *iter_x); - int angle_bin_index = (angle - min_angle) / angle_increment; + const int angle_bin_index = (angle - min_angle) / angle_increment; + const double range = std::hypot(*iter_y, *iter_x); + // Ignore obstacle points exceed the range of the raw points + if (raw_pointcloud_angle_bins.at(angle_bin_index).empty()) { + continue; // No raw point in this angle bin + } else if (range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { + continue; // Obstacle point exceeds the range of the raw points + } obstacle_pointcloud_angle_bins.at(angle_bin_index) - .push_back(BinInfo(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy)); + .push_back(BinInfo(range, *iter_wx, *iter_wy)); } - - // Sort by distance for (auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { std::sort( obstacle_pointcloud_angle_bin.begin(), obstacle_pointcloud_angle_bin.end(), [](auto a, auto b) { return a.range < b.range; }); } - for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { - std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { - return a.range < b.range; - }); - } // First step: Initialize cells to the final point with freespace for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { - auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); BinInfo end_distance; - if (raw_pointcloud_angle_bin.empty() && obstacle_pointcloud_angle_bin.empty()) { + if (raw_pointcloud_angle_bin.empty()) { continue; - } else if (raw_pointcloud_angle_bin.empty()) { - end_distance = obstacle_pointcloud_angle_bin.back(); - } else if (obstacle_pointcloud_angle_bin.empty()) { - end_distance = raw_pointcloud_angle_bin.back(); } else { - end_distance = obstacle_pointcloud_angle_bin.back().range + distance_margin_ < - raw_pointcloud_angle_bin.back().range - ? raw_pointcloud_angle_bin.back() - : obstacle_pointcloud_angle_bin.back(); + end_distance = raw_pointcloud_angle_bin.back(); } raytrace( scan_origin.position.x, scan_origin.position.y, end_distance.wx, end_distance.wy, diff --git a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp index 64b76a2488e24..eae66eb90355b 100644 --- a/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp +++ b/perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/occupancy_grid_map_projective.cpp @@ -72,7 +72,7 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( utils::transformPointcloud(map_raw_pointcloud, scan2map_pose, scan_raw_pointcloud); utils::transformPointcloud(map_obstacle_pointcloud, scan2map_pose, scan_obstacle_pointcloud); - // Create angle bins + // Create angle bins and sort points by range struct BinInfo3D { BinInfo3D( @@ -110,6 +110,12 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( raw_pointcloud_angle_bins.at(angle_bin_index) .emplace_back(std::hypot(*iter_y, *iter_x), *iter_wx, *iter_wy, *iter_wz); } + for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { + std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { + return a.range < b.range; + }); + } + // Create obstacle angle bins and sort points by range for (PointCloud2ConstIterator iter_x(scan_obstacle_pointcloud, "x"), iter_y(scan_obstacle_pointcloud, "y"), iter_z(scan_obstacle_pointcloud, "z"), iter_wx(map_obstacle_pointcloud, "x"), iter_wy(map_obstacle_pointcloud, "y"), @@ -121,6 +127,12 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( const double angle = atan2(*iter_y, *iter_x); const int angle_bin_index = (angle - min_angle) / angle_increment; const double range = std::hypot(*iter_x, *iter_y); + // Ignore obstacle points exceed the range of the raw points + if (raw_pointcloud_angle_bins.at(angle_bin_index).empty()) { + continue; // No raw point in this angle bin + } else if (range > raw_pointcloud_angle_bins.at(angle_bin_index).back().range) { + continue; // Obstacle point exceeds the range of the raw points + } if (dz > projection_dz_threshold_) { const double ratio = obstacle_z / dz; const double projection_length = range * ratio; @@ -136,18 +148,11 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( std::numeric_limits::infinity(), std::numeric_limits::infinity()); } } - - // Sort by distance for (auto & obstacle_pointcloud_angle_bin : obstacle_pointcloud_angle_bins) { std::sort( obstacle_pointcloud_angle_bin.begin(), obstacle_pointcloud_angle_bin.end(), [](auto a, auto b) { return a.range < b.range; }); } - for (auto & raw_pointcloud_angle_bin : raw_pointcloud_angle_bins) { - std::sort(raw_pointcloud_angle_bin.begin(), raw_pointcloud_angle_bin.end(), [](auto a, auto b) { - return a.range < b.range; - }); - } grid_map::Costmap2DConverter converter; if (pub_debug_grid_) { @@ -177,22 +182,13 @@ void OccupancyGridMapProjectiveBlindSpot::updateWithPointCloud( // First step: Initialize cells to the final point with freespace for (size_t bin_index = 0; bin_index < obstacle_pointcloud_angle_bins.size(); ++bin_index) { - const auto & obstacle_pointcloud_angle_bin = obstacle_pointcloud_angle_bins.at(bin_index); const auto & raw_pointcloud_angle_bin = raw_pointcloud_angle_bins.at(bin_index); BinInfo3D ray_end; - if (raw_pointcloud_angle_bin.empty() && obstacle_pointcloud_angle_bin.empty()) { + if (raw_pointcloud_angle_bin.empty()) { continue; - } else if (raw_pointcloud_angle_bin.empty()) { - ray_end = obstacle_pointcloud_angle_bin.back(); - } else if (obstacle_pointcloud_angle_bin.empty()) { - ray_end = raw_pointcloud_angle_bin.back(); } else { - const auto & farthest_obstacle_this_bin = obstacle_pointcloud_angle_bin.back(); - const auto & farthest_raw_this_bin = raw_pointcloud_angle_bin.back(); - ray_end = is_visible_beyond_obstacle(farthest_obstacle_this_bin, farthest_raw_this_bin) - ? farthest_raw_this_bin - : farthest_obstacle_this_bin; + ray_end = raw_pointcloud_angle_bin.back(); } raytrace( scan_origin.position.x, scan_origin.position.y, ray_end.wx, ray_end.wy, From 8adf18ea8c4e1f550df6438b2a37c996ce5b3c25 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 22 Apr 2024 13:34:25 +0900 Subject: [PATCH 061/192] perf(behavior_path_planner): improve getReferencePath to support very long routes (#6739) Signed-off-by: Maxime CLEMENT --- .../interface.hpp | 2 +- .../src/scene.cpp | 2 +- .../behavior_path_planner_manager_design.md | 54 +-- .../image/manager/avoidance.svg | 415 ++++++++++++++--- .../image/manager/current_route_lanelet.svg | 147 ++++++ .../image/manager/lane_change.svg | 428 ++++++++++-------- .../image/manager/root_lanelet.svg | 166 ------- .../behavior_path_planner/planner_manager.hpp | 45 +- .../src/behavior_path_planner_node.cpp | 11 +- .../src/planner_manager.cpp | 116 ++--- .../interface/scene_module_interface.hpp | 2 +- .../utils/utils.hpp | 4 +- .../src/utils/utils.cpp | 7 +- .../sampling_planner_module.hpp | 2 +- 14 files changed, 829 insertions(+), 572 deletions(-) create mode 100644 planning/behavior_path_planner/image/manager/current_route_lanelet.svg delete mode 100644 planning/behavior_path_planner/image/manager/root_lanelet.svg diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp index 757ccd3a3116d..4e886c33f832b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/interface.hpp @@ -67,7 +67,7 @@ class LaneChangeInterface : public SceneModuleInterface bool isExecutionReady() const override; - bool isRootLaneletToBeUpdated() const override + bool isCurrentRouteLaneletToBeReset() const override { return getCurrentStatus() == ModuleStatus::SUCCESS; } diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index d0e48be72e2cb..97bb30ac8174d 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -387,7 +387,7 @@ void NormalLaneChange::insertStopPoint( PathWithLaneId NormalLaneChange::getReferencePath() const { - return utils::getCenterLinePathFromRootLanelet( + return utils::getCenterLinePathFromLanelet( status_.lane_change_path.info.target_lanes.front(), planner_data_); } diff --git a/planning/behavior_path_planner/docs/behavior_path_planner_manager_design.md b/planning/behavior_path_planner/docs/behavior_path_planner_manager_design.md index 5af70a4f98e29..7188c03bd2604 100644 --- a/planning/behavior_path_planner/docs/behavior_path_planner_manager_design.md +++ b/planning/behavior_path_planner/docs/behavior_path_planner_manager_design.md @@ -532,67 +532,33 @@ When the manager removes succeeded modules, the last added module's output is us ## Reference path generation -The root reference path is generated from the centerline of the **lanelet sequence** that obtained from the **root lanelet**, and it is not only used as an input to the first added module of approved modules stack, but also used as the output of `behavior_path_planner` if none of the modules are running. +The reference path is generated from the centerline of the **lanelet sequence** obtained from the **current route lanelet**, and it is not only used as an input to the first added module of approved modules stack, but also used as the output of `behavior_path_planner` if none of the modules are running.

![root_generation](../image/manager/root_generation.svg){width=500}
root reference path generation
-The root lanelet is the closest lanelet within the route, and the update timing is based on Ego's operation mode state. +The **current route lanelet** keeps track of the route lanelet currently followed by the planner. +It is initialized as the closest lanelet within the route. +It is then updated as ego travels along the route such that (1) it follows the previous **current route lanelet** and (2) it is the closest lanelet within the route. -- the state is `OperationModeState::AUTONOMOUS`: Update only when the ego moves to right or left lane by lane change module. -- the state is **NOT** `OperationModeState::AUTONOMOUS`: Update at the beginning of every planning cycle. +The **current route lanelet** can be reset to the closest lanelet within the route, ignoring whether it follows the previous **current route lanelet** . -![root_lanelet](../image/manager/root_lanelet.svg) +![current_route_lanelet](../image/manager/current_route_lanelet.svg) The manager needs to know the ego behavior and then generate a root reference path from the lanes that Ego should follow. -For example, during autonomous driving, even if Ego moves into the next lane in order to avoid a parked vehicle, the target lanes that Ego should follow will **NOT** change because Ego will return to the original lane after the avoidance maneuver. Therefore, the manager does **NOT** update **root lanelet** even if the avoidance maneuver is finished. +For example, during autonomous driving, even if Ego moves into the next lane in order to avoid a parked vehicle, the target lanes that Ego should follow will **NOT** change because Ego will return to the original lane after the avoidance maneuver. Therefore, the manager does **NOT** reset the **current route lanelet**, even if the avoidance maneuver is finished. ![avoidance](../image/manager/avoidance.svg) -On the other hand, if the lane change is successful, the manager updates **root lanelet** because the lane that Ego should follow changes. +On the other hand, if the lane change is successful, the manager resets the **current route lanelet** because the lane that Ego should follow changes. ![lane_change](../image/manager/lane_change.svg) -In addition, while manual driving, the manager always updates **root lanelet** because the pilot may move to an adjacent lane regardless of the decision of the autonomous driving system. - -```c++ - /** - * @brief get reference path from root_lanelet_ centerline. - * @param planner data. - * @return reference path. - */ - BehaviorModuleOutput getReferencePath(const std::shared_ptr & data) const - { - const auto & route_handler = data->route_handler; - const auto & pose = data->self_odometry->pose.pose; - const auto p = data->parameters; - - constexpr double extra_margin = 10.0; - const auto backward_length = - std::max(p.backward_path_length, p.backward_path_length + extra_margin); - - const auto lanelet_sequence = route_handler->getLaneletSequence( - root_lanelet_.value(), pose, backward_length, std::numeric_limits::max()); - - lanelet::ConstLanelet closest_lane{}; - if (lanelet::utils::query::getClosestLaneletWithConstrains( - lanelet_sequence, pose, &closest_lane, p.ego_nearest_dist_threshold, - p.ego_nearest_yaw_threshold)) { - return utils::getReferencePath(closest_lane, data); - } - - if (lanelet::utils::query::getClosestLanelet(lanelet_sequence, pose, &closest_lane)) { - return utils::getReferencePath(closest_lane, data); - } - - return {}; // something wrong. - } -``` - -Code is [here](https://github.com/autowarefoundation/autoware.universe/blob/b1734916e3efd9786507a271e0fe829dd37476c8/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp#L202-L227) +In addition, while manually driving (i.e., either the `OperationModeState` is different from `AUTONOMOUS` or the Autoware control is not engaged), the manager resets the **current route lanelet** at each iteration because the ego vehicle may move to an adjacent lane regardless of the decision of the autonomous driving system. +The only exception is when a module is already approved, allowing testing the module's behavior while manually driving. ## Drivable area generation diff --git a/planning/behavior_path_planner/image/manager/avoidance.svg b/planning/behavior_path_planner/image/manager/avoidance.svg index b61231aa69b17..ea69166abee5f 100644 --- a/planning/behavior_path_planner/image/manager/avoidance.svg +++ b/planning/behavior_path_planner/image/manager/avoidance.svg @@ -1,80 +1,373 @@ + - - - - - - - - - -
-
-
- Ego + + + + + + + + + + + + + +
+
+
+ lanelet +
-
- - Ego - - - - - - -
-
-
- ego's driving lane + + + + + + + + + + + + +
+
+
+ lanelet +
-
- - ego's driving lane - - - - - - -
-
-
- obstacle + + + + + + + + + + + + +
+
+
+ + current route lanelet +
+
+
-
- - obstacle - + + + + + + + + + + + + +
+
+
+ lanelet +
+
+
+
+ +
+
+
+ + + + + + + + + + +
+
+
+ root reference path +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + +
+
+
+ Ego +
+
+
+
+ +
+
+
+ + + + + + + + + + +
+
+
+ lanelet sequence +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Ego +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ current route lanelet +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ obstacle +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + - - - - Text is not SVG - cannot display - - diff --git a/planning/behavior_path_planner/image/manager/current_route_lanelet.svg b/planning/behavior_path_planner/image/manager/current_route_lanelet.svg new file mode 100644 index 0000000000000..bbeaf17db79d1 --- /dev/null +++ b/planning/behavior_path_planner/image/manager/current_route_lanelet.svg @@ -0,0 +1,147 @@ + + + + + + + + + + + + + + + +
+
+
+ current route lanelet +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ driving lane data +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ root reference path +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ generate root reference path +
+
+
+
+ +
+
+
+
+
diff --git a/planning/behavior_path_planner/image/manager/lane_change.svg b/planning/behavior_path_planner/image/manager/lane_change.svg index b0a01d6b9daae..ba7cccddda523 100644 --- a/planning/behavior_path_planner/image/manager/lane_change.svg +++ b/planning/behavior_path_planner/image/manager/lane_change.svg @@ -1,212 +1,274 @@ + + - - - - - - - - - -
-
-
- ego's driving lane -
-
-
-
- ego's driving lane -
-
- - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - - -
-
-
- before lane change + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ current route lanelet +
-
- - before lane change - - - - - - -
-
-
- after lane change + + + + + + + + + + + + +
+
+
+ Ego +
-
- - after lane change - - - - - - - -
-
-
- root lanelet + + + + + + + + + + + + + + + + + + +
+
+
+ before lane change +
-
- - root lanelet - - - - - - - -
-
-
- root lanelet (UPDATED) + + + + + + + + + + + + +
+
+
+ after lane change +
-
- - root lanelet (UPDATED) - - - - - - - -
-
-
- lanelet + + + + + + + + + + + + + + + +
+
+
+
+ current route lanelet +
+
+
+ (updated) +
+
+
-
- - lanelet - - - - - - -
-
-
- lanelet + + + + + + + + + + + + + + + +
+
+
+ lanelet +
-
- - lanelet - - - - - - - -
-
-
- Ego + + + + + + + + + + + + + + + +
+
+
+ Ego +
-
- - Ego - + + + + + + + - - - - Text is not SVG - cannot display - - diff --git a/planning/behavior_path_planner/image/manager/root_lanelet.svg b/planning/behavior_path_planner/image/manager/root_lanelet.svg deleted file mode 100644 index 802eb1613e77b..0000000000000 --- a/planning/behavior_path_planner/image/manager/root_lanelet.svg +++ /dev/null @@ -1,166 +0,0 @@ - - - - - - - - - - -
-
-
- root lanelet -
-
-
-
- root lanelet -
-
- - - - -
-
-
- lanelet -
-
-
-
- lanelet -
-
- - - - -
-
-
- lanelet -
-
-
-
- lanelet -
-
- - - - -
-
-
- lanelet -
-
-
-
- lanelet -
-
- - - - - -
-
-
- root reference path -
-
-
-
- root refe... -
-
- - - - - - -
-
-
- Ego -
-
-
-
- Ego -
-
- - - - - -
-
-
- lanelet sequence -
-
-
-
- lanelet sequence -
-
- - - -
- - - - Text is not SVG - cannot display - - -
diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 5e773eba96aee..9054435a33912 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -137,7 +137,7 @@ class PlannerManager std::for_each(manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->reset(); }); approved_module_ptrs_.clear(); candidate_module_ptrs_.clear(); - root_lanelet_ = std::nullopt; + current_route_lanelet_ = std::nullopt; resetProcessingTime(); } @@ -239,13 +239,6 @@ class PlannerManager */ bool hasCandidateModules() const { return !candidate_module_ptrs_.empty(); } - /** - * @brief reset root lanelet. if there are approved modules, don't reset root lanelet. - * @param planner data. - * @details this function is called only when it is in disengage and drive by manual. - */ - void resetRootLanelet(const std::shared_ptr & data); - /** * @brief show planner manager internal condition. */ @@ -261,6 +254,18 @@ class PlannerManager */ std::shared_ptr getDebugMsg(); + /** + * @brief reset the current route lanelet to be the closest lanelet within the route + * @param planner data. + */ + void resetCurrentRouteLanelet(const std::shared_ptr & data) + { + lanelet::ConstLanelet ret{}; + data->route_handler->getClosestLaneletWithinRoute(data->self_odometry->pose.pose, &ret); + RCLCPP_DEBUG(logger_, "update current route lanelet. id:%ld", ret.id()); + current_route_lanelet_ = ret; + } + private: /** * @brief run the module and publish RTC status. @@ -300,11 +305,16 @@ class PlannerManager BehaviorModuleOutput & output, const std::shared_ptr & data) const; /** - * @brief get reference path from root_lanelet_ centerline. + * @brief get reference path from current_route_lanelet_ centerline. * @param planner data. * @return reference path. */ - BehaviorModuleOutput getReferencePath(const std::shared_ptr & data) const; + BehaviorModuleOutput getReferencePath(const std::shared_ptr & data); + + /** + * @brief publish the root reference path and current route lanelet + */ + void publishDebugRootReferencePath(const BehaviorModuleOutput & reference_path); /** * @brief stop and unregister the module from manager. @@ -361,19 +371,6 @@ class PlannerManager candidate_module_ptrs_.clear(); } - /** - * @brief get current root lanelet. the lanelet is used for reference path generation. - * @param planner data. - * @return root lanelet. - */ - lanelet::ConstLanelet updateRootLanelet(const std::shared_ptr & data) const - { - lanelet::ConstLanelet ret{}; - data->route_handler->getClosestLaneletWithinRoute(data->self_odometry->pose.pose, &ret); - RCLCPP_DEBUG(logger_, "update start lanelet. id:%ld", ret.id()); - return ret; - } - /** * @brief get manager pointer from module name. * @param module pointer. @@ -447,7 +444,7 @@ class PlannerManager static std::string getNames(const std::vector & modules); - std::optional root_lanelet_{std::nullopt}; + std::optional current_route_lanelet_{std::nullopt}; std::vector manager_ptrs_; diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index d250fd97c3aec..bc1140d627206 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -372,10 +372,8 @@ void BehaviorPathPlannerNode::run() const bool is_first_time = !(planner_data_->route_handler->isHandlerReady()); if (route_ptr) { planner_data_->route_handler->setRoute(*route_ptr); - planner_manager_->resetRootLanelet(planner_data_); - // uuid is not changed when rerouting with modified goal, - // in this case do not need to rest modules. + // in this case do not need to reset modules. const bool has_same_route_id = planner_data_->prev_route_id && route_ptr->uuid == planner_data_->prev_route_id; // Reset behavior tree when new route is received, @@ -385,14 +383,13 @@ void BehaviorPathPlannerNode::run() planner_manager_->reset(); planner_data_->prev_modified_goal.reset(); } + planner_manager_->resetCurrentRouteLanelet(planner_data_); } - const auto controlled_by_autoware_autonomously = planner_data_->operation_mode->mode == OperationModeState::AUTONOMOUS && planner_data_->operation_mode->is_autoware_control_enabled; - if (!controlled_by_autoware_autonomously) { - planner_manager_->resetRootLanelet(planner_data_); - } + if (!controlled_by_autoware_autonomously && !planner_manager_->hasApprovedModules()) + planner_manager_->resetCurrentRouteLanelet(planner_data_); // run behavior planner const auto output = planner_manager_->run(planner_data_); diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 5ec34ebbab6e3..6ac67605839e1 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -89,9 +89,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da stop_watch_.tic("total_time"); debug_info_.clear(); - if (!root_lanelet_) { - root_lanelet_ = updateRootLanelet(data); - } + if (!current_route_lanelet_) resetCurrentRouteLanelet(data); std::for_each( manager_ptrs_.begin(), manager_ptrs_.end(), [&data](const auto & m) { m->setData(data); }); @@ -416,8 +414,7 @@ BehaviorModuleOutput PlannerManager::runKeepLastModules( return output; } -BehaviorModuleOutput PlannerManager::getReferencePath( - const std::shared_ptr & data) const +BehaviorModuleOutput PlannerManager::getReferencePath(const std::shared_ptr & data) { const auto & route_handler = data->route_handler; const auto & pose = data->self_odometry->pose.pose; @@ -428,20 +425,41 @@ BehaviorModuleOutput PlannerManager::getReferencePath( std::max(p.backward_path_length, p.backward_path_length + extra_margin); const auto lanelet_sequence = route_handler->getLaneletSequence( - root_lanelet_.value(), pose, backward_length, std::numeric_limits::max()); + current_route_lanelet_.value(), pose, backward_length, p.forward_path_length); lanelet::ConstLanelet closest_lane{}; - if (lanelet::utils::query::getClosestLaneletWithConstrains( - lanelet_sequence, pose, &closest_lane, p.ego_nearest_dist_threshold, - p.ego_nearest_yaw_threshold)) { - return utils::getReferencePath(closest_lane, data); - } - - if (lanelet::utils::query::getClosestLanelet(lanelet_sequence, pose, &closest_lane)) { - return utils::getReferencePath(closest_lane, data); - } + const auto could_calculate_closest_lanelet = + lanelet::utils::query::getClosestLaneletWithConstrains( + lanelet_sequence, pose, &closest_lane, p.ego_nearest_dist_threshold, + p.ego_nearest_yaw_threshold) || + lanelet::utils::query::getClosestLanelet(lanelet_sequence, pose, &closest_lane); + + if (could_calculate_closest_lanelet) + current_route_lanelet_ = closest_lane; + else + resetCurrentRouteLanelet(data); + + const auto reference_path = utils::getReferencePath(*current_route_lanelet_, data); + publishDebugRootReferencePath(reference_path); + return reference_path; +} - return {}; // something wrong. +void PlannerManager::publishDebugRootReferencePath(const BehaviorModuleOutput & reference_path) +{ + using visualization_msgs::msg::Marker; + MarkerArray array; + Marker m = tier4_autoware_utils::createDefaultMarker( + "map", clock_.now(), "root_reference_path", 0UL, Marker::LINE_STRIP, + tier4_autoware_utils::createMarkerScale(1.0, 1.0, 1.0), + tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 1.0)); + for (const auto & p : reference_path.path.points) m.points.push_back(p.point.pose.position); + array.markers.push_back(m); + m.points.clear(); + m.id = 1UL; + for (const auto & p : current_route_lanelet_->polygon3d().basicPolygon()) + m.points.emplace_back().set__x(p.x()).set__y(p.y()).set__z(p.z()); + array.markers.push_back(m); + debug_publisher_ptr_->publish("root_reference_path", array); } SceneModulePtr PlannerManager::selectHighestPriorityModule( @@ -770,7 +788,8 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptrisRootLaneletToBeUpdated(); - })) { - root_lanelet_ = updateRootLanelet(data); - } + return m->isCurrentRouteLaneletToBeReset(); + })) + resetCurrentRouteLanelet(data); std::for_each(itr, approved_module_ptrs_.end(), [&](auto & m) { debug_info_.emplace_back(m, Action::DELETE, "From Approved"); @@ -875,62 +893,6 @@ void PlannerManager::updateCandidateModules( sortByPriority(candidate_module_ptrs_); } -void PlannerManager::resetRootLanelet(const std::shared_ptr & data) -{ - if (!root_lanelet_) { - root_lanelet_ = updateRootLanelet(data); - return; - } - - // when lane change module is running, don't update root lanelet. - const bool is_lane_change_running = std::invoke([&]() { - const auto lane_change_itr = std::find_if( - approved_module_ptrs_.begin(), approved_module_ptrs_.end(), - [](const auto & m) { return m->isRootLaneletToBeUpdated(); }); - return lane_change_itr != approved_module_ptrs_.end(); - }); - if (is_lane_change_running) { - return; - } - - const auto root_lanelet = updateRootLanelet(data); - - // if root_lanelet is not route lanelets, reset root lanelet. - // this can be caused by rerouting. - const auto & route_handler = data->route_handler; - if (!route_handler->isRouteLanelet(root_lanelet_.value())) { - root_lanelet_ = root_lanelet; - return; - } - - // check ego is in same lane - if (root_lanelet_.value().id() == root_lanelet.id()) { - return; - } - - // check ego is in next lane - const auto next_lanelets = route_handler->getRoutingGraphPtr()->following(root_lanelet_.value()); - for (const auto & next : next_lanelets) { - if (next.id() == root_lanelet.id()) { - return; - } - } - - if (!approved_module_ptrs_.empty()) { - return; - } - - for (const auto & m : candidate_module_ptrs_) { - if (m->isLockedNewModuleLaunch()) { - return; - } - } - - root_lanelet_ = root_lanelet; - - RCLCPP_INFO_EXPRESSION(logger_, verbose_, "change ego's following lane. reset."); -} - void PlannerManager::print() const { const auto get_status = [](const auto & m) { diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index 73f7448133ee7..a2481040f7548 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -259,7 +259,7 @@ class SceneModuleInterface return is_waiting_approval_ || current_state_ == ModuleStatus::WAITING_APPROVAL; } - virtual bool isRootLaneletToBeUpdated() const { return false; } + virtual bool isCurrentRouteLaneletToBeReset() const { return false; } bool isLockedNewModuleLaunch() const { return is_locked_new_module_launch_; } diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp index 22db593b45586..b25238a49333c 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp @@ -262,8 +262,8 @@ std::vector getTargetLaneletPolygons( const lanelet::ConstLanelets & lanelets, const Pose & pose, const double check_length, const std::string & target_type); -PathWithLaneId getCenterLinePathFromRootLanelet( - const lanelet::ConstLanelet & root_lanelet, +PathWithLaneId getCenterLinePathFromLanelet( + const lanelet::ConstLanelet & current_route_lanelet, const std::shared_ptr & planner_data); // route handler diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index 6fcfad2209815..e2a0db1c3f75f 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -1114,16 +1114,15 @@ std::shared_ptr generateCenterLinePath( return centerline_path; } -PathWithLaneId getCenterLinePathFromRootLanelet( - const lanelet::ConstLanelet & root_lanelet, - const std::shared_ptr & planner_data) +PathWithLaneId getCenterLinePathFromLanelet( + const lanelet::ConstLanelet & lanelet, const std::shared_ptr & planner_data) { const auto & route_handler = planner_data->route_handler; const auto & current_pose = planner_data->self_odometry->pose.pose; const auto & p = planner_data->parameters; const auto reference_lanes = route_handler->getLaneletSequence( - root_lanelet, current_pose, p.backward_path_length, p.forward_path_length); + lanelet, current_pose, p.backward_path_length, p.forward_path_length); return getCenterLinePath( *route_handler, reference_lanes, current_pose, p.backward_path_length, p.forward_path_length, diff --git a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp index f72be654d1e1e..6fac6216eb740 100644 --- a/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_sampling_planner_module/include/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -93,7 +93,7 @@ class SamplingPlannerModule : public SceneModuleInterface BehaviorModuleOutput plan() override; CandidateOutput planCandidate() const override; void updateData() override; - bool isRootLaneletToBeUpdated() const override + bool isCurrentRouteLaneletToBeReset() const override { return getCurrentStatus() == ModuleStatus::SUCCESS; } From 4917b54caa1331f016eec6c65f396765120c7f89 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Mon, 22 Apr 2024 13:34:53 +0900 Subject: [PATCH 062/192] feat: remake diagnostic graph packages (#6715) Signed-off-by: Takagi, Isamu --- .../CMakeLists.txt | 19 +- system/diagnostic_graph_aggregator/README.md | 41 +- .../config/default.param.yaml | 1 - .../doc/format/edit/remove.md | 4 +- .../doc/format/graph.md | 2 +- .../doc/format/node/remap.md | 21 - .../doc/format/{node.md => unit.md} | 18 +- .../doc/format/{node => unit}/and.md | 4 +- .../doc/format/{node => unit}/const.md | 2 +- .../doc/format/{node => unit}/diag.md | 2 +- .../doc/format/{node => unit}/link.md | 4 +- .../doc/format/{node => unit}/or.md | 4 +- .../doc/format/unit/remap.md | 21 + .../doc/message.drawio.svg | 677 ------------------ .../doc/tool/converter.md | 29 - .../doc/tool/dump.md | 36 - .../doc/tool/images/rqt_robot_monitor.png | Bin 87323 -> 0 bytes .../doc/tool/tree.md | 26 +- .../example/dummy-diags.py | 6 +- .../example/example-edit.launch.xml | 6 +- .../example/example-main.launch.xml | 4 - .../example/graph/main.yaml | 2 +- .../example/graph/module1.yaml | 11 +- .../example/graph/module2.yaml | 8 +- .../launch/converter.launch.xml | 6 - .../script/dump.py | 94 --- .../src/common/graph/config.cpp | 454 ++++++------ .../src/common/graph/config.hpp | 129 ++-- .../src/common/graph/data.cpp | 97 +++ .../src/common/graph/data.hpp | 56 ++ .../src/common/graph/debug.cpp | 75 -- .../src/common/graph/debug.hpp | 29 - .../src/common/graph/error.cpp | 58 ++ .../src/common/graph/error.hpp | 92 ++- .../src/common/graph/graph.cpp | 221 +----- .../src/common/graph/graph.hpp | 31 +- .../src/common/graph/loader.cpp | 189 +++++ .../src/common/graph/loader.hpp | 67 ++ .../src/common/graph/names.hpp | 42 ++ .../src/common/graph/types.hpp | 31 +- .../src/common/graph/units.cpp | 224 +++--- .../src/common/graph/units.hpp | 220 ++++-- .../src/node/aggregator.cpp | 58 +- .../src/node/aggregator.hpp | 16 +- .../{plugin/modes.cpp => availability.cpp} | 32 +- .../{plugin/modes.hpp => availability.hpp} | 12 +- .../src/node/converter.cpp | 133 ---- .../src/tool/plantuml.cpp | 20 +- .../src/tool/tree.cpp | 42 +- .../src/tool/utils/loader.cpp | 57 -- .../src/tool/utils/loader.hpp | 48 -- .../test/files/test1/field-not-found.yaml | 2 +- .../test/files/test1/graph-circulation.yaml | 2 +- .../test/files/test1/invalid-dict-type.yaml | 2 +- .../test/files/test1/invalid-list-type.yaml | 2 +- .../test/files/test1/path-conflict.yaml | 2 +- .../test/files/test1/path-not-found.yaml | 2 +- ...-node-type.yaml => unknown-unit-type.yaml} | 2 +- .../test/files/test2/and.yaml | 8 +- .../test/files/test2/or.yaml | 8 +- .../test/files/test2/warn-to-error.yaml | 11 +- .../test/files/test2/warn-to-ok.yaml | 11 +- .../test/src/test1.cpp | 20 +- .../test/src/test2.cpp | 23 +- system/diagnostic_graph_utils/CMakeLists.txt | 20 + system/diagnostic_graph_utils/README.md | 13 + .../doc/node/converter.md | 31 + .../diagnostic_graph_utils/doc/node/dump.md | 46 ++ .../doc/node}/images/rqt_runtime_monitor.png | Bin .../include/diagnostic_graph_utils/graph.hpp | 133 ++++ .../diagnostic_graph_utils/subscription.hpp | 53 ++ system/diagnostic_graph_utils/package.xml | 23 + .../diagnostic_graph_utils/src/lib/graph.cpp | 109 +++ .../src/lib/subscription.cpp | 67 ++ .../src/node/converter.cpp | 53 ++ .../src/node/converter.hpp | 32 +- .../diagnostic_graph_utils/src/node/dump.cpp | 145 ++++ .../diagnostic_graph_utils/src/node/dump.hpp | 52 ++ system/hazard_status_converter/package.xml | 1 + .../hazard_status_converter/src/converter.cpp | 230 ++---- .../hazard_status_converter/src/converter.hpp | 26 +- .../system_diagnostic_monitor/CMakeLists.txt | 13 + system/system_diagnostic_monitor/README.md | 16 + .../config/autoware-main.yaml | 70 ++ .../config/autoware-psim.yaml | 11 + .../config/control.yaml | 73 ++ .../config/hardware.yaml | 121 ++++ .../config/localization.yaml | 43 ++ .../system_diagnostic_monitor/config/map.yaml | 16 + .../config/perception.yaml | 16 + .../config/planning.yaml | 90 +++ .../config/system.yaml | 27 + .../config/vehicle.yaml | 16 + .../system_diagnostic_monitor.launch.xml | 7 + system/system_diagnostic_monitor/package.xml | 25 + .../script/component_state_diagnostics.py | 102 +++ .../CMakeLists.txt | 9 + tools/rqt_diagnostic_graph_monitor/README.md | 1 + .../rqt_diagnostic_graph_monitor/package.xml | 24 + tools/rqt_diagnostic_graph_monitor/plugin.xml | 16 + .../python/__init__.py | 37 + .../python/graph.py | 127 ++++ .../python/items.py | 54 ++ .../python/module.py | 61 ++ .../python/utils.py | 29 + .../python/widget.py | 85 +++ .../script/cui_diagnostic_graph_monitor | 14 + .../script/rqt_diagnostic_graph_monitor | 8 + 108 files changed, 3429 insertions(+), 2292 deletions(-) delete mode 100644 system/diagnostic_graph_aggregator/doc/format/node/remap.md rename system/diagnostic_graph_aggregator/doc/format/{node.md => unit.md} (59%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/and.md (71%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/const.md (86%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/diag.md (84%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/link.md (67%) rename system/diagnostic_graph_aggregator/doc/format/{node => unit}/or.md (66%) create mode 100644 system/diagnostic_graph_aggregator/doc/format/unit/remap.md delete mode 100644 system/diagnostic_graph_aggregator/doc/message.drawio.svg delete mode 100644 system/diagnostic_graph_aggregator/doc/tool/converter.md delete mode 100644 system/diagnostic_graph_aggregator/doc/tool/dump.md delete mode 100644 system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png delete mode 100644 system/diagnostic_graph_aggregator/launch/converter.launch.xml delete mode 100755 system/diagnostic_graph_aggregator/script/dump.py create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/data.cpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/data.hpp delete mode 100644 system/diagnostic_graph_aggregator/src/common/graph/debug.cpp delete mode 100644 system/diagnostic_graph_aggregator/src/common/graph/debug.hpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/error.cpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/loader.cpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/loader.hpp create mode 100644 system/diagnostic_graph_aggregator/src/common/graph/names.hpp rename system/diagnostic_graph_aggregator/src/node/{plugin/modes.cpp => availability.cpp} (66%) rename system/diagnostic_graph_aggregator/src/node/{plugin/modes.hpp => availability.hpp} (85%) delete mode 100644 system/diagnostic_graph_aggregator/src/node/converter.cpp delete mode 100644 system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp delete mode 100644 system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp rename system/diagnostic_graph_aggregator/test/files/test1/{unknown-node-type.yaml => unknown-unit-type.yaml} (74%) create mode 100644 system/diagnostic_graph_utils/CMakeLists.txt create mode 100644 system/diagnostic_graph_utils/README.md create mode 100644 system/diagnostic_graph_utils/doc/node/converter.md create mode 100644 system/diagnostic_graph_utils/doc/node/dump.md rename system/{diagnostic_graph_aggregator/doc/tool => diagnostic_graph_utils/doc/node}/images/rqt_runtime_monitor.png (100%) create mode 100644 system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp create mode 100644 system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp create mode 100644 system/diagnostic_graph_utils/package.xml create mode 100644 system/diagnostic_graph_utils/src/lib/graph.cpp create mode 100644 system/diagnostic_graph_utils/src/lib/subscription.cpp create mode 100644 system/diagnostic_graph_utils/src/node/converter.cpp rename system/{diagnostic_graph_aggregator => diagnostic_graph_utils}/src/node/converter.hpp (56%) create mode 100644 system/diagnostic_graph_utils/src/node/dump.cpp create mode 100644 system/diagnostic_graph_utils/src/node/dump.hpp create mode 100644 system/system_diagnostic_monitor/CMakeLists.txt create mode 100644 system/system_diagnostic_monitor/README.md create mode 100644 system/system_diagnostic_monitor/config/autoware-main.yaml create mode 100644 system/system_diagnostic_monitor/config/autoware-psim.yaml create mode 100644 system/system_diagnostic_monitor/config/control.yaml create mode 100644 system/system_diagnostic_monitor/config/hardware.yaml create mode 100644 system/system_diagnostic_monitor/config/localization.yaml create mode 100644 system/system_diagnostic_monitor/config/map.yaml create mode 100644 system/system_diagnostic_monitor/config/perception.yaml create mode 100644 system/system_diagnostic_monitor/config/planning.yaml create mode 100644 system/system_diagnostic_monitor/config/system.yaml create mode 100644 system/system_diagnostic_monitor/config/vehicle.yaml create mode 100644 system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml create mode 100644 system/system_diagnostic_monitor/package.xml create mode 100755 system/system_diagnostic_monitor/script/component_state_diagnostics.py create mode 100644 tools/rqt_diagnostic_graph_monitor/CMakeLists.txt create mode 100644 tools/rqt_diagnostic_graph_monitor/README.md create mode 100644 tools/rqt_diagnostic_graph_monitor/package.xml create mode 100644 tools/rqt_diagnostic_graph_monitor/plugin.xml create mode 100644 tools/rqt_diagnostic_graph_monitor/python/__init__.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/graph.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/items.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/module.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/utils.py create mode 100644 tools/rqt_diagnostic_graph_monitor/python/widget.py create mode 100755 tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor create mode 100755 tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor diff --git a/system/diagnostic_graph_aggregator/CMakeLists.txt b/system/diagnostic_graph_aggregator/CMakeLists.txt index 574978ec5adce..905cc07d81da1 100644 --- a/system/diagnostic_graph_aggregator/CMakeLists.txt +++ b/system/diagnostic_graph_aggregator/CMakeLists.txt @@ -5,32 +5,27 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED + src/common/graph/error.cpp + src/common/graph/data.cpp src/common/graph/config.cpp - src/common/graph/debug.cpp + src/common/graph/loader.cpp src/common/graph/graph.cpp src/common/graph/units.cpp ) ament_auto_add_executable(aggregator src/node/aggregator.cpp - src/node/plugin/modes.cpp + src/node/availability.cpp ) target_include_directories(aggregator PRIVATE src/common) -ament_auto_add_executable(converter - src/node/converter.cpp -) -target_include_directories(converter PRIVATE src/common) - ament_auto_add_executable(tree src/tool/tree.cpp - src/tool/utils/loader.cpp ) target_include_directories(tree PRIVATE src/common) ament_auto_add_executable(plantuml src/tool/plantuml.cpp - src/tool/utils/loader.cpp ) target_include_directories(plantuml PRIVATE src/common) @@ -45,10 +40,4 @@ if(BUILD_TESTING) target_include_directories(gtest_${PROJECT_NAME} PRIVATE src/common) endif() -install(PROGRAMS - script/dump.py - RENAME dump - DESTINATION lib/${PROJECT_NAME} -) - ament_auto_package(INSTALL_TO_SHARE config example launch) diff --git a/system/diagnostic_graph_aggregator/README.md b/system/diagnostic_graph_aggregator/README.md index cc49ed88ba98f..c0cd78e0610c2 100644 --- a/system/diagnostic_graph_aggregator/README.md +++ b/system/diagnostic_graph_aggregator/README.md @@ -3,20 +3,25 @@ ## Overview The diagnostic graph aggregator node subscribes to diagnostic array and publishes aggregated diagnostic graph. -As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional unit. -Diagnostic status dependencies will be directed acyclic graph (DAG). +As shown in the diagram below, this node introduces extra diagnostic status for intermediate functional units. ![overview](./doc/overview.drawio.svg) -## Diagnostics graph message +## Diagnostic graph structures -The diagnostics graph that this node outputs is a combination of diagnostic status and connections between them. -This graph consists of an array of diagnostic nodes, and each node has a status and links. -This link contains an index indicating the position of the node in the graph. -Therefore, the graph can be reconstructed from the array of nodes using links. -The following is an example of a message representing the graph in the overview section. +The diagnostic graph is actually a set of fault tree analysis (FTA) for each operation mode of Autoware. +Since the status of the same node may be referenced by multiple nodes, the overall structure is a directed acyclic graph (DAG). +Each node in the diagnostic graph represents the diagnostic status of a specific functional unit, including the input diagnostics. +So we define this as "unit", and call the unit corresponding to the input diagnosis "diag unit" and the others "node unit". -![message](./doc/message.drawio.svg) +Every unit has an error level that is the same as DiagnosticStatus, a unit type, and optionally a unit path. +In addition, every diag unit has a message, a hardware_id, and values that are the same as DiagnosticStatus. +The unit type represents how the unit status is calculated, such as AND or OR. +The unit path is any unique string that represents the functionality of the unit. + +NOTE: This feature is currently under development. +The diagnostic graph also supports "link" because there are cases where connections between units have additional status. +For example, it is natural that many functional units will have an error status until initialization is complete. ## Operation mode availability @@ -34,11 +39,13 @@ This feature breaks the generality of the graph and may be changed to a plugin o ## Interfaces -| Interface Type | Interface Name | Data Type | Description | -| -------------- | ------------------------------------- | ------------------------------------------------- | ------------------ | -| subscription | `/diagnostics` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics input. | -| publisher | `/diagnostics_graph` | `tier4_system_msgs/msg/DiagnosticGraph` | Diagnostics graph. | -| publisher | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | mode availability. | +| Interface Type | Interface Name | Data Type | Description | +| -------------- | ------------------------------------- | ------------------------------------------------- | ---------------------------------- | +| subscription | `/diagnostics` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics input. | +| publisher | `/diagnostics_graph/unknowns` | `diagnostic_msgs/msg/DiagnosticArray` | Diagnostics not included in graph. | +| publisher | `/diagnostics_graph/struct` | `tier4_system_msgs/msg/DiagGraphStruct` | Diagnostic graph (static part). | +| publisher | `/diagnostics_graph/status` | `tier4_system_msgs/msg/DiagGraphStatus` | Diagnostic graph (dynamic part). | +| publisher | `/system/operation_mode/availability` | `tier4_system_msgs/msg/OperationModeAvailability` | Operation mode availability. | ## Parameters @@ -49,7 +56,6 @@ This feature breaks the generality of the graph and may be changed to a plugin o | `input_qos_depth` | `uint` | QoS depth of input array topic. | | `graph_qos_depth` | `uint` | QoS depth of output graph topic. | | `use_operation_mode_availability` | `bool` | Use operation mode availability publisher. | -| `use_debug_mode` | `bool` | Use debug output to stdout. | ## Examples @@ -73,13 +79,12 @@ ros2 launch diagnostic_graph_aggregator example-edit.launch.xml ## Debug tools -- [dump](./doc/tool/dump.md) -- [converter](./doc/tool/converter.md) - [tree](./doc/tool/tree.md) +- [diagnostic_graph_utils](../diagnostic_graph_utils/README.md) ## Graph file format - [graph](./doc/format/graph.md) - [path](./doc/format/path.md) -- [node](./doc/format/node.md) +- [unit](./doc/format/unit.md) - [edit](./doc/format/edit.md) diff --git a/system/diagnostic_graph_aggregator/config/default.param.yaml b/system/diagnostic_graph_aggregator/config/default.param.yaml index 2660396bd86df..4fb2303bbd898 100644 --- a/system/diagnostic_graph_aggregator/config/default.param.yaml +++ b/system/diagnostic_graph_aggregator/config/default.param.yaml @@ -1,7 +1,6 @@ /**: ros__parameters: use_operation_mode_availability: true - use_debug_mode: false rate: 10.0 input_qos_depth: 1000 graph_qos_depth: 1 diff --git a/system/diagnostic_graph_aggregator/doc/format/edit/remove.md b/system/diagnostic_graph_aggregator/doc/format/edit/remove.md index 6cd4b25e98828..9a9847e5c6dd3 100644 --- a/system/diagnostic_graph_aggregator/doc/format/edit/remove.md +++ b/system/diagnostic_graph_aggregator/doc/format/edit/remove.md @@ -1,10 +1,10 @@ # Remove -The `remove` object is a edit that removes other nodes. +The `remove` object is a edit that removes other units. ## Format | Name | Type | Required | Description | | ------ | -------- | -------- | ---------------------------------------- | | `type` | `string` | yes | Specify `remove` when using this object. | -| `path` | `string` | yes | The path of the node to remove. | +| `path` | `string` | yes | The path of the unit to remove. | diff --git a/system/diagnostic_graph_aggregator/doc/format/graph.md b/system/diagnostic_graph_aggregator/doc/format/graph.md index 9dace8a2f0e6d..efe85c6e6aaff 100644 --- a/system/diagnostic_graph_aggregator/doc/format/graph.md +++ b/system/diagnostic_graph_aggregator/doc/format/graph.md @@ -7,5 +7,5 @@ The graph object is the top level structure that makes up the configuration file | Name | Type | Required | Description | | ------- | -------------------------------------- | -------- | ------------------------------------------------- | | `files` | list\[[path](./path.md)\] | no | List of path objects for importing subgraphs. | -| `nodes` | list\[[node](./node.md)\] | no | List of node objects that make up the graph. | +| `units` | list\[[unit](./unit.md)\] | no | List of unit objects that make up the graph. | | `edits` | list\[[edit](./edit.md)\] | no | List of edit objects to partially edit the graph. | diff --git a/system/diagnostic_graph_aggregator/doc/format/node/remap.md b/system/diagnostic_graph_aggregator/doc/format/node/remap.md deleted file mode 100644 index abf0d11fae12d..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/format/node/remap.md +++ /dev/null @@ -1,21 +0,0 @@ -# Constant - -!!! warning - - This object is under development. It may be removed in the future. - -The remapping object is a node that converts error levels. - -## Format - -| Name | Type | Required | Description | -| ------ | -------------------------------------- | -------- | ---------------------------------------------------- | -| `type` | `string` | yes | Specify remapping type when using this object. | -| `list` | list\[[node](../node.md)] | yes | List of input node objects. The list size must be 1. | - -## Remapping types - -The supported remapping types are as follows. - -- `warn-to-ok` -- `warn-to-error` diff --git a/system/diagnostic_graph_aggregator/doc/format/node.md b/system/diagnostic_graph_aggregator/doc/format/unit.md similarity index 59% rename from system/diagnostic_graph_aggregator/doc/format/node.md rename to system/diagnostic_graph_aggregator/doc/format/unit.md index 0f4b52b9b8a72..6df4671259f9d 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit.md @@ -1,24 +1,24 @@ -# Node +# Unit -The `node` is a base object that makes up the diagnostic graph. -Any derived object can be used where a node object is required. +The `unit` is a base object that makes up the diagnostic graph. +Any derived object can be used where a unit object is required. ## Format | Name | Type | Required | Description | | ------ | -------- | -------- | ------------------------------------------------- | | `type` | `string` | yes | The string indicating the type of derived object. | -| `path` | `string` | no | Any string to reference from other nodes. | +| `path` | `string` | no | Any string to reference from other units. | ## Derived objects -- [diag](./node/diag.md) -- [and](./node/and.md) -- [or](./node/or.md) -- [remapping](./node/remap.md) +- [diag](./unit/diag.md) +- [and](./unit/and.md) +- [or](./unit/or.md) +- [remapping](./unit/remap.md) - warn-to-ok - warn-to-error -- [constant](./node/const.md) +- [constant](./unit/const.md) - ok - warn - error diff --git a/system/diagnostic_graph_aggregator/doc/format/node/and.md b/system/diagnostic_graph_aggregator/doc/format/unit/and.md similarity index 71% rename from system/diagnostic_graph_aggregator/doc/format/node/and.md rename to system/diagnostic_graph_aggregator/doc/format/unit/and.md index 562018bf0995b..ea14d5101a53c 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/and.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/and.md @@ -1,6 +1,6 @@ # And -The `and` object is a node that is evaluated as the maximum error level of the input nodes. +The `and` object is a unit that is evaluated as the maximum error level of the input units. Note that error level `stale` is treated as `error`. ## Format @@ -8,7 +8,7 @@ Note that error level `stale` is treated as `error`. | Name | Type | Required | Description | | ------ | -------------------------------------- | -------- | ------------------------------------------------------------ | | `type` | string | yes | Specify `and` or `short-circuit-and` when using this object. | -| `list` | list\[[node](../node.md)] | yes | List of input node objects. | +| `list` | list\[[unit](../unit.md)] | yes | List of input unit objects. | ## Short-circuit evaluation diff --git a/system/diagnostic_graph_aggregator/doc/format/node/const.md b/system/diagnostic_graph_aggregator/doc/format/unit/const.md similarity index 86% rename from system/diagnostic_graph_aggregator/doc/format/node/const.md rename to system/diagnostic_graph_aggregator/doc/format/unit/const.md index 13495be6cdbda..dac095814a616 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/const.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/const.md @@ -1,6 +1,6 @@ # Constant -The constant object is a node with a fixed error level. +The constant object is a unit with a fixed error level. ## Format diff --git a/system/diagnostic_graph_aggregator/doc/format/node/diag.md b/system/diagnostic_graph_aggregator/doc/format/unit/diag.md similarity index 84% rename from system/diagnostic_graph_aggregator/doc/format/node/diag.md rename to system/diagnostic_graph_aggregator/doc/format/unit/diag.md index beba8ed0df5b4..377284322d9a9 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/diag.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/diag.md @@ -1,6 +1,6 @@ # Diag -The `diag` object is a node that refers to a specific status within the source diagnostics. +The `diag` object is a unit that refers to a specific status within the source diagnostics. ## Format diff --git a/system/diagnostic_graph_aggregator/doc/format/node/link.md b/system/diagnostic_graph_aggregator/doc/format/unit/link.md similarity index 67% rename from system/diagnostic_graph_aggregator/doc/format/node/link.md rename to system/diagnostic_graph_aggregator/doc/format/unit/link.md index c23aa92575e54..3649bc49df112 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/link.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/link.md @@ -1,10 +1,10 @@ # Link -The `link` object is a node that refers to other nodes. +The `link` object is a unit that refers to another unit. ## Format | Name | Type | Required | Description | | ------ | -------- | -------- | -------------------------------------- | | `type` | `string` | yes | Specify `link` when using this object. | -| `link` | `string` | yes | The path of the node to reference. | +| `link` | `string` | yes | The path of the unit to reference. | diff --git a/system/diagnostic_graph_aggregator/doc/format/node/or.md b/system/diagnostic_graph_aggregator/doc/format/unit/or.md similarity index 66% rename from system/diagnostic_graph_aggregator/doc/format/node/or.md rename to system/diagnostic_graph_aggregator/doc/format/unit/or.md index 74e94ffd628e3..66d0d5fa75125 100644 --- a/system/diagnostic_graph_aggregator/doc/format/node/or.md +++ b/system/diagnostic_graph_aggregator/doc/format/unit/or.md @@ -1,6 +1,6 @@ # Or -The `or` object is a node that is evaluated as the minimum error level of the input nodes. +The `or` object is a unit that is evaluated as the minimum error level of the input units. Note that error level `stale` is treated as `error`. ## Format @@ -8,4 +8,4 @@ Note that error level `stale` is treated as `error`. | Name | Type | Required | Description | | ------ | -------------------------------------- | -------- | ------------------------------------ | | `type` | string | yes | Specify `or` when using this object. | -| `list` | list\[[node](../node.md)] | yes | List of input node objects. | +| `list` | list\[[unit](../unit.md)] | yes | List of input unit objects. | diff --git a/system/diagnostic_graph_aggregator/doc/format/unit/remap.md b/system/diagnostic_graph_aggregator/doc/format/unit/remap.md new file mode 100644 index 0000000000000..35bbf9cb5b408 --- /dev/null +++ b/system/diagnostic_graph_aggregator/doc/format/unit/remap.md @@ -0,0 +1,21 @@ +# Constant + +!!! warning + + This object is under development. It may be removed in the future. + +The remapping object is a unit that converts error levels. + +## Format + +| Name | Type | Required | Description | +| ------ | ------------------------------- | -------- | ---------------------------------------------- | +| `type` | `string` | yes | Specify remapping type when using this object. | +| `item` | [unit](../unit.md) | yes | Input unit object. | + +## Remapping types + +The supported remapping types are as follows. + +- `warn-to-ok` +- `warn-to-error` diff --git a/system/diagnostic_graph_aggregator/doc/message.drawio.svg b/system/diagnostic_graph_aggregator/doc/message.drawio.svg deleted file mode 100644 index aef836dccf235..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/message.drawio.svg +++ /dev/null @@ -1,677 +0,0 @@ - - - - - - - -
-
-
- Top LiDAR -
-
-
-
- Top LiDAR -
-
- - - - -
-
-
- Front LiDAR -
-
-
-
- Front LiDAR -
-
- - - - -
-
-
- obstacle detection -
-
-
-
- obstacle detection -
-
- - - - -
-
-
- pose estimation -
-
-
-
- pose estimation -
-
- - - - -
-
-
- autonomous -
-
-
-
- autonomous -
-
- - - - -
-
-
- remote -
-
-
-
- remote -
-
- - - - -
-
-
- remote command -
-
-
-
- remote command -
-
- - - - -
-
-
- local -
-
-
-
- local -
-
- - - - -
-
-
- joystick command -
-
-
-
- joystick command -
-
- - - - -
-
-
- stop -
-
-
-
- stop -
-
- - - - -
-
-
- Front radar -
-
-
-
- Front radar -
-
- - - - -
-
-
- MRM -
-
-
-
- MRM -
-
- - - - -
-
-
- index -
-
-
-
- index -
-
- - - - -
-
-
- status -
-
-
-
- status -
-
- - - - -
-
-
- 0 -
-
-
-
- 0 -
-
- - - - -
-
-
- 1 -
-
-
-
- 1 -
-
- - - - -
-
-
- 2 -
-
-
-
- 2 -
-
- - - - -
-
-
- 3 -
-
-
-
- 3 -
-
- - - - -
-
-
- 4 -
-
-
-
- 4 -
-
- - - - -
-
-
- 5 -
-
-
-
- 5 -
-
- - - - -
-
-
- 6 -
-
-
-
- 6 -
-
- - - - -
-
-
- 7 -
-
-
-
- 7 -
-
- - - - -
-
-
- 8 -
-
-
-
- 8 -
-
- - - - -
-
-
- 9 -
-
-
-
- 9 -
-
- - - - -
-
-
- 10 -
-
-
-
- 10 -
-
- - - - -
-
-
- 11 -
-
-
-
- 11 -
-
- - - - -
-
-
- links -
-
-
-
- links -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- 10, 11 -
-
-
-
- 10, 11 -
-
- - - - -
-
-
- 9 -
-
-
-
- 9 -
-
- - - - -
-
-
- 5, 6 -
-
-
-
- 5, 6 -
-
- - - - -
-
-
- 8 -
-
-
-
- 8 -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- 7 -
-
-
-
- 7 -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
- - - - -
-
-
- - -
-
-
-
- - -
-
-
- - - - Text is not SVG - cannot display - - -
diff --git a/system/diagnostic_graph_aggregator/doc/tool/converter.md b/system/diagnostic_graph_aggregator/doc/tool/converter.md deleted file mode 100644 index 2351bc1e01054..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/tool/converter.md +++ /dev/null @@ -1,29 +0,0 @@ -# Converter tool - -This tool converts `/diagnostics_graph` to `/diagnostics_agg` so it can be read by tools such as `rqt_runtime_monitor` and `rqt_robot_monitor`. - -## Usage - -```bash -ros2 launch diagnostic_graph_aggregator converter.launch.xml complement:=false -``` - -The `complement` argument specifies whether to add an intermediate path that does not exist. -This means that if the graph contains paths `/A/B` and `/A/B/C/D/E`, the intermediate paths `/A`, `/A/B/C` and `/A/B/C/D` will be added. -This is useful for tree view in `rqt_robot_monitor`. The completed node has an error level of `STALE`. - -## Examples - -```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml complement:=false -ros2 run rqt_runtime_monitor rqt_runtime_monitor --ros-args -r diagnostics:=diagnostics_agg -``` - -![rqt_runtime_monitor](./images/rqt_runtime_monitor.png) - -```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml complement:=true -ros2 run rqt_robot_monitor rqt_robot_monitor -``` - -![rqt_robot_monitor](./images/rqt_robot_monitor.png) diff --git a/system/diagnostic_graph_aggregator/doc/tool/dump.md b/system/diagnostic_graph_aggregator/doc/tool/dump.md deleted file mode 100644 index 33f05ff866603..0000000000000 --- a/system/diagnostic_graph_aggregator/doc/tool/dump.md +++ /dev/null @@ -1,36 +0,0 @@ -# Dump tool - -This tool displays `/diagnostics_graph` in table format. - -## Usage - -```bash -ros2 run diagnostic_graph_aggregator dump -``` - -## Examples - -```bash -ros2 launch diagnostic_graph_aggregator example-main.launch.xml -ros2 run diagnostic_graph_aggregator dump -``` - -```txt -| ----- | ----- | -------------------------------- | ----- | -| index | level | name | links | -| ----- | ----- | -------------------------------- | ----- | -| 0 | OK | /sensing/radars/front | | -| 1 | OK | /sensing/lidars/front | | -| 2 | ERROR | /sensing/lidars/top | | -| 3 | OK | /functions/obstacle_detection | 1 0 | -| 4 | ERROR | /functions/pose_estimation | 2 | -| 5 | OK | /external/remote_command | | -| 6 | OK | /external/joystick_command | | -| 7 | ERROR | /autoware/modes/pull_over | 4 3 | -| 8 | OK | /autoware/modes/comfortable_stop | 3 | -| 9 | OK | /autoware/modes/emergency_stop | | -| 10 | OK | /autoware/modes/remote | 5 | -| 11 | OK | /autoware/modes/local | 6 | -| 12 | ERROR | /autoware/modes/autonomous | 4 3 | -| 13 | OK | /autoware/modes/stop | | -``` diff --git a/system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png b/system/diagnostic_graph_aggregator/doc/tool/images/rqt_robot_monitor.png deleted file mode 100644 index e4aa169f02addf3c6a60972c41bb4aee228e06b8..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 87323 zcma%iWk6h8&n{BjiaWGGp}4!XxKp6G>l7c{wP>;84lPb`_rcv-26uNG+_}^DJ)G~# zpPN6!Y}V|ZtYjs5lI-wLO41mpB&aYjFc`8j5~?sTuU27T;F*yTp;vgUFcY93ubjkW zKO;lQ8`&%j`kmNWQp;J*-on|<*wGvYU}tY@&g^9BXl`!j^u^x!1ioDax`@;AvzD{C zqq(uOrM=yo&z834(2FoI9Bdq1TTQiWoZA^;>|EQ)`ES@cwo?N+__o4AxOsO9IUxsQT*jH!fI7Y(`WQ=_-FzhMZkf z!p^{NvlJc|lD{r6C-P7yyfC=)0B(R~QL#5c&N$zevk%g&c?D|#z5qHD$khlxqS1yB zb$WlR$oL`q#`y?{0Q(=Jm(k!c)SVOBzVxt&;TsdNKp&_^UFEnJs4&)Z9ha2&hfsAa z0(9?onlR=kKs=3nlf&+y+L2*Lv)NR&A4y9|a}H+bDG-l7ftU3XXAC7qOsu)f)u<~R z$HRwYQq4Ob_K_PO5bc_lIIPnZvf?9V{=Iv3{0t0B;Sc5p-Me~lC{XH7_mdMYXwLCQ z=WRyVKcq(=Obkj*_0H5MCtM6nn|rX=4z@`Z9#?!XO*;-2weV)4`iC5g&jeOG}p)$CXco<5ehVOc#zyt zB85#>ze!SGO@dha{Xl*V*9b$|p|lN4Mr;5dZ2R&gRX&dBz+t;J1lI59c`)o9^lt*r zwKeY8SWHPRKQ2nX)zg60)A*^|cgl?X9-Jo|Z_yos(bDFy(TD%|@Sx|~vSdLtH2Jb+ zoAbun1O^o|3Q*DpdEb`L82UZ>4JWf2A|Ar8^NFIe*vg|VOoZAK2Ad!jQ%^gR93?r_ zz?&b;RIGTe_k=4azE{a9S~%+4fEcCG7Fe2SYe(JSzUaB>jwmEx)S}y>W(~*(6v!mw zcieQoK3-aRJ|7p|i6`mtkj0pV$b1;P0~3>_d_n2OPB&Ku*wB@-MSN-*@gMSyfDflm4K}FqnbvL1uzBdYc6Z!IZG8Hd8<#jYI z*{yGE$jZre{YUXh=K7V@0695SyM}u`n0$dVgV33SeCNFhNm_*zw(N6QJrc%lYDYxAMqOqT44^DjRaO0>rgXWvyF&!7W#(&J z*jNg_y;lLUco|0_;Qg~XvEC6eG5s5m&HG1+n9!RW_o>)^0kUG;{(P)e4z%?*`Y_2; zyA8EF(a!cb*x0dtf{a<>eq}~aCpB7rdL_Bf8@qSk!ou`87wz0YQl91sJXmS_18U@Z zoHdc!^ODr7Zw^+E^c(@&cN_8&5}Q`$`59{iS#4y>AO*S$n{7Ypm9_W^U(+Lp^SHF; z!#cxXJ&F&f>yHa{L)GqLq&mIhZ_ zpZn)Z4+9?}N4_?qsWy*@HC}Y@K#hBo!K|0rY_prPW=JhugfcqMtJr!c`^dV=^}L5* z`bbDTuqnJw5ciAU63H@1=gx@Se7XPRbolOzQZMcIK=}3_CK8{UvuGQf^G&;vy;%YL z{CX>m2=)`#@l)<(Di^L8thkWR_>=X4e>q63oOr`?oYst4yI7Mb?5~3 zMiADR^rB{YY!lnmqdh;4n3EIR3)jKY5?9xk!Zj*@1)z#+BJp4!wRXw7tJ7>Ln;aFo z08$MrCGHdyd?d;$DZAybO7_ejwG48fFk0WwQA@`%O=uZ>9DOp))U1WLSc*>qS z6d{d|?^iO?F=}eyynLPp4&!2=u)#1XG2bR?BeiM~We9nqV<8ZB=ugeCtvsRlyvB}g zZBEeTu8E6_3(U?o449799zdK6bwbb%9ks}X`qfBEQHq#;aj26Bm^`(8xPe?8FWu*y zGGn=zjZCnhuJDm|m|umA1oA;epl8}PPV&8`=A5xLJ^7|V0N49Wz(MKLHU~i#Tsm5kRjY-Hgl19_vS6%B@kdMx%p+whcz54i> z`8KaqZcnnBhU1;xK~5S^pZ6NY*tR5u#^V!`r7NWHo%zK}$G&%$MY1wFy8KfcOT!~7 zD{O%Kx6%DQIN3I@KT*Z?=^t+_r!%bE!(^3>5Q)YH%f4f?;@tvG%w2R2t$EMs!%JI` zk24D<-g^(|Hb}1W*JZAV5_jIXRM}+QBZb-@E76yS99TQ<_t2}_-&FFo+2EX?eECoq zhvNp!*pjlEySZM zj69W`*cq^IU(K6@FLPvP*ZUh^zZ+OlS{z(@fPlUDL) zi;e8LcS!BJboOM;cb#z7PaHq}YMfCry%ND~Klo;pB@leCfL=w5*YMa~v6grv4D~BB zwTIi>Eg7~3j4o#AYsYQZ%Mo_6qtfL3=9a0^{=>(k(4<3kHWJ6#`xf`O!m4|Ny(&9x zbcYjjl{P3OrgiW~dN+IWQ>fR<{nv;myvoG<;o;kqd-`}MU-oktyIi8tY|r>Yogm=F zb!;o2EAs-KvYAUi;7eN4@7b zyh7h*0}c14ye~EdnZ7xEDtrdCF46|i*$WNs9GJ{C+953$xKw5jG-WwGa>)H&%U5m` zJ$u!T<(F1Ps#Iy!>v}g`E}Qf+aJmDP#M`yc8_y*=>T=WcW+7%ar9 zdG0V)qIIvddH3aZQwGtEDcGY<&yX{k6GA|w1Sj86U<#&s-SVw?<$2&DYLG8?{!h6p zvM=IyJn4)b9Z-m!hR+I|#a=-@WFwHqm&2BgTdQv z8A~g$9X2WPgLlp)YfH$UUib<;6_ul6<-(CRi_rJ%DQWOL(}2KP$&UjWN>G0GIrEY0 zWa)Omuq1iY5SU{OHu-6km=x-?V~0m54AOw4hu`J~zKuFemg0xaY&5MBb@x;H6~c!1 z&o+p{mN>t0Z!>DxIiLhe-@a$yC#+r@(b;}<$Vg)r<7)FyCMe%{~(Eds-cyYJ7Xiz4#C03iI%6LFi#H?!Ga>#SR$VfXA?tU zfyc}IjA^O%mw;mI@#0xCg@@whGPF9M4&YV}`QKfs^xcxw$bR+`M%(fBFrjW;5_V1z z4hp}=Vn4W_tMw`yRd?{Aj>na`(D6s3EQFO}*IAxUt?R=KOn3XyjD|iOIw|UbD=SmW zM)edmb2{|*#Ku~G?OyA!YapCu$a8HGHl!Y}E}<6vX!LQ$xMq%s4`@^Xs~bVU+_)A( z%CVH(FHoH}&0H7aEXV<(uR;8qW;sIrjooU*qL28yZ+Grt%Fds1%m#uPNl9k@G(X2X zmuQ9%DEtZP;a*isM;F}5)jB2v|}{hF-! zc)R{_Hr|9U@k^mh)19;Dg$tq^OFRkcWD5+sG!vnL%yS(q9`&WhWMn$$lE(FHm8q$tlg8hKMQ_lugi@n1 z-tE~5X{&bj=RkY3FIHHXj3)#F$;->rQzd0dj_~(~`I|s@b#)=aSj&tP+YN>_XN%+*P~|$Hp|QQ5IzCe~z`E&5K2d)KvUGzylhI+4kue_&wkVn(lW;_U(d&> z*qUcmulI5LG;+M=Zs8~Y1QsQPvOlQt>C-2WlrMfy7$@`=^#_Teu>yY9ce=`)EeI~o zzT^J__~7v)*Z7o_l#MQQ*A{Y7QPB*g!u`gezcNw0JJCZg zOf$D$OfYKs#|+agm@*G{ZCqyD-$kue{0~P>eKvE|!96_^4C=pvMw41d=@r3dC(CU% z3-wV&MMaY{Oc4%h(~yl3j0-!%WIC^g9~z(eU`Xr9EtcxVFUUp0MaZq33=8LH(Q|*_ zIltQ!@R#R2Ja2jsG8He6KAHj%V6BiO?&SQV0g26_h^VN1)qFW~5p&!l*=>4yCm67xS`7mz<5Y{2sUmCiCL>e`0W`gnuK_b! z%v}}}T=3di!e$T`yEso2x6BmaScMlubYjtC5xfx z;S&go)8SSXTRtowdHVtIySlqkuqr;xk&HGzHnES);m0I)->ND-jV?0N$qqW@8(gv8 zB^l0Sjck%pO#4m*eTxdMS~Y8K+cqu`QBP)Y^Bs4!&r(i_9t=P@Vc!*XnzM(q;41Nb ziWS97Po5}xkssfbBDGh(%u2Op`*N~qA#&`|V55Y8fj?eyu?lLSzG-!_#xaW{9oGe? z{UL11)K_B$|@VG9DO z*gk1$ZJzi!zorXDyH7X)$|ljb>aJ(_9dr63vpzmWg!loY?ZTG~p-#GwKF|xm+oscV zNbhmFfO1BEx=1hTS~;s`mDe~e&lu@={MOTIae!zg|1FN^cXGyXp9m>V7cZM6N>!5! zJd08h2fKC;AhFsu8NGk}Lipi1HRH1vrTU@2N054U3}B;JzDe)J0cfTuGa5YFzAGVk zpgg%Q8|!4HFc}E4rLn;AP|$Bp6d^yTGCQ(MvY$ojI2JG5y&7@9YdsUCAm=CcPr77y zO}5#e)Yh-v{)mj_YTYy0tIG=>C<${+GxKPjy-95@d9xE;ZWQZb|@_Y%TIGXx;Z%EYL>La@&UNd_% za&sX`vHRz1Xh@{-RXHCMV~A+GPv)PR=*p*1USh6YeBXsw2buJEEAB2WAs>W4wEoFH z@`a9-Ch!xioUxYoFdFD3eV~z959^f6TSg)8dvc+>rMMnQ{I~U%bp|jgc};M{gk8* zvssJ>gf0%oR*6jw3KSQ<0&r~sYzWvEgSMe+N zBcw3yU~V|iJ2Yk7+~nC^mLzWPEss_*MX=JAb&k&ug z1h3mHxUHYL_6l`v;|mrow({g3?HODbD=cjXls-6-7M}AXvy7MgfD>A>Mn*(zxqj|i z2~|?7=bB{FO%Pb4Aer*TVRUgP%8tH&BMw72UK;DO$3Ok%_|*04rq=v4)J>Jy1HZz@ zHK9e+FCqH!k-ey|Lz>`^$D$sEjSCXu>VgH#xQIKhxvf#+-f&!np~+Ly(`QavPR}i7 z^vsp7w36sW*kfuX^QTW2OU{ReF$~5cHqoW>;DRj!NmczrB_AMVp4QcX@q zep`7F-Fxjn<+WFT@ta?9_NIZWRNDwQMn6_ZqZ|C~$rocU7#6y|qin(|m54YMeu|Rk zd{n?yX4n5syMvDZV$NVk#eirwQvh_^B==&`!Q;SN+|BHf*c&sZhXEUMx%APFJ>aTi zft?5o9jovxPIC8H19+y!e1-nuQE%3U=fPW#h$yu_o>7D2&%*Pzk++qO#jC`hQd=f` zPTq!aRsBCDWIlvAEuf$?qv)Ed+1HFp8{eX?NTp#y_e{DFUO*BwHm5S~ z7ReF*1jj;D0(cdqI>{Q6TWG?c*_s}oZ-qnQU4JcwO~nx6@a05hz0`!?tq*zijwdtx z$>?p3(u2~M9XI-uStr***^#xwd1Z3iJ?Db59IO5{$GD7D+CoyP(GC9VIbws113iAX zkN>0#n{rig>wJl?2V6P{L+znCj_F1;^<;_8w|vs8{OCX@0c4aj^YJyJD{|rPoJ*wB zbC)&XY}Eor&JclVe?YuM;;>|SyyZuL*7=DQaA7>ykGYXQj zg`RvzcWV57RcP?*@8h4@3}F{1qY@qNnt->Bz`Mpu!TL|!-UJ#GzBVD9BbnSXatg3K z03uibUF~P{Uz1j1?H|$h?xwYpYCRK^KF+Abb!YHxyyLdy3>PHEFt^6ZkPV(r-5`@? zl5_v_0S>ndC_za_I|t_nUn*gul<}rg3;78knvfxdboaR}mW5r|R%r*l-J%|N$bRCp^%*X;rZ&Ifjq}Hcc^sM`*mnHv^UXF zId`*B0ne9-dFU$0k_=zi9k67Vt6}EAb0i?P#PIH1Gp-Dox0Njd175A2%lq5wjCAyV zjf{izDUqt~!Eg_kV%80J(43&v z>3#ivV;k*qO-+LbXD0lZ)L?zgsada~`$;G_4W6~cPI=YC^}VHyVB&|x&MoMl2$L=6 zQVdybJJW6U!qyFxbjKraHJ%>G!Hm}hw(68{R&_gB>$ta1Gf`yFR)*&zYvgk~>P1r% zqKFjC&t6*zN`56VRWgUcRB4A0#yE|Jsji(qB`)UFCu;U;dr_?Hlr>U?s#P_z@aVVn zEYS&i7uqkDv>&f9682MPB+%dM*5`X-lC}$eRyU?} z%PbWUp@f!&nf1$Yz`4~k&twS+)BwBfM6-YKjgO&e)*ZTB*l35(w5N!lxN_4|Qh46p zIVU;jJ0beqvM63fu7i^5il(lx`!bsn$E7cG?TkQx{BD>onKpdx$8CiMe*b3iP!QK$ zezHNQb=vHa>*6tn_COubL?W9iswqFhrlPn>^kx2-piiSTB+1Y%8 zepp;g54HS*9~t2hk1RCr^?&2d8T3U%j*LAVGf>RiDb?MA_Tb8Cyel3U;tq#=<(7eQ z>bU#w@x!mSnqv5im5hnp+xSP_vxn>&OtlFF-Qb8#<6mY0j`NJWLsF6?S7zu`IGBQF zD4J3)1#`69snf*!H=w43tzJ)5$AF(};*LxWO6$*p@4xkyp|j~r9F=XAt)d};eRXF> z{tBO7byLNNc@=hXk4O2Ac?Nb7OVpd!6AJ2X8Tc4}p*Aef^BbPv{{t3d8BOo6j(U1~ zRm%1FZR!`JWH=P#g}ts`MGoCl5`O$Ix+=ZtS-!tzy9NS!t{(6>TRiMX+xm!UXPp-2S@D7 zm))jQ<~HF_Wlk4}#L!mr*fael?8W656+N(o z0ISZ{ehT?YZ@^if=)|7Pjl3X42^zrv4v}Nw{=ZOllL5lt_A*rbtzt+=$A@2^i{t(W zbxJ(ZJCb+w_V)hmgbHzkJTLc!2%!zO|I(Rq+yM;c8ycECqj5VASy|VwV8UeKqdFoD z?<)p1s;t$za{Ma5LdTX#Y@^>hc`T{lr4GaoQDOq}he}DMLgJqzniGKdWBe}?Y@Rje zICXf``}FH`Tb-^3>AR1&%Z(g2m4++9bwF#Mc@F2Z8=#CtkGb|;U0;1K95k4Cc(i5H z-+tTGD@>(MIy6TqeWyF1&6r&=!I!3Yn4X0uoBw&G(;SzQdc{z=h> zVjMF`DQc&lFuU*|pqOdF$)Rg|>0Hph{T%lodSpGGFncSQ-48ec$LT5v7WIw3Z@xC^ zAQi0^n8!#V(?5O7`dk}^FB)Uiu>^l>drhwq<&#=NC90 z3Fu!kpGfjBA~->(=%%DAo4n$A=vXD}ucBqSJm4&8HyLPg;w$>-{Gxl!U`B$DrUq8? z{o;DAV%=m5TUSooIXez1VEym+^IXNRo~D{0^;wJ4Ib=`A!Vh8#hgTm|FFa|51pTqx)N`-FSm2_dWVHoaj*BX6Cakt_->=6xJ*}PIY$xw&2^@5H zYWRLK=u>zl8oMPMJ#{psc+ATF-?@HGEM8ldC25W<3X8JD`tyz5pE=Jm&eC+ABwORH z_r@0bx(x6u)#j&}f=P3Jh07-L6DuRcEeSt3@*QZ&Odz$k8D}us7f$xEY~GrYrprn0 zOpAwFcjThcl>J?0gC95+2>tp|HQB#ezRr9}D%96dd%5gfnKFkUuDqX?Si=s|8;tuW z%@5D?+!L^M!V&9+)=t#Y(xTEQHt&#ctZ_{1oi}3d({Qy5$m#^HHr9{Z z*MLqlGzBd4VmRL~u1yL^mcFQgvoEX#Y0RfIoFz$?%}hJz^&8vnwHj!kH7}`3_ai%@ ztTr3H42ATKjM|5`w(P+6dkk!pR7*%{)PyA(TcXGW{4C0w^HD!;`OmpFBaRM7cPu?SSdy9s@Gm7vuYq6t;{p9?T<12}x z9B|fFRe(M9kQmQ)HY>Wqdyul_gz9kB+d|59tsj-g#KO!_cYguCXs(`g`EA7PLf zdNH59SMoln=@6g_qfXke-9vaV2d4jS?x46kGu6GXJY925V3>4bFB|g<7H>kV>_v{yaobXup&)DK$g)V>*u-#^u#jiwRXDEi50s0Z=<&@cSyUGEK_?>d&_xr0Ox;FTGu zu1C9H_46UMb7~!kyNqHhMEZU7`0M6Fvo5gafG$NcZNhuTCTZl{R5~K-bMgMq+v9Al zX10{N%XE&~uyx*-U{%tK--y5+Y#UJstTm+*;3`r)ny)L?FGL|1th2b^%s)IOnmt^F zxI=V|Ug75ldZgsi#mj`r_cUmDc?$Zirav$AgqyJ*bKYyUK;F=MFn7zXIy=KjMiBPS zc!jhL?^Kyx&mrJO!iYsIgo!w21m*Fq$8kzHNWFHk-|y+nURjUdtJ|F{<>EnybJR_@ zcdbCFHw-C`b#XC=wsQy3Y7V&soMxe0SZNk28jE4SI*D|0z953@6`a1i zVoLaxBuK61q~Z`#q5Q0Dn17f7%T@L%#1Z3o3*6MgmpG#?YMb8(`3a(FpULy>R&*{Eb9X$y9< z9r-%}-a=K{jn_4{!y0JEBC!!}Gw? zLUV_4YaWgF9lj(3c6LGmmLRXP%2U-CW_^B%!x9`n_wHV1tt3$YzcYy-*LZiz?G?fEKV58TCW{yJA3etScDJa;cd+$s9Tl*3q<+YHN9) z%%Y!m;Iv8aFAt63dLkjldZ*$qU6NqBmQ!Y1PIPKzTLypJCdBtI4T2_DXl4HY_`dZ& zrF!gJ-V`AZ4j5=&*1TEI1*f!0@&o&&S&=-xIT$~V0ECW^IU)mwR~8f&Wo2n-X$uzO zWFQ71{vBuEGZH*OW)0eGihajMYlqxqvh?4#B~Z2Z#|>5G`c9rp4gPj|pcK0(M+t&e zNaYBoS1Zs{O}{0D-B}uHq~JZ{(hJS3VFy$6I$EVYwvCHhKENnRKi5%ZG5Xer=lM%6Zj_kawlP z)2+<2_knQlh^S%)i+IEBpgFg3*DK$rTL3g8>?Lwpr$HhYT3B3EV7%hDRdZH@~qlPk&; z{yNOMAs?0#?X<2-I=lRN=Um6Sey|e#$9FT-nXx{ec*T2A*{Q*}!V}HyvL!~B0l`Fz zz4XD6=77=p=WH|O%}K!>`r|sRRpUfmXZS7Iswb>MIm}7(04`B}DEo+L=Vi z6pqrpfGbN!#p_;Sk{eQxt=g!@VeZ27rRzU64zK#EFh){^5LAML+`K>8}Z&g3I?E?~MtMEW|uB?2FA=|zPf`4_S& zI&sIH3(s6yZf}bhh$-2FG()aC7cUGAPHxE@a77Ee=J1s4ZWBAZXC~Zw&e2<&sPf5+ zseM_B0?vzb{Voe?T}6k|j>2oP_=kc5uGx<6c-nro+q015LB3H-5mT~GSbRtPHFG$pBGo;xQMGn?9$ z^hCP5suh%2ypoX&qSl^xm-Cc6L})SmQn28jW8S(nKzjXS!o03HrPP(zPs|0wc@?h| zDTYktNg-SJkH{j`-_)z@I%r&n$p~ma=MUp%?)jJr*b6}ru{ryJx;?Vn?cnSRxX`oC z#`j7}K8Z*L>RX~dB{=S8wBq;PQUmAW9y=euDz3DTn3{^;?){m+q5t~df^w{1st^K@ zB8KiVeCF$noH6*skkhk_6=qDwhnQGB@<7Nyp@gPE_?il*|UWh-zPw~#p#?byZW%_{k*HJ+3rKTdyxhC zEMGRg6z_8RaaRlYl|ril)^Yss&Dw_WBL5wyoi$n5M~q**L3!Mi7W2mw!ou%$I}KjX zh&{c_$<2j$wq5N0*~sxRs7MwM#Z+l^hd5Qt+3*NaD2HT=0w=%7Cf`=DpPUGu&Itqy zH;5=uZn(9E8?@3RrSKkmbx~&Yl+8#RQ3sYU4S~Im5h>c2qZbrtc|;J}PY;@!+!Q;8 zMPiWby_ry?u=lx+m1z9?<$+*2_gs4S^_)3n1ggh&^Q9{-0sV&fDK+Ik&I+7E!A7{+sK!TjjKNG5yZ3cXR5czHkGK*C_>hIn;x$gSliwL-s!kvY^L7UKn(pN zm6SDm-PY!OEV%A@Bskal1@b5XgzP^EkNtUsI6PnHN(qf%3kEBHrgYmB5A(pPadDNs)F1*+OKU)b#^FbBXNmjMR(&d5V}`tE^y61ZD~ptnbm zoWbR?Nx{uXr-l*zn=jhXY&(Sdj;JtRfeBjdePt4z{kPcbn^%{7D{+=2xsSa!FWTk` zTLVAOo>PqlJ81lh$2-0kj0p7U(-n``aY}!bB&e_s<6p|QJJIYk*LEMz0?RQ+<3NXn z`x~oD&vC~Qf-IKG3GBXiC0sqaK*qB(t49TKr}y}!G(2JrsWWLXXH39u2KRj&|>7K8v{D882gHj+B&jSzetYDeTvUiuPfccYHu<_w{4EUp^Yg zdMC2pKZt>1&bU&V+Nr_Bl#9%5_oXM5wf}TPj8~G>bz|cvd03@387qO**2nBBBbgfX zk9W5Vga71Q<%r?o;Y_;qhk-K_0AX$6@d$aMi1l|oo}ymYG#TXd7OTiCvh>dx%YfIP zN`$ZR{31{Mj%2ou6WJP`yKbIKK4jZlt%{qljAi!hnTGOj%50u)r+P#BPA2`1rPD&@ zfzwvX_B&wjb3bO{i86-HL8M#jicAu2`L(mMu_%2X_x;RgBLp{dg@l6~D0Ifyn_a`R z_dX|OMp}{c*m%RJ*{4#Y&2zMUTZ2nabQMOryEqY=SHN7n%XV|W812Y)G8cK>ejELc z`|c0ZVrMaVI=_B3OQI0tjrq?^i=%y2hF=tQLv*Lohs5=dBJn=>_CL+dw5_H}#CG$D z*4t1rqLqGp8O^!z9Iten5=uIB#YHrtu-NPA<)UCqCDaWu;w6Lj(4ORqC$=f5PHsc8 z=hgGvGEKDlpDer_-&rLqi&p=W%5DxZs^%d>adDf`(`AOn$2z8neEH<$z=3@zltIvR*Cgwo(CU|X7A3mGARuQc6eS;UNRU)5`Bmd5Ddc#%jwSTCRPy+ z#NnY+DQm{LyCUT?B$bu)vJxirZj>UjHGGHzpI~hr>nP(M>Be5gV3_Vk*;ZTfvS#PV zEbG-yLgrL{5D+A(1YS`S{^`RG8|45;QPin4pC5Rq-iUPDMXir*D1GBS9+kJ(_~~4k zJezp(=e*Y?qa!BG4b&-ECN7iO7V|9pC+(>Pw<@$@ZSJ|X^HO9+00zdrhsooeFw)kl{yE@tONB#6&PRNgwpBQP$aCas(LrbalhR%#YEbWU+=2!l@x{h zrQ)wd#=;Jr|7MxxR&&Ajmbyv}#TI5T#(9Vid%S?=QP{~$cGJFHsVEZsFQFYY^gI-B zfv3!;uZL;gu@E#crod?W_AP3;(*8Y49Ht{FQ$piRb}a^=b`L23Ls@w5}pWxG$j z?za^85wqwK@5BXA`Cw4-W04&a6E6f12YiLFmiyy{ZLxG-dyvs9Jv;bDs8LLSeD0+K z>im&_g$qJ^4G&TNjBJP^0Rebpt)CFb{Ead;+wEHHUk4DjJx?s)4@N{tb!;UrC9l32 z8^dtRT0^CoO@z1z`gVTY8B2ef{efPQic-ku$q<_YM$vi~SeeZ~5?$s+zp&5J6;+#U ziS*PNe98F_s&Taa?HNQB$66nT*?OUZZs>CX!&@P&BvU6^vYSC|-M+53@YOgT5wn{GX*p4GR!= zp}X6Edelu)P;@jreD;e#3#z06 zXqv+`ICj89KcB)+Sxx6D)LG4va&=TQ39+-&lpBl=oq%#@g|B~q8A)N(|Mg#ap@V+) z<;^g5zM+^2Lhj#Dg+0GlyD}dqGCFv*X(a_)`g2|gST$Jp7kiwito(#8^Lu`jOJ@3~ zzCab1Ut)#Xm1_4mHz}z&E&!&5GnYH`r{U<B`eJ*T}ry2xKVY%vortaqRHd ztG9D78I*42F=w^-d9{8xH)aEP8kr(fVkttz)w-WD@}14-`AJ*>_PbHQOy$q)AD+(6 z%6kTsgg2lTMROh7D!A`CY4j2}cfauP%%rIZgBBT1H z6%ZSt#|^t!?yynh`goaFsvEj>8HkdEl9VcNH`>)z%`{fvuzDF+>%oaXoCug{bl|VI z?=1&(rcHBI?5o{mc6PL{y&+6i1G&f(Plm}uV5`1|qptJMHGF_vS5_-q8ylQ~4=+&^oTzW&E|lu73P$_z`e=3g0$0D6@)O z_m)B8)of+*Uf(LA-Pj67>#>(=v6 z;Rwyj6;Py;wMA<`^M=nwB%QlCzO(b$a<7~{hJ>I$7x03d z`cKz1Ip@|&<cPXpjvPiLJOoIL}Q1(Ikj zPlP~^&SYvcbgH0BeW8hVQtpV^w;t3RNXlK)%^aaS3TDg4FeJ+mKIJ9tm>kVfx7>fu zmP}`pl~hOX(Q?$N=<8vH%yVYC0!w2LVImefhZeUTpfi;pvw;LSi5s%R=OiuCF&=Pz zwnljJy8`sJk*4Dt;Bg0Q!rso|E|RD>-KX4izMGZvu`)an=zp7iu>q-~D{>k)LaY-Q z8UVDL+fr#k7>OT$-}fxt5g7VDaPcDc#rp?97bCPkj>=*gWg5@)%rpUh+yDMW$tr3P zkHLz$oqR-58O?q@dVkvm{(9|8(jTEX#%8KXZ?~tF`MtK&E{mKgT|IXC@|%&_?p*Lr zxanx&^~6Ctk3ic4X2r!XnW2DOz)ovT*n&{REeiK8eX`MIH zb?fzlCwV?~pGw8S?o|t~d8C8~NKepn6enh!Pww&4ampsg*Bct#Z_h^)+8!mB$tL5# zxt@@RJosdDJCXl-TIf*!(LRZjvumB&@KCRr2_R-zQA>Jag(*unTO;O`$@icc>o}t1 zprd9vu00j*x+bvGjqzs=tcS%=+C=hCx30%F)87V5V!-7>ujeCXmObNG-r1y>3xGGf zSLQsr@(hZ?XB4PJI%z6xgat0ku>1jjeN|pXXY}Pm6xl zMQuE%%AO>=Mkf09;rp@|8nQ$_gAD%1Z-I9@A6{Mf2j@_fhSL5pg2jA4fsIZMrtsVRLk_E8w+2wFMWOwqrmi(p|GWqQk0!t;SJ`j;)AGgRH6k@<6}t}T!b{t zwVDDW`LNAAHA{-~hmg$vIFEuaeUOij(rne5$ROIvr@an4McTRTk491b9-yHu12X6f zQ{QF@>{S;{x{4(*tP%!8b>$@Yd91?P2m3ndH&P8Diac$vyQnRSbgYQH4%!DYZ1p|b zc|O3jg<=&t`SAY0v19Y68`1e~`6#`0bo#U3zc3X5y%)im`teCP^9Azw`q&>U+& zz(#Kl_Zy3fV&2|5{_YQjUtT6VJ?k5&_alhb<5f9z9eM}pIkBBwJEJ~N zlo_4<>VF<}PkuOWR>}9(6nU^@O}0ymO?7asH~U21*Qt#`e3x6JZgi0vnG&<|oJkh%=ONhHTsMvb!*QI6J8qHe zn(&Q1Oq_UD)@-YvMn;{CKeL^Jm%W8SRBQ0opGqD-ffih0N&T^VuciQBR4OJ%!MfDJ zPIQ>-dOTrbsTe&dfvP zm7ciwF84TGZ7HOWe7^2-8w=7eBfMWf=UO4J(?1&K8!u(~=+-Dh>&@uA{?$Ww?p9GZ zr~lIEaDO-bm12Vt%ZDx6%W%U>eE8;zt>Li#RGtFzUKY1~zR~GK#F!Zd*Zy?#v(x-H zgyD*ZPgVHr;{n7ubVDJtIz>ErqAI@^Xm(&QwqP%6*B=}; zlF^o`7CwgOSxPV^M~fT(J?Rl<%pv5`Nki>9Dttuy0ylnTPia(4(|VX}r@o5eCxT0a zZn-yrC%x06+gE?gf<-T$Krx!bdfPGDK<>@msa#TN^vKO0nRQh&90WMjRg0J%i5t{u zikfAUPlyhJ+h>nyraiGS9CcQ&ZDOccdOt3f*B#m}`>!%a45ppZf5IEfpl0At4We-` z-9r1UeTE@wC!i>%%5}f(*Nr8`J3rO@fZ0NGWxMcELXYYX5&`?;{duidfr#Y)vwcRH z0yo!(vLgYHjR_UsvAfKRJ*m$t*4R4Cy7HZgag;Nuez@7AP8T~3yB^W`(Tx=H*KzFF zlkDwjv9bU@<-UPKOU^l%@AKxbd<#kvt0iKOpV2P>gUm#{&o%R|6M$6f_LTYB;G-V< zC;#6QlJsPgf!ZNAXtNn~eVLyM-${<$8?;P%izkUGWm4TzG7?t8ezDD?!uIoW3 z9a`fCQ&Ea$Q-;!)w<1d~5uT)wc<>qtWk`ksK?Q%EY6;@xji zA3W|hI1ld$3I%*mcF29fp-&rPFq*L3z4qU;`4X1ev2j$PU!0Vj%;NtOl6Rk*7zB^j|cv$5? zgsCfagP7vo>Oij&7o=7gR-%{s{eQ9d)^Bk%U6?QuAOs7+Jwb!JYaqd45+GP`cXu1y zCAbU{T!Xv2JHg#u26uMyydlrK-|n~j4{ZOybq&+g-Bn#x=bXFlb01A$lZ+{{&(SQN}7%87E_?G zjcc~#CVuPYBSSG&K12sJH~#X9M^RD1dr?w4d$oAoV)5tO+)t=ubfs})YSR=LdE=>C%g>|{V!_e8$0UJW$3a1vIn?84VX$JT( z6pi(~VMj`e<{cl8Lm?H{xwy#x?QZ_ife;k|0hO@VfrR_jik!T>ZF$3U^w|5v*Axhm zK={u=jI*fV%e}13le?at5fT=AZg<_6)K~x9O6UU#Pe6?JO*rdEsw}YdgP2pj z$7^;eoE054nlsLnjcktCGA?dr3)xE%E;4JzeMk1}52dCIscrg{3#N^-Gs6;m54{g{ zoyGwiWjT_%G_Hv@RV07!(vnPk3B>@aw-bbWXxzb?EQEvExzAx!&kE*YX=g{Fq#=|`34QnjRxw=ecAK_s-kQ@Or);epKSo$bWr$1klMT&3T;(nGBSUuvUwMnh~mPNa#^X~4~T z2c~dd!_oaR1ULpX2m5c&{dn>OVy;1vM)vXy~or1M8cgD2^S6dP-nL%lXEk z`wUe$t>0P>2Ikm6VxT7Qr|zZ)vIeXMh6+Gx7m>um+4>*6itlket^7|IH=i}Te+T}VWXtyYbN zx-`Em)VTSsZ%E`Bo8TkJS~)FVjp^afxojr7Ql`>)dHKZz?Fmh@dC}i9hCGz-tnzss zxp&`4d{ygkA;qHoXaQeYIEZE%9{F9TtIw=k&l}*eB&BA4~riiq&4b zU#v9$yf++{OHA%&ZjXO)*8UL_7333>r67GH^`*g`2}<<9!~h_hyB)EZcb10{Q3F|67ACJogu;4|#w2uUTC>ON zM`R};CL`Nvr`}ci*Zf_=VDZ-XU>qP_Q1)tNH=k;!-y0dwXNP-gHz}MhGFJ17w3+sP z&({KsM*j1SLqmb{?a6(S=gF6pL?*7wR`F2e}0DMtG5d#fXr|>!?DvhB8{`;%%u5tBXQ^+t6Qe8`@K88TpnetkT&cX|-Aq z@w)n?Lye&-z^W%V+|ukJEhr`zE4 z<#E2PZ&tT-r7FS$2%}HIeD&r^_q7D#XliZ?0-U} zf!2JHKEW28s-#Q31ID|+CSy^9?%BR5m9{P45Z$;-u@7=I2gNk3_6PeXMo65~aXAS;WP;hWKE&dD{rP)HC*>kJG+TzsgEfiAiE~(5 z{8KLu+1=Qh0}_Nd^M2Cg^>WdTj|yWg)7_1uvYo1F{P=J_*x2(Pu^9i+9oFY7m zluRvRqSuNib0_9j)$N?E9^UkY!LQ|-w7UCL0cCqVa0kKCUG$}-?6lYvlpKhzZ9J8h zS2)Wa6`^EhyE79yT=niGI0rSBOV-vHPbm$4@)E<>2-8_6LF5b+S^9#Ww#oYIBl~$* zd-3-tXVQ;n4mbsOnkje(f%iV_h(r163pSg)6|=|=1eg1#OtwNONt`^x$+OyoAu?~b zdQCjkF%rR6MCB+Jh3v_l@(VM1I`e%Wln0kCe0_A&e$Of!>e5Q zXk{Pq4Y~hAJ-;7pbp4l~dWe#f1Oe_du6FOu>$)EQm=01KTFTb6&@S9^i(wTGsvmQw zn*&rF#^W1as1^&!L`g!*dn{blcmLVqJ39`nXyS%!=ICX+|rn z>s}M~jM5bluiwaNZGF{l!ZClbGPm-@+Rx%^mpZ*WTqrUZtd99d;h(cllx!_T4g4t; zEzKSB@&%;-wp--wsG zuIxvqFwtkGu^Eyys-Nj8{@I`>wE;kqdZ|^)$&ZeXX6KeIYSyi|xU5#7($mvny;3|; zN)2YsRBHHA3XqS~h%6nEM#7bSYZ~NHJ2+dd!w(DPjWqTtkF6_e*VkQjuj9bcjLqCH zm!SrWm##ON++dlabh${Ph1JYhD3z3w&Bh4%PjI?GUvrGw8K#JhWSdz2QX&h+Tfy$ z*cZ(d%sBb^IX=f+^u#^aWut-|JT-WGUC)2;<#{^xF7}^6FYq(ht*Ecu?v?R%Z^(X* zZVojbk7wq*-}&Ux62L_H*Wa>atNC|t24^!5W_U=(_TBTM_0dN7zdY``_ag{a(bz}n zn?IbTRcp7k(f*!C-g9aP#p$r6sFqAeM>vlf-Pbvj_>JW9`?J%%LDCKJ)0O5&Dxeo2 z-%!hqf{G&$DlV)r`9%iSH&+W@|J50IR6N!D=UOliO}h(~bo*E8D{f}^g^p>NBai^V z*1mb*_3&Gl_4vk?Yx3|rfi=)MHqe)yw%V5A5ZaFNdDuEDhAVz>f89O2ASvWw$-_=P zkR&(~9c9qdXGY3Eow5l`P6zHw{s2HpNaJpoFzf{YNwb1IIO*^sd98N`S zIe^sBVz3!RjtupUjn@z;-g5cVX!%%V>!8k;sFVaW!uymYb)7?Uz0!5*D{uxcU#&Kn z+`sqM;h0e1U_P!V%_+Q1lVMA!2==bbFO-lac6l9He171{N5BAlT$sSpi1SmVfyHf0 zV~s^bUhF_%E9?+3Px-DA_(%asFX}DS1+E|XB+x!jR8pk{1~*n@*Z{I^FPT)t6%Q4l z?-6}}nOhGYDI-O+K~;2;0U5>6?=XOF(INPk9j}Bj$0MI}5Q!quR<^^}gqBBf4pqSF z2+Dr`bnP4Bk7awAOM~FOJ{)<0bRY`V8+mB5phe9Vp{K8YJIpS8x-J`r#x0I24#QrN zZb|G?Tv^ zHugMk$fq|Gsq+AwG()~O4S1u)EP_ScqQb#gR26v9hypjxjMja-ot?SpX)&T>FvND2 zivB@ojuYwDiM*VtE}kfbCZih^jM7;;HN4^y(p||1rYs1GfUTr0umnD_1hWX7bfoN)7g^K!Ovx&WXaN{ARVSsLtOT^&+mtfNajRj`05gy zp6UrSb3Og+*9A98ts8&=N8k^~y%(uPn8Im*cx$$?R%>Q&9~`9<8!X0!g#{~Hq?LR| zoj`!(kXaWNRqo)&!C5#?If)wYzCz+B&UN+Ek$utFTlJfh+$ObpV~PwsLqjA=sAvoZ zi|3JBlgb#f8+r~kMo`T?RmQ8a`XA&e7wiQ z?N|#Cczbm`vep%HT))VN(F%=Mn1m1izjxzU;X7P^^@$e#i&bwK{-3aF{lsb4R26ma zBdbX1YsDRiid%L08L0YW#D3e%!zMuqmG@DUVlyA6_`S5*Q?osF; z$D~(Kv%%reXu5b2Wx2+9!k@!@Zo$66nPCfWs)<93$$Hho->yhn%OfK6U^o0 zpQYy^7pMcqSTXarQ%3gk&VrbiOx~JSHApo!1f2*JxY$AraO4{PMIFLzM@{ri6T;Pmv`t!ME}N!77}!D6Jyt)>2w;I3q3LUe?hByPuWS z=Xt0<=2n`|$3a-&8aG!>{+8bnV7Yo@2Cr%;&~$Rc}!S>ncfzhzfAyPw744c^O{mwD!~D+2`R2eU~oy zWqW(XnWY65L>5*dwUpD9RY3RcjwV(C`FU1FnJWHN{Uk0f9;Xzw=**fZ?Hdq)fsfDg zdIoU@$~0~$&VB%57~@g)zXZ4~726TlCAckFa3e26^{7-AOQ(NI0X6mvt%XM{hd~5h z0nOK&Zy_#A!|h6Z#|cWSc=$UO9>19xJuBO;KK!A`2dejAr?0^(HZuv&e(wgib91wa z)*a2P>h5`t^ke0%9uEWDsYR4N!&KatWi_34u@O1LJGgtAU%4uGXbFqiZLy!o{+j+{ zT8Q6p)wvN2_%I#7A3V=mC(pM*A%N%{1R%at{(D;UogufpO`q_{U@V!Bh~HZ z6y;w4xV-6A!SDO>ajA4vxZeE3KtW6UFI;nj6z<;^*1eyX|6F4>8wFbbL%e}dZ^Zh? zcvq4*EmOa(e@8eNO&5V=a|j-2Key(d9-@mzGk>@B-V>7l(Bl)?*rUgyjq87u`{#^a z*dI_wz?i>jpOFY6&je*&l9AZ3>T{r$2dvjRv$K`D=j!)RH>jK#sP(b7fPz`)Th?PG)bAXoNvdE zd`}y?*Nc;SY7l1)3Ge3igNC|5Vs6N07+w=3n>SO~?^Vs>cG4@ZyLSeB6ESG8-53H@ zWbuHGK=pxMN}|MNcesXtU!C0XJ@n7^3t)#M|C#^&mokpNvv8YX#ek?SJydf|kwIri z2SS-lYj&lBT(mQUDr3dL``0<#1}~&UyFL5nnzTJvr-Da1a>uEe5_^3L6E8Jf;YA2AUHG4<@O=MN3{Du)Okx-&t{ulb23l zFB$GQNFTRB?l{<=93?&w1N_P5wJ z)?IAfmI#Ib%huQyM~EEJX|_TBOYEYj5ZMv_;4bS(`T>sDpKq8MG-jz%Y(a*s&bOov zlvugW5nktr^kMOR9}b#tq*G5cIg-!PB|{9InqA+wSs1Da>hj6QA9blVzB8{E1oZHD zB`_RmZ)Q*wp)Pl~RYG7^_mt*$A8Hd@(QDE^$y2hh9=zXrqfdQc(VnmT4Ia(Je>tDs zP4LDwj>OjnaK5&gD)WBJ0Vn_YMfJkkDTOd86FZ0U(5;Ue^M);4l~Ok$Hu0wEj^;zw~37x7`D>0Qx7a`$tz(B86af4+}#&PE_Dx%2lY1@N6Gj@Ea zpo?qz?xirfD{3DQuOox)_Hffy1Gnv#7H+qUNUdqk4}7R%HurjdUhJYx@ol-7pt->) zck`WJCRowTOvnh#pzg7|CN7sSd=a#fm)IUN5hG0=+D=s+(s(BnK|Yj}U*1DX3H+x< z0Bf@w4FU%dS>Nhgow1i1s3k+cMsC+J>cY$s6Ani+B0>$x|t1kXQ10&!}_p+6y zmiAB11$rbOofvfTkio$93i?OCSLkMf_!3#ptO5J>KTdW1@*jt>FU7u6nm9soc;R%a z8|3n*0~Fe2ZO-u?X*A-*9v8a3LKfd|>h@@3=5%}$*Btmd7@f@D(Ftz9U;Sl%E+Fh~^8o)0T@+AHC{v-cF%M8$+@@D;gJ`t9Ld{Eztp{zkbm@5x9}VL6_oPc-8h-zZvTeTV${ zslD{%1q!B|lUSfQcm*yr^cDC^DKu6vDX7=ML=EBOqdZT{)r@r?nG4+S+cQ;Jh->sbRCIr$tA@U!;=p)4&C*M*W+K3cm zQtvn($`vsTE3?ohB`2%DV@4rB)fpk)UN|~NM8S8r*G%(wOCtRA%i{f&9lF}lnnGxd zlTMV|`<;E!g`c}YUY7!RaEeuh?$(Qj|8rmnO{6?RDVTlbAZvk#& zEZc_^^1cQ3+97!Oeidaeh2J_AsC|G6zujJWXA{fLw@zI;s52xhC^WxAZm^}%$kR`G{SA&l@&b2t7I z`6!4uxpjrG@-Us&N)&~X#;qk(4z2vVk_T7&Tcd7GfFQ8ZBuu+w99m(J$9%%W_Zapa zB?DqWBpRzyZpsoD92RmYZOALn4+q0lzRuM;cE(D46Bc6#LMAVX=tO2q3$erXi7TJz zaB(``X67)Q%{kqoYjF?wanbr)v!ga{&Xm;Upbc*dR4}xE2Tu!s?%=qt@d%0V4qzz> zWi>Ws_24|o5c>R1!-*;s7;tOb;R4a`WIni4JioC;Olw(+7`ev=YebX&I= za7Hy7rfX5=JF(cWPn!2gE;{5X`rCU|_lXWY-IndXhMS-3xkvPFA-fy06}n*&TH8yk zS>L?#uvEiQY=PQmyH0Nyh_yC@hsYPpe=6uOrmmZHqCYANc+~_vNQTw8d>I*W+ZTXZ z=%1)ep*<74;Y4zq8>>ACyKpdgQsukpq%Z(zwl?RHM`fT@Y)z+RDK^S9IEPY{LYw0^ z$W^)PN^&w)Mkk*zeoN`6h^mWu zJ+i84h~e-azd`ABY$3ur4whIHf8q>MALe@nC{9;CDxl_2H^x+`0O9t_v=%QOSb@#? z*=6wT4_O8Jofljf3kTf&bP2-;f}|4Fv*J88@#;VdQ~lrKu)mMKv!iktROwFxpDR3h zsqnw1$Htiqvp!gKa=8Zr@8NN1A^5(j48Ds6e&$%H71x zO2jQ!D3~~Z-R=S(GwYv2?KNA+kdKt}F`tNt#-owfp7q?{9WZGWKcL6M5R5m;7<)^1 z%RpRZah0Ky(K$Cv<>0+AVPio94k7~hRkr{En8D!~^KsOc2(i`sN3oc4Jw>p7J|(O4 zBO3`%?97PhXw&JwnicJ*odGhuvC3KVxu!diV@;@OG4pp7JR>cw1eli(M*Ks`jZ6fn z#S0W2(q$YZOzfMiq5@yz7`_Z+7EFXWcE6Ax?2&Ds0_<|x;f&SF=MTIWKm=3p(|M<9 zpsaRbP%8(s>5jIDeHmjH?7F?wZW}CK05p-eldf?dZK&5OKg# znoa&)=dyjC-L&1I|K@ zKZNF^H>j~xt0Fyp0NOce?RhXk5*@@Bbx;!zJMJE3N&6i|_hKE7ta}U2)#Z7eu`4zjBi+?zidM}L zSp%KLlGCEqeN&CA;KFCELpz4|g@LcmZdVl!OC`XTUjmm@?UbWho;@W_=e?`2irxw$m4A z+RSOirEv5NfCB*#9!!yh@Ye9 z-sPy88prCZp)XL=Wx73tXrg}u^fUuVX8-KcbaKdl1*~bg|0)EN zb^qT_p2Z6wi`f6`vFEY&@qY)@{24IZn|j+=w2F{9@b~P;$a13A$$WV#&Yr)yN~aN7 z)OpWdAZeXA^uH?C403+~YtpC?%+}v3Q5zrTYb<*p0$8bnzwL8xhat>;pK|EC{jFqu zTbKg%dOPE_4*aa&Up*xaK&!gA-158st|b<^5Y4FB?A0pU3a?yYR$cV1TInBvB@%(k z)X9M{?Kc9lu{wdN@MjLANB+T`{xnD5_0?V+{Wlw1!oLsuB+l)Epmw%3WNS)D>fE0$ z67Uig)nlgP4@?xvXEIsvb#{pp5}jz{aubL4E{FZb$&mSv|6IaG6QYSxhxixuv1$4L zem27T@8@~N6$$zb_uN4Xj8}@#hBFcX8H&Z!iw0$m2%ukj3t>mNk8MlXYHXQyvh6~8 z{tk*8xL-U@bV0l4TUk%3<)q|eX!WwQW+b7tmW&Jq1phHSQ(S)bb=2$uSXNU$6V6-U zNGG?-@I-#%E*LH4Ab#v_jsYoL{|_eT9_^R$I;GlH4c?>y7jMMc9oDaasK^~L>ln;y z4$P)ApF_(A@Ft6(xGg_y6qwSi90VkQrR4>XaRJxA!Z8Oze}>Ieg_?~=-YhDWx{Avr zlPp>NL7&Lc8Umn(`^Qj1g7Qyrx3MkPKE})OnRtc940#Sf`)g}y>A~aInDW}LGvq$r zux~b95VUnsQ~)AfZ8y0G-5ePIS7e5Eq&}7V&l{~vB!sh?E+y7qU;D_@%$l5)9{o~q zELKeFo6V@_hqW>+H(oG;BC%tpT#EO!w7fkzp}{O?bYjyjdFmwZsHK*nN&S7>w5~_y zOsk`jIw{!;NRoNjSRwK19 z;Q$)?)YY4#^cM{&O}ngy^|b-9A#tTVZUhJul5gg&>~H;FtQx?GEqGwdB=!!LW+q6* zWS2G|=0cdFe0g{txl<<(8^>KCS4+zSDPbU@x|=@0BsYR0#At`2m{1Chho?=h+pDemS*^CxL2b+vF&bvVK@ zuUxIq@!9=}Q_<<}OG(mPAKFh$0uotPq~0LN7`WXipqlZBMsF6P zo@<`-w}>3Tz1VvXqa>XnqJ?ZK;2de$D0*@eTHZbcdmNpelSnEM6x-DC{>6EEgFznZ}W8@ zTlUOE?92C~IPDp$-W$TKq5~#KE8#kFELX(0-|!_}BWSn8{Wy%EV4BUa!iAqPSJvfV zJu7V4VXv`k6o>8ehnMde{Ahf}l%+M^~y&PpU`K zB&$bOFA|b-fzDe47~|>Y7mJFAtFgh@Md563qQ7suh2g!aqpD7(^l_<8!(&CJlD~PM{QdZqobDcZjKc%`rn%W}U~XL%}SEMhd5M zzHR9CNgc**F${awLpsRec@u=;s$DDaUU-M_G3gUoQsm^{5KZphVSpaGW^(btgWoM@ zoG4|E&!bGa1tr%VH0abZy6ZI=$9b{{l?Vr?RcO5KT- zReB7!tDn4n2sfU{;y$5Xv@p*yOowYP*JO;ONnPJxc(`rV1YRX!)`1i6z|^GOO}&Gj zjEPlw*dByBx8a+F?X66knZiDEoq&{1(0&nS-ehWtDBp)4vu_K22xdccln+mCoitcC z6(;ij7%k%JhCENH?Gyj5WMDZv;8&4wEX~(Exhe)gHR@__hE@2SbOOCr#cUaYR<&}g zLB~<=oIk7nUKN$rEFt!h06_Sj+uFY9tC_qY;MT;WYtH$|{(XcFjGzzWZYvjZ8jp$CZP4S283CB@pix4=FWS z6l8Pp{^{sF{%%^i|LSkng{bZNefl`G{?9RZ83k8&@^w$ZE@X*M`#CJK|CTlh9Hm4-Cn6G;Zt} zYGX;yHzPxhRAVVEW!`DuBiI#=M@%Sc(g>bmXD%~(yQ;nrY{G93p^_`bH17TZjL68S zC)5sNbcuy)P4wf>43!M#yXssG3=pC`+?goh!` zOu~!!O)z_XRQ=<+Y&JvYHF;{qm&kH&nR!A|n)V}LY)vG161W~-b%Dhh2hdm~& z)_Krrjh*(+H4dJA4-_S!Z}Sk5D8G&ju7surJUU=$BQ;szq;?toXGgxbN(<^kGSV7@ z#$`wxiV-Fe5r32O*_JciJ~dZ=@4J0kw;H?gH6 zI&37@t0M|Fwo0LG&@i1GE6P1gW9_xl;jk>((5{4MNe>p#_UNF}wgqtfRH8)*Df+V% zVsttSTKGC1Hjy%vpUpV29?i4`YJ#bH=HWY+8c$F{n22I9%$^v% zO-9^|8gMS~3$ZF-#FO>*v)qGb=ov=G=0${-fhms1+l5BEwM}5(Ej9oMvvPmd@YrH` z3?c(&k5?RLK;vVdnB*ZM7KqIkeb z;9$)A4gSm@*nqkkQaq$?aV}QK0@b3X0rzo<|D^?M0?s`0R+nI-#hQcZ!k=WRtlEAh zsCW>_wd(dYHAj&mt!%D*i{l>yNsS4S)#osqvHJa`1Ei>|`Y-xF;IcUL=J9dbwl1W2 z#KqAf@AA-}{|5#x7{x*K8MbxlmCDfmTn9Z8q)~>pVn8?7tqy>ck;pLrwD`>A2o!I| zf>iKXTaa;@DWXfl_0qGkSis5sDFmb-!4BOKDX)G&#L%EHRGL^Ibw0f z(cgG9I8g`ZpNrdM-|tSOV;4FkQ+BMj8!(Ia^}f5E#z1c1LeJeG^9>~@ z=nZCA{DoSAV|B3p`8^AT`|dPz%nm)3xcESh(tiKBnYv#NyA(#+n$~KB817OPG%h^G zHfF@@;rI3kmKKk(K`D~DnD(sCv7}tl%&Sas1qIA6U%teWrgDUxXEeH6)|U+6#2QxFb zfWK=2wY3Op^h3K6SsY)WJ&t9ff4DT0wMgjrm56l1PUg!?;+DL6<+~=vA~@m{M$djH zZ$A=0_y8#*YEH5WQE!y%=xKE}z=%A42)H4T&l|lbJ|b`tbX4H$Tqq;aMNaJeahnKq z7BJxGnI2ke+SLTx+TiUeFa{B!sq&p-qp_XS?4$`jcXn{TaH3~}T5sI+3ChZT)g7Lb zAyGyRZy>maculIM?cQ~Z+@HNH@(5~B0hL~3FrAI_e)2}>GIchTxGK>_ zS8(;r@lM`gpOXv!GRI!u^|8h2c|22JzS4(5z2-M+U_y*fJ3;wj*pMXs4R;_g5Hdq~ z#8nj;I6~k$JS8;EsVGfm0(xNy>3~J=bLw6`=K6Xh39&m?8o7AdV zl#dfBOHTgKFX7oPUcFup(Kxz4?X=YFsV-%ZHdaoQ6n&dAcf-^{m4KgJp`Zh}V4bFJ_s_5r^s{)+>e#t?B``Tw83mM}=My@i-b9OTTcr0yfU+${CXl zYf^xzAgqRfFf%b!S+c-})QF9DJ#6*9_Ika%%hqon#^)K-PTlBUOqzDl&nuN#T;UB9 zYmDrr`51qp5+4cwv+$wUeZabB$TJ#b-!4^K`0^ zXp+%ZnG&1d#~HeE{?MULgH)7F6!f=TKYP=x9aXL`P@zOb?ic0DVJd7sts-YrU^DM| zS#-Ukt4Jb2Hl5g&m;#!Ow(}#Wzj{9)@J(ot8bPB?o6Yodkne__%^CQ{rkZh8WWc@g z5iFcx0MOCf-n*u8|JxhdSPf99!+uu&#w`3MwCi{5S^6pE(mTt6#$Udjp*KU<_B!a7 znVMMc!7IJ31CpxsJaYkZhGdc}&})pDGF(LrKALwi_0F5;0(GLIPgqzRFj-6UxY=wA(L@Wt_Y-DGx@a;tMq)G%c( z`*emq`BAI)?bdJKf#j_# z)^Gm*$q6Gk7eb~hz4=Tk2ua7C1bM!>L0N`kjgP6Y*2|`d+^byOM8xa4ETyW$8Zw2W zar@ix(6hnyUbJ|#O{-XrJWUq30&FCY=n+7slrN3~Z5oCzhj@G^jzf0sei}3G{k1R~ zH198=7s9&b3f{SQ1BKGSpBA5uR-hVE*DdyQBhVxF)tf0-2vK_`_eB2ARsSr+XUZ3P zWZ_N@(u#muc}Ouv^JWJ{Lva0Hepnsif&%oy#trkelXLm?&m%~&2+ENN>bcV!48$xW5by-?3Hk?rpxF8UF{A)MgegXQ zA~$4_>VDi%`>#nAM8NaUk8Si}cK$C`R1p-`r@80wx7#2zs|<@3x#pWK0&GSNx4x@- z`+ZS}Y;B41I;4x<%eO~B6PcE+^khN|O4&S}TmAi8EJ?bKRaVa9}VkFuIU%uIU`7H@|?8FlkMW~ z1whwEIhOAD;JK9@VP+?>wUg~;$Qf3bnSnWrlv{$D!cBb9+=J6=l-fctIfjyZr}ofe zf)YD$c#}@nDtRRmcw^C87DX+@dFxT#zAw?!uIX=_4LrZnNYesk*;f0*xmb(E`iI?% zMt@7F5Dr3}l@$BHB^z&fiA25adMiENzJ7-{kj7AeB365?BO?#>dLqe5l@4^BK8j#l za-C26EgBPQuz9`HZSGpS`O0B zO6+<@L2RbC`3szU<|jRVMQ3Qwm0YfX=((OpKD8vxt+N`tS!&p}4#+d4| z$5AxK$YLYHF51Ew7JoP0nt0Tiaq^sxpEW}phhf!v{9)ctqV^t=HjnjRtEPxjg_N9?iymfbJlg|7w3&f$nYJg<#vxyz^hcv*eSTvbe}4twZtt{I-GkXbvJ zzgH0k>Gpq2rHdth@~~PCWANriqR%4GTXFcFp|F zbWPgha7eJeWb)Ig^!TMmhagEa$W`ny+S&9nDk)l2u^O}y9l-q!l7cOz;i51Ui#rfs zf}CX=k(+or2_WpZj!t#f79N(|eWicG3Pq=I$Q+rNf_iqFLceqQOL~gP(TEJ;k24av zFI0xQvZD4fe);6ko7tUU)do^g5Nlwx!Nkir>ieG7O4ip}wIe}a%bbBe)(8CUJA8v~ z0|R8xN7X0sxZ$*Z)653B9;DXR`H~k?*O)9ejP^P(w9CZ8dadhjSo{IN7Pc5(+NZ9x z4zdIXvYgY0980I_Q%Pcv1KUgPv&G`)1wc)=OThE4q5It2cVJTw;!va>E_w!MyAAtU z>ObN(hfxb%!wWgE7!JRXD-LBexJ9g{)9iCV@cbY&V{TVLr**WpNS;MuyOC=YcPJpZ zYGCl)jmL*YUuu0*a-5MOASjoYH;gSF%}Zd4 zPpw7Q<%pj*QRiq-~N$ooX)E=oIK7RWDWV7ad(@V*-yDB&?zf}{@v{w5FYL_V+ zeQv@+F|AJT_^FO~PXF~6{c}Jl&J5A|f>Ey1e}~qzn0oz7*Un@q_7u;MJGGQ#f8l=+YYhPEnc7p$XBma z8?ILB+q^X3Fbb6#zjEV*x3@c5$X4<98LK0TLo`?!(x z1u9-FDBm#Q^uo6C<$f!Wvsp@K%eu$`78C&25D$k&0^3jn2g>#HEy^?#IN|p>#vMSr zGq54|xY|Sl;h8;NOBlrC4&P05TZ>`2uCgBrbO9nOlpWjEo!FmOC~{5A*3Ge~w5`!B z*>4=g*Qp9UD##&TT_##pUPB$N9rMAEzdAmOUtO58E_h$WBU2QunGdSookH#asfe5= zY@`fpGM)DUPBZf)$)N{)785a(l=qh>kd^n|b09O}VgKbhZCm;TZyVoJ24dB{MP^nL zOOCOQ)+o0gn-563eSQL=VNo`|G@Vdl&S5vhfU+zSbg}p)fFr? zRdnlV2ybWDJ}zIIg4j6>j9%sEwH<+7PpI3%Ma5{9Svak6a+$*SP&wgSJSE{41@Y#{O#M)aWTFrB<4XdKWQ)a)rYP=bXt= z2^TQ(D*D7eHq$kBdPhwc6H=!cG~^Gd!yBrJRW9qKS)Zq!E4(gSi40D+DJ(v3YG9yX ziKsB?e=q6*DV~D9j{9pgQp^bZhQw53HG#cw%zeGXm`~&W{jP?JkL>MAI70~l9;R^>TV)+0)rK= zOcKIHro?A72OMsqF0X_vpkDebul_!JrmPB@!=$lj zgTbVgC4$@B*`O3)g8!F)Vq>ylZYTKjM)b$Zldc~E>wuDs^+6+l$9fW^mBkz9CF1D- ze8uQn2_ol*l!s2d8u=Q1cN*s#`E2WNbAG#k=QT?XlMOmv>}&rtITa^PLl=Qkai4$Y z8FxZCdf{a7q)FGr(Sz%?K^ZP&?7TS!3VQvjBri}Zif##UR>&};riD7X&O8|U`KjvF zQZh)hLatcSJn$xLq7Em#Mw?%7!Jx)fILT*0D&}A31^}%_%w9YjzA@-@&o8+?$lPbW zadI;iKWlA(g&hJ1p}|1zs=swILLqW(v*`N52_8M|wOF(&(JMD~vL9?%Tz#{c(>F>B zS(M4%-`~QVasA4nYI*joF^S-;oPXu3ka+Mmr+r`fES(#>U>1EqM^ypzh#V4&(<)OI zwHy@US0#UD;Rdug)<%Rxkj*={o8}9uNOXbsD|NMzRnz zO8dgf-x1Lp27}9)2Tn|N?k0@juYav72bu2dG*j8G^FS*OFmjdf-fDl@caVNm%I-$y zE#1w~HFP)9HN+6Z8K3vT=XuZhzrS zxFmcD-n`i6HmGx%W!2#Rrr_WJfefb$;45c#`wbjyz@}65E+4nPA&*MqmC@Hn$hT#g z`KeZX<(@#Dt50vXW2Pn}P)TxgI*x@-TpM=X9 zOmJ>*=-spBN9dNqkFW4I1edYm>2p~g=8xJNZpq>bf_V&(WwPwSUQBA2j|H9ssVVr# z(CKjr-us)E5MZ(S+Etd>LiF*7;Ktnx(3!}RvbuH-*kfk#s9pn0!vdm!K2cN*Ny8mjpwdkmZ<>M2(^$Y|bz9mk~@<#U!YFpkXH91Xu6;dA^%kx3l# z^<597Kfl%TJ5-j2Zlwa%;7tN(mfn)M?wllHS^P(}XV;mkpxGspgto2$iy zj2;+NR*~C5uf4B=QM9viH7Akpd5a;iSZ(_G9EXon*tu9BvXeNmoZbztN+%SmQ~6l% z#6^cFzG{WPDnxaAWBj`)$Fk=w;>FvellOrb9&88pQyJ(RQ;lwCD|f3C&zrK&6#ssN z7-Gc=8HWa^1F2f;MHs|QyOYO9jQBbG@i0GpV%opw%KWs~;{BO!Xe59NBpHky0@-ZT z_4YdbT$jL#VZ2}$%%%wEA?g26P)~gb4LYaecpTT|2(-V?u|Od@#sWs{yxXZVFx2Lq za1DzbbElt$QDk^qFdbmSy5lk}`JCO&wT-XNlXF-a zO-DQFR%SeYeRkv?Fn%AI)PC^lqzgzrS=x6p*%)fiL-VAqfLUJno>$9ah7IgZ*`F>e zo`}}kA6a+P-t%-%@?lelX;!59G_G_|YkI-wFY9uub7#=#|B5x*Hm19_-a)+U*ZCT7 zcU8(lKzU0%l~-1qoMd}bfx$~x5k~XteNugGwyU1ey8Vge2)b9*h8w}_^wr02Qx>_u zhUy$q&uW#|JPae(6rN)E4Vl4#9u@*{?Ms$|I6{RA^yVVGue7M&pCid>1P*M%M6Zk+ z(geXrK$#Rm;U`F<`sPSUa}ZAF5lu382Tam@?++6G7$s%l4b=8L(hSlnmx7}$OTyuA9+HrU)FpXSTzv)&K-tMU7@J3(m+2Ha3FsVI; z1DBvTgBl52mlHv-7EF_R5&1U~$Z=lJKkDwAEdA(;%NFyqGLZtmN!+tnAMQZ z6_Re5I5^~uu*(U+iJ#T0Gp+&gzS~{Tf?%qgh)Y0dMEtYWyJ7E6ZH${^kG%x+V(pCb z7BDZ?gin9ctSSW$NNjfmh^0`=uPoYlESAUPvRit}10sLWYui9Ffad_`BUaapT1{tt z#K*?Qzyc1xK7R7V3+vOdZZDttjWz?aYu20^pE=EcXAF;bI7Wl?To>@j+5yJ<&LN;} z@7g-Hbi;i9@~2m;F~PF3i?e3ATW(mtwtX+&JU9=ph5tj?L-d0PT*eMtQn_xaBk%@( zZqI}opVJ=4!XZB2#Y-&sKfO*mHX!_eH#igPkEq`JQj4UpP;1l9!xGiwbh!t=`u*un ze#$?5&-$tVq8|QzTtFM1P7Vz0nV(ij=)7g3)kQL*hDN9cm z7=Hw46L2K(Ez26+T^td5-%n&){|S}DzQFU6tHH8olEZ@11L6m8C!8?x@H(XP^=F&; zN}D+jzAsfVGy?aX5!KP)dQZ&QpKDj9n`f%UsqS`MN5XbIq#eN=CeFi?_Yb1sly*bE zIT^|!wd?wu$28r7(ww9+!0Y2ggHLBPFNY;N!QKr9t+U$s#O@*CIoY` zv;89BNNJa)T|LkqX(m|&{{)33kq3av@*G*g06$G*>AN}$VMK6 zo^M5Zr?Os>>%;bP2%%k|F2j_h!#}uiDG}Vkt-9}$)69>HhdhzNwjr)UbNkxJ7*Svn zD0$V;Ki1rD;ZVx{tZ^}F$hgzGR;j1#nL1q)tJXxhQkE^9M$pyAdS%t?C9Nc^WRNemqExP%y?h8W9QTNi+H_}ejEpw{ zMtIS3pXGm6lVAu`=cdS;r8w-2_y{wj*5I!>JT%-4*$8!dJ496g2!;&e$l%wd(+>Gx zk5LyQs}vG9#MATWAQ6r)J; zE;p(PHte+)G5>x3r*J~k?f3CI=7SDM!EY|`@6YRJDe%?GuxSw+mm0pf7Rfkm*f|Cz zk(mvFhaTqDYi5@)A&*Kmbokl{y=={VW3GWU$vD-w+%3qUP!o^)$oW>`Vrwc}<0)`> zs7(E}Y94pjZO_gE8fd;egWS4uUWj7o?IBJ7!+!0pE_lQeO*C!!!OmC^MwVy0^>u^S z?#g3tV4t`089d}2! z*zPv;I_Y&p=5(Z1uy=QY6-BO$ryNb%w|ml@?}{u{EBM@gb!UNmg6n{AcZQ@qk8qP& ze6l|G%fL0;JbR&zUwkc8jBct~4vTb9mSL@9;fK>T_YL~15c^bi&8B^PX5vwLettK% z?cwzBA0zthn@)E37DMGXK04npKgf~Lva>%1^Ws~oGpXD*OJOOp$5%l(nex+TvAufq zam0ts)&^y$2DYMGKX^F-xNMDczgSAr(g+@@&gZc#`ukQl9E5KS_ z3Hw>Qc?G-0ZS<{syPC>vgU`yB(|}KE_iU-2kuO*K+GSlHxt1tzVRUq=8646f{7IW3_bg8wMs-N z!CSR+Jh8_3wDS9ci!|^yj_4Q}?fn+pCjnU#t`8bY6509tV1-GQ&pb!*> zo^FLoRaQHF{oci@P|YMXFsCiCE~`RVP`W@|l`#e}C8cSlse(f7L(vkYn8b+BK=4-( zS&qIYNuH>vEt5{v%^;yoJ)0~~{yc^pe(9A9$=(#!$M0BgkukB(W(>p@YyOOu0&X1R z>s$enIv#J6dm{Ums!+k3T~-aYskGK{_SiPGb++qH4K|jGQlT2v5@`ZST|=q&*+0W` zibPghKVz|#%@+KZg@D%#Sct)a3ewPsjl}EozS#y`@FoJ!S8KM#?fhjK85!_~2N5z0 zew0>Yp*B|lRZL70t0h10Pq$~`7kU4{r1g(?2yI+(TAi3FY9}b1!NxMRl9Nid-mbSx zZI2ct`(_xCuv?uD@-R8#W^Yf5Zt3`=(us98Pcr*$=YLJ_C^N(R#|p1?LM`~VycxB~ z35MHh5{@|*(lnr~ON-?FRy728p7^2~lX8NPtIh?5N#b<|59@~~fV%%ib_iSVg1SMN zV9pz4}a>Q@%Jpy2d~Wv|9T1?^AfPQ;P@(2w<-LXZRExBlbmmN&hjA1GnhIY`#q%3A&!{(|TFnLMQkNNaOz@IjLD(C(&)UDSjHIc{Zbv7wSFJx{ z^0`cp=5SIo`JvHP%n?yd9%a;B8pCO}rEE&B{BVzF!Ejr5ih;-3-+bp+0$yE{L~JZz?a4=)AC02%1Li+$Wzz@u&8!> z+bbtWTj+ViIMvFgWb!0FAHkM7w_&(-jh6X@^Aoe^w>zxuydLZ%<)CMIp13U!!5WSz ze9sr|etWyWSc&X@Ft<%RzknZXeRy`?QcnDX7|d247+`aCW&7hfkpr|Nh?QnQgV*tt zi7<+j15snN*@Vd6*t2t~OJ+RkzPCx8(TxAt$y{wDJ=WfVvGp*LPU!rJh&Sx@a?ta& z;Rdqlt?)ng!Q(d^otMIuGtuTteYh0(VbN{-U0rzo67RhZ*ve0DMF9{GF#yp6T-e}O zHG1e#`Q+baW}ogi(toa?0a`)6t=GxB_M31oTBu~3H*U{(Pt!Gl%V=9aSn}OKcTZ|Q zp_&a+?O7Z3Pk6uBDuMF+y#Vi@OH({>0b2u#hp<{xO_w_34WKhjsq6{z!M{@O+NHbKn-lTKjQXk)qbaaGs?i)FCiT7SAf9 z&9aQVtA8GSA|7nvq5iN+#L?Ql0O5QYb&d4wOFhmeine_QWtczijeRu$Qp zq1_fCHvcaoK#T|D)Z>M&`qblcb#+d5gif}vyv|Dh0<2z2109IE} z7lwZTt39a-^cC9S#rNH>yssBk!m9;FZ20+76Dn-ccN8&M<=tCE>lWgQTrXo9cU}m` z^EKL+%7O9Ol`bpIcUZfObk3z8*1H6|>OMjp95YZTjTiCcpU|I-0vqyb&M+apCggj6 z@8+j>8KhUKen!@j{J*C>D4Z>0tDR8+_y^RBO~*%pf;?^vdn0vdP>qKZ#;*Cb%3lvl zuQZ1BLUEDwaSiGz7Cnt=(%Kj~|mn9KVc4CZi&; zZXHA@uq*ImQ6SN_+IuzcJ}rBmvD1vu)Cb@@QzoL@gKxpRwHy-S9ieY?)9*rPy_P7i ze|n;Vete%it5dor@qJhjc1v$vw()otq;@{m*wpGmTu*Tj>Y|Hsr}1=Md4}*0>qC<( zkR#i%{tI*2DskJi#Udr&s=i_~+dg{E z1&FTXH)joHX_MI;?NBA;q?3l)si^%2=s77s+1fgyf5yWtZ?QQV;etUx)9|myOZ6>nt~D zG57p~EAmu?qf_Mm;tO+lZDMhwu`WiF1xAfEPY72QVE2=Q@tI!%G*Q8nnbg^VtVrjC z-fp<0CgOl5@SWPDqv4UWi#p+n@{|er-QK;UeY#;s;w2XR(m{uxLj8&bcb*diXSILx z@hK_0#j=ER_uu_WTt3Fog(s`O=BMt2>({p$U|6c4N$$*&gv)QwF6og7rC+#Takt!; z$V7*AvkeX`duiz6?K?3d!O@mZG?Ll+y7lOvAcZ821kb*a7byZTdUtyZg%ZC@=vi@m zks`6a*SfU0@*QgD{LfSeJQ>=BWy9q|ghxrn%mr2DQ6IZj85{`kD)-7J6c9`sUVqUZXryfDnv z3z)F4dGs|Vrdn}Z9;+2OuO^St9#vsxsU%5uRTD_yX9}j7z8+aD8#IVGvTO*B&$CR2 zc{Hsvneidv@}uji4exQD7fBQl&iB?|2~vd!=zQ%22v^n>*s1r|x+Hq8#xyzW(35$) zwv(jIe)xK6qXe&dc>{0Nvfl2DY+q#JE7I_1bdM2H))tJ>@mX)g29P+zqM|aE>g~5J z<`%m6h;37ms2X?-#V1tI{Sg+Ou1&0eg2!!dkXF)30m8HKJ&*1NG;4C-X#)?j7%6S^(oDr(9Y#JPdwz3As5bq@GJ0s+rje)F;#wryp!iqIR0ZAR{Rz%Ue;IM zf5C>e@4x-y0_;sB)I6rQqiW=7dM1$m=Xlm6?sh|vdpPVj-2PQ-zroNy&0P3Ac>RCI z3qS4i=+QIv?U<;y-U-x@UWdY?K>Z4}Lh^BV!mGq|dW8(ZLkiC^{9zs1AvV0GU76}) zF}`X&qUPJfN&kGl=5La8GB%^U0JeTaSdS`rJM!Fe2Ii^o&!*=2M(l-f7}>j;Yf^Ch zKjMWRE=0dM67r2+a2knoc!SY{hf?pmFp6!%=%w{W!wHL-xY}SV#YC-PkLr1WWxLf# zhuOf!n{n~P{aZ}Hl(5|Pg^vYF^7mO=}=u6<{Cqld<^pJ{FNodRCqo^ z$&_X&!12}{BF)6N%Tkr%x+P_}9k#hIQJ25`aK!W~+jb(^NSd7tUTqouKSGK|n_2R_ zZcg%#%XXf5>;T>x{ih%>8Y>gPK5n*^De-Eb(P2|~ zsK+(Nl2`rMBDHV+>Uw>Xq+jU%C|+$Vk{r}Dv*G9chXm8zg+bgV2E0zAb)5To(sr54 zKdi5Y&ZL4^gkedBM7E>?|BFXl^<&(hqGXw(&X8UY7ie%O57cZFmqq@dBCj{rQnd%L zw9C|AuacilR69Og44uDP6A`h$zHLiY_(4@xdLJ`w%^Im7@dxk4Ng%!;w5dSm`Ix8g zsDHt{d1*NC8<>o-clX+3rc+reLguf^NpYNDfz@`Bta+t?BBJptX)2$kBSmhl9;aO08KoG-da6gH*g1JFNzrIWsTP(3bfM^!h991 zMBKXJFP}5xP{UN>_FPXbGe5rCe{YmhJJJEmOO?B5OZ?<)_Q!icp~T>ngnC=>!}6~$ zT_`8)_Kj<_NtRO_$7Yjlvl?ajrFU4$mXU!=ySm5l;gX?jtiFeS-${Tw6$4I(A#7zZ zOh0b%SWWZyfT{uW)69l@r**btdg#6`SfJ~W+h&Ngb=SaiJrgUBGrZ4V?jCptA}?vk z`U&_Z9HFl>F8j)4z-UE@<|Uk66u!?|aWZU+ZYExi)&ifv_5AbxUM(ytOxJ+<{lm@&_;_o&Q{QrpJRs)uB1ydfx5s!!Qh5-weg-bl8PpJ0ulzU8dT z;ZydM0@F8P-nmtOqYO^I?|Rk3c4*Ymx~#AEt4#0);_-Y_yW#$Q=A47M7PiN(y?dD# z#G2eM8lISyPPE~j#P~{WeMN`(p(Oj$$hM2cyC<+^%yr*O?ihW9WIA<#C$;>r)VFre zk>mF_F0|3_A}LSK+svyK`x(C~oVRpL z&yyETUb|n_ILw>u3)IAIKynAB94$Zh#%CUFRbzOXY4!V*KNGC3V7|XK#@G6w{G@o{ zy0=nrsaja&+f+Hs!|fikD+0Ciz#%SSwT)gmeQVJolku0eRQgZt{o=&{ZmW0YkFtPG z=+?-gbY4{7on)iRmf*EXFH4UKD!=u_F_DiYzhHbZb>*Ri&-E+H;JjFZLFkn9Wi66H z9z(Oca=}PHso-J_b4ya1pS|s?YtfdX%O{LM3v$YgoG82PwP0bSHW_I0$nuEZaoUZk zLMPIs`&jK}x<}(VTnn#;tXWs>`M@*ij5*bOM-7&1IYTSY764k#_do1e$i<-m{||HE`qib3WZ4@mjaLr2 zs&C`-C0@RKk{d!<`0bTyJ&K}sIb(=gnI9$nB3l1bg)d7u@s!GL7|hfZ6n(ievB`W# zkji(ULK_l>Ws{p0QaXBOsp?Ei0Ra4pAtM|dp7tPsvc{mpVr33 zlgWQmRnSzYRUc*&UOu4|0hP4tSHRg!aB?$NJ~*w(Q13qM!v96`)q zydVl<=FZ4PYxGYcqy}YDu?ga|4h*skNQF?$X~*ifBTbdN2?|*)UFo3l&B~~x%MQK)euJ_ ztUowTbynKAobmxQp`xJn*e|`EGvatlRY*_c$IoFTzuOJt;E-cG@a+v3c?B3bL$!p^ zrYd?73Q#%m-4#K#>tO@UR2EMZnfhgA^!vNP8Szi_=|#t0S&cp97kOIW5w}$rPbaSz zJb$VD11o<($|+ycI4GP@M0h0eSGO7yo?;qm1T-6M&)GY2^)&mFjZsuO-8qq3Z}1x@bb0+jFoHzH^4+aZI)g&Cs7L z4&3M6>nbqBAex{T(^n*#4HC&(#T(Ax`;Y>Lx88D*dn*2d%&?vC5>TXKMS<~%^~b{b zi^-OZj;f<2Nvpc@uu3Oln!N5b2P0TU06Kf-uNE9{H-IbWg;{p z_b_g+@MP)z_2k8X=gCCs4_L6vP0Nq??{ks$V&Z3gEAyyMMyvd_X)m3Xvo&XbKwyW@ zX(7OOCLuook z6~1l#D14+C`IAfFWO(d_HR|ARK^h-sNPzv`f#fQXeE3f#K;0*y^D*J}jh2Rj<1YEpmr)z5{ zb-9rL{zWaQ+hF~uZD9G;tC{FuV3352OdF@&l5dq-@ssNSEajhAQJ;|ON@NHd$ii*8 z`l65vs4#93PwE#o579{oxe*Zd36e3{`~Qg zc9Q$Rcw8X7-jxSPeuy5cMDc1S2~D~uIXS&rhS1!Fo z!kU~Z)dF~m3_o}kVsLw%O#Dz)nj}XgHccTfH757^eWF-(jNq)6b~-k;%yv&y^t#)V zZ!61W+)W6m=MBg0K|05qEgpKNtO)+iUY>)y(#JG+MBJ@9QOT(L>L(Z?dH38tmD6rM z4E2xGR&n15I|okkd|gfi>YkxdY)p%-;Sxkl155AVP5su0N$l#2ya~I>-h2^Seqg-3 zx8@Jz_dz_qI5m=(t~FJzWklnV(>pq0rl!qAM11ETrjTPvm2o(oxvPKybof4vZzw%sNlzDcP_ zZ-(>_=fn{bt&VuOkS|M;&JCAWvXB&VLih2p+YB)s^E>st{#dM#L#+9yeIkzdeaIv0 zGoQz4sY0or&8MhO6F--8oBEig)Wyd2%`_wo0ZbJ4SA**v$8(9b{>eRZ1Pc3n2A7g{ z%V*|mCb1Y=Ez4bO4H-5re$5XBJ#v?LX6^;q(nBz5qwB7@f-ClNb)2o4`jVSj4i6vHIdhhNCku-_Ua;Je6}SjpJ# zNs7!a8NJjtev~80Q?}0bu!49h;AcYmd{wA@rHN9pwh#vou*aeC_$!$pd_>eHNNK2K zf-aiYX#!3!6ze%o0LC`f;Cx~&7?%m{!OB420AFnS4WBD=WsvYd@qwgfqvfD1WLN&` zXewYqcri^4%8#g{B@Q_sgg!W-*7||mJ_7t!M70xzZ>OS2zgqLSv_X7!`jYRA_4QL| z>&@WL#Cv&|=P^qkC70@yGtjyvh$@hLJ}f@Gg`_7Q)9B(kARl3+jI*wRq0i6Pa&3i2 zBGHGjV)@C_f#Rn15X2k^Gcx)6&BqKdR#iys&sD!yDS3CX#r%~l?x%^tX*2AN&5MjP z$r9#W7a=+JG$~Tl+n9D%E5$e*~yk*x!wY=A-#NPIj_n0At+)lr0n0nTo z0_;vsn`H~fq-9+xsG>hSJVTeSDSPj;N?~@1f4kj0TP#2-lU}pb|#S@L83&9fAB3?%=R|#&&u)`#$u<70EhcWw-z|4%ztJ zbfSbPj&31l8!qVvG0*qrjRZOwznJ_v%6Lo$&uSodsxyZG zrYq}LrvC1so%885V-;XUF`Be<4Ilm@)z1#31j(?$2OY;hL6UO5jAE3aENP3+oGt?YvyEq|L15&A^V=8LKQ%g3Uh zDnchSfX)hlP41mKabW=6xNEOMk)Wd5z|&Y(K)p2||M6MAp_)E8Gr40-ESz`u_|Yu& zVJgTzy0xdKw-lXtEG*vH&CaB8noq4BxiiDMZFQ^@dbDKOM(ucHHS1S%~hP=O3*!G1(3HY|~?HvU;JG=CeJhFYZ9peb^s;x_gziuyY$f z94%`kAC!EiiQhEXDT@E@3>HE5DNc(@{B)B-wHPLU#DhX6n&HIws527`AE~Te|393_kvWmei7M5Txa}yLdr-> z|JOsua`$XrxA|1+YPV3mbVdXFU~o&%2TPHR0Ck~=Z03yh1H2WxG@3b;n9sKbKko{I zS!9V7nLC0ri@0-lNH@z@R+H$#-R(eO-M5hxmL63!F?fYaUet}Lg6#{;LasY1K5R(M z+)-XbckG(&3re=nZnBlw8G|(&rwt!KOPGG36O!hedb>KsSax} zHgzRXkl*>ulH+u>w7t1_`ecP&R;IH}Mw;%MW<5fLAw{9uYub!0tT6i{^9_$Zq8V-H3R|L7Y0Pm?GAN;4$}xM0TS*ujj2Cg1Feh zqFrr`({|YHJ9xnUG_QOHbEzpcs_5G!tg%MOf`7gY2*AmEV#1r`p*J9p`5M)Pf+0ee zc&3ABbi0IR|4I*`_Ruv^nB1C%s{D6U0=O&ROG+73+k()a-FTBwg_PU9L|4NJpTFJI zmTLhAQ3k!WIY)MJg&Eh#H%AAcVzN6qcCZSh!)BS~hwO_zO5lSCDmR_f6n241Y9v7& z^O8tAjwz@G5#%i?U*og%%55!}p>>BNnFpo*eX!$bz>g2cbPp3(EGXog` zF`}u?*n7h!E*3bX2Z0GU$!LZS`W{R@@-+3L}FB7YwL2WGeJhhLa_qULnyB}JER78T*lL$lO((5 z@CwvcdBx8y%NR}dD8ZG1XDW3W07Ie?b`M;DA>^GIwoiYwKL2Z8rV3x`HM_^v0a>*t ze{2WXxEeRd+?4IGx3eApPz#-iqYM2tpQIm2q?P5&6S~|i27lx6^?S@5HzO-~?ozt! z9d+)5OhHiD98W{uZek%&dkw(#s9kEN@@H?9PJgBB?;ek?ZlzW|?ubXPW{8FtM@Edx zr%fCf@TF{Gh#=`rzSys!vdWbTH3Lt!1YdymhQhJ2H2r$~O)3v$_|?^|6}?=NYjC9% zng$mKLrFmPR#LiUGl>Q6B*wb9BK;S)X;j{vzLoFC%}3vG=oE=ogoq1Pc6~EPY)!Kl ze}O?xBEDh5jLM)9J|r1h4m_EvD^FQTx^n9r=0p$$Y{jI)c>lyTI&=v>44D>H@+iNH_XJ_6c-=z<5h? zKg6cfK^FVCjCengNWi0;Otfafrc$dsEBOTv%e9;4O zu_?$~m6FuEk0N~!IglQZj4N%>!7hg)y>ywaMB;8;<}*2`q2D<5)bRALx9N|w3*pi! zqk-`d)6W#T=i|HZ2tpsrhW(a`qA^1DaknA=>p6T1+r952O4l+0nyG$D$;Z@W&RpcA2uy#Pe}1; zX9|Pr>bj-b;`LI*Qk2u`moTu|w2ZTk323W%k0;1Kf2Sfdq}AL1R(KY~ij z{j!9AUDUfq;Q&-fK6hUWk?l7;A0{AcEZ~QE2?ufn*poxasgOK-G5fauHGtBrR2H99 zHlP4a=R22gu0~V0B+@D1NO*BlT4MKjrX2WwDaFOzT?_PLcqp_w^R&C>32dC6i7Js? zm4u@ET=n@M8qD;(EL>a(KF|>Tw+=w{(7buMxRu^q={N~~p4X!OVPc{3PCs=GIOUxR z11F6QIu`a`bR^4VPq&PyB9nSs{UaS57<-`MaC$ziQ)xPuJ&@6O)N=D{G^-Q$=F0Fy zJ1p?YXr+;vlNwyqURd(%NZG48QRS$i%)X%Bg5(MI zL}!x*(|P_lu1fsV_4=O<9!|WT#CV-+wlGYAvaoD35J&0vgRz2ez=zsIa#PY<0bo)+4zHWEl+jJ zj!h_N^Qg5arD{8YSgMDA{S^;;Uq&aL;q5(-Xed>C#;;Y6~xW!OJC&Gn>?FYfgvA zKeZKSgv@u;OFfi4Nh?2AM3V z-{$E&N9NiTq9gE{{58|~8VJ$s5IXDmDA4w3Bu}gBWiudg#6)@hOfXm)V^@;)u@5Fq zc%UXn!YEqfWG}RA5e=ATXoP5t1e*5fp9hZ6H8@b2r<@p47pyXk#y#k@#k9s*v|OnL zKPP=g(xSyy^;v6y1s~pvHdkk_UpIw1mv@KD3&Xm0TXi*c2i}?4y_peW3dg9$b#r)T z<73~7i(7|l$=#c)3{H>^-auYlLVz94nXIed&XSzpvcg7Ca@9UPxoe4_WnNDbe%|WJ zBNpMesPiA7YMt^wwWS-tt^Ch--lnw;b&D*tUe$5i4O7{MFI&@&OJ>SCYqM104fxP+ z_o}w_Zs0m$CxGoV>z_*5vo(7->c;#cBOVE}2|*{fGuzPGZD#Fsca(xvdDFT;xB_O( zmcy4_2I>C*>M~q)Se3@xr#*{!CD`i+I5bfynR_=E7>9@Ev{1L8@u!DwE?fN$0&g$s zsvrwKHvXZm;pH4>Dba8tnIqI@H3}gB$QRKTB*+C-?q~5%bED}DDID{6P9mo;Ue@gK zdeOF0a7fuv#P5N-B;NhE3~ecg5akmG&8hcS;| z-m@>`-oDM@$ehDuYv?m~OJJ27vL?qORSEB1Po^1s{w(KM`ety0_Mhi68+`a zIQ#zR9qg+7ug#Dix3}O&<9^+t6zUFTruUH^IOZkg6%>8~oqfGBU-IWj#Mh{`CjIZO zfptHj4LEVs_utA6$5L1o6jYd+%eg?o3rw$wLghuQF?GC zo@KogK|Ji1C#T{QiZLN40S$wTl3VQs3#N`h<`o}nOfeXOxC{pk$k{CVkUd&&K8p)O z+9O&1lzlymc_)Nu4c&63&dbcPUCfu!=7}(JFR)>9B_?x6V)@J;JOb1|$+%}Ty8~32 zIf-lo^uPXegG91?e%3YQJCeB-8eJ1>y!1=sVL)C*qewQPuWg&|TkmrehPFH^c1W?n z@_N<8Gfhl0o=h%K!WmEInI>jx!!+H2Rp5^2v`r#;nvBD33mk`|k>PmGWPGaXE}`7( zfEot@?5Q~|_}+*oJ@@8{A6M?fSe^U$=rt%}V!-RKH)gR#S9TJjNHquxl%muE+P(FVEkC@5Fww>?1K*^2CC;O>P*VgPu z!ixzkKx^vm!HvP7?-6br+H(%1T>-%7n}eSQ7KS2BmRE`*2d->PG3Tn><14~3vAutN zULqd%cS?uBi6a$tERX{!-R-7n*Pr&pb0QpmeS30ioI+j2Ua9PHQ`nUkqCp~DA*zXK zU7be}$*kDh-_K=8?+8fe9deh^z|a#*THRQ(<}k?-A(t={McMV3c#;b}oTHavN*?#QDSM_d&+0 z@5ld$YN)*-^RRr%M(jK>?k=n?*2Au50 zu?^uwvA86IU_d_D0TN*MG5MC@c#1%^0P!*|g zhALT<{@&tPrS0KIbZYXDoAiEdT zk`|EY3#4a`Lo2@T_p#X@U78-j}_+*Qj%bxb!%%%1?b)6P&)f zr22co+LhqUX?@fxWl{vku`jOJCNB_8rC;k^8dPh%UQ-Gy_~9Me3Vfwfbgq9@V>#{c zJYzvraTm%6(e|@8&^B%p>aK8+1Kd}e#go;=4m(QgQG{79GK|`8vIH%gKkXnm9v=`K zA0)>bw%;BQ`RF!?2KjLmSa52V(#)6CX-gaV&Rcith8>a)1@d#Bg1#Y98BCAbopNNP zO^076ygTVDe7m0S{K7cH7$)5cFs?MdB2Mz8B)Q)5Y$@c8IG0}(P7zk#Xt z(Ex>*+)6U{>25rE-yy9$o3pgMc0)o@OK=aoshd^(qg_mw@asCsXpz2{uu1xxVdD!r zL8-|vXi-rXk@b(8QdAKw3&VBpw_jo zNqWXMTfM^jlLJZ}7klgfKvw?$f~>?BCl?W)HcU|)Ex+p#8V{Sg>*26C7mlqYG1P2& zjOOHSEfR#mN^WCpyw2ww>pyJ%iREC#$X@&b*H4wn!dTf=wv+`ZmEiVdHG(g9tDXhtlKK(YyH87fEB%> zPe3mUgB0qp4GXkGJA+ISYxvzKf_8jFz*%&(nG3ciQ^bBHYVL-o4)`B@YFbVDZ+uF- z_RE0Gd>67ODE4$^yIB2--2mBn4KI_?d*m1`pWuW#Z#Pfr!8Ewj!|4b`L6|nT6BOA} z${h~seZ!o6gEs8zpzT?#W`gkUcVPfub{z-3yTdYeP3`z+rGpg!WYfuS1CyABk=bG+ z#>Lkz3>G=0hK(E{^Ob>j+huiB9c5}AsiXB4&j7+&y)9jwBy_DNTLp~u)y|9zv*>`M zTRB}M_3)NNO5kT3u9Qj+m^9jsg*~cYVbaz_y?2NgS+cIRxE zVwQ#(0(x6q=4kCu;!xk=Gpyzzc^tNiCh zna%z*g7+CeSvT|Zpl zI6#q)$TOg(_F_dxOZ&d_H`(`$iu!6q1@2j(Q6AeBFbO{igt=u^=|m^X4%T#gRBw-K z5w~G21bncDC+wJ(o*=pF-rb!&a4OzqkJ1q=X}6#s zL4~b|986%&^)lDQ5&ORZ6hFVxDs38%gK=c#oAX!#j$SNVu2um5Zr@@;O-DefZ)O1U4lDJ z1Hpm^cSvw|cXxMp3BlbOc$M=u+55b6-x%-S@%T~jgYK@X{_0z6%{AAYi9n8OR&)t> zDE`SMn5&`YDn9$mKCol_jo#LQj;M*wW~Ou@h8hsQ)}rV;h=b<)sW>D>Z> zR`yeRg(>U@hF`Q`O`~9EP58g%r<*rDf`-$PXxDm2cK%MDJOAD%PKB-kzAP@5k%?L> z1*#H)?(!xDuGq#G;ry_1^eG)XoMkQ}p7E6rc=K!xY0-sT*+rhrk1|V$kVZR7LF(EP z`wJ>OYOwB2H%4aCjb?0J@UBm)@o@8=*2vH>g~6R7{EG+1yT{#d;lE;!)!W}K-J`E2 z<1>uoxyJU*v*)ORyE&!vFD$jO_XV&UAt?LJ*p|!KuUKSCw~lMhn=QBs!omH4_II8& zI;>_06=ET}!^4KB16@c@n3nG%m_J$d9)2W5qYY73K!cEQ)g)TQ+#Hj3np zN=(wteVG$%yll9~7dcv=3MFve8YaV?Dc7A4KcBz4`SqQg)2l*$D}r&B`%x}my=3d% z)2caD0oY`V!{h{irN0a^N~}NZ-XRMgL;y{EZ=s}Iq4Q!vVjXKi06Dyx-0um@Txwad zz0_{TWe=)zFSiqDcs0lF$@lmR%$Pz}u1gU%7@t8(uT+UP`X8a|qGlU@68ZCiNQm6gHUw9Q+t;AO zH(pCFyT=9`HiR#C2c zV_}uaP_*_Wv{WUeOyv|NIQ%26FSc;cmjfDSGhm9@XtM~azgzi|M1(F(6lsW=V^yq% zEVRw=uJ^+6nZ%t5&ya#t_Q9fIL|yk;gcOjspIL0vwEAju1j#ClR1#x*O*~()rljRu z<_z>8vbmjNX}gv)SNj?+0`nht4l2vx4Kdy&&HWe`GORxaK0V+Zz?6$GK2m1DH@02M zr{J-iGY}qKWe<65aI5AKyoaCO=?%`f*7xLq8m=W8#Dg#jaH;udcOb|ejh>y??+Im7 zO=nzHgnzocTMN0r#3YuIzbY~Gn5SQS9JFY>{fMai!p)D;gb$~OaPG*6!@tsa^=rUa zRe=yrmEER?=1Hd1aKu?qBQ@WRgc)$YmR-BF+qlRqz<4xj7`4OEdT;o$JfydYWVgl}os4woB za=S}wt11)9zkul*?2g`(p5I(jr7j@{ z^ZoBib0j>hTKJKWiNkaV`-ax6saaauThzF}zmQY@ZrqftFr4hkmxmC~Z%z@=Agd?Q zAU}InbSJjm=$xz_l{0>D`3}Wgp#YJqMrQS%WZ|UW--?Y!|J~3llsN|kYj9H>s%#8g z;Us8VL{#7tazhSX4}O#MX^MeMwE<<}q0PL~qc2fU6tguAjF|~`YIIFKqLo%) zAG+)r#LFqV)No_z7R&8GP@F0P(~QHHGtrxtJr-jcX>naJG(~Kpu7!fz;NcD{)w7ht ziG^9CsTBi3X5-XFmDhl(85a9gu>s%3K)!fSz1vggd)ia$q1REx)TC8JRPi+}FF`{W zj&pS%;L^(#*@*bRRR$Lh-I;$YZU7s)cX%_ANYDn~mV{zmJ~Q8rjNPbGVD7p=-Cmm- zVt646Z${w2<#sGbQ*NUvViHCQ;k6a|T*_g3c3MpNRk)E|fkC62Gx;F_OTv*1_u0y5 z+u-Z%pWyweemO|_URziB=9W;1X1uTUr`O9Ws>#FlhZG1b1@biGf+IXm#F4{_MOM^|^AwyHTs6uT?2uV3XFW(+Y476P%N9zvos7;-d(0~$ z?5mz7#R(c3Z?Lqb)JD}YUZfA*kDNZl3EHp?yf?pPoVc@e(m0G)-q&_wVXd%nU*|4^ z&5vOWRC%a*!rScLW6eVq%iJu8ON3L87Q88@i=s2ZPCIgmNZXkHP4-o#Q!P?nG{&}O z0Eg7AG>Lt4#yvq~o-CR@&+lgX5+wfx_m%u&ofse2D}x`F%wG<4L+gVNYl?LHt_bEz zCp+$)m3wen3oxY-K&>@NE!%ayQ+yBSJA{K;|ex7Zv-@;5=&iOFJq zhVY|QkF7bmeRff{Pzi6I?lZvg`0|~`bm+aHv7uwS5jzPJE7$Q5UF?BmD;BQE!EMb; z{4}Zh-G4y2i3yy_r|JD#XmSU8G*WjAiJRw`GFCVKQvr;F$+T@5Bj;JR8whw~JD3L4 zbZeD&<&-;(rl*9Wz)VgCJ0#LoS2z)eoh-O(TUA* zPQt&2oCu0M46;S)PrSj_#w2k@>ftQbT^fVHet;@8s;lx~p9ViXBaorm_`1+>YR&o0 zt?Ad3#_f#{(q|}@=1%&>g<4JkgvljTB65!P+ee8Sbih%V4%_zBSTWg5zMFO5r(R6J zP7j(|wQM)5=kSc|Jq}Xg{EFV4LM~wNbp?e-iB5Vh`?2T8blR!%RZv}t2)-}duaC|f zaNbunnfaXWu!{>ZAkObF-hL2~+p9ArCSD0vUlwBf$?V&USA@to7jG*Fbgzx$tS_2D z*Jk#Yp{5db<8qbw75*4FCZ1|#>h!vBpK3-v@*IIfYvR(j%A>ZR=+G&F~ z3-yli>^&hQoRp z@>I?ccp_*&0B|%g?kyntTO2b2LmCi@f$eFIxmG^V{t11x;sCT2GXR_%*89Kg;S5Pga{V(+j5w>Ln)@VAkJO9Ji<@`;Q}`;ywQ^_P&;ST z;A{sWUt^R$YM)X1hJ#RPRZGeuvE{rGda{=!bem8!#M%bH! ziCTPkr^i;1v&U1TvMvJ25ei}TU~Ax8vGrKKl?t|1a{Kaz#z!du1bDz}FGF-rly9j- za4G{|`v-MY?dJ*?i*2*F&1^xJDlRi)Qv4mV11dI^gDp3eGg`j)StX+Qa5H;d_7@NR z%uhSarX7+8l(SF~QjJ_e`)AK|1muVVZGH8If`<9$`R|WrenA3Ho^EF*(`e+yQ>sih zBL|dJH`mviB|K06@BxW(=pVvxVOFk2+%JJ1YQ)-rpaJeuMpSL|JJTbWGT^piJI6qCxtH*b6CIjD}vE zolBy@!~S@M9i!Gl9X6XOrF;~!R_30+vGG~u`JYPBlK>Dh{r!n#L2#$<&iV^)xMSIJ z2$H&9bJGWB38rK}HnEq@6?zIi-=T85poTbGz-&7b|2ZF|lBBm@1ibF7UBdUf%jK^m zYf`A%BE;jUA{?yb{o%2KU#0CEwso7P?tel?@hPh)Hh6CG#9x*ByV>qJ%Z|8;&7k=) zO~8X;0raYcg~PMN^tbK!6=w`Xu9QESa@BdMUg z;Y*?l-vp?kmUsKE@B-}7t_X{(|B0}-+1nv9qJhJYUP-l5c-)zwfVT~*x$Fd}AGrcO zTW;y8wOVw7?|NY#j&AA-HO`nj+?@0$%PU-dQ(_@lw~prTbHF7`&NHryp8K+Y3&8dQ zm&@b$>qCxAO7ZRW7R36V)NM&C1|TcgUxIiN=B$zv7+6@eDvMNtx-?|g2koL_ch`4* zo(*a`exv4{Hg3Cpf8(4?)PW{>DVN!`(a5&;XliT4_m~L5Fr#vj4=c49V?SsSaWk7$ z{suT7*-r$4fKIye3{7BKO-#t3C2*;kCdRA}151{RI6V=#2ne!NYZf)*d&3e^>a|gK zNlN`K21otpZW~I(pA`an$wX*8B`IaB7CRCkc61#9kyZaHNrJI!Rak*>xbfmQVnKiJiEKKyeraKJl!pTU$V=nuc+gd z&`zz-gy=EyN#+=b=KZROnIkbAzuFBj)ht87!WVoOPF0}RctIHSr-}CAqiXi z1s5URU`|Cg4b;lW7-cHi7DReL}PXc=5SrKZjeoK5O)Lh@R5>hEa%uuDT9w;E8TFgEmLIN-8r68cau}4+ zWky7YzhE&uZBv|+>?^)MzO$~J;?M0VGf7j?FN(KJ$F#ADf3zL9fZ#7$jg+)=B2#4$ zn>%y~R9p?|wt9I~#y3V%Dy$f~gu`F&q*naaN!X}+>6OqTy~RMt{5y$cO_ppfMM?^Y z_N{n{C0aW4I@4Gok>u99YJkJ$yU6=|CF_p^)QV*-pDFU{>nw3P)tpg}rdyB0XvVs8yyiH43k>0_ zoN~*+V^Wj#3X3i>DATP-sULE?yI@w8*Hn1O^7WPR#-ELu>^FTY!Grb{RSo1Ok_85_ z)Q>+q945Ah$l{bUGQa5QJ4(3Om9RQk3Xb&iX;wsvZi}PME8MEuq#1fxKZR+jh!E^dfg40NEMy z4G8u)Zy_Zvu{cv>_fx)uTiV8&cq#pUuQW5^J*cf$KS)5Yq&$Vz2!h|~j~X(= z|AFQ*(p&8pO1nt;K&P0qnysOt_!PJuoO4Ryn9<yzogD?}==SvYLGF5&!5519hM(^KyI)EP!nB0@SgWJ_B@1(}`(_P=Tx48+p^dq%P# z%?*3_B?66|jBPaOkP#$p`hA2186aH{JhZjoxTqbYHiCdL9+zjY+?atre(BA#`?BMM zpeoH&U>@hCpY_v9_mrG*z?t0B)6JPzS>9EA`hqs892G|X4$3zT3V%l<`JC+gcoOEWwE9o)b8Qpj z7801o+-SHp-;Fx3#X(F=LetSss>Ykf zY#*hD^lwT`@IapIfSACc*UMotdOKLbl#kshBY%`VdyCF$P*;~#YoorkL!XCv-qF&D*BTVD@{hD;Y4)tayFjhn5HT2svH6!f z5wBC``v6qV!jrLaSWMK@4R36$Yqtp+dDaxJeX2AFC`A8Rlc`1loZtc9z)dCHb_sWX zsSLZz-?&ed>mMM~Tj7-Q^n~6UerD&qcX;kuOOFNnIIZ?HD%I;*#LH5( zJNg3_xG>1XUfpj3-hxYVfcjDwaHF_M(nO7`0rnmBZi3AG^xL-a&pCa)b`goYhAVw8 z+r@l?1}WyHE*mF%I8M|UCrgqjt`8<4jc{E{6vD+)SH+`TYRk|%yC?RyilPax=$b5CS5XDUqH3BqRVzg<;;j>IC3&?M zXQM=)y~tG#k<-9GyN!fhe6(TH0okNBvx<#nrINtM*wox}>WIPCa@AY%4B)>oaNK(f zhxe)6#Kag?r)NyS(WZ`7T-td}C7?g?Tcdt`Rrgj=NieHHl4(0p#5Sjoed z*&a1X0UFUAR;+=teVYyrNCx#P8K8PISw^#=}o|;WL!>fy-Vnr zigt&RHl_0?E+iPUb%xWc{X^6@x0v(6V~RJm&(}7n2>y=W}fORe;Fp7vk6y~PvgMIH8f6KPEb>WSusq4>io8tqYPY7i~t?)dXL zJ+RDCKu1=xkKan-D{Rol^71|$K)%Q}zm;6!P&z@(8)}jcJL~$A#ufWbYB55IPQ&A2 zy$bbh^)E5M5)&3{4GJK|k{>zH>p5Z5980^eZZPdT#rekXk8k-jdPy-B*>CpX(gdM zgB`?V`NP4@mgjSLSdQG>_#&%5BA!vc7Whq?N>+0tZxgh84_mrn#LKsfk1#7lL1gp; zBIAsV6M1%O5&X<@iR>1! zIv&fftU+b49hIz=_Ajy-=lvEA>bq)Ew1bmEHWiOAdiG?+6N1k-QTD;jT*cK1c`?!w z`tV^;o_r;>({SA78eJ0-=@b82Q!%`0aL!k@>gbQ1n;z9}kkR5PGwJXdiLhrY-ocDF@D#`)yR1 z*y|19%af5o9n&iKf7>3SS!faT+nX8LLH)C($b5%7q_QO9iH;u;$dIoxkIq*_)JWk` zjrC(?jyOM9nB#F~@Vh(zv3$OJ^S2D{ChKnn?0R4XB9&h^KaOo!zz=xNikP*Us<8wE z2k<$_Dh_OTdo$>t$|?N92=(?xf7Ij=aPGvmw0^@;u^E10cxXKRjdXB6#WiXAkH<&S z4=9E>{c20n?TV2%ng!Si8a4WL$+h&HRs-#yBUqtLya_n1a)Lv&8lLBW^8P6+NNGF} zyD+X`ybo614<|)#l~|jU6}07cm_@masK z=)jMO(Pmid7PF2&R@m-(_5{h?| zC1vOc4n$4Vd~-1SI_w%EG7_r4T|%R3XlJ$2BlXi+@N+%dPUuniH+`*NyJp!Xv%M-M zDA{MQBxNejZBMdVn%TfT1y&D}2c&e7dj!;gUbE0{$IZ+~nEBy@=G_O{z>Q#Sz4Z`S z-%H${fsCZcV{OK6kTX0dUh+!w*AzK59NA&2!&NelWa*Y0D2BZ^X913zMaUO;C-Vg; z1s;hrJOX`j)F=|MG@T_1Ek^G8GB7)Q)&2=OLU~LiuQ(dJ-)~$h82uz@yaFL4v)(Zq zX~AI6brNaz{tTch&oh>$UnK zo||tzQ|z#4g;8gm@12uzd^GRzj4ZpOU7nvzjjIuSxA6sDk+Cga=htb!^W9H~Dy>`0 z&!KSM?y+?eFyX>6JvvcZI`|U>t;ulqW@*~4dIcPn-ub>-n2g|&o@JB-lrL&(=h?l+ zOVh>EKkNLV0FdXVY+*67p`z5+(^X>#!(vFrD6L!K7Az}W#OdG$7N(l2zjsWczfJ;+ zt7;#`cN;`549Rhwx{>qz#m+Q-QOmrN!tf-e*p`H;i*SM(dk7H5CS+sM_7O=sL4jEdXJyFQLR#`|Z~RBhG+s?_px5BE0*qojmbwA)hEbtNcEi#VPwm4E>608?pzAG+-} ziqYLwi_nGQrS(EvUMHqL8pC#!EaPaN26@mNl6-k1=bh93mV+=KI;{!IeUk5hN#B#gtoc!#sJsP~`tNOUOJ=TtjtHvf#1^Oa^%K%8V&uCWmN(Gh@1rxG^!KEQ^O zLccDBdyPOB?s@}V*?)5)N4!uw1$!V?t3|h4luG5$hx-T$!`wK+>UQnu=1z0cE;}N5 zw{>Nv?da&bvR6WeVuJOhCmO7#8AUcOSNX8bx%pcBn#e~#B+LsIC{8?anpGSx6=HqW zfdoxwO)osOU&C8w!+SEQ@?o;0v%kFWU{ z?#<6gnMTRhW`;m5=Ww3*z7<$GTdT*x(8+-+@7@*PHI&DFZ{_>@JOm}77o~GKJ$RV! z@9aUBmJER1qr?ZeZxssWANQu&_E!XPfNa7LPOi*EHl$Um? zfY8ZFLrUrY!rfDMP#vr(%pq0bQd4}- zvXzMNt?NA7es>77AhZ3x`8=nq*W|t`eA9ABsC(R&bJCwI69I5TA#P&3VwPvYaJ_9) zne%YM(m6_PPjCz}g|Xi>dzOLG-$?AeADWT~IgxcS@6ar3tVd0W3u3l%qO zDm;7A@!GtJs;w>+dLXY2@3`&!1Q&jbU)J4<(QQ4o=|m;6xSHIcHYaz>0u`?vkwSoT zx>AoG9apsD!n7^Xoxg3ziiv&t#SSOy6_d%e&Gvqi$6oMXWT(Zz-+Kwjj%^}NDjQs7 z4656rUmqXVwa1<1mm<`rA{Ky0wZ>@35x2ahsV34AU2*Rz|8-3#(?!_d(p{ujJwn_8 zX%%xlIvA^b?znm2cJ-`!Fm0gQ{*WLo3GA%{<`IoN`{j|WT^GqpQjlCNXcXD!t z@Uc$f@Co&gTmjBu{Im!;*F(jinovtrUKGXOOm`l|(y7!P*TrQ4IL14f;?Dbdhc0J+ z@V3dvvK}@`()oP`F2h99nVM7izH#)DawO!|GYumZTlccF7|uD_8rXdSai@p<3Wl4` zf66A6A11(u9U2fI(rd@21gNxT(e-~p0uPBZk$)^7*3})QvgA5w7hB!k1z3Em&F0~! z%Om8)8Vf0Q$uahV`fWi?nK4$P;oh*jnoUq@Inzu>K6P|UQ9`@h{J4C%m)dcK05ZLu#U;+OiDnc??g>Ztt2@d&K`~z)@xD>GcF-Uc8)<4)K$M6{#vqAUZ#pL-+kXYBSv1@a!Y{_JiQ&!r-it91G_@6Gmx#db6ju- z1t>&B{d&e=TvrTt$>0$;RiJD)nkxk;WPF#+NOytkDwv?xxe81OY7d50ep0{08~$Fs zb<&_M5bv5;mDboJwsJ(uTZl+R{7W(_q$K`y44!Nxb#0CsphGj+%?EG>uMN>P z41z{W_uj!@<-SKps15V%L9W=y)1VFw4F+$1R|-U(*_Zq4aojAKfYW3k;&+CM+oE8m z#2$cIgqQw;FjhS4QjeYVrG(aZ_y^;7_TmN?Au7PmLJja~2mi=SyJ&V=+kf8dme0y~ zuN)x|rL(=O4BgqoYb(aEGnX1QORyZ?$0#Ts9KwB0$dcrqELS~ z&pkaH-#HlyuEaZm!6=@~`0HWqE&732t7*qm@ljl|)6RRrOpdV@r^=^6w_@(iPo*zC z1t7nY8bOYv1H0>L{SiXcv}IXg2?+b1@&1Fq^K_N&x<9z`ImhbZugR`1YZ6%#+pUPg z!wHZD0hkBs{=ajCz?cFy701zogJYbuQ^hU8LhK6YfW~w24J19xf2^ND0|Wm zCJPjUkwo~oRLeN7CK-%8{{zSmGA4;y=S0TwHX8R@ETRu=%fRk9c@uj8&>W#OI zb6l&aS-mr@WVq6uOTDcDsD%01j#C3LLmj#MM%b^rDHraYxOpt2mx`OwuO)jlzoH7z z*?7)1s#>Q(5$zh(+pthwwHjB;pBe$xGkaz2TC)%Rf`6ilk|_*BoP=LAIY8tI*bSv! z(BH`OBa~eH0=NwsSFG(GHxo7|WVh`*j-0iXBT`WIC}gX4StvS2*&O2HNGOw4u43gy z#SGtIw5&Zx%i1f%OMK!2^mes;TT@78*;3$k<2YQ8jt^Wi)`yxUa?$Ou8sVNRbzc>K zn=t1YPd%Wd#TbNxT7N0%A2S@Nbi`V|;ep~}hAMavO2yB7;XI<#01-zKMDm~ILQna+ z=S;#I6xG03`d!Be2_F6xuBuo6JyjCGg(Vas?vukF9xJS8|Ewtbbf7*tWN=4AG#k5i$81k9iinBm`l1yz zhf{?Qm_+*B)PE>r3bu~T!jQ?{;4C-cZ;K3V+1`{#%8MR;hxppLq;&di*sWVtWd z{2Has!+grAAIa!XxCDn%2F9kf>T-Nt?}@E%-Jd!sbsW!Z>J+P0DG#kjQIBG zG8T!{BZE>_jQ9K~7M(Bje)SB^3f7bUprjqUKl>7rcEcuJ%uD8EpdE9nI+KBvl4{od z3!z`3aT|9U`=Gm1w7@0TQZD}jlor)CMdR3&RV_~`t|1T!|HG)xq@8)*gU|2Kh-mfA z`xF`P!FaZSdl`ZsTG~c3Gp5=WSP~y2m=Z%DlC>gsXXboKkxiy)1W4w;+Ue;jlGsNI zC=jRD2Z)b#-{Z#LzYRt5vt1EGc)klks&MZ)aT{PliZL5n$h*JZOuLeUoO-(BHwYfe zh6-LjDJajZeXl>SWs7< zD$cYg#C}8q!`;p@(@~p=r=2S^ zwyyOfRn|OLPQ3ls(h8>A5kXsL0Y@5t1!xMK>0&L(h3d}%(7e#p-#oh38c#IW~|@X7%Y`!=o~cn=C+s>jdd}ZT~>( zwa(U73!SXvi+uqhIIV}NFxl@bjw4scXOCwC9M&+fk2cv$J3%w$fxpuh5{HKqi9s)T zKE*OPa5hnzAT~5p)AQ%2w;rDZNT5}SEGwWeN)}GLp0E>0>Ti#n^J8PhD^4@D3f^Fj zq0QF7&z+RrUeM2AkQAyMJVXU};@|2yo;6H83TrF=V)2*Ivf6kB{!#hsP=s{J_DP4~ zkrZjwO8&y`MV@xC9=L|o)ezZYq=IqF`N_!YwB^G;yr&jLT@$^|0EF;F{3)X+vrG7g zdx;e}KkOk@7qwW0)z#HLPkjV`4~Ib_)zkn-rs$2ksgpATj0f_zbMVuv?SOh4Z?$u0D4+@$+f;)UmkQq4 zMbI(2no|Nbxg(iO6SW&BMl&eJoVGc-TCKVd-mUR->}z#j2dw-XNCqIH|86vZdwMB|$N7Y+x>UD%;?PpRA9E92tC-tV3e+7^u`*}e!+ zy2dAa8U~u6ycIsld-I`dy8(^Ptdut39o*x&8m0I^D1^&YPO?$6=L(j*^&!nyVOu>N zBz7#fy5O3}l@X8BA$yaGheF;K-lvMH4+GeXDjm-F%vYx3>BZtAqS1Zy@Z&jPlZf_z zE01#k$7~{ee6(T#F$UtAI`)dd92I#Q5#7lr_hdp#%?9sI zI0q#TezNYP&->jOtWurs&@_T;VXo$#kB6>WA_=Gcy)*nrc?JnKrtdYLCS(=?<4wEW z-nsi)I_f~0GF5EAu>KX_SEsJ-iK;>RX9?qKlQ1|6fc<$4rh7r`>8C<${gs{rFWhbouE--mgje34Wnd5% z!sS8v@Z$$p@r8#fb0NqPO6U4w>i{i>skS-=(*)hT(()Z%n($*uEr1JGxk1vg_O#?!*gF2)mC8*h(3IvIeQhy4G<$(%eRR~eaKw?5j`Qgp z`VfEx=WKpKC&Da$ramso;Z+#krpVQLmW|^Pgd5yz8;qK`9 zEtn+^0sqe6Q&a;1tl@Z>H8in$eP~3e`l^R6eQ2x8GxJk`{`p{09F4M)`u@Fk4aeutitWZI6aZ#-QR;1QG~f;!@mJ>4I5 z@=efQ=6UfqUs;*-L6D@!& zzHGqN*6|SA3*!>^RJ2&>*EHOzZrUNu&u3!Yr#W@wegAgv;6n3SqXA@Q|xX@Uw_g&U;rIZXlK6}lS4HlB-*P1(2pUC5< zF?Lv9Z+ILQOn>pVerO$w7L+Nf3lww@nU&w70h}6Q<-8)-NRzpV#ZR*)N>sa#>EG!c z!7+5^q~rbBe`V!?22WK#Cn+gCzGt{FR|Q=;OSx*P11c`22rT`zC6}MkExU-Z891rdH275GyTP)>qCD_sXrs;jjUAX== zPG;@_${6CXV3P^sL{Pw?THDngN9h^@=aRbe1`p@vwkC#Vzyol_#Y5JgtRE-NJw18N za1<(%Nw`;%Hb9ssYH`aSsY&1BKaxGGRc|(-6hTkWj@S2toTL1??(pB&O}}@!+L=J^ z8}q!!ZoYT8vRBIabeAz|*2#`0+bl8~eZXGF$zW-j5?2OI0#5n$`l5AZ;lu&H(hG>W zldhKmHmktOdk6oh{Y(tY701LvKF6K!@_S;n7HbHDb9P~DCLDPt&L?|i1+wl&2U`7N z+dh!J4QsXYT}=Nfn&1*>W1IK&PTa#{Bn)dc*L2AVwuE!_amdAcC05vG?{dOy2UAZd z-P0AsL%DlpgKN+?;0N{Dj+RoD7(=$A3au73F5qiCjRAvVZk>uV5WF^JzFdu)xITuw zjT-_wA?`pOav&g$qubH|3mXh>D}2`QRYH2JJ?z<_rfQhjywb)vV94uKdjE;7Puygd z@5rFJU^cBY{lQqJ+TGj{x z2_yV^jir(;uDX_=9L_I!rAEdz<^~!pf^mZx&3=v5&iY7Ls5{W6Z8PEuE;IO_-0H z@a>);rVL=dF4a|n2h~O>h;!DOP0&d+cn+IX9_2Wo(h5g3xSgFe<3?7{wZ6{P!y#sq zeKmSPqFCSmVL7I-kghx2PT`oSSmS-ZggNKC#4)e%Ug*Dh6`n zCh;3AG=;j4==pr*iRMS1o!=5w7U7dTd`C!1B**lX@Jg$xCInoff6X-9Klwp!axi)6 z+Hn}vp4w>I&Uz;f#4)B#11fotUuR*fcD%0FUG-d`R>skQC=>Fp!NFZDcH=A)m1{>z zUZv}66gdZk%Kz?}QP$`50^S97V}*RBx1Z@v9gl*~k8@1Rmuv^bJ{NSq7|+u^WL zOZ=C1+Y`!tcAIW7xWT*%N3d_Z0YyDZjcd4DUC!cMz?L9rP3-$fRx==*o#mwi z=yS(8V4TdsR$ez_SnN3E=&ExpKQyaMKIMWp7RrUHLjQF&LfjHq(?UD|py1gbROQ+w zV#pU_5V2>EDd_qAHmJkLs!-wlZA7+#m%0jDW^X(mi=vc zWLT+NAAb5H+m=ZVsD~w*ezUdI72`Mu9+;pN^87i_N&9*=oLU=Fh#kA@?dfI3`&W$} z0m%T&k@@%=@$Om`=O=f&X7)@<8TFCN5XW@iwYBQz$C>s1lzE@0Tnz@-xH(!|fjm;f=;W4c|Wl zO%yA6VF?t1%ZJv~jifo8vS$-)dHBj{=0*hLnQrbdAf(OzC}IyJS9NrePV#ywNFe7SQ@aOeqqkB)=@Q5 zy51^9_R4wHDRZMT$CeF@EP2&3aPBBOnr(&?S)Lx>WMv1gp?|tdHy@!j8Gy2l)uYew zmx@JqoW?R4!vP9MfcH{I=bF*_n!)NZN11zKXLg$Y!kE!{lQUgG*vPu#;18hqK%*N+ zW8By{Li?t_<;?i>mY&u?Q`78b`q^Z20kcLJ133*jd#qJhvaQ5x`-!^7#n~j(5{Qt;ca622I-0sK3x9I-0#WtQ zkgVA~kaXlR#Ci`sili+!mPU$*HAzQ-zEpnhZ0t3$>T34XPnCFx zE-r8P#d;cT#tF^Df1vLrW!s+n1W#V-H}2yMx&Q6_nn00J;tFwuxmH?E>WaJB<1+(g z0OVaxgQRW-+fqYJR!_bMpH>e%9IMMX1+mpWY}pB$yDKea4-nxv@XX zahf6{F9&C?P?PU|0@#lId>B>!9IT$(V(-mfs7jvpo>|*%+%C8X1=9&KO>b6m_#nOHFhFD0_Lii^uM}X4OYj z=+w3kJ)-gzpr}Pg!)paDI$yCC9&vLwo?V>qjFOskU1F-S5HDd&^2pgtNm*a}C_-mw z2^^|X+g-Z7*y1M{0y59ve4GCf`fGoPQ|>obX<{%9;!ASOk?(cN#&ERZZK2#eFtaqa z@!)ZmHeTMRgkZ;so&s7LX-z>qX!kyL96nycU2BW3`r{Mg!*6UQ|9&C_6@UcMC|GIz z0p24pFgRUU6$|jancKxqFq1JZPUz)a$YBA4#ZW&$f@miw3T>2zds4I9D|+52WrB#6 z%hBhzl(rp0x2u$Y_+lbv%>5jh!%9f4d4V3H`@npNA$kLn*g2)7S=v+!t4!@mYU_ zl0XYNA}4?|qrOFaAaO~p(u@j0#*&P35Rhr_36Dqgb_%un1S+GwVdp$ z@!^T9EdRolCbpJ^Kl>}M7uD*i>1m-iMRwQ8`Tr$$@^K#XZ{Hsi6I?PFKst`LoClu5 zN@O_Tp^hMErS(x*9p(QacCJs5C)Am*Uj!TfVG8aMRKJ?N9)6kn@as*nhRz>fXgi_b zL6uU3`69_APp1e^$I3Ohwvu(05Z(z5BOop?Al$oSq4Ut}RT4Ppvsm2N)p8lc<@&vh zC`qG}9<85(;C<(=;vR=XiuC#zmL-4M@Imh1gF(L^=UA&$v4aNuimjh4ku3U5Qm_-o zx)nZ49jzS;{=l*Fea9#R3Sh-ViR7zLkLqt-+{D2g#@4HuZ$KE3b+!CBk-z%DM=tv5opyJN;PYZ_Y-}z#ZT)b0+I=w zepvES_<&tx{HtIiXe%G8HXl9!dx;hj+&GlfH2LR18&2BLrtA-$GQ<0Ec6 zR_L@bOA~iv_pF?sdt}zS1oSLPmST3mA?=|ekZhWBx1Y3w92u?$II;~KrXr)6W8f&Ccfu-NsaecRyL+1`dKZ6~vdF9sxNyi>+jA5*Kf z;{SvjZpH$*Ax)*JYk7HvZTxa=IbiFh-dom5KWoVWz$>Y!M+0j~X842JS9~ONN$=$C z_>6*AVhY$7$8xUe8(@rrTn(Uf$tfzy_W9cU29ZDPJIGNsQlxs;4r4V$-HcphcHPS! zPvazUrEXDC9&qgEKQ#czTz@Yl^B8O4|5h|=5U$WH(u2cH$KClV?w|$gl9u0heU3~u zx+eRBiHjhm_sEK&O8@#Mt9cL+w`)B{=Xe=8e2hoYQ~9qY5W(vgnW$;5R)au2Oh{Vz zfh%@G)G1rUxIRkOGoiCON)p&8GDB2T@5%}GE*aWv+&+<&!l3VfGmKKKW*990#l-WI z%S6{|pg!3x6d??eq`WzY-yXhAaP!c3b*ScV%%4=ckrA$Xt3jC8w=;L&fwnI$LHYoC z>nDt~wk1KPzkxJOIMA%R*jed4u+?59jrX+6o%+GlYQ9xzWJw_q6qeG&#A?r9?Puwe zsp*xnXR#mp&^#v)b8^OO_j+ALGl5FaufR^=lCJ59NXGQzbrmvizkG@0>j|ns{WRKm z<&mKcytKJWMkU|$iyoWW1I=YuCPK9R=z|;UZ9&43XzZ+GTJ>O39THOJ|5e*t2F2Ai zZKDu^1Pu_}5=bBfcbNf_;4Z-#+}#BR0?TdPbT%Wh2I%y}mU1s#%MW;}4hmUliRHg0tovPCGOUCs997=7F&)ouf8Q{a)Ys z_0nc*7I;2R^nHUX(%JQD6QPtG_DCtTMMYNa^As?EU<&hy-I(upuF9JE18 z*^<=rIT-M}69bC~&z@h%UpV|8F<1B%gf9mQhxb+}4l1%xhwfhDVnuESllJ2IQeI&2 ziVWm^J8e*S8dHxUGStB7=19E>4a#(_vC!L}6TO%y(rbWX+JDZ%2+MpisWj%lo2fF} z8}oN*x}|Scdve{wTr;7duGYaY3TjdU(f=I|-`X8gX1n(1&f+N{DsU18eGvj?tAqaz z*Q!WW&tg7c-DahFu9gm^MsVTL7mt3IhTIB3^_mJs^Tq5+0C18r^PwDj55OEzKFOECK4zScGe zb83sfqFQ^{zFi+!l|QGn!T_;Ck(QnIsw^)5DNuuKh;&eNmc4oHdFHGq%nC!>_L*TN>jy-qm0-*1l%-xL8dI{A zV3&wPj>mq))mtl%oOco`4neWHG>#r-WZdVj0R#ydR_Zsv$-UOjGC^zt9$P?<(i!W` zew9GokN(lZdo5aw#l;Yfc1?qY4O_gDC*y9BNh?KUF)Fm3aNa7PTqn3qXQ-QP!>bHR3@>;a=r5bNe&qO! zbw@3?>D*N{$Nfj!ia4dJ$n>RaReu|$6`U;eJeMMx;L;&D+55KC^KM%U*b_`>wUk3g zd{LPeUt%8gIiJmx9~AYOoy|ltM~VrbI?(Z~sD18gSmdS>tu6Ic2DW?pBqB=fefVxE z432Zi`XedfXP$x{_#Snq<$)yPW4q<8Iq+3=j|lGKRIn3zE_)As$D=ABUzmn!YQuo%3$SGyvjM2j1d z(Eu3P$J-^PPtj*S&lk0F$RYl%QPBbZKaA_AaR}nbN}Yh$p|P>ao>qgb$FY>z+FAw% zn8ettF5L#~$ANrnRg+D6mID{8ETLgZ@uE@$yQjp95Ca9}Xno($4ufl^h=QOsv&UJg zQ?XuRHbwmMm#9Uu(+r`ftD z&`cz)S`BdnaZoJgsJMrdW=@NbNGJ-K$2lc*RF~(cfSFVzKe@xaXT>?0D82{CDjX3@ zeyZglS`u5o(ncAM`r7;Edr~n%!FbqW;E}+w#^!47ml#aT<9o}+W2+*;Id&WFS#^ER z+9&zp%7Q75+(9MksxDG1<1mR_tQc4&sdqxwz#H`0X=Oz5?sGj?LbK0_ z_%$OB%itZ=G6s}kL(rhr@ZyubQFKl6c|vGJeCZF!LPA?~n^_+cWqQC*3g3{3xCkjl zWtSTak#+dnt`N2y&e1d9N>eMO~%VJPD!M;kD-IWUf~f(=Z0?vj!e*cXa->Uv-TZ>X|UR<$Ad9 zi!PqNfL0#sJ{GU=O1AZUJE`nF8#)9nACw&9ZcXj+_#voPb%Q<3tqp!!K|{ST0Y;6 zXt1X_h?JKIrQvgh3o4Z%X0jJuY))CrmfU7Fo!ADO)c+CdYsJO&T#fAS^J3w_23vi^ z3Gf$}G~}k9c4%vZ>p9#qSm_m`>c$oOlLw%Qql!60#rUF)^RaAn&NxcOD^A!zh!i&M zOU}agA-k}sXn#yBA^3uWho^Fe^+^cdqr~At;~~NXEd5)EskIYBymwj<_dtASeHg{` zWe?R@i8_%>l?gs9Y%D3pLB9mZ*x2m;9!&0wku!RAoHd)LP4N-f(d~;%oR-$aVegG) zEho(crzV5nbfHKt4wI&BSiVfHa9!M5icP$;nr-J3oO*QBoB{LX$lLJ4&Jh@KxdTPp zeagT)@*#98UkzM=zxckHjAg})I8T*g`6fL_7OwxEoj+Dx^p*X|HQ=I?Y9o%gy+QZ#;WC$p=yHB+J zm+CYUZUEJ-czVP$;Pv>&`{;v>aT}fKb#( zq9$LOJ;+e;;4Zl`arK#xw7o^PHDEwntL%&KjFPQsw^AM^rg+5;9*a}YH+^8d=uEYx z(|vcN-tDU1lNwkn9DY3}r&^;+%~sG=YH{oOaWBf?Yx}Q2(XzdF1HkV;zLdne)B!Je zU%Yq$CEW)N?>SJ?5^qC|3MF8pshucdqhgd)_|nv3qcQJMQWY>SpELG61)7mc9H42p#U&7It((zxL-7<2O5}$MyjWEMdrMr5@4Or=IJxJ< zjb$pT9_t_e#t$tT%L4z9v}>Ha$8PqBtUS}(Q3yS))4YY}I6Y94RB;EJ&RlqShbnzo z`cxlI_2bI^wNlNFKjVNbn@^XSo~Gv}TGWkrua5k;Y=Qr_a`6{WQxG3-@(rSx0-N#nixM zNbuVoO(q}eKK7H&eRSTs2koY5P5gYEIkQ0|iu~dPet%;s3%*TJ$+frkeyB7X(tjI% zHYfNf(Bxe{HSYVvl?}Df&XptrcRxrv#{4>=wC8#8sQ|eijjp;@IRkZb&h<}|*=lX+It19) zMOMD}fSehsGIZVc#-XU=gaJ#mOwnMIF{5+xVrvL97x<0ToUP_S^5qe z!|C?9=$Pd#G0tPW{V9T?d) z>8_>5sYYC)A)AHYPL`KDlo#Q&E~M1H2R61Wq2?yKnMM@Ic`EaI5rze@StGhvCeEw(CpqV!Y3%b47zgKytE&tOT?vwiD4gCK& zn*aAx&IQ3+9n3EtUBO|i#F^k;QUjWZ+u_KHC@N}0p%I)1Yv9`Y#**D`V9}fvRhiQ< zIs1pY$6}J`Id`U{OcLq$r-$5$i+MbMJu@51UIiFosTa+3bNs4h!7>qh?R_e>3~-R? zVrYBu4zfAGm7WNotDo;;vUwKxs_@2@u$gqCW=&H&+gz`!wmYuuT~srb=E=OfHC3^} z3SH9H&^^}7xx04>*x+8W`;4lp`|lbLc4#6kN!WxQzU7r2V8Fx-vmLbcRydT>*0s3~ zwd!S|NGDpwz3;%rQ))Zf{L%j=TH4W1(0pM%W^wXp)eCpQ)eK=a=>eDvRl|uTiLV;` zrL7;}-1lxT%cGo7ls>sk(yjU)W*;BdOwTc!Bh<*#i-&BkZRImuY4w5&rGnDkniFd6 zKhvb|b&~Ajn;JCrWm-;z%T~alRm>}=_kqg%{QmHToK6Yh4kY)jXew6laQO6DkoFAV zO_C2C{i=7uJ(NsrEpOKbIc|@m63GOjSvK}eHeBdo=5U zcv~pVfJhFLM3Ua?W*q_?CO^=tJI3@I09xo%(%R|%W->IwbNY$ zMopK*0j!Z~ZI6MktPaT5#*6T^*gvjN;iBh<1SB23g=BTL{k6+ zPW*uUDVR&^i2>Kp%O=oZ+LAMC?jDR9u~+wkP{S`h_Wt;e%o6u?M?FM@1#5sCL$2R> zN7S*^S>BY+R2-Sq=53X~K-GRbS`CPQ)`+wG z#C9PCnod=zs$08hs9i6=dASK~+8yzY$%jW!6QTsXt&2(v)f8Wa`A*F4@j%P6*Y0Td z8CA5?+)^h0A~3G$N2hK6(B|ldw_2gMeN#B8bW>Z2i_dWGaEhVY9b1XecR(&XlJHJEy7dw4Vi{rwmF;8DAqh9p5sT^GEJ0_{@cVu z5AcZHpN|hLrLVMe0A!lyIN34Ds4E^xePER6GM#(vuc{a;3oeKwh3Qbl8~QzWl7ECj z8Fv|_h+=25Jd%YrftwdI$ zp&-hZsYGH*FlHD$oQ9=m8QV2FdV+s;6 zoUFU%L%~G*GYuuzxCMFzMK}Ampt*q+@1q2|s2CN`)qMRH{F*HrArqdy*Tu zPs1QwSc|o+ow(U`wA+i>vv%TS+%$eTHB}e-eL@+Ek?%{>4zJQV=JkWh2@Yjq z%E)cs3wXMvplmn?@z(E&t>rqJ|2D@{!pzZl0&6)ZmvWC1Ze%5>w4?ZEBedtz<`E(b z0vzBZ*Rp$FQ#^*k3rjy-Ktz=xL5RXfT?bttkH`JWf=Y<+z!F#eFT-Mw*!8Ge=9_Kb zZ8aV*y&Tcr5=$#+JA{#~=*QJ{rbcT?g4TrQOdaPD|HlWHmC<*l4s^9xZn{N z+Cs@_sVWuGnBB}ZdoKbvr+BM3CNfmB?y_TL-vz{vUzXpB_)Id4c52#s(JoF>GbEP? zYxV`s64~7AN}r}2q-DNuI3m7=M&ft}vTrz!u0}6M=r*w}YQdk>Z2Pev$-p5Aa3q#1 zX#m30?r)F!6ZDtHGrGJxrw80y+->>rv;JGapfU(hWHa+P==us=E@5Ty7&MGg^x=T- zan)-RQO0Q%Xp?ZB<%VXuJ^Qy3WgR5d=4=48BeOIs;a|KZT|?F-)a6zFlJ5_3m|XDt z_(Dm_V0c18;$*7M_0wp!#Kxw1-Di40w3L1pMfe{%DsF^#`=nYEkcirXtc1k{LMaF= z#!**)mYKNxzBb z4MkNaxt%udh8o8rq1Bvcr4$ZLxbw8#e)L-3h{oBO1R`-C%&@@MI|LRQsWC@Fu#V;F zKDA%b1nNR{zYQc+ZZixxO8_ExMO-?bBRfQ8HWwk8f=dcCppTm-{c6IVGg*oY6KftX z!}HcVegH6(CTh)RC}h(&C0tjm`}%#>$a$86JlQ>?mn!Gc7@tJWqgzk%D&+u{;qlAq-Gzt_0R25WBMSzO8pd)X!7Xd-AZy58U&a@+ zPZ1AOp$%#z4uvX0dND3W-*N~i2(WVA5YxYfgYEuDvJ!g>hJ5a@1tCs z>BIV*g_F(-(yBV=gPgQr=w7@t+)v;&A^mRJ)8P6I{NDC(OO%9Ws1n{0{dE6yG}nEX zW~UzXI7<02x&tva^sY`dY$ooao9-o{Q*DXP>Sw<>U4b{Ib<4fl7iRCF zQ@`zu<0t&`k`sB+>NP&H3YQaA(FXNFe9l9^1leSsX_ShD@yq)&hkmT`b44uTl-=~lCRM<%vZ9kmJ`1wT_Z$w$T~@v$6$|p!hmaQRy6TQo z>f)vdPC~}5yzbTr@sl*iaNS*7t!>2+N7dK0>q_kELlJlh6PfjxLNy^@T$R(fnU-I< zDt&b+1Iu66|NLt}w_iGt4Sd5m%PAhuw6?+1h$~H?NG^V9b~bz<7xpJhx9<035s=3iy}%*oS3-Sc z&a41735lfL9-G91^Di!ngw5s+_M^@Uj$!Z-KBa48IFA!4bGa>(=dAUnx36EUJyDX& zd{^J18D*CId^_D#;l$mcd;$p~``(1-f|3IORxd1Jlk)t?0=>i|dchvKY1Z_7WBR^F zPhTx}{?eGzE_CxJO#`!4|NCgNet6Au&d_q3-c^vtIAik7k&8RuFMcrxdJ76~1Ud%t zW~Que#?nCfkV?{t-d*Jr@tqL6-`b+f(ke3>5DCF-;d zvycwU_61I#{DrtosvnI+Sh3b>;`xHY*d*$~(KV2_Y%B>8?r`j$#tz0Fa}_bAY*Yz! z;)c4-H#+g0u9hj^W-i3F7%`(!%cT=l=~ePx6TYz;SuCtIJ-Bd6Di`JXoshw{noF{5 zZ^x2AaqFOEDHGVX*Nc=dB;h6DKqf}NWo_7MQGqjN){cq9HTZk9vOA#UFcUW^ZeSsW z@?@#SeeQULigv~>F>#F6rc9mB+Ql#%5>^ZT(5I-7Vc#wi#9WE@*QdpNVfN-i zynGt&Ed`>IsCjIn*2;|L*Ol<|4zj5~3i5*O`54e+#|zYLvJjV?t%DB zJBbrZi#<{C6-Ksge3Q@dlgFNIx&2V`5T3}I9#!ZR?s_HGa+D5rRL>G5Zma2Vrn`hq zH_Omqyh^+7o$O33EpBz$OBOv4ON3qfBIr=q@5K?>k&5vJMP@gZxeZ@RO4lta+H=o8 za91F7pYE*--HJ+uwO|29qK_B@mPMgR`;)pw<5m+IZ*1swAE$hxZuoP`jIFdoIRFmgN+px*Hqk)I#h4J=^U@zc?o%d0VMJFYe3NSF(7oq}R+zgHf+Q}Fd;3UU%2o80(%e8=Q_ax!4sPWGd6Q|#<^kp!l*8__ohypxx z9>Tqw5Bs4)(hJYA{pxm_h)mkm6?p7&X$@qFi1eoYq?9L-3J7kb!7VeBei#yf9OLv~ z+29~Dn+vd+b^c^hd7lG##~AddR4?RxW_U!{mqCIL)(EY57aPvEIj(2plvuX&Ygzlc z^Icw?17;4cd`a-LSk}H{8*PfgxsJf7Gw+q1o)0|RuZw#X{7N^&ey>vD7EAD1H#Oi& z8(Nmg{ysjoqvY{mQ0n@r3ricezh$cc{6-1UH4MN8TQE0Fm{GR6`LL~~4u6=$Q6tQf{KYl%+>osB6a9hwXo?A@LDDr8v8l4@3&@# zWQUTe-ET*#HG`H6&T6?6ESogC(x8nu2Ok6A@y>E|NlHEsbhAMMj_i|AJsI|Te)Y0k zTivLl8|sB&H7C|JlV-SIYO^Ns{e*Y`1pelZniG0AlYfAQ^L6}TLH?Vo8BG!;q;Ut8 z0_Z>G-+dbUI#?!oSLsNn0-wUg@!0aFj}7?HEFH^!+&nkKL&?ViRR51eWwN6x=d)&f zi}?Bb_(mEu#vP5^8f-MH{feRKi0+)5gQEVAQhFz@6}j&#JLR(Evl$_g1lhZz{n?EP7*CfJY4+06vYqas(2VoTrp5E1b3|%wJBuOADsqE z=1o4x;u3RJ7zYLoP0VpEQ=2?;dZOE#%H|AMQPR#ymUsKpfcaPs8@ws4tt;K^$R_!~ zB-U?~r0oecj$ypOyaIjo16!AEgq{hkRFA&uC~OH1tvnCNJCnIWRVGYhrqjM*heb=V z1U;P?%@FkqX@VJ`kE%Vu2GUK#^-IGheyhO%$&5LOgUUgBx0bYn&2Kf}@u9!z3}kZQ z=5u*VwmD8iB-h|T;T)3Gb3-xRdG^+BXlvy`{_Y-}eruQAgw`TPr#Tx_eXrv^a!@=; z5PpOj)78bab!wFCYyfjErCN4nxRF*Y$q$X^Vjd<@O-VS1)s_`;(m> zNve7EAEl{nm-Bi#n_4KZx{75H|L*#Z*Rms^`#;*PG0JEvjwCxJ80}W{l0#W+B}Kxx zmo9Fh$;ZRi2AL6?NEA~pLJFgTimJHLzhqt%c{FL7@f;A3l)rt?dIZtD10r5+EF`G# z84+UClzi{or!<_DI3R0EbYGNQncw961JsyL<6g(Ne5#q5wEu{x~4!Dpg5vfyS{niMh_+i4MhUD#eFD=SC~f( z)(oTE0aQKCp%ub`J||DEoM;THJQz=Ty#lN+Fl)U+`f!&CE|fZFyoo{-1ar_x1m9}9b-iQn7j=g z&MW4K=>}bZ?<#$|b>woD@f1O#Z)iL$E&A6ssr!ync-j8#$oRv3@mcq>*RO5j&s{;b zAGf(xkWgt1h{R#u8QL{{NR)nco^%DIU0b_^vYGn}_Y8`@cA)hdhVB3j*@`i)Llmq}g#`Ak>*ZWa}@^psG_D(kf?%xb_PWjOg)gS@*u|<2gpZ4IzB7^0oyC)<-hj?N8;53<$mj8}2r9ag+h`sF zDTAs1OXt)sj_66~K#*};_2VL9x!98Vn)Ft2`vCTXsKCW2^%pPttarWH5wDWR< zdcKGeV~uqCs+#=)^IT(oLFtl7uRZx`tZ13M#??a0oRuieiK_L*FXfprs4yM2IJ*ee zj2=*yPLxlbQR;yN81kuK<;_*Whuy)K3+=zy6$T4rc7OvU&{y%FqqhW(ZpZe^DSP33 zl9ZkRKHfM66|nLJx^M7MDonmgQf)cNj3-et2_ab27&EZXf-gfC2f^w=CAI5M$&`~3 z)vU*Dd`z+3No%k)^JeNSr2G6)4)y6`QBhOWApzpRZ8!OgY>9r1zi~pi%Lb>f5 z8c}@+?E&k{867JwKj8d+JkPUFaiXCmiDaVXbz3_{E-?vzAn*Nlr}SMDz$?=nCGO+| z-=cZr6GDiiza>~t>xDrtGG&N+{Pc119SP^7*36dgwW~Pk(!2Fg21oaf&&69FG`dv% z`f4T*&dF!{{qFa$#fP?NHGFJQi&!Uv(_DD=yyq9s&^F;x)xxPl#TTevh4U_=z=M_p zn`P#A+NMC21PAE8>8pXrNBr?pn8?pZL+iB1k;ga)^naEGx62=X9q<} zMQPI83o?q?2>#Dfl!JvJn+Unmb-f6JH$DRfzarv9Ws-^d2pqnjn!+IJ6~_(|F+6&H z*nMldap&iB+i(_&LQ&phTiGHxaSXSYH|saEs#HN|jgLm_VPU>O<)~p_Z|!39=Z_6G zsDi7}w+7~|%Yf4Fs&x|$*D92Cr@bBv!Nevr zxMSh49eyOVoz3;FtI#CoLIhiHU50L}+{f`@kWIu*R@`&6o2q<#&R|g+ws9Qjs0E9t zDilbbqv&vMIbi*EL40=r8iDh)5)zQDvgh{<5?H}T58vp?D4&1JdI?f;&u{Tj-+e^PAU;Np3w0Zu6VE6ky$fi7!eJlz3vg)YLCI}Vr!FJwEJ&uVY@r@A2>^EY z?g9$S^>M#xATg$(NCV!r{=z&f4I;l(;K+N_C*{5_v2@IuK4EFNn*Tvy?I1^R5`~Gr z-me3f#Hz+z+Kbe@loKO7!WCcG>a~*s`P57yIzbxF;FjYqt40sJbFZ3@ru(DzAf=eor8omRjj5a7QzDLioKI)Vc@R#6@rJh4T@J zGjwM^v4-@oZ&@xz0Kw=kN<~>Z0xxA13T&2_V9mB&zr=;EmmC#Yy+8;+DQ%l&IcqiI zZ7e6PqOVVaFq;embC+ygbZ>Z={Tf%fvBATV5-bf&nO<;=)*JPrYS%B|;yKd4L^Smm z9&0|>8spHuE2=x)f0T1+Rj({jPl~7WWp;0+$Aa#wYs!CG{cE}8&{ZmuUhZ7K@D~0tkyerhN)2bUM((kwb`Xb#rS;5nSF!o zX9NbO#HhCA>FPK`I3B)O>A?2}!UB%1akS$kn@liWnT$HgZNq z!SJtf_gdaIuY!JZ$DE{GGH443aXW=DdXfk+b>F-ED}dK{j4%bGl15*dzw{7zmy|ED z_upO4lhR7zjfanv8f=!&oRu=a_v0?8iMi&4>T@XwDRDs33LG89TW>AR6t1sGwlZrE zR?r;45@X8kUBiFhnMtCQ>ofqvdXAC}oit}hNt_84uFpRXB@_5>d#w`;1Ey>7*4er} z*h}dw(&s`dxlho%vm=lcwY_Ck_ONaQ+9VSC7gRvS8iSv+xnZaBP;WvFN>WZwkKWEW zXwUVCL>lT#r&j%%lvHEK9QAF$-P=KzG8a1b)b-y^rwb3WH2;E?vfXYk_NL0bDl1vT zBO)MwFNQwT+t+tA^$Q&INeBPJ%d!q&C!5?{_#&S?8}dy#Gqb%q`ejXsO)<*9Wz-xr z)ZbZ9o}Ph;d0f;%EXni#l*x8Nw8{>B?nXdvAtV6jW?F@0 zgLZIj_Olfb=m;F$K66)zzuU`vm%DTS?^nfPCRKYgR} zbU%SXlqR1fTmny3Rz4_tL2Xz?rm>wvJS_O%nf-GD3rarNeS@SeNjV2P)MWB!9xBZ1 z$xj3S4A$+ZB^4dQYXs$Em|C-OP+6={Q4p*am~3BGrv=Gl{{ZI?>R8JlX$+z79~9>ao$-wsZi z9(IqyTfcD%nRIzl+T(%~{QOGR6{!>L8JOZx&ahBO;*7oh4Lr7r;2l+KY> zl7Ul`2gFLGWiMHed_@p|VD*#c%_qVjCp=|nquwJY?IXpR zBgwQU@Q`1kWEO$@4oQ;}9|K_<&gJi^+tw%pET43ET=nMKWJ^JQPBF)Smy1ZumaI0t zaVo&aw8@hrC4zA(fH;@6BIyQshxU%kdmQjRBX(1eI_SvZ_U`(Zk5 z=bNR1Nj1@mWRn+9%||e~5?m!aWUlV)D$;TB+L8_$vEVp4*}Pf)`Kdz$X}?yAPqsv! zf0C^=&_}{195>oLDv)*Kifbdd_dTj02D%4=$&q0yRF-g>lt4!tyUCV>?oXQ)azi!I pcA3VMTjV7% ## Examples ```bash -ros2 run diagnostic_graph_aggregator tree system/diagnostic_graph_aggregator/example/graph/main.yaml +ros2 run diagnostic_graph_aggregator tree '$(find-pkg-share diagnostic_graph_aggregator)/example/graph/main.yaml' ``` ```txt -===== root nodes ================================= +===== Top-level trees ============================ +- /autoware/modes/autonomous (and) + - /functions/pose_estimation (and) + - /functions/obstacle_detection (or) - /autoware/modes/local (and) - /external/joystick_command (diag) +- /autoware/modes/remote (and) + - /external/remote_command (diag) - /autoware/modes/comfortable_stop (and) - /functions/obstacle_detection (or) - /autoware/modes/pull_over (and) - /functions/pose_estimation (and) - /functions/obstacle_detection (or) -- /autoware/modes/autonomous (and) - - /functions/pose_estimation (and) - - /functions/obstacle_detection (or) -- /autoware/modes/remote (and) - - /external/remote_command (diag) -===== intermediate nodes ========================= +===== Subtrees =================================== +- /functions/pose_estimation (and) + - /sensing/lidars/top (diag) - /functions/obstacle_detection (or) - /sensing/lidars/front (diag) - /sensing/radars/front (diag) -- /functions/pose_estimation (and) - - /sensing/lidars/top (diag) -===== isolated nodes ============================= -- /autoware/modes/stop (const) -- /autoware/modes/emergency_stop (const) +===== Isolated units ============================= +- /autoware/modes/stop (ok) +- /autoware/modes/emergency_stop (ok) ``` diff --git a/system/diagnostic_graph_aggregator/example/dummy-diags.py b/system/diagnostic_graph_aggregator/example/dummy-diags.py index 08f81bcd738ed..210462271a1ea 100755 --- a/system/diagnostic_graph_aggregator/example/dummy-diags.py +++ b/system/diagnostic_graph_aggregator/example/dummy-diags.py @@ -53,9 +53,9 @@ def create_status(name: str): if __name__ == "__main__": diags = [ - "lidar_driver/top: status", - "lidar_driver/front: status", - "radar_driver/front: status", + "lidar_driver_top: status", + "lidar_driver_front: status", + "radar_driver_front: status", "external_command_checker: joystick_command", "external_command_checker: remote_command", ] diff --git a/system/diagnostic_graph_aggregator/example/example-edit.launch.xml b/system/diagnostic_graph_aggregator/example/example-edit.launch.xml index c168b76f19c21..d56f76b1726cf 100644 --- a/system/diagnostic_graph_aggregator/example/example-edit.launch.xml +++ b/system/diagnostic_graph_aggregator/example/example-edit.launch.xml @@ -1,10 +1,6 @@ - - + - - - diff --git a/system/diagnostic_graph_aggregator/example/example-main.launch.xml b/system/diagnostic_graph_aggregator/example/example-main.launch.xml index cdc1bc8afca53..b7019640e993c 100644 --- a/system/diagnostic_graph_aggregator/example/example-main.launch.xml +++ b/system/diagnostic_graph_aggregator/example/example-main.launch.xml @@ -1,10 +1,6 @@ - - - - diff --git a/system/diagnostic_graph_aggregator/example/graph/main.yaml b/system/diagnostic_graph_aggregator/example/graph/main.yaml index 2bea907d9c119..b48c1ebe801ea 100644 --- a/system/diagnostic_graph_aggregator/example/graph/main.yaml +++ b/system/diagnostic_graph_aggregator/example/graph/main.yaml @@ -2,7 +2,7 @@ files: - { path: $(dirname)/module1.yaml } - { path: $(dirname)/module2.yaml } -nodes: +units: - path: /autoware/modes/stop type: ok diff --git a/system/diagnostic_graph_aggregator/example/graph/module1.yaml b/system/diagnostic_graph_aggregator/example/graph/module1.yaml index 07d4951b89446..1e1ae9b994587 100644 --- a/system/diagnostic_graph_aggregator/example/graph/module1.yaml +++ b/system/diagnostic_graph_aggregator/example/graph/module1.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /functions/pose_estimation type: and list: @@ -12,12 +12,15 @@ nodes: - path: /sensing/lidars/top type: diag - diag: "lidar_driver/top: status" + node: lidar_driver_top + name: status - path: /sensing/lidars/front type: diag - diag: "lidar_driver/front: status" + node: lidar_driver_front + name: status - path: /sensing/radars/front type: diag - diag: "radar_driver/front: status" + node: radar_driver_front + name: status diff --git a/system/diagnostic_graph_aggregator/example/graph/module2.yaml b/system/diagnostic_graph_aggregator/example/graph/module2.yaml index a03701b661ba9..47e100087c650 100644 --- a/system/diagnostic_graph_aggregator/example/graph/module2.yaml +++ b/system/diagnostic_graph_aggregator/example/graph/module2.yaml @@ -1,8 +1,10 @@ -nodes: +units: - path: /external/joystick_command type: diag - diag: "external_command_checker: joystick_command" + node: external_command_checker + name: joystick_command - path: /external/remote_command type: diag - diag: "external_command_checker: remote_command" + node: external_command_checker + name: remote_command diff --git a/system/diagnostic_graph_aggregator/launch/converter.launch.xml b/system/diagnostic_graph_aggregator/launch/converter.launch.xml deleted file mode 100644 index 9111338bf622a..0000000000000 --- a/system/diagnostic_graph_aggregator/launch/converter.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/system/diagnostic_graph_aggregator/script/dump.py b/system/diagnostic_graph_aggregator/script/dump.py deleted file mode 100755 index 9abcaeb7a080c..0000000000000 --- a/system/diagnostic_graph_aggregator/script/dump.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright 2024 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import argparse - -from diagnostic_msgs.msg import DiagnosticStatus -import rclpy -import rclpy.node -from tier4_system_msgs.msg import DiagnosticGraph - - -def print_table(lines: list, header: list): - widths = [0 for _ in range(len(header))] - lines.insert(0, header) - for line in lines: - widths = map(max, widths, map(len, line)) - widths = list(widths) - lines.insert(0, ["-" * w for w in widths]) - lines.insert(2, ["-" * w for w in widths]) - for line in lines: - line = map(lambda v, w: f"{v:{w}}", line, widths) - line = " | ".join(line) - print(f"| {line} |") - - -def get_level_text(level: int): - if level == DiagnosticStatus.OK: - return "OK" - if level == DiagnosticStatus.WARN: - return "WARN" - if level == DiagnosticStatus.ERROR: - return "ERROR" - if level == DiagnosticStatus.STALE: - return "STALE" - return "-----" - - -class NodeData: - def __init__(self, index, node): - self.index = index - self._node = node - - @property - def level(self): - return get_level_text(self._node.status.level) - - @property - def name(self): - return self._node.status.name - - @property - def links(self): - return " ".join(str(link.index) for link in self._node.links) - - @property - def line(self): - return [str(self.index), self.level, self.name, self.links] - - -class DumpNode(rclpy.node.Node): - def __init__(self, args): - super().__init__("dump_diagnostic_graph") - self.sub = self.create_subscription(DiagnosticGraph, args.topic, self.callback, 1) - - def callback(self, msg): - nodes = [NodeData(index, node) for index, node in enumerate(msg.nodes)] - table = [node.line for node in nodes] - print_table(table, ["index", "level", "name", "links"]) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("--topic", default="/diagnostics_graph") - args, unparsed = parser.parse_known_args() - - try: - rclpy.init(args=unparsed) - rclpy.spin(DumpNode(args)) - rclpy.shutdown() - except KeyboardInterrupt: - pass diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp index 39044d1c82bf9..9005084f84503 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -14,341 +14,297 @@ #include "config.hpp" -#include "error.hpp" +#include "names.hpp" +#include "types.hpp" #include +#include #include -#include +#include #include -#include #include #include #include -#include - -// DEBUG -#include namespace diagnostic_graph_aggregator { -template -void extend(std::vector & u, const std::vector & v) +std::string resolve_substitution(const std::string & substitution, const TreeData & data) { - u.insert(u.end(), v.begin(), v.end()); -} + std::stringstream ss(substitution); + std::string word; + std::vector words; + while (getline(ss, word, ' ')) { + words.push_back(word); + } -template -auto enumerate(const std::vector & v) -{ - std::vector> result; - for (size_t i = 0; i < v.size(); ++i) { - result.push_back(std::make_pair(i, v[i])); + if (words.size() == 2 && words[0] == "find-pkg-share") { + return ament_index_cpp::get_package_share_directory(words[1]); } - return result; + if (words.size() == 1 && words[0] == "dirname") { + return std::filesystem::path(data.path().file()).parent_path(); + } + throw UnknownSubstitution(data.path(), substitution); } -ConfigData::ConfigData(const std::string & path) +std::string resolve_file_path(const std::string & path, const TreeData & data) { - file = path; + static const std::regex pattern(R"(\$\(([^()]*)\))"); + std::smatch m; + std::string result = path; + while (std::regex_search(result, m, pattern)) { + const std::string prefix = m.prefix(); + const std::string suffix = m.suffix(); + result = prefix + resolve_substitution(m.str(1), data) + suffix; + } + return result; } -ConfigData ConfigData::load(YAML::Node yaml) +FileLoader::FileLoader(const PathConfig * path) { - if (!yaml.IsMap()) { - throw error("object is not a dict type", *this); - } - for (const auto & kv : yaml) { - object[kv.first.as()] = kv.second; + if (!std::filesystem::exists(path->resolved)) { + throw FileNotFound(path->data.path(), path->resolved); } - return *this; + + TreeData tree = TreeData::Load(path->resolved); + const auto paths = tree.optional("files").children("files"); + const auto edits = tree.optional("edits").children("edits"); + const auto units = tree.optional("units").children("units"); + for (const auto & data : paths) create_path_config(data); + for (const auto & data : edits) create_edit_config(data); + for (const auto & data : units) create_unit_config(data); } -ConfigData ConfigData::type(const std::string & name) const +PathConfig * FileLoader::create_path_config(const TreeData & data) { - ConfigData data(file); - data.mark = mark.empty() ? name : mark + "-" + name; - return data; + const auto path = paths_.emplace_back(std::make_unique(data)).get(); + path->original = path->data.required("path").text(); + path->resolved = resolve_file_path(path->original, data); + return path; } -ConfigData ConfigData::node(const size_t index) const +EditConfig * FileLoader::create_edit_config(const TreeData & data) { - return type(std::to_string(index)); + const auto edit = edits_.emplace_back(std::make_unique(data)).get(); + edit->type = edit->data.required("type").text(); + return edit; } -std::optional ConfigData::take_yaml(const std::string & name) +UnitConfig * FileLoader::create_unit_config(const TreeData & data) { - if (!object.count(name)) { - return std::nullopt; - } + const auto unit = units_.emplace_back(std::make_unique(data)).get(); + unit->type = unit->data.required("type").text(); + unit->path = unit->data.optional("path").text(); - const auto yaml = object.at(name); - object.erase(name); - return yaml; + const auto item = unit->data.optional("item").child("c"); + if (item.is_valid()) { + unit->item = create_link_config(item, unit); + } + const auto list = unit->data.optional("list").children(); + for (const auto & data : list) { + unit->list.push_back(create_link_config(data, unit)); + } + return unit; } -std::string ConfigData::take_text(const std::string & name) +LinkConfig * FileLoader::create_link_config(const TreeData & data, UnitConfig * unit) { - if (!object.count(name)) { - throw error("required field is not found", name, *this); - } - - const auto yaml = object.at(name); - object.erase(name); - return yaml.as(); + const auto link = links_.emplace_back(std::make_unique()).get(); + link->parent = unit; + link->child = create_unit_config(data); + return link; } -std::string ConfigData::take_text(const std::string & name, const std::string & fail) +void FileLoader::release(FileConfig & config) { - if (!object.count(name)) { - return fail; - } - - const auto yaml = object.at(name); - object.erase(name); - return yaml.as(); + for (auto & path : paths_) config.paths.push_back(std::move(path)); + for (auto & edit : edits_) config.edits.push_back(std::move(edit)); + for (auto & unit : units_) config.units.push_back(std::move(unit)); + for (auto & link : links_) config.links.push_back(std::move(link)); } -std::vector ConfigData::take_list(const std::string & name) +TreeLoader TreeLoader::Load(const std::string & path) { - if (!object.count(name)) { - return std::vector(); - } - - const auto yaml = object.at(name); - object.erase(name); + PathConfig root(TreeData::None()); + root.original = path; + root.resolved = resolve_file_path(path, root.data); + return TreeLoader(&root); +} - if (!yaml.IsSequence()) { - throw error("field is not a list type", name, *this); +TreeLoader::TreeLoader(const PathConfig * root) +{ + std::queue paths; + paths.push(root); + + // TODO(Takagi, Isamu): check include loop. + while (!paths.empty()) { + files_.emplace_back(paths.front()); + paths.pop(); + for (const auto & path : files_.back().paths()) { + paths.push(path.get()); + } } - return std::vector(yaml.begin(), yaml.end()); } -void resolve_link_nodes(RootConfig & root) +auto create_path_mapping(const std::vector> & units) { - std::unordered_map paths; - for (const auto & node : root.nodes) { - if (node->path.empty()) { + std::unordered_map path_to_unit; + for (const auto & unit : units) { + if (unit->path.empty()) { continue; } - if (paths.count(node->path)) { - throw error("object path is not unique", node->path); + if (path_to_unit.count(unit->path)) { + throw PathConflict(unit->path); } - paths[node->path] = node; + path_to_unit[unit->path] = unit.get(); } + return path_to_unit; +} - std::vector nodes; - std::vector links; - for (const auto & node : root.nodes) { - if (node->type == "link") { - links.push_back(node); +void apply_links(FileConfig & config) +{ + // Separate units into link types and others. + std::vector> link_units; + std::vector> node_units; + for (auto & unit : config.units) { + if (unit->type == unit_name::link) { + link_units.push_back(std::move(unit)); } else { - nodes.push_back(node); + node_units.push_back(std::move(unit)); } } - std::unordered_map targets; - for (const auto & node : nodes) { - targets[node] = node; - } - for (const auto & node : links) { - const auto path = node->data.take_text("link"); - if (!paths.count(path)) { - throw error("link path is not found", path, node->data); - } - const auto link = paths.at(path); - if (link->type == "link") { - throw error("link target is link type", path, node->data); + // Create a mapping from path to unit. + const auto path_to_unit = create_path_mapping(node_units); + + // Create a mapping from unit to unit. + std::unordered_map unit_to_unit; + for (const auto & unit : link_units) { + const auto path = unit->data.required("link").text(); + if (path_to_unit.count(path) == 0) { + throw PathNotFound(unit->data.path(), path); } - targets[node] = link; + unit_to_unit[unit.get()] = path_to_unit.at(path); } - for (const auto & node : nodes) { - for (auto & child : node->children) { - child = targets.at(child); + + // Update links. + for (const auto & link : config.links) { + if (unit_to_unit.count(link->child) != 0) { + link->child = unit_to_unit.at(link->child); } } - root.nodes = nodes; + + // Remove link type units from the graph. + config.units = std::move(node_units); } -void resolve_remove_edits(RootConfig & root) +void apply_edits(FileConfig & config) { - std::unordered_map paths; - for (const auto & node : root.nodes) { - paths[node->path] = node; - } - - std::unordered_set removes; - for (const auto & edit : root.edits) { - if (edit->type == "remove") { - if (!paths.count(edit->path)) { - throw error("remove path is not found", edit->path, edit->data); + // Create a mapping from path to unit. + const auto path_to_unit = create_path_mapping(config.units); + + // List units to remove and links from/to them. + std::unordered_set remove_units; + std::unordered_set remove_links; + for (const auto & edit : config.edits) { + if (edit->type == edit_name::remove) { + const auto path = edit->data.required("path").text(); + if (path_to_unit.count(path) == 0) { + throw PathNotFound(edit->data.path(), path); } - removes.insert(paths.at(edit->path)); + remove_units.insert(path_to_unit.at(path)); } } - - const auto filter = [removes](const std::vector & nodes) { - std::vector result; - for (const auto & node : nodes) { - if (!removes.count(node)) { - result.push_back(node); - } + for (const auto & link : config.links) { + if (remove_units.count(link->parent) || remove_units.count(link->child)) { + remove_links.insert(link.get()); } - return result; - }; - for (const auto & node : root.nodes) { - node->children = filter(node->children); - } - root.nodes = filter(root.nodes); -} - -std::string complement_node_type(ConfigData & data) -{ - if (data.object.count("diag")) { - return "diag"; } - return data.take_text("type"); -} -std::string resolve_substitution(const std::string & substitution, const ConfigData & data) -{ - std::stringstream ss(substitution); - std::string word; - std::vector words; - while (getline(ss, word, ' ')) { - words.push_back(word); + // Filter references to the removed links. + for (const auto & unit : config.units) { + if (remove_links.count(unit->item) != 0) { + unit->item = nullptr; + } + std::vector filtered_list; + for (const auto & link : unit->list) { + if (remove_links.count(link) == 0) { + filtered_list.push_back(link); + } + unit->list = filtered_list; + } } - if (words.size() == 2 && words[0] == "find-pkg-share") { - return ament_index_cpp::get_package_share_directory(words[1]); - } - if (words.size() == 1 && words[0] == "dirname") { - return std::filesystem::path(data.file).parent_path(); + // Remove units and links. + std::vector> filtered_units; + std::vector> filtered_links; + for (auto & unit : config.units) { + if (remove_units.count(unit.get()) == 0) { + filtered_units.push_back(std::move(unit)); + } } - throw error("unknown substitution", substitution, data); -} - -std::string resolve_file_path(const std::string & path, const ConfigData & data) -{ - static const std::regex pattern(R"(\$\(([^()]*)\))"); - std::smatch m; - std::string result = path; - while (std::regex_search(result, m, pattern)) { - const std::string prefix = m.prefix(); - const std::string suffix = m.suffix(); - result = prefix + resolve_substitution(m.str(1), data) + suffix; + for (auto & link : config.links) { + if (remove_links.count(link.get()) == 0) { + filtered_links.push_back(std::move(link)); + } } - return result; + config.units = std::move(filtered_units); + config.links = std::move(filtered_links); } -PathConfig::SharedPtr parse_path_config(const ConfigData & data) +void topological_sort(FileConfig & config) { - const auto path = std::make_shared(data); - path->original = path->data.take_text("path"); - path->resolved = resolve_file_path(path->original, path->data); - return path; -} - -UnitConfig::SharedPtr parse_node_config(const ConfigData & data) -{ - const auto node = std::make_shared(data); - node->path = node->data.take_text("path", ""); - node->type = node->data.take_text("type", ""); - - if (node->type.empty()) { - node->type = complement_node_type(node->data); + std::unordered_map degrees; + std::deque units; + std::deque result; + std::deque buffer; + + // Create a list of raw pointer units. + for (const auto & unit : config.units) units.push_back(unit.get()); + + // Count degrees of each unit. + for (const auto & unit : units) { + if (const auto & link = unit->item) ++degrees[link->child]; + for (const auto & link : unit->list) ++degrees[link->child]; } - for (const auto & [index, yaml] : enumerate(node->data.take_list("list"))) { - const auto child = data.node(index).load(yaml); - node->children.push_back(parse_node_config(child)); + // Find initial units that are zero degrees. + for (const auto & unit : units) { + if (degrees[unit] == 0) buffer.push_back(unit); } - return node; -} - -EditConfig::SharedPtr parse_edit_config(const ConfigData & data) -{ - const auto edit = std::make_shared(data); - edit->path = edit->data.take_text("path", ""); - edit->type = edit->data.take_text("type", ""); - return edit; -} -FileConfig::SharedPtr parse_file_config(const ConfigData & data) -{ - const auto file = std::make_shared(data); - const auto path_data = data.type("file"); - const auto node_data = data.type("node"); - const auto edit_data = data.type("edit"); - const auto paths = file->data.take_list("files"); - const auto nodes = file->data.take_list("nodes"); - const auto edits = file->data.take_list("edits"); - - for (const auto & [index, yaml] : enumerate(paths)) { - const auto path = path_data.node(index).load(yaml); - file->paths.push_back(parse_path_config(path)); - } - for (const auto & [index, yaml] : enumerate(nodes)) { - const auto node = node_data.node(index).load(yaml); - file->nodes.push_back(parse_node_config(node)); - } - for (const auto & [index, yaml] : enumerate(edits)) { - const auto edit = edit_data.node(index).load(yaml); - file->edits.push_back(parse_edit_config(edit)); + // Sort by topological order. + while (!buffer.empty()) { + const auto unit = buffer.front(); + buffer.pop_front(); + if (const auto & link = unit->item) { + if (--degrees[link->child] == 0) { + buffer.push_back(link->child); + } + } + for (const auto & link : unit->list) { + if (--degrees[link->child] == 0) { + buffer.push_back(link->child); + } + } + result.push_back(unit); } - return file; -} -FileConfig::SharedPtr load_file_config(PathConfig & config) -{ - const auto path = std::filesystem::path(config.resolved); - if (!std::filesystem::exists(path)) { - throw error("file is not found", path, config.data); + // Detect circulation because the result does not include the units on the loop. + if (result.size() != units.size()) { + throw GraphStructure("detect graph circulation"); } - const auto file = ConfigData(path).load(YAML::LoadFile(path)); - return parse_file_config(file); } -RootConfig load_root_config(const PathConfig::SharedPtr root) +FileConfig TreeLoader::construct() { - std::vector paths; - paths.push_back(root); - - std::vector files; - for (size_t i = 0; i < paths.size(); ++i) { - const auto path = paths[i]; - const auto file = load_file_config(*path); - files.push_back(file); - extend(paths, file->paths); - } - - std::vector nodes; - std::vector edits; - for (const auto & file : files) { - extend(nodes, file->nodes); - extend(edits, file->edits); - } - for (size_t i = 0; i < nodes.size(); ++i) { - const auto node = nodes[i]; - extend(nodes, node->children); - } - - RootConfig config; - config.files = files; - config.nodes = nodes; - config.edits = edits; - resolve_link_nodes(config); - resolve_remove_edits(config); + FileConfig config; + for (auto & file : files_) file.release(config); + apply_links(config); + apply_edits(config); + topological_sort(config); // Check graph structure. return config; } -RootConfig load_root_config(const std::string & path) -{ - const auto root = std::make_shared(ConfigData("root-file")); - root->original = path; - root->resolved = path; - return load_root_config(root); -} - } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.hpp b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp index 40f16235ed5d6..a22daf907a27e 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.hpp @@ -15,114 +15,87 @@ #ifndef COMMON__GRAPH__CONFIG_HPP_ #define COMMON__GRAPH__CONFIG_HPP_ -#include +#include "data.hpp" +#include "types.hpp" #include -#include #include -#include #include namespace diagnostic_graph_aggregator { -struct ConfigData +struct PathConfig { - explicit ConfigData(const std::string & file); - ConfigData load(YAML::Node yaml); - ConfigData type(const std::string & name) const; - ConfigData node(const size_t index) const; - - template - T take(const std::string & name, const T & fail) - { - const auto yaml = take_yaml(name); - return yaml ? yaml.value().as() : fail; - } - - std::optional take_yaml(const std::string & name); - std::string take_text(const std::string & name); - std::string take_text(const std::string & name, const std::string & fail); - std::vector take_list(const std::string & name); - - std::string file; - std::string mark; - std::unordered_map object; -}; - -struct BaseConfig -{ - explicit BaseConfig(const ConfigData & data) : data(data) {} - ConfigData data; -}; - -struct PathConfig : public BaseConfig -{ - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; + explicit PathConfig(const TreeData & data) : data(data) {} + TreeData data; std::string original; std::string resolved; }; -struct UnitConfig : public BaseConfig +struct EditConfig { - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; + explicit EditConfig(const TreeData & data) : data(data) {} + TreeData data; std::string type; - std::string path; - std::vector children; }; -struct EditConfig : public BaseConfig +struct LinkConfig { - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; - std::string type; - std::string path; + UnitConfig * parent = nullptr; + UnitConfig * child = nullptr; }; -struct FileConfig : public BaseConfig +struct UnitConfig { - using SharedPtr = std::shared_ptr; - using BaseConfig::BaseConfig; - std::vector paths; - std::vector nodes; - std::vector edits; + explicit UnitConfig(const TreeData & data) : data(data) {} + TreeData data; + std::string type; + std::string path; + LinkConfig * item = nullptr; + std::vector list; + size_t index; }; -struct RootConfig +struct FileConfig { - std::vector files; - std::vector nodes; - std::vector edits; + // Note: keep order correspondence between links and unit children for viewer. + std::vector> paths; + std::vector> edits; + std::vector> units; + std::vector> links; }; -template -T error(const std::string & text, const ConfigData & data) -{ - const auto hint = data.mark.empty() ? data.file : data.mark + ":" + data.file; - return T(text + " (" + hint + ")"); -} - -template -T error(const std::string & text) +class FileLoader { - return T(text); -} - -template -T error(const std::string & text, const std::string & value, const ConfigData & data) -{ - return error(text + ": " + value, data); -} +public: + explicit FileLoader(const PathConfig * path); + const auto & paths() const { return paths_; } + void release(FileConfig & config); + +private: + PathConfig * create_path_config(const TreeData & data); + EditConfig * create_edit_config(const TreeData & data); + UnitConfig * create_unit_config(const TreeData & data); + LinkConfig * create_link_config(const TreeData & data, UnitConfig * unit); + + // Note: keep order correspondence between links and unit children for viewer. + std::vector> paths_; + std::vector> edits_; + std::vector> units_; + std::vector> links_; +}; -template -T error(const std::string & text, const std::string & value) +class TreeLoader { - return error(text + ": " + value); -} +public: + static TreeLoader Load(const std::string & path); + explicit TreeLoader(const PathConfig * root); + FileConfig construct(); -RootConfig load_root_config(const std::string & path); +private: + std::vector files_; +}; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.cpp b/system/diagnostic_graph_aggregator/src/common/graph/data.cpp new file mode 100644 index 0000000000000..ff186098c32e3 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/data.cpp @@ -0,0 +1,97 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "data.hpp" + +namespace diagnostic_graph_aggregator +{ + +TreeData TreeData::Load(const std::string & path) +{ + return TreeData(YAML::LoadFile(path), TreePath(path)); +} + +TreeData TreeData::None() +{ + return TreeData(YAML::Node(), TreePath("")); +} + +TreeData::TreeData(const YAML::Node & yaml, const TreePath & path) : path_(path) +{ + yaml_ = yaml; +} + +TreeData::Item TreeData::required(const std::string & name) +{ + // TODO(Takagi, Isamu): check map type. + const auto path = path_.field(name); + if (!yaml_[name]) { + throw FieldNotFound(path); + } + const auto data = yaml_[name]; + yaml_.remove(name); + return TreeData(data, path); +} + +TreeData::Item TreeData::optional(const std::string & name) +{ + // TODO(Takagi, Isamu): check map type. + const auto path = path_.field(name); + if (!yaml_[name]) { + return TreeData(YAML::Node(YAML::NodeType::Undefined), path); + } + const auto data = yaml_[name]; + yaml_.remove(name); + return TreeData(data, path); +} + +bool TreeData::is_valid() const +{ + return yaml_.Type() != YAML::NodeType::Undefined; +} + +TreeData::Item TreeData::child(const std::string & path) +{ + return TreeData(yaml_, path_.child(path)); +} + +TreeData::List TreeData::children(const std::string & path) +{ + if (yaml_.Type() == YAML::NodeType::Undefined) { + return {}; + } + if (yaml_.Type() != YAML::NodeType::Sequence) { + throw InvalidType(path_); + } + + TreeData::List result; + for (size_t i = 0; i < yaml_.size(); ++i) { + result.emplace_back(yaml_[i], path_.child(path, i)); + } + return result; +} + +std::string TreeData::text(const std::string & fail) +{ + // TODO(Takagi, Isamu): check conversion failure + return yaml_.as(fail); +} + +double TreeData::real(double fail) +{ + // TODO(Takagi, Isamu): check conversion failure + return yaml_.as(fail); +} + +} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.hpp b/system/diagnostic_graph_aggregator/src/common/graph/data.hpp new file mode 100644 index 0000000000000..437e3793df398 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/data.hpp @@ -0,0 +1,56 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMMON__GRAPH__DATA_HPP_ +#define COMMON__GRAPH__DATA_HPP_ + +#include "error.hpp" + +#include + +#include +#include +#include + +namespace diagnostic_graph_aggregator +{ + +class TreeData +{ +public: + using Item = TreeData; + using List = std::vector; + + static TreeData Load(const std::string & path); + static TreeData None(); + TreeData(const YAML::Node & yaml, const TreePath & path); + + const auto & path() const { return path_; } + Item required(const std::string & name); + Item optional(const std::string & name); + bool is_valid() const; + + Item child(const std::string & path); + List children(const std::string & path = ""); + std::string text(const std::string & fail = ""); + double real(double fail); + +private: + YAML::Node yaml_; + TreePath path_; +}; + +} // namespace diagnostic_graph_aggregator + +#endif // COMMON__GRAPH__DATA_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp deleted file mode 100644 index 8f2b741edd805..0000000000000 --- a/system/diagnostic_graph_aggregator/src/common/graph/debug.cpp +++ /dev/null @@ -1,75 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "debug.hpp" - -#include "graph.hpp" -#include "types.hpp" -#include "units.hpp" - -#include -#include -#include -#include - -namespace diagnostic_graph_aggregator -{ - -std::string get_level_text(DiagnosticLevel level) -{ - switch (level) { - case DiagnosticStatus::OK: - return "OK"; - case DiagnosticStatus::WARN: - return "WARN"; - case DiagnosticStatus::ERROR: - return "ERROR"; - case DiagnosticStatus::STALE: - return "STALE"; - } - return "UNKNOWN"; -} - -void Graph::debug() -{ - std::vector lines; - for (const auto & node : nodes_) { - const auto level_name = get_level_text(node->level()); - const auto index_name = std::to_string(node->index()); - lines.push_back({index_name, level_name, node->path(), node->type()}); - } - for (const auto & [name, level] : unknowns_) { - const auto level_name = get_level_text(level); - lines.push_back({"*", level_name, name, "unknown"}); - } - - std::array widths = {}; - for (const auto & line : lines) { - for (size_t i = 0; i < diag_debug_size; ++i) { - widths[i] = std::max(widths[i], line[i].length()); - } - } - - const size_t total_width = std::accumulate(widths.begin(), widths.end(), 0); - std::cout << std::string(total_width + 3 * diag_debug_size + 1, '=') << std::endl; - - for (const auto & line : lines) { - for (size_t i = 0; i < diag_debug_size; ++i) { - std::cout << "| " << std::left << std::setw(widths[i]) << line[i] << " "; - } - std::cout << "|" << std::endl; - } -} - -} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp b/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp deleted file mode 100644 index 69a0eeb2c8023..0000000000000 --- a/system/diagnostic_graph_aggregator/src/common/graph/debug.hpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef COMMON__GRAPH__DEBUG_HPP_ -#define COMMON__GRAPH__DEBUG_HPP_ - -#include -#include - -namespace diagnostic_graph_aggregator -{ - -constexpr size_t diag_debug_size = 4; -using DiagDebugData = std::array; - -} // namespace diagnostic_graph_aggregator - -#endif // COMMON__GRAPH__DEBUG_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.cpp b/system/diagnostic_graph_aggregator/src/common/graph/error.cpp new file mode 100644 index 0000000000000..e78a444c5ab7f --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.cpp @@ -0,0 +1,58 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "error.hpp" + +namespace diagnostic_graph_aggregator +{ + +TreePath::TreePath(const std::string & file) +{ + file_ = file; +} + +TreePath TreePath::field(const std::string & name) +{ + TreePath result(file_); + result.node_ = node_; + result.name_ = name; + return result; +} + +TreePath TreePath::child(const std::string & path) +{ + const auto sep = node_.empty() ? "" : "-"; + TreePath result(file_); + result.node_ = node_ + sep + path; + return result; +} + +TreePath TreePath::child(const std::string & path, const size_t index) +{ + const auto sep = path.empty() ? "" : "-"; + return child(path + sep + std::to_string(index)); +} + +TreePath TreePath::child(const size_t index) +{ + return child(std::to_string(index)); +} + +std::string TreePath::text() const +{ + const auto sep = node_.empty() ? "" : ":"; + return " (" + file_ + sep + node_ + ")"; +} + +} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.hpp b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp index dadfab450c783..d923e12caf783 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/error.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.hpp @@ -16,51 +16,113 @@ #define COMMON__GRAPH__ERROR_HPP_ #include +#include namespace diagnostic_graph_aggregator { +struct TreePath +{ + explicit TreePath(const std::string & file); + TreePath field(const std::string & name); + TreePath child(const std::string & path); + TreePath child(const std::string & path, const size_t index); + TreePath child(const size_t index); + std::string text() const; + std::string file() const { return file_; } + std::string node() const { return node_; } + std::string name() const { return name_; } + +private: + std::string file_; + std::string node_; + std::string name_; +}; + struct Exception : public std::runtime_error { using runtime_error::runtime_error; }; -class FileNotFound : public Exception +struct FileNotFound : public Exception { - using Exception::Exception; + explicit FileNotFound(const TreePath & path, const std::string & file) + : Exception(format(path, file)) + { + } + static std::string format(const TreePath & path, const std::string & file) + { + return "file is not found: " + file + path.text(); + } }; -class UnknownType : public Exception +struct FieldNotFound : public Exception { - using Exception::Exception; + explicit FieldNotFound(const TreePath & path) : Exception(format(path)) {} + static std::string format(const TreePath & path) + { + return "required field is not found: " + path.name() + path.text(); + } }; -class InvalidType : public Exception +struct InvalidType : public Exception { - using Exception::Exception; + explicit InvalidType(const TreePath & path) : Exception(format(path)) {} + static std::string format(const TreePath & path) + { + return "field is not a list type: " + path.name() + path.text(); + } }; -class InvalidValue : public Exception +struct ModeNotFound : public Exception { - using Exception::Exception; + explicit ModeNotFound(const std::string & path) : Exception(format(path)) {} + static std::string format(const std::string & path) { return "mode path is not found: " + path; } }; -class FieldNotFound : public Exception +struct PathConflict : public Exception { - using Exception::Exception; + explicit PathConflict(const std::string & path) : Exception(format(path)) {} + static std::string format(const std::string & path) { return "node path is not unique: " + path; } }; -class PathConflict : public Exception +struct PathNotFound : public Exception { - using Exception::Exception; + explicit PathNotFound(const TreePath & path, const std::string & link) + : Exception(format(path, link)) + { + } + static std::string format(const TreePath & path, const std::string & link) + { + return "path is not found: " + link + path.text(); + } }; -class PathNotFound : public Exception +struct UnknownSubstitution : public Exception { - using Exception::Exception; + explicit UnknownSubstitution(const TreePath & path, const std::string & substitution) + : Exception(format(path, substitution)) + { + } + static std::string format(const TreePath & path, const std::string & substitution) + { + return "unknown substitution: " + substitution + path.text(); + } +}; + +struct UnknownUnitType : public Exception +{ + explicit UnknownUnitType(const TreePath & path, const std::string & type) + : Exception(format(path, type)) + { + } + static std::string format(const TreePath & path, const std::string & type) + { + return "unknown unit type: " + type + path.text(); + } }; -class GraphStructure : public Exception +struct GraphStructure : public Exception { using Exception::Exception; }; diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp index 5d7c11879a9cc..0a7d78a5ce982 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp @@ -16,211 +16,64 @@ #include "config.hpp" #include "error.hpp" +#include "loader.hpp" #include "units.hpp" -#include -#include -#include #include -#include -#include - -// DEBUG -#include namespace diagnostic_graph_aggregator { -BaseUnit::UniquePtrList topological_sort(BaseUnit::UniquePtrList && input) -{ - std::unordered_map degrees; - std::deque nodes; - std::deque result; - std::deque buffer; - - // Create a list of raw pointer nodes. - for (const auto & node : input) { - nodes.push_back(node.get()); - } - - // Count degrees of each node. - for (const auto & node : nodes) { - for (const auto & child : node->children()) { - ++degrees[child]; - } - } - - // Find initial nodes that are zero degrees. - for (const auto & node : nodes) { - if (degrees[node] == 0) { - buffer.push_back(node); - } - } - - // Sort by topological order. - while (!buffer.empty()) { - const auto node = buffer.front(); - buffer.pop_front(); - for (const auto & child : node->children()) { - if (--degrees[child] == 0) { - buffer.push_back(child); - } - } - result.push_back(node); - } - - // Detect circulation because the result does not include the nodes on the loop. - if (result.size() != nodes.size()) { - throw error("detect graph circulation"); - } - - // Reverse the result to process from leaf node. - result = std::deque(result.rbegin(), result.rend()); - - // Replace node vector. - std::unordered_map indices; - for (size_t i = 0; i < result.size(); ++i) { - indices[result[i]] = i; - } - std::vector> sorted(input.size()); - for (auto & node : input) { - sorted[indices[node.get()]] = std::move(node); - } - return sorted; -} - -BaseUnit::UniquePtr make_node(const UnitConfig::SharedPtr & config) -{ - if (config->type == "diag") { - return std::make_unique(config->path); - } - if (config->type == "and") { - return std::make_unique(config->path, false); - } - if (config->type == "short-circuit-and") { - return std::make_unique(config->path, true); - } - if (config->type == "or") { - return std::make_unique(config->path); - } - if (config->type == "warn-to-ok") { - return std::make_unique(config->path, DiagnosticStatus::OK); - } - if (config->type == "warn-to-error") { - return std::make_unique(config->path, DiagnosticStatus::ERROR); - } - if (config->type == "ok") { - return std::make_unique(config->path, DiagnosticStatus::OK); - } - if (config->type == "warn") { - return std::make_unique(config->path, DiagnosticStatus::WARN); - } - if (config->type == "error") { - return std::make_unique(config->path, DiagnosticStatus::ERROR); - } - if (config->type == "stale") { - return std::make_unique(config->path, DiagnosticStatus::STALE); - } - throw error("unknown node type", config->type, config->data); -} - -Graph::Graph() +void Graph::create(const std::string & file, const std::string & id) { - // for unique_ptr + GraphLoader graph(file); + nodes_ = graph.release_nodes(); + diags_ = graph.release_diags(); + links_ = graph.release_links(); + for (const auto & diag : diags_) names_[diag->name()] = diag.get(); + for (const auto & node : nodes_) units_.push_back(node.get()); + for (const auto & diag : diags_) units_.push_back(diag.get()); + + id_ = id; } -Graph::~Graph() +void Graph::update(const rclcpp::Time & stamp) { - // for unique_ptr + for (const auto & diag : diags_) diag->on_time(stamp); } -void Graph::init(const std::string & file) +bool Graph::update(const rclcpp::Time & stamp, const DiagnosticStatus & status) { - BaseUnit::UniquePtrList nodes; - BaseUnit::NodeDict dict; - - for (const auto & config : load_root_config(file).nodes) { - const auto node = nodes.emplace_back(make_node(config)).get(); - dict.configs[config] = node; - dict.paths[config->path] = node; - } - dict.paths.erase(""); - - for (const auto & [config, node] : dict.configs) { - node->init(config, dict); - } - - // Sort units in topological order for update dependencies. - nodes = topological_sort(std::move(nodes)); - - // List diag nodes that have diag name. - for (const auto & node : nodes) { - const auto diag = dynamic_cast(node.get()); - if (diag) { - diags_[diag->name()] = diag; - } - } - - // List unit nodes that have path name. - for (const auto & node : nodes) { - if (!node->path().empty()) { - units_.push_back(node.get()); - } - } - - // Set unit index. - for (size_t index = 0; index < units_.size(); ++index) { - units_[index]->set_index(index); - } - - nodes_ = std::move(nodes); + const auto iter = names_.find(status.name); + if (iter == names_.end()) return false; + iter->second->on_diag(stamp, status); + return true; } -void Graph::callback(const rclcpp::Time & stamp, const DiagnosticArray & array) +DiagGraphStruct Graph::create_struct(const rclcpp::Time & stamp) const { - for (const auto & status : array.status) { - const auto iter = diags_.find(status.name); - if (iter != diags_.end()) { - iter->second->callback(stamp, status); - } else { - unknowns_[status.name] = status.level; - } - } + DiagGraphStruct msg; + msg.stamp = stamp; + msg.id = id_; + for (const auto & node : nodes_) msg.nodes.push_back(node->create_struct()); + for (const auto & diag : diags_) msg.diags.push_back(diag->create_struct()); + for (const auto & link : links_) msg.links.push_back(link->create_struct()); + return msg; } -DiagnosticGraph Graph::report(const rclcpp::Time & stamp) +DiagGraphStatus Graph::create_status(const rclcpp::Time & stamp) const { - for (const auto & node : nodes_) { - node->update(stamp); - } - - DiagnosticGraph message; - message.stamp = stamp; - message.nodes.reserve(units_.size()); - for (const auto & node : units_) { - const auto report = node->report(); - DiagnosticNode temp; - temp.status.name = node->path(); - temp.status.level = report.level; - for (const auto & [ref, used] : report.links) { - DiagnosticLink link; - link.index = ref->index(); - link.used = used; - temp.links.push_back(link); - } - message.nodes.push_back(temp); - } - return message; + DiagGraphStatus msg; + msg.stamp = stamp; + msg.id = id_; + for (const auto & node : nodes_) msg.nodes.push_back(node->create_status()); + for (const auto & diag : diags_) msg.diags.push_back(diag->create_status()); + for (const auto & link : links_) msg.links.push_back(link->create_status()); + return msg; } -std::vector Graph::nodes() const -{ - std::vector result; - result.reserve(nodes_.size()); - for (const auto & node : nodes_) { - result.push_back(node.get()); - } - return result; -} +// For unique_ptr members. +Graph::Graph() = default; +Graph::~Graph() = default; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp index 8c29a303814b8..ed7bac0e96ce3 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.hpp @@ -22,29 +22,34 @@ #include #include #include -#include #include namespace diagnostic_graph_aggregator { -class Graph final +class Graph { public: - Graph(); - ~Graph(); - - void init(const std::string & file); - void callback(const rclcpp::Time & stamp, const DiagnosticArray & array); - void debug(); - DiagnosticGraph report(const rclcpp::Time & stamp); - std::vector nodes() const; + void create(const std::string & file, const std::string & id = ""); + void update(const rclcpp::Time & stamp); + bool update(const rclcpp::Time & stamp, const DiagnosticStatus & status); + const auto & nodes() const { return nodes_; } + const auto & diags() const { return diags_; } + const auto & units() const { return units_; } + DiagGraphStruct create_struct(const rclcpp::Time & stamp) const; + DiagGraphStatus create_status(const rclcpp::Time & stamp) const; + + Graph(); // For unique_ptr members. + ~Graph(); // For unique_ptr members. private: - std::vector> nodes_; + // Note: keep order correspondence between links and unit children for viewer. + std::vector> nodes_; + std::vector> diags_; + std::vector> links_; std::vector units_; - std::unordered_map diags_; - std::unordered_map unknowns_; + std::unordered_map names_; + std::string id_; }; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp b/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp new file mode 100644 index 0000000000000..74636adab7415 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp @@ -0,0 +1,189 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "loader.hpp" + +#include "config.hpp" +#include "error.hpp" +#include "names.hpp" +#include "types.hpp" +#include "units.hpp" + +#include + +namespace diagnostic_graph_aggregator +{ + +struct UnitLoader::GraphLinks +{ + std::unordered_map config_links; + std::unordered_map> parent_links; +}; + +size_t UnitLoader::index() const +{ + return config_->index; +} + +const std::string & UnitLoader::path() const +{ + return config_->path; +} + +const std::string & UnitLoader::type() const +{ + return config_->type; +} + +TreeData & UnitLoader::data() const +{ + return config_->data; +} + +UnitLink * UnitLoader::child() const +{ + return links_.config_links.at(config_->item); +} + +std::vector UnitLoader::children() const +{ + std::vector result; + for (const auto & config : config_->list) { + result.push_back(links_.config_links.at(config)); + } + return result; +} + +std::vector UnitLoader::parents() const +{ + return links_.parent_links.at(config_); +} + +GraphLoader::GraphLoader(const std::string & file) +{ + TreeLoader tree = TreeLoader::Load(file); + FileConfig root = tree.construct(); + + // Init array index to be able get it from unit itself. + std::vector diags; + std::vector nodes; + for (const auto & config : root.units) { + (config->type == unit_name::diag ? diags : nodes).push_back(config.get()); + } + for (size_t i = 0; i < diags.size(); ++i) diags[i]->index = i; + for (size_t i = 0; i < nodes.size(); ++i) nodes[i]->index = i; + + // Create link objects. + UnitLoader::GraphLinks graph_links; + for (const auto & config : root.units) { + graph_links.parent_links[config.get()] = {}; + } + for (const auto & config : root.links) { + const auto link = links_.emplace_back(create_link()).get(); + graph_links.config_links[config.get()] = link; + graph_links.parent_links[config->child].push_back(link); + } + + // Create node objects. + std::unordered_map config_units; + for (const auto & config : diags) { + const auto unit = UnitLoader(config, graph_links); + const auto diag = diags_.emplace_back(create_diag(unit)).get(); + config_units[config] = diag; + } + for (const auto & config : nodes) { + const auto unit = UnitLoader(config, graph_links); + const auto node = nodes_.emplace_back(create_node(unit)).get(); + config_units[config] = node; + } + + // Connect links and nodes; + for (const auto & [config, link] : graph_links.config_links) { + const auto parent = config_units.at(config->parent); + const auto child = config_units.at(config->child); + link->initialize_object(parent, child); + } + + // Init struct. + for (auto & node : nodes_) node->initialize_struct(); + for (auto & diag : diags_) diag->initialize_struct(); + for (auto & link : links_) link->initialize_struct(); + + // Init status that needs struct. + for (auto & node : nodes_) node->initialize_status(); + for (auto & diag : diags_) diag->initialize_status(); + for (auto & link : links_) link->initialize_status(); +} + +std::vector> GraphLoader::release_links() +{ + return std::move(links_); +} + +std::vector> GraphLoader::release_nodes() +{ + return std::move(nodes_); +} + +std::vector> GraphLoader::release_diags() +{ + return std::move(diags_); +} + +std::unique_ptr GraphLoader::create_link() +{ + return std::make_unique(); +} + +std::unique_ptr GraphLoader::create_diag(const UnitLoader & unit) +{ + if (unit.type() == unit_name::diag) { + return std::make_unique(unit); + } + throw UnknownUnitType(unit.data().path(), unit.type()); +} + +std::unique_ptr GraphLoader::create_node(const UnitLoader & unit) +{ + if (unit.type() == unit_name::max) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::short_circuit_max) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::min) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::warn_to_ok) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::warn_to_error) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::ok) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::warn) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::error) { + return std::make_unique(unit); + } + if (unit.type() == unit_name::stale) { + return std::make_unique(unit); + } + throw UnknownUnitType(unit.data().path(), unit.type()); +} + +} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp b/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp new file mode 100644 index 0000000000000..226b3ab279b22 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/loader.hpp @@ -0,0 +1,67 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMMON__GRAPH__LOADER_HPP_ +#define COMMON__GRAPH__LOADER_HPP_ + +#include "types.hpp" + +#include +#include +#include +#include + +namespace diagnostic_graph_aggregator +{ + +class UnitLoader +{ +public: + struct GraphLinks; + UnitLoader(UnitConfig * config, GraphLinks & links) : config_(config), links_(links) {} + const std::string & path() const; + const std::string & type() const; + size_t index() const; + TreeData & data() const; + UnitLink * child() const; + std::vector children() const; + std::vector parents() const; + +private: + UnitConfig * config_; + GraphLinks & links_; +}; + +class GraphLoader +{ +public: + explicit GraphLoader(const std::string & file); + std::vector> release_nodes(); + std::vector> release_diags(); + std::vector> release_links(); + +private: + std::unique_ptr create_link(); + std::unique_ptr create_diag(const UnitLoader & unit); + std::unique_ptr create_node(const UnitLoader & unit); + + // Note: keep order correspondence between links and unit children for viewer. + std::vector> nodes_; + std::vector> diags_; + std::vector> links_; +}; + +} // namespace diagnostic_graph_aggregator + +#endif // COMMON__GRAPH__LOADER_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/names.hpp b/system/diagnostic_graph_aggregator/src/common/graph/names.hpp new file mode 100644 index 0000000000000..aa5a9c46e7b37 --- /dev/null +++ b/system/diagnostic_graph_aggregator/src/common/graph/names.hpp @@ -0,0 +1,42 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef COMMON__GRAPH__NAMES_HPP_ +#define COMMON__GRAPH__NAMES_HPP_ + +namespace diagnostic_graph_aggregator::unit_name +{ + +constexpr char const * link = "link"; +constexpr char const * diag = "diag"; +constexpr char const * min = "or"; +constexpr char const * max = "and"; +constexpr char const * short_circuit_max = "short-circuit-and"; +constexpr char const * warn_to_ok = "warn-to-ok"; +constexpr char const * warn_to_error = "warn-to-error"; +constexpr char const * ok = "ok"; +constexpr char const * warn = "warn"; +constexpr char const * error = "error"; +constexpr char const * stale = "stale"; + +} // namespace diagnostic_graph_aggregator::unit_name + +namespace diagnostic_graph_aggregator::edit_name +{ + +constexpr char const * remove = "remove"; + +} // namespace diagnostic_graph_aggregator::edit_name + +#endif // COMMON__GRAPH__NAMES_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/common/graph/types.hpp b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp index 693094914db1d..6eae26a1f98c7 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/types.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/types.hpp @@ -17,22 +17,47 @@ #include #include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include +#include + namespace diagnostic_graph_aggregator { using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; -using tier4_system_msgs::msg::DiagnosticGraph; -using tier4_system_msgs::msg::DiagnosticLink; -using tier4_system_msgs::msg::DiagnosticNode; +using tier4_system_msgs::msg::DiagGraphStatus; +using tier4_system_msgs::msg::DiagGraphStruct; +using tier4_system_msgs::msg::DiagLeafStatus; +using tier4_system_msgs::msg::DiagLeafStruct; +using tier4_system_msgs::msg::DiagLinkStatus; +using tier4_system_msgs::msg::DiagLinkStruct; +using tier4_system_msgs::msg::DiagNodeStatus; +using tier4_system_msgs::msg::DiagNodeStruct; using DiagnosticLevel = DiagnosticStatus::_level_type; +struct PathConfig; +struct EditConfig; +struct UnitConfig; +struct LinkConfig; + +class TreeData; +class UnitLink; class BaseUnit; +class NodeUnit; class DiagUnit; +class Graph; +class UnitLoader; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/units.cpp b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp index 6048cae85e633..da801ae078e6c 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/units.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.cpp @@ -14,168 +14,216 @@ #include "units.hpp" +#include "config.hpp" #include "error.hpp" +#include "loader.hpp" #include -#include -#include -#include namespace diagnostic_graph_aggregator { -using LinkList = std::vector>; +void UnitLink::initialize_object(BaseUnit * parent, BaseUnit * child) +{ + parent_ = parent; + child_ = child; +} -void merge(LinkList & a, const LinkList & b, bool uses) +void UnitLink::initialize_struct() { - for (const auto & [node, used] : b) { - a.push_back(std::make_pair(node, used && uses)); - } + struct_.parent = parent_->index(); + struct_.child = child_->index(); + struct_.is_leaf = child_->is_leaf(); } -auto resolve(const BaseUnit::NodeDict & dict, const std::vector & children) +void UnitLink::initialize_status() { - std::vector result; - for (const auto & child : children) { - result.push_back(dict.configs.at(child)); - } - return result; + // Do nothing. } -BaseUnit::BaseUnit(const std::string & path) : path_(path) +BaseUnit::BaseUnit(const UnitLoader & unit) { - index_ = 0; - level_ = DiagnosticStatus::OK; + index_ = unit.index(); + parents_ = unit.parents(); } -BaseUnit::NodeData BaseUnit::status() const +bool BaseUnit::update() { - if (path_.empty()) { - return {level_, links_}; - } else { - return {level_, {std::make_pair(this, true)}}; + // Update the level of this unit. + update_status(); + + // If the level does not change, it will not affect the parents. + const auto curr_level = level(); + if (curr_level == prev_level_) return false; + prev_level_ = curr_level; + + // If the level changes, the parents also need to be updated. + bool result = false; + for (const auto & link : parents_) { + const auto unit = link->parent(); + result = result || unit->update(); } + return result; } -BaseUnit::NodeData BaseUnit::report() const +NodeUnit::NodeUnit(const UnitLoader & unit) : BaseUnit(unit) { - return {level_, links_}; + struct_.path = unit.path(); + status_.level = DiagnosticStatus::STALE; } -void DiagUnit::init(const UnitConfig::SharedPtr & config, const NodeDict &) +void NodeUnit::initialize_struct() { - name_ = config->data.take_text("diag"); - timeout_ = config->data.take("timeout", 1.0); + struct_.type = type(); } -void DiagUnit::update(const rclcpp::Time & stamp) +void NodeUnit::initialize_status() { - if (diagnostics_) { - const auto updated = diagnostics_.value().first; - const auto elapsed = (stamp - updated).seconds(); - if (timeout_ < elapsed) { - diagnostics_ = std::nullopt; - } - } + if (child_links().size() == 0) update(); +} - if (diagnostics_) { - level_ = diagnostics_.value().second.level; - } else { - level_ = DiagnosticStatus::STALE; - } +LeafUnit::LeafUnit(const UnitLoader & unit) : BaseUnit(unit) +{ + const auto node = unit.data().required("node").text(); + const auto name = unit.data().required("name").text(); + const auto sep = node.empty() ? "" : ": "; + + struct_.path = unit.path(); + struct_.name = node + sep + name; + status_.level = DiagnosticStatus::STALE; } -void DiagUnit::callback(const rclcpp::Time & stamp, const DiagnosticStatus & status) +void LeafUnit::initialize_struct() { - diagnostics_ = std::make_pair(stamp, status); + struct_.type = type(); } -AndUnit::AndUnit(const std::string & path, bool short_circuit) : BaseUnit(path) +void LeafUnit::initialize_status() { - short_circuit_ = short_circuit; + if (child_links().size() == 0) update(); } -void AndUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +DiagUnit::DiagUnit(const UnitLoader & unit) : LeafUnit(unit) { - children_ = resolve(dict, config->children); + timeout_ = unit.data().optional("timeout").real(1.0); } -void AndUnit::update(const rclcpp::Time &) +void DiagUnit::update_status() { - if (children_.empty()) { - return; - } + // Do nothing. The level is updated by on_diag and on_time. +} - bool uses = true; - level_ = DiagnosticStatus::OK; - links_ = LinkList(); +bool DiagUnit::on_diag(const rclcpp::Time & stamp, const DiagnosticStatus & status) +{ + last_updated_time_ = stamp; + status_.level = status.level; + status_.message = status.message; + status_.hardware_id = status.hardware_id; + status_.values = status.values; + return update(); +} - for (const auto & child : children_) { - const auto status = child->status(); - level_ = std::max(level_, status.level); - merge(links_, status.links, uses); - if (short_circuit_ && level_ != DiagnosticStatus::OK) { - uses = false; +bool DiagUnit::on_time(const rclcpp::Time & stamp) +{ + if (last_updated_time_) { + const auto updated = last_updated_time_.value(); + const auto elapsed = (stamp - updated).seconds(); + if (timeout_ < elapsed) { + last_updated_time_ = std::nullopt; + status_ = DiagLeafStatus(); + status_.level = DiagnosticStatus::STALE; } } - level_ = std::min(level_, DiagnosticStatus::ERROR); + return update(); } -void OrUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +MaxUnit::MaxUnit(const UnitLoader & unit) : NodeUnit(unit) { - children_ = resolve(dict, config->children); + links_ = unit.children(); } -void OrUnit::update(const rclcpp::Time &) +void MaxUnit::update_status() { - if (children_.empty()) { - return; + DiagnosticLevel level = DiagnosticStatus::OK; + for (const auto & link : links_) { + level = std::max(level, link->child()->level()); } + status_.level = std::min(level, DiagnosticStatus::ERROR); +} - level_ = DiagnosticStatus::ERROR; - links_ = LinkList(); - - for (const auto & child : children_) { - const auto status = child->status(); - level_ = std::min(level_, status.level); - merge(links_, status.links, true); +void ShortCircuitMaxUnit::update_status() +{ + // TODO(Takagi, Isamu): update link flags. + DiagnosticLevel level = DiagnosticStatus::OK; + for (const auto & link : links_) { + level = std::max(level, link->child()->level()); } - level_ = std::min(level_, DiagnosticStatus::ERROR); + status_.level = std::min(level, DiagnosticStatus::ERROR); } -RemapUnit::RemapUnit(const std::string & path, DiagnosticLevel remap_warn) : BaseUnit(path) +MinUnit::MinUnit(const UnitLoader & unit) : NodeUnit(unit) { - remap_warn_ = remap_warn; + links_ = unit.children(); } -void RemapUnit::init(const UnitConfig::SharedPtr & config, const NodeDict & dict) +void MinUnit::update_status() { - if (config->children.size() != 1) { - throw error("list size must be 1", config->data); + DiagnosticLevel level = DiagnosticStatus::OK; + if (!links_.empty()) { + level = DiagnosticStatus::STALE; + for (const auto & link : links_) { + level = std::min(level, link->child()->level()); + } } - children_ = resolve(dict, config->children); + status_.level = std::min(level, DiagnosticStatus::ERROR); +} + +RemapUnit::RemapUnit(const UnitLoader & unit) : NodeUnit(unit) +{ + link_ = unit.child(); +} + +void RemapUnit::update_status() +{ + const auto level = link_->child()->level(); + status_.level = (level == level_from_) ? level_to_ : level; +} + +WarnToOkUnit::WarnToOkUnit(const UnitLoader & unit) : RemapUnit(unit) +{ + level_from_ = DiagnosticStatus::WARN; + level_to_ = DiagnosticStatus::OK; } -void RemapUnit::update(const rclcpp::Time &) +WarnToErrorUnit::WarnToErrorUnit(const UnitLoader & unit) : RemapUnit(unit) { - const auto status = children_.front()->status(); - level_ = status.level; - links_ = status.links; + level_from_ = DiagnosticStatus::WARN; + level_to_ = DiagnosticStatus::ERROR; +} - if (level_ == DiagnosticStatus::WARN) level_ = remap_warn_; +void ConstUnit::update_status() +{ + // Do nothing. This unit always returns the same level. +} + +OkUnit::OkUnit(const UnitLoader & unit) : ConstUnit(unit) +{ + status_.level = DiagnosticStatus::OK; } -DebugUnit::DebugUnit(const std::string & path, DiagnosticLevel level) : BaseUnit(path) +WarnUnit::WarnUnit(const UnitLoader & unit) : ConstUnit(unit) { - level_ = level; // overwrite + status_.level = DiagnosticStatus::WARN; } -void DebugUnit::init(const UnitConfig::SharedPtr &, const NodeDict &) +ErrorUnit::ErrorUnit(const UnitLoader & unit) : ConstUnit(unit) { + status_.level = DiagnosticStatus::ERROR; } -void DebugUnit::update(const rclcpp::Time &) +StaleUnit::StaleUnit(const UnitLoader & unit) : ConstUnit(unit) { + status_.level = DiagnosticStatus::STALE; } } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/units.hpp b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp index dce223b30f728..f478fa9ef1a2a 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/units.hpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/units.hpp @@ -15,120 +15,212 @@ #ifndef COMMON__GRAPH__UNITS_HPP_ #define COMMON__GRAPH__UNITS_HPP_ -#include "config.hpp" +#include "names.hpp" #include "types.hpp" #include -#include #include #include -#include -#include #include namespace diagnostic_graph_aggregator { +class UnitLink +{ +public: + void initialize_object(BaseUnit * parent, BaseUnit * child); + void initialize_struct(); + void initialize_status(); + DiagLinkStruct create_struct() const { return struct_; } + DiagLinkStatus create_status() const { return status_; } + BaseUnit * parent() const { return parent_; } + BaseUnit * child() const { return child_; } + +private: + BaseUnit * parent_; + BaseUnit * child_; + DiagLinkStruct struct_; + DiagLinkStatus status_; +}; + class BaseUnit { public: - struct NodeDict - { - std::unordered_map configs; - std::unordered_map paths; - }; - struct NodeData - { - DiagnosticLevel level; - std::vector> links; - }; - using UniquePtr = std::unique_ptr; - using UniquePtrList = std::vector>; - - explicit BaseUnit(const std::string & path); + explicit BaseUnit(const UnitLoader & unit); virtual ~BaseUnit() = default; - virtual void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) = 0; - virtual void update(const rclcpp::Time & stamp) = 0; + virtual DiagnosticLevel level() const = 0; + virtual std::string path() const = 0; virtual std::string type() const = 0; - - NodeData status() const; - NodeData report() const; - DiagnosticLevel level() const { return level_; } - - auto path() const { return path_; } - auto children() const { return children_; } - + virtual std::vector child_links() const = 0; + virtual bool is_leaf() const = 0; size_t index() const { return index_; } - void set_index(const size_t index) { index_ = index; } + size_t parent_size() const { return parents_.size(); } protected: - DiagnosticLevel level_; - std::string path_; - std::vector children_; - std::vector> links_; + bool update(); private: + virtual void update_status() = 0; size_t index_; + std::vector parents_; + std::optional prev_level_; +}; + +class NodeUnit : public BaseUnit +{ +public: + explicit NodeUnit(const UnitLoader & unit); + void initialize_struct(); + void initialize_status(); + bool is_leaf() const override { return false; } + DiagNodeStruct create_struct() const { return struct_; } + DiagNodeStatus create_status() const { return status_; } + DiagnosticLevel level() const override { return status_.level; } + std::string path() const override { return struct_.path; } + +protected: + DiagNodeStruct struct_; + DiagNodeStatus status_; }; -class DiagUnit : public BaseUnit +class LeafUnit : public BaseUnit { public: - using BaseUnit::BaseUnit; - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "diag"; } + explicit LeafUnit(const UnitLoader & unit); + void initialize_struct(); + void initialize_status(); + bool is_leaf() const override { return true; } + DiagLeafStruct create_struct() const { return struct_; } + DiagLeafStatus create_status() const { return status_; } + DiagnosticLevel level() const override { return status_.level; } + std::string name() const { return struct_.name; } + std::string path() const override { return struct_.path; } - std::string name() const { return name_; } - void callback(const rclcpp::Time & stamp, const DiagnosticStatus & status); +protected: + DiagLeafStruct struct_; + DiagLeafStatus status_; +}; + +class DiagUnit : public LeafUnit +{ +public: + explicit DiagUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::diag; } + std::vector child_links() const override { return {}; } + bool on_time(const rclcpp::Time & stamp); + bool on_diag(const rclcpp::Time & stamp, const DiagnosticStatus & status); private: + void update_status() override; double timeout_; - std::optional> diagnostics_; - std::string name_; + std::optional last_updated_time_; +}; + +class MaxUnit : public NodeUnit +{ +public: + explicit MaxUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::max; } + std::vector child_links() const override { return links_; } + +protected: + std::vector links_; + +private: + void update_status() override; +}; + +class ShortCircuitMaxUnit : public MaxUnit +{ +public: + using MaxUnit::MaxUnit; + std::string type() const override { return unit_name::short_circuit_max; } + +private: + void update_status() override; }; -class AndUnit : public BaseUnit +class MinUnit : public NodeUnit { public: - AndUnit(const std::string & path, bool short_circuit); - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return short_circuit_ ? "short-circuit-and" : "and"; } + explicit MinUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::min; } + std::vector child_links() const override { return links_; } + +protected: + std::vector links_; private: - bool short_circuit_; + void update_status() override; +}; + +class RemapUnit : public NodeUnit +{ +public: + explicit RemapUnit(const UnitLoader & unit); + std::vector child_links() const override { return {link_}; } + +protected: + UnitLink * link_; + DiagnosticLevel level_from_; + DiagnosticLevel level_to_; + +private: + void update_status() override; +}; + +class WarnToOkUnit : public RemapUnit +{ +public: + explicit WarnToOkUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::warn_to_ok; } }; -class OrUnit : public BaseUnit +class WarnToErrorUnit : public RemapUnit { public: - using BaseUnit::BaseUnit; - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "or"; } + explicit WarnToErrorUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::warn_to_error; } }; -class RemapUnit : public BaseUnit +class ConstUnit : public NodeUnit { public: - RemapUnit(const std::string & path, DiagnosticLevel remap_warn); - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "remap"; } + using NodeUnit::NodeUnit; + std::vector child_links() const override { return {}; } private: - DiagnosticLevel remap_warn_; + void update_status() override; +}; + +class OkUnit : public ConstUnit +{ +public: + explicit OkUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::ok; } +}; + +class WarnUnit : public ConstUnit +{ +public: + explicit WarnUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::warn; } +}; + +class ErrorUnit : public ConstUnit +{ +public: + explicit ErrorUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::error; } }; -class DebugUnit : public BaseUnit +class StaleUnit : public ConstUnit { public: - DebugUnit(const std::string & path, DiagnosticLevel level); - void init(const UnitConfig::SharedPtr & config, const NodeDict & dict) override; - void update(const rclcpp::Time & stamp) override; - std::string type() const override { return "const"; } + explicit StaleUnit(const UnitLoader & unit); + std::string type() const override { return unit_name::stale; } }; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp index cd16ce8e33e59..3287d30d4de18 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -15,6 +15,7 @@ #include "aggregator.hpp" #include +#include #include namespace diagnostic_graph_aggregator @@ -22,51 +23,78 @@ namespace diagnostic_graph_aggregator AggregatorNode::AggregatorNode() : Node("aggregator") { + const auto stamp = now(); + // Init diagnostics graph. { - const auto file = declare_parameter("graph_file"); - graph_.init(file); + const auto graph_file = declare_parameter("graph_file"); + std::ostringstream id; + id << std::hex << stamp.nanoseconds(); + graph_.create(graph_file, id.str()); } // Init plugins. if (declare_parameter("use_operation_mode_availability")) { - modes_ = std::make_unique(*this, graph_.nodes()); + modes_ = std::make_unique(*this, graph_); } // Init ros interface. { - using std::placeholders::_1; const auto qos_input = rclcpp::QoS(declare_parameter("input_qos_depth")); - const auto qos_graph = rclcpp::QoS(declare_parameter("graph_qos_depth")); - - const auto callback = std::bind(&AggregatorNode::on_diag, this, _1); + const auto qos_unknown = rclcpp::QoS(1); // TODO(Takagi, Isamu): parameter + const auto qos_struct = rclcpp::QoS(1).transient_local(); + const auto qos_status = rclcpp::QoS(declare_parameter("graph_qos_depth")); + const auto callback = std::bind(&AggregatorNode::on_diag, this, std::placeholders::_1); sub_input_ = create_subscription("/diagnostics", qos_input, callback); - pub_graph_ = create_publisher("/diagnostics_graph", qos_graph); + pub_unknown_ = create_publisher("/diagnostics_graph/unknowns", qos_unknown); + pub_struct_ = create_publisher("/diagnostics_graph/struct", qos_struct); + pub_status_ = create_publisher("/diagnostics_graph/status", qos_status); const auto rate = rclcpp::Rate(declare_parameter("rate")); timer_ = rclcpp::create_timer(this, get_clock(), rate.period(), [this]() { on_timer(); }); } - // Init debug mode. - debug_ = declare_parameter("use_debug_mode"); + // Send structure topic once. + pub_struct_->publish(graph_.create_struct(stamp)); } AggregatorNode::~AggregatorNode() { - // for unique_ptr + // For unique_ptr members. +} + +DiagnosticArray AggregatorNode::create_unknown_diags(const rclcpp::Time & stamp) +{ + DiagnosticArray msg; + msg.header.stamp = stamp; + for (const auto & [name, diag] : unknown_diags_) msg.status.push_back(diag); + return msg; } void AggregatorNode::on_timer() { + // Check timeout of diag units. const auto stamp = now(); - pub_graph_->publish(graph_.report(stamp)); - if (debug_) graph_.debug(); + graph_.update(stamp); + + // Publish status. + pub_status_->publish(graph_.create_status(stamp)); + pub_unknown_->publish(create_unknown_diags(stamp)); if (modes_) modes_->update(stamp); } -void AggregatorNode::on_diag(const DiagnosticArray::ConstSharedPtr msg) +void AggregatorNode::on_diag(const DiagnosticArray & msg) { - graph_.callback(now(), *msg); + // Update status. Store it as unknown if it does not exist in the graph. + const auto & stamp = msg.header.stamp; + for (const auto & status : msg.status) { + if (!graph_.update(stamp, status)) { + unknown_diags_[status.name] = status; + } + } + + // TODO(Takagi, Isamu): Publish immediately when graph status changes. + // pub_status_->publish(); } } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp index 6bf9aead9754d..8a0e12edb25e5 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -15,13 +15,14 @@ #ifndef NODE__AGGREGATOR_HPP_ #define NODE__AGGREGATOR_HPP_ +#include "availability.hpp" #include "graph/graph.hpp" -#include "graph/types.hpp" -#include "plugin/modes.hpp" #include #include +#include +#include namespace diagnostic_graph_aggregator { @@ -34,14 +35,17 @@ class AggregatorNode : public rclcpp::Node private: Graph graph_; - std::unique_ptr modes_; + std::unique_ptr modes_; rclcpp::TimerBase::SharedPtr timer_; rclcpp::Subscription::SharedPtr sub_input_; - rclcpp::Publisher::SharedPtr pub_graph_; + rclcpp::Publisher::SharedPtr pub_unknown_; + rclcpp::Publisher::SharedPtr pub_struct_; + rclcpp::Publisher::SharedPtr pub_status_; + DiagnosticArray create_unknown_diags(const rclcpp::Time & stamp); void on_timer(); - void on_diag(const DiagnosticArray::ConstSharedPtr msg); + void on_diag(const DiagnosticArray & msg); - bool debug_; + std::unordered_map unknown_diags_; }; } // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp b/system/diagnostic_graph_aggregator/src/node/availability.cpp similarity index 66% rename from system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp rename to system/diagnostic_graph_aggregator/src/node/availability.cpp index c73de86cba439..60ad418799716 100644 --- a/system/diagnostic_graph_aggregator/src/node/plugin/modes.cpp +++ b/system/diagnostic_graph_aggregator/src/node/availability.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "modes.hpp" +#include "availability.hpp" -#include "graph/config.hpp" #include "graph/error.hpp" +#include "graph/graph.hpp" #include "graph/units.hpp" #include @@ -25,38 +25,38 @@ namespace diagnostic_graph_aggregator { -OperationModes::OperationModes(rclcpp::Node & node, const std::vector & graph) +ModesAvailability::ModesAvailability(rclcpp::Node & node, const Graph & graph) { pub_ = node.create_publisher("/system/operation_mode/availability", rclcpp::QoS(1)); using PathDict = std::unordered_map; PathDict paths; - for (const auto & node : graph) { - paths[node->path()] = node; + for (const auto & unit : graph.units()) { + paths[unit->path()] = unit; } - const auto find_node = [](const PathDict & paths, const std::string & name) { + const auto find_unit = [](const PathDict & paths, const std::string & name) { const auto iter = paths.find(name); if (iter != paths.end()) { return iter->second; } - throw error("summary node is not found", name); + throw ModeNotFound(name); }; // clang-format off - stop_mode_ = find_node(paths, "/autoware/modes/stop"); - autonomous_mode_ = find_node(paths, "/autoware/modes/autonomous"); - local_mode_ = find_node(paths, "/autoware/modes/local"); - remote_mode_ = find_node(paths, "/autoware/modes/remote"); - emergency_stop_mrm_ = find_node(paths, "/autoware/modes/emergency_stop"); - comfortable_stop_mrm_ = find_node(paths, "/autoware/modes/comfortable_stop"); - pull_over_mrm_ = find_node(paths, "/autoware/modes/pull_over"); + stop_mode_ = find_unit(paths, "/autoware/modes/stop"); + autonomous_mode_ = find_unit(paths, "/autoware/modes/autonomous"); + local_mode_ = find_unit(paths, "/autoware/modes/local"); + remote_mode_ = find_unit(paths, "/autoware/modes/remote"); + emergency_stop_mrm_ = find_unit(paths, "/autoware/modes/emergency_stop"); + comfortable_stop_mrm_ = find_unit(paths, "/autoware/modes/comfortable_stop"); + pull_over_mrm_ = find_unit(paths, "/autoware/modes/pull_over"); // clang-format on } -void OperationModes::update(const rclcpp::Time & stamp) const +void ModesAvailability::update(const rclcpp::Time & stamp) const { - const auto is_ok = [](const BaseUnit * node) { return node->level() == DiagnosticStatus::OK; }; + const auto is_ok = [](const BaseUnit * unit) { return unit->level() == DiagnosticStatus::OK; }; // clang-format off Availability message; diff --git a/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp b/system/diagnostic_graph_aggregator/src/node/availability.hpp similarity index 85% rename from system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp rename to system/diagnostic_graph_aggregator/src/node/availability.hpp index 1ed22c7d9d058..c91db089266f5 100644 --- a/system/diagnostic_graph_aggregator/src/node/plugin/modes.hpp +++ b/system/diagnostic_graph_aggregator/src/node/availability.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NODE__PLUGIN__MODES_HPP_ -#define NODE__PLUGIN__MODES_HPP_ +#ifndef NODE__AVAILABILITY_HPP_ +#define NODE__AVAILABILITY_HPP_ #include "graph/types.hpp" @@ -21,15 +21,13 @@ #include -#include - namespace diagnostic_graph_aggregator { -class OperationModes +class ModesAvailability { public: - OperationModes(rclcpp::Node & node, const std::vector & graph); + ModesAvailability(rclcpp::Node & node, const Graph & graph); void update(const rclcpp::Time & stamp) const; private: @@ -48,4 +46,4 @@ class OperationModes } // namespace diagnostic_graph_aggregator -#endif // NODE__PLUGIN__MODES_HPP_ +#endif // NODE__AVAILABILITY_HPP_ diff --git a/system/diagnostic_graph_aggregator/src/node/converter.cpp b/system/diagnostic_graph_aggregator/src/node/converter.cpp deleted file mode 100644 index f0b2108374017..0000000000000 --- a/system/diagnostic_graph_aggregator/src/node/converter.cpp +++ /dev/null @@ -1,133 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "converter.hpp" - -#include - -namespace diagnostic_graph_aggregator -{ - -std::string level_to_string(DiagnosticLevel level) -{ - switch (level) { - case DiagnosticStatus::OK: - return "OK"; - case DiagnosticStatus::WARN: - return "WARN"; - case DiagnosticStatus::ERROR: - return "ERROR"; - case DiagnosticStatus::STALE: - return "STALE"; - } - return "UNKNOWN"; -} - -std::string parent_path(const std::string & path) -{ - return path.substr(0, path.rfind('/')); -} - -auto create_tree(const DiagnosticGraph & graph) -{ - std::map, std::greater> tree; - for (const auto & node : graph.nodes) { - tree.emplace(node.status.name, std::make_unique(true)); - } - for (const auto & node : graph.nodes) { - std::string path = node.status.name; - while (path = parent_path(path), !path.empty()) { - if (tree.count(path)) break; - tree.emplace(path, std::make_unique(false)); - } - } - for (const auto & [path, node] : tree) { - const auto parent = parent_path(path); - node->parent = parent.empty() ? nullptr : tree[parent].get(); - } - return tree; -} - -ConverterNode::ConverterNode() : Node("converter") -{ - using std::placeholders::_1; - const auto qos_graph = rclcpp::QoS(1); - const auto qos_array = rclcpp::QoS(1); - - const auto callback = std::bind(&ConverterNode::on_graph, this, _1); - sub_graph_ = create_subscription("/diagnostics_graph", qos_graph, callback); - pub_array_ = create_publisher("/diagnostics_agg", qos_array); - - initialize_tree_ = false; - complement_tree_ = declare_parameter("complement_tree"); -} - -void ConverterNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg) -{ - DiagnosticArray message; - message.header.stamp = msg->stamp; - message.status.reserve(msg->nodes.size()); - for (const auto & node : msg->nodes) { - message.status.push_back(node.status); - for (const auto & link : node.links) { - diagnostic_msgs::msg::KeyValue kv; - const auto & status = msg->nodes[link.index].status; - kv.key = status.name; - kv.value = level_to_string(status.level); - if (link.used) { - message.status.back().values.push_back(kv); - } - } - } - - if (complement_tree_ && !initialize_tree_) { - initialize_tree_ = true; - tree_ = create_tree(*msg); - } - - if (complement_tree_) { - for (const auto & [path, node] : tree_) { - node->level = DiagnosticStatus::OK; - } - for (const auto & node : msg->nodes) { - tree_[node.status.name]->level = node.status.level; - } - for (const auto & [path, node] : tree_) { - if (!node->parent) continue; - node->parent->level = std::max(node->parent->level, node->level); - } - for (const auto & [path, node] : tree_) { - if (node->leaf) continue; - message.status.emplace_back(); - message.status.back().name = path; - message.status.back().level = node->level; - } - } - - pub_array_->publish(message); -} - -} // namespace diagnostic_graph_aggregator - -int main(int argc, char ** argv) -{ - using diagnostic_graph_aggregator::ConverterNode; - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} diff --git a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp b/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp index bfbb382a78fcb..9f7eb34bf3454 100644 --- a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/loader.hpp" +#include "graph/graph.hpp" +#include "graph/units.hpp" #include @@ -21,18 +22,19 @@ namespace diagnostic_graph_aggregator void dump_root(const std::string & path) { - const auto graph = load_graph_nodes(path); - const auto color = "#FFFFFF"; + const auto color = "#EEEEEE"; + Graph graph; + graph.create(path); - for (const auto & node : graph.nodes) { - std::cout << "card " << node << " " << color << " [" << std::endl; - std::cout << node->path << std::endl; + for (const auto & unit : graph.units()) { + std::cout << "card " << unit << " " << color << " [" << std::endl; + std::cout << unit->path() << std::endl; std::cout << "]" << std::endl; } - for (const auto & node : graph.nodes) { - for (const auto & child : node->children) { - std::cout << node << " --> " << child << std::endl; + for (const auto & unit : graph.units()) { + for (const auto & link : unit->child_links()) { + std::cout << unit << " --> " << link->child() << std::endl; } } } diff --git a/system/diagnostic_graph_aggregator/src/tool/tree.cpp b/system/diagnostic_graph_aggregator/src/tool/tree.cpp index 9dbbc539b3b91..1e6fe93b18a80 100644 --- a/system/diagnostic_graph_aggregator/src/tool/tree.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/tree.cpp @@ -12,47 +12,49 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "utils/loader.hpp" +#include "graph/graph.hpp" +#include "graph/units.hpp" #include namespace diagnostic_graph_aggregator { -void dump_node(const GraphNode * node, const std::string & indent = "", bool root = true) +void dump_unit(const BaseUnit * unit, const std::string & indent = "", bool root = true) { - const auto path = node->path.empty() ? "" : node->path + " "; - const auto type = "(" + node->type + ")"; + const auto path = unit->path().empty() ? "" : unit->path() + " "; + const auto type = "(" + unit->type() + ")"; std::cout << indent << "- " << path << type << std::endl; - if (root || node->parents.size() == 1) { - for (const auto child : node->children) { - dump_node(child, indent + " ", false); + if (root || unit->parent_size() == 1) { + for (const auto link : unit->child_links()) { + dump_unit(link->child(), indent + " ", false); } } } void dump_root(const std::string & path) { - const auto graph = load_graph_nodes(path); + Graph graph; + graph.create(path); - std::cout << "===== root nodes =================================" << std::endl; - for (const auto & node : graph.nodes) { - if (node->parents.size() == 0 && node->children.size() != 0) { - dump_node(node); + std::cout << "===== Top-level trees ============================" << std::endl; + for (const auto & unit : graph.units()) { + if (unit->parent_size() == 0 && unit->child_links().size() != 0) { + dump_unit(unit); } } - std::cout << "===== intermediate nodes =========================" << std::endl; - for (const auto & node : graph.nodes) { - if (node->parents.size() >= 2) { - dump_node(node); + std::cout << "===== Subtrees ===================================" << std::endl; + for (const auto & unit : graph.units()) { + if (unit->parent_size() >= 2 && unit->child_links().size() != 0) { + dump_unit(unit); } } - std::cout << "===== isolated nodes =============================" << std::endl; - for (const auto & node : graph.nodes) { - if (node->parents.size() == 0 && node->children.size() == 0) { - dump_node(node); + std::cout << "===== Isolated units =============================" << std::endl; + for (const auto & unit : graph.units()) { + if (unit->parent_size() == 0 && unit->child_links().size() == 0) { + dump_unit(unit); } } } diff --git a/system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp b/system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp deleted file mode 100644 index a2e6ce8b85334..0000000000000 --- a/system/diagnostic_graph_aggregator/src/tool/utils/loader.cpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "loader.hpp" - -#include -#include - -namespace diagnostic_graph_aggregator -{ - -GraphRoot load_graph_nodes(const std::string & path) -{ - GraphRoot result; - { - std::unordered_map mapping; - Graph graph; - graph.init(path); - - for (const auto & node : graph.nodes()) { - auto data = std::make_unique(); - data->path = node->path(); - data->type = node->type(); - mapping[node] = std::move(data); - } - - for (const auto & [node, data] : mapping) { - for (const auto & link : node->children()) { - const auto parent = data.get(); - const auto child = mapping.at(link).get(); - child->parents.push_back(parent); - parent->children.push_back(child); - } - } - - for (auto & [node, data] : mapping) { - result.owner.push_back(std::move(data)); - } - for (const auto & node : result.owner) { - result.nodes.push_back(node.get()); - } - } - return result; -} - -} // namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp b/system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp deleted file mode 100644 index 70e01ec2a77b4..0000000000000 --- a/system/diagnostic_graph_aggregator/src/tool/utils/loader.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// Copyright 2023 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef TOOL__UTILS__LOADER_HPP_ -#define TOOL__UTILS__LOADER_HPP_ - -#include "graph/graph.hpp" -#include "graph/types.hpp" -#include "graph/units.hpp" - -#include -#include -#include - -namespace diagnostic_graph_aggregator -{ - -struct GraphNode -{ - using UniquePtr = std::unique_ptr; - std::string type; - std::string path; - std::vector children; - std::vector parents; -}; - -struct GraphRoot -{ - std::vector owner; - std::vector nodes; -}; - -GraphRoot load_graph_nodes(const std::string & path); - -} // namespace diagnostic_graph_aggregator - -#endif // TOOL__UTILS__LOADER_HPP_ diff --git a/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml index 9e2b3708c049a..6070f690a3882 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/field-not-found.yaml @@ -1,2 +1,2 @@ -nodes: +units: - test-type: test-type diff --git a/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml b/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml index 4c014bdcec3f9..980d0670a7ccf 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/graph-circulation.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /foo/bar type: and list: diff --git a/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml index 6499b05ab8b7d..6c4cb8701ceea 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/invalid-dict-type.yaml @@ -1 +1 @@ -nodes: test-object +units: test-object diff --git a/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml index 4fc5d96c08c62..34fd1436ed496 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/invalid-list-type.yaml @@ -1,3 +1,3 @@ -nodes: +units: - type: and list: test-list diff --git a/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml index ea3e536b74216..280276b7077db 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/path-conflict.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /foo/bar type: and - path: /foo/bar diff --git a/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml b/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml index 6b0b10dfa94f4..f9d3021bb2a74 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/path-not-found.yaml @@ -1,4 +1,4 @@ -nodes: +units: - path: /foo/bar type: and - link: /foo/baz diff --git a/system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml b/system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml similarity index 74% rename from system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml rename to system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml index a3d66fbfa43cb..865e535dc7173 100644 --- a/system/diagnostic_graph_aggregator/test/files/test1/unknown-node-type.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test1/unknown-unit-type.yaml @@ -1,2 +1,2 @@ -nodes: +units: - type: test-type diff --git a/system/diagnostic_graph_aggregator/test/files/test2/and.yaml b/system/diagnostic_graph_aggregator/test/files/test2/and.yaml index 0c9b651f89b2e..479a281ff9d08 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/and.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/and.yaml @@ -1,10 +1,12 @@ -nodes: +units: - path: output type: and list: - path: input-0 type: diag - diag: "test: input-0" + node: test + name: input-0 - path: input-1 type: diag - diag: "test: input-1" + node: test + name: input-1 diff --git a/system/diagnostic_graph_aggregator/test/files/test2/or.yaml b/system/diagnostic_graph_aggregator/test/files/test2/or.yaml index c7f37a6c32064..cb8440829891e 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/or.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/or.yaml @@ -1,10 +1,12 @@ -nodes: +units: - path: output type: or list: - path: input-0 type: diag - diag: "test: input-0" + node: test + name: input-0 - path: input-1 type: diag - diag: "test: input-1" + node: test + name: input-1 diff --git a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml index 816bf4fd6e1bf..42eef3d976151 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-error.yaml @@ -1,7 +1,8 @@ -nodes: +units: - path: output type: warn-to-error - list: - - path: input-0 - type: diag - diag: "test: input-0" + item: + path: input-0 + type: diag + node: test + name: input-0 diff --git a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml index 1f5cf18978e3c..90a10cfd42bc5 100644 --- a/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml +++ b/system/diagnostic_graph_aggregator/test/files/test2/warn-to-ok.yaml @@ -1,7 +1,8 @@ -nodes: +units: - path: output type: warn-to-ok - list: - - path: input-0 - type: diag - diag: "test: input-0" + item: + path: input-0 + type: diag + node: test + name: input-0 diff --git a/system/diagnostic_graph_aggregator/test/src/test1.cpp b/system/diagnostic_graph_aggregator/test/src/test1.cpp index 48a0e1f45ce07..ea157852675ec 100644 --- a/system/diagnostic_graph_aggregator/test/src/test1.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test1.cpp @@ -23,59 +23,59 @@ using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) TEST(ConfigFile, RootNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/fake-file-name.yaml")), FileNotFound); + EXPECT_THROW(graph.create(resource("test1/fake-file-name.yaml")), FileNotFound); } TEST(ConfigFile, FileNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/file-not-found.yaml")), FileNotFound); + EXPECT_THROW(graph.create(resource("test1/file-not-found.yaml")), FileNotFound); } TEST(ConfigFile, UnknownSubstitution) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/unknown-substitution.yaml")), UnknownType); + EXPECT_THROW(graph.create(resource("test1/unknown-substitution.yaml")), UnknownSubstitution); } TEST(ConfigFile, UnknownNodeType) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/unknown-node-type.yaml")), UnknownType); + EXPECT_THROW(graph.create(resource("test1/unknown-unit-type.yaml")), UnknownUnitType); } TEST(ConfigFile, InvalidDictType) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/invalid-dict-type.yaml")), InvalidType); + EXPECT_THROW(graph.create(resource("test1/invalid-dict-type.yaml")), InvalidType); } TEST(ConfigFile, InvalidListType) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/invalid-list-type.yaml")), InvalidType); + EXPECT_THROW(graph.create(resource("test1/invalid-list-type.yaml")), InvalidType); } TEST(ConfigFile, FieldNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/field-not-found.yaml")), FieldNotFound); + EXPECT_THROW(graph.create(resource("test1/field-not-found.yaml")), FieldNotFound); } TEST(ConfigFile, PathConflict) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/path-conflict.yaml")), PathConflict); + EXPECT_THROW(graph.create(resource("test1/path-conflict.yaml")), PathConflict); } TEST(ConfigFile, PathNotFound) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/path-not-found.yaml")), PathNotFound); + EXPECT_THROW(graph.create(resource("test1/path-not-found.yaml")), PathNotFound); } TEST(ConfigFile, GraphCirculation) { Graph graph; - EXPECT_THROW(graph.init(resource("test1/graph-circulation.yaml")), GraphStructure); + EXPECT_THROW(graph.create(resource("test1/graph-circulation.yaml")), GraphStructure); } diff --git a/system/diagnostic_graph_aggregator/test/src/test2.cpp b/system/diagnostic_graph_aggregator/test/src/test2.cpp index 1098ff9efb0db..b010994f5a1ca 100644 --- a/system/diagnostic_graph_aggregator/test/src/test2.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test2.cpp @@ -56,11 +56,14 @@ DiagnosticArray create_input(const std::vector & levels) return array; }; -uint8_t get_output(const DiagnosticGraph & graph) +uint8_t get_output(const Graph & graph, const rclcpp::Time & stamp) { - for (const auto & node : graph.nodes) { - if (node.status.name == "output") { - return node.status.level; + const auto struct_nodes = graph.create_struct(stamp).nodes; + const auto status_nodes = graph.create_status(stamp).nodes; + + for (size_t i = 0; i < struct_nodes.size(); ++i) { + if (struct_nodes[i].path == "output") { + return status_nodes[i].level; } } throw std::runtime_error("output node is not found"); @@ -68,13 +71,17 @@ uint8_t get_output(const DiagnosticGraph & graph) TEST_P(GraphTest, Aggregation) { - const auto param = GetParam(); const auto stamp = rclcpp::Clock().now(); + const auto param = GetParam(); Graph graph; - graph.init(resource(param.config)); - graph.callback(stamp, create_input(param.inputs)); + graph.create(resource(param.config)); + + const auto array = create_input(param.inputs); + for (const auto & status : array.status) { + graph.update(stamp, status); + } - const auto output = get_output(graph.report(stamp)); + const auto output = get_output(graph, stamp); EXPECT_EQ(output, param.result); } diff --git a/system/diagnostic_graph_utils/CMakeLists.txt b/system/diagnostic_graph_utils/CMakeLists.txt new file mode 100644 index 0000000000000..48af5e8fc304f --- /dev/null +++ b/system/diagnostic_graph_utils/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.14) +project(diagnostic_graph_utils) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/lib/graph.cpp + src/lib/subscription.cpp +) + +ament_auto_add_executable(dump + src/node/dump.cpp +) + +ament_auto_add_executable(converter + src/node/converter.cpp +) + +ament_auto_package() diff --git a/system/diagnostic_graph_utils/README.md b/system/diagnostic_graph_utils/README.md new file mode 100644 index 0000000000000..a06d664622bff --- /dev/null +++ b/system/diagnostic_graph_utils/README.md @@ -0,0 +1,13 @@ +# diagnostic_graph_utils + +This package is a utility for diagnostic graph published by [diagnostic_graph_aggregator](../diagnostic_graph_aggregator/README.md). + +## ROS node + +- [dump](./doc/node/dump.md) +- [converter](./doc/node/converter.md) + +## C++ library + +- [DiagGraph](./include/diagnostic_graph_utils/graph.hpp) +- [DiagGraphSubscription](./include/diagnostic_graph_utils/subscription.hpp) diff --git a/system/diagnostic_graph_utils/doc/node/converter.md b/system/diagnostic_graph_utils/doc/node/converter.md new file mode 100644 index 0000000000000..c3db547167474 --- /dev/null +++ b/system/diagnostic_graph_utils/doc/node/converter.md @@ -0,0 +1,31 @@ +# Converter tool + +This tool converts `/diagnostics_graph` to `/diagnostics_array` so it can be read by tools such as `rqt_runtime_monitor`. + +## Usage + +```bash +ros2 run diagnostic_graph_utils converter +``` + +## Examples + +Terminal 1: + +```bash +ros2 launch diagnostic_graph_aggregator example-main.launch.xml +``` + +Terminal 2: + +```bash +ros2 run diagnostic_graph_utils converter +``` + +Terminal 3: + +```bash +ros2 run rqt_runtime_monitor rqt_runtime_monitor --ros-args -r diagnostics:=diagnostics_array +``` + +![rqt_runtime_monitor](./images/rqt_runtime_monitor.png) diff --git a/system/diagnostic_graph_utils/doc/node/dump.md b/system/diagnostic_graph_utils/doc/node/dump.md new file mode 100644 index 0000000000000..090e9679676b6 --- /dev/null +++ b/system/diagnostic_graph_utils/doc/node/dump.md @@ -0,0 +1,46 @@ +# Dump tool + +This tool displays `/diagnostics_graph` in table format. + +## Usage + +```bash +ros2 run diagnostic_graph_utils dump +``` + +## Examples + +Terminal 1: + +```bash +ros2 launch diagnostic_graph_aggregator example-main.launch.xml +``` + +Terminal 2: + +```bash +ros2 run diagnostic_graph_utils dump +``` + +Output: + +```txt +|----|-------|----------------------------------|------|----------| +| No | Level | Path | Type | Children | +|----|-------|----------------------------------|------|----------| +| 1 | OK | /autoware/modes/stop | ok | | +| 2 | ERROR | /autoware/modes/autonomous | and | 8 9 | +| 3 | OK | /autoware/modes/local | and | 13 | +| 4 | OK | /autoware/modes/remote | and | 14 | +| 5 | OK | /autoware/modes/emergency_stop | ok | | +| 6 | OK | /autoware/modes/comfortable_stop | and | 9 | +| 7 | ERROR | /autoware/modes/pull_over | and | 8 9 | +| 8 | ERROR | /functions/pose_estimation | and | 10 | +| 9 | OK | /functions/obstacle_detection | or | 11 12 | +| 10 | ERROR | /sensing/lidars/top | diag | | +| 11 | OK | /sensing/lidars/front | diag | | +| 12 | OK | /sensing/radars/front | diag | | +| 13 | OK | /external/joystick_command | diag | | +| 14 | OK | /external/remote_command | diag | | + +``` diff --git a/system/diagnostic_graph_aggregator/doc/tool/images/rqt_runtime_monitor.png b/system/diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png similarity index 100% rename from system/diagnostic_graph_aggregator/doc/tool/images/rqt_runtime_monitor.png rename to system/diagnostic_graph_utils/doc/node/images/rqt_runtime_monitor.png diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp new file mode 100644 index 0000000000000..b2c6fc752e463 --- /dev/null +++ b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp @@ -0,0 +1,133 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ +#define DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace diagnostic_graph_utils +{ + +class DiagLink; +class DiagUnit +{ +public: + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticLevel = DiagnosticStatus::_level_type; + + struct DiagChild + { + DiagLink * link; + DiagUnit * unit; + }; + + virtual DiagnosticStatus create_diagnostic_status() const = 0; + virtual DiagnosticLevel level() const = 0; + virtual std::string type() const = 0; + virtual std::string path() const = 0; + virtual std::vector children() const = 0; +}; + +class DiagLink +{ +public: + using DiagLinkStruct = tier4_system_msgs::msg::DiagLinkStruct; + using DiagLinkStatus = tier4_system_msgs::msg::DiagLinkStatus; + explicit DiagLink(const DiagLinkStruct & msg) : struct_(msg) {} + void update(const DiagLinkStatus & msg) { status_ = msg; } + +private: + DiagLinkStruct struct_; + DiagLinkStatus status_; +}; + +class DiagNode : public DiagUnit +{ +public: + using DiagNodeStruct = tier4_system_msgs::msg::DiagNodeStruct; + using DiagNodeStatus = tier4_system_msgs::msg::DiagNodeStatus; + explicit DiagNode(const DiagNodeStruct & msg) : struct_(msg) {} + void update(const DiagNodeStatus & msg) { status_ = msg; } + + DiagnosticStatus create_diagnostic_status() const override; + DiagnosticLevel level() const override { return status_.level; } + std::string type() const override { return struct_.type; } + std::string path() const override { return struct_.path; } + std::vector children() const override { return children_; } + void add_child(const DiagChild & child) { children_.push_back(child); } + +private: + DiagNodeStruct struct_; + DiagNodeStatus status_; + std::vector children_; +}; + +class DiagLeaf : public DiagUnit +{ +public: + using DiagLeafStruct = tier4_system_msgs::msg::DiagLeafStruct; + using DiagLeafStatus = tier4_system_msgs::msg::DiagLeafStatus; + explicit DiagLeaf(const DiagLeafStruct & msg) : struct_(msg) {} + void update(const DiagLeafStatus & msg) { status_ = msg; } + + DiagnosticStatus create_diagnostic_status() const override; + DiagnosticLevel level() const override { return status_.level; } + std::string type() const override { return struct_.type; } + std::string path() const override { return struct_.path; } + std::vector children() const override { return {}; } + +private: + DiagLeafStruct struct_; + DiagLeafStatus status_; +}; + +class DiagGraph +{ +public: + using DiagGraphStruct = tier4_system_msgs::msg::DiagGraphStruct; + using DiagGraphStatus = tier4_system_msgs::msg::DiagGraphStatus; + using SharedPtr = std::shared_ptr; + using ConstSharedPtr = std::shared_ptr; + void create(const DiagGraphStruct & msg); + bool update(const DiagGraphStatus & msg); + rclcpp::Time created_stamp() const { return created_stamp_; } + rclcpp::Time updated_stamp() const { return updated_stamp_; } + std::vector units() const; + std::vector nodes() const; + std::vector diags() const; + std::vector links() const; + +private: + rclcpp::Time created_stamp_; + rclcpp::Time updated_stamp_; + std::string id_; + std::vector> nodes_; + std::vector> diags_; + std::vector> links_; +}; + +} // namespace diagnostic_graph_utils + +#endif // DIAGNOSTIC_GRAPH_UTILS__GRAPH_HPP_ diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp new file mode 100644 index 0000000000000..5aebde7ea3a38 --- /dev/null +++ b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/subscription.hpp @@ -0,0 +1,53 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ +#define DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ + +#include "diagnostic_graph_utils/graph.hpp" + +#include + +#include +#include + +namespace diagnostic_graph_utils +{ + +class DiagGraphSubscription +{ +public: + using CallbackType = std::function; + DiagGraphSubscription(); + DiagGraphSubscription(rclcpp::Node & node, size_t depth); + void subscribe(rclcpp::Node & node, size_t depth); + void register_create_callback(const CallbackType & callback); + void register_update_callback(const CallbackType & callback); + +private: + using DiagGraphStruct = tier4_system_msgs::msg::DiagGraphStruct; + using DiagGraphStatus = tier4_system_msgs::msg::DiagGraphStatus; + void on_struct(const DiagGraphStruct & msg); + void on_status(const DiagGraphStatus & msg); + rclcpp::Subscription::SharedPtr sub_struct_; + rclcpp::Subscription::SharedPtr sub_status_; + + DiagGraph::SharedPtr graph_; + CallbackType create_callback_; + CallbackType update_callback_; +}; + +} // namespace diagnostic_graph_utils + +#endif // DIAGNOSTIC_GRAPH_UTILS__SUBSCRIPTION_HPP_ diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml new file mode 100644 index 0000000000000..42d44efb6697e --- /dev/null +++ b/system/diagnostic_graph_utils/package.xml @@ -0,0 +1,23 @@ + + + + diagnostic_graph_utils + 0.1.0 + The diagnostic_graph_utils package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + diagnostic_msgs + rclcpp + tier4_system_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/system/diagnostic_graph_utils/src/lib/graph.cpp b/system/diagnostic_graph_utils/src/lib/graph.cpp new file mode 100644 index 0000000000000..f1177c1047bdb --- /dev/null +++ b/system/diagnostic_graph_utils/src/lib/graph.cpp @@ -0,0 +1,109 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "diagnostic_graph_utils/graph.hpp" + +namespace diagnostic_graph_utils +{ + +DiagUnit::DiagnosticStatus DiagNode::create_diagnostic_status() const +{ + DiagnosticStatus status; + status.level = level(); + status.name = path(); + return status; +} + +DiagUnit::DiagnosticStatus DiagLeaf::create_diagnostic_status() const +{ + DiagnosticStatus status; + status.level = level(); + status.name = path(); + status.message = status_.message; + status.hardware_id = status_.hardware_id; + status.values = status_.values; + return status; +} + +void DiagGraph::create(const DiagGraphStruct & msg) +{ + created_stamp_ = msg.stamp; + id_ = msg.id; + for (const auto & node : msg.nodes) nodes_.push_back(std::make_unique(node)); + for (const auto & diag : msg.diags) diags_.push_back(std::make_unique(diag)); + + const auto get_child = [this](bool is_leaf, size_t index) -> DiagUnit * { + if (is_leaf) { + return diags_.at(index).get(); + } else { + return nodes_.at(index).get(); + } + }; + + for (const auto & data : msg.links) { + DiagNode * parent = nodes_.at(data.parent).get(); + DiagUnit * child = get_child(data.is_leaf, data.child); + const auto link = links_.emplace_back(std::make_unique(data)).get(); + parent->add_child({link, child}); + } +} + +bool DiagGraph::update(const DiagGraphStatus & msg) +{ + if (id_ != msg.id) return false; + updated_stamp_ = msg.stamp; + for (size_t i = 0; i < msg.nodes.size(); ++i) nodes_[i]->update(msg.nodes[i]); + for (size_t i = 0; i < msg.diags.size(); ++i) diags_[i]->update(msg.diags[i]); + for (size_t i = 0; i < msg.links.size(); ++i) links_[i]->update(msg.links[i]); + return true; +} + +template +void extend_ptrs(std::vector & result, const std::vector> & list) +{ + for (const auto & item : list) result.push_back(item.get()); +} + +template +std::vector create_ptrs(const std::vector> & list) +{ + std::vector result; + extend_ptrs(result, list); + return result; +} + +std::vector DiagGraph::units() const +{ + std::vector result; + extend_ptrs(result, nodes_); + extend_ptrs(result, diags_); + return result; +} + +std::vector DiagGraph::nodes() const +{ + return create_ptrs(nodes_); +} + +std::vector DiagGraph::diags() const +{ + return create_ptrs(diags_); +} + +std::vector DiagGraph::links() const +{ + return create_ptrs(links_); +} + +} // namespace diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/lib/subscription.cpp b/system/diagnostic_graph_utils/src/lib/subscription.cpp new file mode 100644 index 0000000000000..655544c2e1f28 --- /dev/null +++ b/system/diagnostic_graph_utils/src/lib/subscription.cpp @@ -0,0 +1,67 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "diagnostic_graph_utils/subscription.hpp" + +namespace diagnostic_graph_utils +{ + +DiagGraphSubscription::DiagGraphSubscription() +{ + graph_ = std::make_shared(); +} + +DiagGraphSubscription::DiagGraphSubscription(rclcpp::Node & node, size_t depth) +{ + graph_ = std::make_shared(); + subscribe(node, depth); +} + +void DiagGraphSubscription::subscribe(rclcpp::Node & node, size_t depth) +{ + const auto qos_struct = rclcpp::QoS(1).transient_local(); + const auto qos_status = rclcpp::QoS(depth); + + sub_struct_ = node.create_subscription( + "/diagnostics_graph/struct", qos_struct, + std::bind(&DiagGraphSubscription::on_struct, this, std::placeholders::_1)); + sub_status_ = node.create_subscription( + "/diagnostics_graph/status", qos_status, + std::bind(&DiagGraphSubscription::on_status, this, std::placeholders::_1)); +} + +void DiagGraphSubscription::register_create_callback(const CallbackType & callback) +{ + create_callback_ = callback; +} + +void DiagGraphSubscription::register_update_callback(const CallbackType & callback) +{ + update_callback_ = callback; +} + +void DiagGraphSubscription::on_struct(const DiagGraphStruct & msg) +{ + graph_->create(msg); + if (create_callback_) create_callback_(graph_); +} + +void DiagGraphSubscription::on_status(const DiagGraphStatus & msg) +{ + if (graph_->update(msg)) { + if (update_callback_) update_callback_(graph_); + } +} + +} // namespace diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/node/converter.cpp b/system/diagnostic_graph_utils/src/node/converter.cpp new file mode 100644 index 0000000000000..e9e40fa0a0756 --- /dev/null +++ b/system/diagnostic_graph_utils/src/node/converter.cpp @@ -0,0 +1,53 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "converter.hpp" + +#include + +namespace diagnostic_graph_utils +{ + +ConverterNode::ConverterNode() : Node("converter") +{ + using std::placeholders::_1; + pub_array_ = create_publisher("/diagnostics_array", rclcpp::QoS(1)); + sub_graph_.register_update_callback(std::bind(&ConverterNode::on_update, this, _1)); + sub_graph_.subscribe(*this, 1); +} + +void ConverterNode::on_update(DiagGraph::ConstSharedPtr graph) +{ + DiagnosticArray array; + array.header.stamp = graph->updated_stamp(); + for (const auto & unit : graph->units()) { + if (unit->path().empty()) continue; + array.status.push_back(unit->create_diagnostic_status()); + } + pub_array_->publish(array); +} + +} // namespace diagnostic_graph_utils + +int main(int argc, char ** argv) +{ + using diagnostic_graph_utils::ConverterNode; + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node = std::make_shared(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); +} diff --git a/system/diagnostic_graph_aggregator/src/node/converter.hpp b/system/diagnostic_graph_utils/src/node/converter.hpp similarity index 56% rename from system/diagnostic_graph_aggregator/src/node/converter.hpp rename to system/diagnostic_graph_utils/src/node/converter.hpp index 1f98abed4d619..09ce62d7293ec 100644 --- a/system/diagnostic_graph_aggregator/src/node/converter.hpp +++ b/system/diagnostic_graph_utils/src/node/converter.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 The Autoware Contributors +// Copyright 2024 The Autoware Contributors // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,41 +15,29 @@ #ifndef NODE__CONVERTER_HPP_ #define NODE__CONVERTER_HPP_ -#include "graph/types.hpp" +#include "diagnostic_graph_utils/subscription.hpp" #include -#include -#include // Use map for sorting keys. -#include -#include -#include +#include +#include -namespace diagnostic_graph_aggregator +namespace diagnostic_graph_utils { -struct TreeNode -{ - explicit TreeNode(bool leaf) : leaf(leaf) {} - bool leaf; - TreeNode * parent; - uint8_t level; -}; - class ConverterNode : public rclcpp::Node { public: ConverterNode(); private: - bool initialize_tree_; - bool complement_tree_; - std::map, std::greater> tree_; - rclcpp::Subscription::SharedPtr sub_graph_; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + void on_update(DiagGraph::ConstSharedPtr graph); rclcpp::Publisher::SharedPtr pub_array_; - void on_graph(const DiagnosticGraph::ConstSharedPtr msg); + DiagGraphSubscription sub_graph_; }; -} // namespace diagnostic_graph_aggregator +} // namespace diagnostic_graph_utils #endif // NODE__CONVERTER_HPP_ diff --git a/system/diagnostic_graph_utils/src/node/dump.cpp b/system/diagnostic_graph_utils/src/node/dump.cpp new file mode 100644 index 0000000000000..5fa4922dec1a5 --- /dev/null +++ b/system/diagnostic_graph_utils/src/node/dump.cpp @@ -0,0 +1,145 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "dump.hpp" + +#include +#include +#include +#include +#include +#include + +namespace diagnostic_graph_utils +{ + +DumpNode::DumpNode() : Node("dump") +{ + using std::placeholders::_1; + sub_graph_.register_create_callback(std::bind(&DumpNode::on_create, this, _1)); + sub_graph_.register_update_callback(std::bind(&DumpNode::on_update, this, _1)); + sub_graph_.subscribe(*this, 1); +} + +void DumpNode::on_create(DiagGraph::ConstSharedPtr graph) +{ + // Initialize table line information. + const std::string title_index = "No"; + const std::string title_level = "Level"; + const std::string title_path = "Path"; + const std::string title_type = "Type"; + const std::string title_link = "Children"; + + // Cache units. + const auto units = graph->units(); + + // Assign merged units index. + int table_index = 0; + for (const auto & unit : units) { + TableLine line; + line.index = ++table_index; + table_.emplace(unit, line); + } + + // Create link index text. Use text2 as a temporary variable. + for (const auto & unit : units) { + std::string links; + for (const auto & child : unit->children()) { + links += std::to_string(table_.at(child.unit).index) + " "; + } + if (!links.empty()) { + links.pop_back(); + } + table_.at(unit).text2 = links; + } + + // Calculate table cell width. + const auto width_index = std::max(title_index.length(), std::to_string(units.size()).length()); + const auto width_level = title_level.length(); + auto width_path = title_path.length(); + auto width_type = title_type.length(); + auto width_link = title_link.length(); + for (const auto & unit : units) { + const auto & line = table_.at(unit); + width_path = std::max(width_path, unit->path().length()); + width_type = std::max(width_type, unit->type().length()); + width_link = std::max(width_link, line.text2.length()); + } + + // Create table lines. + for (const auto & unit : units) { + auto & line = table_.at(unit); + std::ostringstream text1; + std::ostringstream text2; + text1 << "| " << std::right << std::setw(width_index) << line.index << " |"; + text2 << "| " << std::left << std::setw(width_path) << unit->path() << " "; + text2 << "| " << std::left << std::setw(width_type) << unit->type() << " "; + text2 << "| " << std::left << std::setw(width_link) << line.text2 << " |"; + line.text1 = text1.str() + " "; + line.text2 = " " + text2.str(); + } + + // Create table header. + { + std::ostringstream header; + header << "| " << std::left << std::setw(width_index) << title_index << " "; + header << "| " << std::left << std::setw(width_level) << title_level << " "; + header << "| " << std::left << std::setw(width_path) << title_path << " "; + header << "| " << std::left << std::setw(width_type) << title_type << " "; + header << "| " << std::left << std::setw(width_link) << title_link << " "; + header << "|"; + header_ = header.str(); + + border_ += "|" + std::string(width_index + 2, '-'); + border_ += "|" + std::string(width_level + 2, '-'); + border_ += "|" + std::string(width_path + 2, '-'); + border_ += "|" + std::string(width_type + 2, '-'); + border_ += "|" + std::string(width_link + 2, '-'); + border_ += "|"; + } +} + +void DumpNode::on_update(DiagGraph::ConstSharedPtr graph) +{ + const auto text_level = [](DiagUnit::DiagnosticLevel level) { + if (level == DiagUnit::DiagnosticStatus::OK) return "OK "; + if (level == DiagUnit::DiagnosticStatus::WARN) return "WARN "; + if (level == DiagUnit::DiagnosticStatus::ERROR) return "ERROR"; + if (level == DiagUnit::DiagnosticStatus::STALE) return "STALE"; + return "-----"; + }; + + std::cout << border_ << std::endl; + std::cout << header_ << std::endl; + std::cout << border_ << std::endl; + + for (const auto & unit : graph->units()) { + const auto & line = table_.at(unit); + std::cout << line.text1 << text_level(unit->level()) << line.text2 << std::endl; + } +} + +} // namespace diagnostic_graph_utils + +int main(int argc, char ** argv) +{ + using diagnostic_graph_utils::DumpNode; + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor executor; + auto node = std::make_shared(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); +} diff --git a/system/diagnostic_graph_utils/src/node/dump.hpp b/system/diagnostic_graph_utils/src/node/dump.hpp new file mode 100644 index 0000000000000..e37a1ea971bf5 --- /dev/null +++ b/system/diagnostic_graph_utils/src/node/dump.hpp @@ -0,0 +1,52 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NODE__DUMP_HPP_ +#define NODE__DUMP_HPP_ + +#include "diagnostic_graph_utils/subscription.hpp" + +#include + +#include +#include + +namespace diagnostic_graph_utils +{ + +class DumpNode : public rclcpp::Node +{ +public: + DumpNode(); + +private: + void on_create(DiagGraph::ConstSharedPtr graph); + void on_update(DiagGraph::ConstSharedPtr graph); + DiagGraphSubscription sub_graph_; + + struct TableLine + { + int index; + std::string text1; + std::string text2; + }; + + std::unordered_map table_; + std::string header_; + std::string border_; +}; + +} // namespace diagnostic_graph_utils + +#endif // NODE__DUMP_HPP_ diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index 082aa85cba97a..35ff28998ee80 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -12,6 +12,7 @@ autoware_adapi_v1_msgs autoware_auto_system_msgs + diagnostic_graph_utils diagnostic_msgs rclcpp rclcpp_components diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp index 58282306491dd..9aa354c124bba 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/hazard_status_converter/src/converter.cpp @@ -17,180 +17,104 @@ #include #include -namespace -{ - -using autoware_auto_system_msgs::msg::HazardStatus; -using autoware_auto_system_msgs::msg::HazardStatusStamped; -using diagnostic_msgs::msg::DiagnosticStatus; -using tier4_system_msgs::msg::DiagnosticGraph; -using tier4_system_msgs::msg::DiagnosticNode; -using DiagnosticLevel = DiagnosticStatus::_level_type; - -enum class HazardLevel { NF, SF, LF, SPF }; - -struct TempNode -{ - const DiagnosticNode & node; - bool is_root_tree; -}; - -HazardLevel get_hazard_level(const TempNode & node, DiagnosticLevel root_mode_level) +namespace hazard_status_converter { - // Convert the level according to the table below. - // The Level other than auto mode is considered OK. - // |-------|-------------------------------| - // | Level | Root level | - // |-------|-------------------------------| - // | | OK | WARN | ERROR | STALE | - // | OK | NF | NF | NF | NF | - // | WARN | SF | LF | LF | LF | - // | ERROR | SF | LF | SPF | SPF | - // | STALE | SF | LF | SPF | SPF | - // |-------|-------------------------------| - - const auto root_level = node.is_root_tree ? root_mode_level : DiagnosticStatus::OK; - const auto node_level = node.node.status.level; - - if (node_level == DiagnosticStatus::OK) { - return HazardLevel::NF; - } - if (root_level == DiagnosticStatus::OK) { - return HazardLevel::SF; - } - if (node_level == DiagnosticStatus::WARN) { - return HazardLevel::LF; - } - if (root_level == DiagnosticStatus::WARN) { - return HazardLevel::LF; - } - return HazardLevel::SPF; -} -void set_root_tree(std::vector & nodes, int index) +Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", options) { - TempNode & node = nodes[index]; - if (node.is_root_tree) { - return; - } - - node.is_root_tree = true; - for (const auto & link : node.node.links) { - set_root_tree(nodes, link.index); - } + using std::placeholders::_1; + pub_hazard_ = create_publisher("~/hazard_status", rclcpp::QoS(1)); + sub_graph_.register_create_callback(std::bind(&Converter::on_create, this, _1)); + sub_graph_.register_update_callback(std::bind(&Converter::on_update, this, _1)); + sub_graph_.subscribe(*this, 1); } -HazardStatusStamped convert_hazard_diagnostics( - const DiagnosticGraph & graph, const std::string & root, bool ignore) +void Converter::on_create(DiagGraph::ConstSharedPtr graph) { - // Create temporary tree for conversion. - std::vector nodes; - nodes.reserve(graph.nodes.size()); - for (const auto & node : graph.nodes) { - nodes.push_back({node, false}); - } - - // Mark nodes included in the auto mode tree. - DiagnosticLevel root_mode_level = DiagnosticStatus::STALE; - if (!root.empty() && !ignore) { - for (size_t index = 0; index < nodes.size(); ++index) { - const auto & status = nodes[index].node.status; - if (status.name == root) { - set_root_tree(nodes, index); - root_mode_level = status.level; - } + const auto find_auto_mode_root = [](const DiagGraph & graph) { + for (const auto & unit : graph.units()) { + if (unit->path() == "/autoware/modes/autonomous") return unit; } - } + return static_cast(nullptr); + }; - // Calculate hazard level from node level and root level. - HazardStatusStamped hazard; - for (const auto & node : nodes) { - switch (get_hazard_level(node, root_mode_level)) { - case HazardLevel::NF: - hazard.status.diag_no_fault.push_back(node.node.status); - break; - case HazardLevel::SF: - hazard.status.diag_safe_fault.push_back(node.node.status); - break; - case HazardLevel::LF: - hazard.status.diag_latent_fault.push_back(node.node.status); - break; - case HazardLevel::SPF: - hazard.status.diag_single_point_fault.push_back(node.node.status); - break; + const auto make_auto_mode_tree = [](DiagUnit * root) { + std::unordered_set result; + std::unordered_set buffer; + if (root) { + buffer.insert(root); } - } - return hazard; -} - -} // namespace - -namespace hazard_status_converter -{ - -Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", options) -{ - pub_hazard_ = create_publisher("~/hazard_status", rclcpp::QoS(1)); - sub_graph_ = create_subscription( - "~/diagnostics_graph", rclcpp::QoS(3), - std::bind(&Converter::on_graph, this, std::placeholders::_1)); - sub_state_ = create_subscription( - "/autoware/state", rclcpp::QoS(1), - std::bind(&Converter::on_state, this, std::placeholders::_1)); - sub_mode_ = create_subscription( - "/system/operation_mode/state", rclcpp::QoS(1).transient_local(), - std::bind(&Converter::on_mode, this, std::placeholders::_1)); -} + while (!buffer.empty()) { + const auto unit = *buffer.begin(); + buffer.erase(buffer.begin()); + result.insert(unit); + for (const auto & child : unit->children()) buffer.insert(child.unit); + } + return result; + }; -void Converter::on_state(const AutowareState::ConstSharedPtr msg) -{ - state_ = msg; + auto_mode_root_ = find_auto_mode_root(*graph); + auto_mode_tree_ = make_auto_mode_tree(auto_mode_root_); } -void Converter::on_mode(const OperationMode::ConstSharedPtr msg) +void Converter::on_update(DiagGraph::ConstSharedPtr graph) { - mode_ = msg; -} + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; + using DiagnosticLevel = DiagnosticStatus::_level_type; + using HazardStatus = autoware_auto_system_msgs::msg::HazardStatus; + using HazardLevel = HazardStatus::_level_type; + + const auto get_hazard_level = [](DiagnosticLevel unit_level, DiagnosticLevel root_level) { + // Convert the level according to the table below. + // The Level other than auto mode is considered OK. + // |-------|-------------------------------| + // | Level | Root level | + // |-------|-------------------------------| + // | | OK | WARN | ERROR | STALE | + // | OK | NF | NF | NF | NF | + // | WARN | SF | LF | LF | LF | + // | ERROR | SF | LF | SPF | SPF | + // | STALE | SF | LF | SPF | SPF | + // |-------|-------------------------------| + if (unit_level == DiagnosticStatus::OK) return HazardStatus::NO_FAULT; + if (root_level == DiagnosticStatus::OK) return HazardStatus::SAFE_FAULT; + if (unit_level == DiagnosticStatus::WARN) return HazardStatus::LATENT_FAULT; + if (root_level == DiagnosticStatus::WARN) return HazardStatus::LATENT_FAULT; + return HazardStatus::SINGLE_POINT_FAULT; + }; -void Converter::on_graph(const DiagnosticGraph::ConstSharedPtr msg) -{ const auto get_system_level = [](const HazardStatus & status) { - if (!status.diag_single_point_fault.empty()) { - return HazardStatus::SINGLE_POINT_FAULT; - } - if (!status.diag_latent_fault.empty()) { - return HazardStatus::LATENT_FAULT; - } - if (!status.diag_safe_fault.empty()) { - return HazardStatus::SAFE_FAULT; - } + if (!status.diag_single_point_fault.empty()) return HazardStatus::SINGLE_POINT_FAULT; + if (!status.diag_latent_fault.empty()) return HazardStatus::LATENT_FAULT; + if (!status.diag_safe_fault.empty()) return HazardStatus::SAFE_FAULT; return HazardStatus::NO_FAULT; }; - const auto is_ignore = [this]() { - if (mode_ && state_) { - if (mode_->mode == OperationMode::AUTONOMOUS || mode_->mode == OperationMode::STOP) { - if (state_->state == AutowareState::WAITING_FOR_ROUTE) return true; - if (state_->state == AutowareState::PLANNING) return true; - } - if (state_->state == AutowareState::INITIALIZING) return true; - if (state_->state == AutowareState::FINALIZING) return true; - } - return false; + const auto get_hazards_vector = [](HazardStatus & status, HazardLevel level) { + if (level == HazardStatus::SINGLE_POINT_FAULT) return &status.diag_single_point_fault; + if (level == HazardStatus::LATENT_FAULT) return &status.diag_latent_fault; + if (level == HazardStatus::SAFE_FAULT) return &status.diag_safe_fault; + if (level == HazardStatus::NO_FAULT) return &status.diag_no_fault; + return static_cast *>(nullptr); }; - const auto get_root = [this]() { - if (mode_) { - if (mode_->mode == OperationMode::STOP) return "/autoware/modes/stop"; - if (mode_->mode == OperationMode::AUTONOMOUS) return "/autoware/modes/autonomous"; - if (mode_->mode == OperationMode::LOCAL) return "/autoware/modes/local"; - if (mode_->mode == OperationMode::REMOTE) return "/autoware/modes/remote"; - } - return ""; - }; + if (!auto_mode_root_) { + RCLCPP_ERROR_STREAM_THROTTLE(get_logger(), *get_clock(), 10000, "No auto mode unit."); + return; + } - HazardStatusStamped hazard = convert_hazard_diagnostics(*msg, get_root(), is_ignore()); - hazard.stamp = msg->stamp; + // Calculate hazard level from unit level and root level. + HazardStatusStamped hazard; + for (const auto & unit : graph->units()) { + if (unit->path().empty()) continue; + const bool is_auto_tree = auto_mode_tree_.count(unit); + const auto root_level = is_auto_tree ? auto_mode_root_->level() : DiagnosticStatus::OK; + const auto unit_level = unit->level(); + if (auto diags = get_hazards_vector(hazard.status, get_hazard_level(unit_level, root_level))) { + diags->push_back(unit->create_diagnostic_status()); + } + } + hazard.stamp = graph->updated_stamp(); hazard.status.level = get_system_level(hazard.status); hazard.status.emergency = hazard.status.level == HazardStatus::SINGLE_POINT_FAULT; hazard.status.emergency_holding = false; diff --git a/system/hazard_status_converter/src/converter.hpp b/system/hazard_status_converter/src/converter.hpp index 04e84cfb3c0c4..ad14ddde2bf5c 100644 --- a/system/hazard_status_converter/src/converter.hpp +++ b/system/hazard_status_converter/src/converter.hpp @@ -15,16 +15,12 @@ #ifndef CONVERTER_HPP_ #define CONVERTER_HPP_ +#include #include -#include -#include #include -#include -#include -#include -#include +#include namespace hazard_status_converter { @@ -35,20 +31,16 @@ class Converter : public rclcpp::Node explicit Converter(const rclcpp::NodeOptions & options); private: - using AutowareState = autoware_auto_system_msgs::msg::AutowareState; - using OperationMode = autoware_adapi_v1_msgs::msg::OperationModeState; - using DiagnosticGraph = tier4_system_msgs::msg::DiagnosticGraph; using HazardStatusStamped = autoware_auto_system_msgs::msg::HazardStatusStamped; - rclcpp::Subscription::SharedPtr sub_state_; - rclcpp::Subscription::SharedPtr sub_mode_; - rclcpp::Subscription::SharedPtr sub_graph_; + using DiagGraph = diagnostic_graph_utils::DiagGraph; + using DiagUnit = diagnostic_graph_utils::DiagUnit; + void on_create(DiagGraph::ConstSharedPtr graph); + void on_update(DiagGraph::ConstSharedPtr graph); + diagnostic_graph_utils::DiagGraphSubscription sub_graph_; rclcpp::Publisher::SharedPtr pub_hazard_; - void on_state(const AutowareState::ConstSharedPtr msg); - void on_mode(const OperationMode::ConstSharedPtr msg); - void on_graph(const DiagnosticGraph::ConstSharedPtr msg); - AutowareState::ConstSharedPtr state_; - OperationMode::ConstSharedPtr mode_; + DiagUnit * auto_mode_root_; + std::unordered_set auto_mode_tree_; }; } // namespace hazard_status_converter diff --git a/system/system_diagnostic_monitor/CMakeLists.txt b/system/system_diagnostic_monitor/CMakeLists.txt new file mode 100644 index 0000000000000..b253b5dbc0529 --- /dev/null +++ b/system/system_diagnostic_monitor/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.14) +project(system_diagnostic_monitor) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +install(PROGRAMS + script/component_state_diagnostics.py + RENAME component_state_diagnostics + DESTINATION lib/${PROJECT_NAME} +) + +ament_auto_package(INSTALL_TO_SHARE config launch) diff --git a/system/system_diagnostic_monitor/README.md b/system/system_diagnostic_monitor/README.md new file mode 100644 index 0000000000000..94f5897076ff6 --- /dev/null +++ b/system/system_diagnostic_monitor/README.md @@ -0,0 +1,16 @@ +# system_diagnostic_monitor + +This package contains default configurations of diagnostic graph and scripts for system integration. + +## Configs + +| Name | Description | +| ------------------------------------------------- | ------------------------------------------------------------ | +| [autoware-main.yaml](./config/autoware-main.yaml) | Diagnostic graphs for basic monitoring of Autoware. | +| [autoware-psim.yaml](./config/autoware-psim.yaml) | Diagnostic graph with some units disabled for the simulator. | + +## Scripts + +| Name | Description | +| ---------------------------------------------------------------------- | --------------------------------------------------- | +| [component_state_diagnostics](./script/component_state_diagnostics.py) | Node that converts component states to diagnostics. | diff --git a/system/system_diagnostic_monitor/config/autoware-main.yaml b/system/system_diagnostic_monitor/config/autoware-main.yaml new file mode 100644 index 0000000000000..26f3fee2863d0 --- /dev/null +++ b/system/system_diagnostic_monitor/config/autoware-main.yaml @@ -0,0 +1,70 @@ +files: + - { path: $(find-pkg-share system_diagnostic_monitor)/config/map.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/localization.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/planning.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/perception.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/control.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/vehicle.yaml } + - { path: $(find-pkg-share system_diagnostic_monitor)/config/system.yaml } + +units: + - path: /autoware/modes/stop + type: ok + + - path: /autoware/modes/autonomous + type: and + list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/modes/local + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + - { type: link, link: /autoware/control/local } + + - path: /autoware/modes/remote + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + - { type: link, link: /autoware/control/remote } + + - path: /autoware/modes/emergency_stop + type: and + list: + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/modes/comfortable_stop + type: and + list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/modes/pull_over + type: and + list: + - { type: link, link: /autoware/map } + - { type: link, link: /autoware/localization } + - { type: link, link: /autoware/planning } + - { type: link, link: /autoware/perception } + - { type: link, link: /autoware/control } + - { type: link, link: /autoware/vehicle } + - { type: link, link: /autoware/system } + + - path: /autoware/debug/tools + type: and + list: + - { type: link, link: /autoware/system/service_log_checker } diff --git a/system/system_diagnostic_monitor/config/autoware-psim.yaml b/system/system_diagnostic_monitor/config/autoware-psim.yaml new file mode 100644 index 0000000000000..6962607f912b3 --- /dev/null +++ b/system/system_diagnostic_monitor/config/autoware-psim.yaml @@ -0,0 +1,11 @@ +files: + - { path: $(find-pkg-share system_diagnostic_monitor)/config/autoware-main.yaml } + +edits: + - { type: remove, path: /autoware/map/topic_rate_check/pointcloud_map } + - { type: remove, path: /autoware/localization/matching_score } + - { type: remove, path: /autoware/localization/accuracy } + - { type: remove, path: /autoware/localization/sensor_fusion_status } + - { type: remove, path: /autoware/localization/topic_rate_check/pose_twist_fusion } + - { type: remove, path: /autoware/perception/topic_rate_check/pointcloud } + - { type: remove, path: /autoware/control/emergency_braking } diff --git a/system/system_diagnostic_monitor/config/control.yaml b/system/system_diagnostic_monitor/config/control.yaml new file mode 100644 index 0000000000000..57bf1b86c2bfc --- /dev/null +++ b/system/system_diagnostic_monitor/config/control.yaml @@ -0,0 +1,73 @@ +units: + - path: /autoware/control + type: and + list: + - { type: link, link: /autoware/control/topic_rate_check/trajectory_follower } + - { type: link, link: /autoware/control/topic_rate_check/control_command } + - { type: link, link: /autoware/control/node_alive_monitoring/vehicle_cmd_gate } + - { type: link, link: /autoware/control/emergency_braking } + - { type: link, link: /autoware/control/performance_monitoring/lane_departure } + - { type: link, link: /autoware/control/performance_monitoring/trajectory_deviation } + - { type: link, link: /autoware/control/performance_monitoring/control_state } + + - path: /autoware/control/local + type: and + list: + - { type: link, link: /autoware/control/topic_rate_check/selector } + - { type: link, link: /autoware/control/topic_rate_check/local } + + - path: /autoware/control/remote + type: and + list: + - { type: link, link: /autoware/control/topic_rate_check/selector } + - { type: link, link: /autoware/control/topic_rate_check/remote } + + - path: /autoware/control/topic_rate_check/trajectory_follower + type: diag + node: topic_state_monitor_trajectory_follower_control_cmd + name: control_topic_status + + - path: /autoware/control/topic_rate_check/control_command + type: diag + node: topic_state_monitor_control_command_control_cmd + name: control_topic_status + + - path: /autoware/control/node_alive_monitoring/vehicle_cmd_gate + type: diag + node: vehicle_cmd_gate + name: heartbeat + + - path: /autoware/control/emergency_braking + type: diag + node: autonomous_emergency_braking + name: aeb_emergency_stop + + - path: /autoware/control/performance_monitoring/lane_departure + type: diag + node: lane_departure_checker_node + name: lane_departure + + - path: /autoware/control/performance_monitoring/trajectory_deviation + type: diag + node: lane_departure_checker_node + name: trajectory_deviation + + - path: /autoware/control/performance_monitoring/control_state + type: diag + node: controller_node_exe + name: control_state + + - path: /autoware/control/topic_rate_check/selector + type: diag + node: external_cmd_selector + name: heartbeat + + - path: /autoware/control/topic_rate_check/local + type: diag + node: joy_controller + name: joy_controller_connection + + - path: /autoware/control/topic_rate_check/remote + type: diag + node: external_cmd_converter + name: remote_control_topic_status diff --git a/system/system_diagnostic_monitor/config/hardware.yaml b/system/system_diagnostic_monitor/config/hardware.yaml new file mode 100644 index 0000000000000..d73f723670f98 --- /dev/null +++ b/system/system_diagnostic_monitor/config/hardware.yaml @@ -0,0 +1,121 @@ +# TODO(Takagi, Isamu): This file is under construction. +units: + - path: /autoware/system/resources/clock/offset + diag: ": NTP Offset" + timeout: 10.0 + + - path: /autoware/system/resources/cpu/offset + diag: ": CPU Temperature" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/usage + diag: ": CPU Usage" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/thermal_throttling + diag: ": CPU Thermal Throttling" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/frequency + diag: ": CPU Frequency" + timeout: 3.0 + + - path: /autoware/system/resources/cpu/load_average + diag: ": CPU Load Average" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/temperature + diag: ": GPU Temperature" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/usage + diag: ": GPU Usage" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/memory_usage + diag: ": GPU Memory Usage" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/thermal_throttling + diag: ": GPU Thermal Throttling" + timeout: 3.0 + + - path: /autoware/system/resources/gpu/frequency + diag: ": GPU Frequency" + timeout: 3.0 + + - path: /autoware/system/resources/memory/usage + diag: ": Memory Usage" + timeout: 3.0 + + - path: /autoware/system/resources/network/usage + diag: ": Network Usage" + timeout: 3.0 + + - path: /autoware/system/resources/network/traffic + diag: ": Network Traffic" + timeout: 3.0 + + - path: /autoware/system/resources/network/crc + diag: ": Network CRC Error" + timeout: 3.0 + + - path: /autoware/system/resources/network/packet_reassembles + diag: ": IP Packet Reassembles Failed" + timeout: 3.0 + + - path: /autoware/system/resources/storage/temperature + diag: ": HDD Temperature" + timeout: 3.0 + + - path: /autoware/system/resources/storage/recovered_error + diag: ": HDD RecoveredError" + timeout: 3.0 + + - path: /autoware/system/resources/storage/read_data_rate + diag: ": HDD ReadDataRate" + timeout: 3.0 + + - path: /autoware/system/resources/storage/write_data_rate + diag: ": HDD WriteDataRate" + timeout: 3.0 + + - path: /autoware/system/resources/storage/read_iops + diag: ": HDD ReadIOPS" + timeout: 3.0 + + - path: /autoware/system/resources/storage/write_iops + diag: ": HDD WriteIOPS" + timeout: 3.0 + + - path: /autoware/system/resources/storage/usage + diag: ": HDD Usage" + timeout: 3.0 + + - path: /autoware/system/resources/storage/power_on_hours + diag: ": HDD PowerOnHours" + timeout: 3.0 + + - path: /autoware/system/resources/storage/total_data_written + diag: ": HDD TotalDataWritten" + timeout: 3.0 + + - path: /autoware/system/resources/storage/connection + diag: ": HDD Connection" + timeout: 3.0 + + - path: /autoware/system/resources/process/high_load + diag: ": High-load" + timeout: 3.0 + + - path: /autoware/system/resources/process/high_mem + diag: ": High-mem" + timeout: 3.0 + + - path: /autoware/system/resources/process/tasks_summary + diag: ": Tasks Summary" + timeout: 3.0 + + - path: /autoware/system/resources/voltage/battery + diag: ": CMOS Battery Status" + timeout: 3.0 diff --git a/system/system_diagnostic_monitor/config/localization.yaml b/system/system_diagnostic_monitor/config/localization.yaml new file mode 100644 index 0000000000000..334101875aba6 --- /dev/null +++ b/system/system_diagnostic_monitor/config/localization.yaml @@ -0,0 +1,43 @@ +units: + - path: /autoware/localization + type: short-circuit-and + list: + - type: link + link: /autoware/localization/state + - type: and + list: + - { type: link, link: /autoware/localization/topic_rate_check/transform } + - { type: link, link: /autoware/localization/topic_rate_check/pose_twist_fusion } + - { type: link, link: /autoware/localization/matching_score } + - { type: link, link: /autoware/localization/accuracy } + - { type: link, link: /autoware/localization/sensor_fusion_status } + + - path: /autoware/localization/state + type: diag + node: component_state_diagnostics + name: localization_state + + - path: /autoware/localization/topic_rate_check/transform + type: diag + node: topic_state_monitor_transform_map_to_base_link + name: localization_topic_status + + - path: /autoware/localization/topic_rate_check/pose_twist_fusion + type: diag + node: topic_state_monitor_pose_twist_fusion_filter_pose + name: localization_topic_status + + - path: /autoware/localization/matching_score + type: diag + node: "" + name: ndt_scan_matcher + + - path: /autoware/localization/accuracy + type: diag + node: localization + name: localization_error_monitor + + - path: /autoware/localization/sensor_fusion_status + type: diag + node: localization + name: ekf_localizer diff --git a/system/system_diagnostic_monitor/config/map.yaml b/system/system_diagnostic_monitor/config/map.yaml new file mode 100644 index 0000000000000..45c1db294119f --- /dev/null +++ b/system/system_diagnostic_monitor/config/map.yaml @@ -0,0 +1,16 @@ +units: + - path: /autoware/map + type: and + list: + - { type: link, link: /autoware/map/topic_rate_check/vector_map } + - { type: link, link: /autoware/map/topic_rate_check/pointcloud_map } + + - path: /autoware/map/topic_rate_check/vector_map + type: diag + node: topic_state_monitor_vector_map + name: map_topic_status + + - path: /autoware/map/topic_rate_check/pointcloud_map + type: diag + node: topic_state_monitor_pointcloud_map + name: map_topic_status" diff --git a/system/system_diagnostic_monitor/config/perception.yaml b/system/system_diagnostic_monitor/config/perception.yaml new file mode 100644 index 0000000000000..24e3c4eed5295 --- /dev/null +++ b/system/system_diagnostic_monitor/config/perception.yaml @@ -0,0 +1,16 @@ +units: + - path: /autoware/perception + type: and + list: + - { type: link, link: /autoware/perception/topic_rate_check/objects } + - { type: link, link: /autoware/perception/topic_rate_check/pointcloud } + + - path: /autoware/perception/topic_rate_check/objects + type: diag + node: topic_state_monitor_object_recognition_objects + name: perception_topic_status + + - path: /autoware/perception/topic_rate_check/pointcloud + type: diag + node: topic_state_monitor_obstacle_segmentation_pointcloud + name: perception_topic_status diff --git a/system/system_diagnostic_monitor/config/planning.yaml b/system/system_diagnostic_monitor/config/planning.yaml new file mode 100644 index 0000000000000..c403fec2371c3 --- /dev/null +++ b/system/system_diagnostic_monitor/config/planning.yaml @@ -0,0 +1,90 @@ +units: + - path: /autoware/planning + type: short-circuit-and + list: + - type: link + link: /autoware/planning/routing/state + - type: and + list: + - { type: link, link: /autoware/planning/topic_rate_check/route } + - { type: link, link: /autoware/planning/topic_rate_check/trajectory } + - { type: link, link: /autoware/planning/trajectory_validation } + + - path: /autoware/planning/trajectory_validation + type: and + list: + - { type: link, link: /autoware/planning/trajectory_validation/finite } + - { type: link, link: /autoware/planning/trajectory_validation/interval } + - { type: link, link: /autoware/planning/trajectory_validation/curvature } + - { type: link, link: /autoware/planning/trajectory_validation/angle } + - { type: link, link: /autoware/planning/trajectory_validation/lateral_acceleration } + - { type: link, link: /autoware/planning/trajectory_validation/acceleration } + - { type: link, link: /autoware/planning/trajectory_validation/deceleration } + - { type: link, link: /autoware/planning/trajectory_validation/steering } + - { type: link, link: /autoware/planning/trajectory_validation/steering_rate } + - { type: link, link: /autoware/planning/trajectory_validation/velocity_deviation } + + - path: /autoware/planning/routing/state + type: diag + node: component_state_diagnostics + name: route_state + + - path: /autoware/planning/topic_rate_check/route + type: diag + node: topic_state_monitor_mission_planning_route + name: planning_topic_status + + - path: /autoware/planning/topic_rate_check/trajectory + type: diag + node: topic_state_monitor_scenario_planning_trajectory + name: planning_topic_status + + - path: /autoware/planning/trajectory_validation/finite + type: diag + node: planning_validator + name: trajectory_validation_finite + + - path: /autoware/planning/trajectory_validation/interval + type: diag + node: planning_validator + name: trajectory_validation_interval + + - path: /autoware/planning/trajectory_validation/curvature + type: diag + node: planning_validator + name: trajectory_validation_curvature + + - path: /autoware/planning/trajectory_validation/angle + type: diag + node: planning_validator + name: trajectory_validation_relative_angle + + - path: /autoware/planning/trajectory_validation/lateral_acceleration + type: diag + node: planning_validator + name: trajectory_validation_lateral_acceleration + + - path: /autoware/planning/trajectory_validation/acceleration + type: diag + node: planning_validator + name: trajectory_validation_acceleration + + - path: /autoware/planning/trajectory_validation/deceleration + type: diag + node: planning_validator + name: trajectory_validation_deceleration + + - path: /autoware/planning/trajectory_validation/steering + type: diag + node: planning_validator + name: trajectory_validation_steering + + - path: /autoware/planning/trajectory_validation/steering_rate + type: diag + node: planning_validator + name: trajectory_validation_steering_rate + + - path: /autoware/planning/trajectory_validation/velocity_deviation + type: diag + node: planning_validator + name: trajectory_validation_velocity_deviation diff --git a/system/system_diagnostic_monitor/config/system.yaml b/system/system_diagnostic_monitor/config/system.yaml new file mode 100644 index 0000000000000..cb96c2cd7f276 --- /dev/null +++ b/system/system_diagnostic_monitor/config/system.yaml @@ -0,0 +1,27 @@ +units: + - path: /autoware/system + type: and + list: + - { type: link, link: /autoware/system/duplicated_node_checker } + - { type: link, link: /autoware/system/topic_rate_check/emergency_control_command } + - { type: link, link: /autoware/system/emergency_stop_operation } + + - path: /autoware/system/duplicated_node_checker + type: diag + node: duplicated_node_checker + name: duplicated_node_checker + + - path: /autoware/system/service_log_checker + type: diag + node: service_log_checker + name: response_status + + - path: /autoware/system/topic_rate_check/emergency_control_command + type: diag + node: topic_state_monitor_system_emergency_control_cmd + name: system_topic_status + + - path: /autoware/system/emergency_stop_operation + type: diag + node: vehicle_cmd_gate + name: emergency_stop_operation diff --git a/system/system_diagnostic_monitor/config/vehicle.yaml b/system/system_diagnostic_monitor/config/vehicle.yaml new file mode 100644 index 0000000000000..e040e3c3c305e --- /dev/null +++ b/system/system_diagnostic_monitor/config/vehicle.yaml @@ -0,0 +1,16 @@ +units: + - path: /autoware/vehicle + type: and + list: + - { type: link, link: /autoware/vehicle/topic_rate_check/velocity } + - { type: link, link: /autoware/vehicle/topic_rate_check/steering } + + - path: /autoware/vehicle/topic_rate_check/velocity + type: diag + node: topic_state_monitor_vehicle_status_velocity_status + name: vehicle_topic_status + + - path: /autoware/vehicle/topic_rate_check/steering + type: diag + node: topic_state_monitor_vehicle_status_steering_status + name: vehicle_topic_status diff --git a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml new file mode 100644 index 0000000000000..b00fcb8a26f68 --- /dev/null +++ b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/system/system_diagnostic_monitor/package.xml b/system/system_diagnostic_monitor/package.xml new file mode 100644 index 0000000000000..a54a3dd0d109a --- /dev/null +++ b/system/system_diagnostic_monitor/package.xml @@ -0,0 +1,25 @@ + + + + system_diagnostic_monitor + 0.1.0 + The system_diagnostic_monitor package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_adapi_v1_msgs + diagnostic_graph_aggregator + diagnostic_msgs + rclpy + tier4_system_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/system/system_diagnostic_monitor/script/component_state_diagnostics.py b/system/system_diagnostic_monitor/script/component_state_diagnostics.py new file mode 100755 index 0000000000000..9117f818e60fd --- /dev/null +++ b/system/system_diagnostic_monitor/script/component_state_diagnostics.py @@ -0,0 +1,102 @@ +#!/usr/bin/env python3 + +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from autoware_adapi_v1_msgs.msg import LocalizationInitializationState as LocalizationState +from autoware_adapi_v1_msgs.msg import RouteState +from diagnostic_msgs.msg import DiagnosticArray +from diagnostic_msgs.msg import DiagnosticStatus +import rclpy +import rclpy.node +import rclpy.qos +import rclpy.time + + +class ComponentStateDiagnostics: + def __init__(self, node, diag_name, topic_name, topic_type, topic_qos, diag_func): + self.node = node + self.name = diag_name + self.func = diag_func + self.sub = node.create_subscription(topic_type, topic_name, self.callback, topic_qos) + self.level = DiagnosticStatus.STALE + self.stamp = None + + def callback(self, msg): + self.level = DiagnosticStatus.OK if self.func(msg) else DiagnosticStatus.ERROR + self.stamp = self.node.get_clock().now() + + def update(self, stamp): + if self.stamp: + elapsed = (stamp - self.stamp).nanoseconds * 1e-9 + if 3.0 < elapsed: + self.level = DiagnosticStatus.STALE + self.stamp = None + + def message(self): + status = DiagnosticStatus() + status.name = self.name + status.level = self.level + return status + + +class ComponentStateDiagnosticsNode(rclpy.node.Node): + def __init__(self): + super().__init__("component_state_diagnostics") + durable_qos = rclpy.qos.QoSProfile( + depth=1, + durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL, + reliability=rclpy.qos.ReliabilityPolicy.RELIABLE, + ) + + self.timer = self.create_timer(0.5, self.on_timer) + self.pub = self.create_publisher(DiagnosticArray, "/diagnostics", 1) + self.states = [] + self.states.append( + ComponentStateDiagnostics( + self, + "component_state_diagnostics: localization_state", + "/api/localization/initialization_state", + LocalizationState, + durable_qos, + lambda msg: msg.state == LocalizationState.INITIALIZED, + ) + ) + self.states.append( + ComponentStateDiagnostics( + self, + "component_state_diagnostics: route_state", + "/api/routing/state", + RouteState, + durable_qos, + lambda msg: msg.state != RouteState.UNSET, + ) + ) + + def on_timer(self): + stamp = self.get_clock().now() + array = DiagnosticArray() + array.header.stamp = stamp.to_msg() + for state in self.states: + array.status.append(state.message()) + self.pub.publish(array) + + +if __name__ == "__main__": + try: + rclpy.init() + rclpy.spin(ComponentStateDiagnosticsNode()) + rclpy.shutdown() + except KeyboardInterrupt: + pass diff --git a/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt b/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt new file mode 100644 index 0000000000000..9e8bb20bb92a3 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required(VERSION 3.14) +project(rqt_diagnostic_graph_monitor) + +find_package(autoware_cmake REQUIRED) +autoware_package() +ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR python) +install(FILES plugin.xml DESTINATION share/${PROJECT_NAME}) +install(PROGRAMS script/rqt_diagnostic_graph_monitor DESTINATION lib/${PROJECT_NAME}) +ament_auto_package(INSTALL_TO_SHARE script) diff --git a/tools/rqt_diagnostic_graph_monitor/README.md b/tools/rqt_diagnostic_graph_monitor/README.md new file mode 100644 index 0000000000000..8dccca34db8c5 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/README.md @@ -0,0 +1 @@ +# System diagnostic monitor diff --git a/tools/rqt_diagnostic_graph_monitor/package.xml b/tools/rqt_diagnostic_graph_monitor/package.xml new file mode 100644 index 0000000000000..60780e2794998 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/package.xml @@ -0,0 +1,24 @@ + + + + rqt_diagnostic_graph_monitor + 0.1.0 + The rqt_diagnostic_graph_monitor package + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + python_qt_binding + rqt_gui + rqt_gui_py + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + + diff --git a/tools/rqt_diagnostic_graph_monitor/plugin.xml b/tools/rqt_diagnostic_graph_monitor/plugin.xml new file mode 100644 index 0000000000000..6c64185e3f0af --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/plugin.xml @@ -0,0 +1,16 @@ + + + + + + + + folder + + + + utilities-system-monitor + + + + diff --git a/tools/rqt_diagnostic_graph_monitor/python/__init__.py b/tools/rqt_diagnostic_graph_monitor/python/__init__.py new file mode 100644 index 0000000000000..10f125fa447b5 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/__init__.py @@ -0,0 +1,37 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from rqt_gui_py.plugin import Plugin + +from .module import MonitorModule +from .widget import MonitorWidget + + +class MonitorPlugin(Plugin): + def __init__(self, context): + super().__init__(context) + self.widget = MonitorWidget() + self.module = MonitorModule(context.node) + self.module.append_struct_callback(self.widget.on_graph) + context.add_widget(self.widget) + + def shutdown_plugin(self): + self.module.shutdown() + self.widget.shutdown() + + def save_settings(self, plugin_settings, instance_settings): + pass + + def restore_settings(self, plugin_settings, instance_settings): + pass diff --git a/tools/rqt_diagnostic_graph_monitor/python/graph.py b/tools/rqt_diagnostic_graph_monitor/python/graph.py new file mode 100644 index 0000000000000..cea81c1226637 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/graph.py @@ -0,0 +1,127 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from diagnostic_msgs.msg import DiagnosticStatus +from rclpy.time import Time + + +class DummyStatus: + def __init__(self): + self.level = DiagnosticStatus.STALE + + +class BaseUnit: + def __init__(self, status=DummyStatus()): + self._parents = [] + self._children = [] + self._path = None + self._type = None + self._status = status + + @property + def parents(self): + return self._parents + + @property + def children(self): + return self._children + + @property + def path(self): + return self._path + + @property + def kind(self): + return self._type + + +class NodeUnit(BaseUnit): + def __init__(self, struct): + super().__init__() + self._path = struct.path + self._type = struct.type + + def update(self, status): + self._status = status + + @property + def level(self): + return self._status.level + + +class DiagUnit(BaseUnit): + def __init__(self, struct): + super().__init__() + self._path = struct.path + self._name = struct.name + self._type = "diag" + + def update(self, status): + self._status = status + + @property + def level(self): + return self._status.level + + +class UnitLink: + def __init__(self, parent: BaseUnit, child: BaseUnit): + self._parent = parent + self._child = child + parent._children.append(self) + child._parents.append(self) + + def update(self, status): + self.status = status + + @property + def parent(self): + return self._parent + + @property + def child(self): + return self._child + + +class Graph: + def __init__(self, msg): + self._struct_stamp = Time.from_msg(msg.stamp) + self._status_stamp = None + self._id = msg.id + self._nodes = [NodeUnit(struct) for struct in msg.nodes] + self._diags = [DiagUnit(struct) for struct in msg.diags] + self._units = self._nodes + self._diags + self._links = [] + for struct in msg.links: + units = self._diags if struct.is_leaf else self._nodes + nodes = self._nodes + self._links.append(UnitLink(nodes[struct.parent], units[struct.child])) + + def update(self, msg): + if msg.id == self._id: + self._status_stamp = Time.from_msg(msg.stamp) + for node, status in zip(self._nodes, msg.nodes): + node.update(status) + for diag, status in zip(self._diags, msg.diags): + diag.update(status) + for link, status in zip(self._links, msg.links): + link.update(status) + + @property + def units(self): + return self._units + + @property + def links(self): + return self._links diff --git a/tools/rqt_diagnostic_graph_monitor/python/items.py b/tools/rqt_diagnostic_graph_monitor/python/items.py new file mode 100644 index 0000000000000..96f60ef0e09cf --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/items.py @@ -0,0 +1,54 @@ +# Copyright 2024 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +from diagnostic_msgs.msg import DiagnosticStatus +from python_qt_binding import QtGui +from python_qt_binding import QtWidgets + +from .graph import BaseUnit +from .graph import UnitLink + + +class MonitorIcons: + def __init__(self): + self.disable = QtGui.QIcon.fromTheme("dialog-question") + self.unknown = QtGui.QIcon.fromTheme("system-search") + self.ok = QtGui.QIcon.fromTheme("emblem-default") + self.warn = QtGui.QIcon.fromTheme("emblem-important") + self.error = QtGui.QIcon.fromTheme("dialog-error") + self.stale = QtGui.QIcon.fromTheme("appointment-missed") + + self._levels = {} + self._levels[DiagnosticStatus.OK] = self.ok + self._levels[DiagnosticStatus.WARN] = self.warn + self._levels[DiagnosticStatus.ERROR] = self.error + self._levels[DiagnosticStatus.STALE] = self.stale + + def get(self, level): + return self._levels.get(level, self.unknown) + + +class MonitorItem: + icons = MonitorIcons() + + def __init__(self, link: UnitLink, unit: BaseUnit): + item_text = f"{unit.path} ({unit.kind})" if unit.path else f"({unit.kind})" + self.item = QtWidgets.QTreeWidgetItem([item_text]) + self.link = link + self.unit = unit + self.item.setIcon(0, self.icons.stale) + + def update(self): + self.item.setIcon(0, self.icons.get(self.unit.level)) diff --git a/tools/rqt_diagnostic_graph_monitor/python/module.py b/tools/rqt_diagnostic_graph_monitor/python/module.py new file mode 100644 index 0000000000000..74294659ef61a --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/module.py @@ -0,0 +1,61 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +from rclpy.node import Node +from tier4_system_msgs.msg import DiagGraphStatus +from tier4_system_msgs.msg import DiagGraphStruct + +from .graph import Graph +from .utils import default_qos +from .utils import durable_qos +from .utils import foreach + + +class MonitorModule: + def __init__(self, node: Node): + self.graph = None + self.struct_callbacks = [] + self.status_callbacks = [] + self.node = node + self.sub_struct = self.subscribe_struct() + self.sub_status = self.subscribe_status() + + def append_struct_callback(self, callback): + self.struct_callbacks.append(callback) + + def append_status_callback(self, callback): + self.status_callbacks.append(callback) + + def on_struct(self, msg): + self.graph = Graph(msg) + foreach(self.struct_callbacks, lambda callback: callback(self.graph)) + + def on_status(self, msg): + self.graph.update(msg) + foreach(self.status_callbacks, lambda callback: callback(self.graph)) + + def subscribe_struct(self): + return self.node.create_subscription( + DiagGraphStruct, "/diagnostics_graph/struct", self.on_struct, durable_qos(1) + ) + + def subscribe_status(self): + return self.node.create_subscription( + DiagGraphStatus, "/diagnostics_graph/status", self.on_status, default_qos(1) + ) + + def shutdown(self): + self.node.destroy_subscription(self.sub_struct) + self.node.destroy_subscription(self.sub_status) diff --git a/tools/rqt_diagnostic_graph_monitor/python/utils.py b/tools/rqt_diagnostic_graph_monitor/python/utils.py new file mode 100644 index 0000000000000..6e66102b16dc9 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/utils.py @@ -0,0 +1,29 @@ +# Copyright 2024 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from rclpy.qos import QoSDurabilityPolicy +from rclpy.qos import QoSProfile + + +def default_qos(depth): + return QoSProfile(depth=depth) + + +def durable_qos(depth): + return QoSProfile(depth=depth, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) + + +def foreach(iterable, function): + for item in iterable: + function(item) diff --git a/tools/rqt_diagnostic_graph_monitor/python/widget.py b/tools/rqt_diagnostic_graph_monitor/python/widget.py new file mode 100644 index 0000000000000..e7f022e5907c0 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/python/widget.py @@ -0,0 +1,85 @@ +# Copyright 2023 The Autoware Contributors +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from python_qt_binding import QtCore +from python_qt_binding import QtWidgets + +from .graph import Graph +from .items import MonitorItem +from .utils import foreach + + +class MonitorWidget(QtWidgets.QSplitter): + def __init__(self): + super().__init__() + self.graph = None + self.items = [] + self.root_widget = QtWidgets.QTreeWidget() + self.tree_widget = QtWidgets.QTreeWidget() + self.root_widget.setHeaderLabels(["Top-level"]) + self.tree_widget.setHeaderLabels(["Subtrees"]) + self.addWidget(self.root_widget) + self.addWidget(self.tree_widget) + + self._timer = QtCore.QTimer() + self._timer.timeout.connect(self.on_timer) + self._timer.start(500) + + def shutdown(self): + self.clear_graph() + + def on_timer(self): + foreach(self.items, lambda item: item.update()) + + def on_graph(self, graph: Graph): + self.clear_graph() + self.build_graph(graph) + + def clear_graph(self): + self.graph = None + self.items = [] + self.root_widget.clear() + self.tree_widget.clear() + + def build_graph(self, graph: Graph): + self.graph = graph + root_units = filter(self.is_root_unit, self.graph.units) + tree_units = filter(self.is_tree_unit, self.graph.units) + root_items = [MonitorItem(None, unit) for unit in root_units] + tree_items = [MonitorItem(None, unit) for unit in tree_units] + link_items = [MonitorItem(link, link.child) for link in self.graph.links] + self.items = root_items + tree_items + link_items + + # Note: overwrite link items with root/tree items if there is more than one. + parents = {} + for items in [link_items, tree_items, root_items]: + parents.update({item.unit: item.item for item in items}) + + # Connect tree widget items. + root_widget_item = self.root_widget.invisibleRootItem() + tree_widget_item = self.tree_widget.invisibleRootItem() + for item in root_items: + root_widget_item.addChild(item.item) + for item in tree_items: + tree_widget_item.addChild(item.item) + for item in link_items: + parents[item.link.parent].addChild(item.item) + + @staticmethod + def is_root_unit(unit): + return len(unit.parents) == 0 + + @staticmethod + def is_tree_unit(unit): + return len(unit.parents) >= 2 and len(unit.children) != 0 diff --git a/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor b/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor new file mode 100755 index 0000000000000..8b0685125d026 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor @@ -0,0 +1,14 @@ +#!/usr/bin/env python3 + +import rclpy +from rqt_diagnostic_graph_monitor.module import MonitorModule + +if __name__ == "__main__": + try: + rclpy.init() + node = rclpy.create_node("test_rqt_diagnostic_graph_monitor") + test = MonitorModule(node) + rclpy.spin(node) + rclpy.shutdown() + except KeyboardInterrupt: + print("KeyboardInterrupt") diff --git a/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor b/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor new file mode 100755 index 0000000000000..a5237a87e87d6 --- /dev/null +++ b/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor @@ -0,0 +1,8 @@ +#!/usr/bin/env python3 + +import sys + +import rqt_gui.main + +rqt_main = rqt_gui.main.Main() +sys.exit(rqt_main.main(sys.argv, standalone="rqt_diagnostic_graph_monitor.MonitorPlugin")) From 1da2091c034ca80cb0f1ec6fc462d5551a4b6c4d Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 22 Apr 2024 14:32:04 +0900 Subject: [PATCH 063/192] docs(tier4_logging_level_configure_rviz_plugin): update document (#6720) * docs(tier4_logging_level_configure_rviz_plugin): update document Signed-off-by: Zulfaqar Azmi * fix spell check Signed-off-by: Zulfaqar Azmi * fix Warning Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../README.md | 67 ++++++++++++++++++- 1 file changed, 65 insertions(+), 2 deletions(-) diff --git a/common/tier4_logging_level_configure_rviz_plugin/README.md b/common/tier4_logging_level_configure_rviz_plugin/README.md index 8df17a82e3de7..ed400e521e6aa 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/README.md +++ b/common/tier4_logging_level_configure_rviz_plugin/README.md @@ -1,9 +1,72 @@ # tier4_logging_level_configure_rviz_plugin -This package provides an rviz_plugin that can easily change the logger level of each node +This package provides an rviz_plugin that can easily change the logger level of each node. ![tier4_logging_level_configure_rviz_plugin](tier4_logging_level_configure_rviz_plugin.png) This plugin dispatches services to the "logger name" associated with "nodes" specified in YAML, adjusting the logger level. -As of November 2023, in ROS 2 Humble, users are required to initiate a service server in the node to use this feature. (This might be integrated into ROS standards in the future.) For easy service server generation, you can use the [LoggerLevelConfigure](https://github.com/autowarefoundation/autoware.universe/blob/main/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp) utility. +!!! Warning + + It is highly recommended to use this plugin when you're attempting to print any debug information. Furthermore, it is strongly advised to avoid using the logging level INFO, as it might flood the terminal with your information, potentially causing other useful information to be missed. + +!!! note + + To add your logger to the list, simply include the `node_name` and `logger_name` in the [logger_config.yaml](https://github.com/autowarefoundation/autoware.universe/blob/main/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml) under the corresponding component or module. If the relevant component or module is not listed, you may add them yourself. + +!!! note + + As of November 2023, in ROS 2 Humble, users are required to initiate a service server in the node to use this feature. (This might be integrated into ROS standards in the future.) For easy service server generation, you can use the [LoggerLevelConfigure](https://github.com/autowarefoundation/autoware.universe/blob/main/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp) utility. + +## How to use the plugin + +In RVIZ2, go to Panels and add LoggingLevelConfigureRVizPlugin. Then, search for the node you're interested in and select the corresponding logging level to print the logs. + +## How to add or find your logger name + +Because there are no available ROS 2 CLI commands to list loggers, there isn't a straightforward way to check your logger name. Additionally, the following assumes that you already know which node you're working with. + +### For logger as a class member variable + +If your class doesn't have an `rclcpp::Logger` member variable, you can start by including one yourself: + +```c++ +mutable rclcpp::Logger logger_; +``` + +If your node already has a logger, it should, under normal circumstances, be similar to the node's name. + +For instance, if the node name is `/some_component/some_node/node_child`, the `logger_name` would be `some_component.some_node.node_child`. + +Should your log not print as expected, one approach is to initially set your logging level in the code to info, like so: + +```c++ +RCLCPP_INFO(logger_, "Print something here."); +``` + +This will result in something like the following being printed in the terminal: + +```shell +[component_container_mt-36] [INFO 1711949149.735437551] [logger_name]: Print something here. (func() at /path/to/code:line_number) +``` + +Afterward, you can simply copy the `logger_name`. + +!!! warning + + Remember to revert your code to the appropriate logging level after testing. + ```c++ + RCLCPP_DEBUG(logger_, "Print something here."); + ``` + +### For libraries + +When dealing with libraries, such as utility functions, you may need to add the logger manually. Here's an example: + +```c++ +RCLCPP_WARN( + rclcpp::get_logger("some_component").get_child("some_child").get_child("some_child2"), + "Print something here."); +``` + +In this scenario, the `logger_name` would be `some_component.some_child.some_child2`. From 75885a5f8a46e58308d4ed0ec8ec35c7be7cf6ff Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 22 Apr 2024 15:15:28 +0900 Subject: [PATCH 064/192] refactor(lane_change): refactor min and max lane change length (#6845) Signed-off-by: Muhammad Zulfaqar Azmi --- .../src/scene.cpp | 6 +- .../utils/utils.hpp | 9 +- .../src/scene.cpp | 61 +++++------- .../src/utils/utils.cpp | 95 +++++++++++-------- 4 files changed, 89 insertions(+), 82 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 63965bc15986f..6a41eccc22ba3 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -273,12 +273,8 @@ double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const return std::numeric_limits::infinity(); } - // get minimum lane change distance - const auto shift_intervals = - getRouteHandler()->getLateralIntervalsToPreferredLane(current_lanes.back(), direction_); return utils::lane_change::calcMinimumLaneChangeLength( - *lane_change_parameters_, shift_intervals, - lane_change_parameters_->backward_length_buffer_for_end_of_lane); + getRouteHandler(), current_lanes.back(), *lane_change_parameters_, direction_); } double AvoidanceByLaneChange::calcLateralOffset() const diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 76331bd98eb9c..cd4f55599d964 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -58,8 +58,11 @@ double calcLaneChangeResampleInterval( const double lane_changing_length, const double lane_changing_velocity); double calcMinimumLaneChangeLength( - const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, - const double length_to_intersection = 0.0); + const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals); + +double calcMinimumLaneChangeLength( + const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lane, + const LaneChangeParameters & lane_change_parameters, Direction direction); double calcMaximumLaneChangeLength( const double current_velocity, const LaneChangeParameters & lane_change_parameters, @@ -139,7 +142,7 @@ std::vector generateDrivableLanes( double getLateralShift(const LaneChangePath & path); bool hasEnoughLengthToLaneChangeAfterAbort( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, + const std::shared_ptr & route_handler, const lanelet::ConstLanelets & current_lanes, const Pose & curent_pose, const double abort_return_dist, const LaneChangeParameters & lane_change_parameters, const Direction direction); diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 97bb30ac8174d..1e84fd41b3215 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -38,6 +38,7 @@ namespace behavior_path_planner { using motion_utils::calcSignedArcLength; +using utils::lane_change::calcMinimumLaneChangeLength; using utils::traffic_light::getDistanceToNextTrafficLight; NormalLaneChange::NormalLaneChange( @@ -257,8 +258,8 @@ void NormalLaneChange::insertStopPoint( } const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lanelets.back()); - const double lane_change_buffer = - utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0); + const auto lane_change_buffer = + calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); const auto getDistanceAlongLanelet = [&](const geometry_msgs::msg::Pose & target) { return utils::getSignedDistance(path.points.front().point.pose, target, lanelets); @@ -545,10 +546,8 @@ bool NormalLaneChange::isNearEndOfCurrentLanes( const auto & route_handler = getRouteHandler(); const auto & current_pose = getEgoPose(); - const auto shift_intervals = - route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const auto lane_change_buffer = - utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); + const auto lane_change_buffer = calcMinimumLaneChangeLength( + route_handler, current_lanes.back(), *lane_change_parameters_, Direction::NONE); const auto distance_to_lane_change_end = std::invoke([&]() { auto distance_to_end = utils::getDistanceToEndOfLane(current_pose, current_lanes); @@ -905,12 +904,10 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( const lanelet::ConstLanelets & target_backward_lanes) const { const auto current_pose = getEgoPose(); - const auto & route_handler = *getRouteHandler(); + const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; - const auto shift_intervals = - route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction_); - const double minimum_lane_change_length = - utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); + const auto minimum_lane_change_length = calcMinimumLaneChangeLength( + route_handler, current_lanes.back(), *lane_change_parameters_, direction_); // Guard if (objects.objects.empty()) { @@ -919,9 +916,9 @@ LaneChangeTargetObjectIndices NormalLaneChange::filterObject( // Get path const auto path = - route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); const auto target_path = - route_handler.getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + route_handler->getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); const auto current_polygon = utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); @@ -1108,32 +1105,30 @@ bool NormalLaneChange::hasEnoughLength( const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, const Direction direction) const { + if (target_lanes.empty()) { + return false; + } + const auto current_pose = getEgoPose(); - const auto & route_handler = *getRouteHandler(); - const auto overall_graphs_ptr = route_handler.getOverallGraphPtr(); - const double lane_change_length = path.info.length.sum(); - const auto shift_intervals = - route_handler.getLateralIntervalsToPreferredLane(target_lanes.back(), direction); - double minimum_lane_change_length_to_preferred_lane = - utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); + const auto & route_handler = getRouteHandler(); + const auto overall_graphs_ptr = route_handler->getOverallGraphPtr(); + const auto minimum_lane_change_length_to_preferred_lane = calcMinimumLaneChangeLength( + route_handler, target_lanes.back(), *lane_change_parameters_, direction); + const double lane_change_length = path.info.length.sum(); if (lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; } - const auto goal_pose = route_handler.getGoalPose(); + const auto goal_pose = route_handler->getGoalPose(); if ( - route_handler.isInGoalRouteSection(current_lanes.back()) && + route_handler->isInGoalRouteSection(current_lanes.back()) && lane_change_length + minimum_lane_change_length_to_preferred_lane > utils::getSignedDistance(current_pose, goal_pose, current_lanes)) { return false; } // return if there are no target lanes - if (target_lanes.empty()) { - return true; - } - if ( lane_change_length + minimum_lane_change_length_to_preferred_lane > utils::getDistanceToEndOfLane(current_pose, target_lanes)) { @@ -1770,10 +1765,8 @@ bool NormalLaneChange::calcAbortPath() const auto ego_nearest_yaw_threshold = common_param.ego_nearest_yaw_threshold; const auto direction = getDirection(); - const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane( - selected_path.info.current_lanes.back(), direction); - const double minimum_lane_change_length = - utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals); + const auto minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( + route_handler, selected_path.info.current_lanes.back(), *lane_change_parameters_, direction); const auto & lane_changing_path = selected_path.path; const auto lane_changing_end_pose_idx = std::invoke([&]() { @@ -1820,7 +1813,7 @@ bool NormalLaneChange::calcAbortPath() } if (!utils::lane_change::hasEnoughLengthToLaneChangeAfterAbort( - *route_handler, reference_lanelets, current_pose, abort_return_dist, + route_handler, reference_lanelets, current_pose, abort_return_dist, *lane_change_parameters_, direction)) { RCLCPP_ERROR(logger_, "insufficient distance to abort."); return false; @@ -2027,10 +2020,8 @@ bool NormalLaneChange::isVehicleStuck( route_handler->isInGoalRouteSection(current_lanes.back()) ? utils::getSignedDistance(getEgoPose(), route_handler->getGoalPose(), current_lanes) : utils::getDistanceToEndOfLane(getEgoPose(), current_lanes); - const auto shift_intervals = - route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double lane_change_buffer = - utils::lane_change::calcMinimumLaneChangeLength(*lane_change_parameters_, shift_intervals, 0.0); + const auto lane_change_buffer = calcMinimumLaneChangeLength( + route_handler, current_lanes.back(), *lane_change_parameters_, Direction::NONE); const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; const double terminal_judge_buffer = lane_change_buffer + stop_point_buffer + 1.0; if (distance_to_terminal < terminal_judge_buffer) { diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 97fcc841a546e..97a5ae732ec1b 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -49,6 +49,8 @@ #include #include #include +#include +#include #include #include #include @@ -77,29 +79,40 @@ double calcLaneChangeResampleInterval( } double calcMinimumLaneChangeLength( - const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals, - const double length_to_intersection) + const LaneChangeParameters & lane_change_parameters, const std::vector & shift_intervals) { if (shift_intervals.empty()) { return 0.0; } - const double & vel = lane_change_parameters.minimum_lane_changing_velocity; - const auto lat_acc = lane_change_parameters.lane_change_lat_acc_map.find(vel); - const double & max_lateral_acc = lat_acc.second; - const double & lateral_jerk = lane_change_parameters.lane_changing_lateral_jerk; - const double & finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; - const double & backward_buffer = lane_change_parameters.backward_length_buffer_for_end_of_lane; - - double accumulated_length = length_to_intersection; - for (const auto & shift_interval : shift_intervals) { - const double t = - PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, max_lateral_acc); - accumulated_length += vel * t + finish_judge_buffer; + const auto min_vel = lane_change_parameters.minimum_lane_changing_velocity; + const auto [min_lat_acc, max_lat_acc] = + lane_change_parameters.lane_change_lat_acc_map.find(min_vel); + const auto lat_jerk = lane_change_parameters.lane_changing_lateral_jerk; + const auto finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; + + const auto calc_sum = [&](double sum, double shift_interval) { + const auto t = PathShifter::calcShiftTimeFromJerk(shift_interval, lat_jerk, max_lat_acc); + return sum + (min_vel * t + finish_judge_buffer); + }; + + const auto total_length = + std::accumulate(shift_intervals.begin(), shift_intervals.end(), 0.0, calc_sum); + + const auto backward_buffer = lane_change_parameters.backward_length_buffer_for_end_of_lane; + return total_length + backward_buffer * (static_cast(shift_intervals.size()) - 1.0); +} + +double calcMinimumLaneChangeLength( + const std::shared_ptr & route_handler, const lanelet::ConstLanelet & lane, + const LaneChangeParameters & lane_change_parameters, Direction direction) +{ + if (!route_handler) { + return std::numeric_limits::max(); } - accumulated_length += backward_buffer * (shift_intervals.size() - 1.0); - return accumulated_length; + const auto shift_intervals = route_handler->getLateralIntervalsToPreferredLane(lane, direction); + return utils::lane_change::calcMinimumLaneChangeLength(lane_change_parameters, shift_intervals); } double calcMaximumLaneChangeLength( @@ -110,31 +123,34 @@ double calcMaximumLaneChangeLength( return 0.0; } - const double & finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; - const double & lateral_jerk = lane_change_parameters.lane_changing_lateral_jerk; - const double & t_prepare = lane_change_parameters.lane_change_prepare_duration; + const auto finish_judge_buffer = lane_change_parameters.lane_change_finish_judge_buffer; + const auto lat_jerk = lane_change_parameters.lane_changing_lateral_jerk; + const auto t_prepare = lane_change_parameters.lane_change_prepare_duration; - double vel = current_velocity; - double accumulated_length = 0.0; - for (const auto & shift_interval : shift_intervals) { + auto vel = current_velocity; + + const auto calc_sum = [&](double sum, double shift_interval) { // prepare section - const double prepare_length = vel * t_prepare + 0.5 * max_acc * t_prepare * t_prepare; + const auto prepare_length = vel * t_prepare + 0.5 * max_acc * t_prepare * t_prepare; vel = vel + max_acc * t_prepare; // lane changing section - const auto lat_acc = lane_change_parameters.lane_change_lat_acc_map.find(vel); - const double t_lane_changing = - PathShifter::calcShiftTimeFromJerk(shift_interval, lateral_jerk, lat_acc.second); - const double lane_changing_length = + const auto [min_lat_acc, max_lat_acc] = + lane_change_parameters.lane_change_lat_acc_map.find(vel); + const auto t_lane_changing = + PathShifter::calcShiftTimeFromJerk(shift_interval, lat_jerk, max_lat_acc); + const auto lane_changing_length = vel * t_lane_changing + 0.5 * max_acc * t_lane_changing * t_lane_changing; - accumulated_length += prepare_length + lane_changing_length + finish_judge_buffer; vel = vel + max_acc * t_lane_changing; - } - accumulated_length += - lane_change_parameters.backward_length_buffer_for_end_of_lane * (shift_intervals.size() - 1.0); + return sum + (prepare_length + lane_changing_length + finish_judge_buffer); + }; + + const auto total_length = + std::accumulate(shift_intervals.begin(), shift_intervals.end(), 0.0, calc_sum); - return accumulated_length; + const auto backward_buffer = lane_change_parameters.backward_length_buffer_for_end_of_lane; + return total_length + backward_buffer * (static_cast(shift_intervals.size()) - 1.0); } double calcMinimumAcceleration( @@ -658,23 +674,24 @@ double getLateralShift(const LaneChangePath & path) } bool hasEnoughLengthToLaneChangeAfterAbort( - const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes, + const std::shared_ptr & route_handler, const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, const double abort_return_dist, const LaneChangeParameters & lane_change_parameters, const Direction direction) { - const auto shift_intervals = - route_handler.getLateralIntervalsToPreferredLane(current_lanes.back(), direction); - const double minimum_lane_change_length = - calcMinimumLaneChangeLength(lane_change_parameters, shift_intervals); + if (current_lanes.empty()) { + return false; + } + + const auto minimum_lane_change_length = calcMinimumLaneChangeLength( + route_handler, current_lanes.back(), lane_change_parameters, direction); const auto abort_plus_lane_change_length = abort_return_dist + minimum_lane_change_length; if (abort_plus_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) { return false; } if ( - route_handler.isInGoalRouteSection(current_lanes.back()) && abort_plus_lane_change_length > - utils::getSignedDistance(current_pose, route_handler.getGoalPose(), current_lanes)) { + utils::getSignedDistance(current_pose, route_handler->getGoalPose(), current_lanes)) { return false; } From c09bc59b3d08def5b35dc6e0beed8f45155a0055 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 22 Apr 2024 17:51:15 +0900 Subject: [PATCH 065/192] refactor(bpp, avoidance): remove unnecessary verbose flag (#6822) * refactor(avoidance): logger small change Signed-off-by: satoshi-ota * refactor(bpp): remove verbose flag Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../config/logger_config.yaml | 2 ++ .../config/avoidance.param.yaml | 1 - .../data_structs.hpp | 1 - .../parameter_helper.hpp | 1 - .../behavior_path_avoidance_module/utils.hpp | 3 +++ .../schema/avoidance.schema.json | 7 +----- .../src/manager.cpp | 1 - .../src/scene.cpp | 23 +++++++++---------- .../src/utils.cpp | 19 ++++++++------- .../config/behavior_path_planner.param.yaml | 1 - .../behavior_path_planner/planner_manager.hpp | 4 +--- .../src/behavior_path_planner_node.cpp | 3 +-- .../src/planner_manager.cpp | 12 +++------- .../parameters.hpp | 1 - 14 files changed, 33 insertions(+), 46 deletions(-) diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index a298967a31af9..f54d991a9d852 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -37,6 +37,8 @@ Planning: behavior_path_planner_avoidance: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils behavior_path_planner_goal_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml index 5d6044df64b2f..c85fdd5a2351a 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/behavior_path_avoidance_module/config/avoidance.param.yaml @@ -290,4 +290,3 @@ # for debug debug: marker: false - console: false diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp index e74b546f31fc4..8516cc61f860b 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp @@ -322,7 +322,6 @@ struct AvoidanceParameters // debug bool publish_debug_marker = false; - bool print_debug_info = false; }; struct ObjectData // avoidance target diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp index 6dbf52c0425fb..e115e676b1dbf 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp @@ -379,7 +379,6 @@ AvoidanceParameters getParameter(rclcpp::Node * node) { const std::string ns = "avoidance.debug."; p.publish_debug_marker = getOrDeclareParameter(*node, ns + "marker"); - p.print_debug_info = getOrDeclareParameter(*node, ns + "console"); } return p; diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp index 3f1d3495e51cb..92e9da61c4ada 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp @@ -31,6 +31,9 @@ using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPoly using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; +static constexpr const char * logger_namespace = + "planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance.utils"; + bool isOnRight(const ObjectData & obj); double calcShiftLength( diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json index 79882beb805f8..eee34edbc0e0c 100644 --- a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json +++ b/planning/behavior_path_avoidance_module/schema/avoidance.schema.json @@ -1379,14 +1379,9 @@ "type": "boolean", "description": "Publish debug marker.", "default": "false" - }, - "console": { - "type": "boolean", - "description": "Output debug info on console.", - "default": "false" } }, - "required": ["marker", "console"], + "required": ["marker"], "additionalProperties": false } }, diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/behavior_path_avoidance_module/src/manager.cpp index e3391f251e55f..dbff6f60365f3 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_avoidance_module/src/manager.cpp @@ -257,7 +257,6 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "marker", p->publish_debug_marker); - updateParam(parameters, ns + "console", p->print_debug_info); } std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/behavior_path_avoidance_module/src/scene.cpp index b16395f825385..1d46e4e1f9d5d 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_avoidance_module/src/scene.cpp @@ -40,12 +40,6 @@ #include #include -// set as macro so that calling function name will be printed. -// debug print is heavy. turn on only when debugging. -#define DEBUG_PRINT(...) \ - RCLCPP_DEBUG_EXPRESSION(getLogger(), parameters_->print_debug_info, __VA_ARGS__) -#define printShiftLines(p, msg) DEBUG_PRINT("[%s] %s", msg, toStrInfo(p).c_str()) - namespace behavior_path_planner { @@ -109,7 +103,7 @@ AvoidanceModule::AvoidanceModule( bool AvoidanceModule::isExecutionRequested() const { - DEBUG_PRINT("AVOIDANCE isExecutionRequested"); + RCLCPP_DEBUG(getLogger(), "AVOIDANCE isExecutionRequested"); // Check ego is in preferred lane updateInfoMarker(avoid_data_); @@ -132,7 +126,11 @@ bool AvoidanceModule::isExecutionRequested() const bool AvoidanceModule::isExecutionReady() const { - DEBUG_PRINT("AVOIDANCE isExecutionReady"); + RCLCPP_DEBUG_STREAM(getLogger(), "---Avoidance GO/NO-GO status---"); + RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "SAFE:" << avoid_data_.safe); + RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "COMFORTABLE:" << avoid_data_.comfortable); + RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "VALID:" << avoid_data_.valid); + RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "READY:" << avoid_data_.ready); return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid && avoid_data_.ready; } @@ -1139,7 +1137,7 @@ void AvoidanceModule::addNewShiftLines( const auto new_shift_length = front_new_shift_line.end_shift_length; const auto new_shift_end_idx = front_new_shift_line.end_idx; - DEBUG_PRINT("min_start_idx = %lu", min_start_idx); + RCLCPP_DEBUG(getLogger(), "min_start_idx = %lu", min_start_idx); // Remove shift points that starts later than the new_shift_line from path_shifter. // @@ -1152,8 +1150,9 @@ void AvoidanceModule::addNewShiftLines( // farther avoidance. for (const auto & sl : current_shift_lines) { if (sl.start_idx >= min_start_idx) { - DEBUG_PRINT( - "sl.start_idx = %lu, this sl starts after new proposal. remove this one.", sl.start_idx); + RCLCPP_DEBUG( + getLogger(), "sl.start_idx = %lu, this sl starts after new proposal. remove this one.", + sl.start_idx); continue; } @@ -1171,7 +1170,7 @@ void AvoidanceModule::addNewShiftLines( } } - DEBUG_PRINT("sl.start_idx = %lu, no conflict. keep this one.", sl.start_idx); + RCLCPP_DEBUG(getLogger(), "sl.start_idx = %lu, no conflict. keep this one.", sl.start_idx); future.push_back(sl); } diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index bef3976be7e1e..33718ae16a038 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -563,13 +563,15 @@ bool isNeverAvoidanceTarget( if (object.is_within_intersection) { if (object.behavior == ObjectData::Behavior::NONE) { object.reason = "ParallelToEgoLane"; - RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it."); + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it."); return true; } if (object.behavior == ObjectData::Behavior::MERGING) { object.reason = "MergingToEgoLane"; - RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object belongs to ego lane. never avoid it."); + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it."); return true; } } @@ -581,7 +583,8 @@ bool isNeverAvoidanceTarget( planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false); if (right_lane.has_value() && left_lane.has_value()) { object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; - RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it."); + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); return true; } } @@ -589,7 +592,8 @@ bool isNeverAvoidanceTarget( if (isCloseToStopFactor(object, data, planner_data, parameters)) { if (object.is_on_ego_lane && !object.is_parked) { object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; - RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is close to stop factor. never avoid it."); + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object is close to stop factor. never avoid it."); return true; } } @@ -604,12 +608,12 @@ bool isObviousAvoidanceTarget( { if (!object.is_within_intersection) { if (object.is_parked && object.behavior == ObjectData::Behavior::NONE) { - RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is obvious parked vehicle."); + RCLCPP_DEBUG(rclcpp::get_logger(logger_namespace), "object is obvious parked vehicle."); return true; } if (!object.is_on_ego_lane && object.behavior == ObjectData::Behavior::NONE) { - RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object is adjacent vehicle."); + RCLCPP_DEBUG(rclcpp::get_logger(logger_namespace), "object is adjacent vehicle."); return true; } } @@ -2187,8 +2191,7 @@ DrivableLanes generateExpandedDrivableLanes( } if (i == max_recursive_search_num - 1) { RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("avoidance"), - "Drivable area expansion reaches max iteration."); + rclcpp::get_logger(logger_namespace), "Drivable area expansion reaches max iteration."); } } }; diff --git a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml index f3f6870085e02..2c181489ba4c2 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -1,6 +1,5 @@ /**: ros__parameters: - verbose: false max_iteration_num: 100 traffic_light_signal_timeout: 1.0 planning_hz: 10.0 diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 9054435a33912..51a4cddabb941 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -96,7 +96,7 @@ struct SceneModuleStatus class PlannerManager { public: - PlannerManager(rclcpp::Node & node, const size_t max_iteration_num, const bool verbose); + PlannerManager(rclcpp::Node & node, const size_t max_iteration_num); /** * @brief run all candidate and approved modules. @@ -471,8 +471,6 @@ class PlannerManager mutable std::shared_ptr debug_msg_ptr_; size_t max_iteration_num_{100}; - - bool verbose_{false}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index bc1140d627206..b56d1a207f76d 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -133,7 +133,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod const std::lock_guard lock(mutex_manager_); // for planner_manager_ const auto & p = planner_data_->parameters; - planner_manager_ = std::make_shared(*this, p.max_iteration_num, p.verbose); + planner_manager_ = std::make_shared(*this, p.max_iteration_num); for (const auto & name : declare_parameter>("launch_modules")) { // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter. @@ -208,7 +208,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() { BehaviorPathPlannerParameters p{}; - p.verbose = declare_parameter("verbose"); p.max_iteration_num = declare_parameter("max_iteration_num"); p.traffic_light_signal_timeout = declare_parameter("traffic_light_signal_timeout"); diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 6ac67605839e1..418a70cb269d6 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -30,13 +30,11 @@ namespace behavior_path_planner { -PlannerManager::PlannerManager( - rclcpp::Node & node, const size_t max_iteration_num, const bool verbose) +PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num) : plugin_loader_("behavior_path_planner", "behavior_path_planner::SceneModuleManagerInterface"), logger_(node.get_logger().get_child("planner_manager")), clock_(*node.get_clock()), - max_iteration_num_{max_iteration_num}, - verbose_{verbose} + max_iteration_num_{max_iteration_num} { processing_time_.emplace("total_time", 0.0); debug_publisher_ptr_ = std::make_unique(&node, "~/debug"); @@ -946,11 +944,7 @@ void PlannerManager::print() const state_publisher_ptr_->publish("internal_state", string_stream.str()); - if (!verbose_) { - return; - } - - RCLCPP_INFO_STREAM(logger_, string_stream.str()); + RCLCPP_DEBUG_STREAM(logger_, string_stream.str()); } void PlannerManager::publishProcessingTime() const diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp index 1eae4a1c4c345..1241f98daa747 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp @@ -30,7 +30,6 @@ struct ModuleConfigParameters struct BehaviorPathPlannerParameters { - bool verbose; size_t max_iteration_num{100}; double traffic_light_signal_timeout{1.0}; From 00db87d97792f70efee906a7db4b38752b0303fd Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Mon, 22 Apr 2024 21:40:42 +0900 Subject: [PATCH 066/192] feat(perception_online_evaluator): add use_perception_online_evaluator option and disable it by default (#6861) Signed-off-by: kosuke55 --- launch/tier4_perception_launch/launch/perception.launch.xml | 3 ++- launch/tier4_simulator_launch/launch/simulator.launch.xml | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index d9e18e76bc4c4..822376b365fa8 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -85,6 +85,7 @@ + @@ -249,7 +250,7 @@ - + diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index 76fb66e4ebfdf..2ffd2a701fb65 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -21,6 +21,7 @@ + @@ -89,7 +90,7 @@ - + From 5a25d8449a91a85ac940fae9e81bd92f7578444a Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Tue, 23 Apr 2024 00:14:49 +0900 Subject: [PATCH 067/192] feat(pointcloud_preprocessor): add pickup based voxel grid filter (#6138) * add pickup based voxel grid filter Signed-off-by: Yukihito Saito * style(pre-commit): autofix * add comment Signed-off-by: Yukihito Saito * add readme Signed-off-by: Yukihito Saito * add comment Signed-off-by: Yukihito Saito * Update sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> * Update sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp * style(pre-commit): autofix * tuning for processing time Signed-off-by: Yukihito Saito * change to robin_hood Signed-off-by: Yukihito Saito * style(pre-commit): autofix * fix: ignore cpplint for external file Signed-off-by: Ryohsuke Mitsudome * fix cspell Signed-off-by: Yukihito Saito * style(pre-commit): autofix * fix cspell error Signed-off-by: Yukihito Saito --------- Signed-off-by: Yukihito Saito Signed-off-by: Ryohsuke Mitsudome Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome --- .../pointcloud_preprocessor/CMakeLists.txt | 7 +- .../docs/downsample-filter.md | 16 + ...kup_based_voxel_grid_downsample_filter.hpp | 64 + ...kup_based_voxel_grid_downsample_filter.cpp | 193 ++ .../src/downsample_filter/robin_hood.h | 2748 +++++++++++++++++ 5 files changed, 3027 insertions(+), 1 deletion(-) create mode 100644 sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp create mode 100644 sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp create mode 100644 sensing/pointcloud_preprocessor/src/downsample_filter/robin_hood.h diff --git a/sensing/pointcloud_preprocessor/CMakeLists.txt b/sensing/pointcloud_preprocessor/CMakeLists.txt index 219f43e48730a..0cbb04345477e 100644 --- a/sensing/pointcloud_preprocessor/CMakeLists.txt +++ b/sensing/pointcloud_preprocessor/CMakeLists.txt @@ -65,6 +65,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp src/downsample_filter/random_downsample_filter_nodelet.cpp src/downsample_filter/approximate_downsample_filter_nodelet.cpp + src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp src/outlier_filter/ring_outlier_filter_nodelet.cpp src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp @@ -114,6 +115,11 @@ rclcpp_components_register_node(pointcloud_preprocessor_filter PLUGIN "pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" EXECUTABLE voxel_grid_downsample_filter_node) +# -- Pickup Based Voxel Grid Downsample Filter -- +rclcpp_components_register_node(pointcloud_preprocessor_filter + PLUGIN "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent" + EXECUTABLE pickup_based_voxel_grid_downsample_filter_node) + # -- Random Downsample Filter -- rclcpp_components_register_node(pointcloud_preprocessor_filter PLUGIN "pointcloud_preprocessor::RandomDownsampleFilterComponent" @@ -214,7 +220,6 @@ ament_auto_package(INSTALL_TO_SHARE config ) - if(BUILD_TESTING) add_ros_test( test/test_distortion_corrector.py diff --git a/sensing/pointcloud_preprocessor/docs/downsample-filter.md b/sensing/pointcloud_preprocessor/docs/downsample-filter.md index 181cebb496cbf..25faf62b765bc 100644 --- a/sensing/pointcloud_preprocessor/docs/downsample-filter.md +++ b/sensing/pointcloud_preprocessor/docs/downsample-filter.md @@ -18,6 +18,10 @@ The `downsample_filter` is a node that reduces the number of points. `pcl::VoxelGrid` is used, which points in each voxel are approximated with their centroid. +### Pickup Based Voxel Grid Downsample Filter + +This algorithm samples a single actual point existing within the voxel, not the centroid. The computation cost is low compared to Centroid Based Voxel Grid Filter. + ## Inputs / Outputs These implementations inherit `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). @@ -52,8 +56,20 @@ These implementations inherit `pointcloud_preprocessor::Filter` class, please re | `voxel_size_y` | double | 0.3 | voxel size y [m] | | `voxel_size_z` | double | 0.1 | voxel size z [m] | +### Pickup Based Voxel Grid Downsample Filter + +| Name | Type | Default Value | Description | +| -------------- | ------ | ------------- | ---------------- | +| `voxel_size_x` | double | 1.0 | voxel size x [m] | +| `voxel_size_y` | double | 1.0 | voxel size y [m] | +| `voxel_size_z` | double | 1.0 | voxel size z [m] | + ## Assumptions / Known limits + + +This implementation uses the `robin_hood.h` hashing library by martinus, available under the MIT License at [martinus/robin-hood-hashing](https://github.com/martinus/robin-hood-hashing) on GitHub. Special thanks to martinus for this contribution. + ## (Optional) Error detection and handling ## (Optional) Performance characterization diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp new file mode 100644 index 0000000000000..a923473ecbe36 --- /dev/null +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp @@ -0,0 +1,64 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ +#define POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ + +#include "pointcloud_preprocessor/filter.hpp" + +#include + +#include +#include + +#include +#include +#include + +namespace pointcloud_preprocessor +{ +/** + * @class PickupBasedVoxelGridDownsampleFilterComponent + * @brief A filter component for downsampling point clouds using a voxel grid approach. + * + * This component reduces the number of points in a point cloud by grouping them into voxels + * and picking a representative point for each voxel. It's useful for reducing computational + * load when processing large point clouds. + */ +class PickupBasedVoxelGridDownsampleFilterComponent : public pointcloud_preprocessor::Filter +{ +protected: + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; + +private: + float voxel_size_x_; ///< The size of the voxel in the x dimension. + float voxel_size_y_; ///< The size of the voxel in the y dimension. + float voxel_size_z_; ///< The size of the voxel in the z dimension. + + /** \brief Parameter service callback result : needed to be hold */ + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + + /** \brief Parameter service callback */ + rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector & p); + +public: + PCL_MAKE_ALIGNED_OPERATOR_NEW + explicit PickupBasedVoxelGridDownsampleFilterComponent(const rclcpp::NodeOptions & options); +}; +} // namespace pointcloud_preprocessor + +// clang-format off +#endif // POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__PICKUP_BASED_VOXEL_GRID_DOWNSAMPLE_FILTER_HPP_ // NOLINT +// clang-format on diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp new file mode 100644 index 0000000000000..6393a935562ac --- /dev/null +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp @@ -0,0 +1,193 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "pointcloud_preprocessor/downsample_filter/pickup_based_voxel_grid_downsample_filter.hpp" + +#include "robin_hood.h" + +namespace +{ +/** + * @brief Hash function for voxel keys. + * Utilizes prime numbers to calculate a unique hash for each voxel key. + */ +struct VoxelKeyHash +{ + std::size_t operator()(const std::array & k) const + { + // Primes based on the following paper: 'Investigating the Use of Primes in Hashing for + // Volumetric Data'. + return (k[0] * 73856093 ^ k[1] * 19349663 ^ k[2] * 83492791); + // In general, the performance of the search may be improved by restricting the hashkey to the + // following However, the risk of key collisions also increases, so the value must be + // appropriate. Enable the following code depending on the situation. return ((1 << 16) - 1) & + // (k[0] * 73856093 ^ k[1] * 19349663 ^ k[2] * 83492791); + } +}; + +/** + * @brief Equality function for voxel keys. + * Checks if two voxel keys are equal. + */ +struct VoxelKeyEqual +{ + bool operator()(const std::array & a, const std::array & b) const + { + return a == b; + } +}; +} // namespace + +namespace pointcloud_preprocessor +{ +PickupBasedVoxelGridDownsampleFilterComponent::PickupBasedVoxelGridDownsampleFilterComponent( + const rclcpp::NodeOptions & options) +: Filter("PickupBasedVoxelGridDownsampleFilterComponent", options) +{ + // initialize debug tool + { + using tier4_autoware_utils::DebugPublisher; + using tier4_autoware_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ = std::make_unique(this, this->get_name()); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + } + + // Initialization of voxel sizes from parameters + voxel_size_x_ = static_cast(declare_parameter("voxel_size_x", 1.0)); + voxel_size_y_ = static_cast(declare_parameter("voxel_size_y", 1.0)); + voxel_size_z_ = static_cast(declare_parameter("voxel_size_z", 1.0)); + + using std::placeholders::_1; + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&PickupBasedVoxelGridDownsampleFilterComponent::paramCallback, this, _1)); +} + +void PickupBasedVoxelGridDownsampleFilterComponent::filter( + const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices, + PointCloud2 & output) +{ + std::scoped_lock lock(mutex_); + + stop_watch_ptr_->toc("processing_time", true); + + using VoxelKey = std::array; + // std::unordered_map voxel_map; + robin_hood::unordered_map voxel_map; + + voxel_map.reserve(input->data.size() / input->point_step); + + constexpr float large_num_offset = 100000.0; + const float inverse_voxel_size_x = 1.0 / voxel_size_x_; + const float inverse_voxel_size_y = 1.0 / voxel_size_y_; + const float inverse_voxel_size_z = 1.0 / voxel_size_z_; + + const int x_offset = input->fields[pcl::getFieldIndex(*input, "x")].offset; + const int y_offset = input->fields[pcl::getFieldIndex(*input, "y")].offset; + const int z_offset = input->fields[pcl::getFieldIndex(*input, "z")].offset; + + // Process each point in the point cloud + for (size_t global_offset = 0; global_offset + input->point_step <= input->data.size(); + global_offset += input->point_step) { + const float & x = *reinterpret_cast(&input->data[global_offset + x_offset]); + const float & y = *reinterpret_cast(&input->data[global_offset + y_offset]); + const float & z = *reinterpret_cast(&input->data[global_offset + z_offset]); + + // The reason for adding a large value is that when converting from float to int, values around + // -1 to 1 are all rounded down to 0. Therefore, to prevent the numbers from becoming negative, + // a large value is added. It has been tuned to reduce computational costs, and deliberately + // avoids using round or floor functions. + VoxelKey key = { + static_cast((x + large_num_offset) * inverse_voxel_size_x), + static_cast((y + large_num_offset) * inverse_voxel_size_y), + static_cast((z + large_num_offset) * inverse_voxel_size_z)}; + + voxel_map.emplace(key, global_offset); + } + + // Populate the output point cloud + size_t output_global_offset = 0; + output.data.resize(voxel_map.size() * input->point_step); + for (const auto & kv : voxel_map) { + std::memcpy( + &output.data[output_global_offset + x_offset], &input->data[kv.second + x_offset], + sizeof(float)); + std::memcpy( + &output.data[output_global_offset + y_offset], &input->data[kv.second + y_offset], + sizeof(float)); + std::memcpy( + &output.data[output_global_offset + z_offset], &input->data[kv.second + z_offset], + sizeof(float)); + output_global_offset += input->point_step; + } + + // Set the output point cloud metadata + output.header.frame_id = input->header.frame_id; + output.height = 1; + output.fields = input->fields; + output.is_bigendian = input->is_bigendian; + output.point_step = input->point_step; + output.is_dense = input->is_dense; + output.width = static_cast(output.data.size() / output.height / output.point_step); + output.row_step = static_cast(output.data.size() / output.height); + + // add processing time for debug + if (debug_publisher_) { + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); + debug_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + + auto pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds((this->get_clock()->now() - input->header.stamp).nanoseconds())) + .count(); + + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); + } +} + +rcl_interfaces::msg::SetParametersResult +PickupBasedVoxelGridDownsampleFilterComponent::paramCallback( + const std::vector & p) +{ + std::scoped_lock lock(mutex_); + + // Handling dynamic updates for the voxel sizes + if (get_param(p, "voxel_size_x", voxel_size_x_)) { + RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", voxel_size_x_); + } + if (get_param(p, "voxel_size_y", voxel_size_y_)) { + RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", voxel_size_y_); + } + if (get_param(p, "voxel_size_z", voxel_size_z_)) { + RCLCPP_DEBUG(get_logger(), "Setting new distance threshold to: %f.", voxel_size_z_); + } + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + + return result; +} + +} // namespace pointcloud_preprocessor + +#include +RCLCPP_COMPONENTS_REGISTER_NODE( + pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent) diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/robin_hood.h b/sensing/pointcloud_preprocessor/src/downsample_filter/robin_hood.h new file mode 100644 index 0000000000000..02fa183e5d017 --- /dev/null +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/robin_hood.h @@ -0,0 +1,2748 @@ +// Copyright (c) 2018-2021 Martin Ankerl +// ______ _____ ______ _________ +// ______________ ___ /_ ___(_)_______ ___ /_ ______ ______ ______ / +// __ ___/_ __ \__ __ \__ / __ __ \ __ __ \_ __ \_ __ \_ __ / +// _ / / /_/ /_ /_/ /_ / _ / / / _ / / // /_/ // /_/ // /_/ / +// /_/ \____/ /_.___/ /_/ /_/ /_/ ________/_/ /_/ \____/ \____/ \__,_/ +// _/_____/ +// +// Fast & memory efficient hashtable based on robin hood hashing for C++11/14/17/20 +// https://github.com/martinus/robin-hood-hashing +// +// Licensed under the MIT License . +// SPDX-License-Identifier: MIT +// Copyright (c) 2018-2021 Martin Ankerl +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in all +// copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. + +// clang-format off +// (because it messes up the whole file and this is a external file) + +// cspell: ignore _CPPUNWIND +// cspell: ignore BITSCANFORWARD +// cspell: ignore clzl +// cspell: ignore ctzll +// cspell: ignore clzll +// cspell: ignore WCHART +// cspell: ignore Inds +// cspell: ignore inlinings +// cspell: ignore murmurhash +// cspell: ignore Wuseless +// cspell: ignore martinus +// cspell: ignore keyval +// cspell: ignore initlist +// cspell: ignore ilist +// cspell: ignore nonheap + +#ifndef DOWNSAMPLE_FILTER__ROBIN_HOOD_H_ +#define DOWNSAMPLE_FILTER__ROBIN_HOOD_H_ + +// see https://semver.org/ +#define ROBIN_HOOD_VERSION_MAJOR 3 // for incompatible API changes +#define ROBIN_HOOD_VERSION_MINOR 11 // for adding functionality in a backwards-compatible manner +#define ROBIN_HOOD_VERSION_PATCH 5 // for backwards-compatible bug fixes + +#include +#include +#include +#include +#include +#include // only to support hash of smart pointers +#include +#include +#include +#include +#if __cplusplus >= 201703L +#include +#endif + +// #define ROBIN_HOOD_LOG_ENABLED +#ifdef ROBIN_HOOD_LOG_ENABLED +#include +#define ROBIN_HOOD_LOG(...) \ + std::cout << __FUNCTION__ << "@" << __LINE__ << ": " << __VA_ARGS__ << std::endl; +#else +#define ROBIN_HOOD_LOG(x) +#endif + +// #define ROBIN_HOOD_TRACE_ENABLED +#ifdef ROBIN_HOOD_TRACE_ENABLED +#include +#define ROBIN_HOOD_TRACE(...) \ + std::cout << __FUNCTION__ << "@" << __LINE__ << ": " << __VA_ARGS__ << std::endl; +#else +#define ROBIN_HOOD_TRACE(x) +#endif + +// #define ROBIN_HOOD_COUNT_ENABLED +#ifdef ROBIN_HOOD_COUNT_ENABLED +#include +#define ROBIN_HOOD_COUNT(x) ++counts().x; +namespace robin_hood +{ +struct Counts +{ + uint64_t shiftUp{}; + uint64_t shiftDown{}; +}; +inline std::ostream & operator<<(std::ostream & os, Counts const & c) +{ + return os << c.shiftUp << " shiftUp" << std::endl << c.shiftDown << " shiftDown" << std::endl; +} + +static Counts & counts() +{ + static Counts counts{}; + return counts; +} +} // namespace robin_hood +#else +#define ROBIN_HOOD_COUNT(x) +#endif + +// all non-argument macros should use this facility. See +// https://www.fluentcpp.com/2019/05/28/better-macros-better-flags/ +#define ROBIN_HOOD(x) ROBIN_HOOD_PRIVATE_DEFINITION_##x() + +// mark unused members with this macro +#define ROBIN_HOOD_UNUSED(identifier) + +// bitness +#if SIZE_MAX == UINT32_MAX +#define ROBIN_HOOD_PRIVATE_DEFINITION_BITNESS() 32 +#elif SIZE_MAX == UINT64_MAX +#define ROBIN_HOOD_PRIVATE_DEFINITION_BITNESS() 64 +#else +#error Unsupported bitness +#endif + +// endianess +#ifdef _MSC_VER +#define ROBIN_HOOD_PRIVATE_DEFINITION_LITTLE_ENDIAN() 1 +#define ROBIN_HOOD_PRIVATE_DEFINITION_BIG_ENDIAN() 0 +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_LITTLE_ENDIAN() (__BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__) +#define ROBIN_HOOD_PRIVATE_DEFINITION_BIG_ENDIAN() (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__) +#endif + +// inline +#ifdef _MSC_VER +#define ROBIN_HOOD_PRIVATE_DEFINITION_NOINLINE() __declspec(noinline) +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_NOINLINE() __attribute__((noinline)) +#endif + +// exceptions +#if !defined(__cpp_exceptions) && !defined(__EXCEPTIONS) && !defined(_CPPUNWIND) +#define ROBIN_HOOD_PRIVATE_DEFINITION_HAS_EXCEPTIONS() 0 +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_HAS_EXCEPTIONS() 1 +#endif + +// count leading/trailing bits +#if !defined(ROBIN_HOOD_DISABLE_INTRINSICS) +#ifdef _MSC_VER +#if ROBIN_HOOD(BITNESS) == 32 +#define ROBIN_HOOD_PRIVATE_DEFINITION_BITSCANFORWARD() _BitScanForward +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_BITSCANFORWARD() _BitScanForward64 +#endif +#include +#pragma intrinsic(ROBIN_HOOD(BITSCANFORWARD)) +#define ROBIN_HOOD_COUNT_TRAILING_ZEROES(x) \ + [](size_t mask) noexcept -> int { \ + unsigned long index; \ // NOLINT + return ROBIN_HOOD(BITSCANFORWARD)(&index, mask) ? static_cast(index) \ + : ROBIN_HOOD(BITNESS); \ + }(x) +#else +#if ROBIN_HOOD(BITNESS) == 32 +#define ROBIN_HOOD_PRIVATE_DEFINITION_CTZ() __builtin_ctzl +#define ROBIN_HOOD_PRIVATE_DEFINITION_CLZ() __builtin_clzl +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_CTZ() __builtin_ctzll +#define ROBIN_HOOD_PRIVATE_DEFINITION_CLZ() __builtin_clzll +#endif +#define ROBIN_HOOD_COUNT_LEADING_ZEROES(x) ((x) ? ROBIN_HOOD(CLZ)(x) : ROBIN_HOOD(BITNESS)) +#define ROBIN_HOOD_COUNT_TRAILING_ZEROES(x) ((x) ? ROBIN_HOOD(CTZ)(x) : ROBIN_HOOD(BITNESS)) +#endif +#endif + +// fallthrough +#ifndef __has_cpp_attribute // For backwards compatibility +#define __has_cpp_attribute(x) 0 +#endif +#if __has_cpp_attribute(clang::fallthrough) +#define ROBIN_HOOD_PRIVATE_DEFINITION_FALLTHROUGH() [[clang::fallthrough]] +#elif __has_cpp_attribute(gnu::fallthrough) +#define ROBIN_HOOD_PRIVATE_DEFINITION_FALLTHROUGH() [[gnu::fallthrough]] +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_FALLTHROUGH() +#endif + +// likely/unlikely +#ifdef _MSC_VER +#define ROBIN_HOOD_LIKELY(condition) condition +#define ROBIN_HOOD_UNLIKELY(condition) condition +#else +#define ROBIN_HOOD_LIKELY(condition) __builtin_expect(condition, 1) +#define ROBIN_HOOD_UNLIKELY(condition) __builtin_expect(condition, 0) +#endif + +// detect if native wchar_t type is available in MSVC +#ifdef _MSC_VER +#ifdef _NATIVE_WCHAR_T_DEFINED +#define ROBIN_HOOD_PRIVATE_DEFINITION_HAS_NATIVE_WCHART() 1 +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_HAS_NATIVE_WCHART() 0 +#endif +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_HAS_NATIVE_WCHART() 1 +#endif + +// detect if MSVC supports the pair(std::piecewise_construct_t,...) constructor being constexpr +#ifdef _MSC_VER +#if _MSC_VER <= 1900 +#define ROBIN_HOOD_PRIVATE_DEFINITION_BROKEN_CONSTEXPR() 1 +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_BROKEN_CONSTEXPR() 0 +#endif +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_BROKEN_CONSTEXPR() 0 +#endif + +// workaround missing "is_trivially_copyable" in g++ < 5.0 +// See https://stackoverflow.com/a/31798726/48181 +#if defined(__GNUC__) && __GNUC__ < 5 +#define ROBIN_HOOD_IS_TRIVIALLY_COPYABLE(...) __has_trivial_copy(__VA_ARGS__) +#else +#define ROBIN_HOOD_IS_TRIVIALLY_COPYABLE(...) std::is_trivially_copyable<__VA_ARGS__>::value +#endif + +// helpers for C++ versions, see https://gcc.gnu.org/onlinedocs/cpp/Standard-Predefined-Macros.html +#define ROBIN_HOOD_PRIVATE_DEFINITION_CXX() __cplusplus +#define ROBIN_HOOD_PRIVATE_DEFINITION_CXX98() 199711L +#define ROBIN_HOOD_PRIVATE_DEFINITION_CXX11() 201103L +#define ROBIN_HOOD_PRIVATE_DEFINITION_CXX14() 201402L +#define ROBIN_HOOD_PRIVATE_DEFINITION_CXX17() 201703L + +#if ROBIN_HOOD(CXX) >= ROBIN_HOOD(CXX17) +#define ROBIN_HOOD_PRIVATE_DEFINITION_NODISCARD() [[nodiscard]] +#else +#define ROBIN_HOOD_PRIVATE_DEFINITION_NODISCARD() +#endif + +namespace robin_hood +{ + +#if ROBIN_HOOD(CXX) >= ROBIN_HOOD(CXX14) +#define ROBIN_HOOD_STD std +#else + +// c++11 compatibility layer +namespace ROBIN_HOOD_STD +{ +template +struct alignment_of +: std::integral_constant::type)> +{ +}; + +template +class integer_sequence +{ +public: + using value_type = T; + static_assert(std::is_integral::value, "not integral type"); + static constexpr std::size_t size() noexcept { return sizeof...(Ints); } +}; +template +using index_sequence = integer_sequence; + +namespace detail_ +{ +template +struct IntSeqImpl +{ + using TValue = T; + static_assert(std::is_integral::value, "not integral type"); + static_assert(Begin >= 0 && Begin < End, "unexpected argument (Begin<0 || Begin<=End)"); + + template + struct IntSeqCombiner; + + template + struct IntSeqCombiner, integer_sequence> + { + using TResult = integer_sequence; + }; + + using TResult = typename IntSeqCombiner< + typename IntSeqImpl::TResult, + typename IntSeqImpl< + TValue, Begin + (End - Begin) / 2, End, (End - Begin + 1) / 2 == 1>::TResult>::TResult; +}; + +template +struct IntSeqImpl +{ + using TValue = T; + static_assert(std::is_integral::value, "not integral type"); + static_assert(Begin >= 0, "unexpected argument (Begin<0)"); + using TResult = integer_sequence; +}; + +template +struct IntSeqImpl +{ + using TValue = T; + static_assert(std::is_integral::value, "not integral type"); + static_assert(Begin >= 0, "unexpected argument (Begin<0)"); + using TResult = integer_sequence; +}; +} // namespace detail_ + +template +using make_integer_sequence = typename detail_::IntSeqImpl::TResult; + +template +using make_index_sequence = make_integer_sequence; + +template +using index_sequence_for = make_index_sequence; + +} // namespace ROBIN_HOOD_STD + +#endif + +namespace detail +{ + +// make sure we static_cast to the correct type for hash_int +#if ROBIN_HOOD(BITNESS) == 64 +using SizeT = uint64_t; +#else +using SizeT = uint32_t; +#endif + +template +T rotr(T x, unsigned k) +{ + return (x >> k) | (x << (8U * sizeof(T) - k)); +} + +// This cast gets rid of warnings like "cast from 'uint8_t*' {aka 'unsigned char*'} to +// 'uint64_t*' {aka 'long unsigned int*'} increases required alignment of target type". Use with +// care! +template +inline T reinterpret_cast_no_cast_align_warning(void * ptr) noexcept +{ + return reinterpret_cast(ptr); +} + +template +inline T reinterpret_cast_no_cast_align_warning(void const * ptr) noexcept +{ + return reinterpret_cast(ptr); +} + +// make sure this is not inlined as it is slow and dramatically enlarges code, thus making other +// inlinings more difficult. Throws are also generally the slow path. +template +[[noreturn]] ROBIN_HOOD(NOINLINE) +#if ROBIN_HOOD(HAS_EXCEPTIONS) + void doThrow(Args &&... args) +{ + // NOLINTNEXTLINE (cppcoreguidelines-pro-bounds-array-to-pointer-decay) + throw E(std::forward(args)...); +} +#else + void doThrow(Args &&... ROBIN_HOOD_UNUSED(args) /*unused*/) +{ + abort(); +} +#endif + +template +T * assertNotNull(T * t, Args &&... args) +{ + if (ROBIN_HOOD_UNLIKELY(nullptr == t)) { + doThrow(std::forward(args)...); + } + return t; +} + +template +inline T unaligned_load(void const * ptr) noexcept +{ + // using memcpy so we don't get into unaligned load problems. + // compiler should optimize this very well anyways. + T t; + std::memcpy(&t, ptr, sizeof(T)); + return t; +} + +// Allocates bulks of memory for objects of type T. This deallocates the memory in the destructor, +// and keeps a linked list of the allocated memory around. Overhead per allocation is the size of a +// pointer. +template +class BulkPoolAllocator +{ +public: + BulkPoolAllocator() noexcept = default; + + // does not copy anything, just creates a new allocator. + BulkPoolAllocator(const BulkPoolAllocator & ROBIN_HOOD_UNUSED(o) /*unused*/) noexcept + : mHead(nullptr), mListForFree(nullptr) + { + } + + BulkPoolAllocator(BulkPoolAllocator && o) noexcept : mHead(o.mHead), mListForFree(o.mListForFree) + { + o.mListForFree = nullptr; + o.mHead = nullptr; + } + + BulkPoolAllocator & operator=(BulkPoolAllocator && o) noexcept + { + reset(); + mHead = o.mHead; + mListForFree = o.mListForFree; + o.mListForFree = nullptr; + o.mHead = nullptr; + return *this; + } + + BulkPoolAllocator & + // NOLINTNEXTLINE (bugprone-unhandled-self-assignment,cert-oop54-cpp) + operator=(const BulkPoolAllocator & ROBIN_HOOD_UNUSED(o) /*unused*/) noexcept + { + // does not do anything + return *this; + } + + ~BulkPoolAllocator() noexcept { reset(); } + + // Deallocates all allocated memory. + void reset() noexcept + { + while (mListForFree) { + T * tmp = *mListForFree; + ROBIN_HOOD_LOG("std::free") + std::free(mListForFree); + mListForFree = reinterpret_cast_no_cast_align_warning(tmp); + } + mHead = nullptr; + } + + // allocates, but does NOT initialize. Use in-place new constructor, e.g. + // T* obj = pool.allocate(); + // ::new (static_cast(obj)) T(); + T * allocate() + { + T * tmp = mHead; + if (!tmp) { + tmp = performAllocation(); + } + + mHead = *reinterpret_cast_no_cast_align_warning(tmp); + return tmp; + } + + // does not actually deallocate but puts it in store. + // make sure you have already called the destructor! e.g. with + // obj->~T(); + // pool.deallocate(obj); + void deallocate(T * obj) noexcept + { + *reinterpret_cast_no_cast_align_warning(obj) = mHead; + mHead = obj; + } + + // Adds an already allocated block of memory to the allocator. This allocator is from now on + // responsible for freeing the data (with free()). If the provided data is not large enough to + // make use of, it is immediately freed. Otherwise it is reused and freed in the destructor. + void addOrFree(void * ptr, const size_t numBytes) noexcept + { + // calculate number of available elements in ptr + if (numBytes < ALIGNMENT + ALIGNED_SIZE) { + // not enough data for at least one element. Free and return. + ROBIN_HOOD_LOG("std::free") + std::free(ptr); + } else { + ROBIN_HOOD_LOG("add to buffer") + add(ptr, numBytes); + } + } + + void swap(BulkPoolAllocator & other) noexcept + { + using std::swap; + swap(mHead, other.mHead); + swap(mListForFree, other.mListForFree); + } + +private: + // iterates the list of allocated memory to calculate how many to alloc next. + // Recalculating this each time saves us a size_t member. + // This ignores the fact that memory blocks might have been added manually with addOrFree. In + // practice, this should not matter much. + ROBIN_HOOD(NODISCARD) size_t calcNumElementsToAlloc() const noexcept + { + auto tmp = mListForFree; + size_t numAllocs = MinNumAllocs; + + while (numAllocs * 2 <= MaxNumAllocs && tmp) { + auto x = reinterpret_cast(tmp); + tmp = *x; + numAllocs *= 2; + } + + return numAllocs; + } + + // WARNING: Underflow if numBytes < ALIGNMENT! This is guarded in addOrFree(). + void add(void * ptr, const size_t numBytes) noexcept + { + const size_t numElements = (numBytes - ALIGNMENT) / ALIGNED_SIZE; + + auto data = reinterpret_cast(ptr); + + // link free list + auto x = reinterpret_cast(data); + *x = mListForFree; + mListForFree = data; + + // create linked list for newly allocated data + auto * const headT = + reinterpret_cast_no_cast_align_warning(reinterpret_cast(ptr) + ALIGNMENT); + + auto * const head = reinterpret_cast(headT); + + // Visual Studio compiler automatically unrolls this loop, which is pretty cool + for (size_t i = 0; i < numElements; ++i) { + *reinterpret_cast_no_cast_align_warning(head + i * ALIGNED_SIZE) = + head + (i + 1) * ALIGNED_SIZE; + } + + // last one points to 0 + *reinterpret_cast_no_cast_align_warning(head + (numElements - 1) * ALIGNED_SIZE) = mHead; + mHead = headT; + } + + // Called when no memory is available (mHead == 0). + // Don't inline this slow path. + ROBIN_HOOD(NOINLINE) T * performAllocation() + { + size_t const numElementsToAlloc = calcNumElementsToAlloc(); + + // alloc new memory: [prev |T, T, ... T] + size_t const bytes = ALIGNMENT + ALIGNED_SIZE * numElementsToAlloc; + ROBIN_HOOD_LOG( + "std::malloc " << bytes << " = " << ALIGNMENT << " + " << ALIGNED_SIZE << " * " + << numElementsToAlloc) + add(assertNotNull(std::malloc(bytes)), bytes); + return mHead; + } + + // enforce byte alignment of the T's +#if ROBIN_HOOD(CXX) >= ROBIN_HOOD(CXX14) + static constexpr size_t ALIGNMENT = + (std::max)(std::alignment_of::value, std::alignment_of::value); +#else + static const size_t ALIGNMENT = + (ROBIN_HOOD_STD::alignment_of::value > ROBIN_HOOD_STD::alignment_of::value) + ? ROBIN_HOOD_STD::alignment_of::value + : +ROBIN_HOOD_STD::alignment_of::value; // the + is for walk around +#endif + + static constexpr size_t ALIGNED_SIZE = ((sizeof(T) - 1) / ALIGNMENT + 1) * ALIGNMENT; + + static_assert(MinNumAllocs >= 1, "MinNumAllocs"); + static_assert(MaxNumAllocs >= MinNumAllocs, "MaxNumAllocs"); + static_assert(ALIGNED_SIZE >= sizeof(T *), "ALIGNED_SIZE"); + static_assert(0 == (ALIGNED_SIZE % sizeof(T *)), "ALIGNED_SIZE mod"); + static_assert(ALIGNMENT >= sizeof(T *), "ALIGNMENT"); + + T * mHead{nullptr}; + T ** mListForFree{nullptr}; +}; + +template +struct NodeAllocator; + +// dummy allocator that does nothing +template +struct NodeAllocator +{ + // we are not using the data, so just free it. + void addOrFree(void * ptr, size_t ROBIN_HOOD_UNUSED(numBytes) /*unused*/) noexcept + { + ROBIN_HOOD_LOG("std::free") + std::free(ptr); + } +}; + +template +struct NodeAllocator : public BulkPoolAllocator +{ +}; + +// c++14 doesn't have is_nothrow_swappable, and clang++ 6.0.1 doesn't like it either, so I'm making +// my own here. +namespace swappable +{ +#if ROBIN_HOOD(CXX) < ROBIN_HOOD(CXX17) +using std::swap; +template +struct nothrow +{ + static const bool value = noexcept(swap(std::declval(), std::declval())); +}; +#else +template +struct nothrow +{ + static const bool value = std::is_nothrow_swappable::value; +}; +#endif +} // namespace swappable + +} // namespace detail + +struct is_transparent_tag +{ +}; + +// A custom pair implementation is used in the map because std::pair is not is_trivially_copyable, +// which means it would not be allowed to be used in std::memcpy. This struct is copyable, which is +// also tested. +template +struct pair +{ + using first_type = T1; + using second_type = T2; + + template < + typename U1 = T1, typename U2 = T2, + typename = typename std::enable_if< + std::is_default_constructible::value && std::is_default_constructible::value>::type> + constexpr pair() noexcept(noexcept(U1()) && noexcept(U2())) : first(), second() + { + } + + // pair constructors are explicit so we don't accidentally call this ctor when we don't have to. + explicit constexpr pair(std::pair const & o) noexcept( + noexcept(T1(std::declval())) && noexcept(T2(std::declval()))) + : first(o.first), second(o.second) + { + } + + // pair constructors are explicit so we don't accidentally call this ctor when we don't have to. + explicit constexpr pair(std::pair && o) noexcept(noexcept( + T1(std::move(std::declval()))) && noexcept(T2(std::move(std::declval())))) + : first(std::move(o.first)), second(std::move(o.second)) + { + } + + constexpr pair(T1 && a, T2 && b) noexcept(noexcept( + T1(std::move(std::declval()))) && noexcept(T2(std::move(std::declval())))) + : first(std::move(a)), second(std::move(b)) + { + } + + template + constexpr pair(U1 && a, U2 && b) noexcept(noexcept(T1(std::forward( + std::declval()))) && noexcept(T2(std::forward(std::declval())))) + : first(std::forward(a)), second(std::forward(b)) + { + } + + template + // MSVC 2015 produces error "C2476: ‘constexpr’ constructor does not initialize all members" + // if this constructor is constexpr +#if !ROBIN_HOOD(BROKEN_CONSTEXPR) + constexpr +#endif + pair(std::piecewise_construct_t /*unused*/, std::tuple a, std::tuple b) noexcept( + noexcept(pair( + std::declval &>(), std::declval &>(), + ROBIN_HOOD_STD::index_sequence_for(), ROBIN_HOOD_STD::index_sequence_for()))) + : pair( + a, b, ROBIN_HOOD_STD::index_sequence_for(), + ROBIN_HOOD_STD::index_sequence_for()) + { + } + + // constructor called from the std::piecewise_construct_t ctor + template + pair( + std::tuple & a, std::tuple & b, ROBIN_HOOD_STD::index_sequence /*unused*/, + ROBIN_HOOD_STD::index_sequence< + I2...> /*unused*/) noexcept(noexcept(T1(std:: + forward(std::get( + std::declval &>()))...)) && noexcept(T2(std:: + forward(std::get(std::declval &>()))...))) // NOLINT + : first(std::forward(std::get(a))...), second(std::forward(std::get(b))...) + { + // make visual studio compiler happy about warning about unused a & b. + // Visual studio's pair implementation disables warning 4100. + (void)a; + (void)b; + } + + void swap(pair & o) noexcept( + (detail::swappable::nothrow::value) && (detail::swappable::nothrow::value)) + { + using std::swap; + swap(first, o.first); + swap(second, o.second); + } + + T1 first; // NOLINT (misc-non-private-member-variables-in-classes) + T2 second; // NOLINT (misc-non-private-member-variables-in-classes) +}; + +template +inline void swap(pair & a, pair & b) noexcept( + noexcept(std::declval &>().swap(std::declval &>()))) +{ + a.swap(b); +} + +template +inline constexpr bool operator==(pair const & x, pair const & y) +{ + return (x.first == y.first) && (x.second == y.second); +} +template +inline constexpr bool operator!=(pair const & x, pair const & y) +{ + return !(x == y); +} +template +inline constexpr bool operator<(pair const & x, pair const & y) noexcept(noexcept( + std::declval() < + std::declval()) && noexcept(std::declval() < std::declval())) +{ + return x.first < y.first || (!(y.first < x.first) && x.second < y.second); +} +template +inline constexpr bool operator>(pair const & x, pair const & y) +{ + return y < x; +} +template +inline constexpr bool operator<=(pair const & x, pair const & y) +{ + return !(x > y); +} +template +inline constexpr bool operator>=(pair const & x, pair const & y) +{ + return !(x < y); +} + +inline size_t hash_bytes(void const * ptr, size_t len) noexcept +{ + static constexpr uint64_t m = UINT64_C(0xc6a4a7935bd1e995); + static constexpr uint64_t seed = UINT64_C(0xe17a1465); + static constexpr unsigned int r = 47; + + auto const * const data64 = static_cast(ptr); + uint64_t h = seed ^ (len * m); + + size_t const n_blocks = len / 8; + for (size_t i = 0; i < n_blocks; ++i) { + auto k = detail::unaligned_load(data64 + i); + + k *= m; + k ^= k >> r; + k *= m; + + h ^= k; + h *= m; + } + + auto const * const data8 = reinterpret_cast(data64 + n_blocks); + switch (len & 7U) { + case 7: + h ^= static_cast(data8[6]) << 48U; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + case 6: + h ^= static_cast(data8[5]) << 40U; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + case 5: + h ^= static_cast(data8[4]) << 32U; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + case 4: + h ^= static_cast(data8[3]) << 24U; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + case 3: + h ^= static_cast(data8[2]) << 16U; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + case 2: + h ^= static_cast(data8[1]) << 8U; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + case 1: + h ^= static_cast(data8[0]); + h *= m; + ROBIN_HOOD(FALLTHROUGH); // FALLTHROUGH + default: + break; + } + + h ^= h >> r; + + // not doing the final step here, because this will be done by keyToIdx anyways + // h *= m; + // h ^= h >> r; + return static_cast(h); +} + +inline size_t hash_int(uint64_t x) noexcept +{ + // tried lots of different hashes, let's stick with murmurhash3. It's simple, fast, well tested, + // and doesn't need any special 128bit operations. + x ^= x >> 33U; + x *= UINT64_C(0xff51afd7ed558ccd); + x ^= x >> 33U; + + // not doing the final step here, because this will be done by keyToIdx anyways + // x *= UINT64_C(0xc4ceb9fe1a85ec53); + // x ^= x >> 33U; + return static_cast(x); +} + +// A thin wrapper around std::hash, performing an additional simple mixing step of the result. +template +struct hash : public std::hash +{ + size_t operator()(T const & obj) const + noexcept(noexcept(std::declval>().operator()(std::declval()))) + { + // call base hash + auto result = std::hash::operator()(obj); + // return mixed of that, to be save against identity has + return hash_int(static_cast(result)); + } +}; + +template +struct hash> +{ + size_t operator()(std::basic_string const & str) const noexcept + { + return hash_bytes(str.data(), sizeof(CharT) * str.size()); + } +}; + +#if ROBIN_HOOD(CXX) >= ROBIN_HOOD(CXX17) +template +struct hash> +{ + size_t operator()(std::basic_string_view const & sv) const noexcept + { + return hash_bytes(sv.data(), sizeof(CharT) * sv.size()); + } +}; +#endif + +template +struct hash +{ + size_t operator()(T * ptr) const noexcept + { + return hash_int(reinterpret_cast(ptr)); + } +}; + +template +struct hash> +{ + size_t operator()(std::unique_ptr const & ptr) const noexcept + { + return hash_int(reinterpret_cast(ptr.get())); + } +}; + +template +struct hash> +{ + size_t operator()(std::shared_ptr const & ptr) const noexcept + { + return hash_int(reinterpret_cast(ptr.get())); + } +}; + +template +struct hash::value>::type> +{ + size_t operator()(Enum e) const noexcept + { + using Underlying = typename std::underlying_type::type; + return hash{}(static_cast(e)); + } +}; + +#define ROBIN_HOOD_HASH_INT(T) \ + template <> \ + struct hash \ + { \ + size_t operator()(T const & obj) const noexcept \ + { \ + return hash_int(static_cast(obj)); \ + } \ + } + +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wuseless-cast" +#endif +// see https://en.cppreference.com/w/cpp/utility/hash +ROBIN_HOOD_HASH_INT(bool); +ROBIN_HOOD_HASH_INT(char); +ROBIN_HOOD_HASH_INT(signed char); +ROBIN_HOOD_HASH_INT(unsigned char); +ROBIN_HOOD_HASH_INT(char16_t); +ROBIN_HOOD_HASH_INT(char32_t); +#if ROBIN_HOOD(HAS_NATIVE_WCHART) +ROBIN_HOOD_HASH_INT(wchar_t); +#endif +ROBIN_HOOD_HASH_INT(short); // NOLINT +ROBIN_HOOD_HASH_INT(unsigned short); // NOLINT +ROBIN_HOOD_HASH_INT(int); +ROBIN_HOOD_HASH_INT(unsigned int); +ROBIN_HOOD_HASH_INT(long); // NOLINT +ROBIN_HOOD_HASH_INT(long long); // NOLINT +ROBIN_HOOD_HASH_INT(unsigned long); // NOLINT +ROBIN_HOOD_HASH_INT(unsigned long long); // NOLINT +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic pop +#endif +namespace detail +{ + +template +struct void_type +{ + using type = void; +}; + +template +struct has_is_transparent : public std::false_type +{ +}; + +template +struct has_is_transparent::type> +: public std::true_type +{ +}; + +// using wrapper classes for hash and key_equal prevents the diamond problem when the same type +// is used. see https://stackoverflow.com/a/28771920/48181 +template +struct WrapHash : public T +{ + WrapHash() = default; + explicit WrapHash(T const & o) noexcept(noexcept(T(std::declval()))) : T(o) {} +}; + +template +struct WrapKeyEqual : public T +{ + WrapKeyEqual() = default; + explicit WrapKeyEqual(T const & o) noexcept(noexcept(T(std::declval()))) : T(o) {} +}; + +// A highly optimized hashmap implementation, using the Robin Hood algorithm. +// +// In most cases, this map should be usable as a drop-in replacement for std::unordered_map, but +// be about 2x faster in most cases and require much less allocations. +// +// This implementation uses the following memory layout: +// +// [Node, Node, ... Node | info, info, ... infoSentinel ] +// +// * Node: either a DataNode that directly has the std::pair as member, +// or a DataNode with a pointer to std::pair. Which DataNode representation to use +// depends on how fast the swap() operation is. Heuristically, this is automatically choosen +// based on sizeof(). there are always 2^n Nodes. +// +// * info: Each Node in the map has a corresponding info byte, so there are 2^n info bytes. +// Each byte is initialized to 0, meaning the corresponding Node is empty. Set to 1 means the +// corresponding node contains data. Set to 2 means the corresponding Node is filled, but it +// actually belongs to the previous position and was pushed out because that place is already +// taken. +// +// * infoSentinel: Sentinel byte set to 1, so that iterator's ++ can stop at end() without the +// need for a idx variable. +// +// According to STL, order of templates has effect on throughput. That's why I've moved the +// boolean to the front. +// https://www.reddit.com/r/cpp/comments/ahp6iu/compile_time_binary_size_reductions_and_cs_future/eeguck4/ +template < + bool IsFlat, size_t MaxLoadFactor100, typename Key, typename T, typename Hash, typename KeyEqual> +class Table +: public WrapHash, + public WrapKeyEqual, + detail::NodeAllocator< + typename std::conditional< + std::is_void::value, Key, + robin_hood::pair::type, T>>::type, + 4, 16384, IsFlat> +{ +public: + static constexpr bool is_flat = IsFlat; + static constexpr bool is_map = !std::is_void::value; + static constexpr bool is_set = !is_map; + static constexpr bool is_transparent = + has_is_transparent::value && has_is_transparent::value; + + using key_type = Key; + using mapped_type = T; + using value_type = typename std::conditional< + is_set, Key, + robin_hood::pair::type, T>>::type; + using size_type = size_t; + using hasher = Hash; + using key_equal = KeyEqual; + using Self = Table; + +private: + static_assert( + MaxLoadFactor100 > 10 && MaxLoadFactor100 < 100, "MaxLoadFactor100 needs to be >10 && < 100"); + + using WHash = WrapHash; + using WKeyEqual = WrapKeyEqual; + + // configuration defaults + + // make sure we have 8 elements, needed to quickly rehash mInfo + static constexpr size_t InitialNumElements = sizeof(uint64_t); + static constexpr uint32_t InitialInfoNumBits = 5; + static constexpr uint8_t InitialInfoInc = 1U << InitialInfoNumBits; + static constexpr size_t InfoMask = InitialInfoInc - 1U; + static constexpr uint8_t InitialInfoHashShift = 0; + using DataPool = detail::NodeAllocator; + + // type needs to be wider than uint8_t. + using InfoType = uint32_t; + + // DataNode //////////////////////////////////////////////////////// + + // Primary template for the data node. We have special implementations for small and big + // objects. For large objects it is assumed that swap() is fairly slow, so we allocate these + // on the heap so swap merely swaps a pointer. + template + class DataNode + { + }; + + // Small: just allocate on the stack. + template + class DataNode final + { + public: + template + explicit DataNode(M & ROBIN_HOOD_UNUSED(map) /*unused*/, Args &&... args) noexcept( + noexcept(value_type(std::forward(args)...))) + : mData(std::forward(args)...) + { + } + + DataNode(M & ROBIN_HOOD_UNUSED(map) /*unused*/, DataNode && n) noexcept( + std::is_nothrow_move_constructible::value) + : mData(std::move(n.mData)) + { + } + + // doesn't do anything + void destroy(M & ROBIN_HOOD_UNUSED(map) /*unused*/) noexcept {} + void destroyDoNotDeallocate() noexcept {} + + value_type const * operator->() const noexcept { return &mData; } + value_type * operator->() noexcept { return &mData; } + + const value_type & operator*() const noexcept { return mData; } + + value_type & operator*() noexcept { return mData; } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() noexcept + { + return mData.first; + } + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() noexcept + { + return mData; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() const noexcept + { + return mData.first; + } + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() const noexcept + { + return mData; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getSecond() noexcept + { + return mData.second; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getSecond() const noexcept + { + return mData.second; + } + + void swap(DataNode & o) noexcept( + noexcept(std::declval().swap(std::declval()))) + { + mData.swap(o.mData); + } + + private: + value_type mData; + }; + + // big object: allocate on heap. + template + class DataNode + { + public: + template + explicit DataNode(M & map, Args &&... args) : mData(map.allocate()) + { + ::new (static_cast(mData)) value_type(std::forward(args)...); + } + + DataNode(M & ROBIN_HOOD_UNUSED(map) /*unused*/, DataNode && n) noexcept + : mData(std::move(n.mData)) + { + } + + void destroy(M & map) noexcept + { + // don't deallocate, just put it into list of data pool. + mData->~value_type(); + map.deallocate(mData); + } + + void destroyDoNotDeallocate() noexcept { mData->~value_type(); } + + value_type const * operator->() const noexcept { return mData; } + + value_type * operator->() noexcept { return mData; } + + const value_type & operator*() const { return *mData; } + + value_type & operator*() { return *mData; } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() noexcept + { + return mData->first; + } + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() noexcept + { + return *mData; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() const noexcept + { + return mData->first; + } + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getFirst() const noexcept + { + return *mData; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getSecond() noexcept + { + return mData->second; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::type getSecond() const noexcept + { + return mData->second; + } + + void swap(DataNode & o) noexcept + { + using std::swap; + swap(mData, o.mData); + } + + private: + value_type * mData; + }; + + using Node = DataNode; + + // helpers for insertKeyPrepareEmptySpot: extract first entry (only const required) + ROBIN_HOOD(NODISCARD) key_type const & getFirstConst(Node const & n) const noexcept + { + return n.getFirst(); + } + + // in case we have void mapped_type, we are not using a pair, thus we just route k through. + // No need to disable this because it's just not used if not applicable. + ROBIN_HOOD(NODISCARD) key_type const & getFirstConst(key_type const & k) const noexcept + { + return k; + } + + // in case we have non-void mapped_type, we have a standard robin_hood::pair + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::value, key_type const &>::type + getFirstConst(value_type const & vt) const noexcept + { + return vt.first; + } + + // Cloner ////////////////////////////////////////////////////////// + + template + struct Cloner; + + // fast path: Just copy data, without allocating anything. + template + struct Cloner + { + void operator()(M const & source, M & target) const + { + auto const * const src = reinterpret_cast(source.mKeyVals); + auto * tgt = reinterpret_cast(target.mKeyVals); + auto const numElementsWithBuffer = target.calcNumElementsWithBuffer(target.mMask + 1); + std::copy(src, src + target.calcNumBytesTotal(numElementsWithBuffer), tgt); + } + }; + + template + struct Cloner + { + void operator()(M const & s, M & t) const + { + auto const numElementsWithBuffer = t.calcNumElementsWithBuffer(t.mMask + 1); + std::copy(s.mInfo, s.mInfo + t.calcNumBytesInfo(numElementsWithBuffer), t.mInfo); + + for (size_t i = 0; i < numElementsWithBuffer; ++i) { + if (t.mInfo[i]) { + ::new (static_cast(t.mKeyVals + i)) Node(t, *s.mKeyVals[i]); + } + } + } + }; + + // Destroyer /////////////////////////////////////////////////////// + + template + struct Destroyer + { + }; + + template + struct Destroyer + { + void nodes(M & m) const noexcept { m.mNumElements = 0; } + + void nodesDoNotDeallocate(M & m) const noexcept { m.mNumElements = 0; } + }; + + template + struct Destroyer + { + void nodes(M & m) const noexcept + { + m.mNumElements = 0; + // clear also resets mInfo to 0, that's sometimes not necessary. + auto const numElementsWithBuffer = m.calcNumElementsWithBuffer(m.mMask + 1); + + for (size_t idx = 0; idx < numElementsWithBuffer; ++idx) { + if (0 != m.mInfo[idx]) { + Node & n = m.mKeyVals[idx]; + n.destroy(m); + n.~Node(); + } + } + } + + void nodesDoNotDeallocate(M & m) const noexcept + { + m.mNumElements = 0; + // clear also resets mInfo to 0, that's sometimes not necessary. + auto const numElementsWithBuffer = m.calcNumElementsWithBuffer(m.mMask + 1); + for (size_t idx = 0; idx < numElementsWithBuffer; ++idx) { + if (0 != m.mInfo[idx]) { + Node & n = m.mKeyVals[idx]; + n.destroyDoNotDeallocate(); + n.~Node(); + } + } + } + }; + + // Iter //////////////////////////////////////////////////////////// + + struct fast_forward_tag + { + }; + + // generic iterator for both const_iterator and iterator. + template + // NOLINTNEXTLINE (hicpp-special-member-functions,cppcoreguidelines-special-member-functions) + class Iter + { + private: + using NodePtr = typename std::conditional::type; + + public: + using difference_type = std::ptrdiff_t; + using value_type = typename Self::value_type; + using reference = typename std::conditional::type; + using pointer = typename std::conditional::type; + using iterator_category = std::forward_iterator_tag; + + // default constructed iterator can be compared to itself, but WON'T return true when + // compared to end(). + Iter() = default; + + // Rule of zero: nothing specified. The conversion constructor is only enabled for + // iterator to const_iterator, so it doesn't accidentally work as a copy ctor. + + // Conversion constructor from iterator to const_iterator. + template ::type> + // NOLINTNEXTLINE (hicpp-explicit-conversions) + Iter(Iter const & other) noexcept : mKeyVals(other.mKeyVals), mInfo(other.mInfo) + { + } + + Iter(NodePtr valPtr, uint8_t const * infoPtr) noexcept : mKeyVals(valPtr), mInfo(infoPtr) {} + + Iter( + NodePtr valPtr, uint8_t const * infoPtr, + fast_forward_tag ROBIN_HOOD_UNUSED(tag) /*unused*/) noexcept + : mKeyVals(valPtr), mInfo(infoPtr) + { + fastForward(); + } + + template ::type> + Iter & operator=(Iter const & other) noexcept + { + mKeyVals = other.mKeyVals; + mInfo = other.mInfo; + return *this; + } + + // prefix increment. Undefined behavior if we are at end()! + Iter & operator++() noexcept + { + mInfo++; + mKeyVals++; + fastForward(); + return *this; + } + + Iter operator++(int) noexcept + { + Iter tmp = *this; + ++(*this); + return tmp; + } + + reference operator*() const { return **mKeyVals; } + + pointer operator->() const { return &**mKeyVals; } + + template + bool operator==(Iter const & o) const noexcept + { + return mKeyVals == o.mKeyVals; + } + + template + bool operator!=(Iter const & o) const noexcept + { + return mKeyVals != o.mKeyVals; + } + + private: + // fast forward to the next non-free info byte + // I've tried a few variants that don't depend on intrinsics, but unfortunately they are + // quite a bit slower than this one. So I've reverted that change again. See map_benchmark. + void fastForward() noexcept + { + size_t n = 0; + while (0U == (n = detail::unaligned_load(mInfo))) { + mInfo += sizeof(size_t); + mKeyVals += sizeof(size_t); + } +#if defined(ROBIN_HOOD_DISABLE_INTRINSICS) + // we know for certain that within the next 8 bytes we'll find a non-zero one. + if (ROBIN_HOOD_UNLIKELY(0U == detail::unaligned_load(mInfo))) { + mInfo += 4; + mKeyVals += 4; + } + if (ROBIN_HOOD_UNLIKELY(0U == detail::unaligned_load(mInfo))) { + mInfo += 2; + mKeyVals += 2; + } + if (ROBIN_HOOD_UNLIKELY(0U == *mInfo)) { + mInfo += 1; + mKeyVals += 1; + } +#else +#if ROBIN_HOOD(LITTLE_ENDIAN) + auto inc = ROBIN_HOOD_COUNT_TRAILING_ZEROES(n) / 8; +#else + auto inc = ROBIN_HOOD_COUNT_LEADING_ZEROES(n) / 8; +#endif + mInfo += inc; + mKeyVals += inc; +#endif + } + + friend class Table; + NodePtr mKeyVals{nullptr}; + uint8_t const * mInfo{nullptr}; + }; + + //////////////////////////////////////////////////////////////////// + + // highly performance relevant code. + // Lower bits are used for indexing into the array (2^n size) + // The upper 1-5 bits need to be a reasonable good hash, to save comparisons. + template + void keyToIdx(HashKey && key, size_t * idx, InfoType * info) const + { + // In addition to whatever hash is used, add another mul & shift so we get better hashing. + // This serves as a bad hash prevention, if the given data is + // badly mixed. + auto h = static_cast(WHash::operator()(key)); + + h *= mHashMultiplier; + h ^= h >> 33U; + + // the lower InitialInfoNumBits are reserved for info. + *info = mInfoInc + static_cast((h & InfoMask) >> mInfoHashShift); + *idx = (static_cast(h) >> InitialInfoNumBits) & mMask; + } + + // forwards the index by one, wrapping around at the end + void next(InfoType * info, size_t * idx) const noexcept + { + *idx = *idx + 1; + *info += mInfoInc; + } + + void nextWhileLess(InfoType * info, size_t * idx) const noexcept + { + // unrolling this by hand did not bring any speedups. + while (*info < mInfo[*idx]) { + next(info, idx); + } + } + + // Shift everything up by one element. Tries to move stuff around. + void shiftUp(size_t startIdx, size_t const insertion_idx) noexcept( + std::is_nothrow_move_assignable::value) + { + auto idx = startIdx; + ::new (static_cast(mKeyVals + idx)) Node(std::move(mKeyVals[idx - 1])); + while (--idx != insertion_idx) { + mKeyVals[idx] = std::move(mKeyVals[idx - 1]); + } + + idx = startIdx; + while (idx != insertion_idx) { + ROBIN_HOOD_COUNT(shiftUp) + mInfo[idx] = static_cast(mInfo[idx - 1] + mInfoInc); + if (ROBIN_HOOD_UNLIKELY(mInfo[idx] + mInfoInc > 0xFF)) { + mMaxNumElementsAllowed = 0; + } + --idx; + } + } + + void shiftDown(size_t idx) noexcept(std::is_nothrow_move_assignable::value) + { + // until we find one that is either empty or has zero offset. + // TODO(martinus) we don't need to move everything, just the last one for the same + // bucket. + mKeyVals[idx].destroy(*this); + + // until we find one that is either empty or has zero offset. + while (mInfo[idx + 1] >= 2 * mInfoInc) { + ROBIN_HOOD_COUNT(shiftDown) + mInfo[idx] = static_cast(mInfo[idx + 1] - mInfoInc); + mKeyVals[idx] = std::move(mKeyVals[idx + 1]); + ++idx; + } + + mInfo[idx] = 0; + // don't destroy, we've moved it + // mKeyVals[idx].destroy(*this); + mKeyVals[idx].~Node(); + } + + // copy of find(), except that it returns iterator instead of const_iterator. + template + ROBIN_HOOD(NODISCARD) + size_t findIdx(Other const & key) const + { + size_t idx{}; + InfoType info{}; + keyToIdx(key, &idx, &info); + + do { + // unrolling this twice gives a bit of a speedup. More unrolling did not help. + if ( + info == mInfo[idx] && + ROBIN_HOOD_LIKELY(WKeyEqual::operator()(key, mKeyVals[idx].getFirst()))) { + return idx; + } + next(&info, &idx); + if ( + info == mInfo[idx] && + ROBIN_HOOD_LIKELY(WKeyEqual::operator()(key, mKeyVals[idx].getFirst()))) { + return idx; + } + next(&info, &idx); + } while (info <= mInfo[idx]); + + // nothing found! + return mMask == 0 ? 0 + : static_cast(std::distance( + mKeyVals, reinterpret_cast_no_cast_align_warning(mInfo))); + } + + void cloneData(const Table & o) + { + Cloner()(o, *this); + } + + // inserts a keyval that is guaranteed to be new, e.g. when the hashmap is resized. + // @return True on success, false if something went wrong + void insert_move(Node && keyval) + { + // we don't retry, fail if overflowing + // don't need to check max num elements + if (0 == mMaxNumElementsAllowed && !try_increase_info()) { + throwOverflowError(); + } + + size_t idx{}; + InfoType info{}; + keyToIdx(keyval.getFirst(), &idx, &info); + + // skip forward. Use <= because we are certain that the element is not there. + while (info <= mInfo[idx]) { + idx = idx + 1; + info += mInfoInc; + } + + // key not found, so we are now exactly where we want to insert it. + auto const insertion_idx = idx; + auto const insertion_info = static_cast(info); + if (ROBIN_HOOD_UNLIKELY(insertion_info + mInfoInc > 0xFF)) { + mMaxNumElementsAllowed = 0; + } + + // find an empty spot + while (0 != mInfo[idx]) { + next(&info, &idx); + } + + auto & l = mKeyVals[insertion_idx]; + if (idx == insertion_idx) { + ::new (static_cast(&l)) Node(std::move(keyval)); + } else { + shiftUp(idx, insertion_idx); + l = std::move(keyval); + } + + // put at empty spot + mInfo[insertion_idx] = insertion_info; + + ++mNumElements; + } + +public: + using iterator = Iter; + using const_iterator = Iter; + + Table() noexcept(noexcept(Hash()) && noexcept(KeyEqual())) : WHash(), WKeyEqual() + { + ROBIN_HOOD_TRACE(this) + } + + // Creates an empty hash map. Nothing is allocated yet, this happens at the first insert. + // This tremendously speeds up ctor & dtor of a map that never receives an element. The + // penalty is payed at the first insert, and not before. Lookup of this empty map works + // because everybody points to DummyInfoByte::b. parameter bucket_count is dictated by the + // standard, but we can ignore it. + explicit Table( + size_t ROBIN_HOOD_UNUSED(bucket_count) /*unused*/, const Hash & h = Hash{}, + const KeyEqual & equal = KeyEqual{}) noexcept(noexcept(Hash(h)) && noexcept(KeyEqual(equal))) + : WHash(h), WKeyEqual(equal) + { + ROBIN_HOOD_TRACE(this) + } + + template + Table( + Iter first, Iter last, size_t ROBIN_HOOD_UNUSED(bucket_count) /*unused*/ = 0, + const Hash & h = Hash{}, const KeyEqual & equal = KeyEqual{}) + : WHash(h), WKeyEqual(equal) + { + ROBIN_HOOD_TRACE(this) + insert(first, last); + } + + Table( + std::initializer_list initlist, + size_t ROBIN_HOOD_UNUSED(bucket_count) /*unused*/ = 0, const Hash & h = Hash{}, + const KeyEqual & equal = KeyEqual{}) + : WHash(h), WKeyEqual(equal) + { + ROBIN_HOOD_TRACE(this) + insert(initlist.begin(), initlist.end()); + } + + Table(Table && o) noexcept + : WHash(std::move(static_cast(o))), + WKeyEqual(std::move(static_cast(o))), + DataPool(std::move(static_cast(o))) + { + ROBIN_HOOD_TRACE(this) + if (o.mMask) { + mHashMultiplier = std::move(o.mHashMultiplier); + mKeyVals = std::move(o.mKeyVals); + mInfo = std::move(o.mInfo); + mNumElements = std::move(o.mNumElements); + mMask = std::move(o.mMask); + mMaxNumElementsAllowed = std::move(o.mMaxNumElementsAllowed); + mInfoInc = std::move(o.mInfoInc); + mInfoHashShift = std::move(o.mInfoHashShift); + // set other's mask to 0 so its destructor won't do anything + o.init(); + } + } + + Table & operator=(Table && o) noexcept + { + ROBIN_HOOD_TRACE(this) + if (&o != this) { + if (o.mMask) { + // only move stuff if the other map actually has some data + destroy(); + mHashMultiplier = std::move(o.mHashMultiplier); + mKeyVals = std::move(o.mKeyVals); + mInfo = std::move(o.mInfo); + mNumElements = std::move(o.mNumElements); + mMask = std::move(o.mMask); + mMaxNumElementsAllowed = std::move(o.mMaxNumElementsAllowed); + mInfoInc = std::move(o.mInfoInc); + mInfoHashShift = std::move(o.mInfoHashShift); + WHash::operator=(std::move(static_cast(o))); + WKeyEqual::operator=(std::move(static_cast(o))); + DataPool::operator=(std::move(static_cast(o))); + + o.init(); + + } else { + // nothing in the other map => just clear us. + clear(); + } + } + return *this; + } + + Table(const Table & o) + : WHash(static_cast(o)), + WKeyEqual(static_cast(o)), + DataPool(static_cast(o)) + { + ROBIN_HOOD_TRACE(this) + if (!o.empty()) { + // not empty: create an exact copy. it is also possible to just iterate through all + // elements and insert them, but copying is probably faster. + + auto const numElementsWithBuffer = calcNumElementsWithBuffer(o.mMask + 1); + auto const numBytesTotal = calcNumBytesTotal(numElementsWithBuffer); + + ROBIN_HOOD_LOG( + "std::malloc " << numBytesTotal << " = calcNumBytesTotal(" << numElementsWithBuffer << ")") + mHashMultiplier = o.mHashMultiplier; + mKeyVals = + static_cast(detail::assertNotNull(std::malloc(numBytesTotal))); + // no need for calloc because cloneData does memcpy + mInfo = reinterpret_cast(mKeyVals + numElementsWithBuffer); + mNumElements = o.mNumElements; + mMask = o.mMask; + mMaxNumElementsAllowed = o.mMaxNumElementsAllowed; + mInfoInc = o.mInfoInc; + mInfoHashShift = o.mInfoHashShift; + cloneData(o); + } + } + + // Creates a copy of the given map. Copy constructor of each entry is used. + // Not sure why clang-tidy thinks this doesn't handle self assignment, it does + // NOLINTNEXTLINE (bugprone-unhandled-self-assignment,cert-oop54-cpp) + Table & operator=(Table const & o) + { + ROBIN_HOOD_TRACE(this) + if (&o == this) { + // prevent assigning of itself + return *this; + } + + // we keep using the old allocator and not assign the new one, because we want to keep + // the memory available. when it is the same size. + if (o.empty()) { + if (0 == mMask) { + // nothing to do, we are empty too + return *this; + } + + // not empty: destroy what we have there + // clear also resets mInfo to 0, that's sometimes not necessary. + destroy(); + init(); + WHash::operator=(static_cast(o)); + WKeyEqual::operator=(static_cast(o)); + DataPool::operator=(static_cast(o)); + + return *this; + } + + // clean up old stuff + Destroyer::value>{}.nodes(*this); + + if (mMask != o.mMask) { + // no luck: we don't have the same array size allocated, so we need to realloc. + if (0 != mMask) { + // only deallocate if we actually have data! + ROBIN_HOOD_LOG("std::free") + std::free(mKeyVals); + } + + auto const numElementsWithBuffer = calcNumElementsWithBuffer(o.mMask + 1); + auto const numBytesTotal = calcNumBytesTotal(numElementsWithBuffer); + ROBIN_HOOD_LOG( + "std::malloc " << numBytesTotal << " = calcNumBytesTotal(" << numElementsWithBuffer << ")") + mKeyVals = + static_cast(detail::assertNotNull(std::malloc(numBytesTotal))); + + // no need for calloc here because cloneData performs a memcpy. + mInfo = reinterpret_cast(mKeyVals + numElementsWithBuffer); + // sentinel is set in cloneData + } + WHash::operator=(static_cast(o)); + WKeyEqual::operator=(static_cast(o)); + DataPool::operator=(static_cast(o)); + mHashMultiplier = o.mHashMultiplier; + mNumElements = o.mNumElements; + mMask = o.mMask; + mMaxNumElementsAllowed = o.mMaxNumElementsAllowed; + mInfoInc = o.mInfoInc; + mInfoHashShift = o.mInfoHashShift; + cloneData(o); + + return *this; + } + + // Swaps everything between the two maps. + void swap(Table & o) + { + ROBIN_HOOD_TRACE(this) + using std::swap; + swap(o, *this); + } + + // Clears all data, without resizing. + void clear() + { + ROBIN_HOOD_TRACE(this) + if (empty()) { + // don't do anything! also important because we don't want to write to + // DummyInfoByte::b, even though we would just write 0 to it. + return; + } + + Destroyer::value>{}.nodes(*this); + + auto const numElementsWithBuffer = calcNumElementsWithBuffer(mMask + 1); + // clear everything, then set the sentinel again + uint8_t const z = 0; + std::fill(mInfo, mInfo + calcNumBytesInfo(numElementsWithBuffer), z); + mInfo[numElementsWithBuffer] = 1; + + mInfoInc = InitialInfoInc; + mInfoHashShift = InitialInfoHashShift; + } + + // Destroys the map and all it's contents. + ~Table() + { + ROBIN_HOOD_TRACE(this) + destroy(); + } + + // Checks if both tables contain the same entries. Order is irrelevant. + bool operator==(const Table & other) const + { + ROBIN_HOOD_TRACE(this) + if (other.size() != size()) { + return false; + } + for (auto const & otherEntry : other) { + if (!has(otherEntry)) { + return false; + } + } + + return true; + } + + bool operator!=(const Table & other) const + { + ROBIN_HOOD_TRACE(this) + return !operator==(other); + } + + template + typename std::enable_if::value, Q &>::type operator[](const key_type & key) + { + ROBIN_HOOD_TRACE(this) + auto idxAndState = insertKeyPrepareEmptySpot(key); + switch (idxAndState.second) { + case InsertionState::key_found: + break; + + case InsertionState::new_node: + ::new (static_cast(&mKeyVals[idxAndState.first])) Node( + *this, std::piecewise_construct, std::forward_as_tuple(key), std::forward_as_tuple()); + break; + + case InsertionState::overwrite_node: + mKeyVals[idxAndState.first] = Node( + *this, std::piecewise_construct, std::forward_as_tuple(key), std::forward_as_tuple()); + break; + + case InsertionState::overflow_error: + throwOverflowError(); + } + + return mKeyVals[idxAndState.first].getSecond(); + } + + template + typename std::enable_if::value, Q &>::type operator[](key_type && key) + { + ROBIN_HOOD_TRACE(this) + auto idxAndState = insertKeyPrepareEmptySpot(key); + switch (idxAndState.second) { + case InsertionState::key_found: + break; + + case InsertionState::new_node: + ::new (static_cast(&mKeyVals[idxAndState.first])) Node( + *this, std::piecewise_construct, std::forward_as_tuple(std::move(key)), + std::forward_as_tuple()); + break; + + case InsertionState::overwrite_node: + mKeyVals[idxAndState.first] = Node( + *this, std::piecewise_construct, std::forward_as_tuple(std::move(key)), + std::forward_as_tuple()); + break; + + case InsertionState::overflow_error: + throwOverflowError(); + } + + return mKeyVals[idxAndState.first].getSecond(); + } + + template + void insert(Iter first, Iter last) + { + for (; first != last; ++first) { + // value_type ctor needed because this might be called with std::pair's + insert(value_type(*first)); + } + } + + void insert(std::initializer_list ilist) + { + for (auto && vt : ilist) { + insert(std::move(vt)); + } + } + + template + std::pair emplace(Args &&... args) + { + ROBIN_HOOD_TRACE(this) + Node n{*this, std::forward(args)...}; + auto idxAndState = insertKeyPrepareEmptySpot(getFirstConst(n)); + switch (idxAndState.second) { + case InsertionState::key_found: + n.destroy(*this); + break; + + case InsertionState::new_node: + ::new (static_cast(&mKeyVals[idxAndState.first])) Node(*this, std::move(n)); + break; + + case InsertionState::overwrite_node: + mKeyVals[idxAndState.first] = std::move(n); + break; + + case InsertionState::overflow_error: + n.destroy(*this); + throwOverflowError(); + break; + } + + return std::make_pair( + iterator(mKeyVals + idxAndState.first, mInfo + idxAndState.first), + InsertionState::key_found != idxAndState.second); + } + + template + iterator emplace_hint(const_iterator position, Args &&... args) + { + (void)position; + return emplace(std::forward(args)...).first; + } + + template + std::pair try_emplace(const key_type & key, Args &&... args) + { + return try_emplace_impl(key, std::forward(args)...); + } + + template + std::pair try_emplace(key_type && key, Args &&... args) + { + return try_emplace_impl(std::move(key), std::forward(args)...); + } + + template + iterator try_emplace(const_iterator hint, const key_type & key, Args &&... args) + { + (void)hint; + return try_emplace_impl(key, std::forward(args)...).first; + } + + template + iterator try_emplace(const_iterator hint, key_type && key, Args &&... args) + { + (void)hint; + return try_emplace_impl(std::move(key), std::forward(args)...).first; + } + + template + std::pair insert_or_assign(const key_type & key, Mapped && obj) + { + return insertOrAssignImpl(key, std::forward(obj)); + } + + template + std::pair insert_or_assign(key_type && key, Mapped && obj) + { + return insertOrAssignImpl(std::move(key), std::forward(obj)); + } + + template + iterator insert_or_assign(const_iterator hint, const key_type & key, Mapped && obj) + { + (void)hint; + return insertOrAssignImpl(key, std::forward(obj)).first; + } + + template + iterator insert_or_assign(const_iterator hint, key_type && key, Mapped && obj) + { + (void)hint; + return insertOrAssignImpl(std::move(key), std::forward(obj)).first; + } + + std::pair insert(const value_type & keyval) + { + ROBIN_HOOD_TRACE(this) + return emplace(keyval); + } + + iterator insert(const_iterator hint, const value_type & keyval) + { + (void)hint; + return emplace(keyval).first; + } + + std::pair insert(value_type && keyval) { return emplace(std::move(keyval)); } + + iterator insert(const_iterator hint, value_type && keyval) + { + (void)hint; + return emplace(std::move(keyval)).first; + } + + // Returns 1 if key is found, 0 otherwise. + size_t count(const key_type & key) const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + auto kv = mKeyVals + findIdx(key); + if (kv != reinterpret_cast_no_cast_align_warning(mInfo)) { + return 1; + } + return 0; + } + + template + // NOLINTNEXTLINE (modernize-use-nodiscard) + typename std::enable_if::type count(const OtherKey & key) const + { + ROBIN_HOOD_TRACE(this) + auto kv = mKeyVals + findIdx(key); + if (kv != reinterpret_cast_no_cast_align_warning(mInfo)) { + return 1; + } + return 0; + } + + bool contains(const key_type & key) const + { // NOLINT (modernize-use-nodiscard) + return 1U == count(key); + } + + template + // NOLINTNEXTLINE (modernize-use-nodiscard) + typename std::enable_if::type contains(const OtherKey & key) const + { + return 1U == count(key); + } + + // Returns a reference to the value found for key. + // Throws std::out_of_range if element cannot be found + template + // NOLINTNEXTLINE (modernize-use-nodiscard) + typename std::enable_if::value, Q &>::type at(key_type const & key) + { + ROBIN_HOOD_TRACE(this) + auto kv = mKeyVals + findIdx(key); + if (kv == reinterpret_cast_no_cast_align_warning(mInfo)) { + doThrow("key not found"); + } + return kv->getSecond(); + } + + // Returns a reference to the value found for key. + // Throws std::out_of_range if element cannot be found + template + // NOLINTNEXTLINE (modernize-use-nodiscard) + typename std::enable_if::value, Q const &>::type at(key_type const & key) const + { + ROBIN_HOOD_TRACE(this) + auto kv = mKeyVals + findIdx(key); + if (kv == reinterpret_cast_no_cast_align_warning(mInfo)) { + doThrow("key not found"); + } + return kv->getSecond(); + } + + const_iterator find(const key_type & key) const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + const size_t idx = findIdx(key); + return const_iterator{mKeyVals + idx, mInfo + idx}; + } + + template + const_iterator find(const OtherKey & key, is_transparent_tag /*unused*/) const + { + ROBIN_HOOD_TRACE(this) + const size_t idx = findIdx(key); + return const_iterator{mKeyVals + idx, mInfo + idx}; + } + + template + typename std::enable_if< + Self_::is_transparent, // NOLINT (modernize-use-nodiscard) + const_iterator>::type // NOLINT (modernize-use-nodiscard) + find(const OtherKey & key) const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + const size_t idx = findIdx(key); + return const_iterator{mKeyVals + idx, mInfo + idx}; + } + + iterator find(const key_type & key) + { + ROBIN_HOOD_TRACE(this) + const size_t idx = findIdx(key); + return iterator{mKeyVals + idx, mInfo + idx}; + } + + template + iterator find(const OtherKey & key, is_transparent_tag /*unused*/) + { + ROBIN_HOOD_TRACE(this) + const size_t idx = findIdx(key); + return iterator{mKeyVals + idx, mInfo + idx}; + } + + template + typename std::enable_if::type find(const OtherKey & key) + { + ROBIN_HOOD_TRACE(this) + const size_t idx = findIdx(key); + return iterator{mKeyVals + idx, mInfo + idx}; + } + + iterator begin() + { + ROBIN_HOOD_TRACE(this) + if (empty()) { + return end(); + } + return iterator(mKeyVals, mInfo, fast_forward_tag{}); + } + const_iterator begin() const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return cbegin(); + } + const_iterator cbegin() const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + if (empty()) { + return cend(); + } + return const_iterator(mKeyVals, mInfo, fast_forward_tag{}); + } + + iterator end() + { + ROBIN_HOOD_TRACE(this) + // no need to supply valid info pointer: end() must not be dereferenced, and only node + // pointer is compared. + return iterator{reinterpret_cast_no_cast_align_warning(mInfo), nullptr}; + } + const_iterator end() const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return cend(); + } + const_iterator cend() const + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return const_iterator{reinterpret_cast_no_cast_align_warning(mInfo), nullptr}; + } + + iterator erase(const_iterator pos) + { + ROBIN_HOOD_TRACE(this) + // its safe to perform const cast here + // NOLINTNEXTLINE (cppcoreguidelines-pro-type-const-cast) + return erase(iterator{const_cast(pos.mKeyVals), const_cast(pos.mInfo)}); + } + + // Erases element at pos, returns iterator to the next element. + iterator erase(iterator pos) + { + ROBIN_HOOD_TRACE(this) + // we assume that pos always points to a valid entry, and not end(). + auto const idx = static_cast(pos.mKeyVals - mKeyVals); + + shiftDown(idx); + --mNumElements; + + if (*pos.mInfo) { + // we've backward shifted, return this again + return pos; + } + + // no backward shift, return next element + return ++pos; + } + + size_t erase(const key_type & key) + { + ROBIN_HOOD_TRACE(this) + size_t idx{}; + InfoType info{}; + keyToIdx(key, &idx, &info); + + // check while info matches with the source idx + do { + if (info == mInfo[idx] && WKeyEqual::operator()(key, mKeyVals[idx].getFirst())) { + shiftDown(idx); + --mNumElements; + return 1; + } + next(&info, &idx); + } while (info <= mInfo[idx]); + + // nothing found to delete + return 0; + } + + // reserves space for the specified number of elements. Makes sure the old data fits. + // exactly the same as reserve(c). + void rehash(size_t c) + { + // forces a reserve + reserve(c, true); + } + + // reserves space for the specified number of elements. Makes sure the old data fits. + // Exactly the same as rehash(c). Use rehash(0) to shrink to fit. + void reserve(size_t c) + { + // reserve, but don't force rehash + reserve(c, false); + } + + // If possible reallocates the map to a smaller one. This frees the underlying table. + // Does not do anything if load_factor is too large for decreasing the table's size. + void compact() + { + ROBIN_HOOD_TRACE(this) + auto newSize = InitialNumElements; + while (calcMaxNumElementsAllowed(newSize) < mNumElements && newSize != 0) { + newSize *= 2; + } + if (ROBIN_HOOD_UNLIKELY(newSize == 0)) { + throwOverflowError(); + } + + ROBIN_HOOD_LOG("newSize > mMask + 1: " << newSize << " > " << mMask << " + 1") + + // only actually do anything when the new size is bigger than the old one. This prevents to + // continuously allocate for each reserve() call. + if (newSize < mMask + 1) { + rehashPowerOfTwo(newSize, true); + } + } + + size_type size() const noexcept + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return mNumElements; + } + + size_type max_size() const noexcept + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return static_cast(-1); + } + + ROBIN_HOOD(NODISCARD) bool empty() const noexcept + { + ROBIN_HOOD_TRACE(this) + return 0 == mNumElements; + } + + float max_load_factor() const noexcept + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return MaxLoadFactor100 / 100.0F; + } + + // Average number of elements per bucket. Since we allow only 1 per bucket + float load_factor() const noexcept + { // NOLINT (modernize-use-nodiscard) + ROBIN_HOOD_TRACE(this) + return static_cast(size()) / static_cast(mMask + 1); + } + + ROBIN_HOOD(NODISCARD) size_t mask() const noexcept + { + ROBIN_HOOD_TRACE(this) + return mMask; + } + + ROBIN_HOOD(NODISCARD) size_t calcMaxNumElementsAllowed(size_t maxElements) const noexcept + { + if (ROBIN_HOOD_LIKELY(maxElements <= (std::numeric_limits::max)() / 100)) { + return maxElements * MaxLoadFactor100 / 100; + } + + // we might be a bit imprecise, but since maxElements is quite large that doesn't matter + return (maxElements / 100) * MaxLoadFactor100; + } + + ROBIN_HOOD(NODISCARD) size_t calcNumBytesInfo(size_t numElements) const noexcept + { + // we add a uint64_t, which houses the sentinel (first byte) and padding so we can load + // 64bit types. + return numElements + sizeof(uint64_t); + } + + ROBIN_HOOD(NODISCARD) + size_t calcNumElementsWithBuffer(size_t numElements) const noexcept + { + auto maxNumElementsAllowed = calcMaxNumElementsAllowed(numElements); + return numElements + (std::min)(maxNumElementsAllowed, (static_cast(0xFF))); + } + + // calculation only allowed for 2^n values + ROBIN_HOOD(NODISCARD) size_t calcNumBytesTotal(size_t numElements) const + { +#if ROBIN_HOOD(BITNESS) == 64 + return numElements * sizeof(Node) + calcNumBytesInfo(numElements); +#else + // make sure we're doing 64bit operations, so we are at least safe against 32bit overflows. + auto const ne = static_cast(numElements); + auto const s = static_cast(sizeof(Node)); + auto const infos = static_cast(calcNumBytesInfo(numElements)); + + auto const total64 = ne * s + infos; + auto const total = static_cast(total64); + + if (ROBIN_HOOD_UNLIKELY(static_cast(total) != total64)) { + throwOverflowError(); + } + return total; +#endif + } + +private: + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::value, bool>::type has(const value_type & e) const + { + ROBIN_HOOD_TRACE(this) + auto it = find(e.first); + return it != end() && it->second == e.second; + } + + template + ROBIN_HOOD(NODISCARD) + typename std::enable_if::value, bool>::type has(const value_type & e) const + { + ROBIN_HOOD_TRACE(this) + return find(e) != end(); + } + + void reserve(size_t c, bool forceRehash) + { + ROBIN_HOOD_TRACE(this) + auto const minElementsAllowed = (std::max)(c, mNumElements); + auto newSize = InitialNumElements; + while (calcMaxNumElementsAllowed(newSize) < minElementsAllowed && newSize != 0) { + newSize *= 2; + } + if (ROBIN_HOOD_UNLIKELY(newSize == 0)) { + throwOverflowError(); + } + + ROBIN_HOOD_LOG("newSize > mMask + 1: " << newSize << " > " << mMask << " + 1") + + // only actually do anything when the new size is bigger than the old one. This prevents to + // continuously allocate for each reserve() call. + if (forceRehash || newSize > mMask + 1) { + rehashPowerOfTwo(newSize, false); + } + } + + // reserves space for at least the specified number of elements. + // only works if numBuckets if power of two + // True on success, false otherwise + void rehashPowerOfTwo(size_t numBuckets, bool forceFree) + { + ROBIN_HOOD_TRACE(this) + + Node * const oldKeyVals = mKeyVals; + uint8_t const * const oldInfo = mInfo; + + const size_t oldMaxElementsWithBuffer = calcNumElementsWithBuffer(mMask + 1); + + // resize operation: move stuff + initData(numBuckets); + if (oldMaxElementsWithBuffer > 1) { + for (size_t i = 0; i < oldMaxElementsWithBuffer; ++i) { + if (oldInfo[i] != 0) { + // might throw an exception, which is really bad since we are in the middle of + // moving stuff. + insert_move(std::move(oldKeyVals[i])); + // destroy the node but DON'T destroy the data. + oldKeyVals[i].~Node(); + } + } + + // this check is not necessary as it's guarded by the previous if, but it helps + // silence g++'s overeager "attempt to free a non-heap object 'map' + // [-Werror=free-nonheap-object]" warning. + if (oldKeyVals != reinterpret_cast_no_cast_align_warning(&mMask)) { + // don't destroy old data: put it into the pool instead + if (forceFree) { + std::free(oldKeyVals); + } else { + DataPool::addOrFree(oldKeyVals, calcNumBytesTotal(oldMaxElementsWithBuffer)); + } + } + } + } + + ROBIN_HOOD(NOINLINE) void throwOverflowError() const + { +#if ROBIN_HOOD(HAS_EXCEPTIONS) + throw std::overflow_error("robin_hood::map overflow"); +#else + abort(); +#endif + } + + template + std::pair try_emplace_impl(OtherKey && key, Args &&... args) + { + ROBIN_HOOD_TRACE(this) + auto idxAndState = insertKeyPrepareEmptySpot(key); + switch (idxAndState.second) { + case InsertionState::key_found: + break; + + case InsertionState::new_node: + ::new (static_cast(&mKeyVals[idxAndState.first])) Node( + *this, std::piecewise_construct, std::forward_as_tuple(std::forward(key)), + std::forward_as_tuple(std::forward(args)...)); + break; + + case InsertionState::overwrite_node: + mKeyVals[idxAndState.first] = Node( + *this, std::piecewise_construct, std::forward_as_tuple(std::forward(key)), + std::forward_as_tuple(std::forward(args)...)); + break; + + case InsertionState::overflow_error: + throwOverflowError(); + break; + } + + return std::make_pair( + iterator(mKeyVals + idxAndState.first, mInfo + idxAndState.first), + InsertionState::key_found != idxAndState.second); + } + + template + std::pair insertOrAssignImpl(OtherKey && key, Mapped && obj) + { + ROBIN_HOOD_TRACE(this) + auto idxAndState = insertKeyPrepareEmptySpot(key); + switch (idxAndState.second) { + case InsertionState::key_found: + mKeyVals[idxAndState.first].getSecond() = std::forward(obj); + break; + + case InsertionState::new_node: + ::new (static_cast(&mKeyVals[idxAndState.first])) Node( + *this, std::piecewise_construct, std::forward_as_tuple(std::forward(key)), + std::forward_as_tuple(std::forward(obj))); + break; + + case InsertionState::overwrite_node: + mKeyVals[idxAndState.first] = Node( + *this, std::piecewise_construct, std::forward_as_tuple(std::forward(key)), + std::forward_as_tuple(std::forward(obj))); + break; + + case InsertionState::overflow_error: + throwOverflowError(); + break; + } + + return std::make_pair( + iterator(mKeyVals + idxAndState.first, mInfo + idxAndState.first), + InsertionState::key_found != idxAndState.second); + } + + void initData(size_t max_elements) + { + mNumElements = 0; + mMask = max_elements - 1; + mMaxNumElementsAllowed = calcMaxNumElementsAllowed(max_elements); + + auto const numElementsWithBuffer = calcNumElementsWithBuffer(max_elements); + + // malloc & zero mInfo. Faster than calloc everything. + auto const numBytesTotal = calcNumBytesTotal(numElementsWithBuffer); + ROBIN_HOOD_LOG( + "std::calloc " << numBytesTotal << " = calcNumBytesTotal(" << numElementsWithBuffer << ")") + mKeyVals = + reinterpret_cast(detail::assertNotNull(std::malloc(numBytesTotal))); + mInfo = reinterpret_cast(mKeyVals + numElementsWithBuffer); + std::memset(mInfo, 0, numBytesTotal - numElementsWithBuffer * sizeof(Node)); + + // set sentinel + mInfo[numElementsWithBuffer] = 1; + + mInfoInc = InitialInfoInc; + mInfoHashShift = InitialInfoHashShift; + } + + enum class InsertionState { overflow_error, key_found, new_node, overwrite_node }; + + // Finds key, and if not already present prepares a spot where to pot the key & value. + // This potentially shifts nodes out of the way, updates mInfo and number of inserted + // elements, so the only operation left to do is create/assign a new node at that spot. + template + std::pair insertKeyPrepareEmptySpot(OtherKey && key) + { + for (int i = 0; i < 256; ++i) { + size_t idx{}; + InfoType info{}; + keyToIdx(key, &idx, &info); + nextWhileLess(&info, &idx); + + // while we potentially have a match + while (info == mInfo[idx]) { + if (WKeyEqual::operator()(key, mKeyVals[idx].getFirst())) { + // key already exists, do NOT insert. + // see http://en.cppreference.com/w/cpp/container/unordered_map/insert + return std::make_pair(idx, InsertionState::key_found); + } + next(&info, &idx); + } + + // unlikely that this evaluates to true + if (ROBIN_HOOD_UNLIKELY(mNumElements >= mMaxNumElementsAllowed)) { + if (!increase_size()) { + return std::make_pair(size_t(0), InsertionState::overflow_error); + } + continue; + } + + // key not found, so we are now exactly where we want to insert it. + auto const insertion_idx = idx; + auto const insertion_info = info; + if (ROBIN_HOOD_UNLIKELY(insertion_info + mInfoInc > 0xFF)) { + mMaxNumElementsAllowed = 0; + } + + // find an empty spot + while (0 != mInfo[idx]) { + next(&info, &idx); + } + + if (idx != insertion_idx) { + shiftUp(idx, insertion_idx); + } + // put at empty spot + mInfo[insertion_idx] = static_cast(insertion_info); + ++mNumElements; + return std::make_pair( + insertion_idx, + idx == insertion_idx ? InsertionState::new_node : InsertionState::overwrite_node); + } + + // enough attempts failed, so finally give up. + return std::make_pair(size_t(0), InsertionState::overflow_error); + } + + bool try_increase_info() + { + ROBIN_HOOD_LOG( + "mInfoInc=" << mInfoInc << ", numElements=" << mNumElements + << ", maxNumElementsAllowed=" << calcMaxNumElementsAllowed(mMask + 1)) + if (mInfoInc <= 2) { + // need to be > 2 so that shift works (otherwise undefined behavior!) + return false; + } + // we got space left, try to make info smaller + mInfoInc = static_cast(mInfoInc >> 1U); + + // remove one bit of the hash, leaving more space for the distance info. + // This is extremely fast because we can operate on 8 bytes at once. + ++mInfoHashShift; + auto const numElementsWithBuffer = calcNumElementsWithBuffer(mMask + 1); + + for (size_t i = 0; i < numElementsWithBuffer; i += 8) { + auto val = unaligned_load(mInfo + i); + val = (val >> 1U) & UINT64_C(0x7f7f7f7f7f7f7f7f); + std::memcpy(mInfo + i, &val, sizeof(val)); + } + // update sentinel, which might have been cleared out! + mInfo[numElementsWithBuffer] = 1; + + mMaxNumElementsAllowed = calcMaxNumElementsAllowed(mMask + 1); + return true; + } + + // True if resize was possible, false otherwise + bool increase_size() + { + // nothing allocated yet? just allocate InitialNumElements + if (0 == mMask) { + initData(InitialNumElements); + return true; + } + + auto const maxNumElementsAllowed = calcMaxNumElementsAllowed(mMask + 1); + if (mNumElements < maxNumElementsAllowed && try_increase_info()) { + return true; + } + + ROBIN_HOOD_LOG( + "mNumElements=" << mNumElements << ", maxNumElementsAllowed=" << maxNumElementsAllowed + << ", load=" + << (static_cast(mNumElements) * 100.0 / + (static_cast(mMask) + 1))) + + if (mNumElements * 2 < calcMaxNumElementsAllowed(mMask + 1)) { + // we have to resize, even though there would still be plenty of space left! + // Try to rehash instead. Delete freed memory so we don't steadily increase mem in case + // we have to rehash a few times + nextHashMultiplier(); + rehashPowerOfTwo(mMask + 1, true); + } else { + // we've reached the capacity of the map, so the hash seems to work nice. Keep using it. + rehashPowerOfTwo((mMask + 1) * 2, false); + } + return true; + } + + void nextHashMultiplier() + { + // adding an *even* number, so that the multiplier will always stay odd. This is necessary + // so that the hash stays a mixing function (and thus doesn't have any information loss). + mHashMultiplier += UINT64_C(0xc4ceb9fe1a85ec54); + } + + void destroy() + { + if (0 == mMask) { + // don't deallocate! + return; + } + + Destroyer::value>{}.nodesDoNotDeallocate( + *this); + + // This protection against not deleting mMask shouldn't be needed as it's sufficiently + // protected with the 0==mMask check, but I have this anyways because g++ 7 otherwise + // reports a compile error: attempt to free a non-heap object 'fm' + // [-Werror=free-nonheap-object] + if (mKeyVals != reinterpret_cast_no_cast_align_warning(&mMask)) { + ROBIN_HOOD_LOG("std::free") + std::free(mKeyVals); + } + } + + void init() noexcept + { + mKeyVals = reinterpret_cast_no_cast_align_warning(&mMask); + mInfo = reinterpret_cast(&mMask); + mNumElements = 0; + mMask = 0; + mMaxNumElementsAllowed = 0; + mInfoInc = InitialInfoInc; + mInfoHashShift = InitialInfoHashShift; + } + + // members are sorted so no padding occurs + uint64_t mHashMultiplier = UINT64_C(0xc4ceb9fe1a85ec53); // 8 byte 8 + Node * mKeyVals = reinterpret_cast_no_cast_align_warning(&mMask); // 8 byte 16 + uint8_t * mInfo = reinterpret_cast(&mMask); // 8 byte 24 + size_t mNumElements = 0; // 8 byte 32 + size_t mMask = 0; // 8 byte 40 + size_t mMaxNumElementsAllowed = 0; // 8 byte 48 + InfoType mInfoInc = InitialInfoInc; // 4 byte 52 + InfoType mInfoHashShift = InitialInfoHashShift; // 4 byte 56 + // 16 byte 56 if NodeAllocator +}; + +} // namespace detail + +// map + +template < + typename Key, typename T, typename Hash = hash, typename KeyEqual = std::equal_to, + size_t MaxLoadFactor100 = 80> +using unordered_flat_map = detail::Table; + +template < + typename Key, typename T, typename Hash = hash, typename KeyEqual = std::equal_to, + size_t MaxLoadFactor100 = 80> +using unordered_node_map = detail::Table; + +template < + typename Key, typename T, typename Hash = hash, typename KeyEqual = std::equal_to, + size_t MaxLoadFactor100 = 80> +using unordered_map = detail::Table< + sizeof(robin_hood::pair) <= sizeof(size_t) * 6 && + std::is_nothrow_move_constructible>::value && + std::is_nothrow_move_assignable>::value, + MaxLoadFactor100, Key, T, Hash, KeyEqual>; + +// set + +template < + typename Key, typename Hash = hash, typename KeyEqual = std::equal_to, + size_t MaxLoadFactor100 = 80> +using unordered_flat_set = detail::Table; + +template < + typename Key, typename Hash = hash, typename KeyEqual = std::equal_to, + size_t MaxLoadFactor100 = 80> +using unordered_node_set = detail::Table; + +template < + typename Key, typename Hash = hash, typename KeyEqual = std::equal_to, + size_t MaxLoadFactor100 = 80> +using unordered_set = detail::Table< + sizeof(Key) <= sizeof(size_t) * 6 && std::is_nothrow_move_constructible::value && + std::is_nothrow_move_assignable::value, + MaxLoadFactor100, Key, void, Hash, KeyEqual>; + +} // namespace robin_hood + +#endif // DOWNSAMPLE_FILTER__ROBIN_HOOD_H_ From 5b1b77622dda686e58c1ef8534096950bdd8ac07 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 23 Apr 2024 09:53:50 +0900 Subject: [PATCH 068/192] feat(tier4_screen_capture_panel): add new service to capture screen shot (#6867) * feat(tier4_screen_capture_panel): add new service to capture screen shot Signed-off-by: satoshi-ota * docs(tier4_screen_capture_rviz_plugin): update readme Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../README.md | 7 +++++++ .../package.xml | 2 ++ .../src/screen_capture_panel.cpp | 20 +++++++++++++++---- .../src/screen_capture_panel.hpp | 8 ++++++-- 4 files changed, 31 insertions(+), 6 deletions(-) diff --git a/common/tier4_screen_capture_rviz_plugin/README.md b/common/tier4_screen_capture_rviz_plugin/README.md index d108d43a5dc41..d16c19c343017 100644 --- a/common/tier4_screen_capture_rviz_plugin/README.md +++ b/common/tier4_screen_capture_rviz_plugin/README.md @@ -4,6 +4,13 @@ This plugin captures the screen of rviz. +## Interface + +| Name | Type | Description | +| ---------------------------- | ------------------------ | ---------------------------------- | +| `/debug/capture/video` | `std_srvs::srv::Trigger` | Trigger to start screen capturing. | +| `/debug/capture/screen_shot` | `std_srvs::srv::Trigger` | Trigger to capture screen shot. | + ## Assumptions / Known limits This is only for debug or analyze. diff --git a/common/tier4_screen_capture_rviz_plugin/package.xml b/common/tier4_screen_capture_rviz_plugin/package.xml index 38479dc3c38ee..180bf9eedc9ca 100644 --- a/common/tier4_screen_capture_rviz_plugin/package.xml +++ b/common/tier4_screen_capture_rviz_plugin/package.xml @@ -5,6 +5,8 @@ 0.0.0 The screen capture package Taiki, Tanaka + Satoshi Ota + Kyoichi Sugahara Apache License 2.0 ament_cmake_auto diff --git a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp index 5ec8f9b02d0e8..cad828903e0d3 100644 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp +++ b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp @@ -81,7 +81,7 @@ AutowareScreenCapturePanel::AutowareScreenCapturePanel(QWidget * parent) state_ = State::WAITING_FOR_CAPTURE; } -void AutowareScreenCapturePanel::onCaptureTrigger( +void AutowareScreenCapturePanel::onCaptureVideoTrigger( [[maybe_unused]] const std_srvs::srv::Trigger::Request::SharedPtr req, const std_srvs::srv::Trigger::Response::SharedPtr res) { @@ -90,12 +90,24 @@ void AutowareScreenCapturePanel::onCaptureTrigger( res->message = stateToString(state_); } +void AutowareScreenCapturePanel::onCaptureScreenShotTrigger( + [[maybe_unused]] const std_srvs::srv::Trigger::Request::SharedPtr req, + const std_srvs::srv::Trigger::Response::SharedPtr res) +{ + onClickScreenCapture(); + res->success = true; + res->message = stateToString(state_); +} + void AutowareScreenCapturePanel::onInitialize() { raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - capture_service_ = raw_node_->create_service( - "/debug/service/capture_screen", - std::bind(&AutowareScreenCapturePanel::onCaptureTrigger, this, _1, _2)); + capture_video_srv_ = raw_node_->create_service( + "/debug/capture/video", + std::bind(&AutowareScreenCapturePanel::onCaptureVideoTrigger, this, _1, _2)); + capture_screen_shot_srv_ = raw_node_->create_service( + "/debug/capture/screen_shot", + std::bind(&AutowareScreenCapturePanel::onCaptureScreenShotTrigger, this, _1, _2)); } void onPrefixChanged() diff --git a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp index 8ddd390206b81..5c4d16f57da82 100644 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp +++ b/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp @@ -60,7 +60,10 @@ class AutowareScreenCapturePanel : public rviz_common::Panel void onTimer(); void save(rviz_common::Config config) const override; void load(const rviz_common::Config & config) override; - void onCaptureTrigger( + void onCaptureVideoTrigger( + const std_srvs::srv::Trigger::Request::SharedPtr req, + const std_srvs::srv::Trigger::Response::SharedPtr res); + void onCaptureScreenShotTrigger( const std_srvs::srv::Trigger::Request::SharedPtr req, const std_srvs::srv::Trigger::Response::SharedPtr res); @@ -98,7 +101,8 @@ public Q_SLOTS: } protected: - rclcpp::Service::SharedPtr capture_service_; + rclcpp::Service::SharedPtr capture_video_srv_; + rclcpp::Service::SharedPtr capture_screen_shot_srv_; rclcpp::Node::SharedPtr raw_node_; }; From 702b183b2889f458bd5086231d76ac9f6eff4424 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 23 Apr 2024 13:13:26 +0900 Subject: [PATCH 069/192] feat(bpp-interface): add empty path validation (#6868) Signed-off-by: satoshi-ota --- .../interface/scene_module_interface.hpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index a2481040f7548..4947a1b544302 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -141,7 +141,13 @@ class SceneModuleInterface virtual BehaviorModuleOutput run() { updateData(); - return isWaitingApproval() ? planWaitingApproval() : plan(); + const auto output = isWaitingApproval() ? planWaitingApproval() : plan(); + try { + motion_utils::validateNonEmpty(output.path.points); + } catch (const std::exception & ex) { + throw std::invalid_argument("[" + name_ + "]" + ex.what()); + } + return output; } /** From 5a6cde954790dc744b2ec10e88749437e8b57f9e Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 23 Apr 2024 13:21:09 +0900 Subject: [PATCH 070/192] refactor(bpp): simplify extended predicted object initialization (#6858) * refactor(bpp): simplify extended predicted object initialization Signed-off-by: Muhammad Zulfaqar Azmi * Update planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../src/utils/utils.cpp | 7 +------ .../path_safety_checker_parameters.hpp | 12 ++++++++++++ .../utils/path_safety_checker/objects_filtering.cpp | 8 +------- 3 files changed, 14 insertions(+), 13 deletions(-) diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 97a5ae732ec1b..c401d59f6b71d 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -1112,12 +1112,7 @@ ExtendedPredictedObject transform( [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase) { - ExtendedPredictedObject extended_object; - extended_object.uuid = object.object_id; - extended_object.initial_pose = object.kinematics.initial_pose_with_covariance; - extended_object.initial_twist = object.kinematics.initial_twist_with_covariance; - extended_object.initial_acceleration = object.kinematics.initial_acceleration_with_covariance; - extended_object.shape = object.shape; + ExtendedPredictedObject extended_object(object); const auto & time_resolution = lane_change_parameters.prediction_time_resolution; const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp index b3c8034a3545c..d83c748f214b4 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp @@ -31,6 +31,7 @@ namespace behavior_path_planner::utils::path_safety_checker { +using autoware_auto_perception_msgs::msg::PredictedObject; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using tier4_autoware_utils::Polygon2d; @@ -79,6 +80,17 @@ struct ExtendedPredictedObject autoware_auto_perception_msgs::msg::Shape shape; std::vector classification; std::vector predicted_paths; + + ExtendedPredictedObject() = default; + explicit ExtendedPredictedObject(const PredictedObject & object) + : uuid(object.object_id), + initial_pose(object.kinematics.initial_pose_with_covariance), + initial_twist(object.kinematics.initial_twist_with_covariance), + initial_acceleration(object.kinematics.initial_acceleration_with_covariance), + shape(object.shape), + classification(object.classification) + { + } }; using ExtendedPredictedObjects = std::vector; diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 91d743df11ca2..b8014deee9500 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -289,13 +289,7 @@ ExtendedPredictedObject transform( const PredictedObject & object, const double safety_check_time_horizon, const double safety_check_time_resolution) { - ExtendedPredictedObject extended_object; - extended_object.uuid = object.object_id; - extended_object.initial_pose = object.kinematics.initial_pose_with_covariance; - extended_object.initial_twist = object.kinematics.initial_twist_with_covariance; - extended_object.initial_acceleration = object.kinematics.initial_acceleration_with_covariance; - extended_object.shape = object.shape; - extended_object.classification = object.classification; + ExtendedPredictedObject extended_object(object); const auto obj_velocity = extended_object.initial_twist.twist.linear.x; From 8881d23d1bb666a8fab913e7c30e60b9b4a2b5b5 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 24 Apr 2024 10:16:42 +0900 Subject: [PATCH 071/192] chore(roi_pointcloud_fusion): add maximum cluster size param (#6860) Signed-off-by: badai-nguyen --- .../config/roi_pointcloud_fusion.param.yaml | 1 + .../docs/roi-pointcloud-fusion.md | 1 + .../roi_pointcloud_fusion/node.hpp | 1 + .../include/image_projection_based_fusion/utils/utils.hpp | 4 ++-- .../schema/roi_pointcloud_fusion.schema.json | 5 +++++ .../src/roi_pointcloud_fusion/node.cpp | 7 +++++-- .../image_projection_based_fusion/src/utils/utils.cpp | 8 +++++--- 7 files changed, 20 insertions(+), 7 deletions(-) diff --git a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml index 5b86b8e81d1aa..acf5f75163ffe 100644 --- a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml @@ -2,4 +2,5 @@ ros__parameters: fuse_unknown_only: true min_cluster_size: 2 + max_cluster_size: 20 cluster_2d_tolerance: 0.5 diff --git a/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md b/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md index 5d0b241a578d6..f2ce7662da976 100644 --- a/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md @@ -37,6 +37,7 @@ The node `roi_pointcloud_fusion` is to cluster the pointcloud based on Region Of | Name | Type | Description | | ---------------------- | ------ | -------------------------------------------------------------------------------------------- | | `min_cluster_size` | int | the minimum number of points that a cluster needs to contain in order to be considered valid | +| `max_cluster_size` | int | the maximum number of points that a cluster needs to contain in order to be considered valid | | `cluster_2d_tolerance` | double | cluster tolerance measured in radial direction | | `rois_number` | int | the number of input rois | diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index fe685baa0b6e2..4cbc0990352e6 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -26,6 +26,7 @@ class RoiPointCloudFusionNode { private: int min_cluster_size_{1}; + int max_cluster_size_{20}; bool fuse_unknown_only_{true}; double cluster_2d_tolerance_; diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp index d7fd3c3882046..943f028621189 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp @@ -70,8 +70,8 @@ PointCloud closest_cluster( void updateOutputFusedObjects( std::vector & output_objs, const std::vector & clusters, const std_msgs::msg::Header & in_cloud_header, const std_msgs::msg::Header & in_roi_header, - const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const float cluster_2d_tolerance, - std::vector & output_fused_objects); + const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const int max_cluster_size, + const float cluster_2d_tolerance, std::vector & output_fused_objects); geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud); diff --git a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json index f39ef257ea789..9dba97a2029ee 100644 --- a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json @@ -16,6 +16,11 @@ "description": "The minimum number of points that a cluster must contain to be considered as valid.", "default": 2 }, + "max_cluster_size": { + "type": "integer", + "description": "The maximum number of points that a cluster must contain to be considered as valid.", + "default": 20 + }, "cluster_2d_tolerance": { "type": "number", "description": "A cluster tolerance measured in radial direction [m]", diff --git a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 421aa3a453451..af04d174ba661 100644 --- a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -35,6 +35,7 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt { fuse_unknown_only_ = declare_parameter("fuse_unknown_only"); min_cluster_size_ = declare_parameter("min_cluster_size"); + max_cluster_size_ = declare_parameter("max_cluster_size"); cluster_2d_tolerance_ = declare_parameter("cluster_2d_tolerance"); pub_objects_ptr_ = this->create_publisher("output_clusters", rclcpp::QoS{1}); @@ -138,7 +139,9 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( auto & feature_obj = output_objs.at(i); const auto & check_roi = feature_obj.feature.roi; auto & cluster = clusters.at(i); - + if (cluster.points.size() >= static_cast(max_cluster_size_)) { + continue; + } if ( check_roi.x_offset <= normalized_projected_point.x() && check_roi.y_offset <= normalized_projected_point.y() && @@ -152,7 +155,7 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( // refine and update output_fused_objects_ updateOutputFusedObjects( output_objs, clusters, input_pointcloud_msg.header, input_roi_msg.header, tf_buffer_, - min_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); + min_cluster_size_, max_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); } bool RoiPointCloudFusionNode::out_of_scope(__attribute__((unused)) diff --git a/perception/image_projection_based_fusion/src/utils/utils.cpp b/perception/image_projection_based_fusion/src/utils/utils.cpp index 76cd1e3c61e82..e978b5ab55868 100644 --- a/perception/image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/image_projection_based_fusion/src/utils/utils.cpp @@ -83,8 +83,8 @@ PointCloud closest_cluster( void updateOutputFusedObjects( std::vector & output_objs, const std::vector & clusters, const std_msgs::msg::Header & in_cloud_header, const std_msgs::msg::Header & in_roi_header, - const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const float cluster_2d_tolerance, - std::vector & output_fused_objects) + const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const int max_cluster_size, + const float cluster_2d_tolerance, std::vector & output_fused_objects) { if (output_objs.size() != clusters.size()) { return; @@ -107,7 +107,9 @@ void updateOutputFusedObjects( for (std::size_t i = 0; i < output_objs.size(); ++i) { PointCloud cluster = clusters.at(i); auto & feature_obj = output_objs.at(i); - if (cluster.points.size() < std::size_t(min_cluster_size)) { + if ( + cluster.points.size() < std::size_t(min_cluster_size) || + cluster.points.size() >= std::size_t(max_cluster_size)) { continue; } From 645981641a3d12b2d3cd93d6a083bee846aa9513 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 24 Apr 2024 11:51:45 +0900 Subject: [PATCH 072/192] feat(perception_evaluator): counts objects within detection range (#6848) * feat(perception_evaluator): counts objects within detection range Signed-off-by: kosuke55 detection counter Signed-off-by: kosuke55 add enable option and refactoring Signed-off-by: kosuke55 fix update document Signed-off-by: kosuke55 readme Signed-off-by: kosuke55 clean up Signed-off-by: kosuke55 * fix from review Signed-off-by: kosuke55 * use $ Signed-off-by: kosuke55 fix Signed-off-by: kosuke55 * fix include Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../CMakeLists.txt | 3 +- .../perception_online_evaluator/README.md | 90 +++- .../images/detection_counts.drawio.svg | 445 ++++++++++++++++++ .../images/yaw_rate.drawio.svg | 172 ++++++- .../metrics/detection_count.hpp | 149 ++++++ .../metrics/metric.hpp | 10 +- .../metrics_calculator.hpp | 19 +- .../parameters.hpp | 12 +- .../perception_online_evaluator_node.hpp | 1 + .../perception_online_evaluator.defaults.yaml | 70 ++- .../src/metrics/detection_count.cpp | 234 +++++++++ .../src/metrics_calculator.cpp | 137 ++++-- .../src/perception_online_evaluator_node.cpp | 98 ++-- .../src/utils/objects_filtering.cpp | 44 -- .../test_perception_online_evaluator_node.cpp | 404 +++++++++++++++- 15 files changed, 1697 insertions(+), 191 deletions(-) create mode 100644 evaluator/perception_online_evaluator/images/detection_counts.drawio.svg create mode 100644 evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp create mode 100644 evaluator/perception_online_evaluator/src/metrics/detection_count.cpp diff --git a/evaluator/perception_online_evaluator/CMakeLists.txt b/evaluator/perception_online_evaluator/CMakeLists.txt index e1cd0546ea94a..3d967ea6d86ce 100644 --- a/evaluator/perception_online_evaluator/CMakeLists.txt +++ b/evaluator/perception_online_evaluator/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME}_node SHARED src/metrics_calculator.cpp src/${PROJECT_NAME}_node.cpp src/metrics/deviation_metrics.cpp + src/metrics/detection_count.cpp src/utils/marker_utils.cpp src/utils/objects_filtering.cpp ) @@ -31,7 +32,7 @@ target_link_libraries(${PROJECT_NAME}_node glog::glog) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_perception_online_evaluator_node.cpp - TIMEOUT 180 + TIMEOUT 300 ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}_node diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index fd8aee9766308..7ee93d2ffddf2 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -15,6 +15,9 @@ The evaluated metrics are as follows: - lateral_deviation - yaw_deviation - yaw_rate +- total_objects_count +- average_objects_count +- interval_objects_count ### Predicted Path Deviation / Predicted Path Deviation Variance @@ -89,6 +92,67 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p ![yaw_rate](./images/yaw_rate.drawio.svg) +### Object Counts + +Counts the number of detections for each object class within the specified detection range. These metrics are measured for the most recent object not past objects. + +![detection_counts](./images/detection_counts.drawio.svg) + +In the provided illustration, the range $R$ is determined by a combination of lists of radii (e.g., $r_1, r_2, \ldots$) and heights (e.g., $h_1, h_2, \ldots$). +For example, + +- the number of CAR in range $R = (r_1, h_1)$ equals 1 +- the number of CAR in range $R = (r_1, h_2)$ equals 2 +- the number of CAR in range $R = (r_2, h_1)$ equals 3 +- the number of CAR in range $R = (r_2, h_2)$ equals 4 + +#### Total Object Count + +Counts the number of unique objects for each class within the specified detection range. The total object count is calculated as follows: + +$$ +\begin{align} +\text{Total Object Count (Class, Range)} = \left| \bigcup_{t=0}^{T_{\text{now}}} \{ \text{uuid} \mid \text{class}(t, \text{uuid}) = C \wedge \text{position}(t, \text{uuid}) \in R \} \right| +\end{align} +$$ + +where: + +- $\bigcup$ represents the union across all frames from $t = 0$ to $T_{\text{now}}$, which ensures that each uuid is counted only once. +- $\text{class}(t, \text{uuid}) = C$ specifies that the object with uuid at time $t$ belongs to class $C$. +- $\text{position}(t, \text{uuid}) \in R$ indicates that the object with uuid at time $t$ is within the specified range $R$. +- $\left| \{ \ldots \} \right|$ denotes the cardinality of the set, which counts the number of unique uuids that meet the class and range criteria across all considered times. + +#### Average Object Count + +Counts the average number of objects for each class within the specified detection range. This metric measures how many objects were detected in one frame, without considering uuids. The average object count is calculated as follows: + +$$ +\begin{align} +\text{Average Object Count (Class, Range)} = \frac{1}{N} \sum_{t=0}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right| +\end{align} +$$ + +where: + +- $N$ represents the total number of frames within the time period time to $T\_{\text{now}}$ (it is precisely `detection_count_purge_seconds`) +- $text{object}$ denotes the number of objects that meet the class and range criteria at time $t$. + +#### Interval Object Count + +Counts the average number of objects for each class within the specified detection range over the last `objects_count_window_seconds`. This metric measures how many objects were detected in one frame, without considering uuids. The interval object count is calculated as follows: + +$$ +\begin{align} +\text{Interval Object Count (Class, Range)} = \frac{1}{W} \sum_{t=T_{\text{now}} - T_W}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right| +\end{align} +$$ + +where: + +- $W$ represents the total number of frames within the last `objects_count_window_seconds`. +- $T_W$ represents the time window `objects_count_window_seconds` + ## Inputs / Outputs | Name | Type | Description | @@ -99,14 +163,24 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p ## Parameters -| Name | Type | Description | -| --------------------------------- | ------------ | ------------------------------------------------------------------------------------------------ | -| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. | -| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. | -| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. | -| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped | -| `target_object.*.check_deviation` | bool | Whether to check deviation for specific object types (car, truck, etc.). | -| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). | +| Name | Type | Description | +| ------------------------------------------------------ | ------------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. | +| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. | +| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. | +| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped | +| `detection_radius_list` | list[double] | Detection radius for objects to be evaluated.(used for objects count only) | +| `detection_height_list` | list[double] | Detection height for objects to be evaluated. (used for objects count only) | +| `detection_count_purge_seconds` | double | Time window for purging object detection counts. | +| `objects_count_window_seconds` | double | Time window for keeping object detection counts. The number of object detections within this time window is stored in `detection_count_vector_` | +| `target_object.*.check_lateral_deviation` | bool | Whether to check lateral deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_yaw_deviation` | bool | Whether to check yaw deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_predicted_path_deviation` | bool | Whether to check predicted path deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_yaw_rate` | bool | Whether to check yaw rate for specific object types (car, truck, etc.). | +| `target_object.*.check_total_objects_count` | bool | Whether to check total object count for specific object types (car, truck, etc.). | +| `target_object.*.check_average_objects_count` | bool | Whether to check average object count for specific object types (car, truck, etc.). | +| `target_object.*.check_interval_average_objects_count` | bool | Whether to check interval average object count for specific object types (car, truck, etc.). | +| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). | ## Assumptions / Known limits diff --git a/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg b/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg new file mode 100644 index 0000000000000..f6dc7431e7ae6 --- /dev/null +++ b/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg @@ -0,0 +1,445 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `r_2` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `r_1` +
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `h_1` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `h_2` +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
diff --git a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg index 20587ec30d683..eeabd7dca8d43 100644 --- a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg +++ b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg @@ -5,10 +5,10 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="283px" + width="365px" height="77px" - viewBox="-0.5 -0.5 283 77" - content="<mxfile host="app.diagrams.net" modified="2024-04-15T16:43:48.109Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/122.0.0.0 Safari/537.36" version="24.2.5" etag="-1Cxl0cC8cre4wtqPdY1" type="google" scale="1" border="0"> <diagram name="ページ1" id="hj15VFmwux7EVVTqehov"> <mxGraphModel dx="-203" dy="1514" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="0" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="1" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-180;" vertex="1" parent="1"> <mxGeometry x="955" y="-534" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="3" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-210;" vertex="1" parent="1"> <mxGeometry x="1120" y="-540" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="4" value="`t_2`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1120" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="5" value="`t_1`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="955" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="6" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="967" y="-520" as="sourcePoint" /> <mxPoint x="1030" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="7" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1189" y="-551" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;dashed=1;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1197" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="9" value="" style="endArrow=classic;html=1;rounded=0;curved=1;endFill=1;endSize=2;strokeColor=#000000;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1181" y="-520" as="sourcePoint" /> <mxPoint x="1178" y="-545" as="targetPoint" /> <Array as="points"> <mxPoint x="1182" y="-533" /> </Array> </mxGeometry> </mxCell> <mxCell id="10" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\Deltayaw`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1168" y="-549" width="70" height="30" as="geometry" /> </mxCell> <mxCell id="11" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1060" y="-519.92" as="sourcePoint" /> <mxPoint x="1095" y="-519.92" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + viewBox="-0.5 -0.5 365 77" + content="<mxfile host="app.diagrams.net" modified="2024-04-18T12:50:45.453Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/122.0.0.0 Safari/537.36" version="24.2.5" etag="KrfeBttdqJpC7U2PhJCb" type="google" scale="1" border="0"> <diagram name="ページ1" id="3M-pu1oXXIi-LJN1ZMRq"> <mxGraphModel dx="722" dy="2026" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="0" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="1" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-180;" vertex="1" parent="1"> <mxGeometry x="955" y="-534" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="3" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-210;" vertex="1" parent="1"> <mxGeometry x="1120" y="-540" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="4" value="`t_2`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1120" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="5" value="`t_1`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="955" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="6" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="967" y="-520" as="sourcePoint" /> <mxPoint x="1030" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="7" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1189" y="-551" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;dashed=1;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1197" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="9" value="" style="endArrow=classic;html=1;rounded=0;curved=1;endFill=1;endSize=2;strokeColor=#000000;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1181" y="-520" as="sourcePoint" /> <mxPoint x="1178" y="-545" as="targetPoint" /> <Array as="points"> <mxPoint x="1182" y="-533" /> </Array> </mxGeometry> </mxCell> <mxCell id="10" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\Deltayaw`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1168" y="-549" width="70" height="30" as="geometry" /> </mxCell> <mxCell id="11" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\omega_{yaw} = (\Delta yaw) / (t2-t1)`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1130" y="-511" width="190" height="30" as="geometry" /> </mxCell> <mxCell id="12" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1060" y="-519.92" as="sourcePoint" /> <mxPoint x="1095" y="-519.92" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " > + + + + + + + + + + + + + + + + diff --git a/localization/autoware_pose_covariance_modifier/launch/pose_covariance_modifier.launch.xml b/localization/autoware_pose_covariance_modifier/launch/pose_covariance_modifier.launch.xml new file mode 100755 index 0000000000000..0395496ae0b78 --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/launch/pose_covariance_modifier.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/localization/autoware_pose_covariance_modifier/package.xml b/localization/autoware_pose_covariance_modifier/package.xml new file mode 100644 index 0000000000000..c6c5a49f991dd --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/package.xml @@ -0,0 +1,24 @@ + + + + autoware_pose_covariance_modifier + 1.0.0 + Add a description. + + Melike Tanrikulu + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + geometry_msgs + interpolation + rclcpp + rclcpp_components + std_msgs + + + ament_cmake + + diff --git a/localization/autoware_pose_covariance_modifier/schema/pose_covariance_modifier.schema.json b/localization/autoware_pose_covariance_modifier/schema/pose_covariance_modifier.schema.json new file mode 100644 index 0000000000000..02cf301d731b1 --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/schema/pose_covariance_modifier.schema.json @@ -0,0 +1,73 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Pose Covariance Modifier Node Parameters", + "type": "object", + "actual_parameters": { + "type": "object", + "properties": { + "threshold_gnss_stddev_yaw_deg_max": { + "type": "number", + "default": 0.3, + "description": "If GNSS yaw standard deviation values are larger than this, trust only NDT" + }, + "threshold_gnss_stddev_z_max": { + "type": "number", + "default": 0.1, + "description": "If GNSS position Z standard deviation values are larger than this, trust only NDT" + }, + "threshold_gnss_stddev_xy_bound_lower": { + "type": "number", + "default": 0.1, + "description": "If GNSS position XY standard deviation values are lower than this, trust only GNSS" + }, + "threshold_gnss_stddev_xy_bound_upper": { + "type": "number", + "default": 0.25, + "description": "If GNSS position XY standard deviation values are higher than this, trust only NDT" + }, + "ndt_std_dev_bound_lower": { + "type": "number", + "default": 0.15, + "description": "Lower bound value for standard deviation of NDT positions (x, y, z) when used with GNSS" + }, + "ndt_std_dev_bound_upper": { + "type": "number", + "default": 0.3, + "description": "Upper bound value for standard deviation of NDT positions (x, y, z) when used with GNSS" + }, + "gnss_pose_timeout_sec": { + "type": "number", + "default": 1.0, + "description": "If GNSS data is not received for this duration, trust only NDT" + }, + "enable_debug_topics": { + "type": "boolean", + "default": true, + "description": "Publish additional debug topics" + } + }, + "required": [ + "threshold_gnss_stddev_yaw_deg_max", + "threshold_gnss_stddev_z_max", + "threshold_gnss_stddev_xy_bound_lower", + "threshold_gnss_stddev_xy_bound_upper", + "gnss_pose_timeout_sec", + "enable_debug_topics" + ], + "additionalProperties": false + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/actual_parameters" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/localization/autoware_pose_covariance_modifier/src/include/pose_covariance_modifier.hpp b/localization/autoware_pose_covariance_modifier/src/include/pose_covariance_modifier.hpp new file mode 100644 index 0000000000000..ffafe41269468 --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/src/include/pose_covariance_modifier.hpp @@ -0,0 +1,86 @@ +// Copyright 2024 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef POSE_COVARIANCE_MODIFIER_HPP_ +#define POSE_COVARIANCE_MODIFIER_HPP_ + +#include + +#include +#include +#include + +namespace autoware::pose_covariance_modifier +{ +class PoseCovarianceModifierNode : public rclcpp::Node +{ +public: + explicit PoseCovarianceModifierNode(const rclcpp::NodeOptions & node_options); + + enum class PoseSource { + GNSS = 0, + GNSS_NDT = 1, + NDT = 2, + }; + +private: + // covariance matrix indexes + const int X_POS_IDX_ = 0; + const int Y_POS_IDX_ = 7; + const int Z_POS_IDX_ = 14; + const int YAW_POS_IDX_ = 35; + + // parameters + double threshold_gnss_stddev_yaw_deg_max_; + double threshold_gnss_stddev_z_max_; + double threshold_gnss_stddev_xy_bound_lower_; + double threshold_gnss_stddev_xy_bound_upper_; + double ndt_std_dev_bound_lower_; + double ndt_std_dev_bound_upper_; + double gnss_pose_timeout_sec_; + bool debug_mode_; + + rclcpp::Time gnss_pose_received_time_last_; + geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr gnss_pose_with_cov_last_; + PoseSource pose_source_; + + rclcpp::Subscription::SharedPtr + sub_gnss_pose_with_cov_; + rclcpp::Subscription::SharedPtr + sub_ndt_pose_with_cov_; + rclcpp::Publisher::SharedPtr + pub_pose_with_covariance_stamped_; + rclcpp::Publisher::SharedPtr pub_str_pose_source_; + rclcpp::Publisher::SharedPtr pub_double_ndt_position_stddev_; + rclcpp::Publisher::SharedPtr pub_double_gnss_position_stddev_; + + void callback_gnss_pose_with_cov( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg); + + void callback_ndt_pose_with_cov( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg_pose_with_cov_in); + + bool gnss_pose_has_timed_out(const rclcpp::Time & gnss_pose_received_time_last); + + PoseSource pose_source_from_gnss_stddev( + double gnss_pose_yaw_stddev_deg, double gnss_pose_stddev_z, double gnss_pose_stddev_xy) const; + + std::array update_ndt_covariances_from_gnss( + const std::array & ndt_covariance_in); + + void publish_pose_type(const PoseSource & pose_source); +}; + +} // namespace autoware::pose_covariance_modifier + +#endif // POSE_COVARIANCE_MODIFIER_HPP_ diff --git a/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp b/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp new file mode 100644 index 0000000000000..bb811c55d585d --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp @@ -0,0 +1,246 @@ +// Copyright 2024 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "include/pose_covariance_modifier.hpp" + +#include +#include + +#include +#include +#include + +namespace autoware::pose_covariance_modifier +{ +using PoseSource = PoseCovarianceModifierNode::PoseSource; + +PoseCovarianceModifierNode::PoseCovarianceModifierNode(const rclcpp::NodeOptions & node_options) +: Node("PoseCovarianceModifierNode", node_options), + gnss_pose_received_time_last_(this->now()), + pose_source_(PoseSource::NDT) +{ + // parameters + threshold_gnss_stddev_yaw_deg_max_ = + this->declare_parameter("threshold_gnss_stddev_yaw_deg_max"); + threshold_gnss_stddev_z_max_ = this->declare_parameter("threshold_gnss_stddev_z_max"); + threshold_gnss_stddev_xy_bound_lower_ = + this->declare_parameter("threshold_gnss_stddev_xy_bound_lower"); + threshold_gnss_stddev_xy_bound_upper_ = + this->declare_parameter("threshold_gnss_stddev_xy_bound_upper"); + ndt_std_dev_bound_lower_ = this->declare_parameter("ndt_std_dev_bound_lower"); + ndt_std_dev_bound_upper_ = this->declare_parameter("ndt_std_dev_bound_upper"); + gnss_pose_timeout_sec_ = this->declare_parameter("gnss_pose_timeout_sec"); + debug_mode_ = this->declare_parameter("enable_debug_topics"); + + // subscribers + sub_gnss_pose_with_cov_ = + this->create_subscription( + "input_gnss_pose_with_cov_topic", 10, + std::bind( + &PoseCovarianceModifierNode::callback_gnss_pose_with_cov, this, std::placeholders::_1)); + + sub_ndt_pose_with_cov_ = this->create_subscription( + "input_ndt_pose_with_cov_topic", 10, + std::bind( + &PoseCovarianceModifierNode::callback_ndt_pose_with_cov, this, std::placeholders::_1)); + + // publishers + pub_pose_with_covariance_stamped_ = + this->create_publisher( + "output_pose_with_covariance_topic", 10); + + pub_str_pose_source_ = this->create_publisher("~/selected_pose_type", 10); + + if (debug_mode_) { + pub_double_ndt_position_stddev_ = + this->create_publisher("~/debug/ndt_position_stddev", 10); + pub_double_gnss_position_stddev_ = + this->create_publisher("~/debug/gnss_position_stddev", 10); + } +} + +void PoseCovarianceModifierNode::callback_gnss_pose_with_cov( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg_pose_with_cov_in) +{ + // will be used to check if GNSS pose has timed out in the NDT pose callback + gnss_pose_received_time_last_ = this->now(); + + // if the pose source is not GNSS, it will be used to calculate the NDT covariance in the NDT pose + // callback + gnss_pose_with_cov_last_ = msg_pose_with_cov_in; + + const double gnss_pose_yaw_stddev_deg = + std::sqrt(msg_pose_with_cov_in->pose.covariance[YAW_POS_IDX_]) * 180 / M_PI; + + const double gnss_pose_stddev_z = std::sqrt(msg_pose_with_cov_in->pose.covariance[Z_POS_IDX_]); + + const double gnss_pose_stddev_xy = + (std::sqrt(msg_pose_with_cov_in->pose.covariance[X_POS_IDX_]) + + std::sqrt(msg_pose_with_cov_in->pose.covariance[Y_POS_IDX_])) / + 2; + + pose_source_ = + pose_source_from_gnss_stddev(gnss_pose_yaw_stddev_deg, gnss_pose_stddev_z, gnss_pose_stddev_xy); + publish_pose_type(pose_source_); + + if (pose_source_ == PoseSource::NDT) { + // if the pose source is only NDT, don't publish GNSS poses + return; + } + + pub_pose_with_covariance_stamped_->publish(*msg_pose_with_cov_in); + + if (debug_mode_) { + std_msgs::msg::Float64 msg_double; + msg_double.data = gnss_pose_stddev_xy; + pub_double_gnss_position_stddev_->publish(msg_double); + } +} + +void PoseCovarianceModifierNode::callback_ndt_pose_with_cov( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr & msg_pose_with_cov_in) +{ + if (pose_source_ == PoseSource::GNSS) { + // if the pose source is only gnss, GNSS pose will be used in the GNSS pose callback + return; + } + geometry_msgs::msg::PoseWithCovarianceStamped msg_pose_with_cov_out; + + // pose_source_ was determined in the GNSS callback + if (gnss_pose_has_timed_out(gnss_pose_received_time_last_) || pose_source_ == PoseSource::NDT) { + msg_pose_with_cov_out = *msg_pose_with_cov_in; + } else if (pose_source_ == PoseSource::GNSS_NDT) { + auto ndt_pose_with_cov_updated = *msg_pose_with_cov_in; + ndt_pose_with_cov_updated.pose.covariance = + update_ndt_covariances_from_gnss(msg_pose_with_cov_in->pose.covariance); + msg_pose_with_cov_out = ndt_pose_with_cov_updated; + } + + pub_pose_with_covariance_stamped_->publish(msg_pose_with_cov_out); + + if (debug_mode_) { + std_msgs::msg::Float64 msg_double; + msg_double.data = (std::sqrt(msg_pose_with_cov_out.pose.covariance[X_POS_IDX_]) + + std::sqrt(msg_pose_with_cov_out.pose.covariance[Y_POS_IDX_])) / + 2.0; + pub_double_ndt_position_stddev_->publish(msg_double); + } +} + +bool PoseCovarianceModifierNode::gnss_pose_has_timed_out( + const rclcpp::Time & gnss_pose_received_time_last) +{ + auto duration = this->now() - gnss_pose_received_time_last; + if (duration.seconds() > gnss_pose_timeout_sec_) { + RCLCPP_WARN(this->get_logger(), "GNSS pose has timed out"); + return true; + } + return false; +} + +PoseSource PoseCovarianceModifierNode::pose_source_from_gnss_stddev( + const double gnss_pose_yaw_stddev_deg, const double gnss_pose_stddev_z, + const double gnss_pose_stddev_xy) const +{ + // If the GNSS pose z or yaw has a high standard deviation, use NDT pose + if ( + gnss_pose_yaw_stddev_deg > threshold_gnss_stddev_yaw_deg_max_ || + gnss_pose_stddev_z > threshold_gnss_stddev_z_max_) { + return PoseSource::NDT; + } + if (gnss_pose_stddev_xy <= threshold_gnss_stddev_xy_bound_lower_) { + return PoseSource::GNSS; + } + if (gnss_pose_stddev_xy <= threshold_gnss_stddev_xy_bound_upper_) { + return PoseSource::GNSS_NDT; + } + // If the gnss xy standard deviation is above the upper bound, use NDT pose + return PoseSource::NDT; +} + +std::array PoseCovarianceModifierNode::update_ndt_covariances_from_gnss( + const std::array & ndt_covariance_in) +{ + // See the ../README.md#NDT-covariance-calculation for detailed explanation + + auto lerp_range_to_range = [](double x, double x_min, double x_max, double y_min, double y_max) { + // Normalize input value to range [0, 1] + const double input_normalized = (x - x_min) / (x_max - x_min); + + // Interpolate to the output range + return interpolation::lerp(y_min, y_max, input_normalized); + }; + + auto ndt_variance_from_gnss_variance = [&](double ndt_variance, double gnss_variance) { + // Check NDT stddev bound values. + double ndt_stddev = std::sqrt(ndt_variance); + if (ndt_stddev > ndt_std_dev_bound_upper_ || ndt_stddev < ndt_std_dev_bound_lower_) { + RCLCPP_ERROR( + get_logger(), + "Input variance of NDT exceeds bound values. Variance values of NDT were not modified. " + "Check your bound values for NDT stddev."); + return ndt_variance; + } + // calculate NDT covariance value based on gnss covariance + const double gnss_std_dev = std::sqrt(gnss_variance); + + // interpolate the gnss_std_dev from gnss ranges to ndt ranges + const double interpolated_std_dev = lerp_range_to_range( + gnss_std_dev, threshold_gnss_stddev_xy_bound_lower_, threshold_gnss_stddev_xy_bound_upper_, + ndt_std_dev_bound_lower_, ndt_std_dev_bound_upper_); + + // As the gnss error increases, the ndt error should decrease + const double reversed_std_dev = + ndt_std_dev_bound_lower_ + ndt_std_dev_bound_upper_ - interpolated_std_dev; + + const double interpolated_variance = std::pow(reversed_std_dev, 2); + + // Make sure the ndt covariance is not below the lower bounds of ndt covariance value and return + return (std::max(interpolated_variance, std::pow(ndt_std_dev_bound_lower_, 2))); + }; + + std::array ndt_covariance = ndt_covariance_in; + std::array indices = {X_POS_IDX_, Y_POS_IDX_, Z_POS_IDX_}; + for (int idx : indices) { + ndt_covariance[idx] = ndt_variance_from_gnss_variance( + ndt_covariance_in[idx], gnss_pose_with_cov_last_->pose.covariance[idx]); + } + + return ndt_covariance; +} + +void PoseCovarianceModifierNode::publish_pose_type(const PoseSource & pose_source) +{ + std_msgs::msg::String selected_pose_type; + switch (pose_source) { + case PoseSource::GNSS: + selected_pose_type.data = "GNSS"; + break; + case PoseSource::GNSS_NDT: + selected_pose_type.data = "GNSS_NDT"; + break; + case PoseSource::NDT: + selected_pose_type.data = "NDT"; + break; + default: + selected_pose_type.data = "NOT_DEFINED"; + break; + } + pub_str_pose_source_->publish(selected_pose_type); +} + +} // namespace autoware::pose_covariance_modifier + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pose_covariance_modifier::PoseCovarianceModifierNode) From 788b2e324b0121fcbb028c8f20f176cb8cbf8bf3 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 9 May 2024 12:13:00 +0900 Subject: [PATCH 131/192] chore(glog): add initialization check (#6792) Signed-off-by: Takamasa Horibe --- common/glog_component/CMakeLists.txt | 2 +- common/glog_component/package.xml | 2 +- common/glog_component/src/glog_component.cpp | 6 ++++-- evaluator/perception_online_evaluator/CMakeLists.txt | 2 -- evaluator/perception_online_evaluator/package.xml | 2 +- .../src/perception_online_evaluator_node.cpp | 6 ++++-- localization/ndt_scan_matcher/package.xml | 2 +- localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp | 6 ++++-- localization/pose_estimator_arbiter/package.xml | 2 +- .../pose_estimator_arbiter/pose_estimator_arbiter_node.cpp | 6 ++++-- localization/yabloc/yabloc_common/package.xml | 2 +- .../yabloc_common/src/ground_server/ground_server_node.cpp | 6 ++++-- .../src/camera_corrector/camera_particle_corrector_node.cpp | 6 ++++-- perception/map_based_prediction/package.xml | 2 +- .../map_based_prediction/src/map_based_prediction_node.cpp | 6 ++++-- perception/multi_object_tracker/CMakeLists.txt | 5 +---- perception/multi_object_tracker/package.xml | 2 +- .../multi_object_tracker/src/multi_object_tracker_node.cpp | 6 ++++-- perception/radar_object_tracker/package.xml | 2 +- .../radar_object_tracker_node/radar_object_tracker_node.cpp | 6 ++++-- perception/tracking_object_merger/package.xml | 2 +- .../src/decorative_tracker_merger.cpp | 6 ++++-- 22 files changed, 51 insertions(+), 36 deletions(-) diff --git a/common/glog_component/CMakeLists.txt b/common/glog_component/CMakeLists.txt index c2a68d0130b37..a233914cc1524 100644 --- a/common/glog_component/CMakeLists.txt +++ b/common/glog_component/CMakeLists.txt @@ -8,7 +8,7 @@ autoware_package() ament_auto_add_library(glog_component SHARED src/glog_component.cpp ) -target_link_libraries(glog_component glog) +target_link_libraries(glog_component glog::glog) rclcpp_components_register_node(glog_component PLUGIN "GlogComponent" diff --git a/common/glog_component/package.xml b/common/glog_component/package.xml index 0d6e7daac1de3..6feedd090f2c6 100644 --- a/common/glog_component/package.xml +++ b/common/glog_component/package.xml @@ -13,7 +13,7 @@ ament_cmake_auto autoware_cmake - libgoogle-glog-dev + glog rclcpp rclcpp_components diff --git a/common/glog_component/src/glog_component.cpp b/common/glog_component/src/glog_component.cpp index 9e7e70da6c884..7fd9c923d23c9 100644 --- a/common/glog_component/src/glog_component.cpp +++ b/common/glog_component/src/glog_component.cpp @@ -17,8 +17,10 @@ GlogComponent::GlogComponent(const rclcpp::NodeOptions & node_options) : Node("glog_component", node_options) { - google::InitGoogleLogging("glog_component"); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging("glog_component"); + google::InstallFailureSignalHandler(); + } } #include diff --git a/evaluator/perception_online_evaluator/CMakeLists.txt b/evaluator/perception_online_evaluator/CMakeLists.txt index 3d967ea6d86ce..b323d07a882e8 100644 --- a/evaluator/perception_online_evaluator/CMakeLists.txt +++ b/evaluator/perception_online_evaluator/CMakeLists.txt @@ -6,8 +6,6 @@ autoware_package() find_package(pluginlib REQUIRED) -find_package(glog REQUIRED) - ament_auto_add_library(${PROJECT_NAME}_node SHARED src/metrics_calculator.cpp src/${PROJECT_NAME}_node.cpp diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index 18dde41c99566..3f855e2f1f887 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -21,8 +21,8 @@ diagnostic_msgs eigen geometry_msgs + glog lanelet2_extension - libgoogle-glog-dev motion_utils nav_msgs object_recognition_utils diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index f97ec68b75126..0fcdd77f4d515 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -43,8 +43,10 @@ PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode( { using std::placeholders::_1; - google::InitGoogleLogging("perception_online_evaluator_node"); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging("perception_online_evaluator_node"); + google::InstallFailureSignalHandler(); + } objects_sub_ = create_subscription( "~/input/objects", 1, std::bind(&PerceptionOnlineEvaluatorNode::onObjects, this, _1)); diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index 0913ee04174f5..b9a1f7dbad1bd 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -22,7 +22,7 @@ diagnostic_msgs fmt geometry_msgs - libgoogle-glog-dev + glog libpcl-all-dev localization_util nav_msgs diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp index 6e2ed022f531e..785055eef3700 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp @@ -20,8 +20,10 @@ int main(int argc, char ** argv) { - google::InitGoogleLogging(argv[0]); // NOLINT - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging(argv[0]); // NOLINT + google::InstallFailureSignalHandler(); + } rclcpp::init(argc, argv); auto ndt_scan_matcher = std::make_shared(); diff --git a/localization/pose_estimator_arbiter/package.xml b/localization/pose_estimator_arbiter/package.xml index b416d42c8617f..480b323f3031d 100644 --- a/localization/pose_estimator_arbiter/package.xml +++ b/localization/pose_estimator_arbiter/package.xml @@ -15,8 +15,8 @@ autoware_auto_mapping_msgs diagnostic_msgs geometry_msgs + glog lanelet2_extension - libgoogle-glog-dev magic_enum pcl_conversions pcl_ros diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_node.cpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_node.cpp index e48507948520b..20aaaf10abaab 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_node.cpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_node.cpp @@ -18,8 +18,10 @@ int main(int argc, char * argv[]) { - google::InitGoogleLogging(argv[0]); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging(argv[0]); + google::InstallFailureSignalHandler(); + } rclcpp::init(argc, argv); auto node = std::make_shared(); diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index 710ec0aeb75f8..213057f428c38 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -19,9 +19,9 @@ autoware_auto_mapping_msgs cv_bridge geometry_msgs + glog lanelet2_core lanelet2_extension - libgoogle-glog-dev pcl_conversions rclcpp sensor_msgs diff --git a/localization/yabloc/yabloc_common/src/ground_server/ground_server_node.cpp b/localization/yabloc/yabloc_common/src/ground_server/ground_server_node.cpp index ff50eeee0421d..4e032ff72c998 100644 --- a/localization/yabloc/yabloc_common/src/ground_server/ground_server_node.cpp +++ b/localization/yabloc/yabloc_common/src/ground_server/ground_server_node.cpp @@ -18,8 +18,10 @@ int main(int argc, char ** argv) { - google::InitGoogleLogging(argv[0]); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging(argv[0]); + google::InstallFailureSignalHandler(); + } rclcpp::init(argc, argv); rclcpp::spin(std::make_shared()); diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_node.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_node.cpp index 4def604030c95..01378f05a0ac8 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_node.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_node.cpp @@ -18,8 +18,10 @@ int main(int argc, char * argv[]) { - google::InitGoogleLogging(argv[0]); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging(argv[0]); + google::InstallFailureSignalHandler(); + } namespace mpf = yabloc::modularized_particle_filter; rclcpp::init(argc, argv); diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index 8efea9efa1844..0db8d757ee540 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/map_based_prediction/package.xml @@ -17,9 +17,9 @@ autoware_auto_perception_msgs autoware_perception_msgs + glog interpolation lanelet2_extension - libgoogle-glog-dev motion_utils rclcpp rclcpp_components diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 56dc1c2293583..dac8cc0829e3c 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -715,8 +715,10 @@ void replaceObjectYawWithLaneletsYaw( MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) : Node("map_based_prediction", node_options), debug_accumulated_time_(0.0) { - google::InitGoogleLogging("map_based_prediction_node"); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging("map_based_prediction_node"); + google::InstallFailureSignalHandler(); + } enable_delay_compensation_ = declare_parameter("enable_delay_compensation"); prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); lateral_control_time_horizon_ = diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 41d150ef0ba1b..46af1f9b9a1de 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -48,16 +48,13 @@ ament_auto_add_library(multi_object_tracker_node SHARED target_link_libraries(multi_object_tracker_node Eigen3::Eigen + glog::glog ) ament_auto_add_executable(${PROJECT_NAME} src/multi_object_tracker_node.cpp ) -target_link_libraries(${PROJECT_NAME} - multi_object_tracker_node glog -) - ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/perception/multi_object_tracker/package.xml b/perception/multi_object_tracker/package.xml index 4033f85eafb8a..1e4a90d8cc08c 100644 --- a/perception/multi_object_tracker/package.xml +++ b/perception/multi_object_tracker/package.xml @@ -16,8 +16,8 @@ autoware_auto_perception_msgs diagnostic_updater eigen + glog kalman_filter - libgoogle-glog-dev mussp object_recognition_utils rclcpp diff --git a/perception/multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp index f20aedf16efef..c6eed297c02c4 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_node.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp @@ -20,8 +20,10 @@ int main(int argc, char ** argv) { - google::InitGoogleLogging(argv[0]); // NOLINT - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging(argv[0]); // NOLINT + google::InstallFailureSignalHandler(); + } rclcpp::init(argc, argv); rclcpp::NodeOptions options; diff --git a/perception/radar_object_tracker/package.xml b/perception/radar_object_tracker/package.xml index a371d9054966a..3697903e77e41 100644 --- a/perception/radar_object_tracker/package.xml +++ b/perception/radar_object_tracker/package.xml @@ -16,9 +16,9 @@ autoware_auto_perception_msgs eigen + glog kalman_filter lanelet2_extension - libgoogle-glog-dev mussp nlohmann-json-dev object_recognition_utils diff --git a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp index e4b394256101d..460578699e780 100644 --- a/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp +++ b/perception/radar_object_tracker/src/radar_object_tracker_node/radar_object_tracker_node.cpp @@ -196,8 +196,10 @@ RadarObjectTrackerNode::RadarObjectTrackerNode(const rclcpp::NodeOptions & node_ tf_listener_(tf_buffer_) { // glog for debug - google::InitGoogleLogging("radar_object_tracker"); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging("radar_object_tracker"); + google::InstallFailureSignalHandler(); + } // Create publishers and subscribers detected_object_sub_ = create_subscription( diff --git a/perception/tracking_object_merger/package.xml b/perception/tracking_object_merger/package.xml index 027a7bf26d2c4..5912675c819fc 100644 --- a/perception/tracking_object_merger/package.xml +++ b/perception/tracking_object_merger/package.xml @@ -15,7 +15,7 @@ autoware_auto_perception_msgs eigen - libgoogle-glog-dev + glog mussp object_recognition_utils rclcpp diff --git a/perception/tracking_object_merger/src/decorative_tracker_merger.cpp b/perception/tracking_object_merger/src/decorative_tracker_merger.cpp index 2273ad6504e2a..5ff016379dd18 100644 --- a/perception/tracking_object_merger/src/decorative_tracker_merger.cpp +++ b/perception/tracking_object_merger/src/decorative_tracker_merger.cpp @@ -88,8 +88,10 @@ DecorativeTrackerMergerNode::DecorativeTrackerMergerNode(const rclcpp::NodeOptio tf_listener_(tf_buffer_) { // glog for debug - google::InitGoogleLogging("decorative_object_merger_node"); - google::InstallFailureSignalHandler(); + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging("decorative_object_merger_node"); + google::InstallFailureSignalHandler(); + } // Subscriber sub_main_objects_ = create_subscription( From dd19bb826b43c22625ff4a9eb610551573fc6d51 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Thu, 9 May 2024 12:55:03 +0900 Subject: [PATCH 132/192] feat(image projection based fusion): revert #6902 (unrecify 3d point for image projection based fusion) (#6954) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Revert "feat(image projection based fusion): unrecify 3d point for image proj…" This reverts commit 2c9a936b130596da15375156211f45ee65931de4. --- .../roi_detected_object_fusion/node.hpp | 5 +-- .../roi_pointcloud_fusion/node.hpp | 2 -- .../segmentation_pointcloud_fusion/node.hpp | 2 -- .../utils/utils.hpp | 5 --- .../image_projection_based_fusion/package.xml | 1 - .../src/pointpainting_fusion/node.cpp | 13 +++---- .../src/roi_cluster_fusion/node.cpp | 34 +++++++++++-------- .../src/roi_detected_object_fusion/node.cpp | 21 ++++++++---- .../src/roi_pointcloud_fusion/node.cpp | 20 ++++++----- .../segmentation_pointcloud_fusion/node.cpp | 21 +++++++----- .../src/utils/utils.cpp | 9 ----- 11 files changed, 65 insertions(+), 68 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index f65ff4ad322a5..7d7132309fb91 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -18,8 +18,6 @@ #include "image_projection_based_fusion/fusion_node.hpp" #include "tier4_autoware_utils/ros/debug_publisher.hpp" -#include - #include "autoware_auto_perception_msgs/msg/object_classification.hpp" #include @@ -47,8 +45,7 @@ class RoiDetectedObjectFusionNode std::map generateDetectedObjectRoIs( const DetectedObjects & input_object_msg, const double image_width, const double image_height, - const Eigen::Affine3d & object2camera_affine, - const image_geometry::PinholeCameraModel & pinhole_camera_model); + const Eigen::Affine3d & object2camera_affine, const Eigen::Matrix4d & camera_projection); void fuseObjectsOnImage( const DetectedObjects & input_object_msg, diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index 4d4fd8d2dac42..4cbc0990352e6 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -17,8 +17,6 @@ #include "image_projection_based_fusion/fusion_node.hpp" -#include - #include #include namespace image_projection_based_fusion diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp index 446417f060b9b..4168c483469ab 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -17,8 +17,6 @@ #include "image_projection_based_fusion/fusion_node.hpp" -#include - #include #include diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp index 04c010523b02a..1851d3faaee6e 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp @@ -42,7 +42,6 @@ #include "autoware_auto_perception_msgs/msg/shape.hpp" #include "tier4_perception_msgs/msg/detected_object_with_feature.hpp" -#include #include #include #include @@ -61,10 +60,6 @@ struct PointData float distance; size_t orig_index; }; - -Eigen::Vector2d calcRawImageProjectedPoint( - const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d); - std::optional getTransformStamped( const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, const std::string & source_frame_id, const rclcpp::Time & time); diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index f6eef1d0c2ace..a5b41a30be166 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -20,7 +20,6 @@ autoware_point_types cv_bridge euclidean_cluster - image_geometry image_transport lidar_centerpoint message_filters diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 99fe667c354d5..2c33df0b65afc 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -307,9 +307,6 @@ void PointPaintingFusionNode::fuseOnSingleImage( const auto class_offset = painted_pointcloud_msg.fields.at(4).offset; const auto p_step = painted_pointcloud_msg.point_step; // projection matrix - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); - Eigen::Matrix3f camera_projection; // use only x,y,z camera_projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6); @@ -345,15 +342,15 @@ dc | dc dc dc dc ||zc| continue; } // project - Eigen::Vector2d projected_point = - calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(p_x, p_y, p_z)); - + Eigen::Vector3f normalized_projected_point = camera_projection * Eigen::Vector3f(p_x, p_y, p_z); // iterate 2d bbox for (const auto & feature_object : objects) { sensor_msgs::msg::RegionOfInterest roi = feature_object.feature.roi; // paint current point if it is inside bbox int label2d = feature_object.object.classification.front().label; - if (!isUnknown(label2d) && isInsideBbox(projected_point.x(), projected_point.y(), roi, p_z)) { + if ( + !isUnknown(label2d) && + isInsideBbox(normalized_projected_point.x(), normalized_projected_point.y(), roi, p_z)) { data = &painted_pointcloud_msg.data[0]; auto p_class = reinterpret_cast(&output[stride + class_offset]); for (const auto & cls : isClassTable_) { @@ -364,7 +361,7 @@ dc | dc dc dc dc ||zc| #if 0 // Parallelizing loop don't support push_back if (debugger_) { - debug_image_points.push_back(projected_point); + debug_image_points.push_back(normalized_projected_point); } #endif } diff --git a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index bfe313a838fd6..feaf1ad495ce8 100644 --- a/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -83,8 +83,10 @@ void RoiClusterFusionNode::fuseOnSingleImage( const DetectedObjectsWithFeature & input_roi_msg, const sensor_msgs::msg::CameraInfo & camera_info, DetectedObjectsWithFeature & output_cluster_msg) { - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); + Eigen::Matrix4d projection; + projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), + camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), + camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), camera_info.p.at(11); // get transform from cluster frame id to camera optical frame id geometry_msgs::msg::TransformStamped transform_stamped; @@ -131,19 +133,23 @@ void RoiClusterFusionNode::fuseOnSingleImage( continue; } - Eigen::Vector2d projected_point = - calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z)); + Eigen::Vector4d projected_point = + projection * Eigen::Vector4d(*iter_x, *iter_y, *iter_z, 1.0); + Eigen::Vector2d normalized_projected_point = Eigen::Vector2d( + projected_point.x() / projected_point.z(), projected_point.y() / projected_point.z()); if ( - 0 <= static_cast(projected_point.x()) && - static_cast(projected_point.x()) <= static_cast(camera_info.width) - 1 && - 0 <= static_cast(projected_point.y()) && - static_cast(projected_point.y()) <= static_cast(camera_info.height) - 1) { - min_x = std::min(static_cast(projected_point.x()), min_x); - min_y = std::min(static_cast(projected_point.y()), min_y); - max_x = std::max(static_cast(projected_point.x()), max_x); - max_y = std::max(static_cast(projected_point.y()), max_y); - projected_points.push_back(projected_point); - if (debugger_) debugger_->obstacle_points_.push_back(projected_point); + 0 <= static_cast(normalized_projected_point.x()) && + static_cast(normalized_projected_point.x()) <= + static_cast(camera_info.width) - 1 && + 0 <= static_cast(normalized_projected_point.y()) && + static_cast(normalized_projected_point.y()) <= + static_cast(camera_info.height) - 1) { + min_x = std::min(static_cast(normalized_projected_point.x()), min_x); + min_y = std::min(static_cast(normalized_projected_point.y()), min_y); + max_x = std::max(static_cast(normalized_projected_point.x()), max_x); + max_y = std::max(static_cast(normalized_projected_point.y()), max_y); + projected_points.push_back(normalized_projected_point); + if (debugger_) debugger_->obstacle_points_.push_back(normalized_projected_point); } } if (projected_points.empty()) { diff --git a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 7d85ecb2f9200..762d3e0ee51b1 100644 --- a/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -86,12 +86,15 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( object2camera_affine = transformToEigen(transform_stamped_optional.value().transform); } - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); + Eigen::Matrix4d camera_projection; + camera_projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), + camera_info.p.at(3), camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), + camera_info.p.at(7), camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), + camera_info.p.at(11); const auto object_roi_map = generateDetectedObjectRoIs( input_object_msg, static_cast(camera_info.width), - static_cast(camera_info.height), object2camera_affine, pinhole_camera_model); + static_cast(camera_info.height), object2camera_affine, camera_projection); fuseObjectsOnImage(input_object_msg, input_roi_msg.feature_objects, object_roi_map); if (debugger_) { @@ -106,8 +109,7 @@ void RoiDetectedObjectFusionNode::fuseOnSingleImage( std::map RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( const DetectedObjects & input_object_msg, const double image_width, const double image_height, - const Eigen::Affine3d & object2camera_affine, - const image_geometry::PinholeCameraModel & pinhole_camera_model) + const Eigen::Affine3d & object2camera_affine, const Eigen::Matrix4d & camera_projection) { std::map object_roi_map; int64_t timestamp_nsec = @@ -146,8 +148,13 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( continue; } - Eigen::Vector2d proj_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(point.x(), point.y(), point.z())); + Eigen::Vector2d proj_point; + { + Eigen::Vector4d proj_point_hom = + camera_projection * Eigen::Vector4d(point.x(), point.y(), point.z(), 1.0); + proj_point = Eigen::Vector2d( + proj_point_hom.x() / (proj_point_hom.z()), proj_point_hom.y() / (proj_point_hom.z())); + } min_x = std::min(proj_point.x(), min_x); min_y = std::min(proj_point.y(), min_y); diff --git a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index b7f792bfe6e75..3f78ee159330f 100644 --- a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -101,9 +101,10 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( } // transform pointcloud to camera optical frame id - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); - + Eigen::Matrix4d projection; + projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), + camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), + camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), camera_info.p.at(11); geometry_msgs::msg::TransformStamped transform_stamped; { const auto transform_stamped_optional = getTransformStamped( @@ -142,8 +143,10 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( if (transformed_z <= 0.0) { continue; } - Eigen::Vector2d projected_point = calcRawImageProjectedPoint( - pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z)); + Eigen::Vector4d projected_point = + projection * Eigen::Vector4d(transformed_x, transformed_y, transformed_z, 1.0); + Eigen::Vector2d normalized_projected_point = Eigen::Vector2d( + projected_point.x() / projected_point.z(), projected_point.y() / projected_point.z()); for (std::size_t i = 0; i < output_objs.size(); ++i) { auto & feature_obj = output_objs.at(i); const auto & check_roi = feature_obj.feature.roi; @@ -153,9 +156,10 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( continue; } if ( - check_roi.x_offset <= projected_point.x() && check_roi.y_offset <= projected_point.y() && - check_roi.x_offset + check_roi.width >= projected_point.x() && - check_roi.y_offset + check_roi.height >= projected_point.y()) { + check_roi.x_offset <= normalized_projected_point.x() && + check_roi.y_offset <= normalized_projected_point.y() && + check_roi.x_offset + check_roi.width >= normalized_projected_point.x() && + check_roi.y_offset + check_roi.height >= normalized_projected_point.y()) { std::memcpy( &cluster.data[clusters_data_size.at(i)], &input_pointcloud_msg.data[offset], point_step); clusters_data_size.at(i) += point_step; diff --git a/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp index 2693a58366b9d..1c9c865b8d21e 100644 --- a/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -65,9 +65,11 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( if (mask.cols == 0 || mask.rows == 0) { return; } - image_geometry::PinholeCameraModel pinhole_camera_model; - pinhole_camera_model.fromCameraInfo(camera_info); - + Eigen::Matrix4d projection; + projection << camera_info.p.at(0), camera_info.p.at(1), camera_info.p.at(2), camera_info.p.at(3), + camera_info.p.at(4), camera_info.p.at(5), camera_info.p.at(6), camera_info.p.at(7), + camera_info.p.at(8), camera_info.p.at(9), camera_info.p.at(10), camera_info.p.at(11), 0.0, 0.0, + 0.0, 1.0; geometry_msgs::msg::TransformStamped transform_stamped; // transform pointcloud from frame id to camera optical frame id { @@ -97,11 +99,13 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( continue; } - Eigen::Vector2d projected_point = - calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z)); + Eigen::Vector4d projected_point = projection * Eigen::Vector4d(*iter_x, *iter_y, *iter_z, 1.0); + Eigen::Vector2d normalized_projected_point = Eigen::Vector2d( + projected_point.x() / projected_point.z(), projected_point.y() / projected_point.z()); - bool is_inside_image = projected_point.x() > 0 && projected_point.x() < camera_info.width && - projected_point.y() > 0 && projected_point.y() < camera_info.height; + bool is_inside_image = + normalized_projected_point.x() > 0 && normalized_projected_point.x() < camera_info.width && + normalized_projected_point.y() > 0 && normalized_projected_point.y() < camera_info.height; if (!is_inside_image) { output_cloud.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); continue; @@ -109,7 +113,8 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage( // skip filtering pointcloud where semantic id out of the defined list uint8_t semantic_id = mask.at( - static_cast(projected_point.y()), static_cast(projected_point.x())); + static_cast(normalized_projected_point.y()), + static_cast(normalized_projected_point.x())); if (static_cast(semantic_id) >= filter_semantic_label_target_.size()) { output_cloud.push_back(pcl::PointXYZ(*iter_orig_x, *iter_orig_y, *iter_orig_z)); continue; diff --git a/perception/image_projection_based_fusion/src/utils/utils.cpp b/perception/image_projection_based_fusion/src/utils/utils.cpp index 8a7650d9fd5e7..fd25696243951 100644 --- a/perception/image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/image_projection_based_fusion/src/utils/utils.cpp @@ -13,17 +13,8 @@ // limitations under the License. #include "image_projection_based_fusion/utils/utils.hpp" - namespace image_projection_based_fusion { -Eigen::Vector2d calcRawImageProjectedPoint( - const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d) -{ - cv::Point2d rectified_image_point = pinhole_camera_model.project3dToPixel(point3d); - - cv::Point2d raw_image_point = pinhole_camera_model.unrectifyPoint(rectified_image_point); - return Eigen::Vector2d(raw_image_point.x, raw_image_point.y); -} std::optional getTransformStamped( const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, From 2f46b25b189e022077bc5e05bca2c77264004e28 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Thu, 9 May 2024 14:06:33 +0900 Subject: [PATCH 133/192] chore: update sensing/perception maintainer (#6950) * chore: update maintainer Signed-off-by: yoshiri * chore: remove owner Signed-off-by: yoshiri --------- Signed-off-by: yoshiri --- perception/ground_segmentation/package.xml | 1 + perception/map_based_prediction/package.xml | 1 - perception/object_range_splitter/package.xml | 1 + perception/traffic_light_classifier/package.xml | 1 + perception/traffic_light_map_based_detector/package.xml | 1 + perception/traffic_light_visualization/package.xml | 1 + sensing/image_diagnostics/package.xml | 1 + sensing/pointcloud_preprocessor/package.xml | 1 + 8 files changed, 7 insertions(+), 1 deletion(-) diff --git a/perception/ground_segmentation/package.xml b/perception/ground_segmentation/package.xml index 1734487dcc6b3..05d5d18baf29e 100644 --- a/perception/ground_segmentation/package.xml +++ b/perception/ground_segmentation/package.xml @@ -8,6 +8,7 @@ Yukihiro Saito Shunsuke Miura Dai Nguyen + Yoshi Ri Apache License 2.0 diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index 0db8d757ee540..ba127ee39d5dd 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/map_based_prediction/package.xml @@ -5,7 +5,6 @@ 0.1.0 This package implements a map_based_prediction Tomoya Kimura - Shunsuke Miura Yoshi Ri Takayuki Murooka Kyoichi Sugahara diff --git a/perception/object_range_splitter/package.xml b/perception/object_range_splitter/package.xml index d2bb2b401fb2b..1705162ff7faf 100644 --- a/perception/object_range_splitter/package.xml +++ b/perception/object_range_splitter/package.xml @@ -5,6 +5,7 @@ 0.1.0 The object_range_splitter package Yukihiro Saito + Yoshi Ri Apache License 2.0 ament_cmake_auto diff --git a/perception/traffic_light_classifier/package.xml b/perception/traffic_light_classifier/package.xml index ef04aae7ee3cb..9e460e8ad1a1d 100644 --- a/perception/traffic_light_classifier/package.xml +++ b/perception/traffic_light_classifier/package.xml @@ -6,6 +6,7 @@ The traffic_light_classifier package Yukihiro Saito Shunsuke Miura + Tao Zhong Apache License 2.0 ament_cmake_auto diff --git a/perception/traffic_light_map_based_detector/package.xml b/perception/traffic_light_map_based_detector/package.xml index 4631935fe42fa..6f1befb79b98c 100644 --- a/perception/traffic_light_map_based_detector/package.xml +++ b/perception/traffic_light_map_based_detector/package.xml @@ -6,6 +6,7 @@ The traffic_light_map_based_detector package Yukihiro Saito Shunsuke Miura + Tao Zhong Apache License 2.0 ament_cmake_auto diff --git a/perception/traffic_light_visualization/package.xml b/perception/traffic_light_visualization/package.xml index 276f04762cdea..3d3683a8be6cc 100644 --- a/perception/traffic_light_visualization/package.xml +++ b/perception/traffic_light_visualization/package.xml @@ -5,6 +5,7 @@ 0.1.0 The traffic_light_visualization package Yukihiro Saito + Tao Zhong Apache License 2.0 ament_cmake_auto diff --git a/sensing/image_diagnostics/package.xml b/sensing/image_diagnostics/package.xml index ea57285e81aba..ceb1283b115a5 100644 --- a/sensing/image_diagnostics/package.xml +++ b/sensing/image_diagnostics/package.xml @@ -5,6 +5,7 @@ 0.1.0 The image_diagnostics_package Dai Nguyen + Yoshi Ri Apache License 2.0 Dai Nguyen diff --git a/sensing/pointcloud_preprocessor/package.xml b/sensing/pointcloud_preprocessor/package.xml index d12181f498dea..9a1eae786c379 100644 --- a/sensing/pointcloud_preprocessor/package.xml +++ b/sensing/pointcloud_preprocessor/package.xml @@ -11,6 +11,7 @@ Dai Nguyen Kenzo Lobos-Tsunekawa Yihsiang Fang + Yoshi Ri Apache License 2.0 From 473f238a2114f4bcf88cc1a4a9e1f69069276b88 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 9 May 2024 17:47:16 +0900 Subject: [PATCH 134/192] fix(system_monitor): fix warning of containerOutOfBounds (#6927) Signed-off-by: Ryuta Kambe --- system/system_monitor/src/net_monitor/net_monitor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/system_monitor/src/net_monitor/net_monitor.cpp b/system/system_monitor/src/net_monitor/net_monitor.cpp index c8775e585765e..0b5bc4c1ee7ec 100644 --- a/system/system_monitor/src/net_monitor/net_monitor.cpp +++ b/system/system_monitor/src/net_monitor/net_monitor.cpp @@ -258,7 +258,7 @@ void NetMonitor::monitor_traffic(diagnostic_updater::DiagnosticStatusWrapper & s if (line.empty()) continue; boost::split(list, line, boost::is_any_of("\t"), boost::token_compress_on); - if (list.size() >= 3) { + if (list.size() > 3) { status.add(fmt::format("nethogs {}: program", index), list[3].c_str()); status.add(fmt::format("nethogs {}: sent (KB/s)", index), list[1].c_str()); status.add(fmt::format("nethogs {}: received (KB/sec)", index), list[2].c_str()); From 569d56c3d09a5992fd763c2f575cdac50069c769 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 9 May 2024 17:48:27 +0900 Subject: [PATCH 135/192] fix(bpp): keep publishing rtc cooperate status (#6953) Signed-off-by: satoshi-ota --- .../behavior_path_planner/planner_manager.hpp | 3 --- .../behavior_path_planner/src/planner_manager.cpp | 6 ++++-- .../interface/scene_module_interface.hpp | 13 ------------- .../interface/scene_module_manager_interface.hpp | 11 +++++++++-- 4 files changed, 13 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp index 51a4cddabb941..877a8c62cbb63 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/planner_manager.hpp @@ -290,8 +290,6 @@ class PlannerManager module_ptr->updateCurrentState(); - module_ptr->publishRTCStatus(); - module_ptr->publishSteeringFactor(); module_ptr->publishObjectsOfInterestMarker(); @@ -323,7 +321,6 @@ class PlannerManager void deleteExpiredModules(SceneModulePtr & module_ptr) const { module_ptr->onExit(); - module_ptr->publishRTCStatus(); module_ptr->publishObjectsOfInterestMarker(); module_ptr.reset(); } diff --git a/planning/behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/src/planner_manager.cpp index 418a70cb269d6..6cb2fccb31117 100644 --- a/planning/behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/src/planner_manager.cpp @@ -191,8 +191,10 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da return BehaviorModuleOutput{}; // something wrong. }(); - std::for_each( - manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); }); + std::for_each(manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { + m->updateObserver(); + m->publishRTCStatus(); + }); generateCombinedDrivableArea(result_output, data); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index 4947a1b544302..0e06c1f8ab908 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -186,7 +186,6 @@ class SceneModuleInterface clearWaitingApproval(); removeRTCStatus(); - publishRTCStatus(); unlockNewModuleLaunch(); unlockOutputPath(); steering_factor_interface_ptr_->clearSteeringFactors(); @@ -196,18 +195,6 @@ class SceneModuleInterface processOnExit(); } - /** - * @brief Publish status if the module is requested to run - */ - void publishRTCStatus() - { - for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { - if (ptr) { - ptr->publishCooperateStatus(clock_->now()); - } - } - } - void publishObjectsOfInterestMarker() { for (const auto & [module_name, ptr] : objects_of_interest_marker_interface_ptr_map_) { diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index e8a28ee684ce6..0bea7c08c6601 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -99,6 +99,15 @@ class SceneModuleManagerInterface observers_.erase(itr, observers_.end()); } + void publishRTCStatus() + { + for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { + if (ptr) { + ptr->publishCooperateStatus(rclcpp::Clock(RCL_ROS_TIME).now()); + } + } + } + void publishVirtualWall() const { using tier4_autoware_utils::appendMarkerArray; @@ -235,7 +244,6 @@ class SceneModuleManagerInterface std::for_each(observers_.begin(), observers_.end(), [](const auto & observer) { if (!observer.expired()) { observer.lock()->onExit(); - observer.lock()->publishRTCStatus(); } }); @@ -243,7 +251,6 @@ class SceneModuleManagerInterface if (idle_module_ptr_ != nullptr) { idle_module_ptr_->onExit(); - idle_module_ptr_->publishRTCStatus(); idle_module_ptr_.reset(); } From 729eec036a11754945dc5752e3c00139ef6c4a8e Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 9 May 2024 20:50:14 +0900 Subject: [PATCH 136/192] fix(ground_segmentation): add intensity field (#6791) * fix(grond_segmentation): add intensity Signed-off-by: badai-nguyen * fix(ray_ground_filter): change to pointXYZI Signed-off-by: badai-nguyen * fix(ransac_ground_filter): change to pointXYZI Signed-off-by: badai-nguyen * fix(scan_ground_filter): intensity bug fix Signed-off-by: badai-nguyen * fix(ground_segmentation): add field select option Signed-off-by: badai-nguyen * Revert "fix(ground_segmentation): add field select option" This reverts commit 36fc5541ab80270b9e6d5575a707801ee38e32e1. * fix: copy input field to output Signed-off-by: badai-nguyen * fix(ray_ground_filter): copy input fields Signed-off-by: badai-nguyen * fix(ransac_ground_filter): copy input fields Signed-off-by: badai-nguyen * fix(ray_ground_filter): indices extract bug fix Signed-off-by: badai-nguyen * refactor: ray_ground_filter Signed-off-by: badai-nguyen * fix: indices max Signed-off-by: badai-nguyen * style(pre-commit): autofix --------- Signed-off-by: badai-nguyen Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../ray_ground_filter_nodelet.hpp | 9 +-- .../src/ransac_ground_filter_nodelet.cpp | 33 +++++++--- .../src/ray_ground_filter_nodelet.cpp | 64 ++++++++++++++----- .../src/scan_ground_filter_nodelet.cpp | 4 +- 4 files changed, 78 insertions(+), 32 deletions(-) diff --git a/perception/ground_segmentation/include/ground_segmentation/ray_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/ray_ground_filter_nodelet.hpp index 069c6ea27b1fa..6e2638e8566d8 100644 --- a/perception/ground_segmentation/include/ground_segmentation/ray_ground_filter_nodelet.hpp +++ b/perception/ground_segmentation/include/ground_segmentation/ray_ground_filter_nodelet.hpp @@ -186,15 +186,16 @@ class RayGroundFilterComponent : public pointcloud_preprocessor::Filter * @param out_removed_indices_cloud_ptr Resulting PointCloud with the indices removed */ void ExtractPointsIndices( - const pcl::PointCloud::Ptr in_cloud_ptr, const pcl::PointIndices & in_indices, - pcl::PointCloud::Ptr out_only_indices_cloud_ptr, - pcl::PointCloud::Ptr out_removed_indices_cloud_ptr); + const PointCloud2::ConstSharedPtr in_cloud_ptr, pcl::PointIndices & in_indices, + PointCloud2::SharedPtr out_only_indices_cloud_ptr, + PointCloud2::SharedPtr out_removed_indices_cloud_ptr); boost::optional calcPointVehicleIntersection(const Point & point); void setVehicleFootprint( const double min_x, const double max_x, const double min_y, const double max_y); - + void initializePointCloud2( + const PointCloud2::ConstSharedPtr & in_cloud_ptr, PointCloud2::SharedPtr & out_cloud_msg_ptr); /** \brief Parameter service callback result : needed to be hold */ OnSetParametersCallbackHandle::SharedPtr set_param_res_; diff --git a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index ed5fb6abe7fe7..587db9c9e0dac 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -284,19 +284,36 @@ void RANSACGroundFilterComponent::filter( const Eigen::Affine3d plane_affine = getPlaneAffine(*segment_ground_cloud_ptr, plane_normal); pcl::PointCloud::Ptr no_ground_cloud_ptr(new pcl::PointCloud); + int x_offset = input->fields[pcl::getFieldIndex(*input, "x")].offset; + int y_offset = input->fields[pcl::getFieldIndex(*input, "y")].offset; + int z_offset = input->fields[pcl::getFieldIndex(*input, "z")].offset; + int point_step = input->point_step; + + sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_msg_ptr( + new sensor_msgs::msg::PointCloud2); + no_ground_cloud_msg_ptr->header = input->header; + no_ground_cloud_msg_ptr->fields = input->fields; + no_ground_cloud_msg_ptr->point_step = point_step; + size_t output_size = 0; // use not downsampled pointcloud for extract pointcloud that higher than height threshold - for (const auto & p : current_sensor_cloud_ptr->points) { - const Eigen::Vector3d transformed_point = - plane_affine.inverse() * Eigen::Vector3d(p.x, p.y, p.z); + for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) { + float x = *reinterpret_cast(input->data[global_size + x_offset]); + float y = *reinterpret_cast(input->data[global_size + y_offset]); + float z = *reinterpret_cast(input->data[global_size + z_offset]); + const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z); if (std::abs(transformed_point.z()) > height_threshold_) { - no_ground_cloud_ptr->points.push_back(p); + std::memcpy( + &no_ground_cloud_msg_ptr->data[output_size], &input->data[global_size], point_step); + output_size += point_step; } } + no_ground_cloud_msg_ptr->data.resize(output_size); + no_ground_cloud_msg_ptr->height = input->height; + no_ground_cloud_msg_ptr->width = output_size / point_step / input->height; + no_ground_cloud_msg_ptr->row_step = output_size / input->height; + no_ground_cloud_msg_ptr->is_dense = input->is_dense; + no_ground_cloud_msg_ptr->is_bigendian = input->is_bigendian; - sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_msg_ptr( - new sensor_msgs::msg::PointCloud2); - pcl::toROSMsg(*no_ground_cloud_ptr, *no_ground_cloud_msg_ptr); - no_ground_cloud_msg_ptr->header = input->header; sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_transformed_msg_ptr( new sensor_msgs::msg::PointCloud2); if (!transformPointCloud( diff --git a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp index 7bcae47fd9f1f..c58f1c0e507e5 100644 --- a/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp @@ -257,20 +257,53 @@ void RayGroundFilterComponent::ClassifyPointCloud( // return (true); // } -void RayGroundFilterComponent::ExtractPointsIndices( - const pcl::PointCloud::Ptr in_cloud_ptr, const pcl::PointIndices & in_indices, - pcl::PointCloud::Ptr out_only_indices_cloud_ptr, - pcl::PointCloud::Ptr out_removed_indices_cloud_ptr) +void RayGroundFilterComponent::initializePointCloud2( + const PointCloud2::ConstSharedPtr & in_cloud_ptr, PointCloud2::SharedPtr & out_cloud_msg_ptr) { - pcl::ExtractIndices extract_ground; - extract_ground.setInputCloud(in_cloud_ptr); - extract_ground.setIndices(pcl::make_shared(in_indices)); - - extract_ground.setNegative(false); // true removes the indices, false leaves only the indices - extract_ground.filter(*out_only_indices_cloud_ptr); + out_cloud_msg_ptr->header = in_cloud_ptr->header; + out_cloud_msg_ptr->height = in_cloud_ptr->height; + out_cloud_msg_ptr->fields = in_cloud_ptr->fields; + out_cloud_msg_ptr->is_bigendian = in_cloud_ptr->is_bigendian; + out_cloud_msg_ptr->point_step = in_cloud_ptr->point_step; + out_cloud_msg_ptr->is_dense = in_cloud_ptr->is_dense; + out_cloud_msg_ptr->data.resize(in_cloud_ptr->data.size()); +} - extract_ground.setNegative(true); // true removes the indices, false leaves only the indices - extract_ground.filter(*out_removed_indices_cloud_ptr); +void RayGroundFilterComponent::ExtractPointsIndices( + const PointCloud2::ConstSharedPtr in_cloud_ptr, pcl::PointIndices & in_indices, + PointCloud2::SharedPtr ground_cloud_msg_ptr, PointCloud2::SharedPtr no_ground_cloud_msg_ptr) +{ + initializePointCloud2(in_cloud_ptr, ground_cloud_msg_ptr); + initializePointCloud2(in_cloud_ptr, no_ground_cloud_msg_ptr); + int point_step = in_cloud_ptr->point_step; + size_t ground_count = 0; + size_t no_ground_count = 0; + std::vector is_ground_idx(in_cloud_ptr->width, false); + for (const auto & idx : in_indices.indices) { + if (std::size_t(idx) >= is_ground_idx.size()) { + continue; + } + is_ground_idx[idx] = true; + } + for (size_t i = 0; i < is_ground_idx.size(); ++i) { + if (is_ground_idx[i]) { + std::memcpy( + &ground_cloud_msg_ptr->data[ground_count * point_step], &in_cloud_ptr->data[i * point_step], + point_step); + ground_count++; + } else { + std::memcpy( + &no_ground_cloud_msg_ptr->data[no_ground_count * point_step], + &in_cloud_ptr->data[i * point_step], point_step); + no_ground_count++; + } + } + ground_cloud_msg_ptr->data.resize(ground_count * point_step); + no_ground_cloud_msg_ptr->data.resize(no_ground_count * point_step); + ground_cloud_msg_ptr->width = ground_count; + no_ground_cloud_msg_ptr->width = no_ground_count; + ground_cloud_msg_ptr->row_step = ground_count * point_step; + no_ground_cloud_msg_ptr->row_step = no_ground_count * point_step; } void RayGroundFilterComponent::filter( @@ -299,14 +332,11 @@ void RayGroundFilterComponent::filter( pcl::PointCloud::Ptr no_ground_cloud_ptr(new pcl::PointCloud); pcl::PointCloud::Ptr radials_cloud_ptr(new pcl::PointCloud); - ExtractPointsIndices( - current_sensor_cloud_ptr, ground_indices, ground_cloud_ptr, no_ground_cloud_ptr); - sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_msg_ptr( new sensor_msgs::msg::PointCloud2); - pcl::toROSMsg(*no_ground_cloud_ptr, *no_ground_cloud_msg_ptr); - no_ground_cloud_msg_ptr->header = input->header; + sensor_msgs::msg::PointCloud2::SharedPtr ground_cloud_msg_ptr(new sensor_msgs::msg::PointCloud2); + ExtractPointsIndices(input, ground_indices, ground_cloud_msg_ptr, no_ground_cloud_msg_ptr); output = *no_ground_cloud_msg_ptr; } diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp index 7d7e11ee03bdb..6399726740041 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -575,8 +575,6 @@ void ScanGroundFilterComponent::extractObjectPoints( std::memcpy( &out_object_cloud.data[output_data_size], &in_cloud_ptr->data[i * in_cloud_ptr->point_step], in_cloud_ptr->point_step * sizeof(uint8_t)); - *reinterpret_cast(&out_object_cloud.data[output_data_size + intensity_offset_]) = - 1; // set intensity to 1 output_data_size += in_cloud_ptr->point_step; } } @@ -606,7 +604,7 @@ void ScanGroundFilterComponent::faster_filter( output.row_step = no_ground_indices.indices.size() * input->point_step; output.data.resize(output.row_step); output.width = no_ground_indices.indices.size(); - output.fields.assign(input->fields.begin(), input->fields.begin() + 3); + output.fields = input->fields; output.is_dense = true; output.height = input->height; output.is_bigendian = input->is_bigendian; From 010965b9b1f8ba8056fdbe5e6a2aa8eb3e68e6a0 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Thu, 9 May 2024 15:54:27 +0300 Subject: [PATCH 137/192] fix(freespace_planner): fix motion_velocity_smoother error while parking (#6713) * fix(freespace_planner): prevent publishing stop trajectory with only one point in a new parking cycle --------- Signed-off-by: Ahmed Ebrahim --- .../freespace_planner_node.hpp | 1 + .../freespace_planner_node.cpp | 22 +++++++++++++------ 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp index e5dfda844e21e..2c10b1b491ace 100644 --- a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp +++ b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp @@ -134,6 +134,7 @@ class FreespacePlannerNode : public rclcpp::Node size_t target_index_; bool is_completed_ = false; bool reset_in_progress_ = false; + bool is_new_parking_cycle_ = true; LaneletRoute::ConstSharedPtr route_; OccupancyGrid::ConstSharedPtr occupancy_grid_; diff --git a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index 503216fa68bc8..1c2b4513e9c45 100644 --- a/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp +++ b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp @@ -321,6 +321,8 @@ void FreespacePlannerNode::onRoute(const LaneletRoute::ConstSharedPtr msg) goal_pose_.header = msg->header; goal_pose_.pose = msg->goal_pose; + is_new_parking_cycle_ = true; + reset(); } @@ -447,13 +449,16 @@ void FreespacePlannerNode::onTimer() // Must stop before replanning any new trajectory const bool is_reset_required = !reset_in_progress_ && isPlanRequired(); if (is_reset_required) { - // Stop before planning new trajectory - const auto stop_trajectory = partial_trajectory_.points.empty() - ? createStopTrajectory(current_pose_) - : createStopTrajectory(partial_trajectory_); - trajectory_pub_->publish(stop_trajectory); - debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory)); - debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory)); + // Stop before planning new trajectory, except in a new parking cycle as the vehicle already + // stops. + if (!is_new_parking_cycle_) { + const auto stop_trajectory = partial_trajectory_.points.empty() + ? createStopTrajectory(current_pose_) + : createStopTrajectory(partial_trajectory_); + trajectory_pub_->publish(stop_trajectory); + debug_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory)); + debug_partial_pose_array_pub_->publish(trajectory2PoseArray(stop_trajectory)); + } reset(); @@ -476,6 +481,7 @@ void FreespacePlannerNode::onTimer() // StopTrajectory if (trajectory_.points.size() <= 1) { + is_new_parking_cycle_ = false; return; } @@ -487,6 +493,8 @@ void FreespacePlannerNode::onTimer() trajectory_pub_->publish(partial_trajectory_); debug_pose_array_pub_->publish(trajectory2PoseArray(trajectory_)); debug_partial_pose_array_pub_->publish(trajectory2PoseArray(partial_trajectory_)); + + is_new_parking_cycle_ = false; } void FreespacePlannerNode::planTrajectory() From d5aa5d61c5d346aa97ea12065dd75a6f7b1e6b5c Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 10 May 2024 11:34:15 +0900 Subject: [PATCH 138/192] feat(map_based_prediction): use different time horizon (#6877) Signed-off-by: Mamoru Sobue --- .../config/map_based_prediction.param.yaml | 5 +- .../map_based_prediction_node.hpp | 11 +++- .../map_based_prediction/path_generator.hpp | 31 +++++----- .../schema/map_based_prediction.schema.json | 20 ++++++- .../src/map_based_prediction_node.cpp | 57 +++++++++--------- .../src/path_generator.cpp | 58 ++++++++++--------- 6 files changed, 109 insertions(+), 73 deletions(-) diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/map_based_prediction/config/map_based_prediction.param.yaml index f8ad371ab92a6..803933ef4dbfd 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -1,7 +1,10 @@ /**: ros__parameters: enable_delay_compensation: true - prediction_time_horizon: 10.0 #[s] + prediction_time_horizon: + vehicle: 15.0 #[s] + pedestrian: 10.0 #[s] + unknown: 10.0 #[s] lateral_control_time_horizon: 5.0 #[s] prediction_sampling_delta_time: 0.5 #[s] min_velocity_for_map_based_prediction: 1.39 #[m/s] diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 829c4d6e4a114..c9d0ac84c4f91 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -99,6 +99,13 @@ struct PredictedRefPath Maneuver maneuver; }; +struct PredictionTimeHorizon +{ + double vehicle; + double pedestrian; + double unknown; +}; + using LaneletsData = std::vector; using ManeuverProbability = std::unordered_map; using autoware_auto_mapping_msgs::msg::HADMapBin; @@ -161,7 +168,7 @@ class MapBasedPredictionNode : public rclcpp::Node // Parameters bool enable_delay_compensation_; - double prediction_time_horizon_; + PredictionTimeHorizon prediction_time_horizon_; double lateral_control_time_horizon_; double prediction_time_horizon_rate_for_validate_lane_length_; double prediction_sampling_time_interval_; @@ -238,7 +245,7 @@ class MapBasedPredictionNode : public rclcpp::Node std::vector getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, - const double object_detected_time); + const double object_detected_time, const double time_horizon); Maneuver predictObjectManeuver( const TrackedObject & object, const LaneletData & current_lanelet_data, const double object_detected_time); diff --git a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp index 6dfc4a8db9e20..443a7c671ec83 100644 --- a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -80,21 +80,23 @@ using PosePath = std::vector; class PathGenerator { public: - PathGenerator( - const double time_horizon, const double lateral_time_horizon, - const double sampling_time_interval, const double min_crosswalk_user_velocity); + PathGenerator(const double sampling_time_interval, const double min_crosswalk_user_velocity); - PredictedPath generatePathForNonVehicleObject(const TrackedObject & object); + PredictedPath generatePathForNonVehicleObject( + const TrackedObject & object, const double duration); - PredictedPath generatePathForLowSpeedVehicle(const TrackedObject & object) const; + PredictedPath generatePathForLowSpeedVehicle( + const TrackedObject & object, const double duration) const; - PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object); + PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object, const double duration); PredictedPath generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double speed_limit = 0.0); + const TrackedObject & object, const PosePath & ref_paths, const double duration, + const double lateral_duration, const double speed_limit = 0.0); PredictedPath generatePathForCrosswalkUser( - const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const; + const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, + const double duration) const; PredictedPath generatePathToTargetPoint( const TrackedObject & object, const Eigen::Vector2d & point) const; @@ -111,21 +113,21 @@ class PathGenerator private: // Parameters - double time_horizon_; - double lateral_time_horizon_; double sampling_time_interval_; double min_crosswalk_user_velocity_; bool use_vehicle_acceleration_; double acceleration_exponential_half_life_; // Member functions - PredictedPath generateStraightPath(const TrackedObject & object) const; + PredictedPath generateStraightPath(const TrackedObject & object, const double duration) const; PredictedPath generatePolynomialPath( - const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0); + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double lateral_duration, const double speed_limit = 0.0); FrenetPath generateFrenetPath( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length); + const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, + const double duration, const double lateral_duration); Eigen::Vector3d calcLatCoefficients( const FrenetPoint & current_point, const FrenetPoint & target_point, const double T); Eigen::Vector2d calcLonCoefficients( @@ -139,7 +141,8 @@ class PathGenerator const PosePath & ref_path); FrenetPoint getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0); + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double speed_limit = 0.0); }; } // namespace map_based_prediction diff --git a/perception/map_based_prediction/schema/map_based_prediction.schema.json b/perception/map_based_prediction/schema/map_based_prediction.schema.json index 8ddb122ebb56e..8e5ef9e542f54 100644 --- a/perception/map_based_prediction/schema/map_based_prediction.schema.json +++ b/perception/map_based_prediction/schema/map_based_prediction.schema.json @@ -12,9 +12,23 @@ "description": "flag to enable the time delay compensation for the position of the object" }, "prediction_time_horizon": { - "type": "number", - "default": "10.0", - "description": "predict time duration for predicted path" + "properties": { + "vehicle": { + "type": "number", + "default": "15.0", + "description": "predict time duration for predicted path of vehicle" + }, + "pedestrian": { + "type": "number", + "default": "10.0", + "description": "predict time duration for predicted path of pedestrian" + }, + "unknown": { + "type": "number", + "default": "10.0", + "description": "predict time duration for predicted path of unknown" + } + } }, "lateral_control_time_horizon": { "type": "number", diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index dac8cc0829e3c..7be2b1d8f9dcf 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -720,7 +720,10 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ google::InstallFailureSignalHandler(); } enable_delay_compensation_ = declare_parameter("enable_delay_compensation"); - prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); + prediction_time_horizon_.vehicle = declare_parameter("prediction_time_horizon.vehicle"); + prediction_time_horizon_.pedestrian = + declare_parameter("prediction_time_horizon.pedestrian"); + prediction_time_horizon_.unknown = declare_parameter("prediction_time_horizon.unknown"); lateral_control_time_horizon_ = declare_parameter("lateral_control_time_horizon"); // [s] for lateral control point prediction_sampling_time_interval_ = declare_parameter("prediction_sampling_delta_time"); @@ -791,8 +794,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ "crosswalk_with_signal.timeout_set_for_no_intention_to_walk"); path_generator_ = std::make_shared( - prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_, - min_crosswalk_user_velocity_); + prediction_sampling_time_interval_, min_crosswalk_user_velocity_); path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_); path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_); @@ -969,8 +971,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // For off lane obstacles if (current_lanelets.empty()) { - PredictedPath predicted_path = - path_generator_->generatePathForOffLaneVehicle(transformed_object); + PredictedPath predicted_path = path_generator_->generatePathForOffLaneVehicle( + transformed_object, prediction_time_horizon_.vehicle); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -985,8 +987,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt transformed_object.kinematics.twist_with_covariance.twist.linear.x, transformed_object.kinematics.twist_with_covariance.twist.linear.y); if (std::fabs(abs_obj_speed) < min_velocity_for_map_based_prediction_) { - PredictedPath predicted_path = - path_generator_->generatePathForLowSpeedVehicle(transformed_object); + PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( + transformed_object, prediction_time_horizon_.vehicle); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -998,13 +1000,14 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // Get Predicted Reference Path for Each Maneuver and current lanelets // return: - const auto ref_paths = - getPredictedReferencePath(transformed_object, current_lanelets, objects_detected_time); + const auto ref_paths = getPredictedReferencePath( + transformed_object, current_lanelets, objects_detected_time, + prediction_time_horizon_.vehicle); // If predicted reference path is empty, assume this object is out of the lane if (ref_paths.empty()) { - PredictedPath predicted_path = - path_generator_->generatePathForLowSpeedVehicle(transformed_object); + PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( + transformed_object, prediction_time_horizon_.vehicle); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -1039,7 +1042,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt for (const auto & ref_path : ref_paths) { PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( - yaw_fixed_transformed_object, ref_path.path, ref_path.speed_limit); + yaw_fixed_transformed_object, ref_path.path, prediction_time_horizon_.vehicle, + lateral_control_time_horizon_, ref_path.speed_limit); if (predicted_path.path.empty()) continue; if (!check_lateral_acceleration_constraints_) { @@ -1102,8 +1106,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } default: { auto predicted_unknown_object = convertToPredictedObject(transformed_object); - PredictedPath predicted_path = - path_generator_->generatePathForNonVehicleObject(transformed_object); + PredictedPath predicted_path = path_generator_->generatePathForNonVehicleObject( + transformed_object, prediction_time_horizon_.unknown); predicted_path.confidence = 1.0; predicted_unknown_object.kinematics.predicted_paths.push_back(predicted_path); @@ -1170,7 +1174,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( { auto predicted_object = convertToPredictedObject(object); { - PredictedPath predicted_path = path_generator_->generatePathForNonVehicleObject(object); + PredictedPath predicted_path = + path_generator_->generatePathForNonVehicleObject(object, prediction_time_horizon_.pedestrian); predicted_path.confidence = 1.0; predicted_object.kinematics.predicted_paths.push_back(predicted_path); @@ -1221,7 +1226,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( if (hasPotentialToReach( object, edge_points.front_center_point, edge_points.front_right_point, - edge_points.front_left_point, prediction_time_horizon_ * 2.0, + edge_points.front_left_point, prediction_time_horizon_.pedestrian * 2.0, min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) { PredictedPath predicted_path = path_generator_->generatePathToTargetPoint(object, edge_points.front_center_point); @@ -1231,7 +1236,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( if (hasPotentialToReach( object, edge_points.back_center_point, edge_points.back_right_point, - edge_points.back_left_point, prediction_time_horizon_ * 2.0, + edge_points.back_left_point, prediction_time_horizon_.pedestrian * 2.0, min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) { PredictedPath predicted_path = path_generator_->generatePathToTargetPoint(object, edge_points.back_center_point); @@ -1255,27 +1260,27 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( const auto reachable_first = hasPotentialToReach( object, edge_points.front_center_point, edge_points.front_right_point, - edge_points.front_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, - max_crosswalk_user_delta_yaw_threshold_for_lanelet_); + edge_points.front_left_point, prediction_time_horizon_.pedestrian, + min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_); const auto reachable_second = hasPotentialToReach( object, edge_points.back_center_point, edge_points.back_right_point, - edge_points.back_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, - max_crosswalk_user_delta_yaw_threshold_for_lanelet_); + edge_points.back_left_point, prediction_time_horizon_.pedestrian, + min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_); if (!reachable_first && !reachable_second) { continue; } const auto reachable_crosswalk = isReachableCrosswalkEdgePoints( - object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_, + object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_.pedestrian, min_crosswalk_user_velocity_); if (!reachable_crosswalk) { continue; } - PredictedPath predicted_path = - path_generator_->generatePathForCrosswalkUser(object, reachable_crosswalk.get()); + PredictedPath predicted_path = path_generator_->generatePathForCrosswalkUser( + object, reachable_crosswalk.get(), prediction_time_horizon_.pedestrian); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) { @@ -1613,7 +1618,7 @@ void MapBasedPredictionNode::updateObjectsHistory( std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, - const double object_detected_time) + const double object_detected_time, const double time_horizon) { const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, @@ -1625,7 +1630,7 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( object.kinematics.acceleration_with_covariance.accel.linear.x, object.kinematics.acceleration_with_covariance.accel.linear.y) : 0.0; - const double t_h = prediction_time_horizon_; + const double t_h = time_horizon; const double λ = std::log(2) / acceleration_exponential_half_life_; auto get_search_distance_with_decaying_acc = [&]() -> double { diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index 413a0e233186b..c2800fc0de7e7 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/map_based_prediction/src/path_generator.cpp @@ -23,18 +23,16 @@ namespace map_based_prediction { PathGenerator::PathGenerator( - const double time_horizon, const double lateral_time_horizon, const double sampling_time_interval, - const double min_crosswalk_user_velocity) -: time_horizon_(time_horizon), - lateral_time_horizon_(lateral_time_horizon), - sampling_time_interval_(sampling_time_interval), + const double sampling_time_interval, const double min_crosswalk_user_velocity) +: sampling_time_interval_(sampling_time_interval), min_crosswalk_user_velocity_(min_crosswalk_user_velocity) { } -PredictedPath PathGenerator::generatePathForNonVehicleObject(const TrackedObject & object) +PredictedPath PathGenerator::generatePathForNonVehicleObject( + const TrackedObject & object, const double duration) { - return generateStraightPath(object); + return generateStraightPath(object, duration); } PredictedPath PathGenerator::generatePathToTargetPoint( @@ -71,7 +69,8 @@ PredictedPath PathGenerator::generatePathToTargetPoint( } PredictedPath PathGenerator::generatePathForCrosswalkUser( - const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const + const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, + const double duration) const { PredictedPath predicted_path{}; const double ep = 0.001; @@ -88,7 +87,7 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( const auto velocity = std::max(std::hypot(obj_vel.x, obj_vel.y), min_crosswalk_user_velocity_); const auto arrival_time = pedestrian_to_entry_point.norm() / velocity; - for (double dt = 0.0; dt < time_horizon_ + ep; dt += sampling_time_interval_) { + for (double dt = 0.0; dt < duration + ep; dt += sampling_time_interval_) { geometry_msgs::msg::Pose world_frame_pose; if (dt < arrival_time) { world_frame_pose.position.x = @@ -131,39 +130,43 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( return predicted_path; } -PredictedPath PathGenerator::generatePathForLowSpeedVehicle(const TrackedObject & object) const +PredictedPath PathGenerator::generatePathForLowSpeedVehicle( + const TrackedObject & object, const double duration) const { PredictedPath path; path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); const double ep = 0.001; - for (double dt = 0.0; dt < time_horizon_ + ep; dt += sampling_time_interval_) { + for (double dt = 0.0; dt < duration + ep; dt += sampling_time_interval_) { path.path.push_back(object.kinematics.pose_with_covariance.pose); } return path; } -PredictedPath PathGenerator::generatePathForOffLaneVehicle(const TrackedObject & object) +PredictedPath PathGenerator::generatePathForOffLaneVehicle( + const TrackedObject & object, const double duration) { - return generateStraightPath(object); + return generateStraightPath(object, duration); } PredictedPath PathGenerator::generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double speed_limit) + const TrackedObject & object, const PosePath & ref_paths, const double duration, + const double lateral_duration, const double speed_limit) { if (ref_paths.size() < 2) { - return generateStraightPath(object); + return generateStraightPath(object, duration); } - return generatePolynomialPath(object, ref_paths, speed_limit); + return generatePolynomialPath(object, ref_paths, speed_limit, duration, lateral_duration); } -PredictedPath PathGenerator::generateStraightPath(const TrackedObject & object) const +PredictedPath PathGenerator::generateStraightPath( + const TrackedObject & object, const double longitudinal_duration) const { const auto & object_pose = object.kinematics.pose_with_covariance.pose; const auto & object_twist = object.kinematics.twist_with_covariance.twist; constexpr double ep = 0.001; - const double duration = time_horizon_ + ep; + const double duration = longitudinal_duration + ep; PredictedPath path; path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); @@ -178,11 +181,12 @@ PredictedPath PathGenerator::generateStraightPath(const TrackedObject & object) } PredictedPath PathGenerator::generatePolynomialPath( - const TrackedObject & object, const PosePath & ref_path, const double speed_limit) + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double lateral_duration, const double speed_limit) { // Get current Frenet Point const double ref_path_len = motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path, speed_limit); + const auto current_point = getFrenetPoint(object, ref_path, speed_limit, duration); // Step1. Set Target Frenet Point // Note that we do not set position s, @@ -196,13 +200,13 @@ PredictedPath PathGenerator::generatePolynomialPath( // Step2. Generate Predicted Path on a Frenet coordinate const auto frenet_predicted_path = - generateFrenetPath(current_point, terminal_point, ref_path_len); + generateFrenetPath(current_point, terminal_point, ref_path_len, duration, lateral_duration); // Step3. Interpolate Reference Path for converting predicted path coordinate const auto interpolated_ref_path = interpolateReferencePath(ref_path, frenet_predicted_path); if (frenet_predicted_path.size() < 2 || interpolated_ref_path.size() < 2) { - return generateStraightPath(object); + return generateStraightPath(object, duration); } // Step4. Convert predicted trajectory from Frenet to Cartesian coordinate @@ -210,11 +214,10 @@ PredictedPath PathGenerator::generatePolynomialPath( } FrenetPath PathGenerator::generateFrenetPath( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length) + const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, + const double duration, const double lateral_duration) { FrenetPath path; - const double duration = time_horizon_; - const double lateral_duration = lateral_time_horizon_; // Compute Lateral and Longitudinal Coefficients to generate the trajectory const Eigen::Vector3d lat_coeff = @@ -385,7 +388,8 @@ PredictedPath PathGenerator::convertToPredictedPath( } FrenetPoint PathGenerator::getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double speed_limit) + const TrackedObject & object, const PosePath & ref_path, const double duration, + const double speed_limit) { FrenetPoint frenet_point; const auto obj_point = object.kinematics.pose_with_covariance.pose.position; @@ -411,7 +415,7 @@ FrenetPoint PathGenerator::getFrenetPoint( : 0.0; // Using a decaying acceleration model. Consult the README for more information about the model. - const double t_h = time_horizon_; + const double t_h = duration; const float λ = std::log(2) / acceleration_exponential_half_life_; auto have_same_sign = [](double a, double b) -> bool { From c7c826d8b77496630a9745d0111c58aeb32342ff Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 10 May 2024 12:02:21 +0900 Subject: [PATCH 139/192] fix(map_based_prediction): improve pedestrian path generation efficiency (#6964) fix: improve pedestrian path generation efficiency Signed-off-by: Taekjin LEE --- .../src/map_based_prediction_node.cpp | 2 +- .../src/path_generator.cpp | 40 +++++++++---------- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 7be2b1d8f9dcf..e717109b94cd7 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -1145,7 +1145,7 @@ bool MapBasedPredictionNode::doesPathCrossFence( const PredictedPath & predicted_path, const lanelet::ConstLineString3d & fence_line) { // check whether the predicted path cross with fence - for (size_t i = 0; i < predicted_path.path.size(); ++i) { + for (size_t i = 0; i < predicted_path.path.size() - 1; ++i) { for (size_t j = 0; j < fence_line.size() - 1; ++j) { if (isIntersecting( predicted_path.path[i].position, predicted_path.path[i + 1].position, fence_line[j], diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index c2800fc0de7e7..562fa966c40a9 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/map_based_prediction/src/path_generator.cpp @@ -48,14 +48,18 @@ PredictedPath PathGenerator::generatePathToTargetPoint( const auto velocity = std::max(std::hypot(obj_vel.x, obj_vel.y), min_crosswalk_user_velocity_); const auto arrival_time = pedestrian_to_entry_point.norm() / velocity; + const auto pedestrian_to_entry_point_normalized = pedestrian_to_entry_point.normalized(); + const auto pedestrian_to_entry_point_orientation = tier4_autoware_utils::createQuaternionFromYaw( + std::atan2(pedestrian_to_entry_point_normalized.y(), pedestrian_to_entry_point_normalized.x())); + for (double dt = 0.0; dt < arrival_time + ep; dt += sampling_time_interval_) { geometry_msgs::msg::Pose world_frame_pose; world_frame_pose.position.x = - obj_pos.x + velocity * pedestrian_to_entry_point.normalized().x() * dt; + obj_pos.x + velocity * pedestrian_to_entry_point_normalized.x() * dt; world_frame_pose.position.y = - obj_pos.y + velocity * pedestrian_to_entry_point.normalized().y() * dt; + obj_pos.y + velocity * pedestrian_to_entry_point_normalized.y() * dt; world_frame_pose.position.z = obj_pos.z; - world_frame_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; + world_frame_pose.orientation = pedestrian_to_entry_point_orientation; predicted_path.path.push_back(world_frame_pose); if (predicted_path.path.size() >= predicted_path.path.max_size()) { break; @@ -87,25 +91,32 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( const auto velocity = std::max(std::hypot(obj_vel.x, obj_vel.y), min_crosswalk_user_velocity_); const auto arrival_time = pedestrian_to_entry_point.norm() / velocity; + const auto pedestrian_to_entry_point_normalized = pedestrian_to_entry_point.normalized(); + const auto pedestrian_to_entry_point_orientation = tier4_autoware_utils::createQuaternionFromYaw( + std::atan2(pedestrian_to_entry_point_normalized.y(), pedestrian_to_entry_point_normalized.x())); + const auto entry_to_exit_point_normalized = entry_to_exit_point.normalized(); + const auto entry_to_exit_point_orientation = tier4_autoware_utils::createQuaternionFromYaw( + std::atan2(entry_to_exit_point_normalized.y(), entry_to_exit_point_normalized.x())); + for (double dt = 0.0; dt < duration + ep; dt += sampling_time_interval_) { geometry_msgs::msg::Pose world_frame_pose; if (dt < arrival_time) { world_frame_pose.position.x = - obj_pos.x + velocity * pedestrian_to_entry_point.normalized().x() * dt; + obj_pos.x + velocity * pedestrian_to_entry_point_normalized.x() * dt; world_frame_pose.position.y = - obj_pos.y + velocity * pedestrian_to_entry_point.normalized().y() * dt; + obj_pos.y + velocity * pedestrian_to_entry_point_normalized.y() * dt; world_frame_pose.position.z = obj_pos.z; - world_frame_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; + world_frame_pose.orientation = pedestrian_to_entry_point_orientation; predicted_path.path.push_back(world_frame_pose); } else { world_frame_pose.position.x = reachable_crosswalk.front_center_point.x() + - velocity * entry_to_exit_point.normalized().x() * (dt - arrival_time); + velocity * entry_to_exit_point_normalized.x() * (dt - arrival_time); world_frame_pose.position.y = reachable_crosswalk.front_center_point.y() + - velocity * entry_to_exit_point.normalized().y() * (dt - arrival_time); + velocity * entry_to_exit_point_normalized.y() * (dt - arrival_time); world_frame_pose.position.z = obj_pos.z; - world_frame_pose.orientation = object.kinematics.pose_with_covariance.pose.orientation; + world_frame_pose.orientation = entry_to_exit_point_orientation; predicted_path.path.push_back(world_frame_pose); } if (predicted_path.path.size() >= predicted_path.path.max_size()) { @@ -113,17 +124,6 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( } } - // calculate orientation of each point - if (predicted_path.path.size() >= 2) { - for (size_t i = 0; i < predicted_path.path.size() - 1; i++) { - const auto yaw = tier4_autoware_utils::calcAzimuthAngle( - predicted_path.path.at(i).position, predicted_path.path.at(i + 1).position); - predicted_path.path.at(i).orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); - } - predicted_path.path.back().orientation = - predicted_path.path.at(predicted_path.path.size() - 2).orientation; - } - predicted_path.confidence = 1.0; predicted_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); From 35d39e77907fe4e150bb4d1e2d755215f2c2c61b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 10 May 2024 13:17:34 +0900 Subject: [PATCH 140/192] feat(goal_planner): fix non-thread-safe access in goal_planner (revert of #6809 and minor fix) (#6965) Signed-off-by: Mamoru Sobue --- .../geometric_pull_over.hpp | 6 +- .../goal_planner_module.hpp | 190 +++-- .../goal_searcher.hpp | 36 +- .../goal_searcher_base.hpp | 25 +- .../shift_pull_over.hpp | 6 +- .../src/geometric_pull_over.cpp | 5 +- .../src/goal_planner_module.cpp | 699 ++++++++++++------ .../src/goal_searcher.cpp | 108 +-- .../src/shift_pull_over.cpp | 4 +- 9 files changed, 715 insertions(+), 364 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp index 6de1a726d4d4e..e67d458874d17 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/geometric_pull_over.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GEOMETRIC_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include "behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp" #include @@ -34,9 +33,7 @@ class GeometricPullOver : public PullOverPlannerBase public: GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr occupancy_grid_map, - const bool is_forward); + const LaneDepartureChecker & lane_departure_checker, const bool is_forward); PullOverPlannerType getPlannerType() const override { @@ -61,7 +58,6 @@ class GeometricPullOver : public PullOverPlannerBase protected: ParallelParkingParameters parallel_parking_parameters_; LaneDepartureChecker lane_departure_checker_{}; - std::shared_ptr occupancy_grid_map_; bool is_forward_{true}; bool left_side_parking_{true}; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 21ea06531c2f4..818aa7ff79edb 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -91,6 +91,33 @@ public: \ DEFINE_SETTER_WITH_MUTEX(TYPE, NAME) \ DEFINE_GETTER_WITH_MUTEX(TYPE, NAME) +enum class DecidingPathStatus { + NOT_DECIDED, + DECIDING, + DECIDED, +}; +using DecidingPathStatusWithStamp = std::pair; + +struct PreviousPullOverData +{ + struct SafetyStatus + { + std::optional safe_start_time{}; + bool is_safe{false}; + }; + + void reset() + { + found_path = false; + safety_status = SafetyStatus{}; + deciding_path_status = DecidingPathStatusWithStamp{}; + } + + bool found_path{false}; + SafetyStatus safety_status{}; + DecidingPathStatusWithStamp deciding_path_status{}; +}; + class ThreadSafeData { public: @@ -145,6 +172,9 @@ class ThreadSafeData void set(const std::shared_ptr & arg) { set_pull_over_path(arg); } void set(const PullOverPath & arg) { set_pull_over_path(arg); } void set(const GoalCandidate & arg) { set_modified_goal_pose(arg); } + void set(const BehaviorModuleOutput & arg) { set_last_previous_module_output(arg); } + void set(const PreviousPullOverData & arg) { set_prev_data(arg); } + void set(const CollisionCheckDebugMap & arg) { set_collision_check(arg); } void clearPullOverPath() { @@ -182,6 +212,8 @@ class ThreadSafeData last_path_update_time_ = std::nullopt; last_path_idx_increment_time_ = std::nullopt; closest_start_pose_ = std::nullopt; + last_previous_module_output_ = std::nullopt; + prev_data_.reset(); } DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) @@ -193,6 +225,9 @@ class ThreadSafeData DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates) DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, modified_goal_pose) DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, closest_start_pose) + DEFINE_SETTER_GETTER_WITH_MUTEX(std::optional, last_previous_module_output) + DEFINE_SETTER_GETTER_WITH_MUTEX(PreviousPullOverData, prev_data) + DEFINE_SETTER_GETTER_WITH_MUTEX(CollisionCheckDebugMap, collision_check) private: std::shared_ptr pull_over_path_{nullptr}; @@ -203,6 +238,9 @@ class ThreadSafeData std::optional last_path_update_time_; std::optional last_path_idx_increment_time_; std::optional closest_start_pose_{}; + std::optional last_previous_module_output_{}; + PreviousPullOverData prev_data_{}; + CollisionCheckDebugMap collision_check_{}; std::recursive_mutex & mutex_; rclcpp::Clock::SharedPtr clock_; @@ -234,33 +272,6 @@ struct LastApprovalData Pose pose{}; }; -enum class DecidingPathStatus { - NOT_DECIDED, - DECIDING, - DECIDED, -}; -using DecidingPathStatusWithStamp = std::pair; - -struct PreviousPullOverData -{ - struct SafetyStatus - { - std::optional safe_start_time{}; - bool is_safe{false}; - }; - - void reset() - { - found_path = false; - safety_status = SafetyStatus{}; - deciding_path_status = DecidingPathStatusWithStamp{}; - } - - bool found_path{false}; - SafetyStatus safety_status{}; - DecidingPathStatusWithStamp deciding_path_status{}; -}; - // store stop_pose_ pointer with reason string struct PoseWithString { @@ -363,6 +374,50 @@ class GoalPlannerModule : public SceneModuleInterface CandidateOutput planCandidate() const override { return CandidateOutput{}; } private: + /** + * @brief shared data for onTimer(onTimer/onFreespaceParkingTimer just read this) + */ + struct GoalPlannerData + { + GoalPlannerData(const PlannerData & planner_data, const GoalPlannerParameters & parameters) + { + initializeOccupancyGridMap(planner_data, parameters); + }; + GoalPlannerParameters parameters; + std::shared_ptr ego_predicted_path_params; + std::shared_ptr objects_filtering_params; + std::shared_ptr safety_check_params; + tier4_autoware_utils::LinearRing2d vehicle_footprint; + + PlannerData planner_data; + ModuleStatus current_status; + BehaviorModuleOutput previous_module_output; + // collision detector + // need to be shared_ptr to be used in planner and goal searcher + std::shared_ptr occupancy_grid_map; + std::shared_ptr goal_searcher; + + const BehaviorModuleOutput & getPreviousModuleOutput() const { return previous_module_output; } + const ModuleStatus & getCurrentStatus() const { return current_status; } + void updateOccupancyGrid(); + GoalPlannerData clone() const; + void update( + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params_, + const std::shared_ptr & objects_filtering_params_, + const std::shared_ptr & safety_check_params_, + const PlannerData & planner_data, const ModuleStatus & current_status, + const BehaviorModuleOutput & previous_module_output, + const std::shared_ptr goal_searcher_, + const tier4_autoware_utils::LinearRing2d & vehicle_footprint); + + private: + void initializeOccupancyGridMap( + const PlannerData & planner_data, const GoalPlannerParameters & parameters); + }; + std::optional gp_planner_data_{std::nullopt}; + std::mutex gp_planner_data_mutex_; + // Flag class for managing whether a certain callback is running in multi-threading class ScopedFlag { @@ -420,9 +475,10 @@ class GoalPlannerModule : public SceneModuleInterface // goal searcher std::shared_ptr goal_searcher_; - // collision detector - // need to be shared_ptr to be used in planner and goal searcher - std::shared_ptr occupancy_grid_map_; + // NOTE: this is latest occupancy_grid_map pointer which the local planner_data on + // onFreespaceParkingTimer thread storage may point to while calculation. + // onTimer/onFreespaceParkingTimer and their callees MUST NOT use this + std::shared_ptr occupancy_grid_map_{nullptr}; // check stopped and stuck state std::deque odometry_buffer_stopped_; @@ -431,10 +487,10 @@ class GoalPlannerModule : public SceneModuleInterface tier4_autoware_utils::LinearRing2d vehicle_footprint_; std::recursive_mutex mutex_; - ThreadSafeData thread_safe_data_; + // TODO(Mamoru Sobue): isSafePath() modifies ThreadSafeData::check_collision, avoid this mutable + mutable ThreadSafeData thread_safe_data_; std::unique_ptr last_approval_data_{nullptr}; - PreviousPullOverData prev_data_{}; // approximate distance from the start point to the end point of pull_over. // this is used as an assumed value to decelerate, etc., before generating the actual path. @@ -460,11 +516,12 @@ class GoalPlannerModule : public SceneModuleInterface mutable PoseWithString debug_stop_pose_with_info_; // collision check - void initializeOccupancyGridMap(); - void updateOccupancyGrid(); - bool checkOccupancyGridCollision(const PathWithLaneId & path) const; + bool checkOccupancyGridCollision( + const PathWithLaneId & path, + const std::shared_ptr occupancy_grid_map) const; bool checkObjectsCollision( - const PathWithLaneId & path, const double collision_check_margin, + const PathWithLaneId & path, const std::shared_ptr planner_data, + const GoalPlannerParameters & parameters, const double collision_check_margin, const bool extract_static_objects, const bool update_debug_data = false) const; // goal seach @@ -487,13 +544,39 @@ class GoalPlannerModule : public SceneModuleInterface bool isStopped( std::deque & odometry_buffer, const double time); bool hasFinishedCurrentPath(); - bool isOnModifiedGoal() const; + bool isOnModifiedGoal(const Pose & current_pose, const GoalPlannerParameters & parameters) const; double calcModuleRequestLength() const; - bool needPathUpdate(const double path_update_duration) const; - bool isStuck(); - bool hasDecidedPath() const; - bool hasNotDecidedPath() const; - DecidingPathStatusWithStamp checkDecidingPathStatus() const; + bool needPathUpdate( + const Pose & current_pose, const double path_update_duration, + const GoalPlannerParameters & parameters) const; + bool isStuck( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters); + bool hasDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const; + bool hasNotDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const; + DecidingPathStatusWithStamp checkDecidingPathStatus( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const; void decideVelocity(); bool foundPullOverPath() const; void updateStatus(const BehaviorModuleOutput & output); @@ -508,7 +591,10 @@ class GoalPlannerModule : public SceneModuleInterface bool hasEnoughTimePassedSincePathUpdate(const double duration) const; // freespace parking - bool planFreespacePath(); + bool planFreespacePath( + std::shared_ptr planner_data, + const std::shared_ptr goal_searcher, + const std::shared_ptr occupancy_grid_map); bool canReturnToLaneParking(); // plan pull over path @@ -537,10 +623,12 @@ class GoalPlannerModule : public SceneModuleInterface TurnSignalInfo calcTurnSignalInfo(); std::optional ignore_signal_{std::nullopt}; - std::optional last_previous_module_output_{}; - bool hasPreviousModulePathShapeChanged() const; - bool hasDeviatedFromLastPreviousModulePath() const; - bool hasDeviatedFromCurrentPreviousModulePath() const; + bool hasPreviousModulePathShapeChanged(const BehaviorModuleOutput & previous_module_output) const; + bool hasDeviatedFromLastPreviousModulePath( + const std::shared_ptr planner_data) const; + bool hasDeviatedFromCurrentPreviousModulePath( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output) const; // timer for generating pull over path candidates in a separate thread void onTimer(); @@ -556,16 +644,22 @@ class GoalPlannerModule : public SceneModuleInterface // safety check void initializeSafetyCheckParameters(); SafetyCheckParams createSafetyCheckParams() const; + /* void updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const; + */ /** * @brief Checks if the current path is safe. * @return std::pair * first: If the path is safe for a certain period of time, true. * second: If the path is safe in the current state, true. */ - std::pair isSafePath() const; + std::pair isSafePath( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params) const; // debug void setDebugData(); diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp index f228ecc378c28..89f4086874183 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher.hpp @@ -29,33 +29,45 @@ using BasicPolygons2d = std::vector; class GoalSearcher : public GoalSearcherBase { public: - GoalSearcher( - const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint, - const std::shared_ptr & occupancy_grid_map); + GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint); - GoalCandidates search() override; - void update(GoalCandidates & goal_candidates) const override; + GoalCandidates search( + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) override; + void update( + GoalCandidates & goal_candidates, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const override; // todo(kosuke55): Functions for this specific use should not be in the interface, // so it is better to consider interface design when we implement other goal searchers. GoalCandidate getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates) const override; + const GoalCandidates & goal_candidates, + const std::shared_ptr & planner_data) const override; bool isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor) const override; + const GoalCandidate & goal_candidate, const double margin_scale_factor, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const override; private: void countObjectsToAvoid( - GoalCandidates & goal_candidates, const PredictedObjects & objects) const; - void createAreaPolygons(std::vector original_search_poses); - bool checkCollision(const Pose & pose, const PredictedObjects & objects) const; + GoalCandidates & goal_candidates, const PredictedObjects & objects, + const std::shared_ptr & planner_data) const; + void createAreaPolygons( + std::vector original_search_poses, + const std::shared_ptr & planner_data); + bool checkCollision( + const Pose & pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map) const; bool checkCollisionWithLongitudinalDistance( - const Pose & ego_pose, const PredictedObjects & objects) const; + const Pose & ego_pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const; BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const; BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const; bool isInAreas(const LinearRing2d & footprint, const BasicPolygons2d & areas) const; LinearRing2d vehicle_footprint_{}; - std::shared_ptr occupancy_grid_map_{}; bool left_side_parking_{true}; }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp index 2ddacc0aac46d..f5d879358cd38 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_searcher_base.hpp @@ -17,6 +17,7 @@ #include "behavior_path_goal_planner_module/goal_planner_parameters.hpp" #include "behavior_path_planner_common/data_manager.hpp" +#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -49,23 +50,29 @@ class GoalSearcherBase { reference_goal_pose_ = reference_goal_pose; } + const Pose & getReferenceGoal() const { return reference_goal_pose_; } - void setPlannerData(const std::shared_ptr & planner_data) + MultiPolygon2d getAreaPolygons() const { return area_polygons_; } + virtual GoalCandidates search( + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) = 0; + virtual void update( + [[maybe_unused]] GoalCandidates & goal_candidates, + [[maybe_unused]] const std::shared_ptr occupancy_grid_map, + [[maybe_unused]] const std::shared_ptr & planner_data) const { - planner_data_ = planner_data; + return; } - - MultiPolygon2d getAreaPolygons() { return area_polygons_; } - virtual GoalCandidates search() = 0; - virtual void update([[maybe_unused]] GoalCandidates & goal_candidates) const { return; } virtual GoalCandidate getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates) const = 0; + const GoalCandidates & goal_candidates, + const std::shared_ptr & planner_data) const = 0; virtual bool isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor) const = 0; + const GoalCandidate & goal_candidate, const double margin_scale_factor, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const = 0; protected: GoalPlannerParameters parameters_{}; - std::shared_ptr planner_data_{nullptr}; Pose reference_goal_pose_{}; MultiPolygon2d area_polygons_{}; }; diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp index 892ef7d5dd303..d0b0aee83e20c 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/shift_pull_over.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__SHIFT_PULL_OVER_HPP_ #include "behavior_path_goal_planner_module/pull_over_planner_base.hpp" -#include "behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp" #include @@ -34,9 +33,7 @@ class ShiftPullOver : public PullOverPlannerBase public: ShiftPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr & occupancy_grid_map); - + const LaneDepartureChecker & lane_departure_checker); PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::SHIFT; }; std::optional plan(const Pose & goal_pose) override; @@ -57,7 +54,6 @@ class ShiftPullOver : public PullOverPlannerBase const Pose & start_pose, const Pose & end_pose, const double resample_interval); LaneDepartureChecker lane_departure_checker_{}; - std::shared_ptr occupancy_grid_map_{}; bool left_side_parking_{true}; }; diff --git a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp index b7d1c240d032a..0779002690f8f 100644 --- a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -27,13 +27,10 @@ namespace behavior_path_planner { GeometricPullOver::GeometricPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr occupancy_grid_map, - const bool is_forward) + const LaneDepartureChecker & lane_departure_checker, const bool is_forward) : PullOverPlannerBase{node, parameters}, parallel_parking_parameters_{parameters.parallel_parking_parameters}, lane_departure_checker_{lane_departure_checker}, - occupancy_grid_map_{occupancy_grid_map}, is_forward_{is_forward}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index d423b8c922ee7..ef3de3b0363ce 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -78,14 +78,14 @@ GoalPlannerModule::GoalPlannerModule( for (const std::string & planner_type : parameters_->efficient_path_order) { if (planner_type == "SHIFT" && parameters_->enable_shift_parking) { - pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, occupancy_grid_map_)); + pull_over_planners_.push_back( + std::make_shared(node, *parameters, lane_departure_checker)); } else if (planner_type == "ARC_FORWARD" && parameters_->enable_arc_forward_parking) { pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, occupancy_grid_map_, /*is_forward*/ true)); + node, *parameters, lane_departure_checker, /*is_forward*/ true)); } else if (planner_type == "ARC_BACKWARD" && parameters_->enable_arc_backward_parking) { pull_over_planners_.push_back(std::make_shared( - node, *parameters, lane_departure_checker, occupancy_grid_map_, /*is_forward*/ false)); + node, *parameters, lane_departure_checker, /*is_forward*/ false)); } } @@ -97,8 +97,7 @@ GoalPlannerModule::GoalPlannerModule( // currently there is only one goal_searcher_type const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); vehicle_footprint_ = vehicle_info.createFootprint(); - goal_searcher_ = - std::make_shared(*parameters, vehicle_footprint_, occupancy_grid_map_); + goal_searcher_ = std::make_shared(*parameters, vehicle_footprint_); // timer callback for generating lane parking candidate paths const auto lane_parking_period_ns = rclcpp::Rate(1.0).period(); @@ -123,51 +122,44 @@ GoalPlannerModule::GoalPlannerModule( // Initialize safety checker if (parameters_->safety_check_params.enable_safety_check) { initializeSafetyCheckParameters(); - utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); } - - prev_data_.reset(); -} - -// This function is needed for waiting for planner_data_ -void GoalPlannerModule::updateOccupancyGrid() -{ - if (!planner_data_->occupancy_grid) { - RCLCPP_WARN_THROTTLE(getLogger(), *clock_, 5000, "occupancy_grid is not ready"); - return; - } - occupancy_grid_map_->setMap(*(planner_data_->occupancy_grid)); } -bool GoalPlannerModule::hasPreviousModulePathShapeChanged() const +bool GoalPlannerModule::hasPreviousModulePathShapeChanged( + const BehaviorModuleOutput & previous_module_output) const { - if (!last_previous_module_output_) { + const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); + if (!last_previous_module_output) { return true; } - const auto current_path = getPreviousModuleOutput().path; + const auto current_path = previous_module_output.path; // the terminal distance is far return calcDistance2d( - last_previous_module_output_->path.points.back().point, + last_previous_module_output->path.points.back().point, current_path.points.back().point) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath() const +bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath( + const std::shared_ptr planner_data) const { - if (!last_previous_module_output_) { + const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); + if (!last_previous_module_output) { return true; } return std::abs(motion_utils::calcLateralOffset( - last_previous_module_output_->path.points, - planner_data_->self_odometry->pose.pose.position)) > 0.3; + last_previous_module_output->path.points, + planner_data->self_odometry->pose.pose.position)) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath() const +bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath( + const std::shared_ptr planner_data, + const BehaviorModuleOutput & previous_module_output) const { return std::abs(motion_utils::calcLateralOffset( - getPreviousModuleOutput().path.points, - planner_data_->self_odometry->pose.pose.position)) > 0.3; + previous_module_output.path.points, planner_data->self_odometry->pose.pose.position)) > + 0.3; } // generate pull over candidate paths @@ -175,7 +167,50 @@ void GoalPlannerModule::onTimer() { const ScopedFlag flag(is_lane_parking_cb_running_); - if (getCurrentStatus() == ModuleStatus::IDLE) { + std::shared_ptr local_planner_data{nullptr}; + std::optional current_status_opt{std::nullopt}; + std::optional previous_module_output_opt{std::nullopt}; + std::shared_ptr occupancy_grid_map{nullptr}; + std::optional parameters_opt{std::nullopt}; + std::shared_ptr ego_predicted_path_params{nullptr}; + std::shared_ptr objects_filtering_params{nullptr}; + std::shared_ptr safety_check_params{nullptr}; + std::shared_ptr goal_searcher{nullptr}; + + // begin of critical section + { + std::lock_guard guard(gp_planner_data_mutex_); + if (gp_planner_data_) { + const auto & gp_planner_data = gp_planner_data_.value(); + local_planner_data = std::make_shared(gp_planner_data.planner_data); + current_status_opt = gp_planner_data.current_status; + previous_module_output_opt = gp_planner_data.previous_module_output; + occupancy_grid_map = gp_planner_data.occupancy_grid_map; + parameters_opt = gp_planner_data.parameters; + ego_predicted_path_params = gp_planner_data.ego_predicted_path_params; + objects_filtering_params = gp_planner_data.objects_filtering_params; + safety_check_params = gp_planner_data.safety_check_params; + goal_searcher = gp_planner_data.goal_searcher; + } + } + // end of critical section + if ( + !local_planner_data || !current_status_opt || !previous_module_output_opt || + !occupancy_grid_map || !parameters_opt || !ego_predicted_path_params || + !objects_filtering_params || !safety_check_params || !goal_searcher) { + RCLCPP_ERROR( + getLogger(), + "failed to get valid " + "local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt/" + "ego_predicted_path_params/objects_filtering_params/safety_check_params/goal_searcher in " + "onTimer"); + return; + } + const auto & current_status = current_status_opt.value(); + const auto & previous_module_output = previous_module_output_opt.value(); + const auto & parameters = parameters_opt.value(); + + if (current_status == ModuleStatus::IDLE) { return; } @@ -184,27 +219,31 @@ void GoalPlannerModule::onTimer() return; } - if (!planner_data_ || !utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(local_planner_data->route_handler)) { return; } // check if new pull over path candidates are needed to be generated const bool need_update = std::invoke([&]() { - if (isOnModifiedGoal()) { + if (isOnModifiedGoal(local_planner_data->self_odometry->pose.pose, parameters)) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath()) { + if (hasDeviatedFromCurrentPreviousModulePath(local_planner_data, previous_module_output)) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } if (thread_safe_data_.get_pull_over_path_candidates().empty()) { return true; } - if (hasPreviousModulePathShapeChanged()) { + if (hasPreviousModulePathShapeChanged(previous_module_output)) { RCLCPP_DEBUG(getLogger(), "has previous module path shape changed"); return true; } - if (hasDeviatedFromLastPreviousModulePath() && !hasDecidedPath()) { + if ( + hasDeviatedFromLastPreviousModulePath(local_planner_data) && + !hasDecidedPath( + local_planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params, goal_searcher)) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; } @@ -214,13 +253,12 @@ void GoalPlannerModule::onTimer() return; } - const auto previous_module_output = getPreviousModuleOutput(); const auto goal_candidates = thread_safe_data_.get_goal_candidates(); // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, + local_planner_data, parameters.backward_goal_search_length, + parameters.forward_goal_search_length, /*forward_only_in_route*/ false); std::vector path_candidates{}; std::optional closest_start_pose{}; @@ -228,7 +266,7 @@ void GoalPlannerModule::onTimer() const auto planCandidatePaths = [&]( const std::shared_ptr & planner, const GoalCandidate & goal_candidate) { - planner->setPlannerData(planner_data_); + planner->setPlannerData(local_planner_data); planner->setPreviousModuleOutput(previous_module_output); auto pull_over_path = planner->plan(goal_candidate.goal_pose); if (pull_over_path) { @@ -254,7 +292,7 @@ void GoalPlannerModule::onTimer() is_center_line_input_path); // plan candidate paths and set them to the member variable - if (parameters_->path_priority == "efficient_path") { + if (parameters.path_priority == "efficient_path") { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line if (!is_center_line_input_path && planner->getPlannerType() != PullOverPlannerType::SHIFT) { @@ -264,7 +302,7 @@ void GoalPlannerModule::onTimer() planCandidatePaths(planner, goal_candidate); } } - } else if (parameters_->path_priority == "close_goal") { + } else if (parameters.path_priority == "close_goal") { for (const auto & goal_candidate : goal_candidates) { for (const auto & planner : pull_over_planners_) { // todo: temporary skip NON SHIFT planner when input path is not center line @@ -277,49 +315,76 @@ void GoalPlannerModule::onTimer() } else { RCLCPP_ERROR( getLogger(), "path_priority should be efficient_path or close_goal, but %s is given.", - parameters_->path_priority.c_str()); + parameters.path_priority.c_str()); throw std::domain_error("[pull_over] invalid path_priority"); } // set member variables - { - const std::lock_guard lock(mutex_); - thread_safe_data_.set_pull_over_path_candidates(path_candidates); - thread_safe_data_.set_closest_start_pose(closest_start_pose); - RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); - } + thread_safe_data_.set_pull_over_path_candidates(path_candidates); + thread_safe_data_.set_closest_start_pose(closest_start_pose); + RCLCPP_INFO(getLogger(), "generated %lu pull over path candidates", path_candidates.size()); - last_previous_module_output_ = previous_module_output; + thread_safe_data_.set_last_previous_module_output(previous_module_output); } void GoalPlannerModule::onFreespaceParkingTimer() { const ScopedFlag flag(is_freespace_parking_cb_running_); - if (getCurrentStatus() == ModuleStatus::IDLE) { + std::shared_ptr local_planner_data{nullptr}; + std::optional current_status_opt{std::nullopt}; + std::shared_ptr occupancy_grid_map{nullptr}; + std::optional parameters_opt{std::nullopt}; + std::shared_ptr goal_searcher{nullptr}; + + // begin of critical section + { + std::lock_guard guard(gp_planner_data_mutex_); + if (gp_planner_data_) { + const auto & gp_planner_data = gp_planner_data_.value(); + local_planner_data = std::make_shared(gp_planner_data.planner_data); + current_status_opt = gp_planner_data.current_status; + occupancy_grid_map = gp_planner_data.occupancy_grid_map; + parameters_opt = gp_planner_data.parameters; + goal_searcher = gp_planner_data.goal_searcher; + } + } + // end of critical section + if (!local_planner_data || !current_status_opt || !parameters_opt || !goal_searcher) { + RCLCPP_ERROR( + getLogger(), + "failed to get valid planner_data/current_status/parameters/goal_searcher in " + "onFreespaceParkingTimer"); return; } - if (!planner_data_) { + const auto & current_status = current_status_opt.value(); + const auto & parameters = parameters_opt.value(); + + if (current_status == ModuleStatus::IDLE) { return; } - if (!planner_data_->costmap) { + + if (!local_planner_data->costmap) { return; } // fixed goal planner do not use freespace planner - if (!utils::isAllowedGoalModification(planner_data_->route_handler)) { + if (!utils::isAllowedGoalModification(local_planner_data->route_handler)) { return; } - if (isOnModifiedGoal()) { + if (isOnModifiedGoal(local_planner_data->self_odometry->pose.pose, parameters)) { return; } const bool is_new_costmap = - (clock_->now() - planner_data_->costmap->header.stamp).seconds() < 1.0; + (clock_->now() - local_planner_data->costmap->header.stamp).seconds() < 1.0; constexpr double path_update_duration = 1.0; - if (isStuck() && is_new_costmap && needPathUpdate(path_update_duration)) { - planFreespacePath(); + if ( + isStuck(local_planner_data, occupancy_grid_map, parameters) && is_new_costmap && + needPathUpdate( + local_planner_data->self_odometry->pose.pose, path_update_duration, parameters)) { + planFreespacePath(local_planner_data, goal_searcher, occupancy_grid_map); } } @@ -349,28 +414,64 @@ void GoalPlannerModule::updateObjectsFilteringParams( void GoalPlannerModule::updateData() { + // In PlannerManager::run(), it calls SceneModuleInterface::setData and + // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). + // Then module_ptr->run() invokes GoalPlannerModule::updateData and then + // planWaitingApproval()/plan(), so we can copy latest current_status/previous_module_output to + // gp_planner_data_ here + + // NOTE: onTimer/onFreespaceParkingTimer copies gp_planner_data_ to their local clone, so we need + // to lock gp_planner_data_ here to avoid data race. But the following clone process is + // lightweight because most of the member variables of PlannerData/RouteHandler is + // shared_ptrs/bool + // begin of critical section + { + std::lock_guard guard(gp_planner_data_mutex_); + if (!gp_planner_data_) { + gp_planner_data_ = GoalPlannerData(*planner_data_, *parameters_); + } + auto & gp_planner_data = gp_planner_data_.value(); + // NOTE: for the above reasons, PlannerManager/behavior_path_planner_node ensure that + // planner_data_ is not nullptr, so it is OK to copy as value + // By copying PlannerData as value, the internal shared member variables are also copied + // (reference count is incremented), so `gp_planner_data_.foo` is now thread-safe from the + // **re-pointing** by `planner_data_->foo = msg` in behavior_path_planner::onCallbackFor(msg) + // and if these two coincided, only the reference count is affected + gp_planner_data.update( + *parameters_, ego_predicted_path_params_, objects_filtering_params_, safety_check_params_, + *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), goal_searcher_, + vehicle_footprint_); + // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as + // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since + // behavior_path_planner::run() updates + // planner_data_->route_handler->lanelet_map_ptr_/routing_graph_ptr_ especially, we also have + // to copy route_handler as value to use lanelet_map_ptr_/routing_graph_ptr_ thread-safely in + // onTimer/onFreespaceParkingTimer + // TODO(Mamoru Sobue): If the copy of RouteHandler.road_lanelets/shoulder_lanelets is not + // lightweight, we should update gp_planner_data_.route_handler only when + // `planner_data_.is_route_handler_updated` variable is set true by behavior_path_planner + // (although this flag is not implemented yet). In that case, gp_planner_data members except + // for route_handler should be copied from planner_data_ + + // GoalPlannerModule::occupancy_grid_map_ and gp_planner_data.occupancy_grid_map share the + // ownership, and gp_planner_data.occupancy_grid_map maybe also shared by the local + // planner_data on onFreespaceParkingTimer thread local memory space. So following operation + // is thread-safe because gp_planner_data.occupancy_grid_map is only re-pointed here and its + // prior resource is still owned by the onFreespaceParkingTimer thread locally. + occupancy_grid_map_ = gp_planner_data.occupancy_grid_map; + } + // end of critical section + if (getCurrentStatus() == ModuleStatus::IDLE && !isExecutionRequested()) { return; } - // Initialize Occupancy Grid Map - // This operation requires waiting for `planner_data_`, hence it is executed here instead of in - // the constructor. Ideally, this operation should only need to be performed once. - if ( - parameters_->use_occupancy_grid_for_goal_search || - parameters_->use_occupancy_grid_for_path_collision_check) { - initializeOccupancyGridMap(); - } - resetPathCandidate(); resetPathReference(); path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); - updateOccupancyGrid(); - // update goal searcher and generate goal candidates if (thread_safe_data_.get_goal_candidates().empty()) { - goal_searcher_->setPlannerData(planner_data_); goal_searcher_->setReferenceGoal( calcRefinedGoal(planner_data_->route_handler->getOriginalGoalPose())); thread_safe_data_.set_goal_candidates(generateGoalCandidates()); @@ -391,21 +492,6 @@ void GoalPlannerModule::updateData() } } -void GoalPlannerModule::initializeOccupancyGridMap() -{ - OccupancyGridMapParam occupancy_grid_map_param{}; - const double margin = parameters_->occupancy_grid_collision_check_margin; - occupancy_grid_map_param.vehicle_shape.length = - planner_data_->parameters.vehicle_length + 2 * margin; - occupancy_grid_map_param.vehicle_shape.width = - planner_data_->parameters.vehicle_width + 2 * margin; - occupancy_grid_map_param.vehicle_shape.base2back = - planner_data_->parameters.base_link2rear + margin; - occupancy_grid_map_param.theta_size = parameters_->theta_size; - occupancy_grid_map_param.obstacle_threshold = parameters_->obstacle_threshold; - occupancy_grid_map_->setParam(occupancy_grid_map_param); -} - void GoalPlannerModule::initializeSafetyCheckParameters() { updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); @@ -418,7 +504,7 @@ void GoalPlannerModule::processOnExit() resetPathCandidate(); resetPathReference(); debug_marker_.markers.clear(); - prev_data_.reset(); + thread_safe_data_.reset(); last_approval_data_.reset(); } @@ -499,7 +585,10 @@ bool GoalPlannerModule::isExecutionRequested() const bool GoalPlannerModule::isExecutionReady() const { if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) { - if (!isSafePath().first) { + if (!isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_) + .first) { RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects"); return false; } @@ -582,18 +671,17 @@ Pose GoalPlannerModule::calcRefinedGoal(const Pose & goal_pose) const return refined_goal_pose; } -bool GoalPlannerModule::planFreespacePath() +bool GoalPlannerModule::planFreespacePath( + std::shared_ptr planner_data, + const std::shared_ptr goal_searcher, + const std::shared_ptr occupancy_grid_map) { GoalCandidates goal_candidates{}; - { - const std::lock_guard lock(mutex_); - goal_searcher_->setPlannerData(planner_data_); - goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); - thread_safe_data_.set_goal_candidates(goal_candidates); - debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); - debug_data_.freespace_planner.is_planning = true; - } + goal_candidates = thread_safe_data_.get_goal_candidates(); + goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data); + thread_safe_data_.set_goal_candidates(goal_candidates); + debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); + debug_data_.freespace_planner.is_planning = true; for (size_t i = 0; i < goal_candidates.size(); i++) { const auto goal_candidate = goal_candidates.at(i); @@ -605,7 +693,7 @@ bool GoalPlannerModule::planFreespacePath() if (!goal_candidate.is_safe) { continue; } - freespace_planner_->setPlannerData(planner_data_); + freespace_planner_->setPlannerData(planner_data); auto freespace_path = freespace_planner_->plan(goal_candidate.goal_pose); freespace_path->goal_id = goal_candidate.id; if (!freespace_path) { @@ -643,13 +731,15 @@ bool GoalPlannerModule::canReturnToLaneParking() if ( parameters_->use_object_recognition && checkObjectsCollision( - path, parameters_->object_recognition_collision_check_hard_margins.back(), + path, planner_data_, *parameters_, + parameters_->object_recognition_collision_check_hard_margins.back(), /*extract_static_objects=*/false)) { return false; } if ( - parameters_->use_occupancy_grid_for_path_collision_check && checkOccupancyGridCollision(path)) { + parameters_->use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision(path, occupancy_grid_map_)) { return false; } @@ -669,7 +759,7 @@ GoalCandidates GoalPlannerModule::generateGoalCandidates() const // calculate goal candidates const auto & route_handler = planner_data_->route_handler; if (utils::isAllowedGoalModification(route_handler)) { - return goal_searcher_->search(); + return goal_searcher_->search(occupancy_grid_map_, planner_data_); } // NOTE: @@ -776,7 +866,7 @@ std::vector GoalPlannerModule::sortPullOverPathCandidatesByGoalPri utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); for (const auto & margin : margins) { if (!checkObjectsCollision( - resampled_path, margin, + resampled_path, planner_data_, *parameters_, margin, /*extract_static_objects=*/true)) { return margin; } @@ -863,16 +953,17 @@ std::optional> GoalPlannerModule::selectP const auto resampled_path = utils::resamplePathWithSpline(pull_over_path.getParkingPath(), 0.5); if ( - parameters_->use_object_recognition && checkObjectsCollision( - resampled_path, collision_check_margin, - /*extract_static_objects=*/true, - /*update_debug_data=*/true)) { + parameters_->use_object_recognition && + checkObjectsCollision( + resampled_path, planner_data_, *parameters_, collision_check_margin, + /*extract_static_objects=*/true, + /*update_debug_data=*/true)) { continue; } if ( parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(resampled_path)) { + checkOccupancyGridCollision(resampled_path, occupancy_grid_map_)) { continue; } @@ -908,7 +999,12 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) } if ( - parameters_->safety_check_params.enable_safety_check && !isSafePath().first && isActivated()) { + parameters_->safety_check_params.enable_safety_check && + !isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_) + .first && + isActivated()) { // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints @@ -931,7 +1027,11 @@ void GoalPlannerModule::setOutput(BehaviorModuleOutput & output) setDrivableAreaInfo(output); // set hazard and turn signal - if (hasDecidedPath() && isActivated()) { + if ( + hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_) && + isActivated()) { setTurnSignalInfo(output); } } @@ -995,20 +1095,47 @@ void GoalPlannerModule::updateSteeringFactor( pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); } -bool GoalPlannerModule::hasDecidedPath() const -{ - return checkDecidingPathStatus().first == DecidingPathStatus::DECIDED; -} - -bool GoalPlannerModule::hasNotDecidedPath() const -{ - return checkDecidingPathStatus().first == DecidingPathStatus::NOT_DECIDED; -} - -DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const -{ - const auto & prev_status = prev_data_.deciding_path_status; - const bool enable_safety_check = parameters_->safety_check_params.enable_safety_check; +bool GoalPlannerModule::hasDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const +{ + return checkDecidingPathStatus( + planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params, goal_searcher) + .first == DecidingPathStatus::DECIDED; +} + +bool GoalPlannerModule::hasNotDecidedPath( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const +{ + return checkDecidingPathStatus( + planner_data, occupancy_grid_map, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params, goal_searcher) + .first == DecidingPathStatus::NOT_DECIDED; +} + +DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params, + const std::shared_ptr goal_searcher) const +{ + const auto & prev_status = thread_safe_data_.get_prev_data().deciding_path_status; + const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; // Once this function returns true, it will continue to return true thereafter if (prev_status.first == DecidingPathStatus::DECIDED) { @@ -1022,7 +1149,13 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const // If it is dangerous against dynamic objects before approval, do not determine the path. // This eliminates a unsafe path to be approved - if (enable_safety_check && !isSafePath().first && !isActivated()) { + if ( + enable_safety_check && + !isSafePath( + planner_data, parameters, ego_predicted_path_params, objects_filtering_params, + safety_check_params) + .first && + !isActivated()) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before " @@ -1038,11 +1171,11 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const const double hysteresis_factor = 0.9; // check goal pose collision - goal_searcher_->setPlannerData(planner_data_); const auto modified_goal_opt = thread_safe_data_.get_modified_goal_pose(); if ( - modified_goal_opt && !goal_searcher_->isSafeGoalWithMarginScaleFactor( - modified_goal_opt.value(), hysteresis_factor)) { + modified_goal_opt && + !goal_searcher->isSafeGoalWithMarginScaleFactor( + modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, planner_data)) { RCLCPP_DEBUG(getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } @@ -1050,15 +1183,20 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const // check current parking path collision const auto parking_path = utils::resamplePathWithSpline(pull_over_path->getParkingPath(), 0.5); const double margin = - parameters_->object_recognition_collision_check_hard_margins.back() * hysteresis_factor; - if (checkObjectsCollision(parking_path, margin, /*extract_static_objects=*/false)) { + parameters.object_recognition_collision_check_hard_margins.back() * hysteresis_factor; + if (checkObjectsCollision( + parking_path, planner_data, parameters, margin, /*extract_static_objects=*/false)) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects"); return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } - if (enable_safety_check && !isSafePath().first) { + if ( + enable_safety_check && !isSafePath( + planner_data, parameters, ego_predicted_path_params, + objects_filtering_params, safety_check_params) + .first) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects"); @@ -1082,7 +1220,7 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const } // if ego is sufficiently close to the start of the nearest candidate path, the path is decided - const auto & current_pose = planner_data_->self_odometry->pose.pose; + const auto & current_pose = planner_data->self_odometry->pose.pose; const size_t ego_segment_idx = motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); @@ -1091,13 +1229,13 @@ DecidingPathStatusWithStamp GoalPlannerModule::checkDecidingPathStatus() const const double dist_to_parking_start_pose = calcSignedArcLength( current_path.points, current_pose.position, ego_segment_idx, pull_over_path->start_pose.position, start_pose_segment_idx); - if (dist_to_parking_start_pose > parameters_->decide_path_distance) { + if (dist_to_parking_start_pose > parameters.decide_path_distance) { return {DecidingPathStatus::NOT_DECIDED, clock_->now()}; } // if object recognition for path collision check is enabled, transition to DECIDING to check // collision for a certain period of time. Otherwise, transition to DECIDED directly. - if (parameters_->use_object_recognition) { + if (parameters.use_object_recognition) { RCLCPP_DEBUG( getLogger(), "[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain " @@ -1122,7 +1260,9 @@ void GoalPlannerModule::decideVelocity() BehaviorModuleOutput GoalPlannerModule::planPullOver() { - if (!hasDecidedPath()) { + if (!hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_)) { return planPullOverAsCandidate(); } @@ -1166,7 +1306,12 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() return getPreviousModuleOutput(); } - if (hasNotDecidedPath() && needPathUpdate(1.0 /*path_update_duration*/)) { + if ( + hasNotDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_) && + needPathUpdate( + planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, *parameters_)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_ @@ -1175,9 +1320,8 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput() thread_safe_data_.clearPullOverPath(); // update goal candidates - goal_searcher_->setPlannerData(planner_data_); auto goal_candidates = thread_safe_data_.get_goal_candidates(); - goal_searcher_->update(goal_candidates); + goal_searcher_->update(goal_candidates, occupancy_grid_map_, planner_data_); // update pull over path candidates const auto pull_over_path_candidates = sortPullOverPathCandidatesByGoalPriority( @@ -1238,9 +1382,14 @@ void GoalPlannerModule::postProcess() return; } - const bool has_decided_path = hasDecidedPath(); const auto distance_to_path_change = calcDistanceToPathChange(); + // TODO(Mamoru Sobue): repetitive call to checkDecidingPathStatus() in the main thread is a + // waste of time because it gives same result throughout the main thread. + const bool has_decided_path = hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_); + if (has_decided_path) { updateRTCStatus(distance_to_path_change.first, distance_to_path_change.second); } @@ -1258,27 +1407,35 @@ void GoalPlannerModule::updatePreviousData() { // for the next loop setOutput(). // this is used to determine whether to generate a new stop path or keep the current stop path. - prev_data_.found_path = thread_safe_data_.foundPullOverPath(); + // TODO(Mamoru Sobue): put prev_data_ out of ThreadSafeData + auto prev_data = thread_safe_data_.get_prev_data(); + prev_data.found_path = thread_safe_data_.foundPullOverPath(); - prev_data_.deciding_path_status = checkDecidingPathStatus(); + prev_data.deciding_path_status = checkDecidingPathStatus( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_); // This is related to safety check, so if it is disabled, return here. if (!parameters_->safety_check_params.enable_safety_check) { - prev_data_.safety_status.is_safe = true; - return; - } - - // Even if the current path is safe, it will not be safe unless it stands for a certain period of - // time. Record the time when the current path has become safe - const auto [is_safe, current_is_safe] = isSafePath(); - if (current_is_safe) { - if (!prev_data_.safety_status.safe_start_time) { - prev_data_.safety_status.safe_start_time = clock_->now(); - } + prev_data.safety_status.is_safe = true; } else { - prev_data_.safety_status.safe_start_time = std::nullopt; + // Even if the current path is safe, it will not be safe unless it stands for a certain period + // of time. Record the time when the current path has become safe + const auto [is_safe, current_is_safe] = isSafePath( + planner_data_, *parameters_, ego_predicted_path_params_, objects_filtering_params_, + safety_check_params_); + if (current_is_safe) { + if (!prev_data.safety_status.safe_start_time) { + prev_data.safety_status.safe_start_time = clock_->now(); + } + } else { + prev_data.safety_status.safe_start_time = std::nullopt; + } + prev_data.safety_status.is_safe = is_safe; } - prev_data_.safety_status.is_safe = is_safe; + + // commit the change + thread_safe_data_.set_prev_data(prev_data); } BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() @@ -1355,8 +1512,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath() const // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible // stop point is found, stop at this position. - const auto closest_goal_candidate = - goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); + const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( + thread_safe_data_.get_goal_candidates(), planner_data_); const auto decel_pose = calcLongitudinalOffsetPose( extended_prev_path.points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -1484,10 +1641,13 @@ bool GoalPlannerModule::isStopped() return isStopped(odometry_buffer_stopped_, parameters_->th_stopped_time); } -bool GoalPlannerModule::isStuck() +bool GoalPlannerModule::isStuck( + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const GoalPlannerParameters & parameters) { const std::lock_guard lock(mutex_); - if (isOnModifiedGoal()) { + if (isOnModifiedGoal(planner_data->self_odometry->pose.pose, parameters)) { return false; } @@ -1507,17 +1667,18 @@ bool GoalPlannerModule::isStuck() } if ( - parameters_->use_object_recognition && + parameters.use_object_recognition && checkObjectsCollision( - thread_safe_data_.get_pull_over_path()->getCurrentPath(), + thread_safe_data_.get_pull_over_path()->getCurrentPath(), planner_data, parameters, /*extract_static_objects=*/false, - parameters_->object_recognition_collision_check_hard_margins.back())) { + parameters.object_recognition_collision_check_hard_margins.back())) { return true; } if ( - parameters_->use_occupancy_grid_for_path_collision_check && - checkOccupancyGridCollision(thread_safe_data_.get_pull_over_path()->getCurrentPath())) { + parameters.use_occupancy_grid_for_path_collision_check && + checkOccupancyGridCollision( + thread_safe_data_.get_pull_over_path()->getCurrentPath(), occupancy_grid_map)) { return true; } @@ -1563,15 +1724,15 @@ bool GoalPlannerModule::hasFinishedCurrentPath() parameters_->th_arrived_distance; } -bool GoalPlannerModule::isOnModifiedGoal() const +bool GoalPlannerModule::isOnModifiedGoal( + const Pose & current_pose, const GoalPlannerParameters & parameters) const { if (!thread_safe_data_.get_modified_goal_pose()) { return false; } - const Pose current_pose = planner_data_->self_odometry->pose.pose; return calcDistance2d(current_pose, thread_safe_data_.get_modified_goal_pose()->goal_pose) < - parameters_->th_arrived_distance; + parameters.th_arrived_distance; } TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() @@ -1640,31 +1801,34 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo() return new_signal; } -bool GoalPlannerModule::checkOccupancyGridCollision(const PathWithLaneId & path) const +bool GoalPlannerModule::checkOccupancyGridCollision( + const PathWithLaneId & path, + const std::shared_ptr occupancy_grid_map) const { - if (!occupancy_grid_map_) { + if (!occupancy_grid_map) { return false; } const bool check_out_of_range = false; - return occupancy_grid_map_->hasObstacleOnPath(path, check_out_of_range); + return occupancy_grid_map->hasObstacleOnPath(path, check_out_of_range); } bool GoalPlannerModule::checkObjectsCollision( - const PathWithLaneId & path, const double collision_check_margin, + const PathWithLaneId & path, const std::shared_ptr planner_data, + const GoalPlannerParameters & parameters, const double collision_check_margin, const bool extract_static_objects, const bool update_debug_data) const { const auto target_objects = std::invoke([&]() { - const auto & p = parameters_; - const auto & rh = *(planner_data_->route_handler); - const auto objects = *(planner_data_->dynamic_object); + const auto & p = parameters; + const auto & rh = *(planner_data->route_handler); + const auto objects = *(planner_data->dynamic_object); if (extract_static_objects) { return goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects, p->th_moving_object_velocity); + rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, + p.detection_bound_offset, objects, p.th_moving_object_velocity); } return goal_planner_utils::extractObjectsInExpandedPullOverLanes( - rh, left_side_parking_, p->backward_goal_search_length, p->forward_goal_search_length, - p->detection_bound_offset, objects); + rh, left_side_parking_, p.backward_goal_search_length, p.forward_goal_search_length, + p.detection_bound_offset, objects); }); std::vector obj_polygons; @@ -1683,8 +1847,8 @@ bool GoalPlannerModule::checkObjectsCollision( const auto p = path.points.at(i); const double extra_stopping_margin = std::min( - std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters_->maximum_deceleration, - parameters_->object_recognition_collision_check_max_extra_stopping_margin); + std::pow(p.point.longitudinal_velocity_mps, 2) * 0.5 / parameters.maximum_deceleration, + parameters.object_recognition_collision_check_max_extra_stopping_margin); // The square is meant to imply centrifugal force, but it is not a very well-founded formula. // TODO(kosuke55): It is needed to consider better way because there is an inherently different @@ -1695,9 +1859,9 @@ bool GoalPlannerModule::checkObjectsCollision( const auto ego_polygon = tier4_autoware_utils::toFootprint( p.point.pose, - planner_data_->parameters.base_link2front + collision_check_margin + extra_stopping_margin, - planner_data_->parameters.base_link2rear + collision_check_margin, - planner_data_->parameters.vehicle_width + collision_check_margin * 2.0 + + planner_data->parameters.base_link2front + collision_check_margin + extra_stopping_margin, + planner_data->parameters.base_link2rear + collision_check_margin, + planner_data->parameters.vehicle_width + collision_check_margin * 2.0 + extra_lateral_margin * 2.0); ego_polygons_expanded.push_back(ego_polygon); } @@ -1780,8 +1944,8 @@ double GoalPlannerModule::calcSignedArcLengthFromEgo( void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const { // decelerate before the search area start - const auto closest_goal_candidate = - goal_searcher_->getClosetGoalCandidateAlongLanes(thread_safe_data_.get_goal_candidates()); + const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( + thread_safe_data_.get_goal_candidates(), planner_data_); const auto decel_pose = calcLongitudinalOffsetPose( pull_over_path.getFullPath().points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -1953,6 +2117,7 @@ bool GoalPlannerModule::isCrossingPossible(const PullOverPath & pull_over_path) return isCrossingPossible(start_pose, end_pose, lanes); } +/* void GoalPlannerModule::updateSafetyCheckTargetObjectsData( const PredictedObjects & filtered_objects, const TargetObjectsOnLane & target_objects_on_lane, const std::vector & ego_predicted_path) const @@ -1961,6 +2126,7 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData( goal_planner_data_.target_objects_on_lane = target_objects_on_lane; goal_planner_data_.ego_predicted_path = ego_predicted_path; } +*/ static std::vector filterObjectsByWithinPolicy( const std::shared_ptr & objects, @@ -2006,26 +2172,29 @@ static std::vector filterOb return refined_filtered_objects; } -std::pair GoalPlannerModule::isSafePath() const +std::pair GoalPlannerModule::isSafePath( + const std::shared_ptr planner_data, const GoalPlannerParameters & parameters, + const std::shared_ptr & ego_predicted_path_params, + const std::shared_ptr & objects_filtering_params, + const std::shared_ptr & safety_check_params) const { if (!thread_safe_data_.get_pull_over_path()) { return {false, false}; } const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath(); - const auto & current_pose = planner_data_->self_odometry->pose.pose; + const auto & current_pose = planner_data->self_odometry->pose.pose; const double current_velocity = std::hypot( - planner_data_->self_odometry->twist.twist.linear.x, - planner_data_->self_odometry->twist.twist.linear.y); - const auto & dynamic_object = planner_data_->dynamic_object; - const auto & route_handler = planner_data_->route_handler; + planner_data->self_odometry->twist.twist.linear.x, + planner_data->self_odometry->twist.twist.linear.y); + const auto & dynamic_object = planner_data->dynamic_object; + const auto & route_handler = planner_data->route_handler; const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length, + planner_data, parameters.backward_goal_search_length, parameters.forward_goal_search_length, /*forward_only_in_route*/ false); const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( - *route_handler, left_side_parking_, parameters_->backward_goal_search_length, - parameters_->forward_goal_search_length); - const size_t ego_seg_idx = planner_data_->findEgoSegmentIndex(pull_over_path.points); + *route_handler, left_side_parking_, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + const size_t ego_seg_idx = planner_data->findEgoSegmentIndex(pull_over_path.points); const std::pair terminal_velocity_and_accel = utils::parking_departure::getPairsTerminalVelocityAndAccel( thread_safe_data_.get_pull_over_path()->pairs_terminal_velocity_and_accel, @@ -2033,15 +2202,15 @@ std::pair GoalPlannerModule::isSafePath() const RCLCPP_DEBUG( getLogger(), "pairs_terminal_velocity_and_accel for goal_planner: %f, %f", terminal_velocity_and_accel.first, terminal_velocity_and_accel.second); - utils::parking_departure::updatePathProperty( - ego_predicted_path_params_, terminal_velocity_and_accel); + auto temp_param = std::make_shared(*ego_predicted_path_params); + utils::parking_departure::updatePathProperty(temp_param, terminal_velocity_and_accel); // TODO(Sugahara): shoule judge is_object_front properly const bool is_object_front = true; const bool limit_to_max_velocity = true; const auto ego_predicted_path = behavior_path_planner::utils::path_safety_checker::createPredictedPath( - ego_predicted_path_params_, pull_over_path.points, current_pose, current_velocity, - ego_seg_idx, is_object_front, limit_to_max_velocity); + ego_predicted_path_params, pull_over_path.points, current_pose, current_velocity, ego_seg_idx, + is_object_front, limit_to_max_velocity); // ========================================================================================== // if ego is before the entry of pull_over_lanes, the beginning of the safety check area @@ -2083,36 +2252,38 @@ std::pair GoalPlannerModule::isSafePath() const const auto expanded_pull_over_lanes_between_ego = goal_planner_utils::generateBetweenEgoAndExpandedPullOverLanes( pull_over_lanes, left_side_parking_, ego_pose_for_expand, - planner_data_->parameters.vehicle_info, parameters_->outer_road_detection_offset, - parameters_->inner_road_detection_offset); + planner_data->parameters.vehicle_info, parameters.outer_road_detection_offset, + parameters.inner_road_detection_offset); const auto merged_expanded_pull_over_lanes = lanelet::utils::combineLaneletsShape(expanded_pull_over_lanes_between_ego); debug_data_.expanded_pull_over_lane_between_ego = merged_expanded_pull_over_lanes; const auto filtered_objects = filterObjectsByWithinPolicy( - dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params_); + dynamic_object, {merged_expanded_pull_over_lanes}, objects_filtering_params); + const auto prev_data = thread_safe_data_.get_prev_data(); const double hysteresis_factor = - prev_data_.safety_status.is_safe ? 1.0 : parameters_->hysteresis_factor_expand_rate; + prev_data.safety_status.is_safe ? 1.0 : parameters.hysteresis_factor_expand_rate; + CollisionCheckDebugMap collision_check{}; const bool current_is_safe = std::invoke([&]() { - if (parameters_->safety_check_params.method == "RSS") { + if (parameters.safety_check_params.method == "RSS") { return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( - pull_over_path, ego_predicted_path, filtered_objects, goal_planner_data_.collision_check, - planner_data_->parameters, safety_check_params_->rss_params, - objects_filtering_params_->use_all_predicted_path, hysteresis_factor); - } else if (parameters_->safety_check_params.method == "integral_predicted_polygon") { + pull_over_path, ego_predicted_path, filtered_objects, collision_check, + planner_data->parameters, safety_check_params->rss_params, + objects_filtering_params->use_all_predicted_path, hysteresis_factor); + } else if (parameters.safety_check_params.method == "integral_predicted_polygon") { return utils::path_safety_checker::checkSafetyWithIntegralPredictedPolygon( ego_predicted_path, vehicle_info_, filtered_objects, - objects_filtering_params_->check_all_predicted_path, - parameters_->safety_check_params.integral_predicted_polygon_params, - goal_planner_data_.collision_check); + objects_filtering_params->check_all_predicted_path, + parameters.safety_check_params.integral_predicted_polygon_params, collision_check); } RCLCPP_ERROR( getLogger(), " [pull_over] invalid safety check method: %s", - parameters_->safety_check_params.method.c_str()); + parameters.safety_check_params.method.c_str()); throw std::domain_error("[pull_over] invalid safety check method"); }); + thread_safe_data_.set_collision_check(collision_check); /* * ==== is_safe @@ -2129,9 +2300,9 @@ std::pair GoalPlannerModule::isSafePath() const */ if (current_is_safe) { if ( - prev_data_.safety_status.safe_start_time && - (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds() > - parameters_->safety_check_params.keep_unsafe_time) { + prev_data.safety_status.safe_start_time && + (clock_->now() - prev_data.safety_status.safe_start_time.value()).seconds() > + parameters.safety_check_params.keep_unsafe_time) { return {true /*is_safe*/, true /*current_is_safe*/}; } } @@ -2165,8 +2336,12 @@ void GoalPlannerModule::setDebugData() }; if (utils::isAllowedGoalModification(planner_data_->route_handler)) { // Visualize pull over areas - const auto color = hasDecidedPath() ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow - : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green + const auto color = + hasDecidedPath( + planner_data_, occupancy_grid_map_, *parameters_, ego_predicted_path_params_, + objects_filtering_params_, safety_check_params_, goal_searcher_) + ? createMarkerColor(1.0, 1.0, 0.0, 0.999) // yellow + : createMarkerColor(0.0, 1.0, 0.0, 0.999); // green const double z = planner_data_->route_handler->getGoalPose().position.z; add(goal_planner_utils::createPullOverAreaMarkerArray( goal_searcher_->getAreaPolygons(), header, color, z)); @@ -2179,9 +2354,11 @@ void GoalPlannerModule::setDebugData() // Visualize previous module output add(createPathMarkerArray( getPreviousModuleOutput().path, "previous_module_path", 0, 1.0, 0.0, 0.0)); - if (last_previous_module_output_.has_value()) { + + const auto last_previous_module_output = thread_safe_data_.get_last_previous_module_output(); + if (last_previous_module_output.has_value()) { add(createPathMarkerArray( - last_previous_module_output_.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); + last_previous_module_output.value().path, "last_previous_module_path", 0, 0.0, 1.0, 1.0)); } // Visualize path and related pose @@ -2238,6 +2415,7 @@ void GoalPlannerModule::setDebugData() } } + auto collision_check = thread_safe_data_.get_collision_check(); // safety check if (parameters_->safety_check_params.enable_safety_check) { if (goal_planner_data_.ego_predicted_path.size() > 0) { @@ -2252,33 +2430,35 @@ void GoalPlannerModule::setDebugData() } if (parameters_->safety_check_params.method == "RSS") { - add(showSafetyCheckInfo(goal_planner_data_.collision_check, "object_debug_info")); + add(showSafetyCheckInfo(collision_check, "object_debug_info")); } - add(showPredictedPath(goal_planner_data_.collision_check, "ego_predicted_path")); - add(showPolygon(goal_planner_data_.collision_check, "ego_and_target_polygon_relation")); + add(showPredictedPath(collision_check, "ego_predicted_path")); + add(showPolygon(collision_check, "ego_and_target_polygon_relation")); // set objects of interest - for (const auto & [uuid, data] : goal_planner_data_.collision_check) { + for (const auto & [uuid, data] : collision_check) { const auto color = data.is_safe ? ColorName::GREEN : ColorName::RED; setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); } - utils::parking_departure::initializeCollisionCheckDebugMap(goal_planner_data_.collision_check); + // TODO(Mamoru Sobue): it is not clear where ThreadSafeData::collision_check should be cleared + utils::parking_departure::initializeCollisionCheckDebugMap(collision_check); // visualize safety status maker { + const auto prev_data = thread_safe_data_.get_prev_data(); visualization_msgs::msg::MarkerArray marker_array{}; - const auto color = prev_data_.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) - : createMarkerColor(1.0, 0.0, 0.0, 0.99); + const auto color = prev_data.safety_status.is_safe ? createMarkerColor(1.0, 1.0, 1.0, 0.99) + : createMarkerColor(1.0, 0.0, 0.0, 0.99); auto marker = createDefaultMarker( header.frame_id, header.stamp, "safety_status", 0, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0), color); marker.pose = planner_data_->self_odometry->pose.pose; - marker.text += "is_safe: " + std::to_string(prev_data_.safety_status.is_safe) + "\n"; - if (prev_data_.safety_status.safe_start_time) { + marker.text += "is_safe: " + std::to_string(prev_data.safety_status.is_safe) + "\n"; + if (prev_data.safety_status.safe_start_time) { const double elapsed_time_from_safe_start = - (clock_->now() - prev_data_.safety_status.safe_start_time.value()).seconds(); + (clock_->now() - prev_data.safety_status.safe_start_time.value()).seconds(); marker.text += "elapsed_time_from_safe_start: " + std::to_string(elapsed_time_from_safe_start) + "\n"; } @@ -2306,7 +2486,7 @@ void GoalPlannerModule::setDebugData() std::to_string(thread_safe_data_.get_pull_over_path()->partial_paths.size() - 1); } - if (isStuck()) { + if (isStuck(planner_data_, occupancy_grid_map_, *parameters_)) { marker.text += " stuck"; } else if (isStopped()) { marker.text += " stopped"; @@ -2356,9 +2536,12 @@ void GoalPlannerModule::printParkingPositionError() const distance_from_real_shoulder); } -bool GoalPlannerModule::needPathUpdate(const double path_update_duration) const +bool GoalPlannerModule::needPathUpdate( + const Pose & current_pose, const double path_update_duration, + const GoalPlannerParameters & parameters) const { - return !isOnModifiedGoal() && hasEnoughTimePassedSincePathUpdate(path_update_duration); + return !isOnModifiedGoal(current_pose, parameters) && + hasEnoughTimePassedSincePathUpdate(path_update_duration); } bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const @@ -2369,4 +2552,58 @@ bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration return (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > duration; } + +void GoalPlannerModule::GoalPlannerData::initializeOccupancyGridMap( + const PlannerData & planner_data, const GoalPlannerParameters & parameters) +{ + OccupancyGridMapParam occupancy_grid_map_param{}; + const double margin = parameters.occupancy_grid_collision_check_margin; + occupancy_grid_map_param.vehicle_shape.length = + planner_data.parameters.vehicle_length + 2 * margin; + occupancy_grid_map_param.vehicle_shape.width = planner_data.parameters.vehicle_width + 2 * margin; + occupancy_grid_map_param.vehicle_shape.base2back = + planner_data.parameters.base_link2rear + margin; + occupancy_grid_map_param.theta_size = parameters.theta_size; + occupancy_grid_map_param.obstacle_threshold = parameters.obstacle_threshold; + occupancy_grid_map = std::make_shared(); + occupancy_grid_map->setParam(occupancy_grid_map_param); +} + +GoalPlannerModule::GoalPlannerData GoalPlannerModule::GoalPlannerData::clone() const +{ + GoalPlannerModule::GoalPlannerData gp_planner_data(planner_data, parameters); + gp_planner_data.update( + parameters, ego_predicted_path_params, objects_filtering_params, safety_check_params, + planner_data, current_status, previous_module_output, goal_searcher, vehicle_footprint); + return gp_planner_data; +} + +void GoalPlannerModule::GoalPlannerData::update( + const GoalPlannerParameters & parameters_, + const std::shared_ptr & ego_predicted_path_params_, + const std::shared_ptr & objects_filtering_params_, + const std::shared_ptr & safety_check_params_, + const PlannerData & planner_data_, const ModuleStatus & current_status_, + const BehaviorModuleOutput & previous_module_output_, + const std::shared_ptr goal_searcher_, + const tier4_autoware_utils::LinearRing2d & vehicle_footprint_) +{ + parameters = parameters_; + ego_predicted_path_params = ego_predicted_path_params_; + objects_filtering_params = objects_filtering_params_; + safety_check_params = safety_check_params_; + vehicle_footprint = vehicle_footprint_; + + planner_data = planner_data_; + planner_data.route_handler = std::make_shared(*(planner_data_.route_handler)); + current_status = current_status_; + previous_module_output = previous_module_output_; + occupancy_grid_map->setMap(*(planner_data.occupancy_grid)); + // to create a deepcopy of GoalPlanner(not GoalPlannerBase), goal_searcher_ is not enough, so + // recreate it here + goal_searcher = std::make_shared(parameters, vehicle_footprint); + // and then copy the reference goal + goal_searcher->setReferenceGoal(goal_searcher_->getReferenceGoal()); +} + } // namespace behavior_path_planner diff --git a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index bd19871c482fc..df91687622349 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -90,35 +90,35 @@ struct SortByWeightedDistance }; GoalSearcher::GoalSearcher( - const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint, - const std::shared_ptr & occupancy_grid_map) + const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint) : GoalSearcherBase{parameters}, vehicle_footprint_{vehicle_footprint}, - occupancy_grid_map_{occupancy_grid_map}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } -GoalCandidates GoalSearcher::search() +GoalCandidates GoalSearcher::search( + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) { GoalCandidates goal_candidates{}; - const auto & route_handler = planner_data_->route_handler; + const auto & route_handler = planner_data->route_handler; const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; const double margin_from_boundary = parameters_.margin_from_boundary; const double lateral_offset_interval = parameters_.lateral_offset_interval; const double max_lateral_offset = parameters_.max_lateral_offset; const double ignore_distance_from_lane_start = parameters_.ignore_distance_from_lane_start; - const double vehicle_width = planner_data_->parameters.vehicle_width; - const double base_link2front = planner_data_->parameters.base_link2front; - const double base_link2rear = planner_data_->parameters.base_link2rear; + const double vehicle_width = planner_data->parameters.vehicle_width; + const double base_link2front = planner_data->parameters.base_link2front; + const double base_link2rear = planner_data->parameters.base_link2rear; const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( *route_handler, left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length); auto lanes = utils::getExtendedCurrentLanes( - planner_data_, backward_length, forward_length, + planner_data, backward_length, forward_length, /*forward_only_in_route*/ false); lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); @@ -193,17 +193,18 @@ GoalCandidates GoalSearcher::search() goal_candidates.push_back(goal_candidate); } } - createAreaPolygons(original_search_poses); + createAreaPolygons(original_search_poses, planner_data); - update(goal_candidates); + update(goal_candidates, occupancy_grid_map, planner_data); return goal_candidates; } void GoalSearcher::countObjectsToAvoid( - GoalCandidates & goal_candidates, const PredictedObjects & objects) const + GoalCandidates & goal_candidates, const PredictedObjects & objects, + const std::shared_ptr & planner_data) const { - const auto & route_handler = planner_data_->route_handler; + const auto & route_handler = planner_data->route_handler; const double forward_length = parameters_.forward_goal_search_length; const double backward_length = parameters_.backward_goal_search_length; @@ -225,7 +226,7 @@ void GoalSearcher::countObjectsToAvoid( // generate current lane center line path to check collision with objects const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); const auto current_center_line_path = std::invoke([&]() -> PathWithLaneId { const double s_start = @@ -264,16 +265,19 @@ void GoalSearcher::countObjectsToAvoid( } } -void GoalSearcher::update(GoalCandidates & goal_candidates) const +void GoalSearcher::update( + GoalCandidates & goal_candidates, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const { const auto pull_over_lane_stop_objects = goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); + *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); if (parameters_.prioritize_goals_before_objects) { - countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects); + countObjectsToAvoid(goal_candidates, pull_over_lane_stop_objects, planner_data); } if (parameters_.goal_priority == "minimum_weighted_distance") { @@ -293,7 +297,7 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const const Pose goal_pose = goal_candidate.goal_pose; // check collision with footprint - if (checkCollision(goal_pose, pull_over_lane_stop_objects)) { + if (checkCollision(goal_pose, pull_over_lane_stop_objects, occupancy_grid_map)) { goal_candidate.is_safe = false; continue; } @@ -301,9 +305,10 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects, + goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, parameters_.object_recognition_collision_check_hard_margins.back(), filter_inside); - if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) { + if (checkCollisionWithLongitudinalDistance( + goal_pose, target_objects, occupancy_grid_map, planner_data)) { goal_candidate.is_safe = false; continue; } @@ -316,7 +321,9 @@ void GoalSearcher::update(GoalCandidates & goal_candidates) const // current planner_data_ and margin scale factor. // And is_safe is not updated in this function. bool GoalSearcher::isSafeGoalWithMarginScaleFactor( - const GoalCandidate & goal_candidate, const double margin_scale_factor) const + const GoalCandidate & goal_candidate, const double margin_scale_factor, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const { if (!parameters_.use_object_recognition) { return true; @@ -326,9 +333,9 @@ bool GoalSearcher::isSafeGoalWithMarginScaleFactor( const auto pull_over_lane_stop_objects = goal_planner_utils::extractStaticObjectsInExpandedPullOverLanes( - *(planner_data_->route_handler), left_side_parking_, parameters_.backward_goal_search_length, + *(planner_data->route_handler), left_side_parking_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, parameters_.detection_bound_offset, - *(planner_data_->dynamic_object), parameters_.th_moving_object_velocity); + *(planner_data->dynamic_object), parameters_.th_moving_object_velocity); const double margin = parameters_.object_recognition_collision_check_hard_margins.back() * margin_scale_factor; @@ -341,23 +348,26 @@ bool GoalSearcher::isSafeGoalWithMarginScaleFactor( // check longitudinal margin with pull over lane objects constexpr bool filter_inside = true; const auto target_objects = goal_planner_utils::filterObjectsByLateralDistance( - goal_pose, planner_data_->parameters.vehicle_width, pull_over_lane_stop_objects, margin, + goal_pose, planner_data->parameters.vehicle_width, pull_over_lane_stop_objects, margin, filter_inside); - if (checkCollisionWithLongitudinalDistance(goal_pose, target_objects)) { + if (checkCollisionWithLongitudinalDistance( + goal_pose, target_objects, occupancy_grid_map, planner_data)) { return false; } return true; } -bool GoalSearcher::checkCollision(const Pose & pose, const PredictedObjects & objects) const +bool GoalSearcher::checkCollision( + const Pose & pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map) const { if (parameters_.use_occupancy_grid_for_goal_search) { - const Pose pose_grid_coords = global2local(occupancy_grid_map_->getMap(), pose); + const Pose pose_grid_coords = global2local(occupancy_grid_map->getMap(), pose); const auto idx = pose2index( - occupancy_grid_map_->getMap(), pose_grid_coords, occupancy_grid_map_->getParam().theta_size); + occupancy_grid_map->getMap(), pose_grid_coords, occupancy_grid_map->getParam().theta_size); const bool check_out_of_range = false; - if (occupancy_grid_map_->detectCollision(idx, check_out_of_range)) { + if (occupancy_grid_map->detectCollision(idx, check_out_of_range)) { return true; } } @@ -373,7 +383,9 @@ bool GoalSearcher::checkCollision(const Pose & pose, const PredictedObjects & ob } bool GoalSearcher::checkCollisionWithLongitudinalDistance( - const Pose & ego_pose, const PredictedObjects & objects) const + const Pose & ego_pose, const PredictedObjects & objects, + const std::shared_ptr occupancy_grid_map, + const std::shared_ptr & planner_data) const { if ( parameters_.use_occupancy_grid_for_goal_search && @@ -385,22 +397,22 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( // check forward collision const Pose ego_pose_moved_forward = calcOffsetPose(ego_pose, offset, 0, 0); const Pose forward_pose_grid_coords = - global2local(occupancy_grid_map_->getMap(), ego_pose_moved_forward); + global2local(occupancy_grid_map->getMap(), ego_pose_moved_forward); const auto forward_idx = pose2index( - occupancy_grid_map_->getMap(), forward_pose_grid_coords, - occupancy_grid_map_->getParam().theta_size); - if (occupancy_grid_map_->detectCollision(forward_idx, check_out_of_range)) { + occupancy_grid_map->getMap(), forward_pose_grid_coords, + occupancy_grid_map->getParam().theta_size); + if (occupancy_grid_map->detectCollision(forward_idx, check_out_of_range)) { return true; } // check backward collision const Pose ego_pose_moved_backward = calcOffsetPose(ego_pose, -offset, 0, 0); const Pose backward_pose_grid_coords = - global2local(occupancy_grid_map_->getMap(), ego_pose_moved_backward); + global2local(occupancy_grid_map->getMap(), ego_pose_moved_backward); const auto backward_idx = pose2index( - occupancy_grid_map_->getMap(), backward_pose_grid_coords, - occupancy_grid_map_->getParam().theta_size); - if (occupancy_grid_map_->detectCollision(backward_idx, check_out_of_range)) { + occupancy_grid_map->getMap(), backward_pose_grid_coords, + occupancy_grid_map->getParam().theta_size); + if (occupancy_grid_map->detectCollision(backward_idx, check_out_of_range)) { return true; } } @@ -408,23 +420,24 @@ bool GoalSearcher::checkCollisionWithLongitudinalDistance( if (parameters_.use_object_recognition) { if ( utils::calcLongitudinalDistanceFromEgoToObjects( - ego_pose, planner_data_->parameters.base_link2front, - planner_data_->parameters.base_link2rear, objects) < parameters_.longitudinal_margin) { + ego_pose, planner_data->parameters.base_link2front, planner_data->parameters.base_link2rear, + objects) < parameters_.longitudinal_margin) { return true; } } return false; } -void GoalSearcher::createAreaPolygons(std::vector original_search_poses) +void GoalSearcher::createAreaPolygons( + std::vector original_search_poses, const std::shared_ptr & planner_data) { using tier4_autoware_utils::MultiPolygon2d; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; - const double vehicle_width = planner_data_->parameters.vehicle_width; - const double base_link2front = planner_data_->parameters.base_link2front; - const double base_link2rear = planner_data_->parameters.base_link2rear; + const double vehicle_width = planner_data->parameters.vehicle_width; + const double base_link2front = planner_data->parameters.base_link2front; + const double base_link2rear = planner_data->parameters.base_link2rear; const double max_lateral_offset = parameters_.max_lateral_offset; const auto appendPointToPolygon = @@ -506,10 +519,11 @@ bool GoalSearcher::isInAreas(const LinearRing2d & footprint, const BasicPolygons } GoalCandidate GoalSearcher::getClosetGoalCandidateAlongLanes( - const GoalCandidates & goal_candidates) const + const GoalCandidates & goal_candidates, + const std::shared_ptr & planner_data) const { const auto current_lanes = utils::getExtendedCurrentLanes( - planner_data_, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, + planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length, /*forward_only_in_route*/ false); // Define a lambda function to compute the arc length for a given goal candidate. diff --git a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp index 93779de1e513e..8fba7f760ab9d 100644 --- a/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/shift_pull_over.cpp @@ -28,11 +28,9 @@ namespace behavior_path_planner { ShiftPullOver::ShiftPullOver( rclcpp::Node & node, const GoalPlannerParameters & parameters, - const LaneDepartureChecker & lane_departure_checker, - const std::shared_ptr & occupancy_grid_map) + const LaneDepartureChecker & lane_departure_checker) : PullOverPlannerBase{node, parameters}, lane_departure_checker_{lane_departure_checker}, - occupancy_grid_map_{occupancy_grid_map}, left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE} { } From 04faf5ede5c0b01ca69a5e254c4834b1d7448307 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 10 May 2024 13:51:09 +0900 Subject: [PATCH 141/192] feat(autonomous_emergency_braking): add param update support for AEB (#6956) add param update support for AEB Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/node.hpp | 9 ++++ .../autonomous_emergency_braking/src/node.cpp | 49 ++++++++++++++++++- 2 files changed, 57 insertions(+), 1 deletion(-) diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp index e2e2d0ae6745a..b5ddb7bf309d7 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -87,6 +87,11 @@ class CollisionDataKeeper previous_obstacle_keep_time_ = previous_obstacle_keep_time; } + std::pair getTimeout() + { + return {collision_keep_time_, previous_obstacle_keep_time_}; + } + bool checkObjectDataExpired(std::optional & data, const double timeout) { if (!data.has_value()) return true; @@ -246,6 +251,8 @@ class AEB : public rclcpp::Node void onTimer(); void onPredictedTrajectory(const Trajectory::ConstSharedPtr input_msg); void onAutowareState(const AutowareState::ConstSharedPtr input_msg); + rcl_interfaces::msg::SetParametersResult onParameter( + const std::vector & parameters); bool isDataReady(); @@ -321,6 +328,8 @@ class AEB : public rclcpp::Node double mpc_prediction_time_horizon_; double mpc_prediction_time_interval_; CollisionDataKeeper collision_data_keeper_; + // Parameter callback + OnSetParametersCallbackHandle::SharedPtr set_param_res_; }; } // namespace autoware::motion::control::autonomous_emergency_braking diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index 9847d7aae63b5..d8886672a8ecd 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -34,7 +35,6 @@ #include #include #include - #ifdef ROS_DISTRO_GALACTIC #include #include @@ -171,12 +171,59 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) collision_data_keeper_.setTimeout(collision_keeping_sec, previous_obstacle_keep_time); } + // Parameter Callback + set_param_res_ = + add_on_set_parameters_callback(std::bind(&AEB::onParameter, this, std::placeholders::_1)); + // start time const double aeb_hz = declare_parameter("aeb_hz"); const auto period_ns = rclcpp::Rate(aeb_hz).period(); timer_ = rclcpp::create_timer(this, this->get_clock(), period_ns, std::bind(&AEB::onTimer, this)); } +rcl_interfaces::msg::SetParametersResult AEB::onParameter( + const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + updateParam(parameters, "publish_debug_pointcloud", publish_debug_pointcloud_); + updateParam(parameters, "use_predicted_trajectory", use_predicted_trajectory_); + updateParam(parameters, "use_imu_path", use_imu_path_); + updateParam(parameters, "path_footprint_extra_margin", path_footprint_extra_margin_); + updateParam(parameters, "detection_range_min_height", detection_range_min_height_); + updateParam( + parameters, "detection_range_max_height_margin", detection_range_max_height_margin_); + updateParam(parameters, "voxel_grid_x", voxel_grid_x_); + updateParam(parameters, "voxel_grid_y", voxel_grid_y_); + updateParam(parameters, "voxel_grid_z", voxel_grid_z_); + updateParam(parameters, "min_generated_path_length", min_generated_path_length_); + updateParam(parameters, "expand_width", expand_width_); + updateParam(parameters, "longitudinal_offset", longitudinal_offset_); + updateParam(parameters, "t_response", t_response_); + updateParam(parameters, "a_ego_min", a_ego_min_); + updateParam(parameters, "a_obj_min", a_obj_min_); + + updateParam(parameters, "cluster_tolerance", cluster_tolerance_); + updateParam(parameters, "minimum_cluster_size", minimum_cluster_size_); + updateParam(parameters, "maximum_cluster_size", maximum_cluster_size_); + + updateParam(parameters, "imu_prediction_time_horizon", imu_prediction_time_horizon_); + updateParam(parameters, "imu_prediction_time_interval", imu_prediction_time_interval_); + updateParam(parameters, "mpc_prediction_time_horizon", mpc_prediction_time_horizon_); + updateParam(parameters, "mpc_prediction_time_interval", mpc_prediction_time_interval_); + + { // Object history data keeper setup + auto [previous_obstacle_keep_time, collision_keeping_sec] = collision_data_keeper_.getTimeout(); + updateParam(parameters, "previous_obstacle_keep_time", previous_obstacle_keep_time); + updateParam(parameters, "collision_keeping_sec", collision_keeping_sec); + collision_data_keeper_.setTimeout(collision_keeping_sec, previous_obstacle_keep_time); + } + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; +} + void AEB::onTimer() { updater_.force_update(); From 32186deaa16350ade572670cd6e415b52d5aef26 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 10 May 2024 14:10:08 +0900 Subject: [PATCH 142/192] fix(autonomous_emergency_braking): add missing erase to velocity history (#6966) add missing erase Signed-off-by: Daniel Sanchez --- .../autonomous_emergency_braking/node.hpp | 17 ++++++++--------- 1 file changed, 8 insertions(+), 9 deletions(-) diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp index b5ddb7bf309d7..43fb310b17416 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -142,13 +142,14 @@ class CollisionDataKeeper { // remove old msg from deque const auto now = clock_->now(); - std::remove_if( - obstacle_velocity_history_.begin(), obstacle_velocity_history_.end(), - [&](const auto & velocity_time_pair) { - const auto & vel_time = velocity_time_pair.second; - return ((now - vel_time).nanoseconds() * 1e-9 > previous_obstacle_keep_time_); - }); - + obstacle_velocity_history_.erase( + std::remove_if( + obstacle_velocity_history_.begin(), obstacle_velocity_history_.end(), + [&](const auto & velocity_time_pair) { + const auto & vel_time = velocity_time_pair.second; + return ((now - vel_time).nanoseconds() * 1e-9 > previous_obstacle_keep_time_); + }), + obstacle_velocity_history_.end()); obstacle_velocity_history_.emplace_back( std::make_pair(current_object_velocity, current_object_velocity_time_stamp)); } @@ -204,8 +205,6 @@ class CollisionDataKeeper }); if (!estimated_velocity_opt.has_value()) { - this->setPreviousObjectData(closest_object); - this->resetVelocityHistory(); return std::nullopt; } From 9378b4f94b13b498a110dbd25fb41d3e8922d834 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Fri, 10 May 2024 14:50:49 +0900 Subject: [PATCH 143/192] fix(componet_state_monitor): remove ndt node alive monitoring (#6957) remove ndt node alive monitoring Signed-off-by: Yamato Ando --- system/component_state_monitor/config/topics.yaml | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/system/component_state_monitor/config/topics.yaml b/system/component_state_monitor/config/topics.yaml index 6e8ef1b6ed445..098aa0e56b1ae 100644 --- a/system/component_state_monitor/config/topics.yaml +++ b/system/component_state_monitor/config/topics.yaml @@ -50,19 +50,6 @@ error_rate: 1.0 timeout: 1.0 -- module: localization - mode: [online, logging_simulation] - type: autonomous - args: - node_name_suffix: pose_estimator_pose - topic: /localization/pose_estimator/pose_with_covariance - topic_type: geometry_msgs/msg/PoseWithCovarianceStamped - best_effort: false - transient_local: false - warn_rate: 2.0 - error_rate: 1.0 - timeout: 1.3 - - module: perception mode: [online, logging_simulation] type: launch From 299b05048f63ecc7714ac76115508e679836ccc9 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 10 May 2024 14:57:16 +0900 Subject: [PATCH 144/192] feat(path_sampler): make the trajectory smoother, add params, fix crash (#6939) Signed-off-by: Maxime CLEMENT --- .../src/sampling_planner_module.cpp | 16 +- .../include/path_sampler/node.hpp | 5 +- .../include/path_sampler/parameters.hpp | 6 + .../path_sampler/src/node.cpp | 167 +++++++++++------- .../constraints/hard_constraint.hpp | 4 +- .../include/sampler_common/structures.hpp | 17 +- .../constraints/hard_constraint.cpp | 19 +- 7 files changed, 149 insertions(+), 85 deletions(-) diff --git a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 73a726d8cdf7c..4b0ecdcd24e14 100644 --- a/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -54,19 +54,19 @@ SamplingPlannerModule::SamplingPlannerModule( sampler_common::Path & path, const sampler_common::Constraints & constraints, const MultiPoint2d & footprint) -> bool { if (!footprint.empty()) { - path.constraint_results.drivable_area = + path.constraint_results.inside_drivable_area = bg::within(footprint, constraints.drivable_polygons); } for (const auto & f : footprint) { const auto collision_index = constraints.rtree.qbegin(bgi::intersects(f)); if (collision_index != constraints.rtree.qend()) { - path.constraint_results.collision = false; + path.constraint_results.collision_free = false; break; } } - return path.constraint_results.collision && path.constraint_results.drivable_area; + return path.constraint_results.collision_free && path.constraint_results.inside_drivable_area; }); hard_constraints_.emplace_back( @@ -74,14 +74,14 @@ SamplingPlannerModule::SamplingPlannerModule( sampler_common::Path & path, const sampler_common::Constraints & constraints, [[maybe_unused]] const MultiPoint2d & footprint) -> bool { if (path.curvatures.empty()) { - path.constraint_results.curvature = false; + path.constraint_results.valid_curvature = false; return false; } const bool curvatures_satisfied = std::all_of(path.curvatures.begin(), path.curvatures.end(), [&](const auto & v) -> bool { return (v > constraints.hard.min_curvature) && (v < constraints.hard.max_curvature); }); - path.constraint_results.curvature = curvatures_satisfied; + path.constraint_results.valid_curvature = curvatures_satisfied; return curvatures_satisfied; }); @@ -267,9 +267,9 @@ bool SamplingPlannerModule::isReferencePathSafe() const []( sampler_common::Path & path, const sampler_common::Constraints & constraints, const MultiPoint2d & footprint) -> bool { - path.constraint_results.collision = + path.constraint_results.collision_free = !sampler_common::constraints::has_collision(footprint, constraints.obstacle_polygons); - return path.constraint_results.collision; + return path.constraint_results.collision_free; }); evaluateHardConstraints( reference_path, internal_params_->constraints, footprint, hard_constraints_reference_path); @@ -591,7 +591,7 @@ BehaviorModuleOutput SamplingPlannerModule::plan() sampler_common::constraints::buildFootprintPoints(path, internal_params_->constraints); std::vector hard_constraints_results = evaluateHardConstraints(path, internal_params_->constraints, footprint, hard_constraints_); - path.constraint_results.curvature = true; + path.constraint_results.valid_curvature = true; debug_data_.footprints.push_back(footprint); std::vector soft_constraints_results = evaluateSoftConstraints( path, internal_params_->constraints, soft_constraints_, soft_constraints_input); diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp b/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp index 50464f12114b0..ab9bc71bc79e4 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp +++ b/planning/sampling_based_planner/path_sampler/include/path_sampler/node.hpp @@ -95,7 +95,10 @@ class PathSampler : public rclcpp::Node void copyVelocity( const std::vector & from_traj, std::vector & to_traj, const geometry_msgs::msg::Pose & ego_pose); - std::vector generatePath(const PlannerData & planner_data); + sampler_common::Path generatePath(const PlannerData & planner_data); + std::vector generateCandidatesFromPreviousPath( + const PlannerData & planner_data, const sampler_common::transform::Spline2D & path_spline); + std::vector generateTrajectoryPoints(const PlannerData & planner_data); void publishVirtualWall(const geometry_msgs::msg::Pose & stop_pose) const; void publishDebugMarker(const std::vector & traj_points) const; }; diff --git a/planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp b/planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp index 1c5c51e33b431..03887d8357e0d 100644 --- a/planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp +++ b/planning/sampling_based_planner/path_sampler/include/path_sampler/parameters.hpp @@ -46,6 +46,12 @@ struct Parameters bool force_zero_heading{}; bool smooth_reference{}; } preprocessing{}; + + struct + { + double max_lat_dev{}; + double direct_reuse_dist{}; + } path_reuse{}; }; #endif // PATH_SAMPLER__PARAMETERS_HPP_ diff --git a/planning/sampling_based_planner/path_sampler/src/node.cpp b/planning/sampling_based_planner/path_sampler/src/node.cpp index 748486edf9ff6..97bafb68c47a8 100644 --- a/planning/sampling_based_planner/path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/path_sampler/src/node.cpp @@ -84,12 +84,20 @@ PathSampler::PathSampler(const rclcpp::NodeOptions & node_options) declare_parameter("constraints.hard.max_curvature"); params_.constraints.hard.min_curvature = declare_parameter("constraints.hard.min_curvature"); + params_.constraints.hard.min_dist_from_obstacles = + declare_parameter("constraints.hard.min_distance_from_obstacles"); + params_.constraints.hard.limit_footprint_inside_drivable_area = + declare_parameter("constraints.hard.limit_footprint_inside_drivable_area"); params_.constraints.soft.lateral_deviation_weight = declare_parameter("constraints.soft.lateral_deviation_weight"); params_.constraints.soft.length_weight = declare_parameter("constraints.soft.length_weight"); params_.constraints.soft.curvature_weight = declare_parameter("constraints.soft.curvature_weight"); + params_.path_reuse.max_lat_dev = + declare_parameter("path_reuse.maximum_lateral_deviation"); + params_.path_reuse.direct_reuse_dist = + declare_parameter("path_reuse.direct_reuse_distance"); params_.sampling.enable_frenet = declare_parameter("sampling.enable_frenet"); params_.sampling.enable_bezier = declare_parameter("sampling.enable_bezier"); params_.sampling.resolution = declare_parameter("sampling.resolution"); @@ -144,6 +152,12 @@ rcl_interfaces::msg::SetParametersResult PathSampler::onParam( updateParam(parameters, "constraints.hard.max_curvature", params_.constraints.hard.max_curvature); updateParam(parameters, "constraints.hard.min_curvature", params_.constraints.hard.min_curvature); + updateParam( + parameters, "constraints.hard.min_distance_from_obstacles", + params_.constraints.hard.min_dist_from_obstacles); + updateParam( + parameters, "constraints.hard.limit_footprint_inside_drivable_area", + params_.constraints.hard.limit_footprint_inside_drivable_area); updateParam( parameters, "constraints.soft.lateral_deviation_weight", params_.constraints.soft.lateral_deviation_weight); @@ -243,9 +257,8 @@ void PathSampler::onPath(const Path::SharedPtr path_ptr) const auto generated_traj_points = generateTrajectory(planner_data); // 3. extend trajectory to connect the optimized trajectory and the following path smoothly if (!generated_traj_points.empty()) { - auto full_traj_points = extendTrajectory(planner_data.traj_points, generated_traj_points); const auto output_traj_msg = - motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); + motion_utils::convertToTrajectory(generated_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); } else { auto stopping_traj = trajectory_utils::convertToTrajectoryPoints(planner_data.traj_points); @@ -367,7 +380,7 @@ std::vector PathSampler::generateTrajectory(const PlannerData & const auto & input_traj_points = planner_data.traj_points; - auto generated_traj_points = generatePath(planner_data); + auto generated_traj_points = generateTrajectoryPoints(planner_data); copyVelocity(input_traj_points, generated_traj_points, planner_data.ego_pose); copyZ(input_traj_points, generated_traj_points); @@ -377,65 +390,89 @@ std::vector PathSampler::generateTrajectory(const PlannerData & return generated_traj_points; } -std::vector PathSampler::generatePath(const PlannerData & planner_data) +std::vector PathSampler::generateCandidatesFromPreviousPath( + const PlannerData & planner_data, const sampler_common::transform::Spline2D & path_spline) { - std::vector trajectory; - time_keeper_ptr_->tic(__func__); - const auto & p = planner_data; - - const auto path_spline = preparePathSpline(p.traj_points, params_.preprocessing.smooth_reference); + std::vector candidates; + if (!prev_path_ || prev_path_->points.size() < 2) return candidates; + // Update previous path sampler_common::State current_state; current_state.pose = {planner_data.ego_pose.position.x, planner_data.ego_pose.position.y}; current_state.heading = tf2::getYaw(planner_data.ego_pose.orientation); + const auto closest_iter = std::min_element( + prev_path_->points.begin(), prev_path_->points.end() - 1, + [&](const auto & p1, const auto & p2) { + return boost::geometry::distance(p1, current_state.pose) <= + boost::geometry::distance(p2, current_state.pose); + }); + if (closest_iter != prev_path_->points.end()) { + const auto current_idx = std::distance(prev_path_->points.begin(), closest_iter); + const auto length_offset = prev_path_->lengths[current_idx]; + for (auto & l : prev_path_->lengths) l -= length_offset; + constexpr auto behind_dist = -5.0; // [m] TODO(Maxime): param + auto behind_idx = current_idx; + while (behind_idx > 0 && prev_path_->lengths[behind_idx] > behind_dist) --behind_idx; + *prev_path_ = *prev_path_->subset(behind_idx, prev_path_->points.size()); + + // Use previous path for replanning + const auto prev_path_length = prev_path_->lengths.back(); + const auto reuse_step = prev_path_length / params_.sampling.previous_path_reuse_points_nb; + for (double reuse_length = reuse_step; reuse_length <= prev_path_length; + reuse_length += reuse_step) { + sampler_common::State reuse_state; + size_t reuse_idx = 0; + for (reuse_idx = 0; reuse_idx + 1 < prev_path_->lengths.size() && + prev_path_->lengths[reuse_idx] < reuse_length; + ++reuse_idx) + ; + if (reuse_idx == 0UL) continue; + const auto reused_path = *prev_path_->subset(0UL, reuse_idx); + reuse_state.curvature = reused_path.curvatures.back(); + reuse_state.pose = reused_path.points.back(); + reuse_state.heading = reused_path.yaws.back(); + reuse_state.frenet = path_spline.frenet(reuse_state.pose); + auto paths = generateCandidatePaths(reuse_state, path_spline, reuse_length, params_); + for (auto & p : paths) candidates.push_back(reused_path.extend(p)); + } + } + return candidates; +} - const auto planning_state = getPlanningState(current_state, path_spline); - prepareConstraints(params_.constraints, *in_objects_ptr_, p.left_bound, p.right_bound); - - auto candidate_paths = generateCandidatePaths(planning_state, path_spline, 0.0, params_); - if (prev_path_ && prev_path_->lengths.size() > 1) { - // Update previous path - constexpr auto max_deviation = 2.0; // [m] TODO(Maxime): param - const auto closest_iter = std::min_element( - prev_path_->points.begin(), prev_path_->points.end() - 1, - [&](const auto & p1, const auto & p2) { - return boost::geometry::distance(p1, current_state.pose) <= - boost::geometry::distance(p2, current_state.pose); - }); - if ( - closest_iter != prev_path_->points.end() && - boost::geometry::distance(*closest_iter, current_state.pose) <= max_deviation) { - const auto current_idx = std::distance(prev_path_->points.begin(), closest_iter); - const auto length_offset = prev_path_->lengths[current_idx]; - for (auto & l : prev_path_->lengths) l -= length_offset; - constexpr auto behind_dist = -5.0; // [m] TODO(Maxime): param - auto behind_idx = current_idx; - while (behind_idx > 0 && prev_path_->lengths[behind_idx] > behind_dist) --behind_idx; - *prev_path_ = *prev_path_->subset(behind_idx, prev_path_->points.size()); - - // Use previous path for replanning - const auto prev_path_length = prev_path_->lengths.back(); - const auto reuse_step = prev_path_length / params_.sampling.previous_path_reuse_points_nb; - for (double reuse_length = reuse_step; reuse_length <= prev_path_length; - reuse_length += reuse_step) { - sampler_common::State reuse_state; - size_t reuse_idx = 0; - for (reuse_idx = 0; reuse_idx + 1 < prev_path_->lengths.size() && - prev_path_->lengths[reuse_idx] < reuse_length; - ++reuse_idx) - ; - if (reuse_idx == 0UL) continue; - const auto reused_path = *prev_path_->subset(0UL, reuse_idx); - reuse_state.curvature = reused_path.curvatures.back(); - reuse_state.pose = reused_path.points.back(); - reuse_state.heading = reused_path.yaws.back(); - reuse_state.frenet = path_spline.frenet(reuse_state.pose); - auto paths = generateCandidatePaths(reuse_state, path_spline, reuse_length, params_); - for (auto & p : paths) candidate_paths.push_back(reused_path.extend(p)); - } +sampler_common::Path PathSampler::generatePath(const PlannerData & planner_data) +{ + time_keeper_ptr_->tic(__func__); + sampler_common::Path generated_path{}; + + if (prev_path_ && prev_path_->points.size() > 1) { + sampler_common::constraints::checkHardConstraints(*prev_path_, params_.constraints); + if (prev_path_->constraint_results.isValid()) { + const auto prev_path_spline = + preparePathSpline(trajectory_utils::convertToTrajectoryPoints(*prev_path_), false); + const auto frenet_p = prev_path_spline.frenet( + {planner_data.ego_pose.position.x, planner_data.ego_pose.position.y}); + if (std::abs(frenet_p.d) > params_.path_reuse.max_lat_dev || frenet_p.s < 0.0) + resetPreviousData(); + else if (frenet_p.s <= params_.path_reuse.direct_reuse_dist) + return *prev_path_; } else { resetPreviousData(); } } + const auto path_spline = + preparePathSpline(planner_data.traj_points, params_.preprocessing.smooth_reference); + sampler_common::State current_state; + current_state.pose = {planner_data.ego_pose.position.x, planner_data.ego_pose.position.y}; + current_state.heading = tf2::getYaw(planner_data.ego_pose.orientation); + + const auto planning_state = getPlanningState(current_state, path_spline); + prepareConstraints( + params_.constraints, *in_objects_ptr_, planner_data.left_bound, planner_data.right_bound); + + auto candidate_paths = generateCandidatePaths(planning_state, path_spline, 0.0, params_); + const auto candidates_from_prev_path = + generateCandidatesFromPreviousPath(planner_data, path_spline); + candidate_paths.insert( + candidate_paths.end(), candidates_from_prev_path.begin(), candidates_from_prev_path.end()); debug_data_.footprints.clear(); for (auto & path : candidate_paths) { const auto footprint = @@ -457,9 +494,7 @@ std::vector PathSampler::generatePath(const PlannerData & plann }; const auto selected_path_idx = best_path_idx(candidate_paths); if (selected_path_idx) { - const auto & selected_path = candidate_paths[*selected_path_idx]; - trajectory = trajectory_utils::convertToTrajectoryPoints(selected_path); - prev_path_ = selected_path; + generated_path = candidate_paths[*selected_path_idx]; } else { RCLCPP_WARN( get_logger(), "No valid path found (out of %lu) outputting %s\n", candidate_paths.size(), @@ -468,18 +503,28 @@ std::vector PathSampler::generatePath(const PlannerData & plann int da = 0; int k = 0; for (const auto & p : candidate_paths) { - coll += static_cast(!p.constraint_results.collision); - da += static_cast(!p.constraint_results.drivable_area); - k += static_cast(!p.constraint_results.curvature); + coll += static_cast(!p.constraint_results.collision_free); + da += static_cast(!p.constraint_results.inside_drivable_area); + k += static_cast(!p.constraint_results.valid_curvature); } RCLCPP_WARN(get_logger(), "\tInvalid coll/da/k = %d/%d/%d\n", coll, da, k); - if (prev_path_) trajectory = trajectory_utils::convertToTrajectoryPoints(*prev_path_); + if (prev_path_) generated_path = *prev_path_; } time_keeper_ptr_->toc(__func__, " "); debug_data_.previous_sampled_candidates_nb = debug_data_.sampled_candidates.size(); debug_data_.sampled_candidates = candidate_paths; debug_data_.obstacles = params_.constraints.obstacle_polygons; - return trajectory; + + prev_path_ = generated_path; + return generated_path; +} + +std::vector PathSampler::generateTrajectoryPoints(const PlannerData & planner_data) +{ + std::vector trajectory; + time_keeper_ptr_->tic(__func__); + const auto path = generatePath(planner_data); + return trajectory_utils::convertToTrajectoryPoints(path); } void PathSampler::publishVirtualWall(const geometry_msgs::msg::Pose & stop_pose) const diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp b/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp index 652167ad94e75..a314e83b065d7 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp +++ b/planning/sampling_based_planner/sampler_common/include/sampler_common/constraints/hard_constraint.hpp @@ -22,7 +22,9 @@ namespace sampler_common::constraints { /// @brief Check if the path satisfies the hard constraints MultiPoint2d checkHardConstraints(Path & path, const Constraints & constraints); -bool has_collision(const MultiPoint2d & footprint, const MultiPolygon2d & obstacles); +bool has_collision( + const MultiPoint2d & footprint, const MultiPolygon2d & obstacles, + const double min_distance = 0.0); bool satisfyMinMax(const std::vector & values, const double min, const double max); } // namespace sampler_common::constraints diff --git a/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp b/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp index 05c7fe47d79ef..cef791a01df44 100644 --- a/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp +++ b/planning/sampling_based_planner/sampler_common/include/sampler_common/structures.hpp @@ -50,13 +50,16 @@ typedef boost::geometry::index::rtree #include #include @@ -30,11 +31,12 @@ bool satisfyMinMax(const std::vector & values, const double min, const d return true; } -bool has_collision(const MultiPoint2d & footprint, const MultiPolygon2d & obstacles) +bool has_collision( + const MultiPoint2d & footprint, const MultiPolygon2d & obstacles, const double min_distance) { + if (footprint.empty()) return false; for (const auto & o : obstacles) - for (const auto & p : footprint) - if (boost::geometry::within(p, o)) return true; + if (boost::geometry::distance(o, footprint) <= min_distance) return true; return false; } @@ -42,14 +44,15 @@ MultiPoint2d checkHardConstraints(Path & path, const Constraints & constraints) { const auto footprint = buildFootprintPoints(path, constraints); if (!footprint.empty()) { - if (!boost::geometry::within(footprint, constraints.drivable_polygons)) { - path.constraint_results.drivable_area = false; - } + if (constraints.hard.limit_footprint_inside_drivable_area) + path.constraint_results.inside_drivable_area = + boost::geometry::within(footprint, constraints.drivable_polygons); + path.constraint_results.collision_free = !has_collision( + footprint, constraints.obstacle_polygons, constraints.hard.min_dist_from_obstacles); } - path.constraint_results.collision = !has_collision(footprint, constraints.obstacle_polygons); if (!satisfyMinMax( path.curvatures, constraints.hard.min_curvature, constraints.hard.max_curvature)) { - path.constraint_results.curvature = false; + path.constraint_results.valid_curvature = false; } return footprint; } From 885c0affe55e687bdb216fb55abe297a062af54d Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Fri, 10 May 2024 15:57:12 +0900 Subject: [PATCH 145/192] fix(map_based_prediction): revert use different time horizon (#6877) (#6970) Revert "feat(map_based_prediction): use different time horizon (#6877)" This reverts commit d5aa5d61c5d346aa97ea12065dd75a6f7b1e6b5c. Signed-off-by: yoshiri --- .../config/map_based_prediction.param.yaml | 5 +- .../map_based_prediction_node.hpp | 11 +--- .../map_based_prediction/path_generator.hpp | 31 +++++----- .../schema/map_based_prediction.schema.json | 20 +------ .../src/map_based_prediction_node.cpp | 57 +++++++++--------- .../src/path_generator.cpp | 58 +++++++++---------- 6 files changed, 73 insertions(+), 109 deletions(-) diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/map_based_prediction/config/map_based_prediction.param.yaml index 803933ef4dbfd..f8ad371ab92a6 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -1,10 +1,7 @@ /**: ros__parameters: enable_delay_compensation: true - prediction_time_horizon: - vehicle: 15.0 #[s] - pedestrian: 10.0 #[s] - unknown: 10.0 #[s] + prediction_time_horizon: 10.0 #[s] lateral_control_time_horizon: 5.0 #[s] prediction_sampling_delta_time: 0.5 #[s] min_velocity_for_map_based_prediction: 1.39 #[m/s] diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index c9d0ac84c4f91..829c4d6e4a114 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -99,13 +99,6 @@ struct PredictedRefPath Maneuver maneuver; }; -struct PredictionTimeHorizon -{ - double vehicle; - double pedestrian; - double unknown; -}; - using LaneletsData = std::vector; using ManeuverProbability = std::unordered_map; using autoware_auto_mapping_msgs::msg::HADMapBin; @@ -168,7 +161,7 @@ class MapBasedPredictionNode : public rclcpp::Node // Parameters bool enable_delay_compensation_; - PredictionTimeHorizon prediction_time_horizon_; + double prediction_time_horizon_; double lateral_control_time_horizon_; double prediction_time_horizon_rate_for_validate_lane_length_; double prediction_sampling_time_interval_; @@ -245,7 +238,7 @@ class MapBasedPredictionNode : public rclcpp::Node std::vector getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, - const double object_detected_time, const double time_horizon); + const double object_detected_time); Maneuver predictObjectManeuver( const TrackedObject & object, const LaneletData & current_lanelet_data, const double object_detected_time); diff --git a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp index 443a7c671ec83..6dfc4a8db9e20 100644 --- a/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/path_generator.hpp @@ -80,23 +80,21 @@ using PosePath = std::vector; class PathGenerator { public: - PathGenerator(const double sampling_time_interval, const double min_crosswalk_user_velocity); + PathGenerator( + const double time_horizon, const double lateral_time_horizon, + const double sampling_time_interval, const double min_crosswalk_user_velocity); - PredictedPath generatePathForNonVehicleObject( - const TrackedObject & object, const double duration); + PredictedPath generatePathForNonVehicleObject(const TrackedObject & object); - PredictedPath generatePathForLowSpeedVehicle( - const TrackedObject & object, const double duration) const; + PredictedPath generatePathForLowSpeedVehicle(const TrackedObject & object) const; - PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object, const double duration); + PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object); PredictedPath generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double duration, - const double lateral_duration, const double speed_limit = 0.0); + const TrackedObject & object, const PosePath & ref_paths, const double speed_limit = 0.0); PredictedPath generatePathForCrosswalkUser( - const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, - const double duration) const; + const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const; PredictedPath generatePathToTargetPoint( const TrackedObject & object, const Eigen::Vector2d & point) const; @@ -113,21 +111,21 @@ class PathGenerator private: // Parameters + double time_horizon_; + double lateral_time_horizon_; double sampling_time_interval_; double min_crosswalk_user_velocity_; bool use_vehicle_acceleration_; double acceleration_exponential_half_life_; // Member functions - PredictedPath generateStraightPath(const TrackedObject & object, const double duration) const; + PredictedPath generateStraightPath(const TrackedObject & object) const; PredictedPath generatePolynomialPath( - const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double speed_limit = 0.0); + const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0); FrenetPath generateFrenetPath( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, - const double duration, const double lateral_duration); + const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length); Eigen::Vector3d calcLatCoefficients( const FrenetPoint & current_point, const FrenetPoint & target_point, const double T); Eigen::Vector2d calcLonCoefficients( @@ -141,8 +139,7 @@ class PathGenerator const PosePath & ref_path); FrenetPoint getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double duration, - const double speed_limit = 0.0); + const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0); }; } // namespace map_based_prediction diff --git a/perception/map_based_prediction/schema/map_based_prediction.schema.json b/perception/map_based_prediction/schema/map_based_prediction.schema.json index 8e5ef9e542f54..8ddb122ebb56e 100644 --- a/perception/map_based_prediction/schema/map_based_prediction.schema.json +++ b/perception/map_based_prediction/schema/map_based_prediction.schema.json @@ -12,23 +12,9 @@ "description": "flag to enable the time delay compensation for the position of the object" }, "prediction_time_horizon": { - "properties": { - "vehicle": { - "type": "number", - "default": "15.0", - "description": "predict time duration for predicted path of vehicle" - }, - "pedestrian": { - "type": "number", - "default": "10.0", - "description": "predict time duration for predicted path of pedestrian" - }, - "unknown": { - "type": "number", - "default": "10.0", - "description": "predict time duration for predicted path of unknown" - } - } + "type": "number", + "default": "10.0", + "description": "predict time duration for predicted path" }, "lateral_control_time_horizon": { "type": "number", diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index e717109b94cd7..8f080ba0edc35 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -720,10 +720,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ google::InstallFailureSignalHandler(); } enable_delay_compensation_ = declare_parameter("enable_delay_compensation"); - prediction_time_horizon_.vehicle = declare_parameter("prediction_time_horizon.vehicle"); - prediction_time_horizon_.pedestrian = - declare_parameter("prediction_time_horizon.pedestrian"); - prediction_time_horizon_.unknown = declare_parameter("prediction_time_horizon.unknown"); + prediction_time_horizon_ = declare_parameter("prediction_time_horizon"); lateral_control_time_horizon_ = declare_parameter("lateral_control_time_horizon"); // [s] for lateral control point prediction_sampling_time_interval_ = declare_parameter("prediction_sampling_delta_time"); @@ -794,7 +791,8 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ "crosswalk_with_signal.timeout_set_for_no_intention_to_walk"); path_generator_ = std::make_shared( - prediction_sampling_time_interval_, min_crosswalk_user_velocity_); + prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_, + min_crosswalk_user_velocity_); path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_); path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_); @@ -971,8 +969,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // For off lane obstacles if (current_lanelets.empty()) { - PredictedPath predicted_path = path_generator_->generatePathForOffLaneVehicle( - transformed_object, prediction_time_horizon_.vehicle); + PredictedPath predicted_path = + path_generator_->generatePathForOffLaneVehicle(transformed_object); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -987,8 +985,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt transformed_object.kinematics.twist_with_covariance.twist.linear.x, transformed_object.kinematics.twist_with_covariance.twist.linear.y); if (std::fabs(abs_obj_speed) < min_velocity_for_map_based_prediction_) { - PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( - transformed_object, prediction_time_horizon_.vehicle); + PredictedPath predicted_path = + path_generator_->generatePathForLowSpeedVehicle(transformed_object); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -1000,14 +998,13 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // Get Predicted Reference Path for Each Maneuver and current lanelets // return: - const auto ref_paths = getPredictedReferencePath( - transformed_object, current_lanelets, objects_detected_time, - prediction_time_horizon_.vehicle); + const auto ref_paths = + getPredictedReferencePath(transformed_object, current_lanelets, objects_detected_time); // If predicted reference path is empty, assume this object is out of the lane if (ref_paths.empty()) { - PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle( - transformed_object, prediction_time_horizon_.vehicle); + PredictedPath predicted_path = + path_generator_->generatePathForLowSpeedVehicle(transformed_object); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) break; @@ -1042,8 +1039,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt for (const auto & ref_path : ref_paths) { PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle( - yaw_fixed_transformed_object, ref_path.path, prediction_time_horizon_.vehicle, - lateral_control_time_horizon_, ref_path.speed_limit); + yaw_fixed_transformed_object, ref_path.path, ref_path.speed_limit); if (predicted_path.path.empty()) continue; if (!check_lateral_acceleration_constraints_) { @@ -1106,8 +1102,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } default: { auto predicted_unknown_object = convertToPredictedObject(transformed_object); - PredictedPath predicted_path = path_generator_->generatePathForNonVehicleObject( - transformed_object, prediction_time_horizon_.unknown); + PredictedPath predicted_path = + path_generator_->generatePathForNonVehicleObject(transformed_object); predicted_path.confidence = 1.0; predicted_unknown_object.kinematics.predicted_paths.push_back(predicted_path); @@ -1174,8 +1170,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( { auto predicted_object = convertToPredictedObject(object); { - PredictedPath predicted_path = - path_generator_->generatePathForNonVehicleObject(object, prediction_time_horizon_.pedestrian); + PredictedPath predicted_path = path_generator_->generatePathForNonVehicleObject(object); predicted_path.confidence = 1.0; predicted_object.kinematics.predicted_paths.push_back(predicted_path); @@ -1226,7 +1221,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( if (hasPotentialToReach( object, edge_points.front_center_point, edge_points.front_right_point, - edge_points.front_left_point, prediction_time_horizon_.pedestrian * 2.0, + edge_points.front_left_point, prediction_time_horizon_ * 2.0, min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) { PredictedPath predicted_path = path_generator_->generatePathToTargetPoint(object, edge_points.front_center_point); @@ -1236,7 +1231,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( if (hasPotentialToReach( object, edge_points.back_center_point, edge_points.back_right_point, - edge_points.back_left_point, prediction_time_horizon_.pedestrian * 2.0, + edge_points.back_left_point, prediction_time_horizon_ * 2.0, min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) { PredictedPath predicted_path = path_generator_->generatePathToTargetPoint(object, edge_points.back_center_point); @@ -1260,27 +1255,27 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( const auto reachable_first = hasPotentialToReach( object, edge_points.front_center_point, edge_points.front_right_point, - edge_points.front_left_point, prediction_time_horizon_.pedestrian, - min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_); + edge_points.front_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, + max_crosswalk_user_delta_yaw_threshold_for_lanelet_); const auto reachable_second = hasPotentialToReach( object, edge_points.back_center_point, edge_points.back_right_point, - edge_points.back_left_point, prediction_time_horizon_.pedestrian, - min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_); + edge_points.back_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_, + max_crosswalk_user_delta_yaw_threshold_for_lanelet_); if (!reachable_first && !reachable_second) { continue; } const auto reachable_crosswalk = isReachableCrosswalkEdgePoints( - object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_.pedestrian, + object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_, min_crosswalk_user_velocity_); if (!reachable_crosswalk) { continue; } - PredictedPath predicted_path = path_generator_->generatePathForCrosswalkUser( - object, reachable_crosswalk.get(), prediction_time_horizon_.pedestrian); + PredictedPath predicted_path = + path_generator_->generatePathForCrosswalkUser(object, reachable_crosswalk.get()); predicted_path.confidence = 1.0; if (predicted_path.path.empty()) { @@ -1618,7 +1613,7 @@ void MapBasedPredictionNode::updateObjectsHistory( std::vector MapBasedPredictionNode::getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, - const double object_detected_time, const double time_horizon) + const double object_detected_time) { const double obj_vel = std::hypot( object.kinematics.twist_with_covariance.twist.linear.x, @@ -1630,7 +1625,7 @@ std::vector MapBasedPredictionNode::getPredictedReferencePath( object.kinematics.acceleration_with_covariance.accel.linear.x, object.kinematics.acceleration_with_covariance.accel.linear.y) : 0.0; - const double t_h = time_horizon; + const double t_h = prediction_time_horizon_; const double λ = std::log(2) / acceleration_exponential_half_life_; auto get_search_distance_with_decaying_acc = [&]() -> double { diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index 562fa966c40a9..83fbc16feb7fa 100644 --- a/perception/map_based_prediction/src/path_generator.cpp +++ b/perception/map_based_prediction/src/path_generator.cpp @@ -23,16 +23,18 @@ namespace map_based_prediction { PathGenerator::PathGenerator( - const double sampling_time_interval, const double min_crosswalk_user_velocity) -: sampling_time_interval_(sampling_time_interval), + const double time_horizon, const double lateral_time_horizon, const double sampling_time_interval, + const double min_crosswalk_user_velocity) +: time_horizon_(time_horizon), + lateral_time_horizon_(lateral_time_horizon), + sampling_time_interval_(sampling_time_interval), min_crosswalk_user_velocity_(min_crosswalk_user_velocity) { } -PredictedPath PathGenerator::generatePathForNonVehicleObject( - const TrackedObject & object, const double duration) +PredictedPath PathGenerator::generatePathForNonVehicleObject(const TrackedObject & object) { - return generateStraightPath(object, duration); + return generateStraightPath(object); } PredictedPath PathGenerator::generatePathToTargetPoint( @@ -73,8 +75,7 @@ PredictedPath PathGenerator::generatePathToTargetPoint( } PredictedPath PathGenerator::generatePathForCrosswalkUser( - const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk, - const double duration) const + const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const { PredictedPath predicted_path{}; const double ep = 0.001; @@ -98,7 +99,7 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( const auto entry_to_exit_point_orientation = tier4_autoware_utils::createQuaternionFromYaw( std::atan2(entry_to_exit_point_normalized.y(), entry_to_exit_point_normalized.x())); - for (double dt = 0.0; dt < duration + ep; dt += sampling_time_interval_) { + for (double dt = 0.0; dt < time_horizon_ + ep; dt += sampling_time_interval_) { geometry_msgs::msg::Pose world_frame_pose; if (dt < arrival_time) { world_frame_pose.position.x = @@ -130,43 +131,39 @@ PredictedPath PathGenerator::generatePathForCrosswalkUser( return predicted_path; } -PredictedPath PathGenerator::generatePathForLowSpeedVehicle( - const TrackedObject & object, const double duration) const +PredictedPath PathGenerator::generatePathForLowSpeedVehicle(const TrackedObject & object) const { PredictedPath path; path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); const double ep = 0.001; - for (double dt = 0.0; dt < duration + ep; dt += sampling_time_interval_) { + for (double dt = 0.0; dt < time_horizon_ + ep; dt += sampling_time_interval_) { path.path.push_back(object.kinematics.pose_with_covariance.pose); } return path; } -PredictedPath PathGenerator::generatePathForOffLaneVehicle( - const TrackedObject & object, const double duration) +PredictedPath PathGenerator::generatePathForOffLaneVehicle(const TrackedObject & object) { - return generateStraightPath(object, duration); + return generateStraightPath(object); } PredictedPath PathGenerator::generatePathForOnLaneVehicle( - const TrackedObject & object, const PosePath & ref_paths, const double duration, - const double lateral_duration, const double speed_limit) + const TrackedObject & object, const PosePath & ref_paths, const double speed_limit) { if (ref_paths.size() < 2) { - return generateStraightPath(object, duration); + return generateStraightPath(object); } - return generatePolynomialPath(object, ref_paths, speed_limit, duration, lateral_duration); + return generatePolynomialPath(object, ref_paths, speed_limit); } -PredictedPath PathGenerator::generateStraightPath( - const TrackedObject & object, const double longitudinal_duration) const +PredictedPath PathGenerator::generateStraightPath(const TrackedObject & object) const { const auto & object_pose = object.kinematics.pose_with_covariance.pose; const auto & object_twist = object.kinematics.twist_with_covariance.twist; constexpr double ep = 0.001; - const double duration = longitudinal_duration + ep; + const double duration = time_horizon_ + ep; PredictedPath path; path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); @@ -181,12 +178,11 @@ PredictedPath PathGenerator::generateStraightPath( } PredictedPath PathGenerator::generatePolynomialPath( - const TrackedObject & object, const PosePath & ref_path, const double duration, - const double lateral_duration, const double speed_limit) + const TrackedObject & object, const PosePath & ref_path, const double speed_limit) { // Get current Frenet Point const double ref_path_len = motion_utils::calcArcLength(ref_path); - const auto current_point = getFrenetPoint(object, ref_path, speed_limit, duration); + const auto current_point = getFrenetPoint(object, ref_path, speed_limit); // Step1. Set Target Frenet Point // Note that we do not set position s, @@ -200,13 +196,13 @@ PredictedPath PathGenerator::generatePolynomialPath( // Step2. Generate Predicted Path on a Frenet coordinate const auto frenet_predicted_path = - generateFrenetPath(current_point, terminal_point, ref_path_len, duration, lateral_duration); + generateFrenetPath(current_point, terminal_point, ref_path_len); // Step3. Interpolate Reference Path for converting predicted path coordinate const auto interpolated_ref_path = interpolateReferencePath(ref_path, frenet_predicted_path); if (frenet_predicted_path.size() < 2 || interpolated_ref_path.size() < 2) { - return generateStraightPath(object, duration); + return generateStraightPath(object); } // Step4. Convert predicted trajectory from Frenet to Cartesian coordinate @@ -214,10 +210,11 @@ PredictedPath PathGenerator::generatePolynomialPath( } FrenetPath PathGenerator::generateFrenetPath( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length, - const double duration, const double lateral_duration) + const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length) { FrenetPath path; + const double duration = time_horizon_; + const double lateral_duration = lateral_time_horizon_; // Compute Lateral and Longitudinal Coefficients to generate the trajectory const Eigen::Vector3d lat_coeff = @@ -388,8 +385,7 @@ PredictedPath PathGenerator::convertToPredictedPath( } FrenetPoint PathGenerator::getFrenetPoint( - const TrackedObject & object, const PosePath & ref_path, const double duration, - const double speed_limit) + const TrackedObject & object, const PosePath & ref_path, const double speed_limit) { FrenetPoint frenet_point; const auto obj_point = object.kinematics.pose_with_covariance.pose.position; @@ -415,7 +411,7 @@ FrenetPoint PathGenerator::getFrenetPoint( : 0.0; // Using a decaying acceleration model. Consult the README for more information about the model. - const double t_h = duration; + const double t_h = time_horizon_; const float λ = std::log(2) / acceleration_exponential_half_life_; auto have_same_sign = [](double a, double b) -> bool { From bca574a9a37cd28616e146dca4b945a6cd8d8c4b Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 10 May 2024 17:02:24 +0900 Subject: [PATCH 146/192] feat(control_evaluator): implement a control evaluator (#6959) * add control evaluator module Signed-off-by: Daniel Sanchez * make the evaluator depend on messages from AEB Signed-off-by: Daniel Sanchez * update output msg Signed-off-by: Daniel Sanchez * delete extra new line Signed-off-by: Daniel Sanchez * update/fix details Signed-off-by: Daniel Sanchez * add a package mantainer Signed-off-by: Daniel Sanchez * Add a timer to maintain a constant rate of msg publishing Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- evaluator/control_evaluator/CMakeLists.txt | 23 +++++ evaluator/control_evaluator/README.md | 5 ++ .../control_evaluator_node.hpp | 61 +++++++++++++ .../launch/control_evaluator.launch.xml | 12 +++ evaluator/control_evaluator/package.xml | 29 +++++++ .../param/control_evaluator.defaults.yaml | 2 + .../src/control_evaluator_node.cpp | 86 +++++++++++++++++++ .../launch/control.launch.py | 17 ++++ launch/tier4_control_launch/package.xml | 1 + 9 files changed, 236 insertions(+) create mode 100644 evaluator/control_evaluator/CMakeLists.txt create mode 100644 evaluator/control_evaluator/README.md create mode 100644 evaluator/control_evaluator/include/control_evaluator/control_evaluator_node.hpp create mode 100644 evaluator/control_evaluator/launch/control_evaluator.launch.xml create mode 100644 evaluator/control_evaluator/package.xml create mode 100644 evaluator/control_evaluator/param/control_evaluator.defaults.yaml create mode 100644 evaluator/control_evaluator/src/control_evaluator_node.cpp diff --git a/evaluator/control_evaluator/CMakeLists.txt b/evaluator/control_evaluator/CMakeLists.txt new file mode 100644 index 0000000000000..b97a14e29cdcd --- /dev/null +++ b/evaluator/control_evaluator/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.14) +project(control_evaluator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(pluginlib REQUIRED) + +ament_auto_add_library(${PROJECT_NAME}_node SHARED + src/${PROJECT_NAME}_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME}_node + PLUGIN "control_diagnostics::controlEvaluatorNode" + EXECUTABLE ${PROJECT_NAME} +) + + +ament_auto_package( + INSTALL_TO_SHARE + param + launch +) diff --git a/evaluator/control_evaluator/README.md b/evaluator/control_evaluator/README.md new file mode 100644 index 0000000000000..71bd5c0142570 --- /dev/null +++ b/evaluator/control_evaluator/README.md @@ -0,0 +1,5 @@ +# Planning Evaluator + +## Purpose + +This package provides nodes that generate metrics to evaluate the quality of control. diff --git a/evaluator/control_evaluator/include/control_evaluator/control_evaluator_node.hpp b/evaluator/control_evaluator/include/control_evaluator/control_evaluator_node.hpp new file mode 100644 index 0000000000000..3a3ba47d88e03 --- /dev/null +++ b/evaluator/control_evaluator/include/control_evaluator/control_evaluator_node.hpp @@ -0,0 +1,61 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef CONTROL_EVALUATOR__CONTROL_EVALUATOR_NODE_HPP_ +#define CONTROL_EVALUATOR__CONTROL_EVALUATOR_NODE_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "diagnostic_msgs/msg/diagnostic_array.hpp" + +#include +#include +#include +#include +#include + +namespace control_diagnostics +{ + +using diagnostic_msgs::msg::DiagnosticArray; +using diagnostic_msgs::msg::DiagnosticStatus; + +/** + * @brief Node for control evaluation + */ +class controlEvaluatorNode : public rclcpp::Node +{ +public: + explicit controlEvaluatorNode(const rclcpp::NodeOptions & node_options); + + /** + * @brief publish the given metric statistic + */ + DiagnosticStatus generateDiagnosticStatus(const bool is_emergency_brake) const; + void onDiagnostics(const DiagnosticArray::ConstSharedPtr diag_msg); + void onTimer(); + +private: + rclcpp::Subscription::SharedPtr control_diag_sub_; + rclcpp::Publisher::SharedPtr metrics_pub_; + + // Calculator + // Metrics + std::deque stamps_; + DiagnosticArray metrics_msg_; + rclcpp::TimerBase::SharedPtr timer_; +}; +} // namespace control_diagnostics + +#endif // CONTROL_EVALUATOR__CONTROL_EVALUATOR_NODE_HPP_ diff --git a/evaluator/control_evaluator/launch/control_evaluator.launch.xml b/evaluator/control_evaluator/launch/control_evaluator.launch.xml new file mode 100644 index 0000000000000..75012791888a6 --- /dev/null +++ b/evaluator/control_evaluator/launch/control_evaluator.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/evaluator/control_evaluator/package.xml b/evaluator/control_evaluator/package.xml new file mode 100644 index 0000000000000..10686e9b73761 --- /dev/null +++ b/evaluator/control_evaluator/package.xml @@ -0,0 +1,29 @@ + + + + control_evaluator + 0.1.0 + ROS 2 node for evaluating control + Daniel SANCHEZ + takayuki MUROOKA + Apache License 2.0 + + Daniel SANCHEZ + takayuki MUROOKA + + ament_cmake_auto + autoware_cmake + + diagnostic_msgs + pluginlib + rclcpp + rclcpp_components + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/evaluator/control_evaluator/param/control_evaluator.defaults.yaml b/evaluator/control_evaluator/param/control_evaluator.defaults.yaml new file mode 100644 index 0000000000000..a20dbd7ffd3d9 --- /dev/null +++ b/evaluator/control_evaluator/param/control_evaluator.defaults.yaml @@ -0,0 +1,2 @@ +/**: + ros__parameters: diff --git a/evaluator/control_evaluator/src/control_evaluator_node.cpp b/evaluator/control_evaluator/src/control_evaluator_node.cpp new file mode 100644 index 0000000000000..d575a35a2389f --- /dev/null +++ b/evaluator/control_evaluator/src/control_evaluator_node.cpp @@ -0,0 +1,86 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "control_evaluator/control_evaluator_node.hpp" + +#include +#include +#include +#include +#include +#include +#include + +namespace control_diagnostics +{ +controlEvaluatorNode::controlEvaluatorNode(const rclcpp::NodeOptions & node_options) +: Node("control_evaluator", node_options) +{ + using std::placeholders::_1; + + control_diag_sub_ = create_subscription( + "~/input/diagnostics", 1, std::bind(&controlEvaluatorNode::onDiagnostics, this, _1)); + + // Publisher + metrics_pub_ = create_publisher("~/metrics", 1); + + // Timer callback to publish evaluator diagnostics + using namespace std::literals::chrono_literals; + timer_ = + rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&controlEvaluatorNode::onTimer, this)); +} + +DiagnosticStatus controlEvaluatorNode::generateDiagnosticStatus(const bool is_emergency_brake) const +{ + DiagnosticStatus status; + status.level = status.OK; + status.name = "autonomous_emergency_braking"; + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "decision"; + key_value.value = (is_emergency_brake) ? "stop" : "none"; + status.values.push_back(key_value); + return status; +} + +void controlEvaluatorNode::onTimer() +{ + if (!metrics_msg_.status.empty()) { + metrics_pub_->publish(metrics_msg_); + metrics_msg_.status.clear(); + } +} + +void controlEvaluatorNode::onDiagnostics(const DiagnosticArray::ConstSharedPtr diag_msg) +{ + const auto start = now(); + const auto aeb_status = + std::find_if(diag_msg->status.begin(), diag_msg->status.end(), [](const auto & status) { + const bool aeb_found = status.name.find("autonomous_emergency_braking") != std::string::npos; + return aeb_found; + }); + + if (aeb_status == diag_msg->status.end()) return; + + const bool is_emergency_brake = (aeb_status->level == DiagnosticStatus::ERROR); + metrics_msg_.header.stamp = now(); + metrics_msg_.status.emplace_back(generateDiagnosticStatus(is_emergency_brake)); + + const auto runtime = (now() - start).seconds(); + RCLCPP_DEBUG(get_logger(), "control evaluation calculation time: %2.2f ms", runtime * 1e3); +} + +} // namespace control_diagnostics + +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(control_diagnostics::controlEvaluatorNode) diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a63e7f547fef1..2ef2e07367f81 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -343,6 +343,22 @@ def launch_setup(context, *args, **kwargs): ], ) + # control evaluator + control_evaluator_component = ComposableNode( + package="control_evaluator", + plugin="control_diagnostics::controlEvaluatorNode", + name="control_evaluator", + remappings=[ + ("~/input/diagnostics", "/diagnostics"), + ("~/output/metrics", "~/metrics"), + ], + ) + + control_evaluator_loader = LoadComposableNodes( + composable_node_descriptions=[control_evaluator_component], + target_container="/control/control_container", + ) + # control validator checker control_validator_component = ComposableNode( package="control_validator", @@ -369,6 +385,7 @@ def launch_setup(context, *args, **kwargs): obstacle_collision_checker_loader, autonomous_emergency_braking_loader, predicted_path_checker_loader, + control_evaluator_loader, ] ) diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index 4bfefa4d93747..801fa274dd086 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -11,6 +11,7 @@ ament_cmake_auto autoware_cmake + control_evaluator external_cmd_converter external_cmd_selector lane_departure_checker From e2182189ffbc236ce4d4b183b899b5f401e4e406 Mon Sep 17 00:00:00 2001 From: Khalil Selyan <36904941+KhalilSelyan@users.noreply.github.com> Date: Fri, 10 May 2024 15:38:27 +0300 Subject: [PATCH 147/192] feat: update rviz2 overlay (#6883) Signed-off-by: KhalilSelyan --- .../include/turn_signals_display.hpp | 2 +- .../src/gear_display.cpp | 13 +++---- .../src/signal_display.cpp | 34 +++++++++---------- .../src/speed_display.cpp | 9 ++--- .../src/speed_limit_display.cpp | 24 ++++++++----- .../src/steering_wheel_display.cpp | 4 +-- .../src/traffic_display.cpp | 10 +++--- .../src/turn_signals_display.cpp | 8 ++--- 8 files changed, 54 insertions(+), 50 deletions(-) diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp index 87f141353d5b2..ca10c92c06a3e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp @@ -47,7 +47,7 @@ class TurnSignalsDisplay private: QImage arrowImage; - QColor gray = QColor(46, 46, 46); + QColor gray = QColor(79, 79, 79); int current_turn_signal_; // Internal variable to store turn signal state int current_hazard_lights_; // Internal variable to store hazard lights state diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp index 8f05ce6fdce1c..825c7c1620e2c 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp @@ -81,18 +81,19 @@ void GearDisplay::drawGearIndicator(QPainter & painter, const QRectF & backgroun break; } - QFont gearFont("Quicksand", 16, QFont::Bold); + QFont gearFont("Quicksand", 12, QFont::Bold); painter.setFont(gearFont); QPen borderPen(gray); - borderPen.setWidth(4); + borderPen.setWidth(1); painter.setPen(borderPen); - int gearBoxSize = 30; - int gearX = backgroundRect.left() + 30 + gearBoxSize; - int gearY = backgroundRect.height() - gearBoxSize - 20; + double gearBoxSize = 37.5; + double gearX = backgroundRect.left() + 54; + double gearY = backgroundRect.height() / 2 - gearBoxSize / 2; QRect gearRect(gearX, gearY, gearBoxSize, gearBoxSize); - painter.setBrush(QColor(0, 0, 0, 0)); + painter.setBrush(gray); painter.drawRoundedRect(gearRect, 10, 10); + painter.setPen(Qt::black); painter.drawText(gearRect, Qt::AlignCenter, QString::fromStdString(gearString)); } diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp index 3b1536919512b..841b33c29fbb0 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp @@ -39,11 +39,11 @@ namespace autoware_overlay_rviz_plugin SignalDisplay::SignalDisplay() { property_width_ = new rviz_common::properties::IntProperty( - "Width", 517, "Width of the overlay", this, SLOT(updateOverlaySize())); + "Width", 550, "Width of the overlay", this, SLOT(updateOverlaySize())); property_height_ = new rviz_common::properties::IntProperty( - "Height", 175, "Height of the overlay", this, SLOT(updateOverlaySize())); + "Height", 100, "Height of the overlay", this, SLOT(updateOverlaySize())); property_left_ = new rviz_common::properties::IntProperty( - "Left", 10, "Left position of the overlay", this, SLOT(updateOverlayPosition())); + "Left", 0, "Left position of the overlay", this, SLOT(updateOverlayPosition())); property_top_ = new rviz_common::properties::IntProperty( "Top", 10, "Top position of the overlay", this, SLOT(updateOverlayPosition())); property_signal_color_ = new rviz_common::properties::ColorProperty( @@ -325,16 +325,18 @@ void SignalDisplay::drawWidget(QImage & hud) QPainter painter(&hud); painter.setRenderHint(QPainter::Antialiasing, true); - QRectF backgroundRect(0, 0, 322, hud.height()); + QRectF backgroundRect(0, 0, 550, hud.height()); drawHorizontalRoundedRectangle(painter, backgroundRect); // Draw components - if (steering_wheel_display_) { - steering_wheel_display_->drawSteeringWheel(painter, backgroundRect); - } if (gear_display_) { gear_display_->drawGearIndicator(painter, backgroundRect); } + + if (steering_wheel_display_) { + steering_wheel_display_->drawSteeringWheel(painter, backgroundRect); + } + if (speed_display_) { speed_display_->drawSpeedDisplay(painter, backgroundRect); } @@ -342,18 +344,12 @@ void SignalDisplay::drawWidget(QImage & hud) turn_signals_display_->drawArrows(painter, backgroundRect, property_signal_color_->getColor()); } - // a 27px space between the two halves of the HUD - - QRectF smallerBackgroundRect(340, 0, 190.0 / 2, hud.height()); - - drawVerticalRoundedRectangle(painter, smallerBackgroundRect); - if (traffic_display_) { - traffic_display_->drawTrafficLightIndicator(painter, smallerBackgroundRect); + traffic_display_->drawTrafficLightIndicator(painter, backgroundRect); } if (speed_limit_display_) { - speed_limit_display_->drawSpeedLimitIndicator(painter, smallerBackgroundRect); + speed_limit_display_->drawSpeedLimitIndicator(painter, backgroundRect); } painter.end(); @@ -364,8 +360,8 @@ void SignalDisplay::drawHorizontalRoundedRectangle( { painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value - colorFromHSV.setAlphaF(0.65); // Transparency + colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value + colorFromHSV.setAlphaF(0.60); // Transparency painter.setBrush(colorFromHSV); @@ -404,7 +400,9 @@ void SignalDisplay::updateOverlaySize() void SignalDisplay::updateOverlayPosition() { std::lock_guard lock(mutex_); - overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); + overlay_->setPosition( + property_left_->getInt(), property_top_->getInt(), HorizontalAlignment::CENTER, + VerticalAlignment::TOP); queueRender(); } diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp index b1df14956d16c..5c5342259005b 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp @@ -85,7 +85,7 @@ void SpeedDisplay::drawSpeedDisplay(QPainter & painter, const QRectF & backgroun backgroundRect.width() / 2 - referenceRect.width() / 2 - 5, backgroundRect.height() / 2); QString speedNumber = QString::number(current_speed_, 'f', 0); - int fontSize = 60; + int fontSize = 40; QFont speedFont("Quicksand", fontSize); painter.setFont(speedFont); @@ -94,16 +94,17 @@ void SpeedDisplay::drawSpeedDisplay(QPainter & painter, const QRectF & backgroun // Center the speed number in the backgroundRect QPointF speedPos( - backgroundRect.center().x() - speedNumberRect.width() / 2, backgroundRect.center().y()); + backgroundRect.center().x() - speedNumberRect.width() / 2, + backgroundRect.center().y() + speedNumberRect.bottom()); painter.setPen(gray); painter.drawText(speedPos, speedNumber); - QFont unitFont("Quicksand", 14); + QFont unitFont("Quicksand", 8, QFont::DemiBold); painter.setFont(unitFont); QString speedUnit = "km/h"; QRect unitRect = painter.fontMetrics().boundingRect(speedUnit); QPointF unitPos( - (backgroundRect.width() / 2 - unitRect.width() / 2), referencePos.y() + unitRect.height()); + (backgroundRect.width() / 2 - unitRect.width() / 2), referencePos.y() + unitRect.height() + 15); painter.drawText(unitPos, speedUnit); } diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp index 6913ef6a48ecd..4c83b4a73c0c2 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include #include @@ -99,10 +100,9 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF } // Define the area for the outer circle - QRectF outerCircleRect = backgroundRect; - outerCircleRect.setWidth(backgroundRect.width() - 30); - outerCircleRect.setHeight(backgroundRect.width() - 30); - outerCircleRect.moveTopLeft(QPointF(backgroundRect.left() + 15, backgroundRect.top() + 10)); + QRectF outerCircleRect = QRectF(45, 45, 45, 45); + outerCircleRect.moveTopRight( + QPointF(backgroundRect.right() - 44, backgroundRect.top() + outerCircleRect.height() / 2 + 5)); // Now use borderColor for drawing painter.setPen(QPen(borderColor, 2, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin)); @@ -112,24 +112,30 @@ void SpeedLimitDisplay::drawSpeedLimitIndicator(QPainter & painter, const QRectF // Define the area for the inner circle QRectF innerCircleRect = outerCircleRect; - innerCircleRect.setWidth(outerCircleRect.width() / 1.25); - innerCircleRect.setHeight(outerCircleRect.height() / 1.25); + innerCircleRect.setWidth(outerCircleRect.width() / 1.09); + innerCircleRect.setHeight(outerCircleRect.height() / 1.09); innerCircleRect.moveCenter(outerCircleRect.center()); + QRectF innerCircleRect2 = innerCircleRect; + painter.setRenderHint(QPainter::Antialiasing, true); QColor colorFromHSV; - colorFromHSV.setHsv(0, 0, 0); // Hue, Saturation, Value - + colorFromHSV.setHsv(0, 0, 29); // Hue, Saturation, Value + colorFromHSV.setAlphaF(0.60); // Transparency painter.setBrush(colorFromHSV); painter.drawEllipse(innerCircleRect); + // Add a second inner circle as a mask to make the speed limit indicator look like a ring + // and follow the rest of the background color as close as possible + painter.drawEllipse(innerCircleRect2); + int current_limit_int = std::round(current_limit * 3.6); // Define the text to be drawn QString text = QString::number(current_limit_int); // Set the font and color for the text - QFont font = QFont("Quicksand", 24, QFont::Bold); + QFont font = QFont("Quicksand", 16, QFont::Bold); painter.setFont(font); // #C2C2C2 diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp index 5882d7780dc92..45ebcde086165 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp @@ -82,8 +82,8 @@ void SteeringWheelDisplay::drawSteeringWheel(QPainter & painter, const QRectF & // Rotate the wheel float steeringAngle = steering_angle_; // No need to round here // Calculate the position - int wheelCenterX = backgroundRect.right() - wheel.width() - 17.5; - int wheelCenterY = backgroundRect.height() - wheel.height() + 15; + int wheelCenterX = backgroundRect.left() + wheel.width() + 54 + 54; + int wheelCenterY = backgroundRect.height() / 2; // Rotate the wheel image QTransform rotationTransform; diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp index a1b991e4742e3..f6d232709a333 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp @@ -62,12 +62,10 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF painter.setBrush(QBrush(tl_gray_, Qt::SolidPattern)); painter.setPen(Qt::NoPen); // Define the area for the circle (background) - QRectF circleRect = backgroundRect; - circleRect.setWidth(backgroundRect.width() - 30); - circleRect.setHeight(backgroundRect.width() - 30); + QRectF circleRect = QRectF(50, 50, 50, 50); circleRect.moveTopRight(QPointF( - backgroundRect.left() + circleRect.width() + 15, - backgroundRect.top() + circleRect.height() + 30)); + backgroundRect.right() - circleRect.width() - 75, + backgroundRect.top() + circleRect.height() / 2)); painter.drawEllipse(circleRect); if (!current_traffic_.elements.empty()) { @@ -96,7 +94,7 @@ void TrafficDisplay::drawTrafficLightIndicator(QPainter & painter, const QRectF } // Scaling factor (e.g., 1.5 for 150% size) - float scaleFactor = 1.00; + float scaleFactor = 0.75; // Calculate the scaled size QSize scaledSize = traffic_light_image_.size() * scaleFactor; diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp index b6d37062bf08b..1aaa5871015a8 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp @@ -72,12 +72,12 @@ void TurnSignalsDisplay::updateHazardLightsData( void TurnSignalsDisplay::drawArrows( QPainter & painter, const QRectF & backgroundRect, const QColor & color) { - QImage scaledLeftArrow = arrowImage.scaled(64, 43, Qt::KeepAspectRatio, Qt::SmoothTransformation); + QImage scaledLeftArrow = arrowImage.scaled(50, 32, Qt::KeepAspectRatio, Qt::SmoothTransformation); scaledLeftArrow = coloredImage(scaledLeftArrow, gray); QImage scaledRightArrow = scaledLeftArrow.mirrored(true, false); - int arrowYPos = (backgroundRect.height() / 3 - scaledLeftArrow.height() / 2); - int leftArrowXPos = backgroundRect.width() / 4 - scaledLeftArrow.width(); // Adjust as needed - int rightArrowXPos = backgroundRect.width() * 3 / 4; // Adjust as needed + int arrowYPos = (backgroundRect.height() / 2 - scaledLeftArrow.height() / 2 - 4); + int leftArrowXPos = backgroundRect.left() + scaledLeftArrow.width() * 2 + 180; + int rightArrowXPos = backgroundRect.right() - scaledRightArrow.width() * 3 - 175; bool leftActive = (current_turn_signal_ == autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ENABLE_LEFT || From c24ad46e156b0ff3564824e23936541f4834770e Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 10 May 2024 21:40:28 +0900 Subject: [PATCH 148/192] perf(side_shift): fix unupdated prev path that caused heavy interpolation (#6967) Signed-off-by: Maxime CLEMENT --- .../behavior_path_side_shift_module/scene.hpp | 1 - .../behavior_path_side_shift_module/src/scene.cpp | 14 ++++++-------- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp index 1748f57a61bec..08c2345df5814 100644 --- a/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_side_shift_module/include/behavior_path_side_shift_module/scene.hpp @@ -92,7 +92,6 @@ class SideShiftModule : public SceneModuleInterface // member PathWithLaneId refined_path_{}; PathWithLaneId reference_path_{}; - PathWithLaneId prev_reference_{}; lanelet::ConstLanelets current_lanelets_; std::shared_ptr parameters_; diff --git a/planning/behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_side_shift_module/src/scene.cpp index 6df8c1ec629c9..36321050da1ad 100644 --- a/planning/behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_side_shift_module/src/scene.cpp @@ -202,9 +202,6 @@ void SideShiftModule::updateData() const auto reference_pose = prev_output_.shift_length.empty() ? planner_data_->self_odometry->pose.pose : utils::getUnshiftedEgoPose(getEgoPose(), prev_output_); - if (prev_reference_.points.empty()) { - prev_reference_ = getPreviousModuleOutput().path; - } if (getPreviousModuleOutput().reference_path.points.empty()) { return; } @@ -433,13 +430,14 @@ PathWithLaneId SideShiftModule::extendBackwardLength(const PathWithLaneId & orig const auto backward_length = std::max( planner_data_->parameters.backward_path_length, longest_dist_to_shift_point + extra_margin); + const auto & prev_reference = getPreviousModuleOutput().path; const size_t orig_ego_idx = findNearestIndex(original_path.points, getEgoPose().position); - const size_t prev_ego_idx = findNearestSegmentIndex( - prev_reference_.points, getPoint(original_path.points.at(orig_ego_idx))); + const size_t prev_ego_idx = + findNearestSegmentIndex(prev_reference.points, getPoint(original_path.points.at(orig_ego_idx))); size_t clip_idx = 0; for (size_t i = 0; i < prev_ego_idx; ++i) { - if (backward_length > calcSignedArcLength(prev_reference_.points, clip_idx, prev_ego_idx)) { + if (backward_length > calcSignedArcLength(prev_reference.points, clip_idx, prev_ego_idx)) { break; } clip_idx = i; @@ -448,8 +446,8 @@ PathWithLaneId SideShiftModule::extendBackwardLength(const PathWithLaneId & orig PathWithLaneId extended_path{}; { extended_path.points.insert( - extended_path.points.end(), prev_reference_.points.begin() + clip_idx, - prev_reference_.points.begin() + prev_ego_idx); + extended_path.points.end(), prev_reference.points.begin() + clip_idx, + prev_reference.points.begin() + prev_ego_idx); } { From 8176c63275ca55e9ffd6de6d1263593e16b1cb27 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Sat, 11 May 2024 22:57:37 +0900 Subject: [PATCH 149/192] refactor(mission_planner): remove redundant `is_reroute` check (#6980) remove redundant is_reroute check Signed-off-by: Ryuta Kambe --- .../mission_planner/src/mission_planner/mission_planner.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 4cc646526a0ac..af363bcf23da7 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -250,7 +250,7 @@ void MissionPlanner::on_set_lanelet_route( if (is_reroute && !check_reroute_safety(*current_route_, route)) { cancel_route(); - change_state(is_reroute ? RouteState::SET : RouteState::UNSET); + change_state(RouteState::SET); throw service_utils::ServiceException( ResponseCode::ERROR_REROUTE_FAILED, "New route is not safe. Reroute failed."); } @@ -298,7 +298,7 @@ void MissionPlanner::on_set_waypoint_route( if (is_reroute && !check_reroute_safety(*current_route_, route)) { cancel_route(); - change_state(is_reroute ? RouteState::SET : RouteState::UNSET); + change_state(RouteState::SET); throw service_utils::ServiceException( ResponseCode::ERROR_REROUTE_FAILED, "New route is not safe. Reroute failed."); } From fd6306d6fc3fff852046474c71a9181ddc7aa40c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Sat, 11 May 2024 22:09:46 +0300 Subject: [PATCH 150/192] fix(autoware_overlay_rviz_plugin): fix subs and cleanup (#6978) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_overlay_msgs/CHANGELOG.rst | 24 - .../autoware_overlay_msgs/CMakeLists.txt | 19 - .../autoware_overlay_msgs/msg/OverlayText.msg | 31 - .../autoware_overlay_msgs/package.xml | 24 - .../CMakeLists.txt | 115 ++-- .../include/overlay_text_display.hpp | 157 ----- .../include/overlay_utils.hpp | 14 +- .../autoware_overlay_rviz_plugin/package.xml | 1 - .../src/overlay_text_display.cpp | 556 ------------------ .../src/signal_display.cpp | 80 +-- 10 files changed, 62 insertions(+), 959 deletions(-) delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp delete mode 100644 common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst deleted file mode 100644 index e7672ee001955..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst +++ /dev/null @@ -1,24 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package rviz_2d_overlay_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.3.0 (2023-05-18) ------------------- -* Removed old position message fields -* Contributors: Dominik, Jonas Otto - -1.2.1 (2022-09-30) ------------------- - -1.2.0 (2022-09-27) ------------------- -* Rename package from overlay_rviz_msgs to rviz_2d_overlay_msgs -* Contributors: Jonas Otto - -1.1.0 (2022-09-11) ------------------- - -1.0.0 (2022-08-30) ------------------- -* Create OverlayText message (currently same as jsk_rviz_plugins) -* Contributors: Jonas Otto, Dominik Authaler diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt deleted file mode 100644 index e23a4e755cbc4..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(autoware_overlay_msgs) - -if (NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 17) -endif () - - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rosidl_default_generators REQUIRED) -find_package(std_msgs REQUIRED) -rosidl_generate_interfaces(${PROJECT_NAME} - "msg/OverlayText.msg" - DEPENDENCIES - std_msgs -) - -ament_package() diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg deleted file mode 100644 index db3cf628b895b..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg +++ /dev/null @@ -1,31 +0,0 @@ -uint8 ADD = 0 -uint8 DELETE = 1 - -# constants for the horizontal and vertical alignment -uint8 LEFT = 0 -uint8 RIGHT = 1 -uint8 CENTER = 2 -uint8 TOP = 3 -uint8 BOTTOM = 4 - -uint8 action - -int32 width -int32 height -# Position: Positive values move the overlay towards the center of the window, -# for center alignment positive values move the overlay towards the bottom right -int32 horizontal_distance # Horizontal distance from left/right border or center, depending on alignment -int32 vertical_distance # Vertical distance between from top/bottom border or center, depending on alignment - -# Alignment of the overlay withing RVIZ -uint8 horizontal_alignment # one of LEFT, CENTER, RIGHT -uint8 vertical_alignment # one of TOP, CENTER, BOTTOM - -std_msgs/ColorRGBA bg_color - -int32 line_width -float32 text_size -string font -std_msgs/ColorRGBA fg_color - -string text diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml deleted file mode 100644 index 4881b126ffffb..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - autoware_overlay_msgs - 1.3.0 - Messages describing 2D overlays for RVIZ, extracted/derived from the jsk_visualization package. - Team Spatzenhirn - BSD-3-Clause - - ament_cmake - rosidl_default_generators - - autoware_auto_vehicle_msgs - autoware_perception_msgs - std_msgs - unique_identifier_msgs - rosidl_default_runtime - - rosidl_interface_packages - - - ament_cmake - - diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt index afb12bffeeaa7..aafc62fc90d25 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt @@ -3,28 +3,13 @@ project(autoware_overlay_rviz_plugin) # find dependencies find_package(ament_cmake_auto REQUIRED) -find_package(ament_cmake REQUIRED) -find_package(autoware_auto_vehicle_msgs REQUIRED) -find_package(tier4_planning_msgs REQUIRED) -find_package(autoware_perception_msgs REQUIRED) ament_auto_find_build_dependencies() -find_package(autoware_overlay_msgs REQUIRED) - -find_package(rviz_common REQUIRED) -find_package(rviz_rendering REQUIRED) -find_package(rviz_ogre_vendor REQUIRED) -find_package(std_msgs REQUIRED) - -set( - headers_to_moc - include/overlay_text_display.hpp - include/signal_display.hpp - +set(headers_to_moc + include/signal_display.hpp ) -set( - headers_to_not_moc +set(headers_to_not_moc include/steering_wheel_display.hpp include/gear_display.hpp include/speed_display.hpp @@ -34,47 +19,42 @@ set( ) - foreach(header "${headers_to_moc}") - qt5_wrap_cpp(display_moc_files "${header}") + qt5_wrap_cpp(display_moc_files "${header}") endforeach() -set( - display_source_files - src/overlay_text_display.cpp - src/overlay_utils.cpp - src/signal_display.cpp - src/steering_wheel_display.cpp - src/gear_display.cpp - src/speed_display.cpp - src/turn_signals_display.cpp - src/traffic_display.cpp - src/speed_limit_display.cpp - +set(display_source_files + src/overlay_utils.cpp + src/signal_display.cpp + src/steering_wheel_display.cpp + src/gear_display.cpp + src/speed_display.cpp + src/turn_signals_display.cpp + src/traffic_display.cpp + src/speed_limit_display.cpp ) -add_library( - ${PROJECT_NAME} SHARED - ${display_moc_files} - ${headers_to_not_moc} - ${display_source_files} +add_library(${PROJECT_NAME} SHARED + ${display_moc_files} + ${headers_to_not_moc} + ${display_source_files} ) set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17) target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic) target_include_directories( - ${PROJECT_NAME} PUBLIC - $ - $ - ${Qt5Widgets_INCLUDE_DIRS} - ${OpenCV_INCLUDE_DIRS} + ${PROJECT_NAME} PUBLIC + $ + $ + ${Qt5Widgets_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} ) target_link_libraries( - ${PROJECT_NAME} PUBLIC - rviz_ogre_vendor::OgreMain - rviz_ogre_vendor::OgreOverlay + ${PROJECT_NAME} PUBLIC + rviz_ogre_vendor::OgreMain + rviz_ogre_vendor::OgreOverlay ) @@ -85,22 +65,19 @@ target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNC pluginlib_export_plugin_description_file(rviz_common plugins_description.xml) -ament_target_dependencies( - ${PROJECT_NAME} - PUBLIC - rviz_common - rviz_rendering - autoware_overlay_msgs - autoware_auto_vehicle_msgs - tier4_planning_msgs - autoware_perception_msgs +ament_target_dependencies(${PROJECT_NAME} PUBLIC + rviz_common + rviz_rendering + autoware_auto_vehicle_msgs + tier4_planning_msgs + autoware_perception_msgs ) ament_export_include_directories(include) ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) ament_export_dependencies( - rviz_common - rviz_ogre_vendor + rviz_common + rviz_ogre_vendor ) if(BUILD_TESTING) @@ -109,32 +86,32 @@ if(BUILD_TESTING) endif() install( - TARGETS ${PROJECT_NAME} - EXPORT ${PROJECT_NAME} - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin - INCLUDES DESTINATION include + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include ) install( - DIRECTORY include/ - DESTINATION include + DIRECTORY include/ + DESTINATION include ) install( - TARGETS - DESTINATION lib/${PROJECT_NAME} + TARGETS + DESTINATION lib/${PROJECT_NAME} ) # Copy the assets directory to the installation directory install( - DIRECTORY assets/ - DESTINATION share/${PROJECT_NAME}/assets + DIRECTORY assets/ + DESTINATION share/${PROJECT_NAME}/assets ) add_definitions(-DQT_NO_KEYWORDS) ament_package( - CONFIG_EXTRAS "autoware_overlay_rviz_plugin-extras.cmake" + CONFIG_EXTRAS "autoware_overlay_rviz_plugin-extras.cmake" ) diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp deleted file mode 100644 index ccea51b9a5349..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp +++ /dev/null @@ -1,157 +0,0 @@ -// Copyright 2024 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -// -*- mode: c++; -*- -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2022, Team Spatzenhirn - * Copyright (c) 2014, JSK Lab - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/o2r other materials provided - * with the distribution. - * * Neither the name of the JSK Lab nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ -#ifndef OVERLAY_TEXT_DISPLAY_HPP_ -#define OVERLAY_TEXT_DISPLAY_HPP_ - -#include "autoware_overlay_msgs/msg/overlay_text.hpp" -#ifndef Q_MOC_RUN -#include "overlay_utils.hpp" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#include -#endif - -namespace autoware_overlay_rviz_plugin -{ -class OverlayTextDisplay -: public rviz_common::RosTopicDisplay -{ - Q_OBJECT -public: - OverlayTextDisplay(); - virtual ~OverlayTextDisplay(); - -protected: - autoware_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; - - int texture_width_; - int texture_height_; - - bool overtake_fg_color_properties_; - bool overtake_bg_color_properties_; - bool overtake_position_properties_; - bool align_bottom_; - bool invert_shadow_; - QColor bg_color_; - QColor fg_color_; - int text_size_; - int line_width_; - std::string text_; - QStringList font_families_; - std::string font_; - int horizontal_dist_; - int vertical_dist_; - HorizontalAlignment horizontal_alignment_; - VerticalAlignment vertical_alignment_; - - void onInitialize() override; - void onEnable() override; - void onDisable() override; - void update(float wall_dt, float ros_dt) override; - void reset() override; - - bool require_update_texture_; - // properties are raw pointers since they are owned by Qt - rviz_common::properties::BoolProperty * overtake_position_properties_property_; - rviz_common::properties::BoolProperty * overtake_fg_color_properties_property_; - rviz_common::properties::BoolProperty * overtake_bg_color_properties_property_; - rviz_common::properties::BoolProperty * align_bottom_property_; - rviz_common::properties::BoolProperty * invert_shadow_property_; - rviz_common::properties::IntProperty * hor_dist_property_; - rviz_common::properties::IntProperty * ver_dist_property_; - rviz_common::properties::EnumProperty * hor_alignment_property_; - rviz_common::properties::EnumProperty * ver_alignment_property_; - rviz_common::properties::IntProperty * width_property_; - rviz_common::properties::IntProperty * height_property_; - rviz_common::properties::IntProperty * text_size_property_; - rviz_common::properties::IntProperty * line_width_property_; - rviz_common::properties::ColorProperty * bg_color_property_; - rviz_common::properties::FloatProperty * bg_alpha_property_; - rviz_common::properties::ColorProperty * fg_color_property_; - rviz_common::properties::FloatProperty * fg_alpha_property_; - rviz_common::properties::EnumProperty * font_property_; - -protected Q_SLOTS: - void updateOvertakePositionProperties(); - void updateOvertakeFGColorProperties(); - void updateOvertakeBGColorProperties(); - void updateAlignBottom(); - void updateInvertShadow(); - void updateHorizontalDistance(); - void updateVerticalDistance(); - void updateHorizontalAlignment(); - void updateVerticalAlignment(); - void updateWidth(); - void updateHeight(); - void updateTextSize(); - void updateFGColor(); - void updateFGAlpha(); - void updateBGColor(); - void updateBGAlpha(); - void updateFont(); - void updateLineWidth(); - -private: - void processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) override; -}; -} // namespace autoware_overlay_rviz_plugin - -#endif // OVERLAY_TEXT_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp index 8581628ef0bce..b9c060899bace 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp @@ -54,8 +54,6 @@ #include #include -#include "autoware_overlay_msgs/msg/overlay_text.hpp" - #include #include #include @@ -89,17 +87,9 @@ class ScopedPixelBuffer Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; }; -enum class VerticalAlignment : uint8_t { - CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER, - TOP = autoware_overlay_msgs::msg::OverlayText::TOP, - BOTTOM = autoware_overlay_msgs::msg::OverlayText::BOTTOM, -}; +enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM }; -enum class HorizontalAlignment : uint8_t { - LEFT = autoware_overlay_msgs::msg::OverlayText::LEFT, - RIGHT = autoware_overlay_msgs::msg::OverlayText::RIGHT, - CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER -}; +enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER }; /** * Helper class for realizing an overlay object on top of the rviz 3D panel. diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml index da075b2648937..4d2f53e1e27ed 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml @@ -12,7 +12,6 @@ BSD-3-Clause autoware_auto_vehicle_msgs - autoware_overlay_msgs autoware_perception_msgs boost rviz_common diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp deleted file mode 100644 index b853e14a5858d..0000000000000 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp +++ /dev/null @@ -1,556 +0,0 @@ -// Copyright 2024 The Autoware Contributors -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -// -*- mode: c++; -*- -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2022, Team Spatzenhirn - * Copyright (c) 2014, JSK Lab - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/o2r other materials provided - * with the distribution. - * * Neither the name of the JSK Lab nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -#include "overlay_text_display.hpp" - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include - -#include -#include - -namespace autoware_overlay_rviz_plugin -{ -OverlayTextDisplay::OverlayTextDisplay() -: texture_width_(0), - texture_height_(0), - bg_color_(0, 0, 0, 0), - fg_color_(255, 255, 255, 255.0), - text_size_(14), - line_width_(2), - text_(""), - font_(""), - require_update_texture_(false) -{ - overtake_position_properties_property_ = new rviz_common::properties::BoolProperty( - "Overtake Position Properties", false, - "overtake position properties specified by message such as left, top and font", this, - SLOT(updateOvertakePositionProperties())); - overtake_fg_color_properties_property_ = new rviz_common::properties::BoolProperty( - "Overtake FG Color Properties", false, - "overtake color properties specified by message such as foreground color and alpha", this, - SLOT(updateOvertakeFGColorProperties())); - overtake_bg_color_properties_property_ = new rviz_common::properties::BoolProperty( - "Overtake BG Color Properties", false, - "overtake color properties specified by message such as background color and alpha", this, - SLOT(updateOvertakeBGColorProperties())); - align_bottom_property_ = new rviz_common::properties::BoolProperty( - "Align Bottom", false, "align text with the bottom of the overlay region", this, - SLOT(updateAlignBottom())); - invert_shadow_property_ = new rviz_common::properties::BoolProperty( - "Invert Shadow", false, "make shadow lighter than original text", this, - SLOT(updateInvertShadow())); - hor_dist_property_ = new rviz_common::properties::IntProperty( - "hor_dist", 0, "horizontal distance to anchor", this, SLOT(updateHorizontalDistance())); - ver_dist_property_ = new rviz_common::properties::IntProperty( - "ver_dist", 0, "vertical distance to anchor", this, SLOT(updateVerticalDistance())); - hor_alignment_property_ = new rviz_common::properties::EnumProperty( - "hor_alignment", "left", "horizontal alignment of the overlay", this, - SLOT(updateHorizontalAlignment())); - hor_alignment_property_->addOption("left", autoware_overlay_msgs::msg::OverlayText::LEFT); - hor_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER); - hor_alignment_property_->addOption("right", autoware_overlay_msgs::msg::OverlayText::RIGHT); - ver_alignment_property_ = new rviz_common::properties::EnumProperty( - "ver_alignment", "top", "vertical alignment of the overlay", this, - SLOT(updateVerticalAlignment())); - ver_alignment_property_->addOption("top", autoware_overlay_msgs::msg::OverlayText::TOP); - ver_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER); - ver_alignment_property_->addOption("bottom", autoware_overlay_msgs::msg::OverlayText::BOTTOM); - width_property_ = new rviz_common::properties::IntProperty( - "width", 128, "width position", this, SLOT(updateWidth())); - width_property_->setMin(0); - height_property_ = new rviz_common::properties::IntProperty( - "height", 128, "height position", this, SLOT(updateHeight())); - height_property_->setMin(0); - text_size_property_ = new rviz_common::properties::IntProperty( - "text size", 12, "text size", this, SLOT(updateTextSize())); - text_size_property_->setMin(0); - line_width_property_ = new rviz_common::properties::IntProperty( - "line width", 2, "line width", this, SLOT(updateLineWidth())); - line_width_property_->setMin(0); - fg_color_property_ = new rviz_common::properties::ColorProperty( - "Foreground Color", QColor(25, 255, 240), "Foreground Color", this, SLOT(updateFGColor())); - fg_alpha_property_ = new rviz_common::properties::FloatProperty( - "Foreground Alpha", 0.8, "Foreground Alpha", this, SLOT(updateFGAlpha())); - fg_alpha_property_->setMin(0.0); - fg_alpha_property_->setMax(1.0); - bg_color_property_ = new rviz_common::properties::ColorProperty( - "Background Color", QColor(0, 0, 0), "Background Color", this, SLOT(updateBGColor())); - bg_alpha_property_ = new rviz_common::properties::FloatProperty( - "Background Alpha", 0.8, "Background Alpha", this, SLOT(updateBGAlpha())); - bg_alpha_property_->setMin(0.0); - bg_alpha_property_->setMax(1.0); - - QFontDatabase database; - font_families_ = database.families(); - font_property_ = new rviz_common::properties::EnumProperty( - "font", "DejaVu Sans Mono", "font", this, SLOT(updateFont())); - for (ssize_t i = 0; i < font_families_.size(); i++) { - font_property_->addOption(font_families_[i], static_cast(i)); - } -} - -OverlayTextDisplay::~OverlayTextDisplay() -{ - onDisable(); -} - -void OverlayTextDisplay::onEnable() -{ - if (overlay_) { - overlay_->show(); - } - subscribe(); -} - -void OverlayTextDisplay::onDisable() -{ - if (overlay_) { - overlay_->hide(); - } - unsubscribe(); -} - -// only the first time -void OverlayTextDisplay::onInitialize() -{ - RTDClass::onInitialize(); - rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_); - - onEnable(); - updateTopic(); - updateOvertakePositionProperties(); - updateOvertakeFGColorProperties(); - updateOvertakeBGColorProperties(); - updateAlignBottom(); - updateInvertShadow(); - updateHorizontalDistance(); - updateVerticalDistance(); - updateHorizontalAlignment(); - updateVerticalAlignment(); - updateWidth(); - updateHeight(); - updateTextSize(); - updateFGColor(); - updateFGAlpha(); - updateBGColor(); - updateBGAlpha(); - updateFont(); - updateLineWidth(); - require_update_texture_ = true; -} - -void OverlayTextDisplay::update(float /*wall_dt*/, float /*ros_dt*/) -{ - if (!require_update_texture_) { - return; - } - if (!isEnabled()) { - return; - } - if (!overlay_) { - return; - } - - overlay_->updateTextureSize(texture_width_, texture_height_); - { - autoware_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); - QImage Hud = buffer.getQImage(*overlay_, bg_color_); - QPainter painter(&Hud); - painter.setRenderHint(QPainter::Antialiasing, true); - painter.setPen(QPen(fg_color_, std::max(line_width_, 1), Qt::SolidLine)); - uint16_t w = overlay_->getTextureWidth(); - uint16_t h = overlay_->getTextureHeight(); - - // font - if (text_size_ != 0) { - // QFont font = painter.font(); - QFont font(font_.length() > 0 ? font_.c_str() : "Liberation Sans"); - font.setPointSize(text_size_); - font.setBold(true); - painter.setFont(font); - } - if (text_.length() > 0) { - QColor shadow_color; - if (invert_shadow_) - shadow_color = Qt::white; // fg_color_.lighter(); - else - shadow_color = Qt::black; // fg_color_.darker(); - shadow_color.setAlpha(fg_color_.alpha()); - - std::string color_wrapped_text = - (boost::format("%1%") % text_ % - fg_color_.red() % fg_color_.green() % fg_color_.blue() % fg_color_.alpha()) - .str(); - - // find a remove "color: XXX;" regex match to generate a proper shadow - std::regex color_tag_re("color:.+?;"); - std::string null_char(""); - std::string formatted_text_ = std::regex_replace(text_, color_tag_re, null_char); - std::string color_wrapped_shadow = - (boost::format("%1%") % - formatted_text_ % shadow_color.red() % shadow_color.green() % shadow_color.blue() % - shadow_color.alpha()) - .str(); - - QStaticText static_text( - boost::algorithm::replace_all_copy(color_wrapped_text, "\n", "
").c_str()); - static_text.setTextWidth(w); - - painter.setPen(QPen(shadow_color, std::max(line_width_, 1), Qt::SolidLine)); - QStaticText static_shadow( - boost::algorithm::replace_all_copy(color_wrapped_shadow, "\n", "
").c_str()); - static_shadow.setTextWidth(w); - - if (!align_bottom_) { - painter.drawStaticText(1, 1, static_shadow); - painter.drawStaticText(0, 0, static_text); - } else { - QStaticText only_wrapped_text(color_wrapped_text.c_str()); - QFontMetrics fm(painter.fontMetrics()); - QRect text_rect = fm.boundingRect( - 0, 0, w, h, Qt::TextWordWrap | Qt::AlignLeft | Qt::AlignTop, - only_wrapped_text.text().remove(QRegExp("<[^>]*>"))); - painter.drawStaticText(1, h - text_rect.height() + 1, static_shadow); - painter.drawStaticText(0, h - text_rect.height(), static_text); - } - } - painter.end(); - } - overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); - require_update_texture_ = false; -} - -void OverlayTextDisplay::reset() -{ - RTDClass::reset(); - - if (overlay_) { - overlay_->hide(); - } -} - -void OverlayTextDisplay::processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) -{ - if (!isEnabled()) { - return; - } - if (!overlay_) { - static int count = 0; - std::stringstream ss; - ss << "OverlayTextDisplayObject" << count++; - overlay_.reset(new autoware_overlay_rviz_plugin::OverlayObject(ss.str())); - overlay_->show(); - } - if (overlay_) { - if (msg->action == autoware_overlay_msgs::msg::OverlayText::DELETE) { - overlay_->hide(); - } else if (msg->action == autoware_overlay_msgs::msg::OverlayText::ADD) { - overlay_->show(); - } - } - - // store message for update method - text_ = msg->text; - - if (!overtake_position_properties_) { - texture_width_ = msg->width; - texture_height_ = msg->height; - text_size_ = msg->text_size; - horizontal_dist_ = msg->horizontal_distance; - vertical_dist_ = msg->vertical_distance; - - horizontal_alignment_ = HorizontalAlignment{msg->horizontal_alignment}; - vertical_alignment_ = VerticalAlignment{msg->vertical_alignment}; - } - if (!overtake_bg_color_properties_) - bg_color_ = QColor( - msg->bg_color.r * 255.0, msg->bg_color.g * 255.0, msg->bg_color.b * 255.0, - msg->bg_color.a * 255.0); - if (!overtake_fg_color_properties_) { - fg_color_ = QColor( - msg->fg_color.r * 255.0, msg->fg_color.g * 255.0, msg->fg_color.b * 255.0, - msg->fg_color.a * 255.0); - font_ = msg->font; - line_width_ = msg->line_width; - } - if (overlay_) { - overlay_->setPosition( - horizontal_dist_, vertical_dist_, horizontal_alignment_, vertical_alignment_); - } - require_update_texture_ = true; -} - -void OverlayTextDisplay::updateOvertakePositionProperties() -{ - if (!overtake_position_properties_ && overtake_position_properties_property_->getBool()) { - updateVerticalDistance(); - updateHorizontalDistance(); - updateVerticalAlignment(); - updateHorizontalAlignment(); - updateWidth(); - updateHeight(); - updateTextSize(); - require_update_texture_ = true; - } - - overtake_position_properties_ = overtake_position_properties_property_->getBool(); - if (overtake_position_properties_) { - hor_dist_property_->show(); - ver_dist_property_->show(); - hor_alignment_property_->show(); - ver_alignment_property_->show(); - width_property_->show(); - height_property_->show(); - text_size_property_->show(); - } else { - hor_dist_property_->hide(); - ver_dist_property_->hide(); - hor_alignment_property_->hide(); - ver_alignment_property_->hide(); - width_property_->hide(); - height_property_->hide(); - text_size_property_->hide(); - } -} - -void OverlayTextDisplay::updateOvertakeFGColorProperties() -{ - if (!overtake_fg_color_properties_ && overtake_fg_color_properties_property_->getBool()) { - // read all the parameters from properties - updateFGColor(); - updateFGAlpha(); - updateFont(); - updateLineWidth(); - require_update_texture_ = true; - } - overtake_fg_color_properties_ = overtake_fg_color_properties_property_->getBool(); - if (overtake_fg_color_properties_) { - fg_color_property_->show(); - fg_alpha_property_->show(); - line_width_property_->show(); - font_property_->show(); - } else { - fg_color_property_->hide(); - fg_alpha_property_->hide(); - line_width_property_->hide(); - font_property_->hide(); - } -} - -void OverlayTextDisplay::updateOvertakeBGColorProperties() -{ - if (!overtake_bg_color_properties_ && overtake_bg_color_properties_property_->getBool()) { - // read all the parameters from properties - updateBGColor(); - updateBGAlpha(); - require_update_texture_ = true; - } - overtake_bg_color_properties_ = overtake_bg_color_properties_property_->getBool(); - if (overtake_bg_color_properties_) { - bg_color_property_->show(); - bg_alpha_property_->show(); - } else { - bg_color_property_->hide(); - bg_alpha_property_->hide(); - } -} - -void OverlayTextDisplay::updateAlignBottom() -{ - if (align_bottom_ != align_bottom_property_->getBool()) { - require_update_texture_ = true; - } - align_bottom_ = align_bottom_property_->getBool(); -} - -void OverlayTextDisplay::updateInvertShadow() -{ - if (invert_shadow_ != invert_shadow_property_->getBool()) { - require_update_texture_ = true; - } - invert_shadow_ = invert_shadow_property_->getBool(); -} - -void OverlayTextDisplay::updateVerticalDistance() -{ - vertical_dist_ = ver_dist_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateHorizontalDistance() -{ - horizontal_dist_ = hor_dist_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateVerticalAlignment() -{ - vertical_alignment_ = - VerticalAlignment{static_cast(ver_alignment_property_->getOptionInt())}; - - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateHorizontalAlignment() -{ - horizontal_alignment_ = - HorizontalAlignment{static_cast(hor_alignment_property_->getOptionInt())}; - - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateWidth() -{ - texture_width_ = width_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateHeight() -{ - texture_height_ = height_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateTextSize() -{ - text_size_ = text_size_property_->getInt(); - if (overtake_position_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateBGColor() -{ - QColor c = bg_color_property_->getColor(); - bg_color_.setRed(c.red()); - bg_color_.setGreen(c.green()); - bg_color_.setBlue(c.blue()); - if (overtake_bg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateBGAlpha() -{ - bg_color_.setAlpha(bg_alpha_property_->getFloat() * 255.0); - if (overtake_bg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateFGColor() -{ - QColor c = fg_color_property_->getColor(); - fg_color_.setRed(c.red()); - fg_color_.setGreen(c.green()); - fg_color_.setBlue(c.blue()); - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateFGAlpha() -{ - fg_color_.setAlpha(fg_alpha_property_->getFloat() * 255.0); - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateFont() -{ - int font_index = font_property_->getOptionInt(); - if (font_index < font_families_.size()) { - font_ = font_families_[font_index].toStdString(); - } else { - RVIZ_COMMON_LOG_ERROR_STREAM("Unexpected error at selecting font index " << font_index); - return; - } - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -void OverlayTextDisplay::updateLineWidth() -{ - line_width_ = line_width_property_->getInt(); - if (overtake_fg_color_properties_) { - require_update_texture_ = true; - } -} - -} // namespace autoware_overlay_rviz_plugin - -#include -PLUGINLIB_EXPORT_CLASS(autoware_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp index 841b33c29fbb0..9add6336ece46 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp @@ -120,59 +120,13 @@ void SignalDisplay::onInitialize() void SignalDisplay::setupRosSubscriptions() { - // Don't create a node, just use the one from the parent class - auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); - - gear_sub_ = rviz_node_->create_subscription( - gear_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) { - updateGearData(msg); - }); - - steering_sub_ = rviz_node_->create_subscription( - steering_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) { - updateSteeringData(msg); - }); - - speed_sub_ = rviz_node_->create_subscription( - speed_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) { - updateSpeedData(msg); - }); - - turn_signals_sub_ = - rviz_node_->create_subscription( - turn_signals_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) { - updateTurnSignalsData(msg); - }); - - hazard_lights_sub_ = - rviz_node_->create_subscription( - hazard_lights_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) { - updateHazardLightsData(msg); - }); - - traffic_sub_ = rviz_node_->create_subscription( - traffic_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) { - updateTrafficLightData(msg); - }); - - speed_limit_sub_ = rviz_node_->create_subscription( - speed_limit_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), - [this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) { - updateSpeedLimitData(msg); - }); + topic_updated_gear(); + topic_updated_steering(); + topic_updated_speed(); + topic_updated_speed_limit(); + topic_updated_turn_signals(); + topic_updated_hazard_lights(); + topic_updated_traffic(); } SignalDisplay::~SignalDisplay() @@ -419,8 +373,7 @@ void SignalDisplay::topic_updated_gear() auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); gear_sub_ = rviz_ros_node->get_raw_node()->create_subscription( - gear_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + gear_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), [this](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) { updateGearData(msg); }); @@ -433,8 +386,7 @@ void SignalDisplay::topic_updated_steering() auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); steering_sub_ = rviz_ros_node->get_raw_node() ->create_subscription( - steering_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + steering_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), [this](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) { updateSteeringData(msg); }); @@ -447,8 +399,7 @@ void SignalDisplay::topic_updated_speed() auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); speed_sub_ = rviz_ros_node->get_raw_node() ->create_subscription( - speed_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + speed_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), [this](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) { updateSpeedData(msg); }); @@ -462,7 +413,7 @@ void SignalDisplay::topic_updated_speed_limit() speed_limit_sub_ = rviz_ros_node->get_raw_node()->create_subscription( speed_limit_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + rclcpp::QoS(rclcpp::KeepLast(10)).transient_local(), [this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) { updateSpeedLimitData(msg); }); @@ -477,8 +428,7 @@ void SignalDisplay::topic_updated_turn_signals() turn_signals_sub_ = rviz_ros_node->get_raw_node() ->create_subscription( - turn_signals_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + turn_signals_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), [this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) { updateTurnSignalsData(msg); }); @@ -493,8 +443,7 @@ void SignalDisplay::topic_updated_hazard_lights() hazard_lights_sub_ = rviz_ros_node->get_raw_node() ->create_subscription( - hazard_lights_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + hazard_lights_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), [this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) { updateHazardLightsData(msg); }); @@ -507,8 +456,7 @@ void SignalDisplay::topic_updated_traffic() auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); traffic_sub_ = rviz_ros_node->get_raw_node() ->create_subscription( - traffic_topic_property_->getTopicStd(), - rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + traffic_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), [this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) { updateTrafficLightData(msg); }); From bffbccec54f79cd2ed3e1143feb2f5584ecfc169 Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Mon, 13 May 2024 08:10:45 +0800 Subject: [PATCH 151/192] fix(accel_brake_calibrator): fix to set service name and exception failure (#6973) * add service * fix exception * fix style --- ...ccel_brake_map_calibrator_button_panel.cpp | 48 ++++++++++++++++--- ...ccel_brake_map_calibrator_button_panel.hpp | 3 ++ 2 files changed, 44 insertions(+), 7 deletions(-) diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp index 5c1c98488b0f6..d89f13ce74d02 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp @@ -34,13 +34,19 @@ namespace tier4_calibration_rviz_plugin AccelBrakeMapCalibratorButtonPanel::AccelBrakeMapCalibratorButtonPanel(QWidget * parent) : rviz_common::Panel(parent) { - topic_label_ = new QLabel("Topic name of update suggest "); + topic_label_ = new QLabel("topic: "); topic_label_->setAlignment(Qt::AlignCenter); topic_edit_ = new QLineEdit("/vehicle/calibration/accel_brake_map_calibrator/output/update_suggest"); connect(topic_edit_, SIGNAL(textEdited(QString)), SLOT(editTopic())); + service_label_ = new QLabel("service: "); + service_label_->setAlignment(Qt::AlignCenter); + + service_edit_ = new QLineEdit("/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); + connect(service_edit_, SIGNAL(textEdited(QString)), SLOT(editService())); + calibration_button_ = new QPushButton("Wait for subscribe topic"); calibration_button_->setEnabled(false); connect(calibration_button_, SIGNAL(clicked(bool)), SLOT(pushCalibrationButton())); @@ -56,8 +62,13 @@ AccelBrakeMapCalibratorButtonPanel::AccelBrakeMapCalibratorButtonPanel(QWidget * topic_layout->addWidget(topic_label_); topic_layout->addWidget(topic_edit_); + auto * service_layout = new QHBoxLayout; + service_layout->addWidget(service_label_); + service_layout->addWidget(service_edit_); + auto * v_layout = new QVBoxLayout; v_layout->addLayout(topic_layout); + v_layout->addLayout(service_layout); v_layout->addWidget(calibration_button_); v_layout->addWidget(status_label_); @@ -75,7 +86,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize() &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); client_ = raw_node->create_client( - "/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); + service_edit_->text().toStdString()); } void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( @@ -85,6 +96,12 @@ void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( return; } + if (!client_ || !client_->service_is_ready()) { + calibration_button_->setText("wait for service"); + calibration_button_->setEnabled(false); + return; + } + if (msg->data) { status_label_->setText("Ready"); status_label_->setStyleSheet("QLabel { background-color : white;}"); @@ -98,17 +115,34 @@ void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( void AccelBrakeMapCalibratorButtonPanel::editTopic() { - update_suggest_sub_.reset(); rclcpp::Node::SharedPtr raw_node = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - update_suggest_sub_ = raw_node->create_subscription( - topic_edit_->text().toStdString(), 10, - std::bind( - &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); + try { + update_suggest_sub_.reset(); + update_suggest_sub_ = raw_node->create_subscription( + topic_edit_->text().toStdString(), 10, + std::bind( + &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); + } catch (const rclcpp::exceptions::InvalidTopicNameError & e) { + RCLCPP_WARN_STREAM(raw_node->get_logger(), e.what()); + } calibration_button_->setText("Wait for subscribe topic"); calibration_button_->setEnabled(false); } +void AccelBrakeMapCalibratorButtonPanel::editService() +{ + rclcpp::Node::SharedPtr raw_node = + this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + try { + client_.reset(); + client_ = raw_node->create_client( + service_edit_->text().toStdString()); + } catch (const rclcpp::exceptions::InvalidServiceNameError & e) { + RCLCPP_WARN_STREAM(raw_node->get_logger(), e.what()); + } +} + void AccelBrakeMapCalibratorButtonPanel::pushCalibrationButton() { // lock button diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp index e26789c9f120f..70ebe0631fa21 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp @@ -46,6 +46,7 @@ class AccelBrakeMapCalibratorButtonPanel : public rviz_common::Panel public Q_SLOTS: // NOLINT for Qt void editTopic(); + void editService(); void pushCalibrationButton(); protected: @@ -56,6 +57,8 @@ public Q_SLOTS: // NOLINT for Qt QLabel * topic_label_; QLineEdit * topic_edit_; + QLabel * service_label_; + QLineEdit * service_edit_; QPushButton * calibration_button_; QLabel * status_label_; }; From fd89ca2e9e043be5de92a259a32e8e75b6f34707 Mon Sep 17 00:00:00 2001 From: go-sakayori Date: Mon, 13 May 2024 10:22:47 +0900 Subject: [PATCH 152/192] test: behavior path obstacle avoidance (#6972) * write test for behavior avoidance Signed-off-by: Go Sakayori * style(pre-commit): autofix --------- Signed-off-by: Go Sakayori Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../test/test_utils.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/planning/behavior_path_avoidance_module/test/test_utils.cpp b/planning/behavior_path_avoidance_module/test/test_utils.cpp index 95488daa69cf8..1a114eef9f7f7 100644 --- a/planning/behavior_path_avoidance_module/test/test_utils.cpp +++ b/planning/behavior_path_avoidance_module/test/test_utils.cpp @@ -21,6 +21,7 @@ using behavior_path_planner::ObjectData; using behavior_path_planner::utils::avoidance::isOnRight; using behavior_path_planner::utils::avoidance::isSameDirectionShift; +using behavior_path_planner::utils::avoidance::isShiftNecessary; TEST(BehaviorPathPlanningAvoidanceUtilsTest, shiftLengthDirectionTest) { @@ -37,3 +38,19 @@ TEST(BehaviorPathPlanningAvoidanceUtilsTest, shiftLengthDirectionTest) ASSERT_TRUE(isSameDirectionShift(isOnRight(left_obj), positive_shift_length)); ASSERT_FALSE(isSameDirectionShift(isOnRight(left_obj), negative_shift_length)); } + +TEST(BehaviorPathPlanningAvoidanceUtilsTest, shiftNecessaryTest) +{ + ObjectData right_obj; + right_obj.direction = route_handler::Direction::RIGHT; + const double negative_shift_length = -1.0; + const double positive_shift_length = 1.0; + + ASSERT_TRUE(isShiftNecessary(isOnRight(right_obj), positive_shift_length)); + ASSERT_FALSE(isShiftNecessary(isOnRight(right_obj), negative_shift_length)); + + ObjectData left_obj; + left_obj.direction = route_handler::Direction::LEFT; + ASSERT_TRUE(isShiftNecessary(isOnRight(left_obj), negative_shift_length)); + ASSERT_FALSE(isShiftNecessary(isOnRight(left_obj), positive_shift_length)); +} From bd46dc3ac15b15bff515900e2b9c84c339338813 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 13 May 2024 13:54:31 +0900 Subject: [PATCH 153/192] feat(rtc_interface)!: add new field to rtc cooperate status (#6933) * feat(rtc_interface): add new field Signed-off-by: satoshi-ota * feat(bvp): support new rtc cooperate status Signed-off-by: satoshi-ota * feat(bpp): support new rtc cooperate status Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/interface.cpp | 5 ++++- .../behavior_path_avoidance_module/scene.hpp | 14 ++++++++------ .../behavior_path_avoidance_module/type_alias.hpp | 2 ++ .../interface/scene_module_interface.hpp | 5 ++++- .../src/manager.cpp | 3 ++- .../src/manager.cpp | 4 ++-- .../src/manager.cpp | 3 ++- .../src/manager.cpp | 11 ++++++----- .../src/manager.cpp | 3 ++- .../scene_module_interface.hpp | 7 +++++-- .../src/scene_module_interface.cpp | 3 ++- .../src/manager.cpp | 3 ++- .../include/rtc_interface/rtc_interface.hpp | 6 ++++-- planning/rtc_interface/src/rtc_interface.cpp | 6 ++++-- 14 files changed, 49 insertions(+), 26 deletions(-) diff --git a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 3a7c22c84b3e8..a2e26557d9726 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -57,7 +57,10 @@ void AvoidanceByLaneChangeInterface::updateRTCStatus( return (dir == Direction::LEFT) ? "left" : "right"; }); + const auto state = isWaitingApproval() ? State::WAITING_FOR_EXECUTION : State::RUNNING; + rtc_interface_ptr_map_.at(direction)->updateCooperateStatus( - uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now()); + uuid_map_.at(direction), isExecutionReady(), state, start_distance, finish_distance, + clock_->now()); } } // namespace behavior_path_planner diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp index d7c101f885cdf..6b11d490e8c23 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp @@ -77,15 +77,17 @@ class AvoidanceModule : public SceneModuleInterface { if (candidate.lateral_shift > 0.0) { rtc_interface_ptr_map_.at("left")->updateCooperateStatus( - uuid_map_.at("left"), isExecutionReady(), candidate.start_distance_to_path_change, - candidate.finish_distance_to_path_change, clock_->now()); + uuid_map_.at("left"), isExecutionReady(), State::WAITING_FOR_EXECUTION, + candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change, + clock_->now()); candidate_uuid_ = uuid_map_.at("left"); return; } if (candidate.lateral_shift < 0.0) { rtc_interface_ptr_map_.at("right")->updateCooperateStatus( - uuid_map_.at("right"), isExecutionReady(), candidate.start_distance_to_path_change, - candidate.finish_distance_to_path_change, clock_->now()); + uuid_map_.at("right"), isExecutionReady(), State::WAITING_FOR_EXECUTION, + candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change, + clock_->now()); candidate_uuid_ = uuid_map_.at("right"); return; } @@ -108,7 +110,7 @@ class AvoidanceModule : public SceneModuleInterface motion_utils::calcSignedArcLength(path.points, ego_idx, left_shift.start_pose.position); const double finish_distance = start_distance + left_shift.relative_longitudinal; rtc_interface_ptr_map_.at("left")->updateCooperateStatus( - left_shift.uuid, true, start_distance, finish_distance, clock_->now()); + left_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now()); if (finish_distance > -1.0e-03) { steering_factor_interface_ptr_->updateSteeringFactor( {left_shift.start_pose, left_shift.finish_pose}, {start_distance, finish_distance}, @@ -121,7 +123,7 @@ class AvoidanceModule : public SceneModuleInterface motion_utils::calcSignedArcLength(path.points, ego_idx, right_shift.start_pose.position); const double finish_distance = start_distance + right_shift.relative_longitudinal; rtc_interface_ptr_map_.at("right")->updateCooperateStatus( - right_shift.uuid, true, start_distance, finish_distance, clock_->now()); + right_shift.uuid, true, State::RUNNING, start_distance, finish_distance, clock_->now()); if (finish_distance > -1.0e-03) { steering_factor_interface_ptr_->updateSteeringFactor( {right_shift.start_pose, right_shift.finish_pose}, {start_distance, finish_distance}, diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/type_alias.hpp b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/type_alias.hpp index 8e7c7820a3650..67bca3099df6f 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/type_alias.hpp +++ b/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/type_alias.hpp @@ -28,6 +28,7 @@ #include #include #include +#include #include namespace behavior_path_planner @@ -49,6 +50,7 @@ using visualization_msgs::msg::MarkerArray; // tier4 msgs using tier4_planning_msgs::msg::AvoidanceDebugMsg; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; +using tier4_rtc_msgs::msg::State; // tier4 utils functions using tier4_autoware_utils::appendMarkerArray; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index 0e06c1f8ab908..b4e1ffce8104a 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include @@ -67,6 +68,7 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::StopFactor; using tier4_planning_msgs::msg::StopReason; using tier4_planning_msgs::msg::StopReasonArray; +using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; using visualization_msgs::msg::MarkerArray; using PlanResult = PathWithLaneId::SharedPtr; @@ -490,8 +492,9 @@ class SceneModuleInterface { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { if (ptr) { + const auto state = isWaitingApproval() ? State::WAITING_FOR_EXECUTION : State::RUNNING; ptr->updateCooperateStatus( - uuid_map_.at(module_name), isExecutionReady(), start_distance, finish_distance, + uuid_map_.at(module_name), isExecutionReady(), state, start_distance, finish_distance, clock_->now()); } } diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_blind_spot_module/src/manager.cpp index d114ab0c65da9..faa10c1fbe9b4 100644 --- a/planning/behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/manager.cpp @@ -73,7 +73,8 @@ void BlindSpotModuleManager::launchNewModules( clock_)); generateUUID(module_id); updateRTCStatus( - getUUID(module_id), true, std::numeric_limits::lowest(), path.header.stamp); + getUUID(module_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits::lowest(), + path.header.stamp); } } diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index ad56df5f76944..5110ff9993a62 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -190,8 +190,8 @@ void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path) clock_)); generateUUID(crosswalk_lanelet_id); updateRTCStatus( - getUUID(crosswalk_lanelet_id), true, std::numeric_limits::lowest(), - path.header.stamp); + getUUID(crosswalk_lanelet_id), true, State::WAITING_FOR_EXECUTION, + std::numeric_limits::lowest(), path.header.stamp); }; const auto crosswalk_reg_elem_map = planning_utils::getRegElemMapOnPath( diff --git a/planning/behavior_velocity_detection_area_module/src/manager.cpp b/planning/behavior_velocity_detection_area_module/src/manager.cpp index 834ffc03e5dde..8e9a6b6a58a96 100644 --- a/planning/behavior_velocity_detection_area_module/src/manager.cpp +++ b/planning/behavior_velocity_detection_area_module/src/manager.cpp @@ -66,7 +66,8 @@ void DetectionAreaModuleManager::launchNewModules( logger_.get_child("detection_area_module"), clock_)); generateUUID(module_id); updateRTCStatus( - getUUID(module_id), true, std::numeric_limits::lowest(), path.header.stamp); + getUUID(module_id), true, State::WAITING_FOR_EXECUTION, + std::numeric_limits::lowest(), path.header.stamp); } } } diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 3941362d96242..424fb6841eca9 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -345,10 +345,10 @@ void IntersectionModuleManager::launchNewModules( const UUID uuid = getUUID(new_module->getModuleId()); const auto occlusion_uuid = new_module->getOcclusionUUID(); rtc_interface_.updateCooperateStatus( - uuid, true, std::numeric_limits::lowest(), std::numeric_limits::lowest(), - clock_->now()); + uuid, true, State::RUNNING, std::numeric_limits::lowest(), + std::numeric_limits::lowest(), clock_->now()); occlusion_rtc_interface_.updateCooperateStatus( - occlusion_uuid, true, std::numeric_limits::lowest(), + occlusion_uuid, true, State::RUNNING, std::numeric_limits::lowest(), std::numeric_limits::lowest(), clock_->now()); registerModule(std::move(new_module)); } @@ -404,12 +404,13 @@ void IntersectionModuleManager::sendRTC(const Time & stamp) const UUID uuid = getUUID(scene_module->getModuleId()); const bool safety = scene_module->isSafe() && (!intersection_module->isOcclusionFirstStopRequired()); - updateRTCStatus(uuid, safety, scene_module->getDistance(), stamp); + updateRTCStatus(uuid, safety, State::RUNNING, scene_module->getDistance(), stamp); const auto occlusion_uuid = intersection_module->getOcclusionUUID(); const auto occlusion_distance = intersection_module->getOcclusionDistance(); const auto occlusion_safety = intersection_module->getOcclusionSafety(); occlusion_rtc_interface_.updateCooperateStatus( - occlusion_uuid, occlusion_safety, occlusion_distance, occlusion_distance, stamp); + occlusion_uuid, occlusion_safety, State::RUNNING, occlusion_distance, occlusion_distance, + stamp); // ========================================================================================== // module debug data diff --git a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp index c4192750af1d5..46cc224ea0f6b 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/manager.cpp @@ -68,7 +68,8 @@ void NoStoppingAreaModuleManager::launchNewModules( clock_)); generateUUID(module_id); updateRTCStatus( - getUUID(module_id), true, std::numeric_limits::lowest(), path.header.stamp); + getUUID(module_id), true, State::WAITING_FOR_EXECUTION, + std::numeric_limits::lowest(), path.header.stamp); } } } diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp index d8b042ec880e4..082a88e306169 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp @@ -31,6 +31,7 @@ #include #include #include +#include #include #include @@ -58,6 +59,7 @@ using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::StopFactor; using tier4_planning_msgs::msg::StopReason; using tier4_rtc_msgs::msg::Module; +using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; struct ObjectOfInterest @@ -235,9 +237,10 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface virtual void setActivation(); void updateRTCStatus( - const UUID & uuid, const bool safe, const double distance, const Time & stamp) + const UUID & uuid, const bool safe, const uint8_t state, const double distance, + const Time & stamp) { - rtc_interface_.updateCooperateStatus(uuid, safe, distance, distance, stamp); + rtc_interface_.updateCooperateStatus(uuid, safe, state, distance, distance, stamp); } void removeRTCStatus(const UUID & uuid) { rtc_interface_.removeCooperateStatus(uuid); } diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp index 362493005eb17..803682489ebde 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -211,7 +211,8 @@ void SceneModuleManagerInterfaceWithRTC::sendRTC(const Time & stamp) { for (const auto & scene_module : scene_modules_) { const UUID uuid = getUUID(scene_module->getModuleId()); - updateRTCStatus(uuid, scene_module->isSafe(), scene_module->getDistance(), stamp); + const auto state = scene_module->isActivated() ? State::RUNNING : State::WAITING_FOR_EXECUTION; + updateRTCStatus(uuid, scene_module->isSafe(), state, scene_module->getDistance(), stamp); } publishRTCStatus(stamp); } diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index 89817f3342dbd..6e6871e20a354 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -133,7 +133,8 @@ void TrafficLightModuleManager::launchNewModules( planner_param_, logger_.get_child("traffic_light_module"), clock_)); generateUUID(module_id); updateRTCStatus( - getUUID(module_id), true, std::numeric_limits::lowest(), path.header.stamp); + getUUID(module_id), true, State::WAITING_FOR_EXECUTION, + std::numeric_limits::lowest(), path.header.stamp); } } } diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index aed7d42cda5e6..8d6e8c8fc1c7c 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -24,6 +24,7 @@ #include "tier4_rtc_msgs/msg/cooperate_status.hpp" #include "tier4_rtc_msgs/msg/cooperate_status_array.hpp" #include "tier4_rtc_msgs/msg/module.hpp" +#include "tier4_rtc_msgs/msg/state.hpp" #include "tier4_rtc_msgs/srv/auto_mode.hpp" #include "tier4_rtc_msgs/srv/cooperate_commands.hpp" #include @@ -41,6 +42,7 @@ using tier4_rtc_msgs::msg::CooperateResponse; using tier4_rtc_msgs::msg::CooperateStatus; using tier4_rtc_msgs::msg::CooperateStatusArray; using tier4_rtc_msgs::msg::Module; +using tier4_rtc_msgs::msg::State; using tier4_rtc_msgs::srv::AutoMode; using tier4_rtc_msgs::srv::CooperateCommands; using unique_identifier_msgs::msg::UUID; @@ -51,8 +53,8 @@ class RTCInterface RTCInterface(rclcpp::Node * node, const std::string & name, const bool enable_rtc = true); void publishCooperateStatus(const rclcpp::Time & stamp); void updateCooperateStatus( - const UUID & uuid, const bool safe, const double start_distance, const double finish_distance, - const rclcpp::Time & stamp); + const UUID & uuid, const bool safe, const uint8_t state, const double start_distance, + const double finish_distance, const rclcpp::Time & stamp); void removeCooperateStatus(const UUID & uuid); void clearCooperateStatus(); bool isActivated(const UUID & uuid) const; diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index a7661f4c419a5..c7afea57afce3 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -201,8 +201,8 @@ void RTCInterface::onTimer() } void RTCInterface::updateCooperateStatus( - const UUID & uuid, const bool safe, const double start_distance, const double finish_distance, - const rclcpp::Time & stamp) + const UUID & uuid, const bool safe, const uint8_t state, const double start_distance, + const double finish_distance, const rclcpp::Time & stamp) { std::lock_guard lock(mutex_); // Find registered status which has same uuid @@ -218,6 +218,7 @@ void RTCInterface::updateCooperateStatus( status.module = module_; status.safe = safe; status.command_status.type = Command::DEACTIVATE; + status.state.type = State::WAITING_FOR_EXECUTION; status.start_distance = start_distance; status.finish_distance = finish_distance; status.auto_mode = is_auto_mode_enabled_; @@ -228,6 +229,7 @@ void RTCInterface::updateCooperateStatus( // If the registered status is found, update status itr->stamp = stamp; itr->safe = safe; + itr->state.type = state; itr->start_distance = start_distance; itr->finish_distance = finish_distance; } From f3cd528230b46be523f69f94e6629a1be5758d82 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 13 May 2024 14:39:18 +0900 Subject: [PATCH 154/192] fix(behavior_velocity_run_out_module): initialize `accel_reason_` (#6982) fix(behavior_velocity_run_out_module): initialize accel_reason_ Signed-off-by: Ryuta Kambe --- planning/behavior_velocity_run_out_module/src/debug.cpp | 2 ++ planning/behavior_velocity_run_out_module/src/debug.hpp | 1 + 2 files changed, 3 insertions(+) diff --git a/planning/behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_run_out_module/src/debug.cpp index 23764bc73fbff..3f6935365c1a4 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_run_out_module/src/debug.cpp @@ -73,6 +73,8 @@ visualization_msgs::msg::MarkerArray createPolygonMarkerArray( RunOutDebug::RunOutDebug(rclcpp::Node & node) : node_(node) { + accel_reason_ = AccelReason::UNKNOWN; + pub_debug_values_ = node.create_publisher("~/debug/run_out/debug_values", 1); pub_accel_reason_ = node.create_publisher("~/debug/run_out/accel_reason", 1); diff --git a/planning/behavior_velocity_run_out_module/src/debug.hpp b/planning/behavior_velocity_run_out_module/src/debug.hpp index e9b269ee437f0..fbf682279e363 100644 --- a/planning/behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/behavior_velocity_run_out_module/src/debug.hpp @@ -86,6 +86,7 @@ class RunOutDebug NO_OBSTACLE = 1, PASS = 2, LOW_JERK = 3, + UNKNOWN = 4, }; struct TextWithPosition From 86804e1d99fa6106b26914b6fc969fa9b7bb3229 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Mon, 13 May 2024 10:19:53 +0300 Subject: [PATCH 155/192] feat: add autoware_remaining_distance_time_calculator and overlay (#6855) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: AhmedEbrahim Signed-off-by: M. Fatih Cırıt --- .../CMakeLists.txt | 108 +++++++ .../LICENSE | 12 + .../README.md | 35 +++ .../assets/av_timer.png | Bin 0 -> 2010 bytes .../assets/font/Quicksand/LICENSE | 93 ++++++ .../font/Quicksand/static/Quicksand-Bold.ttf | Bin 0 -> 78596 bytes .../Quicksand/static/Quicksand-Regular.ttf | Bin 0 -> 78936 bytes .../assets/path.png | Bin 0 -> 1461 bytes ...n_details_overlay_rviz_plugin-extras.cmake | 31 ++ .../include/mission_details_display.hpp | 83 ++++++ .../include/overlay_utils.hpp | 131 +++++++++ .../remaining_distance_time_display.hpp | 57 ++++ .../package.xml | 28 ++ .../plugins_description.xml | 5 + .../src/mission_details_display.cpp | 212 ++++++++++++++ .../src/overlay_utils.cpp | 267 ++++++++++++++++++ .../src/remaining_distance_time_display.cpp | 157 ++++++++++ .../launch/planning.launch.xml | 5 + launch/tier4_planning_launch/package.xml | 1 + .../CMakeLists.txt | 21 ++ .../README.md | 39 +++ ...aining_distance_time_calculator.param.yaml | 3 + ...aining_distance_time_calculator.launch.xml | 20 ++ .../package.xml | 35 +++ ...ining_distance_time_calculator.schema.json | 31 ++ ...emaining_distance_time_calculator_node.cpp | 188 ++++++++++++ ...emaining_distance_time_calculator_node.hpp | 110 ++++++++ 27 files changed, 1672 insertions(+) create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp create mode 100644 planning/autoware_remaining_distance_time_calculator/CMakeLists.txt create mode 100644 planning/autoware_remaining_distance_time_calculator/README.md create mode 100644 planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml create mode 100644 planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml create mode 100644 planning/autoware_remaining_distance_time_calculator/package.xml create mode 100644 planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json create mode 100644 planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp create mode 100644 planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..8692ea1bb152a --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -0,0 +1,108 @@ +cmake_minimum_required(VERSION 3.8) +project(autoware_mission_details_overlay_rviz_plugin) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +set( + headers_to_moc + include/mission_details_display.hpp +) + +set( + headers_to_not_moc + include/remaining_distance_time_display.hpp +) + +foreach(header "${headers_to_moc}") + qt5_wrap_cpp(display_moc_files "${header}") +endforeach() + +set( + display_source_files + src/overlay_utils.cpp + src/mission_details_display.cpp + src/remaining_distance_time_display.cpp +) + +add_library( + ${PROJECT_NAME} SHARED + ${display_moc_files} + ${headers_to_not_moc} + ${display_source_files} +) + +set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17) +target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic) + +target_include_directories( + ${PROJECT_NAME} PUBLIC + $ + $ + ${Qt5Widgets_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} +) + +target_link_libraries( + ${PROJECT_NAME} PUBLIC + rviz_ogre_vendor::OgreMain + rviz_ogre_vendor::OgreOverlay +) + +target_compile_definitions(${PROJECT_NAME} PRIVATE "${PROJECT_NAME}_BUILDING_LIBRARY") + +# prevent pluginlib from using boost +target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +pluginlib_export_plugin_description_file(rviz_common plugins_description.xml) + +ament_target_dependencies( + ${PROJECT_NAME} + PUBLIC + rviz_common + rviz_rendering + autoware_internal_msgs +) + +ament_export_include_directories(include) +ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_dependencies( + rviz_common + rviz_ogre_vendor +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +install( + DIRECTORY include/ + DESTINATION include +) + +install( + TARGETS + DESTINATION lib/${PROJECT_NAME} +) + +# Copy the assets directory to the installation directory +install( + DIRECTORY assets/ + DESTINATION share/${PROJECT_NAME}/assets +) + +add_definitions(-DQT_NO_KEYWORDS) + +ament_package( + CONFIG_EXTRAS "autoware_mission_details_overlay_rviz_plugin-extras.cmake" +) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE new file mode 100644 index 0000000000000..a2fe2d3d1c7ed --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE @@ -0,0 +1,12 @@ +Copyright (c) 2022, Team Spatzenhirn +Copyright (c) 2014, JSK Lab + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md new file mode 100644 index 0000000000000..3a4040a7065d0 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -0,0 +1,35 @@ +# autoware_mission_details_overlay_rviz_plugin + +This RViz plugin displays the remaining distance and time for the current mission. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------- | +| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time | + +## Overlay Parameters + +| Name | Type | Default Value | Description | +| -------- | ---- | ------------- | --------------------------------- | +| `Width` | int | 170 | Width of the overlay [px] | +| `Height` | int | 100 | Height of the overlay [px] | +| `Right` | int | 10 | Margin from the right border [px] | +| `Top` | int | 10 | Margin from the top border [px] | + +The mission details display is aligned with top right corner of the screen. + +## Usage + +Similar to [autoware_overlay_rviz_plugin](../autoware_overlay_rviz_plugin/README.md) + +## Credits + +Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) package. + +### Icons + +- +- diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png new file mode 100644 index 0000000000000000000000000000000000000000..f7f5db12495113f6b0afacbc182658bb519a9059 GIT binary patch literal 2010 zcmV<02POE4P)Px+lu1NERCr$PoZC+0I2eF`r)agicO#%fuC_eMlqaEm65vT-o@BaDLPlDt(1N&H zt+Y$y#Yqz!C;!2*LyOej%pp!}fBw&QqTuigBA|lqKHLlkfPq4A0C)fxNFea`y_CS^ z@?~PrD^0&-f%6>f_PqnRTs_ScsN0SiZz1YTfhzubNATd!1hDXUx;?2( z0W5X}bMFBn&@kD^0Cc9cTBKi(Zv+Aq++^E&6 zU@_2JKP^CC7z*Gn-y}D&J^JSZ=xG!k(3##O7cn751GrqRX6bkw98wTrjIYq4jz(*^ zi{)gZ0DM?I{Qyu?t>HR!U=%>}d{Fvl0_vLvm;yi};PxRLW2~mXV1O08YVe^0BLRY* z+g`QESd#owDVX(xnJ>=9rx!lp-L^phU3f7d)&M(fopu1)lPT|mOQQ)sK#X(wIzFEJ z++(-x4X_2znQ&i8BqcD>^YnyH-HcSKQT_v$NR!Jnr`>m~y;XSm_(YzmTf37+{F>*)TbXLjm+tXT3NZpNQf^5y16&J>3W#hY^1b zMNmurD2Q%3-+oYx99HTCrBWyYD3QJj%8(%rw=mM{!ZBuN!nlS?V%*@WC1>|o^Ls|>=Jk3D#Oko67g)6R3)GnW5yP;03TM* z9s4-%Yfrg-A;c_ZdC5mA1*VBrV-ldGHpdxT6r!CwYsfUjtI&{bcz zKq3+GB7BhL&O4DrUJB`uh6Ko|uf)jK*}$GcEQ=S339vE2CDjFTl&#)woM17G#Qqg&+0kpU@#7}v5)%Ocy&X&4_v=x{nVIF&(@f=X3vX58uERIr zBnq}hkpLTYKeuF0R4kB4zg4hAAvXK+g4k8M;x^UoaHeA`#_&QN2?dZ0pf%w@2$hgS zY?^ctM8+YY5Crj{A3%|3LI5^))hY;$rD!{!SnABBotQU8=WB`M+4#6q*gF4H0uXy3 zHwjD~#1M&+JGb3{dDF&xyL8x?#@FtUEjmDnhsEG?5IM)i0i?Vsn=~LA*BhYT{C=LM zzqQUTbM}PWbHE^S@Qk(K!V&BlAsQ$5!cLq{+Y`Lj#wF)P?(CeCmcX-0_DEKN2maim zn`e93K+$S4Va)c-N?lZat0`vSvF}#^YzpB zRg!chl|&|=jTSm_wy!v_qBMKVjRj~+AyTb1O`=GLL@Hv0PLh744pIcrjR~=`cc>~$ zlKL0`x&0m^5z>A{0EM=&kVMImun@aMZ6!#|M8ia&Dka~t6$9LE6y4LIqXq>k=*1P< zHpwT}1(T~6R`*DyPvnK|f$)a6Y#mZ)z|Zc5!Q(0})jWM2qF4e=2R^6W!yx`MfzjVn z^HO1M;y|;n9PkRibm9A$ATNLxL^4ONrPdr<%j3SEE3tD`8|g{ZKB{X;tk00jwo-N2 zJ~?WjEgh|ow)l8mw|{R5tXG$>7utQ5pC%dLm3wzW_sf^bujMPS*F@afxGluo^af}~ z&}CbgK^G?sAWy!>&TFlAhuOpJP3U3HDF|TyK|`h>S>&(@`tnfKe-Tay-X3kMe;7RP zFb1o-Jg?Pmr_p#7l2u_$%h zeLPHR`un!q7B&$3;r_Qzpv;XZ8bB+=A>J0}hBNr}C`FG!B+!n%+)Z^kmiB%`<6go; z*_XPTh1Pt*;FVt{UfH z64(N1oJFn%TSp_6)f+7I|34{bgSVd$I6_-KB!DSQ` z71wb<9Y+yyM+Z@HLq)~~5D^h~L`6xz-#K^b4xr=rfA9OhbgJ&Tr%s(Zb?Vf9Z(SjU z5Rvd~LJX;`tFL~!>TMxZ7O+Q#j2Yc9?bq<*LJaFKMCD^c8pcM&bk?!dBU^-6bxeqd!ke2KXC}?F6(js=gqJk~5jZB`LEIyKk<~n}bIDbkF9QFJ zF+zmi*4jR!G4#28o4~452>aN1jZ5Zh11Uo?1)jUDabD9+x4d$d5E{}9m^r_FLFbNn zAx{cX@Qo18Ve>nh<~Q4~z7+JKpm%JM-b){{{Ta7Hdc7h7SE2O~?ZP3h5rK5)_h%<6 zgdg_W!Mnj*+La$rcnXcsa+ykx8_S_7LM@)%+{w(8PA>!0Hs(x7O*d4n|0!RG|E3BSQiZ4}$PuUF0H>)m z`1h#$;6I=qfd3D*8U8=jNJ}0s9gqZ6DjHu0}c>Qb&~yADT2i&16Cp&rOR=p2AXvSY(t5yHsAnXUZh>P#4H2v5E-J@ zfCGhFWEpS}AS3TGnDceESSVV=3^7+M5RIZu%oM#vgJ=@-fUQRDX$9s?G-rWkCTJFd z@=W1l5k4ECt>D^mMv9S$JzF%xW=>7dpLcgYzBm)X-;7T@I>mhCps(nI-vZ>P1EKSQ zT>v{@0Js&`c3@{Ce6*++BgHtR-GVST?%I*_PCyNSW&v8vQa1skQ?%kb11YwFp7QNR z&PZ2H;OGW@Ga!mR41C?-Kc8v+Ig{i*4!uA%fn$?wl)76KK|*qFKgqhMYf9577C}DB zQ=^y;pVD58dy>Nq9HmC|M8b{q%U0*AB#;gYX&9zZ;rZ$Yn$JNA}j^ zwDOp3l-@#=r>Va_tW8scz0auYK4(b39`UI5wnFv-ln&WNPeB&vvk|IQWXT<{B;B5U zbzl_7r@UpHfqMqpk5aT2i_yyeRoo^1DP9n7i;u+@;ujf$);?eMlS5>KJYUY0i{&M9 zt^8CCRwLCUwC0bf6WRc6m^NN()Gp92(yq{+)Lzlv)edN1X+PTnY*DsUTW{M8Tf6N- z+vT$IXs=91lC5a_n%t?Kt50((zNE78nue49pHZFR(fA zhQK=mHw7LJJQfrelpfS8s3NE)Xmrq&pxHr-gH{DS8FV7p9^5y$K6q^K)ZjV6i-K1L zuMOT6{88|c;Nv0XA@f3(hFlu*mylaS{t@z2$ZH`VhI|?Fb7(+lTxfP^QRslsVWHzg zn?e_cUK)CR=-r_Yhdveha_IY^pNG|l-57RP*ygZj!d?&iIJ{^0)bPKC{~R$YVsgZ+ zh>nOA5m!ds5OHV3&yfLywqQj$|(K*qc=z-D0qbEeqie40bS@aFj_e4Ju{dDxs=)EyTF#}?T z#hep!S} z$6XtDOWXr-PsHtrdoS)#+;?$Z@nP|)@x9{v#gB-e5Z@R-FMetKrSaFs-;!WUh)i%N zg3es)CH+4Qm;r|pL%cVx2eCn z9Ikv|j2B(cko02vw?Qdzv+``?@J;XiMJ=NXfUg-Xl z`_Jy(?t|{H-6zrqrC*SKQTm$nb?F<@H>W?7zAOEs^smx?&ah>~WMpRa$>^6cB%>i? zM#h4SOEUhNac9P+j3+X-XS|(pAhU1g>db31Z^?Wh^NGwInY*)6vu0&&&f1rCH0#G~ zEjv6rDLX5>PxhtRf62Zh`@!rdvtP=7GyB8r&$EBX3CLNLvpHvL&PzFO=6sNIIOkZ7 zH#a!9ICoI)@Z9ma({ktLF3Me%yEgac+tH%dgBInm;jrdj7op<@s0T-<*Gc{+9d~@^|I$&Hpt2oBUsT*?V2t>-t_B zdu{HW)H|zppWc0Y*Y!TT_qn~BdoS;OQ}6qFKim6_-X9b=3+fA&7i=on-6x?>Tc6wd zd|lYTaAx7tMZrb!MO8(!ita8t=1KRodhYYQS?n%8x45aet$1@?vC5O4gLzRC0gG z){>ni|0y|I^6RO;()iM<()Q9#rB9b0DN87uQ}$HZdu893Pbq)6{H^jI%1>4VRD@N; zRiswrR1B=Bub5h~sA5IMWff~H?y1;R@mR&v6-O(bm93S}RUYme**CGTyKj%ag?%gf z4(>a&@3_9x`nLAHvG4PJclF)dPxQ;}H@e@fejWW*^t-Iz+J5i$pWc7>fP?{e42&AM zdf>i6p@U)v^%^vB(5gZE2d55h9sKd&&#H!0-C6CdzP0-Pn%J6UHJ8@>rRI~`3v2&V zmsU5w?(zEU`X%)ThBOa(V`$#c!9yE|UOn{gp?il#4;wJ-Ps1J_c3^ns@R`H!7@HSBHpwBgH!9~w@M3mBI?ZsfQ{*|bnCLW|atwJfcNR-hGWrP{NuAXkJd!IkPtcV(kh z=;JDP4RAHMrnp*M7q~7&`*4lxudW+ix4C|Hhqxo%ac-yE<<4;DxC`CI?!N9?_k8zK z_Z99t+#B8Zy6<=Y!~KZ+U+%5$r_y86Y%p@NL2j1YWX%yxZJKRSDvc?EnHt$wQI6#s;kwt#I@43)^#1{WP{s*oJ6}5-6?Lj zk&{Z!NvC@ya&njZ9^~Zj?uU_+C*0foaxw)u2|!Mwkdq`UCo_=~%&=7rW>}vhKf>Eb zs;>P6>3?1Q^s6_c>tnCPILPnM`?2>U@4MdDy}P_Sy*s=wc8&83{7vwaj00&DcwmM} za-i(My$9wTXgFZozYD(y4#0{IgdM<2fe`z@WqcF#E0PyUL_DOf&PFrYiqQ%#Et&6tF^V-wc2{^9&MA3 z@%Od+vB5m)})4sB6>`wN%YePoY-K!|1C? zO;%IXcJ-WkL7lIzM;%MWd@&ofs$LAiIJp61b$zV32qU|D#r@&|@rZav{2ODted1Gb zNPMG~t6AzI^@{3LC&dpkN=C~hnU1-AUs)yVI#`#mlcriP(l3xDIpV z%f+2yt$Idm5U-;hc}2V?J`?xJN2Eg>7hN)32FOquA>(AB%#b;(=8l_TU?(kU0o z%jHtJT;3=zQO{znV!M1wJ}aM>AE4#=NW^3Atcf2*f(#L9GDc*|1d$~Zg&QklJ!G=T zlc}Og7KEhkG1mjlF5*-wm=gTx3qP@FAm#b{YAX2^-6QH~cAM0g~v|LSU3hjN47NCAbTN$i5lvjPC4q|oa3w2a|t`4aE>PvM*eX0(N z3>h!-rAzdZX`(0A8f#>!sFo$7SZ0f}B)Mof{T#C(Z4lAJB($?0MtT8QQH z0&x*mu~y23Vwr3gcgdT?M)@~!8`iXLmDh>Qa-(=y-Xpfk&EiSu{b6_7tvVBiIss^UGs`CtO$im zB_e1A2;HJh{Dj`{1lBZv!J6i;ST+1v43K@qAXy~pu+mm4b49uADJo>1sFeAlO!g4x z%dz4-IY#_NUMBu3*N8RpB5|d>SX?DnimTM@V*Ycn`TQ#T&YOI>5E>P`i zKKkJ`>I$`5U8XKqm#PiwPBk4Xcn_(+s|VF)^)IzaJ+2!)NiP_(9b=o-bP>d zBHA)!Qv}P8u=c2G>qm~0n_3$?+n|LNBB*L|om)<>sT${&Wi?~rM~|qQ>=s|0HF~65 z>>M?+)-CQCJNhiQScS!Gx0pI^>F!jCjg76H z(leuRL6ht?W5&Gs(#?M4%+{9KGI(ZN`#foz)zLUZoB*Ox9K$|AtN4oj!|Wem{{!~l zW&aKKce1~o{ioX&&g&3c+B;^piH8=nw9OI^ELc!jBsMNsIDLV*ZNb9%3&c&!nmXFi zPmo>YuurSu64pR|F8igN3c)(ArclvKJ7(F)LrtU*binu8@`6# zDh2&6g*n;Jf=@dESjR={Nsj8cc~5kiz$m8e;jr6>2HX~a=}LgGy@X$X?IUfc^?L}T zk4|ltHVG^Af$AIl4yfIzQ;)!(qt3<8C4WUvT!0q%CG_oM!JSeF1plET9ple0#WS*KQ0;mOqR7=!FA`qjRKZ|g6Jw{y7=z~5LG3b-N7K!RxbzG#Y zpRl8ni(KilO0-70Zft5Ja^QU*= zXs?IjrNdX^63|cx?aXu!k>UrY(^DSkJ!%EBSd0l zl}d+vfu2Ol^XZ;_!7`X}sfJU!k7LyJAjVz(ISb-AWZ5S5C{Xu8+SrdmI*}q+eE|FV zLj4E+mufHkPt^PH5BgE;V~UTN;v=T`kSU-C*xTpeXmWR<#w>?L&Bw@XCPvJY&<>2m z9AGf|Nou_?szXS-xPZrWZaGVKsz|PxsE1T1Wj*}4&@JjJ`$-rRDzS)Q@SO?2h2a*} zN-$%xnI>C&XXRaC*EartRO56DPcf`A3!E?yVtx+TB0*2XQQ7Nls^nckokF*lGLeY2 z>2v-^sVZT|+@>CECLvdn>oDo`YvJHJ9LaTl^r@mJ|sN+OOd!S60fiPVI#8p{b zzd;WJTcBB*K}q)P##+QfVxz#QT3iOJ=)k_jRP1aF$L>gfk_s&Y?fX)_gWbdOL(tka z!Ag`Gs#>u7Ived?E2Qs<^_Kx^2%sLyqxvh@v&vOPs-LO@l!G;mzN!{bw(6rQRSlpl zRiG+VHK0ta-ju55nKqZ+dBN6H{>Cgm&-= z%n<%x_FZzcoUCHxCbn_y;JWWS>A_rM)ll3dX zmUHQ_R%hUricGB-a>1#Op+kp$CHQpb{Y?AL5C1*jACdO|ZTAV%BzH=>+P{ID0-4Bt z4|p@Kzvsq-=8w7~&`}`hJA~_Z-E&Cuf79I~T-s(4d8$L1_g3RX)E{zdM5a2`bs}&7 zo335wuiYkkkV9HkiuCzgj$|1Qx1DLb$!41b+^GLuhcz#kT7fiv%MFM8!@XZZM!J4Z zS8-I7!}Zmjcb7Qo{SxjQxXa+)(H+x(&ig*-B(ASvm4xnJfg}1SP^XXjJ5>prG8|g` z5$w*UtJe$IiPadw4MiVExDVitYB!52aJ=LjF=qfjM`Z(-1zZJSqPqlf z2jkj`_3{~5JAVxDg(&~?fj>|5#u~7P;s2lL@Qh!qHWKYzKe!RXqvhZ_9oGwR9SYg7 zf~0aVuA7BHJ7#orPYyc|`rpr3_m06@c$BD@IikP10QVtSeTKs-MlxKg_y{Z0=V3i& zuE=OjTMaUbm(tRUV zn@#*Rz+VIW3gA}&PqIFOIR6Ij-+<|!+#%e53w*4IVYdmh_ubeFG4a6&4@UTBB1WTj z{zcfu60`+_Ac~wE|mFtTvv)7*!>#8@o8+RA^rmB zq6W`bqHmYfek}0*tUTTmJTAM&`xV-n5VaI`NB#82-lJ-Y_Y2)&{?Zfl2&ev)`cmlJ zqsk#yHSlwxryp>StL4G~hlwQgrvup$T`h1aa1X%EfxA%TXs}Dnaw627pnVH#I{R=9 z6S?Xsgik}9sbY*)h&pmB(wc>*D@8Zw!M(rh;df7Kj3sbIaP&+x(a}BeAlRgJ118#D zaKFF}hckJa@v;n@8P|hd3XeE|d~4Wc2oNRMV=2O}0NW9l|h`G(Fzy; zdDnAV`i-BjQEFM($5K+0Htg@&r2{)D|CT{A7*D5#$}se%(`5v9#UgqCG6s8Zv3TP4 zS{Wy@k%yDmbD1gQWddq#E}mch9D9MuGDW6JmrRpxXuL_L%M6(*cE~K5ja|cB*#rA6 zJ7u2C7q7@(*hMUmeXyfgBt2Ne$`e1yVp$?fWf^v7@?{0@mi9vp?~fg>0oVh4O%B3N z%V2RrR*BbTwXBh~vJUGFy|Gd;6gzCgL?1aEyOJZZFF6Xc)G^ql9E)-*#GYA^94E)i z334K4hv&%2atd}}&%>@Eo*c){&G~W~_URh&)b$KGQ#N6jZnm5)n`H}jaOTLlvQ^H* z&SATpFE5ZCasi&pUMLq~muN9|v6f)>a~akKip7_(f>L=Q_Chbhvlkc3mDn*VldI5D zA4F^Xi@a1`hP~1?@(Ot+_KeEq)$-4H=IyIFmbYM!_*UK}-hgL0?v!`Qjo9_8M0~{VKyTBjHkL1U4pWKfT$uQXS&+-#_P=1Q1I6lKj?XdiuR@1Sr_MYgZ zHFd0xeI*v_>+0A?^jlfSjw7$Fi&3*4M=+VvGt9XZu#!Rfq~zVJaMb#S*NQ zj}=Q*6xKm5#F}s{R%+r^f=U$2Rg!Y5WU)-8;OznzucD-PU)2zIphdh0Yb*Jxmv~q- zh_A5nGahR(1z4jg#M+HV6^jX2Unmuysxt8_)@UlQcGFk&6IY0dSmPO>24Y`+u&Pqk zXp<+26{;5P;7Y9h{0U=*i?Kp9Oby3={YZ6|8l^_7G1w&>i+#dz*#Dm(&JmNbTR2Ib zgXig|h;s$nYOxi26z8d_cs^ko)|$@4n#N~p2A*iZ3cIy}kM$-s56=nEF5?BNLoLA5 z2>O~nJ@2p#&lfDmGYbCe`>U}7N&AqrBYCBGRy-$e6}O37{PzA5(aJb!ZwAj8T&@0$ zrzozmb_Ld9#pDJ&g>Vy|QMg&%f@c$M#ZwHoV^8xA>}uYnHmbYvWb3`^K0M9v0Pk=9 z1G}4>vDZoaoBzam`!TGc9aoQH*Yh##dTyb&7u1tj_t=JKGoHpC5%u{l@pr8H+=W%} zJMld2Ra1gmjV#WXwv zF&KNPuc=+?b?m6Vi8l>i6pxC3iO0m_{4B@Qc$OmoBd@ox&$?T^BksY@Qjl1Kb-$~` zmEvk~iF#L@FAj@U>OJwi+Jm<%_F~0(HP)V=!b<0d>Lc-^`dID5%FzMdS^rcW!uru+ zaVb`pZ@|v_7g+WDT6}{y8Qgf^CLL|}^>}09uXvKAQEbF0`>421tjGHGS6FTQo48xt zgq6-f>_a_)eJXt|^BAvY{;02K;+c?N)k!=7;>8ZX#O}U^{rv#!?K`wUEeJdO-S%q4 zTJeFX5r4+BDtl<(M(o#O#ec+y;(f6f{l~uF+Qq>$1Q}W;o+8M`vje$!O01`rr{!zC z@QhV~)<-MUitJU>JDL_XITp6H6xCJL>DTHq<63B3J;t?!u7yQ4wfcP(-y>d)ac{({ zsxa=WnBG%p@ToGd%&*W>=y6odYn;*1-sY%kpWWWpG&i`aqor+j*N%QYD(<2Ga88zQx|z~+tJ?0p+$9thJ1yb zzrvz=J^iAZQhOa|-(Ke**`TgAv{7T^s>YDM#?VHMt_@FNNpM{^af<4y4Fy!23Mg~b z85z~(GguatIO_C_>vC7u*oUwrAwztb)pO|a1P?hS6;GjU==8=8J*uZFWN7y|MRlGM zHEg(jm{r0kxq9a2DKrH1n0aJDi|T3^kCLf!3^N2CrVD5v*4ffJvnhlOps=K>u(+@& zWO(-k3yX?5Ur46hK9UR1KGILI#jIFRRog})E4tiP6hoq7Ly{7+jH>LTbXKGMSe59C zEh;J1xs-5O6xEd&0#vevLXc`Byh5vMn{6NMr;6GlJ*d_w)>=b=TBCSt4VJY!OOI|u zg&vPlrp2Z?80Jz_7cjcHy~D7;S|b~ECO3ns)=+p|Vc6*Ag)sGwh4We)7qT*-_BzLC ze>*8PVwZASg{WyEqZhO`E@<|v86^hi65Y5xo*MgDU14J_g%uW+8o4Mkq%JjbQDml2 zXK(OhT4rRvtSqGAltT6t8Hy@1Sd|$p$_#v^E=W;Dy=@%K(>~5m43oB8&yc6cP*a(a ziLyHTc>gjgrZOt@pq_BOsWY!-0poqTt}_y@Hw3CPb#E}Os|y={x~_}L9OM0UU0&rF zubXquZH3aiye)Ik{XQ`y3yA{H#Yg1Okrin3}5zxXIL4r z&$JAnsIJHmw9pW!P;ZcmYRc?QoKJg`Kea(sZDhN~5WmI{v&P_7qi5SwSQ^}9rE6%& z$Z55i({e|Xf3X)CEQ?AVP2HMey#?`-;mN%AJkGnPx#=;E?s`J1*>5SP*$s!IgS=13oS^^tz}aldDzzq5 zz;=H{88yXfwGAO^4GX9>Sk@XWb^AhVZ4`U4X)%UH)zk;H`&y7%BP(?#H-oCyu)DgV zu=dki5ZG?JzbTa(u}e8EwAR%j?WeWY2Imsp?meDbJDvr@aL3+ZDGaT(k&7Zj>QW;Y zX6-4hw=eLkdSyoD%gRF*oKo7JB12JS2CFhd$g)aXC$-LX14VBeb+Ltl= z;AN*&`^sW_V*x#Y7t+WC2FyBQIF!4us(Qbh>T>^^BLACW|C>_lhMIN0iEQ-czzRj@ z;3LINt$&DrT2+<)A=TCm^#Xho-e_vf3IjhqEToYYrPlafIX@Jl8NWZq25u{&gkohLU*D70qXnFMvXtU0r6##dB zi=F*BeA8+JVone}F0na}PF2te+gc2UWP2Eh^PmM+t`@j*Lx(FH9j;utaOFycD-RuTW#hz^2S2!0 z>N3-Vp)4~4Br^eq%mnH(>k!GzbR;v==`u5@%glrZ4|-);OU zF{xk1v)RdKMl%Nz213*Z&uW>y5UF9PuFI#lji_OTA4bqX0C zFP;rrLl!1ul#k55plL>X+f2@BQBiSF(}GS6P&%7TOqrum&xo#z>e8?o?XB%?^HBJm zjU7vEGuzu{+v*l}v>V|@6{xDUwYGFL8c3s{t9guo32K>re$xWPH-e4oQ_Z~zMoC8b z>jPbn(GB8S8rU>%e& z{_FGvoAd;m^aOLg#+B;;uH`}8qRwcaH$8|u4}wTGgjE~-Y6|dBxq;K`TCp)5g=_}C zDu|m;zt|;V&F$@T8>hD~Lh)EU^?^sRKC~z-)+d0tR)?Zfo8HvgzSu|X;fh>XtSbpu zy+Sl}Z^A9@_=lD7O>{Rs`G?p0-4qr1-{_J=`RmLt*rPMnGwAUb$D`-g z2=Uj0r_PT-v7Q*0tw*={LXSCzG1^^^J}m-XSHDLeKSRwGv}Z)m-vwhwXPn^oOhmZ; zo(a}r@rU;quyGF>CA7Is9c?0KUSr2x;hHyh-dsV?`(s%WlmUR~$xhmrB7XMV3fpA$ z0oLXFV?ET4r+4W@7otePkDkrMvy(Z?a+XnyoKAL#&8P2})btGTqj)Pz;vJ<>k&Rs| zJ6NBv4#IzcX;x_$0$#=N1==Nm z-_}+^vdLO6!0%vHSBj6Zk}JjKnhpMk3a9#DzhFQ7JF(MCG}pp^N*#g!4Ev8V{VMh^ zz|(TzsdmBNuU>_})u1GvUgp1t{dcfFP29f5KAp(k0`~~qgK+o2Z7|%;xUPd+3%3St z72I;TMR4=s=D^K_n+i7xZY0^91Gg>W}w8PBu}spV0)7ETtRN|-huuyPJ|_BA+M#@NfS^N$*YeJ^^S27Anz zTj3ss+XQzX+?|G7kLwL^W}a39UIDiRt^=+WZWi1$xXEzi;6}j>g(G~mkeOw0g>ZRr zS#UVpDico~XNDpi$!DB^I|la^++nx_a3ARLGu{RK2HZ~EgKx%mI6RYX^32#GWX2-~ zze426;eXl|>pg+b*hg5C-4_o8-06n) z+yxfY!-6s_2sn2N)5Tl3NDB(KAlvCs8tQ|Q210c%X{aAME)BKBfKXQq2sOrl_L&e# zYQ)`Z;?j0o&@KzwVM4yVr9E%r(zaR9V?v}ogaQ$14_MGfK({gOCP3FQbhQP+nhYF; zuCzjR$QQcIqU!|I2G>lq^q1D0X5rGNo1u(5_mohgn_%I_5Tx_y4y6speQnx6_!Sle z8#i#hEQoM9Oy|S7tx&=_IW*S7g8`axue6}mfL6dQadp6Ng`4Ff z+%(2bhOdVbZXDxA!5`|XhTk8q%vA_K&%$L{kn0RkqJ@jLpim34TM(roD2>z;CNA}u z1$|{fhfT<3NtJrQ#HD_K`0rBAQ{S+lohFpF5jwq%LJ3OU&U8P=ZqLAv%UOn2;WqaW|jBg<`B@y0!4vFmHlZF|-`eB8KK$&>Rb*(3uw9RE8#X z3mwb2k-*hkbb}e{YtfaY7Nqt_%}7m2jklmk3kp61Wb?Dm+r65M~agJeyGVU9~B_HWVchJNo>(ED_ z*aP=gvJZN-8}215^jQnqYC(@$&?biNOTIICeew-}ueG2nEok)_pcNKwi3Jgt4(8Ho z;bvLTwB$QoD>!tr1rcr>R?0Lpv#MrX}rsjGNHs@E$FxfePcmKEa;#G zeT0L4_rSfC*d2P6aW8cXeU@=s;Xj(V3I2U>cQUlzf^M*&Yc1$X3tDYKD=cV<1rcYR zA3+_=xz)nWvY=@uM7ak{vP?E{eo~FIaH9YXW!h>B>Tf}17E}l*kLd`?V#sBVK@t-a zqZ31cwT_lSifx(BTo_b{}fTj|Q_9iS(Sd=i|g63GzObeQ7 zL6a;9xP-AB*N5}P7-`YfThL$&>T5wICPcCr{0dB5LJt#4bS11xt>@G-Oo(s^DU6FZ zaX4|(qzkqnpL{lxUwoGZ{bWJknb4W^5`WYTjXz{Tmj2@RTDaW_tKxS-*Nc+&LBo4V z&+$9po+ro|No_3SwgLATLl0Td0~SP~8#(m0Zn&EmhnB{OOLSK=?lM3t8CqsRofgz) zLCqFKF{X2jbGzXtFm6mY+;9u0L$&b(<10YniT^FAmlc|0L2ibe-Qvbtq2UY##;dqr zp!F7Xg9TlS+1*ysY21~ljVMn*t1W1S1)-fZLOU#| z6|}P`MtmTkX#~Z6V?iHT&|4NX*@QU8IF9j>iHm#If;L&udJ7r_Xeh@(D{4UfEvU?b zh^~<7@-X&pi_5~j%YqUu2S?-|AP})tV9mFoj{UQqS;b;b=&zW4$>K5j|!r~iyry{OCQ}>(a zb&~XO%|4u!?tI@!-#2c@y8mjNPbQ_JvwLKoIuCvs-p7;DhByDne};SwtJpF`?PZMa zuLK+n?g*9N!;hpL0$Ht5Xe8|u0E3+aiBsH!6o+YV02ta8_>SRl+8dAwv^M~}?jJ?y zFT6K!lJ*8WN0? z@Vaz8<6&P2Jw~B&63eraWRsUOhewEmT*;wHIt|`2BMy|u9L`;iwwy7P#~hLwKIJiy z^V`L6j*%{L4rEMk=AUEul%q+UBVJ#ZIh?O0$RBZ|-0kPRf&HAvhqW<;;a!3Kyic&7 z_X%D^=>gAi7vViMDIQjr!vB_Ieao8pmSg=y=>ku?3*TyVYR$JSNv3uyQp{w%(Mg+x zr_`5m>hE)jEMsm@QZB?Y=Jr0v4dGbJIM(~DD_AhNIms&2OoG)+##d<90AHa!2!9Ui zvx4;*$*IrLE~ZennF`itFAjB)K4FKX+g_~Csa!gFjE`h|g?16e$~lDQ4x zTu7oeUf+PF6T16oan^~re8yQc(NCB zOXbx0)G?XLq1TZN*pnm6zlt&Ua@?!9^cPVs#3J6wTg0W=%vL&zbRsTh8Sc~8GY!>H zt`T^Xh|OMIWg?j7D}B77fCtBg4~ zm|Gu)8`%aN%%KlcRxn(_@Ou=hozJP<&G@?+U(EJ4OM3;Ji@BW{VBo2p$!41mVfl+W zcX13Caqfy4?#rnc8$Pv5{aHVC+@cO(4Gc0kP=1>@zaEx>&-s$YoMJ8Kx0ZH@Wi9O@ z%f+;FENhvv7T=+;tR7E#s1EWJwOGmnjwIQ%O6!vXVLUr=4BE z)Fwo;B~&t>O1!;E=hu-fRdTF+rq5^H7H}*Z)92er{(O!#)rP%GIhAFmH*kUHxRW@= zNu0+?%x4nIJcap8;<#6FtVvAIEwfz4a3u4IBpC0AQJarZ82KD}kl}+2FSiW@ez|Q5 z{LQTM<*d)UnR5qIb};2|+eoIt&Z=C_mav>pNXA+|K;pVwzayc01EtO>&B>`B{ytNmpV8*PY3vC2=*Sf>6{Q@rzHyir?^^d1s^_3Qzmg-50^zc!-6fO$wn69VV)kgkSw+h z!M5SyR6J}I9vx%DzP-${-41`9Ef2nna-kA5)IRYe*B1}V<6(K4SkL#fZD7_yX>sZU zx$FkA1_pAum#_{mprhI6sdRzfi6dLhYxcXd(X=rQS;l{jc85i-%&yAttK$0D5jw?wP}v{L*@T!?eY zwuy`QOJ0xDm%L;&-d~@F_uKI$FT8cW5SGzQU-H5m;P{dk-r&ZUyySCu3pq~yf_IM7 z58_ZZwm za1X$3gu4yyCOFuZg#F6P;8wz+4P$&Ka@mGcD}p>I-hps-2w zv=TjCRsqfj$r7sW6~Ca$JNwTl1)2vK9?kxv>|enC+w5<{`QmsQNaxA^R`O*C zr+5itu3-Od_Ag*xaBn@Cd~uTf>)HR1{ZHAyll^zte~SGr>_5u>7#i(VA0{bt+_kT|61b<`BjkksIO*Wyzr$KfVoJG&NguWEA0%u83-Sqpz z$x7Cr_YLpo-fz9%c&RM9{dwsO48eHJIdP387^g4^oNdZ~-e5^W#~tg#CzlVhX#6zhpEC;Y9@|e=zc?lzre|I2QhGo0anNZDZpbr- z7+UNuk$0c>J!s_}GcE5Slw|G4WRE~O~<_-nfy=#zW2VY z^D%K0k0{}+7LD`xBX}J5wJym0NowbOX%YvHYuT$GPi}(|pRLOKDbrf~bvin$%KSqO z|Js7P*+6%DFlqd+XQt@Z#-jd0mTs2i&*6Ur(~SH~e>6AxKl&r9B|YK~V-D-DKSn|x z{#hsnG?W01JJ6q?Opc=FuwKd6ZPGuVMq9#mqK9^8cKY3!>d@&_I_6Z4r^O98Jtk`N z5mQ1)Z}d%PpySdqDa~-R6j7c&tx=g}00F zzuEsD()DG=#nmS<+mt%@r%Tp0@*lUhrS3KjWg7WaN=m#&Z7AMDbtsfaGDanr$eWS9>qH% z-{3cZznL&l;(JPB627REBqn37m5lGtq~px6bLqq|oIO>A^T8JKSkAS0&BbShF_Ptc^8mW6j#2B^Pu)1iv8GR0wM) z2zt367}859>m`i!62N*1V7&yeUIJJz0j!q*)=L2N@-fP6AAS+g&Zj83L(q|fb>v_j zMX`<~bQC25F$;~x9E&uiSVwd!eI-sJ>nMjhr^)}{=yD=+u%6Fik-nyqJCeGWTAMw2frY;&;Yj30JhKow$K2!&;Yj30JhKoSZJLH!1-nM zuyiVea4v%gw$@0t)+nPq$XcU~Qh5M28^dK2%ViVCWn<^Ev2)qjxoqrQHg+x>JC}`} z%O;-7CV|T)k;^8K%O;S^CdnupDitS}N($R=2$v0gzoQbT2vXU&xNL&iiqp7+++0HG zTtXRKLLuEsh)N}sOC^g-C7Vknhf76qspN90^x#tI$))1pQpsbx4&w4iMp-PUK2%iV zt8ClxjkYz~3T=rtN-M!hQcE-&&boRP=W5-DlfF9DRBby>GV6g(WaX6Q698UD};MBifGDF6)3&x3m_;wfl@U<-RC0Z+LL+%y# zp*)@uAM=@l^wqRRKL73!oME?H?uEQ`b{n7DW}Mnar=uCCp{eO=2A_jAk54}9#F_5? z=bF(OWjIX?r-jj3VLNEeS;eCdv!VR3n&CZ8t14=CU zS=c6E6|kTAI8kh@nJ^F3JeJGgcz~&}HwdZmmKmiD$s9;~E2NFb>F7z6LluvJ6z>6? zcf3cPgPcg5&?!)>C|5(^E`hrrXMx7!EKbT}GShAa?E&U<6sOW63lyKYA=GJbH1tAu zps*92dJ67oxM$&Zz`cwRXWHflHznvTvTjkdPZqX zMuLnlD~&42l(E3(${c%Kk4*VUW@gu@%yNfKZcw&>u3-W4R)?*t5$lkD%gj7^WoD+j z(0=lMoEfSn1f0Ayz^*0&hOGxfqJ`>ttdF{csM75A%#57UlJc0cvII|jLQH&IEMamr ztvo$Jj@;u&jY@WEKL@7AM5j592V}-Yrv|>azFdaKsI)FyOq?q|C|FI1#bZG+Cm#z7 zNp{D_$RD~^FIYhDn{ry(CH5RxyATd7T+lqt#9wLQqj8Sq6DHo)-@xZ;j5p%x;q%l& z&5W0;ImMgIw|o4-r^OEwYyJ2yIxRdNr>AyU>7O1y7N9m|EsiRn2=Nx-t5(lr9D%j=Kr& z!i$DvRSZrJDElOpY}yrX`%$-PJX;YO*}Gp%aA;6ak^|rFF6~;D1@nHrq`YT&RzhH2 zsEV|cr6(nYg{TJI($@zD1;+=3Fv6^a2g60#gntH<-N|r1K&7IJ^zi1=TUX`G&Dt1IANNzN8$|drd z&T7w0FOSRBOCU27povBKl_sRWcrZGy>&fV(m`sJQmfjSS8Yv5$nVHV6UxI_)BVbQ( zunb_#i_XlXuD$r6olLiPxe`;7V&l}Xh>&z=Qd-a}F?5Oe(3zQ#`E ztmg%%%~BgX0>(5OGCMJLDMGpE){$B6ajCf2aFt07VN^+3aRP~p0}xP3nh(s8tEWvZ zm|Sg38#AIPzkW>i&m`TEN5VoMO)bbzek>^X>4LH>?72;z)MrR;@2LE<`d5!Dh{|-T zYG>x6$bSXpWaZ~}eHHk2a8Xh39<)Q*1AX3Poa@~Svc$*3ZgX>B7U2-arI37iS$smg z-2uTe3KZEql&MOcK`~)H;}T0#%f|Ol%N#haD7h>tu4i~`NRqR>B6aAWn);SDt{&BE zoVq!zA|cuq91@x_XhO+=$^BDL6TR?53p3W4DUnrmVt+=%ALTN=& ze^|w3gucowqZm&a%BKK@Rvwir7Z06(R&M>JjbBrdd^%`Mc3iL8KAVH>YFk<3#X}o! zpQ@L_$;Yea4(c<$DkrEb9-kuhQW^n;+DcmvEJ9!u_zg~7zI*Pb^o4euNVy=!y<8qVQ zX2^;ef!b-||E7+Zc>tdCpbl#g4pxSo;1uO;nE8tavkv}d&4l@{k)yfV9S#aSLcnJM zfii(H55rg6sKQ0P5J;E6ok4oNBNI3Dsbbj%`mkog#V4kWz*E1i8tx<|2Y=YcQTG^I!V?LU~W zfBaZmxD{^355qk0a--y9ZMUBm9*-~O-eQIKI4wLDCn4N{@B%6e?r-({CWwiC`l0?- z$A{qDVxK;#Zs_<>@tmO_8J zjG*sOdyM|zDm>3qK{~RU{DgRONKU;24{k8JDJyrBCh*9;te84kec&UnAGvyFW#!D( zBl}Fsj)-t41x5uXRivTS8#K4dH8de8s-1+`=*)--EtnTvF=N$;5vyiY#Ks0DhbQLP zY$2gl^Qx=bszQTZe~-v;Ix{kzyJMY!De2G$wbNH|9Uj7UCR%J}8`AMqr*wRjc$RJG zRD7g((P;1c;!N_FEcz4~>PJtuuJZ|%F@AWmMI9f9RR^;-r>AeiFwUYG6O<6eQy1#P z$)tRDGCeN+s>JM^q?C*-`Cdv!W-4yFrpTwe@W@D}^W@W{6l%l#;jRxCU^GYbvXe$C zJ?U!>4JdPr5e%En?v~E!sZNPcO^sLW2`MQFCy$<40(m4gJ`Uk=DR22F?+=qGWRc!F ztdLM|G>S_g4QG*?^>Q`0YC1j=HI91L5$Iw3>7Dq#yJ5jtBPGp=#g@j%h<31sQWCQV z_!NTi_Xw1{VETOIzgvtL%oJH4m^#LjS<*a}$KBAreV56vrgC~(Xl_hIYG`b35(cw` zAKWVYQ8KcY^}e_uKRPNYBRVuX0z+82k&s>I4rm^1}YDykc{%duIRxzDJfaOk-Z1RgoZ@MM$kmaoB|EXQ0H+WZKO$0PEvGqL^E9ZHZ2Ahv{;Cm-!(rC%`>a2RFM13~p>+rnr#I)$H z^8)19gswSgJ5o~8u@+N!Uf1@R_>@fbTyAV!bXWT|@~niDgZvv1F7>_&X`*aqvy3U? zd0h3;81)`8LNrn8cC7H|vkpo+SH8w}|D-cB3)L`wAx2s07Uxf+D3_>>wg?^vwh(8m zieaaY@Mx)mSu2D`9VxM}>Kn+x)asD=DOyZZ5bop)b9tOIYo{ME>?fgJ$QscC3Y!`}&eA!_xx4_xv2= zO3cYfNy*H8H7GeeEIH^IryH_ltEVDDyRKBSGdUyq*^ z?sCYBqVO=TJMrWb&di`d`F&(pR-)UTsD?N*LqfWoq4JGHw_XazZQHn17g6cJl0LRd zdmUR6<1uupuS5lA=Xm3=1NRUawf(G80v^mPfEn< z0ISL6>Q#{WqD)UnOK~_{J>u0YKdt!b?Bs#+Aw8mOx?KIW``MaFUb1HBiLKeJOU>Qn zc4Kty%je~$UbI+oCFKV-xB~k!+pycJuV$4|eo7N$g3rpV0_LpoBG!*7S?Nh}DdG06 ziz0P9jz|iYYof`}OU~Yrl9-q-Wq4ZBFqoX|8o_pkAx&s_S9+k_PPZrjIe5re6s6*p z@^y?fW2nwm(b|VK-gGHPNwugPzkk(*L7)4olniJ~yXpHM7oL;7Ys%=z#BoxO#jR#Ik1zE6B#1lw@Go23_9n8lCrkT(we zXq3VF;W;YB%hf`S{80G6IUM=r@wLvE^J~V_$QpHg820$B^mxpnxgCZ`s(j*GG}OuuB6Lhy3pXx5T(ZRZd`BaBN!W$-Ry^HRX2&O-qf7 zj!^dm2c_V8axxZvFZw+RS@)2T+msEkL26SneP!lnI!p<90{TCHA?X zNcmNC)}V2H2DRYJ@;n|ahD>oHgV(xgu!;54avF0QLr#4W6|Ft3a?93|DHRn{O11>k zNG8*HFeWQ8F)LFmqW_S6CAXnPfH|aWikJyYN@y5vU(1#OBp!4FwYf}kerC|;p>y1 zugokhEKX0(4v$I>{aw>d$xKM->5fiFO$ZCiiO&r?D}HEtoHH&uBrHxY`#mG3S@lWv z7nDx{?GgE{B(aVhJl#D#sfWokgc+CtW)K(=7?3C^U|iFpt_ekdy8c{O*~L{+46HfJnsHZ# z(HSHz21J?H|L>`~@4nYP4eR>z^XJ3de)rtEbx)l-byA(GS{QaKuJ+DIC?7UCx_u6l z$!IN1_jzIgoAT3ehFzE%N>@gb^E^RTH zLV=o|MqC0+Sm@BJ6LAVrIg=T?4RdylA2 z&y9M|Ma{RyRA`={{GHF}j`Md8;}k@SxruLCuo6mpi`zy5?$*6Ti_x`~kK%N@W_gNm zi1Kz=S^|FQiu%K?aBk^Sd5X8Ayo#5wg#Uo-o*(J9@*YE&Ky;ZFOX7XT=e}x6hh)k_ zcj|@s@`?E{-j6g#h9I%r=)zxS&sva~D;73~%*uQ^U6I=-GO4kAc6cte5UC7xXJ-eJ zQZ5$FN~NVM=4a1OO+?F~L~lG?4aY|M5>pphefg-A@GB*=CDiVU`4X9s)7d`R-8)|i z>PKCE8)I_ETvz=zl2dHY%$2*l{mxKNz-uy@UGbQl3R`|y0BV`(g%8Qa>~ zb#~cT_4@Vl@J(Bx1!@EPZ?u-TUbPs?<*vz3bYi>Hy`xim2gAX%%kAm&^%NS$Ib=1W z)_kp=StnB@1fhpscpZ9jwzZ%p8;oXe$^D79?Xz@+*qA+yU()(yIGmt=;3>5xLqYlz z#&KCPA`gssfx|gZ;U0bM(Oo6rm^a+crGkK4bbqJ92V3Fr9&b|N!>w?5kN={=FI@o- zt9EQ0^JcB}C+Wm$?rr^9x*9%yf@?wY6G>4tV=iDEE>X#w9t|hwuRrUo8|Jf7C0Cv= zmKQtX(&wOx@7#9t!otnlm{3f2_N*@!*Z0sJwRi(EYOdz;@vFSWPRtfH;pE{6xEE_u z$-@!lX#@+nr{OR1dYW)IPR6Aq{Vr?%%X}ujcwh&?`u5gthk1 zYvluC-d6OJK~doacwn#O{Y!Li%xMv4jdSTGBCY8cWG*#Gp$e-N`6-_k_Wk8nzm@Y| zG%0v5Er*kVuJ%+_UOAQ3KG~HtA7E=TBr$7Y&z6W>DXf~$;@tHOt(89b$<5X`xx$Y% zvKpM*%%T@KocFR9HZSAj{0{7n6B6UfZ=zHd=vaM2@A^!>0SQ9M_^c)6amUTi>ZOt| z@A-M=>mKR;RLJ2xeZSwwd|qkR=rG0-h0~{z3`m(`Zf;F~p65kymjgAMC?$<&%kWQd z&5mp}1ndSBJC*fYYcIa5oF_Q7hmyItARu+FHsJy#?IC5bcE5RYm`t4|-ZaQP|N_qUD9!K&}V* zf5Kd0B&IRvLiu`%$tabSl;i8Op9s{?jrrN9>_vafUte$(9CFh2&FO#jOP|a7eV+QW z=R6jZ!l(bu9f&5w(t5W)oH;$3@*`2tci?wXl93*0g?0EgWHe5{{rXl8)A&H86b~6y#sw z6#O+>40(ZkY~nNlCkhI<8yOEI_XM0MNN}UxwyRm1Y!Fe}uKTp8W%(u41`Qt8-H+Lc zMlD2dQQkpON)1j@PrzlI?n}}|e3hhu_-bHNvvi{tquxJDbVENOgPG5Ai2h=&LF&F5 zQz*I*%_?Q(va|jQJKIdesjm;`o$O{y{rhx>P;JELtNRTJ1p9Nc&&QrLsydd}&nfn_ zO0nN_+y$H{Cg2|3%`I@Ejey&A4+=Om0`Sz}VSOVj$Af0f5TSDxNx!E=~xd(a;CDevuk6evazdkV+GU~82uTTqNRwkozOjkwNVZD zcT~7hdh}fC6<%8Z1{Io@9z9~@?>wcuia*_t)-~QKNY6m8fsaFQv z@6c-gVDsrgKgIlXAK-Z$;=9*3pJL+GBs~UA@cPEP(r?tKCh3&QaiVQa_(@gL5`4Y> zuvXhiOb4Ll>>@tLQe381G~Q~o!h|@akkbN}n^wL32y76_@DxwCG@oAk2(^QaLAy1c z9#fwdQ0LWHcStQ+;`yZlHMsP+_RXi7JuQ7ggFe1f@NWTUxTlb7iP^71tJssvNt*p!o10aAtj&kE z#N(Djh2T+QB z!2vM!lQ$yVDYA-dB1Q=!ahsWEv7#2-rkbfJ12qISnLD>>s`#>OPaxBkcKgD8a}sY#|<-!S55csn`>v;;OWn0Gl*Gu ztD`wfzjJh(lyYUqs@IzKFDK{=ia@?Fmyj=P2d$aVO<@dfgtTc$ zLLPxETR7kgA?6GIicO@>Fg#iHDrzw6#gp1g?;nJXc zSm)4=&YO_r9yucU*Tr@MvhPW&i+2?mha9Y=9mmZlJD0{x_u-Yid+)M6V7^=y|%YOJcdXm(8}X z+g`3Mb(tsS%1l*>haxWb@VVWOQMbHPB(8$14D(B=MHbw^Eur@dxR>o38n_;(0t@J6~ z#f|aOQkura2TMQxrVA?A}#I(i9yrw?GQJXhZUXkRgbmsVym9aL{3SJIG!OOArQ$kBx^B!x^ z?#Y*fEAm}w9AgJpjY^MAt{QjnaGF|?j0FW#S~Sr@LCh641xzXC*?E0q+(}p*b7Q>z zCRv}=On_{)VFH{7z4-D?du~=0HU?g_lk4=_V!`1yS`t3e=_LE%owARkhk}@ABR^Hu ziQFA&c&mN1ijACQ)$wB6$+n>NGkEax7rh zdtIabyIKs(%Y+Lhbd%t3!ky&NFqc!0s%xx@$UYh45=p>M(d-H5_?7UJl&#W$>u0oj zo~Auf8gQpzn%m&uRUo>Ot+EQ#Vi;*R#C~8=^!l zcM0k-Lci#r%aZIElv3jtO)Tqpm+4ad$z*>@+(|q@`$xT}kPg84e?oi}xZwL3-G5rX zk0pTP)be)1Mui)tKa!kSew0eKHE+~(^kx8G3T2AC)XYs7c1n)foee`{VA=-lzBuSeH z=qa9+O1}Q{EzpzqQ`y^4ua(PXDr=IST)vk2hxXsXuG7R9qK=2})}Z>YsL;FwD3^wL z-9G`xHCjs0<^8(*wf5&FYQIr>#!2=4lv9BuxA@8<-vSiW(IG>YD_PQ-4ywSYK@P-1D&}11ae@1ihXJM ze7u$gt0oP4{7y{u$t%ofJq10)$cFGZ1fOqUDt?4I%pZ&STazxF>1ZOEiN-0r0u$io z68jJ8$ohrRgx4KbTJkLP1v%=A1^5M+ej1qebNMP-`PiEX|Hqd{b>HBv+=F%*rQ=}~ zf^4T8FlEq!gPRHko5ZnSGHkQftTl$i!Qs z_7fw-TlgmPaDEZclL!WhELjgmr~_HZDV;VW4QYz8$w;UoQ?`caW1&#v({8tm0hwl5 zB^|6k*!C-5G3@>HzJK+#Bc{d2Az9IqlJ^D!^~YZG3*YJA`2T(TzxzYs6!q_h`u8P# z54fGpdvuTPt;>5gJZSv<4e$`7tbV}@;Q@|BXZfM!OR>vn z^V`p1qF%z@1Ul?)d;)uQBpZ3WT5!b#GYJHt(1SW0W1(Q;$3~km6!bWMY_z|xL3JeW zI^(VjBz?~544N*`OCngx84DjEjiTQJ-HgAm1(X6t2NZK75frtr)-0>oz#KAXlYZlyo>0y>DT&`5#<%c@3#=GjkJqqh!oN0)Y|`OX8m4D2o_P51<=^VXUSW_N%YAx@_`rD zU$=4Nb?e3Tn)Y?2(zX6_pk9KP|j+TC~u_A|}=+l~iyukhA#`EjcDEbb~LtfyP7(IuF zJko3-*eB+OAkhwb{w@A|KWI!Nk?JH% z70(;*Q4C&%KcZ#|a4K_qOq72@2eVHtzh1&@ms%)S?;rPx8-9u_$ z?w6YHHJ?ADyRW6*1|H4lkKlZF?YkO2&F4?(-qw81Z79OG@f_o6zVY^g^o)k}ue2B> zaUMkl1f`#9;V`ls1@!TKS{*zpKu|;l_HjOfwb_UYEbyp6>r)io zW80d&^-~p^mjLD5cuMz$2G{F9y6Wk}xy{rX4z zrFnuu%o8+cOexj?YX%9L+Jw34M*MB&3F^;4_wpst=MXkgTgi2whCk-mp} zJ!@h_5r*Ct8ofx29$w8~7o%4Yqkku%@LWp_ga=C|Fsr<2MTnkTSL{6;qgKC0wH_#1 zltwfjvtIalgYarhwoIib6mL)aeF?uem+)cTm{6YQ&IEHIds<1woStld_6d;#1`Urd z5Z}I6<=a|;{lr?;3_&iLph|O$9rS(@xJ8f z-p-M$w>c|rtKJh!GE*olhrMQtoEfh4%;jCFh^yqW>+Nt?m5>tgn9Xu_sM5QTYo~Sz zT#1q&QYra9PDu{ezgvYDpmPAnXg{vINB14=J)$(d2TJqxkK(OQs?a<^`8zl3PV#pS z6J4}-et%gLgJw-9hd2~{)+|f*?8V%k75I`pEATz8S|maAT5I`dR=^wO$ribpx0AmI z2@{7Ua}7?xnW3y$kr%FdHjp%?0_Hq~Tt-k#?MQV#2_2^f321jAa5MaNu64u?0pRja zgwv_<-L={My{X=)zPz=6;M}pnS-0q0Ytoa*xl_ZrknD1V3i4n_s6FmZAEiNdZrJ5Q z7AX7lz^?IRbyHVnpx`h#2X~E69UM%_qNA-2tlRDw&05SMpFd)9#PY#x#+|6f>NChE zzdnUEn#oXztWC_kvX@A&fv;SEf5_F1*w_UgG7mR^IeUZ}!pMYZg{L_G1O;sAax0b% z_-uB+!>NpA0=?CEMsg&BN`n5~fI!TQ6RZ|iqFGa9u$z4;oIyXUUqm1M3+IhLS-z`6 z@6(T}P|S4cj_WoO9CMbyPb>X0_H`{^e9l0lmgc0bhyq2phfBf%^;ynyCv-m&Qi^|xY*B*42H)B&P2)g7PaR$h zdXkTs0bT=1E>ZSLK9m-_^5%B+pu1>10ypGFaf|Hd9c#D-v-*3LxeBQ89MZFC?n$H_nDu1rw(|q2rQpNjZ ztF(T4E|cx`AF(&9;(_C)x@q@5>+Q zzJRvIv5Lko1+k|W?Eu2_K*a*8Zqz-g2U_(?4vp32kM z6Yz)CY;RGXxLd#?dfe3;Cy6qUKszr&wGiV!=j}2~FOJwA0Owyn?jT zdmOotzuqR8kQ7W|d7$M} zyY8l)Y{{x7j)ihYERPfyi8?4W@FT1e2s)Zvb0RefI!+7Y3pj2`0LAQtkbmR|TA?MsV0@{ms%uA5r?ax;iNa3ktYu@Mj1P`+=esH2ZGT&GM{2 z%s#_ng%7Q0nIZ73vCM|RCayI3C5h9Ii~Leb@X?EjEiMkg4`2t>G>nMHSc+ZGNND<_nxQ0#3X`aOhwy zN|dJzR}RffkG6{p*NX=J#HToZxoDa{*ig`V6^y(_SwtQ9JY$Q;aCl3ue~WUl#6 zvjwg1Qr1fAyN}?kw?=NO$XZdK?i5kEuojgQSu5((Z6a%>%42d#&O>Cc&{M?Zd>XD? zW(w%Tw9gP)(8x|9C`HvkK3`#(sYW6N4xdQrlui)>3 zRObABU?qQR8Lb$p4QbfeSd`fPf8zIsns3qa4c7meNOSGz?o7IBQ}NoisyYxNv$=Xbzd6;2i|sDFXQg-D6sxkkk|JJO;kS4*$zN5++5U+afrj zU;$c2Xc#RHhZwgIAy756)TBU;NV5#7cvTI7%B1W`+mo1NPmUd)o<2M#uGdU-cTdp2 z>zu(h@7CA9bMtHV&0bgw$)U8{HJIt&)>YVf_3%EkY?ZO^soBi7j-Aurf6mw#ZKg5Z zJu=eWH8S!In`g1@{B6SrM$!W@egq$^@rJ_yu8}kyJ1(Fw? zPixShY0y*iYe7$L)S&uat?bhu(V(=Bg4av_^;>WvS>t=}(@H;H;82(jhxiQP5RDD& zjDIg58_3l$Bs6$Iz%gGkuRp@a&~g3cqTKRmoAiR^5aFhBG|yrf6z>_%((13C@t%pD zNA+`TNA;Upp3f6rkdVjOXGDF{t)f2Z-HrOBBWILH>#01|hk<#G_8i~g^BOJmr90nNp^eZ zQfFm-d187j;tB=bzxB$BCshg!mo``1OFiAG!Vvk<410BAT`6((i*hvEQd-|pT_}|n zsvYY~=VcP{bUL2MNV)2Kd;5H~W1(DL=tz~zsYH7_Yy>~rO6M%YI~VZ>zU!(m4M=Nd z(v657_9PcKuL(rju)HW5V4tL`yDb_3`vQG?q?}mD2d46yN_J*{(bx2f60-%_g&L}$MJUoq#l2dx;@ zp3wMoV&;N@soL$f%XlCo6!JY<+@9ze^Ckmsb4vCkJ)wM{|G;$Z_K`PQ2n)zS_PF$K zw9@_93eiN7J7LFRAB3hsM=qYJz=c*rtiiYjhaR;A9G=cZqLxkc#^hMUtAuQ}k4OH% zO}(B(!fE|P#8z;O?CPApW+}H2mR+gW8!ZlhVyKw!37aiR*(p2jQ-uBJ2wCq>x0%Nd z3@*N8*z2;#910vKMkj6|9?W;lJOIt*QB12=NeQQu(o9~3{VcxN#?I%&+7KwX*r++| z#%2-dj~}%?#REO*knCl*+8k=9Fx@0{xdGIGguonzXxNH%|0-4Tyu)GN5)-GeD_%3M z_TRbf5r+%yN9LiwYc8J|N+mk-zEsjIB@EaHKgAKM+aeBQu`e`pWNh|2t0LPnZcp52 zb!Wy)`GL4U5G%TW8;B4wEZ@vqy$&da4M)c?QhR`*5$o&tek$tTo_g*vQqMT`0u>S3 zJA>(C1G~mjuKeubjdq)oiv`m&L+#jftbL?d*ff!!I6Rf?jmLYF{A#UkKEE%$|H#3m zfIgU%QzmO+aK4>+3bE|Oj;_fgt7$2kEDsonrF92`N86hz;L?j zWT+CwlKonHsdk`C-6MUPU7&adCeuUb4dMTenGRRfnj0<*?i(1`H&`A{zbaA+g-VfP ze}8?)NC^qCk&aktgk+HDov&jxAIvYY(=@uIF^({2*J5j(k<}Sl)jJ)#Cc!1xcxU>+ zz{HVB^h&fh&HG0BdUf-G{`C2mUUXJKA4(`mlXL2v8gmz8Lx<-kj!ayZs-<(axagpU z{R7zujT_*)>Ht<*Q?3yr#Ox4uW8!ijy{1_)U?y5!p!q{z>R7Cl7Q4FFw^!D8#8XMg z{gkzD_dsoTU*GQ9!0x_1qt)st{Ue!zZ#>P8Hl$=fq@*ALMhz)449^FAVN<)wW0vL6 zexFs2hQj{Gg3&f($`x|f%u%KO-~KRaLZ${zg2A2uLf*pn(xhXf&Za1WT%y`BBKP~l zR?CJ+!SAsvW|P}2E2Ys$$52?#24;*e^(u-t?8DyW>%x5@Ka!x#Z6UXkmve)0rCRb2 zTNRH7Ow4qnpw0;P?rKN_p@)U}CMdI7K=SXekdObI=yJ-6w+)7Fz$51pK~K=X#h>m)Y00WKg^wIqa9Mo9&W5*&8bj z#|S%68D|XNKpwIx3v0bS0l%tYxquS1W>#Ogbi3he?d?y=i8kX0ZDBJfI5T_RrWA`& z+3Yoa!D#}~Pk`vCxoi1ZHqS1n7z&qyXSSQVlYc=aI1UeK(FyMfbbA!9--NATkXM+A zMLi*}HR_Z+davUHK1K2Uea4Y>_oQOIsg6w+yTcptcnn5^H4^m3E!LFd%~q%E_68%j z2g2b{f4OfAMhWri?{GrWb=U<9Ef>7Xr7k+WkT(WQLiDfVTdW_=hOpgHM=?|_jt_cg z%l$LO>4HBFGbt9ccW*BDo;4f~DgKDr)HyOgG(J%+PvsVq!9XGr2quXd)#YW@&n`tQ zOUShWESOgHp=iActoUYk#Gt>%{w|*^``#1AktdfKgIM!zvYS|25esqsDQu2odd7iD z^pFz2V@o)RIgS-s1C6#IaAI09{!9hUbkT;P(mEsy(}i%}V+fV9W4YXDwll!8rNUI+ z6ApX)!Jwa7ASaXdWIyb{klAG}CX;lWLo$;yJ6*joz<(QXdi;KmGw|V9z#qbC2(dNj zjNVt|fqtYLh*r}O#wc@2t@7d3MBw%@jlk6@BD<0HEC#LZVRdVa29O#4))2c& z_eqpN>~VPrkgnxU6Xd z;>#7h^)G0uLWiPuBYf$)g~GQ}|@14=+%2Auzhw}`!OK$#+YEpYxbAcXU4c|F$x=RW`fI1A z2}6{~NcW?L3^c+be7^;(?G`0Irq=O0soqitzOh8li%dMnh}RFUs^QhVh9W!Fs6oG; zm&h&uk!|GPxLYmpoQlQo^hsW#fHSqWP&=*=-}oNN(P{yv`#e@!fJVpE$vu)!qz|u- zB@!_QU05RKp})A$JJIE1*n#5;^7@WJa;oaA;eZHvgi3z8R!XsX?L1;gkU8M|i+`3>;p?Vx1Z%-iCK5=BGXHzX@ zVv>}jxs#_`nhz{v%kAt0<{CJbhtS^Us%aR6u*iTKNC5K{HZ~d{ES5k)<^KkC*ahiu zai)+O&P02B?hcvI+&?&bbWJpoBn~W7{jFGDGX26>GVC(*r0x^!*jgj-Vy*R0wzdoj z-ns|bD0@PEXNCR!vHVoNFp2*Qg~e_sO(+9#G@E=BYy z+TR6sC_*-LR26w1uzOVrT2fZg!_IrzWf>7V=c$B z1^af8|Me`}%PvEH4c95?0p3nyh9Ca%F&e4QVsK*zPNd_IrWECY!KILd^!{_~2gsam zzOTki`1>qR6+EZq^YHTe*%vG?y?sS_{yknlzK7VZxTp7Ve^kBa_&4#v{L34#77zIF zp5t?rBtOp&L?Qw9JYDaK`2G0frxkTQEP?jl$=@&X`xM&qR{lNp9^a$;qwq>7hhUNI zg#3q3wvM)h1kVnr!5J}Qf&qxnv8>C!@$kR^;xMjYI54y^m)STHh<(!Bd;49xcHMP* zuQ}^hJk`r@oSC`#^0F)BO`~oX>Yf*M3$9bM?)bpKjsQHH%VeBFg~JT`UFa!?^ZfIKw> z>uyZ_Pzom6E0MQokHKVEza=3l#jwE_iTI46f+Bf}^R;Ny=PDK*(r{1Du;eHf)4^{r zSO3P&3-etH3;X?HN$JX6m>KKJ+S+1%xW>*@HF@#yl-uB*8ooGDNx2;{55)ppu+VQu z`$rpnM~m1B2nhr*dN{g*5}XtqF_l*{9AT#ffrnjOeXjO`LmKJs9ue4h8i==tnuxpG z=W7Pj*HaE>0QhtyE*_b5W9x(Ai<9NFi|}F2ftDt)U}s)5fzi3fOUu*jR$!`njFe^2 zKm|vPsXuQfUVD%(f8S<*7yZ3I63~a~2YjW|U3U6Qed9-M)bFTmN;vdf+f$`{<6qut zrkqio^w~(@`CqH`N#7IofrsPE*Mmo&#HhapmM!I|U611ix_ldZJq&Fa+~3~s*YZDp-5Vm+>D0ZY4H$WC-Y za(s>b93I2#bU%S4G)k{~p4uD-{5XfdUiS=#zurcD?1Q9y8rc;HJHcu!pi7~wIir}c z=MZn&XM(O{7R$BHpeN%v|B$gQ*Aw`l)9JE*z#maO-dDNqFnP_P=*qfaDbnbK#^)os zhP|1&rdhwLE+lpYKIm{!Wl@<|hSQ#Kx(qC@1bY*sy@hRr+cwU~ygI@U2#Vi5ZJjZM zk!J1jr2cXK+rocKuj@*Lzn^OV0sm8?mZCo0zw!E3)P@=oQ5kO~lKRG5#3Q;}*w>`8 zO2;KmM`$Y0@fKLE1SdKY{Pi}1yRZ-A<5E9(?{&}93b8ou|IF`SZ`+I3_?G|7PJxHg zl=G}=fF2n(uWC*RQWx?_aWkH2c5GKlVV}ik^!eK6oJ(6>VP`lH_JdTJym{8SBSO&* zCeaB^ZGmK1HdMpx)(uONzAfqr#2CxA*I&6b#}3D2IU1E^inSD%&(*&hb3og42Qdo- z0~T{FYHkwbE$E9KsD%v#`>nY>0tA{k*b&MF@)v`kdFlc&i&M&BD+Snud36US=}oEO zxDjEW+H@+nuAH0N)l;4}L;_Mcl2O`TfTJkig#_v&RtOdS-6~(4FOvv7Vpk@v6aMNrkWfWk&BDHoriW0j1ElQ z;S49D&!^)Z8_(^UJ2E6hoDM2goO&34(6g$lC4x2N05~0;2;o4R z`3fjg=3hFMnXhf0>x|D1b#AC-j8Y&JjvFk!JFaDZyQgj8*uhF>IMaXr%(}~c%p486 zy>0SPzS>zC@+CHHo(VV{igo3vyqG!N`$7io_D02yR7-Ktgqy9xvl1?&8}FLNObDQ=0ws`tfzPxvK!?{((d-|OrOa+i_<{6)=decE?Iv~eP9(UAZbod?EE!*bZG3n^;FB*n}bH#xz zIPuibS+OWcmoUW;|M2;ueuu%g>#_)QguNccm^7NgiZzA!EalBV3GVY@-g-0f9~p8q z9LdI_xF=a&jor=SQcasT0W~ldHA?UfRyy6}*2Tu(k&CxfDqAid8M$an z6@NDlTsSp)XtY-K8|~Jl(-CuLN3!|Rlq=?RCaq43H`t4F_HJElYz9x&EYka<7g0SI zjZ%FJz58d7?-8_=-3|l3njTCS24m>gHix&}Vu!Xd==|`{euVbr`EDdgqH2xN2+NN5 ztKUQ(C3r8N;hX)dNe8sWzoNC7kGC^+qPo}SvRigUOPJboGNw10jTWEDj7W3A>>PIb ze9j)Dp*()k=;%e`I1XU!!tss`9rXXkYIP&K#O1i(>?kEYNwdMC*zE2$qrc6BqshZj zr`xjVaNU8UlAXqB<5Sw}sA{;nkypWMK`;8*cIi0w)OBF*g9*{brXi+>Wy|-g_JO-` zN-qy0G;$I8dqFr1fI^|y!+%hs=%`0gJP){o9_64nyf66eK*;*axtm;BcR;3;i;3r-p?DLpAc&lXs;NQD8l*=2sy6M`TDU~wmQi;8yx>&9* zRw|3t@?v$VH<9Y;$|QQp_E0rBe3dtF-)wUER^6xIgOV@AEvH60?57&*<|oPB((_za z;I$6rKgY|H1-9Z12qiKw$k2s_ie0YhY%J~-^1tjss)%{$`us!9-z0ykx?i*RNk0P? z!mgtV)anYt`%pc`k5CYa{w;Df>m)TR@tse^-s#_fN+q?b=7Ri={Z{%vn1w}r1i2sx z2%$?kI}f0*Yna&V<06&3c6xxg7D-#d2PmrN&J`DE$fKUzz0WAMNujF6qy!xyyCJo4 z`m7zrvo{&C$i=n?O4vf(AKrXHJnvBgo`A)E_HMILVn_!K;8<#Fo88FT+P4-5_m7-6 zUp;$oJ8PTF#qDON!Q<=p$SHP*(pmL~W4@&SN((r*s{1OtT>1s42_oP;Dz};{L?=+4 z;)+eKzOzB20iw}EM52eZU(#Jf`T9Y+E;oqvy2cOc3(AMvBW>op&k@x$&O?ZZ&frE` ztSZv@*Fh#9HZjUWM3A`z8Wz~(jvLplyK%?T%h$Itr>%ajL1M{G9TWTWW}C^?)^W*h z3zO2Ds~wvXdW&`G)!Vk;u{3wxSyq?%>yloIC;Eo%R-4H@J;JuZF4D7PB9YJ=-ft$U zwE>rpKwnZ+c|x}d+Dd3k4a?Q5%Nd3?KiaIxQ!9=>V=MT}@R5nblVgWQM-Pon9-g=+ z-kXSaMDag1^M8IPKMHNd*qtaRq1#2FpcKQv85JjOvd={*@{3ZRn^(BnbzlTjoeexPWl$Xrzrh#d-($KV8-~5*z|2;$uvwc>wSGLoyh3?ZQ z2Bqu&k|V*1r)Y-j3F&*le-ak%n)ri`_%@Y%-;=%ydtv!s(es>G?`eB51- zJMbP6H6d?wV4#gFAQO^qkg`fU_rM0^mY)$8IMJd8yU%27+CppF1vkrqbv=9=>>0eRLHi#uohzIgp#oS3?vcg14P`M_)YcJ}t}?Ca-OCGK{|73{?7 zPD-A@9M!ZgAUhMXW&WA@K&p3_sH(qjSMTM4 ztgK`MfvkeW5NOEa@~t>W1#3954wNDl@6pjZA%1c%`%g%oB)rCP9d_zF*21w$V<@Ux z3)_csHNA3U&K07DjE|LovMb|q? zo_~ricU3m`^lq+12MUoBw6eQ?F>!de#naz@zMS#+GqRlVdopsp-Uw()W{N3A`~j$1 zJz_0?koLkCCe4c(JG6N&&U){0y_C1?!Ij`UE zYjE=D;km7s^jRHNqc_xVM-~rk8#<>KD^xyCayF;TJyWmEBFtRjE<+ zbN-S;Uy0{z%a2KC!wRI{nWeMrU#x#j7@Vzgl6t5^Pu2^5k!8jgttc3?@@VG zkhVg9L)eNC@&=xr*TvHmf6OOIl63t)?Ms_7o(`u)u>?c;c3+P_IJY?IwMRo%kKf~s zMnnFdUhlb%fWsg1*DhLUUxzeAQT{D+p*P`?NwHdjPZ(pIxYKc$${-HGCcb(67)1A{)dD~oEZCa*Wq6_!V5rlW-^ zq$$ywvp+}^7^4xKf;A~5wrY<0$X|nD$9ovw8<7L2!HRqMMWEFR5JCPt(m`61nPQ{0 zio=+6$K!qbuKWobV_WY3E-#3LbXa8i5*UVxnzrU<=pO~QrIw_y^kLr zE9tXt>_3I$V?V6j^V4KWPl}UV$QnmH0G3UQJxz8B+Cm6xR$%L%RP5aigS&nTr_S(Q z@iQ@;Iy2W!r_QixJ`&&0@xppuc4Yfa3kx@Guk($G*%5I94c!3`+Hnh+40P5T5}wH~ zBteDkImP(E*=v}i)lBpi<`l6MH@Dj9OA{q_Z!eCC&4f4h*4Jg(pI_i~SyrZTVYSi- z!Et?WTGK?*3@DOYj{(EK1BP@)9HMwCj;h?kIn3Om7Y=KKh`z?8Ho2}vLP{#p_17eu7YXCVLj8LYE^*Ea zvrL7b0kK%F|2Y1e7i`M)O2`v*Iz2cW-tWK66AF3#eji4i)%t@MYZ_z_1Ene3+Kf1A zndXL$30czH3l{jF5Z9}`Bm9&LIn|5I_(Eu2MXlo#ighAA+wdZ|)t}caW^N%b!`1q% z@Cih$2C*V0dR9$l~R zuWss$cSV^$g~$@l%0rN*{?X=h<}c55(II&8a5xelNLO&gqHu|e#kp#Hyx-$-l{yqU zHP0M|H_JZUcn)dSl>P&{{TffH*#AwX{aJrw3D3s=wvt`a&hX(L(AuL5?1)(oqzS;4 z;47+)8ALDjTzEk$tvuUj8}-pZUfNjhrC*!I>ZTFtfxq;;A0e;&ev(&yKYQ!{^7J3{ zEwTpq2|1+MF_-ybdfmqd&zUFaKoy8aeSq^DpGL3$r1^V_PS$zIn~gYtLnTolun1( zo5HD77=u}%0imSONoe&A>;cKiBMze7Eqhwk_z6nr2=zpz!-2GiB|UKCz4c#uPt<>j zy#cVgBm_#ei=CxK_y+qh z>a5>Kb+UDsIHJ$hKWJhH?AFu*>NMlzGSq3d6arSC_A%nTaorqb#2!cp#Q(U2c!4HB z;I;T^Z^900?4YUsT8AU(cgEdpkHc(m*8VukWL11^cBE&E1lYyuz7|gi}%FQxVE(LcTgA#y4mriT-WO z!y~4tI;Z*?^!iIfd57uU_EIESw7tjV$cOD=)BA!SG=UzIdS4w|`@$wEnu33|Yb zbe48a&+IH!ig&{!D5X**zuD)$yI48s3*OycF72F|-c_m=?sogk;wkmF3;A=%=O?}b zB~|;1A`c={Q|&VzctEe+7OQ3QX|LNI47Z)-KW`>p%f{j|&WccMh9%#DyKJ#&tZME{ zuwP$&fgOV{Z;iAE>fx&|z?YEiB)uB(5BT!xIyyumN$o=sih&4vVDf>c9(Yfw;f#je zZ|cAS&Epc=I`z^W-HEP#C3HzBkqEur8@C#!*Z1w}@7vv%8m}0vaqrvd!Bt7Q)}8F$ zafS4ijz5TyLS%s9X!-;K%kW$B2bCU?>M)6=B3-< zvP;Om)JY$az65&}i>MCCm^{VF5rsU3jTITY{2;UjlQeCTKGJc+kBOKV>0E{6DO~6;;y~{ z{&FO9OMyoVr3IP@x-p!)CI7WtOnUCLDVEdQGm%g#6A7lD|6MMocRc^wSPoRDH5tE> z{(;)^GW0L9Q6R;%pkN9SUnCPXmfT*EE;8l2ZU3RLVwz3TH|kHDzu7dTwDfawO?cTI{bkdUNjOd;lSuvlBVE$vM>%b0g_I!;RL&u&jNV6e5F z{wJ>sy+dNK77_D$f)OGv(4uu{dL0ykYamp$+BASwrEj^S2GOnbN*!qHpi9+t+m+ z+SyMhb9HSjmp68)Cvz=fJO!~nUd=|*BiI5Kr=%60>_e(uSh~d4jg2}AbdK2TV+ls= z=`QDEm4vGiIF=0Qv5F-Tw;1AgC1N7V@ss>SE|BkuaR;G(jNF8n$y&{uT#oSDXdOr! zWjyG;(wF(1a~av!h?hbh)A%L?xXfvtd4{L_g3p9y*Ib|TrLM)&>XoDHTWc&Qt>3s} zB@dfib9rg~oHfB)SFQWenW#;Mn^v@G8=YPE|In_#eVf_q)*!@b$NvK%_WVWUf%aMc zBQ)>b*wG+KGvwS^=Jq(I6NN8bkfCyrzXScFu%58*yB5p0ag>#p{#rvGgW)Zb^cGwh zGly8p>2TRuDjcr=m)+%X)_>`6+-NZThhG1n!SEo&7ozc1X_DPY`wvNv>cq}Nui`ro zRi!z=uSCA*qdKvxP?_&4RFyUZ{y`2G`w30*{e-ap3j3J;dV+^_673{peSrvmmHs9T{s>Noq&g9pN)g(Rgf(R&E(K?^s_Vnuw=j@kbNUcq|i(OS_c_wyKe%-nbvXqH-XH zU!+e_r|#o8T}1Usn{^yj&jyipH&6aRd8AR}EQX)cx&iPpI!9H(uo)l|{t1Z&2ferPM^tAQLw%&UUR!0Ze>v4Z@0OyagVLW zecLLy|3+{juai>rNI(mVQB;d*xF6;wI_y?I4!LyL5KK+koFRmMt@e%yX*f`dhvGgD zqLpY*EEq52U>M@HJ($_m#++MG=$ z2QiCegB6fTcuEQW8|DP>#og=<=@U5d8sF*fL+4>3{K1}{XL>Ngs+CF=Ws*|A?l*eA z(rBBe*3jkX2esF^)+b(q!JQxIb7v!^DwyBu^gA5^i^=T5U%$nKT+>p<_nNqSC<63C0yqZJ=r4PqCq9KqjSc`NN+HK14B z5+y45>W$dtpZEisTez)ah7ZlcH?eBshxzdiyUp(pgq(su9N~a3V0Ba{q{mnBN20|0 z@z2r%`;>l$k3C@%5chJ!o2>tav-amTbMNnYq1^jL_GYG+4s+?(Pl;{Z+QHafEOdlJ z(LjDHd-K6~(woV-k<7;Xd3nF?GHR*MrsdMG3+JYTRx04u;a8hjqr(THRKPz z%$f+=H_zAXZ?grQF4y6|hni)&>~c4AW2OT3^)W88#i}5pVZ-1R%s4Lnyu)C3V}7Ca z#HcvmT5ZB+w&1{Dvl8{RoDn7VN#pnovT>Yd1&OvxbUB&{RsI)Cw4-YaG};MaJG&8Q zwt=^(rTyOiCr{1qCxyH<_dxA1{WEz;H5-W99DAoFP0Hdmq5wHYC< z*}101Du9RiN)uJf;{G_lSG6eaAK~|^PQ?8Qey{2`-2X~_pX&(RlVw3#dp-LBJTX;k zgKgDlY0IiMX?US&veW zs(5fIjeB+Fx{$88$DF9zZb(7gV-}Zl!vCH#!KO5_Xtmc025s`^yVU*t8tkbZ9YN=q z)v}7Yl|8jHB1p&lkzJ{$wS*XpFKR#aCt~qwvuXqj+C{ca>4O<0T`r#0x=F1@td zYIj@AcIyIUnRCHvH(T6xYd0SYC)jTN&D?&{c!VrIiqdHMO;PTl%AGh^yQOk3cK_P0 z9~iJ%+!mAFChE4?O%}Hw+oC|;NMq1t->0+d$l7h1I^sk4$PWj%`N+`WimWRj>>S@V zX{@^abfzDmC=z`{u+$iT^yfkQtV_RW**4*mR^_RW);eKY*m+Bb^F;(Ias z#)fpO)%MNukEN&C<@$Fvy#Ssl*fg7Ky#H4WuwyF+*nKN+rKeYoH|wf<;)x2z&W-xJ z{!05sf7jaf&0k}QTnbBs&N$@qa;4-UOXMvrf``WZ@`bQO9um^;e`SgM!&;UIC^5S{ ztos=-z_>>KzAziefPyj6-v@Rh1BY8wKg0H9AqCl09<$A9H5uUv=Huz=#d0|&V_8X? z%i*xdzM#TSTUM^O*37&^g6!VytfY2_-6lN7b%<=H;nr&QZx?edJT Jl2>2&{{USQh2;PM literal 0 HcmV?d00001 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf new file mode 100644 index 0000000000000000000000000000000000000000..60323ed6abdf13d27724c20971cae30198b4bebc GIT binary patch literal 78936 zcmc${2b@$z);C;Lx5G?#PtK{QCl3P*Gd&RokcmXeNkm|PAr3P*3{eCGM0Ax^*JTZe zm_RXyH6pSui;9Y@0mCW+1`HTLMMatZ{^#7=w|fBh+2{M-eZTHs)jjvrsZ*y;oeH
V{>`b{BJKCoZ*A3ki<@OA%k2{CYp5WVj2KWa>kx?Q|A(;x#)6zJv=_c*93xv>+o^}5G z)&=b^&2v60L=OZf51ilDG=G-u>dQfoJPP|$(s%j8mTPb;q|YZJa1~mOJ)-Bsr?S6JeTDOB4yfTGR>kBd|ZIUxYQYiLeC3 zPJ~MqZSdR0W$@RC9q^x*NkYmLSpmN%>`Kb15;U?M5=!}J`3U^SSNsT@Kor;36c zaVidQx=M$?Row%ByV?%_0re34$JCSXpH|PnCrLF(dJ39$LK-R&A(Et*@@xr(4idFo z1C}BhmZamA2-j=|tcgms&wwo=Q{8XCR*|f(H((p^^9?uz@K6H|4T7DbuZlGAt{^x} zW{PhNe7GnVPZ@AhKpvQlOBm@&DIDSsokj-9DK*e+H1HOb*g6BY!n#)&uuZtd6a%&g zWR@YqBl;QmP?0TC4cGxlh!J9;m@TG>xnhB66fI)9=q_qdbD9C2D{Pc#67vw_-_e{8 zn(3ff2+DKu7=o~wViv5$&*e<6!5jkA3@_ zp%6J~Ls~t=Fwr1}h|x%OHo`o(YejC`0gVDQ1JGjRzYQsP42ou4r{TT@^pqbD@!W#y!d50glqGhPDZAhfX}K-~YXa{Cd^3x)^CJhJ3nZkaiX$pN-HcN!bF3wAKQO zX~@w$NI)9W={#ciIVjI%4@jychxy;Be z$qw_+DyNx7sV+o0`}Nv`wd~hy_j8s(k8`BofOu3}n<0B4bWHZrMUW*1Y=`nr7TyL6 z)9pM^H->V2%3J0+xM!mMC??I_q%jh1NONrPjBshinnHNwzt*MYh$p z4Yr$YTW$ZcXW9$xz3dJ4$@VSw`|MBH|7L&H{*L{K{kZ+N5PL{;h&!Z9NNGrO$l{Q@ zLmmlvF65U`YiMq$H?&Xaz|hg5Q$m|VmxQhl{Zr^G4woa*F~l+6G2JoWvD~rVaf4%v z<0Hqnj$fU2=K$vl=T**)&O4kBI(ItvIS)F&adx;Iu6S3jtK3!N8tR(hn&DdHTIbs6 z+Uk13^@3}k>wVXku2W&-!tM!sJZx9k{;)$~--Y)MZwucR5f(8uq9tNk#JY&%c zcQL=khQ!9kj*PuL_PW?jvD;!Fi+w)!mDqP;kHmf*mloG0t}L!P?)2cgGjT_lX}8e_{NL_>1E&jlVMf&+%L0?@NeH@FWx^R3+?A*q@l3 zctK)Q;>C%VCSH?xQ{vr;-zJSsnwr#-v@B^|(sfCC~G-YJUMJacte305JwIOw6>ZH^;sf$uCOMNc& z<7^<-LjT2fkeT933|Y4vHt(|nfY?&TbUncp2!-Mbwk#ctoyQ_$$B~K-K-$$cmHNbc9UKj&HUBJz^+>hnhA zP0X8_*Oqr_-uk>7^0wsNm-l4ei+S(l9nJeG-J><^B>Ots7r1a zZKG*e?t_Qjv?)r7tpSx+@!n-AP+th7awp@_tcLS<+r|Y00{hKbG8Ba(l`4lE+GRl>DP)U&%Wq zhf2OEIZ^U!siicmG`=*wG{3aCv{z|u>5$SfrISi$md-C-TDrP)OXEw#D!r9em7^*z ztXxp}hsr-y-cosI<+GK4uY9HQ&7QJnkDjZ09_V?xS5B|)y~=v^=~dtB{9a>vUDRuK zuZ6uX>-9jd_j-NW>v&aS)p=Djt5#P1q3SPHw^ePcI^O%z-rx4|_IajnLEp`Ne?2en zydLNEKdzS5sE=RL$<%9<>{5Z?AozPSpLS?w9&L^&9FB zG}JfT*kAR(qW?Do1`e1!VAX*82J9a2%fRA+69;Y?_|HLVQ0<_#gZ?%+WAK>43kPo< z{QZ#ghpZX$!TDk5pLhP^^B+3@)X=^|?-^DxZ2qw2!`2VGVc3>o_YZq&*zRGk5Bp_! z)Nt?cQNuS3e`fgSBcez288Lgr<`EB%_+n)C$YCQd8F|CV`$xV#^23qekIES}a@6us z8%Av%_28%{M(rH6XVkt?2S$B6>Zeh@(T>s4qmxHxjxHG8Z}i2ZZyEjA=(k3n9MgTw z#4%Tmd1TCoVvxI4yeANTgSj`8v1 z>G2K^8gMk4=Mg(!E%uYRz9d%RxoLn1!+5TzSRq%SN4Z|!DsPt$%eUlF`IS7OQdD)RrR4}(Og=D7Okad*;>9J2;jVD^ zagTCe=$`Gq*nNrna`zwIe{%oDz1jVX$LWdm#CeiEZcnBs*Hh#v@$~Z4dFFeTdam@` z?zzje&2z8k0nekJzj~hWJeLuZ5ucHnk(*JNF)34J+A^Mi-SRW}r92@|sRC7G=HywmQ|(djYC^LiCsD{rmX@n^ zH*yk!mMz+y>h`#^-39JKce%TlyT(1iJ;~kdUgBQm-r&BTbF#%_M^2(WiJnxC$H+-f z&Plsx6>@T?XDf1YpXU+e52-p1 z6Qut-s`RTbv*RP5#5gGE=ljTa(09Q1x^JIvukR(_KRQMS1^zDhapsY93Oq8+PjaOE z$hISMj*L2DIlK@5?MLhg4LgF_3Ly?3XMe-t4TqN=zW4CLL&p!jA;h5<;I_d%bm-1Q zs}4;S;=^z|&l-q5pg$rFIW>=#35%)I8eotO+InpRaigDhwYC9cmQC7L?Li$A>}&UE z+qH+aXS5yKPHh)PHoLVw+N;_(+IJS4CDIaa@mOf=Byfc^mUk@&Ek`V$1#{40%ezc< z!16w*-nV?vnZmLkSi>3gd-battu9g<)O3uq4ycXlk7|ips-~&uP%GxC@v2Epz!+?| z`kVT@nymheXZ18ZJLaHPHHiKgGmpX;ULPwi!n6D~aj)1e9u?1v7sW>y-F+%P6W^)j zYKFR0y`tLHY4M|slF>3rX5cx$m#mfza=e@^7FRL+XlG>)8QunH7)NSfU^{cu`MPmkJuWC^@YawcrdQtUL)v80it^T4K zwNQ1Qicx=1gVaDZSWOWzXe}I=eTc#=M2g4|eNmrEG3K8n#)$D^g2=;+#Pt}TUV-Q8 z4eEKZMZAu7A>(9`%#^vZyBvX$>tK1lOqPq}6>_Ou zF8?Ces9l)1*e#!vyW|V<1GGE`MZ9#Nt@=qMNT*1bF(OMQh-{fCJeVoVmnot^rip4< zB8p{}=#BZDI$4f+ooq2k_7MYQl^7z=6N6=6F+$dfVX{U{ljB6A93#fcfnus0D<;bR zVzeABX2=W0EO`-Th33jBqD4*<&9YIn%IRW(oF$gXW^swc6N+q+^TcYoSZtEliOc0O zakKoR*eY)k_sK2d0eOeGU*0YrllO?Hs17O%>`iFf5|;%WJy*e#zDf0S#*-STE}t-M@(BR@tR z&CqgCPcads<>9$Pp}o)5tm-$kl@86WeClKM31*7EQpeO6>WDh5zE)qVPu1rlQ^t#~ z(k;5lbkPNKkF~N))W}j%B6Gy~vY!|!>&0+cD=w5n#e9ipBso*elT*b)v=GbX#o|)g zCRWLXVwr3ecgh>ZUGgTe8S`7W%In2L@-Fd++$x@t4~b{x!{TvyuXsYmTwN zu}3~D{w|*s2j!dMeawS>BHt5-qSHzo`KRzZ8i?8G%@wGf6zLlS-5o(kgt46AE>SEQZ=A$28 zudY;U)jD;Bx?F8hcc`hD&3jngr|wq|slTcR)syNG^{9FRJ@tO|2Ku>Y)tl(+{(-g( z*%S_W5c80#u3^Y%`CxNndkeI%LWEXNsQ1VTwbi3Nvb=UA{OG~e6FlOZ^M?)bh`mFH z)Op0#k;BgSh}D?f_J~QNM-KL&rxiRuOq?;V37y%Xzeuzm(P&9xMVyGojOMv$BK`xK z@c)1&>_4D!{RcG8|A5BvAJByU2Q(q)pb6*F(M%n7)}RHUq(z-7py|$3iH(iT?b17~ zaY2*pHf`Fx`O?FFCoBf?F3+J_or&`;lw}^)q%x;+>wl7#vR4ndVuyE=Ev3bG5`3uC2%bMC+(NBmw2tMLw-fNYq{Oqu6(_p95b*Z~vzsOVaSHwRpJETw1GKf-|vM8&vDZ2_$p_tDH8sh@!2P1-h z$f2LVL>@8QkNNvJJykeXS9${H;%h@t z>{O1epl_Rs0PScM#x$dW$JzsYf8NH6E^4NlrDj75&1#`qq!z0cYNcAGE>o-38g;F@ zPF=75r0&Lwf=dh2!ZFs4#ArKOi_v1WI4xdF&=R#IXf;Jk)zUOKuY(|E)u^VTaGKN% ztYOSmbFpSJPt6lnY5^hD5_PEv!KmgM5w8A>5mz+&pie~%`lN3~qB^cliVXELR#)X!98)KQt)$gb6BbB!?aQj z2;yqFXSrt-OqDf9*d3EW@ z2D2d%<#@Uz?LkA*FNpvjU1wtq?mEV={p?N>#UuZuRh=_Q6%Hp=BY4LnL}F%@N{4)b zo06U>+# zrpXZ}%)BeC;>Q24YMgH2sfJZ%gA<;En4cZCNYG9=Dto<6mApczQ|R_mE)r#bdBOiG zRV8eAwrK#H@yM0rI!rqKR@k`?M{*q|d!Uwk74%sEJE6J}TyLmNCtLXeRQ@o3z0nY6 zVZO8m`z_iJY8%3tFU^Kf4hDfHmP?3IL2f{ELVd4(R40j!)>ifyL~GXsD^Y5I znvIp%nP~T#A$=Fjzw}Z40p%;N>aAeUDo+)wDpe0C7jqiDR2`rk)kF1EwScl!p{i6h zfU+=qQ=zH>WvXtfT=fH#p}MLvbslt)j@G6?m8!mw{!69jO)t$I;zHavp&fi0PYC}X z`z|?5PEaxOLHQKY%YYmi6$U_@)Kb|w6KugjEn&~47FuI;9O7V0)LzHn(RL(t71@}ai z+!OWUo~R%9M0IQz^=xf}*xE+1wOxQVJ6~NPQvWM%J^1<^($M}QLddBJJhyQfw!rD1$t{JX9a@>hy5I9z?- z(G}zAYPj=t=le(;Kz%;o`vLCnaL07VG@$dH1YInyU&{{&=X)ED==aNT&>jysm4G(G zaF}5o!|nuKeWw8Tkfn?phKWW#BVdT(v>Ta^{LlgGn=vwRhNE;qRN4SZ| z_y0{dN_79d^tA6G3)zb9iZK&4%y133=EEhz)xg!t%Y5(1w=u8!A3E?%!<=H&|KwCp zr2pS^QD}$0JKM=mP^Wb}BU}5o4zq&Y&vYsoy8CZ9r|8*I z4G?Z|P`EKq?!_~FvFwF;<2u0cz-3{!wh(je-Jp;EpXe~&OjI`^4-df|MqBr|I8W`x z^&Q+lCrTw|d{i#Rbu%z%#}gghlf%k`{`)J|DPF)6>a(IkyePV%O)tghwVWL4xEJk3 zcky@3-j2l#bs1(1HXuC*#z;;)ncjmLUBYAL7tSe05=-BB% zge}4h@gk9o8RXc)(GO{HsDtRzXEelFJiP=C2~-fnQ$p+*K#0# z3TA{88?Ny8^x518DMWKol-Lw?637CP`%8-{K zNR#5eh8d{+SRc6oWquHPxB~V)RTNvEMt@K7X?&;32ma#teSvLOm~`aP+US)R$sS$O~I^f>#mxDlcZ^y{ZJxZn$XJ zs1tKEBaq$*^s7$Lg&A~LfyRcqG9KgDX4vCzcxJg8FJ$>^7ju9POtAki!Y$sR0UH{6qq#81x`>7Ko$%RM$5K+07Od~tq#Y|MFUnBqkWQ@jh2gnss*J#@ zSfr%&%NVS^#fk^9suYJ5b78YS%p1ka1gz%eK`UR#Wb9^6m1)u~(4{40fVqAIRxvHL-CY49IKQg zQD#Nx+lsNzZj2l&$KmPl0y#lmh!xn2uxf~1?dt`R%1r^)HE3H5uXoGE9? z*;v7ugBhG=IS(s`t#ZD+ShmRp*rUA=ZNqg~M|=p+nM>s|%ng)?uTgqs@)E3tUW&aJ zE9ENm$K`UhT!Xc%wc=NKxm<^}()IF6c@@@-D&*Dj8o2>G8?KetVLhx8D@T7qt$rKU zGYhMK2e6`gqr6GpEN{UY@vXc{yajtX?vQuNyRhol6YbSjtQ+5hb+anWL41Xk%4g+$ zc;bBk&*l$dMXe83(mul)?qi}3^GuJ+zv4OgN%@p~8mnt_<+E6CeopR`&!cr}#tPyb ztl9n@tGEBa>ggWrirj)0s$Mi;^;cjW^(FZ-*0lO#41=F~Ae_KjGq&#Pk{F=%ET^^WJ(#Za1E#|Y?*`E~KJ7_O{hL|~R3d*)p# zOogNET7tRqkz%QeLceqg=7eK0QxmTe&|@!GNh(>Th-E5Or71VhqMR|SA#PV)#HE;9 z>8iSkN3j0?4W2{CU@oQ*b2LSmyP?)_Ean%=#HVOuf5RM2CFX8=p?$qljKdsHAJrG@ z^8Hk`szEz9UaU}cnC)4Gxu4506SNXDL<6y6KUfV>=c}RE0XiJ3gd?#|I2!B!W5oqx z0#*yhV|T&?aUtGSIHoQX&tQ$>BJ2&AtfpYD=_2$1N3nxpI?b?~Gx(TqQuDA+fL0kV zR&8nlb|dI>`n2C+8TJ<}#~y{?`Tez6fuwavT9Ld;>_WS8tJo}VK@Z?x`%A>iPBN{{ zV2{Do>Kg2#_@lWha06ycHewgTjo71bv$_R)6K=&WhTE{Fc{^4$?^JiGyYbG#Hgykn zGi>Me%?Gf$`4HARX?^oC%(wr5Ikc1NajbeifmP3^=uHOoEauL3U~k4wtPw@vJb&!S6u-e+A~{Y?#M84?CH5VaLV`*t4-)L}GRHQSlg7bY4_1VP4>6?3Z{2;{X@t z7p7njL_e&hzNYr6*Ri7dPwdM5hj?84RXl+)l=J=7B$%yw#+WBuddgxHRZ;&$hdlqYbjleifili`)a;NyjtVl zh*w={+*dQbx5(gA?Y}a=B5#q`UOlgIT3c(2y}ET~YfIByM|IommYI#y7PdFptLybE zi&j+WterNyZQ8x&He zia38o#SMD;#kFO&dd|MBJ~*;LU1MmY*2q<@A$_f(japqB-l9@ReJ62>>uU@J)c6%p zZm%~os>^4vEH1Uz>lxSOuBo;4XGxs>1DVxx==D1KpOK2U$TDDRW1Ak;TkRasIZkoC zw^R)rWE*IfFiNh0xp|8W0loe_vY^HFwTwr}RNDs{0uR&$v<+;Z-8{X?Nd{0}l>xQa z+lK|)NtqG5jMFMYO>+)g(A>CSR#43-H8_{*#_jdi+D7UM8)+)6sJP6?MX@1unURZP ze+u=sQ9(@0jm(#qJ4c;S$lhW@QRN1!a)U*=f$ymcQe4?!84dHajSdpSPg|j9$Xjfv zsocm!dA)5+a2b_Q85Ma^Pq^OH`>*BJF#%oI8wocU0@eF~#= zaW|COE?^QJ-C&ePiJ`iNO4|fx@0f5#9q;M2HJS=R`E&h615=?hsxgeXh7|=o*9X|W zk#4n7KdSvLwh^zoryjqW>jwAghHd~r#wr5QQY zB`IM|!L|%pOZ;tXiLFJi8!e6WQgd7D{8>%5mLPVey6%hh))}p|ztz?`dMmgZfV00T z>!~%N0=5P#%BU%3t8EBTXIMa;!LrU^soNJ?Yopjp{1#(aRBeN`HPC|88Cj|Kb2F&w z47;l@4r@KT1%d6h2Afiu5xb1jLTg>)Y(1;BHaM5+cJKAp*{~N3!yQ|jsW7zGMlOmC zsmqL9_-jvDgKa@j)hjnLUtZx{a7Jl+iw#AU8?4F=A)c>k-w?L&Y#mee4AyZ4 zVi~RULT;rOnwDQ&U(wUHShvK*0X2j!He2b%dMmv&5U5*rrBTccWwxckt+Y`JC5Flx zdfJvTd&jafs(sHATVo+@z;iY-fdR9Q7E9_DOh1qBBLqy-1##^^M3GNb3< z8wYnE3`PWc625mfa#1pDo2jE_22_almj?KZj|^&y8A1A`2AOXn0M}DS%S@0ivoU%rs^KbKR8*t4 z-$nW;#9LHh$XsE_Tw%yuVaQxz$XwAg6x!uMJVr_-|{25Zv`X=ko;>cZycrgnxM+(a`NKDBY$ z+`w)888N9}#@_6dbEBC92?HVO95ZImT!_>#RM+Lx+eXx|BIm57=pS2jIhtCC#DM3S zaQOVjHuTR;GjtIn__mF0h{O+{iaw($5X`rM;7Gck+th9nL>Y(xN%YKxv!Q``tpTDK z6Lkg|winL?tsx7OF)Bc2ThKJEwPiZzw79q=v}r**1}N=KeoVQ&QO}63i<+{qX|2tz zE%Q+L?Tu|qEz?_DW?JeOwzV4JMir>8voz0cYc!BXLD%pY0S~Cmrw$hd;d=(b zB?gSP5ADBBPq3e!U_U*tOsv>5Q7puF)mxLZu3Q6|1*ry?t1mdBH(rPd-d@%)LcnxMzsIVffb$6 zg5NU{;re?fn1{s=`?K^Nl}c!Ho7!4L?!3mfxxzhf?!38}H>O>j`g;(xCWW1qzz{!M zex_xKI;HZlb`g#_Tsmim_9W9zX??FW_D<$a%9}(n^2W16Y(9y{PfdG>U&R|(QkG+G zHwWuXZkdR+Di>C>1a^u2fSLNwu>$k~R%7>zy_o6UiCNc2#r>Gm-GbTG8!#KXUaZD` z&NFxUO7Wz&0kZ7W*1*3^eFFbAtr-3*+H&|eYWv|or_t`{ZQ4NiTeT?oPifWg7hxxv z6brRl_!G4m@E>9SZtPa2SfqjH)zk2AXU;F-G#x4SVy+sT8S|XF7VzCzC6(eq#^0uP z0bZoGz+b5Dg+EbU4gV!|1^lp{w>z; zMDA5^YvESFErDx;Ylg#meC`yu32>v~uwt5v^~Bs7xZZGBb}Wo`i+RwHwe#!!1WSpX+=je_4~x?#G|@ z_`5Lcf98(tQmmWiV^x4`=Mmpk@c-(g_a@f(E{5NTw`&Q%4E{vlLijJT|D5jv!1wv+ zEr@oeoZ(9b{D^M}{E5CvNJ(VB1-B3GCAb&ho`8E8Zadr{I0~zS>kEgKW8Bj|<=;CM z$_ne}o$^?=k^Fh~c-qkp+x{2P%YVTxRPr0yH3;`0ma*d< zyNw^GaIB)h8nEk!Xx{{^lDB5_o_K`u+c+vo{)Bk?Nm9HboxKjSu7XYDMJeJoi?yG1wda(uW-Q0sDNfJlLU@jN@CLExfC=q4p}i(V zxZO+#+csjr!VL&^Za}bh0}60~^#|c}E?Z0->Vy$`g9!!VZZL5qsUCN|i9`J{;x0F# zMJ5!;+k6u@$AqQ>nk4Y^j5nc?fQB%x0Z>1NdYMqE2~lXF8LC71W@x4fr2>kFizHh5 zc_KX~&g1ZhGR|^FDCp8V{J8X=3DS9VhSE=f?pXR~@DG{L`zG|32@!4|(*;6b>J<6{ zhwdrLot6Iy3Nt4wH_3AF=ift!^+75+rh zMEY108g4=X9MKJ8x;itouL)HG^1^jX&xP-SOHL!E}TVVuGSn%~?f;eQAB zrTY{32Tk0&CiI301#kiARWo#t37NQbN@EwN@r)VzxCuRILid=^9e_5uH^RTx#9akw zE#=(3!i1KXP#d6T4kc&?LsM`j#Aw_Ng`2>bq3!{GoZAd#sD|hm>TNEvY8NtQlM}HN;^eR+7H2@Y2PsJbKs8<#B?7p?tq^zZGYO{ zwB2bt)1FFu)P(Lgp{*tqz-{S-yP4zOVB$8I(0UUJ#9eLTmY)M6S#*Aj%+UEJbS_E% zeT+F~-03DX$%Mw6&`1*+VnTt`8i4D^x$I>^r6ygW3FVtmrU|7&_wlUpNI(uaOKOJ@ zsXsGrFQ5|yr5=O(jG;p&^u7sE=vy4RuM-aK6YgK=gxkTmCxCmHq3tGgmkDh)p&Lzz zVqDKLuI_|e$GBCUaLY`b4z(k+1#VVq0GiqfH_;3oYeK_KXpjljG1ND;GS!>f4REdr zc}ytTgaWt#6l;bOmvH71V&aq^O8G6dGUX(NrhI2Yg!__lpP0CVCiJceyMxO&hj1;tK@CTToH73;Cgvw2*2($$p18tQ7p%F5mL=z%9Zn;uifNUv< zl6=a9elQ`lP(~%iZ#JPDOlX4%tw)U2Ec0>`x5$L%o6sE4O;4T#f4m8egicXsa1SVX2ty4f)X#({ zw3ivGL#1YDp$V-|&QD&AyUgUyQ0h5w@g^>kAh>)^Av4(l*pk$N17UwQp%W%_%!GhT z`i$ugnYi~&2)LxTICP(hLtABVe!+xxn9vg@^spZySqv`Q{kWvNOlY$S-DpDBo6yxJ zw9bT9nb0yJGQXr8C$+((hWmvJ8W z$uveviiHbjD8z)6A4>eqgie~!cP4~9=y4N?lg@=Wn^59G;+*)dAD8%s3BBrvNDmkd z5ZxX>j-_Jx5_kD=iO+xv@__Df6ME2u?lGY|K(UGG2-?WdwScZ-Xl>$(#3i_EOKdhF z!p&eDK~qdfrz6}1!ojUz9&L$)8+``dP}~pTaDr+W>J6xzpyUQWlvo6)fJ3uQ9MQSW z7>Nu;cM5fxp*Du#>6{ZzA?Irem+(WvH>oWNpC=qi_`rk?_@UHxKa{ZFg!Y;ca5(po z;_ftYPnpo8CUn0EZ8f1SCUmn2K^BAG4JK}bA4*gjA}@r19kS zaI0DO@t}!h$YDaDF>nZt@1W55pF81BFz#3<+-HnC1lso*ddr0Nnb1on^nwXdj2#@~ ziB7nO8MnO??k*FjL!0AojK3ZfSI7Szw9X7&WkSmsYVQ=c#SERr(A4;e?$PmM0S`B! zK_*mZLVZoB(uBMw1TOL2m`kpS^Z22}YvU&-UPYk^>-`Yn5>_*AxgVFX$b{zmq4;D! zm-tu{3OAt;6H! z;kanw4Cp}@IxG96UW%-$HiT1LRXp4S`$JG7Po|Bw3$$|3C%DeqMO2W69A2l zLz@;iz=Uc{2rZWpS`Mg)=?Y9-wh6gSDA9zXO$e=zDHHm^gud}Z zaU?0njs4t@i#=jOADGYq6WWhfbW`kJ99p^C#O*Ypr%dQkP~1=2h}~*JTTJL?6S~2K zHki<;u((lzZj>E-=v04F zPmAcLuaCVqwZsWJ^M6|e*!z; z3I8zrH2?i67y~1}M=Ym$6@G$-^#j0|YsGtl9I9}31~7;#otg!{U44yMAFIDIp6E4o z1b#HF9DoM%=AcK4@Ue0rBe7$i;9c;Q77gE~6_Kw_zz_2^F}#C)Jr=PT1#*?pTt{ElwyH46@D70 zn?~y{GEM8t7?L4P{mlMz@RM1dA4wjW#(7C&N#fN3U@}>rG|pEVr&vI;K@Bv2ze1j- zSd^mJ&8rT(iG$dPxoIh0;Pr;xyaKVCS0L^Ym^;T>73r|IJVli1O88%KtglFi;tP)T z9ihk z3u#qaSgYMwt3A0)yRrq^)FT{gF#Gl7<1J4q^YDg+lx6G}k`96YihSl!$o5>KUS#}J z@T+Le4DZ82t9XN!O5{8V7;^gHXK;?XvpgB3ADO{?y0fjOlV*Uy`jG6-<=dCbWe~^8 zV7NQOFLSJy8S^q>!~)j#0>X=nS;Gssl(%S?Q7GO@gHQD04Mp{O0b5`<=Fp9KIyiL~ zV_eL0CCMq)k%i+_MJmT-Y!7o8KbPu`n9JomlP$KER|@B`42$v3ABCa@iD_K!^Vxpp za=Fjt7G^P*{#=%7E~hw8hgln`%x9i<4YZNUD`(5pP=c9ep4tPritBF`(^n~KqwsDH zwbHtp8NT{G>I4vYSS&Vmfn6=bD(xIr@pMC0#Eau7inO2XpZ@ z4(PQ=jzw)+GM7j?-pi3Pn`KC*ngX6ANjgi?jqU9hwu)qyDxKx=vL$$#gO^MHeKiC2 zqnCRjr|xB*Hs)E#JbN)W^rzro$b9xwd#DX#{84&UHTL*Tebk!THVS{N}UG=W|ZGvsC$d9yJ^I7iih=yQ$CMXK{|Y8uZjQ zmXgeP%RGcaS%!R;p_VmJOY7FMR+|TZzIFk@OjE0N08Z4Fvp*JooVFEq^(&WMlCPcd z6gN>@1HYc*CUPu#e^tsJ4DVt3k2#f(iBd%}<;P6(G1ClTcnHJSTc|!Zak@>k29I~e zNRlQC@odsak|tWYhfj5RCR0u$+2kNjYbNLG22N!rbDqf@8kuGQ(=;(n6HC>^d2ixe zTu-soWn7v~6c-0aQSZ>i913aG8Lbed+k@7d0aLr-(Jh4e6yl9j;5pqwj+MmpNt{+P z$4cU~TpTOO5)b+$j@w{CPbwQ&a$eCzFG+bH%;^s1Tn}b$gPFq+<~Eq)F5y^%Io-h= zYc0c}x=$FfO56i(7*mqZG{+b|#_&p(WThn+q4#qstYqEZ$eg*wkaL-Gs`e|<;M58! zS8|E0WZ717iCm(s0)9Dbdn#*tC70bw*1%;Pccu0=Xb$6?9dMu=sS=H3TgiD@$+^3q z(_KmWL_a~T`bw5|tu8J5%`9Ov>*qoay->%qmYO-md90;oE~#ebe-m?VX8LBP-^}!z z8MB!&Y0NW?@owgj#%=rU9M{36%%@kvLP)pm9IKQmOPJ3{#yrn?ImWRtaz`$nXZjT+ zxj0Pu5}Yr*r%HTQkUrtl-jror;~F)zmSP1-BJLv#K`81SeAHR^s8ixT;*U31iQDOF8?Z=C4jG9F(!rM_T@6_#&8Cg{#>@4zRa^PTTT^QONNG=%D$XRU#6_G zP`k8A`x1U7Oa7~N7vKV}JAGM(zAVFB*6CzYIfUrw=<%dwQ>ma+|0vfkLPaHb4N zUdfb8INf#3?F#0@pYWXI?iJ? z=P{4-SjTDAX&-?8eeD4JE!rXYC$#O%fpT4Ese@n58pyNc6NYnfu_c3PQ10?#N(FBi zquga3OH~IM6rb%#<2m{&St9nJEW#OvOT-F5t8gCpB{*Ykhq#o#Q1&E!p$t2!@P#tG ztB)^~;SKtQcu##6eW46*v*Qb8cpDvGD3gD~8`W|0SG+%+E`OtMlgZQcZ8F$DzD=h1 z+hjNcmEPzL#fct5IpC<`cfkD&cLEOWjr{~V2U#Wr;#{H7qX86~$ zKanXPVSkIn6B^Efpmd*O|33D=Wf|HT<{FDufM_QAeu0ng;1NBIgK^&W`|$5(d0t|8 zFXL}CXfV1$DAC``_}iFr4#T%Hej<-YUt<3?e(KxFG|w~qH2W_}^bI&u;uQSt>^}^A z@XoJO{AE24-iuara%uP!zuE z^?m4vk?xzmV}aNtr~k(?|H5~$LYDWW?)e#qslDdLs`k|Iq*koyOpXJadSl#m*A>4*A}JR^Ilf<@*ff z`i$==Y$539LmT1y3ho1v5r2ax?8eZL53LFPC`SnW5t=xBX6_7%li0@^^aCYJZiF5= zcPxK8K@t66CrSOt-@gV@M@~=s>0rx0`%dBXH2(QZ-3(;Sp;9HE*$3&v~2#L?{hzd(4z?doze|Z5%ha{=}dL@o$o8k6;e4ydxTMce%7rN zeozfS2>J%!Z@$yMUwr5xf`7>Om%iNyHRSaD1GV8uFoh0-+kbG;A!pzkh{ z8u{Msdma>S+y!#+CWmbDT|<(A{FpzmQ#Cvh5{@k0&x-uE&jH{($N=LR!q0XaC2 zKY_=|KQ95?|#02>1BY}7=f6--WVr&`EQ~a&`<&-1Nswa z>KJMcx1r?gHW{2xqg~Ll0gFXT=8qe=2IC+@kR1kSf+61zR1eO|onPNZ z3S?uT`U}UTlGA_ajr>2ZX@(V|-v@MN{!B_gm2vgs&%Ppuej2oJ_~q*~z7FR9d;RZc zy1x8zaScdpj8*io;4;=>-?#o)MoJXdNR=?u&+0kj{QBGHbCd&9`Srxi0;vTcP#HY* z^v>xkfw>m^N%l}&o!C8Z$H_p^B8*Qj3dh+&X~5;+AB8j2dLX12{}`OyRRW4KoGTY6 z`rw};&J+Das;CjQXk+Vf>Xip?8%)P3Kr`{r7PIls!86ht?8M)Oe;%J2lrJ8|zW`?k zJ&!T!i{d4m#r6vRg*cJzHKg`B{zc*){ENkV_!?vSVvcw=PBFU#XPC{!7kTitDSVR$-ya!J?=j(zQxWmEvV~gNLal6}R<=+pTd0*S)Cvo&2W12PVO$2` zTm}(rt&wc4QAT-?wMHAIvK=Q~#c~C6(>h$z?-dD(Q){PpNF&Ts982;&d({50_8|mry2` zkh4<>QK@8csbq7h)ZwP%e)Yl*DqB1T8hKjU1wL-GLLJ=-I9 z;e@@ra7y2`avA1GCg9Y;39>IvFZAM{k24X;MdB2_3HbWP&u}Lgl4z}{4cUe{*L$J= zkNEUN`aWDEpY-=APV0M1z7KinlsZ14&N!cr&Ve(|eN$6$<{O>(HjmGEYscyJ!6&%U zX>2$*4dA4^NN#y(^-v?MDIVs=reWsS8M^wNZm+yl@Q%SzvD#iCt z<;EyV;qG0AB-$9Okn&d4Ns9kC;vd9a2zb1V_<8u2OT6!&oWef^?8NsvD87`B`c8r3 zYw-4|85qS{fjtE555S%V_PA;SRsnkybqe38Ax?<>73Nhw@*TlEjDx87?rl&VK|Ith zK*v#vkQ#Bv<1HXcTfsj7iI3n7tazLUo9a8F#zX!K&=+C-5BN~w2HYQR4cxuHW1uVI zJf<-13!r_I`TUAEry>w*Je~!?&G(B+HaHRo(#vsh{2I9?=sC=2?S$I}_Yxef1yW9b zQH`8K%KLG(5&8`Q_D3}tC#p_Ciqk{{^8YnLPpfv{%b=h$QkUXv)Jt*x>N-$efmXqe zJpV$aqZ)BG-84wuY9B z3~Ba4zDdaGWSq)7#rG<5e?(37eTC515&F3LGfoQMi11s`4^x`>ei5|zGQy7H%WZE# zJH+=Q;)49^{FBsF=wupl+k~>5fi#hhy2XdtH{__^6_)JBUuoi_aVlb=A8*Mu@Ojw7 z0lX3KQx0FK=4k$Sd0H~wl_kEN=;_XYn z+zX9xJKmq&EV51fauXjZZWC=L{vnee<0(IKxoG8Z%8x%@AU~bsA3Q65nCvQUHTfSn zD?A=&{hlzx-|G}U2I*6NrkLTgjBvY_0DaTj(R#Txns_J9derfdS3PgyS^p;eWD`&N z4wUm&6AwLO_sH4&6LGp@Al(Lo-loMZ&S9Ia!6~25V@!cr`1;J;veLe)A_3B#(|qwE zwYb=LysghB4STjp*s}8GRK;fGMcdJdr@j?s>>b{<_J%Ykn5|eXe_U5 zZvxuk6pTZAp`K;tLTHwUDwr+LTV7V0o0Um|o;wp%EA={9mr|IPR+y5~BQ>>0N>WB< zVnSwS%Kua^Hzs#aN$H-f`vn;ZNuG?vgp3jYQEmMd+D|lV>$7HQEj3G#tcPagLwp?? zt)`U-)!M_+31Rn zc6IzU#4ghqIvi@3gBaQz79G>E?c;cPNA&3j!y>~Rq3SZbEh;Q5($Vp?E6PRJ_rjxb zjdtA_Mz+M#aodxk=SJnB&C_t6s=!IKJJ15=V5};tSx}oj&+ArkvEd4BZZ2Be@)Bzn zWG^YFlF}IDLd%txkDi>}P-@BPUzwRzHKa?&_avW`U%8xLmiF&g`jyr8O~0`PSWCNb zM8S|AT5McleR1jF!uV*HTIGtaithL{Le^AQoY%3})^Rwry1%z~GIUvlUa$pcz+x?@ zIzApYoRn4aps_VroVClvM+J&Qa?_l3bz6nv~jgL`zLw>+piqM0`lqnPiVljVhhI zcEr#%Q_4Ni8B4)BL+`-tR3EO#I-c4+9Up~}G_`w0zKcm}6Ca8`hIG$(lTV(;__O#? zyQlMu#JVxHmwGxAO}vZu=_oF<+fZgv)H_ylNulQ=Yon5i@lq)jsw^rddC8#G0a@o= zHr+?%^5d9U#VI{6Jnvt2o7z!1ZAJZ*+a~J;aeC#@%ZK-xJ)%eG>1_^@8FpdK(H3I2 zKo0Vrhc6=28YtR$Z7%0E3U&h-ARC3-)Txh#=&{so8fk{G)FWKS)RTObLDY79gXT)s z%T|6tq?4@2 zQ0OrmV~lfD%b?1tt9H3;<=S_T!zsHlbRg6!M=^9Ae6@pWU{uG^FsgZujzc!R29l*4 z@~BX@gC4A%aPcGC6Lbwc_2W7|8f&=J|Lb_trjCyie=)RqaS%Q12~Qz`9Lo ziBpKlo`~N?+Pwxo4?B;5XFI%H%wqj61YdtV>VL5=gYe+^q1xwX#Sg=J>o&i^fXi3E6QeY0eP6dpGk$ zJ)y2QDo204LIXps*#e_cI%g(gZI^~eLB{5=sHm`xhb&f^!_a$nV5!nTj3`^j$x!Oh zLOS-M78!lRCD^H0NxCwd|Act|V4Zpj9`s<;Q(j>&OWnJ=$RnwPX(OK6c%ZA?wC=zc9lZ@jzH~blCG@Q6ctj^BhD-5t5RuVfOGS zO~u3yT|aj0`k~43ai5`+4UdcpJ022lb!R~*)Mj78b-6!uL1Xdfxi0H?s>?b)O1y3K z8AMNYPRB>$q#M2MABgka_n7!pna8%R^C6qp>0QzjgeRNS@p0lIw847+-iERW!|02i zrJ#f;e$1i1f=VTDCo}9BD_k)$#)VRmABSUFE}X_0C76Ke$W%L`!%nXzy{HxB2jGqu zF{rcPt4#u5?$lH2f^WNsQ7C)#M@G@-P+I&rb?%fec11?I)Fkpx!|-BU5s?rg4D(N6 zrVttOizp`ooUX_>gCz)tNgA?E-)x+izXSRh%H@zQ9y8mLHrBU}kHi`D+%}@m38qh$ zF2v(LLfp!^5{pf}ktyA(>nYq7lO9kCRDhIE%3nAJdYMt3;>6I?CFukYm+@qt^dw7n zq#4_G8SRRQiiXY?o;NMU660`$*<$*4?@^y09UdN8F-1&Uv|$JVh?@6bqw zo=<;aE$P_EccCME%MZI~G-{u9Y{D*R8q`9Z=GIxqI$txe5(6@WHdh0dTf;K(5@L)- zoNXFeu^z{jNo6(~`=7RPndw-(@Cx=PKzpl3t+tL0J4S6bY6H%5+G=3!8qJI0S&CN3 z@hC%WwoaY+BJubHShq&CL&wHFl7l>2eKpvXvxCMe2~$ z7*B4jjEg}Tg}PFU-7!&-VWAFJ0=1v~Y!u^Am+Q5|;j%iqds5QE!ue^4q`;n7>;$Fu zQkNq3F(5<@?ByV&NaMEu-`Iz=oHsq$8Vj?q#ti6Q*pL?!79LeO)$wmE0ld{vwuI@> z7d>e&;vSFiy|{dJd?aR?+Nibg{f2K$?7$3L4EFD!ea*w>F=|*f*l4UBUw|o>MvG2H zYqP15VWAzL^pI|QLcA*~w4+yuyvxy1g9ZdDlF=5YZ0gam(cz4YR6C=cuF#Hgb@Cd= z>4xA|1f@C2H;~eWW@fUSsp3ssx%NpPv>us(JDPk`c3^M-*1p zINs`@cs9+`Ozlh|JlcUA$>UeD---%uOJeP?+!*sgGf-Xw!^5Hu+3n%3=tC-Gg4@QxGBj%Mn2PD>2o)7}8XZ2m{aV#=naz&Z zoosSV*y#ru=N~_#jfMm$g?7@9mW;Va!%8s2ze9f-@=FBE4G2OFuC$|St4U!IF)mxU zrK2V)(iIjF?F1~Jc0{Qi=yz5{L|Lusg3!|s!C;+gO+*2jvA6<-gt-PYIGCCSv3r3Ga(<-E;aLpMW72%4{Pcqcu zjB>dm4K+o_x^r{(M7km(lr^!yt^OXQlwg(3$SBT?ce1rsX_uHG6$$4oU(Oj#D#?T47(NzzW2CL4x0Ov9 zgEvj?VYAK}@=^pI)nsyy^kM0$L7je8x3lob5bNnDLsTESJ$>Eq9)k-|(`d}K4?KI#lSNn=5TrzOrB@>GM*M9ZOh7Y@>zW$P7!vIv1nOk@r zA1U59=M?s74;Xyt84Y+&=Q%Nt(_a`A56^(GWs;+F{EyFyA10f{9j5%>`oq;xwB*mC z^uNY;xyU;7e9$u>$rVUH7GLjKVTRKfLzg?js2h4b>eqF=Q|Qn5I{rJ8ALAi!9Ohj2 znfwCbE+an_{yK*vzdX*?`Eq{Ecr@zJ@nPcYpmLybhmMcO96rtA>T+~5@kw&6_=kz7 zIe((h(-_~WTuI;lc!BV9%Ml1aw>*LH&T?IPR{F8{;+e&iuicb80{b4yOngA!iNI5v zqvw-GQhNSLkM#7b>~PhsRygePFCW2x9<(a)&qG_P$u z;9|;8@7qwb|Az`F@4?)*Cod*1xoe6$CN#`qi?q`aO-A@Dr2pEfV)6*i9cN2ZNx68; z)vTco9=NGge?|3QgDR|G$-jW)2QV9#gB5;#Bx$T5(U9qX7Wg7ZgiZCaxk4O~A*Wxo zhO3!=0sYrbf+k=|DO5ckVhwX*jcK^uAs6~3^IwA{WZgqTZd10v2B}TS46)Bp zB+ZO+ScR2V+MK=FtkdFk!r2DnY_KtK*!T>_a3&r(hXYKq$s7iA2S>8k_N}wQKd`a! zj{e_Q-4nFC2JZK}zdv3{{kprl>eZ{4>y>=MeWHoSh@S#&p9DuwkgvR~*KrNJXf7V- zDv!gVZaaWsH;LqIGmd@x)T_titIt`mxpm<)vcj6_M&Wmg)TK&aoY*;B+k0s92r>V? zcki2d{i%8SQz0KUn7>+hSk{H@YS)G{ht^-a7X2c>PCNP)b~STPI4PX)t5)g}wsRF6 zpF3C2%x}$Pw&ov%e6iqZeJmZZkDCI^CJ<^LfK9MZzuqUO~Wlui=l?dQkw$&;w>b z9uu=xRa13TRm1G|A_*6NSCX1!KEoi!(v zbi%`2UfXa#&W9s;O%@PFhBafu>s*uQ;8+HB_E2QlzE9pax-W_T^9ko1>NXr`f}s4Juc3M{-93*m)k^iU#^H=$F9nLu>yxUKc?r!(kpxr$je&LGeYbxPf*SAN);ZCo( ztpi>3ZICt_xQr}KSjnH%C2+zg(Mj_J@hRHOC1{7q_#{&346cnxasGbXGCmMtO2G7( zo~l*NiP2V}CD#}mNi^oy_IN`BqpcIC4Auxfuh%Cu&Yizu@U*5n-LK~sll48dHT~(D z%yuo9s1v-Z5%Nf}w)%m1TYrl$*gnzII^0n$Hu$4P^Vo)TVXx)$S?rGN!Hqq25r0_I zJc1JIZfxp|Syp4`M0d}I3}}*ch3|qUAt%Vgo8(@^Xj20iBQ0Z2e=u=DtXwOwBbDs( ziHmmSgpet0_8hy<-LvSs0Lk+^%eXSI$Rqu)=|b zOXlV-SzzzsF8u>TyK=c*Lv%$w+Ov!=@OAuMK4J@zP40i;aI$i2cmUaTJQBv?w0>>4 z-}QBlA-f$~i#FT`OxfOCYM;2K4UbZUtn^*tjy7C(G@d=+rWkPvUc=Oi=gA7NpEqI6 zl>7O?5}a}=$qJzU{6~ zUHQI=C_=G6zv14{mG>ivh?VI$A=kT0?H>}!3ZVP4h*P7v6=37HjIS!3A6>@d zZ0Y&1>ke)O*w0hWg#8^3M|*_lJIRLxEuScBjB_vBx`t31w+mc|)$R+K%?B0edD=*}`;xaMq+pTqe)*I{odBVA9p79Q#*c zdk8Hf)+T-!-nq_V%T6{>DJ@8}zYvKAF9?N2{8ojl6zENwdh82~eMZ$$Z%8ey zcMD6Z2CC+L;;Z~2XO-W{snv$ls20{&);$ zGv5nubv5_QkY+23$spod#oRq$7Hk@E7kEd5a8U}4hF|{greA4=9-qp7Er)aj7F%SP ziI)7|vHwzqd%e1*7QWld+DzlvWvXf+D0RJ}nf_yAeiZ{8%oKiU0^jgRtl7)|Q!LhcA4SIBs z>9-2M7FgT@2KiSw25BE8_ysb$X}#NU!XUvV(RTrHJsV2+v!VLwM8h_8mjfl8$o5hP zmtRLCD8Y*wi2Xca+y18My1wF@A1uKm&@73!*w4>8a74q`kUzkN(h9Nr5?Uh30)s@@ ziuGS#q*7Mtrbez*l%n2{tHOXcAQc7$#-rGUCd)6e`=r9@Buo&AG&JSd2NWNo(;;0` zgspCJSmLX^eU7g`IQV**_uYn*{IKDE@I8{SHk@!{!wuI_PH|bt1N5^5uOT>efnI1P zK0$}X24&K`J1*vd9JiVHw8KvUjf9jIk!RwR-Gl6Ta;RenjoJCs^r6wQvsQJi$v1}m z--g=Ty>Xy_6MnMgfLRzLg1A_z8_G1!UbeXQ;^~I|RW05(n1MofZvV*eo_u!C=m?MX z***FidJ69<{A`c9zK)%i%T7;!>cA!8i9@j>RNUu46T%ahwDWg<=z15wdkCW|zLON5 z2Nze6+f(`Oj`F(~cjDbgkdyMBQp*R*cVE|tH=nuU^`(2SE#Eu025&y)Iu+-36npw* z=dLU~?r1ai$nGt{kGkG~opR3eV!YJa(To2?W5BMOz5FhXq4-vD3^M$Xm2dZy-#(At ze#Euxx~SB4s(knI7jX9(R6?6A-R*PkCeh~Wk>M^0Pwl7GXZQCZ=dL6?d!W7q{d5WX z@IC|r@htUHcc8M3>C)5xR)Rl*6U%80+igEwfvH z5XsV9C`VhnDhc_yzI1J>E+mC+JqgWYJq*ZxNln$%)_Y`Rm#S6`kH^?pAz!mi`%k*w zTE>=mg9A?rumK%z@N{_|g|C$G^VFV~fS(K^g%SUEGcr?vyXx{y>>?$$iDnWke;HLdE)tw|c8?y2UgzIEB*efdyR zK=o;c+A=V8(Yh^{Og4^gA2R$k{jIT7IGKxf){Jz3x@?SmUrI2q&0Dbh#RE*O0~btV z%@nyH_r6d}B$?wLg0eD~9227zV<&X7sp&Jv#?G3GkN3AxhL7p@AuMTW$^NnWEV04t zz=ocl4T3&>@!G}9W+Sbcdh}kyJ?9Xf;ZtL^~k@#YQA+I@aeBuH@54VK1 zpy87xEx&hoWM9rw^|06QCF^G|U7WvU-d>0JI=C=)OW9obJ4G%GICz@_f86mQ^e&%A zy)D82?0UOHxdbn^lN30dxEtyYIx8FZ!QGtpj=HWZ@@ z3c=A=l~)b9`P8aIn6*{y3xiFNSJ@3kd9_J+6rtPgTwYmqqy4ejOO_Tdo#FC|9W(;R z7IJ$>NA~7&dq;pd@<;YUYcnvS7I=SWZ7+tC!W)Ug*@P)01t1e`aMMg7Ih=BiON>e+ zCslS_*C_-OIBxh&n3I&Q{Mb*HVqo07dbY9cg?|bUfa3l>eWModvXIi z^Y}lvXOKND%DUkfTfI$gh5o2D9S;0y${1kK=`mCPEkN_(@H{yDqb2x@PVOM_tfdP0 z%WRl!=FgKvC_n!^^1u`hzqSG{2`?RTS|l~2%z{ZOg!RmCquQnbE zgnFuvBiXY(?0SnxwrhQc%TJ)zI}Cp36<^*iAZwgQusqP(3Ca%GcedV&sP8BB=|}rd*gp zEIblXsZ~IkDnPQAmYv^VZ#N1TnV!BiNk<829_+AGgDU}oj^1v*Yyu*C&KqRiq6mPu7r)drTa09YhP5+wxl#uyn z-S5{yv|cZ~zQK6)v2PK-7se*0pMnkM^Xn!Q1d=v+p$RkH>zZ^lDDJwo%_J^!!MbVh z29Gph&x<7%1@Q@5LQ8saFa~4K@=cw$I=++>6{cvBh}PU)v-4D4ZO>1}W)4qIp1qjc zMlrA)1>yv~u{T#;wVM*~3hUM%9t_lZRlg+bs%WUEZ{8=iWLtx_e9GJMD7$xTZ0~@* zMyT(^jfOavdIHtdY<@&=;zu_8ao6o7{@%p7hYdgKdb=Zu>G_vR&;P-7yQ8TSoYu1a z{1NQ*wAV7hX}u9#5}v-G9(1%0bN3`dbKeI?j2!>`60hr4SD3#R>D^aeAC75?(_ zuh|IT>z4OYe;l|Z{ADkm#@fjK_XBVNig zgql{P7 z%ci-rp^x8Bz5WxRkMWtap+~<3S+V?WK>v&LWgGhJ2f+8RN7&_hlJjL7`tUsf+E8)P zX*VGN%DEwP-H0BZWSj(DK7=aJH2>66LZH#361N{Rp4Y~>Ng%#$f8~*%&|HM@+*btR z+BWo=`@yxbSJ~xyk#lVu`rIdoYfml@v-5=aLLVr%p2V(4Bn1$&~B;!rgW>zLW=BN`ti!;v@5>Z1RyejjL!ppMC>uzLt(iJ#mXreM5++ zT*zLYav_Gp(NHiPAqQ+*eNYauBSeISVPDuEtf|bh5Y=En_XmT1JrG1se+tTyId`>t z`qcYqmY-f8cHP5AxdS7Sgd=diQMTK#>kd@tjv)8KR_&>G<&?MZ9qFki6Hdx#vWhy{ z)w8O_r@IZy&S!H|j|e-|&JoHk1m39iM}5U_{)xO~4)o{)*j-P#?(7+?Ptz5pJlP9? zkrKirMl6-*$_AU0u%?K?UO=`B{;@edpcg(RvQ9N*s*k3RsI(J~FGEtI1s2pzt#D+H z3EHt`{rUDkYT$rG4O^Dm=!@vbE4LyVMi*ztNK_u!nE(`I$I*PrTsrjK=PI z8z1{|EB0-)V(DK+J_7X|FEP#~_7Yx2D>VyQLC{{|Y4jUeiYr$>EM^iGG>KgIhs2Vh z!}0{6(l_24OGgzefK39(fww%8EHsB};}u_y*Y-7OmL)1mmCv-?ZjYh*t2;5zFE8g^ zPjO80{s=FAkMP^Q+~)d71$2jgx6}7L*R$za8T;fv?%DwOJXZ6&E1rHnO1k`&jj*#ZC8RMLs1Ia@mq(!e7Y6* zhFf*(rmlR`t-PU#bGCr=U3t48_>i~c-X;iz2Wcv8(y}FrIE6}$;7*VzNcZ5ICjW+H zaZIk2k|s=&W?*c)&yvj1wQb`|aiZ#)e0TerZu+Y#+togwE()Jou_-$vh?5iUK*K;R zd&;0AgR0u6+uEkv3y)I|S4t$C0C%@GjP#J+xo-Io^%_)vCddEt>}=@hwtV~(G>v~u zKJs2qOs$Jk$7+UqI+l8hU5pB?Lvw;Ya7wQ5U%WT*wy8G!U-&J*;>%%kOAO+XdIOsM z6PG=QcyAo5oa&SbNFa76gj+uc3TKDviK6VMN&47NKkmAbYYyv{^Js;%cY-6A{38A| z)^`~yqu$Jymx%)HR!DBxtsHSZ07~MRS@HbyuKNfx%fAN=5@z6^p0n2w^i79$2oKN~ zPB!V5C>dVMh$O3N8aY;4Rv@f8k!rfnr+Y1tX90_Z9vd+y;_hwjxn`fo9@Vh$80Xm3 zd#ngyiev7Gu+PE8wH2d)b-S~SInu3d3_W!!>DCV3?5qIJ9mqBCDk@RsP$f3yg+|!Z zA3Dk0(7_>902bG|W5fd|=Y@JAh*^kC0cmlL)ydUE?qJUt#p)}B%`Bya=AU2U;7*10S+$V7<&}+OSrM& zzjWZRn$K%1K}ky4Pm`aCIFkMJcS~^c7ZLSvxY*&qVHv;v71Cf3hdZ6$J%sTU-y+NS zXP_)@#~E-l^_ zjyiW?AD_`$f_|w4efV^_2o;kK6nfa{GQRV)>onKrN_P>9=Qv413;G#y_U-#$=J#oo zv<_{Y@lh7v6TVe~KY~5XWn4a9fyJ6>%XyX?5Tgw1;)|I_da zB>5T|fkZ0WHI64;B+dmlfh5T#@0Fbg33>pg8@~>R#(acc2%sj!W;U!>pPM5>#LT_EAjL>zur|>*PyDZy?Kkg zmXBe!>iL@QE@%0Y`9)ED_IJ3zR^2bN&nqT=6&4is{a57)wLV=}*fQ*FT`4e))xHXg zuxEw(M63R`B9B0A#v(<2vou>zy{0sW;w`250MwbS?-$<@-+0{Jhh3+;epNir*4+SRX`bGHYUA$8U-g`&9ObziOZS|Eqlx&!wIfK6R2#*?yCg zMV0;kv#9dl^wMJ+?XlN!oo4)aH~kwCR!*<<(%Tx=`Bvp6?FhXoL3go_i@W@9CP#BqU4C#Sjy`n07WS zFq2W3p@h}irGdI!OUq!ad7`(WYh9*#C?8QZB`jA>CF=W{h1StTY&c!pyD^hJxWS0Z zvY^I0g2{%)L_|@e@k~o6ni6TsBswRWQ-l}0rzB%OC#WeDu2ssI;@{pY+%cYK8Cjj() zo#kWE-nF^m#YCvRk@c+Y9zHPA(C<^-m_gl$1={C2d)Ks?mZrtpgQMAGzRAaYJCF-+ z%$NoW7Fg_owoNms_Q^yj)2X|yiQQv!uN^Z@)Tq&zDr;SvvJ)H9su<9a=A|~Z`&$PZ z`$l7hE`0c_l+OaUst;rIgCzTK{+Y>lUUGp`^w;LNYn6}6frGh{w%_#xxow|7XW)47 zRvC(^sAeppwj`?k?3mxs(YWEe1sqAMt5ZFeZUx0)Pnx}C1b|oPi|egix9(pZ2HgLyXPEYSWDA0 zYklk$AmP7HJ>!g1Sq*2=|Gj$6n$`3-^_REGc@%P{xU~EnUtczyyu}2E7QQc5dYV?1 z4SoEQavS%SphsUvE5vSrc$fX`vpmjXLqA=DKD-6X1J53!u{luksD6{L4*O}+5bfSQ z;=0PQs(=gbIkek;<`Q@g>5IZn;q21We`K$BNhLV(5PF*QP{8?EZ9NrVuXwL~zo@6$ z?G}4czF*W+?fVa((0)-*weOR)SNZ*-o{GB|3wh=2F+PTz8)r0t6F;}d_}o5{9`@63 zD?y*$LK1;P#WNi!^wcdBy?Pivs4sHLnc|d#Vr9i@YS1#l#fxUMpZh<{SEYDVg-?`S z(mol9ry~7komD|y$ZSZa!fn+pQNwaeD5gfGR`Oj9-Ocd8h{B0PN5nX^t=gz*X{c+G zJ(8_|7RMkU*TuoZlgP>|Q&$mtz}lt~9z^oY6Lt~=wW$}oMrqH-GJJ`etH$2RO?jYp z7)TZ+8S!;HeQ}lIbAQtOtP<7&BKwXKRQ>MzaJrX(?9;+Ng?%{0OhZDI#r^Vfi3ZKw}0=pCGrvderz?Jw~ zKzxtrM`b$kEx|V`A#Z`(Xp*KsVs;D&aW`` z(GcOs?#(BFiC+K{WaC<>US5QMssulZ-JnmD;QvyBKa2?HA4>3#mEe!KevSA7bX(Lv z{T9x_@gfJch46W@%u{Tyvc1A^=p}R6Nw3NdU}KS`7w(dRh8C1R()4bXZ8p84`y-8a z>Vn%WWEBk=qwEK=j?~kaEO`5V)$>C`kWpSzbN{aACzOLq9+4*zJLxa+JR;kbvJOEu zYy*L`Tfqu#Uic%^Kk?d`j`^rzcsya{WOY?zPi^nkA=by)=6}pCwy#RCRFQ8|&xoh|+Qz!;vku=RIPpS) zOTy6$Y+guE;(9i;$n^+Hvfpmw2<h=WdnY z#DDD8i`=CE^>H?HtbZ=kxu2L)cB18d#mI>#8@d8_XtSC^O~Jq?-1s z*z9QGFX6C>t${UdHQ|PIghorggrGo~Xiqx0d0)v}5fpyoz#)g%!ozPrEs|%2o=yl) zY#QL)??b#w8Tnnx?~qRUX-Dh0eTyHAf zy`+41Qv!FNf=%p5EQ-2A4*g=1jCAx1M4h@%x`u4yZYx7HR*cwx~}d(#pt$mr2$@G98M*-bW`57`$ew(D52djWZJnIjym@MJ>%V%d-1@>*Z<>Go+R1I5 zNGb_y=6nj}tkS2R8Jbiq%?L3?VGD!U@w{~qj=s#c;mO6t$%)0qcc?~-=fK*bZQZey zg;HUv5p5Xh#O7XRw5`*WfCb}+c!)iwA4v&1wT{+%Z(Rxc`4aT;`BzF%$P(w-qceXh zLH}HW{$ZYUExX-!IZ(2(-;Og;ig5VboHm|LR0E2v9O0|NL-3Ui(#k*`{WG|f0$hAe z37)j!h?vX?h=pUmjtIZw{Jnm8*gg5G&%w)0&rzgBe2@K}_;025_wm>yeYe=Y%=S|I z)UV}X;a3&y&QZT$4IE(?+wBQRv*rB&JF&-sQv!?QKtK8O=qEkz+<&R`J$#4X$H|2_ zbFg3d0c2?hk9HEZaLH0k6|#Lx1IR;%)>t8@{wbBOi;pIICcIwM?V&Po-o{)wmCdxb zWK-;ht~Fhqv#H7PuC(g&YJb%&uhtW*9%$_u%MJ{Ur+X>p9A!7+RLA?FtJVH(ie|HI zGo2mN$>elL=S*9Ft}8t-knYL}t?9Y;_PKP|>JI2dJ>%m&>G5&s2T9E75d56@ZD#@$ z)2VE=09VDlThuMLFWzo=Jv~%p2-`(rsrP!kNJ93!>>m3A=_- z*~t)gYCEKm;Zx6X3yk?uP06m;IE>a_M314dlxsckVpUGrXQ&&;=^Nk^a+3WQSEX(; zgUZodZvAxQXt#;l(?$Rl8zLI(6=J`}zjdWj@_4N1~nU`iAD>qT6rE zy8K%od3eGaRKeexqTIiKZuZQfx;n{_j4*m@q06XRM!U=Sj$>5Ya%hR~k1CcI!9=ig zQ2x2_lE|*&*xCm4uqlrhyU1ut)+mMdqxKdRbApNX0U3oV__Q!&3>DZDIMqGRV;T0) zR_yzC@RG=3w_v#_hn#fs27r<$+c(7|*@rSDHKUEg+j}}U2^it_I^%-pZ_YNMMnm-%UB)En! zXMYtQaPhh-POVQd$GHV4#1dthI%7NeP9Xipp>2b;Rhjwyqq4^gntE#EY_Apx3@&t} z7jun+r%raQZjaCO4J@^{t#2QaQ(t3Za%1Q4Y2!nw zHNEMj-kx=oTZj1>hSm2ds0k~CXG|Su2~gFS&mh~JX?o!koG#8m;Jok*P9>oooWiLV zQLPW9(2iZF>aZen@Nztc`EEkSHikY~_FQuQn3JiPMVS~|oj94Ttp_=mOwfcuAhXws z&H3iR10$pR2jhc{Vr_Q=Lf5$+0}VaPuEbbt%UJ8;@aW=A(_2!r?d`Lv&1|1)_RX|s zxA*sN&vwrAn3|a$Ph=^fGMgMrzrAgwxp|~*cwyn#OKXSQCR$o1+J>oG%FyzkF+1PI z&dWZsKlv_vvBGl5Rp?tMq<4mgx8>`qd*=^~pvF83M+}~|WQP4i^BohrGnkuh%*|{j zyO?TQ5WdSN=j?M{vpynVpNQ98wfD+ZW~{${{EQK2YC6|;cdza4Sm+|jU*46H=KUQbjg2E6ox}7q+1{SSKP|n~-MyGjFLrk? zrF&Nm^i5Cq4XgqsG~ld{_d}LDlrR8ZSz?wBuY9v%Nxg2xqnYNCrs+sV^6F2?je_V? zEw#(TnAa%0tb2(|A!~!_Y&FS7k|eOez;cT=nZu?^ED1c)G0Bz;uOw{@w^vmMVv2x5 zLRL+0OLIrKs@XR!U8Q-w__VA`J8F7r{87X!6+^Mw8?Z^JF4Y=b#CB(m7!KJ@%tQ`A zktb9ta>Y*AovN&<8}SNd%DkB{B^138ok=o;np}yxfm*|{&xJW?GLd! zr7m6DoYlPOi0+j^!ZK?1dSUxWPxNZry5Z6_0zV0%+jF9bHjNdkXm4Q!Zn zC|Y&Eb*>My=SbUP))biH4>hlKn0>aY>L>7Bx!>ZpB*W+Rc=czsHybQc<+*+7r-qH0w5F{)X0AU9j4ZLluN7 zK{u|_A)YR`0uie0+PX%Q4c&F| zY(sK!qV?0w;i_0;G(xqa8YIC4j`8x9XPrP)FhdK;VIN-s-}cYG(t|>OdNnyIg;9T?t46kU_NEzTCq^*I_`Q zxAM2*%Uw+4&w$=IB)yzwvg-;w18**eG_XrqO85aFL@L)%pV=FcKYTAB=rg;X`pn+Q zba-ocpV=D$>BXsRCNdRxpBecf>e!X60e%DCXAa4rWxw!6K+tEW^@-!o0@0)+ZZkTlwn`CHUyoQ&nFf`;)|)HZ-vAYMnuh;YsW z)uLbbd)UWR>_^FM-O(`ohjUlIx|hK0J|O@u+_a}yEWrf zL6VR?IECpAEAJ!JjZrapPjEkj`=1fMf%oG`-MyOL$BT6T9sK?{Y!IA4!`pAR+sDu_ z8l0VOzyE@8=gRkCSJ3^pI^Tam_z-`;6Lc>lotwwLV>V9f;U>0Z^9WwlVtZ5bHw=? zcchwANGNi5tSh2;gQ#9iNyT6wOlXSK#+8$%5_4+|J-HT^AI}8bbX;G=`o=rR zf3Ww3(a$jc_lFC6(OK#E5?bWV23%C6@=m_4*Me!zeEl7oqRki zKDzCsg98-+%j~bN1ITLKj!`D@^DFo*3)^Xy(LeGBTmzkzc1*i2Zcd8a?IR<|bKJOh z!|#k@tX^m~5lZow0)BtsJ7M;fKr|XC%!a>HF>Gpgd6nxLwrsbHcuFwBWp5C5U+p<2 zrc86bJBSv&el)BJ5o%MS*4ap;Fc+w*3a~FnzRhvTo2MR=c6Fcd5M&U@eG^(JZN-Ap z1``OV1RX)6umrg|>+EIDMUNZK_X9@P>Qr(n)xNq)2^)r6jUC7h?ajyX3mu~7p~y08 zD2GU-gpr}|YTE*W&hzq;PccGDWX_&5aZ@rT1$gZS}R z42*sgL1PtmxE^AijLrk4cSw_T@GVInjSt27|1B*;58;oNq2^|k=Np2EW8h(LWv!@f zGs!(h(83Zj1rm{(lgsue?TL#SwW=R@UFtYB3y)(LuWFy(7w&|)vZ7h`>gAc7A$B=oCr zrx^^I>_xg$Fk^@hcMf$7f$L0FJkuk)v5#AQ<#t)oEs`mNs0DO0dxu*>HT4{>J6uOWOOK-h z{Q(|XaQcb+2e}M!zKZM9__d2IxHhtn(fi+92M6VLwr2UG?Bj0i=~#}r)}x<8INx-M zZNsd%h?8RmxWI)>Aq)POJa?`(fMS>Q4?S?6M-R>hC&c@%C)j-~PVdu-D9_*y%kQ_? z5-p-9uoZ=B4G?DWyhtbKocwv=HvT*n4FX4@tQ@C(eD54SBIkWvpKD*+{V(@tc^}4h zJGIYeu0&B=O)t)Sdyf2$@5NCX@TclNKAtrg|MmR+9)4Yo@oePZv#(?5?{5CR9Qr@7 zJi$&8zD3p;&Izy`6pnMISYD7!Yc?q>o6j8_K7WHO8D z-rVE%!xCwK!yW6^-T8*3?9*_jq^o9ml1&QVE?Rp1cA^%RJfRh(0eD`Q3{A*uIt`j| zrflJ#k?w^DN3k2cDhcBBxjWwc(Oo+~@}?d*{uy$X^6XmpBjE?1Y33czQC=TO6`FI% z1eBr>z(3G=8VI%{al=HWf{7HvV21>^xOQVbi}a>EbLaS`j^QLW z$tgN|*@j-;E_?^k7iabe1?XTd3dRYw1-P)qRUeQ6J1J76R_+GkB1~$YG;!p@$Y?mz zDRlRS&>aEJ0nx+OZLAAt+9l2B)2Q!()IyHAzvn|~74&DQbL03aIzxXprU%>oa#+zZ zgr(js7=jO5|Jx^%TUv6dwkk&0T)#ZU&H^uUY(>g4aFz{K$aVfaL|A&1e*9Qfenh{& z?$gC--3N?#M$C-+o+F*)<*5tCLz!$OSm{MyZ|ttBGz2docu$&K=pq8m9IMO zi7jXkc0Fi#VEKH|=%29aFM(FO47$RZ+rpo5eJQ^VFP{Zk_zSKtoQF^sMIa1RbJEUaeGYFSKUeY#rIsdIqjZQgS2n-(BnhSOhmy-BU!@Zhns7?SOxT!*4;hAi-}D zs2@q_Vvn&0$ZH18k(Ms-*|iONA>?H!Wj)N<~)uCrvOc z?SsA#qr8p1Be9}2=!>-95^|r@4ICFx53p=zEY)evuUsl#DSE=}0pnAOp{d2@K7?)l zXik8=_E|`8CQi=0IqG2_R0(Q2H!Ie}OvODeMSS8fEB+S#rN(FcGFpytRrJnoL=opce3!^Ek)l1?(;%;NWtS<8qSY@&e?@5}a^J@LL3eM{!=l zgF*;2c=L19{JD!eyRiFh$B0uns@6->J&wBlLlhZqajnuSj{bVc2&6<)QWtz#d)^TD_5NNxJ3Z=HMoyVu3X zw-vq?pB-vto|;^uW4fnmFjtkXpAoVPt?7lX?t|O2YqFWQ>b^jr@L+R8-m~ZazXnZc$ zv34T0d3193L_!rz=>LM+v+;E-3a{npdFPDA^UYnGhgRs zI`=MZ+?Did$1byAevoy2A>v=(0iNO7n1nYqXB&RNAfeFagS=3MO?;esA{ii%D_XLUM>jF!rv4GZ(d8ZS6o*-t|KJ*8tk$wN@J+GlKn=5 zF0v1YOtX9zC4kvm=C9hH%k95vezpC3_1NJp-Q8ObkBuMR+}*wT@P?67`ZK#mCo&qO zS4atVR&`Ccv`lwZb%Ye?U2e5{SQyxI^_r!t_6`i}y=rOA)q4iI(;Ls7nmT7wSJ$R< zrl!u_n0{^F&U|*~K$E9R#nGyUm7Gj`zc7i1g}oA!PfD) z!UyVdG(4J9XE5X#ijxPxarxr!WVAG9E}%{*P4(}Jp~~}#j>bB{SI0cEBr*|s3PE3> zTQjnu+N#j7rS^=TJ~DFp=-9#0(Su_dl+oId>7#mQ?2xYf$fGyKs~aRmY>IfXrc@7( z{$+J_{)oCo(XS2q5yspqKRtBX#Kghj;e!(srww&OOJ7hYcvhGJNj@Mf=O;6Ke<__B7%7FWVz2Pd=$3&SmO_ACP^_ ztY3LNlKbJpll%%{AX$Yc_U-d^_p zw#h`>WHLFK!~qDsL#?etgUJ?t5}+f`VYj@6+i9zp*SM}ljcu}vIL9oe#$HRV8&rPt zy_0M`@l9lTp$ta10uP?q&ZE!cxKXapTCpGlSMfTtHlSbR? z`X)OS{D*u1+!y7jyRi0Ymda}M$9y>a5C8mZFWGG`(+}Z8JhYxA6OL8mBqNJ*V$doo z_OTBLA4EhJz7km5uoN(&^9g&NTQ5vVtA*+k`gim z_t5JQJnvqc?>lRMo8aEloejeTQM4*G6k{72=9gMyX~^hrD4^Y5*O#Gr**Jk8oIG@| zh86NLmT~l<5{`BfdY&bl_Sw>3sDS`H6}m`AVF|(%LX_4!N@%0mz$ple$Z(>Xbc8o* zoIW0b@fSzkrcflzrBYEzg_Z=zTOw&IO~7K3jc>ek)v8N3E?qS1R?NaqnKka{8a>z| zshTFG&%}WTtZ8RwdPgHu^`&dpZ@6Y@`jT}Xzw{-jNbz{zxQcb8ObxR+>7SUuS{h?< zq{D+!+;ozJ8{T^EV;-maHz&!(BavTZzFCIF%?~>(V{gS_Xw1f)<6m;WA-`_~wXX8} zP}(p*lAP&G&9t@6q&jDkujKjRXe&+wL*jxrAl%858s<1ge>YCdXnf+d;o;LJdKWu8 z7kj(uCo@Zjr&XR4Rytbk*!?JrZy^-Q>zlMKe@naz71bo+Ht2+O=GGycpV5o6Sf(%| z_BtDYMM<*`q6otr3>KNSt?Y5d(2+c(OBMxKgngJ6q<|yls1Wn#|IuT@FQ#RCd6RHq z6+egl)bOzz>x4J{BS(kR`i6GHeuw;;uxkPu?n(Q9+}>tz5{ICQGl^A6W5q&cqju-* zfkYNim-752l&t-@APKc3DN4_$P1y&*06i4RuRXU3>7jVzg@19 zSF=RfYgNtf9YuzvS2x1&6ejDj0#i6~;4@+j-o7||VkhzVK?d?zl-)7Pb7BABEX$#?ik$9K3v^0Ev5(TO=bpevHN;CLB7uWQYIU6sU57P1^P^_7nq zsu=x;rb)tiO&75*vPU=?;gp=ImiZokhx zq219j-+}+r^QqK)XMJ~VZFfEY$sW-L-GP8OgfnX_Y$T-fn*s2PgKFU&T3!tJ-Gdt4 z(r`x`b^HDJN+7+E?po;VTl16k=UI4f76Y;)IVAR%SpJ&5!) zfb+oPfk?zxT`^dWV^qKI;!4g~aZ)M?!D7NDX}=|Qw6X_>HH#XIin-hA5i2Z{vAo_V9pYz$0uNL!6_7lu1>Y{TM zEHjakW>~>#OU$N+e6?(j{Je!Pm;WA{ro%>dUOJoEpD;xQ8$X-Yb}U`Kdj9goj-@6& zBCBpAGB*7z_#jMU{CE?kh2by5U%0k^@3kA&Ub8P7t1r?rP6<5a#)Y~nN!0Xe*;mI; z(x5u)IBp7ahq1sX@bbf7!;JPUpN3PV(}2#|Gs@!7GdwQMIp0;m3a>?89c6CWET*HV zb+EsC<|~{3cN*!x@BJnX^+#;?-#h}A-2tWrPHOoJulYw#gXMJhgm4MG;a zx(c^)@pcZ0x*w*tZECJdn6l}yu%jiKjWkS7jn`FY5}H*d8>VSCXS3a%W*x$~zJXI$ z4V>Db8DT@x-PKDyy|W2Gqb_)qh%vqUw7YQ(0-Mzh z1@2m<@D)`_SYGJ!ECv6v?)4S^Lsc{!>3bs)#IY-?Ly2rN&V~>oMq<@K{dYpDDZi|$ zh^d>>%ZhSyK(&-33a-7{BZ^GY(mqckh8c(4gnmN|#Tf)?EBKQpt!%0kSq!-at|R6_ zg(3?tn7-MI=k2p-f>|Uz?#_FWhz$A1{z#9!@@K5l_bgDgorS^yzE0mWv@4t4HAGj` z4;4Rt3|xlkB)?)52!%Us(!zOcO)@K~q$`vvqA9L)wNbm1VfJ9{B(0L!nnG_7h5t`} z>MYyD*FInTg22u^siIU;qlkM^56Rz7=f=UG=k(E83kU*pb%D+~D_N zk*P)}0xFP)9TYLzM3hN}NAT}=-4T8c?OeKs$YISNUag;Jk(GB3J;PFjezyH@_U=DX ztqZ0OxBB{!t`8Xidmq-pK`yhv0E<1fEjs7QA(VKLQp#uMfgP?i4A@7M+S&jehj%#< z!_D#G#M0O;gmA`VllSFt{9r8K(i|Uaqcik0Me!HzD&J>D%c?w`j)$K5#8w=Qw@?)G z&7F%qskw})iK*FMI!@06hog`Ews@a&wW18jy7rZ*>i-v>zwp1z=h>S7MgA^O9Z>OK zk^R6ep_8vJ;z=R$-D8&dK5P3APO0EaD^L9Cqbb@`EnHBwmHs-T;n-*Dg=hcKQ-Exa z(8nJXS-UL5 zXPrR~=3VR}#Dt3cjrZ-0NGui!$6`$9zrv9ip4FGHKzz9ATzusWMP8isQA4i<(CB`IQ$Yf!|$S>|850>*cKIFJ>c73 zY|8NeGGMU}q41qm*ly9j{0!@152B8uSsH`W<_3L92h<2qMh$V{b}8!{;!&kq-2jvB!KcBF{Y?17J_H*f_(y%xe_wDP~oe$5_*jyVH;+%~6>`C=;(AX?kk#4! zSA2k7Q@d(ryvho>ade6|oNB0BH9J-Xmo`EInlIc|%Wr#w{B|hS$Zt0Y{B9RJ6sQUW zLps6>p;UdaDu{~7me;CDRec;ckcAKS7ig=)jW)oIj(*PTba1Zgse0Mp?LC_gWd^$a zPUk}Hv2cH1kB>SBbIjL?4AY3uA4IUj7fRM5H#daTNw3ik)0y_`+=hJE_mfn^IzY@4 zP9c(KM2$d{+Zxioxah`)* z-)i_h;+=BP@&;rg6x3Mo{FC=Kc+GAO7#@_92&1oN;Yrj`(1W_hysYpC4Z=#qo|zYf zVN_%BVlL5TvJNYA$)j9br1*I;&d0--iK3Td5ap`b!#MQ-%(_v3d|=m1A~ADHcHk8J zo<0RdOnZ8_qWWScvt178hQ=P$u%fj>Ck{$py*HQNKiA$iw|_9VZ*^Nfzk6t8PY%1k zhxX)1x};s*;yC*}G;8d5!wM(F5kI7SO&IhgKN1oyDAbm-y`h8_ju(W!i=F%tY7Y0T zY3rL$d^OVF*w7b?_f=PSwHWs|Ot;4R!(UCz_qDC*>6}k>P1k={Z|SP3>W|0zyHney zR&7mnw%v!LWygDa#~VU*#siJ515MHU+B#EPS50k8B^n+u>O%Hins4{=7qBn$XGB-P zB%kWaR0`^x<4_=NY)vp0LMC}YPiK_%*2dXTQ^*gaSC4g8d)8T-7Ce?|1wDf)_KOYM zJeCi2znEClRafX(zYX6)MwM_gydbdYo!xbCVmQWxy%2$sN@ttn)3ERL^~qg0xOq%q zn`SQ9)D`O+tWj@)?PGjc4alCEZ4>9MSv+q%InyC&e(l2)<-66Y9YmSB&F2gEr#GCl zYT%6B>l?wNjDUqHm9~Cz%iQ7d@xycZ^Itb8L&{s^uQM9g?K&+tdCo?d?bu(9AO9?T z)8(VeLI;t3ODA8!!N3q*f}S8@S)jI1vn<@^_Q)PDPLYuPDvPVa3j1lY_g|K=q*f-bYyigy{&F zrX2Foamb`|c}ge>H;BLr$4pigWc*u&4;afTQ;tb&6MZ_09ZO9iR&T|k5TV{c;UP7w z79LY6?UHCJ39QWspCp>vPwIOPXydDt2b=hbptLMNT0~Q*66BZOR(}?JDQ4hwRaN}% zH(U3*y*Q|nvG02V$n4zf&U<{C4_;wiD||%Q2!X1(74g`+EUwkj`AY%eL7N}Ua4NR* zXQH4OP%oAtKYPhS(0?U?v8JiR6N$;K-2+S6KvYdlZp(rUd^2aQ>5j%HcJ$+nZun+1 zn|gXTiK{Q2&+eIRORr7|`GXtsy4$B=lbAle|Ln8V!>6xH=Lh!<4(u94QE>bLEUaHX z13PL-=B@Bx@r|yqV9Sz@a8oR5l*DF6>9B<|Iw(D!OE(UtYi$z}xh-1HbbIY!N-}+S z_$*;Bd4UQKq40Qh$3Pv6@k^Ya5-`@PRejCTj+pWT6x#P758^MvuMvZ!D0Byp2oPs3 z@+QuGDtFt#WPa6qwvJccxAXZl_LYvM)1!^C(aw(6_V!e3JNs7WSYwQU4YARVR06<6 zs_=#tJABwSpfs~NliA$cvpLhhkQ-W9%ni;L&ORx)`?&o;sCkSrxm#9@X%n4s_x~`i z|NSwub54SYV^@)ThpyyI8md(5}QM<5)^@+QX4f@1O-GD!WodQ&?vt1Yi{2+%n z1OAK)`=0>M2&f(+o=b3FJuJqjz#%^g_>eHi?i9NLKdMkX=TX=9c-L?#WcbFR448k*F8Al0H>o0H9_q4HnE12e*+>pJ1RXp`$f$rhP>iR)T``d6Ye?b zZZAFqb1W`=k87gnDVIQ`b5S-oX=L{7CX=7rChLlDMzhJz_NCQTO!2hQ6@Pccm{W8dL%rGBsF<>% zxjn1(h%o3|tEjSSP7AX#u;o@gYq`|y73$cq@F}}Z3Y_!l=bEE4la}y>=D}7`FlooV z)KOp80XHKGCy8Q9UZ`uz$8`8P;>lzjr&k%VJj6ZCX$MZ|c#d;_n$uV1b9dBs*VR!_ zmVQ<>H&;cQn}v>=bZu?A#{QXVidM&(s-kEY)klOSb{c2}G9In+4px{@*k#~^tmKF^ z?^8u7(;R4RX++G7j1a#jxT7sq-qw~T%M5v#S6GUKo8kfN6%6PWxD?LGiunB@&EWGm z&UOl~BftEn=7D}pA2!IZt*iS(U7avqQ(H?J$!mpP*Pp-@TJVe$SOLja#>=?eCwh`3 zV0OE=HQE^W22f;xp|G)r5`=~y8ER1#iNTT}+-C-=;$DBPPcje(GGtiSlnU(EWtl0m zA9!sLvMh_eB7CiYXB@v`L2k!`SbXIwey3!4*2-Aas4p@tYeH6W&%j7;DB}QsEXP z=VO1Ao6e;%5SMV9bS@3rU0~mI{YE&Q^S}YxXznl$X`#Ct&Q>ix!M-^VPg#*FBRLFF z1+KY#Do$khBE3PH@Jg-;h8w=Cf@uE{Ckb-Ezn$Z%a<7w<@sz z<+I-ma~XOz&Yd~}>kkX$VxCb^thGk$%vN}9HZ&%@w*|x*X|HJrI%QN*#y^VsYfWtp z9?^q>Dnb>NLMzovrD|#oA>N-ni!XnPxY{;*T7abg30FIhn3@O7Y`sqcQ&W(43}J$n z`*9-L7|yK#ZP7?i%74E6s{H4DO}Ur>_S2GV1N-sm#C`~S*RqYvU!b+St#a)?QCoXO zRZR`H4dNNsi!8vpY0fVu0mB(IG3WIZKYBm?c(D{3!VEdm8Z-1T--+T#T3jFD*N!B` z^&|Y+k&C!~)OnsuIb1*HTyr^r>!Z*@7}|d$dpj&LM{=V-j%9Q@>{*K$*q!1P-WV_u z-nP6v)2j#jA>NDAawOqaUYE_04!C}te<6kY|BU-{!mX%Q>-vUk!q%BMzsFNgIQ`(9 z8rM(qYlp+)`YGo==YzO@n)kB>l=3d;OB_MTyp(Ym7DU@Hi; zOrN*54hNeOpMximLfkoOBx&0bl~$|VJ8 zQBysh9g?M@GOv2TqYFRMW$ZPWam#)a{;OWp#S>gJ!spllv_TnXTw*zjSV@U0sb&sj zvscceKpGq;?itztcAq>*<~=39Lk-D8%AyB)4$6=16n-`1v01`Kq|hlFI8TtJNwnS}{Dd`& z8@LWtq7lLb#bQhHEgF5#cE$22DjJuNn56q;-nj1DDHLX9NrevO*{CXtN^MK3v5IE5 zNBAXM5Ko~~?ttqGc4L1CANg9}YRj!b!;#I7*jSAOF{ZiA)xs|adXQzQ*EJwx%<}di zv4QlQqppJZ(f><5=V(p3rmnNLwzCd@w3D6_t9JApQDmo!m(t29>N&Pb#?>>f=h)&m zA}yGxd)C`noq_As4_7bz^`aPUid6OWz!wWG2Up=(yuLmHe=D56F@Jqs(AIJKh3DAW zV)IHJXG4Aca(%tTfu|mTU_d``B4To?>8ctmrj=TRm zP2@soB0nMCLmbl{BzeHeej`of&7q(k4DlbF{+2I;Ch~JU4?E_6q={T#Zm9eh`rNrZ z?|S$01ANDD$u5Ex!KWDtUtHqCG81`sBpwR-RLNuNl$tH8hE-P;jU5Wbk(jP(9)bDb zL1F*jgt!DnOM%LrI21NqQa3vfvC8@OIE{GZ7PJPi(SI{@MhzQDA-70p_E~gTe1*|fx)#3covwlk_50*!^I0MH94e2WFPx)Z%IT!RCr$PoLyGiIuL+IPB+j)o06x}l@wOevJzk=(3Rk>r0&B#2`M>u1C8fi zDLB}&tr=MwI|<5LPc^diX*7S5P>_B>1XPf85{3jYPze&i1Tc_5pm@^21Tc_5pm@^2 z1Tc_5pm@^2Ljbs3{(AxM{$4CTe#`^Mb9CZ^G;sOn&n1-ESEcY0KwVn1E&#AVg?DcO zs24z^X<7MADZB+n5~Bbf%58SHSiCQePPLc=W&_k(r!aeD_FHdOAi~4q)7jks*@G8h z0Stgw0Vq(F*QdCpSpZk-%`X7B=u-#X3DUZ9k`PINtJU)(WT2e|jfiZ4`T6|A71`{F z8aSy$*t#tgsLHET+R9FVPwUM+0(_6F5SU{IKcF1gt3u<^4`mUY04dw2CxQsKP-Z_2 z4in-S;Jx;8kBwzGwPo!cVxa)?67c6@{^4QZas-P}0G+-;$9bRTXV>*nET1+vO2O^$ zkvXAR-R|2?=Ae23>Y!Q8O6`4nf4I%Q*g-N!Zs)UOIHktWCW$w_0NT5*&mpYV8%9*) zSQ%=2JN{prlre+$=v&z7cqlN#_kBZhOo#-)=f{1qpnLLW+gMH{!2U%d2r!yWbjN`$ zhtO-gbZ9|)Uc(1-1lW0P-yf>aRRxGv=5d1dqYR{9t3pk0&$ZFM>*i`ty27}@bX={V zGo`rS>jFsvd=h0&u4}op)+zCLS%My{~sB z;xYElrc}yhggkTWzA=pjZ!`_8+pAzky&dc_k1-s_;8bpi7E;E3NS_Uvddw%BwsnnF z)C*H#MlihB4n`~C+hZ05*shZBsy8%P)6d}_tkVzJ-~uqV~g z(9Tbrw%=Rft#-L*qiDW@j~(AdH4{h$f;PT67n zL-%X{H=R#2!~j+Sthpv!O-^i*E+wNqu3et8uGc!9i6}q=G4RrPgZU&2pidI|-?qpD zWL*d8(ULx31jwPByX6pYJ8NC0ue4SiVD%wZNuM_NGA#(=uCwLQ09H2f<-PICLv4)_>T(Eo+kfTlLttFD~zcYg1aERGnPpK^04q*@gDi``!o7S9L}E&1rQ46OnCd5PH-%|{T)Yct6jPb`1Cc(?a+u!*AeRKgHf8XKc zY+xOUUrFEGENMO8rIzue0XBnpUD(jS#vckYuiwpkzpVT@ +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#endif + +namespace autoware::mission_details_overlay_rviz_plugin +{ +class MissionDetailsDisplay : public rviz_common::Display +{ + Q_OBJECT +public: + MissionDetailsDisplay(); + ~MissionDetailsDisplay() override; + +protected: + void onInitialize() override; + void update(float wall_dt, float ros_dt) override; + void reset() override; + void onEnable() override; + void onDisable() override; + +private Q_SLOTS: + void update_size(); + void topic_updated_remaining_distance_time(); + +private: + std::mutex mutex_; + autoware::mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; + rviz_common::properties::IntProperty * property_width_; + rviz_common::properties::IntProperty * property_height_; + rviz_common::properties::IntProperty * property_right_; + rviz_common::properties::IntProperty * property_top_; + std::unique_ptr + remaining_distance_time_topic_property_; + + void draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect); + void setupRosSubscriptions(); + + std::unique_ptr remaining_distance_time_display_; + + rclcpp::Subscription::SharedPtr + remaining_distance_time_sub_; + + std::mutex property_mutex_; + + void cb_remaining_distance_time( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + void draw_widget(QImage & hud); +}; +} // namespace autoware::mission_details_overlay_rviz_plugin + +#endif // MISSION_DETAILS_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp new file mode 100644 index 0000000000000..a0344f872f524 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -0,0 +1,131 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// -*- mode: c++ -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#ifndef OVERLAY_UTILS_HPP_ +#define OVERLAY_UTILS_HPP_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ +class OverlayObject; + +class ScopedPixelBuffer +{ +public: + explicit ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer); + virtual ~ScopedPixelBuffer(); + virtual Ogre::HardwarePixelBufferSharedPtr getPixelBuffer(); + virtual QImage getQImage(unsigned int width, unsigned int height); + virtual QImage getQImage(OverlayObject & overlay); + virtual QImage getQImage(unsigned int width, unsigned int height, QColor & bg_color); + virtual QImage getQImage(OverlayObject & overlay, QColor & bg_color); + +protected: + Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; +}; + +enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM }; + +enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER }; + +/** + * Helper class for realizing an overlay object on top of the rviz 3D panel. + * + * This class is supposed to be instantiated in the onInitialize method of the + * rviz_common::Display class. + */ +class OverlayObject +{ +public: + using SharedPtr = std::shared_ptr; + + explicit OverlayObject(const std::string & name); + virtual ~OverlayObject(); + + virtual std::string getName() const; + virtual void hide(); + virtual void show(); + virtual bool isTextureReady() const; + virtual void updateTextureSize(unsigned int width, unsigned int height); + virtual ScopedPixelBuffer getBuffer(); + virtual void setPosition( + double hor_dist, double ver_dist, HorizontalAlignment hor_alignment = HorizontalAlignment::LEFT, + VerticalAlignment ver_alignment = VerticalAlignment::TOP); + virtual void setDimensions(double width, double height); + virtual bool isVisible() const; + virtual unsigned int getTextureWidth() const; + virtual unsigned int getTextureHeight() const; + +protected: + const std::string name_; + Ogre::Overlay * overlay_; + Ogre::PanelOverlayElement * panel_; + Ogre::MaterialPtr panel_material_; + Ogre::TexturePtr texture_; +}; +} // namespace autoware::mission_details_overlay_rviz_plugin + +#endif // OVERLAY_UTILS_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp new file mode 100644 index 0000000000000..843b75e352648 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef REMAINING_DISTANCE_TIME_DISPLAY_HPP_ +#define REMAINING_DISTANCE_TIME_DISPLAY_HPP_ +#include "overlay_utils.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ + +class RemainingDistanceTimeDisplay +{ +public: + RemainingDistanceTimeDisplay(); + void drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect); + void updateRemainingDistanceTimeData( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + +private: + double remaining_distance_; // Internal variable to store remaining distance + double remaining_time_; // Internal variable to store remaining time + + QColor gray = QColor(194, 194, 194); + + QImage icon_dist_; + QImage icon_dist_scaled_; + QImage icon_time_; + QImage icon_time_scaled_; +}; + +} // namespace autoware::mission_details_overlay_rviz_plugin + +#endif // REMAINING_DISTANCE_TIME_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml new file mode 100644 index 0000000000000..1054ac4f516bd --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -0,0 +1,28 @@ + + + + autoware_mission_details_overlay_rviz_plugin + 0.0.1 + + RViz2 plugin for 2D overlays for mission details in the 3D view. Mainly a port of the JSK overlay plugin + (https://github.com/jsk-ros-pkg/jsk_visualization). + + Ahmed Ebrahim + + BSD-3-Clause + + autoware_internal_msgs + boost + rviz_common + rviz_ogre_vendor + rviz_rendering + + ament_lint_auto + autoware_lint_common + + ament_cmake_auto + + + ament_cmake + + diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml new file mode 100644 index 0000000000000..5177b10859704 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml @@ -0,0 +1,5 @@ + + + Mission Details overlay plugin for the 3D view. + + diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp new file mode 100644 index 0000000000000..bafae1727b2f1 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -0,0 +1,212 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "mission_details_display.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ + +MissionDetailsDisplay::MissionDetailsDisplay() +{ + property_width_ = new rviz_common::properties::IntProperty( + "Width", 170, "Width of the overlay", this, SLOT(update_size())); + property_height_ = new rviz_common::properties::IntProperty( + "Height", 100, "Height of the overlay", this, SLOT(update_size())); + property_right_ = new rviz_common::properties::IntProperty( + "Right", 10, "Margin from the right border", this, SLOT(update_size())); + property_top_ = new rviz_common::properties::IntProperty( + "Top", 10, "Margin from the top border", this, SLOT(update_size())); + + // Initialize the component displays + remaining_distance_time_display_ = std::make_unique(); +} + +void MissionDetailsDisplay::onInitialize() +{ + std::lock_guard lock(property_mutex_); + + rviz_common::Display::onInitialize(); + rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_); + static int count = 0; + std::stringstream ss; + ss << "MissionDetailsDisplay" << count++; + overlay_ = + std::make_shared(ss.str()); + overlay_->show(); + update_size(); + + auto rviz_ros_node = context_->getRosNodeAbstraction(); + + remaining_distance_time_topic_property_ = + std::make_unique( + "Remaining Distance and Time Topic", "/planning/mission_remaining_distance_time", + "autoware_internal_msgs/msg/MissionRemainingDistanceTime", + "Topic for Mission Remaining Distance and Time Data", this, + SLOT(topic_updated_remaining_distance_time())); + remaining_distance_time_topic_property_->initialize(rviz_ros_node); +} + +void MissionDetailsDisplay::setupRosSubscriptions() +{ + // Don't create a node, just use the one from the parent class + auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); + + remaining_distance_time_sub_ = + rviz_node_->create_subscription( + remaining_distance_time_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + cb_remaining_distance_time(msg); + }); +} + +MissionDetailsDisplay::~MissionDetailsDisplay() +{ + std::lock_guard lock(property_mutex_); + overlay_.reset(); + + remaining_distance_time_sub_.reset(); + remaining_distance_time_display_.reset(); + remaining_distance_time_topic_property_.reset(); +} + +// mark maybe unused +void MissionDetailsDisplay::update(float wall_dt, float ros_dt) +{ + (void)wall_dt; // Mark as unused + (void)ros_dt; // Mark as unused + + if (!overlay_) { + return; + } + autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage hud = buffer.getQImage(*overlay_); + hud.fill(Qt::transparent); + draw_widget(hud); +} + +void MissionDetailsDisplay::onEnable() +{ + std::lock_guard lock(property_mutex_); + if (overlay_) { + overlay_->show(); + } + setupRosSubscriptions(); +} + +void MissionDetailsDisplay::onDisable() +{ + std::lock_guard lock(property_mutex_); + + remaining_distance_time_sub_.reset(); + + if (overlay_) { + overlay_->hide(); + } +} + +void MissionDetailsDisplay::cb_remaining_distance_time( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) +{ + std::lock_guard lock(property_mutex_); + + if (remaining_distance_time_display_) { + remaining_distance_time_display_->updateRemainingDistanceTimeData(msg); + queueRender(); + } +} + +void MissionDetailsDisplay::draw_widget(QImage & hud) +{ + std::lock_guard lock(property_mutex_); + + if (!overlay_->isVisible()) { + return; + } + + QPainter painter(&hud); + painter.setRenderHint(QPainter::Antialiasing, true); + + QRectF backgroundRect(0, 0, qreal(property_width_->getInt()), qreal(property_height_->getInt())); + draw_rounded_rect(painter, backgroundRect); + + if (remaining_distance_time_display_) { + remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect); + } + + painter.end(); +} + +void MissionDetailsDisplay::draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect) +{ + painter.setRenderHint(QPainter::Antialiasing, true); + QColor colorFromHSV; + colorFromHSV.setHsv(0, 0, 29); + colorFromHSV.setAlphaF(0.60); + + painter.setBrush(colorFromHSV); + + painter.setPen(Qt::NoPen); + painter.drawRoundedRect(backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); +} + +void MissionDetailsDisplay::reset() +{ + rviz_common::Display::reset(); + overlay_->hide(); +} + +void MissionDetailsDisplay::update_size() +{ + std::lock_guard lock(mutex_); + overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); + overlay_->setPosition( + property_right_->getInt(), property_top_->getInt(), HorizontalAlignment::RIGHT, + VerticalAlignment::TOP); + queueRender(); +} + +void MissionDetailsDisplay::topic_updated_remaining_distance_time() +{ + // resubscribe to the topic + remaining_distance_time_sub_.reset(); + auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); + remaining_distance_time_sub_ = + rviz_ros_node->get_raw_node() + ->create_subscription( + remaining_distance_time_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + cb_remaining_distance_time(msg); + }); +} + +} // namespace autoware::mission_details_overlay_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS( + autoware::mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp new file mode 100644 index 0000000000000..68813a5f1140f --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp @@ -0,0 +1,267 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// -*- mode: c++ -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#include "overlay_utils.hpp" + +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ +ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) +: pixel_buffer_(pixel_buffer) +{ + pixel_buffer_->lock(Ogre::HardwareBuffer::HBL_NORMAL); +} + +ScopedPixelBuffer::~ScopedPixelBuffer() +{ + pixel_buffer_->unlock(); +} + +Ogre::HardwarePixelBufferSharedPtr ScopedPixelBuffer::getPixelBuffer() +{ + return pixel_buffer_; +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height) +{ + const Ogre::PixelBox & pixelBox = pixel_buffer_->getCurrentLock(); + Ogre::uint8 * pDest = static_cast(pixelBox.data); + memset(pDest, 0, width * height); + return QImage(pDest, width, height, QImage::Format_ARGB32); +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height, QColor & bg_color) +{ + QImage Hud = getQImage(width, height); + for (unsigned int i = 0; i < width; i++) { + for (unsigned int j = 0; j < height; j++) { + Hud.setPixel(i, j, bg_color.rgba()); + } + } + return Hud; +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight()); +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay, QColor & bg_color) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight(), bg_color); +} + +OverlayObject::OverlayObject(const std::string & name) : name_(name) +{ + std::string material_name = name_ + "Material"; + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + overlay_ = mOverlayMgr->create(name_); + panel_ = static_cast( + mOverlayMgr->createOverlayElement("Panel", name_ + "Panel")); + panel_->setMetricsMode(Ogre::GMM_PIXELS); + + panel_material_ = Ogre::MaterialManager::getSingleton().create( + material_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); + panel_->setMaterialName(panel_material_->getName()); + overlay_->add2D(panel_); +} + +OverlayObject::~OverlayObject() +{ + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + if (mOverlayMgr) { + mOverlayMgr->destroyOverlayElement(panel_); + mOverlayMgr->destroy(overlay_); + } + if (panel_material_) { + panel_material_->unload(); + Ogre::MaterialManager::getSingleton().remove(panel_material_->getName()); + } +} + +std::string OverlayObject::getName() const +{ + return name_; +} + +void OverlayObject::hide() +{ + if (overlay_->isVisible()) { + overlay_->hide(); + } +} + +void OverlayObject::show() +{ + if (!overlay_->isVisible()) { + overlay_->show(); + } +} + +bool OverlayObject::isTextureReady() const +{ + return texture_ != nullptr; +} + +void OverlayObject::updateTextureSize(unsigned int width, unsigned int height) +{ + const std::string texture_name = name_ + "Texture"; + if (width == 0) { + RVIZ_COMMON_LOG_WARNING_STREAM("[OverlayObject] width=0 is specified as texture size"); + width = 1; + } + + if (height == 0) { + RVIZ_COMMON_LOG_WARNING_STREAM("[OverlayObject] height=0 is specified as texture size"); + height = 1; + } + + if (!isTextureReady() || ((width != texture_->getWidth()) || (height != texture_->getHeight()))) { + if (isTextureReady()) { + Ogre::TextureManager::getSingleton().remove(texture_name); + panel_material_->getTechnique(0)->getPass(0)->removeAllTextureUnitStates(); + } + + texture_ = Ogre::TextureManager::getSingleton().createManual( + texture_name, // name + Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, + Ogre::TEX_TYPE_2D, // type + width, height, // width & height of the render window + 0, // number of mipmaps + Ogre::PF_A8R8G8B8, // pixel format chosen to match a format Qt can use + Ogre::TU_DEFAULT // usage + ); + panel_material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_name); + + panel_material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); + } +} + +ScopedPixelBuffer OverlayObject::getBuffer() +{ + if (isTextureReady()) { + return ScopedPixelBuffer(texture_->getBuffer()); + } else { + return ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr()); + } +} + +void OverlayObject::setPosition( + double hor_dist, double ver_dist, HorizontalAlignment hor_alignment, + VerticalAlignment ver_alignment) +{ + // ogre position is always based on the top left corner of the panel, while our position input + // depends on the chosen alignment, i.e. if the horizontal alignment is right, increasing the + // horizontal dist moves the panel to the left (further away from the right border) + double left = 0; + double top = 0; + + switch (hor_alignment) { + case HorizontalAlignment::LEFT: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_LEFT); + left = hor_dist; + break; + case HorizontalAlignment::CENTER: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_CENTER); + left = hor_dist - panel_->getWidth() / 2; + break; + case HorizontalAlignment::RIGHT: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_RIGHT); + left = -hor_dist - panel_->getWidth(); + break; + } + + switch (ver_alignment) { + case VerticalAlignment::BOTTOM: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_BOTTOM); + top = -ver_dist - panel_->getHeight(); + break; + case VerticalAlignment::CENTER: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_CENTER); + top = ver_dist - panel_->getHeight() / 2; + break; + case VerticalAlignment::TOP: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_TOP); + top = ver_dist; + break; + } + + panel_->setPosition(left, top); +} + +void OverlayObject::setDimensions(double width, double height) +{ + panel_->setDimensions(width, height); +} + +bool OverlayObject::isVisible() const +{ + return overlay_->isVisible(); +} + +unsigned int OverlayObject::getTextureWidth() const +{ + if (isTextureReady()) { + return texture_->getWidth(); + } else { + return 0; + } +} + +unsigned int OverlayObject::getTextureHeight() const +{ + if (isTextureReady()) { + return texture_->getHeight(); + } else { + return 0; + } +} +} // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp new file mode 100644 index 0000000000000..86395ef1918bc --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -0,0 +1,157 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "remaining_distance_time_display.hpp" + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ + +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() +: remaining_distance_(0.0), remaining_time_(0.0) +{ + std::string package_path = + ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); + std::string font_path = package_path + "/assets/font/Quicksand/static/Quicksand-Regular.ttf"; + std::string font_path2 = package_path + "/assets/font/Quicksand/static/Quicksand-Bold.ttf"; + int fontId = QFontDatabase::addApplicationFont( + font_path.c_str()); // returns -1 on failure (see docs for more info) + int fontId2 = QFontDatabase::addApplicationFont( + font_path2.c_str()); // returns -1 on failure (see docs for more info) + if (fontId == -1 || fontId2 == -1) { + std::cout << "Failed to load the Quicksand font."; + } + + std::string dist_image = package_path + "/assets/path.png"; + std::string time_image = package_path + "/assets/av_timer.png"; + icon_dist_.load(dist_image.c_str()); + icon_time_.load(time_image.c_str()); + icon_dist_scaled_ = icon_dist_.scaled(28, 28, Qt::KeepAspectRatio, Qt::SmoothTransformation); + icon_time_scaled_ = icon_time_.scaled(28, 28, Qt::KeepAspectRatio, Qt::SmoothTransformation); +} + +void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) +{ + remaining_distance_ = msg->remaining_distance; + remaining_time_ = msg->remaining_time; +} + +void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( + QPainter & painter, const QRectF & backgroundRect) +{ + const QFont font("Quicksand", 15, QFont::Bold); + painter.setFont(font); + + // We'll display the distance and time in two rows + + auto calculate_inner_rect = [](const QRectF & outer_rect, double ratio_x, double ratio_y) { + QSizeF size_inner(outer_rect.width() * ratio_x, outer_rect.height() * ratio_y); + QPointF top_left_inner = QPointF( + outer_rect.center().x() - size_inner.width() / 2, + outer_rect.center().y() - size_inner.height() / 2); + return QRectF(top_left_inner, size_inner); + }; + + QRectF rect_inner = calculate_inner_rect(backgroundRect, 0.7, 0.7); + // Proportionally extend the rect to the right to account for visual icon distance to the left + rect_inner.setWidth(rect_inner.width() * 1.08); + + // Calculate distance row rectangle + const QSizeF distance_row_size(rect_inner.width(), rect_inner.height() / 2); + const QPointF distance_row_top_left(rect_inner.topLeft()); + const QRectF distance_row_rect_outer(distance_row_top_left, distance_row_size); + + // Calculate time row rectangle + const QSizeF time_row_size(rect_inner.width(), rect_inner.height() / 2); + const QPointF time_row_top_left( + rect_inner.topLeft().x(), rect_inner.topLeft().y() + rect_inner.height() / 2); + const QRectF time_row_rect_outer(time_row_top_left, time_row_size); + + const auto rect_time = calculate_inner_rect(time_row_rect_outer, 1.0, 0.9); + const auto rect_dist = calculate_inner_rect(distance_row_rect_outer, 1.0, 0.9); + + auto place_row = [&, this]( + const QRectF & rect, const QImage & icon, const QString & str_value, + const QString & str_unit) { + // order: icon, value, unit + + // place the icon + QPointF icon_top_left(rect.topLeft().x(), rect.center().y() - icon.height() / 2.0); + painter.drawImage(icon_top_left, icon); + + // place the unit text + const float unit_width = 40.0; + QRectF rect_text_unit( + rect.topRight().x() - unit_width, rect.topRight().y(), unit_width, rect.height()); + + painter.setPen(gray); + painter.drawText(rect_text_unit, Qt::AlignLeft | Qt::AlignVCenter, str_unit); + + // place the value text + const double margin_x = 5.0; // margin around the text + + const double used_width = icon.width() + rect_text_unit.width() + margin_x * 2.0; + + QRectF rect_text( + rect.topLeft().x() + icon.width() + margin_x, rect.topLeft().y(), rect.width() - used_width, + rect.height()); + + painter.drawText(rect_text, Qt::AlignRight | Qt::AlignVCenter, str_value); + }; + + // remaining_time_ is in seconds + if (remaining_time_ <= 60) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_, 'f', 0), "sec"); + } else if (remaining_time_ <= 600) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_ / 60.0, 'f', 1), "min"); + } else if (remaining_time_ <= 3600) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_ / 60.0, 'f', 0), "min"); + } else if (remaining_time_ <= 36000) { + place_row( + rect_time, icon_time_scaled_, QString::number(remaining_time_ / 3600.0, 'f', 1), "hrs"); + } else { + place_row( + rect_time, icon_time_scaled_, QString::number(remaining_time_ / 3600.0, 'f', 0), "hrs"); + } + + // remaining_distance_ is in meters + if (remaining_distance_ <= 10) { + place_row(rect_dist, icon_dist_scaled_, QString::number(remaining_distance_, 'f', 1), "m"); + } else if (remaining_distance_ <= 1000) { + place_row(rect_dist, icon_dist_scaled_, QString::number(remaining_distance_, 'f', 0), "m"); + } else if (remaining_distance_ <= 10000) { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 2), "km"); + } else if (remaining_distance_ <= 100000) { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 1), "km"); + } else { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 0), "km"); + } +} + +} // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 710fb20631a45..0e693943a4d03 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -43,5 +43,10 @@ + + + + + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 950ef67865a85..d04a405a61c7b 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -57,6 +57,7 @@ ament_cmake_auto autoware_cmake + autoware_remaining_distance_time_calculator behavior_path_planner behavior_velocity_planner costmap_generator diff --git a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt new file mode 100644 index 0000000000000..d29a153a0ce5d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_remaining_distance_time_calculator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/remaining_distance_time_calculator_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode" + EXECUTABLE ${PROJECT_NAME}_node +) + + +ament_auto_package( + INSTALL_TO_SHARE + config + launch +) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md new file mode 100644 index 0000000000000..694c6764de91c --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -0,0 +1,39 @@ +## Remaining Distance and Time Calculator + +### Role + +This package aims to provide mission remaining distance and remaining time calculations. + +### Activation and Timing + +- The calculations are activated once we have a route planned for a mission in Autoware. +- The calculations are triggered timely based on the `update_rate` parameter. + +### Module Parameters + +| Name | Type | Default Value | Explanation | +| ------------- | ------ | ------------- | --------------------------- | +| `update_rate` | double | 10.0 | Timer callback period. [Hz] | + +### Inner-workings + +#### Remaining Distance Calculation + +- The remaining distance calculation is based on getting the remaining shortest path between the current vehicle pose and goal pose using `lanelet2` routing APIs. +- The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet. + - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet. + - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. +- When there is only one lanelet remaining, the distance is calculated by getting the 2D distance between the current vehicle pose and goal pose. +- Checks are added to handle cases when current lanelet, goal lanelet, or routing graph are not valid to prevent node process die. + - In such cases when, last valid remaining distance and time are maintained. + +#### Remaining Time Calculation + +- The remaining time currently depends on a simple equation of motion by getting the maximum velocity limit. +- The remaining distance is calculated by dividing the remaining distance by the maximum velocity limit. +- A check is added to the remaining time calculation to make sure that maximum velocity limit is greater than zero. This prevents division by zero or getting negative time value. + +### Future Work + +- Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path. +- Engage more sophisticated motion models for more accurate remaining time calculations. diff --git a/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml b/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml new file mode 100644 index 0000000000000..5b8c019de5a20 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + update_rate: 10.0 diff --git a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml new file mode 100644 index 0000000000000..cfb456c57ca41 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml new file mode 100644 index 0000000000000..4f0324b23f299 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -0,0 +1,35 @@ + + + autoware_remaining_distance_time_calculator + 0.1.0 + Calculates and publishes remaining distance and time of the mission. + + Ahmed Ebrahim + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_internal_msgs + autoware_planning_msgs + geometry_msgs + lanelet2_extension + motion_utils + nav_msgs + planning_test_utils + rclcpp + rclcpp_components + route_handler + std_msgs + tier4_autoware_utils + tier4_planning_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json new file mode 100644 index 0000000000000..4b3bc15432d0d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json @@ -0,0 +1,31 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Remaining Distance Time Calculator Parameters", + "type": "object", + "actual_parameters": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "default": 10.0, + "description": "Recalculate remaining distance and time at this rate, Hz" + } + }, + "required": ["update_rate"], + "additionalProperties": false + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/actual_parameters" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp new file mode 100644 index 0000000000000..327bd0ff3b582 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -0,0 +1,188 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "remaining_distance_time_calculator_node.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +namespace autoware::remaining_distance_time_calculator +{ + +RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( + const rclcpp::NodeOptions & options) +: Node("remaining_distance_time_calculator", options), + is_graph_ready_{false}, + has_received_route_{false}, + velocity_limit_{99.99}, + remaining_distance_{0.0}, + remaining_time_{0.0} +{ + using std::placeholders::_1; + + sub_odometry_ = create_subscription( + "~/input/odometry", 1, std::bind(&RemainingDistanceTimeCalculatorNode::on_odometry, this, _1)); + + const auto qos_transient_local = rclcpp::QoS{1}.transient_local(); + + sub_map_ = create_subscription( + "~/input/map", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_map, this, _1)); + sub_route_ = create_subscription( + "~/input/route", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_route, this, _1)); + sub_planning_velocity_ = create_subscription( + "/planning/scenario_planning/current_max_velocity", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1)); + + pub_mission_remaining_distance_time_ = create_publisher( + "~/output/mission_remaining_distance_time", + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); + + node_param_.update_rate = declare_parameter("update_rate"); + + const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); + timer_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); +} + +void RemainingDistanceTimeCalculatorNode::on_map(const HADMapBin::ConstSharedPtr & msg) +{ + route_handler_.setMap(*msg); + lanelet_map_ptr_ = std::make_shared(); + lanelet::utils::conversion::fromBinMsg( + *msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_); + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); + road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); + is_graph_ready_ = true; +} + +void RemainingDistanceTimeCalculatorNode::on_odometry(const Odometry::ConstSharedPtr & msg) +{ + current_vehicle_pose_ = msg->pose.pose; + current_vehicle_velocity_ = msg->twist.twist.linear; +} + +void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstSharedPtr & msg) +{ + goal_pose_ = msg->goal_pose; + has_received_route_ = true; +} + +void RemainingDistanceTimeCalculatorNode::on_velocity_limit( + const VelocityLimit::ConstSharedPtr & msg) +{ + if (msg->max_velocity > 1e-5) { + velocity_limit_ = msg->max_velocity; + } +} + +void RemainingDistanceTimeCalculatorNode::on_timer() +{ + if (is_graph_ready_ && has_received_route_) { + calculate_remaining_distance(); + calculate_remaining_time(); + publish_mission_remaining_distance_time(); + } +} + +void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() +{ + size_t index = 0; + + lanelet::ConstLanelet current_lanelet; + if (!lanelet::utils::query::getClosestLanelet( + road_lanelets_, current_vehicle_pose_, ¤t_lanelet)) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find current lanelet."); + + return; + } + + lanelet::ConstLanelet goal_lanelet; + if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet)) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find goal lanelet."); + + return; + } + + const lanelet::Optional optional_route = + routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + if (!optional_route) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find proper route."); + + return; + } + + lanelet::routing::LaneletPath remaining_shortest_path; + remaining_shortest_path = optional_route->shortestPath(); + + remaining_distance_ = 0.0; + + for (auto & llt : remaining_shortest_path) { + if (remaining_shortest_path.size() == 1) { + remaining_distance_ += + tier4_autoware_utils::calcDistance2d(current_vehicle_pose_.position, goal_pose_.position); + break; + } + + if (index == 0) { + lanelet::ArcCoordinates arc_coord = + lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); + double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + + remaining_distance_ += this_lanelet_length - arc_coord.length; + } else if (index == (remaining_shortest_path.size() - 1)) { + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); + remaining_distance_ += arc_coord.length; + } else { + remaining_distance_ += lanelet::utils::getLaneletLength2d(llt); + } + + index++; + } +} + +void RemainingDistanceTimeCalculatorNode::calculate_remaining_time() +{ + if (velocity_limit_ > 0.0) { + remaining_time_ = remaining_distance_ / velocity_limit_; + } +} + +void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time() +{ + MissionRemainingDistanceTime mission_remaining_distance_time; + + mission_remaining_distance_time.remaining_distance = remaining_distance_; + mission_remaining_distance_time.remaining_time = remaining_time_; + pub_mission_remaining_distance_time_->publish(mission_remaining_distance_time); +} + +} // namespace autoware::remaining_distance_time_calculator + +#include +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp new file mode 100644 index 0000000000000..2a88cdb57abf4 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -0,0 +1,110 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ +#define REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +namespace autoware::remaining_distance_time_calculator +{ + +struct NodeParam +{ + double update_rate{0.0}; +}; + +class RemainingDistanceTimeCalculatorNode : public rclcpp::Node +{ +public: + explicit RemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options); + +private: + using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; + using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using Odometry = nav_msgs::msg::Odometry; + using VelocityLimit = tier4_planning_msgs::msg::VelocityLimit; + using MissionRemainingDistanceTime = autoware_internal_msgs::msg::MissionRemainingDistanceTime; + + rclcpp::Subscription::SharedPtr sub_route_; + rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_odometry_; + rclcpp::Subscription::SharedPtr sub_planning_velocity_; + + rclcpp::Publisher::SharedPtr pub_mission_remaining_distance_time_; + + rclcpp::TimerBase::SharedPtr timer_; + + route_handler::RouteHandler route_handler_; + lanelet::LaneletMapPtr lanelet_map_ptr_; + lanelet::routing::RoutingGraphPtr routing_graph_ptr_; + lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; + lanelet::ConstLanelets road_lanelets_; + bool is_graph_ready_; + + // Data Buffer + geometry_msgs::msg::Pose current_vehicle_pose_; + geometry_msgs::msg::Vector3 current_vehicle_velocity_; + geometry_msgs::msg::Pose goal_pose_; + bool has_received_route_; + double velocity_limit_; + + double remaining_distance_; + double remaining_time_; + + // Parameter + NodeParam node_param_; + + // Callbacks + void on_timer(); + void on_odometry(const Odometry::ConstSharedPtr & msg); + void on_route(const LaneletRoute::ConstSharedPtr & msg); + void on_map(const HADMapBin::ConstSharedPtr & msg); + void on_velocity_limit(const VelocityLimit::ConstSharedPtr & msg); + + /** + * @brief calculate mission remaining distance + */ + void calculate_remaining_distance(); + + /** + * @brief calculate mission remaining time + */ + void calculate_remaining_time(); + + /** + * @brief publish mission remaining distance and time + */ + void publish_mission_remaining_distance_time(); +}; +} // namespace autoware::remaining_distance_time_calculator +#endif // REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ From 7302cd762c98f777023636f9b44ab01210a43f3d Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Mon, 13 May 2024 19:02:42 +0900 Subject: [PATCH 156/192] fix(accel_brake_map_calibrator): fix accel_brake_map_calibrator not to output invalid maps (#6992) Signed-off-by: tomoya.kimura --- .../src/accel_brake_map_calibrator_node.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/vehicle/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp index ecfc312d2bdfd..37f0a11165df3 100644 --- a/vehicle/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp +++ b/vehicle/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp @@ -703,17 +703,19 @@ void AccelBrakeMapCalibrator::takeConsistencyOfAccelMap() { const double bit = std::pow(1e-01, precision_); for (std::size_t ped_idx = 0; ped_idx < update_accel_map_value_.size() - 1; ped_idx++) { - for (std::size_t vel_idx = 0; vel_idx < update_accel_map_value_.at(0).size() - 1; vel_idx++) { + for (std::size_t vel_idx = update_accel_map_value_.at(0).size() - 1;; vel_idx--) { + if (vel_idx == 0) break; + const double current_acc = update_accel_map_value_.at(ped_idx).at(vel_idx); const double next_ped_acc = update_accel_map_value_.at(ped_idx + 1).at(vel_idx); - const double next_vel_acc = update_accel_map_value_.at(ped_idx).at(vel_idx + 1); + const double prev_vel_acc = update_accel_map_value_.at(ped_idx).at(vel_idx - 1); - if (current_acc <= next_vel_acc) { + if (current_acc + bit >= prev_vel_acc) { // the higher the velocity, the lower the acceleration - update_accel_map_value_.at(ped_idx).at(vel_idx + 1) = current_acc - bit; + update_accel_map_value_.at(ped_idx).at(vel_idx - 1) = current_acc + bit; } - if (current_acc >= next_ped_acc) { + if (current_acc + bit >= next_ped_acc) { // the higher the accel pedal, the higher the acceleration update_accel_map_value_.at(ped_idx + 1).at(vel_idx) = current_acc + bit; } From 2f2438ecdae686d9c7d041744677cb332a375b17 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 13 May 2024 19:58:46 +0900 Subject: [PATCH 157/192] feat(mrm_emergency_stop_operator): add support for real time param reconfigure for mrm_emergency_stop (#6994) add support for real time param reconfigure for mrm_emergency_stop Signed-off-by: Daniel Sanchez --- .../mrm_emergency_stop_operator_core.hpp | 5 +++++ .../mrm_emergency_stop_operator/package.xml | 1 + .../mrm_emergency_stop_operator_core.cpp | 19 +++++++++++++++++++ 3 files changed, 25 insertions(+) diff --git a/system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp b/system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp index 19e41397fe4da..5b91f56973ae9 100644 --- a/system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp +++ b/system/mrm_emergency_stop_operator/include/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp @@ -27,6 +27,7 @@ // ROS 2 core #include +#include namespace mrm_emergency_stop_operator { using autoware_auto_control_msgs::msg::AckermannControlCommand; @@ -48,6 +49,10 @@ class MrmEmergencyStopOperator : public rclcpp::Node private: // Parameters Parameters params_; + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + + rcl_interfaces::msg::SetParametersResult onParameter( + const std::vector & parameters); // Subscriber rclcpp::Subscription::SharedPtr sub_control_cmd_; diff --git a/system/mrm_emergency_stop_operator/package.xml b/system/mrm_emergency_stop_operator/package.xml index 251e79a07a73d..6ca4e3a815f72 100644 --- a/system/mrm_emergency_stop_operator/package.xml +++ b/system/mrm_emergency_stop_operator/package.xml @@ -17,6 +17,7 @@ rclcpp_components std_msgs std_srvs + tier4_autoware_utils tier4_system_msgs ament_lint_auto diff --git a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp b/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp index 08814dbbd710d..9ee9d7a685df3 100644 --- a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp +++ b/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp @@ -14,6 +14,8 @@ #include "mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.hpp" +#include + namespace mrm_emergency_stop_operator { @@ -49,6 +51,23 @@ MrmEmergencyStopOperator::MrmEmergencyStopOperator(const rclcpp::NodeOptions & n // Initialize status_.state = MrmBehaviorStatus::AVAILABLE; is_prev_control_cmd_subscribed_ = false; + + // Parameter Callback + set_param_res_ = add_on_set_parameters_callback( + std::bind(&MrmEmergencyStopOperator::onParameter, this, std::placeholders::_1)); +} + +rcl_interfaces::msg::SetParametersResult MrmEmergencyStopOperator::onParameter( + const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + updateParam(parameters, "target_acceleration", params_.target_acceleration); + updateParam(parameters, "target_jerk", params_.target_jerk); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; } void MrmEmergencyStopOperator::onControlCommand(AckermannControlCommand::ConstSharedPtr msg) From aff5370c45853810a2ac075a5c21d010f0c30439 Mon Sep 17 00:00:00 2001 From: Dmitrii Koldaev <39071246+dkoldaev@users.noreply.github.com> Date: Mon, 13 May 2024 20:05:24 +0900 Subject: [PATCH 158/192] feat(map_based_prediction): incorporate crosswalk user history (#6905) Signed-off-by: Dmitrii Koldaev --- .../config/map_based_prediction.param.yaml | 3 + .../map_based_prediction_node.hpp | 25 +- .../src/map_based_prediction_node.cpp | 245 +++++++++++++----- 3 files changed, 209 insertions(+), 64 deletions(-) diff --git a/perception/map_based_prediction/config/map_based_prediction.param.yaml b/perception/map_based_prediction/config/map_based_prediction.param.yaml index f8ad371ab92a6..a1b776bdb6393 100644 --- a/perception/map_based_prediction/config/map_based_prediction.param.yaml +++ b/perception/map_based_prediction/config/map_based_prediction.param.yaml @@ -27,6 +27,9 @@ timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] values of map # parameter for shoulder lane prediction prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8 + use_crosswalk_user_history: + match_lost_and_appeared_users: false + remember_lost_users: false # parameters for lc prediction lane_change_detection: diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 829c4d6e4a114..213f18d63ef3a 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -48,6 +48,7 @@ #include #include #include +#include #include #include @@ -85,6 +86,12 @@ struct ObjectData Maneuver::UNINITIALIZED}; // output maneuver considering previous one shot maneuvers }; +struct CrosswalkUserData +{ + std_msgs::msg::Header header; + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; +}; + struct LaneletData { lanelet::Lanelet lanelet; @@ -135,8 +142,10 @@ class MapBasedPredictionNode : public rclcpp::Node std::unique_ptr processing_time_publisher_; // Object History - std::unordered_map> objects_history_; + std::unordered_map> road_users_history; std::map, rclcpp::Time> stopped_times_against_green_; + std::unordered_map> crosswalk_users_history_; + std::unordered_map known_matches_; // Lanelet Map Pointers std::shared_ptr lanelet_map_ptr_; @@ -200,6 +209,9 @@ class MapBasedPredictionNode : public rclcpp::Node std::vector distance_set_for_no_intention_to_walk_; std::vector timeout_set_for_no_intention_to_walk_; + bool match_lost_and_appeared_crosswalk_users_; + bool remember_lost_crosswalk_users_; + std::unique_ptr published_time_publisher_; // Member Functions @@ -222,8 +234,7 @@ class MapBasedPredictionNode : public rclcpp::Node PredictedObject getPredictedObjectAsCrosswalkUser(const TrackedObject & object); - void removeOldObjectsHistory( - const double current_time, const TrackedObjects::ConstSharedPtr in_objects); + void removeStaleTrafficLightInfo(const TrackedObjects::ConstSharedPtr in_objects); LaneletsData getCurrentLanelets(const TrackedObject & object); bool checkCloseLaneletCondition( @@ -232,10 +243,14 @@ class MapBasedPredictionNode : public rclcpp::Node const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const; void updateObjectData(TrackedObject & object); - void updateObjectsHistory( + void updateRoadUsersHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const LaneletsData & current_lanelets_data); - + void updateCrosswalkUserHistory( + const std_msgs::msg::Header & header, const TrackedObject & object, + const std::string & object_id); + std::string tryMatchNewObjectToDisappeared( + const std::string & object_id, std::unordered_map & current_users); std::vector getPredictedReferencePath( const TrackedObject & object, const LaneletsData & current_lanelets_data, const double object_detected_time); diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 8f080ba0edc35..b55ea72402d74 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -585,6 +585,52 @@ bool hasPotentialToReach( return false; } +template +std::unordered_set removeOldObjectsHistory( + const double current_time, const double buffer_time, + std::unordered_map> & target_objects) +{ + std::unordered_set invalid_object_id; + for (auto iter = target_objects.begin(); iter != target_objects.end(); ++iter) { + const std::string object_id = iter->first; + std::deque & object_data = iter->second; + + // If object data is empty, we are going to delete the buffer for the obstacle + if (object_data.empty()) { + invalid_object_id.insert(object_id); + continue; + } + + const double latest_object_time = rclcpp::Time(object_data.back().header.stamp).seconds(); + + // Delete Old Objects + if (current_time - latest_object_time > buffer_time) { + invalid_object_id.insert(object_id); + continue; + } + + // Delete old information + while (!object_data.empty()) { + const double post_object_time = rclcpp::Time(object_data.front().header.stamp).seconds(); + if (current_time - post_object_time <= buffer_time) { + break; + } + object_data.pop_front(); + } + + if (object_data.empty()) { + invalid_object_id.insert(object_id); + continue; + } + } + + for (const auto & key : invalid_object_id) { + target_objects.erase(key); + } + + return invalid_object_id; +} + /** * @brief change label for prediction * @@ -776,7 +822,10 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ * parameter control the estimated path length = vx * th * (rate) */ prediction_time_horizon_rate_for_validate_lane_length_ = declare_parameter("prediction_time_horizon_rate_for_validate_shoulder_lane_length"); - + match_lost_and_appeared_crosswalk_users_ = + declare_parameter("use_crosswalk_user_history.match_lost_and_appeared_users"); + remember_lost_crosswalk_users_ = + declare_parameter("use_crosswalk_user_history.remember_lost_users"); use_vehicle_acceleration_ = declare_parameter("use_vehicle_acceleration"); speed_limit_multiplier_ = declare_parameter("speed_limit_multiplier"); acceleration_exponential_half_life_ = @@ -918,7 +967,19 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // Remove old objects information in object history const double objects_detected_time = rclcpp::Time(in_objects->header.stamp).seconds(); - removeOldObjectsHistory(objects_detected_time, in_objects); + removeOldObjectsHistory(objects_detected_time, object_buffer_time_length_, road_users_history); + removeStaleTrafficLightInfo(in_objects); + + auto invalidated_crosswalk_users = removeOldObjectsHistory( + objects_detected_time, object_buffer_time_length_, crosswalk_users_history_); + // delete matches that point to invalid object + for (auto it = known_matches_.begin(); it != known_matches_.end();) { + if (invalidated_crosswalk_users.count(it->second)) { + it = known_matches_.erase(it); + } else { + ++it; + } + } // result output PredictedObjects output; @@ -928,6 +989,20 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // result debug visualization_msgs::msg::MarkerArray debug_markers; + // get current crosswalk users for later prediction + std::unordered_map current_crosswalk_users; + for (const auto & object : in_objects->objects) { + const auto label_for_prediction = + changeLabelForPrediction(object.classification.front().label, object, lanelet_map_ptr_); + if ( + label_for_prediction == ObjectClassification::PEDESTRIAN || + label_for_prediction == ObjectClassification::BICYCLE) { + const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); + current_crosswalk_users.emplace(object_id, object); + } + } + std::unordered_set predicted_crosswalk_users_ids; + for (const auto & object : in_objects->objects) { std::string object_id = tier4_autoware_utils::toHexString(object.object_id); TrackedObject transformed_object = object; @@ -948,6 +1023,12 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt switch (label) { case ObjectClassification::PEDESTRIAN: case ObjectClassification::BICYCLE: { + std::string object_id = tier4_autoware_utils::toHexString(object.object_id); + if (match_lost_and_appeared_crosswalk_users_) { + object_id = tryMatchNewObjectToDisappeared(object_id, current_crosswalk_users); + } + predicted_crosswalk_users_ids.insert(object_id); + updateCrosswalkUserHistory(output.header, transformed_object, object_id); const auto predicted_object_crosswalk = getPredictedObjectAsCrosswalkUser(transformed_object); output.objects.push_back(predicted_object_crosswalk); @@ -965,7 +1046,7 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt const auto current_lanelets = getCurrentLanelets(transformed_object); // Update Objects History - updateObjectsHistory(output.header, transformed_object, current_lanelets); + updateRoadUsersHistory(output.header, transformed_object, current_lanelets); // For off lane obstacles if (current_lanelets.empty()) { @@ -1113,6 +1194,19 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt } } + // process lost crosswalk users to tackle unstable detection + if (remember_lost_crosswalk_users_) { + for (const auto & [id, crosswalk_user] : crosswalk_users_history_) { + // get a predicted path for crosswalk users in history who didn't get path yet using latest + // message + if (predicted_crosswalk_users_ids.count(id) == 0) { + const auto predicted_object = + getPredictedObjectAsCrosswalkUser(crosswalk_user.back().tracked_object); + output.objects.push_back(predicted_object); + } + } + } + // Publish Results pub_objects_->publish(output); published_time_publisher_->publish_if_subscribed(pub_objects_, output.header.stamp); @@ -1125,6 +1219,79 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt "debug/processing_time_ms", processing_time_ms); } +void MapBasedPredictionNode::updateCrosswalkUserHistory( + const std_msgs::msg::Header & header, const TrackedObject & object, const std::string & object_id) +{ + CrosswalkUserData crosswalk_user_data; + crosswalk_user_data.header = header; + crosswalk_user_data.tracked_object = object; + + if (crosswalk_users_history_.count(object_id) == 0) { + crosswalk_users_history_.emplace(object_id, std::deque{crosswalk_user_data}); + return; + } + + crosswalk_users_history_.at(object_id).push_back(crosswalk_user_data); +} + +std::string MapBasedPredictionNode::tryMatchNewObjectToDisappeared( + const std::string & object_id, std::unordered_map & current_users) +{ + const auto known_match_opt = [&]() -> std::optional { + if (!known_matches_.count(object_id)) { + return std::nullopt; + } + + std::string match_id = known_matches_[object_id]; + // object in the history is already matched to something (possibly itself) + if (crosswalk_users_history_.count(match_id)) { + // avoid matching two appeared users to one user in history + current_users[match_id] = crosswalk_users_history_[match_id].back().tracked_object; + return match_id; + } else { + RCLCPP_WARN_STREAM( + get_logger(), "Crosswalk user was " + << object_id << "was matched to " << match_id + << " but history for the crosswalk user was deleted. Rematching"); + } + return std::nullopt; + }(); + // early return if the match is already known + if (known_match_opt.has_value()) { + return known_match_opt.value(); + } + + std::string match_id = object_id; + double best_score = std::numeric_limits::max(); + const auto object_pos = current_users[object_id].kinematics.pose_with_covariance.pose.position; + for (const auto & [user_id, user_history] : crosswalk_users_history_) { + // user present in current_users and will be matched to itself + if (current_users.count(user_id)) { + continue; + } + // TODO(dkoldaev): implement more sophisticated scoring, for now simply dst to last position in + // history + const auto match_candidate_pos = + user_history.back().tracked_object.kinematics.pose_with_covariance.pose.position; + const double score = + std::hypot(match_candidate_pos.x - object_pos.x, match_candidate_pos.y - object_pos.y); + if (score < best_score) { + best_score = score; + match_id = user_id; + } + } + + if (object_id != match_id) { + RCLCPP_INFO_STREAM( + get_logger(), "[Map Based Prediction]: Matched " << object_id << " to " << match_id); + // avoid matching two appeared users to one user in history + current_users[match_id] = crosswalk_users_history_[match_id].back().tracked_object; + } + + known_matches_[object_id] = match_id; + return match_id; +} + bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predicted_path) { const lanelet::ConstLineStrings3d & all_fences = @@ -1345,49 +1512,9 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) return; } -void MapBasedPredictionNode::removeOldObjectsHistory( - const double current_time, const TrackedObjects::ConstSharedPtr in_objects) +void MapBasedPredictionNode::removeStaleTrafficLightInfo( + const TrackedObjects::ConstSharedPtr in_objects) { - std::vector invalid_object_id; - for (auto iter = objects_history_.begin(); iter != objects_history_.end(); ++iter) { - const std::string object_id = iter->first; - std::deque & object_data = iter->second; - - // If object data is empty, we are going to delete the buffer for the obstacle - if (object_data.empty()) { - invalid_object_id.push_back(object_id); - continue; - } - - const double latest_object_time = rclcpp::Time(object_data.back().header.stamp).seconds(); - - // Delete Old Objects - if (current_time - latest_object_time > object_buffer_time_length_) { - invalid_object_id.push_back(object_id); - continue; - } - - // Delete old information - while (!object_data.empty()) { - const double post_object_time = rclcpp::Time(object_data.front().header.stamp).seconds(); - if (current_time - post_object_time > object_buffer_time_length_) { - // Delete Old Position - object_data.pop_front(); - } else { - break; - } - } - - if (object_data.empty()) { - invalid_object_id.push_back(object_id); - continue; - } - } - - for (const auto & key : invalid_object_id) { - objects_history_.erase(key); - } - for (auto it = stopped_times_against_green_.begin(); it != stopped_times_against_green_.end();) { const bool isDisappeared = std::none_of( in_objects->objects.begin(), in_objects->objects.end(), @@ -1502,9 +1629,9 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( // If the object is in the objects history, we check if the target lanelet is // inside the current lanelets id or following lanelets const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); - if (objects_history_.count(object_id) != 0) { + if (road_users_history.count(object_id) != 0) { const std::vector & possible_lanelet = - objects_history_.at(object_id).back().future_possible_lanelets; + road_users_history.at(object_id).back().future_possible_lanelets; bool not_in_possible_lanelet = std::find(possible_lanelet.begin(), possible_lanelet.end(), lanelet.second) == @@ -1571,7 +1698,7 @@ float MapBasedPredictionNode::calculateLocalLikelihood( return static_cast(1.0 / dist); } -void MapBasedPredictionNode::updateObjectsHistory( +void MapBasedPredictionNode::updateRoadUsersHistory( const std_msgs::msg::Header & header, const TrackedObject & object, const LaneletsData & current_lanelets_data) { @@ -1595,13 +1722,13 @@ void MapBasedPredictionNode::updateObjectsHistory( single_object_data.lateral_kinematics_set[current_lane] = lateral_kinematics; } - if (objects_history_.count(object_id) == 0) { + if (road_users_history.count(object_id) == 0) { // New Object(Create a new object in object histories) std::deque object_data = {single_object_data}; - objects_history_.emplace(object_id, object_data); + road_users_history.emplace(object_id, object_data); } else { // Object that is already in the object buffer - std::deque & object_data = objects_history_.at(object_id); + std::deque & object_data = road_users_history.at(object_id); // get previous object data and update const auto prev_object_data = object_data.back(); updateLateralKinematicsVector( @@ -1789,10 +1916,10 @@ Maneuver MapBasedPredictionNode::predictObjectManeuver( }(); const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); - if (objects_history_.count(object_id) == 0) { + if (road_users_history.count(object_id) == 0) { return current_maneuver; } - auto & object_info = objects_history_.at(object_id); + auto & object_info = road_users_history.at(object_id); // update maneuver in object history if (!object_info.empty()) { @@ -1828,11 +1955,11 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByTimeToLaneChange( { // Step1. Check if we have the object in the buffer const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); - if (objects_history_.count(object_id) == 0) { + if (road_users_history.count(object_id) == 0) { return Maneuver::LANE_FOLLOW; } - const std::deque & object_info = objects_history_.at(object_id); + const std::deque & object_info = road_users_history.at(object_id); // Step2. Check if object history length longer than history_time_length const int latest_id = static_cast(object_info.size()) - 1; @@ -1899,11 +2026,11 @@ Maneuver MapBasedPredictionNode::predictObjectManeuverByLatDiffDistance( { // Step1. Check if we have the object in the buffer const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); - if (objects_history_.count(object_id) == 0) { + if (road_users_history.count(object_id) == 0) { return Maneuver::LANE_FOLLOW; } - const std::deque & object_info = objects_history_.at(object_id); + const std::deque & object_info = road_users_history.at(object_id); const double current_time = (this->get_clock()->now()).seconds(); // Step2. Get the previous id @@ -2060,12 +2187,12 @@ void MapBasedPredictionNode::updateFuturePossibleLanelets( const TrackedObject & object, const lanelet::routing::LaneletPaths & paths) { std::string object_id = tier4_autoware_utils::toHexString(object.object_id); - if (objects_history_.count(object_id) == 0) { + if (road_users_history.count(object_id) == 0) { return; } std::vector & possible_lanelets = - objects_history_.at(object_id).back().future_possible_lanelets; + road_users_history.at(object_id).back().future_possible_lanelets; for (const auto & path : paths) { for (const auto & lanelet : path) { bool not_in_buffer = std::find(possible_lanelets.begin(), possible_lanelets.end(), lanelet) == From d9b3df7da042fdc9759f330404b73a4f9a91167b Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 13 May 2024 20:59:20 +0900 Subject: [PATCH 159/192] feat(out_of_lane): add option to ignore overlaps in lane changes (#6991) Signed-off-by: Maxime CLEMENT --- .../config/out_of_lane.param.yaml | 1 + .../src/lanelets_selection.cpp | 11 +++++++++++ .../src/manager.cpp | 2 ++ .../src/types.hpp | 2 ++ 4 files changed, 16 insertions(+) diff --git a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml index 1b483b95510ed..e4d08367ee4f7 100644 --- a/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml +++ b/planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -3,6 +3,7 @@ out_of_lane: # module to stop or slowdown before overlapping another lane with other objects mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc" skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane + ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored threshold: time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp index 738ea22106b29..67d8a79a63f03 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -78,6 +78,15 @@ lanelet::ConstLanelets calculate_path_lanelets( return path_lanelets; } +void add_lane_changeable_lanelets( + lanelet::ConstLanelets & lanelets_to_ignore, const lanelet::ConstLanelets & path_lanelets, + const route_handler::RouteHandler & route_handler) +{ + for (const auto & path_lanelet : path_lanelets) + for (const auto & ll : route_handler.getLaneChangeableNeighbors(path_lanelet)) + if (!contains_lanelet(lanelets_to_ignore, ll.id())) lanelets_to_ignore.push_back(ll); +} + lanelet::ConstLanelets calculate_ignored_lanelets( const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler, const PlannerParam & params) @@ -93,6 +102,8 @@ lanelet::ConstLanelets calculate_ignored_lanelets( const auto is_path_lanelet = contains_lanelet(path_lanelets, l.second.id()); if (!is_path_lanelet) ignored_lanelets.push_back(l.second); } + if (params.ignore_overlaps_over_lane_changeable_lanelets) + add_lane_changeable_lanelets(ignored_lanelets, path_lanelets, route_handler); return ignored_lanelets; } diff --git a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp index 8055f5c9106ef..7d764722405af 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/manager.cpp @@ -38,6 +38,8 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node) pp.mode = getOrDeclareParameter(node, ns + ".mode"); pp.skip_if_already_overlapping = getOrDeclareParameter(node, ns + ".skip_if_already_overlapping"); + pp.ignore_overlaps_over_lane_changeable_lanelets = + getOrDeclareParameter(node, ns + ".ignore_overlaps_over_lane_changeable_lanelets"); pp.time_threshold = getOrDeclareParameter(node, ns + ".threshold.time_threshold"); pp.intervals_ego_buffer = getOrDeclareParameter(node, ns + ".intervals.ego_time_buffer"); diff --git a/planning/behavior_velocity_out_of_lane_module/src/types.hpp b/planning/behavior_velocity_out_of_lane_module/src/types.hpp index d482870e5ce18..ff690699ee638 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/types.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/types.hpp @@ -39,6 +39,8 @@ struct PlannerParam std::string mode; // mode used to consider a conflict with an object bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps // another lane + bool ignore_overlaps_over_lane_changeable_lanelets; // if true, overlaps on lane changeable + // lanelets are ignored double time_threshold; // [s](mode="threshold") objects time threshold double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range From b6bd75073a61757b6212c578409363680df2ddd8 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 14 May 2024 01:13:18 +0900 Subject: [PATCH 160/192] feat(tier4_perception_launch): downsample perception input pointcloud (#6886) * feat: downsample perception input pointcloud Signed-off-by: yoshiri * fix: add group if to switch downsample node Signed-off-by: yoshiri * fix: add test and exec depend Signed-off-by: yoshiri * Update launch/tier4_perception_launch/launch/perception.launch.xml Co-authored-by: Yukihiro Saito * chore: refactor perception.launch.xml Signed-off-by: yoshiri --------- Signed-off-by: yoshiri Co-authored-by: Yukihiro Saito --- .../launch/perception.launch.xml | 29 +++++++++++++++++-- 1 file changed, 26 insertions(+), 3 deletions(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 71fb38f883144..d020bfe0d6786 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -121,9 +121,32 @@ description="if use_radar_tracking_fusion:=true, radar information is merged in tracking launch. Otherwise, radar information is merged in detection launch." /> + + + + + + + + + + + + + + + + + + + + + + + @@ -133,7 +156,7 @@ - + @@ -142,7 +165,7 @@ - + @@ -162,7 +185,7 @@ - + From a3c1ed33a47afb7e57647aeb22bc9871ef8b1135 Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Tue, 14 May 2024 10:36:53 +0900 Subject: [PATCH 161/192] feat(tier4_perception_launch): fix typo error (#6999) * feat: downsample perception input pointcloud Signed-off-by: yoshiri * fix: add group if to switch downsample node Signed-off-by: yoshiri * fix: add test and exec depend Signed-off-by: yoshiri * Update launch/tier4_perception_launch/launch/perception.launch.xml Co-authored-by: Yukihiro Saito * chore: refactor perception.launch.xml Signed-off-by: yoshiri * fix: fix name Signed-off-by: yoshiri --------- Signed-off-by: yoshiri Co-authored-by: Yukihiro Saito --- launch/tier4_perception_launch/launch/perception.launch.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index d020bfe0d6786..d60f54c2e641a 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -132,9 +132,9 @@ - - - + + + From a714f945b9a7856fb574ad67a9e6ec84957cf78d Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 14 May 2024 13:26:48 +0900 Subject: [PATCH 162/192] refactor(behavior_velocity_occlusion_spot_module): reduce cppcheck warning (#6987) * remove unnecessary if branch Signed-off-by: Ryuta Kambe * add const for const variable Signed-off-by: Ryuta Kambe * remove redundant assignment Signed-off-by: Ryuta Kambe * remove redundant if branch Signed-off-by: Ryuta Kambe * underflow check Signed-off-by: Ryuta Kambe * use const for const parameter Signed-off-by: Ryuta Kambe * style(pre-commit): autofix * delete unnecessary pointsToRays function Signed-off-by: Ryuta Kambe --------- Signed-off-by: Ryuta Kambe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/debug.cpp | 2 +- .../src/grid_utils.cpp | 66 +++++-------------- .../src/occlusion_spot_utils.cpp | 6 +- .../src/occlusion_spot_utils.hpp | 3 +- 4 files changed, 24 insertions(+), 53 deletions(-) diff --git a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp index a6e13d0dfdcdc..f4d3fbf6cc2c1 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp @@ -118,7 +118,7 @@ MarkerArray makeDebugInfoMarkers(T & debug_data) { // add slow down markers for occlusion spot MarkerArray debug_markers; - auto & possible_collisions = debug_data.possible_collisions; + const auto & possible_collisions = debug_data.possible_collisions; size_t id = 0; // draw obstacle collision for (const auto & pc : possible_collisions) { diff --git a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp index 9f580149be7ae..c8adb324b9055 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/grid_utils.cpp @@ -43,23 +43,6 @@ Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius) return line_poly; } -std::vector> pointsToRays( - const grid_map::Position p0, const grid_map::Position p1, const double radius) -{ - using grid_map::Position; - std::vector> lines; - const double angle = atan2(p0.y() - p1.y(), p0.x() - p1.x()); - const double r = radius; - lines.emplace_back(std::make_pair(p0, p1)); - lines.emplace_back(std::make_pair( - Position(p0.x() + r * sin(angle), p0.y() - r * cos(angle)), - Position(p1.x() + r * sin(angle), p1.y() - r * cos(angle)))); - lines.emplace_back(std::make_pair( - Position(p1.x() - r * sin(angle), p1.y() + r * cos(angle)), - Position(p0.x() - r * sin(angle), p0.y() + r * cos(angle)))); - return lines; -} - void findOcclusionSpots( std::vector & occlusion_spot_positions, const grid_map::GridMap & grid, const Polygon2d & polygon, [[maybe_unused]] double min_size) @@ -86,36 +69,21 @@ bool isCollisionFree( const double radius) { const grid_map::Matrix & grid_data = grid["layer"]; - bool polys = true; try { - if (polys) { - Point2d occlusion_p = {p1.x(), p1.y()}; - Point2d collision_p = {p2.x(), p2.y()}; - Polygon2d polygon = pointsToPoly(occlusion_p, collision_p, radius); - grid_map::Polygon grid_polygon; - for (const auto & point : polygon.outer()) { - grid_polygon.addVertex({point.x(), point.y()}); - } - for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd(); - ++iterator) { - const grid_map::Index & index = *iterator; - if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) { - return false; - } - } - } else { - std::vector> lines = - pointsToRays(p1, p2, radius); - for (const auto & p : lines) { - for (grid_map::LineIterator iterator(grid, p.first, p.second); !iterator.isPastEnd(); - ++iterator) { - const grid_map::Index & index = *iterator; - if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) { - return false; - } - } + Point2d occlusion_p = {p1.x(), p1.y()}; + Point2d collision_p = {p2.x(), p2.y()}; + Polygon2d polygon = pointsToPoly(occlusion_p, collision_p, radius); + grid_map::Polygon grid_polygon; + for (const auto & point : polygon.outer()) { + grid_polygon.addVertex({point.x(), point.y()}); + } + for (grid_map_utils::PolygonIterator iterator(grid, grid_polygon); !iterator.isPastEnd(); + ++iterator) { + const grid_map::Index & index = *iterator; + if (grid_data(index.x(), index.y()) == grid_utils::occlusion_cost_value::OCCUPIED) { + return false; } - } // polys or not + } } catch (const std::invalid_argument & e) { std::cerr << e.what() << std::endl; return false; @@ -324,7 +292,7 @@ void imageToOccupancyGrid(const cv::Mat & cv_image, nav_msgs::msg::OccupancyGrid const int idx = (height - 1 - y) + (width - 1 - x) * height; unsigned char intensity = cv_image.at(y, x); if (intensity == grid_utils::occlusion_cost_value::FREE_SPACE) { - intensity = grid_utils::occlusion_cost_value::FREE_SPACE; + // do nothing } else if (intensity == grid_utils::occlusion_cost_value::UNKNOWN_IMAGE) { intensity = grid_utils::occlusion_cost_value::UNKNOWN; } else if (intensity == grid_utils::occlusion_cost_value::OCCUPIED_IMAGE) { @@ -348,14 +316,12 @@ void toQuantizedImage( unsigned char intensity = occupancy_grid.data.at(idx); if (intensity <= param.free_space_max) { continue; - } else if (param.free_space_max < intensity && intensity < param.occupied_min) { + } else if (intensity < param.occupied_min) { intensity = grid_utils::occlusion_cost_value::UNKNOWN_IMAGE; occlusion_image->at(y, x) = intensity; - } else if (param.occupied_min <= intensity) { + } else { intensity = grid_utils::occlusion_cost_value::OCCUPIED_IMAGE; border_image->at(y, x) = intensity; - } else { - throw std::logic_error("behavior_velocity[occlusion_spot_grid]: invalid if clause"); } } } diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp index f38768ce26da4..22b93c2c0236c 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp @@ -117,6 +117,9 @@ void calcSlowDownPointsForPossibleCollision( size_t collision_index = 0; double dist_along_path_point = offset; double dist_along_next_path_point = dist_along_path_point; + if (path.points.size() == 0) { + return; + } for (size_t idx = closest_idx; idx < path.points.size() - 1; idx++) { auto p_prev = path.points.at(idx).point; auto p_next = path.points.at(idx + 1).point; @@ -426,7 +429,8 @@ bool isBlockedByPartition(const LineString2d & direction, const BasicPolygons2d std::optional generateOneNotableCollisionFromOcclusionSpot( const grid_map::GridMap & grid, const std::vector & occlusion_spot_positions, const double offset_from_start_to_ego, const Point2d base_point, - const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data) + const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, + const DebugData & debug_data) { const double baselink_to_front = param.baselink_to_front; const double right_overhang = param.right_overhang; diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp index ec58e38dec45a..47242b70f0cbd 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp @@ -241,7 +241,8 @@ void calcSlowDownPointsForPossibleCollision( std::optional generateOneNotableCollisionFromOcclusionSpot( const grid_map::GridMap & grid, const std::vector & occlusion_spot_positions, const double offset_from_start_to_ego, const Point2d base_point, - const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, DebugData & debug_data); + const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param, + const DebugData & debug_data); //!< @brief generate possible collisions coming from occlusion spots on the side of the path bool generatePossibleCollisionsFromGridMap( std::vector & possible_collisions, const grid_map::GridMap & grid, From ac5190bf6b2e76fc56dcd2b5879a29a55b4c9066 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 14 May 2024 13:35:34 +0900 Subject: [PATCH 163/192] fix(ndt_scan_matcher): improved tpe (#6990) * Improved tpe Signed-off-by: Shintaro Sakoda * Added name in TODO Signed-off-by: Shintaro Sakoda * Fixed tpe test Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix --------- Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/ndt_scan_matcher.param.yaml | 2 +- .../schema/sub/initial_pose_estimation.json | 2 +- .../src/ndt_scan_matcher_core.cpp | 72 +++----- .../tree_structured_parzen_estimator.hpp | 27 +-- .../src/tree_structured_parzen_estimator.cpp | 172 +++++++----------- .../test/test_tpe.cpp | 16 +- 6 files changed, 117 insertions(+), 174 deletions(-) diff --git a/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml b/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml index 241892e67b66c..ec80a0ef79c69 100644 --- a/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml +++ b/localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml @@ -48,7 +48,7 @@ # The number of initial random trials in the TPE (Tree-Structured Parzen Estimator). # This value should be equal to or less than 'initial_estimate_particles_num' and more than 0. # If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search. - n_startup_trials: 20 + n_startup_trials: 100 validation: diff --git a/localization/ndt_scan_matcher/schema/sub/initial_pose_estimation.json b/localization/ndt_scan_matcher/schema/sub/initial_pose_estimation.json index 9817f3145bbd3..20250d05782f9 100644 --- a/localization/ndt_scan_matcher/schema/sub/initial_pose_estimation.json +++ b/localization/ndt_scan_matcher/schema/sub/initial_pose_estimation.json @@ -14,7 +14,7 @@ "n_startup_trials": { "type": "number", "description": "The number of initial random trials in the TPE (Tree-Structured Parzen Estimator). This value should be equal to or less than 'initial_estimate_particles_num' and more than 0. If it is equal to 'initial_estimate_particles_num', the search will be the same as a full random search.", - "default": 20, + "default": 100, "minimum": 1 } }, diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 1e3188a15acc9..8e7685180c1f9 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -22,8 +22,6 @@ #include #include -#include - #include #ifdef ROS_DISTRO_GALACTIC @@ -988,34 +986,20 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( const double stddev_roll = std::sqrt(covariance(3, 3)); const double stddev_pitch = std::sqrt(covariance(4, 4)); - // Let phi be the cumulative distribution function of the standard normal distribution. - // It has the following relationship with the error function (erf). - // phi(x) = 1/2 (1 + erf(x / sqrt(2))) - // so, 2 * phi(x) - 1 = erf(x / sqrt(2)). - // The range taken by 2 * phi(x) - 1 is [-1, 1], so it can be used as a uniform distribution in - // TPE. Let u = 2 * phi(x) - 1, then x = sqrt(2) * erf_inv(u). Computationally, it is not a good - // to give erf_inv -1 and 1, so it is rounded off at (-1 + eps, 1 - eps). - const double sqrt2 = std::sqrt(2); - auto uniform_to_normal = [&sqrt2](const double uniform) { - assert(-1.0 <= uniform && uniform <= 1.0); - constexpr double epsilon = 1.0e-6; - const double clamped = std::clamp(uniform, -1.0 + epsilon, 1.0 - epsilon); - return boost::math::erf_inv(clamped) * sqrt2; - }; - - auto normal_to_uniform = [&sqrt2](const double normal) { - return boost::math::erf(normal / sqrt2); + // Since only yaw is uniformly sampled, we define the mean and standard deviation for the others. + const std::vector sample_mean{ + initial_pose_with_cov.pose.pose.position.x, // trans_x + initial_pose_with_cov.pose.pose.position.y, // trans_y + initial_pose_with_cov.pose.pose.position.z, // trans_z + base_rpy.x, // angle_x + base_rpy.y // angle_y }; + const std::vector sample_stddev{stddev_x, stddev_y, stddev_z, stddev_roll, stddev_pitch}; // Optimizing (x, y, z, roll, pitch, yaw) 6 dimensions. - // The last dimension (yaw) is a loop variable. - // Although roll and pitch are also angles, they are considered non-looping variables that follow - // a normal distribution with a small standard deviation. This assumes that the initial pose of - // the ego vehicle is aligned with the ground to some extent about roll and pitch. - const std::vector is_loop_variable = {false, false, false, false, false, true}; TreeStructuredParzenEstimator tpe( TreeStructuredParzenEstimator::Direction::MAXIMIZE, - param_.initial_pose_estimation.n_startup_trials, is_loop_variable); + param_.initial_pose_estimation.n_startup_trials, sample_mean, sample_stddev); std::vector particle_array; auto output_cloud = std::make_shared>(); @@ -1029,16 +1013,13 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( const TreeStructuredParzenEstimator::Input input = tpe.get_next_input(); geometry_msgs::msg::Pose initial_pose; - initial_pose.position.x = - initial_pose_with_cov.pose.pose.position.x + uniform_to_normal(input[0]) * stddev_x; - initial_pose.position.y = - initial_pose_with_cov.pose.pose.position.y + uniform_to_normal(input[1]) * stddev_y; - initial_pose.position.z = - initial_pose_with_cov.pose.pose.position.z + uniform_to_normal(input[2]) * stddev_z; + initial_pose.position.x = input[0]; + initial_pose.position.y = input[1]; + initial_pose.position.z = input[2]; geometry_msgs::msg::Vector3 init_rpy; - init_rpy.x = base_rpy.x + uniform_to_normal(input[3]) * stddev_roll; - init_rpy.y = base_rpy.y + uniform_to_normal(input[4]) * stddev_pitch; - init_rpy.z = base_rpy.z + input[5] * M_PI; + init_rpy.x = input[3]; + init_rpy.y = input[4]; + init_rpy.z = input[5]; tf2::Quaternion tf_quaternion; tf_quaternion.setRPY(init_rpy.x, init_rpy.y, init_rpy.z); initial_pose.orientation = tf2::toMsg(tf_quaternion); @@ -1061,22 +1042,13 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( const geometry_msgs::msg::Pose pose = matrix4f_to_pose(ndt_result.pose); const geometry_msgs::msg::Vector3 rpy = get_rpy(pose); - const double diff_x = pose.position.x - initial_pose_with_cov.pose.pose.position.x; - const double diff_y = pose.position.y - initial_pose_with_cov.pose.pose.position.y; - const double diff_z = pose.position.z - initial_pose_with_cov.pose.pose.position.z; - const double diff_roll = rpy.x - base_rpy.x; - const double diff_pitch = rpy.y - base_rpy.y; - const double diff_yaw = rpy.z - base_rpy.z; - - // Only yaw is a loop_variable, so only simple normalization is performed. - // All other variables are converted from normal distribution to uniform distribution. - TreeStructuredParzenEstimator::Input result(is_loop_variable.size()); - result[0] = normal_to_uniform(diff_x / stddev_x); - result[1] = normal_to_uniform(diff_y / stddev_y); - result[2] = normal_to_uniform(diff_z / stddev_z); - result[3] = normal_to_uniform(diff_roll / stddev_roll); - result[4] = normal_to_uniform(diff_pitch / stddev_pitch); - result[5] = diff_yaw / M_PI; + TreeStructuredParzenEstimator::Input result(6); + result[0] = pose.position.x; + result[1] = pose.position.y; + result[2] = pose.position.z; + result[3] = rpy.x; + result[4] = rpy.y; + result[5] = rpy.z; tpe.add_trial(TreeStructuredParzenEstimator::Trial{result, ndt_result.transform_probability}); auto sensor_points_in_map_ptr = std::make_shared>(); diff --git a/localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp b/localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp index b7b522b4e6b76..30d36e7150113 100644 --- a/localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp +++ b/localization/tree_structured_parzen_estimator/include/tree_structured_parzen_estimator/tree_structured_parzen_estimator.hpp @@ -44,37 +44,40 @@ class TreeStructuredParzenEstimator MAXIMIZE = 1, }; + enum Index { + TRANS_X = 0, + TRANS_Y = 1, + TRANS_Z = 2, + ANGLE_X = 3, + ANGLE_Y = 4, + ANGLE_Z = 5, + INDEX_NUM = 6, + }; + TreeStructuredParzenEstimator() = delete; TreeStructuredParzenEstimator( - const Direction direction, const int64_t n_startup_trials, std::vector is_loop_variable); + const Direction direction, const int64_t n_startup_trials, + const std::vector & sample_mean, const std::vector & sample_stddev); void add_trial(const Trial & trial); Input get_next_input() const; private: - static constexpr double BASE_STDDEV_COEFF = 0.2; static constexpr double MAX_GOOD_RATE = 0.10; - static constexpr double MAX_VALUE = 1.0; - static constexpr double MIN_VALUE = -1.0; - static constexpr double VALUE_WIDTH = MAX_VALUE - MIN_VALUE; static constexpr int64_t N_EI_CANDIDATES = 100; - static constexpr double PRIOR_WEIGHT = 0.0; static std::mt19937_64 engine; - static std::uniform_real_distribution dist_uniform; - static std::normal_distribution dist_normal; double compute_log_likelihood_ratio(const Input & input) const; double log_gaussian_pdf(const Input & input, const Input & mu, const Input & sigma) const; - static std::vector get_weights(const int64_t n); - static double normalize_loop_variable(const double value); std::vector trials_; int64_t above_num_; const Direction direction_; const int64_t n_startup_trials_; const int64_t input_dimension_; - const std::vector is_loop_variable_; - const Input base_stddev_; + const std::vector sample_mean_; + const std::vector sample_stddev_; + Input base_stddev_; }; #endif // TREE_STRUCTURED_PARZEN_ESTIMATOR__TREE_STRUCTURED_PARZEN_ESTIMATOR_HPP_ diff --git a/localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp b/localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp index 99c70a844f331..c81962c14f61c 100644 --- a/localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp +++ b/localization/tree_structured_parzen_estimator/src/tree_structured_parzen_estimator.cpp @@ -21,19 +21,33 @@ // random number generator std::mt19937_64 TreeStructuredParzenEstimator::engine(std::random_device{}()); -std::uniform_real_distribution TreeStructuredParzenEstimator::dist_uniform( - TreeStructuredParzenEstimator::MIN_VALUE, TreeStructuredParzenEstimator::MAX_VALUE); -std::normal_distribution TreeStructuredParzenEstimator::dist_normal(0.0, 1.0); TreeStructuredParzenEstimator::TreeStructuredParzenEstimator( - const Direction direction, const int64_t n_startup_trials, std::vector is_loop_variable) + const Direction direction, const int64_t n_startup_trials, + const std::vector & sample_mean, const std::vector & sample_stddev) : above_num_(0), direction_(direction), n_startup_trials_(n_startup_trials), - input_dimension_(is_loop_variable.size()), - is_loop_variable_(is_loop_variable), - base_stddev_(input_dimension_, VALUE_WIDTH) + input_dimension_(INDEX_NUM), + sample_mean_(sample_mean), + sample_stddev_(sample_stddev) { + if (sample_mean_.size() != ANGLE_Z) { + std::cerr << "sample_mean size is invalid" << std::endl; + throw std::runtime_error("sample_mean size is invalid"); + } + if (sample_stddev_.size() != ANGLE_Z) { + std::cerr << "sample_stddev size is invalid" << std::endl; + throw std::runtime_error("sample_stddev size is invalid"); + } + // base_stddev_ is defined as the stable convergence range of ndt_scan_matcher. + base_stddev_.resize(input_dimension_); + base_stddev_[TRANS_X] = 0.25; // [m] + base_stddev_[TRANS_Y] = 0.25; // [m] + base_stddev_[TRANS_Z] = 0.25; // [m] + base_stddev_[ANGLE_X] = 1.0 / 180.0 * M_PI; // [rad] + base_stddev_[ANGLE_Y] = 1.0 / 180.0 * M_PI; // [rad] + base_stddev_[ANGLE_Z] = 2.5 / 180.0 * M_PI; // [rad] } void TreeStructuredParzenEstimator::add_trial(const Trial & trial) @@ -43,47 +57,45 @@ void TreeStructuredParzenEstimator::add_trial(const Trial & trial) return (direction_ == Direction::MAXIMIZE ? lhs.score > rhs.score : lhs.score < rhs.score); }); above_num_ = - std::min(static_cast(25), static_cast(trials_.size() * MAX_GOOD_RATE)); + std::min({static_cast(10), static_cast(trials_.size() * MAX_GOOD_RATE)}); } TreeStructuredParzenEstimator::Input TreeStructuredParzenEstimator::get_next_input() const { + std::normal_distribution dist_normal_trans_x( + sample_mean_[TRANS_X], sample_stddev_[TRANS_X]); + std::normal_distribution dist_normal_trans_y( + sample_mean_[TRANS_Y], sample_stddev_[TRANS_Y]); + std::normal_distribution dist_normal_trans_z( + sample_mean_[TRANS_Z], sample_stddev_[TRANS_Z]); + std::normal_distribution dist_normal_angle_x( + sample_mean_[ANGLE_X], sample_stddev_[ANGLE_X]); + std::normal_distribution dist_normal_angle_y( + sample_mean_[ANGLE_Y], sample_stddev_[ANGLE_Y]); + std::uniform_real_distribution dist_uniform_angle_z(-M_PI, M_PI); + if (static_cast(trials_.size()) < n_startup_trials_ || above_num_ == 0) { // Random sampling based on prior until the number of trials reaches `n_startup_trials_`. Input input(input_dimension_); - for (int64_t j = 0; j < input_dimension_; j++) { - input[j] = dist_uniform(engine); - } + input[TRANS_X] = dist_normal_trans_x(engine); + input[TRANS_Y] = dist_normal_trans_y(engine); + input[TRANS_Z] = dist_normal_trans_z(engine); + input[ANGLE_X] = dist_normal_angle_x(engine); + input[ANGLE_Y] = dist_normal_angle_y(engine); + input[ANGLE_Z] = dist_uniform_angle_z(engine); return input; } Input best_input; double best_log_likelihood_ratio = std::numeric_limits::lowest(); - const double coeff = BASE_STDDEV_COEFF * std::pow(above_num_, -1.0 / (4 + input_dimension_)); - std::vector weights = get_weights(above_num_); - weights.push_back(PRIOR_WEIGHT); - std::discrete_distribution dist(weights.begin(), weights.end()); for (int64_t i = 0; i < N_EI_CANDIDATES; i++) { - Input mu, sigma; - const int64_t index = dist(engine); - if (index == above_num_) { - mu = Input(input_dimension_, 0.0); - sigma = base_stddev_; - } else { - mu = trials_[index].input; - sigma = base_stddev_; - for (int64_t j = 0; j < input_dimension_; j++) { - sigma[j] *= coeff; - } - } - // sample from the normal distribution Input input(input_dimension_); - for (int64_t j = 0; j < input_dimension_; j++) { - input[j] = mu[j] + dist_normal(engine) * sigma[j]; - input[j] = - (is_loop_variable_[j] ? normalize_loop_variable(input[j]) - : std::clamp(input[j], MIN_VALUE, MAX_VALUE)); - } + input[TRANS_X] = dist_normal_trans_x(engine); + input[TRANS_Y] = dist_normal_trans_y(engine); + input[TRANS_Z] = dist_normal_trans_z(engine); + input[ANGLE_X] = dist_normal_angle_x(engine); + input[ANGLE_Y] = dist_normal_angle_y(engine); + input[ANGLE_Z] = dist_uniform_angle_z(engine); const double log_likelihood_ratio = compute_log_likelihood_ratio(input); if (log_likelihood_ratio > best_log_likelihood_ratio) { best_log_likelihood_ratio = log_likelihood_ratio; @@ -102,50 +114,19 @@ double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input & std::vector above_logs; std::vector below_logs; - // Scott's rule - const double coeff_above = - BASE_STDDEV_COEFF * std::pow(above_num_, -1.0 / (4 + input_dimension_)); - const double coeff_below = - BASE_STDDEV_COEFF * std::pow(n - above_num_, -1.0 / (4 + input_dimension_)); - Input sigma_above = base_stddev_; - Input sigma_below = base_stddev_; - for (int64_t j = 0; j < input_dimension_; j++) { - sigma_above[j] *= coeff_above; - sigma_below[j] *= coeff_below; - } - - std::vector above_weights = get_weights(above_num_); - std::vector below_weights = get_weights(n - above_num_); - std::reverse(below_weights.begin(), below_weights.end()); // below_weights is ascending order - - // calculate the sum of weights to normalize - double above_sum = std::accumulate(above_weights.begin(), above_weights.end(), 0.0); - double below_sum = std::accumulate(below_weights.begin(), below_weights.end(), 0.0); - - // above includes prior - above_sum += PRIOR_WEIGHT; - for (int64_t i = 0; i < n; i++) { + const double log_p = log_gaussian_pdf(input, trials_[i].input, base_stddev_); if (i < above_num_) { - const double log_p = log_gaussian_pdf(input, trials_[i].input, sigma_above); - const double w = above_weights[i] / above_sum; + const double w = 1.0 / above_num_; const double log_w = std::log(w); above_logs.push_back(log_p + log_w); } else { - const double log_p = log_gaussian_pdf(input, trials_[i].input, sigma_below); - const double w = below_weights[i - above_num_] / below_sum; + const double w = 1.0 / (n - above_num_); const double log_w = std::log(w); below_logs.push_back(log_p + log_w); } } - // prior - if (PRIOR_WEIGHT > 0.0) { - const double log_p = log_gaussian_pdf(input, Input(input_dimension_, 0.0), base_stddev_); - const double log_w = std::log(PRIOR_WEIGHT / above_sum); - above_logs.push_back(log_p + log_w); - } - auto log_sum_exp = [](const std::vector & log_vec) { const double max = *std::max_element(log_vec.begin(), log_vec.end()); double sum = 0.0; @@ -157,7 +138,11 @@ double TreeStructuredParzenEstimator::compute_log_likelihood_ratio(const Input & const double above = log_sum_exp(above_logs); const double below = log_sum_exp(below_logs); - const double r = above - below; + + // Multiply by a constant so that the score near the "below sample" becomes lower. + // cspell:disable-line TODO(Shintaro Sakoda): It's theoretically incorrect, consider it again + // later. + const double r = above - below * 5.0; return r; } @@ -174,44 +159,21 @@ double TreeStructuredParzenEstimator::log_gaussian_pdf( double result = 0.0; for (int64_t i = 0; i < n; i++) { double diff = input[i] - mu[i]; - if (is_loop_variable_[i]) { - diff = normalize_loop_variable(diff); + if (i == ANGLE_Z) { + // Normalize the loop variable to [-pi, pi) + while (diff >= M_PI) { + diff -= 2 * M_PI; + } + while (diff < -M_PI) { + diff += 2 * M_PI; + } } - result += log_gaussian_pdf_1d(diff, sigma[i]); - } - return result; -} - -std::vector TreeStructuredParzenEstimator::get_weights(const int64_t n) -{ - // See optuna - // https://github.com/optuna/optuna/blob/4bfab78e98bf786f6a2ce6e593a26e3f8403e08d/optuna/samplers/_tpe/sampler.py#L50-L58 - std::vector weights; - constexpr int64_t WEIGHT_ALPHA = 25; - if (n == 0) { - return weights; - } else if (n < WEIGHT_ALPHA) { - weights.resize(n, 1.0); - } else { - weights.resize(n); - const double unit = (1.0 - 1.0 / n) / (n - WEIGHT_ALPHA); - for (int64_t i = 0; i < n; i++) { - weights[i] = (i < WEIGHT_ALPHA ? 1.0 : 1.0 - unit * (i - WEIGHT_ALPHA)); + // Experimentally, it is better to consider only trans_xy and yaw, so ignore trans_z, angle_x, + // angle_y. + if (i == TRANS_Z || i == ANGLE_X || i == ANGLE_Y) { + continue; } - } - - return weights; -} - -double TreeStructuredParzenEstimator::normalize_loop_variable(const double value) -{ - // Normalize the loop variable to [-1, 1) - double result = value; - while (result >= MAX_VALUE) { - result -= VALUE_WIDTH; - } - while (result < MIN_VALUE) { - result += VALUE_WIDTH; + result += log_gaussian_pdf_1d(diff, sigma[i]); } return result; } diff --git a/localization/tree_structured_parzen_estimator/test/test_tpe.cpp b/localization/tree_structured_parzen_estimator/test/test_tpe.cpp index 32eb66e70fb16..f8a697878d6a3 100644 --- a/localization/tree_structured_parzen_estimator/test/test_tpe.cpp +++ b/localization/tree_structured_parzen_estimator/test/test_tpe.cpp @@ -28,19 +28,25 @@ TEST(TreeStructuredParzenEstimatorTest, TPE_is_better_than_random_search_on_sphe return value; }; - constexpr int64_t kOuterTrialsNum = 10; - constexpr int64_t kInnerTrialsNum = 100; + constexpr int64_t kOuterTrialsNum = 20; + constexpr int64_t kInnerTrialsNum = 200; std::cout << std::fixed; std::vector mean_scores; - for (const int64_t n_startup_trials : {kInnerTrialsNum, kInnerTrialsNum / 10}) { + const int64_t n_startup_trials = kInnerTrialsNum / 10; + const std::string method = ((n_startup_trials == kInnerTrialsNum) ? "Random" : "TPE"); + + const std::vector sample_mean(5, 0.0); + const std::vector sample_stddev{1.0, 1.0, 0.1, 0.1, 0.1}; + + for (const int64_t n_startup_trials : {kInnerTrialsNum, kInnerTrialsNum / 2}) { const std::string method = ((n_startup_trials == kInnerTrialsNum) ? "Random" : "TPE"); std::vector scores; for (int64_t i = 0; i < kOuterTrialsNum; i++) { double best_score = std::numeric_limits::lowest(); - const std::vector is_loop_variable(6, false); TreeStructuredParzenEstimator estimator( - TreeStructuredParzenEstimator::Direction::MAXIMIZE, n_startup_trials, is_loop_variable); + TreeStructuredParzenEstimator::Direction::MAXIMIZE, n_startup_trials, sample_mean, + sample_stddev); for (int64_t trial = 0; trial < kInnerTrialsNum; trial++) { const TreeStructuredParzenEstimator::Input input = estimator.get_next_input(); const double score = -sphere_function(input); From 0e6f175330bf891355175bb2973cd04a1c1e6a3a Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 14 May 2024 13:48:26 +0900 Subject: [PATCH 164/192] refactor(behavior_velocity_occlusion_spot_module): remove unnecessary declaration (#7000) * refactor(behavior_velocity_occlusion_spot_module): remove unnecessary declaration Signed-off-by: Ryuta Kambe * remove unnecessary declaration Signed-off-by: Ryuta Kambe * unify lanelet::ArcCoordinates Signed-off-by: Ryuta Kambe * unify lanelet::geometry::fromArcCoordinates Signed-off-by: Ryuta Kambe * style(pre-commit): autofix * unify lanelet::ConstLineString2d Signed-off-by: Ryuta Kambe * style(pre-commit): autofix * fix Signed-off-by: veqcc --------- Signed-off-by: Ryuta Kambe Signed-off-by: veqcc Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/debug.cpp | 1 - .../src/occlusion_spot_utils.cpp | 44 ++++++++++--------- .../src/occlusion_spot_utils.hpp | 4 -- 3 files changed, 24 insertions(+), 25 deletions(-) diff --git a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp index f4d3fbf6cc2c1..1170afc490a75 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp @@ -33,7 +33,6 @@ using BasicPolygons = std::vector; using occlusion_spot_utils::PossibleCollisionInfo; using tier4_autoware_utils::appendMarkerArray; using tier4_autoware_utils::calcOffsetPose; -using tier4_autoware_utils::createDefaultMarker; using tier4_autoware_utils::createMarkerColor; using tier4_autoware_utils::createMarkerOrientation; using tier4_autoware_utils::createMarkerPosition; diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp index 22b93c2c0236c..f22cedbe67c8f 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp @@ -245,7 +245,8 @@ void categorizeVehicles( return; } -ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineString2d & ll_string) +lanelet::ArcCoordinates getOcclusionPoint( + const PredictedObject & obj, const lanelet::ConstLineString2d & ll_string) { const auto poly = tier4_autoware_utils::toPolygon2d(obj); std::deque arcs; @@ -260,16 +261,18 @@ ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineStr * Ego===============> path **/ // sort by arc length - std::sort(arcs.begin(), arcs.end(), [](ArcCoordinates arc1, ArcCoordinates arc2) { - return arc1.length < arc2.length; - }); + std::sort( + arcs.begin(), arcs.end(), [](lanelet::ArcCoordinates arc1, lanelet::ArcCoordinates arc2) { + return arc1.length < arc2.length; + }); // remove closest 2 polygon point arcs.pop_front(); arcs.pop_front(); // sort by arc distance - std::sort(arcs.begin(), arcs.end(), [](ArcCoordinates arc1, ArcCoordinates arc2) { - return std::abs(arc1.distance) < std::abs(arc2.distance); - }); + std::sort( + arcs.begin(), arcs.end(), [](lanelet::ArcCoordinates arc1, lanelet::ArcCoordinates arc2) { + return std::abs(arc1.distance) < std::abs(arc2.distance); + }); // return closest to path point which is choosen by farthest 2 points. return arcs.at(0); } @@ -289,18 +292,19 @@ double calcSignedLateralDistanceWithOffset( } PossibleCollisionInfo calculateCollisionPathPointFromOcclusionSpot( - const ArcCoordinates & arc_coord_occlusion, - const ArcCoordinates & arc_coord_occlusion_with_offset, + const lanelet::ArcCoordinates & arc_coord_occlusion, + const lanelet::ArcCoordinates & arc_coord_occlusion_with_offset, const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param) { - auto calcPosition = [](const ConstLineString2d & ll, const ArcCoordinates & arc) { - BasicPoint2d bp = fromArcCoordinates(ll, arc); - Point position; - position.x = bp[0]; - position.y = bp[1]; - position.z = 0.0; - return position; - }; + auto calcPosition = + [](const lanelet::ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) { + BasicPoint2d bp = lanelet::geometry::fromArcCoordinates(ll, arc); + Point position; + position.x = bp[0]; + position.y = bp[1]; + position.z = 0.0; + return position; + }; /** * @brief calculate obstacle collision intersection from arc coordinate info. * ^ @@ -341,8 +345,8 @@ bool generatePossibleCollisionsFromObjects( lanelet::ConstLanelet path_lanelet = toPathLanelet(path); auto ll = path_lanelet.centerline2d(); for (const auto & dyn : dyn_objects) { - ArcCoordinates arc_coord_occlusion = getOcclusionPoint(dyn, ll); - ArcCoordinates arc_coord_occlusion_with_offset = { + lanelet::ArcCoordinates arc_coord_occlusion = getOcclusionPoint(dyn, ll); + lanelet::ArcCoordinates arc_coord_occlusion_with_offset = { arc_coord_occlusion.length - param.baselink_to_front, calcSignedLateralDistanceWithOffset( arc_coord_occlusion.distance, param.right_overhang, param.left_overhang, @@ -455,7 +459,7 @@ std::optional generateOneNotableCollisionFromOcclusionSpo if (length_to_col < offset_from_start_to_ego) { continue; } - ArcCoordinates arc_coord_collision_point = { + lanelet::ArcCoordinates arc_coord_collision_point = { length_to_col, calcSignedLateralDistanceWithOffset( arc_coord_occlusion_point.distance, right_overhang, left_overhang, wheel_tread)}; diff --git a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp index 47242b70f0cbd..7f495f042d7f8 100644 --- a/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp +++ b/planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp @@ -57,14 +57,10 @@ using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; -using lanelet::ArcCoordinates; using lanelet::BasicLineString2d; using lanelet::BasicPoint2d; using lanelet::BasicPolygon2d; -using lanelet::ConstLineString2d; using lanelet::LaneletMapPtr; -using lanelet::geometry::fromArcCoordinates; -using lanelet::geometry::toArcCoordinates; using DetectionAreaIdx = std::optional>; using BasicPolygons2d = std::vector; From 590518fb6435bfa379bb2896813f005f843efb23 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 14 May 2024 13:50:38 +0900 Subject: [PATCH 165/192] chore(tools): move system and evaluation tools to autoware_tools repo from autoware.universe (#7002) * chore(tools): move system tools Signed-off-by: satoshi-ota * chore(evaluator): move evaluators Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../tier4_metrics_rviz_plugin/CMakeLists.txt | 31 --- evaluator/tier4_metrics_rviz_plugin/README.md | 16 -- .../icons/classes/MetricsVisualizePanel.png | Bin 18815 -> 0 bytes .../include/metrics_visualize_panel.hpp | 254 ----------------- .../tier4_metrics_rviz_plugin/package.xml | 33 --- .../plugins/plugin_description.xml | 5 - .../src/metrics_visualize_panel.cpp | 262 ------------------ .../CMakeLists.txt | 9 - tools/rqt_diagnostic_graph_monitor/README.md | 1 - .../rqt_diagnostic_graph_monitor/package.xml | 24 -- tools/rqt_diagnostic_graph_monitor/plugin.xml | 16 -- .../python/__init__.py | 37 --- .../python/graph.py | 127 --------- .../python/items.py | 54 ---- .../python/module.py | 61 ---- .../python/utils.py | 29 -- .../python/widget.py | 85 ------ .../script/cui_diagnostic_graph_monitor | 14 - .../script/rqt_diagnostic_graph_monitor | 8 - 19 files changed, 1066 deletions(-) delete mode 100644 evaluator/tier4_metrics_rviz_plugin/CMakeLists.txt delete mode 100644 evaluator/tier4_metrics_rviz_plugin/README.md delete mode 100644 evaluator/tier4_metrics_rviz_plugin/icons/classes/MetricsVisualizePanel.png delete mode 100644 evaluator/tier4_metrics_rviz_plugin/include/metrics_visualize_panel.hpp delete mode 100644 evaluator/tier4_metrics_rviz_plugin/package.xml delete mode 100644 evaluator/tier4_metrics_rviz_plugin/plugins/plugin_description.xml delete mode 100644 evaluator/tier4_metrics_rviz_plugin/src/metrics_visualize_panel.cpp delete mode 100644 tools/rqt_diagnostic_graph_monitor/CMakeLists.txt delete mode 100644 tools/rqt_diagnostic_graph_monitor/README.md delete mode 100644 tools/rqt_diagnostic_graph_monitor/package.xml delete mode 100644 tools/rqt_diagnostic_graph_monitor/plugin.xml delete mode 100644 tools/rqt_diagnostic_graph_monitor/python/__init__.py delete mode 100644 tools/rqt_diagnostic_graph_monitor/python/graph.py delete mode 100644 tools/rqt_diagnostic_graph_monitor/python/items.py delete mode 100644 tools/rqt_diagnostic_graph_monitor/python/module.py delete mode 100644 tools/rqt_diagnostic_graph_monitor/python/utils.py delete mode 100644 tools/rqt_diagnostic_graph_monitor/python/widget.py delete mode 100755 tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor delete mode 100755 tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor diff --git a/evaluator/tier4_metrics_rviz_plugin/CMakeLists.txt b/evaluator/tier4_metrics_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 8475b596e6d6b..0000000000000 --- a/evaluator/tier4_metrics_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,31 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_metrics_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets Charts) -set(QT_WIDGETS_LIB Qt5::Widgets) -set(QT_CHARTS_LIB Qt5::Charts) -set(CMAKE_AUTOMOC ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/metrics_visualize_panel.cpp - include/metrics_visualize_panel.hpp -) - -target_link_libraries(${PROJECT_NAME} - ${QT_WIDGETS_LIB} - ${QT_CHARTS_LIB} -) - -target_compile_options(${PROJECT_NAME} PUBLIC -Wno-error=deprecated-copy -Wno-error=pedantic) -# Export the plugin to be imported by rviz2 -pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) - -ament_auto_package( - INSTALL_TO_SHARE - icons - plugins -) diff --git a/evaluator/tier4_metrics_rviz_plugin/README.md b/evaluator/tier4_metrics_rviz_plugin/README.md deleted file mode 100644 index be94141254030..0000000000000 --- a/evaluator/tier4_metrics_rviz_plugin/README.md +++ /dev/null @@ -1,16 +0,0 @@ -# tier4_metrics_rviz_plugin - -## Purpose - -This plugin panel to visualize `planning_evaluator` output. - -## Inputs / Outputs - -| Name | Type | Description | -| ---------------------------------------- | --------------------------------------- | ------------------------------------- | -| `/diagnostic/planning_evaluator/metrics` | `diagnostic_msgs::msg::DiagnosticArray` | Subscribe `planning_evaluator` output | - -## HowToUse - -1. Start rviz and select panels/Add new panel. -2. Select MetricsVisualizePanel and press OK. diff --git a/evaluator/tier4_metrics_rviz_plugin/icons/classes/MetricsVisualizePanel.png b/evaluator/tier4_metrics_rviz_plugin/icons/classes/MetricsVisualizePanel.png deleted file mode 100644 index 6a67573717ae18b6008e00077defb27256415663..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18815 zcmc#)ig}7!VL~0BI3P>4u>jX{5WQyQGE==@gXiZcsv`yJ3)ShVHnpzyIKV zx%UIl!@PCQ*=Oy&*IwtGaAid)9L!gkAP@*gMjEOL0wKly`$K;YTnXsp8Ulf2BxRtY zY95&f%V-`irs2ZJD-E_>W|QJ#$f(lDGUzn9FhfdJ6ls+f7g13tl1h)8=nGVpD&-eU zEXJbkUMvxiN-bt%sdy?0Ws#;2U}Tww$D9k?tJrv3b90N4w6q7mY>Vu>j)cq`Gq>&g ztxVotd7x=_%0QrfCTU6#h!Tqc9R&LG1r-?ts`)>?Y`h5pRS_lWag8OXawfXJHk9@r zwSCxzbPRm-g9n1hq$!Q)8a9)#!i(M_cz&h|6vnpsyKVD7twGSL0-4KL6Q=BD1ZeP- zzfzYzWVM-q+?d)>KwJl;5;rOeaVP-p8?mb$R~c z!r4STVAB1bJ?W`Q1N^wk6a>;QVI%JxOu}Vf{^G|)Co3MGH{(9RMV<;nHU4Za)%KSC z`;I=`QN*K~)?CjlT%q3CJ0d$G%J_7^;$JI4Ms3f{6oyJDbjK_N!4ju2 z&$?3P$rm$WTureE-aq`r%H%qf&xx}1+^E65XE7*U*@ASHv#;8ex#{Xeuo?I&+x*og zCp;~E10-qE582|U!y4K~`SF#B31Gjpj3?LDSx6hf<#=NRr5x>o;P$^l9osYrEfL{WYjQydU9;g?K5#3k=W*FphTCuCHewl5&`Uu9F)(f>MMOxB>pE z88huBN|GrNq|eH~M(ELpl-tdZkMhs%;OV+^2?6{7^3=m>h4(Sn1AF4SLTeDL;O9g! zBWaM6c%X0DechlP8B_BUQ^1_B5ImG0q$&AGba@Q1!Sx#uv;b)FNlKJ%FF!gu4goAi z+jugMiX+lt3%Db%$x}1fa)yh%A&xxGW-Lle9BaRZcr(Jl8YJvmXVoM8b*d?nDn zr>xqjT|4gjOmgjyb!-I_L=1WSO(};jF5)F9(KK9k$6juv0YKyrQRHz_DK~8jI2)+w zm-Yt$QfvYLhOutzxp@d+SUG4qO=vJ%C2^D=7atD;N#3;^c;DQzmR&&!oPfkcBJT}x-4FY#kT02m@DxoqS-{xT|$ z3PAj4Y06h5S$bR{FjZhmf2ImPCOB3Cm{OLqda0jhqvfLSxmZ+?A2<^h+z64sYjMk*OaM^512bTNz1yJX#3oL;p>F~$69vB)J^K&J0kyCuHxo2qc9?N7 zpx^)Vh!`XhEMW3-8hQ#=jbwx3L_Yk3cspR5f1h~;US}c=&En=n$AFqJRa-Trw&}AF z#AgA`>wx2@JWAg4l9l5}1GY|0Z9CNsXNdgw(z**Vj@S4BOp0I}AA5Z|Zl~>Z3kVbj zqQ+>~?`j3P7S~|HAAK#cX8I@4)zn@Yx%DiDRJ@~c4bTC4ySPXJL&So)v8RA@6#{J%M_y$DCRzdd0*FPR zEH--gPG5+|{w5Yegr~;hMSkzb)vYj91mGV5xcRrf*}fIu`8(Gk(oJHQTMWSTlpe3W z7U|f@97Ozui1Pqn>xtK!34&Gp1$<#-lg>4RGs7K!6%!+v&|>f%Vhw^400u&sGY~q5 zJ^R2hK)+x%+?N_ujGMppd5=D@{V_pS_0HC2*7x*eApoKv>S`$MhIW>f zMXBEn^5P16FfqDGOxdOTX$;a&7%;G-28$P)$1&8Il!2^?K;(-9A|F432ZYVYM^|}I z3>OV1q`?mb9wc7}dJzwJ)_0FSe8o7Cm(><8hzS0{vBcWu7VZ9!xVd$!*%0qZqPEJb=%hJ$Z_L zz~Miu9bQOq9)39Df;+w>C4k8SnA^IR``!NH4|SUf61t|;@Y}Cs7L7w2kT8`ufki#> z(|*WcvwwZbRQK{xx%^U^9it@ui(i`PZ(a!{U!?$lf%er!QwQi?Jq@BTnXsQ0^KiZy z)@H)?s!l`=|Lg4jvo;>IFs7CP;9l8V4UpAo>sjIq#`%v=kuRv~Dh zsiW)pz26t!@MhZgf>?_yj35jsQu16~;-8_l{?rj9%$d(V-9L6Mv^t{|GGZ5-C`W&WqNh29e6d|hsvmvzE$*g zQmyMXe|TD_9?2}u%kdXf_x#(4xd=B4sAmzB{R*=+ZDMv*{0=ZZw`U z1zHnRLzGA%_kVvk=&UnLH`*nK6OLz)IZ+1RaP z$_a6)pzGO}t0_(S2EeN@?u0pWGf^QOT;Fy&fIf+061Vv&k6#eQ9E?CJbN7 zR~KK=eS#kf?q9C)BZqF)@T7l`iF(-E2|R4|?91b}4Ez)Kk2FyYsGq$iY-#*_u@~1} zergZr={EWSme9lc1Lvw@G~X6iq*U zJ>6TJJ1l)Wu8Wk+%I_jO@X>ttg#2Gtvr6H&5?wENhU3wfOD|1HK$EE0JWPIo?o%@w7QX>1z=lRIcDYmm^RdaH!J$U0qdKjR{v?Nj@k8=mLg z!QaffX+{G^hFLx>yzv{!{4I7+*?C}Mw;W;Akw&+^oGNB zKbo1D;RxOCe8*HY+Wq2Z{a&$bq>kL0E*5uqV%bZU97(Rgg}axR>R3#V{3&SGo$cMU zo>il+6}(CD_7>Sn+RG>LD*ZH>q}A^P_|jLN;2-ZSZ)e^-CR7g&UCtF)C)#ml2sjLp zna0G_?3W<_14PCTp7u%y`1jJLdPCb;WW==}ZA1fH$8?tCsR>bJF?vJ$I|J{? zlTYZ~d#P!IC7nc5MI zRsbBkP4l%D7PaBB{&6DKt4yR^NwBqPM*lr^I~U=AH?+LJ*&C$ZAXr^~8P$6rvc|OQ z@5*T^JLt$TP5T0t(=wiG^sXg zEd~AVuZVrio-s!T&LrqYTve>D*P81_=>7;qF3oJb%9-_$ zl7tF5{GK`$Y)Po@y_Df6U|SUSg7!xbv_*4yVe!Q#Ebc;ZcwoSK)rHUB2ho1zr!2(h z%dVk7oadz}SQ849EKz@)p|3b8py_+bZq+KNZ|#0KdDLC_ZhWXy#9XXyyOh3&D_KBd$d5r~dZ&@?gHCJhG5mniAQ@R>y{O zFvmlJ?JS~a-%K~9k;T?h@u&=-btl<6W(Mr?#p_#Nvx_0v`ilrR<$^+%&Dej}o4vNPn* z;owRb6rB0y*XFvkd6OhCQqGB6I?r)a!X@j6i&CJJ1K0a?>M~fR$7l@HLqkBtR{DNi z#>_e~=e6CHkiV3$L3^TB!NYiWD6Xr+?LjRJ218fc9?44c9VrfHEASeRf4u5=;4Pz2 zbmAarlXGC+<}+MNXuEB2%{j_j84W=YGt*J6aB$pdMP%f^yA?e@n6EWm{~fLLbbmH# zB#6dX=5Pv<(zsg%*jkAKL5r0knZM%tivqc1CatP(x82cXPdwWwcmjs-W@q|ImYY99 zYwlE~Y-hze~lk`x3mjPB!27mzk`xg^y;8^_L_ahVv6~)|t~mfqeU``w(TZ zxrTjOPssfK`oySR$6>Am1>m)tK+)!_P=0!6FfqlwTf!xubMJn*u$lh(uwJ8c<*Bgn zDIx;XIk9`S^Zs-&ZN{2BW%h21L^x#Hy{t&3#$u%2EIrNNs9uMGjS4;G4WkVIc79S?9<_)}5sGh^o2GGu01pfp6?z7wr_`sf6M}tS@hT zNCXk5MDOIEc)b#>BL5Byp4r;f?uV$qGqs%c8FpR1U>>e-v`u`iQ65*US#Q)pH|_z0GX?kiG%%(LOU!%Ckq@v`f@JK|pfX2{xiK)~<5soB5N zZ^n6hgiX)Z0q$xxBO+$zshAz%JT;G?R^ui!yaQF=CYolEefA_D418x5EBtuv6S_T# zt>8C5ZK^P2{Tk3jP{74C9i5Z*XB90Em|L^1Lp$Ty?ZVFx%zQ38_!1Hlo_wx*Jxm>5 z;cSTnM62^vnW0! zv(<%*u%dQ#ZEdDm`^UPysNb89-plAwdG@K0)y_jBD-qUQUN%)_5(TsN78%{K)f*=5FXVTI-5jC-M0r)_e2{Uu>Io;LFZ)WTSayCh zH$y%7yq?2_WZ>t-lJJ(ErM5;8)CMsVjU&indTZFQ!V%ji9)yN-+O%Xp_zMN?x2c&~ z$h26bQIZIOY$0|Hl-A{A>HW>D%Vl99Us^*}%6q+6(o_lL&Dq|Mo_&23{zG+CyVGoa zZdPuB-3?-rE;hgTQB^{1j%hnpE81vUZxe{q7+r62)9R zQjuMBfm(#Ms?@4Z$;Ik^iw9oWqRW`6isW|}$3~+7uuRp_uSRo5+uoV%o;%fYOqe&( z|2-;yrIE5RJ-g8wo6hVoIj1wlF#nl)eXp0d4XYB-b^eG|Cv?<)1s7iS_r5%WWTvIf z2b#SW2vI-|e@Dud15=%5ScGn5xI-4JpMXeprsukuG_&3pJ9vw|;{D{iSX$ZsyN-QS zIkazCCe z5tjTIqBD|W;A`f4 z(o2%2vBi}U($ZixbedSg2KMZ`WSTOQSc*AmMXpEHQN>d_Ts3UpJGs9*!n#G=T_Pyr zRXRI_^rJ$49%InZRr>IOdrQ?H&qWVYSv0t<)_MjA=@l6!>}m{uAv-nCbu4CkNL1I0 zszx2HgbeMhEPPFWT{;-iq%i3PmyXoFdjD&`g5k23{NZw;w9<>q|Iu^oZgl-bE6dSw z^mlKsUR{#$i%`XX%3&%n7Tqbvr-=iv3Vn!kYG;%8(aknQHmT914|hK(l9+ATj)ON8U+A7k}qtQoh z(o1n!2r2de-qqvX8LPa^T2)TVwotK{{5PUlaF}h}t$?CyJIDXX_j2AsLij`a@Rsi6 zT9`WmSJ@(5~J3(YDA@J|o3An#c=nA#EWWa`laHX*T$SjobapA&u?(UWP+Q{C%@7Q}QA^ zJNv{`cm#_$-9Pc`0QTcIA;7WaQ;?NPKQ)wA2wg2XAF*`a%1+DL{Ei|8qxs#0>_+qE zIygdQ6ZJGXrnY0=Ug)~OeO>jx(RvJib8E2<`5+hRj<=UQ`XSK&;bJyBjKUK-vv>=H zGCKa(@!Sj)ME<{YC-0A1b(Bqx63NF8LaQ+pwr7++?Y;83W-@6>tv_S?kk#VM|MVs2LY-DySvyPfa--K5g8|I^)y zxR)i5=c%cxpXe{y&Af@{;>*~{b02i&{aB_$54p;>&#@87qjme%iw$;g@1y3hdBV!k zZH`JGW7Tng^Ak~%}#;Q-2Kv@J$5 zPoiIQ%EmkU-JkTeJJ;0SF{mVKykranq(ebDsHb&e)<5FL`@L~x6=ryQdf$-7vCQ0< zVKw1(9v>zMv~Hr4MzS?k%k=W&z-eNFmOLHeG{ZZM>d@B7MqQoA_xwa^NGPaDE9_=G zqs6AdhWYsONzd@+OaTr-8XOBq(wvBuPJ?Raqs7jrj-Q(vB?55luOh~nXxNd`{VH~I zM;8yWZJr7r(}dDk^xNhxwsalXR!sA1N(T6xx8%3 z9i?;He4?%(U&RqXs^zm7y_}z_XZ`rKJWdqi+!lDPbqjFCc03mCyq$|H4*?12d18Xu zsc9-IL6-9k#5yU9z|37?M|bFc*A_tKQa1XE*M2$dVt-b%RtQm5BcL!+`EtBIz{=SB z>EVhR7s6-iy&6K2n(c0w;sbP}fDO(N@z^>W*1LXDq9TP$lSj^&IGFi{KpGIP-++mV zR2tI$TwO=$)6FcJ+Rs%5-rd7wzS5;BWefCwh}pkOiJM7&g&1R6o^Ft!tBsfjK$~LV zchl!;(BZ>dy(Cy;~wVJ*0yFzq6!EcXR5$rY?4gI54mUi2JbS2$QJGSQ5Xyxt;M>AF4Sv@28`bN@} zlqwK4bFtGi`_*QHwN9+3#N)ub$|i36r9T2zdP63$?>Q-i9luzG2$gB(w!3~+Q&2P3 ztg~7hwvPLAu**HR*1BKO`siW+cbQb!0_qL(aGzg2%;p*MKf-C??dsxN<>Sk(?%vrz zzc_PV+EeGDFeZ;i84*ZtW=H3=#2j|W^|ND<(N6Ys^vYL`H`p!um`KLX43QJ|#XvZ& z5VNDI>gv4*nZ&heTY8$rMpSG1;mfQ=IFry0%W*2X;r!dHgLxC(0(fUSoX7 zwNjEXD0t!s_`m5$=5BFW$;8yBAcYLBacVr_p>vrk2KwkD((ynWWJf^m6M0>Rs^j&K zcuG{Bb;k~FsXL?edF#}7S zHZDLmq@^Y_Y4fI*ecn|MwalQipJKC!`&+AEi=Oxumg^tYvS0s6v}&dED>#4Eap zAJNq9yf;-G>9>swxt+fKLmkVyKVy>_Z%8^@94F5{sE|(%yu=RF} zU|f+?>1X;0!Jp9#;p0r9dszlE)NBFz%Xb>g4B!|F;iIe%Rte_9u|W9MNnz3b-6obM zRP{c^sD1ZD1@8DThqDat@NK>7r_aG&(BpD|3!JTXho#kHn#b%IMn={-%208He(I{j z8s5K{sLB<8*d9?YNvdlAkE1Xq4M&^5V`}zED!eajyno=M;-hVhny2RT;+R}Z9r4hs zHg0|z%N0-eaMaHz%=Q`>bdt9ENtBg7zrZD9*0FRwt#|ss^{%z@XNh|0y-*Iz&V$F+ z5b1tlj^6+i1CSkW24b4a6t9GRb-61JetIWG3TakcE8lU{iJ1*WfY zhT3M?F_AEMwx8^2o>J9?B73d2M-Ao0yblIV=w|pGk7+ zChG0Dy~rHOK1Z}(>0iZDOF^?7HV2aYQZklSUv5SgTzl!7E#o4p(rOC24ScRx|^VD=~3JdRynp4w?)W(5A0 z)_C3;5w{#ut;AeK9af+D3$6?#Btje>?{BQL*L-vD2I8Ik7Vg!@QnLe zppa1pgsr!=`wq1_mTHZ}C3xl@K9Vf_gQQRAD_36GdaZ87H=x1+REu&}7i5gjPv`MP z?=NN3^VvFySA4Is?wUDmnv~`eOyF%d=CNUipe$ZOJ}FZgXz3+QW*Yt>xpMko-JL05 zks6_=q<8Zb!SRc%GSdhvd#^TbuH?h6Nef0sA3Wjvs`Q+zGw6AI#HO>wHLBBX;iyJI zFZ5A$b~Ji_KEX=v=l0q7@oKkklDfM5JEnZw<(BE1>)c*>-8TRsJgfKBDNYu#C!HGU zbLvbP6<#?=;4iU0T&Pb*LBnMo{A)%V&E)8oVNDoVfNMGIGqDC~Tscy8s*HW5h(C^+ zG%$nRO&>=ccGarn_c)}SF|TH0#$7Cx8+pN%20+veAhSU?RF1MOcSo&5t!{_L=^j!S zwpKQodunYpRvLi#(OCA4LtJoKXSCHK;j8k9qyr5?e~KQ|t>1+SXe) z>)&;E*Mlsb=gfL7YJkKP1nqI#dXEOw6i8@(OKrTvK3jR+J9~Xn-iY+EwA~bLWlsRR z23NE2O*dU)=1+e<1VW`GQj_6h3MbAnyDHL5QY*f|gl9W++|d2#xN2PS<3Ii9G|AA= zOQyQ5g5I}YLVzr($N9aHm+H&mo*)(pv+|j@cP5Nnz1nAZ%$JsKX2hLXNhUIS$$QnG z1AL<~%s^invTXLbb=gI`FD6^i`_j_7{ay3FG_nui=Feq_SET$RM11j`*GRQ*M5-@2 zd2E<{+liz^%K)8H_K-`#W19`%J018J8$M5t{XUL%67!Kv?T5Y6%HoSPfj9xo@SRNA zO&i%cnz)EbdPRxH)73v%VP9f)rk1ApgoAeZVYB+))9p8Bqd4&bBR~*`oNY>09O~N2 z!Rp>7KnHX=U8>;-697~ZJ_sN<+Irs|Hl_`;G1z694OixT`*V|Cz_YBGLc(tM@Kohm z>JD&MYd3Xf+B|B;lk$xwEPD9_~%=V(vx(C@a6Y-H$#=bfVOn57$&>rkwrVs4#bi zIXh7e(IM6w&y9tw+~I(;y6HV5=yM_(oXxC~r9=|;e>##2d}?n{dgmZtm$kdn2_X2$ zZn1&1c*eQwvMIIRLX^A-fxxJ(8WBPe?||LSuy z{t{iR`A!>-41uqe*4_8|FWHQLq|ffyeq*aJzDYNo!z||t!@KwR;k$ICGOlv)`wp!Q zFe7=&V)-C1g>f{5f5E>X@5^pc*;|x_)H3t0Wj(Hdf}t6f7dj;Lm3y|b61$Fgis3HI zZZTE=iadp@o=Y|={({-`cL3Mp!SitW{cQ0t++xA?d#mq<7jHsy-_FH#^te&BG6e9=TM4K?yE4$gLtJB{QzeetB zryUa6*x1vKi=Ur?^*FjI-@8jse%C$IlbLGM)=y!06b)*c>gqrMkCt)IoHxxwf;h>K zI$ZxUI0Qd&(@HM3+nD1SE<}@A-dyZ1FM9v|iBvCi@E-ah@k7-!4x7-5u`g+?MqO*l zm)P-Zzu$iR6iAlY+w9>D6kT>tx3it8Zf2XNw7OwQn=-dqz_;&l(OUI~)JrvPrtJfn zwVGJjkAIYJ@iHeSyf)eOw~G0ZJld2UGPIIZu3h{4455%Qbz6lZW74FexmYeYM;8aI z$K-h3Y^GFFCuw>-YX)_9?Ig^9A4wx1xQ2#eYVG!-LK}|bv$R8@eqlJgC_fD*}q9KhIE1f_i#O7_ zT)%x`)T#K2OJP6!v6Vb?t~cc+MQq6?;as!glC6mA<(e z<%lFRX`h0@1C67z0NHWh|ZjuVZ|V8t@FP@kIUYdtPp)2I9s3B_BXeBp}-ZP z5|l~AJ-|-~e7adHXKm6rZHQ~nBqb!qRwUhuE_?tsh^Kl=Hlz{jJv5 z%a`iA?S8PdtMf0~>M^6t2;7z3^z?rn(s|R}N+Jo!JO1-*rxQyqqw0F6X>RM!ACLOT zz2%2LmeJ%LT4#%}#EGCHI_{2UWy@EDyhONJs|(RvT?Z?St5 zJe~uJKn9oH8ehO#Qs>h$z{xbsOPOK-DR@vG_GmD%r#DqpIINVFeAg~=yeiV@S@ycUgHP|m(|5vgek*ZEH4RdwK{d$6jL>+4X z`4ChMuWjS9nJF{!ij95ygn<6)v21l;z0gZ@UjZab`9s9KK++(ZU}hS#jlPp@YHsdX+N+j<%}bAm_k9)T8@LAgyH4JzSyw>)>XO5eYZ-f(KZq4CZ8KAE}&p33a#nAw#ZL!zhkYZa0_fy&Jh12UfTAj4W?< z)O2(X-CC!M1+7n}8-n0j-m&cbyUhc#29lDYkyrH{#~wfcNz*@%?SyYHR3jK#qYkg` zfOxt;Xp>!NetI3?-j2$*c6E0peFJ1k0qtRyN~0J}eb0QIcI)6yPMaCaqc?e?=5%L0 z!wWTLgHwtNdLFYf->C5f&&TSGJKKO9egTz|q7H=dL_|bSuP9CLa~>76 znCtPqJkWLkR->ldp7iOcx({hE83#s3x$hnxA+ElF{8rgnRi*qnM5H$vfR4=(~l-hR-WQi)59iT6|TZNDzuRd5R$FCqNF)uguYRz#H!g{_d46@8|;6d)C31g+?wwl9UWUN!_7@iU(y8@`IP%@=plBH%=02yJ&ynGhwto!JlUOX z4ZlnR=UHTX(m73bJ`MY1G35^fepmv;GCh*P+1Gq7e{QeWW1q~jSlc~K9=z&1x!R5Sw+>Pg|4d7B*QMP1eov^xZ{boH28L>~l{Zhb#6){LZ zm@6K(L>wtG?EU!}!s|J9nZo{zoX5(&q`-6B*F~kgn1RWbz(S1+KjtWyba%eqCgn)S zFN@z*^(@_A3M$`75z6`%5E_kQVPm~8vUW(0-)Xpgi@MOw2BBVq0JDHsQp!G~mGIp` zt+g8jO^5Tn$1Dr}bH1cx#Vy}6vXegp0~5m=T_@{(WO?uY<)bNy2_cW;Z}e~9$_)RA z&R+=3N)8DzIPSQK_PD=ZR~&XP^$^GwPJke6@_WV`6v&1R5CO#>3rm*Q23Pe8MP7zS zN4FFUff1Z$-rRg+ zUOSJkl&izPHIn6>?4GZlL7(#}f01PSSIocavf%MkVJQEWW_pySvMFl!k06}^LD&vwY0rFM7Sdo{5 z!^6JOK>wyp&Wqx=>r``x(>dQU>14zTUKY_wnmZX{if`ugWtEtf5;FbfaR!RPMaJd=iiHkN)+{o zw=7_sEj@pbvWiNnS(}3oHAP5B$P(ALz1hl~T>aEY-XZhaZD8r8xs7nX)xEONDCjv; zOUTNmo&)Iqji8`liKzLOKAgKFJ{IZWuJ!WaoUryyAsQa}xqK??8(ZCEx7KBV%c+g} zKb}#TJ3DI#oj_gNy)Lv4->#&&w<8@3lV0qv{JbmRz6E=*>$kXAjlB;|IzAm_X;uCB zv75{DlZUCPX_L_PUzBOWE8nZ-zMA|iD#R`FU!}FRHDgRnO#Q#U-C^A-YHAzgg4T%^ zfT5UUrP9zgG!1;~y?UlKy%*}N2#Hw+^T|{6+|stQd7Vod9abu&XJ-I|3zTY{NPshIIhMP4(e)?%0Uv@SDj|pppr_Jb?SU%^oes09s*d=hLG% ze`5g7Pg|}#S=k6d+Fsg@%%xAxPEJlx7nk#=$7MiN?f*(I2$fs2BE8qna6zlDpw#AvWn%g%t!02^>Yj~m`Jc$>iH%XJ+e zZKMxoZxEm;V0$ox2?Us2H~)s3I>H<)HIzL9C2*B2%2% zuoz$qGG)~AC_jk0_89l)-w}Kjrep=sU*p1KA%bo<^)Jj!7x@I^8msO> z4>V)boi5cC6{?m%cYKi1zpQXO7Sj9MjcR~0ZwA;qj*h|~Zix)e+JeBwbFm_`UgUBj zgZ3CD_k(a;jH;dGQ*p3Bd%O`FzipXyFXu?vx-t zRRt(cFcEnGVV%fzDOH|TTM%e0EhS#yS{w_?&t<&+7NqhCIwh;+O2Q)sTsc~YfC3bU zq)x}416#3Ue7ioXI|D~PEaz~kUWr15fPZx;b=F9Tzwr0+<&|tGXq@ z-!p+0U!6Y(5C2L=UkFUuSvc=t6~zQS+H_VW)Q7oK9zW$`$z@cCY7+mxgHfQ2uQhZ-Bg6F)mmEz|j=0p4I}11k?as_b+mA%#j1I8iXEwQXk2s&yQGt+}5bJPGb zYs;@L`=D=*mVrBcjz(@?+%AG&0^6ZbXHPVwwQtYzgjukZEJ2bVC7?Lfli&RQ%4ql> zZ3Bjstq?yQBdHTP-^B*^9^)d5i0V_-08a5k6bqU|cZ>@XF)H;$15M;U%QGN@6}Z0a%$-dB3&%`n1N7*~lrtIJ9})K!Z&`SKbd?mA;INup)SGh_}|FuM4}K3U^9Fb8+f3I)=dOLQaPRBqE3YvwXIT1%t;9*xKkQh>Kn}+ z;Q<4<$i;f+^O`#E1n{wLZ`^)rpKs3y{DkQ8RNlH1vu<1qB`m4Ar|D>VgG6BuM+f>~Dm_|t=53>L+p^5?Ap9utF zppJ$KnZyZs@R1KmMUXW&i^`seS3FLP#h)k*_YGfPxP+Lf^-x z_sPQj+kVNDcrI(6;l2Q!R|cD$^7tp7bf7;!t@&f~h=LG73c#aHVNd&EsO|JDJ9OOx z4GDygnsW{dr3{vF5xpd#k62wqCZIlHJHXZfU5XlU_yV<>Rk0;H^GfkD(N zC8;^cd!U6lfJ^KX0@2Cm4 zd=8d)ev_63t*c7*w-JRN1{3v+Dme+gIiEr$x928QNy2pGAlduak_Nks{AB%r4d$fH zGhrW1qRbq8d%BIF&*L}E-fw%oD&cP&m%}Rqb%t5mz_v?@_2O7|JOgdKNWi}S@&06z zP{QC}7)~36DkZQSelp`cI3;!}dXmDmA1C4Sk2IJkXca2?Rq1CeU5pr=Z$Eb|MA79r zy57rE7PN*8KqGRYA39>(eT2c|(NGsfr{%mU54|>P>rf=dU$a zVl0M^67U>rcEgp*DN>+P_xfhO3&BA|ja^IR9nZ)3c|`h+cLeVW#xuq+3uv}nG%A6$ z#JM=Sf#pn?8f_ORN$Xqfs`b>*IN!zY+eSWe1i~INHf-G~8xDL(&1R?cv=sOgWv}k5 zvteF@Dw-i34yuxg_Ahk2WZ_t?;YIDiHl87$aT0m1go-04L)r0u>_1x^n=umxKkx@T zXKB)YVqzl*IYMPkmI~jo$xVn-{?=xiJ8`YE6AE&DmVLZJomVQhqu;I!nEhjZSW}A& z9aUJDnK_|~5?EL>2L>l;*|=qJIbzC{IPFmO%Mz2JRMpR3A?xzA_EP8?g@56F6FM$q zslHsKdNUki-|0=HpNsVPE(Hds%j;8TT#?q*MZ~(-<~C%b_A2|X}`fHdwvLeljj~n5@a2L|D4uGt&g#XQX&30uL+(&sRQi{`=)W|ELz*%Z{nK;cEHSxzI zsrA`<4Rz6Z8InRbWPpDMuP7)CHtM(&gT2jMVmcA6EvW4pd-}Qk^8M1f ztkSjGqJ~jOXiyi^+0T{nVA#S8`(S%RprmWLq)G}RWd2UQ3q_lH)oTEP+*uVvg!LsN zp4D^TqM1J4uq;@HeYBs!V3ZI;JIi2~d7$Bqe6W{zYP=5{*J{>)N}3r95vhNZ5{>PP zuI(%1IF+xoU4$(JU!{WLTR0_#*HMh#ml-ls=i#wjLt?A2l@z+gU?w4~g&W3HA^s`4 z4F}UB7IHlO-A+nWfeRdy@gjRdiHelQl{X=Mi%^&FKd0*<@l5nI+3Vc#h{rC$Kmoe- zvpZ3bMn*|-qZj5396y5q;CzC9kn7s`b9To2s502|i^nLOu-LIIk#*-sAS;X19xv|T z{0*ls}liCZmq|f?Z;8zxgGkM?Er0=gxe!}5B)Cfts%zx+KRG~>%xK$^Qwgd zxLTF&cv9bZ<-o^?!iTp33(@-}y0vl_)2I~G)HF}92jl3v=#<)O=E7Rmdy2oglf|Hk z9aQ(|WOUn)IJ?Ev)&Fx6bF6)kaLn)DLr)thofgM!&@~!rT^O7bt@e5Or7|3fA$%9Z zdcgKVh^j?@4Sr`l^A=M|1^Pj?Yjm{L@U2TTmvgF?=HwY>`I&p}76Dqk08?8TUT-A< znh@%m4Kr8Z2eAG|xkt@vbVWTWWo?7J*w`48u>8$6i$5I*42V{tPKX%OlI`)B z()!3ib)k>8#b55^e=w>k^6=B1ZbJ{JnSv5WmCH4hd6f6{<7;|@XRLCWiDm99yGhA{}Wd_r0D9El$(X5~ZD@6Yeq%JJ_WnN-%QoT_^& zls{`|J%9EnfAEk~Gyx};)G-ocS*iS3?;B@s#A40HNR)|D9E{SnkxmA^FH@JMsvova zX8&ayT=lAu;Am_z@Z2<%$ z6{BjEfS{w}t2VXwOJOAH%tlL96JNh1#=Wf*>*+C=wXQ*vNIs(oaU1*ElJg~AWBoz3 zYsEM6%XU&tu#eu|7g)PJi(C|&tXR}Xn&hnaxd#gx>+j>0Lv??-YpZnq{-}DCX85D* z_dAPe6Sn6vuwUIAo->ylZ}KI6nQVFL;mT@J6n=}jh-Pjuf%pEv++Pdkdj*Zwp7DBP zrhTtVw6{gZP)&6$66l-|HJ4w8%;eg~^EPs4nrqIew2C|SrN%S*vk{KJr_g;`Y{qKK za@>)WYnnH1$Y7g~H208STe0$q*DizuUr(^Zw@=B+o)Nq~aS$e4yGfT@>daH^DKIsz z)cwow6@MRvpi+T4eltCU8Nd3QQI$>-+ zFgW?Ai;?m(M6`3~3t0MUNoj|7dB1(@$eb{5jiAiUXxRcsX%N7syb8a-?5DbXQY&dt z%QtBuucYrm*1Dmz5?dn{A0>WU5x4YjETQ|M(8cAmSNvkb`2Ku7q`f}>zYyO<$8g@x zUzs*Gk#M%Gr7AVQ9ITO)uwuolOW^S4&Y0P4a>%SIVE2Gjj|O|=mQu{^v#Iu?g_u(5R=+V-wf&8^chyn4kgY80C{bYAldhLKCoo`h9f)w_=Um8!5STwbwF{_U3Tizp{AyHC84h8bs|GATle zy3F*$Rqlvr6MURu^<;ctoJ-C-Z#8oO_$tvow?$;EY1DOi-(^S-2TIzlGbRuwb&;-U z7yZw0dus6-cg1D}!{`%wA1C;jA;~pKJ=T-XVnJJKHRncn?@V?ZaEO-)De!(_{cb?PQZM`vF>be}<$+yB>x!n%iMG>Ka&r0;UkQJwE7Mk z$`Z}Z4DInTXYHvlPzHtdM7q)!O@~4(CDCwL6=&P!6H8`ZIu8IG){ebnFOOsgJi5#J zo*23$q%3OfclD3VJx10L$%S6mR#0O{Z-fm;yH{W~(%~1?#@9nDw|X-FV4WFNNE?u= zNsUpZB9>X39R6ko>B{E@palselu!fi@;2{*99+kw!vd7==a0k1U~mtD?VxZfC+5?F zS*Nm{8|Z%mvGF+lu?k#)zW_q@WO_h`!~-H-wk-C(55!&CS9;0~tCO{qo!|0Ld`A4R z!?{Ezel$sA7!Q>QFASC6a)j3Q9elimCP?JOd_Bc7+iW%D38BRl_}=XI4MruG!$~Y! z)#3G0Ing0FLqmnq)N|04xKy0c__kp$%3zYQ=jbnv1!pZF??**9r5!AA6QQz8HaBac z-)DvlmLg^;&QlPoDNzVPj2csI+Sp_GZ>Y~5tTw?OOsB`~G>Igi6#!z}vZxRn z_mZ3%^Wj5E=1-Gbo9g3YL(lz--KY}z4P9;Rev`lWf1j9yQ{VAp+Sf5=7Hy=={c`2yJadWY-BAQd=Lk{ z_R5BjK&)=KT9B)gLV{1>rb2!28ThgAIW#%qO5B*yF`N0*A1srvHd0v*yWIk#^?)Ts zM5jSs*i*xFz2D7|(i500ZVx1J5^<9kp}e$hGHAC2LutRtBH%ytYf07!h%N|p$O_p@ zM76*Ze2pGv`4>e77PC@W+j}V~VvZ$pJA7_u0J6SUt6#Bso7y)~k6x^LN|Y_7g&3t~ zc23kDyJ8C;xg3Hmb~#>n;^|83;U1180$1Uh7VPe5U0Yj3=xI`|HIDic);1 z%Zx)#tB~cm_w^{1mrymqhd`i6ceMi`P*4dL1i~7qi~&@l{y)Y0VJg~EDlzW{YoEjk QxT*u><#`b=z=h}h2b9~@i2wiq diff --git a/evaluator/tier4_metrics_rviz_plugin/include/metrics_visualize_panel.hpp b/evaluator/tier4_metrics_rviz_plugin/include/metrics_visualize_panel.hpp deleted file mode 100644 index 3d66099988d8b..0000000000000 --- a/evaluator/tier4_metrics_rviz_plugin/include/metrics_visualize_panel.hpp +++ /dev/null @@ -1,254 +0,0 @@ -// Copyright 2024 TIER IV, Inc. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// - -#ifndef METRICS_VISUALIZE_PANEL_HPP_ -#define METRICS_VISUALIZE_PANEL_HPP_ - -#ifndef Q_MOC_RUN -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#endif - -#include -#include - -#include - -#include -#include -#include -#include -#include -#include - -namespace rviz_plugins -{ - -using diagnostic_msgs::msg::DiagnosticArray; -using diagnostic_msgs::msg::DiagnosticStatus; -using diagnostic_msgs::msg::KeyValue; -using QtCharts::QChart; -using QtCharts::QChartView; -using QtCharts::QLineSeries; - -struct Metric -{ -public: - explicit Metric(const DiagnosticStatus & status) : chart(new QChartView), table(new QTableWidget) - { - init(status); - } - - void init(const DiagnosticStatus & status) - { - QStringList header{}; - - { - auto label = new QLabel; - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(status.name)); - labels.emplace("metric_name", label); - - header.push_back("metric_name"); - } - - for (const auto & [key, value] : status.values) { - auto label = new QLabel; - label->setAlignment(Qt::AlignCenter); - labels.emplace(key, label); - - auto plot = new QLineSeries; - plot->setName(QString::fromStdString(key)); - plots.emplace(key, plot); - chart->chart()->addSeries(plot); - chart->chart()->createDefaultAxes(); - - header.push_back(QString::fromStdString(key)); - } - - { - chart->chart()->setTitle(QString::fromStdString(status.name)); - chart->chart()->legend()->setVisible(true); - chart->chart()->legend()->detachFromChart(); - chart->setRenderHint(QPainter::Antialiasing); - } - - { - table->setColumnCount(status.values.size() + 1); - table->setHorizontalHeaderLabels(header); - table->verticalHeader()->hide(); - table->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); - table->setRowCount(1); - table->setSizeAdjustPolicy(QAbstractScrollArea::AdjustToContents); - } - } - - void updateData(const double time, const DiagnosticStatus & status) - { - for (const auto & [key, value] : status.values) { - const double data = std::stod(value); - labels.at(key)->setText(QString::fromStdString(toString(data))); - plots.at(key)->append(time, data); - updateMinMax(data); - } - - { - const auto area = chart->chart()->plotArea(); - const auto rect = chart->chart()->legend()->rect(); - chart->chart()->legend()->setGeometry( - QRectF(area.x(), area.y(), area.width(), rect.height())); - chart->chart()->axes(Qt::Horizontal).front()->setRange(time - 100.0, time); - } - - { - table->setCellWidget(0, 0, labels.at("metric_name")); - } - - for (size_t i = 0; i < status.values.size(); ++i) { - table->setCellWidget(0, i + 1, labels.at(status.values.at(i).key)); - } - } - - void updateMinMax(double data) - { - if (data < y_range_min) { - y_range_min = data > 0.0 ? 0.9 * data : 1.1 * data; - chart->chart()->axes(Qt::Vertical).front()->setMin(y_range_min); - } - - if (data > y_range_max) { - y_range_max = data > 0.0 ? 1.1 * data : 0.9 * data; - chart->chart()->axes(Qt::Vertical).front()->setMax(y_range_max); - } - } - - void updateTable() { table->update(); } - - void updateGraph() { chart->update(); } - - QChartView * getChartView() const { return chart; } - - QTableWidget * getTable() const { return table; } - - std::unordered_map getLabels() const { return labels; } - -private: - static std::optional getValue(const DiagnosticStatus & status, std::string && key) - { - const auto itr = std::find_if( - status.values.begin(), status.values.end(), - [&](const auto & value) { return value.key == key; }); - - if (itr == status.values.end()) { - return std::nullopt; - } - - return itr->value; - } - - static std::string toString(const double & value) - { - std::stringstream ss; - ss << std::scientific << std::setprecision(2) << value; - return ss.str(); - } - - QChartView * chart; - QTableWidget * table; - - std::unordered_map labels; - std::unordered_map plots; - - double y_range_min{std::numeric_limits::max()}; - double y_range_max{std::numeric_limits::lowest()}; -}; - -class MetricsVisualizePanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit MetricsVisualizePanel(QWidget * parent = nullptr); - void onInitialize() override; - -private Q_SLOTS: - // Slot functions triggered by UI events - void onTopicChanged(); - void onSpecificMetricChanged(); - void onClearButtonClicked(); - void onTabChanged(); - -private: - // ROS 2 node and subscriptions for handling metrics data - rclcpp::Node::SharedPtr raw_node_; - rclcpp::TimerBase::SharedPtr timer_; - std::unordered_map::SharedPtr> subscriptions_; - - // Topics from which metrics are collected - std::vector topics_ = { - "/diagnostic/planning_evaluator/metrics", "/diagnostic/perception_online_evaluator/metrics"}; - - // Timer and metrics message callback - void onTimer(); - void onMetrics(const DiagnosticArray::ConstSharedPtr & msg, const std::string & topic_name); - - // Functions to update UI based on selected metrics - void updateViews(); - void updateSelectedMetric(const std::string & metric_name); - - // UI components - QGridLayout * grid_; - QComboBox * topic_selector_; - QTabWidget * tab_widget_; - - // "Specific Metrics" tab components - QComboBox * specific_metric_selector_; - QChartView * specific_metric_chart_view_; - QTableWidget * specific_metric_table_; - - // Selected metrics data - std::optional> selected_metrics_; - - // Cache for received messages by topics - std::unordered_map current_msg_map_; - - // Mapping from topics to metrics widgets (tables and charts) - std::unordered_map< - std::string, std::unordered_map>> - topic_widgets_map_; - - // Synchronization - std::mutex mutex_; - - // Stored metrics data - std::unordered_map metrics_; - - // Utility functions for managing widget visibility based on topics - void updateWidgetVisibility(const std::string & target_topic, const bool show); - void showCurrentTopicWidgets(); - void hideInactiveTopicWidgets(); -}; -} // namespace rviz_plugins - -#endif // METRICS_VISUALIZE_PANEL_HPP_ diff --git a/evaluator/tier4_metrics_rviz_plugin/package.xml b/evaluator/tier4_metrics_rviz_plugin/package.xml deleted file mode 100644 index d06382bc8c539..0000000000000 --- a/evaluator/tier4_metrics_rviz_plugin/package.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - - tier4_metrics_rviz_plugin - 0.0.0 - The tier4_metrics_rviz_plugin package - Satoshi OTA - Kyoichi Sugahara - Maxime CLEMENT - Kosuke Takeuchi - Fumiya Watanabe - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - diagnostic_msgs - libqt5-charts-dev - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rviz_common - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/evaluator/tier4_metrics_rviz_plugin/plugins/plugin_description.xml b/evaluator/tier4_metrics_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index 5aca5bd7faa54..0000000000000 --- a/evaluator/tier4_metrics_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,5 +0,0 @@ - - - MetricsVisualizePanel - - diff --git a/evaluator/tier4_metrics_rviz_plugin/src/metrics_visualize_panel.cpp b/evaluator/tier4_metrics_rviz_plugin/src/metrics_visualize_panel.cpp deleted file mode 100644 index b92a9a7ace53d..0000000000000 --- a/evaluator/tier4_metrics_rviz_plugin/src/metrics_visualize_panel.cpp +++ /dev/null @@ -1,262 +0,0 @@ -// Copyright 2024 TIER IV, Inc. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// - -#include "metrics_visualize_panel.hpp" - -#include - -#include - -#include -#include -#include -#include - -namespace rviz_plugins -{ -MetricsVisualizePanel::MetricsVisualizePanel(QWidget * parent) -: rviz_common::Panel(parent), grid_(new QGridLayout()) -{ - // Initialize the main tab widget - tab_widget_ = new QTabWidget(); - - // Create and configure the "All Metrics" tab - QWidget * all_metrics_widget = new QWidget(); - grid_ = new QGridLayout(all_metrics_widget); // Apply grid layout to the widget directly - all_metrics_widget->setLayout(grid_); - - // Add topic selector combobox - topic_selector_ = new QComboBox(); - for (const auto & topic : topics_) { - topic_selector_->addItem(QString::fromStdString(topic)); - } - grid_->addWidget(topic_selector_, 0, 0, 1, -1); // Add topic selector to the grid layout - connect(topic_selector_, SIGNAL(currentIndexChanged(int)), this, SLOT(onTopicChanged())); - - tab_widget_->addTab( - all_metrics_widget, "All Metrics"); // Add "All Metrics" tab to the tab widget - - // Create and configure the "Specific Metrics" tab - QWidget * specific_metrics_widget = new QWidget(); - QVBoxLayout * specific_metrics_layout = new QVBoxLayout(); - specific_metrics_widget->setLayout(specific_metrics_layout); - - // Add specific metric selector combobox - specific_metric_selector_ = new QComboBox(); - specific_metrics_layout->addWidget(specific_metric_selector_); - connect( - specific_metric_selector_, SIGNAL(currentIndexChanged(int)), this, - SLOT(onSpecificMetricChanged())); - - // Add clear button - QPushButton * clear_button = new QPushButton("Clear"); - specific_metrics_layout->addWidget(clear_button); - connect(clear_button, &QPushButton::clicked, this, &MetricsVisualizePanel::onClearButtonClicked); - - // Add chart view for specific metrics - specific_metric_chart_view_ = new QChartView(); - specific_metrics_layout->addWidget(specific_metric_chart_view_); - - tab_widget_->addTab( - specific_metrics_widget, "Specific Metrics"); // Add "Specific Metrics" tab to the tab widget - - // Set the main layout of the panel - QVBoxLayout * main_layout = new QVBoxLayout(); - main_layout->addWidget(tab_widget_); - setLayout(main_layout); -} - -void MetricsVisualizePanel::onInitialize() -{ - using std::placeholders::_1; - - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - for (const auto & topic_name : topics_) { - const auto callback = [this, topic_name](const DiagnosticArray::ConstSharedPtr msg) { - this->onMetrics(msg, topic_name); - }; - const auto subscription = - raw_node_->create_subscription(topic_name, rclcpp::QoS{1}, callback); - subscriptions_[topic_name] = subscription; - } - - const auto period = std::chrono::milliseconds(static_cast(1e3 / 10)); - timer_ = raw_node_->create_wall_timer(period, [&]() { onTimer(); }); -} - -void MetricsVisualizePanel::updateWidgetVisibility( - const std::string & target_topic, const bool show) -{ - for (const auto & [topic_name, metric_widgets_pair] : topic_widgets_map_) { - const bool is_target_topic = (topic_name == target_topic); - if ((!is_target_topic && show) || (is_target_topic && !show)) { - continue; - } - for (const auto & [metric, widgets] : metric_widgets_pair) { - widgets.first->setVisible(show); - widgets.second->setVisible(show); - } - } -} - -void MetricsVisualizePanel::showCurrentTopicWidgets() -{ - const std::string current_topic = topic_selector_->currentText().toStdString(); - updateWidgetVisibility(current_topic, true); -} - -void MetricsVisualizePanel::hideInactiveTopicWidgets() -{ - const std::string current_topic = topic_selector_->currentText().toStdString(); - updateWidgetVisibility(current_topic, false); -} - -void MetricsVisualizePanel::onTopicChanged() -{ - std::lock_guard message_lock(mutex_); - hideInactiveTopicWidgets(); - showCurrentTopicWidgets(); -} - -void MetricsVisualizePanel::updateSelectedMetric(const std::string & metric_name) -{ - std::lock_guard message_lock(mutex_); - - for (const auto & [topic, msg] : current_msg_map_) { - const auto time = msg->header.stamp.sec + msg->header.stamp.nanosec * 1e-9; - for (const auto & status : msg->status) { - if (metric_name == status.name) { - selected_metrics_ = {metric_name, Metric(status)}; - selected_metrics_->second.updateData(time, status); - return; - } - } - } -} - -void MetricsVisualizePanel::updateViews() -{ - if (!selected_metrics_) { - return; - } - - Metric & metric = selected_metrics_->second; - specific_metric_chart_view_->setChart(metric.getChartView()->chart()); - auto * specific_metrics_widget = dynamic_cast(tab_widget_->widget(1)); - auto * specific_metrics_layout = dynamic_cast(specific_metrics_widget->layout()); - specific_metrics_layout->removeWidget(specific_metric_table_); - specific_metric_table_ = metric.getTable(); - QSizePolicy sizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); - sizePolicy.setHeightForWidth(specific_metric_table_->sizePolicy().hasHeightForWidth()); - specific_metric_table_->setSizePolicy(sizePolicy); - specific_metrics_layout->insertWidget(1, specific_metric_table_); -} - -void MetricsVisualizePanel::onSpecificMetricChanged() -{ - const auto selected_metrics_str = specific_metric_selector_->currentText().toStdString(); - updateSelectedMetric(selected_metrics_str); - updateViews(); -} - -void MetricsVisualizePanel::onClearButtonClicked() -{ - if (!selected_metrics_) { - return; - } - updateSelectedMetric(selected_metrics_->first); - updateViews(); -} - -void MetricsVisualizePanel::onTimer() -{ - std::lock_guard message_lock(mutex_); - - for (auto & [name, metric] : metrics_) { - metric.updateGraph(); - metric.updateTable(); - } - - if (selected_metrics_) { - selected_metrics_->second.updateGraph(); - selected_metrics_->second.updateTable(); - } -} - -void MetricsVisualizePanel::onMetrics( - const DiagnosticArray::ConstSharedPtr & msg, const std::string & topic_name) -{ - std::lock_guard message_lock(mutex_); - - const auto time = msg->header.stamp.sec + msg->header.stamp.nanosec * 1e-9; - constexpr size_t GRAPH_COL_SIZE = 5; - - for (const auto & status : msg->status) { - const size_t num_current_metrics = topic_widgets_map_[topic_name].size(); - if (metrics_.count(status.name) == 0) { - const auto metric = Metric(status); - metrics_.emplace(status.name, metric); - - // Calculate grid position - const size_t row = num_current_metrics / GRAPH_COL_SIZE * 2 + - 2; // start from 2 to leave space for the topic selector and tab widget - const size_t col = num_current_metrics % GRAPH_COL_SIZE; - - // Get the widgets from the metric - const auto tableWidget = metric.getTable(); - const auto chartViewWidget = metric.getChartView(); - - // Get the layout for the "All Metrics" tab - auto all_metrics_widget = dynamic_cast(tab_widget_->widget(0)); - QGridLayout * all_metrics_layout = dynamic_cast(all_metrics_widget->layout()); - - // Add the widgets to the "All Metrics" tab layout - all_metrics_layout->addWidget(tableWidget, row, col); - all_metrics_layout->setRowStretch(row, false); - all_metrics_layout->addWidget(chartViewWidget, row + 1, col); - all_metrics_layout->setRowStretch(row + 1, true); - all_metrics_layout->setColumnStretch(col, true); - - // Also add the widgets to the topic_widgets_map_ for easy management - topic_widgets_map_[topic_name][status.name] = std::make_pair(tableWidget, chartViewWidget); - } - metrics_.at(status.name).updateData(time, status); - - // update selected metrics - const auto selected_metrics_str = specific_metric_selector_->currentText().toStdString(); - if (selected_metrics_str == status.name) { - if (selected_metrics_) { - selected_metrics_->second.updateData(time, status); - } - } - } - - // Update the specific metric selector - QSignalBlocker blocker(specific_metric_selector_); - for (const auto & status : msg->status) { - if (specific_metric_selector_->findText(QString::fromStdString(status.name)) == -1) { - specific_metric_selector_->addItem(QString::fromStdString(status.name)); - } - } - - // save the message for metrics selector - current_msg_map_[topic_name] = msg; -} - -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::MetricsVisualizePanel, rviz_common::Panel) diff --git a/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt b/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt deleted file mode 100644 index 9e8bb20bb92a3..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(rqt_diagnostic_graph_monitor) - -find_package(autoware_cmake REQUIRED) -autoware_package() -ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR python) -install(FILES plugin.xml DESTINATION share/${PROJECT_NAME}) -install(PROGRAMS script/rqt_diagnostic_graph_monitor DESTINATION lib/${PROJECT_NAME}) -ament_auto_package(INSTALL_TO_SHARE script) diff --git a/tools/rqt_diagnostic_graph_monitor/README.md b/tools/rqt_diagnostic_graph_monitor/README.md deleted file mode 100644 index 8dccca34db8c5..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/README.md +++ /dev/null @@ -1 +0,0 @@ -# System diagnostic monitor diff --git a/tools/rqt_diagnostic_graph_monitor/package.xml b/tools/rqt_diagnostic_graph_monitor/package.xml deleted file mode 100644 index 60780e2794998..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/package.xml +++ /dev/null @@ -1,24 +0,0 @@ - - - - rqt_diagnostic_graph_monitor - 0.1.0 - The rqt_diagnostic_graph_monitor package - Takagi, Isamu - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - python_qt_binding - rqt_gui - rqt_gui_py - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/tools/rqt_diagnostic_graph_monitor/plugin.xml b/tools/rqt_diagnostic_graph_monitor/plugin.xml deleted file mode 100644 index 6c64185e3f0af..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/plugin.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - folder - - - - utilities-system-monitor - - - - diff --git a/tools/rqt_diagnostic_graph_monitor/python/__init__.py b/tools/rqt_diagnostic_graph_monitor/python/__init__.py deleted file mode 100644 index 10f125fa447b5..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/python/__init__.py +++ /dev/null @@ -1,37 +0,0 @@ -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from rqt_gui_py.plugin import Plugin - -from .module import MonitorModule -from .widget import MonitorWidget - - -class MonitorPlugin(Plugin): - def __init__(self, context): - super().__init__(context) - self.widget = MonitorWidget() - self.module = MonitorModule(context.node) - self.module.append_struct_callback(self.widget.on_graph) - context.add_widget(self.widget) - - def shutdown_plugin(self): - self.module.shutdown() - self.widget.shutdown() - - def save_settings(self, plugin_settings, instance_settings): - pass - - def restore_settings(self, plugin_settings, instance_settings): - pass diff --git a/tools/rqt_diagnostic_graph_monitor/python/graph.py b/tools/rqt_diagnostic_graph_monitor/python/graph.py deleted file mode 100644 index cea81c1226637..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/python/graph.py +++ /dev/null @@ -1,127 +0,0 @@ -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from diagnostic_msgs.msg import DiagnosticStatus -from rclpy.time import Time - - -class DummyStatus: - def __init__(self): - self.level = DiagnosticStatus.STALE - - -class BaseUnit: - def __init__(self, status=DummyStatus()): - self._parents = [] - self._children = [] - self._path = None - self._type = None - self._status = status - - @property - def parents(self): - return self._parents - - @property - def children(self): - return self._children - - @property - def path(self): - return self._path - - @property - def kind(self): - return self._type - - -class NodeUnit(BaseUnit): - def __init__(self, struct): - super().__init__() - self._path = struct.path - self._type = struct.type - - def update(self, status): - self._status = status - - @property - def level(self): - return self._status.level - - -class DiagUnit(BaseUnit): - def __init__(self, struct): - super().__init__() - self._path = struct.path - self._name = struct.name - self._type = "diag" - - def update(self, status): - self._status = status - - @property - def level(self): - return self._status.level - - -class UnitLink: - def __init__(self, parent: BaseUnit, child: BaseUnit): - self._parent = parent - self._child = child - parent._children.append(self) - child._parents.append(self) - - def update(self, status): - self.status = status - - @property - def parent(self): - return self._parent - - @property - def child(self): - return self._child - - -class Graph: - def __init__(self, msg): - self._struct_stamp = Time.from_msg(msg.stamp) - self._status_stamp = None - self._id = msg.id - self._nodes = [NodeUnit(struct) for struct in msg.nodes] - self._diags = [DiagUnit(struct) for struct in msg.diags] - self._units = self._nodes + self._diags - self._links = [] - for struct in msg.links: - units = self._diags if struct.is_leaf else self._nodes - nodes = self._nodes - self._links.append(UnitLink(nodes[struct.parent], units[struct.child])) - - def update(self, msg): - if msg.id == self._id: - self._status_stamp = Time.from_msg(msg.stamp) - for node, status in zip(self._nodes, msg.nodes): - node.update(status) - for diag, status in zip(self._diags, msg.diags): - diag.update(status) - for link, status in zip(self._links, msg.links): - link.update(status) - - @property - def units(self): - return self._units - - @property - def links(self): - return self._links diff --git a/tools/rqt_diagnostic_graph_monitor/python/items.py b/tools/rqt_diagnostic_graph_monitor/python/items.py deleted file mode 100644 index 96f60ef0e09cf..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/python/items.py +++ /dev/null @@ -1,54 +0,0 @@ -# Copyright 2024 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -from diagnostic_msgs.msg import DiagnosticStatus -from python_qt_binding import QtGui -from python_qt_binding import QtWidgets - -from .graph import BaseUnit -from .graph import UnitLink - - -class MonitorIcons: - def __init__(self): - self.disable = QtGui.QIcon.fromTheme("dialog-question") - self.unknown = QtGui.QIcon.fromTheme("system-search") - self.ok = QtGui.QIcon.fromTheme("emblem-default") - self.warn = QtGui.QIcon.fromTheme("emblem-important") - self.error = QtGui.QIcon.fromTheme("dialog-error") - self.stale = QtGui.QIcon.fromTheme("appointment-missed") - - self._levels = {} - self._levels[DiagnosticStatus.OK] = self.ok - self._levels[DiagnosticStatus.WARN] = self.warn - self._levels[DiagnosticStatus.ERROR] = self.error - self._levels[DiagnosticStatus.STALE] = self.stale - - def get(self, level): - return self._levels.get(level, self.unknown) - - -class MonitorItem: - icons = MonitorIcons() - - def __init__(self, link: UnitLink, unit: BaseUnit): - item_text = f"{unit.path} ({unit.kind})" if unit.path else f"({unit.kind})" - self.item = QtWidgets.QTreeWidgetItem([item_text]) - self.link = link - self.unit = unit - self.item.setIcon(0, self.icons.stale) - - def update(self): - self.item.setIcon(0, self.icons.get(self.unit.level)) diff --git a/tools/rqt_diagnostic_graph_monitor/python/module.py b/tools/rqt_diagnostic_graph_monitor/python/module.py deleted file mode 100644 index 74294659ef61a..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/python/module.py +++ /dev/null @@ -1,61 +0,0 @@ -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - - -from rclpy.node import Node -from tier4_system_msgs.msg import DiagGraphStatus -from tier4_system_msgs.msg import DiagGraphStruct - -from .graph import Graph -from .utils import default_qos -from .utils import durable_qos -from .utils import foreach - - -class MonitorModule: - def __init__(self, node: Node): - self.graph = None - self.struct_callbacks = [] - self.status_callbacks = [] - self.node = node - self.sub_struct = self.subscribe_struct() - self.sub_status = self.subscribe_status() - - def append_struct_callback(self, callback): - self.struct_callbacks.append(callback) - - def append_status_callback(self, callback): - self.status_callbacks.append(callback) - - def on_struct(self, msg): - self.graph = Graph(msg) - foreach(self.struct_callbacks, lambda callback: callback(self.graph)) - - def on_status(self, msg): - self.graph.update(msg) - foreach(self.status_callbacks, lambda callback: callback(self.graph)) - - def subscribe_struct(self): - return self.node.create_subscription( - DiagGraphStruct, "/diagnostics_graph/struct", self.on_struct, durable_qos(1) - ) - - def subscribe_status(self): - return self.node.create_subscription( - DiagGraphStatus, "/diagnostics_graph/status", self.on_status, default_qos(1) - ) - - def shutdown(self): - self.node.destroy_subscription(self.sub_struct) - self.node.destroy_subscription(self.sub_status) diff --git a/tools/rqt_diagnostic_graph_monitor/python/utils.py b/tools/rqt_diagnostic_graph_monitor/python/utils.py deleted file mode 100644 index 6e66102b16dc9..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/python/utils.py +++ /dev/null @@ -1,29 +0,0 @@ -# Copyright 2024 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from rclpy.qos import QoSDurabilityPolicy -from rclpy.qos import QoSProfile - - -def default_qos(depth): - return QoSProfile(depth=depth) - - -def durable_qos(depth): - return QoSProfile(depth=depth, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) - - -def foreach(iterable, function): - for item in iterable: - function(item) diff --git a/tools/rqt_diagnostic_graph_monitor/python/widget.py b/tools/rqt_diagnostic_graph_monitor/python/widget.py deleted file mode 100644 index e7f022e5907c0..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/python/widget.py +++ /dev/null @@ -1,85 +0,0 @@ -# Copyright 2023 The Autoware Contributors -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from python_qt_binding import QtCore -from python_qt_binding import QtWidgets - -from .graph import Graph -from .items import MonitorItem -from .utils import foreach - - -class MonitorWidget(QtWidgets.QSplitter): - def __init__(self): - super().__init__() - self.graph = None - self.items = [] - self.root_widget = QtWidgets.QTreeWidget() - self.tree_widget = QtWidgets.QTreeWidget() - self.root_widget.setHeaderLabels(["Top-level"]) - self.tree_widget.setHeaderLabels(["Subtrees"]) - self.addWidget(self.root_widget) - self.addWidget(self.tree_widget) - - self._timer = QtCore.QTimer() - self._timer.timeout.connect(self.on_timer) - self._timer.start(500) - - def shutdown(self): - self.clear_graph() - - def on_timer(self): - foreach(self.items, lambda item: item.update()) - - def on_graph(self, graph: Graph): - self.clear_graph() - self.build_graph(graph) - - def clear_graph(self): - self.graph = None - self.items = [] - self.root_widget.clear() - self.tree_widget.clear() - - def build_graph(self, graph: Graph): - self.graph = graph - root_units = filter(self.is_root_unit, self.graph.units) - tree_units = filter(self.is_tree_unit, self.graph.units) - root_items = [MonitorItem(None, unit) for unit in root_units] - tree_items = [MonitorItem(None, unit) for unit in tree_units] - link_items = [MonitorItem(link, link.child) for link in self.graph.links] - self.items = root_items + tree_items + link_items - - # Note: overwrite link items with root/tree items if there is more than one. - parents = {} - for items in [link_items, tree_items, root_items]: - parents.update({item.unit: item.item for item in items}) - - # Connect tree widget items. - root_widget_item = self.root_widget.invisibleRootItem() - tree_widget_item = self.tree_widget.invisibleRootItem() - for item in root_items: - root_widget_item.addChild(item.item) - for item in tree_items: - tree_widget_item.addChild(item.item) - for item in link_items: - parents[item.link.parent].addChild(item.item) - - @staticmethod - def is_root_unit(unit): - return len(unit.parents) == 0 - - @staticmethod - def is_tree_unit(unit): - return len(unit.parents) >= 2 and len(unit.children) != 0 diff --git a/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor b/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor deleted file mode 100755 index 8b0685125d026..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/script/cui_diagnostic_graph_monitor +++ /dev/null @@ -1,14 +0,0 @@ -#!/usr/bin/env python3 - -import rclpy -from rqt_diagnostic_graph_monitor.module import MonitorModule - -if __name__ == "__main__": - try: - rclpy.init() - node = rclpy.create_node("test_rqt_diagnostic_graph_monitor") - test = MonitorModule(node) - rclpy.spin(node) - rclpy.shutdown() - except KeyboardInterrupt: - print("KeyboardInterrupt") diff --git a/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor b/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor deleted file mode 100755 index a5237a87e87d6..0000000000000 --- a/tools/rqt_diagnostic_graph_monitor/script/rqt_diagnostic_graph_monitor +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env python3 - -import sys - -import rqt_gui.main - -rqt_main = rqt_gui.main.Main() -sys.exit(rqt_main.main(sys.argv, standalone="rqt_diagnostic_graph_monitor.MonitorPlugin")) From f012a756023ed140a94a4e1033930880e618d541 Mon Sep 17 00:00:00 2001 From: go-sakayori Date: Tue, 14 May 2024 14:29:31 +0900 Subject: [PATCH 166/192] chore: added maintainer (#7003) added maintainer Signed-off-by: Go Sakayori --- planning/behavior_path_avoidance_module/package.xml | 1 + planning/behavior_path_planner/package.xml | 1 + planning/behavior_path_planner_common/package.xml | 1 + planning/route_handler/package.xml | 2 ++ 4 files changed, 5 insertions(+) diff --git a/planning/behavior_path_avoidance_module/package.xml b/planning/behavior_path_avoidance_module/package.xml index fc34172bb2ce9..5f0a658735b2f 100644 --- a/planning/behavior_path_avoidance_module/package.xml +++ b/planning/behavior_path_avoidance_module/package.xml @@ -13,6 +13,7 @@ Tomoya Kimura Shumpei Wakabayashi Tomohito Ando + Go Sakayori Apache License 2.0 diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 7f50c61a8343a..f6bd82430c389 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -20,6 +20,7 @@ Kosuke Takeuchi Kyoichi Sugahara Takayuki Murooka + Go Sakayori Apache License 2.0 diff --git a/planning/behavior_path_planner_common/package.xml b/planning/behavior_path_planner_common/package.xml index 2dd4d12c05487..7bc40974b9a62 100644 --- a/planning/behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner_common/package.xml @@ -25,6 +25,7 @@ Fumiya Watanabe Takamasa Horibe Zulfaqar Azmi + Go Sakayori Apache License 2.0 diff --git a/planning/route_handler/package.xml b/planning/route_handler/package.xml index 60adfb1531104..22db01d833023 100644 --- a/planning/route_handler/package.xml +++ b/planning/route_handler/package.xml @@ -9,6 +9,8 @@ Kosuke Takeuchi Takayuki Murooka Mamoru Sobue + Go Sakayori + Apache License 2.0 Fumiya Watanabe From a5fdb8d85b2f27f632e48f1fa5682d6b055b696c Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 05:51:35 +0000 Subject: [PATCH 167/192] chore: update CODEOWNERS (#6866) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 36 +++++++++++++++++++++--------------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index b283c95c28a9b..dc745760cb7d0 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -4,7 +4,7 @@ common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.w common/autoware_auto_geometry/** satoshi.ota@tier4.jp common/autoware_auto_perception_rviz_plugin/** opensource@apex.ai satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp common/autoware_auto_tf2/** jit.ray.c@gmail.com satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/** team-spatzenhirn@uni-ulm.de +common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai common/autoware_point_types/** taichi.higashide@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @@ -45,7 +45,7 @@ common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@t common/tier4_logging_level_configure_rviz_plugin/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp -common/tier4_screen_capture_rviz_plugin/** taiki.tanaka@tier4.jp +common/tier4_screen_capture_rviz_plugin/** kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp common/tier4_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp common/tier4_system_rviz_plugin/** koji.minoda@tier4.jp @@ -72,12 +72,12 @@ control/shift_decider/** takamasa.horibe@tier4.jp control/trajectory_follower_base/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/trajectory_follower_node/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +evaluator/control_evaluator/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp evaluator/diagnostic_converter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp evaluator/localization_evaluator/** dominik.jargot@robotec.ai koji.minoda@tier4.jp evaluator/perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp evaluator/planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp -evaluator/tier4_metrics_rviz_plugin/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp launch/tier4_localization_launch/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp @@ -88,6 +88,7 @@ launch/tier4_sensing_launch/** yukihiro.saito@tier4.jp launch/tier4_simulator_launch/** keisuke.shima@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp launch/tier4_system_launch/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp launch/tier4_vehicle_launch/** yukihiro.saito@tier4.jp +localization/autoware_pose_covariance_modifier/** melike@leodrive.ai localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp localization/geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp localization/gyro_odometer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp @@ -122,17 +123,17 @@ perception/detected_object_validation/** dai.nguyen@tier4.jp shintaro.tomie@tier perception/detection_by_tracker/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/elevation_map_loader/** kosuke.takeuchi@tier4.jp shintaro.tomie@tier4.jp taichi.higashide@tier4.jp perception/euclidean_cluster/** dai.nguyen@tier4.jp yukihiro.saito@tier4.jp -perception/ground_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/ground_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/image_projection_based_fusion/** dai.nguyen@tier4.jp koji.minoda@tier4.jp kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/lidar_apollo_instance_segmentation/** yukihiro.saito@tier4.jp perception/lidar_apollo_segmentation_tvm/** ambroise.vincent@arm.com xinyu.wang@tier4.jp perception/lidar_apollo_segmentation_tvm_nodes/** ambroise.vincent@arm.com xinyu.wang@tier4.jp perception/lidar_centerpoint/** kenzo.lobos@tier4.jp koji.minoda@tier4.jp perception/lidar_centerpoint_tvm/** carl.liu@autocore.ai xinyu.wang@tier4.jp -perception/map_based_prediction/** kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp +perception/map_based_prediction/** kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp perception/multi_object_tracker/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/object_merger/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp -perception/object_range_splitter/** yukihiro.saito@tier4.jp +perception/object_range_splitter/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/object_velocity_splitter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp perception/occupancy_grid_map_outlier_filter/** abrahammonrroy@yahoo.com yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/probabilistic_occupancy_grid_map/** mamoru.sobue@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @@ -141,26 +142,28 @@ perception/radar_fusion_to_detected_object/** satoshi.tanaka@tier4.jp shunsuke.m perception/radar_object_clustering/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp perception/radar_object_tracker/** satoshi.tanaka@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/radar_tracks_msgs_converter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp +perception/raindrop_cluster_filter/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/shape_estimation/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp perception/tensorrt_classifier/** kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp perception/tensorrt_yolox/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp perception/tracking_object_merger/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/traffic_light_arbiter/** kenzo.lobos@tier4.jp shunsuke.miura@tier4.jp -perception/traffic_light_classifier/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/traffic_light_classifier/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp perception/traffic_light_fine_detector/** shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp -perception/traffic_light_map_based_detector/** shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp +perception/traffic_light_map_based_detector/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp -perception/traffic_light_visualization/** yukihiro.saito@tier4.jp +perception/traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp +planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_dynamic_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp planning/behavior_path_external_request_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_goal_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_lane_change_module/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_planner/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_sampling_planner_module/** daniel.sanchez@tier4.jp maxime.clement@tier4.jp planning/behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_start_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @@ -197,7 +200,7 @@ planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp planning/planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp -planning/route_handler/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp +planning/route_handler/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp zulfaqar.azmi@tier4.jp planning/rtc_interface/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp planning/rtc_replayer/** fumiya.watanabe@tier4.jp taiki.tanaka@tier4.jp planning/sampling_based_planner/bezier_sampler/** maxime.clement@tier4.jp @@ -208,11 +211,11 @@ planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shum planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp -sensing/image_diagnostics/** dai.nguyen@tier4.jp +sensing/image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp sensing/image_transport_decompressor/** kenzo.lobos@tier4.jp yukihiro.saito@tier4.jp sensing/imu_corrector/** koji.minoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/livox/livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp -sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yukihiro.saito@tier4.jp +sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp kenzo.lobos@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yihsiang.fang@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp @@ -221,6 +224,7 @@ sensing/tier4_pcl_extensions/** david.wong@tier4.jp kenzo.lobos@tier4.jp ryu.yam sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp +simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp simulator/vehicle_door_simulator/** isamu.takagi@tier4.jp system/autoware_auto_msgs_adapter/** isamu.takagi@tier4.jp mfc@leodrive.ai @@ -231,6 +235,7 @@ system/default_ad_api_helpers/ad_api_adaptors/** isamu.takagi@tier4.jp ryohsuke. system/default_ad_api_helpers/ad_api_visualizers/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/default_ad_api_helpers/automatic_pose_initializer/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp yukihiro.saito@tier4.jp system/diagnostic_graph_aggregator/** isamu.takagi@tier4.jp +system/diagnostic_graph_utils/** isamu.takagi@tier4.jp system/dummy_diag_publisher/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/dummy_infrastructure/** ryohsuke.mitsudome@tier4.jp system/duplicated_node_checker/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp uken.ryu@tier4.jp @@ -239,6 +244,7 @@ system/hazard_status_converter/** isamu.takagi@tier4.jp system/mrm_comfortable_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_emergency_stop_operator/** makoto.kurihara@tier4.jp tomohito.ando@tier4.jp system/mrm_handler/** makoto.kurihara@tier4.jp ryuta.kambe@tier4.jp tetsuhiro.kawaguchi@tier4.jp +system/system_diagnostic_monitor/** isamu.takagi@tier4.jp system/system_error_monitor/** fumihito.ito@tier4.jp system/system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp From f30c0350861d020ad26a45806ab1334895122fab Mon Sep 17 00:00:00 2001 From: masayukiaino <101699734+masayukiaino@users.noreply.github.com> Date: Tue, 14 May 2024 17:59:07 +0900 Subject: [PATCH 168/192] feat(smart_mpc_trajectory_follower): add smart_mpc_trajectory_follower (#6805) * feat(smart_mpc_trajectory_follower): add smart_mpc_trajectory_follower * style(pre-commit): autofix * modified control.launch.py * update README.md * Minor changes * style(pre-commit): autofix * bug fixed * update README and add a comment to mpc_param.yaml * minor changes * add copyright * mpc_param.yaml changed * add note to README * update according to spell check * update python_simulator according to spell check * update scripts according to spell check * update according to spell-check-partial * fixed ignored words in spell check --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takamasa Horibe Co-authored-by: Kosuke Takeuchi --- .../smart_mpc_trajectory_follower/.gitignore | 3 + .../CMakeLists.txt | 13 + .../smart_mpc_trajectory_follower/README.md | 338 + .../images/autoware_smart_mpc.png | Bin 0 -> 1328486 bytes .../images/lateral_error_nominal_model.png | Bin 0 -> 36024 bytes .../images/lateral_error_trained_model.png | Bin 0 -> 26903 bytes .../images/proxima_logo.png | Bin 0 -> 20962 bytes ...python_sim_lateral_error_nominal_model.png | Bin 0 -> 492385 bytes ...python_sim_lateral_error_trained_model.png | Bin 0 -> 498530 bytes .../images/test_route.png | Bin 0 -> 676745 bytes .../smart_mpc_trajectory_follower/package.xml | 43 + .../smart_mpc_trajectory_follower/setup.py | 37 + .../smart_mpc_trajectory_follower/.gitignore | 2 + .../smart_mpc_trajectory_follower/__init__.py | 0 .../clear_pycache.py | 31 + .../param/mpc_param.yaml | 56 + .../param/nominal_param.yaml | 10 + .../param/trained_model_param.yaml | 30 + .../python_simulator/.gitignore | 13 + .../python_simulator/accel_map.csv | 20 + .../plot_auto_test_result.ipynb | 180 + .../python_simulator/python_simulator.py | 1593 + .../python_simulator/run_python_simulator.py | 36 + .../python_simulator/run_sim.py | 392 + .../python_simulator/slalom_course_data.csv | 75014 ++++++++++++++++ .../scripts/.gitignore | 7 + .../scripts/__init__.py | 0 .../scripts/drive_GP.py | 110 + .../scripts/drive_NN.py | 247 + .../scripts/drive_controller.py | 943 + .../scripts/drive_functions.py | 1540 + .../scripts/drive_iLQR.py | 644 + .../scripts/drive_mppi.py | 170 + .../scripts/proxima_calc.cpp | 487 + .../scripts/pympc_trajectory_follower.py | 859 + .../training_and_data_check/.gitignore | 4 + .../training_and_data_check/__init__.py | 0 .../add_training_data_from_csv.py | 293 + .../data_checker.ipynb | 252 + .../execute_train_drive_NN_model.ipynb | 77 + .../training_and_data_check/rosbag2.bash | 40 + .../train_drive_GP_model.py | 88 + .../train_drive_NN_model.py | 716 + .../launch/control.launch.py | 67 +- 44 files changed, 84340 insertions(+), 15 deletions(-) create mode 100644 control/smart_mpc_trajectory_follower/.gitignore create mode 100644 control/smart_mpc_trajectory_follower/CMakeLists.txt create mode 100644 control/smart_mpc_trajectory_follower/README.md create mode 100644 control/smart_mpc_trajectory_follower/images/autoware_smart_mpc.png create mode 100644 control/smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png create mode 100644 control/smart_mpc_trajectory_follower/images/lateral_error_trained_model.png create mode 100644 control/smart_mpc_trajectory_follower/images/proxima_logo.png create mode 100644 control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png create mode 100644 control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png create mode 100644 control/smart_mpc_trajectory_follower/images/test_route.png create mode 100644 control/smart_mpc_trajectory_follower/package.xml create mode 100644 control/smart_mpc_trajectory_follower/setup.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/.gitignore create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/__init__.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/mpc_param.yaml create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/nominal_param.yaml create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/trained_model_param.yaml create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/.gitignore create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/.gitignore create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/__init__.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/proxima_calc.cpp create mode 100755 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/.gitignore create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/__init__.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py create mode 100644 control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py diff --git a/control/smart_mpc_trajectory_follower/.gitignore b/control/smart_mpc_trajectory_follower/.gitignore new file mode 100644 index 0000000000000..d914a0aa99e5a --- /dev/null +++ b/control/smart_mpc_trajectory_follower/.gitignore @@ -0,0 +1,3 @@ +# Files generated when installing smart_mpc_trajectory_follower +build/ +*.egg-info/ diff --git a/control/smart_mpc_trajectory_follower/CMakeLists.txt b/control/smart_mpc_trajectory_follower/CMakeLists.txt new file mode 100644 index 0000000000000..7aecab2597dcd --- /dev/null +++ b/control/smart_mpc_trajectory_follower/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.14) +project(smart_mpc_trajectory_follower) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +install(PROGRAMS + smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py + DESTINATION lib/${PROJECT_NAME} +) +ament_auto_package( + INSTALL_TO_SHARE +) diff --git a/control/smart_mpc_trajectory_follower/README.md b/control/smart_mpc_trajectory_follower/README.md new file mode 100644 index 0000000000000..8fcc13142d68b --- /dev/null +++ b/control/smart_mpc_trajectory_follower/README.md @@ -0,0 +1,338 @@ + + + +# Smart MPC Trajectory Follower + +Smart MPC (Model Predictive Control) is a control algorithm that combines model predictive control and machine learning. While inheriting the advantages of model predictive control, it solves its disadvantage of modeling difficulty with a data-driven method using machine learning. + +This technology makes it relatively easy to operate model predictive control, which is expensive to implement, as long as an environment for collecting data can be prepared. + +

+ + + +

+ +## Setup + +After building autoware, move to `control/smart_mpc_trajectory_follower` and run the following command: + +```bash +pip3 install . +``` + +If you have already installed and want to update the package, run the following command instead: + +```bash +pip3 install -U . +``` + +## Provided features + +This package provides smart MPC logic for path-following control as well as mechanisms for learning and evaluation. These features are described below. + +### Trajectory following control based on iLQR/MPPI + +The control mode can be selected from "ilqr", "mppi", or "mppi_ilqr", and can be set as `mpc_parameter:system:mode` in [mpc_param.yaml](./smart_mpc_trajectory_follower/param/mpc_param.yaml). +In "mppi_ilqr" mode, the initial value of iLQR is given by the MPPI solution. + +> [!NOTE] +> With the default settings, the performance of "mppi" mode is limited due to an insufficient number of samples. This issue is being addressed with ongoing work to introduce GPU support. + +To perform a simulation, run the following command: + +```bash +ros2 launch autoware_launch planning_simulator.launch.xml map_path:=$HOME/autoware_map/sample-map-planning vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit trajectory_follower_mode:=smart_mpc_trajectory_follower +``` + +> [!NOTE] +> When running with the nominal model set in [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml), set `trained_model_parameter:control_application:use_trained_model` to `false` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). To run using the trained model, set `trained_model_parameter:control_application:use_trained_model` to `true`, but the trained model must have been generated according to the following procedure. + +### Training of model and reflection in control + +To obtain training data, start autoware, perform a drive, and record rosbag data with the following commands. + +```bash +ros2 bag record /localization/kinematic_state /localization/acceleration /vehicle/status/steering_status /control/command/control_cmd /control/trajectory_follower/control_cmd /control/trajectory_follower/lane_departure_checker_node/debug/deviation/lateral /control/trajectory_follower/lane_departure_checker_node/debug/deviation/yaw /system/operation_mode/state /vehicle/status/control_mode /sensing/imu/imu_data /debug_mpc_x_des /debug_mpc_y_des /debug_mpc_v_des /debug_mpc_yaw_des /debug_mpc_acc_des /debug_mpc_steer_des /debug_mpc_X_des_converted /debug_mpc_x_current /debug_mpc_error_prediction /debug_mpc_max_trajectory_err /debug_mpc_emergency_stop_mode /debug_mpc_goal_stop_mode /debug_mpc_total_ctrl_time /debug_mpc_calc_u_opt_time +``` + +Move [rosbag2.bash](./smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash) to the rosbag directory recorded above and execute the following command on the directory + +```bash +bash rosbag2.bash +``` + +This converts rosbag data into CSV format for training models. + +> [!NOTE] +> Note that a large number of terminals are automatically opened at runtime, but they are automatically closed after rosbag data conversion is completed. +> From the time you begin this process until all terminals are closed, autoware should not be running. + +Instead, the same result can be obtained by executing the following command in a python environment: + +```python +from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model +model_trainer = train_drive_NN_model.train_drive_NN_model() +model_trainer.transform_rosbag_to_csv(rosbag_dir) +``` + +Here, `rosbag_dir` represents the rosbag directory. +At this time, all CSV files in `rosbag_dir` are automatically deleted first. + +The paths of the rosbag directories used for training, `dir_0`, `dir_1`, `dir_2`,... and the directory `save_dir` where you save the models, the model can be saved in the python environment as follows: + +```python +from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model +model_trainer = train_drive_NN_model.train_drive_NN_model() +model_trainer.add_data_from_csv(dir_0) +model_trainer.add_data_from_csv(dir_1) +model_trainer.add_data_from_csv(dir_2) +... +model_trainer.get_trained_model() +model_trainer.save_models(save_dir) +``` + +After performing the polynomial regression, the NN can be trained on the residuals as follows: + +```python +model_trainer.get_trained_model(use_polynomial_reg=True) +``` + +> [!NOTE] +> In the default setting, regression is performed by several preselected polynomials. +> When `use_selected_polynomial=False` is set as the argument of get_trained_model, the `deg` argument allows setting the maximum degree of the polynomial to be used. + +If only polynomial regression is performed and no NN model is used, run the following command: + +```python +model_trainer.get_trained_model(use_polynomial_reg=True,force_NN_model_to_zero=True) +``` + +Move `model_for_test_drive.pth` and `polynomial_reg_info.npz` saved in `save_dir` to the home directory and set `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml) to `true` to reflect the trained model in the control. + +### Performance evaluation + +Here, as an example, we describe the verification of the adaptive performance when the wheel base of the sample_vehicle is 2.79 m, but an incorrect value of 2.0 m is given to the controller side. +To give the controller 2.0 m as the wheel base, set the value of `nominal_parameter:vehicle_info:wheel_base` in [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml) to 2.0, and run the following command: + +```bash +python3 -m smart_mpc_trajectory_follower.clear_pycache +``` + +#### Test on autoware + +To perform a control test on autoware with the nominal model before training, make sure that `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml) is `false` and launch autoware in the manner described in "Trajectory following control based on iLQR/MPPI". This time, the following route will be used for the test: + +

+ +Record rosbag and train the model in the manner described in "Training of model and reflection in control", and move the generated files `model_for_test_drive.pth` and `polynomial_reg_info.npz` to the home directory. + +> [!NOTE] +> Although the data used for training is small, for the sake of simplicity, we will see how much performance can be improved with this amount of data. + +To control using the trained model obtained here, set `trained_model_parameter:control_application:use_trained_model` to `true`, start autoware in the same way, and drive the same route recording rosbag. +After the driving is complete, convert the rosbag file to CSV format using the method described in "Training of model and reflection in control". +A plot of the lateral deviation is obtained by running the `lateral_error_visualize` function in `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb` for the nominal and training model rosbag files `rosbag_nominal` and `rosbag_trained`, respectively, as follows: + +```python +lateral_error_visualize(dir_name=rosbag_nominal,ylim=[-1.2,1.2]) +lateral_error_visualize(dir_name=rosbag_trained,ylim=[-1.2,1.2]) +``` + +The following results were obtained. + +
+ + +
+ +#### Test on python simulator + +First, to give wheel base 2.79 m in the python simulator, create the following file and save it in `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator` with the name `sim_setting.json`: + +```json +{ "wheel_base": 2.79 } +``` + +Next, run the following commands to test the slalom driving on the python simulator with the nominal model: + +```python +import python_simulator +from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model +initial_error = [0.0, 0.03, 0.01, -0.01, 0.0, 0.0] +save_dir = "test_python_sim" +python_simulator.slalom_drive(save_dir=save_dir,use_trained_model=False,initial_error=initial_error) +``` + +Here, `initial_error` is the initial error from the target trajectory, in the order of x-coordinate, y-coordinate, longitudinal velocity, yaw angle, longitudinal acceleration, and steer angle, +and `save_dir` is the directory where the driving test results are saved. + +> [!NOTE] +> The value of `use_trained_model` given as the argument of `python_simulator.slalom_drive` takes precedence over the value of `trained_model_parameter:control_application:use_trained_model` in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). + +Run the following commands to perform training using driving data of the nominal model. + +```python +model_trainer = train_drive_NN_model.train_drive_NN_model() +model_trainer.add_data_from_csv(save_dir) +model_trainer.save_train_data(save_dir) +model_trainer.get_trained_model(use_polynomial_reg=True) +model_trainer.save_models(save_dir=save_dir) +``` + +This way, files `model_for_test_drive.pth` and `polynomial_reg_info.npz` are saved in `save_dir`. +The following results were obtained. + +

+ +

+ +The center of the upper row represents the lateral deviation. + +Finally, to drive with the training model, run the following commands: + +```python +load_dir = save_dir +save_dir = "test_python_trained_sim" +python_simulator.slalom_drive(save_dir=save_dir,load_dir=load_dir,use_trained_model=True,initial_error=initial_error) +``` + +The following results were obtained. + +

+ +

+ +It can be seen that the lateral deviation has improved significantly. + +Here we have described wheel base, but the parameters that can be passed to the python simulator are as follows. + +| Parameter | Type | Description | +| ------------------------ | ----------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| steer_bias | float | steer bias [rad] | +| steer_rate_lim | float | steer rate limit [rad/s] | +| vel_rate_lim | float | acceleration limit [m/s^2] | +| wheel_base | float | wheel base [m] | +| steer_dead_band | float | steer dead band [rad] | +| adaptive_gear_ratio_coef | list[float] | List of floats of length 6 specifying information on speed-dependent gear ratios from tire angle to steering wheel angle. | +| acc_time_delay | float | acceleration time delay [s] | +| steer_time_delay | float | steer time delay [s] | +| acc_time_constant | float | acceleration time constant [s] | +| steer_time_constant | float | steer time constant [s] | +| accel_map_scale | float | Parameter that magnifies the corresponding distortion from acceleration input values to actual acceleration realizations.
Correspondence information is kept in `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv`. | +| acc_scaling | float | acceleration scaling | +| steer_scaling | float | steer scaling | + +For example, to give the simulation side 0.01 [rad] of steer bias and 0.001 [rad] of steer dead band, edit the `sim_setting.json` as follows. + +```json +{ "steer_bias": 0.01, "steer_dead_band": 0.001 } +``` + +#### Auto test on python simulator + +Here, we describe a method for testing adaptive performance by giving the simulation side a predefined range of model parameters while the control side is given constant model parameters. + +First, to restore nominal model settings to default values, set the value of `nominal_parameter:vehicle_info:wheel_base` in [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml) to 2.79, and run the following command: + +```bash +python3 -m smart_mpc_trajectory_follower.clear_pycache +``` + +To run a driving experiment within the parameter change range set in [run_sim.py](./smart_mpc_trajectory_follower/python_simulator/run_sim.py), for example, move to `control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator` and run the following command: + +```bash +python3 run_sim.py --param_name steer_bias +``` + +Here we described the experimental procedure for steer bias, and the same method can be used for other parameters. + +If you want to do it for all parameters at once, run the following command: + +```bash +yes | python3 run_sim.py +``` + +In `run_sim.py`, the following parameters can be set: + +| Parameter | Type | Description | +| ------------------------- | ---- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| USE_TRAINED_MODEL_DIFF | bool | Whether the derivative of the trained model is reflected in the control | +| DATA_COLLECTION_MODE | str | Which method will be used to collect the training data 
"ff": Straight line driving with feed-forward input
"pp": Figure eight driving with pure pursuit control
"mpc": Slalom driving with mpc | +| USE_POLYNOMIAL_REGRESSION | bool | Whether to perform polynomial regression before NN | +| USE_SELECTED_POLYNOMIAL | bool | When USE_POLYNOMIAL_REGRESSION is True, perform polynomial regression using only some preselected polynomials.
The choice of polynomials is intended to be able to absorb the contribution of some parameter shifts based on the nominal model of the vehicle. | +| FORCE_NN_MODEL_TO_ZERO | bool | Whether to force the NN model to zero (i.e., erase the contribution of the NN model).
When USE_POLYNOMIAL_REGRESSION is True, setting FORCE_MODEL_TO_ZERO to True allows the control to reflect the results of polynomial regression only, without using NN models. | +| FIT_INTERCEPT | bool | Whether to include bias in polynomial regression.
If it is False, perform the regression with a polynomial of the first degree or higher. | +| USE_INTERCEPT | bool | When a polynomial regression including bias is performed, whether to use or discard the resulting bias information.
It is meaningful only if FIT_INTERCEPT is True.
If it is False, discard the bias in the polynomial regression in the hope that the NN model can remove the bias term, even if the polynomial regression is performed with the bias included. | + +> [!NOTE] +> When `run_sim.py` is run, the `use_trained_model_diff` set in `run_sim.py` takes precedence over the `trained_model_parameter:control_application:use_trained_model_diff` set in [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). + +## Change of nominal parameters and their reloading + +The nominal parameters of vehicle model can be changed by editing the file [nominal_param.yaml](./smart_mpc_trajectory_follower/param/nominal_param.yaml). +After changing the nominal parameters, the cache must be deleted by running the following command: + +```bash +python3 -m smart_mpc_trajectory_follower.clear_pycache +``` + +The nominal parameters include the following: + +| Parameter | Type | Description | +| ------------------------------------------------ | ----- | ------------------------------ | +| nominal_parameter:vehicle_info:wheel_base | float | wheel base [m] | +| nominal_parameter:acceleration:acc_time_delay | float | acceleration time delay [s] | +| nominal_parameter:acceleration:acc_time_constant | float | acceleration time constant [s] | +| nominal_parameter:steering:steer_time_delay | float | steer time delay [s] | +| nominal_parameter:steering:steer_time_constant | float | steer time constant [s] | + +## Change of control parameters and their reloading + +The control parameters can be changed by editing files [mpc_param.yaml](./smart_mpc_trajectory_follower/param/mpc_param.yaml) and [trained_model_param.yaml](./smart_mpc_trajectory_follower/param/trained_model_param.yaml). +Although it is possible to reflect parameter changes by restarting autoware, the following command allows us to do so without leaving autoware running: + +```bash +ros2 topic pub /pympc_reload_mpc_param_trigger std_msgs/msg/String "data: ''" --once +``` + +The main parameters among the control parameters are as follows. + +### `mpc_param.yaml` + +| Parameter | Type | Description | +| ------------------------------------ | ----------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| mpc_parameter:system:mode | str | control mode
"ilqr": iLQR mode
"mppi": MPPI mode
"mppi_ilqr": the initial value of iLQR is given by the MPPI solution. | +| mpc_parameter:cost_parameters:Q | list[float] | Stage cost for states.
List of length 8, in order: straight deviation, lateral deviation, velocity deviation, yaw angle deviation, acceleration deviation, steer deviation, acceleration input deviation, steer input deviation cost weights. | +| mpc_parameter:cost_parameters:Q_c | list[float] | Cost in the horizon corresponding to the following timing_Q_c for the states.
The correspondence of the components of the list is the same as for Q. | +| mpc_parameter:cost_parameters:Q_f | list[float] | Termination cost for the states.
The correspondence of the components of the list is the same as for Q. | +| mpc_parameter:cost_parameters:R | list[float] | A list of length 2 where R[0] is weight of cost for the change rate of acceleration input value and R[1] is weight of cost for the change rate of steer input value. | +| mpc_parameter:mpc_setting:timing_Q_c | list[int] | Horizon numbers such that the stage cost for the states is set to Q_c. | + +### `trained_model_param.yaml` + +| Parameter | Type | Description | +| ------------------------------------------------------------------ | ---- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| trained_model_parameter:control_application:use_trained_model | bool | Whether the trained model is reflected in the control or not. | +| trained_model_parameter:control_application:use_trained_model_diff | bool | Whether the derivative of the trained model is reflected on the control or not.
It is meaningful only when use_trained_model is True, and if False, the nominal model is used for the derivative of the dynamics, and trained model is used only for prediction. | + +## Request to release the slow stop mode + +If the predicted trajectory deviates too far from the target trajectory, the system enters a slow stop mode and the vehicle stops moving. +To cancel the slow stop mode and make the vehicle ready to run again, run the following command: + +```bash +ros2 topic pub /pympc_stop_mode_reset_request std_msgs/msg/String "data: ''" --once +``` + +## Limitation + +- May not be able to start when initial position/posture is far from the target. + +- It may take some time until the end of the planning to compile numba functions at the start of the first control. + +- In the stopping action near the goal our control switches to another simple control law. As a result, the stopping action may not work except near the goal. Stopping is also difficult if the acceleration map is significantly shifted. diff --git a/control/smart_mpc_trajectory_follower/images/autoware_smart_mpc.png b/control/smart_mpc_trajectory_follower/images/autoware_smart_mpc.png new file mode 100644 index 0000000000000000000000000000000000000000..0349948cf80dd103c0f4dbeeebdd95a27bad30e6 GIT binary patch literal 1328486 zcmX_HWmsEVmoAh-pg@BMcXy|_d!YnMaSu}5-QC^YN-6FR#oaGn+}#Pzaaud1q#0YYky`GD@0Kw}07esBOCJrvHXjEd=btCq&tr`osq zRXpK}rHs{7Zp`*~Vn%%Mh1!uvGyDyxhn=6|HFbs3;LK!!oLmD7>bi3(n)oA(%du}0 z55(-;pCJeaY#=OO5@SE{&OesxzR|pTzJXx-fVWrQH`lv67vun-f+h$-D>O*VkKOQ@ z1aT%EH5K>!y{+$U*OilHD0KY+iGVh=DCs9Sd;7_@^Go5X+5VCQ0qxU}c~}yCRJ^2C z9;H7z>O$4p&T_KUU$N-GRayj}zPHzfH>4-e(C6*8^STCKSvu_5IR@MI2byS)?2^n$ z3s?SoF3p!`@c=1OA?(?>tL2tcnN9m@2w-@BFC8f!veVeGUsUl$dt?VI)3!S;Fx z=#(OJxVE`|NdIL{zvjUzaoy{l@CxgLRt3+k2XUYn*@XTlcx%+0V|Edd$%e9pX6Iwv z^R74Hw~J42e%pLxqMAIr!zi|$x42bZuZS&HA>rW^N(@pRdW8$8_D*hp)?ZK8YwJ3s znpOrHnVA%f=!1)`qUI3{Wr2tYhVPc+TxRmn;$yz1h|Btm=1D{Y^NOh?fl&h);E1Gc zHqD$J&nll-y{6H#36>Jtl4gliHdOX_X@Ea9j?zeXqg4?0eU5Sw<=DYq5g2_DS7>q< zN#p@p^`n^hxY@Ao2M+jVY@EOGLNQ9oyGE+1Bv-7hxS2LM4|Wexk!N$`8< zC{QIRi2d1R>1&ujLNq~zVgQ5?HUQw|oi*2CeIOWxes>g!bqho;{JxhD@gFU$5OS^K z>%|dsA$~kZl1va*Zc{O~cprN_$ePy=qG?ZrgRs~b92f9WOxFtlj#_iYhWrSezjRKL zH`L?-%hrcCDbOPa__0OF3ZRRR+@mTIMIyt2OWyJ2^UW?b~zYN?N@4c^DZ- z)fjNRCQFvA?CjizI@(-SQu?p1I7D6!l`n;2P3!t^Zm?m?5BK&w`KHL92wRD1Q|wHi zK;!?rr}ye?`^O7fez;ka(jP9Lry{sg=1q!>z7(}2GuGwTD#~TH<9)s0#8ALw}m(4 zrYf;w1eC8vUXKO{PEU5{>|OW1Z%EL$F8yi)@K{KpdqdbQa1!%geu{Rh_*>xH)!{ko32ago=f z?}F}E*z3?5rr?+x*S&jH`poond>R@Wy42C~ii%5G-z(bos}V-8=gYz8@%3jkU#P3^ z;MNvJu(<#5u$-Rv?Kk1KXU8@7{cH{2R^Z2Q6(Ue5(w1Pz4FCKu*xTGs$FA)?HdwYp zUp)oA?&EyACP`nWNmZC|EqJt_uTs0nGRGZW9-Y^Go~&~O-Fw>3I~Cei2S9<~2)YQp zte}U-)L9RV-^jqr!tOuracQIb8v5F1_V#dt_8Pjn#S6y{US8q`6iM|%rVeAaV;tO? z1H(lYJS$uoU$S&!S{^<)?9w~nXV&!+E5*8i9&7Rd2~PauLypwwpE%4ioL!4UrNfVX>@EvsGo&|c3~TJ;dbl#&FJeJ(w5gdU7OLi)(X&_K zn8cqtERHYB+zxXLZ31mXq@=1#KIasY|6GgWzir;s5l}G;kfaNbt&uJoW}4c&HJEHiXHDq7BRGU z&BV;CTA?nt!~+HhE^Hf|``NSwvWEmed|*&j#YXu6JDAhI>U>?KX)lodWKk%{r^WN& zi1jD#Yna2{RLPK6urU9xUUkDbL#FvDQpdpzsc9L%r_OK9|FOJj(|w+jLFwHwNgpx6 zr#=1mklP*fTZ#|F4e!w8PBmeVtc++{==X>peL@d zkWy!XIJ_Lgg7!;|hKY+yiWAM34Wtt*+ri6aIx%OatDmzL>ig>SxU`F_tNE)o+Ydg^ z8PmIjteA#d_iUNNV20$h%-oVW8%GC+fc*~#WTKYQ5Y6)PayD*msgl`zy{cJ@rY&!R zK;Y$*qM{<(=g)FA8b#`5_D)Wc*wG0l!64#55VghNN7I-@BNzL4BSZKveRXEa;ZCwO zY9`j!(TY4@esQnbq;_-&p?`|q3bLTyN?VR%Ia=s%*N|i%U<0Arf$3=&aVCD4Wo2be zoqw9*r$`)TBSN262|9nedGhXI3rmcY5$8|1U-OyW{{LS1o-&L&Bl6I6zbpl=e=u&8h#wWK*tob`|JC8Y%rv{CEHfhv z?qXy6QL!l%p4k)$$|#T|+(Y2COuB}*1*{2TSPb7kQ>*x8mt}=jVd>l7|Kz0J-Jgw}#Z)pduNO1+mWpAUc1|@wFe)gA3~oH z#6Od0oUGXzWsdFEF@ce#u~94ma3)L#SZC5ipgZChj*>z<&_Q| z9wV2R^oH2+N@nTlrB{#8uF0OiOpV*so_0gMgRzJ1uSsEK>b=aTy^0S1oXqKmUGtOy`WJO!R?JVy5*5x%%`@5<)a_sEh5ftKQ;A7~2cxa(jfh!{uii#u= zG);$N2Kk6O;_y{I0QR+rO935O1QU~jA*vI<(Alc@pZPr!PEJPy2TA{}4ydrn@dK9E zy0M{8OhW^=dJ5jK>1@3=T4Ph=q04%q4uj*%0GiEuOLTUv#Xm=0SJQ)%VneV-Th;j} zG;_$+dA{v#pIj09hmSra{-?U_#ai3Bqk~qjY-IQ_eXB(7SB;$!_sXs-hN^Z4v!rR3 z%SV=6?;GSv5~2K6i@NIOzJUS6)IHN_ej`WA#EsYYN&?nV80OxWuhDNh?VNi(-e0Iz zgZ{tPY2p3jB9gL=ZCv6Rj~R8^+6TJNaC3cL@sVDHUu8wdu&=_LB60*w94#|#Ne^ayp47ti)0tm$7a_fF(-M8~rE&0sa*nr0+&uFO51tFgd`|X4 z=j|viS$_p^xtJmBoSePMW#1px%Brporj1)yNpe;sWiZ6$Bl;;^_1uGx7pkr=y5E!h z?NV-=iz@SsHheDOWA9EL{jRaDvA?$3mX$ML|6(3$4>^;)A*w=FRA*?vTZX1H;T$@x zWD${K2ElR8F;x9+=`|@v1t3t6L82W4CXb6_bNoW)l&K zoet4!inP{t%Q0OfojP@@vCgDJ`OL?cH+yD4A55exa*0Oq_zM>}$mSGEvElkkT(3tK84wwR`(x^CN?;4Tx~W8!LN&GWx*?2TuRjg7?( zo1|rBQ6#bm7jbu{GY=^`dg3e&8gzA zLs%i3ErE#;&6`%CjB%Q1=|C%<(XkVzPozSEcrn{GSL1_z+$4gms38cTXws0RQ3x&` zZdgIsq{v%VT^*;M=PCCd9-jN-$>$EeSOv#ax6_7m`|U^W38k3(lQmubK)41|V&h^9 z=Qby$V=LkI(Zg<@=S4l}JtiY~blxwZQoen4 zcj*_-`SbSR7&r+VFQlllpM6C8q3o#db$BPfs)M6`C!>jh$hZ(T56FMMZ!e&_AugC2 zfO7HAz-Gk7-HNTTW<=dG{*f&B2GIfuO0+d z9j~z&RK2b)WlT6N_Dam$pJ+w8IdIRtFIWZ#X>X9;yL@t4YHlAW4%W0I;(?;a(G`VR ze++Ujz4J0rWv>)@s}$t=FT8t|AZIZ-q!|$v@A;l!@1V2RJaJsr(NE}VQ_ZEl*`fa; z6f4{n`Ol?zRCgZrFRP63VL99s+)G3j@xG5>EG((tb10407}9W^=l&|7LTR{GvfNQl zc6PD4xq_urw)oM@<+61N1K4;fo;@Zj$^)0eZjQ)SsBK68m?9CDjg3vt3SQ*LGVV+M zbW!^Lks}n_j$2%j`^`_tJ$^EuNQ_FrAnUL490CHpW$RBQ$ApALBt&*jPO=^9g|ilg zg%^UQPS0a(`(;k>70x>S{PHv;%%Nn-eW1W%CfKUGZ%6aqZ^o{f-px=GRPe~t_mGL2 zOO)ztRggaWk#@dN;_l=9TKHilvfh(WBgI{)_(T^`24Yf(cOhbe*ssybg@QI|y64K|R&m~&(< z+eyCB_||kQUEM4F2m0N!I0%0udRqbMCHN?w@KXjwY1`5Tqoaud<0)*MK~>Mk&ANu5 z%lku4lHBYKrZKx0T9J()zZ?Xt5OWc6LSV|5A|}BF*mnyHQ{Drc3XJ6#)v!!KOd1Ym7Ypb~L)c(N*kbclw-uLPB zb!z`-l2nThO=k3JdJmhV25ZnB87d66aS@;e0h8pZbr$*?tznZ-zO}8{3+`DZtk}H{XQ=0Sc@FM8 zh=@pLtaxgyGUXu=hd*#8p)F1pF}JtQ6H1eAZg0Z5B3`m&2A~k^64v|=|7ctDG&Oz} zSR^NKp&vJmr$>r+xxhHdp4ZUVGWcQRZ&j-3-Y5?-%_yYJTwFqy-xW+TOB@iFM6~7G zsdpKH{Yz@=G{7L?q8~r=)!6D42oB>hx~zl7UbL6*-6^88#-NS!T^Ny zk}Ky57q6URN^iCVr_N6gEok>GjrFatq4-C$N6>)}=z_yJ4u)thD6B?}S~>dX7{9Zb z6Ae-%DzWqO%0L_vV5nDII20mB5X~>3tu5$z7bI2{iyflFBf&=G(B3rqdI?w6=@A(g zR##_yw)PVB2dws+GpU4O2jzo@_a}=I3>QS>&tYmAvP(`nv2C%Wl*Rd79>Goeo{0_? z3H6E8$?}{kOzgT9;G7JqL{~sikNu2nzBJEB;SB;O`f|VdQ-4lNcwT1Q|JKDgXp*sy zH-nyr>e)=PfKsY(ZQt!YXl{f`6V0Wl2DJt)8Ej6@mJ*!oGPL8kI3hjL?5vc}_Ae2U z{apJRQFk$Tcmt*;sx?wBljFl$ats+&ET8noKsyOq!^TYessEF?;CMG&- z8z$U~$PiMjF{Cg~Z9)TkB{-H)M;hV2rWB|#UA-*m@9&KhDt==K@{iqba*jCl8~Xx@3yi$O40E(4324 zb zugIhcBq1@;n8&N{s@x?`}Hk;_7bj8vOui`V0crFjj<-F8X|0yqK zmb4H(SsB9cR?5Ltyl=%dcHu-g!QnMHm6CLU7*l6ZxeZ~)i2h=j*-e!Alg`$Zc2Q(yALyBlGa<%q zhA7Wh<;tMT;>2#p#Ehy|*5!>S;gXUPCw}XYv$*7B99+Cq*ll;XWryBb^>(CSWzU^*)Zp2}DThoDO;X5L^ALZT zww0f2zospk0AC1*6@kqpk{OC4hBl@thw{PUUO9&&*oFrQwP3f(K|8jh6=Ilz7PMXT zOKEc225QmZA&Ms<`)vMj7t|RUX!%S?f&izzvT}pujSwL6b}eH3!z06`ZG3pxzFjCH zljEcGC$V=XS>c#6-5~KIa1FIT;N7R7$nL>UI!O?i!kC_uLlXu6xQZSF*<9o~vlATw zFUl9Z&s8t$U)qE#2@R!Fz&He2iz5b-$TS$c+%+z(tV=CL%xXoOX|M39)|Fe`$nMj~ zLQoF$L_y-%a9RN>LH_v*_|9xH>^Cvz6lxA~bJPBe@Dx?Tc_~$vzq~JBVI7Qih#X3PJp%J-06eqTK@(92~JYWm3->nJ@d?-=Q z$@^l}3z7Ejnm8R{lT?vq$%M3OL5z*F^|~haUC$|0={$yUW}jXK~qq z-We5wmFHMT01?1fc_TUZ9JIAlr-R$ppxEB)YeMKzv~}^eULQ;ub9WE_;hez+xIdXy zPOnhk<`Ev4vS|d}Jn_Xy2&c-(g&z-`Innn#?Yci7_A_=eArfYq1RI8J^TBi+ zoduW}yos*Mq>$f01AvEV5D#8CPW+B*m9hXaY^knPsl@-MiIFvw=gqN|*flscAnGxE zYv6JoPy~zLMDeY*g0Fcb9q3{o+i0+$4#K%wi`p?l9bmhq@%pz+;djAF2aI0_} z$(^JxOG=5##Tcc2hS)Rsclh#CEnF@21{@+{a>c_zh$~Ur?kM7Lom}@|Af3N@LNjAg zctuJ>jHOMqXn~5Pta0_1AP9vOmMvD{H}7z1LSkCR7^?(spb>!W9`nY0Q~$tCWL?<6_-gVO`r_`TWWj^=sj{UfUWbo*06R zR_-1y!{cXRa;Fg+2&OL5C(D~x;G-h`2`*52FYd+8Z>;X#~5bY3mr+TZ9)ELw=4X{%v(g zW{XJ6)X&pM%UeIZJQ-F^3L_2z)Q`-afjX`%H+uY>QO4HNo5| zjrsd4F9G;$yhK- z5;kSvhd>}fQ1?dQ#aDGdh(*B=Eh>Bf8H?EZ`pV`Dbgg*BI=+^fDx{)fU#G(%z5n4e zN8=ZHl%i=_1T7>t|4}y379lA!T0VMpQIGtR>%Dm4X?-m^ZU;|CUFD=`G~ z5;?e4Pi_y!+IvbQ)lVU!JWyPJ{5Fyd&sx;o+;c0aswJC5{WZnN!XiGi$!6e5cya&! zAg;8O9v2U9c&E1g`b?y*y|pL$m=}a7?1P;R#UYgWustMd**oQY2y-ybp>bHBYwKpQ zv$*`(WLIcXN7+@=3sfyHhF?6L{=$u>^4@nZ#~z}=$ofs%qXn7*eGtYzkGp+2er`0+ zWslBC&@|L?!T z*kptC;|ovvHV#O5q5>i!)fLU6VIvoM~9x$)!T~Azj zA`FrZbc_X&Z5L^-XzY(St?kU83Ye2cPGmhEM-NEx;HYbWi1k@H2c3S!1J-! zC3~m33bqOZPI`L!=D|VO_O>yi1S$3Q2fSixL&J~@E

S(8&FtKAV&WCmvjq z-~k+XN-hL~syT_KC-Vgv^IkR-3r`7xGrv{S?D^_Rc{gIu4J;=e6QF;1;s;7N;SB{q zlBBjhHI-3P+UJ=hE9$R(%LxRf3-nx#;bi3)QU#|6jHCn42uQu+OENvNYKj*%=MshsS9SE4I41JXx?(M zwaxACmxBG$VspC~D42+Z1RlP4r={WQ=7y`RtPIw(&_AIstu4{aOt-A@Rl>ji)G*Gq zfdi3;u@%i&%(Lp#WRF*OboB29%Ajgl*8|mlmZaQJ1)EwMqmA+#Pw|>$VaGu7gUD{Yk4nsRv<_6Vh7#;&>ixxh{fC}jUjzvte!f@sfYx?($`eZfLlAOyaq;~yCH z1IrfB^*FEI8}eXs8C#kH3d86kQfZ6S$Y2qKdSsdC3LNmGhKuNke^Q}&lLUV@&$voe z{;)&3Pg5{22pA&VVG~MsW1l3xf{P3M02hxwr4ptFZy2uO)g-!vNxzL$UTtN<5V&g+ zA0Jy!T(oOYQmdg(K&?ub+>?NwqG+gX;k8MQMu%#l4IVT5rIcFQpmcc0A7&NeU}Beq z6N`gYFqIVHj?$v2QxPdvur2evh-{EV{JI6*YkLs=Z#LpSHt-?gKv_pk9uxBw%P>kz z2F~yRD@fSmAIk4Tc*39IVI3Yu6os>mA&_8$gF&N8Tx=AnpJh_uMzr={6Cc9kC>o7p zD2P^!AlAu*ytZrtoV_nkQ1{0hWJ6$eO-=XiXli;!_U7_wCKD5Lt;;S)OE~$gJB?Vx|+Th!e^5VW*hdY#Pg@n*w3o^Q5^$AfzR?{4E!Tc2v6{b*Az6r$n zP&B1MQQ0-uhb~mJ^o0o^BWlj&gB{tzl3|YR%h=Zv_cZQYS9OnkO|i#IIjD_bWn;62 zB%D&aD6&YKTpJHAC=%B^a_!u0ie?Y-5}q6zLrqLfBqAdEcm7wcbf<+G)eIe1btx5d z^e;aWK+o2CiCZbz9f%gZ1(=yVJ2b|;uXd1k9nu|I#wLC4^xa-=&$s!|Qy{a)xA!M? zlS8I;YGt!@#pVrKupYGe^h$?(WAwXkG>XwNnjNMd-`(B8%zvE@k7U>%-`k^sAt-a} zA(I(cgGxzFNl(ur@9OqhsA9kwQdHysI$Xh)jo|U7YfqXYK2j>MeC-m`E*ROB>yN>+K}=Wf=>Aq{ zU=(vQEy@S^VoWjMfKZyEm2n7=tu{woChvXJU3d>1zk{3rEnbXE@K+hCVIzyI_!Wuvckhlo&`)WzS+4vcV5HA)LWBj-4JAh3kjE#Vv>_#Xm zX6qdP3-*0bC#iM-vKV%7^IBX!ufYM@0h%WncZ*Jl6@N6D&nIexd|ng219t9j`5Hrs zqebC88@px^n;#jGcIINpxpgA?PsEi6^AJ`p86GVQaC3K`Uy z5j@)IxPB9%1;oMp7?_{g1hbBp@H@{pi)I%ah2-n!KvbCi5KYCD(H#fPjB&(OC8Tv| zcuzBNOfAz%(ifUUYJEDgA`|A!Zig8rCYG%b!@nz52MNO_vL&-RZ9dsY#hQD2dqX9h zV`FOcJJ8fSM(v1to?;mc4=J}H4Rfh2B_O8_;q*C_w z-u3qMz|+zWI(h0&O#HY(e6KY52epid^-F8rIW_S zfn0sbfAR;;&@LN4*~i6A0#V*GhAXq(1 zvXqJ9rC{>h70np+K|JS21InL{C+L0u+q36mAc?dL%pB}X8Ex#JnZblfgWbd)>sKm+ z&6T6Qp`VZg-jO5hI^g?>lZ!-jqr$YjHrI29(`D|x{XGkwOjwv?<_EWme21E$Anx0s z1x6IZ#-`LsQ&Ur@^~&>!naK9YE+cG|G&VKCQhz!ugU`=`Fg>0w;(pxLr+00Q#1PbJ z2Zx&#yK76psJRVC6(lMfK2@{(t!kxs?ng~m!?$&o#S34#rm z|Ba8BxVnC-*q*tv&&{!oWJ859;QAG7*xtXN6?sxEkR9Y1*7=8~|KU#^(?@EY2OV_U z-Kpc-!&}eGvY?2HA*ZlnBUU>@3d9#&nb4IT4wOPzWMt#yCe8P;L?32pI>T&tx7`Uw zr)B2G#++-u+aRU3!L?U%et?}2>8QG!o@C*iq3auPfpEsE;qVse!)ipD!6lwFE43x?VLQs zX)?QAh<^V5Mnf}ta&~fcu_@7*D?*z(49>`+;>tK~vL!DFv#A@0S=-q*sdN$2-{3Hb zgLPV+!oPPxg>2SZhh<2;`&fM*6#m+rRC8Anm~&lt+}}8?AX#QtjJ>PLles z_b2UjQ{{^T5{EZJ;UpINuf3TBD#h9M`i$O)+9B;T|3ypR{Dg0Kb~zedT2J+)r%K zj5KFPav_>z;qUdYav>_BqtIVSEMG9T7{u(lqp!;-ZX&PeuC2E}`ds$-_6ziNXq-AO zWNIjTOruBxFq*z1`wAG|tS7S$8$SP@1vPcqgV9rPCaC$9rZpWjjAh=HblG&H-OlL!b1z>wm` zlMfN8g=0<}QxMT-w9Dv}xN=r4B4lz9dZ^dql9{9yr+EW%&pQSBdNntnKfScdrQF9( z{LDwUs*jbUPo%zMiL1m8N*RV#gG&5MG$@VA=!3`*!RV`2!?ssnE%CvqKy}r2QoZx>ylBkW~zqeB_ z)-<>C^2t}CYWC;s`DU>26Our4FZy7pK#?lFpoq!aMwpVVUjllr_bdL=7_OEKjCI5E z3k6|z^%xfAt`e8rQ zv9}Thg=2C|Bn%oT`UxCd+)wK&#X>&|2vGoZdj6QXx*{zQJ5+bc2&eW#1v8=%d-F%9 zr;*S8Nab1ZYSXRI1aH=>Zzn2?Q2s-1c8e&%y0I1*TErCDSQXymH#=)wAc}R5k?oTE zC-QzA>3kc_d-)U>6u5sUCqVzWN@BQSuP(6N0bPeI3T_su^gb;bAKPVmSrG6haka5z zFXNx(#kxFM341G+d@ETv-a>yef2oao+G_N1fAA9jPxUP9N`+Wc?9fo@^cigZR?Zg# z>8u-XJh=JDV&ngIOl|hqC3vt(F0tjGVt0BcPpK(R2FUrz8B30|Kw6Ba`BKZTk3JvWuo7H z)xiVS_!B0$O%E9WqG|piu-@8PfjJu;p3t=1@{8rNDvr8#Swqu|?L;h?%L5B`6>uzcH?2^k^zwa9b;}o{lfw@AhtRn-kR&CWB72-|;oR|fCkV!7@1QW_ zR!|&S?C~B{NEPf5zEowq(4Ip$M->l6$4X z_@@Ktqbzy)kf|K99C;>n<}fV3ONSdd#>&Jd;EGI6Ee(K0NLb37XBjeNj z>s=#j=NPDWiZ};4avSJIZUT!^9`oA3USLluxO0D>rd1)0Ew#V@`Ssyi_eG%?=S|5g z-7o9EvX>pk<%|<~PF(nO>VC%7uLH%8jy8PwMxcW*rH$!iT+RHcMsK}%2H?=gM8RDo z)FZUB&NsL=L!{ZGxc({2`Oj_y1s%euZAp&k?~z}8QUkMzm5$Bo5xo(kX)Jhq(7h04 z%mg`e6XicIiUomM5l&fDxRV{ycJ2>SoV8Sc^kqZq(E%2-T0LmFw+<{!H8<0x<&;TLu{Uyx*rW#xh)qRY7AeY9@XO@pszxbkvAQ$Yh4 zFpd6MCKhNI20tU8pDa~3w{>ukh9q8qsv%xbT(nk>A?GjkjNt}XGRTbXl5_c12Q{6v z-_dB@|K#Ucj(Qd;OHaKE*41qK-Floc9<`LV>fX-d>y|m*tFdreT0SJ?UmO9Zpl( z$MXA|=44cx>kD@WD(2+Q+snBxtX-v!S1_0S9eozPGNN#6;S+b|BAOPqzTWEpI5FX| znP*DhVTkaa0^Sl7Jpg-V0>P3=1-mVu0%27t)#WJ(N#rGn8~{U`KlX>!O1dJ3QCs<%&a*b~wG z!fUP%Zyk$5pR+HzUN2M9kfk+Za-1Fx4~^?pqG)j$jf}{D(WNqWtsh^GvQEZu==$!^c8hDz8 zKI!|&otIB;uDE6q<$kUBM+J-_!)|$;`S)durLC>)9aVTYL1cBaV^6#NFH9M=G8~$1 zb{H9ZhIYNUs%N12xZi}qe7|Gfs?WzzcCaY+<>R4a$`-*(9m%Q-VIox+o$w$HiYVMX zN~_6DMP38nPW9iCt6pzp=I?ASk5;vP9`~W`?w1LMRmx1s z0(E1An60ZUBCq#Ywt8KAr?0}>n_-K`?(+2IKtLgW>>#QPC2ER%Lj)LO5*CPSj_Zj<0IDVZ>*&0c6?M}(_aUKVt__gkpacbpNvq#yp< z(q*B=V2zr18C0i)XUWtdomg?}oRawkMv!|i(;DW!!MM-E)o7JD*HKhrkgJSLyVqrp z%o)0!Zj$Znk^_gY+^dHrGtD%WO91;B@xV6w07y%rBJQYs{hSkoDoi%w!hY4JL-4kQU5r2}<&q!QxFS|!JicSClUNB_&o*H9d$7F$Ltc)7LYy(O7M_saXj@qefepDN z8}4bnqd;}KJd%KUdZWl&9(oUi(EgKDJf}6FNORNX-I~qPaT&(`RRWBK;Y^<9^e8C! zjKN6dOkb*%I)I;^b9@{yTtw?o;fow7tr5r_Gt@8;*Cb|se7CmQVVyxML-D6rJq0FI z1n$w{U#UagD?;moP00*V54;j}n^>)4{&W=iUAm23<4qEqZ3_XCBiQEI(xYC4c@>VH zr_pcQL&Rk0`-kN+x3{qpsK{fC3uIe`qyDlpRq1!_%^iP_`Is=$*8UoC5z~11y8fYb zM06QFRAQ~e6K{r9+Y%p5CJOYhV%^M|EAK8G@xB`*QMJB(auQ`WnG+1yzmfgthB1O- zA!bI#%6KBac@}?-WyYd!Zy*JYgjCpMQA1Q-#z!j>vxmM$7PA6FJfBLV45P=Wn5xDm zfvzk(il#P15<0jDV0Pg)*NDnkQK+%Wjc zeT$kPvOYytzIGc&J2idkOPEvP1NTO z?&^QqSCB>W%breu@H##ta|*Av(B}^fZ9w#QHan8{uPMcgB@|pXmsv!S^N4X^j}4@B zECzzC|3Gt{!Al=aH&H+E!&$z=g4eI$R(wY&6ICHb=nrHU?<1oqPma+UC~)4AGy5>l zr|g9pgpU#5%=tS=%D7v;8q*L0k^%2H#Eh!_Gig4*VRG%sC7cRt0I*GVZBXSs)+ckz z(P7~g#{!wOZZ{J)(Bq%Rr1sgCMPswap8c)9sHaPQ2(`#{W(Qxw&SB3>)%o?tp+t_b z@4!k^=$REgeoaly_}g>t8!z8@bsb6p-XF@3U<^NiUV~EwIGO^%1|=3 zRh{%W3Sua2*e1vjbxyXXrEy~9k$`SkuB7*H7`bqBNQy=qZk|vw=+BQ-rOyfQhNzgn z$P-hh2g>Cpw`bE4O8^HTbt1UuKFCgdZP}G<`&Ev^l;D#f1tf@7X9JtZ3CJjJc@oDtU*0 z!Jkfu*liXUl#|6I&N}gspG`J~efWo6p;3HP?U$?s6Q(4GkpZ)o6lxU2ii<8dB_YCp zQFQL{`bUkTo!KT20}cbd2(TGtvfmA=6hy{OP{9q@ylYz?19XkJ6dbnw+&_%LQA{c- zp*^8}ulK2~om*lp&%JDeEd@kH5RMTu?Qm!n`P2&};w@x7xq*Icj9__Ol+ly-=f*Al z+v%I2SUq4+A)wE@`u4NHc-__{K^jF7LRJC)bj_wM=xs>n%1Xe^$)Ul#i2$#+IAa~ERS({vp_;F#OiQe&Yj z<2J)ceOTm_$RwkTLfXp`ERGV{5dKt2QE!*X$AM*37(Q)Io~|KV9!d2rp7QuF8IPe> zE8dk#8oUgGR&WvqkUU6CKCnjbBJW*rJZ`j@F>oFe8F_$>9jl&A!$PImNpr@dRs)29 z81{z&N_?1mt_m`)mTu$MMI`qjFqrpl42Z?`pm{O&W0uP;J#b z7{w)vQa$sIv7zTM;-NxpGKg|P@=!PwG%c6%SxG+(&yZ(W%}$- z+AjvNZcG9a7)-iqW8$6ZGoxoaboLnby-u9$N=gaJT@CuzL!s@s-3Mg;^4NuT@yJ+( zHS(Cq`x{K{#ysT0d03GH{YwHe7$tXU3L-pj>QEb|bD)5eV28*Sy}Tq8tAE zzef!Qd`kS2#u|E%%#aCBPG@k5->%wHlO?MQK3GcE(o?u>6EtlR948Z4+9!v&P+`t{ zaBvw?VTDlS|D^oQ|I>z{4~(S{I3+QF$d%AnM<-4n1yrjin}=D+2Mhk(2eK+E5gIK* zzvd9BSB1evo=)YQD%_)buc!8ZSpXvC zkapP#H{mk}GTJP8F>N^|O46I)E7u7c$Ia)p#J}Gj&hf5N)-2fLvU-p*aKK0W+0+PA zyEZ=h+I>sK2b9DVSDu^@Ts-Q>_;mvCgk1|o_e{qP1<6x7-S{^-1IA0! z!SM1A0L?h{!g3m1Tt=Nf8>6h+Ur8g_wSTV65OmhwFRP4Vl4FZ+NrqPI`8)4aVN9s@ z8wBu1T&(qne-Ra@(&egVT#+iFVCs29X4cVYjy%B2k*)XNP^8`bX0Lj!yn#N{h?|t) z-{DH1Vy0#;&#u(b$vLo&NGPheqy1J%e(I0c=q|ma6*;|Jq8amC_bhe{SU+!ZGV}j6 z8Mc(<*U;l;?2mvA_%L%Dd^vzzYV!55cd4I7OfE9Ph6Yqv17DPEQ&FHJ1*E&XyOC~?kQh?BYv@!;y1NERk&^E27LYEy1g=q$$I4}LJ}jAOssho5qX{n zfwg2hE3Qh_udqg*_oT;h=_H@Vix}lKCc_FEK#H{{nQ($y424W6ZCRe z+}yAvID&!;DNs_zpF%{tT^zqS7aRd4?jb+D{_waPOi=^mrl{s2u0 zrp^M4Ss|2(bRk4LwdPgZBIiC#e#>dQl`|7(G>2 zX%$GWH$jEAdiOE&mr%!MCN9lpJjRe5(@MXHFHU8d3aZDFKP7SGdtO5hM)IQprjj!D zE!@Whw$pXl38IgelZH-k zC{$YCagH;y{a{+bb`-JU?UWL`zV1`UL=ZJ7`b*{o9^Ce z!Igqbce~JBcqAFuRGKucisTXT=-;=!-F}p?WW>J6!??mG$YMj)M@D**#LI0pja3*U zT1Q#y5Ju$`nr@vDq(tqP}CdarbgNLD-=U@$iIKz z+!bC*(GiE_SI_fHD97(tI*!WKN^G}OUftfds$LMi3N^63UMWVm?&DikS@m)wG@Tk0 ztXi;(zf#ElZ5no$x%@~OF;K-6rzGpQdAWndB9b)p!OA_GQ6XaU!(hnJZ;Va#$p139 zymTeFH5tTzww>YgRXDc<^zAZy>(KrB5z!))Hguh1(J^yoWG8X%%{ZQ(?HdGd)@rVR zR$n#3o6hRL`uMF6GY?J^XSH$QIAsPFq| zy|=7Rcy|TL=v>>l>T6xNJ~fQcq+Sa>y$_CSoR@b(AS8qNHu~LSxOA7_E=e2aik5SMvw-G zTdhUJAj;BZ&)|}mq3a1o_1*vNRZo;1ileCv)(Kr!#XxyG%Q*qVK6uP}bx6j>9XIw$ z^s)kdFyeCvI_y7{sGL2or{a_Wft_GUC|-V&@5jVG8(!q^sfwy9ae`jb2nC++UBcA! z?28Lj{hJS!#-pgl>o%z)GH!3W$IJs%LILbsG$|^v)3d{_Tc1W&EEj*38|~VL&g<=` zR(5*2Y!3H6>|gkMkh$E5y%@+mE~H{2iqXGtlrk-1x<%0XfWcrnwbIzE={iyychsum z4TvTRlTMM_I=F0h#QYk;U&Du85|f*8*09uJgW^HZFI$sl8Ay0wbUgO z^`*>Vt30fN>ka!oL-eq)F$!P2q4cp~&=VS>hIU^^6(P0tjsw~d-Hbx(O?gMvuBx|wQG87{t*7Ds06kJBgThf8 zS~bKQYi&((wO8!73EWet2OaegX+!-CA^(Eu%k-Eg|2l&oV~%3)*RjG;qVl>e5I(ML zy^jFe5AmVN@;zrB-jbc9J$Q+Ukm3?RSgY9y_uR4UX&&Wd!$t^jPQ@p%wH3|e)@)Lu zOUh4GxR9 zNhww8#MZwOKlfOCq#5B|%T&tY@Py=AC{&<6+%Q@g#nZj2t=P$>2QNSc ztdZ8#)LgBGG5@!9ep6hkXwF#u1Y@|nr%2|Al&I%`>+?>!MKilJJV-$0S_r}@V=8UBtyLH&}tOL9YrCPDFzUyKH2q4ij z)Fx_aX_1CzOH7&{@G?=#dX4Z17kg)~FSO`;EOzAW3=2K}ft%hwWWP?m{^L7$h0~yX zjF==W(I)>wdujVtAYW!7Y`$en-t%;KtojS~@{2IZ6pI~02AUU#cCW(-g)OprRvA9J zOqE-42X{xpiU#4AoeZ~oD8ei3Ny1@??_r*|@pU+1`ucnI-*YWum_05&@2#}|uzz;a z4!MLKwaT-L!|9=)-x^3VnE^m5UDRyRqM#FtS@I8S7sd~5GU!sqfMKJw*GPL@*vH)5 zC_d*o?GcMk#+yp2MRz-0R}%+Ft{%ZO1@x^_1JcP7*@5fIBMeLSVCbD_*Xxh56gW8+ z)sTfo*C?>7g5I4_cv7YkaXRg-=uclJ4d3URS`i-i&&17Gg$O#sP7n(hjZZ8iTkr`BeL@*t=n+jgNST{^D zt?#nK6mijnOQZGaSP_1sr=W9Qt?TC$Dk}q=n$dq=J572VqahxwN{xHtwB#Bst)}O? zLM9KGx)umpVu`WEzW5ySRZMs**&mP+(jr+W$r zQ#>;=X8a6nW~hVKqBgglY1BT$(iZfU?%%Le%}nu}xJs^>hu*aJx;)%Tdw>- zP^3#hf><#u_1g{jJIu)(ch-7sMCNqay;m)*6bg+aVBOlBW_W%omT6JoJF@#<7>AD1 zJbM1iPA{>~<>^g&@jG&1?VJ#Sh-_4{#-dNhfcEXfcp;wkml-wj)TwM}Wy2`V^d-#M z$+mFtxoXR6^#H~$6RL>!)f+nS3#D;==k~SUo4$o^L8J1RdUvg690th6%)<2Zqm)5d z;N>Cbyx9~{PFFz$0b%)n^85q50euT$hYVh@h;C+Cvf)O&iuw_s&D&8C{e#bUm^L?e zMS=|Ej_mj!c?H9+Fs^=UIoJKvYfUi7rm==X4^x>e;Vf`MU1aNl@eS(lmu)TC4i9q* zJb4)UHs_T%R)6@u2oP0PS9f1raP98ysufM5mU||=Q|Mp$lraiL#;~7=8;d=@{Zi?a zqm=BS=R=@R$#yxNBuMEqdKF;YGgSEd-?g$m=81SIBlJfC&GD=V2`ZcJ3ZTjcW@He? ztAzI&QH97k=#)*fOi@BUtHfga84mm--8_^mh_+!HkFzOu?kYuP8a^@S5S5XDR`-LQ z>Y0TFGJex8-fPUu_9=R=2_?D>)ev-SvW$v}0QhGChO%$Z1Cu=l=TBjaJbT5i{bwSi zruex5G_kmaUj5wDQZkdS!$msH*7?{4k-qiPZ?*SOLYvuh?%pCBwq`1CohIz(eLKFp zJHasI>cx^>*K0<$>ZUehMp`oyIUg`yT;3tdee6E+4`g}?qp^F>{fm_PUYg@V zGUB=_oFSsO8oC|~I-2#?wKd7ysP&K7OcG@?MAIb_=DVY6J@-Toi_IC;FzO_1-aJ(d zT<$37Qr$`?84_(`_h0GSRR|+gce(2C6?K!NyMuU|CvQo$(k(W?#@jRaT>*It$LJ5_ zJG-N5xAT$#4-9MP)Z|Z#VgEuQl;ZIt*;gj zYLDJccgHJ9Oua6&uo}}_*XW>D4jGJ5FHernt>e5Ad{?o|lHYLCyyx_7=%$TSNU$Y; z@HW}l!KcUP=l)6a9Go2$TSGz;LlI_u<5S|%VsYY-s5<6ysB4NgZBMTkJuz@Th}`Z1 z59N8}8o}M!oGLtesTA!UI@t4hnS(-0@g5gjH3OY;=`EUD=_D5Q9fOKvDO|?ho#6^Q zjum}6c&NE2l=k-u8f}Kx*vk(>DsBQq>_kd+fX}S0t=;875UgXwkU7|VTxlf7!%#uV z7`C|Q9U7(_GKziL6PH!DJt}W%SjzT^ZuaTzRvVN^P~$O3)9U6jeF~vlXm(8kr1kz| zL@)*ig=mR-r@8+p!!L^Vq6k&2I5yEL6)i12V3kpsfWKqb6s=n{ING-U360%c$qr6g z{v}p+UYKMf#OFHq16MAU-D9qdztd!&T`5kWj1Y#ud?>f&WA2@gXp(ZfXY?hLe@p?j0Y-mfbn$EV3j$K5yD5opS+mo9riSf^s4(T1 zu#?^U0fEQbqe`V_w$@jBZ=w>kO!SCLs}~=-<-LX0AoPwUE|meLM*#<94vTn7hkDG- zLb>0Wlvf>fsGCo}lQ}9e*cy+U$qVm1|Nd^ora;W6;qt?{Ml;)K+u3nDHX{p`Zzf)s zLl6~<(hNiWR5oqFfv@%pvnPkufl^X>W#mu%bIQMlmNXx! zQz>ME*OI|1-1vB`(qVcBVe`t!PNvfM5M9d?ra&A(^S$Yp99}#f>R~%x$eH{X{D(9j z8tk`ey8{f*4rSyU==6$>ldRxQEi&I_*sKa; z3v$BiiC=ID6Lr>OPlrvX&fc)goDbewplzPsEpd7sJ&Q^vdaps+z(nrE9>Sedtd;qe z`1vk^>Ia_;S*6Uf=_bDU%e;+HmO9FwBD8}+jdhh{&+hN~`C=Q0Gy!%=3w-G@%W%15 z-XyaG??6^|-{E>>jrwg5LFejoTHhG`vTpaADR09&xCQg*ZXYj9X;KP9=RZdiz0Pph zF!%B(`;EX=g|ZXVU=3%AQ+?tmcl~Q4_*jpG$GpViT;b@c26kC%;VbhSi!hZmJJZ0r zubJ3My2`7nUCxB8cA-Z1Gc7PQc@#y5evX!}eT>$FOa6VsXG8Qgq9PZ@{N3)g+HIO* z7*Ze-0e02TDa!-q*8v#Pr1!6vhMHDOfn%_O5h~zII#+ zMP;=Q)UdCWPja1fX{ZQX6+nx2oOJi=P+VNIO=V+Kj9Hw$F=Y4M_4}cKq34v(0GmwI zaI3bEa@EMQ)>Rx;#8hc8=__Lw)rt4+n8jzS@D%#Ot9!1cn=DMUQ=uVy9=+`epFXv0 z^bhZfH?Cy0TNsf=tB0K&3NyNtb zxwz(8&QDTz8^Qd6#3l6^7AU8wZ2vIaYr&ppz|`c z)qlr$^iU3j_s`zZ^rxkVv0vj!_R&YCT#{omQM1?vRoR>Q7L3v*(jqD9i2Mr7u{jxM z(iWCb6vFE1My^je{Qie|yRs8ET!L31ibIJ$I+C5#G~6{NuBP4xE70|QBkG9r$*bgz zA#$G9je%*}jH1;Al!sR%`vs0r`k|cdi{BF^zD90JXbzOd_deD1?NQxt}N~liA3Gi+9-|}Us0Lp7`yAwIO`*F zs}J^i|B^T{D&=GmEVlJ!RM!I_wCl}^PW*S+9G!}$5v!!9SRTq;Daz~cw3MhGoOqRk zAwZZ84ZM-3PqoO%(4)yOePvG@4kYP9P{9(OdZLCotjaETWa5ZR`mwUxjh8P)9w&;L zfsxbVFTV8l$Y_RSBBn^ZW2tz^E2FVrlM!j=cY41*{s}bO7z!3OEbhSzi?&cW@~qvv zTvbXEym?;q;H*z-_UCl=d5USXstQ~4=C~uY_D!0VTM$A+ZKJ``EnEoJ(qrmi7}y#d z|K~hkCuWXpTrTvOUCVkPJZV5n(JZ#?8_9qVbLv$)B%%h3Qru0cgi{&gN4zLLbcrub zi22q;@@8js^mzqF#}_XJl$gS;zx75mWmYVU)NneFhy>;5bd@zmcS*w$W$saE>xg9* zvD2G3v;qpUuDO1!2zk*K#Hp7QTltxkfldvYq`Dh-yQ+kvnqjddxyTK$>eoh2e|A3x zd1mBjzZ4}CFE80F@=j`A&J)}%WuuC|4HTktq+v%aTb(cs=iEK08&4iuT>Z6j(eh0i zkwUpte5L0r>+Ah_^&2i`Vn7y&6PLzDw1oHdhu!RYj4AQ{qURoYX()Tq=sc-;X`-r2-uL6oSB?vL z{CL;oTl`3(_RKWwaOJI8A2M&e50m44Y>kqT!i~V21TC1-yvt_w_UFAS>;z|B{=;ke zmli2HI?KP;<+7!JM0BSjYJPCi6yG^g*9Cr+OVm)elFua;|+ozVY|`MOh@wCYa3Cibkl?KX$J}U zaISjE+E=`fEeMUPMU2A4cO3lHtwK>%WVQjCF{7Ie<`KDFy=`Yr51PF>I+wh}WKm|M z1F~ty(^l~?ea#nlHy$Q|llkHYlX#Si*6RhUCa!o^$`0#fjuNKURX)#{(Az6jGZU}= zTc``n)4XsFW4^8F>J3n(YfH^08GQ@QQxkFcAj%^aO-*uw*2FG@^(bXD9{g3lunCR% z+;Kdf#-Z{EFX~v5u0T3};7d*80Ci)dOhYHbyWU2Es#yTLsmQzV>e&JUN_sGqo*z%2#!sTWUPOaIcmHcnq zxwE;y_N8rnM)v0Vc^^0TFjUJ@BrrGTJ`Qoc+px+0VIzKQcbzaCw7QAk?7u2d;B$zQ zcBm?)86;j>{~CF0a@(ecC&)AoJta=WN1m2cIfh*KMal_jC7r!lhnXc*N_2?aX`(@< zRXA3~^cKa6MUuoMrVqL-LW?LZY$l%HI9seRvagMV*}Nq<5#!(hrz>nThdV{r`sBSd z23u^hnfHU7(O5kGL;btGTK_>?G;FRC4uYQZ5w3%r7)6`{jcwiVMGha7V@WHPNw{;>X z^j`}~nNHp-{67nGhEGe84kJa<7#Kp@$$ONxNME+~3_26D>$|8?lozswZ=U-d(ISlJ=bPgyGB(U)KUZx>)=x-6;?UV_SdE;f^bH2y~9 zQ#^kzQIi(R+faiWlMHA&=hPsLnLHvIq3BoV(88%8n$Vww(oos?t{i>}E}qyp$b4{b6j111se}WJn=hqyV#}cB6A^qqOR z%>PkRQpw=FqducH63_jqPKQvKzZEmO^*kh&ecgT5#3!;czq*~SlgT%yBGs!WkK24r})kDevgD+?@S7rnBW}g z)%=*a6!H--vFq=O*G`Obu@uEp4g??IJ+}(+z6a1{rnvrqV}m|%D{&0v2+DGrQi*Ls ztrXfHY44R#XEjF?OO7-yl^whXM@oiYP8JWn!) zJWZY1T!MU!PkEu$;A4zyFuvvee2l=4LtOH&Q6(}upNuqN7h3^U7>S@P+vKe3YBH+4 zS=i?$-i51^&kRR==NZFNI%*x~t0i(?cy6%jZ7LR3su5CXf{KW5^5KyOE0)}5ES+1J z&%orrS`nJO1yL$?kxcIFL`?#$*&$dT3%#--Q`M9-t+Fg;xW5YTE6PArTnGBx=Om@3 z%0%FCzMsPi#z+R1&C1(zru|Oshd%(&JpSr)4Bl?MisC+7cQ86ULGkFnQA(GFayWc& z5MgumL-F)|uB_mwDp}j({_`Ah%F<6|lNn$BnkS8DnZ(c&TT5rM{b!MJ#m8S!4{?zE z3+{4!9n(pnzAh4fr#(;Z{Jx`$OAlaN0;Y^cnI36?0YGwq;M;fhh6paW%nQB$;ap?7rvaR*DU9+{#-DjY!Yl8OC$ZZKRbPc`UhEmzW3; z0bz3VIkW!_FuoyJWg_5Gq37Tt-#9gzg;N=+PfzjeJMr-F{HuZj!-Cp+-$TGL>z*Za zTx)~uPPsB@hJ+f4M~b&FA-xRg6B5g`3+OV(?k3ma>*Wx&Fog`u^^`VJ{b76X@%OZc zr2PGqz`sdi_PZC7tD@){v*czcpvB)!OBsg<_#gm6jE{d(M#qc9iRcAHs!xUL(3lkX zu20OEwH{<_+p~Z)Z*}V^*}v8PJy5c8g^io>zk44TvCq}BuhkLGw)>0uOV%U_ zqOzzxew>*GXZz9B(&gT!Rr+HhEdJdRk+j>9*Y;ZP80PS~quxci-5xN4t#9pGm%8f4 zu&{WSNU}NO0BZ(v$u(9WL3<&S=FvRzKj>pHhJuG$)C&3j;j3AzfEYsizyMOMi%T#) zroI+h&q5Qc@cv9(>HF(q?MP{chx7v_)m2HWVFQ-j<--ZvS}n^Ob4F%%0^}_xe!$Ma zi=f)IvI1|2gyPjW^&rlX4=Tc^&^Z5E0q<+S%9XDXi-avRjS4!S;gxbjA4y8g`ijF4 z#L|TH5tP*BP^b8HL}TT*s+D*beC2AF*G3jStJF1slngx6=vnxeSaZG%)e#TDUz2o$ zB_^qIa!VJiV(+fX>Fn3UWCDLD>RpB_HVzwb7}`MnEprq(OY0gu{AMP9Xf7GE0f`!# z+-ZFXBzt)mI>&3mmh#7%3k;$F1#u)}(B14uif?PFYG`$n=Vc^NL629lwzI1QqAz)l zrInY-neWm2=kH$tYE|fxeb>km(Pirlxq8L#GU@7(zgq3Fwi;}_v86IYStFEi%q-4RD=xc@WkYJKXPHokY64BVY9{;a22?O_Z*PIx`j@gosM`6>IVjt(u|grjlrHtul`Qwfb*`#>b%)i+=J z=4lQGh663P2mD}DTHoiI5>P`Fm3!Cw`m6;0;HMOX_+u2R>IpF}GZ@Ft!a7YkfdD1A zlHWj7JO;w6DPV{`pD~+=CQNb)zl@UU zhT}4IscvgGxmzLN0!#F3Xd8sg3KVlExnT_-dT?zz=Y%94Ol)Fmq-prrhi*9sAmD*F zRyw~od0oc>3F{y*t(yRky0eW^`kE?^6}&Y8pS$EZmo(qo`DGr!rZb5erlq2l31yTL=U<9Y&Ed>sj0LF2pTA!xU`g#Fj&Q zmi7KPYH{T!^c9e9e3Ym@RUVu-Ov>EGe}7NRhJy@%>zbCHS*;}fOu@C`G;R=5{#Y_9 zmra)oom5Qk9!L4!`BTVf>gj#)zEAe|cO7AU*}l(Td%ZJQ_H*jjTT-ZM##y`n8}Jtd ztpFk4L77~ImroDE@;vDqFZ4pL*G{&DM@Z7xsDqrRGk5HEA{Q3lM-%sKAS!NRf-8zx z(3AxyD}H^dM7xj2QKm8CS%zCLDm8f|2&^Y(h-G>$tAos~#wN~`ev&3q6d{81RcdUX{{t(19ku*mP? zVp|Tb6d+RrBBL<}Ub&}Ll3nY4;$-!tH6!Y*hp{waU|m*6Wz2;}f%gFOXr{y5p$O&X zMTuZQv<9BtHowW(hQ+LgrbtsAs)}EJ-S0lLkW6Q6+lU9x|t>)$lFze$N8DU-(b z<3y;8gy?E36wI&m!hBXIi!|%XJ1smRBT%F-HQ=ENZa%7B2+Rd7z+ zhle{m-;JpyqG1nmp8m%1CUV6CD;AuiMb~9kfK%$}nS!jG(@DOx*9wMr(8~kehokSp zf6O^5oQBwMH}GPvl6dAct$?2WKOiq>0ANqc>H(k;J2}wuG7w=>$D1-TU3k~U{b7(f z{ol$b(1R9gOjpJm-uNvH=bO=phFJ_)V>sLXbc)bk|8pE=Z zz)Cu82#yyUNrF_-Fy_!JwF0*{bj-ZXy>urV>`Dx9_w z8F@LY{3oJde%SlmQxI^lz>Qup4<2L6QG*ut?+oCjrKKT%Cs&MA;^E^ntgr5v+N7F< zL`c`iKNj>#0m+;3!^?W_Tdt?;=lkGiTQE4S@7r0s{O~rxa?h9tEyX_p>AVv!));*b zr*4cPRgq7R;?r{L-}kIU7$%z%&bLQq30Kw11ir-VV&mW*j1@_ROXhUIr~IaD-#3C$ zwe#=m-3|c;A-2oZY32rti7LSqv&g>lGDhjL@jVT&N}ndaqcFdF?gpN@Os_eAf)~ZN zOpR`DfB$&Db{TL|+)p=AM!~h|4#N(YB+sS+x&;YO@dJ#Tr>3U-%E?mX-Og_?0r!mj z_V$g}>32I|op$qKIM0;CQit;HQl%~7YLP6*k~tS@=2*}DGded&0x?9<&C|YZtyc+X zGJ;Z!mt5rAn7Mq3o)OT;gj9#3a)0?dxWq~heRb~>1;oq3S@#Z>veltMf7jxSE|&Mm z^NbHKi0J8yNI5G5Pg5!d)R;KG2)$YydQH3jy=jjArIBRhkOJZk2ZZeLnmU2)X$J)+ zZ~{-s(?5K-d_18f>kyHP;V4*WmQ#|qg9GtnG}Wud&FznFR6Sdw0WYCt8J$e zl1~G?Bvx^_Lle7;f+I79)h?3GyL~+zc~(296aj7KohvJ7!jE_CQN+Tgc6L#Vi@Hf3 zxP&TflFIAjltwaCG9;)0PA2BW%GA04!1BuDo&KXtiTcK_uvh2K99{xs5?||?QMr0f ziNhFY=08rM)B!x=gu>jYI=MCoor8S#2bQ2vqr3EUCG=cY5){pEn32eB5cG^J=hZny zH>v&^!jjww0P_Fl@%)%emXwJtMTNA|w+Hm|hy*>la-^cP^!4E&@W@lGEofa}<&pI& z$@4bS_u&)< z4r)bH#n9#^mU1q^m-xsWf@wh+s+1QWvah9pgKz_Qun=&_|V zBYTaOn%u?mRK9pyu^WGvaq?rq`k|{<>hJ-Zc43BPE`qw?JD=8-43t4rtrODfJ9(6mt;apVwzF(s7+MkqDDNB~JTpYoo0}A-=S7pQxVgCN! z>KYm`qOn_uQw@SOicWpMj({2lsBTO0C~y3I`evvl<}$NBOiM{Ndb_Q|vHe6bN*2Mfx64rdd;w3IR^m7}Yf+6x8o^fuvz}ES!?|o{)DC~5S+t*-`-y&E1C+k#3 zI~~OoPNV?qC6N4gX&zFPUyUjpNLNG82;fw>w*F5Nzv>TIguzyLJi#n`zhr;Aq^r)& z)xk#*F4t*Yd>pf@74HnHo~LgOp?w6%{SBaE(g$Sel|AK_^v;;HvblnnqfuyUqkO}W zj;MixqNH;}{BQE&zxce5Dcv|+YF-0kv7pX&1V2B1);zam%{cIiU&}}r!;|SxTfZJ* z1ySC8+5lyrZV?7Tzd6r3pn9*_Ch_054A%XN+Hf$^@?1vcE(mne;u_zR?SXJFiElO~ zx--O_5>_0Tzc7+6ZVN@ABvpTIgs!yS!1-nY&n_;Y-QdY9r1kD3eY#8!_zc-_O>t{l za^Wfw)TcD$OSk6N%u@pm_@V7>disT>`L(G7rU=PJlNtm?1s|O^?^v1wF0EpLciNLd zoIi{h=6+rh zp72OfQqi$N79#>&dpEbf{(eM$e*V3KgK^91pIw;XWjv)WaHYXMCMcEOz22%CQY`2^ z9%Btrd=e&xFeWA?g&4V(0^uTDAYSFu8pRp}b~Kyy3YHJ!C=g`}qi<@}i%9d3CAVA} zftnwvoxn@wgmJM@LNgqu^Za!6_02pz@r{s2^##m0@JIu)AcdfAmTXq<)$E*ijnpif z-chsq3<@q$q*cqj0k9`nq`@51k)cJimRyoyqn-p&%SnEi#qG^_*W4a$nbZC&3bJ$g zrb2*p$-CTVHe#%v)r`(S5K05C(Mc6W|WJrt4`q!Mad8^(%PXlNNhRkDEz{tcOO zYA{Q8nG@nu`D4yCvoza|gYDqy<`!HY1gRd_8K4`M^p~aVvGjj^bN_4>T9 ztRdrFZ*Q-BY(Pl~BZ$4cd`^WS^a)7w+S=Y02y*fxwn7hVk?B`62YZr&z#1%WF(d#)p$`-${(y-F-kP*;c6mCoPb*)e!oon777D*0JXmb)1yU_D3v(2qWH;VPqII5AdCGRbYgz{8 z=8))A!llTUT094{gpZ7W8oRp(0=ED|rJ&JJJcUbp+LZX%6#w?GD_SsMY(=D`gU^M} zP*yT#&9U|VrYcGahzMER*!_q%6mZ<0PfAMC($$urP6d@*D||gs2ANK!eoqBWwgDPA z+Mo-*K%59kX;Mva&cP8WHsQgs|LyxP-6T;P*vavA7EIfeC~Td3G+8EAD24?0;U@rz1rU9_I?*b$lfc!7Gu>R#(1j=CO&BH6Sa&{IE zTIP5)g6p%D#zxPD=G#}Gu9#hz>w<_K?uCPo1o{g=y#^L9!lp$a@A2uiC{P*2t39o& zH`GWLRlk%RU0lichCRBoW&YW9;@wYwT@cL^*_oPM4UDn8fi)xWxdPD3#J0VQizK)k zla^?`tot=_-8nIG{(42z0K+o1@g}4sT!EQ`GI3>VJ)m+47c?xA7)I5Sq{-pEdxwV~ zCN06@JqSZT)r;CmX~q&C+WPlb4ElODU(fUNgZlv5QGjXwCz1#G0t_2{%0|KYi7@rA zp5)w#-~){n_~CvxV{(m);|FGknmu+^)TlSvssTh_oPg{2!y^QS#1QMCjr8qZS9~v4>)Iu zNgA5k+9=A++c?kRbsGp)D{z1EL?y)qFFrxR^Rb`x(h%A$*twW#5Kz#(v0=gavt7rr z40gA`+s&p~1>c2Y!BfQsI#LiQfoOwmZKwHqa44|a<5HiFrjsNKA(Og+Y^%Jp%1NOh z54wNq7`J3Z)e3*Nl*?33l0}lgHhTepkPO@Dek#(CdmgL5yW$B*J$03n=Jhyp?J20YP)@xY@hzz8pXQk0K-9_YxeC%$ixD1BcS~E)LIq@-_!C4MD!W~XQtq2Kik^3#=SIp z)O?pYxmqoj&O!rK>A&PtiF)Q{eVL!Qc4;5+hGRVZ3M}eCK)Tx1f80U-mOxijM1MBo z@uUL;05kxc)%iXO&Ckz=2a&&9;tRY0b;6f8o01KnC!WNtZy5e`7(xFC1e|zyEh@|F zznz6?HMAvkNrWu3k4xt}<-F(}t;PLF}CqLP4X`#7?lky|8hy-3M5O*Sc!t%gb-o@C!$-%LMZ1%J_)- zPdU4io0*;Nu~XiuxPQ%hHWJ$#o)Uf#w!$@MJMU7J{|_fKv+v++VaJfYD%e*AxSwR% zbPmvk1bB}A38LBxkQ4!Jj!RFU_=F(;8fbGgt)4Il zaN0UM$@K($6$|D?ti*Ek;JbD$n-}}@G zElrPQEF zIlbWPj_!ApuU0oPg2wr(qAf1rGG_|I0jdWgk4H(*!3bl^-HDv-@{*VY+LXCRbLH^HdyAV&pmd$D)!7+5>x+K^Y=QV#26M~5vd5b;wW7~-%IiA@1ny4^qNOIE z&VGxue&ddwO)8*Q?PIodEkG48Ik=KZ_$*9QEKx1OA;YPbz0%y;qT>^FKgOI{CNqqH5|%bqGHV|L#g( z*kjf9d&#hZV&r@GtE1Lr3c-WLc_XV`EKuJ|SyoemQYIuGYMde8BQDEI)CuOmyIm5> zQmoS5+ZNx!90|xKRyPd+FVD`(Okw&zyley+=|=~{LZdLDjYqS?=GJ+h34vv$4bj&~ zxI-csm;`fi9{Hn-DXm_k2iy3YXFOGmav0t6sQ<-4i>rj20?AAo%^GU=8z%(4M!reN zk$j?2YhJmgaxE8E3Ba?5dZvMK2wj3~R$s%)$w}<2JPrHc23vwGG_y6qzaGTf8|NJFO7L%pPaCEZ4`Y*_Gzjv1-MgxZ?jS^EvhNpGU#LjZkwA*_LQCPb+*0NxAH}1ls?71R(`vt`Ja+u$pF4iV1=c}TqolUT?r zYtouEMRCkIVmLwpI0etl&6)CLjG6y+e|!+k8Kco0>~+7`!yU~eMA*o>Q$@0Qd~-`8 zI`|LL+%q|e*}1~901O9-fQ!mASXt{ssGGpZL1~{~OGCrv#RahcU<6{v!IC*%kN1~A zff6h1RV4Lho;B0pU{YD%W(8QY_Fl_OOSAel$xk(bsLnO0{zJMWI7=FR@LDulhChQP zN-uogB)%=vvtCoBY&wQwW@hH2DkpG71RI4qIR#|X zq^CC-@nxX1$|KDZRL+L?yLA}W8?eE~EULGwATxuQdePHfPEK9aFfUPB6~q6{{**Z} z>8)Z0;V;{S@WKvNCZzLT)&pOdPk_of&8a(G&JYG4jiSXk>8l`k@T{H3Ox#bA|M@Sp zmw1oI*BmMU8?CFW`?t9nq+S$p=w8Kd1D-TBKTtdXWc9^G!V;1-ZDkCVLJZJu{1~_g zh7SAtHhRq-fflJcIy(05?)_6!Slxzby3@RZf+*9Xq1nId%lq38i10ULQN2k@Y($Q} z<=ISF{;h8Y@Ac-jXMIPoIE|fkh3{3kV||xB$Ld+<8>SKF=dXm#Qx%zDMxf#<*|*_P zm>Kab?R67aJ-bIF9x1a|X32JNR8Q@^*G)agtA=Da)_1hGvjaaIyX6)W4!j?~=<-xT zW}SN67+MMx3lu76vlneaP3A!OMt5R%X^sju%APj-@;GZ=V!|nV3`g;!o8IWHl@y~) ztjO!AkM+zYVwhb^uJsUB*yyo0P11mXuur7TJZMM8e{zEs7aZs>?RZKo84C4{jcez- z8e0t`ZXBBzHK8{1pj82%W8Wq0*o}fHC&qr6NAL^FUM1v)Co;gIi+263cn+)DXE9}p zm-x3yFPk#krVDN!3q;}1?}&NLgMHyK&9}^L>~3niORXg96u_NlrY7RoPX-OSgTq5` z1AN)O-q!v7p0;bmaT+6ZUUqnKJNCxIk1KPhFmorV^bKap?~&uqZtrqUinL)vJgPCx zcz{+qdV6;omj44{jv$3kgIffy4A6@P!%QGj3$9?3&wXmQp$NdCSqKcYa4TjBsHr<1 z4j&#e)%XIl-wvu%{x-WW!k>oi6g~u;pmC{HFp&1k&J1bJyOy-ipZDw?`yIiV5NWHr z{&FZ-*KrCOKQF_)m2I<^gxJ0E%|ybEM*phBfhRGkrZc?)MEY0O7ZHVoU`-DJpc(+0 zl)tirroxD|^zPprp5|2ldi)U4EnMy=)SlCd@OXL*Uz72^RZ}`w^Ys#RVRo~QnA}Hl zj%OGILc+2A6h#T2q)OH4gK|hCckMkrF$zPQo32}C;WjfMW(6(l% zhChq$Z!TYcY+>z|n3Ck<6?-KV#*W=_mC)F-Up`ZDbn_lNTR@xfc-}WrE1bQgi>sw3 z+q(&nWdO@Qx!l4b1uGpcj#N^WnW%-|fZ4;r_1xbb8UvMsB+C7<;Q>JNX&?67sh$9P zye>5YgtorfEU)gs9rvW9%?4uvXp9cuO!m4^V`!;audL>mu?BnLG0>QC8FN!c19H9B zl#7>-ugB?TCdD{jPIOCq)`rJikBKz0)*yWKz`1q4ajfTSi?)21m*DpPNyOtpxL_A^ z053@x^=^+r{S|^ous9tPlE3C9lZM!pG*g?TBUOa`PEr+{J#g8-c#7QIZw82Uuq2?; zHF9J`0TjP9#dK%Ev9YnIV7V|jRLga$-x3||exa#PQ?&;1^)+4pW^{}J>4sGEF#{}k zGw1HAgKiwV%MutugVo!OszDwfGl@c*x0^WJphy?Wz{cI!o-^IPdw%}S=pjbkA>*i1 z)Xd2&Tf8IeNJ5CTSQq-@#iU)sEMKnf1?q)N=N!%}e~mrjTK6auz_hcSgzQG5<@ZHR z;}?6mdj^!2NSdl$=fAjHN775KsQ_8)85c*Zr+=2;dC^w9y|dHPE}?WWOc^qlFJ8)3 zg~ru8{kz$?vu)5XkzV@w^SztfOFM$9Wm%e~Yj5gf#(I6M)>HjTWeCxi0uR#N#m0{z zfykT3LC033+uMv}DP+Kl0aL>8+CO^(QxZ#%#4AQhKPsI&fF|Q8_Lw`>%dw{nz!+jr zUS45h>dP1h3Bc>3%-#T0!p6-l3jIkkTgHN;|L#>Uy;{7br^669kRS7a>mbusFn$36 zF>P~RUOwGQ?e%8!bf%7%9V4#g(N(rvIA4V3HutY1z{8zz>>d;)$)14|1~tw8?Lm{j z9+zbH`W=)!N}5gqGR*?(`Qh-q#lM>(N0pg71JTUixz>8rAvNs+_J*}o)v_jq9hkP& z>F@?_)6v;$!pm3Um5afqWVr<3{r#^D%A1~oKAb9OUGnUS1-Wlz<`M~yzPiNSoJ#z$unAHdN1fhdANq#CCG0S zAMgh`_yJaX>8xEN{D8DG!x1woNJiIC1Y0C&>#?o6+nvH7Fe7Yxn!3{RIjy?egGF zF>sZsri-jk&JW)~N9ZXdO~}z3T3g>k$u1Hha^Jpvo3Lx_bt^pxkkyDruR<3Dzj=S> zIgSvq_gxM8(f#J5bhzbH2qZUwM&*|Z>ZG(^Bhi(3OfyZN!$(lt0j;VDKtGEos~7N& zmL0&CLnx!;l`U0?Ddw>3{&9>0J&bO0unGCMHeUqj*W$(qC!eAR`VZ1)j@uviI8AjG93Q;YldHy^Y6->`kLNqT^M&j{yum@`OpqN^fKm!6gpNTTJN=IH?&_{A9tzQFa zq!kP`$8w3c$a?Bi6WB^>l}>7qPir~rku^whzmxH~xufHQP!>U?R2qWJ?{bA$%A{8J zu}K5197x>Gtsh8-B`Y!kyvOTe*{vd(4cyX6tFMufIFBk3#c9a|h}{x6!}vybo!*vQ zc?#z?HcU});Z+Tx)RB`}PP6Ff=y=_X9ql!=y2nJ89sHc3YWA~E#|?c_#m;_peNa7Q zJ~i0Y?Be1QyxXFiEY;7gN=&lqlB!trEj#n{v$2oT@NnV~iK<0z1PIk`^L@zr)T9Dq z#e4<04Kv=1;6Ie@VzJugV|F3~_#Go2?PBd}0Q!xWg>dE(*7XS`lx@h>I8z(ERkxr& z@N$(R%rD*DoM+EETvI?9JwsNSJATqobriT8VU$yK5b&c09{h0$c9a35R3fY{DlxCu z1FLz#u3eZr4R>ru7_hrOohrN;jAn&&3%k?X5n*Jti!#U9|tAORKhQ;8u^g%@v5&(BGFIAsgfz0Mab z!3K8i5yo0w+>yE(D2|jG7jC#Fs}%41Xpp>Vw*+(>_HJ&W)~UabXlq(qsr3J4W@oFh zrpOle_ID??O`LCo^51EPHU>ptP|#wT6u(r!f6vmjdXp7<(99fh8@bGPz+{XWL(iQy zJ2vIQR6)yX;M;L>+*83xOS26dik+1=HTlgSQ$vqq7p^7u^tJWe+tY`%1QGqYU_E(I zdclvVMCERX%g;V9k(Y@>s_ZG@eWv1l>n&i@1eg#&Y1{!&6*%+DX5P^gJ~NyHBgorn z*!}&{LlziA09FrIQpmY$pqtv&1%3|(g9a?Ez{VICtyRtD6;1)f7Upx^e1F_`J?G1 z=JeiI*H*A}1r#ZDC~1$K#5C+`!1q>0y%YwJW#7BGhuDJys=5V(x6RmfEOQjO2SO5h z-44&eZZgoMMM<0aoMx=XjeSUq8n}&pxL<|CJHYx_%vQzKm+`WH5f3K_knByM0%|Nic?2B*}?}Xv>ZXt zb#@-3DcG~}=aB($Q`+`y*qT3wKj=(ouadRqYg3y6sH*FnwouteRM64${O814P0 z$Rwu09_Fn3q)-es2r@KSN3_$ocpjl#tN=FH#~~8O^iw|s&DaDd)jo=DK?*L4-LLaU zy=fivv>f5vH#tcNZh{y8o9&)Z{DLVtqjoQnottENM#^aEOY+!(Ek^;|o=dfQ`%K}M z#wkNS60=FLFbZwXmHh1HyCBfw-9H5f4WJ!+Ce(Q14cT6xA!XNe7%pkNiRl?8{PkR@Yr!}9lPy#^HrJS5W7Ic8YKhZv2pjS6Gp<<^ib_`dK<8TRE?R~dWG-Uo0iSY z;oof-LiFaFreGgH-;Y)@*S@eDdmXa@NVh)}-_pRy=;VC)9UdOOY;jQC!djizPbZ9tcyZjGn~eIzWt>aT$u_N;R?n1aiB%X?X}EdsNQ!y?u*>32h;{ zVhGK5`QXfJTlh)J zQzyWO9xF2Mk(y>O;CKWxL7*BzxHK{{I%^#{tq2g*E*;o*TsLtDwDMbmAr{DBz(WdV zcxj1}Gq71PnX#f78T`wmo(XJ%eL)mH@d<}096I84+(*{taTZZN!nTr$Y0r}~g7x>4 z(=(-M@GSjYU7fb$4URr#K)Mcn+Y43-z1m=i$ISLR!SeL<{Fa@43U;R;fr%Ydv+3z+ zf{D>>N6-rat_I9{k7`Rm>Z}uQ2*Umxg`=P5n~>Xm{K!QUd-ZqyN&cj4R9`R(;H~~| z+4<$~vzPdUZ;z!JbX&w$Au0QLR;@(Zht=@}1@VU)^;ev)^@J6Y3({x;^ zm;w(SJi*7J@Rqhb%_@S}my}ec;G2p*SoTUjL4#O@OF9i_Bg}V_2S(9Zm$?9mz`EWnMvmB zUQs7N;v1n;X}B#W0np7ic#Ve>2N%DdqVrcpe)uK1>AQe(+TCTRG5aqN@lf5wh$Z%aPJUsW{1YUiI(AoVU6xiO1_SWv0<|1bjst|K3pN^RCx59xGy6EPSLkz`cm)}nv}@y^ zpkRH4p(yr|3FxLNhUh{mxr2PqPiVOto-die4bYzQVkpfy*kKGfI0);^OFTr4B)Ld0 zdJqa^i~%A1x6DlBzkrV=_|*YwyBaZcq&q70a)lN|Ce#(2KVUwurPYN#2jbm#a>$ABr^9aUfG(pfGxmD@IN za?w$gC_HXtXMXXg`JSNjA0UyG7)Ji#{qHx$>2|{Y*wg&@8fWFgY2uSF+U1OMb2^}P zG*F2v25P1|BYe5!!EHyV4%_%R0^Zq4HXGT(Br9FT_TR|CP9rpa$b69OM3O-bG~g6? zA)`gFh32H<$NqW(VYx}xwG|9-p4jh3zSlGzo_QdVhlq(7=NPaiDnhQBd~crDFMOS} zlI4!aMIby5mEQ)ZK;kX=GnIR8djR4VQAoe+ilLOxO0)maK`0XEeeSz!ty*V5w+H6Tr z0g6>t=6968M_KADzvb#-ggLl#iq_cJB;euGYYN}mzgC~exwrrW zf?WGFubv6h>ctP~C#$~jV5c1)myG%8EZsCslJ-5K8-Py$a_`lUvlm8|cNej#+4;G$ zxKm|h$(_wb8LPL*rXAB`C$d|m-Q!{iMtIr6>E@~d(6uB$JF-XEOc;zxHSO)d-oFW0 zrY850bYZvmsR*i$Og>k7k(0N}7-x;VHZdb=Nng*?Oeb)bf{~fPZ&A=!i=Q=&`lI1o zxRe=kiN$LisK)aFKrPVGfa>5Gz?oBO&P@u)8`Dq6Ui}QY|8bBgfPU(ArZT)-d+)48 z@ufy`B;&=HC(wjM(0>IvsE0NUxA_@8L@2$#F;H_`Ti=)-lb7Y8XMbja*3Y44zvn2l z)-SpBqN^OqP2dAPz{31m$BZOg4In#xUU(fU#mg^J5Var)X|i6zw3h$exxZjZCZXW{ z@3Bo=){(+XXk=ePpL(1y`kjbd!<#s|GU_|b^jmXL#GCsQhhK*m{jg6E!_}ckC$EyNzJ(c<{KQ8d(M^?fabtyH4Bwws~~5V+B2QW-ZN8 zL>;*FF2;BOLPfdwiEP(x4ZzxiO#R%UGzm$wbj~nJ#*8tr%(@Hsadvjnb)g}f{9xh) zFgXyk7*)TlYaqj+9$=)2%`Yn(B*mXaUtdunos}k8qi_ftw2w?)J${gLNFy0_bmrRL2$(eL#>p}+%&%;?{Ck~u@a;1f1D!%0fo&=ic*J~H-)iwh^br9W zk_k;i*r}{Wd;9jz4*F~QlYG#QiDVb6GSi{aRn4aa(z98m$LxNAlF`>+zxT~1U)An2!c=FT9L(Yj8uO z&?P|et%FV@SEg9#->bQ?!&uvL!#F}$Wg==^$e@c}rrb4gZBVIkF`6IXb z@MRV{HDE$n2LVik72mu6{`~2du7ZyE_pJ(RGfBXRUNnx6ZHv`Fg`t-;j`O!`T`HCJ z0cX4En!kKUbH38xOUBOH#g={%HPXNCa;PxASxHSX+=ll@Y7~dhP zSHOp9!1)W`iYEg+NxXc#;nMlYT)#{ZEJFbJ%ij}>C<=)_I+M^gcUHm|)6vp6*2W)0 zr4`jwEh`JDirn?LcMnG&&UFc?I%r@TYpbav#(Nck(q48x4)g;gMA^9uDxnU!E`Rph~! zl5}MlDUKFHOOZ*n_OBLs)}#Uh7AH^7p6wZu^rDClRZu{m>avqbGH^{LOVv+q0VE3- zT>?88CET1<)$BT83-twg;b0w7Hj0AjfYG`j@3~DlaU@Y}U)bRvb@r4nX+;A>?%V;; zIC3f_MkO(2Dsxkx$C2PmkvM&=VBPT4(iEb#8z8yELAhBxoBI`66mQ$QadRwWE+?*` z1=EsBB8f*Ux0XfryKlC9fy7VCQsZs6!Ut4nztUr@$t$QcR()?gHMJNs$Ai|wFT&n8 zH0m{cq#AG)Ut^3)#H85}$XkGD3gZVgo%Mj>+6dTALg5v)Yo3PXzFJaJ$&8v>T^GW3 zp244(-LoPOu9@q?!B!<=485tpLbL-8TuSk`g{W7J@;T;lPvTrZrU_6+s}ZNEmr4qz zq01rtkQLvCz(vY1(xLgbl<7tJ)`Eo7l1Uaqb7EQ+U{<{G^aPCbr_bep-=qSR5QlLG zBuNp_Xmln^wtvTqW^7J(#xB4TGp0motgnqRX7&0D&3`C4&+HAT25KcP_~u;nUgndhcF@!K){0quN5s%LxU4g>*zzbjA?15;wN3Wj4+GI{og2AzTS`a^m#aR zYp!BDPb?$Vl@ev{o7+Nh=)7&VZblch^X&6(?*iuBJ(t$6*l6nhcQvHUZ6tDd$OnC1 z{#$_uf_c{a!WB)u5^dGF2lTC4L-D?X3C&r+4LE5c?FOBN#Ne9rgpp>yLI&&pc~@0cxt}h(;a+tb;M%yhmS*hkye0!xYo>?=Q+(!Pde3ZY`<|=JN-k_ zBNgRe_~>8dr2rlzi+^$1Ibi)SKA=`S>MHUo01&V@(-%PFVbtmK>Zd0Pj`aY^m?hVW zd+yl-{!pUmtpFugcq*ZZ+{iVhZmm9h7ly=i-!Aso!z|n^dVl&z+Z9gEr@8m%LS&u| z-7eG~hPk8Bsf2YD3e7KZWiI{lupRsKd44l|qlySd*|psL&!!=+Cb6Lo>^;6-{#2ry zVxD$or)G~ab>=Pb9ib_a_R9LP(XrJjJY74X zyEe7D;FY>OUs`<8;np2NA-;!hK*#C@&vSkAvXF zbx)BuOKcNCcr@hG7vaKu5V2LSgBs-?M5W?b4>Sl@HF4`#((k|1)b|OWq%>(h#0G_mDw$sQJe+I#mNLqj zQm2l6`0v2w`p)MU^Gh~ID_a9*VpVgg-glRsQ6)~oc-0J6i-)ds)bZjcO26j2AF^iZ zt}i!yf2CBuyc^)y361u`QuUfZ8pAM52xG?fu%9^bINK5B)I@uOcvhi@$w!2eGO(@zJ;qHK}%WW9WP*Lm*H%{Z0&qifKYTs^;W`o-FW5w|Bkp1 zdTe&CsA;;kjr*X%O>Qs>y8<*WYf?l_KAax|3lAS3@FxHha`bc>8UKR^co1Mt2M7k+ zQjt3Qv&aE8t>EbBr=X`R2cnvGu~Jn?HX{5f8ByI^2O58lSeaHHn-ds{$c(Wynk~jq zs1>BUJf*rur##2xB&XxdThuB_Mx;*m3NDY$>sJQ_)7GBL+yd_%=M$_|ONx^B^dC@_ zW_+?P?vZiqy_>2tIuNlj%*pb0sQYw=b3+AFg9(sybCat8@)PopcU>)xPjyB2H9~CV zS5M>Ta!wegk@g66e_Y4L#<+}K;ZgdoZ?1niV66K0i^sPttI<*AY4s*8 z!^MLp@r_S-0>K~V>Eoas@4y*HDem|JP1bO`(*|)lEh#hAv$_zw>=D(5}PO~TE67c-VlQ}m&lN>*tUVPEDr>Pqx@AZ8H5>1 zB%5D9iO;u|HZ!lIz+HxrMo!blT;AU_jgsQ9S66|*!@QnUZ-hRRG-6_81c&lW@aD$T z&JL4t>&W-P6As}CNdCU4wBr=7B|sTF zM26kFiRHYE6ck->;33;#H5?@)&Lcn(8!m|&1|Y33H+L8Ry`}*4bA4J3di21vT#^&h zj-#a-ynR9ufwa$#1GJE9a=^0sM{qN>3 z4!YkW?(%^g{ZKmtI3E_h0#x<*GL*&dpAw%m~Y(#`}%D{;NqXdBVS9ub1JwOUh(EdXS6JOYZca?^owzO%>lr zbW&3OVLSoNLRnG0K_z+gOCYM}ldnZ!(9@7R~t^RbQC5H`d-q+<_;1) z+KyL!5LPgVtzN+fcoeYKaNelPQCDyB%OW@1k_%1`rAk-!JJ!+}v1&kx)wGhX4EQw; z|NL1)Kc>5g_B0u*w7#s0jN<2IL3&R*!kD#d_6F}BsDWVgpDhIDS9?yqf&U<|i|%`Y z&rjR0kZ>!_t!So1xt-H5nE%Ox6@poevvyU2R2g*|ec9%&gh zUOL6aw3Zw&4%+3<7qg9xKtmB7Hei-o)Me9PE<{5ZDJAv6mNnSqm+Vxajaq`a!Q7WY zeZwPU$X}ETze%gX_nbLPdm$G?fWZP(@49MS?_p9jbVM>=4Lq;_g5{5qXkErTUG^vV z{Vp)HYI6hr$tu5`75i8>3RJ|L)!o+5oqaBkDvR`rni`!7FWP~Nzl^Hpxt}f!Fa+qf zs+{xzCARc#Y3me?KEA{%3S;>1z<891NU3u~^q3O(YJkiAp8lwk8`{MwNMLC>j3HME z;M%V87&tt9+Ta27RFd=*#dAmWL#Drh#K{8w&CDX0^*`9t{!O*ZE1hzZtleOzy~W|X zM+r^c0V;N{DgB$f zrO%xfwYsXG|I>r^x-?`xQJU^O6~gU#Z{`#Trf2KauWS}T*+ZvRs@Z#G-4Mr^wn;Vs zG=l`OeSw43Q1Eg8k*+d93ugHboacv+?l`en11*Q+yb9{Z{G1XHqNuAIM}^J_3JrH zhX!)kP4JD7oFw-xpS=PvO=Y_wb|3wabAmsH`$;j8*azj}Y3IemAC00R zRTy9Tx=0u?Agq{vYP1{SsJ<6&zKF;a4hLa;JvC0nL~|kk06Nyvx&T%*Ld*!&l@6aX zN{TdKRaC3ghPSkczs5aTsL(y#s^2;lsQO$EO=csKi|q6~#=4rC?a^Oyi$ht+*lYnT zS;zIYZTf|ha}R_lnls}Od3>2BpLgK#>-r*R9^9R&&fl}l1(ElJh?{kUO6x;sKT%LC zE@0*?YjuOhAtuI8*V73i`|J%b5RUdY7d|@Eu=ObGbkH!o=*Qk+K%4@81oSqt5TYP< z8DG;AVM4(_PwE6)|N`j{T1MTxoj{2{jWyRMBEh6>#f1?G{v35OMw1EU- z68mIu4zJ0IVGAd#GI^Hyw#Xaew=f9Ikbx!=%_dB=v%B4R?FT(tf}f<&_)fp{d}jWeLScYJv&MDsl1B`b_=4THHOH3O*xai)L(Kmi!DUeKMG~O1Y5`wSh6kBw= z)N;CUtk@yBiOR)*#RTHhWRQQ{v}7RymLL}a>pqe8m##(oN_IWVSHeCOB(37er9iX_ zD9iVPX+Y$q%bo&)il8IdnlPfnMtc{+#wrrW1!^#OgITbA24E3RE-pZ2WdR3(4^x;_ zK7{D8=>oiJ;fxJerXqz(KXaKl@Z6b7hYf80rlq#`bn00)jNTsp@bK5qH1|jOT=s+= ztYl?*@{g--rCmZe>Z9w;fH2~__zRhSdC;QCT26f(MuGU=oWBA+ydzwkHHj%>3}{mK zTs;Bxw1+P<9}`Wgi&^bY+cPl6olLQxfgPafv3)2L4B=(~Hh2!q zZKqcT=4>CPWb5z~B9E$5Ihej>dcRdu1R_R2VrDKI$`^72NfAWO9CIXM&)qa7n)K1Y;}GBP3TC6a8R24Kzrdu0uyy#3?W zxw*E6Gz|m%wmHzT3)*Eco-tTbOHMXk5QH1}_Z+OE1%_iqwj_)EDL zs=uI&#?tzoKA#iL)cRY2xhnQ|B?DxZbTr4dTYlQk_|Gij(clLpFdM)YZq zF-SJN#|EK`%g_A={gsP2Vb242N-M(5T!qOrcxvlNIgHzZ+-mYuQ`*=EC@Bt@WI_>H zwe1bTkRdQV0c3GzKU38Q`Y~asKvfH4e~-3m&R~uaNDW(?6!KRv`wP&H-M^XEN>)$j zu9Uo{jJ2nhnMWHiHJ`Eu>oFHANr7e8>y_cOcv9);;>J6P>Hq$E>aJ#k7eg_5@9>Z- z4IAtqE0<$R+Ia64yJt>4FZJvnnaL}5z3KssJCSJV=MsF(q}X30q|D{=<_+v5r_=hy;R%C|4a$BW-wu+R$cR*|asW_^RW`XLZgI*#%!x2LB()r-Y!?AmKnl~x?7Gj*OQ2U8Y*f?C0 zTdr1ftK(Jwg;=KwfJHOLxHHBAzKG3V4w!P$BU^cUd5w;pJq5nIb$cajk9j`K;97na z+X({=EybRRqNyb}6u>D|9;0L3FyB`MVwy=mq%H^_eX&O@J5Lz}Ptdpe2kL`y_-!3LGg3h}|J`ZWC7*xIsUs)YcE6 zi2#^-pJ^A+8MIVsFcZ%&FCfd&C&_8Bq*(L58x3IyX%{IBxNHYPdhja|1#~RjeWu}= zhlY*|Let0OLfL&@<3N(Y9D-gY!*2XOUz3S6`sDr}v6NOVksJhpV@L#HvF~y+{43@iCl91u zsxyA`&%=hj5Cfi&7**mVKwi+N;bu$oe~@Dyq$?k+3s8(Jtg`9dzygco$z!G49{&1g zEU}i_0qI_J87shsfKbBf`{I0+3M4D14K4%C96%%Xf(%I|duu9L!1X8pI5&TeXvXQO z`Qqj%o+zGanSkhjd#d_Zb+W1$kt6NgB_(;BS8n z&r;($h#Wm>s?v;O|D#Med4ILO{(8WS^=8y7n~+9$-~;pu3Q0?$La9aG0G!gnO$SWJ2_xH=|E5&{PXyj++c$LKw={-)-9pN* zkj%Q*&Wh3hY24{lzJ1!#NO&8&uhJlLWoFx6qKL*TpKyDr+pDzi`6<=#^0b|6gZefH zP8K@=z%2S=_V*K>Syqyg^zjq=hg{PRcLFp<*ZA-HZvVOkNfpx)VEB&5?qayAsRaJ~ zUs~ZP<>+RL7A?x;%xvF$D&o=EL^c(!x!2wnUGI?S~)vD2eD(1}~ z8CF7U0{;aFB(Uelt!y)x1AbnRS0|PL>KfA>~inm+--8`}Ll!B2yi*^{H zkC(LvC)w`Rx6D`MDnYMwf#fk`3;?9z(q?U5XGB2M+T4~icc4yAHovgAQI8PWgc3c5 zjR0SJLM`|2!$?HN$hIo6o}cB?8~(nF1ly1rjLG+CU0L4G$A z*m2Uv$RLR zL0m02ICD4n@hmMZM|WR?0S$cO(a{4X{p+25*Z$~Y1+$g2;KqeNXQF!Ymg@1v$+iL* zzwbI3S`2XbL!w zruUo&&AEZmysovC&A?ZiZKulxSWAEi`_Y{U{(tOXdXOqNWG>z*`d%mvaE`hQykI{D z*he4X)iG)hGZWOCI*2rQJxxqeTI>GJE=QXCsm8Y(qwG&jY;_tGXbqJD$>W zDg*?lwI8{)(WNxxn1ZjFfs%!l6y?S#+QLn&bM6@-PZqc^roIoVTNGrG)U>plE$n1u zWWXSG0vDPM>8rOyl+00qjtT;lt8}#APOUU6VnOCyd`bAnCEyGIK5C#$mL1Fu{tTE} z+O44eO$SXSzbv>HO%Dt-gMKw=ip5j6`=z9abcLjWR*fb$RNGgykUm_JzRmp@MK75GowuOS6l*AyPpp5(w3ZG$m+uLt|qt%zLHbe%Ec;a{sGlw{xjrUKu9s76Jh9`{Yz@-Ibe>0|H>}I*Ftf2GX zVwN#05p$Xy)*p-rID-Fc>82D;QdEZ$*Ftf?5CekQ;(^9K?BO9S8L<6`?f@o>IO6{%FE7j$CuzxX9>g{~N z>d&83d(Nm6A25jqZ7e_{XfGFrz)YGVI)qc{HMPdG@E}#lNZiOS=-EHO4M18I1ui-y z0n63R^$W;22^L2lZ~&MYP|$E?jHM!WO?Es4>B{e!-z;G0k-q=4axc>EBdUq{`QyiR zID7fbV+_SX3xK#-leiZuko1k)Js64Gk5tGp-~(_2cKg7vkX;5KT#Cs z`vV4fk%wC+#n+&?VF2uRz8uWtK$S>6fHlwwfDBe9WI*Ku*aO1DNaTP#pKfYo02-Y< zH9``<8fDVibO$_qyx?HRR$vnq0rz4Rn5AkR^>!lBLQH_wX_6<}tHWeipd(C@52*O6$kcPM0z`Gd$OcR_dwUoj?KIl`rk{OdcLxx_dp6?; ztk4|IZEZmN5_;hXBq2oML6gYc>Z>?n$Wm&ug|oZUkDJxN0>Yq68XyNP)fDtnhEZ-q zQ}O5Kegmn{YsSPO2zY@&0vKo_0LPDls-@)!hk}>AyQsrMfv=`$mgjk^Ixk%4>XZR)SbOX0&Q1+fMhbvoxZDlu3Es$HO#_7SF!jqtA>U4-%SZ&peB;@ zr?10w3I?kyLFTlE(}TLCePI0fu0RyS294H|dO;akS6@HkCB!KB3p~1HMxr4m@AdRZ z0ZkB`41r0Q&)(35i5R5-x#PIaOC$uLX)Devyu#vvJf%G+e8q*+mDCs)*wdz z(F$17Tw4^i@+i=%(JO2i;iQANner zA&PRrAa$aI@3om_B1Og1Z$6wOqLoSXnIrWLlHv8p9G|^miu~l!`+x20R|3sE$z$)>&>!OnbGmHo|!yCH$341=NA^hF0&LmOvmjQ zL@09o_KbDBHlzGE9^%#bX^7L^ho5unuh842nm&&}{I7Ecg>7d_Zmkbq8jJFOP7xwg z&lRq}9$4)Gp*D}p-3e+zH;%F?%=3LDQRlBvMun5Ur;u01^nW`hx3{$*RPL*K+x_)H z1+yKKgH*rg2x z^gyl#YLS}0TDdmx5rHrak7af(T7Sj};Kv7ku;S^ViUC6!xuY@S0WP54Mv%;@5pVCd za{7`;g0PrMuRC&7u@0l3%gZC}RDb~hZL3iyLiFLZ)Ba%gRRGoSG#oMx(Ti-7FOsQ@fvjK2bm&S|=}g1R zE%ywx^V0Gb7E9H42RP}2c;Ne&(`wi#~Hqp5V1Rr@^FMB~PCM@F> zL&+(zH-ndd@?lSIWGD?k9Hx9 zlvr3@TidrIMlZc%PFJH)y$8=a3w~-KD^==Tm63Ejs+2G621H%v9bS)nDis4z&jI5! zICw8mY5rk=scQesgC=2qn?+$l->Px{-_6ax7VokKN}NNqypo~oYu+CJK5|_vzHoZW z!P$kQi9Oev((UeGoX6FMtGDNTw_7ho*OREK{~mST7_u9~<#kKrn6LtkKroFA(ZKig zvEO?5H4FOrvtjegOH47IIk3ZEv=+mMD*kd_GN12a?JGIz;lD1f1ztSY7T2%TK4(AU zM$9AAkv~%{m#V0MGSGuF9{8Q>kF`MX!_F7RX_$qrS>(H>&&T~#pa1TcSO3*ny<@8~ zfCrG6eD=+*%zQPG?ol}|z7u^YG-mh7eeE<6-9I;}{lV05`6kmFz1=6d(|t>L@#x}o zqQ^A&Kf&!>J`^yenn7}A)A?PG?!u6Qq z&Ti)=TIbE!XZO7;GWWZ8s~Zh-M)|8pyLDFl)H`Z5x1L3)jl6tV(YcFu1TzP}UEToD zQKNe1k#JS~aX*gdP>tY}Q`Kh}rqBX8t#M2&%SHg3KXn`S++&h^yum@G?@j+-3jl7f z&cyXZBj{21R@?*mR=pBaj6A}@{>qa@osRS|uAAS70(G56pC>*wg|QNrx?Cl9syD92ds-O8hL zHt>zw+ksKo|MhrT>+LFt{cbmO^D=SpcPF1dbm89kFM#O#W4rr!WcZvgqrxT0e?3!wYIl+_3>jxAC3rra&7GYp z)pKV2)B$m0k>j%Bk|zRuxNIOsnlf4tq%9sgFM!alA{Hi0tHx#Os#mwicNbU3vG-|i zqPKpX*ImX=$8a_%2ej@#8;x?w0#kTrhjJlh?S#!U3W?91J)f!-Dwn$@Nm!Y35`ww4 zXQx(=CKi_S-%wA8G%4y<=SQ1#F6AyAnN0_Ms9fJkg#HItdR=XqUphyn=i@H1vw{)T z_R+f+sfl*h?7x!B8W>t$KRFl=E!=!#O%e!ZY`;?~i9ee-aGhUXec8y;ARXvhFIV!E zlDt=9mTxwEIw(iIxZNGkf)$lW<7tqXWk&lQUg=xLGD1{km0zW6bdn$cZ5GE%emy-`=V&nG`nc7~B^ul>pt%E1zRSUcL(@+5NIDp>WgKKt^iS@Gk7~+|ntF z|1R)i-bR6qZRxBJ?o|Fo6qDWgefe@xCZWRpKTwud(%D$ZcrAJ*pk@m?q}Gi z6B9z(E6X||6=fyL1eQXO=?9h`SQ;54_cwdXq(|U^=C@739T#y#NQX`)D zWND%kjY9~G0Dej&@3|I3r)It|>!_ywr~%{LPCpZ<>3xNaeElb3(&MlBBIv(QS-q`r z=`YvMk484rvudho=1!W0y;IshLubGL=EncmgH=kivW^-xM)fJKKh}iwGi_E_MkQ1< zZ`zZhGPBE1>Gal$p*|2UG`Mf4eZg3~JMsvM6bQ)L{4ZV6tYPJC8pz z`y)|#VIJ*SBu6V^m4-_ap|#XtM)G+OifLZPm-b{Tcw9t!Bw&LZ>qdTuMRu5)(NSBscHEns4lT&o{ zjfSH>;U-0ZP_sh1X9F&8vz*Tmxh1Py{pMNsE>peR%I6{1U|DY4!~Kod?eTzF-B104 zmF->Qwd;|&(-Io?lS!*r>lW(7Qb8uNiotwkU27HY9g6>p$xlK+e3z#`HbljpFVPUUeMJ*3q2hjRW^R&nYQLSf zTA5uG`9@#VDYmbwF1bYA#M%LCl5&zg6M_l4>Jn`RWsM0|h1i{);u7`k+bb<7sT#7C zMEZ~-Sz4YlV;O_IMV23{r%%pA&i5NAjD0CsBd>QFg~L|5h3D^q5czSyee=zo^FL*y zbCrF#B;M@a_Kw5K01_<afVnDtaPSA0?YKM1Z5u_8nXHqhO<|>u%A4fJcR$Z%jQM%uGHv)C5g4ueTm0 zO?U1ax@J-H6Ktxz_`VgG#h;#_22$r8hl3t5rFaqzVb_^ot$7WbLaA-E#&&XB$sk}= zE+7oVv4N(`pu;PCB!y#oR0t_E%2j~<>E`;i)`xcJ0wu0A_e>%V`@hY>2m^~3l$9k3J%}^w{3)`lyz8LKtB%R;a6NNz8*-yG7IS8cGI(A0G1MTpLUNKkyV`nCD z-0b;pORaedGG@`CWGIU2KXSFV#In(?Z}UvhJFp?lB}<7tqE_0LU^1*Ae~^pf#h){- zgy$O4vGnq5H=5g9hve3qx`q{)<}}8A0=!BZ8~jW$&jNC~#XbFP=c?4owd&+wscC}U zz|mr&Ig@tk;o@J>16?l?tks;Q{UTftxN1RSsn+s+&&?#E+r3&QS+A;&U(TKNaV5nD zcGt7`h(^@pa#Adme5cf4CCRrZH|r;s?Gu*ZT8y=gRp{Fm{wYL}`}fR4{7V6n8*13l z)8{`oWmTCK*OEp^MN_}el5bcz;(HNGc8nUP zH-pp>Kddlev)Ce%MH>HE3Lgx7l-lh_&4Tgu=LG(UF8_VidL$j;TM1)!L?{*#i%GLm zn7RLfmm9R%PqHk=k4|*)qv%+yFfgNLbRzN!;xu$xIkSR~<461^f;Z36sX(g;)OjLT zTZvCjx)RS;coTT7AH*zN+ii(DtRTt)!2V-M&i(q zm&IDUAwKL;H$xd&kn90U_C6~ahtX)ybCn|Hp`;diE8+wS35oMxecOw({bz8*z`+d# z&!2Mb-=~CXGVCLf19w;V?a%Q-!CT61&>Yt!phR@BVinxAoiet)FNr7o@#pE>BGpP% z2M49&rO3I_?ZuzvO>mT94E_WldZ9u}*rq$Q+A-emRZK8_t^QZqdl6w1)@PEbVdjp; zyK3kWb%RuRSP8;ZNur-WJHMX#hzcmGkRE=%m`>M2${GD6ub8pLKf7BS_4b6!%TH$d zw-x(8T$nQ+?Y1G3P!y$iz}7lBb-oLucE=>CocX3|2DX>e*rHvQ0{B}(_n+hMB_d6G7~OOND~S~#LEWyJK1cC zSTfZ{Vxyv)m*U*HH5+*QcPQv*F3ynCDYH<%x7go4)i|o86xyUL-Bk{1gE5oMHYqG{ zq~BGPyXLa8J_j!XA*+e-zNtl{C%5tba$t;^M-7ESP?fUH{)L;T06~>lYnQBQ7FSH zhAF}-#4PuRO_~15BWbjmDZ!W_n%QZ1o81ncr1*MJAR2Rk`tLp0^87RH=$60VLleqf zm3{nu6&~$p)ctmxp-Wa$5nO?uTD?ygYK|E7CqATjrjSTgQbi*ZPLftE95uYt05cY6 zI^(iRjUBNIH3lMDBru*{2Fvxkh!(+PiiMmtSBlA2e@BRSgt;7Es7N8^O)`JZA&nFY z;u|F&!{n_j`j<4Y@$uj$>M)l+uro$f<%jdEjV0xq61u^XLtvC~iX~e6LTp;GLqucn z0rN05G99s01`38`$eq*9d(z?&CiMXw4K+82IBYC*%xxN>QLkKmc={%CQs*Vga>;X( zWrE$D^f~|n2oM;cjX|}bc=F&Wsw+3=aWn=T@Qn2bg~qA}K)$dYP@5a@rv+M$pq|f21hcUv8N}7ARjZ|}>=20YLOhs4Or&A>pm)&m-ZKbxS%8+XMpD(`nn4QcgtWO_q*$fAug9+p$sx=P3(Q zN0PDMbi?wob)CdF?AwkX%P`KegGjti0+=xn;4OQOeVAWuUXll~P_hSDI}d%z`hFXG zLQs39&+Tvbt;*FcrL{maGu~KrJ?k#QCk9F<`Q8=N_`$_21$ipU*hVXeUFvNRioK_-Zi6Q2SNBr@66k=O`2^o?vDzIy+a7^N=C5p0z@R zkzSWVr=-qGwSt+wI~vYAJ*v{pkgl147iWAn)=Q;+$E)@i=^ zCMXqD#}Z}fgZp67i58NdFuAi7POdupDHUqD%ADy(OLLQ2fnCTaxD={uErzjvnf9SF zU1p_k9aUmYkWF%c%WP59C#-cbNd_Ar2A+a~^(jz|6`@kqM8&lV(H;GjZG^>6)hjVr z8f@yGtAnYTPhtDeZ{ee={xX0He=Pgf7uv)gXaf81Q1sC)9H|S|P5a*4q7C{YqVzx>SQ-d}hd0|;FT1p7tbmPL3=?M8znV#X-40nZkL+QMt$7oL}EQiur zVc5TB=h=UFo>O)_+Gb=W-xql|lj@TO_ma7k@Tb^K{vbXi(8V==b&hE#@*N+2m3g}x ze`Q4s(WyS}PI&SbHNJq~Ep#UG50Uw~$&AjecIESS8q}q_UE`$j!ifHR_jk>5g}UvM ziZDX^$5aw>(rIJ8$(IDq#?vQbQygsUFCI?bhY~f>NO7fc&C#FIjVW0|+d~W=DP2^l z85%`uunp{gq4hS?7NSEHTfYX3TtV>u7A{f#Fk?UZ_0{FE$-md4SNG$J77w6XE?CuSVuygN8Z(I)Tl`(Xsjd zCAR5CoIiZRc|_9V*fCg=L|kz=5sNntk^VT633(XBMtX&JkxUfM*b?g7mJ7g4f;G&z za%%^FaKueRLeh{z#SDe#56(BxF+fgePwVdK(N`6V>8sj6Vj)S8`D-f2dc4Ejw@q+KMUU*ZS#RHgpy?<;49dX#p#V2Fnhmr;HAK3oS(G?AZ&%w*1O-vGqI*e0SV8@23N=FG{~8={D13g!!P$ z&SSJ%AM>3b+VM8k@QzPuY?spBeWA6U!H-=35w@km)@eH}*4y6wMahSsgkZdR&@?Qm zRuY=QqvXjtMz=47e-d;X490fSbU#VqKLt@uRrGng6iPiEvUZ#dILu;fUjlLXbgGy= zY={>*4yWilejipwt_^N;g#3Nx^L?C9b#)W;z+flPZZnF-si!?gL3M+jz})&(Tok5)XWVm7r$h&1WgE^XAmzD#CiAn;9j_@7QSgcyOaA)F@@ppe&LdjKt2qVIg&ImSO@Jq(XSTdR^5| zlA|8LVSo;K740AaH;5iylJm1FazC&*8)GlKxoS0eR$n9>&n^ZtfC&Ceg23jF@kcXY zLI|YehE$&pJ53vtnhj9`!?J=D83L8q5HM3a8HT_Ly}pu4!CWtXzJ zZI_q!&(DxY57cCXK5)9C-LFICxYK(ryP-sv0ar@cifZNWq#l^Og4Ac3I16GWM4re( zK07k*z)e-*=w`JVO5sq*do!EV7pL{3JbGs_>Q2N`G=Hlh5-#Uy)!v*V<$kJMp=j@s zvWTl)tF-8#$Td^ZU#du7HAxc@Hg3k^dy2TQQRFRIa#&lE(3w{bpY;k!C%*H{MeFSW zyQK5(R1(5KQ?fsTBG2dEoH330qCP$N&ve)WWE%_3C-)54d8L)4C^HV}6+;u0uIj0t zlKrmR6-Jhpink&X97(s@ zX}(D7^D1TK4mz<`D};Hf3o~~gbqU1}bUPR zsK%g+WF=pUz>UHVc_g6S#OIspk6f1@f3EtbDH=)P&B+{BBZc-8+Z-dgLEBtbTs$wm zrr|uXfdL;aL?hH1qi8&YScdue_G>A=A+h>lMZ}DFyi)Oq*0+Dn@1L+8`M893wPiUJ zUHeJhZ9TF^K(YtGG4=R_roGw#k536BYVT-kC&XK=$VCzPH2$`cbJJ?6RI2Mpe05cb zXx=q&R&WSkAUD>J!D+eR4fHZ^CkF3<8NpR6I<|T1@b|;@@o3xK6rmhmV3B)jLY|H| zF>rovMHenfSG@yAp!iE-d(wrgajGTS0^mr@=e$z|@Z*MU`Z z>TaX#AJgh)%bTH7k5IWVEdTgt+;?BFr_nm}h;8xcD6RaJ#S>aw7{bOw z(`;V3?c*e=y~F*(C!^rYDzDOn7PZ}v2`48V} z%|Q2kp1@-wtuSAIH!~4%@+O3Yj`e|VLXUO|wlB_C6oXDv;8w!Ba_1T+2~+PRY>80S z#wrZ_WDXg{Rq`vtE6iB;Q8=xgM%`i*%YP3vSb>HPTRisf;!RTWiG4^k{^e}Ug(@-<7+FW4 zhw|AJxPVa?7(4uZFf6a z)iLkW=)B8vSw1eEnDcmz(Hn2+$Y{j6`hJzjwX>oEp=&Sk%Q?zzbXcBH7^6T-S2mU# zy7SC3th9xMAa?za!1_rE>9WEy4S9TB5+c^hT^%nOcb*!PL3`6LWxG!8K3&t}>Y`DJ6+9$5|6tFZ0|6DTTjqL&@fv+3IV zT-obQajx^t9UX~jQ@M#n#hpF5*T)IvZye(n;%|_bR^ew7d#)(?Z`rxZS<}^%uI7-D+wH;5%GY2 z(o3{bamtGyM5HY!Y!a1&@A<6bFYh+cFd@Ur-1v}^`Qnh}BHTZF*T}YsNv+V~^*hZv zoFm34AX&!i3!2BOT}zdWTo~!!{D+1-WrM+skHP@iquGPUP$HB*ZaWG?W&?l#KkZ28 zz`!MJS}7Beu3jQSNbXa*4J}1rGqx?$aC&?H#!O<^UGs(2T8?)?j%0M_q6(#C zl-G0;eKv|yI&pPv)Cox^@eKM)$lvo9`|S0M&ULKHT@y{#I|aW(9!PMAU~K5-}}sGvu#?olpH*~V%nm{yM}{t5UZ%FlJ$MW$_>ii zn!LvE8P?~>cj1j9+uW9^BGR0XF0)}=<)ODEKR9y`4!o+y?B1mPANj}dAUom9#`IeM zVVSLn9-fZ(JJXiE;kS}JGsYR0DdSfoVeAul5Wkz^k8~mC<5bcST2Nak>d4h;*w+!1 zsZxQ1)uiZpV!nz$BYvNR$R+Bp$CN;&dHlzC)>OxRj4zIQ8RqQAyKPtQ1|&sCef8f2 ze^$HWl7tRflN%CX;?tXwD-AEBEJ&|E&#Bmi-ZV*@+IiWuM;~-WS;}1s#_(J?d4Mm$ z<4ruUB)N6rr_^<{DP?Wk`!c(yvIJ$c5K+_aYt*PY2q`+8zr#OeaOd<4jLq$0j!Pyu zm<`DUS|iJ~$RhfHq@hhpiT5(F{DbdyiG5su98nUPrI6v0#dJ?@Y?X0UtT5}Bky0$m zuqrD6F2d%HugqJbd0RYW({H{xh3D643y4B!WU{LL2-3%Jys@srRzt5%2z}rURW_8; zw1pL$x*lCEKwyK%TIdWtOx!w16`s_px_+5vJw3L3@6(Bx69vClD!Ebgn9R}I5%EtJ zuqe-#z~T-P)l5cT+51puO7`rOY9*m~fy$th_v3SS`KKIfgJ6}0G!uP#iii}osA&1^ zI0;@CA%gUW?7ZSuFSaHNxBDjB9Mze_%v;h3ez)dl?yI(3LFt{1HnO>&7!hkwt0Y^PaYcwUna?@8{6r<#_=4CGCi z+ALB8kSN`abEniIM=eu@r9(t!Z_d{bLPQJKiXYE=PGmXxTG$fvxeMF{E;OO zrdWochZE1d!u>B6;2<4rvAn#pQoeG^9IV6~L2^hYV_dJ+^Zc*A1DEjsCy-IcRAALqwYmGX=KPi`A7b;~+NweVqQV}Sfvj5EM>7z<7$m6&Qlr#!3`A@`@IFkS|KdD&Ni ztFEeq!XmwqG!Oi)Btk{qk4e*6HpBPQt?sad_7V0`UVCxr6B592?kD@)CC}oh10y{I zV&`pB)qBOe4*Zyw1h&6>NLeOyC2zuZge_l4(74oSuh~WTvZp-z_trK@h{8t4H6zuE zmL{3~-x>#l_GJ?xUf|LjWpi`Wo6$48s_Hm1utR&>ELC8S2a86^;*^2lTQcdOKE9om z6?dQxoBZSysWACR1fDB}mlMf?LRmRuZOuHCs7xZltCKtpl6JdK3ZkKZPKq#ySgyivzYyb0Gb}%a{ibY`KnoFLXQOXESSVEmZ!i7)b6R)2qQH99kQnjB zW6`pExCC5d$v))M4NvfyX8$=q@coYG*^E!Vw9DO z#K!$vV#NcR&E%}!0lfHkq+2km;ri=5aF<9vnym&6~1Zv05p;HlK#(9+!4zf{( z+ti`X+1eyl)bVg|=wf+o1vtjX4;$TL^A)OUR95MA4!i7h$X*<~*W0c@=3vPK&qW{~q`u7>t;EDgKVVKf`pIbfcMjb?&KL2PyhyTb^*zOfh5I**Gp z6m#W}4IE?4wO5y|2I3GX0|tJe7<*mi@w-P<`L?E4Ju&<(=N zvqM@vCx9uZUP6Nx$7BTzE!skmFqMA$#&}n)mHM*2bjHYJl_;9GZGdtg&~XlFy+@;l zN+()W$5ss1{^v0)CBDF@U|t3?;!B30{m@nJH)jLbPMzfWPnYKT0kQ|d=4KRmxeEf6Tvrd+C}aV{a&SObq!G5Ct+);hAU93IB97%7Cx z#AV&(k(1)!3#;Rsi*o7qBK+~7@Avp3^yIFJj*WXttr-?xVWbfr9{`Z4I$Azv?(E$* zDbP}aZ17}kd&=nQ@&22xp}W3mp(DwA1Zsnyb@Vne2Ggg)eu1t~_(la&E$ z=IEZa4rghjxxh>KM9NE~k~%e}hSphlPuHKFwDGp}b4d`nZ(S)Z^k5LqzwWl}BPe_t%A1b@&e-=wb zNQaL!eL=~@s%u7AgybtQXP1wtFal!1$bGl*7VijxklkUM&CH!+)YCKl(_H&21;^6? z_jZP4>m<$ai-&*jxN-&59-9~<*(Z2ZNQn|SI&8T_uHTne=sv0?1~EE7?L*+5=cydQ zJzuNLA%-g-sfaOD^0>3Jc@HvhNFB03r?HAzdUGS#Uf4o}PxTW$t&K%?NaXIorgce< zn7m^_#CcQ9C95467UF*ttpDHam`uB;B@X-pdBa1FIwHf(xgLt`vZ`29Mjg>dPR5Jp z<$38AncqyV%!jC3K8G>vw~Sz&8UOQhvf|p>wwZ$iNj37tBjm-hiIg9}%`g{L<0ZCB z1|54t0J*1^(5YMnA)4#u-IHwrm<0+CSmvT|mF_-?FedTy0`5$m;>@O#k~Y`v{J9>Y zd74uhRc(}|h%BRp#>M1%iqAP#g9e-VJWW1`4`7Vpjb*MzmrW_Mtmij6?cY(w4Nteh zmo8_5-Gy47I>NtLH>Fx}pA}gN1K8NK8n`+snf!WLxfQb*7*zH}N#n$tX-XdJ{(BvW zPD&pV3!K+x4Y0RnljH%OM@2@Qg0Xmrha9sX32T4ZX4)U6jNG?Cl!PJaaYg`xx6o? zRU8fwDJlM?tnutxIkQ1>as7rRe&CgbgPj*PB}aLKuzDfChe-iY%cgG@2`|L9(M+vq z%0&G(GKgM8ImWYDNUtP?lXmR*8ZMRw3P<%$n1Xk5j$s^tMVkR&HIVDRj5a@S@WbMt){W9PTr>ROyEbQ zE16F%ezoPh{Re8HWceh4W_h$s3z%SC#nZqF2N~^lbkZKku4I%Kw7SAei~yXPr8c81 ze^Q^G)&K*($Q0FD+}xjEYW-wQtrN5iy&@QFZNYh=A3N#^?or~cthY2|iaB(0(q=sM zR4lWY(nMt)ZEf3|I|Y-0M{MQm6?=pGe3qu|6xj9q%Fhw8AAhF%9$_j(a*!GqdYG1U z>Jn(a-MyBs)|d;3u>4}Vb@w-6@STwf|G(8XdvN>7va_F$%?%v!g;NFX6B8A+b50LcB zDQ)>ItUC5EQpv1Ij%5u16&)Q~Go-lO(VfK4-7+l-N6Yha6HEPot;HpFFF$Uc75Lx? zpg}HF*5(N8Q)Nw+!lE}O`JHb?Iv6WFovf=Um=y8L`3uv3FFf$%k1?HcLxOSoWqHJh=jkpZ(V>#5Ib_6WHNb-I|0ao6Zorkhz0z-^KLZGLs zYi^fy9d2$$u5JcMJ_Pgp{la$MKit8P`qZ>k&zq1l=8&-YShFcwKpwl+VwXD)!s~HA zfo;c@?`7@I3D{E)EXLe4zj($uU7Krp@#eW6g$M;mprl*=`7w=P(B)O^?(7tds8WOy zTB$xR{1qBN0Z0fpw{(ch`?yWZ?sd+%JJD?O*@Fbw&QtcSV+J|DJrG9OD=nU7N5j;M z)vg@;GyJ=}a{6;igh?I-Y}dV0Cqn<)N<%i zC}|dJa?QXoU@Nu;q}hkoha{TghGA?z9^F5#p2nWuJR0gka{*Mo%ue& za9B3^|2zAA>mj{c5DT8r%%)f9$q2giF4{SU&tTz;Ql9Yn9mVduR?EvC9khgdRtyf(RY$U?5ni`^?#r#)5&>wFv*Snq-t{ zM86TMRkCw#d;I?G@o=$~2@$!;DuCSHPUrF*x{KPb@Gn*PG=_WY?7cD^evs;Vib7;6 zR7^>sY9^-w6(MO$&@3#v^kJ+*74*!eCHmdA$4kTiR6mxmmhOHeh*6A1juV~+i;z;p z*-2*CeW(*fb^RE|(RV%#3n{F_xNdGOo=;oC*GVKGTssahCX`ZEzG!au?bH*@p_sA= zLd01vTPBAx<~d(DgC3MkL<_fdqrs`$JdrFFd= z>vp|QZv>|xOvuTtQkDSA9sTTLdY>O#d0V}{m?8}rM=RuL*-};I$K26lgG*^Dg{?T% z%wM=*L@k{(DGE~#bt+H9mS6~)=%+#~_tk@}uASuFxPz{r7PG#K;0}v#dxHc&t}jX2z@YLjpLag6 zeWqA|+3!nPs6bM%yk39^;mEoBEACb)1|n;GB(-cP(gmuWX$1t7aWEHziKsK%+nBcl zK!7^?LGaKT<*0F6_*ePPpxT`Dzf5_6$e-x zgZ(?;YisN3#bZ5sA?2V9G!;G-LQEsvTmW{IhR}I7hK$fxjci&sH`s4i#jaiu503Ce z%s~}Jlp>#D#>OF-0x80vi}LX`;G)5R^>XxY*s)UpX5An1xkm>g2*ODt)Q7s2C5QarG&=D_inP_Ai4|VefK7Y~{eSfB7||{k$u- zfr$%^h5VjlC-n0B^S0;7ie86T#vRUz5w3`~IG(u3c*qb8;*uOAr_EweKn0h&L^z{5 z)I6oRw|Cmqg?>j685l7LHY>{0Eda*M0^*Jym|%p39KA!XYtEilUbe1wj&gRoCR|o> zEzQA_lCN1l&qGA#SD&#p(>$pVbZj`=UxzG__+A4F*KFntw2SA;5(mXwTDidZd}G`Z z+Uj!kGe+j>S*zx9Ni=J=;>O;Q=}V!`SN-HKWnB1G25p~!MaiOB;lDU$=}lHi=CAA; zx|=202vsZ9!K$U%x;mm^qCaYhQQY-6v*{XqgXXOG^IMyzX|8&Pu7scCuRu$!qWU7X zA>l{UIZDq*U;SbsHD_`T`a?J$-Q2;B6<{F$2)%e?_vq~{dK4nrvK1U>c>^WoJ;v&0 zo07W&;>He56D#6UfQ5HLNs5Lms(B==w}542BBOT~?JLMJ+oGbNahvXj$UDo?>qJj9DIL^EbB#pv0jmWb;C~8T&;S!(JCJGy-6SXC#uk zEsIDFsityh^vXZT`3oAZ-l4%T5KQ?}`4o_t!+hj88C~mW9rSkwbtbZnf2Cf=2(wWq zdk84(Q6fhZ0)FUqdbu`)Z;)@}8}Xo6dw z26B&ajBIv=Cg4;u@XLbBZ7mKFu|s%QersZpUrGq(4w-?@OQI{MODc3Fyp! zFYn{Qvg`fQLFIx=Yo_{o2ebhi>fUG#PYPb{hpYv?7+%NJ`o~Ofb2)U~e0{sO6c$e= zZx(BA|CP7(#KUBN(L3F0;eIH7PC>Qm%1$sl#>wYBE`~**! zA@}Pf&u`k>0hIV}ROG>9WbPS4z-@5s02W!Rd5r5k^4i%8zXpLYDyX0GheqK?~f9IhW~LHs>;Il|JA zK{df;k)qIb&8-8VmpD)k3ix~5!)Y8%M?RIqDJO=9u>P;^dR~{Fzz2LTVhhiJlkiv| z>6Q}WDbISIC9*ka<_Dc78x`BL=LrXY+4&o~61CaB3;q{x@mQo2-Wft*;h^b2*R8)B zW{zr?@J76vnXXa;A6=Mf1o{k2pt>}zD>go!7^$XMAeHDUGSj^Bd2y(O^tl99$4@ac zdekMd-(*P6GkR&>^pXrt+da{vdMGMpx$Ov15E>&;i0LeWO$q=+1`VhK0p}kH1k#U1 zdY5|DjnQr7w05)WyDr`k?ak4JxWL-FZ&O{+$$@{EH&H4GJ+k-J6?}+87Pd#h8`A%@ z9>j!}mVP+3V`|eNwi!Em>z2HG_XPpR~6Mqy@=%#Q4O)7(4^&79cL??-{$ zxJ?q;>iCVFjeS>spf4(>3F=EaLQjNRY4pMGf-w9~Yx*EayhmkgKs>ObfVyFJXM0Zz z^r&XL*jFfmgnDR!zYI@4~M`GqSSQ%=!|PA}Ul7 zdrACxjwj2~u8;07>nlCO>o0dzIfesJ79X=Re%5hfQA3ozfql%c1cukcai9oyp*IQ@ z%!Hq*hVQ31Rkb@K>HkPv;B4!0a?#2nbu<5P_RTHS$IU;hJMTT)_G|CxhoeXpBT&bL zpmF64JdWEy8oGUZNNej@H3Ln|wB3!_`MsYRk{O4r*l+%#wlPc8VU7dmwsDo7U8-FD z$-WUqfAL7P>n{wQ+2V2nbF{FQ;Q6k$v5}GpQ+A7`37$p!U{W;Ooh>R6TqZD!t zgb7-xY>h|>TUX4)MRC4@I-;RP2G)n41z7L}k$C7uGEN-T(^c2m!Zpwm)>UlU(1C8e zj@3r$fbK%;rF=VMrf0-X#*o^3>G*bQAA+a*V+Rn$ z8ryXypDdu;^t!;7=RQ7XTn@cz=6Bm8J~uBX5>hUno*^zv_|>GlDL97ty{r3=rS8vL zBz_a%gz9uPp)t+W46ojQYm(Iao<)Kxf#%TriUxZ1f2jrk61LXY?1O4<|DjlfyjD%c7{(eC5?<0#fUONfX@%Z!-U1gYP}hJiQ6BB1@nWGJF=S+|DGt<-WFj;= zP*Csqp&}Sh)=rm4598n_T&{s+B4@)1&~m=@*nD$ft8)JLVE--O7eY-W4ohSKU|yns zuQ;Y8r4u9%`U-B)G9UYBR-nMhITG6nU!k@Hn5E4VTfYoe3JWi!eOlMZrJPEQAjcbv zf|eCAi4H9plFao!g7J5|>jZOhfL*_iS_+JxSOCAMajBrfqtJumsadz|!(w7yH+Qxz z8aIv})7*7-&QNK@o96N{%bT?m7)dUTz0}=%r$?28aA5|5H(Iai>bLgdu6iS4TD9%1 z!6$Haec|BqSys*OA&L9>LCL@W>N8f(uBmU7D+4dFcr>GTU%BRz%_>|_m^GBv; zuNYCn#^&a+cW?K#t|#cRVJ^_KKZyGgL!o!Y+{rq@t2&gXC&?_FD{{raJLTgMr|Tuk z@D}uTAbflJK+yGfJ#W_I0jnQiKAo_yAgtCD2tZY?R@VmV9Uf0PsOoo0lyRV!zR_1) z?^W|_+peu|?Ok?zS2@_-PG9*ANLl{+Yach&4Ivk0S7?J(!dZ?5Ryq11ig(e~^;rQ- z-0bQajrwYEurMQhQtj?HG5t3U$(!h>@_ESKv&SRm(a*=5!gCP#pakr$7uE!fQ%i9i zn=I|EVb%V{5zUB>p?~hfV;b!ZCAsogJO}v2NFD@+F7qL9A%-qJQ2a5+FxQIm(MKS}Mtx8y=$h1>a zaXkMh**m@rofZEK3WD=G(gS;^rgoS4VmZm`UMHUt|LO7 zH+En;J6+Jvw+O3G#_mj=T`WB313ju2~F z*8UYK7tqi&n-4CjxO*Ov%b3U$=gU?+K3;5#5vq#e=u&78=Z84^d%<(;M@ZeL<(Icd znyQ^%rOK`2{UrwVN=}LM=+{XS7{H5VHlL|diS_c?W}8#c(1~Gj1+p89*+JvX^ZvxE zRgp}x7<8srV_!2)?#UUq!@LqQD_ON>&eDpGC4m6Qnvmk z;FDZ&uyVV=bfE=C$A4ew!G!==nOAn!P3_m4$LSY^K=$p51&t`%NKrXt4 zwVu)HuYga%lb*9n9-vu5y0F zNZ)mw(Hn*9`*X%#zu(UtH6`eBz+>U=jssOlD`x9!G?iwUC+QaH`#Ak&_@Jf_auZXeh; ziNbN{>OZngd%g&}QZ0ubv<8@jsOx2-GcflnWWp_XwDEzZ07{OqTpRmOQ!0Jl&-?*R z9>i3sHk^gP^6Ry31xQ)rRjLd3@IaTY>o-KkCEc#4jh(w%5>UF*&by%h<6m&!Dy&qk z>27-sf9dtc3J2g1no=jlRw#s&S3h|Rk<)8)i|K%u?eI-a(}Ej7Kqy-`^Qw zQ2s9#z-rryB?$U>$*On2r>r~l*Fvh~KuUT3rrilGNW>l(^$2xiSkSo>#r4Z-ff2}lq z;S=!d8W?C+xD?pjom*x;`b&ERB>HnaYmAF5M~Fu&9*Ts=W;Pm6_P-zYvVs^m%j^Se zzB|c5&hP}6QNCqCh(Q4nGR5{_k?k+5Rd#wt&gTgjnd5HO4ZzxczKeMJP$jGHl?TnWQahi?f)qc$3-;OQ3ak8F?9>OR_lHFYX!*@GnV_|1;j{%W z5C3R=Dl6O99PQ81Z+eABg4xq&E`$63tPDP z!P`k-3e&pKjQ@Y3_1_rlB6Nhu{7I0{FH|#qptGVSW?Cq33CYA*5cS!3`Z~W+!TcQ? zG0uTqUub}!_G?4)S4RgokG8cEyuZQppRCXGRE)l9^U@(vt*~&Zo=hPk`dmxJj!M`0P^rt_IPl;SJkEgBUg4IP z%=xwZGn)zb{{;VazZ3rSZ#eR6sspE2QdFMUpffLznzUeTH^PVmzSK!9!3HI`AM&23 zKLuT2BlO55ZZ~+c8&vV>szvivxh89q8@?_&BO(7*PO4Sc(dLtrmZKh_vF6Tn6<2Qa zSXZuC>_5%9loWH|7BdEhDJ@pvX9Dn~2r}5h&m!|_`(5b8`3LIfn%#ce+Ik=R zh>#NY#R+rfu1A>WdY$nUzWFh*B9AAi`zb?5&)CZ*@@0%~DNx+{4V#Dwp7Ky2Ol+It z3T)KN>vszlAy~6jrt>(|i(uK6k?l6HG;xhyU&Xzm6TAT(NPoN3rFz$8G-qG85T= z9MsB6{<_f5r9MP~+x25Ec0f@Hl?&@!#KbN* z;>FV@DJfgWGi9n;zbOGsX{|`X=Uov;$O@1MFSeEzhijVWcy#~mn%P#9e}25Wv2}Qw zGQ;ABSkS>Erdq9zR~dKv2rHb=$3C%q$?P|KXtJm9(~>4VE0g-lD_QPXkiwUQVY)aDO+7rE0Uo{OgxNNIR%q6)S$}d*tE@jT`3QOcJxT^7X1%gxRIvOTQCW*W6ss@m1F-eK$*PFQ>bmH@0_tYJ<(3bHMg%CUL1tFYiv9eyc*;63sX8fiQ0iS;N1%AMZB2$ zcTQJup-gMk4>@DYPyZKPmXO>W%oSUr7xaf_UrLRx^+c^mg9l&5af8Hy<^n8AI|m#b zd?EYyE?jt-d-!Jde={=3QTRMA(G&2KT`1yIBa4=y(%LjbHZ~qqF~&OH_=MEcV=mFd zo{{VmzlEASqt2Wkq<;!(@E0@vR%HPNX{XoGGjOaK^@;*KCwg}MTs30Ph$q#*Z+$oz zJv!ycRxA#cYu1pyc!mmnT+q-6pZ=e`X&@w_I#rwGQgB-pH}lR-_j%#>;goq(QaKpDLsXCOd{Dnw!Y1kWKN zl|kn<0%!vCChX*QghavqWu3MO6Y~tqz}H&6W}9ak z=)wPWr~Ugo-vx`vp`aLq7y+TF+CW=~fCG5N4!R}*QJhS71y;dTFi@qY8TQG@;zGmR z21|T0ZKlU~K=3OSKiT#zhQlMNy&ERLX@C1$sV*4tMJy{{vh>VdEMxN6g?Fu8DTAI}|w~3J_EZ~m=n8h<_De0(aO^)16vkeV4D3Bz;n$z9BozpkKn%90^bxGeBG53rn1HRt+N>sQ%kY5yg z2KU<$J&y1J49P6CrnL+Z$-@ko+Cr}g%>W_{8$!z16J*IRm&Xih4%)tfgKr33kJcWeR zZ;St}w*|ho!QoV68LyynAT{joc@W29!a-)8Y1+6R#u&$2A*~0y4#0dIY%~Fh+z7n8 zn(wLQqH5XR$8pu9@*#10O`*9*g2d(!9CMCgS}%S2i^8-VTZNC7=BU+|5NW7SOXU>@RO+s!Vg!~?Kb#&h6Gh44_RR06mCv@ zyK&hpkP6D4Zxbx zsdxI7FJ^v4@fm3Cin^*!0yJ%+R>#M}Ck+@SWL1zVbvcQo{V>|+CG?~P&?%35MNCgl zUMJ;!1mD%>wwl#IX~_^$iV;Kyo0LqRzcCiFzG+?(R^!yIcB3x}>FBN*FqZ?(TY*|KIa&u*A z;GZgc2cfpXzgn~7G2^Tn*`>N95;k~RyKJh{sCqxE*Y~FTCKr~w6r28T#$x8%@D&_3 zU5Mk+`N!0C!HDknv#*h1#)YeXAQ5t?Z!26}OTYgwq%?>P&7aTpLn8Iw&hl`)8X|g& z$uqybSCa7MrY-8%Nn)J_ij>XWeQpx>=cA?z337#f@JaHp%3ptC+UJLxf%A<&Qid$P z^P>ry2ToYfv+^cx{|>1QNpo;;HhXH_-`z9LUGW=#9gOg;)R|GrC95NE?@{iYW??0< zS1{@OsvZVnbDV3th?SmK?<|5DS5902r^B31kw2L{x#w(v4wCL=7MKy?pWjj|?QoMQ zo{n_g9bEg>C+LbWqHl@<*jAR{0Qn*rB3kHu(-u7~?#GV$j`76-AZAZmX_kzLh=H4Q zMQQ^t;b&{j;m2Sg`o&;i(h-eRBfSvJ`dMGH`@ejZDw% z)(sWEe6s#Rq);wayod1^P%Mob#5H(a#X#! zc#-DHnysS}vBU6RrF}G}o#h{gBTll!mg4*?utG65(TI1#ki?P=#)28fSa(}M67@ivU$k4@nYPFr z5sj7Yf-ek~BVoe*ylVbrlxKX4BT_3<(?Vj%7uKDULCJwiSHt( zJ=OzN%&x76*Rdhg6CS9bZbko8k@N^Pkc1&>u8Uz!y#1e*h}u-{q^KC_uMl@<;-N0j z70PWF;yB*c0C6Z^oavAOktl&lW1VrDdBi;R#mdCqRfur}fUTm#j$bfNP*ooGPPlU- zCnvy6Zq+_BH17<0y1XF_7NIiJ5JtksoO*9S_}17Wdwqjr)ER&}&jE2aaLKboG9~cM zBQ*PY%$}vZh(l$?l~WLFHQm>@q~>#zQ}8rWU!?ACO;wF~;3__IDsF~FnK$&(?=kB1 zC1?wAMHK|Pve&tE3NS1Aq8IPDZ0P)4P!3iZaB~x)K;dUsqump1_rUP>DYJ2S96T@2 zzL2OYP`UnwgYNV9*u=fQ845&P}Pqjeir#(8R|Uu8xccH2|PdY z>iP5&bF1jLA5IBz!I)T7rV26dC=yk`dclKX_8%|$5)9VM>e?s5oD;T{VG0ZqkV8=O z1=9qKtXE9UDJSIzO2iRpI90%m-#8PY@KdmyA2_)@vcuYsz>qW2+OBL0R;tEfs@TX> zIL(3>PSSNka-ORDr(Gxh$;GmR!Z(5#zGroRQ`v{3cGA{WOQ4>GfV9E_l!T|LnMBq#?y~z(`N|W@)}) z-$FS7cYKZDQnM(r0%fi=d4!BaGBL;^{4*W)WC$3_R?Py0Gm(OBO(GJDY+SWx;<9O& z(+k;sd#JDc6iBfio4(ZzA_sBLBZ zBpa2oDdkr6HL|oU<v)AIxh7_i2pCnkM>xx!7hq0*|H*pCnlua_2hL@HefLUx;pB3-lwg zuuLf>hlfvBk-c>3V&=8czlxFJ3}PGou+zRKq837hbY;@P^3}q_;yNn&~LpRMFV}!GaQo5-VDCDu&eUxr#7PxNz70&4bJpdEy6*vbF3F z^L?7sd`|X?`ZC1K?RT9Ry#eVyq?VG3_>(v=3rf#fU>&Ml3W&Q9KuXKo`|O}cuVv3T zOWEoZx_`GKIDao9IDKVy4hdIRvp8Q)ahrN#Is72Do>(0CSmTDp&coFGIbdC>AN9rG zEtgXUvezkCd@PSIc+v_=cSZEO5LaTp$(k!KiaOT^kSn(mF>eT_InS%{;L=`SRTV zzP|!!Z43J1mXOudCOCyZt!L$Hp+whLbw7+5ra+MSWH5LztZyx?8d4rHJXZl}>@j0J zTU^fx89#ZU&vyF1OJlPg1@D;pfG|9VZAvA?*S?LJR7#v)NL{= zva%It;ky%Q(Jw_)s)b0-@)1RTqkQSQi^lcj8MmS~vnCw zKEmX$FKsP#Qa=S`qPdefij|h&=>HCqcxwpa{d#xKxs&^=7LO@HTV*W~ZO4V+KpVDj z)uAv|BkIr7HV*m=t+LYgXEoT&(i7p`g8!Q6Ri!-uUD<**07*!8 zfb6FDjoKJ>YBPB^|N1qY$ze&GDl6^G8*(7`5#;nayz0b$UQE6wS1x^Cy6`+MFSpVeJoT-Yj9KYcQ&@pJsso)F0+o?{TX!Y|S_y`q`0G~<|qv0NfwPFZiS>Y=@5;+kD$zIl8G zg?zA39%rew)Ho-dx#}D0BgNr1g3wI-Uq>bNn&J2SiJ0PVM>2>8`{^1cQb2i^DwGe99ou@D; zV5u^LM2XZ}en@p?tjp|fFI15!N~+c22BbiI9d{j{`ZASGVf}EsbC&<_thl!@Moq_( zSt!1H&_;~Dy@;4PNp32_pe}vGlR9-=OnUx2xH<8#ptgl5py)>S=hnCu&d~>p&%!AH zt^G6z^qtRv`v2u%>jA$mxcA7;V}fr*xM2BdkxL_Jka1!@!lzIm6_X`!H`cQbCbenr zM1POakJVs=B|81Hv5%JLz@bT7$9u?Tz$)Jg;wn7US!qkw3G_$!FI5awAG0iEInPHdlgj zeWEkUZ@Q-{k?&zPgFtvJjpHGInYw~E#J!ftQ?$RhP1O@?8{UKP)}iH`-L6hBa8 z31;aocR9Lc@>{obb4w{H;phNNzvboS0sJLkxT@dn9DD?+sRR54+vg+?w&p9hY`3Mu zr|VSK0-o&G0?+)3Aret*kMA)bj8x-?pb?#=XAgY*d)l8=i|12G3SD()==OFNme!z; zO-Ii!Z%=o2;I)|B5!33d|B{c|fa@`80IT}w+N18*qcs+r!Gt=I4@vO*;%u2~J^!{? zuk8JYikk+HLRA0-{rvk)mt=wF8wTv;n9A^8#r%JO_oK`0v5tkMr9HkWNJX{|utAL_ z;`!x#1^@Jf02sPM_X!Ps1&@Xl3{vLD zLG5mBvExi4F2!rJQm+!MQoK)m{|RBxAu15l3rg%p(egMX(X<2-hwt@)Oa7XTZ!!y; zC}vaCc*BYRop(%hsCRrFR1jir6B)f40~0NlD`l;9NXJJ;Fq5;UC18m4(u0!+=>PRG zx}v2${)&?v9n4X7ZeLwIem>LZf3WWuq#ksNC|qk@&-!UekOv#q2YZCMXS^d2GnZ!l zg&@&u8_j2@G@A53&(8@vk2R?ZZU1*CpRa}zbtg)05L$bx7*4MqVG*|b`jkrRY^z9w zm!h2`z55^uijmCzy04#0YiY-dQiyAX+NLmalUb>yoyo|Sdc>|6{(Ty;=o}>|I8Kz0 zK}Cd5W1joA)u(f0j_9){PqdqQW)S)y-VIsk2{f8ECf-Auz*IPtp#T9-WR;p?E5$kHe-a+4W;6Y!O8f0736Z z*07dnUj^*vSXwOvH^TDR{rCN_HngR%8b9r)U@Tt+oX8Z5@=6~Rq=*o`VMvh`+biLR z;Y58XEiLuBnbQKudz+`Z?SLyic9_VFVO{Svr?F^g9p9VJCUQJ4i}x>qAMeL6?nHsF z3cb+*m25Xbm@n7b&*~c+`zQ2x04Gf)z=k(975DXK@{KFbZDDcM*vu@%rFFcirWzRZ zAjO0O)pQ3Wu0M6=U-lrJUEu{@-~m#Ixj{VBWX4c{gx%rLnwp2jbi6$Nrd-I)>Tl~am0?uDjPS#p3 zYcS78tQFdaV9I`nAp8t)7T&=5ffuc-G|N@nPv1n3!5F?6_+llh#>U3q{`ueQR(-0P z02yQaNa=O{T$~~_Ic~L%-5d56J688(wEaL}K%w|zyIg;K%gWfW32ijKs+75sK(x3ONvjfGn$774?>82 zk9LcG{@zyEJklUn^(z=1i$~*Z0k)t!OU!eT7tZ-@9n#+6kNF-UetpZ=z+^~5HW6P* zUQwPM%;sR;y}!Z>R|k_4iDbZl4Vq0#l6fIbCB;pW)@NI^N6Y{GMn1Cn#Q13S?p9}` zYTO;}|JMSz?d8jw@q_r@R7EkWdT6X`zZ4{pQzIO&O!ZIde8B<9igF&1*Esq}!cBGG z{;&VdX;MT_o=B0#>J#E{ru}m(5~UW)_owz+{C1$o8-KpDP512n!I>L5>7lekyvc4s zN!_D9h`er+GOUCgYfhC~pN^QPwO;0bwV|$MC)3p+@r907=@1u8T~HQ0g}*2TMgW>d za=B>4=m$jOPS;3j5nBb^MU{_4>=SH+k%PEds%RF6-n)_prE*~^tA!-oFxF!t-<=ZU zf=PQ7)tufgm<`vKx0X(VnyScsb20rWkR;H|UC20ltuQ88J{D;3-!OiPOyR0a0G0G7 zqRHB(AS-Ej6e@23Fb2~AhrH>!X`ZzE&njG@v%kDjQVVcMOClwtaU!Ew7Ey$+(_Mbp$GK?4lZ`l#kH~{jZkfI zH7#V33Ti6G!7lZJ4hTX$ZC^;}eBWXJUFprlbHaIY?bK0IBPv`D0TGoTBROyOROicX& zz>FhI*vN>?e{=Nh?Y@FOjgn=vb;ZR;P<{teZ`?2ty*gbVNiHuJGRR4vhTMizwvuv5 zJn21`?o%@VAUySZ%5fEv6kP^@*rBcSwa0zcERZm&u~W+}cY0doYv(z=W7or{IUC%V zRaZ|B53i2akw3TG2J2E%z7q1igT?Nm`_%Sl-hTAvNY6QL2}@+|9hQ-1OsPl}Ov%>UswR=9NFIstaT7 z9l?f1c6KQvkus7)lEA!_r;e^ZbZ~;m?{b8OGYeJGrppv5En}ZUFfvF15x>@Z2}|vz z4^Cgc;Iqb>aZ$}CO=*cVP#RPO2=F2ebH&QElv_t_b*N^JWiey&V;t5f0@W$}^~@K3 zYOdRb|S@N&dT5v>}rZe>BwFpn#73}f>^$8bY0j^;Lg z-`8?P_XBU@O>r>l5EGju`SeJBkI(MmH=^AHXC>e+VKuQ`C)$8`jU>RWOM)2Rc9l1-72Lc#pXl3I9(t zGz+>I=js>Cpt2}&n)*g<1#ea5QpFEdr=uaN>bc?zB!6rJpQenOYE|*LSBApUb z1s7btw%bal1eeCik>EAR8;6Rw$Im=qlIRCk!hk0x=Co@5PE*cZ_1pNz%*Rl2V1X0j z{V_Cha|_X|B=Ali92MU8;2&Sj-#MI{Yz=rJoY1V?(=jr6WU0^QWV05K_Mv9}bi1>l z%|ou5MpW$fJ3?AIUeD-J)bCbM$7gNCSvWQ>uGVcA1si)S5^MI#B}LZUrIk3>Bif-w z0RzzKj%`gSq|5*Z0RuS}Jbckv-?@lV#Bq5qFnhVPW4`8lX0W@52Y}@obth=;>NLi8 zuRZ`6TLFRPY3Czca<2D<0tnT%cIEhV1ptb7v)6lfZ}0xZ@gEDgWLD@mK1~$46|RD- z>s80&A#&m2`2b#ieR~7sDn;?}PtVwn6CfCA2&~ge)Cj>Qn9)^g4+uTS7R11cUt2)@ z{Rp6iERucFFAZd3g)7dsT5;0vp2z8dEb5l53w>~Cu+?c37La&6KSH{99bX?Et(vn( zygh-5tzAHnB-B3M+bd{WX{+BJ08nODw{v2Li0lN{HgY}JHp_$`=m31_N|(O?pOkE* zrq6ySUQJ=C<6=EBupLHTU%|11FmiHo`dx0B6$k%EpaVZz#sAYJ>6)6k{ast1sm3zs z9s@{`z7zh$bXCqV2NL4@I|GeJy2R!p;v}W2{Je>t|A7<^OJusXFJ6biYio<8a}E+= z5=xRjH`SVzjEsz|U~b6@{rcim&3lpGTN6WeXLbz@4PxzcgLnQZ^O}n#Og-Dukue?V z*h&-SU2G3WGDC!{5;xIE$M?Q8vLYB^AOM>iSs_zeTISW*3WM&uLtvUPTvJjheYbUd z%((vadgpbwdiM)(FYSK4H+5L;n&=BhUl3k6don1|H@2~fa;?ePLVukjW#!=+0#ff5 zht<+K8wrg zd?JFN>)4WsT!zs8{jbB|%9vBqyO569JjeduT=8E`^GaN%ia!;UG4ec|AkDY$6+--a z9#w6Lj|-YW;y+@7KQY5ce!>bCC;W`rMTl@-EMD+0NZ**ZtO}y$?5Y zL8UwUEa5p$jVaFZ6=KWoc1(FBlXd8(eeb^gj@Z{3MPx;T7b)kWpOHWUB~;71Whvt1 z(#m#W?kpn2|8{$F8I6(q4sm|a6g4WEdJI@2<$fg2Xm z6@Q9c9;D}T5k*42hb5~pbdN!&>LyMuTf}Pog;~q!N6Ox~bZBeNkDsD~A2z-v5Al-Z zPSq}-|MIWtxzTI)a}P`pUxs-CCb-h~v&dz=C@;7XWkSSVU3O-yji3S3o##n;M{I0t zJ-yGcK=>IG8|!>DZ(sejQ}pU3@qPtN8IWc~M*U@zBn>;Ovei44ED=~`onx}B+7m4kRM7iYi+}A z29gg3sj6_s(im`7_D;l$QoDodF2{TfMG1l;80Y6bVkxQsl^PBfa+Q&nx0C9+hfnl* zbBv|i=w?&w_Vx}_6p8>sczU`w5GDuN36}~<9Z##rb%GzlIP&95LWv zsx-%ZeEGO>%Bh?P$lG<#c<4UpR*1>Uj?sOLnWp8`t^9kelGq*WpCI>K5GzUArM!NB zx2s0I14KfD0}z(WCHqhDb`7mVoOws)~SA!Tl zwW~deo0*$Sg$N70bnB)pfV5qxU7%V$b?U~;yHGZJB2MC&_@@8dkJcY)k=(S7!ZSZJ zqI-~lW=`7jC|#_`wFCgd{&5U}ISbt?#U@>2v*JIaqsSB#6hCWfuJ)%XNQ48%|It(g z1US*ql8)NrY)2N=5zXkf3loMF8<~eTt4+}nFca5h!{r-k5<`iT8ye^)CvoW9v&`qN zZ{4t5KS!Gs4)^xLy1KdoBj0#__nYC*hg#je=zjmD(#u85{k3rid<7Q$o-=?TWy>QN zKso@w<-P|&*vP^oEHu0BW zG{q}U5NFhT!Flp3EV;G9{;z_darlj`jRP@qx36GgwnIZglK!8sLxh(%`N?_l&95}* zHJ_!tor!5K3P|;%e=>#ih~K?mhyaNcST!%Z@#hX>cUfA%lZEu8CW(TS>Js7~M~eqm zBHoB8TV)ibi88MPd5&LZe@Ic@=?~|Zu4or}UtbMuJWL)2$a`)^kNR5Geub`*Z5OPX zcl&>d_!vj@a8xSj8e6)7OfC7}w)v#h_Ri&~P~r5LwJfp6<458mksNyDd$qZ%a#Fus z?=?rtB%o6o>uAy`vCs&wE6tkpg~^tZh`&8)?SCay8O^DP<%OUBns9-N|g7a!e3fYe?UR> z$Ysam$XG*|<U@LsE~}Ea0oD%>r4@zpE11 zdk=mvbd*Q&B+h4RofNWc@6XI<#zdt>OMv`dP*=~?bPKa^1}B=z!_yNWF+X3^2pij& zBt1OvovyaawXeb;J?O{jHc3`#7HKn@bo#*p3|rrJUt&%)ta^=p%~b6j-6qvS%}SLj z&5@l;+7hdlC4ks9ec*QSK3f zo;D^2jN?VY6q}i18E-ewZIIL}4%yWw_)aDc-BYkJR%yP#k&HtfVp-Q`r)Rzz( z{2tgHRYT*Ld{6S%$|{VwnHf1oE;dmXl_Mw1EdYajy}qTzQcTaMb-xpc5q^ly(O~%G zN!4i=08dGe>uiwj(LMsG(tV$N#dG9DGd_Ywc3fhVVgR?5FW|jRA2cB3v}lMuJL=zR zRcB-ea}PcrQw}1=G^bTPA)p>b7O3Nla>~2#!ESdDfBjRW&Zt74dhXI1(ZK~+mSt6a zI?-gf{6vIdLLOhQTcX&hS*A@7(~C8zK%`i|>TrkiH!)nUNk0-Xo-oc0U<(EZ`=g-| zHtJ1;tW1hBSq@K8%pBhEU%6hz{FVCUx`zfJc7Zm>MZ@|VL3?}qzX#{E0%Z*+g# z{FGjxk@0Y#6!@JjEb#vA^&5j$4RG{oq@|~OA62ygK{$L@cOrfs$^Zt5)l?!WS^Aht z8e2W@NC4q8D@tSB{5ccu@mYFXc1YN`Qd_}?NC(9dWF`3}y{ox4B(_iW7Ea#t1O+Lymu!Om^L z4)Dbs*4iR5zUx*E0;w+t2glzdcc5AXz{xTX2!J!~pY;fkD+AL&+}!hv>&rtog7oIu zcwZ4kD(8MoTTPvK066)SF>_)_-mm5!m|kTWrTDl#yPqFFfrd_xg|;!07`Dv>BK zEc7oQS9tS$FDBaTEXVlxc*5k~!wyT}NRut({C$2-_Ezu1$Bu`2J#_|LV5xhbpTht# zBrq2lEZNY5XXw`h?369+Er98k2&^!VJC7%%J)8vLj@w_alK8vCj_?4-w+314X@P_SrO*s=1_Wjw*nzajqtw4*ls5v$ zT+4y0*gXluR&0@@*vYN9G|xiO+IY{j<~(n zNQ&5od{r4j2AE0+N3Ku%7iflS9b=tMLvE>X5DJ{ML0md^&mX!QG-n1D9zUaw+Cq#o z#vAZt4oQ|LhpfLSWuxoURrhmrL(UZg6tRsK;C=aw^ zlt5QAOl`{?AWP{$L+8h?*ZS|I{r0`*`@$4FSZ6>eC`5YgD;>_^?Ve{+ByCvAX;Tsu z;z1Z-xoD1`9WHqz6?DZ%m}Q2^DxC`CV}b}LzYDwgbrl6ih>2|Ud7NGgsg5$-y_6{x z2QlHf|9(q~Uv&-7d7~t5>FTU~SsksErRya#@~s)D3B2Od^JRj?#nK)4EUFv4z^d*Q z*9WY&Jxxts4xVqpaD`6-TwJ$M@9{dAeix{9akHh<^nTWR(`$0`hO&bj@x^21o4mJavLddiZV%)zO)b#zVB1GaIk`+ zE{b_bo+*)jx!+xo+P8X8Fbwt{B)}8a4H8F)0kyU=5Qm(SgpVsBZ_3 z7oTqcC+=Q7$NVG1;pF{*q2KS~8cFb5_2cxJC;$EhTx6mF7BQ;;&)9Z9RcDb3OiQ|DYmEI-B+4Iv*FD?AGj-t)96i0i+t;5+21LJ2KO*KG zVG6V3jZ*FYVXOlbR92mFI7tpIeSiL-wK%TtuI08jW+|9V5}PuL=v1p`Fw!(skE)c%(P7suF?>{ zmh zAXFe?=35=3*6c+N*JqZhP$$oyY^baI^Z3Y5bVL+sseu8|6^M zlbl4KToVAd-bQP`u(V`he}Wl5ueG?kOpZ8Pm@S0dDtKd)I`Hse7Z0xjBKcFw4S2D) z+(+^A+JTLOxAW9XwE9Cu+Ewga0z*Kcr#7p$edYaJJ=uqF*XsYojZW(JDA>edc5fgl z`b?&+tzGc7X7<1X=v4q0>BZ7O^z-7|z2!>xThQCBXW)<&X<$FVvR-v)Ntcpd!04J) zQ_B(Z{q${PFqR0o5OP_%pQBn^y@6A|V(veH(!7cAI?{W7+xU3Pukuw<81Y}b4>(^C zL0->Z$&y<^|BhQ89^iIpLoFi}V*K!p3tu(y?rmWoKYgvWzx!!6aHubw8+;C&oWMB* zjep&bzfTT)a(r0sejy?v^zlT1IMZp3x(OKgtxFLpwCXqeX1`m%L;8+U#nqaF=Z^;T z)@6#nlc6xO^g5}YMCKaVAqNvdY8u+x6T^l zKu6$%o;g3w+iOBJVKVZvOl)ijgKzTIv|C7i78Ml%hvBC9T14H23ee_o2#6brL;}FJ zt%2*+MR|LmTu_*`iL~Oj8X433osYoFm}CdmNyFmyk`~0P;{m_cxXjYRlGpbZrTU1C zi)&!~n6XJWmO-o9323(7qTjZ9o{?Cl{iy}gFrY>asWuRpDL*_&oKeU3vHpNEB$yN3 z)gpN(-BCC&OJRqd1i5xu8nkBqDQ}!~W~wyH8majM=tExCpJ;5AKV)=i>K_FxCeRv$ zz2wk}CP!tzx*kx8Ne>O-+j&I&r!b1eJH1kG9Qy&*7=<6Xf;c&$Q{THxjXK-xSsv@F z-;`-9OMe8+(a8I%YUp4m>gz!=%fs=Z7UEDJBBU8&B~EGjxQgc3wOD+lISd&pZ^fcB zL2B=Q2?rA&F1sm3cFiK>QO4Oh*2Jsrh`*mX^T*CLmlqveKD>qup@}Hj)2hCqiyF}= zcDyZQQ)h_{E_kO_SFu)rBM!M5i{NXL?LcMU2`*2|#}MH_->Ylx4^PEjU-JVenwHV6 z86wY-LwZFvm&(d%|6W49QV%je04?J!3aXg-0$AuG29e42EBtT|cB4P9YNw6Qb%#t| z)(=XKXX49l}#T;{gn&s&s`wnZBvlhRc^c;E|2T$Je$FB zY|I$4SKQtBqMJUv58@Iy@uTj7{8$%v`J!s!S0C|_oNLEt%f3hkWv%SMgLF>JSvW)8 zIc-Ds@xPi*YMqZV*4mGc)c&+xt*RfD)>Y@$lL9)FSKU_v633g?P!94tb^9%Lf|DuY z0&saa{quWk;Rk$8pey)d#Wh~{Ws(ajQSQ&v|6wTf@XCtm$~PZHx z?N9aIhxoE~3W~oZ9P3fLD-}0~7V4ch;CqUsK;LDp1|4~xT}8(SPB?;}U}J-O6dor; zf)J-l$A}#D3y$KH39>2D?=bk`X1hHyyxy=oeQ(cwmb>?Ev&FvTe-jp|^)~dShtlQjZbx0n;sTRIZ*zuTt*P>k8xtp=)dAP~wa5 zd1f|NVdzbVp@aN7Zy#lWagSIY=YWqp*bhC!Oc)1FvL15ma@1q`x-9J98+;@5th}gB zkhoF-6juA4y>5Cxb(OPmgGJ`Be;qXObb=)@4He0MP?r_&ZGF+(dQ!ws>SS8X7k^to zIiuj%eknMfUZzO$$-K@XB+k9>pfG7Hp6w=9Yxp)zQm(|AD=qN+@r{I+5@j>B8WBbr0RI3{^ChQDgmV zq8REUG7}T=-_6fmO|?fXaUMJQ{Ihg;z)S02wp_9r*J)-ar>&` zWiV>RpN%=P(Wl~KF+8hq7=vy({+Ij|v`~|8K+U{m7Em}9rABonr_gIyeA?3izadkr zOTVuc_;Xa#{Raq9w4}gW4ePIIiVdNdu!acoF-qr$0}!vbm%EC;Huxn69&Lzl*rr={ zjt0f&JTmDFFkDc;QDx;d5W~O1g^uDQa3DQ3J=Y zMNcfe;^>s`qHL2#c!pbmtG0!;GfatS+X-5zXdVx9mt?~nv=3c)yRxRs#QsFZ&7L8_ z+B6uJ$h;3o_w9RGftm>`82kswCbO5bgC^w4QtJ8me+b5j;FFaAqrX|`Yi~gtD8cl0Y-CucPCAz)noUs-N z2ig?hrl&D4^NiixU?CF??Y_UO+V6gOTyf`Zu?q{{dbW+S{F;-IK@T zi~}Z-k`1A333q~PK2J;}HI7a%m6H$W>2K2Qb4F%Q=RWYwzKbm?$oq zmpr(TNd650#;ZD7ldyYvz+K;r-mMz*mbi*5Z;y>1ELoztv(oC?xNHw(k`(~kgC6(x z?p9fM>j_+mPRh>CKDxhPh4bIS?bc$0rH+oy=JUf9F#c4W@-NBieyr@41)~SP6WDp5 zS&I&}*7<{p2Hf%;FSpCmpjMY1dLTd76r!V=&`b_|I5+&|vV**;nC{8k*|#&czBR$K zZgzD+-QutgYh-U9TbXaT6TkPi5O;9RX=`gM^JjZ6GEcO_@WEuLd;RGT{wyA>H~uEZ zy!@yCUkgAA2P1;9;Y}h-*Vx?ZJj-XgRc|MbiaCOu1mxGJ>)r8t-s69kXqj{?x1Ttz z1@6~&QQ~f86VvQu4(!AaJ#RnKCGXzdM6wR`qp^s~^22gTmsa_N$u*(*I~M^^U$KCp4Yn$>u z@iJ*s;4l-jG|Njx83(_PMDlaCb_iLF9H@VQ-|eEZ(_lXXw(h75!MFYwqv&S1P_`)X zi_jQ^ZzM$NX?tNpmIG#MBU5j7nXf-QNhwc~lE^q$yze6n{cmx*?{9EDvOv^YJxqwA zi4Bn+F{1dPoXG3zTX>{~B^i?{)#}a((wIc({gW}&s-iZmumlot?9=!Xxjr$B0?*oh zhBP7^5;?MkWd%Yup7q{v$#P{VBz9125Ok^RtkX2#LdooT7Vp1Aud~QoRO}t@{^G~M zFhj1yrbvY`vq*G%9Mxc=3AOh5n>(dv!en=D(QpxImIPPf_3rZ2OE7!?FqjrA=un*a zJKo_1V^mWyCZ#3*Z4IPht#JQlCZBW_u0ZAb{4-+mK&>Hv$(2rlxgReERTBF2(X0cW z+O!5KR#Fc8ie?&I{uX$y}FLCzTAS8#TJny!sZ=lv~jFOT0|pPlj0 zGp^@r2~s=_wTVfW0X6sU{Ss6oos1-G-Hq7LIn#Vzl^XbuV@`{jq*+&K~Vj?n?>+%RG z{!=fZW{w{L(Q02aJ5^|&sw4~Df>f!0^{z#SzY@mAEj`2_3sqn0EGvkXzTNaIW0L~9vw+<6&lP3JaSpNcoWu|_Mr2$E{wIk-Z@yfT$nJ+^( zkzEGENZDM}3xF}HNV=E`nzV<<`%76FzY7zr0d8`WU?NPjYn=HN|>wdDicCANP3{8{aCG|yE1wOz7d(a6>}`|yD7B_KaN9=qo711P4j0G~97 zM(MBaM`D_RoiQz-^}{_jHkOl@=i=fg{nDX0>fQ?Utbn4-zvt*Wn|5fi_T;A>T+#Wl zgc2?m7aza4yu3HMGX`|%5g_i1-gSKkiv(4g$pPJ@Fwr1YWV^9aWyW)$X;uI0mvr~K zDIiDp=|s~7YBK#m*PjOh;o}37qvXvvpeA!a=1orbV1|by0QS48*5Q&{IX<0nq#49b zBKR}bEqqJsrj~c_hGYQ8H@=Eoj!QxI2OI}}g$nf_t2Rb_Xp*nP11_`j6XRGhKF4RI zPJT{7f0b#|blTlAT`I;`1zLEkyNvc*_M3mp=;^olW%{0VjrCr#18$h%L`1;+D@IbL zOXgX}722YHnoFzvsJoLySm*;Xq{e_M;nQTEuw`IiJ}c)8PhU?EP-0DCH}Op7cxw^X z>|$~p>mFbSYnO6Z1I1ZUM4KiKAlQiY2?n12sLiU%x=A-DAF_Yrvn9Bf2FQ1uPL{Yx zgaLHTCaC(TzO8w5he2z>uUQ5^EQB6#6;`gy<-oti{&YeFQI~Sj5(y%zswDM)#soqw zKyHxd05;!_)z;THvp>Nyrqm$_0|EX0&KG|)bTs+g63#efy3DLBlb1pMe7{R1;O8)3 zU3~;N72Mf7yH$GQ6B^q3+W+F$cF)uLrp|!}?_4GDLx>yyfE6cnzDkdn^s|~Hr?!E? z=5(Lb@o5_1mvn)?u&@9$51ifntb&Z`u)?Q#BxnqIord;~B7}C@m;v=gifjp-HaWaz z#ATE&cZE7~>Vzuor_8)e8REdc&38l2MV&JsU;=+%Sw5LYg}DiV)nc-F{m#5^L;uME9c15CykfU zn(dvvoTMw~*tZxdJ00R}nvn5l^hOo@$J+d(OZ&@C(wDdort;l#x@75{vHoWIDIM$k zxnpXl!4L{fmd)8XdwJnYsJFi}V<(6j`0lKKSo2lj^)%Ysn+6n-{w@Rmc-JJC1s1hV zrXu;XHkIAOedaJhMi5T&hH6NwIA#rdeRdN(?jh1K3p^C%-9xFs^M|AX+g>VWX+nQ17H}ekNO)i zw_dZxV`E}|m!W3E+le4ITdNa^A z9)%!w6~e!n(gHmp@85V^(p8hH7~IcElv z27xueGu4La_`TJ!xCe>n_6krgIYE-tOjEWHDM1oPCPk=FFsl~dMDZs93mBOf_Cle8 zt|ciW`ISGw8U>-E$R9$sUSo0sEl}f@?%g+qSc0M0?*uW=`3JY5l7@oDG=B_*PVKKc z;4yEc++vZ|hWhpKwRU#E{#)`REG)bx>^5%DJf(L_3q9{ZSr{C*0UOw~=nNr0PfR2r zscEtE)J^04F|m(}*R51rPh?plDri1*Ov$!HFtV8qxd~R3#*Iz`5UzaUn$=`aHf+~x zQA=v&GLrcCh%-`-FnV%{m|W4N@zfDS^QxgQ?U$J3{YhwPjWI&sMS*_s=!zjd$ral< z^N*|NU-QW?T-Fc;N#DQ;#BOKt=GUdMjxKR`ykvJ=vY)i!O_Gw{OeN-s?_`PgI!WOX zQPxbtrll_l_p0KCaS5w%(r{ZjlHBL~YGT^t5K)v#PpV`?Lv)QIwQ3{@6=*rXO=X~5 zkXuVaW1>ek_{q63$%b!W5pkOeLDNRQ?oR1u;OhbMsq& zk?uQJ#>C?CNn>G6dP&F)>JqW-d3DQGmrk%?e0*z~1VIde08~>yUfU>myijQYv ztSH)1w1NW><|}^`rPS5c7A2Ibjx&`XU^wFDvvR%;WLGN&d0FAcXi>A}ajIrORE&^_ zwrWu(^2p$HGjQ|?aVK7^P!ltnWb}Xbh5GJ^cG84d3d;MrV?};+JwGbVcsQ)vverk% zT;!ofcWs#6c{l|TEhAjJ6RwXGHAzS#1CAzQ3<~AA`|r9@`j@(vjv88S<;v}9ESNoLSW@II zEJK1A`hs2Z!-NyIgwq%UiU1>;B_t(l z3(cd{k%B%^9!#6%%J}SN+cHyYIIlH6PLnVWVm>-YeHJlEim^|M{KUX!3=wZoW?u_T z^1d&aXGB z%FZ4%TK^@=QCH#>gU(r)AJ3+h+`cb-oX}>;5&lJ8OC01uQNK*NRvX9on=Q@nX}h(ph;0r8=Jn zth0_Mv}V(WmhQ=yr#tHwy%3el1z=Dx<)Y9Fi!%bHaCpO0jSe7Qjf@^56HdIaoHpFp zCF@p&!Jn>lj@@(t7+5kn-Ti0<0p#Ycfyau;wdaOQ{^O6 z_BV99AN9LDQuRC?X6>66y`D1yACFxh`!HubbaXRJt5pj##t7d@$f{;C&hF5amX$4n z1$Q@#!UesbLpBT0gF?LxkCh`SdIqPF9LJU~&uaPy{pys>930{Tx|L3T4lW)Lba%bk zA`igcovxY!Jq0DUmHJ%|iZxLbss-|e7+wNwy0(gx7TabwO4hB(ra-5WEGaStpH*02B9;fHH=%I#+$a^|Dn5Y`AZjwzH$+ zUkaR=(kr!U*f}^9T9$VJ4Vye=3DcO#cI>`ejEmID-a54Zb%N>?@gi!EI)4T`QQuHc z{BnqRgN2`PD`KfeU3BPoowpJO954Z3(?t0H(R3DERdsFKRzO;$rMtUZx?4axq#Nl@ z>F(|p6_D&?nQtKP_BwI6!Um{G z2L{qYQ=fcPuU$if|j?+pn_OCQMyeI`}#j%kbT)r4Qboa#G`dM7|3L^C!6RVyksV)EK znS}I1QCjFRMAQM80M56AP*^>ceCbpeb=V(Y4is+FKJA9fz?3dFZcYZb>B$?8iJ z`SmdPQ;qscG)29Ct9Wn7F$rg`!E8roe`h5qFMwdg7cMS8QWda@O9y|W4PpCA?TxMX>ZMM<8AgOn*eSg1Z4f1HjL>=0YfV+SZi@F;G?I7{ zw4`y%Q_-3tt1gGDe_PmciI=!DR*~(k4RZ^(+V#U@wM(tT1!->;P4Sd5z#}n|QDQJs z_1idpz3SyupfGQBP2;d3WyQoEhYsLE%S9`jMkN|)&xE0t@+ql>vJ7KkBgILx7@H3- zNz^LF=(f@=OoL}#uxD?eA}cGL3=8MldbtllKeit9A}6Oq+5Yb=J3V&rbQHz8`_06> z;hMK{Qji>;P**1|OHYPR|MazYql+n)2-e%#IzW~x)^-WTFpQEi#a1GSBb>5Oi+jT) z`nY|N{X0p$InMaI_u|%Jm{3x(qUFYbS+n!Iu+~aDI(`IZjDY?_XYVyNpU%*{7Jh*X zJROG@E?#srDivNOIROk~h6r$$#kfskuBVL9Ax$ipfj@ZKk;7RvCNY*wJE@m@H z%Wx%{xq2ebRV8{^IxhE9!=hydcR+XSrp+7uE!oH4a$rwZI$7#>VFzOv}J%AEY2lGa)#H5*H(m zAQC2Q0hg~QkFq@2v;S-OTjsPkdR!U@AH%SbnOTTjDif=aP_F- zsiuZ~@ff9NqjOs*+9bA|X6>K#@U~pM7`tHFe7zWHrkRHaF7FYkO{#pmbh{?iPGb}- zG{Z1x_a#;`B1g?+z3KMvtRCET%;TkoA28`^D`!O!pp^b~=;SqJSCf9q! z>n*yr$vA%;2Ew_`R^KtuE3>y6_w7=scQAAmN4Kn> zEYrozy@ls8Sm1F`r0%R>;Jf!-ITHS=_flXCJ_ciI*4svDyrn}X&!a4wKE62W<0?)z z9V$jv?PIICC)=~jZEE5z*`w2p87-8Gb+129(r)!KJ#1 z0H`BiY~1o7%2o{R`r2vF(|hU7m(8@a1j5!QDrIUD+L?8V+Tq^cQ19ZM?UtLl@#5x) z6$_>-Ymwt+BJTbW82@6;6L8%oBqY4ppEOofRBQxM3XKZ=d^R0JJ3EvSDYDMR-)kV6 zPMJ9hl9^I`**W$X@IWAv#+CY}PW+1+Eu zt5=SVKt3^=`%|Zq4K}TU{@#503v)Ktb9Y)_zMWAw-&2YY=Yc>Jgp-K5z}%oBG@Z&g zd>hnXsIoT}udM-m3KeF?Y7eyi43}<#Fw}JK^f7$C^$Tmm`lEZ_b1}-jzdr1 zj(=Q{R}+H&F?&crM6~Ha{!;q-(owk8l~_*bd%^7ov0x!dRE!@hNoPuxHopLA7bxaV zeD|#Eoaw`usH?B2;!|rS)J6v_Y1zbXVx_aibB7@0`o|WDkl)A@rizXeZSeA6LR3xM z#|y$(KV%Z~5Qr#gRZ$=#mZ(Qm^Cxhm0qsYnX=G+Zm*RvLf@2KxR~n7~b~FPg#86Et z{&(b50z3rP(C{4*nOc81zQhf(6glYK%9vM=$ScJUn!E`>gr3$A)%(#Awww7j9n&}+ zb_38k69H1y-H2#=XSN0?<-_2pQB;K;B`glqOTu&#fs2YEMLv+r!Lu< zWUY=uYl;*zfxZ4W2iH~qYkGLg!rIU5=<&unh|$i3_9|3QR5ShgL@@EHlI`0ASRaY} z>TbRx%&@7_{fciV5TQhCIhvHNXE66Ra|>~*ZVIPe?<{0 z@UuIZ-O)F9rC<ld87=3fU#I(e%fut-;@nq8yVEyv>O)ULN2fKWl$Iu_ zf1|UwKVd$P|EH!-qAAYQ)d812TVjc+yZVow>Zv#~ry9%q})VS@_(1 zQ8<}5GY=d!EIsb-{7H1z1GmJ%+Mm02sk+t8^?iSqv-_>rbH6;!E04RYcYfE?xzo78 znAJ@8y7B1;yjk)gD?L7Vdbxk|hF7~-_ZSNku(#gQh>a-^i7S@W;G#+jYFV0+k$+ic zo?MNJ2j#{BjS+Rjfy@-jxO!+&qqixD2R9Eh|MtL%Z)Q&4Sca)y%cMEEXL9AXTv~;} z5MhTw)!Z^`r}~NCblXF1cQ;K>lTsX&%93_QE~Z`PHazC>%x6SV)1+YMTBRQY zc2UPGsSeFN(PHS&w|pvPzLtB~#*dfXO9>rYZgQ4rbP}a28(pae2{NU3-(IJQjXtK_ z?L6;!KO9to?~uj&gW4`p{%n-le+VKCO20nuoe57`ah;p#5zKL#2(WAQ2MtT>DJdPb zRT+gF^UAcT;S`W9$qYGgRH-cfmZ}I8mkc09l#_P;aYhdHTctn$*X9d`(Qh2ohEFdq zNM2PAC_3m2QH6E0&=7mvy^CFSmHWYwy&7irE0X&nJ=cIDdFU%bI3wj$%6z?LZZLG!s=_)( z2qJ%kV{$*8iH&tDhnJBkNTl8`UYH?ecClh=?*|>h^yfJ0W*)bRwY#7BPcQPePmL(1 z-c5cG%xBZijLPZsCWfGmD!dy^yu z{~q?6ZGwTcUk&tmwCt5j%vRi}8ODKFv3#%P`s3BZCs52QR|oacNa8!@YsoYmrAkJl zi-5N$-7G~*Uwo;<{x1t~$ol(s!Sn9TtmXHegfT4XJ;WqL3A2(CU@~ljrJTzhez~57 zB4Jb-3~VhdknUxHKHVI7I;;RF?47c*qTC{uct~+Vc>VFUXRVIy7EYRpp_CtVl(7<0 zqBW-uor;!j-t?)X{h#s6az;g^U#KwgA`VpxmB(*c?QZXUwiHIIZKl$Z(`{1pJH(D# zK`zIH=OX;CRDR%NR>BFvoL9 z7<^6cKyO6veq-1DhLRP@pwDQM3^u**jsyJ%lA(I2U z!rxmkHc@dy>a#?f;-08W63Y}vd|Mdmcf-o@!E@G3CGK=>Z6lv&ssrbc!X7cjn3x|q zSuA)lXWp^%PmMe||5I#gH0y&8n>AA;z&_HeqnS4!10XjyTz(IwezL!2jey7G%>JR-kwzTh3 zYH?8DK>h4&y$d>|hZJx?ugmLx6&d5^@FSbF$pj zvwA|5InJe}shc-<2)3YrunpkgR4)(!V@&%v%e5tVFB%6WB%IuXgMfAacF=@fx6L&g zM3(cF~d%B1gVbi-F8&IuTE^|n(796+<`aUif+GUFkTRQ$)C`sbNT z!q}u*4^pg5gL5H_6J;=$5zoEZH-Iy35E9a$+8Y6`hE*RzPZQKj4*u?^ujn3(E`*Jvsk`5XE3&n6s zn$5Y0K3PGo0~}tQCj*2}@Cu2vN|oxTArIc?@*L74iqvs-PR?LVE|ISkr$I5tt!tgu zulS0QlNP-|r36E3nF@lA#ZWMThI&e4bMwH-ByEbno88*_Sh-8}JuRq8zr;*-LM8?2 z<$g&Y*gL8i)1^|KN(b3Grdj8s%CcWU|Ac(G`G5j`H2*wZ2K&7m#*2FfO|EX%uW7=l z-eN(h!db*>B!7;0GHf1URgQMNu^JB1K1jr9Z$ApD0(oC7gzP>1y3&^45F~6vtJwH9Pq3zYd zCND^^r4uaZ5)H>l6B%aF+99J34&+E$1+np}Qafqt!<@D2o1J_y@t;rO6i4f`=h(d4 z4+HtH6zr6N-HUya^_x)_?G@5GvrJ)GJKdI%meckg`-!ctK;{JxciF{J6$YimK`dSY zKEsMEppTN)O3F&?(^{FEt9`iT;pc~>pd6^BcsC7P{G&VYMj3WM{j4_E7=xjb$IQu$ zjMetyZ&nk`eW9hJMM*d~4r$LiPnsC?#h?S0XThY6BdEjs>Wk4zm{xROTtH2;t7^uC zr`6k7CMBR=E!y&3!$N=Sof<+{q)SFcN%%2V6tz;n*}dPJw8(nTN#!0*F4PB;E|$mG z$3kGwW#d?acl6H($ap6lpp`1sjb&1+hisvhlF*<5GlVpA+W znf3lB2%lf650u3gmmML@}($XIt9ZMo&(1K6_8$L0o8)BYyw>{in8(M;#{I ze=V_)JYy7AE;17Hf;XwNC~q>N>;PSLnv!AZt&NRNp-a*sYegYf-lO|+!h5vgDof5x zP>_IO`9h~km->p8RlWJi^GHpN1}gu|Rz@kBhd9fLZMl?hS?o5?1glCF#e^hD^8EMG zVNFMiT;VDOGSse_xt6YGo*Ip#x4ZoHT~N)XYS08`1h1JH9RnkCqKrAJNjk^VdnV(Wh8XHGM=&pz8*7JFljV*y#^a}UvzO+Y zs(j(NQ}>u(cfVPFfHlEnDAyO&q*eT>K~QbtOiIXzE3@CxM$KdigMXQflem0DOS2ifjj^%%TNPmH6Te_141NKnjB3|$)boN$45~;h2-GI zeHQ31Pt|iV#fEelnN%_qpKVTEKertl7B2Q#>c@Q26jUP8@(;!N1dA6K_h;-6e$Tjl z-YLV}tHm6ga48C?QBgGsVK(7KYxv5QxnO6fLgk!F&AfMe&%H2#F2M(7 zY)v*}^Z95CGLqXF^WBZ>zvXY52QMP-i#jgW5BD;{+&*J146(lLZe1ltws2`SiKNU} zAu87&A9#}cV{08nEKX6*>U$p@j;ybjyU*o8=pn#+Nach6i5QJi;U^7i`<%Y^+B>S$ zW|;;XlO~0qM+g_iIcn;Y%+JsL*sYeT|9`5~Q1=xxKcQGNWn%+*Ib-z!2Rd}~V?Zte zwwRDOd^o0h_YhL@pxj1@iism`5aq#53kUxDkiYY?9i=DjaY(=#QdPxrAtOE_#~6idg7b6Wjm?w|_rl78 zDd?1gMo@)8$Jpa($9TC;19)Mlt&(l1tSQ(yw=a0rQ#AVT8HzjWYzZL##(^*Xov~e` z13xDEWys3I%5i!1lZoVbBGO3dqQ%pSqcF57=hFA*Ot^{J>9^YSEhT=4VZ=v~!HcP( z?ulRo#Rnv~>JiYw`{Zuq5s#|UAB-biM+iq$e4G*z-0cd4TdrjQPtpa7yjoiNC7#~h zTT&kumR1TU?Wh>`8cI5WMQ*!g z;PP$qpd7n~zT_ztE^Jr6{G-m3DYAQ)AmWF*bC#2o>f>YrVF@06pkV~5qgsAjz*+*N z8_&YAuRNXgjBM!w#VWXjJ5|u&cP(7CK&^$sL|nT)aOV5(oCXQ7I_)G`%A9YX_PSC( zG>0+$b(1reXxgYA6Z$_ z@YjjbX*+hj_ZWNSifONi!4cAim3YZ_=Ng0vvguqLnF_nRdxN`|dB~lS*l1O9lZV%U zHnO+Bp9W@9FinEC*Psa-;0L6RjE*{h(k}r-hRkXDATB9W_JTT7tR5utHkz4wHsV%R z^fE?wH4sKRT+;LAEyz#TEI90SLyP+;b8H0*r|~hoIM$;Da)kWsRHSQlqzy?Y28lEo zu+t6Fq>L%Hk}{G8pIyHY>{S!;yLObdj;TK>*bby-HzkgDcmCpb%P`mHg8X@M z;MY6hFqH|bTlWW>Ol1T!v(lz?*~Gyja(gmGf3|}NuR!0w2FH*=*5)7BZ&ob^2G2=V znnzNG1-zc#-8%-`RE@OZTWfBF*_DpMHB^FqVyAI~(ylopY&J7hbw7k5|-H*W$ zJK36M{BwXMj&!RSxgc)$O5T_tw;-HYsncZmn4X*6UG>$;3EBs2I=McCFOI{5!m@XC z?k(-OlOhuG>>iO1wxN=;bPf5CWVUmGcYlG|6AxkG5Qm*pFkE6vnYnvGrFEug`z2y2 zz??T}@#owoQnEb2wq;~=B;L`sNFC-Sj0E{lVNKvMPd{xQ=ZbGEHNFz?3%>gK5&JK> z*%|X<-y0F>Xu|kPSGeNV!WHIafX#;hMs|c4?9y9Y4E=rO}WwEhBfi9cv0+Mf36cVrc zR}_9Y%a8SP>tI^J_hCAB>hu~_1=QI=DFVI1S~Wde7XB+d{;*mW=zGDJRW~g? zeNkD3(rGBnCT~2#@=fO~MBhe@C&ap8jFb>V`PzpY+Ls$IP zGu;|gZNIxt1;~fbIZO%6+doFe&tKq(|Fl*Qsg;GzAj%1^(<}a@_CDVsCld4)Z`>jawxs!SZPf1Kx+kG`my|nM}QChpI7x8}BsTt7#KlRldHN3G;S%-#9j}w!@MVjlf-YT(g?53pu1!A2=zKU;_uH%onW+Pq)ALhoW3KPp z^m89?JJ#?2VrSc>&em}X-oH@)=BKT1sK4J4dP$&;&1Lz*q*^xOa6g4tL8+ByK$1F2 zwT&=-$y2WGad$@gf%wyAt3Cj&vUIeL{7a@6@VLo(?t!jYZC0Q&ctihhFHDP_Aetn> z!cA{ZT#xMR%fQ5CRkxrjZ>DRF$hCd0ena0*pBBRoJG}4$O8uK}93;pB698stuLn2m z`dM0lnFJnMm%F#xgp6q`R^VZUXmtWY{LUSkn0W1nB)nM4Q3L4{@)!+3V)VXNu@ z+P*ZrzAy{k#nU8BG;Jxy|i?%-Y(!>~A| zoJ`@uf5+j=eJ*$|yeby%Slfk>u@Pnd%5xB1+Pm`l6cG#+?44t+QMnN-`P-mFgeo!I zWRB9@3(ouIgV5eW&0Zd7aT%@pU#9cbM`HWS6GDbL&PTcR!pZsiXs{TAoVIX%T@vOy z3%rQ7=F|XHtU%vaOg7>8Y8aG^7kl8p#irAm4PXt8s9`&>VdtY5?RZdN=Y!CI=FVVZ zDENd>ma7vkxiq!=2Hp~89>~6n?!5Go%rR$?rj@5CMLCy(7Wfu41=7)|2?hK(XPfI` z&u!2rt&f5`T7?M{gi-Ei?ty+!edFiPZx3pFmPa@mz|#BGl_lLa$9K;Dh+^H!xI090 zl0|*~0YYpz<&+M(AD61n0^f{Z!iy;kDQxhRiK87f1inPS$DoP+2pdGCnXgd8ZG?(g zQLZnNn>}s$cRxmyPb?Q1TRlNr!e9Mk#oa8%P-aqUxU<7C8C2iAF@X?LueL0DF{Q{4 zvfOT*QklP=XvI5W_Qtq7%PgPoJdM~{L_`uVroU9{4srn?_^%hc#V0gYj9CsgR}Eqk(7NFeEl_NRnP?Py_ZY>iZ{4yVw*sibg3 zv;<|EL}tmMuw-OI3MVlbD4G%DeAeF@<(3?oSy}4m-m&sb!`Vx27Bh!7pZpZdUAZQI zQyf1x8W=1fBq}ba#_QNx<%`uK77XmCR-k*h7MtQOWQ7Z;ChDB=5Qp5ax~pD_``Y$&|hK-hyM$58d!&Gkf0q$1`w}5cJ&?_lk`^+fU|at z`1PDv^;h<#x!;XBP;BilcNN+nU)=5sg&xR#Z>Dq48~h#{gp)oX_lW)#zX-0s*7lgM zEZ^IH`=)DV2J^rALC5Q3$2h2B>|Z|!_&g+mn=Kr%cPE6{Z{#aWXB8nw2AF7lZ)$SS zBMqL=lQyr8lKy)-Acz-E7OhyF-%T2$pnTvF6r@5H11jl%Q*$J9JAfs)q@VslaG%Rx`Lo9ShK|TqIJJ48An)z%6;06^bDPuvnhiixgJ3}Pg+MyAZ<8886ghZ$M(lY|(Q)(r)}#4$Quu21 zh*Q~{j{?H1|AE0a+iq94R@=P(^C9#*QhBWOApa2&K@1VBfgkmF7T{Z!={b_B0m;vm z7B?VVW#wdptOxajz5>B#zXr+_ft-@xV|svG>@j@e}sb(rcE_< za1Bu`RJ=Yyru^z_8K0cY>9_#ZrWk5I%{sJkv8(hzH^8E7Z?J+ zl9DZSAdz=w9$gMDPw?G)d=UyY^jD8Ka70)doH%)Z-|-Ur8a;Kzu=cufdcNw`AvHD$ zQcTsFij!q04$GHX*`r&_%~2QpCbomSh0Hv>^BY4(!Lqa;vl->}bVjlL&JBD;+x}9d z4qp)ao)V57f*|3^nZe7`>n=Dah}Q1+;j*}_ZHU#&a=$xL1zNo9GAVBA;w~QVf zAi#w_0)Hk&Jw;11t#ta(-rIX<@-xJz!G}MwfF^EmB3vw#$4j zH2w+kDpJM%Mel@Zo-)sG`L$Rs3CW{K9r;mD)K9#aO`&BrZ}x;mBb_>PaD(TDTQRgU zQZw#zMJEZoWdpyw(zv}CpIYqg{h$Fr{SgZl>yD_6;pYB5$Br>(H$Yw1 zG1z)o#EVgWdbm_N;P{#3#O3yFMf{P<{1+k=-zauaM)AFb@0C{vWO9QQe@W*FWL=<% z<+`%VEN^0!=7q}G2#~dO+IpX!pqgqWuJ_}Tpzn22^08Jeq`lTB|GjswZyTJ3jGuXr zuIQXr*SCf-VwOVSW~?}YI`v-@&C?Z@GK#!n(&pmQ;0X#+-}HFW0=9$z!YeJN90}vU zYgh>6i=vYC$SC6<_4NE{tBcJA*jwUH1*=x}d#i4ZzFV;OqN@XNlDy&uuJaO75#f(q zC1&D#*Fg+;J0uclh!QnxX1_XmYR0(s6camDoLh3J`=N_Bme#(f}jubgO8%(n0x#6 zcN?nlsS7CUR1E~tSb*08EUW|Ph@m5aX?85|N~PEaz(q?Yf zYUzq|NB1j=_``z^*AIlQC`wJQJI25()0j(1FP8_`t&3pfd+!*tU!z@i%7trygczbwRdkF-~EgIILj{h(sg^k0a+ur#VtM4y3Xo&8t%yRRHx3Cy*!s% z>v7Smrp>G+uaXGkz5;hi6P7FRsJiW*!8S~CejG-Z_fB}(*eD5geUuRk1XBr(F%m;i zODdWvqQh_2PVF6A6}Sj5HbQ|))!tjP$9%UV^i05=y)l*SqEd#uwA3O!T*Agank;9{ zlTtKYR?}7|(=bhuICg&0vexA?#j#|YbJ|LxOjpIow!o0`rmTOf^y(L-eMdCATNcrq zr%qItk|7BjNb!p8x!=p_EB(D_x{~jim-lO^5Y;yX{i74s)CNlpw|x}oijh>A@L&6e znYC&H9%ud!gMz8pFXnU-eKE#w@2{U9F(W8#h7Gq4V4rbL1iQu}j5VHFC>=*(6Q6Gc3eax*sDd zl&{Xp>!k7jvH-Hl>TLnWOXB2cV3-Lp#c|eQBochWqTYe#3lyYJWl9{|olr~GU&@=a zGCC0RJ!>0}ql{0KOf~R*L2@3JK!P0H^s5~bUd8*#e?)v&5RaOzo;fs0I;t2cPB*wY z#J1oZ;#oIz{yE*XQqI94z=l+bE?v~#Z}{DIb`1PpMNbX#I>TCDuDfpPSK*!Ax0%Jo_dE`|H4fu-ZU(p19%mLtZbARCDEiWI>S2yd( zm2$?H&GFZ)zCH;uZFm{Xef3|pLl9jpO^V#n@96815QEJ{qMz6%4yM75b^X4U#2WrU z%}m+5gs%t}JTl6J4fakk?2sy5q9%w&i>5}~enUOWCk6Q;`HXTepU|y~*p)>RPSoa_ z9G$AP|AA_xay5^|K={3NSVWky=&#Am$Z_I}ozxFa&93qIa~0?c{UYd-WTXsp)J{ai z8kRHGfIEa3EYQ@1nPaTNE3kfMPdv<~rJF_lrFB0MCh5)hpQJEqz5Xy{`xudmZvK{D z-h0!hXmJvJqjVileay=CY2#)Gu8SN$IYYKs<>-egRA|M&GB7j7 z%a~hmJ>v;i@_+R(O*S&jF=2E0S+Ub}a+-SR$!p z6GaPygTuA-C;QZ*^>_b%&Y|7s*U%%((gfyk5uk*%qkv3blKU|WmU9^w(g@nX=*yp9c{pFB- zXsxfs{o^a)=7%ILL1;#$(D!d!EpIoXWN6^cGj8D9f5%6<|6|>FJtbpf_si`gt|YmG z4KTgQI5hO)fRkdcSI zSbrzUkxLnG_A^t_`@Zg_zE}z;%g5+B=IyTZg?p@~PQW0=WA~cf*a9JkM{gUxF~{Gy zCvUE21_EP}uFEA?qg}ds@G!+Z{UHbI)7qIa^i`Fjo1-WI&aWMR*7@mZXqrr)TKT87 zRlZndqe#0iOa9JyIH*0+?OaG~WIl<#Y~`|Yd~<3?&fESJ8ibj~bA`6f3n5nzJ|R75 z7{=YV?XNx&mlD7VSXfzLadlmjM6rs2HkDo;8QR#$-qF$VXWZvSX0(_);b7AYkg4gQ$IZRk z=7|~iy)oW|ROizQ2AXBkb1H?Thsbq5fR(FMOd5NQpc>@wq5uG6Rvj3;|b!(Y&0KbBF~Z6Hsmh?#%>yI7fb7`0cJc3NmGvBT7n@e)B+xS{(N7Y^P|<`S=op$P ziQ5ZoI~CRhYaVnW5=Gp<|p=3r8A7@ zrjNX#U9hAIlz0dUvc1Z)sMQ3*b!rq!!uGmQ--XGrH~OQkfq^I4)*ty1ByM^PN_mMy z7-h+@c7}F1Rnj?9NG|RcRB!09Dz2H>b7hR8AsqN$P(Iwqm_{zQc%}9Qzr)lLK_f6i zi&n22Ie9^=~+wvMrFd_7%N_E*&Ke<12l>(C6hs;G!wxa0*Y}-dxf)+ zGCl~-91$u?^R^Q!cIqw#`UwKQvNPnol zd&>T1#U>SFYqwDK($Rqlgdcdu!zLas$=-DDbDT7PPauRkbL@KS0he8Q>A8%mb@ z_#ZC%`5-l^p3D9d{QAZEje?zCmN{+a*X3UqcfZEV++e-04nAl$db~59C{bB76xdIY zp;U$rD3hx5Cy@tkfP>qybm8uo*?z)C zCd;yg8n+%f?iXPD4~8T9`T0}DO5O@A;pa~{%E_n zBFMj_Bk;5%G<|TbrI)t#T=!0}rDHc2@;TG*?m+0j(pPyV_x<$v3CWv6yZ6R3Qb;`$Zg_tg+r35p`!qky~W_zpKAy;q{gMlU&zs}Op z=@I&@Xm2X{%c_z*%nHfJa0gb6-gr~NIcj7+Jv?eo&u7xd9mG&6DVXngqpqoD*J-+R zvMuT&#Md$*LPe_lX6CQ{?rajCOtJK3Ps4k$7FYf7CqZ-g7oMAOIRj$3UyFtaQe!v(bl1#>50kZihqA&j`>-Oh_R;G-c;R_uTzQjeE?$&8Zp zIn!0wz;5!qhgxukvSu@zKUOXyn5;;aVRA+oV>CuWulRBI!El$9X@i7p=&j?u2gRfq z@y)@lr&KIDl%bO)9+TB7O#AW6s)QzN(d9KUWM z{!7S+Wgji>T}C-}DiZ^SzIG5Tj%V|=6X(%4{Jp`xwYwFalkD`hW`93IZXLpyp)Xd^ z*ahgF4)1Ir-RDma%_R5NU+0`q1>nA*X|;IAYjXTMJv(^b?dGK%Slhy9A$My7!zY>F(q)0%()FMqkBYZfeDFK1x` z?PA?2x<@m)<0R0W*fwVS`3mz-%l31o?#$l({g(5l3;KNK_w%UJ$vpPfMwnTlB2%WJ zgJJxUF3Ox>7mEUgRsm0{xv3!P0k+w1?>Obfk( zSM~4gW>d(rgc2f(1=~(aB_5TNNajd|ZPH3N}{pp9P)_i?13A}hAT6aEb z#1Zt>cbat%@Xl|{zdVW>CVyoSWx?s5W)$#(6&=ShZ1)SL8R1JS?V}lgH+P$NzFgBC z#ZumLCx||s=}1?%Y*%+s+cF=C0&v!g$4uFiI6bas6zNC0A#vE^M*r~1?q6upQR66( zVWKAEp4&EN{N^|MuMdl+E!onMv+dmI7%e*j9oPCg9{@`tIp+pc}IsLFbj> zO-d)#)p3GT)BUbbEJwgYwB-;w2||ta&_1-m;_cmX*k!}L zqFuiS3p~mXUY#p`Y236lQuPOE&oU#Ug#5Spp={PVD=SO++swlJd>Z!Bb5NfHA#C8r zfiyoWHHWq@sWtYB{_T~=H`$nUi9)T{e*GJ`=Z5x_DbkqUYoA}gx=U9_{e)!+aBUeqjGhBi(3BHyFYOOo99UrOc&?m=T$-kKO}MN% z3ZFfXQYRv`+3h)B7BFC-1c&z(^ct}id|q?=2EYs^Y%&5w)TzVq(!HhC&*a+WfARgV zY`j0Nh0MO@Y&4<(Di)AyFD}>`zO9(CrB4uFRWalS{XM;1SY1u`WzKb`h-3pdoY~|r z*w`OYDdPd&lX!$MR;g=wt&sc4??=$NZSaJair}S6g&G|w9jg4A4VQ1T`|^bn6VYL3 z2uocQm42T<<7_kZr8~K@M&Sfr%Zy|tqafvDUPr4FYr>P_5V`r@>3T07NU70=! zGov1dI*Asc{xtY?%Ojg)_qHmqfQYWTfJ~MyhMsH)uPaWR1yeMow~Q~MSDtcP!S$Y) zX9-Ew#h-hC7JcK7C_~P6Uu3F)*9GN@E5$3VBeq;00XgNs-s@e08r=|Z!>9>k3&Nms4oPI$z@;B(<^mbY3=HS%T~aXJam*&l zUouM#p0iwk4XvJV#S#hi&nB3t(mot>B~}4|mdWwr7yWOon|;H3BjX=&Q2;9~b---z zKT7)G<(~K^F8aL$)CNm+0SO`$hMu{#6NU|3DoqZ3o+Vm$fiwknm#d4SHs{|4gN=}P zx{MqE$u!UwIZ{rW@X{{KhQS$IX&cwb+- z8_A)EMp_&?q`RcMySq~uI;13}d5~@tknWQ1W(bk)davJi{r&+L&YHRRoU`}-Y=MgT zh>juw_m8n5!d8oRwbvKSYerGo#9EMLK@)rT*dHyY-0%Nh5I@0CiMqC&9``+Ya<$K% z&KZ(rO>~LIy|S+}I4VFCTk+CDPfzab)!#49QK$;+SQ3NO_F=)V=4N#yqEE3@^*5U$ zjA;Z{LE*!#qw)3`OhgTk1Soh@VMa~_udkj$`m=b^OsOE5nIC%!S@F_wp>yYc{{ZW( z%NGys@zHBfV|@3_o$FCptzJQ9%$>>KZg#;vf@&!Vrg|~Rcf9z|cwigPuL0+07=)lk zlO!NQas^dpBHNM&V-`k(p}TIn9){MO2jjf?J#kbn`<#vVs5QSbcOIK);Kvs=#DK%UlpQ%qQ`L9#X_rDC^!)xLV{+ zf!>qq)0sJCmiQ#oTP9mph>buCmhe-KX=tfgx%D_@h4KKR+l-yJ95@x6B1b#TSqT1y z^d5g0ycCdke-B?;d^XBBY2)#Ox1FL8iW@Q?!Iv60XQb>3K#td*+)P(0TQpj7TI&guS#dn4|x#Y2kJ;gw>^ zy}_8$NIB7=;v&IR{geglAuS7*-rkAhRqx!E_%ANClltDIlz)?DNjAx}04wSw`+O2H zSxv6<#F$C0pwc>=6R?OiO~9_4C4VpSa!1$x%>Epd;X~U!a)d8Fo{|5@>v7iZ9U@H# zJ}ONN{8o}Q3mzj;{M7dk|A2`A9mvGeGE%xB)O6*$K}Q5WR%*1Qi!ctFsC8iP;03w& zuI{({7SDq`__e}lYJt{8NGoOu-bdR$_9#%o=$h+Z`d{tzNfD5JUsx9;yH-gKt3gC%#pHIWnLjC;kf zVGGH!6%*bgcmEgm{D7x7QeRvgQM&n5g<^L)C_4S_B0{%9K*b-(>OQe-F{7V*EZ;V? z0B%;Is69FdacZ|~+H@3b5w2xVA%kv&6)9=4TDI?X6Fv|LF)^&qnL5~M&mZmPkTLo# zJpv^v*Aa<9qXldKsSEO3xN?mavhn1RI5;?89LwN92X;JA0S>+w1rveaym?$ zP>Kd0%AN5K8OTHwyV;W}lX%!72y9wz?z#*Fsan7izp^#5Ook&8AO( ziRdCs%8Xk&eWWTPRG2hQxAj{<3x9l;Ab;c))=`)&ik zLv;7h`KF_@YjPTrF}c9JPXrNQYG~_}5+duZV|(yIk@?Wt+Ahh24+df4#}7nH7DdOz zg-6*7%2r41qYYtW3IfMm}FRNCN^q{ zvn|gbPm%;9E;7$H58E_V-UuEpei63t9aqKFSe5*2y^Q&_9bd=*4m24|%|gwzm;gA1#fiFk zDQJ^X!%Z`;wI`Q+JEVm0X+ZH8K=0JEY2tkveP_TEuEG`5KE_aepN~)}&`EN(MQ0($ zkSAN$)`TEy!R@|#i3BhICK!u5+qP7DLI01_gt33&=BPw=GjMP!a8rlXF4Lx8BsFH@ zc*MYIegYFJbN`ul9fJ!qS0gwA6QF5jXrI+imhe%+(kO#BxUL;tZ-ggOAFaCx>I|c- zS|-JtCS0rJc$0hHz6A~Tcv9q>poAO~oHrGN`<$(9@_4b#to zBpDGHKUQOi*axtULlSz|Uqpa5s&1EPB5dv~MOpgP?}movLS$TI@wl^Zl08yX!GD}> zMtt&p7)rtsVpvDV-lDIz2a<~?FJXUnaoD*1l@*5DyLG17+30Mf74VlH7%5-^XoRkg4t47A)bY*1?c+iFU+-^`y}#8x@eSO994=-@O92>U;%z=pTp%rX-!Y2pMROJG% z?Cbqq;$y!T>O@M{%V)|z=;-Tz)Oi1L8GJuElrlC~seOOei-U(43K+5}gYPrFR#4tp zHxxM?{A1y5?<9)uudn$R&oBd-h>6N;?bf_e8NfwRmLD`SQ#M)tWpt)1P>{e~3yh*1 zxEx?>6>7u#nT-{-aH#8PoA}S4zqF&=RX`hXN5aY7cPqmW0m07VLX7su_?XCDL2sV$ zZ1le5CzlGHKKY#H{>?bPquhbneuCZJe)&QdUB-gcaJ!h0uY(*ezJY_$onhcN%E`MD zW*mKmK~T8qU%Gec8}@bo(MGA;&|B|L_+&NLOSg39&~_o=3@8m2DOk_C=!vVc*X3Jt zBAx*hMuD-($%cQ-xozNFi61iUB33yUKu1H^dA_UPcO`_Hb5Avq&@D@)#;jfbZUM-r zg==suoK!iEq;Z=Ej_FY42WbN9O#bMqt~RHc zOyW^xW(eU-U#lV}`|yrb37*nPhGDiF&gYAkiIOEN?K6*Aws~Lj<*#;4p36a?p!QUH0nzHh1fI9UX}?1Mp;j*$A35<*(rW%;6vH39Q=`4FBf^ zhe0jAl^55~Y1;{C*ci_69M(eD{sp88jb{^|L22hP-^ zaGr=?UuC?uPP1G|K%dWd07G-&wG2wb;TICR5H#sEbz1u|I;ZcgGi=SN=h?GG4X8@* z3e1j>*Sv@)LnU03o9>xzMRa-{(rgk|hQzaWw9>fHCB(MYpA-KrPol4b`P26AmzLIh zE~N=!sbGQ(9iz@)m)0Eo5Qr)7UvoiS-uDsT5i>`v^Qd5Lz zN^lEDGY)xY7jqb9_n+7ebxLNAfo+hd@xS5}QVY=6y^pJ|RL)Zalvn)BX_=SfRfakr0qBXT#xE(qD>KUf z8>ulj%@I#jKYXJ!*XnK`U(zp>9Q`?J$N6Kj8hmG$Yt{7T-0=bkL^VT&=|Tvl0#G{y zYo1G@0v4veS@tbX8e?zor;VRcdoxu<`NiMTu!SEjp+am5!&!WX!orC(nFt#KZq`mi z%IYtV=mEqw+kOKfEEf2=syg$QgEHEJE(Jmh1`HU+^Pdm%>(7tg)&Mb&(JG~XUDSJ{ z8NO{VF{!C!)fj-nw^gfny&IubltA0tAIlnW>YvZmvN_rzs9~0R_StN(jsJG_vVn)@ zmnJEO0UL-RY#cG_>xz}Ns_CdmLB$nnAA%%BA|hV3q?WE)y6g|MLa(GGy71!=n2A4j z^|61W^Uw9o;Z$pjeQvgQ?~-Lp#Sm9KYlVqtn$gO|8(m1a3OHRIK7S6S^N|e;UjMN} zlg60HOhtj80&ifXx0k9S@@>fm7cJ_3f^lODW#cgprjmbl5X%8!)+X`rvw=%BRfr^C_STP$XF|k` z0wT%ew-Q^N6`G$dXqCW(jBiygw}48sAY0059;S|Nf$tFcRvdnw0mXe zzdUIJ=01;)jLEV<2PD4}FXX#sG^}2-NKMFjzk~74ed6%iMX$;?Jm=DJ-`w=SWeb14 z>H`zA-){O}kS+PD4E@v-ZD=FHBuCI(#SKk#jVzQE30yx8h3yiwml?hh8TRWLcu=4e z_LCIIwX(I%(qzGs4KnOOnyE*#q5VokOOmkZ2OmC-YF=obNyj!SHe=CanpR8ntHF_F z4t;!thU?R|iFc21I{%?bv0}x|HRVYmj;s1U-h^p4RkifOBIY|D)KbTwvk&KGcM?*aSKD!(;s=z) zYn6BgD9WZp4-hcLi0!p1a)Nmp-#rw;od(`<1-~%nCu5;8=egLv-4-1*5_`7S=CHw?_WENDizlQU^k3_n`hCj-t2|@3)pL4@1QaF z!Hug@Q~|!^71)ACj5~e*r2{8Ak`B{PDKGFIsn;vp#wYJyB2@79@5QurK9_5^1|gz# z7=v6iLF$oOR@X!DONxKOD$Ji0Iw@PYi zNXgNqb-X~nbHNm#<=Rz^05#D|5_#Gsh6#3`uoGCvN_cEWJUToCG;<~wt;~lN;SS!h zh8}MCREL}Ewx**^WIa#4>@$cyo^Rlz$zGud=LK9xjI3j)2B9o9S7eON+5y3D?BMg@ zrzF65maB)oWg~n93cL3*A-OH}_ z!KJz60$ni^B4ScqvM~8@Lpc@I)T~sxHhXQWSE8bTxN$!9XMB>ph`sK}ekpdt&iG@b zrA48FwQ_D!EYp-<4GwJP5@PDnpNod-|5UQPC;zz^5dRml_&L(?M*!fK40zf?==8gw z*RT1oxUvRlDhp_K;@fqQCB@Gp(;-e}C;p3m6SmK@=WQ&ldB1EN++0+*fava^4P2Iw z&gQeAw+n;g*D8U_OMa1`w{VxSu}>LYPhDK^!c$YZDftSSXh!k>bzi!SO>f}=G&_k- zSs^0eeixORO7PztS(^c+IH8N z`2$SO0p#lU=X)~Ow?KFntIu ztH+}-i;N|oQCI1blesR@N%JK4#NH*qug1l+3-T^zqlpSDj*aATaepvG35OH>@qaG@Ftyqt5%aXH;zE_{XUF1dXV5?hil6uS_cp} ziZA^F!-0Xby+b4&mK&t)nx5oGnZlH;$j}CCWc6(M^4`d$_?h2aqHWlutMttMt+SO| zM*A|Sh#!CvY|zzUKUNA@V8)L|SU!u0e|mq02()Xc^$&4u7QL{*A>pS~5d*HrHUS^VehRco7!x zrYsNpZ=>KX=zvSmtKktFPEyiBO?<$(;M2(4&Xg`Qp?S0@x^nUOwvd?PP%cXIIB7^J z$K1YO!Dorxn9Eh4SL`sdU!0hVD-8J1r079_QUju-P_JB=9yE6tykA>*{%7b@F5I9x zt2BNEDk)A~fD?YuT`v`_9R9fuC}gd}kdKcKpoz^m;U0Q8c^GEA6igm3)FgwUfOG6@ z-T$<%-4E_;XwMBql@AqXy+^Ca^H2B78{cH``Ol0K{^oL+Zzp=+mn7O87Gj^WjaRIc7+79d zo8m1JBCk@3PEOg%2{&21i-SLUUT4NRKVPz|(3T{FF^Pk=#$Iqc1rOD13q>IpKxM~)p@5*WD3m2=$ZOk}l0smwq z8){z@^{`7sI@?wz!-G$>ZB~T2TBA;!3tRV4CMPd&#-oWeBT4vWRH1188e&%jWvW0; z`PFwta)l|RPm3R)ENg)(9abKQA%#WDgePIzWiE}ixJW=Tc{ykG^U(Lf*{Slz3bv{A z##CCJb=Msby^)VO^4tOnc__UWea<6{E+cGs2iDg`PP_nq)4$-TaCR2|J`5w^Y8s*1 zSeHIE?%p0e*iD@H7R^@NESV&wz~q4Mxl`GXJ=#(wfO>Xb4MDANnlpv12r(?8h>KTO zIyXhwZ;i5O+C>i)7?EQ|7E?#LNv`oMN#EmlYkcx6;^N2)h@7i7R}PSK>^^sShcbB? zJMm35(}frQBbrQY9b)W@MYP}_Q#d_dX*YHSPLfhs6Q>e|R1<1B`&PN4009j?2DLnP zy7{IbUm^Gn{*pl+z#@;@GmnExi4hI&p zQ0Rzv#-`aVjW7NdFv3Wlv7NC=PScTL@NoTdQ&b!UNF17k}g4MwI z*hRoocUCi{0t}@8fwEtKm2!CFM?!!ho}@O13z%Z|!+`noSGRaFBK|pKOLkEOWrB6b zr{S*wu*Prr!B1#>H$d#}e(T7fc%VZkpUTZKsQ)L15s{8|$tJJ0ypE0CMO@#cdxYSM zP*Y#p9SrKuu(?9SG5oN&w6=9NblcM9drYLj%E|lLjBLW-)D9-inx@OZ%@bIa1-RiD+C3^~* z`i3KE<^mnalnl>7IBQd`peVpk3?Z}z1O^|WP?%p3_NiZAq1wMI6W<3JfmAb7Q@FD! z-gv0()afmt8$y{Z4;rHo3FB+Y!2j7sSI5SLM|@PpJrhcg_^h{ENFfI|KbAIzUY6A}5{t~D%ruN_m` z{2^QfpYkg$J|ns*={q2*)M{F#RW&(Bp#!?gl4NAKSYpPJ=VK#U@6II;P zLjU0R@4Ywr3Eb9}=}P;dj2B=HQh2*r8! zAJGTu_HdgEHqp6b{=<)#PU_=SQ~I{xdG;Nxl^srwmPGYXX#fb80>lJ}#vM|nE)%7PqxDDeu z8}i2GcZ5r)157|~FmOptlXvy-*?olR&O5V9-re{HmTPn(SU%_Am&FLqnN zCoGy;o`fKEJ=pSeynVO5T5xiMABN2}iN~KPJBA361zV~$8h$d`)BCiBvo}Xo@<8q> ze03Cbpm$PV`E#|IErULpmN}+KY)p*S+QMSYwaootYc+aE@l6icdu4P{2Rat_bBFYH z{k7xu$IRA5?#gP1`@(Os1jl*BA8Y$NiNV4pclt&~(#%q{hh+4v7@phj=R|*U+Z9IbHz*z(NmjngI$TFn<6KSD!qUmX#*84X}s5p~&MCkI)8^ z`EP;PCFTR4`|la??VB05H{yjcRr{ z*fv?Bii+s|ZnX6dcHL(_cLWZY-mMZX=n*hB_$9el@fX*l7r^{%g*P*Mdl7>CkBN)} z&XJyta2$ENA)7$iNh2?7xCl_4TcBP+oz$A3z=`c*SZTvLDE>x`u&$+LG*{4@i3sD1 zyi`mH{s76%&CS6za%=TR*lxt*?P6^3ID%W0U$>~ z;T5o|QX{5qhPq$iPQ0>RaTU{aO~ve#7LR8{{N&44EQ<-i^W7I$2hm0~ljpA4ZEe1G z*T_o_2}aH#P`ZoGs3|}69@LVdT{oZ+*sX+nS;y~P385+O+1$xW!1dg}Dqb`K4EWIu z`96hvViwp!fr-$5FOJBsTOoyvrvY+Q8VEoC);|{gjEd;q@B~4?3YfovMh*-> zMvB**cG}r9I1H`K%@Ht#0Q+du2qtA;MfUvttS(AL*YxMT8TgEqfN zs+Th**`oBOI^=pn`~}ZR>5;r;Dn_xK5?eu}i@b-d%g2hkW4FRo=Jz!z=oJ?7q@r+d ztTLuj$sE;-5s}c;<>mYFRlL0J?skl4L~IHA@#N)Gc0m+|=wvK38Uj|VC#eL0b*u-- z{|&v3y)hzyg}kBbn{92(FL|O%&1Vc@U;K_>$`c;X$7HQ_8=#(j$BWArL9L7r6aqp7 zgaAl3W^?mBKoqlWQJFYk(D-xSHhLU8zdBp)Uuspq)w*W&bPof8K>u8a>_+WF4-Wzg zqocN12IMp+0_jG&%uxVL?Xk-*-{1Sx)x}4QPzDuI{l7+zuE^gER-%f7(5yoXjfHK| z7^Fa=DNd{T4GwsZGL`I`COMv_h9$Pn)17uAmz0t2gI&efWd}GZz7pJstDt48ZZvwi zFVvc0I$|V@76b|!UyHL4^cb6!J<2{l-jU>j0W%TIFG5_bLaS^(r|5mxP|*p6pURCI zx(7bsVQjsgqrj#VDi9?};&`i;AVvapLzKhEllpjr)69%SUsxbB07WY#cwh_*YJsx( zpynzr;PonczpVM0?bq@ngpey0zGr0}1r#sm%k{^uf|ZjgiYthat-DW5PXO($7iC>X zL%hdkTK0#<#Z^fGY*)h4tUSI-5$&NF8!e{Yx6c#UIH$p(c%vY19N#mW4B5xs(a~8l z1)IOFzxl14ol$ylbHRidNZd=93HA!seXe7xtDxg!`|mYX?mj-zyot#I1BeL9?Q|kf zbB`7&(QXxzUu+t23wTGMBq&iJN*sv82UO{gVUh%lVL3yaf~1NbW1G8~MIFNJjE0;k z4$YE<<{tP(1W;V;gq^K+5j_QuLQZK@OkOf9E$#HX-P8>ipQ|r=O#{a@ozfj#iP*|h zdNdJ%*J(PhLTiudVkBck;(1RqSF;UNW_^4T?(SQ$g zjDxMVzCBEx4~W9C9E!e}2D1 zZu|&7#*)Bgp&UJXG8&`0lvukSumnv$GV-frvw&p9cL;x#T=TZq8&j;&IPCzd#F zlB@D53R!NSZAi8Bam2KbBH^Hh@Db262I!A0CGf7C(x~LTrvm6STg5yUu!D#vwUv5C zer$QUFcZbfC5uWU%RpPGI$xB$qv+#%3;4L;6ESUIi8=nk^%vLt@@p zYlDLGEMxv8cfNhCnsI4zg*w4odAVeRKXe4p-$c%#hk;)ns{hv4p?omFVAc+R#}) zHgSXfuVUlW$+Y;_s3rg5t!zT#;Z-}(ybMD5*F>_?_57|%FWjsn=Cu7zy(DWaj0x(f zWJlu~A%PaDPC3e&{qtg3|L6IQ%9%XYLwJPAlm5jzoNKV;?JjdSQ-P>W>aYMCJ71f} zJ^V7}{T@fq0MMJdw{Kr#o|0+CC&LR;v)RpZ9l%ap?lzPtnv&Yk@%{TRWT&dXY z_wP@K53GOm7LKp)HW5}9n*4Ip_AFx}g@7-(8X*q|)3#*=Fu-zwuzl)(d@Lt;lE^bF zfmh#tB$ZF&?mTt>?c{#?B22VToHX){0E~$exXmPH7e7meGb9_y;ppYBGenan#sUO$ ztS)<4BpCis=5L~Qw=R?f)+Tx(Zn?yzh+NNeOGJ4f!{IdNZ|+s1%HYwX<&4JA>oMr?`r3GWzG8T!}T%X5&@(Ls4~!2<5V-+Jxx>e5|Z0t zsO(1p^eW3YYYJH=LUv>5onAJvSW3`OrlXC6@9C?LX-cRw&ZpIeW{Lu@fLTyP`T_n! zKFwcdfsUkbr~Dn$A!N!-UDtAUU5!pE~zA`xC^M#XIa)SbZXVlF&aO5 z&I#xIpt&c8H#fk$W|OkSDiR=M{9OwcvkXe`t4I+0edw_SRA`=0bD5k4=AWE6-gr^E z*LL+jETcJ9fV0Qrdz z8Nm=eJtVD#2F?xa#`%|_ElL091znLHDgHP^%_gM}cT)S02nVs*U5lbVx}Px0cvD9UU2~z{^5< zL7HL5rP84%Phg=;M^Gm7csht1c;0E}C{GWrl1Hn;DltePk)qA9RWh+BWwfC%_lRJ` zx|UDYD}gjkPl(=QINh4vi)@Z6_%d_s0;U)t__Z)JS0=b?8+nZDzqj{W$ zc@~0i5;i=!d?&d1pz?e$&6vwB(c2g68i$GJ^gguQRG@Y$NhXm}H=G(1EzIO*eFJ$4 zpm|^2Uq5zj$Et{Qdn2kdmh&P=&_y@VDD#Aen<$cep0OrP9Q=nQTFW(D4+etB{j}9E znlH57xC310He&^AG$1T-h$O=|;9!h700L1YkHUtFdD8|+wwVeSPIySJpgl=l&nx-M z+ZSqmE|47Q)oXuYk-Iqn!FFgZsn%!1t7!jYVtrB(&yVN5L<)F&ddDBQo^Sq$5kHM! zBB80nTfPxm@e&mD&&lz)d%EN}d&aD`|IjS=ygV_CR^;juqnCAfPk`XZ3p!u2&UXdi z69JQDs%!u?6X+x0#QawP;3w?&Oc~z&YaXj_p2#7;@i2H9_BZ#3ru`@2ze6e-KK8R;cc9?Vgi&ll7L0ndWYby+mfx)`j(AkjVL&QHjWSU=k#3r^|@vUCd8e^ zHsb1tHNd%lSNt*42FNw4;NV2lk}I)%p^cIFyY^#nx?4nz*J|pNK#AKdUL1v{Mf5SJ z<3|g05TQpLr|3((tRhd%>3Ul)P)K$DjH%8Np~=RZ{qug=zWmF&t~@{>D1E%Q7Fu8F zog_XBq#ATpuk|0B0iH{K9XzCM9CINV7aX7ZDqg$EYQ#w{x}&IEU=tL;lf#v8`t+9H ziHe7EWf^8lQhL?T!}#ZLtk3A5e0^;Ui1}3NY(z8HUVSE<1)>Kl-O^I_gL_HW&Yqjh9un_{*0&;;=XlAHvi;k9~m+ugM$=hT?*a(-{#b zVBz6fUi_WM(RzwV*qp%$taeTtZR0y9CmLU-%9MQu&hNh~@_d+VdTm_)?|JY3)Xb{b zf_6P;xg8Lb6vU&KD?Ea@0-;e1(hLcqG@q=47eW`1Pd6ZO_{Tar!&CLTqh(Jfr z$c&dPluOdKY7tmemi$K6C`}3V$V{!2k520^VtEm6f5c^-vceuMC9(p^GIOVBRf0rt z{^Y%Y9LA6L_AKRX3$%`)`RfYBztmD}Kou@PNp$Vfn>wUz$)hAJ#U5%XX+NGg;g)@T z3i{+V6A?NghEyTvE-+Y_5_;+AhBMSKd!dj(ihbNsCM{%Gg9pY-}=YQC~v<$@$5=%j=J{7Xnbyp z`29Ax#MGeYffrnEM=BpmA15C7_i1if073Tx=#sygHlJnvsHy6u@~cs(+H<;o`J zJ8RID-r>?%h{NT3)Avb}1&Qwi(V}kv@a8afYG`dA>mJs~qoh==oZ#vT03f*HWh<~l zSpJl#2rU^VvyX_rJ~8ktqwPFhBHJHyY@GJ#j4CqV41-{vN6=Jas)x#%Z9^Dh-j#e$ zhF{3gv?J|o_0M=Tb}9-NKJt}vCd3;IYug8&g!%z5**~6+s9r)*S~|D4I#3LLxYZ@_#epluya%9UU31|l*IOVsExz<@W>PitR!%=;Asf7G_&1?Vs1c9v7 z>}O3HaZ3E&r16h;VCV(L|A7qWz+vqcr*mLM&M~sb#LW}%2Y3^&ch;{MHC-(RE9?g7U~~@9CB2;QoB{ zp538prw_17d$nGkohHe1C%~^tWVuyIS=|Dsg^dg1;QI`=8V6MuL!eWGFJzy&D&12u zLtaW~l77B9XA+=otCX#n@`7A}F$FYe>FF8S)bt5R6Hh)zB_4R>rM$b_9r4s_;(o-T ztZxWTe0?Ae?k^$#(CT->0$}!;_6n532uF?xt^aHevo*i@Q;ZisO^uZ-XA?#7xAD|9 zxKZf?rN#ttW(|=pfW6wBw*}M3FsQKKoHt1v5QYpE)WwMxC0F6RtUsQn4qFWEUi`dW z=V)^=ja6?`#MOCoGBde+g)A(+L!+YNH};;~p{iP~MiUpx0HuvKmn7LDJ)03ImzG73 zgs(B^8i)c2eE`2|uzQ^{HLDHWrKXzfxWXChXNX znGzkk{PAs86bkxQ`ET+22M5vlFDEL1p@l^nv&e;iF7<*~%aSnKEt1Y1 zk?+I6UBZfH31NKR?YBOh0kRwr(Z z0G(G7TYOJDZilSgeDVeX_yrFihe3gs6F$9pbIa+)QU*m{^R2D-GKf-iZ~K8vn{S@k z%B}C4G(W%II6b@J&w*$E#Cy?~+t<|V68dJU)t$SuH@8j4yct9!AdkDljn_Cl5!BG* zcD9L04VLsfp#)MyI&RnGxZ`9sY%to+bkbUfFo0W@bacY|B4G#p1t)~aPOFA%2P$f9 zbPavHy=@CV=6ikadgd?Misl5l+1gVKzF%#>=1-&)E)M)HZm-m)`4u?{1<*2TWPp7w zWmwHa2;|7qz@Xd6aa4AySG|qtl7GZSi^T%mzkqE0g-r0B44}Na`J6f6enQ1v>9BIQ zPZfRk4jw6C%@}?g8`qn}lu)`LwJbKhvtu4~-Hp;(9lOKyvK9P<15Bp?v6YFLUkI|> z{rm_F^4uhtBpyEu+WjIG7OGP?-a?xgQpf9CTl)acf$!M?-s`>StMm8o)c~hJwT-*Y zF4ly%ua7Ga*9Y~>ysSx}FEq_6yr%OmXGb~Pjehb;BGsx$zEr3Cxu4_y&jM9pB2HT? zugdR}H`v-WT?y*&TMtj7qL2PW>DtWuZma%hQ`JiV=WcgY|GR_J`O&yG2F#4`+XsX%#YGZY1S-b;f{rw@$NdB4G3V(5=FyYH zTC)nc5|IGk=x3S^Y8qbj9V@i>FjvX2Z$_21^}LfPR8OCKI|4^a@C8?J+Whud`sG76 z0$$J_1#u2h%%#PD0f?xF0f0~^0*0C|531Ng+$|_FBp9Mn8iZUh8gr?vkr~Y8P-nrM z+Sxon?H}9`+VQ~ng7Myl=rhi0M{qt$BGpfy9Qcf8_RAuwu5q0800hw;6=60 zBFY+h3j!QV}E|0Ij6|GRfpv0Nna4#`m*$ z2zN7h*#$I3k*KrME-Rd|(=jQ!GyE63$1~Hp86p7L?RwdGC2n&_04G$8f6CN1ES?D- zxj89&>fd+?UVZoP4h|Q?j9puY8&6n!@>wf5RIYnRZ!b!?0kopEw{t#I+~Ms5K!&PoZ5-;2 zN)!|8T9A=L3GKf8IlEwjuwvAhApCl%`-)*c)QTNjC2+kD&yr2U7o#Q$P*$hMkyXds zO)a5w_l1_NNzA?F^A$?mblM{J!moex#%CPTV2=Le9$%AO!LireAsu3)C$7wQZhe=)Y1yQU@lLmh9`jYbsi%Q!fSbwzNx@=#nSDQ|_!3VkL9 zoF^ftI3j^vm-)fDV|nM_337Q9&TV&I`;Gc)W+ErG9^L~Vt58hU%q5bw&}DJi!dc@B zG{NkF(Gl5XOTP#YOadkgRgM?U`$&;RGVUY9K$3XqAt)5+7kAud`z#iny7=3Y0Xp6+ z|N70mCpjM7OMt>)A$LAf0pIbMr1V-(W%=ar^4NCh%crp)YwT-IAI8Vz|Lil!gZm%mi_m4@6_0K`B&G> zy}hHV zklag6jR_BQ@$67<7SC+mtgRsKnD|+6VlS>VT#Yuc7Qeai=6jhqf^Hv+J#9o4XNanV z3y&fSWAG|vuL=48xgsM0DL z&W91;4(HZSn+$V5`G-W+vYEAC{plKhW)Y!`4=T|y)-Tems_W=diTjm|ufpF*rUXwn zv_MXXPAarvY3?2yH+Ft?hw8}NuO8ZOl{VL8dC@5j;R@eMVghXnAhCaMa*_J=w^Lk( zu8_0#%R!HHf`Tc<127&jR8B56=c=c(hEhwT$yI6XRkf^JfZ}uv^m2}ZQ{#fNZ7aB> zFCXk{E_U*tGUcm2duXDEmCtH~k3;an%(zBz)?4Kp{#>{?=Wo@<9{W2u818S+Tc)Qk z91hZuMb6`)eyq~6bToy|HGSGA)??C69=?y0{s>x7LckJE&(QMm1aWHDs89H|l4dLz z2d1rW;h7TFb=D0(3<$82kH*C_sKfnuNpj^L@cHyL_AL;0ZtLv-y-g+>bnFPggV4ew zMl-5i?k|8?JPV05WFp$HLw;bguC+BnxqjDO>eokmxP!(%*{l!2cLLce85NrQ<(hVP zMtKr-19SE@^{Xs(wY5Eo!J3=hTWEv1<`@zf@owNqgLGDX{kWhfg7p1;9bFwUND5Wg zB|CAAL9_0mtx4Z0ODg|<@zvhI;$}EN1x;KJ$_64tRrx^HV&cg$6UNZ`Q z#`+qs_0@rgtQs)`wo6sB3G%$xj+}iR(!QM3a;t4beoOq)Gzu+5m zxkf7Jle4{JPf7i}_Jf~Nc!@!gmaIx@KV7?G4z^^Fcz7$(qmw#($2QhgOd7r?8)*AP(FKfxJzW%3T!(4IF3ZG~0I?E~8hMnClHrLnvKkx4*Nirz+C@I1sp2HGNl{g}0~67%!NU4mg? z=V{R8J67W3W3TP}85fI%>k?6{$8z~_P42+PzM~L1MMmc!JU$+eRcN9(a2wqleSeR1 zG>&Xf%x9b5h<1ZL{6Na?ft?mWf!VA^L z2yC41(x|gXHy_!nkMX6s`X#b3vVk9&8=6J(mRxcN3ReP#x>-fGyKc;$FE2mKC-Gt- zw)TUoA67IG2mOb^nFm`x7jSPaSMS#IIa{KP1jfe>)Q3p=J^g_^$~~9#)$nH zL!Cd0@Y#VO{1kGhzD>SDXAK&fG3n0o6gi&?&{wkLPVa&2gO3`>LFcol8e_ydDKtvR5JABRBt=OO@?bpJ@EBhfOacS5m`EC)5eu0B&9t_$ zai~Ng1IYhK+sfjHr?5v#q-EFq6ko5Yf8FJ>v6&?sd(Zm)d)1cz=hfBd$M*`q@Z2{-B;)L8A4s~6@ zA?n!td+Hb5gvGIy*5@I7$bU$sF8v(`rL%Q^m1d@4aWROainnQQkAK(zT$xi2jnRcR zWV3v_`B(*@s1F+fsiIFiqJ`@Yw1yergzxWYl-*s#fQ%@>{gq?{{`i)KZwn{t0K8P+ zkRF}R>(&dplPOU*wA}-*U1MPB>iD+Ef#JI(V3+YdK4~eR{m(&kN!%VIz|tVfu4!z4 zK)^koti%9&##u8C5*G5(760R({6=KSmNifA&%xl7ksHK;QP`>r0*U>T9tZLcV4)(hf zy*$`5ALw43pUyMjxDK?c*98DKBP+pYL{)7>>gf7JPHr$w6vgcb^}3;v3+^40xKn-U zZuJ_Oj_HE;3){<0_VcAs3Aae0OAHJ)Hul<|&GO9#JxoZ_dh#&x4;372Nflp)05W;I zAJRK;zeFhOCK2Zej9wHo1zItLz52tsUF$ymNqvY+eqe#{H?c_ z(eWlB%0YD167t7PQleAS?D)bnUEWuIj)+vdzP>%qm@Ro6_9q)%smW+NEjt5OJ;PgT+Scf^8xOM z-!@a7uefo=dKGHHMH7)2eu_y0rFNXbgbaONP;SKmP$YRA`Z z-;`K)cR>Vhm(%>DsZtt4kS_tyQzZw9$9$}Tv@#hFzcuIjuCBz)!xpq}4Pra!p~r6$ z6qPb~3gA$W>GDn44?WebzC$@|w^Q?*rz)^^kJtMY*&qKmqgpd+aNatA=Kefd4A;hh zIdpKXWP@BcneScpPyg*47qGp$J}@)^tMZYBeX zXZXJIrqTQ+!i+axQI-3DG@WHoTurxyUkDCCCb+vp@Bl%AI|L2xKDc`ld~heYySqbh zXKgn;hua|_Xjon>^jxw?A^Q9dKOon@*}1xB`0eCxs$y5vyecSP0rL##7=l& z4o5-(lYQ}G!(r_yceE@dw17X`@?KdZ+J>^17R*xg9Q8&aj~<&cS(7nX(`nX;vsg2B zR(D*8fy5SMP6>*p>NWnZWr7j23n-KSr4{_;CIX0}K+KCvn_|OCp{67DAm_)9kAQ+A zeA`-xEKe>Io53t_hA{ZYY;CscV%h@Kk7(r@cv6ZONLfeR-$mb7G9|sZ@0jDD1mn}v zixr^u{hH9RvbO0_R<7D8A@hOM=|EKF6JMZu-PzQC=K<1gg+(!UW(mQw2=?KnD1p(} z>Dz<`F?+d8r>iR_KvCn@!SDh4Bnr@>a;(nS>2VCVZt{9k6&nh34ymxAFM@Bq_>+^t z-+$&$RxYFm^f=Otd23OmhbMuCosZlE0a_sXYAYt==+gz)9v4550M|yp%UGyUMQMOc zCUf_}s6dVN^O&aBa}~wx$3Gkx?YQL@^2w~|YTFyWpB(x7uG#i4pY&r)t3oF%on49Q z<(;l~kgn~r89D?48FM!)8=9B%b=cHu?lfR{)eY z*@t&#LD7SVAi7cfNYW`NRbqIXZklb;kUkiq+oW8y`fI~;Ykxavn3P<^!p0^!B!n)4 z4jCGW!$p~K{g<1(qC$`7cc^$>CKra{pEr#75uKM)9SFNrY8In=evR{chyl18K4k zffi3v1n5#IA^}GKL0SeFh!+N&J8DgRFEdnzd8X&!yILI(#2E8g`=MQZ;v-9BANpIR1aQdwq8o3#zCKeOzY zE-CCCrmy>7gmb3L*TuLPG~zNceXi~gLCudl4BQLk8t7sr0>jXk>c0SLLkI<0w#S=m|ZTYAD4(@o35<+FAb z?drL?FFhNk>?XD1ke-(F^6f*t8aob8+EBCp`gU}b_aG8F>DDghT^ zSM9>4RjM)eF!8#9K?S;q5YS~Ly7ik$tw`X`1i%rag!gg2Gm3!S+Zncg0vd8__q3^V zDm10Gy@t*@NqUx21o##q6<@;Lc5>iy0^sKUC(8u*zRWlX0n-L>X=9nEpPPQo(a$d4 ziU8^T5XYj`dj5cgBcBNU!ZF)x4YU3t?|j~eNF1HMK@*&(#nRB-tcZ>AS&f6dS^Gy$ ziB?TrcXv!&;C>O^>1Nxw7irx1{>Wi{ieZM%$*%fo{FcrX#{wbuq=&{>V0$&}9~|r7 zu)6DpxL{`FfoJv?%YRgKKj#c{?s1BroP>-@mr}qNMsmUX8yMluuqpeYo*F`OPU%Ln--`!kUpdq zX;w_1Wlxtc0SRzLpGWH2+ZEeBn|E`nG-z3Mc8gc3^}FjUGJ0KyIeuok<1Zow@^#od zvdkL4yL5-M{4vyH#BKAsX1>hGz?HWMjw5_4jwU}y{o;ePbiT6o(U_mGuDMycVDl3b z;NBc`xBEE>a0FakUH2jpfnFuHxdl)p0SVuUljc?re~%f5Yu=eDe9!t)$)V;_D zqpnd7jQFuUwJNTj#*yA$Y7_qA72Dd@+E0ADiIaQQ8Z1HqPO-Gas$+*M?M~k-&(0gU zElmPq5>F)p#ZqmlWU4fB4Xf&%cIok!7ENx*Ag~9Xz;M61!1xGBS$)y|#r-pN^~3+y z0*v$Er{4YEe1jRQLP(-yW&=66;Hr|3epo~Fpl|?m2MTTa|H5xWLg;tTzqz!@7VygS zh*G9P)omtJ?RiEHB3SuI_FTN{V}iIs#p(MOA_-Qs4T}vcc9=qVQZPHU%U!6x3|zYY zIX&Y9a#8ek0i)lJ4><#af0QcEZ$8GV1>5-X1IA=qA@BNr!0OnhpRLaxmN{>(e0wd| z*6(QfkQP09T#8$kx)4m8r?RM2ii;a2qv9N$r>1cibKS$>%wx6)DpLt4X6<#meRxJ7 z?O|-V6JSLDq24s4GD%0Wn)C1tYWO^lX9X5iRJ6NfTfHpmOiI0g>J0SU?|Q1VdFDI^ z9Q+zxLSN!@J{YbE@ieM!^&`l22y_=oO!Hms^;u1lOOAd9LQp+DiDKD!FK8+MWQyKk zG~U|h9A?D+ko+%egSI$1YIbCtDaQAd%yKx#_mJS}$PxzKMn`Bidd$+JHOSGiSqlm7wHt z?`o)~vd%Fq76i*bRKTq&O5w9KmP3totn@lqp#Te za3=N6XML;0-!)Y0%F|(~pbNlc8Sr%3at89v%joq;(F7;R! zvE(PMZ*G?6%gD0K1MbR5Wz4zKlEi4zQr^iX1Ot?FAoj(Xv>?gU(=#)62U5H+)&ip36&1Y=bezn55d; zhe%|C!VyfEH;vM_oXdN+;-{;?2De1VMVy9G&m06XCPf^emu|z<`SL677j{83Wdx`& zlQZXtmP$DRH_6#)jx{sQ@*JM+0!%*_9MQ4_%S)opfdXZ1_GS(ky#140L`zpzRTt$} zvYi1kWWv}XAbBfegGw^}+KlXPwc4=|{@etn-mZ4hl=(PUqIL8%>Z~?W<}{(SGeULb z*_|vKN+^{ICf0pN&THW6lhB81LyKx1hTV2bH4YB495L)dWl(Vx5@$L>^k$=UjEas{+ZIfRK#Pdr^>MK*B;eK@yP)Loii}|@JRsuq!L4l>PU|ET+O;FPekk-yU2J%Px z&&6Pg>uDg~9+~dMZ&1*sNse_od&=VbC$x}+S+#DJw_nZN3+8cz@@|ski?9FSi8FG* z=Sj%InRR6g<8 z?Lz+hg6c+^APE=m;nXRlduL69GbUlCK!qy96(iAS9i`TMT1|s6fU35Zq$nd`wY2Eg z(*TRhjLD(3cLk8#23&~OMjWCHtaMv++)ITXb}Cl_i)2Vs;TYuJ3}KE!osv64@J1}K z5B&D(qAHr44ex_%iH_b`5(`&=-zSSRjZ+rPwWZR=Z#agC5oTzHrJ%gqMG4|T4M!;h zMWI5X6sWl+honmEtrap+Kv{+0aD$Q%Y_EY<-lk0+rAXVU!l( zwrOzKkXqKTU|n-#%wM5FT5LTO5+TQi3$mzM!IxuWp9)dg!px)AL_?ndBmXZ}&j?Ap zLmY${#qCoU7odB<3hj(7&P5(e^i~FisTh{$L_jF&_4R;Q} zj@YzFdHPW>Y*UnIq%2C-E^>G^%Mah@K`P#i1(gm7rxp z%kxOdgp#;xzFzDQ#k933GH!T_g^}fy$2jrjI$E9|gu``UiOhlK%cOzx&PF~ryK6=h zm@Z4vkH5VBb13f)GL5(vVuyA)fh*CU*LEx4UE1t!TO_$jW2RSg3uzNaDOKncXd#HU zMT*zS0@oa%soGhk;JeQ{PJ-^${w{Q`4+a=^+H-v|V-#miekeQ~__RC9WIxbNF?oA@mdM1~2Ux~tp+Br`d0 z_+O_AKb;;Ad)@e#D4*1JUy4|r%02XzY;1F5Unf1JOTW#|R^SdXzStm) zhc7hcJBW72{Q(ho9YW<6n9cN#QU5)W){8sF{5+rq?efjcLr8# zdx8z%3|H8SC~}(cedT@S;)VTU&etej+vYGoFxvr1_5n=avnO(*v~Vh1;M&t9+co?? z#q3NVVxvrS(xdt{b}x$J>5l?x?}Vz4Jj1}mrybOhgzrk7{3%3 zF;z|-p?}9gG68W=x(CBrfl+o;P|B~kPoSV_{@FqIF5JJh7EFb1Rl81TD3bs?s%g=Y zNu76A=n^j!Zf$K12>Sd7>H%B;3%07P_yT~%2vGF&8h>h7$-Gf%vtz1GxnFSVTk`hLA@) z=04r0mOL-w52G$%fRPRI~DPrJ21eMrJCSjBqA3EpX09 z0HHhFSBs;`&Qc-?!|_`Uy@77X&^Ij<^OPbrilIrV;*UfIPOe8HP^Xl=o9^wcJ1ka~ z_Gd3&BSa5hW(`2T)!^$&qDCa+6-U$G-zofAAV)SKSofU`^j#Jv!z_S)Dp#Pd5>294 zFcVN_W8h+Dr&Y7-lLE)Yd8Az+6$MwA*qntcTZIi7u!c~HWguL?*56thCD5#RA3`y{ z)zlqkCpXpU*|{ewc|iK(W5_M1Iwx|3*`lZHb|&ISXyVlxDmuz5Tq>d_mi^(3EiaAH zF`Qb%e9a{-CGon2;=AE2k@RXd&Njg|eXXgQg~?wSKO%N#aU<$pjkp&fOd?6B#lsVu z2g-q>KuHdrC~u@wJ;L7GO9s-`S-~mfiCJ?YJilOqeSe9^g5v5on`{#is1dhs}lN0_s=piC;p%Ayw zCUk2YjjD1xaF(!abe3E$eYy62c|<>?S^7PfToq_@pH2=3BD`6egT_Hul)xw~lYvX+ zdo>3qJR?COVaRU=pSuOqfuA0Q(*-l)Nf%Qh_Gt%JN>WGnj*!cSI1hAwT)~f$&Xo(! zT{=^>1Zl2z(^&*2>7Z0pCtY*l66&31pVVX@U0GD1AmVg&Tj{ks3uH{*y*!?IzdQ*5 z1aLrMb#XL91NasBMMV$q?tTE#w?hS-Ty_4F(4I>n1|@aNOM%4E;A1!Olxu(wDOLt( zg#kSt6rfMi#x!12C(I_pg~kOcnumA$^MRw_R;A3jwIv7&F)*T%7Ex#?ePVd{lH_SX z3U;^_-*G|X{O~Ckjeou!~W=Hr$tF*kjx;;8) zWf$Gz?Q}-|+>5Phn}mZqL>Ww_fCxE?M}x3;IY(q6&q=mwN>GDZEQy0YC4`d`M&pD| zOr8x9k}R%RcX-Hu|6^e;zI+D`rTlQ$t~eLW+HjbV5<+JmQXA}-qMI-!eZXSB{(B#!VMmilDUKTA z^9fqKA#C%@PPAm2J5D-wldjofkgJ;cDU{>tb8*yg3St2>6%CJt{L9$VxRn=UgJjM{? zknpH+4fM1%mXoP$`ih&S&YMX1&x+Z2i?qX1(--^HXcF&Gr5i3`abIDbek4zglq8fT z>D&*cYnWt$>zaj;>LFz}3VrV+Cc*5(7QYpD6MNthv~1jyv*d;H1c{hCHyv2n5t4U4 zQ=Whh@Jq+>uFwrjt9yS(d~=s?N|*FE;#m?s3&BZstm3*;h!O=?IMl6oZiM+jxOI!e ztDiy@|6)hh=xKcW;_a&$={y$okd61#0`GfKo_|yd3dxiW$5(-8 znW1hhEa5WJ)v(KF^7It* z_H?6w70*JawxO&4`SG@GNz^IAMd^5obm<#@ZZxe}f+dshvxx8QSv*U$RtVj6)(+FT zRmOp!kRnH?YdhsJo?`KZNJL)NQY4l$OWoA6VHsmqiMA>}u69kK7gVi^04c8bQd@qT z-{0|<)hMF<`cZ11?w`mAx4CNJM$XdCU^TrOJp@#E8&;~qT5=^ZX03AK)R{&q{fz1> z5O~GVYw%>|9LF)hD+s$Uo8mr9^x_zBez^Hf+;08*=7rB#4@}*}2*2_1&Db^`*Ig*?O{X+L}QQe-!ZI^l_|?J z!r2UD^=(^Dj;Tn!9j!zNQ8TI3I^f;uL%x&YdVP9qXZ=DfVsK(}L39wG787%$@Z%S2 z1^A@C+`pTS3+woync*PRjE_qJdEU%$yu zpDG_*?rC%-O~wn%b_pEy?VmCYyy=KfOqUjZ`Jan zu4`x8uKNkGrM>AgT`I#usBA1f9^HhysRQA$QEo(hSn^AEOp2qMCS!3A_&4DgFeaw*s=6|2CN^#Yy`{SEvCWs|JvRBm8s2<3X_V4Q1E`Q$&7KytGC8gZ9dNb7t&lJhQ1`zR96UTcIbDI zPC9jVGmo-obTuNtF)`=yK3xiyZNWy-e{8x{?q<5PCYl>f0<8Z|UUw;xk(agjqCQvQ z6ajbN|NYI)aW}WL^y%Ilm*fC&W_}R?6CU!sMoSmY?Q7W5zi@gdr%&03N#*9i2rMY* zjr1;#$ZDt&jh(h;$EHouXK4Yok?MH(*Wcr;kfoHqQ7JY48bkYjVe< z?5B(RWM#%W8bM5|LkYvKW=p~IIAC#kyV&@>ka{X73ZcE@#1g`yv?=tcII*b|<7k zR+h=Kdw}=2u4ZgODz*GB{3!Ow{hf8yzfSwQ;!9>$ma~V)5I_d=e!O9O4#*LDe+Sq^ z7!^q1@xVE&Yva_~KI5sO~ zMV|gXRN~bH5BDY zvp*GA{i`o4mH2ObupLZ3%{WuY&Vmr^WO+CXGOMgBa~ih!)D&`6-^t027Tk!*6tHo7 zeOf?%k0P^4@?jI1wV&C$p3A|LtA-OL4@Wwobqi#LYobJ_pDET7&?Z@WBUSNusflwY zyadU`zC)RDTHs9PA($N)gG-D=XL*l8vCm95t_J>z{dOl=Xc+mkj@!}nwq;x>L_>om z1MQSlfSgHt9C zUD2#os+wYC_3>8?rMJ9ae+@?9u$>9I9sQcQGQ6c)NKxWadLIf)2iXqPGSH;#`L0d# zy>CuWCvvu8$e*;xSP<7~BEwx^*Z11*{;+U-Y8ARQX1f`oZHg zguh5!syX75mOM_2i2@5cxajmNcAv(8J)4s4nSX$>-Q7fCeeJFM1s_qLV}hrr=l$=B z8s=F2cRfE=n>H)P9d}CR(lp^oqCMnkAAi6%+L!U1Z!=}p>+oB|$W_7>)XGbNefA4l zy=c0ZJ6^ApRaAb zqyX2a0t^M-kW9ZieK;Yg!3P8=BY96=a{4GHsNM* z5YOL=m{T=zYJ`N}Y{@ftv3U&2PufP&Sv#9BoI}m1clv*Pl3YcoBDFeJB+3>uevH37 zYZAEQk`DR1eXKZ6`m4e;ZI(GIeuzh%c@QWyfR)1NY21i1WDh3lH`%iF0$K5MfU5aD zg`ZnXW*>fMtUWyJ+Fz(hjRHVjf9$xkbaw|tLZ6@gr*ggyU!L`p914w?+ji9js*3&a zq~33;+ru8pVmrpO>WkmyYRJPjaJ7B|B05QAVG;~h!SBN{Sh$O0&t%D8^<03BYv*fw z)ku|S@P57{4X%tqjX+sn#h+`5;{FyB+wA=Aqv6=_H5t+5)-@hIy-UHA3hx<_XmKgD zD-~}hf&_hwgCOXAGS_M>35d$B@l9$DXJ4qswf*lyONJKhouay! zh*hTfypqr?S8z|n5SqJ8h|kCQ;cG$dA}prygcZLbKas=8_aasRqxByt#_#c@g_Mkp zs>oc39BBBFf3CGS{`-m!MiO-T-o^kX`nsmBNiQ%u6=F$A$$H1vSYTIPp5%1zA8o{E zRVY}D(ld!$Tj@2IzodsccPnZ2jweu)j^~}+&5cPT|Gf4$dkgQUwCpN)LSC6p5u8Di zB~uHxFY9BUkB`BHfm`IPUX0PR=02wluNb_kQ^ocjfWeq#wsa3cZB0<_ZeoWsUUjv% z#2qW+C0)O<#d%zp^%K*TmsB3iwtgl2x~^}~-Nqb@edX(K*+7(d9NcrC(etmGJ)OsX z-2;A?Kc6%C`aa4s0S(Ou(M}V=3~CiR85tSUu8*eKP)=!ApiJ2D6)eGkgaXF#gb$9J zwLLvhJ3a{}sdS&THDNV#?^VmzSvUA|I2J!%G!v!ED6H!kC;!PaZt;CBY1wYBvYR}l z7F%W(BQ*J>+R$LWgzsI_X|@=Q>emWAn5*tYeJ}qx%9}ot&bKRH<-X+665{M38gXyt zN)bv>voYE0r^6HMBeNL&C^aJ9KG05WNG|hRa^c;Mt^uf2^oIQ@REE1L6nMXsHW2B# ze$<`(vOqe#Ct1{WjKW{~X=+sJ;#Ff(`)yJ<&P<>xfibWlo^!8(XzTg-qhYsS@5~I& z5Fxpc*H0?|)^C;bb;x+SMy+!y?07n_ze=pUspY06gPx!ixd!~sKVm$NGz{#)*A14(N&;)nD;AJ76B><*T6@qSS-;cA82Q6^6O)s$m6=@&V9d0)^&cd zGW7}85!M5)l$=P81ZPWXk?^dcH1(%sL<>%aQtBw-po$b&kq+`T{;w|1N|`}7!Tmo^ zl_pAd&|@(M_EWHaHKxl< zh$)^{?z4Plefo1X zq#P?>se6lu(Twq_NU|w74t>i5vT#?gLql)JQj^hsv3gV<6O^Ei1_)_#{4P*|u^*rj z3%Jav`Jr55t~2JuU$_KARCqzgB6k8d+39KZ^%cLci7yy{k%e)F0%wc!yK^&g(SV85 zQ+9@76}j2qZR4Xc5R-#M^!+Q1#Sc|>jDSiF%$rwLsR38j0!xhV+R@v?(YTVAPI{s> zBRzxo;Y*+`fd)57_qpbqm;AQtDjO@LSA!SdSA&5|(fo9$an#@rjJ zUo;}K)N2$ml4#NQKm1)0u$WOMY~IjpcG28EWP>ls^FiEvz&KpLc`j{(Hk4g)x{`8;vjD!TtgDmM-wLRFZ!AZi;d2mL7nrpKqLCF+weKXTc9KRsSFAH6 zNB6hVF^bt#pej(&Jgl3`eXXJnfvI_2U2SXOY(DagNmH~WlB?D>JEXz%JOsiA>;Xt&Pb zD-=o;J$yx`^NYq-$mi}KQgsRnJ-+4w+aV^y=|4S9#^#-V5&gOjeS7|6R#P3Nr&!bc zvtrAN+wbe`H4O>t+Uauf)~gex)v6}<{H3%NUi`tKa=1;&3FvO9@h>Ymkq&y~erC^# zo*@)fm~B%#nu(Rvkye1xyI*?|<@DtZ4H@p82bj(}+^BXu88Wc|ECLQd8=QMh93L}z zXVX~py}ZELBqR_Z%A9Sk#GQAMGYk(a7Qc()kZFi_I|`&9YJXQptE*OF$J@lR zXf+Kz>>|6(d-Szf@fabReQO>HKgf9KJe-?XtqGreSB~q}s;^OF7{#fyE9IG!L;dWv zI$&Z`_MzhIXPfsk#oYyQo=pW$ht|_ufV(hpC;%Y9 z2aK0DH;YA&kb~NQIm=UPyscTEUu86%N70puS?9$ds-XBhpH`~UyY2R-1BYGKUzz(N z_I))39E-_Zi^I_u#Vp*IuR31GV7c$rVB2mI^-jFz^yi;?4(yKglOzpo&Nns19+ULP z_C7Mc*ro#F?w@zW0qL%vZBCSO0lXV@+WYzD6jy!hjFN~T_nA2>) zz8Q~Lr`%bS{6c=?Pv%Ipe@NGNd%JuI4P35H$$+FZ6cb^&u1#GYDZCmUFq=;0s#6h1 zs9JK&k2F=>kfzlX)UuBs)!JP_1bXZCQ&L6P;YR-2iWIX7U=lQUz6?YxoS&f9c4yJ# z*`Flb5wfaq2nn-cA?VxZJ3IGQtO_jeKh~h0j3_!5TILJB3&#$Hw)*`x!I!$W>YN=} zP*NA5(Po>F?rFhF9v_B+O4ydLm{%wrNMJLBSz^aGM8KX=5q;*#{CZo{{SdL@Cmnx? zf%K+AR@pARWo5m2*O-G6iathd1r|bz;#C|u#6bQhrclWdX|ftbU0x+#JEico^|HwP zN`B^!P24;0W26)hVtHHxm#WISTNtlRE`6Z+^4vy0N3;ahXL=H;E_>9g7HMZ9G^bu! zSwRgYLg}5F;>-E^B0!Lc`rI2=RmB#Jy?2@E4IJ|!y5O z*eyZRCb0MlYFApH!@pGpr`pI#Io5ye{C(7&o$^(*6FSj2+STj5wPno*)$__y2J1+| zR7l>nO^%wp9gze~+5o5nYM+$AvtLouZOWISic7b9&gj*1^XLzb)4~PTPePT)2#lWz z?HKR9MS!U^Aiy&UxDUDf*>8*!V=tfcGyTLQLqy$qK;hc}C>6scEDW85Y5VP3Q6Tx6v+VIgiLL%c7EqBNdD z?T<&~qb(5FjZXy$YLBp!hS z*7R$C{EcDsFs1R=*KfYax3aTWL84G(_z^BBmRl1TF&aqo8dfw>UPH#cj)4tJ5`cjQiA_1M_)YS2r-DSK(IksGG=W}@9k^sE!nMRmwm0*=+aUP@hCDkvA;>pMBWV zx+)01&oL!gZTkbZxz2&eu!`01LM7a(cL;I`?SBJKS4(H{ZPwanM}7OeeR8Q0cQ{;H zYttghCx`goOR9(XHttt#qNhsCB{rtSe4%f46UFh4@G{+4(n+8_)t@=a+!<-G<0nO` z`OTxSa(vbbJ86TAxi=b$_W$a$6BH0gmSgOwK?%xRI@2^^X)0!ti5RM2QS^dbpJgXG zmKzc5Pg|H>UU2$mG1vSM3hx3}A!nUYab4lQcAj@vRQY{?6Ky{6`j96Mu=V@5M|`#= zO$2~{gSIIdzct-Z(Va}4Z}*4YtV@0ZllV9b5$p8Fj6|wvM8mws#&)M!PR&F!?y|M8 z<`5T$7i`$_7xt_4x8@d;_gF1_R8gc1wf(EKoRU#PIQ`#ooA}?02j~UIr$29xmxl`+QvI1Xr{lGU>n)a(^ zZN*(ZwMK;{@37;l)oP7n^_%hGE}rq6uO{x+UI#{6^?byS7ajOpOXC{;EX0!;7DPJf z+t82rK(sMNzd#is&eS70W|*=iPt@=(cFYoq0}-X%tTAOMhQgQ)L4p$z-KG3hnqc8TEV9l!(o`Du^NX9B8@l`#0l$rxuAavO z%NIQD(uixV^5%;7N)JKCVtwc}eYX@=t#+}~@qg^j{(k9s;m!GaLxj{1w6c0@YwK4& z>vSdZecxD}bDjbdpnLEC*$HHYA&M7hr0kK#3|;w%@Kl-b%dTv#9e(L~ zz?&NlPK6r%z1T-Ta4m826q45Df@1O}Q7hvxuD1oF$j%}#vD%~;mwf~;`W~##e%VXP zvv<|K{LfvoDv1lb{pD#@7td6@ZI{PXdsY>xs94i$XUZSE-tb9?@Nkl}1RQ8g%Ayqf zcN;8qmGx!XN6OkAMK1G`|M*$w*NnVf(s;0t9NsKE#SM36O-H#=TJvfNz82B%6Pz5+ zeLPp2bWM3Sv%nUICx#;QRVIWx?oNHZ;Kn8~5+!OnNafV->}p7z>-CY!Bv*F~O_vr* z)iULwU8%yO9E#Y^n5Mxy@AZZ3kE=9dY#YR6c!Ck7{x|ZSMf#e1DeAX`6~Y>Y>^IV_ zBBj+Bv@IWqu@~$WR4WRKjak{(u!b(h+?=mE$j;)`wB&=6%pp;$8pi$d9c=>|LvYe0 zNvbhkp7#6VeCWqhrC1Nb6all{ze}^l)A%^<@cwflVms8Vjif0#uCr2v9pwjTBFtR` zZ1=T$Yz%ly-wtHA4K)f!ei2?8Zz`7^uPHbB(;;1pth1VG_gc5as><+TC?3*%Y5$pN zU~Rk;r10Lu|6|nKhQEnyH>Pjd&TJ=<3=35FAQ&@$R$wM6jcYY+a`FiQT4Szk8?MbKU7g&KQgimlp zDKx?jCABX21`-wpLq0FBbyKc>o7gH$g07`qyJl(o+NIsn56$mGX^-x>V-A+4jD%eGEn<=O!0jhJKR{$ubW zdtXegm3a?rJu!_u8Fx?G9#=bi5Tl zV+O%Coe#0Fs3^1#+#h?eRuAK_b$*hR6Yo-&_f1Vp#2XXmiz&K2`?gXZK~HkcB}Wg8>Q*2MW;QKHXt{vKPSTO(>EM4>p{ z6h^}Fj-Ihdo`+8(k}n-NxCD4Thi-j+=G_XoWP5MeoiD`3DP|C)u5k})4v)&4cxyi} zI~vfS)K$jS=Fu3LC+g6M`r(7l@U@VGNRHHcW3J|cVaCq>F!hdmYle2o>+}4;y`m=flSVP+Bcvm zrj?b|gK=oix#-hDjew}ISzK`@8AU+^dQy4)jaL8UA&N+mICUZdRb~Ekj*Z^sauSHC zDt}s3vdF0lS0s;J(H;Li|9*UFQWCn=8nIqBKaY`OpJqGz_as!g^aRF`MJ-5Sk_*~o z3SY#d;a)Vz*LHz9vNUs=(edhV+|J+FcC+EccJ$8s9(!D^&+~ z&ifZSDgEoVtTwEd@;g%bu6^AqAn&XbxX0=8z34G&qVJascOUI}Q^W5ZWJZ3-n{9|p zeYyB=L8NC#UD7Q!@3&Z_Ctt;Dy`R>zensNnAI07);yKz@Ms0Snv^yTILx)YeQD~Z% z=6c%PYoGPB**jWOHhluT#@#8-rwz1NKe`ogT$7A&o$OoR1cO0G=?+1ug%VyDCll)5RHQ+|67z<*k?vudbzBr5}l$cl{P+2N_4tbfukk zsfmjUZ>RBz-=}0q?#@d4-#1Naz@E$1-e(Zt*MwU@Y+HXcS4jG%+k1yR63+#P_gr$X z!v%|_wXMgdgg8#>fO4Al2wVf_rL~|1`e2Sxxy}&qsglhQY|=?IuPttYNs!% zpc*~g2_@{4a}37fzC%<=C+#?29rpHnK1?>byX&OBbQe+>xu+O9;u?{qPMWz>96z+{ zzHYWG)vxUIPi~(f_8hc#pS6Js-rA%mT&qRoyX_8=2>Y#5djjR@Al?+C%Pxma&SH33r#*%ZSO@3~tRpJ6s_OkoZGiv2X?fdfnx$<}Y*Cxfj?n#F_xezJmd%8`l zlbM1yFFUC{zYdN3q(!o5nhrV~yDj*#IF}-3=N0Ps#k;7Hqna;LfK!fwTtX6UU3Qy} z?UtUx%gqDiL$U6#RW5N-xmJ_*@lijW0#jCeF1+7Jd3*khR}thpj}lSzP@&D(%8Gzg zcELK5z>V7ZJ;}-9CgMekE_oGpT_w@&clq?_xhuouk$>f0(&sW0D zpJA!Q7b5dl(sT{J{fXBotk8gGR^+}n-kOh@&b;d(>>-S7l(L_opD}C8xxEY?lT7`g zyZ*Dh#(U6D?_BqBkZa#3XxZ?u7PyPW2VT7?R`c^C*U+`&WN?UwykM%)js%zO$(U7N z)j3Al?nQ9_oA+BLJWMiYhtQ<(_0-T6EpCb4;TYx{rbJVt zNg~)}a4zPX0ER^)e#2g(wg1pvq3xy7rJCSB305~Szms+4SL%Fca5y!-hKqExoGUPx zv3v${^d!dvdj6zdtJf^v=$;LXMJknU{t+pUG3njj(u1<-?S0vYiL;n>t(-9V+hX5O>ifeE#0dPQ5$jx?^M79s_A`G zZ=uYS`<`JggBChI*Y$oip*NhHPK@BIX<7KDS9FG3R<>Q_?2ejmz@_t0%6Zoov7{_h z=dULmg;k(VVnG@;5QDbKW64GK=B%KAoK*}DG0bt(NwDqb1Ul#~M9+^mcVmDdj*@m; z*3+cw`FT_C&6ssmQlVM`nvH}%(fW!~u2Tm1yV5Wr2qo_>fk%uU6@@T*I4YC|U_`aO z{vts<6poG({J$CrrUa7y_0g2U0J`;!Oow!L?-*DBZ z1fI6(dS1_72YS6CkMDzll8sz^czC21;%bI?J^S9FOlm(3CVrP}aV$GMknovV*}wNCQ3@50Z|&}^s0x*!$?CE=Q@?l! zJ+&OA2DE2QPG())h%=_?FGV493K{n=F7#*;~nN3`Eg^w(amXFc(5 zuD>Y8yrmNN62?j1Xe!pUZFQ<0JCS8BDs(mwrkC(D;DNdO2Pqi^(pN2L_!uGDkCk6{ zRitdYz_Z`Lf548Pe`~S#+gya7Rn=fge^InWu0>(K3kPz~N$%{un2h9jx*@B6H z*l=Q7UqV}cx@?yW8(|do2#**o)klASbk(taCY!-kG~f^-0sDX_3-#X*43XxcNs~;uIyX7gK?JjxHFh}nb=eE13abj z{_f>op*WF9>bU0bSWU4{hlpSi%_Ya@6uQfMp*UZ;gg7Qx8cUHKRhiH>1DL$2?xIU> z&(@+JlM4CDeMsM0SGVGh_{l;R zL@bQWn98!;pZtZA+Fu=p*w-j8jOqP0__L2LOA@>47*o8t6sCsBw~&vQT0DtObOZrd zYIw!fu{z@7onf=|Ugxd1oT_*|4(-gmkUzg4Qx3OK>`yjRvb9^=`9#>;9+`{U%iKFQ z)Z6S8@4MecW2Djwe211Vfp88=A#ci2_9OWT6Wo!Rd{ z$lgs`QxK4)J(~3*-?DaFvSN4G(aJ4guvNyVi1t+pvgbck!FDO|#}9t4aUA-!3jD2q z@zdn;G+0kDG|DpQG|YPRU&)6XYS-}i-=0t|{I9EW*jmU`h@9%%T;jX#m&2`dqt|l^ z@8=EI9|VPHpf_r3+?YREjQx&?gT9;~D)=zT&hpsBM4yjg&#k-DWM0ra9~Ke86=@~u z(mVo@nGaDtPhX7cc!6PrZ-!xwN_vq7vTJ8aLNRbg5Kf6rbU<)xjck=01m@K(SQV^s z1fzwvFkOS!|D)+0*eZX&_wQ=5IoY;rvTfU*YFCrZoo&0_U-RDar=F7+=Nm1V^Jy~KU@DE`Z}{x zx4F`@rMxNe4|94dFS+Y`W5nf-KEW1>7<^+uGk!KKt^EeZ;m~lp$FhDe|2lpX z(5-iz%8D=x>D28nb#h{b0=DtS$}zGCEFfg4i=`_eYwmvUp@*-Qvt|oqY?9Q@&d<>b zzT-uNO5qcgv(iVPYjCXcU48r}t~*;Nrl!1pTm>a5%B2=XP|Y)^s};LQCuw->O9d-Z z$z@ZNqG;)Shw0Z}ew|GG0}ccITL=l<*|=s0OPG=WM;Lr~GbXQcZTrX3RJiJASn})= zf$I5{_8k<>okQ$OVKycfn>2g>bw?W={gLa>UW!x@}l%Oc^_q0YpNN}I%X z4p1|Nuv5BR7b$4iqGB~M5DdR9NbIlPQCoh@rA%~KY_b(Q~X2%AoC;PiXj9fg;NdmMVbaE`8a z#VnHx@RYQ#b|Ec4x^Z4?P6EwID-}yJe%SPo3y|vwYNm;W954F1!hNr|CYIbe& z2wuF}kn-C_7#u|Rq+1=F=g%o!1>V|zo%vmKjvR)&%I-GiZdtUgTd8;ccQkm61FL== z#~dv!{dZRzm1>PxB85WM%z8uKhNvaqoPzaWz5~o0Wykhn`m4X(cYKgPxHh(%gNjt6 zcN;b4j1$hUGtB~n7!bj-@iAMjL{lMum=$NIRkBzy1jwj8G=iRdML8QjAuBu({T!nc zi<;r!&TUumMGN4Mz<&*_^4RgkrSnI(qbrNw2R)fM&%nf;^}6p=2!ssZAZu`>?L^5m zm4%r{Y3H3C88}OMu<2$9O2t6*`Wf0&9Qi6(c)NDI#PT(9(q`y=Oimd27tMP|i8bfU zO>}`f+;0lWFdV#s-efAw!6#3$h5VeYatB|%)sotGIvNIR<)EoS=*fSm`ZPSb z2-xwEW#_SDr3E;a3ocJbjfghlD7$ht{qAi#CPJ@%bfMAjR?JrAXPp`}DIFib%HP_> z@ob-tEz~9W)}hZ%Nus}KrPwx>CCF}SX?eojSm}uqI4P?7>!2xhnJHs<6Ec>GQ1P`) zNR~!bRd)aXM=`v9%$pM}V@3CQx5&NAQQnY?#DX)q{)=JFXRW}{ch9iVZu>%15%bK) zTQ3x<3(U*)xR^$&)ElM5uDoI22-F;l#t}Tn!~O8oBUn@L<$A#|*FvvIaU>^KNsfci z`*g?Iu0v;0l_DWiw;BB1YZ0LvW!0qO}XN9xhyh5_*_su$StU7fxndZ z=pNq@Wi&ag#PgEwh7Uq7nWBt3FmyD(Z_F3gm!#sc@Xqp7{CLBE^}{jR$9DI{*WxX! zdbPW?OjADzmv4A@_`l@#ZZNjeHkb*?uo|tA3C7#l*~LXnkKy6L1FXlFw$r&3FHDUd zo4pf?72z##Ps81Li3T2|_ z1BFA+o$fEwcRRYoB#aqTr@`xIU;4}ck-dv((h9cW$~b>g`2A7IMhcaQ@TC3i|7ih8 zHSQnl$t4?Oh0E^eK7X}M(0Nyo2kZK+<(AdLh!puhYK^SlV?Fva$KvtC&ii#Ah25g^ z#y%o?lfbL(m~8ekp|tOTXj+wu+x}pf@eIDMuN4hAid!{wkyNiVF-`nvD+XV2#1};B zzdQN1H;BU6!Q%gBa;)U;kD&5S-?OpQ+pfKSJWI7ix+;fReY5T#%>n|7dfX~{WUN!N zilbikF)HB_FQFJRLu8xX7CZ$hh;q^)Tx87%fxw^!)w4+?5BWG2lq?R}{V5|2f-?7* zE6=RM|9%oY5Q>k5#(l%U-s8>hk&VC13b8OeW!iTx0V1 zFUBQ!B-APLhQVD>WSO9DIiYZh@OqYF^HZEXCyyPk)Zr32iDKvJDV9oMR9#MQVz%-R z{0J;QMg7Et1J4&q*_6}(r=VHYuhh?iXl09Z<)&3#bgXC-T}14G1j;bRWIn|0Rn_GH zy>!bgYS%TPz|*h<^ujdhiex`w&!Vh2jmYL!1wWA?%zg0f&YcekwRb5hs{3bjc=Cyu zV!P45p$VfmVun$?uY=)z{Zi^ba#Cp|<#ipcg(Y-nHGO${%zs6`l)sJg8Eo3N4$(4; zsiXYqKi5tbLA~|5u6RVJa7fZv?Kr8#K67e;kYun1SLe+85GLcw1Ul+7+g*yfkAallU z$Aw%eEh_%^Z->gh=X|rwgovG^8X~SVNTn*HP@?wXk(snPdIm=i5XP}1mf=V5=EQ>Vh; zon`5L+pl~6I~_Rm4(F=~Dkqaaprw5?N#RqpiJWD@^66?HVW-%c{ycF~gH={Wr5~pc z4G5VF-@A%63;f;fGW5KIv;f9?Azlati1HJu{!GoNQ(-gz{qSq}V=B_`#~2vkA!Q6f zRwh{m%D9NYuXxytA2ZOA7pq$~aFJO=6gQooTtv9_j#sw|)x}om+J+_*lYQeGRIsT6 z-Ei5yE@#+C=o<56gh?6TFLg}sQ-3d5>g`>6TkIBYSN*cw&#{4AX>)nS?!p(0moQ)3 z{of#^2xqxW{xxY^B4v$u_JtChf3b25nq@;aJPfb>02it&3rPloqG${<;IEwopkyj_ zd4$umabJ=8#1?VVK3`T)!w6)kXh}@_{RlV9M8hndR-u+y#Sd%T!>*?TG|Tzi#(CE} z2Wb`iF!rN{QYM^A)ktyjo8%}S#bz^~Csd&WqX&OPa%g+sLy*gy_SB?Xm`1nJ+Ik+ z_rmmwp7a89Xs3mDO$6~=U&=p+MhiX!u*#m6Kj%Lup0-JxrlCJ~K0oRr&x8wvHg~T3 z5}g7bAKwl??+U=pF>sFjP+rN}9&_mHpUF6Va#8pwbPDti2>sI`_w%N9Y_c-Zin;to z!qF@qW`&m}cjqca%>ajnefO3PqrC3Hm&uNLurW^y-uRjEgli(}z@Iwyzf-6w}KTZLmNoNY;&f#Z2fOP3*_bKk8ug zGk*ScZ#$5dyd_f zASJu~ITU%NK7N4QB31EvJ%E{yL279oIul;8ImH@19!%Z(JoXhPeeilZgVac3JCmDI zPT&(hzus#!Q3oa9BmYR`)Kp78gyBfSvzn1+MNsp+ElsC3u4=2uAbeXKrz#bdKZZAm zQy&XRcvlWv`dL8Md1c$|P;!-3GaOcJ!WuHjHhy{=Ej)2^aE?BOgVGAHmTiyiuM--_ z>^)oyVdR@-Iwx~PC*_*BF&ebm{EE_h`G0G&qwZ&`@^?k_*FXaDzZQiiPc*{Q*mUDA zJ+9LKU0q7D7<2T{Fa!!_1mvoCsk287+h==Wjp9jnK4+Kb>__*<_nfiX6CkYU;!-B; zRXktoS^=GEO@bO^1|7w$+xQT5B-m~eyIvUv>N1AWnB?1AB%0xJDn!Ym%>Qv><2In=t8JiI7X_^@rd z(lp#mTx_icrxQl!k!Vsh@(X&lFM9(AE(+e0r}H-tGm$>7b40H0MLsEa)yAeD3hH04 z5JG1&x84UHyWR%^tq+$?e!V&?vL4^w{3G7#@*C*fjWzig{1i7v9hu%@Uxu-&KoS`gU>{9nTDmdK^&wqM8Vu6;K`eLZ#zC_BYh7(g z%yT;D!t|NZLI^7Onot_KVS(#A_w6*0@a@y(?lC+Y>@N*+f%7&gh zN4GM{Iw|JY+FG#NlHx>aY>MARGJC5|YPljAxFtD}h>cNmLBuZ261wdY zO6!Z+;a3sQz;%xmRa*a0f(t}FBI`YO);>k%qoh9e^ql$$+A{n(~d68yx1Dv zDs$?GqS_Uhe@U5I%p`9;k3T3lyceyhz(J)iFJGgk5698UmhG))YR!35ENO3%23&;( zrke?gjYtO8+v-$=zkxQB+u?&bI)swKa@OqKPZc6^g6zBljm9!T=|>IrEE288o2Z&% zNR`vqrz#lZFFw3Zp1Qb>t}bhyj*klg^K2rAM|TDRo_8`sDxOa#f$y#0(0!N76csOv zsppG(ky{%$N|Lv;L%(awh!U!uoY6<@zlnFFK{f^^$Zui%eUy+ zZb+N*x^G!ToU84_T=ZGrrIxV3Geg&h2bA8A<-k4lN&)9#3*)t3U$Sr zC*D!WCzK4GmmGrYRgZ2xugl96^<)sj&~}$Qkn%^(1U=A=K#K9#>eZBF;3Tc%uT{t# z6%w7gfpN+iO_{8x=?`V7r0$9-jqMXf#4xwL*x%CkeM@zz4V7EYCAdvO^ips3druuJ zW8+eH)=qait*p*NGzqMFKNIw+rR3Tlab{bB|FzdN#f{ZQUPk{k&_Zh#C(vP`_)%#U zTWxPKC)voO^k()2+MI`iu@CbJ7HbMj0sb%}OM)UVt|b)o~!_SbJT{%owF52B)(#V%A2 z2wN63-aqt6T6YOAs5^~#EXvGpT9RJP;*NJ_|A|enh`SPgtQBv3TUH9$a(m&8v+}?3 zfA#5-u~T@YnKOA{A|)d9gxrn2PCrKm^l`ekE&lR1=@5$D&;K6&uhq=Ztqp_8z?H`+ zCjCBXEc5*Paj9`y2?||?s$J~+JYvx~U$b;7okiyE)Sr7o+Y+^*!lst=mwv#n=A}L0 zzkh!6`9X^6Kg#4lt_yzQnuta6u^bO7p_)?yy0WPdFjJIEG=@;XC0kr`y@<)MyvVxm z^E!H`c;%~=4sB_Z#1>R?tf68d_;(m3-$zXSopKv?_H*Xn|*>u^{;p21?L}p z^7xt+^i#%jfi06uyUY&(4?)vo(Ee&y4-~_e2yh0E-q}Jsdq*glL@CyL^y`5yVK&`x zXNn1#ey$^(F&4@+AsIGK-j6NY1s}(xvbSF_Id>;db-G@6P|C|~(uw*~@|6(Em5(-w zHd*g!lJI@I^gjOhK%|%bJ74qkd))Bs^108Zk|SgBNkS|KCMnFK=ku|0;){GpPnM*SpE#0CSegf$#AGIXW#5h|1J{Mxp8wx8PUe?~P z!(PlEkIm;)kJk$^0LR80*$?3*Q<2MIHnkM>yx&sGg;?N1Hm=YV3nkhfAAj0}8^!1SH7o%+kaG4PJqekWXm({_rMr!% zXTqqPxLP^{*i#~-Y9Cz;?rCxsOqV=QEc92IEGyoTr=FF}f~~XAzb!e;II;?xY2+{) zxJpEhQb6fv-ED1!OgN^+LL)|EUE)inR|z53*dYR1X{6Aeu1Y4>x_2%Qn>~W32OGxA z+#HM?Yk{wyA(Bju-!1ySqtyl}}2t3z1f#vmdVO znzPCP&vpay^vP*s+CaF1ih)Ur?7(baZbJMPlJ|p_xELPS&g}Xn;#?6Y=t<_l@ke2X zHCrz8Z$#ku0=jWvO=bR5$}D)*y&QYc%9wMq-hi zTDRpuuDG_WrPgeoP1U!^g@R>j_tl^9au4WNw4F+cO$z6lp7oCBA~?o2=m*Lxlu|*e zle6`!LSflu%8RKW$_G!DYvPqv%hb}wuwC*c{)A*;))nJY%62F=8A<=CcFr#me%yo>SP@H>QL!lS3rDz0?@?bRP?KzY@j z%x-<*@Z$jlu)QFTVP_~imdq!0k`hg3RromCy`t2|X4Y6W4GEEcNyBV2p6M*-I=i|i zV@MvOSJ>sNqu}L@Xax*>WzNg@r8mb8bPryQ;a@ z7df91p&uF~v2eMcyGT>Uz1xGgxO)sTQ~`K|R6{S-1fMqRja%vUbJDCis|Cc%#&oTJ zWV1nZS~uV#{Ga{L>23J)$rCJOE|rBZ?Zn#d7Ij)XZxMXl|M^mM`>n+U@Y4&}LF>f) zjpdqzvkMKHWmbQ8YzJY(`U8}mgPUK{t;%$_wWUSZNP+dZDl1zUy<2M0&AE+T62&F?Y2)d@{aI;9k0;3Ei}a`>O& z=wlP|xoi78rxl#Dkv#3H@UO!M;k0cnf*F_HDd=ZZWcWCFV$u<+c7CAqCnQ)Fk#q=C zZd0yE^B)Es?4$wD$-sUtuulst0@U2&W~cY__nAN=e>}T5YiR8J@_Td?0o(wmD;sHu z1$)@Rs>705cyj27h=_?p*QO;i2iux~bb)*W04V@B3n``n5P|1-GqBO8bXkKNYm~9q zX~&m7$>)x?`*6zg3LtjMeayQRP7Sc2C-;&0RdG1yC`N=s_i@oNBMrSChT1<~B}Mp4bv>r5^M{(nsk`^L(jksDRG)w1!f&Men`KTby|1t(aIIH2Q@U{5DrHlV zK?5213Y7R*xG{-kb>lRYi-?Qt*{06AG_@<7IdZNxt}$FqY115N>HW*Z7)xEEyRT>y zWixvEZG$=3bf^#Y66&$BhY}fKq=Ls3-1I`~LyzBitN^ZzFm@+Q+iBuvHM!nxlMe;{ z{TaOj3aVoU*~85UON zr0_jkYajFmQE_pj@u(tVPgBO-L!0LH$U8#(p?+pvKa5SGn6ph|O=;wNgaVcMPm3_) zyacH_0}CjvyRv)9SzitBs0SkOITU6`@yiGK{7hkQZ@f0&S|3jYHY_Z)Cj z%8I_{PP`E4VFM`_FhTS5y{{XWPmiA;TVRZC5=VuRiO#QeEj^ZWdLCRkp$fa7FCP14 z6Jr$(tFkf&k{~4v3w_?oom%arwT!+po9wL!qK)aaVlO@2G0?g>%CY4N*-N6)oG&@A zpc`&#SAd3Hb$t!*3)_%BN|m|>15mvT>2v?I##+%gbr$WDddu zPVKcEly&}KFSy_PDFo1h;i3uezOV5ULVH)|Ht26c^7_QI<2LS5Ko@B*K1?bJ03=CbtKZ zgkXa)SaVH8LyaCJ;{`}#O51H}TU@a6_d%rhZA_LJC@cy6hy*0Vr zE}J7y8SJWj7PR4LC!4;_t{-5a*x$VrNXO6eV|qf^wpbo_1ls8tUVH_7(ep@iS-#`> z9w%E*v5~;HBmxZ{p~7nr?XskO(nPJ}@ydDd4lr#gRdWozuGrg0tReQ=L_gYzPKtI0 zoS*j6?dwPZgJ69?UQNBc z8d0DQqlCgEM%*%5gj7h;oS|<>@o6uy_HV8i6-j?4X&hI}T3p0fT2J8X;AUO3C}Su) z6um~NqHHGRBytf5J1CjHEEOITGb^N?B!hzq9?Ak*KU6x&GUS5{oW%tWbUuo^yuSNj zdH1CRGjDQtx4OmOchFIh=&G4Yjrb8BsPq)}vbXc>BVuUNg?W(AZ!+zkzd$$3;tt{6 z_)Q5;*B7~1JqefIQLc$D=G(-{#0<1N@8bEH@U*E)M_%Q`^KfgMtz|l)FjdPcXMr0H z9%)KlH`QVyutk1JLH2+*K}hD(`?hC{N5G|!TOUx*!{%VqdfM=+IDk9+@_TA%PJcs-J*BHnBfh$PY2t`vIAvmKs+q~0 zN1)(ixt=_YM;3{bwA&%?y*hH*u4%RMM30 zQ48@Ci->WQ&M~>_^zvny(?|!1)+^tp)WtyNR{6fFCZg4ID(a*1o6}lm5{wbk`WEY1 z?PEeui|8ubL(ACI4_$Q4Ilu1rB?6wE0ta?Y-tf^#M8xq2a#|yZx_t&`J6m(}iChC* zq$_@makOqu_6TP%z*Kc%8(omG7pIJgL46C~-!J`y1hA8Na zT{T1tkz_VEoWkg2LF1{+ufPQcEs7KFRTZYpS3sHgb9=r39xbg0vFYG(? z9)b3E%YOnl@Sfg@^gWi8#BZ83;xn(cHxQL|OBYggO@fiiG;FAik_mkXzjI@w{jblk zmQ9YlT@4q^%&8TXoO)wZSCwwnnF6*$+&9!_u6NjxFkuI}w1%*}rX1^Y9{xpsjih#M z7Qm^9xyuF4qN*OY07FS6OiAvMJVvjb-fOmTbN-+EqLf`#BPA$yZBgFo!8n|G7PwOM zJ~o!bf6^?vhO8)J_%e=O!DdGFJc#l3^`7YMH?CVz_7ySwPY=Xm6puGU2` zIoEeA81umo4Jg=gj^qgs=v7I#YMHi`(EAEc4z~8CSkZ%DU39!dY_KIYVl9c|=9Elx zgfuU`Q8~GXrKxufB%K1C4vvm$>C|BTt8txRZi4cLqtTtllvtN!tM*8S{h zIGlF)9M!rHMU@x@gy_q|rcX}(x!Az0r`_&QQJrj*wL?Pu!HR#`$93^@2oF4hSbKVYtfWA$!D{pGugUd=`%*6X|^RkdPZnj$?`# zhIk9*IVqvgM1K1tL+pd{EE#Kk#I=y$DvYbAo$CUr*=WW_vUDRFRHlHu8|jLX4eTr% zWsY#diX|bENcZW>PKxjR@XdG3v&DL*FY{cKS!Fs8I`TXGEG-th{4Du*>UQBZ{?eIQ zfuPuk8$*ZXJ`F@PU=>yEO`nkjJV$mgIZkb=SMqN{9daWe=(i-Tg`I5Kk$grrvsfsC zMj|dhUr~wOwj3^yO4F1lLr z;gKjg{kYlpRbS8c32@WRgC5EywBs)1!aQNJZD1R=mGXEbx0Q40vkc4k`>|)O@UpXs zk6YtY<9k!UU5?0#|L(tV3%{g(42Qic|1@X&A~g2w1x_`hVbjvqUA`p z>AG~0t53mNw6m88(@{h|aGBB&F-@5^luaT4I((&2eWyTX?{;TqfGhT7=a4A0W2ZGN znFqqaxBDXbcUkY2N@^Co4l0HGWot>G5mK72*+(!n;HHbv@i%vGq+6TgGzyBj@3gvh zRLk+@xU(-c)+M%MNk4l!IzhOydl`jAQm}#p1gx|Wr4Pi0+4F-ctHK(?0!Dn<)kKkU zxe`qZdCqh)@6d=PGsj=#77Gn0t|Km@$||jgb0g7Z_jKHh<0gJE^6T!7OP*n=(jLNp zXl}~RcJpe2wwm0IRaDY*T9m0IQzXBkC2cuV;mz~(3O}MWxY`^$UP?YXn2;6&wvC% zly|SsWcL2$LhjyAIQNbX(u!Qlj|-l=CFyYXx35r_r_kWB&jM29@M*v|z95nRrv=cJ zH9WlUr`>dN-WDs`Bgk6E5{lh*D?c(0+St)u;$r5|T(4;Gu*=|)5IDZxWb9O+FBxGW z7wO&V;^!kRvHv3I>_79@B*x?L{6Ma#SO_-Eu`NJyzLcf#ahfgmh}Fsggupb8NCfqE zWN>=Un5K?L2gC6THiJanr)RBBT^6!`W)x?LeHP;!Rk;dy;d2BfSqL#(YLclb*)kvx z?*_@k10v7F&nYyup6Ng}>I|Km5UoEf*MjGwo=Fo`2_te9uQDUQy6O(v*w)x+hEJD9 zM~1wB#-1iJ`*fwv5^gWhTHL-_Buo|Q99_j#aI4iRYJeriB|?~s6N^$EZ_tVxWI3M; zm4zamxaWB`oO=?Yr@KE$fu8O6$_+i3y~yqOY$ARsy?XwYkg`JnYZp7fp4250d138G z=kff&vJtpy3)nbc*9cCFL#&zRVPP43fiZ=uvR@cSEvRX#;59l>A+h;q+j=D!`oV~O)vKoRY&2c`gVO8-5LV+${S$#5dgL6z=o?)e z;_rf$HFm}F@T-3_ylPVBP4KEibbhYpiWTrr_pZuuO`3s!nq#)jFmjo(15SEme%9JW z{}khr!483?E6wX8sVICLI6(nkQ%4;f&>wCgfR`;+q1k`I-?Vm)owzCU z1$n}wLoV5$Fs^EWg#nvsT8na$X8F3F?d;20L)d^-`+CKB04T{7}-&;mR zzcAlir4bY@WaDBiL zV>EUTKK;m~>2EpV4O(XyY`FS*nx1LXy%P|M9hQ-Db1)z-Ap9X?qypE8LqrJ%P2m|(C<7IEvs$H zwD6OXmi5FsMWn5xc(4{gDBp7H#7WeuMZ|MuB>L{4X2f15gls6KXX74u!n}*?*^r6^WQU9pR0bIh$@LKL#hlC zOc_J`BhM!5Y*HYc(;mJnbaz)39(|+6>xhrw?TC0~*$|L_81*=N?uW7H7Sg2?arm_Y z!tFMTdIA2Gh3pYn@;L5M``LzjZ0|4r@++8sYldlY*r2FuHeA_)c;e#0CdnLm+8~ z6`7kDPr-o1+*y-um5!LWnM3aAsN8A|jlKQX4Q1ZGu$NQpkfiQzZZfL|&?&eIb1bc` z{UO=yb1It&`#olvnUiB-ZJq7FqX1^I%^yn|9m}lUOeca7D&Sb=hx0X=nwFuPIm~-~ zVruFRJ7`Drpm1~5=hKD2NU(-f!*&!kfX-^!9nvqs`$ed^G_`5X(Qx@%g3I75$Ziw2 zj-^ac z$E(cTpA(K$!FT{&{{F_%3hd0^rL|Q$T5orc zncjMiT(!yA(Z=csvIvpcmWur}T>&yQ5g=(XgwpsHRMs6nUM=jXH#N4l;Y(0osUxE=oJ`#t6%)e2kL!N~83#Yk$~24SsgUU;UG^ zpRtw!^0UHJmsH0r1@-VFy`>Ej-$@n=4_r7}3nGu%r`jxawkV*nq7cZCLvaVum%t)J zracj+24?E`2)_D~eNwG?c^0AfnPg7ke&q^Op&anf3IYY4;#|0i0DV&a{lUZXRfsL% z8(h7?%s4~kT7HYGjXpdc7$AvI(A!4)fu;}LAJ2qyRqP-iGitH zWamHss@?&QAs_nw#>2wlQVWnTS+7b|I{O8OM-?l7Y%~9(IIW)UE3KZc?(YVU>e^a$ z79HExwXmW-|H3tCdAag=@`CBcUtlm)N}szS|2e8hE1@DuFA+HPR9i&u)Z5+xF0m8f z^<-L&Kt5v0AzJ}PAwoJcgYkL(nS{m?dMVs=S5EoX1--|y+;jAs}+TT8p#XGG?i(IQV^M+sZ-G5~R>e}f$(1!fU-)M~I~=ouRi zX#pm>Fxv-_6- zgMmey8&%^Y=tc4X$R?A;M2J#g7P9mS54XM}dDkNsr^sGWbr_Tsn;iBJAO0;6812d8 zdnoV;6G+3!RhfzPj}NfPjfSO<)T*hIjp>o+c_%y zsIIV#%a4%7ANa>Zi?WX;vfbuK_(b?kF?)gveprZQAtWpR-lD48L)kHq?gM138}(>t zXu$ACt{kPYeU2Irr0H7_n1Kn@FROVrLXP8 z(c_9a$03N99)B;T5w}>ycYNpEePB_QzU*!m;6V>1OGt_Rn1ccol1@SR0j)iZ7 zUyVMr=@ugpKc8YZ{Wr)?vPuM$y2Eor#U&C_Rho3xo`^4%+|U+p+nbquPWir-zHGmu zaiLTkbpQO^$Vf7LZOMQIf&yn=xZsPq1jPqocRfMrAKWzpCh{1 zVQ8wrt90Q~syI&nMaVVnrccWdZAVVA$jlDbh}xFNz_8Qh%YZ9gUCkU0357)wz7Klw zU(d30En1)c2$L|HUuBauX#((TX5QWy1{yzeVdTk$_6z1?Bw@CH#{9-&_o~>5F!?GE z8(C2&79~lPgxsADU@;NE1X#?|Q;m7nG9P3LHbnp>UXNBus!TQyR@-Bo%Moj~f!K6{ zsj@+EqwzH7Jlb@RXMi!Z;^jY;hkdV)W)izPwvhWqhCBL{qc3jRu zK@lyNftv|6+I)Uz5D9twaYe_uBEIpftB7NeyzFomfk?%!+{i-HI~K!yt_LouH%~`r zGO1NoL{?uAQBYLms8~Q*`&YB?x!+tu`d9FJy?2+_+r3k=9ZM*$)hh)dLa+P3VF95m zEG#lXIP~G?fDG$Kxstzyi+2OP)fxM{a&-C#U0cGAm&9BN)6Yxe_FW7%%uv|4M~wpqVISm}V2 zMIgj@(Wm+$t}m`h{M!W_andNe5bt=aaR9=8yJ2rYUcz*qMSxkp25mfN`sCGL+QW+F z^lKtG;H6_(Dzda>;RtSk$qQ03@=^#JRh+!n29>^;tu8*&1{*r!>N%?Rk~zREKg0Ni zr&&6WRroVjx-)zpAagli{-jKY^@4l4_YI@;wTpMs+Rl^u=|q)vqG7X(bm_7?J+OH+wWlIA zVUc-Z5#5tym$AQm&#mUu90TG37&LlZN~k&xqPq^^VzgRwfuX*;;HTz__|)XMvF ztH}i{n$#G-_Xf@ExSE0j0x0UKsMEHJ>*!lCeQdE2JGG$WKt&j@c0+}=>QP~{Uhq>9 zO1iy>cD~87>dFTQNvB+*v|gg>Sa@)w9u) zXZ|#H$$5sj{5^%nYZLsil&PfOQZJU_(`30O`QpIS(DZ=Eu(Q_H57ZRz2WJ^GKT*(dFL zxBMC)RF!L0Nk5MVRH2bcXKFn`XUNJxa?DVv{%H_x$}|XTR-gLyMeH@`0z^nB^`%=Y z^ctZ56-@XV;QCpc+U|OY3UCf^7!eq_4T5x2lA#|wIbi^b2aB5tu5=>hl0jw2hQXkX z6I<8!v`Ca=6+8+k_ECn3^13;!fo5&Nl+~=PERZT4xCLj& zlhYQQ@!nl5#>qp(_m1>ey7$w|ZabRm+uqdga+#92)lS-i-%wV2JFK#2v~#{d?A~*K zCjDNm+)THZo=dU0Qpw_%p0Fm@-7{mLWniLRx9UWRU~4l+>)pz>AIVjt6saUZO9n}^ z$R%}R1Ib7VS0=tYa)Rb#XYy|UJtrOOwNv0hDB`hE@N(Tqp>su!Tp+KTNUS3XEZZYX z#I%tb7uo_D@%Dl3>3dE(FKmmAxi7Yl*P~BLtwH}6aL2njuC?I+b-cV)c`aFIh4;%+ z#F74V6|EKb04a2EM)fHL@u!Lolo7(2az>1ap{Y{iNS12$2&bzlD^iw3TP>LLXi+^(;R^3S6F;466j&N#GasbSKXvaqe}aDX-y1I7zHk|{}JQb zodQvUo~uk0rpN>#6}$hj2{ZUA@1aB97G=QMN<79~*_V#Z^xtoiAvEO_`aNCn_s^n2 z>-PBC%pVa-zo}h~%~VSCKT2;~h#2`ah*mS9Gb?UJri{ zpXxqe1FbGMVVEGpgJN0G!%;g-?X0pINegx_KR+)2`kKabs^r5iTU-y}lrBrnzhhLC zO8StmR1_hk%ydiP!IqPX44Awh)g7-o66C>N20pPwvjiypMhg4u!Z=Jx8-KNmX1u@s z1{Jehr)tn4mBvHBZwyTWFKW@1xC?X=o^I`Z=a?4xZDm8J$kpMQAm4&l~~ec%M=Be%|;e%@^?^(g4_BwgvRC|fQg zDB^-c2P709F{+`)z1G2Oiq?;cw;6%=8E=bdfg^4eBXwI|p`@Sl3Eqb_p7mv+JhEQ#2EJ1A$MN_2?CRvc-cb%I zSmgShVSs26n@(c<9{8Gw34uF=MBCvmsPEWCaz?UdFtr_z5t9 zc9tui&ZK1(^oh~8qy;h*qk9dxe*d@@_2Zg{7)%TW6Kp#_R?zt+^ZPim4LaD~wWGRZ z`+HC!y@j4?Qw|PFemscT1I=HxfqB|{X9vA5n;(8C62q07Ym~EO`*mc^<1*CkU*y4rL!yL?{@Ig{V21Zx&zGguR6IuhZf_HcKnnFlLk0qo=QgDO ziF4#?st$K*_n>~CT8IDqisiDt>7w|>e93uqC!l& zx)8w)dqAPfnBxV=?kkta?eYr;F^2lbMJsWnsVB7pRy@rjOJ4Az5|wul=Br2&UI|p7%2#;P8jqZ^GHOJuUByYo#t!Yi?wuW3xW%;UCGB?aLz;Ok zjZFNM`fGN<<$;UU0AFf-{(vtSJSKj;-($(7=0aH@u3Jl+NXNdY%k_)Tx`SItEsio4 z4A9OgMT>^hWq%#!zBgwU6xaj+;`{fYi^Xm|E)mKVniM&c4NXmZ zG7#UJ-|LCmIp#99T9Rc0PVwE<^59)Z~f%91pLJa{VcGC}gP;Df2 zam!n6w%lY!H@?{lfa(b)6GHD&WTOGNjMmzSrl9-ni=uofiCRaV^KAx{x=ZC?+HNx( z-rb^3oam=LkFKdHu2GQf#&ydSK{hxb?3#q~V7@a$`>x>qTUTV>&e7>)Qc+MXUj9_? zMk60_eOv^PoH*)*MB`dUUY4+oSnH(Z6M%+BjIlzTMjH2Tu{Y~32ZZrZu%CXur|_=Hw)7~opV*okGK*HE1xM9Pw5eDZP6ZBP&~_>T9N$vgXTb& z#DP$6xgIF_y+{iT#V)#nf(c?Q+63%;GrGw_2A4(iss1tRSqHdQz4DmSD#5TTi2`qN zGGI8i+4{|IPTtI>qW;iANAcP4qmg{fI%za*cJ~7)mb$Fu$hcXHY7R?}sj{budw{43rov%+a!kw9A zj;SA|&}eLQ<43sx3ie}v{GA7P`;o&zJN!n~)zSeIrMd(*9@feA)ymplkX@)_W1hP?-;N6cazf#7XWR$DZwIp)h-q5sb;_sCD1sr}o??jzlv(;ki4e8_N^KR#7!B@RT@nOfT~kW?(Y`p&C~y7=k{&&h9ett}u9v1Qnym9b_L>uVO%hMpZgE91O| ze8Cbun-*+bFrPG9KCjpZ3+3~E+0VUXUv+aB2=-85B_)*;XY)H~IeNo%)`!JE>Cv;? zs@Tu8AR_fLl{Shd)Gz`dg6X(%_)yLJMOEf-Bo_$Wv5O_$a&(xN&KSI;nN2k=m|wkRK7O7rkYllV&<SV`Qh&m1d`Qnw$nL^w zN8?|3^ke^<`@upxuvFxJV54uPe?m2ElD;mH6k;5B?E`ULnP2xzL!8b0P`MOq65Cs6 zH*15qbfq@3=JQ#^&HCL$DpYLzy0z}?qU_qB`EU+OY!gT`@#8n*N?C6ysd19T*e7Ha zPWxUxO)UO>_SQsLsb5FfWvFQ8Y;!Bd&T$p5`G%eJQ1bI=JHY+vPMVUGLW?j-#?nE; z{58`_3G$tgvO_dxBCMzwe6$i)lQ(j@cqpdk%f+m+C*XHS)96-rmn^qpOTov1_^Q|( z#8>aMz2*#}I6k!h%@YCJ>*$A|^R+%nK>#kgv#b%VlEA(#A$>xtdg13^&dtVJD0m&Eo;Jp4Sp`B{c|CmV@2+1@Msamwr*>xRX8 zPFC5k+sa=tqTB5r32O-~iAYREJYidNr0SJK*dC~;s1zO_CSvaYzZO8)br;T7yuv)7 zt|k_kA`y1_(F}g($C}CBaXl&0ak)?7En>RAe|Hh@7943;5R^eQl-SVNq5yo)0I#oXU|-d!&tm9bJi;}R3jhBl+W*Csg9cJ+e2Yircy6-pQ=r)qJIKJgS_ zS0FEZ=3`!KtI)>m#;BHYr8X&-h2c9APLm!VD$iEYhM>D73JU2(?-d9@b+YYUVO6rT z1I{d0H`?k~4^Fj~N1yQ}a`#8~l!NI^$tRe!wda6HIQcpdZg#{mYpz;O(*o959Qd%N zrikL*T##*6e)gaTrMD?;)oigP1j-)=2;@nLJ_mCS#qK0>OGv~JXjE76YW~=~oJ+hs z&NAQep~@}XVrH%Y__@Cx&dwEabZCzxcf9#iJ8hi$oaVL;0a>=~sveHtT05^*GRqH} zMM(R4h7W!irk15M)h5;8Ntwq5O5qjt(jMC$1z2!NP;Gsb+cbMyP8?s4 zVq*HKl~b+?#v11jVK*P#^Zf(Y$xpqp-5UOWk5S_yLdbE=Msk#kvW zT+10^Cei6>-jY$NFhdlS^blUYAF~|0F2iEZKLf&@YaF(1FvuWY&|SPe@bee{2@Uv3 zs}&6m0LI&P$e@p@H9_)A;-IDSb#tOm_g2YOa*3H17{ai8MZp$T88nTk>e)G^-hf_= zWCbGZi6Se5wa_iE-*yWM(s>S_+&e>0sXl&Mg@yM=+@v`sPXBrTq(^@#lPkS4BzXT1 zoq@p%yLO}{B!q|0U%lHBv_%2Uik7wP=uvUNdKuqzL=KlqP!S*NihOMGJmsyHi%VE7 zGSVMcQMEGQ1L}FBkt%tU5zZ1*RkwEa+)h#Pwkx?{Vu~EL5^jNc=M>hP#9tTfX@q0- zzym}n?EN)ZTphf+ceKC`@C36>?OmC!^|PPWEnD_3f&g~ds9KAZ3qUtm-o?#3HnFVT z(7L5g|FODuN>%DmeppV6kWM5tP>gat*!2{;JA){TXI9ME%b2y+9J`tnShQdk(UmEK zS1oO9Ud@5B0NU9Rh@F2}Z@+CL=?n`NR0#BTgRcLlU*R6clDmj&}%gfp>u${d`u1go=x`+ZO=*400 zMghan_~xY-kZwa!SN}=YvRkUibPfa{LUXF6(+=&N0+|_xM#=WsT>h;!k;j1tfuu&9 zRbP5^#aWKGjb*S37n%;!*wYpr3o+AlyjM+2Nzh7k2*n8IKsFZ2B&*j^8g%JM`HNqu z-O_I=DPFU4ZXatJZLzEQm`YoJU{WIbTJ@;`QmSPbA%}Z*#gc~}cX&Qa^FHc#>s#hK zW?UuK4E+ot*yRx7XhPs;HAhSgberz7H0C%U_&i_&bT*g$mF251wizEIj~<5vnCpPIN_aoT{Q*CK_2 zpwORb`UXa3OcMNqKyt~sDcfhSJyfih!D__HxdGdlUC(Qa2fl5H{Rshh4DuO2S0XH5 zt-XKgUhupdCXU?eM!0p{L2ECsz~=jd@f1}YwHH7dz*QeMm;3#&rufqhA3!h&`Cq*7 z3bKW7_q_^zIu?M#yPtD`Flfu-p2hs2j7;-qe!KkO&$bN_&{mGxH29@@Xy592mvY0* zCg7IJ#MN~{kB(2dIUA)sewsDJjq|?+UOYN9yGhZJ%CI{-m3MLeqv(#4p}`3oPiNqc z+keKQNW?Xw7J2CAe{#dhVOk<+*aHHE-Zd0l%`AHbpE^xlUyX5H@6Jupr%T$uKDCW( zpy`<6dOn3B?yCK`y#l&`J&>y-_S)$~Z&Ww4R9A3+Vi-alal$O23X>pI6<|&OCVD%s zZICe%LlZiDb-GGvvNSZOF7|gOGR9udDa{G@YM*pU3?>Q$W|#u?Rk@^2u6=oXpw3Dq zQwc!|pO&F5H-BGoKnfe}vO{9<+~E(zp|E!F{ZJT! zr>Ti4JMHJicPZAxMiEi?JlXRdS7^@`TnsVP{hWrp+zDf}IuwPScm*S;%(t@arYwv; z+m4k(nggyUHZJ4L5hCWn&#%0^g8c8C%y(iW5OhKN&^nb=XQux2vCM$uYViMV`)Em` z_-Fxg6FvB}75XDTt4Pyr7NL&2Zx=Q(Ap(Y*KVOHH*Ef$Ehuu?2ATz@TecCC-Jkz?L zW)l7P$I0$aM7~twur={7a++_FNFYhX{m(z>vFYZAJv((E^3Jb@-^&L)=7E3YKASOR|c8?$g3cReGZMo>ee$A6|Ko5;g%&|Fi`7LU;KGcWK1GV{?6X6 z+PJ>%tc{wek!%-Qx=4U>@HX844Jo)fFY9%V6uHd}zA_)dz_L_ls)Z-WkA9wgauvNL z__^X(INB1eK)B6S#!?fvzo(wV8-lNW9#C_xdf3)z^ua^`qu`{a3%v&CU+RmSG%Y#8 za1!!wugdF3x)L_`U$Cft?(DK>DAqaTDUSZmoSqbuqBQ9pSsHFe+-&|CzqDQjwWe3# z4f;9uss!cte$mDtN3y+tb|F;hTbb2b0l)9f2t)47>APt5@}gn=g9KuWsZwr))=2|9 znuISO4Esw3HA_LdGN~G7Mn$tf-Qk0oltLa~T3f|9DA$H=DHabiM3(ZEOCU0sfA0rK z;lX&2=}!+=6$e7eQe~C1VTmYD-kA(vrCXzDor^RqEG;8`{c-?k#2WK>C`TV7Moj-JAs@pm}#N5CB#D&aK;93!%h0Iyi2JSnU1;TBp!w?>m1!D3cF7eKsQ$&dpiZ0cIj%9;(1!eh zsu);N9{C}6WM=pK0{%BMM8N@v^qJj=6r;{bBD+c8;4ZQn8jteFBFEUbg}J*ULv73L zTD%YGp;HCW26gcgJ#*=z13i)8z^<_}Y!Zk0Bg&=jf{-8*7B#ikJu8@M1)<-STE|a~ z!44lC-!gYijt~uv*s5>_Ukbs4GdhD{S0rJV(&gn!YaJe`TwV9yBhm3aFQ)0tLT;xH zys0MhM8?+EL=*Fa)3lk@wuPvjDs^2=%;gkEo?oI1d2FL)IC!3}d>l>ZO%%HmRL>Xc z-yJ{`a5EY5q5^p6S+8FLt0wJ%QE}$M5p$=Wh$Wuq?HCCQWJF|RwyJoydoscx;wcFF zzxEW}B&NwWE+yUal?*FTLjhE{;;j^9!Hdl?$r!Z6;IupPL}Stsm}D@qTtdnHQt&nb80j)oy-l$ zwkrsD-M(tsR6p9+6+#)d`$kDyJ3{}8idx9``^!g|HjByy5Z+sKES&C1_SRd3D&vg9 zb8l>{DuaEOmrPAO@N@bCFEB6kfj;2Th>urpJmH01Rl999QUu>TKZ2-w*QJL7wqyCM zeWq=4Bs#9e0j2=>+%8YNre^HtTN?c1{`X1psf$k3S;@1$8xne)398c7Z)wnB7V3MV z+rXx-friwJQEa~DXe`M&3VK0!-V+#dzQSCZx9olY;xZ6w;(Bo+$ACg%?|Vu90q56n z7FnZn!t~#9+)4U)lwzMN3fml5k4CMgEGfNU^go%Y3VcGmF}Hga_0K+?Wp3WM&72&} zof~pmJ*7vq^gTLrjVz@er0;|fRH)5zFBBO2nPT8e&GBi3T-*rEPWK&&*fcX*@IbiU z!3hO!lf_iQJu?g461ps^CgNG~+l?HZQY}BmBEtjJI7}Z$&q%h%5o=AS^z&%!zz;0V ze`e#}ZzTl;%>`DxZVP+Z0*o1kygGd4xiU9-p3Jsm<4q0VpEf;oYLxcq5Z7EUV!6Gq zT1Bt^lWEm#6haBvTDdK;~saEHEGm$hX~eLji6QiHO_Puc)hElUdQS`{Cph0()ZzfGh`~ z^7r@mU;JEf&5xDQxyn& z?POYrs)*Nv97(_7Vy?IL72TpfeSbn8!6usnWaI=xY}eme8Mv zmPR7J4g^telBw5)?7tLNljJfkocY@OtYDbR3*b(JOjJugSP^_g1C$=doewV@XiZ+h zi{A2&!hSDA_MWkrTy!E)-x{D{{L$#cucl<_m$@i7R!FniwBevMEdjP=n3Ax}Sy?`F zyRb6$a$imT#F7piE$n&`ZS$YeyFPahQCLlH7RB16r%MWdtHDAnE&-!V z7r_>+k><}VTd&dvaF1#|9v`B9?n_a8$UMtiX852$_sE>OgmRt1?oOh_{us77fMoRx z(IdnSg~iO~}ogXiImXIMQnD zzxGi*qW767)XDzuw_ub__Ww{xip81+qe=_l6rxL>U-ew<~phd!_Zl_AZ9vp@NLOaOe(&1-MeWbJBykuquV;MQ(PvS0^Ls^ zpp$t!qYLb@UCfRXfQT87MtGq2B|3aJRsDW`#;!{G-CV%mEKh@NJ)n zp$YC;o|4!ZoF%M99@P48j}wVL-Dp>F)=nSY+jWlg{FE2?Q01JU!k?HvVVV67eu-+A zADCTH@JN3Bcy~R8yqiKi<9C-s&Wg#%nBufgAmBvAJ?U~V-UM%JlYb0sJ**&6;`s+j z*E4SD#lx{^=su1-wa_5^y5OQWhURLtpi`-GZodJz1bw%z-tALaJSs6M{(|>*&?m1j zFCjIFXTgo2J>ol>rK#?x8)n1?@1kL6x zeG6Gwfx7m_`0)9mP?!vTB0-(w)`+HAdB^%*hh_I{oBe&y;Fd~%Qn_?W-5Co+a)Tl} z1V`ZfKth7;j#s%B#Ur8!)sT_qTb!vpJX1#}hSb1ct?J#2hPHQstFQB$+ag>KlGh54 z1JO34&A#R{C+DBr9Jg^MoNl%}2V5)CvV;seBa~1jm04zA4rp&te7OsF%fL@=c@KS- zJHt#&bKGAaILs%c$Ly(@8^I({m-R{LU10c1I?wW2SK4joAOy8Z541&Orwh~3mEE*? zfY9ImzzQFm&sQl*nrZFx`0-yc_W}=svh?fPQh#RD1#QC5Y|ZyEGnpwCH8e)cv#RxQ z4((J%yc5%&x5BqT>8_L&5Pe+GOUu*;M;+!BNilAaJrI7Ed?}{d*GfkE`UdcD$piB1`ub4$8u)d3?^(*6qwARDXa#)$;PoWR0Z zyj&#U`&vMeJ85tH4jE%;c(YK{+tG%6f3T@QZAvk&{Q>Elu_HFOcI zF*yG!kRh9>NlKJu`#Qn|1rJOAr8FkaUeF?(I^wy(2xFCPFS0UQl0G?KrY%2g(v_)y zzW2%ADj+)nSMRmJ#nsoLeU^Xyqu>Mlz8ZLV4VP}9);4Qw^f$y3_0?soayuwVbT6pA zUCR@(TS6%koJ7<09HIk$semI5-7dpM+zE8=AmMJv3A=wqDMl>ytvKlTRJOszU#GpP z!%jT*D=LN)nelOD~be!{93$A1~^w$e9rIEMXaEra~X75}KJfy(ky0^y&P#I%z z^-0ZNI{wf+u#nFYLlA7T&JBsWocs6r>5={}`Wtmd9uJ*^_iK-TkJFd^#5p(LHQk`vBO0V-d?k$uggZ5$WSG$U~<>kO}IFY=KRt5*3anN)jQS7*a6F$666ul%JN~E;%wao@J{Z#F*q_)^%cLD|T2hzKe6KZmH zJ*`w!r#!FbtyI#=TRIyD&No7Hz#Acnwv`h{Mlab@%VwNC;a4`JPP!{KW50&fO2~xm z@& z3ArE8W^$QtJ^5|yo%*epf1nd-$dpew*}2t!{_^Y4p}f5OkEfw%nL%~+W$$uB$J2T{ zFl}LJ^9A`MVk?&TB$W9JhW?BfG6%kSrO`?4?k4~dki~z@x2;$`vUDx5k7-Utb+A8V z4zVBh@qDE=;2K*4C)%bma(&MmeNfG>Q7*`K1-<_Onjy`iNdBj@FqB=z!hqY|L z!-R5Z&?C3!`d?yps_0@f?E9)&4=Zb$Tz+f4#OSBr)hUapRdTQ3@sskw-ec%0sW!Kc zc7(J}>e$SCEUIX)D=;t;XeH4kvlJrR6xGof|1%Jf(&|UmZ6yBIvve?_%lp=QyZUu_ z=7>EM(}62FW1xjlQzSa<%_g&Cp=?h>SgG1Ya0?W>BS_Z&!vTdVD~D={4qKg_D}Grl z{i$4Jx?`SFNPJ+0;?OBQD1tE50J67db2ol&`QLw^-w!3YcX{L+wf8Qp3jAPEO=+kf z=NxY^GA*go8}jMgG(}|UU1Bp(oYgFn&%76j!J2e8V<`jnRe^Wlk&s9%cSswvafP(W zHp~owCc>wF9;n!NuYb1w68>|g*A3XMaG7%jvu2K|sH=n9_t?+e4LegBc)tHk?#^lfj8<^3OgLJGBAuh!~dvq_-pDZ zcj(C{p}V5@e#^&%OXsu@Dkqlct?~HX^ZD^l=!P>@vs8&p^0MNJvxG}Je>S$C_PU-l ziyO&pLRP#~sGGBUn}_%>Xfw+AI)vh6RzIImI3{Mn|H!i1F9nC|&D|t+-w)PTK=sC> z79aO^z>>DN*P=@UHU{EP{*!*a?|>>FUJ+4)_PQ_zhgatwV`34h7!^05Nr-=lk9&x% zWiPxOOr1P7>uFl0G6*|bxUs0PM?miB5RaH9qVD6z-dF zZNZmlQgfQw7S%I_o{#SYYJ+1JUFpB{fxK(XyGN^6!R{{TxDqnOHBR=?k^-t%QK(tY z)T#kL$`uEBFP&px8zCf%=_c*I*o$>MAlwOkh$Z>!R_Bb^OAl{4`;X*R)zzA{i`*aL zj#kJaHSzpg1@Vh|c67xW5YAb1fRD@gCE-wF!ERZmSt&Qq;OrHZF)=^gzmZ&G32?X3J5 z7m*+3e+LH8XziP_t8^kjIH&ZSeV&yGv#&vl^cOICEJG7zOa_?53z|YIQu`wh$Vf;sN?O zrKWE>{7y~63r4tKdd98mc*)WT0MML2JO1^lUR*Q8wya*MdVSzpl$VTX?53YlZi}J+ zE4I|jHy6H))83JnBZ^ffc&o13P9TS7k;ZmT5>8VoK)L%?j;TLZyTbpn%+2F|_)W%` z%_#ereR;$z$b_-ZG$sM^*8{?$6nQEKZ6$nAL{{CODqsjr4eV4i zeu#NBzpCmu!IWK-I$~Q_511B2mRkmK`enRht*x0o_5S&hyzw-ld;cKYZ91*=OU&w% ziI*?V!Q;2-{x$L6=VN%p#qbU@mMCvilOYt=_wI7i_h$a)5xCy7*V?SaQBSA%#2u3j zVjz`27ZHP&5CQUyi-mcfaI!%40g|sb%N{?se+V$XzqHSeE}|eUk8m(LXp5c(rECpL z(bdi!mWpOd{~1Nr6nnX&2SD%~Q{&Uxd*d+%a3rGp54LJQ#gno>l$@!hlhLOg64d^Z zfAmz2QNmMBC-DD6)TE6T`}!sAXD`_o<;7B~u?L;9EVf0T=Rh(iud1CqeA$AJTYR*n zrM}F8PP75Rzfz-zNlSqp%OL#ryPPf{5q#@Ei|$SQ+*;dPzzG_sMFW>R?Os`_sJsQ* z))~;JhPJ`0ZCqnb zbD)s>qXr8=Qcta|<%WS|%KCum z&!Ndk;eU$MgW4Mt%uf)VE-^WRqN@hI%DVdcJ_JIPh=>TF`DNByJ%+dLm(wa9`KzPe zY@~eyFyZ<6w^33ktIa^w)mi*4m_QWpasW;D|Fr-Yu>UN0aPcBY0~lZz4Qdt2Wm>>8 zgb?@insTR^osCVDZNu`SUjMN~m3aG2&rFX;WuQ2?efU}9kxrdh>@Yfh3wKO`+{cAJ z())hZKVN=Ke@eJg1A|qo!-YZC-cy3dqPAGa83SbBCA&xnXV{<{7vNP=URO`cY^#ur z-Lg2Noo>ZnTSw*Ye8VVa1U}LfVVRovtgX0H@G0%v{j5Mw%)BK!>7LrlKK$RsVLDvx zT|8kDZ&p-iS*(~GV_eo!*Yc=sokW8(0q+7|he~UP4;wD408LC_Ve}3lSh)9L4_Jc4 zaU1kYU-66x>Ca!#CH3LwaYW&7AEABgpslWPFp!eIX2@nfWJ3m<>A%Msi6-#ZnsxL$ z5XLi|>c@B+X~foXMex_4*!DRlnh=!{WL+rQle*+WF?TmTJ+eP|V2xHX^!_`DTKc%I zv$0+4WY(5NOai2OZ;9uVmjiaayaW1IKQ}}eh~4IkhC#GiXY=6b6&5f!Ty(IeA-_+{ zxHtdko-sEx+@GAtXuNLqm49tL{D(o1CE zYT$)G;@G4V&?Hsi)bJ;aMm~YcX5;y#4x5ejSR&gWJKqFAYcYtulU#3Gt#=L2c1W({ z0GVDNmu*GPXHU(DF7|psUbsgA)A{Tby?%|!rPxcAIJKeuv9U~GgG0QKosnv>4C1iU z!vBJ=p`qiV4;yg{w|Ys+I^l*SPG z8y`f|G#kvJ8M${AmdC!hKmBjjRCMYSE3oW1=yB3=EIrMwb3rDo%{NC0fG6?^H2q%A zN;^BEmrD*feEkD5ZziT$)l|GTr|AF(?}0qWe*AQ*0S-WNH+MrEn_-h&H@?{+6+0~z zRVz97k+&5mt15!go8$e(_*_paXN|Y!ClHz`8g;Og?2asJ)NyO5zv|ShB1>D9`c_K4 z!D1&7fI_h}Bm?!|BbS4&xmr_>yRM1cM#_BOVoB;+9)>XH&@-m+#xx=#KRAd&{S$oT z!XWqPk1=FHCp$uX88%}nqWr8`r7ZRB%Mi(z_9w=tx>@N#T_5&i49q$*xhkxBCP`>-o0;E@At&) z#he#jRzz**Xni9@ov58J2=MYGIH#oOIFtq=JI>kEU+^Z7lFBR3MCsVVWBglXe9HTNl=-Vg%HerC5wnZRi;lf#5m)jB8_kZ z2EfG`79i>dkyVkClanQl{(OCgxK~mEW$JV<#@jQFI?Il4g`YwTPETDjGBdOC^7c-a ziRDU?AvxqqrH!D8JNR8$CHYW2$NP!-OE^40PfssN>wn&ssm$u6@p9pRX7IkWulepO z(1ZJwIaIX)zcgcGV-60EKV4muQP?D3i-*Yza=(n{QD&;`9kbPdvph0B5QR@gc4Rpg ze*82ndM$qpm9!kF#~mbYyvtyAF{EUO5`r=ikCoKjLu{pE>0C=~tmZhcQ8QVQMWhzHrY)4N4X?3=tx6WyZCcdtpct#d=V+;* z?O*zY;t8@%Vk~WXVTgaxA71$G_mdbSgM$*=f~3&5{{~BVG~e!7d=0&7q*TnK>6~%n zNwZ0tU2!71$uRuM#VrDsY@b2n`KeO20-cK>1-L)O{*3n5R_M*iQ*ShxhF$%Y?NkAG(!ewR+#K|r%3z>zT`shvO>#nm% zMNxQr6(rTwHH}m()_OtDsJdWJ=hy1b7x+RazVMs^#227^_ifWl-1p+&ZzYBfz_Cg0 zkC6|HYb^n(dhNI?{r^rrHMg`3+k>n_LgM%K_%IkmL{^>8o!@*xQB3*M-rkRX-aQqD zyiCk0$bpWgXZ~C`YQ(=g#2p%NP}+yzTYja9W<%56ydGuex?VZ1Z2(>?>^V+ihwFJ; z!UJ|DwjOj&;h$fqSGg5{l|E|yTI$V7C@F1}^|?hNdLr=LlCcA*@!no0{2zh6t>IEgg+J_zpJk! zKMJ^R*yLJsROdoF!RwpqNVtU6)3)q-;Nu7JRv(hA@?j1eAc0polk;j;nX9h5eXLBG z1Q1;aD5iW-gC+rnX`RbG*P`ST!d%_KQ4Q>N_8=*<5I7@ebuG`F{q$ku;hjjS;pcNq zsVOfEQ`H28ro^DIY3NqTP{+bKfcf_UFV_lR7A5SJcr-_nxpl$$%?K`fYbAE~^vx^* z>b@Jf#|0njMkt5EVcpga9W6>t)g~{AYCqgR)KlpvU3Vk7BBr(FzV^6 zlmVW+e(AtY@ycV8)<3?<@YYu=k#9&Qxvpo^#|9LoDj`J>;ob38Y_#m%pRZ7;sSUH~ zO7lrRCg*UyYx0PEg^p(4`Uu5tUSc23)bQhSf1!R6cK8I~hWAMW& zbdRG~B~o*~4C31FkE8gl;8!)jXgTc_*PoW~MFs^%4_p+6?BN=v3dx$^wam?G5}Ibo>ZYcqzk5I}%Ov z&&Lu&e+#o+pi*-4amAiJR@WE}rQ}kZ8oj`%cx!m`!cPm zFH_h-J+a0B%Bm$x1kK3>2xmtzqL+VhNKq3}u%zc*o~-f~mVT|U*PCdz@hY_NAubIq zbQqw)G(DCh&B| z`sp%t>B5SY%pPcB(I$CpoWbU@;9wH1T-p#a@VF} zBwhTuOCSnOTm@8UvR^1T`)tUkSHI7C`( z7c%!smBqbrZ= zzuE6b)q^7E9gz%-3G~mKG*2kl*j{Tb9(l(CHGm(g>|0sU!29s1zpp~?OK7wz7v2sx zhsH)mzKnhn7dedqQk7{HP`226G8p#$05{&1FJTZsvSVowo3Pg4Jwog_>|qW@oR+bJ-^jltrY^6HsxB5N_^Lcq8wrHN-Tw}+Lb8%d*x1SR* zzY%aVgYG1X{|6#3ezBMaQvTB(s{f*TB8$nb1OA%ipB`CaGy+i}vG-K)Oa-PEwf><* zj;(y+EWRJq4RgtE;On?saRL~5g4fi%s+VXT52NgeOB&>x^Nw342?V;tX49hCUT@^% zT1PX!K^?%sKuLMxwX^Tj><9k2XeVjQhEsXB z{kq}n_^`DcQ0#$!A>gU=+#Np3hP=l|V%kkk&bd-u4I!^-h|qk_B>W}8m0wFdK>G;z zb@1cr2Gfo7WPwDj;3;UY)2(Z$1RXyBv5WcC8@|xwvmSWt@_b42OjiKukgYZYQ(L3< z7H&ZICvp%+`sdf^689*`&9H|z@3%Yz$uHZ1A4wMVT77S|Ys}hv&(=|DyCUelqVPT) z!G)`;o(}}HTsSTGNyVt9)c4?HBaJbN^o#57^MY`PtrZllA~*ZTM|q*OCiM28gLAir z?ywg-JoFP6rSor$zEj`l%)rJ5lu(jV7n%Y~hw|wR5}m3msw8BKBM2gxuDqA5%>$Mm zLJQyP-rsk{oU^7(H3kzh4``aaKu-mYyk}v+{Pl7(mXOO(y zl;K;FqS8J}L=1Cq5;e7W5&He-@b3f41YJ}9lrx9avp-z8yE}URW^w|3w0an5cjnIO zf93jQo5PMPw=8Ta%3$%gncseh)?*pg7U?Sz>0`3h@RD9aC^akQ=kNx*DbHs_z&jF> z!&@Lh>VKZYsugo}atZFD0eq?^Tr#X>5E?%xr#Rb^k*qzw|H*Y(z5#7`EHAgv=Md^z zHtes$u#ZO{_n}ZgFpvo-vrAS_>swn#wzlXLQ#5K9um`EiaSBMjvJo*lWCI(UKNpXy zYHJ%B8)Z^T9dm$wM&tY}MAt#>y@=Xg+=$1mIis!%-N4Aofy1M(u72)Oz|puVXMi2d z>t6zql$(PFwei}GOC#FT>h-+8>sd8D26jN|Umi=N=eU4dw(C@qDKZ%Q@L;O{7PZgw zuQQ3!;lDxxA3pbKuK$!by>8TEa;a1}b_fvsX2Kit9)n5xiYD{?%4ZIjxY9=?sHzxu zT*Tn+VFDM2`T8JbU=M?9&%5$$WJ)6MN2~3BYl3Va#E?0U>|7ql*Mgrfgw$D?$&c4y zd%p$;YyHJRE*^b%zf(S6|8pBmxz$nI(+Q1aAVA#~ES@|4)7hlz&I2eTKN&)X-Z+#? zTcr=1+;;vKoL0|m)t1`ax-_>L6QdD#DTix_jVVQQL^uDkgH|$-ZJ@p$3zp{RnzAB> z(GKBs$e^moD0yvRNdAWrqe+0+L&nZ7u~e+kmvtBM_oMA%#vvpS4YRZ^+c{kzR{O3v zR2;r!$H|~`>{4J10^47~ncnQt<$U2>4?e)q_SAjPb^|7;y^$G*p1&{mMt z$LPa~@J=08JU@UD=85>-A5Mjisw0Os>MwVBCTxl7zk^gS!oAqp5zl_zQ`@uj zT-^xXoE!=S!VVB&R4guUY`mwIM?7(b_O_pgMxKYk+B>}ASYBS&K+h@;-z5^i-;^FK zc~cTva5u@hO3xT;)jk}8IH1!9&~|}!|5#uP2&k{m()|2j(gZot;EN<|lEIFLBlfkn zTQaa)$RI$&1Iz2+7SBD#E?DRJ^$rcvug3H-jRtu?6bx(M*n#-1Zy{Q*LAJJ8E}$0R z@Q{EXss|t!X=Z8S4}3(N-CR7U9eGY*^V~&ZVaW#T?#;^w_0cc<@W@-()-4pf^91~g5^j-~V{-U-Xp%HE!kGNg8@ot`bS2m?z%%89H zgKv%#m)BSJ;|11r=&;IqYCrlvQfzEPHeCLM!m-FcSJIg8r6x+)*g?Z@o5-5MeuuZw zH*F!JXgf1Wz-VWSDoA;Em?&rRbi>9Kc8^lq(J?9F);%%0{0gumIR=_}pJTlLSqiK} zf`FxtD?nlXr>%L=FYFv9=;s^dPkDKN`F<8;=@Jq@rq9^`?w)!If*BYY{pVpBv4MPs zjclhy-iaIMF}d(n(-~tgeeoR+)}l|FDLy!m66gf zPWt*wb<5vfyH^So%LrpRI(7vQ&&K%F;MdQGwx64c{oVd61k%g zm8+hLwzJ^$-L=XtnohYayA}dbs;c-+cjqphrli`KEuIM*P`VfI4_Fg z_jRc39A4)q&aX0{S^j)sr2ey-wD4$f^k0Sw zSFN0a;%4lBmV7z*SjrkXC)EYrdZf-uz+{ZV*WxC}5n7Tc)T`wIa}TlCb}3bx?es>X zQ#Kk?-U-j!kyn|TSn;LGbiU!8`Ql@{qO-TWXk`$MS_tu@#AMl?{ug$0WHG1Ez?Gh!TmB(Js)B0JX>Hl;30b zfK>+w(jp3PKkI>p_YEp|`uL;+u3&8tP9V<(IH-t*FfB=!;PL^DP7T-ryi$HEYyX`I zSR2+>^r=pbkGtQU7;>7nDO7j?X*j@$hdwQly<6#cwxI_XwMI6iIk;$wo1OK`zscF- z?$9kYTGqZ{xtcn$a@|L}Roh=(z7N$-Da~%N{ip!*uPn;CwyKphi)8ZjFA2_6S(j=$+*T+e4;P02?Z9#+Wi!=++ zax&T!EuP!AnWjiF$d6}PoZ9@T z+<_8s@I>Rse+{{lU7jhAz)?gt>>%+RsId8nGW`8hSWmSv7*OC>)mAsOHIMf7b?l)^ zrYH`B2rR-Qc@3Q;(Hu}venp`1UE0d=HN<&zoAsv>s!OIZl@cltVq+=(V*0|NdI$?V zIXjziZ6Zq;)GJED`_FodGPC6)U-BoOwPcYL9DcBa*h;xyYyT{~AveGwe*NhE0Zora z#pdHzos{8mMdKyrwAd49-S>chTLEf&0;Vb(QzWh>u8HUX$$&(xhK-%AQ!k1?f3@cx z7?7DlqfLj!(4YkepRz@I&?vM9!SM3Wz0S`}pZmL!-K`;~Y;N7~*JIe&G9Kgc#{w;( zPp|Q*MWt-rZ&&242j(47fW#4cRX%Zl z-Xs3m9K{XKGi$_TNc0d3xhM3F>Up6Xk%>s`eliA>kgA;Ktx}ulH;-b}Vxa>7lhx{X z&RKnjq6xBXUY-uhQVN7{cHb{g37t>^ws^y}wxJ^vIRfyDe%SKL62mv%Ge~QH_x%R) z6`*5(;O2w?h%3Z3Ge^Mn zr_z}9`VH&mC-NcDwy*-^dF}Hze@c(zNf+S~ajBqhfnD;IAwAu2KO_ms;^J_rJa`o) zi@xE@*%loQ;^<}Qb3=g#e3nrheqd!({Z8T$KGo{=h-aA1D)|W`5Q5T;Scq|U5$(m7 z$^bmGg6uM<#M?(Ej=>7sU-e4*yC1>Ge1;MK`};T6Dd@1XYZ@eCN{DY`xA!z>!1~15 z`N9qe%-x$jJq|wZ1ZU+`@=?kmGLcvMYpq`9DD~Cv01R3lpXT!PJeUF#IDWlOS9FhV zUjrA~>Iuj4J73!yNo7VHBd?L0k+2PD89P@)L+9APe@u_)K?r!k6PYIOKA@<&2@+d* zd_*j|CZ0~c zMli(FbzavB|AM^Rc+SodsJW^%fBp=CP%RWi715e}>m}B_gj5Nen-HGpba9L*a$tp= z+&?qXG53^4%rLuY$KB$f(jZ5Lo!q+mj>_V29;9C<-o;X%OYWuwYCqh#ML25T4!$dF zCrt91ck>!Yd?zU}-F{Pv+Yl>yV?x5E86xepta*_&WF z*aB@P+^&P2Z8Xz3>f04rWj*#6>J>_j+G4^}qH(v945#UpXYSUy;${t z4=tM&`e#EKyh~{8rQ9}|qj~#C`^4-KT98Sb19rJGkewcYZHqeIibm)9}rQh=eM}9uI z`EFa9nuc_D3w3(bP*_X|m2J1*dM$@pkPxCF{C8yne&_%li!^0z5HOdOPW;W5pIP<0ye}ZF7#!58* z_HP6DDzqbymxVfIOi?TPL%51qR4P)7;;*Kg~2$)LC|Mwej~>}~YX&bv&LaW!)b zo{Yr1b`AC@IAM3Me3VZWfCqX;T! z(kDxwEueLo^4e7s)3i;!ecJE22OG>X>PEyH2igRYK53LjbX-mD^KX~sWo+koLfW@> zrqkZ~v9d>EKfsf8;<9@0dPJ!zCuS$&P3xAqjVF%CNiv4? zsTUX{jF7oIQV>t9>Ik+qUm2y`S^d{G+WbXvf8b;U=5tQ(dmYe#^7!~DJNyAbmDm3c zyPrO~{b>if^Hq>s{pAf~a5nIU-QsSRO1hi%V*=T{?LyRE=H#RjFf0fABXxC-wn92d znjQi7MN<>Bbb8rFk6T1Y2>!Ceh8c;JE5q06Zl#PF@}M;oK(sHoKF)IQ^{pSdG;9*31o8@?onKL;Wxhr5lLFsC1+PIAIymj zB1r^4J$i4ny)$??Y+LY=G_-dP@C0!W6M zZdl>>V^e!S_ZTbCVg0;`k4=n!?=&DTDg2~*ClPvW^~t^6{f@`S$7f<{0x;&Ttgr7~ z*Q1IiU*7Nr+-W2x_gjq?h#24fLI_bt-BuvN?6{XP9gaHHD>jK3Nx0+`)RU0!pSl!A zM2v91T-(|(<0b((C<&}kpllEV@`{Bc6Y?B=>--POHnX(M0r0$*)>i&b-*oOISBy@y zaKHD^~mD+Zs(1+g0L4}cZDyd>LH&Y+LK@y#DmA)CK& zLmtdtTdrFM-sSGm`n(fjxA!!Y9isOca$sYY9 zP?7xEYRSa*^-UIKC@Znu(0uAkv;@pqW}&$I-jHu6Mz0vx7y2o!4`r z)v`Nd0w6GN#2HdS*|lOEGF|cAs0WwexHhPmzlb^@q&%<@??M&6g$Sb=Ew&vvQ6R9R z*|y7bXKr@72z~Ny3n)0ryp!BexhGq@SiW<=B572Z-nF7nw0DoO=E_DoPH?-6a(gPG zBs@GPd% zyb071b=x<^aeQP0Aw}F#PPv>H-cMRIi8*Ol>h$w8^$+QCxIl}* z>~;V5gd`x%$imX{zib0*>nQK;smDhiKuZU79LX_i*5!rO?)`n0`x$s=o&Dd#y1jh_ zT$U!L0UOIXxQL!oF8M2xP8RHsk)X^=L7GxY6g=%Nz&C4gg2vYU7rU{s5qK&AG=J#* z9cUl};!Bvbc*NcniF9+n`F~4N#~$GT`ZobD!JI7*kpFA}BIY8F15!^*tOdk^Q=zZ6 zai^Y2Ac6P_3?x48WbN>KVd}}^=!uNkp;++hzYc3(5h-vT+QUU8|SnEyl6iJLt&c;{c9yWJLC8F|@)t!?j9tp1=4ivv+(-NX!P(OIW{h{yGXoxi<;X1`U zA$4yLI3oL4<0sxHLms*{J*#n`GR&Ytc5%Hki@~6ZIG`(m_S=yq0EOkJLwS3}Cf+d@c( zZ6u0?pvxbj8li4~^=W2Hu-@%_?>jP$r*H{FYy=19lFk-$Pi1}kF6MTYwo%?3`6V7B|;X~29~ zvH3vG^~-aicyY@K!zVV}Z_TH&CWajRPgh1iIy{E$Vr?Lry~y^^KzSleCQ4aD>DHzYObXF%TBPVcYfac-LEv!<@dM$;!#ypGQ9o zG6!+q!7K~;WE=&Y_(L{Xsf-|BIgENjY_%x*G`TOVxH(ZISdP${oLCkETua|R53n

K0& zhX0C2LBKkw^Ikeep9p)i!Lzw+VgA376UL?5QQk1Rs1L+MeUw0Ds=-R|MY|$1FRMu7 z%Ueb~LNvHvSGeHPB1A(hG1s69Kkko=@XOn}A?)8t_zvUH;9iVX*2W}F?|(>|8LEpif~EqgWe{p0>2b5!tT z&uF4%b);M%UycGgKJl-jjcLE03?P>kk{6~%h6h#Bz@c2M^TzCIMAVfzyzi#K8)Wq@3K{DIr5 z!WXAh>Wmo>fGGz=4Fxj`6qnwA>~g@I1MlcCq06@!Q2LdBICpZrvc5t^h)}!Jk*=Y^ zi05@NmD6<M<(1y+)?g)q`u=Rc$3C`{C=;D3cp92Hdk8f4y-p0m&=cwzJkD`+39yd~sF)~; zz+71g=$~$6t6BuB%g=y&g3bF4&)dH-zQ`tDv@LJv)B?j@Cfx3xr)ea$ZgdU(YaG3q z9+43?ZPA7@h~K`9Pdz$0p$Q$lCM&k?1&*Dyu=%1Vi2 zgL@a)hDT=9iBiAM=hE)Un6eb`VSf9Sd8hLBeah9_5k0${a5K8drDr%HQYCCym)6H8 z+p04u1z(44v9N8?hjxl-soA}$&n;wXLbb*81r@MOLgD#WKr>dFvqlvbvYAuUa5F}^ z6<3^~NUP`vYJm)8CF;STf?!>uQHuoD0478#??RR6E+STYf$v8cL*zs z){rEOFX#w@926si66A!ZWLt{dhlVAIxn_&YM+T~E1jV>(6Z;3EGbi!qW$#{eeIY`* zAnR8}T00raYB%YsQMYvCh>Y6mda0j0DeNVrnt(>HF5ibjO@>WQhK&G!eoG2kW6exV zo-er{{PE%ag)V%|uN(6Qjwj;yo2BaVe?SpH`j(jfpwz!3TJg{i!} z9E_DzWjgS~^4gl(&B%UxZ~M|*xRW0%gbAL9f6)x7B01TQYUXH?wRwfePh7r8w^x6_ z7>ko|;=4+t&h%Gx6E&d?dA0yC>M2MF`s7yO2pHSUE`u7Pn}1CQZ$s-ve71KEN(pLN-tp?~Z_oFukYfI$pVDDOCa zv1$So3d-K84>Q=E4(92Y)07Mu7WILUWVE6nVBD&}KfXB}^j~kZ`J|QYTKvsT;7d2^ zNf>f*ae33TDUJMjYVvd`@L~y!sg``ZbKqK`PQTjykvA72+3WleI%1HM`f3j=A2q(8 zQPLb8xHu~e)P#O+jx1+N$RYn0_v?L?K<+dz2-#j0cGc7rM1Dg!f6(GwDu4V7oj_YV z^Syqd`pG#+P4Rm|Iw`^8O;C$OwExpuU>yAHMXtDK{Ozrfp;}SN^N_-rLxMK1Tb1c&PpNPt&YV748Lz^d5Ui%~59D#{W&YcA zNeHtno{WtBz*e1_7on*oI`c_kY6uR70)9qQefZdKvbnhmrqP>* zc~(8HpFVgEC~||()q>)3re(?Bz3an8ff6FBOIRZy3LRC#n0D%;E`-o7SV!Qz7Jh^d zAqUk5za{js{4^!$&>~?`HooO0@zkcwu@6;7nh_RUl+}L)mgVON@7)B_O9^TsPEiB{ zu<3d!p?|_8m|`?PC+EEHy%gqEi#MJPVH`xk?P1l$R(2@(7Jl~lDD5~JI9>JAkvL`P zJh(7ei(m*vA-JYFY8S_|#gj2ZS&R8yd3lANp&{@dG?K{zZ2Fr(6WI$Zuvz>con;Pc zx{%@AwwDgBk-YL_PVU=kM#j&%0sjU15^I-ekm33{{n(-mpN-(B%$4%%g~nFAg1LH^ z+wu{-dSzCjom@jIOQnt%_i;I%y+V-@oIzy1D{qO}CMi zqa(*O&U9=&pr}Hzm5qYnX;u>#G$x$FX&5A%^)1{j!VW&B1=EjjR&Rt*Ub8=Jr{Nidf)j;$dqIPg?Dkk9T^y&cC{D z5ST9VyRJ)cCay9gi}}^)^Q1X|p`7iEAsQIu$e2VDR$9`BD*STp_WRkyai@$Nnka3$ zL{EF>q>Rn+RWmNsWI8x{>?g!yaa$0jOpa)Ppl%pTmL^$-lL(7;kWo`0&&-tkI<=8W zI=nX0`4*pwZdWO6t<~Xd0jM^?rr_e|CL{0>(!s8wn5s27J?R8A+5e<1N5><2dF_Vz z0FVn!Jfa{45_6y>*%=YP<&q?v|JZ8Xyn2%#apEHw&r>y|&YsqGwa0dTD~b|y;yu>x zFI3eWsy;aV8zV1)Z6=$+(C3gKP0BfQ%(U5L_K?fky>2ma0=E6^wfG1yNRL_-Y?Lf~ zY~&P3fVF*3P{Tq7fZoCZb*TBrkJ)9rd@i>HhdMP*x2x~SHv>OqT$cr);kRGtbU6!IzM4*OU&g>!%5fY*jM zfinTUC_b^q!reVfyHb@9gOk2^?z5}Qyb^a1wV_UZz;98|=|qY4T(Z=?s>Aq=sfa#! zNUYiO5MD;QDby}O=1P!6eLG|~u9;q;B82qKerl!HPOdjAlW&k@0Ich#$MP%Pc~inN zoItBsS=*3z2Vx&ao(W}T`3h^EOk6+iaUP{I36X$U*1lky1o@jAnQCQn=Lip*Sc}Qia%~%NVNuH2TF(oJD;e(sv`T zeUQj}8f8(+aOTq(54IGLEVQV3?6{!wIHq>pJR1wrkMG}D3e%RBsVpIKv&#m(bdHsv za&n&SFLR_DW<&^AP?#6}?Uk4O=R@>a;asWO3>u=s*!vhsvq)s1iZa}!(z(de&nb8P zUgZ6@Vl!%A?)h-|j$LS-I!+g{X+OJ3@*t%lW)eqot*V)w0xe!7ZHT@?=n3>)1=hoh z?9R1WoBl#IQsOG8PrtUY{M;Ze?0$+EYjfjh^UR$}$~YFXf0Oy}0AF5i3y?N00Rf7o zZ-;Kc-*%?|-ZnH=nRSIW=8=Sq67W&~&460`VT+XNW{_SAEO9G#)McfH%shaWa&X88 zv{c2~Kdque>vJOmsimYZA>;IVZ`E1LY?7%>hKc*Zn|M5H$9r}GxTOJ%+mO+B6N%6G z>En*bejK0=Bzjb;w64)9O^$Fo>YN#&M;W zbhR1CQv?2;RKGX6r5jg3EO7W*tD|$kgXpV84&!RTNsB5mJtjO|7A$+6hxQdFoWS<4 zeLxscsurQy^5z;e@QLH;#fY=e@@B>Q$DZ@oWJo`*yzh>PioN@%zTnsjOEG3KR)RZf zP$`t(>)S+{a)zFPo-9h=s{;S&$47FZ8MCh%eM!-r$NnEo?xJIPJ+x>+%&sHd! zus$IDc-Gn@sW-5?jVAuElEBm!{&aHPGvG>E%t^U_efB;+REBGq%=T=br2`0ZgOhL3zpaF1ru>RJB7gW^OJKS-yw_E z5sWxz7JS$d*}TPY+~^nziNN&gI?DuAHLXj#f9C9&f1o_w)jshVO-l<7vhJyunFpJe_Y_81XgYm05>8(vFqoDH#%tC>mT0 zElzZA@ZsGJz=RI;ia9ZaqpRc?aK`4Dx8HtmTX=zE!8cC$rW6}K$U)ZaTI73$D%QKO zQ(ESiN-=5EcDX7dl43k)*$FC_ieu1JWM%2=YLJ4Ra>Rf=*b-5nod_x)yh)?SrLA!* zj`e3v?PR%V2cwn@N_L;=a?$!m_=`A~(7|ZX^sT9jGtE5Fj5f-;G|F8J%bGU}=RV_F z$9=~hmtidFQ!0(D6UJcwLC^#%>A;tn?K|@iJ&&qFpsLp>enBW6!KyPl#Ws7=1Tw5t z@svL@^z@MSxXRAEZhn5?e0&q&eKUX{bQeK>Mxt0JcvY%Kdlap18i55e`yMyM;-TAu z7(*ISuC}m)CK2nB1G39GIhrII26p~i#Rh!y|2U!>%Oq#*T1@&qf06S(5;N;&1JFbc zOjbWWrn$6FZf{cq`z=sJbsJG2-WBXgj3{n5#$T&!z{d;HkqGd*L>}9gpo1h4#^}!i z#Hr&JmdU|=@z54tMHLYO&xorP>`r-&A6DJ5u#DM*DSY5*|zh~G}|tD-&eOX;iHU& z6BK_cd4SJ%aKJ$b(Ui}f#E8rzHIv~waMrxL#MC9FpIbv>81Z}D!d7d&&ir6lp6Yp8 z@h?$#_q+`C5`OCT2mW*|tNQr8ZsEF})5(I`^6JmhC5ptwaeTAdS~%a;70U1@5!`TI zW{OzClc&_$I4k^WzB~^Rc4kaQDpMgICh%1OSJkJY+yLPgU{a~q9lSCuO_Y`rLfs!b zy`rRdjcW$Xn%L7(BV^eLvi+i5i7sDkW9tBlekW`Wny{7HV>LeRi=qr9a{LBo*&=}? zR$W`0gxH6|wd3=fGc*1I2P&+#coGre6jpUxHo(te20T4iVhWa&;3Vui=OJ188%BxD z>96>iPq?{WgCajFj5#ea6;;;3uv6~KTVqe(9H8b|og!E$L*X9#goz0M+wT(FSKe2P zx$$SfVW%~^63CCGpf*)13SZ9BM}v8`(xzwo{{r&Zom!x-D~Z!aJ6L_L(K2L64gKECsE^fGL&uC zAHIGcJw%!h<95Q+km}joO;P(D%x9?IBO_K|<>8S2<;#KKs60d3HwFT@6~a`o<%-+K zrj0zTCPntYp^tk+H4V0+r4ori*s(@Wd}Nz%4w}P4izFUt`s2yO!CowiIdhF1xf?;l z`n>*R=;~sp!iwlpM5Y@<_z0IMtRdQ5J7KM5?89(h-zQG4+qD?vL-hiUrVV6)szeZLac~Cu?K6cG4VM*Vh zg)bg~1*`hA4k%7jw9K(^{{&ldi}C{~i4nf@$g$zXR>s4qP+e<*NU$I7AI4<{uw(qYc@i-sAw;+nm7; zr_w*vY*{WHcyQaxfC_?d4|5vIw-elODv%uc@BW{fnu@wJKX`;5gVhC+Km?6ZasIW* z)6&e9MdDZ@_oVN=r@ykQ{=NP1Rh!2Zvty5Y&f!wcw(nSPCHhr~85jojSLQK{vGi+% zB)CI_&9=v-jb_15qPr=C*p<-BUk8U;AUBwwpWo}Rb%=5XyXLrBh?}my{@$-2wxMz^ zkbWTo0?Q z|G6kb($XwaQ=^islB9~~-w@*V*trCvg3_&3#$DsMK2aUBV`bF>U21)%FdR4=w)xCiXd^dcc#AuogZaaQl4Zi5_Fm>akO|AP z;GxJG_C$ur8JphotH0)nSNmx%LYjm%N>5Us3>2?pFvCP7GP>T%}_LLYc~*n6)GbmxDb7= z^m2{MEtvnoNrDh9GB%{id8>ACn-aO?8L0T?CqbAJ4)_)cy={Y|CaJAM`{b6`4mXtL zT^vv#SAkxQcE>tevSezJt)*Hn35I^zN&fP6Xbt@W&!_T;;hB~5^C@#N@Qz( z1I1#=Fu+BYX%uNOtFsaa2?>Gb!ol6P>9;MUkQ{CE=T?;FtZCBQTWX{`CAc`qO!dV5 zoWun1@x_sTVrn1*0Te=i;&Gl zKE(q+vVZwk{8+>?N)#!vPR|6jlb;r@(3d8OiR~WT@LEdY+$z#GTTwi!Hk-6k;?4?@ zikpu+d|Vy}68~C3T4xvvHlTNLIaREx@SHq6Bgbp4OsQWDzxiR;5?W!j5Hr|``wlPe z5gcnH2{<3eu8RBmHRY=8=-bw5OEYH;uQ;T@R*8M{zV#Q`nsRRK++^N4i{9?K2pN_! zrYQq@G^E)TcKSdnjK-ynxtl#xAU<>b?fUg}ZM8aEy80(RZ2l;}nM4StWcH>>+z@SS z1ifxmvy*cwg%zN{kqy zc~MbOfBIYy*j85l{N|2268lh;DN>=N+1j zZiQo;8Ra2+F7*iQi8t}m)9zzJ82SdK&o?hJYqa(B^#2jn$JG_fZ=pq;NhToI{ItWu z+ajy^;!vxiLa-+wO22v-Rv>O1=$P;pq~Ms@+sDOZuxp&+qh9bS?Q$FFyE=Kv*kUyV z>=GZoVt0A`3jlE|p`L&sr6P%C+qo)=hJXX=c9$TmsXrSS>mH~x?uqfHK9=D_WwQFm zxDM+beb<{$&l$i9_;)VC?-Vj}dH)<(re{X34IMT+hA;sq64LD-0Ng(ppzg)wxp>CF z%>5+Cv}TPqu%PB?iXB%@WP_rxu z2bOdyMAknWoh1EFKb~P6n@D2W5FaS!QdPS9+DHfESK0Tg#IQG_ECiuHba5qX(dCgy z?H#F<=#NBHH?vzOM4mdSf{GKRhc>Y!KQLW)+a5c+jjSH!UG!O`PEBs(i&zaK&OfX7NA939@t438X2gy$WI>HjyHRi>#wCSAcRQ#g{MiuO(I@`gG)KDixjNx-kL z-Hn$nT~Yp{75NQI*LMHvF4RN;H2vyVt9I#E6I`VTPie>W6^fgf>eQQjHT&{mkc-gvu(;OsG(geV;z6!6gi-RDqW)^f#Twz#N>8GenLKvFC(7>+G1n#m#Lmh)%k_;Sc(? z+_V2}G5OiR4=%K_;ndbMF@SUp#1Q73$fj9HzH$`#+2Terz4^BXuC57!7c;Q!3eBhK zw0vOh#0h5@ROCa@WE@>F2$j_BagM8W+}t})W0_24{`%f9~a)@+HeA;4iem^i3oT->ad% zZx}iPgfI&S@*o_oj`st!bMuM4@7NZv)YvmHK|VoXd1GbBwrP3QXMFygTl~JUM}j2e z#OKIf+{_nBB_H97tj68iGI}|QxA_FQU*;_4=aX&xVeV^{+1IQ47hPTFs&H4>mGjj@PV&U=~#GzYTiR%xq(^cc!xP7B2 z{+=QsNERry%XI$OS=l2%^7R!2o-dDh5an^PSZ%<#`<6Ks_)tm7$>$wBBa4yEG)e*u z(~R-PQ~rbg^G8ZC%|w^q#_CPmi2X*59bdxYz{nsCq(FLLWW^>fetxNs=Fw`SRi3y@ z{PA0)#$dCqJ*h4QHFBxcF6vJC$Ixm-;eFhL=StS8=(tf9B53@{+SFB2L}9Ub^v~8} z_9?FS$=sPHcbHVtPW=U_`p}Z%;P1lt%=R7*SVUwy5`M(Dnl?FbK3goVrbLK+UWT9V z!StEb8=`s6+s#N@mmX=|wyDstik3i#+Yww8tmG$QTAWf(JZ1B}ifr$tf#f^|9LGs= z0n^);`0H{B)9N{OxL7D*3crA=4J9lBm!jW#-#s!Lz4U_wjSe$Wd4*OJ_y8 zLk0OI;;-esT+pWI5uWQ4I?=i)2o(5_#A?oQpbq+TP3ynRqxXJ7Cjb1hYyUvWmm4FU z{KbME;7h?F;+3xqb`M?FhK`PLpm8+;WSpDnP*44k?|-cLzkltfQP;R=U^)c@+i_8| zDz|%%v;lR-L`i9>@VlXl*I+3D$2thiFJcuv54lK2o(&`>rTMWhrMeXKhI^K>=DjX+ znxN-zQoyC%d`n18mMW5{);9C-i04EWdZ`+I#Z*P){YKMNH&U>(#yO3CQrMl&ycebF&|5 zC^nPR>UajSVG_aoGmWE~$If?2)S&#KplTSgc(3rSy{XKTQNcYE#GQ zQlVI(R0RR&FB8aLZ|{^&19YtBa7*}~3$j>?9UBdfzm*>h&+UUnP0;%XY6dXkp-#tl z?&;|n^^0KZi7Ji+O@zc(h#Dy8?WFM<1F=s!Lf2FX3RGEHdAnc+R@GK%c(^LqxB2X% zTy?{@6xahTB(_E|o1K{N@Iv1EU)2Oj&6M~_b6^)cTd^w8{F3Sg9j9~oCf_}`-P-f; ziR0T%uxcepB-**??6G3zX!ko49qPxC>>OK95Z_w3|KQ~07rJn8dJ8Mi%*);eV|C}; z8;HMq?x!5RPWP$eeDbtwmF*qUhgQ*+YK?|G-@6h1QzQTO|3f6w>C4JC4H5K?Rlf;{ zLOs+0A3<(?63|;>c7KFGlWpzpGgi1F<;IjTQf`U5?+Ix^9f0P!_Mf-C`iOQb5~3nMKYs8+qy~o zv%&uRl62vRo(r>DC|v`Airs)MYJA23$2;WlcRuU%KC{tFwAvfi9K@!2(3S>*w z?}}uvDFuHoi0^Y{9%$yXKw$oZcF=%@`SYP7qa_#xn+!vPktTuJHHi|v(_** zf96Jd+)c2~LN=U`eVI@`Nno5C#wyCUNLeP0QlP9m;(BB*L(FHxD-x=Xi?5)zW2sh~ z^t^bEes#IH+cybvhK;6bEcW7nbM)(%lWZ%?IJmQV-zAgviTaOPPSff(rth?-9lIrr zt06m}*OphO))4aR2a92sQ0e52YC5JF%=h=U-x7fWmw%X9;JLdv!7#2wpdIHjnVUeCG&tq>a^ zAL)~%Y5@2J%W*IL3j?<0KZ)pM=V*Y^P1Al6RUBKUiIY8>A8QNtM%RHC5O{- zmW<_}mk2Sg@tl{7ZopAZN(!`ZZcT#@FvZY|^Yb3?vb^-_vP-lrF{(FERd$CNRs_8s z?kfNO_+Wp!`E>um94f77jcC#f@RKQRT>Mly7Mrg^ZP$?$f4A=cK5Ra)IriMMmq3s+ z&=};Q=50dYljq$7Zd1L&K^jk)XZ4I3JNG;i!eU1i zKT0U`uXKY08VP2-`Q~ZU+#$sv+Rk?|uYt4qHFxpzeURpgAX@dH(K3;m*@-!4qzfF;@W(DMtRc z$7z$ii~PnCs_KHjgcpikXS#ndZVDj4bi~=z7|? z7xi%}FshX%RA}-bEkGkwD>vrr*LUcC;+Mx1v-Gt^EyLq~&q;KZ6^|6jIEZ`$!c{Ti zF>WCV0SZ{*x=?9SwPD;)tbJO@($gb_AE;+>6R|JFBFy71P|b>!XC-j`y}k)^e7t^| zzplzai2AFo$zxS4ggROO5oX9lxN*%M|t?0Ltp={?0ZIs2& z>d*-!wa<}1*s2(^xM#-4uN%9ub zz$?XpHa)0Ni7fL8hYBU6A4@k*#dOdvI4(PL8taE$adG0OH|-3x+HmTqKUU0LPf%Qh z%P3|j^(44oKrT>p@?t2K@~<2xpiY18Qw}GMP^x%k%n=;2PNsWaDCW+J3qb}j#r{S7 zu=rg}3G@k-r@S0t2 z2eazkz7V806`HYJAbJq&T|{W%vhUNSS#(_Y#54`SD?O7kTj^=g(zr2f2f>1&ka?mw z)r^U1euXhJ2&ECNs87?3JcYN^Sp`sn^!(ke-A@=MLW!NOFfV8 ziaA3+>j?=$Ho8T?w^sW1#%<`WUr;kj8FyGTi>ul$z)%qKKckZ%n1sHig40WG$4J%q z{I3p`7@7DJhO`!z`FOseh1Qq0%Z>Rdxe)C}#Q;wi)UvO|eS}j}IRdwR;t#lB?E0Pf zZbGj}1du_5?J)?IY4dm>7FJZ84_)z_b_~2?5$o_y5$L&6>F72x3CpXTP_meb`SSbz z95VK`;uVHoTJs{PjFf|7OA>D9W`x8pipjTJKvoE1gcOs3`1tL3#6AD8aqN%N|6iTHr^z)vBN%Y<8Sj1}K~ zkFHeGyWd@`05rLcFfb6kJiG@9U=Y&Av(O>)e#ISmG%NH)!h*)NmwOkff?|-Z!i3~; zk_fGfG=pA6g2wwJai2)6!qiJ|hi177CY$W-T#Izt$q}03(TMc#(~0^a&WI2RhL<5J zVo*qANW}eT%F}CaaX&J*nzz1rdNV@4NdF$I&;@E3+n1gGYDR|ifzcWvZ?*%2 z^$$W13&=hND^6X-pT0PJIl`Hy3Y8X)z+J2*j}00l^!FO=3Y4mBms~zHA>Ao2CI})x zAqqvvW0$Ou7bY{cimHe}mHP4F?bgLUa|N>fC(c66uzb`>N{awavjEPL`W4z=yvP<3 zU*SlJ-jCo(9n5}Y>U+k#FO_yv(+Wmu@a4_MiqTp4*Z~nAq(c=F*bj z$CGm9isqCzzvA7PJb}>X8NT!pxQtyJ_AXblp}RXsNJLXMoBkC2QtbyQm?EHg%n6Ka z#rYftIiHL8;|-r>n*Q4ij_T3!%=e!+miUXhco z0kyz8+{fL5r!Zg76VCiMU38t}I0q;}6KQa(Ticm#{0ug{x(a=E!e-bEgTrg}F!Ozv zsn@ZKw9apEMh2%M&A%CQeMl^|v1HYhBFOK+NGTWfIZeFY@J~4LzwR^)*u@toFo4(K zrog;87U|jDlNS&YBQ}1+zqG9JG9@8>k$Bs@&z!qx9i!f3+O36BwUN^r?#{NA`Q*(;ZJVIwI&WmSTkN(@Y zxgL#UUc8on5WrN?kn6N_f;86bg6H2Z$NgRJT?HGT(p*6Wb zC5NO~O8-<(;4mS`@Wd;zI4f7mkQZ>$O7ZlKD4HjpjreqitylGjPKY7;?cU04=8x}5 zrHUTkt~_|9?mXwmiUZFXpRem7F%cB(|%;nXnW&b_f z8e*j%Ly3=5CZ*LWKf6Yq8OJq7YOfhOFw>`7KtYh@|4M;DT^lF!6D7KnrlhC>$Z2=G zMsqR1;iJ*0s9&TCJEMwYvRBqQ>;Y-{OX+_i=M9!2vx}T6uMni>Y!s=poBHXaR1{6) zT!SUN6lDd~2K7xE__T?ptklmJejacP-jPr1fE0sCc)|%g(Y-(S6sHRm4=k^I-|I_p9$eoZcb+(N6ZHaA~g z35tns3q0N0=JJCMEVpE*x~E7H&l8Ix5vBoSA%j%oI7mu@IAk;65}XNcQQa}G9>i?b zH9*?4_u+{6Klp&whMZo{J1&d`-xPx|A>wC;drIquPfT?+#v)rJluN)dVA72|rHoeo zMY6dV^mnzv-|Z1`$YU64)4N_T&h0$U4an!fWF|S6aYoxluGk2g$BT>}bN;Nl^|eAG zgrAT5G=OaxGp%R5gNN1Gj6)uugTp9rrnARCgW}=z!wtvNQXu5+>d?-?fjjR_o9{I{ zh2QD(p2sOiK~d42?V*^^pknp2aRMpx9rw6b&n+?&Ctd5$MGJJ02a^W^hjOcyPpga| zLMH7^yX|f%fza+&`!BtC)41st4*f^E8BC%)Q}zMuqeq-kT15ESVL_nW&Wl2fn}Y?D zQf)|@u~SLz&8vLjnqPB19USRee}6Y6_Xr|KTTKZ$?$eZ>8qKY6N!?)i&{cQ)t$)Sf zoC!JP4$e68Ow&50!q>U)`sk)*bN$5;cK`a{vYPSgFtVFZ-eRP^!q`wJYAsq`YnoPU zugbO3)^lS?i@KMHfAN(#DLzTNd*(nX>wk_R-_|BpiK9JSmNDf#u z#2E_rBTF-Dn3r1HH!u79zvAJcO$pT#r88pXBu+&~4*OuMfY7fbBP_3mSXx5g@IwlL zN&}e`TTHM?nnt&9RuX>gsDBtER=zGXXqK=DtN(DRbX59x`y^w{-D>Xoy;azO2&zRs z#PxnLH|ht$yWKIrT*9~!u!JYXyyEzmzt()Xl=Y?}mI2B-6+W?Zb47(^+x1u1KX5vQ z$|a5%Ms(Gw4V4{E$)EXgIyy{f=}M7yBa@FMiwzQ_!AGW{(>G{f03P7B&@%+vDUHb8 zzxo>EYF9>hexW)`LREaSpT%rRscBT=8nc#^vStNlNL zc~YQ|w8We1O&a7%AQ#=~dx&6pe38~e6yLa57!c6}i51FdvVoPR=J< z8BdY)~;U(*PDwigR zabUsIL(gM)HPDTj$S~5SNERSrQg9bc|2>0qyec5tdNV=;VwB+T7#RLVGlH4Z&q=GI z34C`E@)4xuq=4oCw}Om`%x9%LQ58+gMm_u43#mdWoapmgkp!O0WSzu9N_Kx=LzA05 z7fb?OkInb&lM!m^{VAb!+(tmdrJ6^lB&!{!&lb%-LYV#ye{?vGd%I!M&6Mb+&p5P9 z@XO^m({TO*bBo5})$0~jstIhm$cDwcpW(bx0Sh+VX|f8^a$ zeT|$i(?WE6XiI~wcZZUM4Gq`2W2A`VEUqV;>-b)Jp_DT;hQ=d+oM)=afq+;MKQ!CQazn%u-wm9b9Kk z?XCDK6jk_TISX@8oDx#6)xJwd=bkx1HY^$TmUSodC*}~NIHyja;&544g`SyRRj|N@ z0t1W;wT3VE|Pu;=V4T90|*F|Lk{`%x$#@n>l(+&TH5r>Kn&}uSp4Q+ zqo8ncF(~C-Yg{PF8w`d`rzJ`$Ilg9+ksJ&+iEK^>n9k$l^E1=F#XkhE*bOP8sY6et zeyn$TW~o*%mbC>u0LwfQ6J4BK2nepnleH-0ndi5vx(LUk$~d&Dm5a+jU}0IoSD+Fk z%5~xv+&cDry72s_AApavK~45DHD5>L&e%FuPV{c7*84K&LoJ*9yK%ig59hChx&ku> z?md_C^d(SGplODBbYaF~1>9L`?e|-cW-}ZIQ_N)B;y8UKPuLL;ou@eq56qw5rlw1H zh(hMpPR{m^uczCx$G`J6*j3iYCM4Vr^*l_hz>t%$jj{N$|C7742y8jWi+KJ97^sYX zXf@m1&lL+>+e$&P5kLM4aYEzE3rrn#sGjp`6{JgLW}DYQ=Qr*UcA6PC_lcrZ-KeOz z1$M!$Cqb@`ydrp*?o>JKW|wve6rWe0ZclkAQzpzCdBsZ5f3Y02VsEnCSV!6TpBA9= z{kJE@G`4Rs!7|mfF)ZWLl`Nwr=sV-nD2fKD481Q)4a>YHxHD#$*4#d(fBAnropn&v z-`lkX0RaJNDJkjhmhKd!K^h6^?nb&>x~03jy9EU4Iv|oqy57zAH_to69}L3aoWuU? zJJ!0E-mi+Wl%%9vhr^ry`rDF^b8NR-V`MBb+nggNJ6NSB0azY}eX`ePG2Ih4vFsTG0A^*#a>E!$E! zCssYD9BNXD&?cSwZUT`6#lkAc%DM5Q3P$65*t9&|#>*Zf`b6VsOVxO~xVFj(v}}@J zn~pE!D5W#WYQFauiPMRahpFy=V&f5^H_x*UkpGleO|uDw)iI246W+C~x!p0j80Tid z$9C%(Xk|#KbS&sa=YsE14_wd-*`G;uN;Xmn1Val1dW?mTGF*geT>f|YLt=SR*1bRA zYyD%h+;A0h;)W&D%^g!F=wHV#1(^uICHN`y6#e@97_stlxuq~mFTTr7aO$BriPu-d z0b2JDrP31hd|mDRhoGquflP%K*C*mkn-nl%ABcF{;&DMhJw(0Yd+IkJsv%o}XXAtP z5taGA**I(W8a&Jd^fO!u6W+R`xW^qfhS#aY{=6pNWE16{!!mvIQE?wlN^Fa#Xzr-G zp+N$K=Pmv=s7b{_6GaFVp$sq`;Ay0DpL}VJmALo}f&OxUrhN(5Qk&*?I*6pnWU_($(?mcCpX{exOLUWPT3-aR7}k z59HVSI(4*hFN^rsObo(G#Hzm|E2fusW8_xzKh7NbD()-jR-rwt8uT=p+Ot9yM)XNn zyX&);URpASb-FF?KK%jOjFl~|KbR~&Dc|g%lfr6_HfSn)F*dljtgNW;bUDcMCTgy! zf1bRx``TjNG`_qsk5_!x$HOwIepyba;iz5c;c~ee=WYU5zBYFLnDpCrrMU-e+N||_ zx1IG`{ymG?e7dHtd{4a}Z?YfpGpXb>*1+!J%ID;&8B749B=di*k)XI;Z}?BGYHh!k zvbk3i6k(pa|J&!@MqXtzDX>TO(1}=17xo&)PRoE_t;0)vY<*H7s0bcekAoX&WXyqn zJI3>ydKGV@wmQ>T*eGYa#e^loKlbpdJrcbyo=Vv%`t<8f{fpr$ynjc1Fm5;}-zR*0 zZfml!&Nnr%5k#h1{(0r`htTX{!0|*>;|9Uxk}2f)jypY(DHlgrHeh@ZL6_8|6+uM7 zd{04zh@=qk7i8D_eI92i8PE*08!XNl{o=kUEbY&MMk`|JFT)t2JiapnH=i7|>Q`iW zjjgFd_7bVLibOVV!Sri-_<))zyjswx%RD2S4zU}#ILhPox!jxe|>cos8I_%pT*ixzMoXK5AS$z>3FJek+Fs3RUHE?gxC-w4Ya=_o^&aTQ6X-`N9Kj_7oNY#FkXsNMMN{HG%rPu4-C-7Kng`&z!>uj0@pJda9U$?JLpS zCoAc8*@h~0?ICF2&mbD3P*YP2xB>1*$A>R< z_`n zHGJtvcJW$&m2magcs#LK`0op$0U3^CNiB;2D z1jA-R*m3LNM`>XhX0@_iQ@ayZ_{cI9X7b5I@}pD~#3|wo{gN;w;qWl>V8wpzPq$wq zw^8L*LCgsQXAC}NG^G9+wba_ZP|2lR^zy(jR*@uw-mHJUqu20~?dnu?9z8o_&GtG+ zN>A4T9g`i1Rz&E7Ss(zEHkP7sLyi9iC_dajjSq^4=7L0gMmTLC=#_~|v?qqgh3T!> zhYZW+^$Q^703hN(u7M#~_=0hY2^;P8G`pDP+vRdh!Ep!49m{-HsyFnW~aB4)aH5@03KcnNBp7_sSWQ%t(DSMU`HcBsv`EP@WTrzn zI>cAH>9+)8s)AYj)8pN;pBaT46jJwDf|u*As9#nW_SO#6|gi6Lu|^YB?Anv;@2f$u|93 zacap-!r6d!Lqw&%*IXKeGViXu5z7RftzV8fPQbXmjy>4JHEdI;o9n^AAgxA>gd)gE zehXSvm_5dglq@)drR0zfsn4Ro4fd_PAkJR!cNxY@#Qjx6#+${?pE0{^gJ~@#UV(r* zM;?cSnEjhGy<8EAC~ufn=?h*1`77Qw0mv8C(!Si!qqDh24CxyTU=z z7Kp(;-xHl!`yyWr{|J6f0A`e;WTO5Fn2d?~SfzdogIpghFrY|Mbx1C3fo{lJ6f_A9 zQpo8Tt;{EP=PRP(>fu_)wSU;jWJNWuAb^wIxu}ZA}@JC~5X?5?m;Vanpf`{qc z0k*N1YWeq{75|&A5?DTTM+DA$o^h~=#Z&y(@js6Y>gxJ{6ae_dLBmh{!K2@VO>4oL z8UJqA>xa(yidt3I+3l0vB=D+$zxJXfD-%O@4H7(!*iP~?r%K@jmE_8vr5P}ZsKa+X zUfBeR13*BS-@rt`94t=Pg1t;J71fsUzUlmTQkPV|@+SO!eP(J3clJcuWKqBU-{7u> z;)MWRaJLIB&daW^{H2>7dO+{qNAsdIY375>*!@Wlav2btLX zl+`=+KQ}?|Q!J8q9Y+av^}32nGUn{Y-@Y!IqXiAOm9_2MK|Rc`<>kF7?zN4Wr|X!T zv95bL5CZfVF7yNyf_&A#BUn`=q@=7{%J@y$Pd1u4=DD=6^(rf1W z-_;KWMik1lcpFbY`Ifp;SNv_NZi}fJvJMQ zcK99@$_PQG+bsFvO3aoU)G4R!76Bd9^g3*H$j^}HX8!tK`JE?Q)$jXk+~j@>j-pUa zD92^kjcyY#&_w&54GN2Jwt1#~6x66T=}6SUQrnAk=sbtZi3uzhmes|Z{o{OKWknu< z$Os$hh}VrMLrRJbTi-*0#1$4d=m({!9N$a-L{EFj!Zl!IH)&KzX$4>3sz5-f5DF)$ z6_lt6qyCH2yYqW_Va8qZaH|!Y?n1?Ni|XD~?5TUQ1Qn^9v5)Oa46LgKkPt(V#<|7i^Nm4AK1~FzKf1^Z zy6%z}@3D~s`!Q%FDByd|x0Vu}*!*u+JojOx!%By7&fz@=vtQ-5P#k`6alTG%IJBJP zE!6{(xanX{NXaAB2X&r}2*u^iv%eCr~ZU`j?!;THFfE&Q-o zJmr|Ox>$NJ#c9Q6ZKveIQ2aAw__+Z{c&`=+peXH`d214*ulCj4#8jQ zf)gF0rq#@I!voG=@2)ktn-{j{4dQL_P|3vizIIjn=%KrZ_GAeRemE#C8jq<3m?54RTWq*SKqHf7LQuNuw`oBDohpo$?{% zd-nU3QRms>f7MGLv~3AK9q=nhU&!U>l+l<CI*gC@L%wHX8>O9jqC4c_2JiAxQInrStfEJu?@V@i$pl1F zd*~$c=Zj{J$CLMziFicgopo9wZA@%%M1)kz9Ex{+6HT{J{7VY*#7J3k^qH_HD(@ohfJl<`*bI978D9hR2YXN7H zuJ|WWXp+LAoVMXN4W@6+#n+d_IUokX~drJB=ump7Es$`ZU!<)28QuLfyp+@PgDdl+MRfvJmuC5U>DwG!2BKl=Wrzx>E(93u89YvkaHu9UgPgBb38p)M9)fHMD z<)F4qfVLRb6!d81PbGe!jm3xg?8XpBU!dh}@T?@-t{aNi)XQ}U7B`m85c$N~JUMhm zJ)E-J>bYvAGhVy9?r?rBDp=Tb)XJA=T`K!0Z@&(imhJ^v#3Ni7`lu4~!jwJ}BKibw zR1~ArPvQ40i1nv+p~I2g1ur&HxD;j%U=2Bt6XL?M#&Md-Z-a4gsTrh0P>IBIv|(!B zk^V+rQh}RzLC?VT-qCv%>Zyjn!*r6Rd6Q|)m=(DDn<_RlN%lov(#O zsEp<>JVuA9m2>?an~cwuK3=~})6xr&Mf$!m+&cbM&3{Yl|0zgv zlYs{nZ+an)?@&y??8S^Z*>{Bi$=A7}86RoPlzWSlEZ_n@`p+ZT6D34T#Znn?(jaNk zSlJ>p5gmxBdbmmu@CLutLh96Rq7Du(9~Ip77GxZ$q%UH@F4tx2>Y5b695T;@jRt!G zK=)I|21p@=PgQU052dOsz4f>R4sLiAj(w6FZmgrIR11Pg_P%vZ4A}ee^TZi`LG|ts2?-Iq_qy-SS86PNmA) zDhhk(x|y;w<={4k(9Kzl`_roHO|wa=G7>oi&NWL+$hB<{qNGj7|WHDyUrCNAt_TaGG(fW^(zMM z<~NznM}-~PQLuw=AX6V3H95cV<&Wo$R8ok&j;CwVbfDR+IDUs_=C}QR4|lIr1ae+B z{m1{~QaQu4DCTRC>El^!v|OxlqiCJT84v#&!Pb}V%P&*1X=9fJCH6m|Ys&D=$VV3k zc`A^vk^)S=(x=!n#DHBTHrqF-I~PYZ3lR*@76 znbbCT$0kxL$=8tLyDfcM{IEQ#UA}@=Vtafs26UYFj4ZuazY+WsU+W@nx(FWv$HHpt zznMsJMnsGPMe;}qJ}FXIf>D1b^K^9PBKdDa96Hu~6T~W#;&e2BVtK}Twa80iSBY06 zJjVxLX22mx<-FB2qftq3QEAlFvryB}EIw=d)0GwBFt=N)akHi|_PJu)Qg3-Ec)ZeM zSv^AQ!$3>zV!v$4PF0H-i#`JnpWt54!=0|jE+*K0Jfne$V|aOZgb7bN=+(FNAX8Ae zAGTg9>3ZL|x=^gaW6f0ZA$q}0y?kyYgIYBoKSuIBZUp?pBY^%g0+%}wQ3E7{BS_K( z4e%gdq6(bIMjr$JsY)?Ao-q&Ke=uRaDk;2g!N063F2dP#EMFZFoU9P3?PjwgeC=>J zWMJbqOV*Il((e?b)d=zd!vu2!n}Xw={xN%DD+<0T9B}1-O7jrJRR0c`cT=gA6mZCe-FMg!tEtI zqNQZjx=vg9Np58M}{M^Ki@I9PreJ1RDbT1kCVg77pXFf zL5A6e^zCiCmvxyYrGJ-`bY#%gNPeQ3E^RxgmL;k0Qo{8VWYzhXIYVK{!Hkmopjea zwZa?&n|y`7*HWyf#bSVS6ah#~#Sr*&RWq1E)RI!kO7*&p2||1 z`|Tqqoy1?jd~E(h{OlWaGH>{9WqX1ynKjMWjte&&?%J!RS2Led`@Q^1Caa|dmgVjF zEC+l$X;tERS2f7Nq#6|weDUHJqSk4a?fB;3s&)M zJIpWz(S*fwnnC{HZBBY-FSudELX;=eBt@l5VQ$XN){$5gO+4gDjFw(~xXL1)XINHm z9)JBaX_Qyv8?BS*R>o9X%AsV+VIoEgL;AdX_ue%ms5v`spcTFY0wUkM~A%?EXaz5#i1dH z3MEDP$kweLQiEGAA?qJ6Xi~4@qyK%ESEf#yRYg|yIgPz}e0rvJJaq=LJwG^Y(*!zB ztsg||7GOp$eB)R#aSmsB^nOmYxe^3qTj!;S z;?OeefBnLY!OFlME-LgEpkB6^{mY4HB3wXTKOJnfUAvE6C=frg-qIdBQ@V>R!f^Oa z{4&EJ?nl7K3GL_}4}3bmX?QqwOl_I(65Jzv<`S^li)RdDJT~rod=s8wFb+nkl4zNi~ED^Nw-%`K4r4>z#L>GA-Na~#Y^VX9p zk4wZhVsBF7%XSU*-)-J~>_Z{~e+NM)7YjEjT8_-6Jt%yQ)%NL6n(V^5SE={P<)gg; z_pT*v^^9ud1|vJbv0f z15aQz8vP5CxOD{tkxgaG$es`=Jwj4CO2aQA(L{2@^@?(@MJ-Dho5@K?U=cc~Mj{ zDtR4t&(Z&VHp#&J|08#7qfB*|p(7`4r_RJ()21_NgwytAfZ9q=9 zy*Xqid3zfR*rmO3?E|=yKbA)R#pW^m)nXSX_mwy#f2sTNrTJ-D9m9p5Ti z)R&jWj8alk9ZU9E&{z``ITGAe+AvUq=BZ1Vco)?Z#8q@zB=4pH0_!{S0a8~Cmhou z6V_xwir7SQFpK#z)2eLt|Fr-Lq32{Fh26O<95{rHb*o1ryh}mk1mNJimc?s7lkv6RavZEZ?)4RyT6zG znd!F%L48X(gKc#cE6+i!G`Z+^D)9nb2nrQ@y(2Fzwd}3i=O^66Qem>;yBX;QZbPw`Yd$WLPlaa%=1(ONiB1~lc~_4 zBfqCC!5aP{Q(rTY?6}Wi$dTP^g=~ScKvo_vFYlR(%wT32tUR)CPCFdI4xSU1E~S6=AU*SQ^C~~v1Tyj9(3<3#&^}j6}_4R zAtjE6cAZ&8nv+Z(x2+fZ`rGb3Uy#KpDV56(vQ-m|;_))h)bmwHO@mM<4e?CfAq)|2 z{tZQ{y}XEt1xw-Rleu$=KMTyu?A1vF&=Oy@FEB){=WDXTgbmaMZ z@6(jACW`Ej3=4bUSjA}d_k$=soe~+m;Re(SPQ||lk7Lk19v^aF$bOQOcTdfu6BfCH z3#*bD;OEjdaJj(cd%7yLan*UrY2$m(+Vyx*)#84LyQ-H$$gKyt;I^r5Ym;kR6(t;_ zc0E2#UvHnFZnCXuX&6~tzeiZVzD*BqI&u?`81{P>z|4}6zJsF!lT6^Eo>=U>^lW!| z;H27S?YfQ8Kii)XT+nW0*4+RBp1Pe5X<(0=s6s^ij#Yu8Wy{GzegbeBA!dze=Zue`)nY3d}EBN zj8~xmZ2HezOoFT@8nuhs`|?;Vmavt81NZtZd(#XXg@eOCAMu_hU`7JYHsAN}F-7Uc zR1@Y>QuyIuD)`}|`lcv9O=lvmL_bgjf>$R$+VPXgYr`{P$s+%Prfq)mu3(14*GzMqcDN+v)q{HV%`oj;9ThMFNh zwMedJmNZjDJ5bzMUevN@f}puN$_52d=d*Yll1Pw*0SrC1%C{fV=vI8%Z7G^4uP6es zq;YdTp|e4?1?iEcI+oo9vKD?;M8fW882@j%0|*|^Yy^r^)MYmf};ZJhQn7ZIVSIU{%e|>HW)*+M@ zrno%I@s0TANSP76T;mf^*zlM7yho$PW{Whx;9B~%Uo&%XD{>{560{%sX zV#L}YLZ)5{DWY`L9*8BHag)#J4>A;Q`fXa)BvLge!6(w1%Fe_4<)@G#YXnjdHJMKO zXMzq~a^#PLYV{Z?Er$;=zSJN>q9T}7Lq z>D|IZ2|oT4qI^Tql4Wf}!$8!c?P=yZ7>VD#THhUQD9iYFw{m~Y1%7*n29y2K{GoZp zQb+aJF?c6BU4nrcR7tR9V68C1>w!=olD>XR%y$J zp|kD<)~$!>x@`_geSu=YDT}wwKo_gq>5=wyn`!HK@droyDEUp56$d$DHBY09iyKsD zedkT*)hjD&8%znZ1wMias;lGmmq=0Sff}~DkS=gI*Y4yIRVtA35UBgeV$d#u8~TvYx zWrHFld*8{eA2RJ7IV~8u-+}b9fJp))hedE+*r$xP^fO*f=6qCd7j#QUCYUB_o`A@fqq zu}%W&k+L&vfRH?3AZ>&dDbqt+P-lROhdN016E=_5gQL6AW7;Nn8J04LJ2qh>R+Ba^ zifUp)p|$NTFR$RgwU!88=@5I9e^q6%_w(P?b#8VOQ74JtEJQN4sJEV46^)-95y{fV zQ|z6dBKqen9@Vt9jR6*Csyr1)zLv~a#&w4bs3ZR03Q0eDdiuD~Vv#TFU;FsB8u3rw z6D$7o3Gm$jMD;vRTUy%`g}{oeQKe~pMvg1vRuWT%zgB`dk@0j1&JI$$Y}JIzjJf;o zDalEv$$bfFyv+M`5`MJHy7Y8$t-qb7jM*aUH$(82rqPA@RLb{q{l?b!UkFEDta`qG zX3X_&jBo$%u4|-|_0}+qZ(plE@9~3_IK8Jo8vFnFK((dc^}r=`H^AKNe#ph|nR4Cr zw4-#hee!@Yiv$MWpU1C{s(c5)7l-aISKq|??|ilO$vk;%IHz&PO)mjF!Cm_wSz_8k!6~Wq#OKNlUX9D%mfXC7pbkq063Ux~}hD`2u+wD9)oK#n}iPub@-zPb5$N`cHe@(zMSyL81Ge z6T9tY&SczHJc!%%HLLFvnEBt4+{eqC>AG#Rb=~EYKs|*XKPR`oPUYCPv(3(aniD#M zUadn6Y)OJPdJA8J{LDZ4GnP#)z?0#7q2UXnwR#dN4j2~vRpVWXCr1C!r7-F4+(r@p z5C%eiskXV?B^z-56^(q(dYIjw-k!{zTmfA0$!Ws+9TK-~r$pHtxuv9Tvy=a%QOHBz z%g3rG$P-lw z>Hueud*6O@%Uyj@9f^?4_saDt4nW*7g299)# z@%r(qbIKP=?b|zlsBv?DX}0os&!v@I(^l8##<3M5bWL`o{v0_2=ows=>~O0xb7 zdr9v5&qk0Y47J)4x3JNlR_ER=EX?a2vT74s>EWND0>_O;lMn|(qn6xi$+)7P07b)} zL&Se)b@Xyu+W$Cq$sMRwT$__?Blfb0Ht-E!!ZKOro03HJAZPO~A_dmriYsFBg@7cd zQ+zip7Hd@0e;Z=!+8}dHkn<{|` zjYXr_^4nG?X6ATe(`H7J?{CXs;MD_gXb8z`QMidQ%+PSS;wq>_urZ~BB{wqq5hDiU z`25Z5%`3`h)|!XSr$aVhM0RV1Ow4)w*m}D~M;=;2{O?~#HUwkxy0AxneyX&z46`-K z`*mT9b56tN#%btKOp~V8=ZgcDwPsl&K&5qj#^^NsnBmn}ZoF-IzWgoQJAY)4=nJ+- zTeIm<(}H3)`S+_p7<-~Q{)3v<#y@=w*@O5Zdg5nCixD2=s?U`cC-TqtqEV0--SwmP z(fqpl{uY4I7HH~u)pgD5kEyF^30=EdfB#`=d-GB(`rAvin9FA9h9iPjc9LTmLq+BJ zDv3|Z>LyuCj7wPZZ-&nTQm)=fS3ra!is9hn9Oeq7qiAnj+^Rb!Zf_;lZYO{1wmXFV zzOqe_?Q{6*-?Z)>;)d-wE!4v|6qRm!o_W&QmoF8=)9N}rGDCL9|EwPY091{&UppNq zT|>Zfy|lWvXXhJpyhXnLaO?_n^={2=6Ql~wH^=;5R~;uczE0f_p04;8uPE{{Jn!1f z6E=fDnGlOEj*KrGl!2z^)`$bM8LKjF)xhKXC;$@3jCcq@R~h&*oFx+Q4&=W^D@G#` zKF7_R_?&>M_QX@S)q$7VNJ;qCE`si(Q|mkJOfGu|(Nb_UQh1u|qa6Ufgn4 zcDZK)K2@~mP>_hU00BEe47!Tl=Bz}e?yAYdJp#C}C4$2nE*y2I*buf^Jw5r$E3)(F ztpl-tu$Ww|5L76pugSzvC`@zZ3+>z6c?ri;X6OioAd42LaOfy7L{rGc`5Uni#DAe( zv|RzoTy{63lnD7`ZJzufv4)iZHLN$*r|XS7b_NhcOOg2YuY#8WEyP_~&OcL4Ji_b^ zh30>SH3H7lJ&%eC$u<;g_HtGl zN^|rX6-G%mDm&UVc0u|2>LjeYGQ^_b)B)}Um(=W&pB{Yp)I{2NDkT`Qm>lmWqPSkC z%k94xJK4u$Uyv?FQVps_=aC8$BM?h2jK!~A!;onbtD6%kc@YqbQq?*SfAfwD@olo^ zO0%?=L%;{#Z*jr$#u;LWY5Yg!)Olm0JI)V9z7*>$ozfQ_M|9jIH2I||V|?!lEJiOc z(Eu$E2=z4g9Ug9-YZdJ^A5ITXD6 zjeE47)f-@Z^!%@fuS2qFcwv;wWPVw(gbv+@WIr%kU_$eoD$lB(?u&K3jS~Pv{|t;@ zg*G<(r2f8pS6kaT*pO~}HnjePksjl+|9HtI;)sO7#1hKrdq?s_oMP#7di?u7=IJQA zrlne}M=D9{D?vVn`f_1Cp$O5ucE?wmcqLfweSTsFo%Ln zz-NCY_nKSa`u#0;kceuS`*W)IKb$5CRmpKV*V~Dh< zCu~ByU|Bx{Cu*cDUtfX-p_sgd7n_x~`cwT<&Le|uEhcW_1qN+^GzJ`UKK8Oq0oJd0 zTyGE0=CqkHoo)q0Zz&lzezO_#`gwB{1quwZILqmJT7=9L!8iDfRu=0r9N8c%at`0+ zvuPP~@zmy5R$1fsa$gH2uC~Z;g&p0lVtWka`*;fw5i3M_MS?_g?5Qa2khuxsvxu-5 zD|33OWD$7CYTUJ=UY5Z2ehE2lfuh939FQDCS{y$OvqSg{y)^%jtJl*c4(cxfas55#5&}gfLmYigl$m>^gMVm1|@$azZh-BF`uAOXOg}l-<1IaxGKvN5LeF@Lw zBsL;68G6TEX6-!!&M(SUNdKv_G*FqDP%gA)=pzo2Sikvn=_j=O@61U?*%Im!2cX8n zZZlY9WmgCh+q>CyYxA2BQ6s`BQXQ`5H!Oqti zttt+tP&Vbdk^Blq!N(me7h*wiJUI%SQm2-ikZm^(_W@F@>%|#{kYV%alSjY(&d_RW*#|$68Px% z^sxR&0++k>std}0ztnZj&ZOTuzOXHY65|OPSWU2!?mx zDn&Y z1gt}AVVLHB_%Mf;7kEm-?jMR1|iCxC@UTKZ4_7L?~E)+=pYn z?}o#Onk1i?N4@<@Xy<@T?q*SS1b(ilv7zUOM-r~Exms5X*PWDVF!HOFc0U*eL^8!G9MrOya^mqvy zZ~hJF2QAmCBmJ+PC8&BkNw5f?m*L9;8P!nOdww7O8$zk2Hutr^A4T%VfqjVwSF;cq z-#nf)Z_d%|aKmQn3*oo2>FlA-Uf*)#$!VzXT`nv$hmADPv50L&SeDSlh%?8F`ZTx= zSHX#i7@U)ftw4#GL1l+OdovxNDEx)PKK}H;EIYShFN!|hs=TVMy}cI@xk+ZM8v#(% zk*xwB1>x`C+w4KFLx z`%H5N00kgeDFPN+3sGCKbjS%iZa!+?qaUcJwtC4YzF>iv36}`PHnFmKQP}O7)YZ&Y zw((QDX$bIjLCUKtW~^O#R(@}9ulw|mC}%?<%nnD(3Tr-x))aPLZo?04t{{6CnNI;9 z^%>3bWZCd*#VZgz+3MQsBb}ou6hens`({D|1I55_=gchJ<~ zik4Q|dtE{H4A5&oA2mSd+BoI4=jK|lAH;|;E*us1V;f4|l;rg%TbK%}93hGMU;$l&DZxa*P>L zBP$%92+6!m>e|n{k?;}%G1C>ZF=}cxGzTsR5Z2zj!uJXIS_N@(;m5o13+t`jh7Q6R zXe061QbE}9ezDyab_AO!7Rk9%Vzb-t1FFLiMOD%B0$#-89aO6uQKSlEGF8?#+lQ^4 z!I-e3sGu7y>wWr4I{Em(BP{5@a+e3Uoj??hrFUPZq}YiV=b23I)rtol_0~@KFq6V> z2Mb}4`Ci*rHx^iE+PcbgNO<_XasmP0^$RE=Vv($-!(wTWwM@QsM=Gtc{a4Rx?uC4h zsuD4mMK_oBN5i#j?2_Gq&BHoqd+@{LykYWlZMhx1b@7f1s3Q6FiXKm>HEcwyxAYmw zEOh1Es>w-~|*c{L;r3lbH7t*vc7 zKHRNzc&4bA^?@zQwmr%Mzk@_=rzf`V<{=A&jdQhSjIc?2QD@*Q!35M!dhM~+@z^7%8}d?c2&cG%xUq(#pi9t=PW za8}Xdq`8cbt;|TpuVnqb$Z@rVQK`kwT~}gy1d7J<)Na#Y_Q@729sAC0rh*~~mL-;w z(pxzEcH3l*UXIx{%Pkavk{U2e9lG0z5MPD|K>(HaqP|WgX zyhfKazzQM8Q^9x->u<%+cWAx5ieN|&?j9AIayy>1G9&m;yF&A{d!q6e30rOveFoB* zU&@WY8OdXFp^IXM`hA4sF+=(+jA7Y=sIMElDLSs~o;?2Jq+q~m5C>V4dK8m4E@4L{ zzmVz=mwEPy-P!6`Y8=^7luV2YW+uA1e>DsYj3^vpiU4r_)L1uE>%0}*MeCA3Y27Tnw7j4ckcjSx*I{0`oi_a0S;p-Mqbo9ndQUhA&l~;* z<@HQUuXNU`CtsMiCyS9`j`HM)j^s_7aHuaCsm+ljUP^%U>#?3k!Hxth?Fj_m>sP+r z1_F6C)$+yjqa)g4IoQg0(}-fCg`pW*taPKC<;4 z17Mv=Ufj1S*9k%opO!1QNWAY^fiDMOEEP+%75n&=oRe$1x?<1+GBe*@US78NY$L4u zo_r{81e54QRoxb^v?lQXBD7rtX!4rI#!=8zfknI5`58!VSj$^7Ki#`HY`<9GZ@)YC zEU&0cF#Ya(b@HhHe8x46TYOK5fB)u(qZ6i+K@S38(sKaPe0S3I zpW7yto^F&z>d)Na>Jp{ikeqHjerU~vul(FGI$vgcTI_pH4JXn)J4>z=@9?zdE%@*c z7u=0L{JX2JT|@eh1Nzf8u84iHt4HsSeSAW;``&{>7O7zC{?`5Re(EWMCmN%Ba*`?A z>mMsHV816GdQPMx1SKyzoPe8MHgHM3jBG$8!%#v0W_ZBD;jY;C+^=6#u`ug0?z}f6 z-Wn6~g~)z_gf+0;9@COvS>$(=q4Pt3Y(gOZx2+Izs9K5Hk#b4J3rZrYVxAdVqT>YO zNGlqJ|I-4HhzgMF*2D4C*J*aW!iOakhdYuW@bB$6md8wp3^BJB*xYC6z47bnMWUG1 zpF=80+8>XPLP?vjlNBDD)wjlUqCBd6lf=>v~nwry0fgXCpiqCt)_FtLUDaCa6m4Oiw(c#HBO9 ztA1h1bIfjn-KQ?kIwO73%`5r5o|I$iylcXy>d`wnz6p^0grTgi-zy*XCN^b+@XPiFM(Nxc<57OwF{qDR9zN!mP7-ZzGTZ? z`QwCki3S+4M3vlyq-$TQ=MS>y5)I!kcx!S`Cq#`ltU zdj`?nsh=7c3JhFh9?y`Lcs6%VQ}x@Q99@XLCZ9Q*YkqHhF6dRv%$b}pl!s?#Qio!E zCqQ((e3wv8+caggv1C35=Cd{U@!^%%;{l`K&AxGTj8gT&`HZa)RU!VV zF~z5vz$>KodQ6Wo*KBs%gcU(2#pt&PpLEJPkvAv@+Epm{kvt5}=Bo`*AF5+(;NUA3 zCWTil@DAo<+2EyRPcKH+(hVuMQ9YO;84Zk8w|u=nw>f&TUO#|#NOB`+x0IT zL~)VE$7`K^v$JetV`I{kGV!UInT*71T}oYxeJ0>Gs)AX}kjdtdUl@$;kHz7)LPeHAHX4Cbq`Dwsp8&q(rY zACHLbeB)Y%{Pn}Ljh>g)$T&{c;s~^iusvA{$eC% zkuD+ii`pFOgoprN(<>X|OjQ-uw@a2{TIrCKq^*wh2dPVcwgroSH(ayY+)%j}{Wo?B zQUNlesWiW3LK+A47?BEI5X(jp(rUaCQ-&z{$p@R+6si`NLK4@^enamd6vG+v_aX*C zVhG{tO%jJH=?#Qm{~lAP=E7iMVFZlPl$Y4S;nrgJ)AXXGn*=h|V&nw8$R$@2lJmDi z#t4F|U|NleNd13IopW%U@%r}LG)|hvwrx8b+iZ*`X=59WZL4u(+qUh78{6vp^qe`r zdH>zn+1+RMi(A*{n(<4Z_kWX|=4zfd%oJ8X;RsvOTP!5jXIKpB%_bFeEVeHEE0EN0 z2HL?KLMOL>a=%ZS(kn=mqA89+Nn9%nJQb6smo>X8I8C?!^JK|hyB!FsO^|W%EUt~~ z@ZF(;63u9%OMC#`6QJNPuc)Z0ukQ!ipu@F@6&!%D!VLGvgjiZePBHfo&C4X2oq1?# z9s20P4>fDHw&xl;{m{=cmp*+O1j{@O1~1zu6+BJz8Szpu^)e~A8HV)>mPp*=y` z16<;WPlSKDX7Cp836v8y;WW(gb22aM{$23RcdJ7;J1MmO-K zC@lC<0P3C*uwOP|0CGMce~KM|i`ZaPk(%ZH_Hcz6;`sttaRnx>Ki{fGBO$q&I3`Gt zkv=<=9}I!KoEYs;3hVMkRX0d5KTJ)v!`7p#YO*oZ)F#Duk?#TQKIuLeXF%=k!v zlJ8*i%@b&o7)6P|NvDGu*EV!y1MH9Sx!^?H9Y2Z(<0 zjU9Zr9tt+_c(HZ-X&lPm>02M z<(7Z>5+gMT*S5xY>j@C#KR_<>RJE4mjQvY9;d4X3KevP4lf(?AO$91Q>6b)v= zlD|@Yr5v5nbv^ux`70}cJ-E+Xp^XVQw_{GJ~%M_^nR)Co~+ex>s zH5DWNRNyFuIO|TT#rygy`FNs5q9lO=8zkF}h`1ZTG9nVWVnLGelURlO=&qWw*nj{j zflEH_CZ$$FF4?~&>@#IU4)OyfRWO?+vPGu+^dPCT@HA{#s6{EIR!9Rh8R8&LCL1@s zLh}*x*wc|LYV9m$T?9&L_4~2=XEbAUR=+`y;ngS(kB4X}g<$e9O61R^wY3z54b=Fv z+`6d7&?qC)5#Q>f{FX%l@Es;Kslcj@#K>W zsY_sQbeq1$G_9I?Vs8Wp@~0Xl$7VN0eCwGcxI=!xZPx^Oc$EMjT# z{)ADztVfPWR_=^{N>tm_77~kENX{M7kWL+G!H#FDJ!-*CN*Dzf;HS_e8&A&tG68n^ z&qOK{JPA-g>Dvn*!g40_j6OYa^vk#@5k?Vgnl7gm=8ix`O`tQtxwrRRGwmQV^$egJG=FFHrCtf8OZ;r9YS#=E8t<#x4O{5EcV?*nGG^jPtA5nYih+Fcb=GSQ4rUh7NRUb(pSJ zuJ<{={omB9YM6Wy>?oJc(~p}HP$Qb^NeXuqBub+v?on5xGt|KJJ+3=CvifR))EN-k zOZRJxs2hg=s_0atvo48^N??^AmXS=SG?Us{Va0M(Hj%?Aa-$7&60hO=`#`3!fmFJd zs3K;xSNw*-`t0Nlr4k+n!t&?vvEK(qTq7bP%B!jzffjcop{>1}(;?VjSb zWuO$NMa9^Z_-&H0XR?`@XA)=0G6eSm62(EFPL`z0RO3ROO;u8^fl&6hxzz)XNzew@ zcQ1_j(!W?CSVmjvsn04wCZmZ z_@Tr^LLCyrVKS#Q@igZ@hDgpvU?jbUizHQ9d_4Dq>5dUy?7t)=Bb>EvkYDd>T;mqx)AH;~2t^zt1)_>dv} zLDEn%#6ckVeRU#O#on(W&gsImKZ8ltjLykr!z63I#F?`eByw-Zg0|_U$YrQ!xd#fg zEj39*XcTe3T93#D&up$}#SW{$2C8lPTN6xjI~CPTl0r)DKg7xWbfzw;rX`j~jbx!N ztR7Tw=ogR-`ueZU%KrtubvAuCE2I?HIj@(YQ4LN~B(AmliDf_=WGtCa21Z96R&o)kJ)>rk&)=Up!MQHtey9E!D)@D6q^nNwU-+9v&PdF;8+Ee zj6^we_TJcN3pD7T{p1$K(t3V3ALC{B8`0{#YYNg78@jD%h_cYab)_c4=)=fy{=%gk7?TX1Il_7W^=U|gtE z86Ck_9Ho)m6%*$>J6zCFq%(5F)BYjTJHt}J&JfM8nRSD3_^t2DRB(#GiEgp<;L&Ao z-Bu0;M61UsJ&GQMOBwBE)&>C*(wA5nhx2s+7Z?JV;37j?RLtm@M3N|pXm92*6g_L8 zVB#t))DVLaKy7Z8*31$q+gauqU8?rYX6og4IK=NRpKKDXo z1!O7dX{!ST&K%XxN8O-gv%*gr<~Y1#!?W~F14owu|2mvkXA&eiUM_i$W*I1$2+5SW zShOTIicvLrD<6E)p$n7Z4ruv;Ngqo#rmEK->{ zqXwrJu|&NV?%-OK71$>u`%Tr!^iWslm$#X4wWk>VP@sfS7704ZByBxF6LE;{mZ~)k z#k*yGL;ER_!fZv7haA#koo*n8zliED4Y`U45g|Q;#vtUAzr8GI_ z+BfNC+M?_A?C+i|T#z^HJp2tW1u+w}4s?zs-#0hsz!{7u?XN9^*aeAz^kp}5mk(&E zfVn19`t4AuA_q6KgLs>8Jz8aA=?Y(W1WR5)Q!+hC*WW!9$zPsKjchA8EYqKZaxg$k z*b$33+R5?__JH)(a@H+dKB5c3b0T;v+cK}^wk=IEcYV(uKKl{-)14#w8Jl62@)y&798A78b(P=9b+Ad@`5@rZia!_z+b=Y@jxHj45 znGbA)CXoa1RfKo>MxE6oyqQk0Wyp|H-38&}AeUIyh{qEcrNku zh*6AzanGdbiKEN3-SCo#0hs`aSaF<*B+e|ZWGzA5YRA`9ts!n}lqdK48AFD+MC6|u z(cR?DMnt@yOy@;LWBriH+HvP0IAP(w611Lx<22CVhic}A-$@8cS{iFcJ(>VGP5-tG zDkdfTDtGkJ!%KmsPP~`us1D5FWZ-p{Xm|E1XZ|Dq$;uB-stYVQup8wQ`-8`gdLEnS zUIe81!r+rM9k?>SX~6?40&kA}pF)kosI9qrcy<=G!X=_FUzAAtTR3`h;j`=gv$!5Y zp;OBvvnCkRs0z495MS@`l=~9yl>>+oWfmH2O^CdUh`k~>nbcM+)8ou6TPjM6DjUbj ze?C}-Z{ix@GyN1x)5F$5+gv}yiM zCiy^@GiIx2Uq13sjV^ZHZ$@noa#!JUZ3ms7=GqyoUiTK37EtHjJjZ0fEWJCzzNjm#j>M#Yr+rhgTbb~&M96BWJybpWGb3&jZ zFkA&?J?3uv;5_lnqq1@dbm;f zOvo*>S-a3+h5xa{aI_|=hkCX6FGuaj)Y1s<{IhTiN@mNActC-#_i@q^F@1h85>3(+ z%4oWffP-ZcjPJZ?zPgYqO@%zroGHmdGjZ-v_tI!L+&+aK(Lz0RRZ9^#HlizuY08fI z%f4pddW81v%p`MS`YnNY&MlVUZ>_ zTB&k+n04Gu%BwzxgNBiS6+1@xs2cH;Zo416eahr-YpR#b;}ob|F45%4U}+!L{`uDf z>8?&Dfu*O~h;`Z!IkW_u?>VGS4d|%F*IRm>C*NMO7RvWHyLJ}!kTJnz+0oz@TGCr>zOqMDfU zUR6elQEQGHhi%d$gVgDYZr6ej8{V}?V?~xDNA7ie?rIFsL(NhyApY&%@vkrRf8%+( zNrNfA-x$_IH*2^qwws)K|Hx2n2Oei^R>`oc@bdHThm{>nrxzIt)MyH5ilAx^YjJtk zmu2QP&+GDqN;7~LeBT#eyNlgE=`J88IiO==3>s%m&C$swG}oT?%FC#?dg&>69f|07~O_jGjKZ4P5BtCKBS;VVA_eDx&e<|h2z zc{L+db%da*^D1}={U-7q^^a4I;7gmi$eC=Z^6pwtmB)_^$#rx{5Y9jo{%aAEm$ZFy z^vt%dNU;1;u`Zb!;_W19;J^yvvt&VsDE1fF+El3^Q$G>I>mV6uVOk4zI802DA?&QY zy1?ZEsp2=D8(7rrW#=b{daoK(fQ?<8Ty6`CBoQhqVp1cGOq<8tPvdX@t7bUUDVy35 z0kw_w8#tBk9Rs2A+K#}dbiW!KHRVsexQ+;!#Vjhrs=Sbdc^YLOaaIrSE*K||d8Yts zlw`R@<|Cyw^9ogybR1QHS4q}~e0l|5+#mAETq#FF`bMdQ38^R=G-|&>t;7sTNwEwe z!qg#l+3k6IKP$klMzHhgiA__+LRdrLK%77-1QJ8lb_iEjN9ySIM8fosgl@cvD(oci zpVo-OY6qV%j5ImS2kn|r|81YQ8>TsSd<#jvKAH~p%kx{%n4 zy;I3T((xtM1NYzcw?H#%R-Aw=4seE3BV_n3m4X_atLU7EF7hk1Hxx8OFvMbyuNX9X zkMIF;QQ^HZ7|iH+^Bgaq#8frUuBguzw#8iJn*j`RPyWV8=jg2XJ+l745mMP8oUZP5 zfdd|dY#&_=wD38;R{XtOhq51!L6_SJ9c6XHHIyR(1XI(k35H>+VvO)Y`?bWU`0-ZZ zn0GCw*N&RN&ddF=?>T%pVI(g5opp-lIRDtoYO>r~x2YL$3q`$>ekK{}GZ`k_zgLLpP zNriLIyvvR#@h}%^S+G9(Mi#dq;Q!Wosqo$?<@y~A@Apy z6Z`6ki1s2MK>LBex_QH54Fh0T&i~9Zy6|^LuBBQbQi@|o*aefW*Tz(mR7-{H)~Z1M zfux-2mo)k5E$&EDxMGRM2?0wk0s6+k9bm_qQzw_qC4T^?_FhW5HO3bGbZ9V6#Gm$~ zppRNwMuL)^0n&OkG?>^0u0}yw;bpvuCyuY?yI?XOr6qwwUUR#ObT$@>`UmhFAGdjp zyLbJtl$p%3<;<#uzogqWOI0E%EtJSPkV^}&v zJ%ly>Aa}hIEEp@m62~xu;OBt)AeAI`TZlZXTJru}LZ(Zj&%4TmxaVl6O|9X?ns8#* z%3Pbmq-xQ-ThMlXBmZ`j-uQ(sAs1npD!g1h5bJVT~Ty#-8Pq~g$4D019*1K zrrh|?)l2RMr3b`Uu!%{}=DE!)@wufn!6R4L-nmJXS zUWUu7i9Z!U*FO8`qn;Z;*8zr_gm6&VP!IjVRa_OZ!l>swCM2(*>jUJm1;4Gb9$wXh zExj7k|2-WA=+5Sed~gA#o$eW zY{UzST!T-}YWNw+F|WouK!$wudA&8w5ppsy0!T1^AHPn>GyF*>{6sl#?W_+L-Flt^ z8_*%s`LGElf9THDv!-GO2c2X>}$EPXjOhD8_HkKJd;ytmyK0#HPNz6e4DLV0C{gPj`yxA@UC){TWt#Cf3pCieKbi1 zxn=X#$&U07uBv!NQpKP!f2u!_J{YgJqVN6kN7XkBX`aT#T{k#q?b&k^E4~L8pg2_< zH1l<#;*GUA+*Ivx5<$fd#e^m_@bNgmY-VL{8S`|IaWk=5*>TF;!qkE^n>={bw#*ZA z$+cL4Yk$6+d-NMz@K4C>bMd53;`Q-Gl?XAmcLx;+|lM|<8n9f_V+vrcviI7 zJ9~e5@z1-l z!gdqW{*@w}|482i!CR*=h12vdO$ohQim8}g;4qyniR?|{eW$5|pDl#&y5nz_Y^e#XVfaUwBENUDml3 z)25_@G7%P#p^nh*>Znl}h(bqbL=>Uf1xXEXk|@0DuxrBD@|5h9%mt+%MFLe(95BQ@ z;YdU?6R^!|CP@PPek~N$G>g?Yi>>Mf?ox{4xQA~Xz#rz>CYqd|S}kQA-c$ zc2A@^syRk!Bo(PVf6+eZW4Jg!udS}`1~m0rdU|FiCZ8%e`nF*!*vcnvIN0EPbw9to ziW9+s1w=6;F2dWp7T!t&OId>HCsNhFYGMpS_``c09(=1yEA#w>t1MQ$mb-F0y7?2) zWzwj^j2)K+AE_9`rFp~g@|LODtQl&!#gP*CE zBRz~%nY2Ihj$XFs0wX&2UEOs;o$Zki6UY7g+V=!8gNTvVacPIc!Dm1V5;gu&bI$C1NRmu!=SO?m=Z3YZZTA)Mdc= zG0(H_=w)i`FCM+_5BJN;*9{mHBr~Z35C~__L$li-RWKyAuCsx{Co*LKDJek_J##NN zv4d)cHv-K)TGL$CAcw&rP(F!ONRmc&WC~n5Dazuzr3xO|Dt2!Or+5Wh+R(YOB~QkU zZsvK!_s+1*o`(5!hYx6XC?j==IVKoeq^RDfybzApDfC0=5Ku@Lod?95$h zv+ULL4q)=mTe6zJZnP+gD$qO*;9T5<<%df+vO=pL{FvK2IbsvwNqs>aeYw4TdnhyF zJOb@IC<@f3^Y+Sbs1_d^lq<+^9KC<+P$TO@#^JOx`c# z<0ag63a;0`3m+qkQCpqHK$yxD=ZnI?j1cDwK!l=IfmHT`?S{`{3a&$s$o#ellVoD{ zbWRO+%rkY0;PI$rq>n~JvZUz!>4cgT60Ht0@)t8TRWQly*{OD?jW{-DSEgAi7@$y) z(v@z`BAkmbDZ{AgH4GXIPPgMRbhiI2FnyS9woYWC3R?~eixmzGBn6dzp!ftqQlmoB z3%g>GhbteclC8y5NrK^TM@`QwKRhUE^%t_3tvxA%r)bPK3JtS1vYkaV8LsFX>Kuoc ze8?7)PSf}1ow-q6<+L@pfBd%Y<6~Oj^E_h@~*g{{=7f1fw;Ufo*!vgHTn1N zO7j6~Sv$5IU%5elz4Nu5hBGvJ<)!x0(8`wgzQbM_V~&KbG)dRuiI1b(s@{!ri)ZIE z^>b#$Z!!b)!YBFIlFIA9UhV6FHUkxWNrf7uaB9NnVt<7^FYd^P;tDA$~WH+BDF7x==!Hl zvPoqppGB@Ur_!uu`>n#AVk|x4aQk8rP+)O*haU`JUR>D{LY9S-7}5h9H7c0127>dpfGa- zYbl7y5ND|q*C-ENl(P|Nr9#)0zVVPck-dNng<&8mrLw1VEDFd*Fj@D)wF^G2UWc8b zkU7V*r1FP+8PF?aC^*CyTO;JZp(LfH!0Zh@gyKY%R>wb%yV$xRKf##fXk2|0ein1#gAdTsEAADB7yhu;rI@rt=K z{Q@Hy{1({1DkLQ%`NnN?hh@GV%oMN)Ux@Bc^ydj!HJ!Rk^0oGSSqkwcg3VKRlF29-jMGG%(q5mVMG*MbsiVaM^Bj>U(U!(Arqx0hcryLQ}v_J=$x zZqa4_zRpyotw|DXVcoyjsmeNrNiSSUle^9;EZa8s-S(bg+mBYmfB;mlWW2(bOKbE< zTz)=7%;dAV}4f_dygfx`TU<}xUY zusbTo_%4oT7vP>Ba>9pR0y}&oMguRhF=r&CTppeME4(!c+zTq1I98#VO{5!YQ}#rJ zu5w<3U=nAl!S)hvJDdAECL1aNh>lL8);d*Fan@*MUx@r^nTKem*2aezGv1f`!yn8% zFePU@h#?l!bVJCdWb^$hM7Hf2y$rYaxVj8uB~q3OG= z0aGq=E>?+3R^g)9z7OySkkpW!)zwi^iI}_zl6w&r#nD%~k@qMP#Nw?>0x!$hAN@aQ zn&_k(P8D~|6mhHMvFFvmV>X@{(oeIhan4{DD8;3RNma)5)z5C%eUo#Fgb|#@E7(op zHYuxX7t6FS_5I9HlVtj@h63?l0efg4h9;F5lc+UEPtQ+lmzDwKPveXHF0nF&pGt{b ziCV#mg^KNB*PVXf{)j!}0dn-d5@QMt@b1%7CENLg_q&;)hbXsgof5U*3(ywq$AJ5f z?$ki-X+ieX$)AbgExR_A8ZlsxuYBKb{r5v3~p`` z0$5*R80FwvDYI!Jo9*U@zp0^5Rnra28G3s?)^gb7WRXGWI96*)rF%-PvP&mB?s|#J zu;kcqFTZQE=gWnEMfRu)YGEeV_tJmaxaq@}AL}}XCEiv?b0|O6vHmEl&@@tI&v7q(Lx=gGqEQxGVP83FA^J*Y6f$bQ z^G?5@Q}TExku<*8^_-u~9^~iggfq61A0`H5lCE!(9d@VrFW|EChRh>5M&~u zvG|Fova*N}TeUN3_@k44^)n!2IFz_-`?rN*OiTzGYy3D7NWoc*-$;;mA8gl#)~<#% z;g_{x3WU>?g0+7sV;3;PtpIjiFQNHvlUueK&=+_+0+7yT%# z97qFdArh}=bhh(Zl$nVrRV-Lo`B_ocE?G(4P4v)lzO_@D(;?X$ziskGU!svAnnLZ@ zuzu6{v#6Jz1>K27Ebmvr5gmEDC>$^YyPw}??bH^1#9j?Aj=v@%O~q>-+>OmE6R=M# zixHlWHs8i@sr#D_w%1TF-^)0dM<9GiZw%%vOYokIggfEJJ8*#sQicYoM#K;aNytcZ zW|&!7MaIRU0Q!jD({_sj*k7%uyYzmH$0CaI=NQ@M~e)L zK7G6y@qJGt4V$)&&6I7kH5cj#n;?Ipv`A6L6tawo_$e?p_U~T@ z_sbFjn;%{jbT&9w4ZGYQMd}F*t`pRHX^s(mKHQD*f6u(x6%%4>iV^Ij>JL=ZWfBjc zUanH3jf{?F73%7~oky3U5qy4=^tyjCH(1*#)BD^(p@aSc7kDj*LnWH4WN7M?s46Qf zH#I(e_ZvF(!t|9IFX7=91jpuW1}ljGO# zid#dq^cvX}mzOi5i%Uy@MXb{X<0UToH`?B3XZ!0t=}q6i-mD724GkR0DJk0CHKV{r z%~Am45saPO8hU&S&guLsI2+IJ+1Q&O^2NQSQ=x66_oiKqbC<-ZhA6R)swi-_z~<0H z*8G6iG>i0;sQ6~5M|9K~MyJOmM)vV9HRRD-6doFtiePeUtsBKv&ISh*O(=^cQCyrW zX8}#{c6JAJu4g~juKmSADq6>|+YA|=r-57y=z^jk>TFrcC}dJiho0ywzHnG&ni<(Xtcoq+JX`$Drbyt3H-&qG=z%%3=u@y~hWXV1bz=g~X7``Z~h zbPSHZPTDD(SvFTUHJR9KH(x)(xQ zV*~;2J(1i^MTSfqY{wQ-@S&Hh+Z<<1&P@!Jy}?p8uc@-wRIyf6FR}n#Bm|n@T5t!! zG2V~8vQK+s6sD9R$hp@bVq#*%L;G4N>O|xq%)RU1Hh5>QN-DpcO=T%uf~5%!IW$rg)EgrA!TqTQqB*^46<`D zg~yOFL37K(+|WR4C76bH(i&S9BYSH#DiR`JdzX)+yx5$7^15uJtPw!UpdOJTtU;hL zi>Fz&0#J3!zjP{8Dl}-4WHPz!Nk=BtWzMQ{UK*TUTw{O=aeifdz(rx#96}}c&)W^G zNXuUO+fM;U?)oZBnlfQ#+FHp$yWHFgG0PL&IP`q4^plqisuDB<-QC1zE&$)SO6i*Ll()C-a!Be`##yVP@#dmmNQEhuenl zLovJWj`=Zyn~(xv7pwJj?+2B~Hi~j37s`~vSSDtE*75OiL@XxVy<bzZJSG@^_Xz(-@ED(* zxPH7c`KR8R$jG@lU10;bWrt3@ZrPH^kR?Cbnh+JFm^Q~DGqck6FW&DjxOsfzixsmS z-V#pMo9zSk_sszO`jLe4aOXw7v^gx1d?{s`twF%Z2paI=UEgfZ$pJNqZkJ0GV4Vp( zQxbru)0x23TcUt{{q#^P^|qMs^RH@bd)OS)LjI#SK-K*aDPbW$S&M^RewFZ0dA;x{ zBMBU{Vkx#lDiKKWMoKEU#~_NToLgfR0xBH7J*7Wc`&wRAPD+kV5I0P^&N$#i5_)oV zUm3alg#c||8q-|N<~%_-I`b3DHkC=+UT3{TqQE!gpOIOGTJ)rl zke!Nc3licF;nvzlcu)K-x|}2Ywp?pYI=P>K3r8@gScx`{X>Vrm542!~LdZA1c1-J` zJSBP+YRqZ^m`_IazGd=Fb3He@#Q1bWBTBT%EPfX+%{Ew5cd!sdmUpbxbt{Mplo14R zQNZ$3XbV6NT>037KL8@JpDhudv1zbyT_q+D^2!F~`kC-)HAb-nYt%`%%?&yV1R_gs z)XNQuh?ybsDhseIImUrvnf8Xk5!?#v(cf&VCeP22CW;~we*yttg9^zmH!MkKqtI;a zH19a7WmAS*wj$?=QpEx_rYvwfM5B#vv}`Z}E~h}GM=z^FpEP{nAS`xnY{7{OC?mbL zs1inkqZ@TGsYZuZT8zX#Etf%a)Q3ca)R&*X0X4s2S<&X#ucKbf&Aqd zV^HIX&*SQmL8OjQ;Q{$>XPg@npL8l>$M1Nl^Obu+zmO@5^1gW7BUR1+eN5c>f>K4J znu$Bfy{saWHa}IdbOK0oSeTi+FE5!*OiY0AoczwjgpY=XizGVA_GQy<-Q%iRZhChy zwQ5e`)zhN^o6g{=GY5H_C7036LI^M|mnlRAGICIE>@bIU9S@M7Z`jair!-e)%%4Z? zr|rHKti^a>IcN9(;rDRyxs&E8Pq(|}++zHFlp$;W090E-?C~$QGy{%zLn7aLB!>*j z?v;t~?}YzW+W%G%1thA%_K8=?*gt-XRetMgH-R0i#l|Bt@$vCT08cqSU7JlBa8IqT zoKb-(r>tiAbE_V(UL0uU(W zB^?Z`B3Qj-P=GI}Ts^7_Cx#EH>+0AtgzV+8vN1LtAiR%P2ASzP59@_4pE?oCL>+(lA zQ8+VY4f z)2zCz%kl2+@O)@_*-!Dh8o*lbbj;Wv8f*7@LS?!{I^`N~UH7fJ@csJ|$aBdiaT*v= z$D5=OsXzF72p1%MNwj%=*gpI#8*a)d3%yo%_UvB4M>2L6U zu%!EPic-{HqFSO{~`JAgadB2Nq>L8WcUQ+4wL~i>@dN zR26mDxL7YBI`x+Sg&tjRhmR*K+ai%UFD~{$ZfKNdkTb)+p!1+DWl2GSl)|%^b z*%EMfk7s4>&h9sHyT0QmTi128jdfIY?tEFQvVV9Npk1Lap2|EpYpP;qqJxGBv1r77-TvbHXFCAktu|4c$vk$#%rf)v41Bfi zm?)W(#jbb)Oa#9G%+v)U`Kg&gFLb=OfP0!7Bij zZE;9CIyKFSuWSx<+!R8Uv)!S7Qc%p(a^=ZvG|5bN)|1-@m?p0a)!j z84!Tu;1V8~3%%fIR_O!zblk)@d;E~BEP_gJuPD5njSqj;Tj~JGb{o2^+4lupfB45U z-*>7U-*=oJKYjqd>h=fYI0`vD6MOUQAo#|n#umU3{vTfCX@pf_kTPL}nVq};<)Uk9 ze4IVGzOTmpF|=VpJw1!kol3Dri}+Gid!ojit(B04+!^-eFh7Qf4+*u!z}19kU64TS z-g|e!o9#$HH1(Sof$g6R$=~?iIAXUY6LNN!Eq-N_;MG?^GT$Y!`f}&)X(hjQ zfphc*@b_n>U}Z@TUE2N~25a!%w5qDAnS$Q9L-x};0MAXlX>H))O{`@v@C&L^&#Du_o7PTU^XzYX(Jf+~G)cwPIr>keN_RC2(4{E~08&+@Rx+8QIyzhM}R+ zk2BdF&(kPm@eaK9^3Tn&0ShmINi2=oMGDC>p9l8}f~~>8@~!|Q->l?gEl$XHv()Wv zqoSfBEnS_x+oQQm0ng->745+xDr!v`Y1L#iZw8UX=raLESr%Z0D&ZMAStSCSCmAz^ z+xZwBknD_)PcpNxh?Juy0IO|n&m-RFM#-z)%;0ya~2-4p$XIkvgP zF|%*qig=t1s$8 z>D5<%(f4&v6X!ReA!-iclt!}hshe4uh9;Tejj>|q;t&!Tc{n78T}fM|6|ULT+#4rF z-Ep{Nd@dE`m^A1dR`h*m1I!mQq z${A=Q>EMtMEnes3phAj8E`4LC4+_ammHIsiByqS-y393@2F*;LrIV`?fvYbF_(*{B zX6)!lm-wNPT(hb(02%noC|XE4#i@Vx834h;E>oXa=@)wAE;EM!KzJrK+1=&W@rkrv zL%)Fn$b^0;9zaa_{SyZ!W(qKqd|JHUrx^$auWTL36`c>I)pK_{xJ)5FjDtJ-&t$!vkK$#X`1OG8s=NCG5ZV}-dqw~W z67L2Q-IOMEaySrf1G@sy;TyTQ1Q#pj#7>yOc@Z%K{-leG`m8K0J%`KGz+L#w(=*~M z>x}tR%Yv!3b(BP%bgmY8$`}ygh~FQ3mY4JQ)zTj*X78P@)I~-|K}=h5TzU(6L48D( zX3U_-8Jkm+j|{IU`LyWg$CXrl0pzJZ!)|k)Pt0*ILw$6xi1*;_&hYF_rs8y&J1@~d z+6PO?f-qR=fG85?aAqu3(c+-Z&4QX15gQA{O#WeJB987}uAh~QQgpIKO1a#o%-Ipg z>@%YjN;XoP5;|nF{bs1fG(MjPi8o>`KHqz_;#uP|9UqpH*zW(L?d2#1z=%>LqCs(= z$eMfwR>-tG-P>RWN#JPb<48<|WgtKL!yS5TFw-qf#wTdko7sKBDh!D2$FKy=krzUH z6z~6bOycb$t##i`M^P4eX+D)C#?U)52IIqjavz<;SOu8!ZF;ZKA$ZNO4AoKHvk;Pg z0P{1aa%<4`4Ac>rG-0Ayr{%(_5`bbs4{=0n?XQmei+g9g;VZk^2Y;BT4;AgqU(rcD zna;Slc`sSF8=|oEi{ou!iy}c6|8_MriGw%h7fNx3DT6w1yMaop%*nVni zs-cGm?}*sO>T2GG4b=<6%iS*iQ-DghE#~qXnWM>14y3&~O2nTW%3-OOY++{70CH;L z8{5cYRACy!n9OLZ8LN?WjlciL`bD4(P>dGeo()EWq}8b#y6Nsw*ZkMP0Y_>|pZra| zv>yF@d(}6<6}Qr~Elj>Zr~CV=0TqwGDn7$a{S3kcQKxM0hFkW+*^KO8L>$E)w&poS zE>xJv9W5%DWA5gb%2qsO_f#?V&n-NY*EzhT)X3-d1Dw1zWzb*)bp}z_!UWEFc+wF@N$j< z`ULP)7Wnn)CX?4Yyrm@ps8a+tpgf#45!KHOih#>M8WrGU)Q^Qb1Ehna3>^a`C7RCT38d8lDv3tHz%85mCWP@Opkz5({sQT zjjrXx~#lDv_KF%I|ZP?K40!nsiB6wI74^Yiu&$YQ1O1KI~Aa=TB2-glvVO`U(X z-(VoKV?F?>n$X)3%$|d`Ms`(oLqia__2mn__}<_ON{w173$&~bEY)bQIxVR-L!yeQ zRYceo8c<_WDf?`9wkkP)vW6I${b$Md#<#k0?$7xI)8TnTH{=WH3>4{TA{<3B3^WXo zsO9T2+^kGY9kw#=qV2x!UXTH9dMnKl^|i0j+ULG5hsECb=RQ>oaO$dsK;!VS_(K=`Kc21vsOmRb zDxj2fcXvp4w=}3occ*}KNrQBQl+p+n=`QKMgmgDZcf4 zE`bSq=a!TN+D#*NqZFc$JH#@?$;~NUtlNPm1c3fI%WwIVt=sHu`10$EZBID7A`d}t zkCwXQ!L3~IB%R}@;)$ZM1Mu<`@Pu*<F(4HEdpgSE-4o$7z?nqhKQU4|IbO?7ORaC2XIkaESmUbk&d z%vzbWRI_f&<1(30*s9Ws8Ru&Z$YQL}R^(p2l~*!Wpc127M~^F_G-btk4W&O8 z)a>Y(i5K!XO(QNF2~P8np^5~a|AX2v6BnlUjDbTuY{0e4X&Xysz#}L{7PwyvI{ic^uB+a@QO{(2arw9yVl%+VO zQDR0$X2=`Xl7EHp4sNO&Nj^9I@UA{pd%eFAhN>TW2irMu)co(=y`&C=Oao2GvniJv z$sp72_IBhUFipP)-+S4@%`F9#>o^b@E@%yey1Dx7#1HZ-GhyM7*ep7+&Y zb59t_amAVWJ&6MmopO-PkD?95>ffo%F`TZ!=%!WtNWnt0wwg%Pv~JD~x*t%xJFa{L zGGpNmzci}VmPr(o|1w*+6YghIrXlFQQ@MCd1^Ngug2CT%Z28>Bo@`BT+t`#Idacl^ zd{*z--+QYU$^J9Q@I&BmtsV2AJT)h{&!Hjbry>PvM6uO>Ws;nsRk=+Aok>V0*%k-mTO{S;tdK~@N3BW3ZHW0 z&(B80Z%x~J@NxPy5t(K+$mx^ihlYn84;Qq6xwWzQPXHJ{QE#ma*OWG`_cwpu;|oov(8M?r(Gp52p%X z@SRwdBs=!;4;5?&mugl7W(n*{NHLS4-XW?iH2ti}RiMl0E%w!oo_$ zA0&tZ*G)Y?$qeMCWd%mD-C2vyMuVhxjgriv#Y|{ITF^KPct+Y0fUzuB2u=N}}JUt`qTJre+1TU)W}KdNP{Pyl9(9lyt?`VDxpS=SIIo4hZc#K$Mh(=Pd0T`+0o zXlxztU5x))N-JKzW?pd zhrN!Pdyo6r#w+O)6+YAyOdPPW^Y^DYTa4jPO&N?^PW78|YDP!xg;cs_+QZv%RXJDj zrM<~rUoRE%>ZvM(0-L~%Q+}j;${X)!F(y!294iS3A-Mji?+(ZjXx_5S=K$G(Cux*9 zXJY?|X}orq?~2LSiVF6T4B^iHh6GSv%zo>`Q_!pa&@E=;~#gB@Fp_TFF!yKXuFv`MPHcM0WxLDNwTW%^Ot1d7gv>I#vH1jS}!7 zFIw~>IV>gJ?~UR*^g|-}60-qM>vLX#wjBC&Kwr7{(ce_KWAH1#F6Y%wEm|ln*%jpB zCJ|mFB0n?NmLpwNTYdGm z3)|Wvd>zgeA6YIQbm30(ngISZqTFI!Q*#c6EFd|jWl{zgZsS!BdHE@-@(4w{>~}U! zUfNbP^PNj|gy@R&cV_=&sDH7&X6g7UVfRMH3z#*)5DE6FRt}ma|I<)W}y#^~q8!0cxPGF{^fGw4dH;azg_ z_VEU-8%bfF&+HxiVcILN9BJJXWc6qtOB?rNzDExmk=$?;NI!p3Jp};q^5*8Doj!Un znny-PvWbX{{HHoGA@jdmr~M+?th^jUSVHyC5}^7^K&xb*Zg^t(#0O*x{}{8RRv)eq zopsEhR;bftX6F$Iu@l69leGt&#&^EV0l)cwQ36piR43sVm1Ps3d~c5ekH~z4{20TJ zp9?IM?BOOa2H)WW+gW{SV;04!b@&#*29t}6830T-tDEdvGTgKET1Q96VLX%Sav8Am z#6hPW00Zes%}ign{qWx2ieaddh?KNI8v=mXwpJDjgWM2#`Z}w5)EnLC)i|R9+CqSz zfLXUHL)bZawn0lKM7HPyqbUbL5YA#`F`NK|dmM?=OUYsO5-A8-l7WVwZm_G1k4`1a z)M^*IP$l$q3>i5hGAc?9q7gTxc97P!q+}X-TW3S&M|sZSyxx88k6^D5#G!RVTw|RC z-fu7i7b<72{rQAe@Ao9))>_}W4t!-#jHB$O;Qo}5co~ohyiBtV`LjLj$|DX%JQdq62Q?8{UR^D65tk8aQrc# zVUnU^?;EhZ@8oJ8>Gn1wNQ|PU9TQiJP9>kCeP;uaQBpFo4G9?ez4? z15oG&q2qdax#+ig|2bSD>|tGpM;h!0NAzg;qD)a3U zU>9payF4>B#+3fev+5>04TIM9e$&)*AJE`-#G9V+??-kf6sqty2=vZ!THKTvJjUA> zrt?*1iTH$&!O`aeb#c?Yk&j7c*`9jY2YPH|Y$T7<8)AU^luesmbTfiahWO!{#DF1j zs=gJfpDR9npz6TmnDNFdN+8LfQ4iXQ2D5J)0uHNGos2>b)%C;7w|!w^2V)FAKU5M!M$U!mDm z$z09TtZQIl;TAe}!VYvHujU;!H8l+lEyEOfA`)>WkaVGi6T7j)n?)afC6?fT93w~J z6tP!t5<@_8(L$q7x^=!ph3X0bGMHI1*AhOR7pl^OD`v%&{*@wq*jTa18{DhDl@;<} zb#{VYO*H^QI=5*9scDKh(&fL44NsJS7lXAO6+|RvMn?YNEfQ%tVQ@QI?7i@2OhUSm z$Z~D!#53^rpZX@B-*JA<_12(uV|JpjnsE3SAC@ftT%=G-afkNo-LeR1#YCdp-T1k~ z{yL~>Eh>`mM-UU^>NsF7<41}2L8ScGl3qQ{HMS0CmnR7H@YFf{6UxL-5XCcUyOjUD3V znd4m{RMg2O6j>^Z;7z6aR1qgF=)DzQUm88*_EmCsE(E zMt0f_(Kee{3klnDmPKe2%Q84tnff;|r~&Ki0&CvHLmv(@uZ}f4B6sz_R^h&;!j{Kx ztd%W@rQuDsaJNTrh4HRaSZTO!rNGid=AeYy9gqjIHqKL8a_?}tR_uGHTG^V7s=vUb zVt#{Li=y%JR1ymTn%_`^sE>E)9T|I)z`Z~JQ{e;gh56~MxJp;ds+xBO^J@BlRjaE8 z>z!Hh`pO`F>rqu*UGMs4ubcu04^Pj`j;4CAi-iSUoc^Q2J460MU1HfC(u*54-z`3N z@t^4O)ZF3g+D*Wv#=J^eBpVRVYka85)#W*-9DsO}uaPL62+vCu7JAE!hIwr?Wgp*1 zu3q(rX{z`0D4>~i z;gQzTA`F8={pr3g*i7M94dbMC(oMpdZoNCOJoe}U;*RU{36%ywi!w1W?b{xWItt2~ zV{{?l)wY;KC^R5;c(w^3zzVJ1SbnCb_T9qUnq8VR2WFyBk-JDhW35a>LAY3qpZ`fu>ai zNZlM7tfBqp?T(|A8JOwAv`@=^_wXI@__@2T0_O|l z8&p(P=44Rbb2RByfy#F37d;L*<_HYQsk!x1fL$sEefNHUgX%lV^&g4fD&>j5B`?1> zC4ioR0=M;dcLGk}$E3ZQ!(T^Xyucruu2wg!cF_DK`*F*HEZhTkRp>y z`dTe<02@gfhz>v&1#r_oA|NiRsITt>-;3YvkXUb8xK^~*Y`xK*is{5K%cYj_xijS$FMG&BQ;`c3I^A|h23%fI}?K0`i}W4P%g z6WIckFFlSbP}<~mkBp#B|28Pp{|$b!ZqfTr(a&pLh~Q%!m@_33gcfbN4-lAlG_9eh zosx_&JS(VUFzz}hTVwbsk{^UD-MtroNjE!{@bPU9e>VNR)at5e3LorZGxqaKxl~YI zHpfcsj_vRF_=E+jB`Y%^A-dC$onWf%grd&ej;3YE3!l|BimXTA%^2t%KrPNUu)rj?KPWsw|qcSg-EbK zsziX*(D5Tb9O2(r`_cS-9aA%0WCGGAx-r`Qm~kYGX_%05r7^F|^T(LGRLb~?A^ZCX z3ie;?LuM>E1E_r{TYba)J0#hVp4Sjh*olvt62?T~(zFBKQ=0xUyRHa?E|D$LQzOAX zP{I%RjR*+UFM@+>t4s&DiMhpH?%}+KNi6sM5fOr5yA zd-sZ8BrP`-()+E}xO=PnPmWflsV-Hv?eQU` z)AHfw#$zN~6dI022T^dg`aJYZ~|omg+aSxhN^K-vTTSe@@#_qBWT^wXPUET^QUfhLWAy zZZg~^ah>vZs=b$1TpQSM^A`)@?v4!4+vL)IMZes6<>L);q%!{O=@fAFyLC7%BIRc1 zw$OHeis2JeWK_)iBUj5tJ@0&k`xnqNs=E#e`Eas+CyOf7Gv~AW{gx|!uS4RtyJJak z7T5g5kWo>b7=Ou1NF_-VSWT_T9Dy&urB3lLfNhaRX-7ugPsTpRy!7oh)MvK-xY1;m|ZvQo(;SOx*=@N3X< zJSPMInO<5N!AJ)GuujS{AV^83_c(;Oq-r!eL0INu8}#xLcV2M*e)6|3!1Dj@d2JxQ zdNXRtE$QT-A6RfLCGzc2NKwGB`I!2uO5n1)6~*jwY|Bg;o$h z0HS1E^}xhd?|t*!NG-OI01SDzQ4i=sd$#NBfwmw`&?6q?;E=QQj~t?w&7&xg;!D=e zZ{E^Pd$cx!1Z%wOyS67U-^W3Nl^YRY&~IX4fwz2C50V4W$V80o>@xfN89373){hMqXZ_ zDh>;V_O8hwL-kS6+1Xi0%U9wDc0xizM%(AC=k%TX4Mbr0?BMa}{R-|w$wv<5*P_S8 zy#H+N9NzyvQiDwPZJ#AFnIQ#BxU2N_{mh<0lwE%EV>lds9@#(6kR6{t3?YZYb|&!e zq}~+QP43k^Dj_VIUa_m8!&k|QHyRnTsWqVcn_%OMfAw#tnbGQ9BoIeKjv^WOKP>=? ziJ%rSQy?a0K21+NJ~dM8c+bctJqn6Rql?gQNy9htHr0QP#PHR$C@3&GdXfoE{3*q3 zf^&(PKN)`~^qZzCdbRUSX3oepBc9L-I}|sFQW-M}x1ZK!K`K4HUIfC=_D^l)Gj&Vp z*tNh9qWZr&C>a4tQv;MQWHssGXjKj0s3Vw~O3GuHU(-qz>_E`QgR02qSa%ifTgC7R zsub}%<{I=G0cV6HsbyUS%Qd}M^l^s^8(0A`v z_iCSzJ48;^E(b>P%o21UxL}B)#$xCIO$`SpXD3Kb6GvZZw6BCr31~T7o>+JFBkj6) z$EvHqtHg@rIkbHS6l5VGAsCcHrznU^JYX-_wMnvY zvFGf8dWXxpF{NJoZ5$;SGqipQ=2bO4w*40k?cewc$A_z{z5$=mQggjaTk` z)uB9zHk{YKsWoi8yuFb0y6eTzHgFmNf9~;kMMXt6c9B0R2EOm=_9`n+-}E|Snn*K9 z|5P;vtq&HRvTDhss=VXTp>U&pih6Mu@TUOaKS(f9`#p^q@FKK4if^28h>PRvzCpXs z{TRCJxJPU6;UOs?^zn&^Obp2rk)fuXEm0q(Pzg}f7H55sClKCo9ox(}`yW+(T3(;6 zvH;>nb;xAV2V&-4f##Dxm#uLv_}WF<3_v&iR=?TM$tiv;PR({cyfS9uPVRu3_6t^S zE#U0&`83@uvQ3i_16fTy<^0XGu3Mo~Q@AB1CDrqp)6tKWqc0Z0ta3Q9m(zJG6mEiWBuX9S1s1d{QjUw@OX-dp9F2YTcZY?9pL$kz;r z-r3595$mSl3RnQ}X-PTra*IcQ<^2#&5zgR;2(ty(P?_9tJ^EGTKnE>)0(pFE2mtw; zpC0c_owR_t_49CH$+P!vNWok8U8Ec1`;2R!+#OdzA&<&Pv9(tsS$HdVq{(I=G*21* z8r(t0+j9?E+5&tLcK>xguJ2y^`?kiBJ(bMACJB#PuSnB$vkneeL|PoFD9xIlCA9p) z{nz1G0O@%d04hEp_kg%#67TIXY<9;Jbji!N*D=qkwJnUx>}vo#LV!LcL-;?9I^E@6 zuMzLGHV-#*=u(yNqOjni6SbLK9GnqiM=sJPlU>&XdYabjSLk_i-1%jpg<%|V7~q%D z(l&QDC1+LD(2z2xFz4{l{+pEFx&<1)2_jPRESLw4jh*5Zz*z?R;@cj=^z=P&kO8c* zLS0c=>2x*J&60_3P4{s4K;f51GK+YL(PeE@7{!-~B&%$jxzqPg|-P7A! z{ILXVC6(9L%V85t{}o41-5yW&xkxk6T&ed|+^m;C588-$wZ3+{Ce8JIybBKSQ5(8= z^E?vF^R;O@sV3&0A+Gbes%#+3HG=OOVs03K=0Hxt_3=okoR!+|$zsw^;A+e|7bQ|= zzXd{`_L{wEevvXZPR_t1crHREZ3r&o#bts>tK`-YX;R2otx*t$%*wEJKmnX$Owwe7 zf)b0gimc2d`$E)N__@_TibuIBH*JfC{&O$Lm;ldGNHA@rP|+s@Ygwr%lZ7?D=mc49 zRJpkNwMnUd+V|S1-Ngg}p20u#sZenojgy#ygIP?dd9-^ht)}RwzkzTedYIDD0Nfz^ zFvdW^G%DUr%2RTZa2o2kWUUqg>!gAzS3+BJ^}T74XdJG9i8m>{Ys06No(w8;VhA8;6)jModd4!xGAq{oP z1sGSW@AvycOJl@|lA{zAxCr@bR<`;h+V5W#((u`I5za0}s6Pmdd4&+uhW^#Yf_ph> zjnnH0vb@YeqX~K*09*u3eV5MQI2{{1o@6z-77Z!{7~SdNQpfk0(~iWnw6yiUiwH`1cz7PI4;f&g&DGV_9XznS z_6sWjmVVB20uHc%@}eEBxvyZ3C@y}-s^8oPfSKrZuwRa1=_C%0VF=X61W95MMU~o|7Su5aI+13WN$oB1lcM~xL7eKw( zbZwcITJhgFx8RFQ#{JCqW`ZrKe>@0yy)uHZvewGU|e2dSj8?3u2i0Oaf>BRlQJ zGdKpn0fLaG4Y@q!-#ZkTRVXv9U>cK=)O~Ky{QRO|&zZHIu&yHj$3Nrf zM$fk{->_3j(^AKvU?k&ane_653O-IKUE70jrhL*t5};095%0gsw1}6C<*jU`5i+R_ z;Hmi{h==7@j~R`9H?C-JyFW3&CnK{kyI=tGT;6P{8;h+c@5(#BBK@WW)5Wly)b)W1 z3|?#10s0<9LpO`i+)ha#1neoy_WkzFB%=c6z&s*wQTSJq$tdAqe4_mN{mIhiJ|?}M~+K_S^E+Xo*yl|Je$9nDYjr{>C9cLZE3^l${VX@1@^KP@wRJ9BTk!S{d= zZwqLEvevemjz(?&hD(5AH@v_9=J_$3t0`%Ay91mb*8O(&VbzUof_c@*$jEcRoT7@# z>D#B%rypZ{(FzT^=6kcx`5S;w2ZEN)`vsx(bsDFe=erH(D|S&YUo}R4?DJpMbqv3< zUtC+ehvA>zyo988iML;#Z4>VwIYZC14D@n8I*eWqJJ4?-!;!=sK(-Unq5%vOOkH*a z@a*>!??HJi2Z$?Z!#15>^*YvRA~$cP9$ zg!``=Rno-Ln(9tBYcxw&qt zL6laMJ0gLJoFzOKSDR54DVTB`Ne97c9jksFOEZ}Ad#Y3$iVk6kK|U3hjRt+9-A`ts zVu~sDir)y*ik967ydA4+~%Z!dGK(ou7(IL6CE`(8D! zda3JwBt%|I#W%R=(_}Np=@VpS92yIcN~)mlkuWrpJI1%0F}VXY5sU|AqLb){^x8{4{+M`yBSwsA6@`st@-to6W$qYv8~5Ft z^WmGsF+T|Yd3!?UPfXZk*QVjIF$}P9pqbna^m-|*dX&*oj`I2H?<58uuz1%9_!uUX zIw&(aVmVc!5P#0?Jp7pn!F*69WA|V6DJ33>ui6zOHGX z^K~i^N_>6TbOf*>BESiOr8i5+bLVbrE2Q%QrN5+T()zD;&CqwyDfpsVavdlW9X0fV zpMTl+j^*iu?CB4g$P;X~&m(`^Q%m?OVRm-^@*s*Zj)NIe-afiZSBn@U|7Ukx@R3&k zP>9|i!#>@CeGd@C*X#Wl3ccA#P^tIXc9Vym=c=}gVvkHSR9et&_EP#Eb*m2y>_v8w~HxcQn>*a zp~3Bn)xhTgC!HuAxTUVXBE<}6u`@P<<0(vBxOxX$L^?5=IHQd6hEfTlZ{lo{;B|F$ zGWp2>RElRKV9yH~wTDRkTzo8QDgz|6|u?vQ@ye0noOgiAiSKuGKTC1LlTI<@C1u8|eM<;?<~eGgtEyI0BDZdUBNE2yuQ@p z1yplEt|i@?747@yToK5~3-z8+72c%FXC6`hmYgdQA_wB8#hT|}XP56L`8yWQ9`xs+6*+xP`z`HG)U zXl2!aln{COL0G^JZRz9C$Vg>%wG=TE;l*oF?M)AEvK@%7&89Q7D)q8;IcKpHtM{dL8vd~nF$VhgnG1hf8KZ6Dd+o1o`$kIg zrb}Irs66RZ_cV6a^rl0vyDO36-|-2#5?8Stjl3$211LRAF{*(9 z+EUshHd5N z?Ciw0v^;bPoY;um9>^{E9n^+}4(%URc!;^75%3ZW~9QNU7ew5TKc{NAPhQdx&QR9HkAwJyiXDRz>4&` zK9f?(tT7O4SfoQW^>j9YyQ`2-W5-s{YoM|Op4i4_3jz$-op$h^gT#+!gb}3VNR;0p z&s{9=em&hd!O9Zy=m6gai0)_S=kph>Ebt2Li~LY2rxPdqLgRzP@Gx`s;aCQQGK%dflG&GIeP1IANrVdk6fZ2Bs-dI)w62 zy`j0fA~}<`n6F>f+F@BoOhPzjt%1`5|~>V$dcm5-M8sen8Fp-UogM{Q3lAJFPW6Fq5s4P@&eTzxDYzg6_B)t zH8iFsHW52UyU18m27Bga&f?mqs#w-`+CDq;-?s;G6i@H{wf+d!qm0mh)NJjPN1ADI zeFsIMSLS4Zw~d=f36RVQGlubiLq5HMvDve+6u$~8T>(#zc1OJ+5Lb5Wle;omGzqRhNGKk+uLbL2U6m}&(Y=pLq_VQIKfHRr z@JL=lLuW~)BQN2>;|~qnFP;{CI{OV(W#hm2PO+T-x}L5|Fs*T#bAa51-}1y#?DgwOnr*jOceP4=dF zPCWY5SHi<6XW?I94>EjtDlMgn6Woj59AjM#)Y`2#vI0*60R9p8{&CSOC@f6NNbN%N z7J_zO4KI@;AO!q?l2oA=8=KTE{6SYOT$&HBpinMF``=^z-nkujcj{vVvwfMFR()B7 zJRA>DX$|Z4MaM*8QNvV%y$L6{%!Ra0Ip2OY_v0Dp_t_FT$5-_f6~%3*mUrFA|h*kdYSEeNs#Slzd&x#_$7RI zcULhTT6;k8W^k9N{#-S!!4(q|fHy-?}+yl*j7f*1^v8cWvrkUB!TAJ3QwFw>I3N zTpcZ2I6Eigo{kmYFnU6qROak51P*H)^A{|6_(Vj2I6TFntp)mAiZ17mGs+pxvk;NlKs5jR7mU~h$}8t_H8;@LS|D_xK7{%&$BKdz@^!zIQ&rUb?xesYPla(NK4|{;5^+ zVJm|JVA@q%3mW1HbH3cI@o`AwCBtI2lxsPjgs~1TA=Qdn#elKII|hK9|K0nTC8Eaz z@5!L1{*}ft7|yPgfBY8T=vR9swFIHgyL{|W_)w5#40?{_YDeAqKF|EF3K9YFc5q&X z-ofwiDa)Bt#eR0Smtm~^4vhU=j|E7WtrB5_6E)Q_i&HfjP|>1iJX@6lX|aq0igyWe z_-HlEKg>oeRE@11AIElf!d6d(f9*n02kW4?0bq{t%$Kj4q>Q8-or^^7{Zng~!zQ(L zW=Yhn5vu2xvVQ8gg*sfz{C$|VH_1eDKz>4Hyz;Xx-I?Zdm-G1OJ8t%F9y$Dg&s;BQ z#YIRXs|-BjCIM_xeblTFvoxM)?kLZ|fiVnmbVIFoU6K^wa?A8f$=S}YKJU}{GzOp- z40C-CKSAW8MV)u78CZJMFDRmkOY5#p?6Gc|wN(8*J)`+aiZM@DO0W?ST!M7{mc{7#w3DQkOezQOh=VKrJQQaPUs@?_k9%zrDwUHM3@))FRouoB%Q<*Haj6%?(C zKuJI|IjOg$;|9#3KE8g}OM&4QEMq14qemM9bG0{KnK-`g+eTlU8)c5_x-5k@qOFyj z8UwaONggSC7=E?lrLJj20(ysgOGsolc1w-CfZos8ubAlH(87*L&;Ypr|B-BG@g%wZeYYVmAQW=+Y}WCr`gV1+(MmGK2FbHcVq z+L~?Q#LtP7uyy*Xxx)j4xE?sa{M!rA#T~hTNeJI4$N+c$aWa=E3Iv~*N}*fN^MFks zV36@VKUVW90arSJb_4MsAanX|=LDLXnx4^TG?DACpa*~65Ap@G-3#66O@K2p>+3$F zJ?&Qwkl98-UEA?e5{|8o({?Pc2tk&GnYLqF0)KGi5rPBXJyh_nyIU2!!Pk z__G+;FE*Pky!E?91k?KFza*xi5$NS#Jt`KeYEl5c!!cVK%`0CrYt{zSz#aJhe?|ba zbuTvnK|JoS*+K2ve0*@w($ibr*$D%q41SB8N70=Ss!uJZaVZ*-^#vigT;5L)SKe0# zZuiG4pc{+aNnb@N)=%(l@PNm2p+p?g`bL!KZD`oZ! zE1x+M!}nIGM3)B zpd95S1Ia&8J#Df!7ACFhQt9nZ4Jn(+-vuuaz>I4#S8cWx{n-$j@Qb7GQ;G$6Y!Ms~ zL$Dewm`Y(RgzkkCXKfb0ywP^Ze6->VNf@R(uNiUKT>1S#UDj}AN&H2L@}u`9kI1fVZ+n3nl5AIJD0IltPsO3z5A8l`|S(fT!U-6rua$aRoO7jaa3=oVD#`n1^q1TaXAv2yLTw`l3TR$ zF+SU?8^4Lk$D2x=uXJdzB_x?mBm_H>*mI~ESfkl}8>H5Ylv~ugujYPmMVFTcMNMHA z!+hEJ>62crMboz#*T9YxjG3GyOA+>}D`2BV3K_X~nA35UQolvwvu=nh7J@3}>=`18 zwwV;`d5^mf&TpfqX1S;j>Uga!7UftJ-tjFt+aAQE#Fe$R$pjrhk0GkEy-{HFL zBLq738P>PemcyoYh1(~Tc}TNXB5K$e(ilKC4o<(Hs(l?Vx8jA*?(c;p5Z3q#W^DnT zZdEf^Jx@DjZ=Lu>zhnW+WuR==!`CY%X6za?fdC2m*om9=p|pe{FHr)?3ht}AdFzu7 zMB`E<+9aoF50m;^)Mt0Fe0y+U2aHXg5nMpr05=fgUL$ZS0_Y$w5yYSYYnSfBLwgx~ z!RUmBavku-Ue^ye43M2ZBNf1jUJ>gbn6Zh8iC6eWm{@$l1S2rE&8V85+6ZP_Z3uAM z+yb+ID4O5K6eRswzL(DH;CL|ik(F7O4gTfLxAgjrr@!1u+g?CCqXwCp@qEnKo`-te z@2~^YpN++I-e+f{dd~yK2s~Wzyb4LE_%GC0>6WXK#DT*)ZHOAfr=m$4AeP{K*2U=5 zxgWJ$HF)o0BIDt5M34>E>fidx;;*`h$r+Wxt%r>w&n_)(-Ap-y@!q}hG?7jv9{;$> zitoq<7#A<_Bgvq{0VAk| z?R+RmUFbwsoHLcM?`EV$HO_KK_gY+-G4=7u+$eDB=Jby9 zq)WmNC=UzW=FQSc{}G_-fJ2aWyHtrdoT9M#9eIxf+wHn%rcGBtDi`FT0p%OyYUSoj z4veMl5Hs<}NoYj0LeOL|rNsZ6SMA~HqtO;5j4MHI_fqadhGuFWRIOC(`)v_DBc*3IV-buy7wkKR_S^2 zT6YN;H933soMywpVulnu;W7D5J_VTmwdj>h_Be~4>DwN1K06weC4sR8P)v1vv%cMG zpU5BDuvXa-Sk6kAOXY+AuIgVO1nx8%Kx26nt%GBUc^j#?X}p@Cvw%1`-V<}vx?@0d z6OFs`l%9AyBb0eFzkBs%NdR?_B6Do`E;5Jv%(5}W)yFx<#d_Fc3T3@PI=~F0o`>;> zGWP`&s$+0Zr5y}KSPkVAE=Ir$|Gxp|_*h?H2*ss3fk8jT&(ko3{#?fz9-A`EcbXXC z5^D%V#c+)3L78Fo7^|PS^z$WES>m(5VI;Ge<|`stpvZS2#+7)kNxNQ&eSd_el`<}# zghMpGLiC7T6hVePL9S3m_z@AVCK|+$+0*tT`5=S z>k~gWs<3l;*@pW~vqwrpiX1jTH%!p%eZA(7FPa@pb)&wDe@{mTq^*f`0yS`9;7M+R zGHHz<0j?1<`2>kWfd{5uFHpJ=s;fUcd3>un!;X22PD~G;ljcA4)hqc;hW{HjvT^^a)|PGeK|n+^gpcmIKNA-bm}~(-sjB z^W++FJyTuBd!crFd>%|3C13fXn*vlAI8z48_RJ3_1IV9UPFYicwG40>;YkOtJJ3G; z0mOx1nSRr=#YS&$FBrYIw((LkGPqdL++1g7XMyKFJ1=i&k|yV0Yi{832{;A+Vijya zL%iBD-ww+OdwB3674=ojSEtB^wvBdgfF3;;T^3_Am&41;YoWypG*&dv9(fMFXGG7o zXom|8oq$xX(at1ycS%{*qwKF2x35XBo>M|aLwnwA28>&?^E%0)w|l6l_aprCpJ}@U zz{|i9yN&!x{7=^|(GWc<16j(=W782hP5#s}+b`7raqzt(0+LKO;N$a>lamw3RylhC z?7<>I)ZM$n#$yYbB^NG@~ z>4}N)-8kfRdv3#Q_6inUn}Wx~IX+4>hLPs{!rOMq-GCRV(N5Zi*6|AnZ8ROVt?&JA z+d5gNvn~ByRn;_M;^KXJ7}EGs@!uJ3Fskv2&!^JDJKqV*52q%6N}*Ss5nXi;Rzdwl zRDFAR37jF0bewFi?jlM2PkIn5wFk^CrWyYe^p~lTE zuCbGUQ!tfc#hPg+v_4$}xUeHMHz{iC%4_pdYoITCqA&0f% z;~~4(hnNeC$-5%UEp`d=gCSB>3O!MTmv9A}yLiw{2aQWE=Bv14&mfE?dunH)Lgak| zpC!J7fe97iZ3cz&7D1Dx-G*%2NgO@QY3c(CR2K=2f(=;HRh~TbncCp>`i%vliUUd~ z>5d8p2_3^;5sveU@QRwCK1~xwmT*EVV(n34C9}9lIXX5+J?wr?Q~8eza*$# zBBvq}IHLZU?t;V?k*uU%0Cxc8ttLG1juaL zB_p*aM zG~7R<5h3UnLlnFQhNq|0nVqx;$_Z=;VG?9CwwygR!TEN~W)$AiLDaQp8-?3ruBdTu zDffvD5q1!AF?7aXQRNI$j7#NAfrZum?4Zc;xLgK{3$IC)k+ZM5!Y| z&j57=gxb%}yWlkhF93LYe@*^ET%6oB)lZe-d#fCuwk=&yEwGWX_^BfnX1w7YgETta zweQ+Hri$ts=0WtUZg$#2THyGPjTGFf8Uo(rzt%3=kOIfL%)Xk5h6iS*4U7}f|IP;} z$~?wEy>$XiQWqQ`w8P10fdicP?QS7`e!bHs5*8K~eLkOnfHBzLBJ;bC3k-zKO9YBg zKyQFCYrQ9m=-F8la1<}mLnwfl0(fUh$oB�BHT3vojtiwE+&2waqRn3LVd75UjEUk0U{^RKt-wETFY~WyEJ-f9&ygy6yDw?g&^q zxBvj7sYy_@p;^&=9(EZGNW+XA9AX^W?vh2HZlGX)Dimyyh0;gPD6GB6;(fx)f1y;e z*s*+qA@SM$OJ8np%r*4sUPa{oSQ7B8v^OWTg%$wGIpOn-{1WY?CRS4yv}((AKahxyJyk!y(Y6N zw_3(gEnhrz$Lor`Rxj;qx2QI+@>=@jS;M`94ZiQ~Grvdf+cQ5Pfv4twxg+uNdUVf3 z1fya3Qbm8Ol%)wqPK?iOonaE-GhhFH$JojEQ@7b?%srXYv!Z^Wh3Q;@YMh zYqr;X`Rs}DC9`mrhY_TE7RzFN{=L7FtrTagu0^_O(gGiO{k6D;#{7?C zBt@*NyyRi{%OkoE`m7Mb5Olro@(rd?$H@Z2uogT_Ufm5g`{2(Xd`Io3x0%M4b+`o& za{KlxtWIT=&lSAx)hhQ|Ul%V3qrn!!PtZy;7FH^nk%8)G$r)&Zh~{Rhv98hhcp7Au zuT+#R%|x+$i_m%&l?Q`92(w73W>E>dgEiO$P8ATxD&a6}p$)>s{4gTh-X?wT8+pF! zTxQ}J48Z{%3H{7f=ymU%055St{bOe;yS`If&G$xw31P{L}h8fy|o z&?KB;YKvh`-ex+!H|yzkxTGA7iB1ALf^Y;D)%Xitqdjk>jIvyb@_Os-_5! zyh<8*Q7D>Mptn5N@+~zhGhJ#-i>vjPIn-B?r7Bdm@3n9u1x7@)^{A?XDR(WJ`9?A& zqzk*aENa#Ddewrz1keOaLPd;khEm<4zdp{ip7DvsHP$;2?^{gX`l#;nB2+dO&0E&C zx7!FBzyK)4(83}Nq`+XLvxV0^dFh--?`GN|^`Zq&EN@u+gU^apa@@G}vAot4JqJBq zucRc#fA)J?jIbS!`0nOaJV2WWAQ?m2VT9a68QY%y_;2yR+FC?d6(u`ei}X~$9Rvhk z{W5F1B-Q;>{bbm7s9=Y`iAHL~uGj4;cn85Wz0?$_mxbqpb}J!GSrG8FL&p z9u>&U+Sa!(b_T&FVx*yZ87EG~(p=5?dGIy66rkq7@d^e5)Y0?P&kdTDRp|ZZdMrI! z@bhN1`R1&j0JjNbi21!F_)q8ll+jD;>ppaQ2q>+ZREBt{G%%Ln(nz;#9EqoptDyxM zMC~kBUa5gXp3VxICRG-JggNt;3Z=>%d{wV$;~<*h^fW6F7r-Zr-@%2#Gbtn~QK*>f ztxO&%n8yJj{ab#=mAw{5+Wu1CnGf0ULE4sgbNk=Z(Z4tLfP0-*z@9vd8zg@*SFgG8sj%!eq!PjA;? z=x zQXFcEhklDp{JhE~ws1?B9!9M|F6E@&UTp)z7}{ ze^H?A(3>xY|N|JLioOO)Jr1*@6B4~r;_*Kre zI`2p0IAVcB(Kt`p(AzpP<0P*@X6fQQ4PnJ5`y0V*7<$JaMkQRKM98E}F-oC)Q4MpL z4;C%zwr|TBqjj(-T#t*WiJ>b|aMXw!1xtDrTE5l82-@ z({Dpu!bnP>6#lGhYsXzMqN0=L@ujl7`7<<(cy1VKxgHUzptvBhH~Q3JL(K28G~#|g!_yB!22+GYPtn2Mt6VvgUzpL1+=+99|p$Z|0!MI7prtgqK&*ai#01z zM5bv574f!2IP@Y9uNs~sW(sr}@+n6;q$E~>BVlK0sVV9NIA%Ei7x)F~tG{N~to2_u zevm6zcIQBAv$XC{mERIjR-58ZRy5Yuz(x*{n3UF*00~<9^-jTbek)f)g*_ri5GeQ(RQl)Av zSyYDQg;Iu_H>FwI+90-X7bh-zrToTB4N(BO4T#*lNnLhv%JW}v(|@!A+Iq>m$zTLc z)Io^qT9vmupJcWgv-B`en@XuF;nCNL_Wi2k7pnp?1<6mj%c=L7cGpb8mHpjYZ{LUL zL^xAbRK=x8hG4`FQvvd8jfa@z^*HC3kHM#r%Tfkv9I?8yR!!zlr( zMV;;?Q+pG?;My=(2mGq_aYAd{oCf@gEjw=|4P(-YS>1lSN4CvbJo43gT6UVN`QH1g zfq+8^H&>a*aF4B7KTRLSnN}||E)pc@lZ*lmg*j|CJjtc38SJzy_do`BM3H8w z5Z*8f+EwU|Pr6sLrGKX-!Jx%Yp^Iuls>{RD!8I}BVXrssHGb|ve!V}P-fORuJ3GRL zNmD6bD_FYpgUVGqydMHMDYPe`qH0g6F=7GT%FX*7r1H;Rl?JCpqfA|zQ-)!s6T40K zP;01ji06K>+BViuNrGy67fkGGfiiDF#D#+HDo?%LHz8K+un^T=wE$5_h{$FjHeDKA z;`pA)Kq;jrW`|gVWoA8+C%1c^%zpM-`Xl=&Rpqjc9NiZQ5ou{*@e;B>^6|~M)@u3& zTU_)_b+M8-%xdc5HY5$AhsK?2O22<;7ClO$8y7EUc`@l4jnR-36TVp_(sQJum5$Lm zBy>w_7$vI9w+{|bCsL8F5JJK@ghBQ?bj6#lFxdOB)WV}FDM(9fkc(<%SV=ZBv4d7j zNvBN=qD$Q0y7ToR!-Y18QnLw9AOGyu0weFY#u5_^@NyL@0wx%INlNibfNcdcXQnGf z?S%Dr!QpnIpBTPRWJ!(PP6}Axf($|zT>MWtQql}PJ<~vxZ$UzsfN(nK7092?S+?GO z^v&irb>e?^?5vj!FSR=SkDbW=`nhrh?Ti4i;`YlzFHEOd@o7`V%dnINmv8I z!cYLatDcnD-!Zo5h>eUp$OK+UYg^k_!TxyqX9t~R&-RJAzi2=hzn-ZBZVd-qBMpou z8?##XUPh3o`no8;4#B`509@*ie8GZW!9omX+bB_%Fq(^xR&B_-Z|z#!HvVRu3ktX} zIR6uU2|7W|46mNtaBrusyYvL*JM9z9kHZiS+ieD|otjqL&Gyg)7F5|$$vFS)K6$d` zKMr&bA&TJal>N@2wfV;~cl9%SE{F{SA+SM#ADQ*%+Ld`gW)XG;D&`qXeNr)`dGqgG z#J=VGpVlqCH1W^3l82b*g~C;}>qEj3c~W^{O0=*_e`mRRC9+sIopr_Snpfj3_9pTw zbT{A4YK>wx8r!99c-X{r{r)$1CVmSUJ36{CPPKCxNi(yx!A&2c7;wM=`L|USUp2(Q zBvZQl(U2|6I(s*Bs@L)!1#4mD`Fi|#)=4BArnorkh>ch7{s@b3O5~s1^I1rfhvEq; z^X*lm2>UxkY-0)|=-V?LS!#@*C1ZNW5bQlLox%n2Gjf|}*+qiRo)ZjO`!#=g57?&L zs*0@ky9(0Bb0C5ar(=&bB82}vIOSQ}>~jW@s}AIi0=B4#JT)uJ5ZLhq`M#fUsLv3K z)BXhe2+)mV!6cGH6I;t;l;GrgPN>4{{P9n9v)L_(NT8P_H7-CB79^(oU}hN3v`Xwu z+tcf#eEkOfeU1#RoDjaN&W$93;D-i`KFJ(Ii6w~wW)8j%y zi!33B7CWqXGa+|}RTWR1Jp9d5lttGTL1F?MXzA znLM#3J6!ZtF-x-e1Ywf6x>_^Ds^Q`sk&}9YVoVN5D6Gc=>yE}~73hTV-!LS0PEhl` zg4BW)q;au$0;Eg%6FrhfO~C)jYs_)CE@0-~t~SBu#{ih4bTO)1+BBD&Q0;+j+eGJ6 zXL#eB#bRhy)QiQRjKU*czRcRnvB<=~!}8`wb_Q6A)rYJ6WntN$w`S+$ z<15mwo;7C$jAM|2vEUmrqk?K*3fqU@o*jQUXk5=>pzX@{e!-9w+>u2pFcFG#A}j8Y zX)k9FI`zs0%b?}E5SuQPVssKFj~Zxzz=>K=Zch*5QY=9LdW-8H908=7`ubk*v_*-& z8?CFQ-LWiQw!Q?>bU+jK14P*Wr_uo9sJNDo^1=t#3 zyR|Wr?-%`^)m~*GAbexf=a!d-M((k~Q|!*c`mE}Xumg$9IDCgkJ;2^6wB!1^w_T`=%{#Kjg}h8 zR-fZF`q=zQL&nSn-MoNZ@rwmY?8_yWy(ay^Qcru*WypS+7gSbpG4>SO(EdMZ$}CCw z`j5lv{6@Iha`@+E33knTGV`*N2Ry{<-QPIanw4NSU&`g$|Ms;d_evzWGZtT=+~yrP z-S%ub>27x9e=j&}nr93SzS=g~6Ro~nIu=G*Z+yc?6W{FZ_zCc|bh-qwk8p;M+1fY1 za5Kka4Am=zCwW#7Qm56@6LNkN(Lt@Zn^nNanrUEw_K#Y_SjAFdzT{p9T#$AXZp8Hm z@#_Kd9baa&S;8(!Fd+8GG)c!wW^&${vu){TPmJ+gY@1|UP|*&~(Le}6e2AG5-M>^v z`OWxdlEi#|T7aUZ+ILi&3O+3Tlq?YfU0^Oe?00BMjsp$ennm(jLLe=ieeTJW`i#-y z%BrFS6IE$?6}8!Q=|mE>NMsUHey!10ObaeeL)fr}D6%T6Pbb<^8hx5XOnnU_u4$!H zw(hn2O>L0ot-D2iB`8#>Rx^~Pq0T{8dod!IZnhcQ{T5}bbUbn-E6ALsD9n09p|L#! zWTGx<=A&dyc-z_=KT7Cjw|^M*%|N5r@eAe`4B)#_j?okW#h&NE3?X_YQb|($PUYb zKWl!%XC!kt$QK{GJK}+!&0JE)rg_x{Sc`YA9WL*^oAALRz2lMP(7nb?pW?GAM+@AJ zq|LBI*F9w&iCDuAdhq$Q5F|&xVMu=B!(T((B#n!>a;v6V4RS;?FCtW(Y`4-Y0EJwe zP$_HoojdFlKyaAY*hE^i$>D|YdEBQOYtZ9N%ZFbb$22tFH%DgL>Oa4L7)h9JfcgNb z-v#eKVIvqKd%R?+WO@e>Ed)&elxT1qw$a)hU29JeudaOXumK(mh&Lk>7PQPWxzmJ0 zwoITBs*4l+7&q#UyH4zGG4U$>B#=7OxIKjKf~{OT&{`EgyMIkI^Lt3{^H{wi3tej< zH|+A!xe-b-P*b{_`^yjY4s!nf#Lsg?`dQ=?*qQFrB~bkK-m%8M>->`8p;*JZM6KcX z7rFT#WjNRPBbgIFiwA)S&(8{{BXj53>+m=|GwuwEN!>aZb-VVm#h`f7GmE_r>yB#q z??jlHE_$W<$Nj>mub{cp&UN(wL;Q|ZX*)v8{$Iz|5oTf~NSp#2Plhv>n@x21BWv5y zpi@D83D_QW&Am&H*Py!ebR$Q@fUb|`jcLwYHo#F5<(cW(_$}Nhh!N5%yO<3jfWw18 z0PRbgz*-4%^D){slp`1UmmDZzn1m!k8$*L3{bJVOd28ZJlY~V=43tuYTr2H{NXh@7 z3ov)ks%usdr@qpoih~}oKs1un=OS}ZBIH0V$Es8yKeDy2UBKv~#C6d|>?vp#wvlvd zvmPIGsxNn2PST&l7K?b1hovPER8vEno-t&kg;C`kmSA<9OPExIujxEoU$H6d24Cdc zI1`_LT&~odHGs%2QyuzN&e`4(@g~FgQZsBtH@0Z80Iz|{G6aI%{A(x>RFNm8xh@gg zYMHMJaw9@S1$Wiq;#%Ye!E)r)$TtNx;X1~%EY*hSRm*=^nX(W#M1?cLwhTLMaT7*+ zK|4exU0#OJi+Zj6O&noLGI4M?A_n^DSNX}o!Rzw?lpDH8UI@0L?n)fX-x=af)&FH| zwyA#J%{_Yr`&0WyR}&rZnE`sj*wHau(ITUE8w=o-&MSCnVITHY%T0{$YKc{c-4#|2 zH)2qH^39$W!=*KZ&m+iw0}j%ri@_$Vp*?Hd5%i$~Dx`d#IYQk+qHNx>E@uh+5#jwz zm-jpX^JD^>Uqy8_Fr`XT1);shHE99pp{}ELqHhD_ z1=G&>uSY(hUd+i|XRaax$)_L^<6ts-*0woz2A420X)b+r&6&+?lH~Bo1i{}AZ9|ym zS{}uY5L8o7guC2X-e*4FCx4qhel|MW1B6^#RSras4w;Q8TZjzZ$+m5vjJ=e*&!(&LPZ7X2Yzy83-)Do?1ZqqA=l zGD8A39r7v9nKN)iWK}z${-*ox4$H`B2c)ck=1NT~K-ZLzU4r;1_?G+`D^&F63hilB zL&C6qYIJd^*pK5lnU=w&Qbgv#7;zjIb``y|Stizrh5JWN{QDrc^D?ClV752|h|!PhNG zZD|P^gdl|YLi+nX&)WJL2Ac|7z0-srMg@CH)xh5-#y|MWhuErb3L_G7rKqGM^b?2_ ziMG4;0uGTfv5nu}D~Nig#NzD%K!@^^L1h2dQ2#@gLXL7Jqa1Q9P08_Z7AV}k&F~l>lh~3c!$K)>;cES!Cu6w#%LCP@$vdK@g$K zuS-m5IEy>YWDyaDc|?Bx?&;0(920URBsyEX>+x+CaR;{myEZyzD)u0WHZ>-SNGV*N zMj8v%^$`Y{GaMJG(gBim8>R#puDg zecyQcqjMWC@X-+X-Vwd#EN}Y#;|22+o<&+N8l*s%VeKyfEIyt0e)N9282tVF^z!eK z(&=XBBxuVTs{1W$RMCh_KydM^JCHiKej$xi0xL?C$Ll5|Fc5Rhlm++@o}k-~h~p&` z%GeR;qfeYtJFw%o>P)xhug9*Bu0DU?f3P{fu~!H`eHfo{nK^e>I^t^i=|M1mv#qoZ zR=MlDWN0$>@uU;k?G8HaPbkeRRYVS-Sk2G(6^euClc(CPD^OeaKC2j+o0!Nf;0~3m zNN!i#vQ~=^5TnRxo8-)_Ac+z=&=m1wF=G7%`f_mv3O62XBPXdea_Iro{d#PPxR`^E zn=(a{EEE;ws4@=UVLWrld~cqT-T?Cyd=`%jH12dH=Wl%i5e-OL!q~zzj)g=0hC)$C zh@lTcaTMRQN1i<+LQr)2OD(5^s7o>+8l7S+>O5q96XK(pFZ1C|^;@AEdawc&28yAp zuIm$GTi8&VBQ?t(bcQe6Xeae@!%+}Grv!>HH?Ckbi4vzo7E)=4RgOX zDP}qC>3ex@%YVNqlYw6fYr;5Gl$M<}r(&!z0PRkZ)V$k(16LPm^gi|!_XxY#@sRYP`1*In2l&=SNOMl3l$&4$L zIelE67DMG>UoDW!;mqdTcFXwq3>pFFCj(3ZYVp+Gw*&l4kw+=M>N3+G! zabNb_J zy#t6pvUj%^Z=0>+nW<=u95ez+L_>igAMZ}|{sFV3_fBG3-nZ8?4wSAtJ4V?PEvmoq z*f)RjFu8iTHO>mJjRYpRX(YJ6ufh21Vsj{YefjdM+KJX(kA!fOFOA;ryvct1UNHiO zqhr&qw8twsPaUTqPCbXJ;#h^Y^B;=-Arut)+ZaY|!R)OIUeD?FUvnSUe7Q}?{ zF#Z5LB;-A?Zm90sq!lg2bw~%V!NEuk&Z)Mb6};v zp!EsU6FFf+BWM!ciR*Np)UTmPioI}k>s1$P$4qROF(K2+YB|Om>}0%*zva$8%iB*X zu758*i=8@t2#r@UUPCWX>i;IH7M2u_o0Iq~GG>dO{CAE^Xn!mw;yYQ3FGeo@wk~1c zxFJ_R59#rI^+u%c)zqWW*pbh}Nxen4#~F6fY%sNGqaD^RM4R9wkB0?UoR~1sM}Qig zbUD8JAh2DQ@mWe}+LFI)5LBS9EYdap_SjL&%3dfF&+S|jr4q?H0H@uVnJkdNX?~bDy-yb?Hd71EJ4waEfD- z#rzSch<97c6+J`6RsLb*Y+ha4isiqK@Ll#lL|!qlA%IEU1Fc1G_P@VoGpr`;>Bx`* z7d5p{dklVCpqu11HY?lrA?(6ElFD~cl0+8kJH^vU=L?OV-!t1pOWC1UOY}@(4GDVp zhm(&48XEM)S`m}|M-9Kz@|5+cuN!fGs%U?e_7e1O`E6vK#%i~X1->oX4Tj8%sJvF; zm$QXz}2r7~m1QJ_x?(m@;icd^_bjH_gE9%PNy9O%BEh@_32Fvd*8KI+QC~nSXwH z>kQ_Q}c=BomkyfXE05 z8RYJP9=gEZce+2_yX(y+Rf%n-6mP&l0vZl)L9<#6t4!J9$|X@8#>kj6SEV9j1kA#6 z;v7;s&k8%Q|3n!-NA`H?L=maPcD7M9VH-Vxd3mgG|M&6om(~f6%4anX-DIkdr7V1% zVadLMgP!v(_fjdvc5pKM?bvgV8VkCMFohE>8&44#lGwX-5PP?!3VmEfcmsXZq_jh8 zmm)r^WiZGk*PF+q3kr{wS>LLdT-pA+dv75|{!vMkKXhtyDh^BZZ}$Zh5pQqsEd)Qw zjLNM#-kEWc}7GBLheZodq#O%0bi;&p~ z)G;d`-4>{lJujdAM-#>8ZxCd@JdM=2C>M(nqWK8|pX5py23X>TGy07Mez7W4IYj4; zmqWEzz)ijWv1HaRwOn1tH5_WeB1T9JHwwOA9mfuow42TgI_g8~6BHI6TB)!Xk;;(^ zukR($*7^)C=ikn8>jbAB$)aW* zPq`vfv4!S%B4s#rx=-7B6|;6#Oy8%~e0pOFyL|(2C~+!w3~%MsH?AhVD*4|)9MBG= zNKVyH#1&CV#4%>dV#^JH10BaoB!Tksx0oLg_Ps#d`Xy)czvyW@zeg?KmwU60=Nm0+ zTbf+sTJ`hmMZK%@Eg^t_1UN-ghO6>?TAY1nUdc4@Mp;nmSy<|0;pL+To|7x49-=G@ z&*!e&Uen?gH-cg_mDbiBotqc-*d#UH&(*VQ{5H0_%`KkjKV*0AqyjT8?_2X-KekR; zR4yAp)lgO_-Yp^7qf2P9M0S-0Xlksh@@Mm`?Qf=WsUYC6farjiW`b!oGq8-GOfl92<*&n6co^8x7xx=95H!|IUH`h?ZiJL^Od6{f!Vt zAsC_1I@!=;Owu;4(9E)3qTEb*!OF$F7OO#S*_z_~2{wP@&HB+)6mbCKr7=C6)^C1H z@o8al;@>v0E{MYiPTEc~R?+BpL$|GjgV}4=NHR~w1qTC7q~+$8(t*X| z%V(6t5DLR|$H$72m)J{5@SE@`!`f5&CszIyoggY9d7r^hfvMT-TZ3k~pUrZfk4A_X zN|#5tGw?(-igcJpZZ-()i|~qv=(Gnhp)rNna@l-)U^IN~6a%$;zz+zj|EN5&;t%*D zw(Cq?15f-T3U*XKIWIjtT0E2r&ey4P?bmbGFGo(B3pcM8Zk~ZP>+lwAMmm=~#bD`5 zl`gYR@yH^vRf;;#W1WHeyGf4j1Pb6it%F1cc$3t!8JTU2dr9XeXS?+9^TxgOj=E5J2dHd1>e5k1$8cB&|B6boI3*kM3j+T_iIg&)73@ov<`Oc$6@_UzQpF0H& zGJm!I!bKFp4|0YUQbx;f5Qyxy2&`%(apwH0K7>-oN+ze2aAoV91xZ_%O!pg(+Vw}9)qSo;$T@+K6`@?@EY`^sUtWqX~U@I5mgN7+M- zD64>ZsEV+7sJUOp*q%DBYRj?u{7-d$bCr?&Cnsj3bjo049xAPb_X>*S?Cf`Cjrzi< zsWHy6F_8zm@$m6DXm2GUB7;JiVW0(K%l);nrO{9uS0Eie;0c>ohL3UZ?KKO^Yoc0- z;9|{)^cZ@>&%*9G&>Gs8+pY`6thEAOjuJrGXw z{pj|6kb!vf;=$>9oA>p++Utt(@k2fWae$L8Sz)h6)GhuO3f@F^8Qw?KW~dPoltGE3@GY|b+}}eDyksV=n}Lw#=`^;I}PO~tdu8a z^Xt;y{4mj7veXDf*KWSBIZvuBGRRVIdP|XYWYspxW(*h6Q_9>}C+C#1#~Do)CM6S# zhMd8X;iBR!qaP4uQQ?^GwVI@8o==GUkHMgg$RbGAe5<#Pf?NYHQluo9Z z-xm}}3d_mphkX0o?GIvob2cdu^Lsc>0p3p<5wz?)0tR}%bd^$u#0ytso#IfM{Jywd zg%h}jGA;U%!^*uPsZSwjp3&dOM5qMOQc;Fbu)d3D@f$e&C2}Z^fF+KEjc{&*3lUA| zfo7`gMigM~Euy-jrOAWA6Vpa zHlr=y(GY^Z6c8ci%m&EkM-E^I(_B}C<5sr~yg)bzw0Q>;=Sg5IVJ}w~X;5JAjG|!9 zg?&th*YId_E+H(!ibvW!yOR>YW+Ob+^C#6iR3Mrrw|PRA~1B>IbQRdV}fzjSp=BA87Kd z^i;?;lMU4*78l48~|Qu0aC=Mj+fh9vq+_!DKFb*3mPk~=4j%g|h& zW`M0$LFN`0G_N@_!aHrWSjlig4wWLdn_yPsKNU2oiVMRhv!ZRmsPqRl7*-r%V zHtolHe*5j))p(<~=es1^Xcv84H=bEX``P&P2hK?Cbt?SDD=3c{@HM;! zp%)2FL|9UT5HE5X;1K|6y({*6pm@1y?sNdcWdKdQ;>dnaI|N`(*q|&!;FJba_q*GiNVe|=h5dz zF+W$n6EsURszfVi$BQyc)AwmW8Sad(rPUIyP?G){+h=&N%`*3%nwL%`_gXixxpI!a zMaJnsCs5I{|IM!`a+mzB{#2>rq=U-0bT8}ZorzT>3@ojf8qK65vY+*T@{Jt66R4Tk zqMm8%P7gNRBf5$fnh%wOO3YVT_SE@o*czwZxXV7ssU?`E3n(^jG&8uhKf8c+ZZOrg?bgdnEAg5+hhAf&-gvnBKv; zf4}!vmn7Tj(f5x8_TYajfKZtJv>Pem>j#5aF!VY5qu4!J(U$;f=XOg6{&U#JBj207%q%f)*TO=xA44^S) zyEYz&QIf0u`Bd8!UdCOW+&Ltg*tXJvQFX$S)k2I=Cn_wIB~aHjZq^`tI2ikV!x6FA zS%8b0*(8NZz7oHxQv}CNTpE&^a1Mzx!VyuafZ@g>l9viA{4Hh-1x7I)R{$Y~@~D9p zmBweHL!2JhFKEHLBcr~FH&q1~zgvrvsi=MriO%=1K4}#KEuDb=>3O;{?Vcqe%>_tiNpd- z6LaH z0jwTIV-DO)fWoHfRu5+Xdolw{&LxkR*0|j{M$K@N??S7Ia;0WbPKo$3sl?D#1}Nmj z9Rx_SXM5HpBNJ9k5mo$f0kP{WYb7rHG3EE#$X|4LX0jB{fEt+k1y;48803U$ibQ)? zRo}<(HFN+D1OKIT@hmmM5P(O3MpNY>$FuKj#I`K`@zdd(z3c2k>@|T{`~9DPLchw6 zExaJO@^^G^3_il!olSKxeL*m?7TeiI`V>McN|#vF{B`sO%{VcGW>YHfSUIg6zonpz zAF5Q--9ZKN#DuN2XpBas6#KeY4~|;!0p(UhY}qY&!}MP_s-K!zW7SzBU&w}tG9`-a!ZQx$*rJYMTX~)6n-H3G9_CNMvCGW4iUbLI`}pYi-DibFq6A zPpz}f46F0M`D*IdpPdRbN9=S>Gnoi}Vk<4lMshL%^`TZxs~*Mzeypjp+oS7;AcY_o z!MLKaeWyBF5)E2F5YS>c&9KslE4Ksh?a9#Iw6KcjifIKmS@n#$l-B+56|%NMdZYF< zI-4zC3rY>uSaGBtj~OG*^y;cuDoj2^0=xR&$=`iQ+62*N&lC_%k1!mKSX=Kej+=Yw zqOYU!enIVC1P%HfgeW|i{_+-A^veVvTE2A7wBMDSy8%m3E`7|6z8H_Qh?0uXX2tcGvh zk&7ZdlJO4)S2%1B46KijNd&+yw@+#Z3_@=7Ln>DZnE1U#FSj|zm^Z~FG5b6eJWGyG z3W*gk^;TA zyf+-@D(xfR@_EaMb<2$wXGMAm6jWky{bKTo@u_2`#6-Fx6KcaC{1*%B}EY4etV;;q~ zmXB&|Opm9iyDOF@aFsYIr8H-|#EbH=faQt77Lo#! zT@p_hD7q_n+Gv|(lo~_(9fou;v^SJqk>6?! zr?jPjdva!B#AZaIv@9(?YfMGmW>{METenNDpIO9?n9`b$2;ZMaE`8DDmFLami^q8__!dWhMi zoLm5B{uWBNk!^_$YvEt9L7gR3b&199)Ym>7I(8n?3eIhvmtR2-vmF(iC;^#74i)y*gb8&jz}>K2s^&Is3LTX?slL24Z@KI!{WC{{hLfAW zG+|w;o0EcHTQfY1;P$>h`}b8#&!^{QLuTe8!RsUb#or4f#4LU@XZxY)3*;-~uP(Nw ztP4LetHY;wk4#jWlREdA^i1(HIp(+mi`mcPkFCEQlgY<6&bL($YRwEM%k1lJvW{jA zp`Ret+U-BI$=0PeZ=>na9|n{!Y>YlDKL!$KFT+iH?fn=tnyY3g%&Bl&huOD-U5p&l z@nf%C{G(ef^JndHk1l<~t3+HWR58fo3kPam%akO#4PJc;?cHj#-%iMxFFCw-YwxnP zXp#wEnJR96FLL}v5QrFuHiDO=I*Zk=Kuu2>cJ9&p_n_wcbRpI?$}AE0s}Fh5VTW$* ze>l-kWNVZlrv7Yr^5(g0)9$ILn5~KboGUTJT>i2tZS z3B-BW(2OEh zixC$@DT23!Kk{KUK6j7k9d@b{`BsmF{0^FK&$k_cMu)PFL~n;s^`ka8RYIWspkjp<>Sa{FeCOlDHWEhD;*x>gvjhlEmrx^JY)n5W?4II=-h6hWoo_ zzrm>LQ^uq2&y!~tcj?*g59_>H&rdL))4FJbNrTs_R*E<0dd)LAH1%HUIL3+Gef&;F z3_Iv%0gmCmx)( zqB=x*=WH+V(5YMm1&q^iF*@(0*j9@*?~ud=5PqS;0)zyj*jNz@c|6lqKd#kPqGq!H z_kl`8EfiNlUT!K*{1AGtfJ)%z$Y3V zpoj6|V3g(xAG)3%s1 zC&w>GF7*iu?~+r@AY(`4c0&Zvd#=RqC|ar63?=W#r#qMD3)fbdM?jPl^%8OH3kc$x z2|wE0@O4T!GE$_<49BCLFv}CciTMjg-1!Gd$Bv^flagoR8?5j;V;L#?)1z@Hz(o)# zB{7;K+x(esbqVRW)-G7j(oYnki4e4}Q+{61&f27*wbJa2jPqe;*(&eC3Jg8}_3{p| ziy&OHt!)%U`%A`=K7pnfQi-~{@du_&o{QG3tX3l5Y8*3!i7=D0LyJ!}>emTK7HYRbob^%fG4rr8H(r`LyIj8#I{yXHy zyiPtIc$kh`W&Cd}+aSE(j2FFk#%}jYJGW1y!j$E&(tP|aqI6~vmaO`oh``%5Wb!4w z`fhvECpZF~pXVjj>)*|1-@9kMUytw4g>z^XkZVe{=#PXa?w@&3j$NYLjxrVs?`D&- zMd8XD7ftk^y{k1%^Vjl`!#BtE|IH{l-Jia45j}Zkys&O0#9Aai(WJ~;)~Z6Ac*B;0uy=h9 zeU3HaNI^8X1KhzKqi94iX>uiN+wwRzlkkx`*_<-PgS!1UMY1JtDJF6aAr>dyBwpzD zkTg8Fml66?tDaA(j8#If5Th=QZP`P1gz66D)PHaGIKNLR0faXmR)(tjS2P*Ia3D@S zw#z+eqt*Qz>n)n4>ByvR63!Bnmyw7$(BO|8#Su78NBwrcYtCRW`iX-i%~Dzo{Elz= z;1&$j@ol^mda7%0q}?Ka6rz3)>n8FXvZX`h~l zhP4O^A6h!CJK5Ylw0Ve|*Zd1@%GgykOA`;G8k>lni)X1EaDnpYe@qnkAVAE~1;_r6 zq{{6E_W9(@$R(faU)8Ta?VZV%;cc(l#GnF$W0fTpj`8@R2ad(#4SYTYcGwIyI}Vm7 z!P!+g=s~^d`1$Vb+T-d+@8?1O^WWb$yLOPJFQ(gYvfq`c5~z-xZ?sxXoYH!8gq{G!83iq0OHd*;BM%VRD( zLm9V0X70>Cz`|fB za^oCvH>oIaqI#)HFttGzM81K5y|HZgbcf}^Wtvn7 z$wdL(w?~N_iKRJ`OG+WNKc>q=^wFpRHmpgoFK8Dc^$K~QWyTn?WWxVug0C_&omTWc zBeu|K`3YBU37d99v!s!lcNH#$Z_9{bq0rE3eyz`ntDRe>Y%vgVCV=)c;7Az#v)YUu z6-}-9d2;k*&vKx^!P~M2>&NFy`~pth7#HZB0J3aF#?P|9Pd<3DY1J#j zRkmL`G24i&w^>|2mUlS`BW6HXdM`DiAc^>sqjhgn_X9sY2IVZ(yrQwTV7x9)fEAyBTYiY?f?jW?^~>3r}mNBIB;iA4;{h>}D01^HK$RrIxn=feEY`@>^a8i)VG zUGxzOtEkg88Ww|S_vRI8dG~6ofGjsOv{$qFraT!T12tomX<*8-@$lLch$G>leKaeV z#J2DWUV}v4xeS=Hw zzaZ{_D9I_;M14@7jz;Br5W+BY8_nqT873bqBIYe()GRa&QL17}iOAd$>P-mg4yJKD zNd@y#Pq$u#@~-7Qa~?8N*4Q`#eJ!KQkDZMEZU}DYDFkx_L1!sckSkYO5m#4vC#3Ri zyXxUAb0?(LcvY%p1_Q5DB!9ZVn3Ub*bRP>3Nk23YCYc)}E{;25#spGJ$Be;DxH7X* z?u5-3N@K;=GOw71*xxBJ_7KWkULoYP6950vbQbQEw_m&-HF9*1?i$T#qnojHcXy5M zX6ufvV+;m^(cRtM&FF5<_x+u7{s1nQ&3c|^tjpC39*q2c`a%%HRj%q9W_jv zXB&q>H9o0mx!CeQOt&Xk8rWjSwOIy*5>A?b=r>`m_Nx>SlASBq*xVipDd%uCB$Xz0 zCjOTf=|h8$!>Zv`#%#P_6t?@S>q@mOoVF2y0t6-qfJ`%xX9A8$KsZe5=aF^f+U+4A zVj5QeIMmh#$~@E<7^-Xjw2o6D)S)0!11uez<96*-y`A}_glb@Mv6Uf24$ zKOW>d`J|lY{@l84iqA_On<0!O_NpPEhBBt|Vh=yCE`KAN%=~6WBuay-Ge>mqT}G5; zWB0)yt-kLGRU}&iZ=84;=+2VK9s700H`OwhPI_#1P? z?H|j|4!1VaB$xM|t*$GS@s@U_L}lhH+X*0E5p8W zAKQ{oh5enae0(n38>#Z_Q;#7hs9X8c>S}n4TH5rnSClV&3OVr->Q6dGeG3m!29GPb zXC!oVe+K^AKlC5rRF%vbk%PLD|JcE`u)`P;8sHsj$9uJ{yEcC|3)8a*J*WLonxdW-S5OML7`xX zqKt2RnXtO-1=1$SEooZM{p@zK99Ik}rgCQFS0!)!^Xm5|p9dy=}l0oYUumHR}YTOqfY606dKxWhF zdSBtcMQ~onR>^ty;N-xJZ0i3t6)LFMRmw zm)m9dt!lx7=jJGF<&?W0p9agJ(D~1qLe=zR-4$pi7jm*7WaVyG6KQQ?+%#5YV3QSua z$;~K#Rh(v*kR}tAJ5KAOv0*^WSX(&XDr&-4bC#ISKSBFIA=S>%Tyj=_;`Au>>s;A` zIBxbUtQN@h_&)49uUPRM?;iS_6qJrPz+>DnEfqH86ov#|e?>+?kLz6Qj8{hwDht{nWIusWXCgs=b0VlcIBmQ^+D*wVOu zZsq@ObH0E^?c35ik+Pw2;9oYcwnG0dfDTLB-W{ldt%a|eK=CUAx@oXy8~bORJ!mPUD6JksQ-Yt8*vwjotVrh>t~0=BynOdafP#K;?^`a(g*?_ zX`eRTHBt<st_N10A0Y-@%^6FIN+coOQLieS_jmePE;e5HS~27Hwk^Teha{wjNKM0-`Hyk(>pQ)OKKEp-58zTFy+OV z3`okTr7pT;i;GEBYb#=RLQ0+jexmJzG8|H|A{8HN=!T{W*krL1$&bK3UgFL-L6hQ# zIbDai&FD#jY*mgT(l*}VlL(dHuN}DqkMPYoCJ7k{sbkeFUTZIDrhmRAs??|6ijUMa zn)%unV{4^e0(&sPmAtaC&mz~qe}L3qKC?t(Y`TIXV8oZ}0Zw%8W_|&Gr&-~x?lsw^ zs{M@J?TSQ2bWL&;P!HS-h{z^4!7SIOi{uu78X({SsH1L&ym?;bZtCK|8j@Ky=W z43oFl4LVG2F33|Ud=o)D`NNuR@*B<~AeZ1&osBmloww9o|kUo|lTMbKO_} zQ0m(;Daw)lAoy9j;)SKjMbw)0-K_=8r}cbzVkZ~c8ZoLCBr$dF_BiJMaQ`y!e(Art zkn7u3Nb0x!{(SHrz46-djyA(2A`4fZX@2ZZ#lrdQkjaX&M2Pz6{(iO~Pm6W7=G_S} z!lVZs;6C_b%%G&<=ii8e?0zTOLX;e*=pI@*LO$2_XR+|BUnS8q^+91PV(w;be^ry;f7AE8 zu9oN&3$K_2(7(D?W!jocdJl{}i{kww8VhB$nJzdBI1^4M?3&s(U?^O?a6EP73VfKr zLF2;*1o%0!#?r?u8oLcE>wh2BT@7DVVxL|$_nQgrC|SFdrbY6UeO8qdpOj^#;31;G zohCTy;y@)4?!0OE&JYqSa`YiLQhHE4KbrzW0pA_LTWq@v6-?~e-dRRe$*H&`>Z^%) z_bXyt0y^34r*1+i)F=)+eSvEnXq1)A_IY+-IemL}+y&7i^6)q4g{gm$Uh4N3)EH-6 zDzO!~T~YoBWd;glUoU0q`3an>WycBvz-9q-;gidC`)G*?VY{rN`x4*@%63Cq*mOwG z***Cz1O#ayW7WnOW|!g(5-r)^tSC|vN?lfO(sv)w=l)?dG{Y*(>l2l@Za46CiraN} zp~4Jh5D6T32nD)A4Po~twKscIHj8wSFpE;XvVWKC5Q(g)7x4c3vsnE%v7Md%+n?tb3LZOMeJ6*s%<-pIz6%HFkvHBi zb{?MX^V-=iyPk@fCBU#Nk;;{i7#Q#a@pj;D<|AYwbUy(s9SvT;z$&li^&Z`a1HpDu z{WsplO7+>-@LZAG zb2UtXt~|Pfe+hqo*tpJpZ+M6JzuZ=Nc)gP_KrU}L-eT}}U`Y22*w3ajQ*Q>s9mihn z3y4+g17`aKq`blIejt$9DBXS4xNj^(^vT|GSr&I8aj;TCB!`SPB@P`Vo1fAj62%jH z^gm%o%ag$K|rT*F|wknTAVm< zdM!JkHfLE$V%<0WeI+d~r6&(qV7+OUn#d5a#kl$C>K1?~T0lnOEXT)%MP3s$MK01J zwMuH7g!qGmY#5t90+~M$qgyDhU;pqqrRT9SZxNC`(A?wyM1D&~rhelME+15k!L z@tA$hmZ&rtZ`{kBpV5bBsuaZ~mlEH)!lun6n{+)afPtAO^Ax4wl|9OYZ0(*H@NuR2 z7yoE|N@vnh)0ZF&?J^X94jB;%A|&K%p!_RzoTx}EZ%$Bqnce9%BTm=e??A@;rL^V< z?CKQ~z1*mdxArejA!G(hoxqt>{ZZPc5++DJP5Q^tM(fzgLxhh&7$@8iW9jhph<-lr z5$5V9XSRN-{q1!#p>MZ7tsjY*RzHBD`~VE!{$u(BqdTG38!L%iu`e=`Rp-)!%$7*SR4#akYjTfr)6Z=KrD}QPZclUO?_I{s2gASIB-6 zf+#W$gkCRSw{NvR1DVhT#F1|=bI)oV69&X0W`9~IVRoK8ChTs`%BJs-3UrGmM?E4{iB(MyU(=N#YjM^-j==&QSayp zH}DyqUqefO+cF?{^+fU=i(xsxa5s1p6!v*dghTK9|5<=f{~|ZCa9JY`BGGjTrmdqG z3sOluR5Gxjl$a#QzuKSHz8~q~dX7&3=?kK^PE&f))pm&@PXEVO(&}2cVSJ^3>btSF zLUt-lj4EnrKkPL4J(j`)p*3uO+Z^+fRa6?BRq0ldfXb|^ob$i5r|nk%uGDF7SuXeU z(X;VxIz<|)AjgvDV)+N}#d~9hRrV;ocYKgj-jt=X}$QW{Lc&#XIC~em}O^a?%t4Yh5K1HNf%b1G~6zYX@f8oxJA5wE4iOufjOQJfhZ5A zH-rioOecEtpXQ!>D51#HPuM*!Vz$6FKTpl3W^HDs_9}JYb33KgD&Fo|#*}40-o4;M z;F>fawDEh~G@Zue&=RU`##Kb##zOh)`;1p3(! zFGz97!TG)I;&}#JSUTy<(wh=}WHqW0ED4FCP63tp1GI8-vbt=xr%P}U?GjGx8=l@% zP2MJKH>?MbfW>$2E^5^8U>$Ews(Hj;!vp2AAsW31Xwl-xfyq&WNGK%BEMjF)DKs}N zRu89_K$4s;Jr0n8H6s8ywgtov0Mu>@qXv)r8PU9UMg4yO z?JY+hJZH~4?WV8q4TuiU6^M-oft%0mtr^$oD{)+7Bs)SmMPeSRI*L!esUDEFw-dK) z7yLqkIEBpdytVxA2tQSSaS~cR>;VSDkHJttKFyU6B2&~PfVr3ScQ1T*>zT*IZp*Ht zGdiHjiGc=X7dG1I+4SLKP7{mJl^r*Q*$Iuc!G>|B&{}3+A9#>iP%=`ZGC{k5{U2QB`bk$qaVIi3D| z8<<>syISW1A0Zl8Ut4+Xx)OhiNc#$fGEiPFPytg%OCg>lgo-E>gGKtT5%o=df>> z46mG}(Suwul}Z-~>RQBmSih8#Y4X*J zsBFt$17^i#h0eBR!3o8^A^N$l_Z=a+eJhpQv0_iql97T6Nm z{QjZ$>)vtq8~%X(6?jw_*NAs)01)S_m!sS_VcU(h65YzH=l3gvKYyDL``J&>H1+hi zX8UQ1^Ezoe-aH1egYw8hV^U7iv3eb&lJ!o`m@Yjs=r@^Rq=_ zjiH5&>c3Oc^Gb?Iv}xyWK7;Gccw*@b=;JGunqt{?%97);eRG4Llyn3vE^YsjQ;`IJ zfS}hIzu6;}EbyA6QI&Kb?QB7XoKcF(D5jX4d6UYrh^D{beX6}PLlzK=&?<}_;JENW z!h7wP^5+n}mmuV!y??J$lUlxKx{hZ0a1ql@HbH)Xc<`S6l0qnDanEz$#@pRJp6xAa zS`WXFfrYSU63SP{CQT1?UH4MV06xo{EROKS)H2ZE#*YiTY1Z?46^a}Z-9tiWKt4@Z zsFCN(O+qwh^!gL~AQF?F@|RTNP>7k0hUPiD?95QoIs3?vwzsBT&LM6jqK7^|S{iYU z(-$1l+bR9cJGZ(mj>Pp+?i2Jzf~iKm=ynmBK2(P;t>te+@9@Q+aWRx&#kNKj|5aV? zA6lQCcfLo~VwT~MkXVzkQNx?T%)x3Xpv&Q^#ghrtC3CEKy)=1*4CnNO+`Dmj#WihA zA6i4xe7p=&ZJ_86gC^-_F>X!1A?Ts+8u($xwC@|Z9Dm(p#uL&lGVS~O=x9@(JJ)fo?InU>2 zx_9D>n?|z_`nme^+!8%cX?mUH>$Ry7paDSGTvnlDYBez4&y2uygRq+CWuMyGV9x9uT<+)XbcF*G4PUo$ zN3xEwt+~X>H;*C2XZkIQSGUAOiQUe@Gil7#e&*40`|R9oKE69NUvJ}UY^PSWw{KF? zE{+xG)Eo=bj}h+d?RNU7z|wb)vxcm#agU4CtZ!Nf`{ur%qP+!ZjOQ4+I({pk*}qC*Y`q#D z$rf~pw0H0Qw~WMCJ|azh36pDGDch!1x~#iZsljqB{5tVYIhVLw7*~bScQKRumi)d4 ze47P*-;`4b@qfyQ`FUIbQ~R>pmJ8g-AC5boY&c`@*Zp%B)_q_M=-S)gaHv@fO|G#4 zdHnv((si%6kJGD4SkGH8!KT*Q0^ZuBq4ImU*bctYBJ%SCbgDYHQ|6tZj6<3`!dh!kIs7{&wNgYVCssc}EJJ#ZxUx?&w-5g1b0g2t;!crVZgn~T zu;G3dMOxSxNHH%|uFb^_cI(5M4aeEvGM3zK7gWY?l<1;?cmbRq`oTeUhx%EpL1O?MbD$N+t?<%lny>CVI0V^q2` zJ2si40{3mUQ>2Z-e=5;phT9^ixiDxm=X$|tRBUbt3}aD%0?6;-5s(>O+_O@ z-c>>}ol}h+LODhLV^!*YHu#~DBkqPMwcDq4dV;!`*m_SjRJDMv(erI#Y zB5%l8P_o&__L<2@sjzunEIjYSq|0<=2np-o%6gQKFlXy){n~PcQ-*-3z~x{ZFf|n# z5sq_D$ncTJ>75z8+MSQo#>w8&F^RhRz4Hv|xWApxGBBZtB~lr&;(upI(bUs310I(sSDBc!h|mpDlP`Q&CeWfHp*pd1xK`?T!m-%!i)q++rgy@;zN`}79^m?5&=kU7Odth!t0@SkGNz< z+(b*4+B)QH-UF0*GQ-SL9q(SWn01?^eSJd>^q;}%Jl!#riH_1`>xQQ{G;+s`z^$yd zrESc*cBriOxB{|a%7le#zZN$5XRT?#Z?>ykz478|gbA|p?IGxMrQk($g`Pl9--3ZL zk(7_`J+2qFlgGJ`GQ0U}H=#~igJs2+%e_-#q&aGCn-N{#Q#0L)CH~ge$>;2--*Jy0 zT(T{v-c&D%PlElh<7}WnNZ_%0XsCk;{r#AQ^>5paF2{WDH%jlF)@{A>%N^Up#pT(; zE~#zL&nR_!b7}hf1~2R9muC*GV+OAW@1wczm+xZ(xxT{=@9XCm^DXBfh6ThPHd6m9 zjJ?c>jO$~ctEH-kIR6K!m!aG@0zBsS-V|gVa6h?I^5!#?#&7+-*W6cdnt^9%$NMJC z+e6%YI-2lHd^t;7Z^z@pd*;Ub>w7G)LE@jca(a1G&oU`#;smtR-&Xt|t9*P<`BJtxC--?EX=?M_zgh{53 z-8H{((S1FpauVkxVZ*;8z~CU$3sR7rWJqI(jT%?RN}S94Mldo-Xlyf;K8kMrLn4cN z0HA`n{F^0^ILKC1kQa1wzRnI!uIq$GW~%OlE_>gmy4gYTc1f&p^jp;B%K?=chVbN6!(!}8IXta;mSbY!Y3U#Y>6j%vNpFs zIyU5vKfxbv*m8o6L-X3f#J7$+7&7Tzzqes!>5H<6*}2E&Y^V`J6Ok+gv$-45M?1Ga z5!oL)QX-qc!v!WHZ3%!XW!g!{#k3~CH7545Dj-3XG$JeEq#a^IRw@dv#S|(Y>Lb?9 zZRG;VNa&P2as1dx?tY{+5+-?dzu!i@qBc=4!cJgU%q7_2A*5rb8ii_}Y}fd`pWMR* zGIX3UvIoQIsb*FF(k&Yl+=w-^u!Ea3wcGReHRC%_F zU)lhU?am`=M~%4eH78`|z)?}m25sAkFhPMw-~hdQ{Of7RM3e2M$;8-GT|$!XymlQo z&w>Q~5RhgmQ)K{3KftN}4}vzn#xG4y+yA-NQz>)=tfz!9_v9Pu;Hx_^0oN{=Ga7w% zInc$1IbZw{K^Z%V3egCE+Pa=DZGj`MsjH>>x=4L34#i&c!YC>PR88RH;UpMcFZL;coK&&Z>dG z*U8mbPXNA~&vm<##|OC`OZvFF|675`&)K`#6?N}W`s7&vkVf5P>oh$c4%-C+lw^ml`AwNiV8Pux{N+c zB0BYu%L&!UHTpLWw6O@Al!9nHPu0c^cqXnM6;MCIJ6iPSwZIq1G!-mU5gqzI1k#_+H47TF@*GJevoOZ=?-;aaoU@f+eEq54vapS09g9sZSAA|%QWY$ zkK91-$fv$`OSj{WcgJxQZ=p)%H|N9lGM=qH#DwRhFs5YX zyr!+Tr|Zmjo_m5UMHC^@jVxuLzn|v#^DzLu!&~@$xpa{0ay)NW$7XweVhAxizQJWI zFZVFm=!6EK{|)|~w7EXr8o54_cAlX+4d)lmZ9~&n?8P7qr6LuIg%1#(0wvI{?~KrE z>Vfbt*8~pNi4&v=OcwiBIMgp)3{q4~30#_m^w2oP_?DlPrESHG4S5Q6aK7c`{eu1{ z5*d@%8+D)}jhW4gKh6GS`)AnME-uN`E~H4;c{?J1`u~;`WTyBn%i)-$pV>Rdrvm1Y zGlfxECo2TqTxc;T-Xvq@N!InE#h?;RCgX~&O~YLMhJid`LrxNm0cF{3#b2DC6Fn3M zEkt*7R0nALD~LRLCr{{&85~Od1sSA7n`3g9`jlo#?L`}94x(dCn3R%Kwhn2K>E-=AC|S(kE*W@i(kdA&3!FG<*wn8(M5NP zifF?$DQjdmvA*9Sh3I2ga3##}BoN}1eEjf(Ci`lXOV1CcWXA}!BH*r6g7Ig(IHw6Z z9-0GOrN27G}OWLzlzsv10HKYHjGg2<&zL|M^|=O>%aA8dgMM#ezc{vDDRz?6)D zBq1;%g&c_m{e_B+y)9P+v7>49-($3EC^arL>RGVjhtRG98oP7?0~ZsHwgJV_wS2f7 zbXtsbQR$*O%Ss^Q26UmT>*@fxT84+v@5)Lx!Wij9&QUwX*%Cjc(S|rcb#j<6(|KU!{R5gKu@<03te%yc+_RuJ6 z7axC2$!%xz7vKc^B48(y)7252x)AzY>0%|c60!pccNMyYh1>P<>NaW52 z8Qt46E2J=GLn+$h8^tN>x}*ZGzERP`@N@AM!;Aa6dzuO$G1gYnDnyqdW}-y=YNb31zC4xLEB46I-f1raC*A7K1?uDWQz{qb`XANR=beHN%Y_(->qc=joLHd zu0)d}?UN#KPY`^e`h0Ao%jchoY@rCm;^M9?n92M{oQ_s`)l)Uf7XH2TuQ*&D4Rq{} zpFxdTr+_x|3*)=;qzX(pW2@}_$21x``Vr#>MO@5?g%Q5XZh{RQx|Gv{bf_$ZP$&tlzl`KrHw3#{_A6oL#7sul6yCjWDx%3$0FIBf`X z!qh__g$Vj)pz{YB6r|MM(I!9o@e<7R@6!f;uQ`3FLgr6?;Zo(|tb@Z{>DP zy!)RPh?VaZhjSg)kiAWC|KGC+!TfM>Xv4+E;LfR8a$F@UjyVG{BLH2qFz$`-al*tnv0SM(orK)^faNXu(iR8N{tSRw z1b0wAs$4l!nW}GNfSV@;dt<^q_`2_LYHAVEhF}pe87Ju&=055RbjLn{b)FABz%!Xa zSKl9RE3!il-~tERq$|ZO5!nbbj#&kRZKMVnV9g}HUv@od9!ay}bIwFC%_#E^5RZS_ z$Ktb)JWq@xNH`LxsI|;bm^L}=PaiZ&DJI~gL&&xM-re`{2H!%)O{%EZ(p)mYttr7> zJ&ozBQ)WZ@V|L-vIhH~YSqxLsxf2v4XhQdtUUvwjjZA0v1ly9R&mS^LR-qKgKJKx} zIo;=hYf8b2ux*6rFk70ZaalnbJ&ZDLluhZhSyZ6hQ~S&cmUDJ*B0VCnVuc4!8rIig@=hQ?6)?1{OLZQMH_bLA8-pU`D;J4l%ymfOKZoe`$8?;MudQ5{FoW9}y zwfO86l+#(Sr18^-$o_4Gs|ZgaTrnaN3<`hGNx#$Kh#(|ipet_6d#%l$h(aUL`cx!= z2QXxe6Q(IIqOBAe$z)LaO^0Ffr$0HE2a}6umJh3t$eLg4BXP>(vwK#Y(keG>{0Ny4 zc*#MGr8~>v!@c$QxJ2Dz3cUJ>9mT|zi7w{PN_OE3{6upi;41Hj3_^L17# z5H+dnwf}E}1g_`g4EIX7gjdKyK~3eEHhcu-vl3`f-t<~vsM3XAgi-nvj$oe$=WwfA zN$A0_h6yJ~7Em>4>gW}(|12yjnzMHSV1$;OR7jMGR5B8(84aC^|Ag2shNJOnT`wjJ&4*^g)C^As|(vm?Ot5wt3H&Pji z5?0+jzZqlZIs1N4yh(V)1kK7{al53nxa+TYCjUZY#3Hq($@h=eei?u0jLZ;eKM}@I zqrKT;*!LeN6#lKU&t&UUIGC)dNo4BwP)(mZ&(hVNzM#!KK$oXCTAP=j%pg9t2@?_`{@hEFP6X;u2Etmj!)B1WY zpbOjN^T>Yd1+@M207D2u5Bi7V*&8nowA8*uJ;T5QG&H2Oj`S*}SW@f^Z|ni=D&~6P zI*#tF57`*K!4cZ9W*y>%>v<{&o#2inuYG06fvGIwNVyv~i++)Exr?1cxX#xO^Z&HX z#b)|VPnaD-mK@C;x!Toy)tcK>M(+M`XCCr>RLP2!E{ir!jt8hi<0O9G->~}@=>_@2 z!!bFVb`zrGDRO;Opafz?yQdHkRimg;8Qt)ISm81-Ega)#p=Yw8o5+aW(t(Ubc>@oq z+OZxo+$^zmQ16#f*4!8%+{bC-H8ss54#!L)#+Q(yO>CT?*FyhjR$YFn?<1c6#;ZOVCE~`~YUo zY$P-f%lQ;yi)WY;GCwAEM`_GxNO!={rXq)L=<$q2&Qq$OsyWZ+v9G-K?cH5x%>H)< zZ=Y8h9I${h4pZOvk-?$ukx=LJ=T@Ivq*A{}Ms08Ma7>KH7zE+T}r+#|{VxUNU(Ea!!$*LnX^&j@j2i;7EVNDr)>mTlDhd;a@ z{1P+_ydeOQGpHw+Tf?AvI21XJF0I_h_nO=L8Nhad6G_^yE|cN8$4rbNF!Wv5=%C`A zMH1?|9JLOiW38)-5&hZsu3}^#Y_1OJN=*@Rf*2{3aNpr#Xi)^~|LTh95}3fK_WORu zG&vg;GYvZ?aZ&#JkZ8}+=mp*V@Z5>FDy?5uRxyDXfo3{1Q0~md)c$kCZg9P)YS_ zrZ#`MX+EW-Lw4Bze7*gR^U$u;HkGGeUh}6lBso!}YQR#UWaVh`_?C6v5Ih!9-a4HG z>6BM9AG3Bb*v9jg5R#1*RJO^^DniN;+`vl}M{qm;Aj8BKE2uiH?Ka%i6CoGupiDoU`>IhI{EpuENG8w`x3vv z>0fGE&5$mcq?7$Gv#Oj$)6pcd@By*~eUwHO;yNKH-Uar=jDgpWDE zwsVOOu>?cH7?g5jIkT;7f|&8CK-Uy;>bf4RnTO^BApM1>*06#^I!;igXq83#-VxFUTSmGV#a%g(JV=g zz$|tuOsa-@qZ&)_S92Qb5sos5k+FcReGM4eM{|97_ayY1YA60Rs{v8Cz5jGhkWly$ z(PG@7$oov7p(lOor(EW8-#PfwuFF7qb#T6_^CF*#Wh;C0h!e$eM}BgSku@> zsk%ih$pMAF_>-?3L>!jx5%83mdq}Uf7Dt%Xbv0eX!ylEuhW!p4?1_Uix~%V;2qD`8 zO?@L%h7K}@qNN^k9NikznYHGMioy9eM@R#%1{J&n$QB0bI#59O%@5OXsqK%8kY;H9 z8vDqQ00w;W&vvFK)r^QDl_<+SZYKSw7&^zFQIu{8NJD-m^u9Fy>=wMC1%($?V2_C=7?(*)g%e2v;nK9AyRwB}-@hpTA)ia2VN?FM zx7o=fN5@G4wMP^PN`|vkGLF3+LW%qbx(yixF(M%D$wJwD;-2EMnL(eR@Fk!H#Ub%> z-DNVqMTAc}5<U7C;+-Yn(`l(oKlE+lH6xi~nuUfHOXblzFqFRyBL_Z7-4dZ>01%t~iL(VUX zx@8;^zq*V8-g~Ho1C7H1XL?-xN`B5GSb>ei*=hbO!9sMajSpNKJeDxFsimr&MfpCEZ-O zj5)qgNWO~BlVBlS#agQh_l6~9ak*PuLLUWS(Dn^-WvbiVp~%3$*6<#Cy>^UZsaV4b zb=34Ak>|sng!CRzJ@hY4Cz9YuP~5hn#zIj%uGZ|?} zMBx*sT_)eAZN@`1yYMH|+@9kX!8fJ(?y>sVJX^C* zG|Y+-I=*4|Xv+B#TH&roVX6-#Hl_2PkGC2g2M~82?>FeI&&P&L20nf<$~-07<$#Zg znov$bePO=Q=Lkuzo~H0D;5gS$#JwtXF1EIGqNcfdy#L50dx=l3_AhKx(%o!;WI;_OFJ!EI~=vue^1`}^0yR-;8(Mf#qSm{al z_CwaWuG8+Ta-m7r2jPiyq_szI`9f-w*Db?;PHqA;DW8X~jqCTfrCgWlhPWw2C+wYy zo@+sU-&-!PSCWSF^@9ac|9(eo%7BqHmg{jPzwYyw^^VP#$7ldObZy~(iTBcH@akXJ zVizS5#|X@@YubnR%T%Z$OTIIJ5PZ0~=bM~%J_3p!L<7B!ae%rx#fCSYdr;Z1u?z5v z4F0P+2~=#PZ$06_Qosf2!^!nTLeB1~`?@4TV@GWdy#KqqE5BWkbB4w`uv836@>txd zdVlGd=3SJ^A~=sG2wjW5^-4H?GhXNjF)da#sst6|!`6A}X%`CVeJwfdw=BCDmME%X zbsGIXU`d9da+^ICl>{=*rgjEee7L+W#YaSt-CZ#tHUVTFuAe?v?ZA_~>XTZiz^VR= z{2;lzFx35xFC3emAlpU(R0y&9-4UrKP|Nc+t5k_mNxtU_wX+2Jx* zQ=jpfAX<33_mtxGTJZ)>P(b~h+IWs&&(VwyHZmMgvH1D<0h==iKI-7YXsffQXqJha zuzK-Lfw8%QzooEGxW}rEko=GLd9HMmaMLGeXj%bBB#kmq1ve{2=PwG`pm@}91wmma zI>f-?X}k>BLauSbkb1*U(^|=LV;3Nh2Tg9p2SyZBFnWtU}D%k4R>$)Cu>eTY`YYMkR)-k7rcXSGV}D=h)q;! zNH?LxDD(X*KYZ-`x6zCb;~e9trca5YSV_wZ0oH%$zsMrm#Z39^{5P`6&h2Sh-CSikBkmi;4?nc%k9(GZdUnJ}CHD#3jn zLQAP{rGrjY5}+P31LAx#ODan*Asgnods+w=0#)_^rjZpNT>=A8K>_JIV5V~^fM)YW zCQ*QO_c~}7csRlNMLZ-VG@;szp=5mCapa-L*HLh48tU(7xHV5PS}k25OdyJl&ldnq ziY24PneLbmu2M=Mf^5`|5$WI#zp)XaHo08eBnG2~9LdxuMD&}4^^iY@!&9|kq;n2m z6zRf`YxfrdCkkmd0uh~!la#fG>k?Lg8m2M>$Uvu9pSjlM8Py)!-1K)RU^nx*W;So> zA@BmG>_kS!3iy&lf0s{Im$uF{8W7N)^S%UvP@ahkf=Og7z<8xsk%Qs_ltj}S9&n_^ z*nF`^fBF8q970waCS|8>nQK~`WlLvF?%znJcy=$|pjsNvrq=|;?*~G5(s{VS{cL>P z;yV%Zepx*$_lFxR!6LmLL>Q86J*=X%nNB?B4*qG7SG|v?%!RDvBm=#L={#WRk0#6B z@F+TZ+sYA+WO^k3T=ZL5X#E9VQqUlU+w0pK?zb$Y6Wf7Rj|7xZfwUvoLD2K~LeDo? zezzn3`^Q;dBYV(^EYmjS{{^z54(PW0h&lcWfGh8X*2d%8+60%|nEAb1{wqTx2Cq>a zuUQ>?=Rz+5IxFt@VK4=k5nFi!uMj)?ji#~ET;K86wP)a8$jQ+I;6wV4-X1Sl5tB@l z-thA9E_(fHLs&i~+{U0UeK79siMZN;b~PQ#!A4+|SpyMp%RnMp&xY2tUcQ7{?aQsLx^T|907$W z_Q%l=GkbnRUF%K}Ha6a8TXuOC*-nw96KGO3`E>K)DGrT&-8$b0SiYXl88n)x;MqRsVY#w&`%m%?A8e55u!{n@q7R~XDK z)Zj6ChBF{kG^k!#c3&>t(?O$d0{q>U`5b*4mCnL~))>Xf#cBe{G8D6q$jJdN-Rf0a zpkjgtC;^KkaIFG%nz1D`Z7k-;3D}MHTapGeXl%?R)j$HOm>w^R-m>YlixAc0lY0wo zYPL2#PXn`D@WqG7a&`K-)C-1B;@>40*vfQecaf44J-W$j(y1sS#R{g-%S}RR=`55R z5fd0`O+sz6i}cq-k+T2f>B{0WMk7$^FHzDxZU!rJuZWlxD(yC>z+=d3MXz3Z3lg(Q zO^h8MfZ~h~;seeFhV>ILp%i5#mBBTrFjUCYI}IWY)Ka*o;enKoe1h1;M}P$w2_e5!U%;T%3ZO~h$|@Hb zS^qIqjK^>Emp+)+<4c>E)NJXzYWl*hf98DchgUg(PUwhaWkwjLTy$=~UCvDj9(|~S zw7QM;ZI90BHb$xyVgrP>I}!f6C99% zBf8seO&kG(A|EDe)AV7SUK%> z1S82}*HPNvF1C1PRSCTlDarQtU7V z2_Z(e_20*YZv^aY1rqHz4xaKiJoE@ZiGgJhq)fV5d(GB^2@hi=eQs~RpuWG7QiPZh zS#ML7v^9*4uiLdZ-qGJm#sr3dsv{S2iOP0QMRdGpbx6>OVD{ZK z3ue23!^He9yWoLsxhll$e0L878ei_c_0Sm~Q=sebA?be zf)<#JUl{pe>;>$KifQ1P0TgK(z7p~8A)H0Zm@ksr&ExO)&Uq#6B?(Nt0 z%{BLpJ~S$LAj;D$*j&jC>}(ythJr$6>%|N8#So%nL?zo$r}CtdHHYW;ie+Pry9P2~ z4^YMtJ55;er$|wuq?)wzmCIF_Qxl|JF{h6I5}gHe;1Sk^WN`3z;g%f=m93Lr~rD2G}NuORIA+hA3t+7KPw(TwW%G-B@ll+Z=5~PZJ z&Qm>aDkukGT_T4*k-9oKxV$YWR^(bK=^O0Mchs^T#ja{{?YMt!>T6q{ zQTcg^LWU^0$Fd4-8MZFahUEediXq8-oBD|x#xgB>f7q^K>K>WqjvP_0pkZlGwJc&pZ7EPdjVttB1L!CdHL#E>guMFJRjr3@WSCZ z?^{#JZM@`zd-)eW1yO^vqEo_+Vn zUN+l*Zvu-`)qQtC6uOYKs5g1x z1to*p(aYYV7(6zS0|~)hUEjOiajF|Zg=UL@`i+#pt-DJ#9`^cYHP18gvS{gnMt}d= z#xR7`390-h)!7;&!7y?+VKII=kwx$MdTAblm%Sg24iOpjN~UQL5WV$!+>x`nUZ4U4 zQyfuizrGEAfBz!*@(Q0NC)fG@jQ@H8enkSDe1+Qd^}id&e{pT+2VB7mK9%K^b5W2 z)jn=x6B~!_y=}eA`#)Ip#JWNl(DWVLNnf4m30>cCOP z;~Q*jE57e5a`W5zt+bd2f>EN?->vqXyl-XlaumJGi5~cYy4h-FucM#q^kbx4MSp+k zVkGpq`*Od74>h!5E4H~JNJDn~U=iQL&Mj0F#W2Rm!XjJ01xQg8wTZ=m*t!AChZ_hk zXJuyQnpwD<#-c~lz5_D)!qhDm*IS)cFCm_I;umL5)Ca?Ucz68T`gsblCc;v)HVZ!?{k*~7Xe;tx?ArO~WtQdUW&VY< z$;y2{s`Haa8&rZ;*L?hzU!W%H4R;WTMRjADCn=jbwZ)$}Ml3-CN7aCNG3tk2!PTCa zHcA;|C(cEn;;bH2AljxhWG(Sa%onuNriO1)kKW+2R%_})wczy~!L+oJdqgL;4ACi3=oIX?yCz;GUoY9GZ|YN7`i< zM3EAeQ<_##Dw5dArybf*%^Iau?ob@$qkBG-Skk$K#7EJRW0@Ss8;H9gR9`wzrC)#6 z<$w>MiyBr_#+d-g3S9QvF%uG-WHl-)oYA>vHKa#XrIoIos{pscM5z(av34irda-HI>LU%_ zB%&yY;aR;IN`NcAO1aEBR~>z(o<@e&$&aQuJn7(D+7xUhZS9@@iQ3C~8wbaSVK;l?vpHaY72+@10)J*X zLT>eWU|Q*ZO)5==Ug>F{7JA<$#=U=De}CqD+sP0Yt0e}o21LpP4Nba6&C0s~q^oSJ zePE|xX05`l6X4j#(WLsa#L>vmVELvkbN%5B2=wPR^s-4FmrXYCzl0BQXW)|Uyt_X= zYLx>O$h8m#s!OY3{eCh%-T&VZfG11f?fI2_MWTat{0OB>z6F2md%&M3X6LO}PnLjm zHuRyK^{IXuzH~fFYmz{f6=Uo{JdO*wvrZHMEb<9uz30s()Lspt5yf|2rVNE(>9KzwJVhIkrzkjL0CWQ z(4nzKRubo|`bgYCRP|cvYNZkOe@N$fim}84kN3R)GM|Wi#O*(!`KYV@7p=}H!1guD z(S86P#MYAd#P+JRK*oQ@h5$4Pbb_RI61jr=}(I`6|TY$ zhO}NQH62vK-+w+F^BV(rjNCbmc;#^*p_@>&YKyHRQLHjnA=!zInY1a&XCi{I0+&NX z;2B9Z08Lb_Z=F|E`B$}FyVL{D#a3UeWI{>85H~z@bcDpxfEHi6&nQ=WY_>4!tDV_P z(tQ1qrqzjnBe9Ub=>HU+x^I8RyIhGq6-VYWIOMR&zHDq-U!M1u-TQ8^;p-x+Tbi{r z_?_3ciHWC~0a>~+S5_Dv9uG(Ed;m2W2>WPlZ8hX30MNB{%Qc9{x+Cqp9G=+9V|j>p zuNha#WG(`8R&&!NUX#1lpFivVe7S)Qcyj33OI8?_3UC{=$oCiJvc0ieJe=``Rh%}; zGPYHy(%KVh;m~48X`ejlUmF@Oh0=>w)8*}Eik`Theg$KOxyomrj&HiYrG|Rm-I)4L zvt$~556dklF)`yku8UiK?n7P5;a`LPT^}QwP zd0qXO4E_pkd;@`3i4Zanm>+LeRWHsQSP64k2q@2{5g4mI!JB${c?1h_WK?^wA5R}| z%-_S&{qM(oUh_XjKBlGeeS0+x-a>aCedf81@Zujq%ss+Vj<07tP7SM%ML;5s1KtG0 zd54O7Fmy|Zv%DHR1G;Rj)Qlnzac)_fTz7l(@JWktr;DSED1^L30wpT9KHg|d*1 zFwp5!Mw~%AumgKw<&Do9?&35kk%pf@kn~=h>jj~45Nk!p=lUo!=<`oGK+u>QTxlo2 z=4@N3Qv`Z`cR!r*w?Ch<%}W|F!or>)&~-lk&kN92=w}omS+MpQ%@cVZV^1J*Vw|2% zNJsO2#%*T4l7r&Gv-+ZQv-Xp1_e!LpxHQXmyP#>~_PL+#nsbRvji$2Jj(?_I^K@3tZ|<#$#1t=`%&%=0`*^0yh#V>~ zkzmHiq1q_#gL{&%1;QlQkDzPeT9gl3<67&6eOS#`X%+K4MO&7v|Ak416AMzrfw)0{ zy{(zQI6Kv9g;Hv~`+eEi#iv`v3eoF!Tnp*6YuZz^B4gwHQux?fK46?(kj%F%JkS!N8M!|b;?b5UxdTMCI( z<#;n0?RDIAJH0v)A2zochxitGHVgmbd_*-VKIlC}XMnAM8yn^3@tRIIcuhOEk2ZKa zF}N8UA-+D!mU>-q@SpJ5@*i=iaY+r>#QOTdLtKBA%cv$k9N{%mm7((?@U zwZpGHan^y}dxL12c2J}MgHtX;UMhxMiY+^dGVRGVNG?>kHxnVb)bxjJk~zQEGeUB# z*X;%uw;fM=K<~FV8wh)SWobQssPme^?=*2-N-w&! zq~$k+XYO26S>h4*Vw19xXjw832*|Il1~eB=83LE<{_-!l@se75Wqa$15Uehq#SZOn9(KIPk7aHI96;Y`#a85&8cut?kB`x<@>IdRN zZ~KiUQIH^lYKFDK=dEhCJ)T?`5$>5E;Pj5zl;1wf+cpOLNy5! zdF0+csW$>jnqp(-iW;^eE?bSfV=Gk~?29`0*hp@ke9~GfhHJ^emx&sn311SVu0IJs z6W}*~r=aTgl;!+wT0shgv6G_6{mPB+$FleiGAW~;sZ+*YxtO*0u#&;A#L%EeLyd8p zWDj{k8w3M!ryZh^SA;0$x*fe3cq*ut#3-CElR zevuZHv7eTsLrB4wDS$f1neF83JGr^3Z_j-%2n^xoS+_eoW_MPCGv=8K-UUY|xagTLw{MqN=^ODFibxJl*j3-knyxpU-H)3^n!LTJXGH zFVU&#R-%&lbF001bx|G{p;=vFrmy+bBdK?jw~oKGPD{R+S+s_F`@sL5^1E$Ed4PL+ zj-uIY`Frvf8npjg?MVKOIs7Maab5weo4pQV8Bh(w#E!pxU-c-8#X0eB|8bgYX7eTsOY z>6Iz;A|&YoF7di1h{Jfq@0ry)SQ&y|k^xioNGol2Fa z@l;J=7ABGD{>UbC8<2yinfcGBaQSx)N;?=@zon?*@&JFJaLC7h7cFAM(SP#wEaU7l zLZe(tu0=RxG0+JvnhL$=M24lQT}S*)ui+ia+%wK?Q)g*cb(SXQ;m{Rs5WQWnCHX$g zwaBufH~cD=ydiNQrtsUs5rcR*v=gs^kLD>=U-%;?^^=EFw*5{U_KZ*FtXuOi3Wh>w zI2{aaLKHccn4v1uE^Ba|;xCBjb3yyG#8O&LWMuog5}c|({2M7s2Fj^^N+&Cf{GnYE zfzs8IZHa-3_=lq@|RNF_|piojz^a#z;L?x7&yk&DvXE^P7$PnjgG#vDJX0zQW)z7uVxPN!`pbFS_O)Q^TLT1LaP zmfBc7gRX=XN)oISeYQwUqc4I&Ral7QXnY{_7e8Vb);IR#Mp$ru-0_<(P!Vmvhlh(J ze_Qp8%Pli?3C^^jDeep{u4II8&?0ea?OcoIfvk0TABVNcYV_umi+VFwDbCWWl!yxt zYAyyj`*9_;%e{T}eN1-42yV>VSC=iknQ>d|)IvzLS;oB18sbc#!%=fX#ve`9q}1E@ z-q#Dx4y4cSDkIUBv#n<6NWUL959&D*2rW91oq1Ywcr4vJp7?DLCVT7{J)fwf`*V|n zZsPuL?^KwzcDP6P`{IaBfc!^?cERdvOLN+)Z``+GQ2R)7d*39RuWx^&kl)1RUl5I1 zX56&bt=r@R_10Bm{u^e```y-Mw82NvnCWk|2sX28gGm4r@o ztM*!D(5M@n6W)RFYzUfX@GC{H0>LWFKpdehJTDxKZUlO8s`h?!65{BcpbAqjmbP7B zD>FDCaiNCz;8S#;v}`|t8L7-6Nu0=HSvjwCMpA|sZaWX<0Jj(_o37F~OpiMuIoTuG ziy3?k>o=hlBTpT7u|t(lNh~C5@JF3n*wco{~wviPs9$)MlIZywn-Q?BO&7HA~I3$mvmR)QLXS2 z9NefAMR~DhvgH3uTP7eNr~@vPK!X-IYHw~_rl+TYc_`Di9Zy0Ptr|=ux$L1x==6e3 z`xcQJrkT_w_IAHq4WL5!qA|M88>quDD_e=Fb#=RDTH0*O`Xyy-97-gm%Jyr%VmbH9 zn(QYv*+OwrSw^PUw68bMcN&|!vKhL+nlbY+1RPMlaKoF%+1{q~@Dn@Vms795J^I}X zwN7jdkVC%-z6~(0DTllNAx)_39GutQf!@KYl5nVcT?-oe&}*8d+h~d$*QSy@82lA!FEtlS%m_7B+qCqa~cM71sl)Tde7ZqkuV21s?W4t zd~#}5*eNM+)?7rZRX*9pZ4o)FVZd?N!IMb5W8vkB>p$B69Wvt4^_~D?uhg4A=-%hl zgw_EsnN*Xrhk5aj-~>CRO=}1mDJGHG4uXT zWR;aL$jS{<3}b?jJO*jQ*zn2i zOi7;EBmY_594Z`R14U}jWvF>x?}zLR(JnVd^fR6Rk}Hrhr4?6>4@VX{-1>O=i1idK zT?y0Zm|CEoc|6RPnmklZfnQz2y9B?l1V{zgL<{-dNp-(3tRQCoE$Gwv9B3n#x*}0* zWqEmT;&h%ivnqk6``H9Ba}4D?^%w6f5Mp|N|M2JUUjWI-n*06fFxz1qC1Ti=MtLb~ zdC5%kN87zOnMdxK*3GL9^#Gp-?bu6A-x9*BuKWV9fHiC0^-@RF2`mY;xk8I5wQ-eOC_@q3 z{~*_>%N&|!lqC3%l0|h=;ZT~Z*NyZf43epr_rF$~Qf%S()*J8vsvjYuKD8??!uRy` z#$2r!(-J0V3sib>rV=^fbS%0fHsnJyuVox@Yynr=sQGI#$8Y74z+_OWal1q9xbQq$ z2T$h2tadT9K>t@l=wiaWw8OZZif zSM4z6uV<_5|JV}t;ef$B#^>Q8)hG?Ve?`0F{h-yTBe5tB(H{KB;8C)T6mzV5t> zI3CoyKmgQiBk{z*iUyvD2~clzcz_!KE^wp847ZSw1zYAKlj_7xr!ZCxh##+N#Ef9d zPOn%bI3Ew9Sv<wZ1at`Zlpl~R_(&7$4X zq_&EVXAR?ybBV5JU8v9;#Y*GK7KqUN`iO_vr6kb@dVm=nVA9DL3FCl1OSyS^Kv0~v z@_UKM4JPD$V>;K*Rw!3&`72dHgZ=Kng|fIn)o=q*1(P zg@39?#8~;4b2+xiKE3Hk)XyGBvu9Rj%7}(qj7>UjhLaIcR0!sR)~vcMJS*X1CSeHs z(T!JA{9T{Q*@0+RI@3?#v}3x_W2s@o z-VVej{9}Lfv?s3;8n0;6Ad{zLKqg5~kc7W8XF&Ykw~PknzN1sF?LMxF&!SD5& z(ev@r17NuY$Oyd~xF@8OL!!$SAJ2sVMouP*5p0f;r+;6-+s8Y8z~cZh4-XGW@#7j> zJQTPn1#!EZO0wscyj~f+ikUeya+}q}k=M1|M0$43n)pU( zYD<)?OiVL&HogjKAhg!j-v7$Kdt9KndPMU20bH*f!`%KT@-Jwmvqh1-c16{8K^uDC zc}Fr*Ota8vg|yU|OYj z-|Y`uNG})AQA$oh?OBb(CNq|D-;ru!JmLzwS|p~4D6NCL%1_x`5l>PUI&Xt>>Ct@) z33tuevrjkI*_y=QiVGNA2yk(WFgQPTp`&e_79nd->VMCOw;*AJAQ;!S%|fmCgb8EJ zc4jNf0CIfJajyiDWT+NDqoysw3gZ0kr;%MDeV{z}X4RBU5h8ox9`4kLc>^qKsV03T~(` z-l?^q^0opJ8e&bDa7zDyxHSr-E#hyWu?r;o2<-wGP(Ur{XSscn$<@2esV*jQiH7ab zHLoJINKd_6UQ3#FTL!IH5a*lW0yaC)O#aRO7<%{Hz0Tpylc?ozrAXkyHr)8~0I3$8 zbpus{4=oS0!r`A}o<=F^NnYV!1(>3ha+Mnr6}?;O9rA(A+H3lelWx(;YgAQXDn^YI zJ6gJui<+~ic|(-@)s^Q4o#OSLx`Kv&xmcs?Hm>27^C}Z=9#1DHWw0Cl>@7boI=wuL z(SCV{b~qI_!zsBf$?DCB7sB=V^Ff%2>~Gp$u+SpPjx(mm3e~z%E~AWaecjT_%4y5q zCLG~P*Wdq3zyBF@oiM>&<+9Dd9W9Gdjk8EY%7!|&c=_frGu9AbRM!}cKIO`GFjwrr z!^cM*X#y#cG|Ug!Ek52AKO%h|ka>8y2TO2g@&!!zGg)#bpWc8__scO4-^*>H^WJ=R z0)0o{*OZ%RR)g0Y>AMu;n(}Ast;Edan;3^viMRc{8p`;%2C%qlIBfaT07n)7Z#nSzgdp*t@c-DWHHZkh~t{Wgk(8t9>`QsDc6pI)MM$vhSZHh4!={y!V@x->d z+au3kSGT@4pgsDH^kI_DgmFb4jxK8@Tzgtc)^V7Xi=9eF9M5i{OiapS77~(*go463 zZP1Kc^+t?YRG7K2(^j6j?su)M(UC(J0+@uf?{ls~`m}%cMJ`h#nA((@9c_bD9mx1* zNmIgr3pIt7u0u*{1VQE^DVK}U!?4mo%2CzmhHI5N@{-`#Hok28%^zo6Jwh}#>T-L@}>npu8X_B#^E$$t{Yw_X{X+f z5f`xHI+QQr)VnPt{&80OhlZd4@2vp zj)YY{iko2`Pvt+|{N8_W2LJW%vG17aJiRk0pGYiy%f3J8sSeBx6mC8~VZx0Ack>;- zjLgh=NmH5-$|UW(v_Y5m(y}FAz21f--+(Mj=XPBhaVsO#gxQF0EPeYL9ePA^`m}3f zoVgkLi^0T!mibho!lLpyrTotqsN-5CD;6((eiSIf$*et3HP*|qE5j@;E%2Q3**!?f44>0$rFcj zgs@46Z>+12Ij*iznP-JXSlVABXo%xhV4-6_tAOhMlkl-2&YZ3*X1$4aVPmU;fes!< z&xSDULjDg;gioFXD`sGt;YUK@8Xg~~X>rUxSzt{;(Wkkfl`as3MXb2*YNH;NtBpB4 ze3Y+2`w(0S1vjX8sI+%|5|^E7@HCSQa}G7Q50tE6D|?8rEawlu!kn*DZPI=ALqkpj ze02)Rmb%--g@XJyY9qX3GJje|;V?sn2&;=hKulLO;)ZAmkXevqX7bPh84M1_n?(8R zrT$6*OHoEKOj8-qzFFS*T2kz?JBE_PV@it^JMmUSC^!8HaTAAtX~yg9t^qKd{oHXJ zO*in5bcq9QfH}Zx{O=T6TQla(eRfkLN=3y359E_=-dX57p++m1Cy!;U+K!Kn(Mkcc zKSV@V$L0CXPX2xWE`9=hX1uw^F(TpKeZLB~sqOi+wf|v^IuX34b%pAM0EA9BGO;sg zI(LY`eV75IrgQ{^cH-qep$m_p?|_-9qk!PWlS&;o!Pv)Ns3XKFgH}XSv;w}m8X;yS zisu#(=sFap`#J6Km)@gq``VG;E7h8R0?Ue@!eoOXrjm}+pJ=5oHg*V#ILIU* zk(rxuPNly`HAZTp(S>RNdC>Ub&A2zFaT7ASkSQ7kn3;ElcaX93n_FU$GvLbVA#>Pr z>~i0`av|sUS6pgp<_!6=h%rm6{85oY)N&=J-XBs~gQiSk;)P4kqtuA@_-#-6Q}fSu zp4k5ciETS!%(Z5fC@hnb<#vvDB7I#JB1B+1bMPu>5+{g6+*RajnytOW#352bI(@8W zwO*~nzCPD~W6pY5d*9#16FP`tAAQROAIkbsT2sFNWC&{nA>`i`ZWzs4lkRluLCd}SN{3?b~HDr2C@ zO1CUY6p!Ulx}^On+g3qR*9L7+`o#}K#+xTsVBmWO4=Pj+-TV9n z-sViAnbB^p5}7FX{pa71^(fpTv)t)q#|W7@$@)!m=S)RnqSf`2WKu0>;moAKzcVxCqd`k2~Rj zns5nxmplk-0kRl$IvZO@Y~MQFyRK`R!aLgNN5;4IX=bj5XY78(? zb(Itb0x2Hp82K4!B09OdE2NcDdUfPsmCYO?fT>ppMf5JXL)`dr0nlaM{8! zK<56pC`gNN6vH!eTAP+rAZ^mjOB>f!PX0e7wx1PlH_d1X`%0(FDy2@HX^}Azj zt>Lxyd8fMI=5^RP(^1V!fe&dKWsTUR}Dv?VyLdBJfVP|7f#A zm}a!4w&Wm3;H}DbWY@fqjRuf;-szz!TaGe)vfmar%1S2~R|xG_lt2w_^(ys@xyb?a zy@&Ws3n7ppMV(VUf7Z!0$!Xx+f}5B4HTKU{eyU^%_s=&<_lDmz4kvd67AX;QI2YaJ zwIwcZ0w5{eEp0qf1c;RDLdbC7f;+PHj-2;fG-)hF+DB2J5n|aeXJTMV-NlYobITdr zIn;34n(N~zx20Jzq^|86nD%Qz4RQ1H`r*qp61<56g8a(|hSKbhpndeVeHX3nWp{l= z7NXczoLm=we#-%CA}z7SFSbr^=SKCCdh@SG6fk7$H-}&{NWT{jg}Gw6P`L-Yr5@o-FE5 zlAKvkUvdCdM1p<3qt92rdWl1o2*e_cz{G1$2g3vM64+e(M9~|T zP8L*9dC_(`sN84?u>)O7#*K#f1Q+v-O8@@g$kGba`7eF~5nG_bMg(>l*VfXKxM|h9 zb!dMmBzX*0hErnqlM`v?=RPttluxM87HDU-F|1@>f0`&TQp^f~qZbxb_h??TcU7z>aLubvp=57S-1RW8WCZ>k1FiusHn%MYAdNzi}Pb^v*U^pHwxsQV1;& z{Fd3ZI;^;|bjL>7$~meest5`Sq`IXQ4aTTp45^ID?o$rHyEbK`ocgPF**&Qab$#Qa z(lPn1y<#lgX)5x8t~}+X*6LfU)sGK0j+-m*D)McIJ-n7s**tHNYjZ#aKBxovXUGGMvO0g?dDB9l{GTi zsYq(|L`W z<<}}P7-EoNDRCFe46|}ZWVWaz(HLP3Qc$?6f9?7rLQm0mS||Gy-PvU-fU3UXm0M4D z(PiFSSAcwFYF~&hBaK>)lf^m?Q@BYsk1D`hA``?4i?vtWi2*T{q$(m|(cz}oOf}W6 z-E#*kf)ef$B%uTm8I^egoBLw7sYqOao&m+)u=mG;L9r6GOEd( zF-!{88Y~N4KTR~M;xwP{#riMoSyiN6*eyjS>6v)a>>zX%O%Hdi5B+3x^6ceJuy^YU zF+@7g21cwyj1f1%_1W=1Xm=Z6j|2J->pdR%tF{{c>-~6TbRBsLV7C+3rMEj9POW&Z zr<&IU@PXO1E>!w9=yHf<@3eE1E!oM*UnHySI~Dr<{XKvd{72ga{MJlNOn?I;W@L{I z+o8|wF-g}f;|6aS5ZpN)o%YObR?LtZPf>mndp0dY8vTqgw0?4muAk=dRcJ|?NTy3^ zP{U^Gl*?g!XY#X_b;j0$sn%UjnQ}R>Z+CJ4{^hlBGKOw0&fzR5Brg~|P48u5Nm$SkF91d7O7dRVn|e9pP<$ zms4z&yy>x1wOtYfQ_&^I|LwC&malAG<@3_aw+RHaamR__Pc6Fdc6+~1^`{6<>n`+? zb^U3|?9-FW^~cHyz3RBak#{sudXnhPT|%{v{d6YJ?02%3ASOj>U~br=={+?ATx&-3 z$|IN-6~}pWvqY^s;goqCf2%F3oBU~**WzsIlQ&WS;n&#O_Ku5ue?w_3}t^bzrU3!`w2GjK! za)Ys`E<7;;BYY~~&RE1%dKR!C2^6?^hTragn#3?yWx?v0jn~|=X_<5B?vpR(Kzbd;^pw?H6o7 zz3tdw8lYAjPM*&)yBab&@V0Tn&JBxwiok4v+(Y zB?64m10@*X8Uhq~g>qFmqdOFOnWO{?SfI&0HW;4C&BFt19nOG*7%i@3kSkS;9hpAl7MY+;HHh+K6HZp;tl4tN&m1%!D8atF<38i)jsy5A{R+}0t z)Q9bl6uy&9yq)8VXQt(R1k=BdJGya$V%sZeu%F`A;advC8wD|HHEr&HkDQ%8mq@|`0POT4}5x4X1td5KXpq{MEB z(xA`YVFham%apTVevMYBGu{D&t}UxcFampjqDVX;o4d4>Zw6SpuBh`X-F{&p{k5YW zK4wS_y?v|uR%(xJeSN}J2pMD>X0&=*N=RE|=32&Y>tdM5ek|oQ6jRnh_=u{jI0Uc3 z)}q`~M#ctlS6MgpDDT}!hpkk`|A_Lm2{d$c;e&D`f)(R3a;JFwo^y_U6$~*5v5P1s z8?pHMl}K?1D~ts56XL>u%|Z3uhZG11L!okVRl5os_ePPS#Gc$A6RjILgFc%(BdsD- z^$b8e5C@U;YEJ+pWafY;cpyj?{LtnBCK}FQn{)4;HuDVp1b}B%!o~ zL${IA`QYE~>~74PWN^P+;<)27r_2Fd8n8bi6AP9I9W7Y52-CRjOW-bJ5%oAcLT|CY zYCWq1Smj`Oo^Auo&rhE;_HA9_pa9$4z!$8Y#5eE%?5B1I2&}7}rW4I@hjFx(qpSO{ zzyX(n(>y?%6=>8su(%L+w~%1^MQoWinx$8MR9y$!TK}9kzt;XT*ioeK2JiK$Ond_jn_U6DCj|wC%&D?LnLM$9r@Cpn7C~$1!xsG5J7qvR*rZ+TB*JQ` zMJt`qT0X#%w5i0KKbWs&Ms7_tIK>!aII_fF7p&o$&`WIx`V@ddYHvnVOp!+&SH(8Uh928y~Ma(HbPRRH5TNWoM~*kK`DcN z^&g)$*e7VHQS}=*hV=WWat(EZZ=zomt2BB%_@mm&-%w|`I8b-C4p5!;%~O1E~4BA z@7sKPCtlxahFDZ|GCFbkU{UgEl&G?5(r;Li7A1S|+KsI9xrM$3` zU@I_D-N&X_9CMx+Zz#ji4{-Lz_EfQg^;1vfT>?z0zaww%_2U&fZ?3{|>SNzm;uPM# zE66G0Z@oJ8@@v2*OI&HG&d5P*P2Lmt0Z|JWF; zRTigFPi@3RzcFBT>)mT7dVAgjMzN6vKhA#sgM<0kg5c}jX8x}0tgJfks16o_0TLVd z90;8Ixtzrz&pPaBe0lkk4`>>Nky>Rrdwa{KnKfxwLm|&o$goh|tY~5B+Z1L*<1fep z<>B=47;WQI6~czDkOg{<3qZmg-eUzGlZM!35cBN(!vtyb(1Be64C4mat<41#0R)PJ ze4kg#eP6Fed>`k+*V|lH!qx3PV2Tr15N5TRLo}G`rnM_FI)g|^qR0ROG2m0kJtqW$ z8-N=QK;bsXb1AWEm|sqxvWSklrC$fnKPY}~VMJLse-au30lGn8*@waB6`X+oChY`c z^jKXiLq18+WGO*~$iC#*!h;;4rq3ytO>9p6m!4}?Z!rTN)%SQ6DH0`0FOfqhEH9=| zYS?=WutTxO-E3TP(M@-Vmi_*>^^d^+c-l#iI;g;KF1|LV@|YlZI&X(JYaJ3=S@hWuSR9k4t?hbRPoIKoaGjOiNT<_UR}>Mh z`l!3jO~zbFDy;daP)J)dx!s{&Q3xiBfUt?Rh=7PaZ&Kb6tnNelz4WEDj?6R^LWchb zZbT^|P0~|{DS!Vo)e(aPK?tvSG#I%w+`h}Mw6)W)sSm0^Ohhys5@|_AoG{kj#@2A$ zdL@_wo5LrSy4BL)qbrR=&vK)POa|uv$;jdnqVD=izHC@ z!C}ovr5KV@D8H4?nT*QisG`&`G%zGNDlAjjVUVgrq#2G~MYARi1%nx=8fX(hl~rSX z>0JSLoVC&&l0+Ry8g4=p?R>OuF+bAKW=w$n4X}~{14hO%0P7lP!`-YDzcZYyc;p5Hy)E+`(m3uNld7}!+njalfx4E`$?Is)Q>mV25Pc8Utn zNq2H}1)xD+X$BZ@?zjCd zd#E3Fn%uTBumm|z->=S@C2LhgV+y1R{%beP2z}%jykDpP<8%IF!T^TX_Ki5jVf`Cj zrnPFA!1GFKGs4rCv>Tjo5$To{#_Ah)fRwVa0o3nNIb(un4MS_YSp_L6J=lT=*ZT)_ z3*PAZZ9D-8!vZZFg^N(h2Vne;;du|BsU^Yj_JO9GJZUziyYr>vz_bPl#`WhgNSXd! zy=XwrJj2F{C;GWF$l8^ZIxFS5EtRikD%kx)3MY{O|cy( zN(p7rL=~?C)oRcy@hQfsT&mAhw#~o8p#{C+dcdTwl9QM{eQcdf3gjHvprRm{d>9Nq zLD88^yL&1jYcMTNKRYl&s>HNBVAM%0xy#mPm+3saY1pe=4Y1lWKGy*K8giy9KDztE zF{AgO$`wODY99zSz*|Vd1GPsG5ya9Tipq30yCo#fE0D6R<$DcV2q%RbRZK|J;Hkh% zXkx)mAz!zQ8b&G`$Q{0|#62pY2^Ef+j*qlGrfcUoZmbR+NN!7CWG_C8$Re_#!xzs@ zjYRJrJE|d&>`m`*gxkD8w_0}@p$@Y~tM-oC`7T??I-Y0>JN&#opmIuGI!UU6+EN<+ zXgnlK9VEJ0;dP*)C?8Bi;3beFN-r-*wmX+&nuMZ=4xuewHWnk6BZ;~zZgN%lA38@Q zW|2a?eZWsl#d%efc9?P86s?pXC7v9a(Ig(KyaE2JHW%e)locK$gWHydT1MG52_Xh> z2kJmgtlMTA6r4pI3qt19Va#x`O1ckd`X7~*Gn+N@duQHUAZv8{$_gU84{c%xf1>W* zI`qm&e7!*W%g3R~rO|u(a-b6d`~R#1mV|X(=Pt+4B0pKfCLc#j-28k9g@!r(u;(Vp z5&dmpWc%us@_54Q+d^d&er5R@(mnf%oMGwboV#bccXSDFh8c)E1p+LHBnsG1 zz@|)cN$V4hGBy39VEp*xt2jyR2%FW52|kWym6!E@6Etu@8VG>LdC37@_n3cN3E=8Y zT(hQ}R7qb_{h^HNIV#!~`l$t0BD+PK5m@UlFE7Blx(3wbtGku0%O%Z#ZD2wXA)K5* zaJ@mrde8I__N21Hw6b(X5oQIEtA2-2%b#oct?TS+v!E}YNZ#PX$SL-o8KzB6^OAmu zkB&JneJAT$tj4mk5(1(W=ayF^Ph8W*LiS(HcC3&I45C8o=b#vJ)l2_|4 zaIc&X9yM-R+n0A)E!AJ1(g2O+m$?4ps^_!mUU=zD6l(u%KE@DAZ#`+*y3kk&hN?f& z0A13Z*)ndOLs)}S4)n21in7L5ymdFZnWCQq9aP)aV#tzOMjEEKp(`)G3AbStDh1W5 zO$RocT0zK)@j*ZhvM0^qu0BF^HA~@0m~uC$P%H1xER{fT+7@@{i0gE;nkra_naUQz zgQu?7Qe|329g8|2D%JnstkX~;GBAz9Jd3ixBy@)<6^ezThpRIuBA1?EPp~P`HdOgY zr+P|>a3^oMNsdoWUb`>e4hRZ#4KYN^Bu^%n%O33HBSNblj81K}HE=Oc%r>+#VrR+@ zeEpO%pcPIdhlPWdK7S&03$}9tTYyPbJp~1g1Qh}y4eTedgeP}BZseYs}2*{qInOuEN?IF>x3o0IPXy2$0XKKKb(s9e0g$36L( z2>;T(J>zATS?v)+%6D)*){6iKK==nxM)quhfMlA|zsEt3{B24hTGLQ9>w68CqfNu} z7fr`^-c5h)fG)C(P_?VfQEG`pr5;+32#R6#)D1hoIa_9e*=i7V#lv$|#QHqDrq|5+ z!UFrD5ZTQ7Qm+ciub+K}y}@6RAI};UpN5$If%{zN4B*iP^jg$ZpEuh&h@^h)8hgJ^ z@Ab6=S~qz0M7CFFKr3B1PRr|E)@EKjm^r;(cB02h&lW_i`H4tqPw3V08iPNx4vlC} zB>&MvtHv(zjk$FyudOug@jugxJ4kO3^+Nijezw;{I(i$|UZxJsSoCa!EJkQZfq3em zWwrUx4|RE_<^+Rhn?4{MI^w{)tLim$Z$j?z+Rm?5hp}8uS*G-iS-Y#?v-L^YHxG^E zfMvR3JlN8I{s{fiapZWsQWftJZ6|u8G{BvYJ+8xNE4$&e6e6}FeriBqzJmLLnsq65m znu!;Vm8NRm(?h3^Hgvdf&?r{qZ_Mlu3i;6n491{-vgx8637&kg#1}DzFTwNdEy7&^401WqGnG`yQ4b+*vW0N@dexSd5pnj(Qz~Tx z8J;;JMX0A@V)XdiN{~h&tZ826(y^2=WI-D6uw)bni6nzG#OAo*;`pIL7V*O2HU#YQ z!GZdR>8VZyWtngPEtc*z#8+$n`1b#3`pU4V+OBQkMp~t%yBkD0q`QVjy1PM2y1TnW zKpIIYX>e$yLAtvezRTx5z90Nzj$zNR_qx_P*BQ-*j5m8f6GNS2I7TcQ7J>{v;fBc3 zsDObJ1ntrr1`?l1?9-qSJ)axnbIkdbU&gavRxuLmpDfPsMzK*^ilmqpSw=X=bQyf= zT%m~|2id+_+f$PC4f|WI4wc2{nXKmkWGFS(?QOo7^iA3U4UVVx{Sb}IPa>zirNq+F z?ZEi4Vzdz9t?AJ5BR9|@0d`saOcNvy0C6yz|g0QX2S#U%Qs8u-}Y}6 z=j0$w0aRVaj;V}C0}PM$4qGpEC0@%%)f$QS1r8H_pb9UFO%2!~Gt`qQ1#7((!`$^# zvc{qp+Wx6(kuRuQ!l+6t znwjy;vDa|&XRH_~?Su=NllN2p#6T8nkMFCLcJE5G@3bmsEYI%y(%x|&EVe(g(3r`J zHU(Qc?mZt&TQhq6+j(ycs0}U|9qLd!N4Di2{9bIvPug<$o~oRE0R2u zPp^Za(%O_NK+X zS2-L^VLH}K+SY(|3m}o=m6NF>w|}go-QBmKzkn0|lt2k&=Q)C3e*+Tz?fpUZ9r*D8 z2h3QGz(!x>dq4?Y(w{PRn2DFV(Yur;T) zNTRttO@Q2K*96i?0jF&5+kkjjUx*seHo=j>|LJ?*flrB!Qrz{4N-EZd0Sl`i$|9;C5AJeJ46q%{i zP@$DNp0B%G>L#%m3U$r@2IbXma`*#1IHfl^{+`g5(S#D%=BfEHRZ@p;%CdP{QTdL2 z+(`Frss1q2S7a^9n=D=1vhOjk**?=)K*!TRjuZ(sT3u-?am~n}tTRw}h`m3_KlBP? zYMd5fLWTr8>T!xd7Yo}&E}Z_!>m*UZr0h6lVpm&v?B67%I9=@}EuinoRbDRLRQGbN zEQP$z+_`OfAt#Kh=j2Zyes`#IremcyA;O~%Z|FCJ&k!-JJ;**L15fsCT9{WiKmnl} zF^OChIPS$WyrmK;B2^85LgZ2mrr?G!dQB{L5VOZp58Cwv<}FboO=_`@YtnIzQpxj0 zT*(W35T=nP;seHaW*a`9==ic&<113edNx+Qo89Vgm4I&ZP zR)U$)N}xQe%W!}9g`)9Nj0L&6&Bd80;+=4vQl|`T)zwqhV1q}@T7k|HR%PB6#c5y6 zl=)5^;(}$8|1S$HG+JREUk!5PM6+J$!@{Em@&Lg7bWT2@fRBt1kaENI8)nCgHslPY zgfTwVd+xB&{Z4B|ji+%q)wK5J-ngH4EQhy#rq~%k=fh?{CNE9__Sa?L=NxlqGs>T% z!K*oc%G_@DB=hGo_Fxn|F4Q#`GhVLoy4NEjv$p@nWTPk$n&kjS){?2SlObs17j+d&DJIVqn#8D91rvsc7a1?ID3~vSr@b+%wl!$P4FNH7ghxrzS`yW__!mq@ncNT*xnwvh(ss!2|v@XN$TOD@Q!3S z=#RrM3a}RcMc(EvnJY`J@Gz))YN(CFTY}nW7k}VOe zF`rQCVS*Jts7ue3l{EAczSGH?VM*6PBQPAds7LGNmG}%#_0b;*FXL6qs?u^!$xpT7 zsRMw-&_=?_%pq2?${1Oryh9;-okE>6I`#j#0O8>UWZ$MfZRtdru8qp_%NhlVhkcR` zMMS9-b_b*bS;nkRF?|$RzXj$XddhFrpdgi`ZcbSV>)D=EWw38=lE?V|u@ zmz9-eWM-}d8!d-j%pjN}w@_N-l558{AG_^N0iO!#tn19OlOKF9b1ga3zp~b}$TJl& zw!SCME?O$dOdMPRU+iHmP0c(=S=`vpnNF+(2%Q-xc`cpAze`K(DX}@q+JjnRwAsW9 z@5Ror-YbFGVAY_o>CFT!&|%*A$qbQ6f&ef7@?|5yrbT#1j0OiI5|tgGZ5=?0JH+yZ zm&khs$dq`q^#`Wq0Z_; zgLOr<{pwGJ{a=6PBh2Z4(?In+aNG+#-7p)XP=aBBFBw>SgQAeF5bD{kfCgtt`pcqF zTE)2F=mS4P79wdTtJClrn8MBf>Mw>Pt9WloQWTH0??dU&{VwakgAj^ojdz zixbiwFJk3hWF#qh}32Ms!7;S9t0;m~Zm)PG(_Q`D(Ye41pN7J)N1DU)=uP64Dc0lF1GNe*EfQBPE;jywsSYZR?j{iZ{& z!iZH{B#wo^ks;~Q%G6ET3*AXCA62eOsi2Z?TFp_xq0q!-omf&9hU+f z^&z}%DQ`s**&`}TvEQCEa~RwuAH0P|eFS4QF3igy{11L(G}iNx;o)lI`g!v-l2C(s z1*j1bPB#%Q|XN1q4VsGTarzRlCB&LnPZD&70CO>9gB#FlV= zRC&ojKE$N#wUd*}6J^9(#Z8SvL`cobF5KOk@F$;P>({g}&WEEl{zSRiBqhHTU!aCx zVN3m!?RTD_V_{MG?4Ot!SR;o1S+ZcKoOOxxU?_@9rmkF1iT$q#CPHIlJc1|$k#$Yu zE9}nMes1QNY#RNF^#zY4ssSWi5e$?-7bi{Aq3%Y?(A7`ky+=5`=xJ%1ew9-{tk^T2 zZ3I985L0Oujvh+UV0iEAyqj=f&YZ=(~I z&R^HhpN^$%B^Jg`A03fTUa2%bP}Z#mbH{*g5Ky21_U3Gy7#tj|N+cskIhd^~mZk79 z{a;CScbYR^Kc4GNP~ez{!yaIhq2nJjHZ~3{E~a9Hk|V+btG*TQi#O2{{~6;-qnP*> z!nPMO#-ssJSTuPjCl{BaZYpg=>FmKj%mYw)f%$Trctm>Vr_1FFuJa*X4hVUP4-{U#+cCq()y5NW4FR zkGzYZ*hZ+hz~@t%K0(uo`e-33-k)F=vb;-d_L!a)hdHv3l;gUzF{3OIW_GSJP?b8A z-YbV|nn;C+ZfD>Sco%m{RSiBNJvpE_1|P~kla`NGCPd) zbyn1{@VHMggm!;rwNq0{KS_<_C-X`Y4)i-FFivpCgcn$-I{!|FVTmI@5j)whGO?g%Cwn_HixNceC@U z^CkMZ^0Q8}OZdvu@t39MGy0VJQWB!GdGp+}J(^sHooic0vNI=QC{z~MU3~_$1<2q| z84=+rc)>*H9rgllm0tU>z0U;!v;MzI02pY%TiIFgVN<1}-T6Jx*>t!i>%ZLVj@sL= zdAxl#7+mK2a(f#1?)H90etUbz{U-a1`$P7Z^vutBn)Dl?f+sI$@BUre>h+P=@CeiS z;>z=z&b#UAp)G#oJN}N9o!pnLT)+wR-ROFH7#9zJ-S9kVD6I4U!Q+8cjy-!PoE<%03=Jxc%B?CSPHM@>K|;?{*fvm;7!w^{VogY@%*95Ih8Ux}M4 z`MWHPXsM`hvbUtyj*rAfb3HMl>)ax^{`FZd`6-$YzY&cL{ZmC#=-qutT9x2BLnB1d zaKbn$ankF_63aQGhIEX{;-xCdFji&7RzyC26sG&dFvsmdfJ9q3S)mVEyf%S}9-7|T zY~fSbjS(X1NkdwRlM?7;4tM+zMe~XZrl}Qm}EJBp$8ij#DhKVv0MUhSe zOVS^WJH%ANc`99C)4hQ0>2egrPR$CFVylt{bv&+ghVvf_d`4>^!Q4kAqsouK6w#0( zlr=I6K1a9}4(cY)WguH*LL+wT>c-gnsg2BmBPAU~sh@x~ixp`oRjD3G3)hJN$%~e- zh^ExCCtxR$n5oS@7kt_xznGUHLwAycycPxzSdXg!DA!O1C|$mnovIO28M8z7)uUAZ#rcMJpbPq1@x;mw|~ulp)D6yY1o z;seUb?bdpI%TUgxOf=L)0kak&WrU3hPxim$7_nkVm#Z$Aa6twHNU6dNDdeTsGSR5( z=~W__^^}hYAt9Qk!$MXqR|5%HhPX~3Mhw_FWGm3vPMP4y%1Ah}f8V-W<3amrmf$3_ zX-_&-udA)Ie!c|-K9S+m(`rt4-sI`GqDUnrmiHRapQP!)8&*_T1Jc=q1+W72 z@_Lx+M{w|#qv_-t5PT?J)6%h=itqMgH8!?)d56CVrz^-g{bNi4%FAB(aLR$(|293| zcpFRR`F1;T=cV=D_nbG~AczfdF<*(XwzebKwiS_RjW@4=to<*re}V5H37EiS;;$6{ zFnkK_y`U+~ef030(M?xwrmmz*;b~4V9Uk&vK)DwDfwMB`fT6ncy`rK5ge3@f#0}t% zOiZ9ZcmduwQT`iM1~p()I5(#`(8v_>1oQ5Axp2yc4G}g73k&cTzN;}GA1X29zzBD) zl&F_0mrnzxpA?;@X4=m0WCldC-TKADqhoYP`tC5C3Pw zY@M>Ooh{t7G_z`G>KA)Vak8qAkv{Rp#wINtE$S!=_>Qrqb=cHu-L3Ux27W<)N>mZn z5Q6Fsnd;e{)z!H1n-&MdP!0XouE|MqWh|$cQ=oSeh>3YC{Ok8`_F27_?qUW${;DG? z7{5m7XZyC0l@sSV3#HOw$E{@RL!F<4NA{f(;xK(8@gPlN!m^2*zk-YkHAI(q_S&Pq z6*_rN4`q;TyW2h>Boy49I2N3&+j|G=c5{t){lLgH`lFtIY|*}5ylJXvaj)iQWB1*~ zj+XA{txWq)GIh3OqjZ95osvZhu>A}|4`4;!bKzYAl?DoB7}of{)a;YJj1b#=anwX( zg4fq;%Ac~C@qcp#cTDxN;%AsFGy6x5HAfbTc)qu0UL9#Z$I(ARzoE=f3Z`$iqfvX% z?&Fe^Oj)w>e~;JK>~VrNH_E1^K%@{2{BbaX#Ys^c57uy?N$*pX@?(|Jd+{$d#oXB$ zH1br~HHt#9cS-v-VJA{|t4ON`ZtrmI%fi%B5EuJ#(AjWclLsHotcU0tl73V#{TSO0 zdXx3~O^F~U6{=LQy$Ipf2Q0zYcWBCRJ9On>CNbk^S}{9w@Qd`}Grg&;4o?=wk7h+ia0n)wVKb~2b#VzB zN*?ksJ@h7{g6)!u#0_K*=$POJ#%cVLhOR_2T#3U+o^aG6mf=Y_(P@82ee}wo+6w540Yvas|sIu z%rKS?4i0o$yumy#-~RX47WU!Un;?*pRWTl9@# zbla5e3fYpe*SMEL6qo<4t5BqxgU_jt1962hW))fWBnGPA)o9?mz1|mzh3pYvFqpl# zQc&P$_9Hxw^K<6sw)+KFX5FQH&EJ@BMeV+NM6$d*$#%5+BG?QqZ1c`m>8w@Gt{8Oi z0);$?1~t$9Dp5UKID151Y~tt`-}%t`;%7R))b5;WRw#~JpIdq*BBL{F2!1tE$#fpf z-*{lq%AB&Xy3JpJm~q7`>1%b~mn%eWKHv7VK+t9l=Y!_(FvFCA5DEepoGlOdQHt3~ zp7vrn7UjQRL_Qw*-tx`3jjG&VTLb#bj$V5|pYOvg;WV-H%U_~nf#!j~J(BhNZ;H^e z78lICyh3GKx=(yxST5m-W@Z|1TRR_OD`sO#|F%mO^A7aSP*2}^2)+Qv;Amcuqo>p9 z7M+}I3Qh*l{yyB0IJ(cRpLL<{u;^@N>$i`1bw0g0$Rq&cM-pVI)hl-4nYdvfcAlqm zr1hj@$o{Wa>c!&D?RBQTW?H7Xj}OdZ-R)*#tOZBx+}zT(@5|T=g6!fB9TT&X{U1zN zzL>B85X6Ym=CkpU`AEme)Fa(nFjvMRGo8fZe;|b9`laP%J!?hTpZ*U`kHxE$@6WuC z(xmZiA;y;UXftvNk@$QgZXYH5k;D1k@HPmXLo+ucoHs9CduJoll+0&JX!eR=;s?ho zKtc>Xf=O{#9|Bd8s3dlSXj7t0Q=+B!7iEn<;fWQo@-lU;SrphIR*^B|(?9Vm82B3- zDp}-@i{wR#g#Wquh`(+bUGo9KVxKTgm5h9io%&ozW>t!) zns)ojINa7KDqd65eX<*|hn0}khG;FR+&$T2Nd{@`8nGc7BVo>OGDOMJo2+&j*3LD4 zf1C4258+-H@tzis#w2Wpf?Ovm4K`iJkRjX;@W0zyq z@EaiNfcI#_S%QU4gH4=kc%U%&*XMn2J)aHrfI!ce_15a?9|>ChBxcA({kYw%l*pKn zFFrmw$;oOdDL9gNZBITVD>stJx`}u{S*SYMz>N7QZm`2BPiuPr3yKK&&mv0txhTn9 zFUMO@u|>zs$A@^p@$_phh^qiKV)J7Ze2;3;&}PpPZsH?+jV(%G*UeXe8%)b2WVinO zDS{O&B^%?iv%yV#L<7AgitlEb^5zoWR1jU|eH$qoX_LKZ1TcO`S&;2#ArH*XcjnW` zgTx9Vh)ykpJB?$GszL>N)fcPJ|MgQ3qK*+5)7ga|{4Bhu?sGyib%6xZM4Wkj)ed#t zucR)?O-~GJwQdD*4mddP2X`*GV*+jG5$O=0{Qkl6CvHft{0##eUY^8Ncmr2ynV${3 z9$;l<%Qtmq9@CZoSth3&N9D9tl7KNLgx>nC~ac=z1cM&U!cEb#ivxdU8H7 zK%(sRnC4S0%1StH_pzqP#MCvp>92R<0aw-8R%-6X!`E#Fl*f^kN2WfV^wGT7gbe+c zZH>p{_RjUyGZ-*_=1*H;grEbHE$JcT%G#h`j)a_?oI^VoLBe4NKNXieE3uxs{9=Wk z(=uD%HJ^`W>i9go*>2eA+yh-J(fL zU#I_Lf?-LIb+u0MvOOmGo+QkIbNb4{C-sO5y#>RIeJWV2YE@aC7SH6+Ci{!C&Zl%q zuLm1jJ3}qbY`a*lzn9!2p{*a zc%R2hruOnVF7HLRw^NY<;>^nBeYwRf<$cFXmWk0q(Uoy)I(~+rv6rnZ+D#m|S^mka z&#;}D)tD3P>|59-pT1MGs-*rxeDY((23?ZvDG-0zE_7D^Yce#Ixwf{pYhvwRp2L8f zgmqT!f3DYu|Hc+GcYOZ4VUH#4LBtCEW^Bvh-tnx2mW!x&TB3(Tg^t_hMT;8yBya6wY_*6pR)Q8a4(T-`92>rWG&=l|d(!s%_+?Jz*4OkR17xt# zSTm)$g()VKd1T32I2M-UqVjWZ<8prC%d9H|sbF(g1s?ENV6iDr3b}~9QXHc2)n}TS z3SZjrzfaVvUDy@tz!5bu3aO2)p~QyvCGwo>`TOwynnahe4wCv23uC!S3)LujE<$>} zom9cA&=f06E>Hi5l1YhHG+C+xX zaGnzd1*N$PdVbE1(C{Dek>L92sY3~7!Z~#-%IHgUePL z>#qe#lh=#&E`#1*Bcp$rGiyk7pVhS}SQl}+^TbA1UZ~=zBU1E%L@G*}RXv<^i6tmr*!KD5K4jTy9IA-g7caEKclX|;fUJVHD%spLxc1@8&a#5Sk zJB~` zpXUTJ4UJ!!5)AxsU_@bJ3i>0R!kmXLB`1@lF!)1oPbyrckB#P0txP=`jW!>HT>~LZ z3Q~jI%*{R7RjWgYnI9zcnHo}nAB4W^(px823o?nCnTIeqQ7sCUaM2=YlP4SaGj*m- zJw+^)Hs%HY-}5CRV)I)9ml*lmT?kP#O_xE zuIc(216Ta}(eNZbx9G87Fil@U8{;9QLA`Yt8&wk)r|(`)UkvNXB8*hMWuCG=#PMh) zL3X(%%5V)a(rL)V_q)&x5*SxS@_+R~Q)@1Gh>wnHJ6l6n2$Yz|*0?z*6W}_=Myl;5 z4~Y{#YZ~rMbNO%L7F)fpeB;&H+V=AN0JqFst>5z7{;zu=$_~q^MRkaR^qG>lx5oto ze&v7X)27VJ?hHue>}Yg-tca&Q;DTv)WU-uZ+DFkFZEG0i(Sqh0M;^QRfvqSGKr{k& zTD;GPfcLp`s3u(y`lb`H^EA(2j~yary*5Nd!KY2k(QK+)c2^~x1IS!2_(#t%%4RdJg!|Qc1{F$g^@Wc?=kf&9|ba4sk zXj_}b-*N3wekZ^+%1=PmEG+rqB)yrDSe3J$m_}KqK;{%18z=2sH9?DojxO?mChAXy z;U7$C-eN(NA1zWiArZS^Bw>qHTJdJjM^Raw_$%wWhzdw#r?#a`p8)GlHntR{umA%? zulRF`=;tHRbz!km*rM97px{hmO#{RH8kb>*IjUWbJk27dvbY;3skOWbF$**#m}=Bs za-@u57N&eJ0+)q1xYuNeufjR@THGy<4|2Jvp$n!ry1)=TCNb|xhk4+BffwBVV#;D@ zaQ|b4%{6A*-E2I;!m_y<3e5|4va|wJGKYy8X}RLBON!&-!4=@h*fsq-x%-UbMe_Y@ z7dbMSJll`InAN=`b^IzRmw);%Hl9wr%|LJzbZzMdP}T45S?T4HPD2s|_2a$DQ6~?m zq5nCxbXyqJFK_jk3{KH)5N*kj%(Azh8>T8 z``5-si57@L6VZzumg`+WEsj?EAJlYbtuV0!Q#-qy=;${%@84T;W|qXYn18WggyZOW z7i^&8MHXWeKq|Gb+f#b%dfxiOV4ObZo)YCYOfBoNk4@WBRff9s@&*H9SUNSfM)?N1 z`z2$@s&T%x;IYI&NRxCi1RRybBZxNfaIF>sWWv4@_TOUT>&@9~D4?HnpH12ZHt69MjnN{LUde24 zBnqTJzMVgma63)f4nUr?9!gS+*XLR{BGuVymrFZo?%9r=-LkC<6}|a-B7@!^RZwcA zn^L{~=2JaD@_dQ_7#TgqvhP6(Ewb;`U$3^Oe(T3){bvMykU9&I0sz93PiCy(ZCp>` zSJt;4HzeHr78CgOWmT&2mf=Bi>&$ze^lPadW=(NCc(>2Jm8o==)=|O?*`wm*NHr7E zdyz#QJXo@zg0}XPsxLjRqX0)&3A!lAWvf6?oO=~C+rG1SX3pG{rr%Y!C<&0O&ih2_ zj(_~~YXZ81%(8z1?`ZkhJr8 z!WJf6oqruvKd-a0dEcOMTfXv~f^c(u223(L&qtc{(clCuF8w?IKNkRCNAKO-Xf+u4 zs|2=BUZB2)XfAULE&VU|xi5beV zXA9C)1iDEnQG4F|jPU%g_r2(HB!90^MWOI85*b#Xy^c`tEJmFZywlLgu5!`=RUdXL zEtX2kpv0HNhlRm?{rqamZrpyx5n1hUNJ%?Bu0=$X)-bF%x>2_c61?7xVOTEw=LF-m zXacEmI2DF9i!1{6dc}XDe`3Nekd@gs8OZeJ`<$2<4JpFoC8&c+ zCrH^JcHDoR(9P;e?3zLT?0w3vw;JB<6jR`q2&0{s5dAXO_gkyE``hXkI%Nl!ctW^A0tKU+|Qu?4|;lacC^a&>;{ zaTctwP) zrMueZep@MNAnS>>`oEK`GHKDNKml+nH|%tiCDjpA0%}?(u+2xbZY_cyy9ao(yOD zflc2VVd#PXRK;YI8sXmZ;UhQ|xaJyhs}Us2g?a|ltK}i5&lATK;4TJ(1qcTHK8@U> z6Qjc%y5ouZWSCIwap*4;vCB?55!|15C6<(m<<9eN)^$RA%7UYG+6shkgD0v|oq-As zqog#6<#~NanhbJLqFq@7;;9rTb=j5En_;B{U0Z+Wv z6x(;W_au4((OKQ0dw#Z4in=YnzHJy$t^XsTVpNQ@PioxHD8wQaw%Rb6&EFX8yO+&g z)cX<&M@HUDNG088Cu10-#_JD5f1|>lTn>xtAtK%xa>VFnDi1>ec-#`_quUvH{e#CW zbP2pxAYl<;LM2mc-~--S1*0tPXnxk+m>IF3U;f&=u+M9KAUmv9eu-dvzZ|Ckm=d#v zCpYue({sd!H63mJd?#(tzmpU|-v>dwe-Z=~jWvT;A~nFb^2FzX&t_olbTw{F@F~it z`bG7KB`LxkMNK^=HN9G$4kv<NtOSn|9vzH_zit<$i(Z;TekfMzFX0X=yCD6G07vWgl#+?p_FaykU}BIR#`tfn z{LDK~c28VX8Cp0t?EqB_q3iJVSF^Q)8)QVHCge%#VwMJa7{@lODW4)3HNBRSCLBka zUDFMjhs6xm{&>i-`y{LG{eA6^dg{cp-MBN4cYJC~Ly7nxMo+G8DAGm|-!Echn2sBY zOY|oE!8Tw9eX?%iH)%F(imks?QAz_EtzkYRLOj$sl|eN{W3OTAez05QTQ9#6A&y{= z{#z|S-l!)bEfIz4SzxS7GT^AGt841&noNp_7~m&S=r43RMroM%L?!8-!I{-q{p04s zrEVAi9EA>t7(`|2-(WZk;W9PzRmr7ul4*geoUxj*u)bhw4=}Ol)l~$4=2G}nJ%LSF zF0vbAwkl4#ab&m4P?`L?-=T|po4&D~-CH^)`egQ;9c5sHvvqOnAIokfc1`*4fnwkR zd~?jOL1@iYd`@{*m1WabOKl#B0J1Dh!Z&>tdjnqaAbt9XN<~JQvqK%U)6ZKB!CR~? zp?*$vOprC9f@?fdu2ctQ#vGU$4mA9C{{-`+?~fvasFg80djsacFR{}!T;B`0hldO@-0;;TWXM7Z}TK}m?&GA{AGk1}M!CU6DB=xq)e57Zx0f4tDd_e>p! z>>-+xVem`_EpgHf@ymeNWwTcP zf+a|%UZ*Tjn(n`uQBPr|bS(hkuRZ(c_$ZNTjZI@JwA+>+y~WHWBM;w`iWyZ|J<*W4KnHvE$FtTgaazGH3LnyA1#1g9Kes_eCarv2T;GcaBUrVB5VZBO+GjP}`1{EGg8wCd^ zrN#RW8?aPH2S|J)&;mxTgiNd5WT)G#9F%?ywNdq_POAtlw_pq+{lPq!OR>v@96&>y>xi>E6ee->+xQE4Fj!2W^=6Gpa+d84fvA6r84i(CSOOwz5Cv@DZg15M_=p%-p-*flb3i6U;M zvU*jtf{jFCy;M|8_M8-?gkD)#ZYj1VkkE?sj1Rf9+~J&)8-vUSjy*mcNBVPu++y!K z-?9_hfZjkM>swlZyToC!$!@g5I1F-%v*@v3sE)OCaTF{9A~cFvV!gc7>U93hsI}vW z`E2A0b#Br>Y-z5AmW%!@;7dy=<~9V4zovlPnWLi*g{?b<2aGzppZN8-NwMy36rOR+ z;oFd*@s@qCDO9ExyZid6P6Ty|lR8Z3#paC1!nLGI$&4c<3Q8SdRx7Kp$Kc2m3q?Q+ z?se1_pN~_Oz~OBeqr%LIDmyqc?S^K=u_xyxl9%UNFLKUS>w`|h>3E3;9E94|G3&fC zeT9b$m@+!+QP$UVjx#>g7xHG1st;|nXyj)?sG&WocP{^cgnztL78XDe1#(TFPDR22 z>AEEV%(C{-)rcO_oqwc2H*DL*6p4!X@(%t#z}oIO+3?^281R-;xLp(2Agee*2R_`e zi>POcegBv{rUD9yj!uCpJ$eW_u$Ta;kAP&NjiRLspB866vrVIkCZPX5%T$_v3%R@; z5J;;xevVpr>#3it6!lt5%v1w1Mt!{)*i7vLnc1c*jJZ4KU_wL?nx$?brM7YeMQ=y`CdyBJ6l+TwA8GNUM=KYDNO8M7ui2KA+$DPiq^8m6k-pd z`zZchyBkoZR$GW;4#&ET5WFlLI7DKe+_)G@N= z)sv(4#J5eDNPH)(y%``Bg2XJnmDa~J*6Ndf`8FVLAk9FgBhN0V_1RS0o;`jqH*8&C z4OQkth$P-3b^N!{r1wF=*}rcXDicu8T_}s>MsJ(-1B`0J4m>s0F*Y&bg)ua-tT?1O zFE_C-5){fmyqfybimPZfX3^Pb3TUa^zCM{&4FMb6a6K@-_f0})cRRUL7My!m@Q-(a zLQ{JU0IR|V`05*M>*K#IV|gp))h&uYrZ*LRpI>$ItuD{5tgrVG)q{>~xr^kj$L*?c zf*MS(axV}c#@PP&=Y=StxO|+PjIG!17?^!@v1$9BNWAUr{(x2}Z+UN==u)`v5?-L= z_WT0?V`Mv5gbAWubZZ#*k8obD&m=FqVXE7lk_%MUY9`k8S6&e8mODh3jwcE3z0U@O zHr|RdA04h%Q~|L2Zg!<}jH}6R(xxFUrH_W>YuL$6^Yw4gKf$&O|LT115jwll(8sLj zChzqI*7@g;kC89x$*;nqj0WZBgDf>2i0`Zhn7-^24W zl9%Yu`abf14u0@+jfuGW2e*hb>ox~XL@2cORA%Nn9b|s4=dCnhmJ4*etWEcbO0&5PnDi)hSeP&M`^ND6S=}m zZZjKyM_+Y-#y%SU(USB#d%~a;BeZ7}+wu3su5d0b^7w!96|a%AG13wZGm*j>-{2}|E)w*6|Lg2 zyK$r#kRFX@Q5I$@W+6hz*ZmtM!kP;I;Y|QVkJ7-VY8`Q1)F<5ZAcX^5g0R9@(Tx+TP-9|95yJ{`)9FKzKJYwyV(s$b@2DVl z4K5SW`@gIe~EnBTzMJhY{S$IZ>H#+G2Qk%ymO?srnuapcaIj!_6o*5k7& z)s((jo80937;>RcgyqSU$;*d^7BDcKJOJpqv9VE8OUn=}tO4M5E0ORTiT2~qPd!rAdP5E=fl9!DKOi~+R!UyZhmvJm=YO>ON0 zfO&_kVVxnR2&OK!mOpM5$&qutFgjJbS>5^qOomx1iPHot~NHp?$Wi{LMy67zy zq1<~dGh)IJ(~PP&8l>OOIq84~kl=s-u*`K9B_!Fv{zJWdWMjcN34(Mpuj$JsXPSF*)MSE+2v=f&1Y(jpE$PXYmX?-@ zqh-9eU}{2=bfaDQ{N^c`Hh)M<5a%o|kn7V%Nl8|IY!?Qyf#azIng*Jko%fphpUuJ6 z+Njp=pqUiZMWyOlo>C$uzEa>usmz;0no}~?OA9QS51NP7cGC1U4SalJoLb~+mE`K~ zr1#GxlzSbxi)N1|tePzT5P%C!f*7}qyMQl&pO5c7ZL$oQD(V^G1Ib3r0-v4)U{`XT z(1$pu|DWOl5G9>j zhVSp;85p2pNzHG1`~bhHP`PCGK!p(paOZ2A>w70B+51G$2c+p8fIgM?h_fLO9}p!K zT0i`r%w97MNp~0U$$dN(*jJ@`g&Nr9*V<(N;qWHW<5y!?kKeN7J05=bsF@7zn6hc& zjRz2w_zqkDtR*(B_(39oGOFYD(V6)0#83yJzMtf6+0n@q!R3SqT0W1}^j+%8%ZExk zf)x^jd}V5_8+1v2_cmD}+&X=}Un1j2SMGqjmp9!N&5;sOy5cox{x!GI>zxB(=CcEk zli!qa?FT7`g;BM}0t*t?xs}Df3!MPc^|c<|eM$NCu2=e&$39PQmOUdueJ5NbLw=~o zkLBU_?#(-)5Kjdz3_+o>#3k%e((;F-r~uEn{Hd#IbGx|_TS`Klrz)o{h--`W@2xGV z*wwzAEak5pIGh~YqGtH4luRE_aF-T_!o+W#A643y&b|dL!Y4ZM>e;o^(>R6JWI>Sx z#%xB0FWQa<=SM>ajymLL#h-rx${Oki{{IMRT+H3^(~PTWIz0q&vl~>1ziju$O4(L$ zXyOKP4E5)*-iidSh|a#V5cu2UEW-^UMeeKT%u7y)!U(496+tF2+^Lau4qAS@U|SeS z#)faY9<)R_?>*#5#a=m|85i9cFJ%bB?1|_oiRnT1la|etpnQ{*pTIwww6fir5+o`7 z>`iP3F}h!{7*Vv&mWER~_eO{GqNTom7Qsvp8o!S2jkPr@_v`KJ$v4=VfM6maO&Uar zq`fM9QyYc}o5k4a#%n^Z{6%KZBHr7IIzy4$6dI4+V5y^#?B$s(Eiu8{v0!UneE z2p651I@x85(GY}pO-jq_uv^Imi$@sZ z%IiPAuB&jSNcv>BfiGDx_M}6-Qx;xFCVh#BRe%y}1Rgd>S?|mY^_6FgXM2tl zx%o1`mR17^JIQmJ?LWp`Cx;EilnrB|S^Ia#AboZHsRWGKt5VhS!^1;Xp(eir&sPAy z0vy`1*#iLCL+In-($cUb@LJ01>ueV{op@$uX66MiyJ%v3n_#Uhr8+mPZi2xrioHx=uD-CZaVyC{d-QszKU#-(BQ4CS26WK@uIrNpEn|57z zDK?5#8J#xnT>)2zHYGwcrO$!Yyw`xM{d8O*c zg&bAmuuKlfk89Dh_N*FAhC^a{3w5?`H#b1-Y`=TcDrV?zM9+wYtn<@5oomHA(TEMN zRoM3zxIU!rIJ;`e2HvrT^4aFI{WmszWvPD-u9{sBsJZOv|0!Rb1GBS%Z0xY6u1zLC zEv^MO@Z_O>k?DA)bD*-?-f?I2pAV@v!?&GuJUws1&VZO9Z*v%`?V_yf#A6}HdL-5m zpUwgBM?t&A6|NR#Ds2N5F{ml}RcC`1pjQog*!2VZPU6?C^C`heIQ=QjIr6Ka{Ktn* z4ln4uQOflF3F`NJJTd*Yjki-1xfndWi(QWWrYs$uchc$)$A5`$+(^(3!&vhY4Y&sC zYKahLYe_j#Gi^IOb!7Jsf18ZFClIZ`Ze+XU)#V+*Y3h8&Pp(=!zk?-}2)H^ji&QV{ z($N2!&i@}HTf9InH{4<+&J_@_b-1DgN+6@mp0V<3saQb)d&}63gr8D=UKnkSdvy+; zjwquN2LZvgn-%|c5-vx4xC2wHchxJ2Q>`aV!TZxO+{$x-t9nD zX$otZGXQ`?aCE4=xSuZk)(Ts3`9h6l&)JpvA)I2}GMnzvpYX!sxl^K57>%$a5J3`$ zZd6QSLy#15m7G$E<$oWbEXn)WIJnY(rg7=UVe1JB+YpbMHyKmGykzoOOg$*x2j8V? zvct?L{6pB1ijeQX#%;7B0+YId{)5%RJ^TAs9Ru(w4gh3u>v=9EKf{gTue~?LLtrg;|v1tEZy%6C8pM|Y<*(jncAbax9#gLH#*OE*Y|bfjgaQx!HIQM;Bd+oK(bsT%<)Ug#`lJlc}^8|~i#*d(AB*v~ignpCOy&kcu z;1Rfns04Mz8{;T25GtNx^S*9h?StOw^3(FI-N=ZYqs|$x&vj|9dn$`YeDm(5N#y3! z6SDPt5qPk7UH0#G%3??D_TSev>~zdg9llq_Ukh8S;yIb3s=0xX#+4>*yo1hQklw2# zRy9v;*DII~1s@1vwI9Ac9~l6U!2Qj#eFOwGocD8_a^9l$=dxKNfIkMf8Hdv~0YEPX z{Emv}7w}*L9j>l!WH@pa(Y{qsrA|WgDcKy`Yo3H@6Lg@Ion@4spnZ(-wu?#1%GV{y`H}ADZDw}q$h#9$ z@2za8{^d_06AV`JUY^%qGuNN?KJt5m5*d+If*n7GM~H8C>nUTZ4`y7un}sY|#4SV= z(4g^9;ApU`H5oo}!v+e1w8;6?K=#>C0(Cu~UI0tMtd-ifdeMw2xTwJ05<37l?#t=x zedp7>c{XeM#9%|o3XI4@x@l(N%pq_QK)oEVzeWMb5IF22IFm_`;RDcU@*cw<4Wl-{ z_-2C@zOypw?6aqPcEQJgop%>yLYGf{_e(J(Ije_YKR>&t$ETeA-@g;IAX49#i_d!z zJWB(*8q)1$ao!|pBTwKpH>_u3~x^q*+f2*3v+~(u| zdIw>Mg&~e!wi{2JC3ubh*pDvG8n}rvFfb65i;D1L!aS0RnVXMKSZ2ugX~6gFE)aEb zdA$hzqp*}NDeJ1`V+UBx_W|lZiw14)^FCbQD2vpa=UChNl_Q9nn6H7Ktn6O?jP-St zukq<}!!#oCN=P^-e0r;|21fI!TK-X}kObM-7iTx)U`C|I@`N2bcoa$w^pz+@FsZZ!QvaT_)p~Xbse!7*aLpPC0mb9=QhB62yiWrq|#&3iln~U7f2g;zqJZWmTXaiKJE#r-9)#1r>1{7 zroi>OlyedB7?h)UU;Uz8Af_XF!jU?~O=~gv4mx%8#}W@Me#z)ikSJ0pw)Kc+6B$w? zhr$X~7(=+1>Y~%EYtkcHQ{Gi>4#OobpTT z$Y56*(y+|lu_6Wq1vIj}O-M5I8RYgqwT@qcUiF!vOW@JQP^Q)(dL)TiSZURZs;BX` zM>t@B&tgH2&pM)$p04#_xDE|^jrfhu{BDIx^mhx$(S^p6=djjW_;CXBe^~&v48ktF&uM0( zX3iatCwzc5%3L5H+CvJsV<55#QWc-^Br>wIYjl~0YRjF1N<`x8myc^38wWD^-2b|@ z?s$#^(kgHSd^aY{?(8Dj-9ls74%k6MCH5VpR><4R?t=~mD5r zy$2O-qh#Zo)|5QrYwu_1%f$?}_^(@%gInJQg5o+~`#BbtS2wp~gvdsaiG8ln+x3a} zLH;*~LIy@GmwH5%1VCv)$0UJ*o{4E3oGjVQcDbt0IId)kFVT{=dw0^eZZn&|#=oG= z|8ku5eG#Coiuuva6Lcv^H>M+Ki~kvuuGCQjtBtJkzxTQs31#Tp zYHoEYl;uo~9-VDYz9&c4OEgeQ&Who+9T_y0>DO%=yDws{g5S#N8xs<5n{5Qda&r{_ z$s-ES^nLqBGyaJ#I9|!nw_Ha-Mk}gWd2smTOzT5!>AapED`m)d-S2_I7Z&ZzTrt2O(1iZ)an3P7wnITkk+kg|pqO`8dmM^?XTDUii!AZ}L>2nF9yq`%J2trx$8TuX0A$?jTIaVa0<$@F~ z(6KIm^&*4{8x=reW4d~|xZMl_An;I4SU+!#lK8A`eb{S7MweD>DoHgWDP%bZyb|;W z`p_e8RceyM{wB17k*8UBxJ2QS-T&L&F=5+U2g9+fGz_hDaHu z9_S%tR{gh*JCjW(Qd)!F33G$K?B2Cn3{5)<4KaoCM;{S;M{fvYffd@Vs0&&=A_Pr6 z+Kza7aj|s1P>%EMe+N$8POLDQeq#{~HVEU`8tr||@7+zSYv$-<b%&f(LLr7P={L6xh+vPc`@D7A>B&j8?n9UtS2{2kf_V*hG}zV@mmB5k#{)m`{$hmL^X4BuVBD*h zsrgh<1dLo_ic5&;ncb`R?S_pNenNx&hwT2ho=?iNPqz7>cFnNz_GcuS2HLp@ymkfE zb4L}DuEEW3J|C?{oRj`}yBRILm+JdVUWG)ost)_>i45mplh#+GEb9W*H&#ft8vtj} z(DDcf7$=zs1~$wWf}w&{KeT^&03-@3s>j`i;6#?-t`kSMS;y&+h?N?=0jFi1+sRTc zSrCb0xLI9a4_wUMvAyp|dn+hRmhmdIej==YyJgINo;QCwQ1CV4O|{Vv?C{u zxGD!OcX!({e{WiV2Sa{hLW>GvT)6ePs%FXtt@xcOrHo9A0P(xavmMg)Z;u}=<2~$h z?{Hz?pRD_K34x`V%c{=D5AFK6*2vQF??7z`96WDS?O7{vH0Tw9j_u`!)x0T-oW#8K zQ{ZFkq>@X~jb{GA{306HEP1E#@fOx=MxIllRdB0K~|^{}d0og@&@G ze_jn_3LSzB#Txe!mPz;r3N2^d4ACYJ+&~6}rqJPz$CNeO`J3Z!ry822rYA?WDD*A@WeqHP8-(?lrBRg)Tk1xhphN;M5}0pWP13@D2Soq8_%7D0;c)FQMB!H;kJ53K?Ts8p5+O=b zz|cc1An&D&GV52fw}1X)ff+>V{~jSja}kjc%#r?noa?Z@ z%pGOXYb-^Fg(x61HcXMdK;Wu%v6w=W;~nEFQxiF1V}n-brfc1m32hSD*GHwGncLFn zB$qL2_E6vp#i6BAF0L$SCZ1`XA^pH8Ma4c%K{*L&$>@LC>uFfw|K8!N_%A&2JXj^7 z8H+~C;&(yJT1K>U0e&i^d9%6AUZ2c)&3IC~y-~CS$0xgU5OtKBTp!z?h8sOv9U2%aT!hHz{ZCGIo!@V&F#w4Pk&Z&Cr*4gHK zhUUkPuUnvn6(bN=<+<&#jo53yK9_Q2>47hEfy6hIww1XSUi)2D_sT(KPP__)yx5m7 zehvW%xYXV^p%eEb1|6GQMv=clwp-obVB7$JA(*>8285pcnLF+R z06pIshmvyc;cIuiXcxUSRJuP3IEEF2ViD?Fg$VIld95zo-K87nePe04wX`^*TWreJfzsN%P#N(uhc zCaUko<;0tu8*3lUxyiR{fY_&(T0wAgDnAsO4jRId$m#S&;0@1Tw?82zZw{(Q3l1aR zbR4!jFhB#}2GB;!qgk<-B2fh2i^(Hb{@->%*+@3w;YQ$QI&)Cl**Sr_{!)Fu%7T1w z`@lgUxBi$xF0InP4NA}-6mmW>42h&q3x-HxKFpo=epTaKDuz3iYFehXg$V07=~Ki@*e;2>bPnnm+oopAr>~{+;Wd?afTj+qbIC z$yHbZwMV%gT`vD%w5u<% z>SZac(DH7)7@U*xYP{D|@_IhGnF4PLaHCoi4ChSQHm87`-<#8ro3$U3tgghAh| zsiki~QaTSROz+<}eDKu&ENSTf1S4j3csjXi?K$?r+z zHgICX-{WA9IY=Vnk*qrxB%EId)ph6B^?cXoN3Z8&TQib$98%Nuc0$_25P1+Z{;g+sium)$_X119--%vgQ`n!id_(D93Jun?%iX z03-_Fpfe|EFc4*<=BvNb7(t`$P1h3m8;#aSz`24GR9kPD|F=K(9rv&*SdhtGHoTN_ z7*3fW1iG+@j}Zbf*PXMzzu5!#))m%e)M8|uIY|5FBoYl zm1(vlfP^4_D$)_W!4PJKC`ULx4|(t#*62CT93t3`2Qy3hD3-Q2P4O9+MSm|dczf{Q>IBI7{iMd$NZ-}we*+>| zy0$z95o9#2$PRS>-YKc9mXcLMcPptjxdx5LBEeAw&nEWuArY(!My;V?Hz>_*CiarC zc2`+rbPdC!b0K^c4S0d(AvTtku~YFLf>L;wLP-t{xk)k2Ljl1ZRgFVVBq5rmEyZA0 zGF6AnK30PicnDkkDHk$05z)Uu71gmR>fohlb>!=pwEWQ@uH9dPDV?X?UuS)CP8m_M;SzjCZ`&tyVr1+=j(Qgr4h+Dvz@lV>vgsObis6~#V$3qc(xpIa_w9i}fQ)&G8a%};`8CXz6#05_Iz zavZZI4x}e=gzZDeg}c37Hj|2{v0TE1u@7}PmlgilcDj4oI(VHMvpo-sWgfT;&lD-p zoA!f|Ie^lp$`^G&8>Ho0FE+bE9`SD0qo6GsMce|qUXB<(H0Vd@pVJD)RmN~8Pwjr6 zwF+kP4wos};&~{n+_E)fSG3_GqFsG~ned638lPy7!u zr=6>-L=L&d<>j)g)rL8Sl+W_|87u~)=pqilLI6q%5k=E$y24mxobe}4ONO9c?W*_o z=!6uT6~B}GixPv>`~mhX+ml8=F3C$r$;@(Y&i%R^JG8iT*Y6^kFq+9BwGv zCH*v+kHWTp*trjeg0r^j+cmx0EouZwVj`fF0=Y)#Ss$)}!`F)d-Tm3yN;8ewx})H$ z2^%xUlzenw&^h-}KXuW+zCYNdT>p0YUKsEEE??pMk}X+Db$?Dl4z^_d_V?<@V$sQy z8y;?cqoz91d~}V}Qmtf1PtPIW*IVDqo?9VRF{Zn_oqMOgS3q`~(-M3-V+COclD|2w z^7&I6puNI3FrcfOQKu~r)O(T413-Ni((|9;-+_F<@GhIZFeh*8ePh1QTVoC&8goSK z#wR4GP+ju0Z!#&>iQ@IW4Po)F%92%-r)(PjUVCxq$eEDVwP`Ydp00U~=9df!G+l&0 z=;8&r6LWl>O&cRZzC*w^J>#x{thdUs?QubHLdOO)%1&YDt|keplxdnQAJYYWXSsynbgqLsgIx~-yKz;`cEeM| zPDPG=8po;JNLXpQ7Ko;?N2X}U*3dW?s4Z^7$U+^X+qi#X2dsQ$7S0jbQV*^ENRn|g zsDbHHiH4ULOJiQzLk|ZZMgy;MKrv1i^v)PtT}KSk&2Wgi`89R#dxwYw1|<|0sj>x8 ze^o=}Tp?pZoWZO|rA=!(;o$t99$XWl;ZSgj8;WfgfA$Pk$BLq8(9SR6crO@gdLM>V z*DslU8q?P%b^`U4dA1|aD~ER)2#Ol5Rl#2>u1w=)HyqG=1AnYJ#&~DM>M~SIM{}j2 z1#-fgn+mTG7O+FB=OYABP z>$TgHncY9{*qwK5n@*^v?(Aih!7qc`KRAuY%o5t41<+UsqQG~A5c=ftX5~*+5f&tP zm>Ef8mA8C*Ilby+7pn$U8ozZ$zLoXR!d-VxqY(+X-nYl@qqxps{0b;Fpo{nAZLXB@ z`tqfN6+U*1fgq`Hai9z9y3jI9|4Mesp+7ii7d7(T{37I+yF&*^o>{w>HhmZ z%DRIL@TMpr8F4CafTlZxAn}LxaYm&J6p3V&qHXp%1@5wy{rT({_MTO}Et-Dqp2bC; z?AP;{rJ>53CcPfIr$Yl;E4WQHBTCe z)xX2A$DSqRJHBW!3P&uEJA(@?-0RTPlLK~jEox;j!1~W>p88j;5KUviq?X1QXC6-- zGw)LionO*{_jd&{LD1dUF01M=61+X8SM0l3WieoC&WQBM+{(kNPmHHQwhTf)X30aB z*wMyyDtmkMj>Q<+Y#wRs!9%F?l;>coo^!dQfS^?4as9i+ZfAC=CLQ+b>yLxw!4CSc z`bLhpw#32Kil$BN;qny%y4CuxXsy@Kxrxc|Ak>X(vCa66E}pzD%(9;|`NTApkKTo; zK%fNUpd69JLMY{nPab1l!xp3z?I`;vL5~|n5Zqz~)nV1n^(Ed)Zp>qKe5*V&sT@pg z+?!OndO#!yAVEZ^rin8~Um!zsQ4x8t^30yMse5Rx935rEDrZ@9&x0nAGr~;%D*d^S zLlxOYN;jPSOF^Hs|L?p^19ToGlYjaLUTQZd*c#bo0xH)$NC~$U>=kPP87F_zATqGtfjPl{9R>h?QLDx`35fQ1N z|6M${-Siq?4&Q&Qsga};q&1pFQ+GRXO0$0}oT5K2xm*9&;iG%qGslip$FObW@*CH{ z+aE39%?AR^jy7D|PXC@!HEz#keE)Kt>=EOf=Ifr#S~oFmcB1-TUAm0}$ z2${N{#sbn@0E>uJm^`Muf`aG6KYVIndzf+gKziG<{h5@W13w1X5I@@Iy_Zf-FyToJ zHp@Y?NW|*(CyUP-eUC1MKW*cBaPtt1C_?MYti_a~ixW>bpH-Mg%MeS20N~xbPHGK} zJ-Mn~;IUafd6#vk$MDo-8z})_6+3CwVA%lL2|?p31dgL%?eADVf*WygI_TU4xa;uE z^U*Kw19E?HZ2u7U)s&+1VrxYI2vl2HqftiX4JMxBE?maEnd%rL)}DpkXpHN1(S1(f zz%%3jFF&fn_LMK9E^AVcg5Iej;^u5T;}d-M)~(wpc$qFoK8V$U2Mj!Ke1Y9->#-u& z#8{mMNtut0Y|iU*TX&4()E}i*JCwNhDWlh&7E99T>`5#B9foBwzpkatG0ugJn_CA^ zJG&x|&>sB7TK(34vdtsxg^C+u0o@Em?ibKDqF5k8nr6H8;%8bHr6b2mHNfp3ETXT8 zm1Z#a>PF(&(OY^}*puP9K;(kRh-)ryg$e_DnW%h7AqTUWNW8&b_Hjl$A>MJh?!&}F8qkTcMkj;vn z=r3nV|85pR^BtZbK&t<4#oSkrAWRvImC2X&wlW3&ypaAZ&n{!c33IL;B>AO5b5xQ3 zYPP^qfUD4yMK$P9fa6R$9-KlKPO@n~gCSGO?jh`A)z_Fd8t>pl zIOBPQIOq#Yo5@Dls1l^rw2 z$cq#5UE^^M#YVO5nmZV~tQyEBoDJYq9(c(O@#25d0x{4=x_yUfv+mi|fyy+;b*lQD z6Bx#&^0l59a7B(0vT2Ms7iS;Yc11xcPW2x>)SRO7r?ygA>eGd`_UTCCQ&%h1p_N)} zJWRv{)87PYCWM?U;fVkAt(jyxDg^^~PJivcwmL`T5i<~_}V%d32N#2^P0r5`nWg43~iA|cH;}UqMz{+eU>f8Y(QvYCdJM=(=_R) zN&kk)_nDjm5@akH#Kd>OpI`-#xT6Whqb%tH8Kp7I>hSNA%2%}6A1$nme~g(?NGqGl z!b8iz)GvXO8^=E$FF%!ePd1!p(XCbM&-ry~J!tqJPym%BIKf2A@G+qSOf2yX^qm}8 zja+zuq{u1OOnJO?<0pyM!mW8_`Iy73G%-7 z#Jmn!^;tEv*_*A*`4>KA-RBG| z``HZj<$gV$wBl!9AJmT-F`B1davE5YE$V@l-<*VeHayq=b-!I21%g`HhTF#?=Rf)# zam+IYmsK>boxxOG=B_R=6`diq_t(fAwaPOls}#DRSUQ!%{3IX!o9N9;bw~}Z^!<14 z5uI%}^(_H~(jSt4S79vzS5A@Rm`-H~=rp9y{03PC^z)X}%da>ENmBWr_*73~B}g&C zvaHnegU02>nlLf6M89BvnUaTWkX>z!PK6B3zGsE2MLor5(- z@)OgIl?T2|vpG@LD&rj`WMm!9{&h<5a=o!=1C+TH$liWsFY0h+|2I>S5~>WJsQQJmU%P%>t5SW( zQ(e4T!=$5ig+nhhoZAhs{I z?gixK^;ue)J{=K$pH9i)4`E%(gYEdgEI`PtlPCL-Hiw^Uv|4f;fu5ssha7abR>quQ z<-)dHHYs z`79AQFxJ-o1Bh^1=#nW0T%?}~VH#E&_Hh#5B#PnCSL@}HcMB{flC2@J)izlnLmhsR zxioqhoXtp9G^97L9q4ydX*3t=twuZ#3+j%aJB_h)aB)r4xqP*iFS1UtO!{&Tdsd3W zlxYsST@rV~#qc|HL$bbtrqVG^4E1w1D}gP1HDA?uOOXz)4xhI|7M2{#Q+RUYS1_%0 zrV;!r=G*84M~BaAB~p_m(K#`GjmpyPlPC>;)HdMl+EgUmZqU7rAmp8}UaUBIHn92s z)vSP0(Z(8~$Sva*)v{#uo{T{VZ=8;n)zJa&0mCpsIa(}r^$%7dUtxO(*|J$O9Ej$? zm9Mmhomp5G(EgF%(`}b}1d>M(q-({NiHyb2DfadaghF*PFkzG^x@3al1ko7Wn~)3C zgFJ(zN!n#C#~5=_Cb=jaAW%MQA0j!VyNQLigRDu5>Im)@S&@6OHW;|@$htkaIw)t@9dnFcpVF+xVle*6qf z?%cu5Pq`MHyc{7oai*ipOp|4l<;i}1h&s9|j=qb?v&)rN-vsqFUOdQ;P7mF~g^KEE z-(*C9yav9wHLa}!aK!v(4Kk_YW){!efd`EXTRwe&7%HgQ%}NjjEJDA(^n!C2fCK@z zO z(&|bRw(=lHlM*A8wC9AS%)Rw+TXjKLJ2>i!wOBs4HT*FDk)f~L6;DTOt(Hry65hQc zrd9Y~GIVarL$W+1%^<*LF1bU&WX=1Qq5V zEUc%-J!#9k$+yad5q*PqLuMB=2sK9DrCW1a6*rv)jJ{J7>um|Jp$T;HeqVC&-`$){ zJod~%(5#bq)-DLaw5}Sl;8oYLQ%I|W+3?p@6k!rpm{dLjJ+^dasp-hNI*=~$H09vZ zkppWg70DBSj@`VVWk{2%67)>>#?9~M(3qQx=*mk|m zDs!^PtNV^6KtRm#ww?$IhO+3v3Qo7-`MvQNalj zrS_b~WAt8INLoh}mjexvFBzYZg4NIsTSfmI8EZHPjW{;z!G$%m`Bm!HNc*yNlLm|6 z`-X5eEEM(x;mo-F4WUXm`Oz#amIE1^*mYvTT7f9oyQ52_!F2M&zFzeDP_kKteDi_u)oG@)W7x04u?Km-)1;dh+A@6 zGxq$B1x?xCzXi9?L9li69%G>4)L`{BWN8lP<3`KVW3t8CR*J+s)l^f@EaS+M+Rn5u3GAJNqa!CdZ`FYy9@c3cHh~KQ1U4;O3)l znx3>sd@4E{qiobnbXVT+m!J7?Z|%g|E9LB?&a^)#tTjXB*NmqC1y~3+MM0&}jw}^X zm~fg%@8os{cH+;qQ(ww=f1*XiFBJU;Z=@%zF5}IbKZbcrQJ|GjH(U2oTE~C@qp+3~ zlfl~mnTwjh7^Xr#yLgHWQDlo|>m-ve@;{+HFkOw^$JgG+cGYS5Gx8~UiI~vXILY%y z`EJl*AF*4>Pu#ddSjL}WX@<9pHb{{WG^b$#<&5oopcRx;m+fskJDPVMSXqnPgxn%0P%FVC1tsg;~E7=<;}TT`C^} zL^TJ%w1bHb?<$aKj+n#ZQVf6)Ab%>rk8VYp+Kv_*XtL^SN2G-5Cp7P_mh@xNev%G~ zCpo&PsEplSisoy?tO{>%Pfu^}XS@;q&l+RuHi2MDTkw()!}WSiH3ap}Q=40hdq9je zOoM5(yIJo_d4CR?EK9b$#;xI~ZR@UJEycPjn8s>y_WSWP!qyyw^S6wWkJD;xR{ZVy zhQ~`9W!67QbU(~#D)i%6G5I4Rx|d!~RI?MhZSVQeX!_F)R&XPcmiGPR6ue{kgkCK2 zYn>pYMhe>h>QY6#8|T>iLz1?CEQXR8*Q2xR21DtOgpBL?jomv=8EFd0Z5feOxPDE< zVC*@hqteRO_#+sO^xqNIUX3=qN~`nn0WY+_rjy^jg;&3!|6xN}Cz5_>`Lj8}*S+jV zJh7?(zw$tPNBM7g$+daxmOi3XVyEShk8P;C#RXQ=Cd-f!k4U+RY_gQZd8Ez>(vYGXKjU5dBsV2Xjksj; z6&twN#*S?fb^E;w>z^+v%$O^){+9WxYB|((ImJ>>a!VVm{e*DOpW!s zc$5!IV<_}Vb+Q=hROFJl>*sLQrayjZF5@d!;zz_bX?JM}v>ATz`}NZ~ipAn!M3;h% zJW^yy(l%O9(1=HyRl%utC2pUGKu&5SFeyryOi>M4AW|L-Jqe#HP z`2p5`0LC4(WADAA=Lo*^D0p6L;T+K#Mi4q+qP_?^aOterL2rcp;*bL!U7(rW;;tN= z<&|y)g5QH22BkUihH>>;FG^DS!X}Av^>xp&><9NKR*Ot~i^0yLGczYc20qDTpl8bj z@pG`~U6SFWEECDq_|2i1k28Vdd`B++i=C&$b!$M%EsBQty|%H|C~kQ&ef?aLA!9+_ z%<=SzOW4*Amn3zfLf83QJ*I@OtN#H*V#kXm-oqn(`@egmW}{~9xPzzn*Sd`_othSv zmyP;zf0KnO@#^+2DM4~#;^~@sy;hd(Ee9`jBIG@qvo2~L0;IQZ8H%Sx_Kw<+x*3(A z*x;+#kr)-eo^YFXbePoRjIP{IgLD`82mEn5+ydoL(w}n3=1}12@E=Lw`L#Z;R%@nX zD$4|rP#}sXBBFJ_G8RJGhC8lcYt@JIPvFJ8McHT{A6r36f+Q$s_TpmDGQPI66)>nj z4f*vMz2)h)hl0c&#b0*+#vlBdzff}&t6KyGISVMruOI7|7=_@tKc`W(aq}3mr7Es1 z#g})M+y})b^?tqQFJl@CsNsC(@X3$ z#D}>D$B|ihNhK+0Bt#uq_(XafBU3J`1F;&@IjeKzM6CjtI4$4trzRCxcdYsvH0;fT zd2d(AhikY$2|rbL*=spWYqY_9DAuS3c??Bq$GQauvi!P~(UIuUnoWE|eu@h+8-_kZ zgZ&HwAB~g1VmokS?;z4_vH+XTDU)4iTv`hqeM-%iV9YFuQjv~tNBi*|ueBuy0SDoG z=m1&kX^P*xpIaBn>_RBY%E_D)yv0q(MM%MQYw#1;DWFqa8?ua8NeU>K)t<3xu;A1Y z9HhOa6xJT2;`aT|Gb_QAR>HbKx$jv6+F!&vaH=KEP)z!)!-#h&zUi&w#vD!dw}z;0 zW1oAk3ZvQHP3~zAem~{dSA}xxc>DA(yTiw)O|H|#-EiY3&6XrXZO917pgI#R$b6N( zeP)aI?iLcPrI?@aj50*|v?jwl+5+M*u=@tpQ;J(DbQp!r@r+r=bAw>a={buJ?XVi0 zVNfh7$!X!;l#2;o<;`+1`FR@VYIaJ>ybr&hwQ^btD9E%1?o)--^qJ(uK9ir~r zSTjo4YPD+_yBjvEO$I6RTzTrSCW3f1Va@9l#3IA~<1FeZHBX83plJx%S?z>K?%A*= zw?8M(qKoXLMQ)m2w^<6!*)R1y26b+ZJKNw-FzCWn3dZIs-c3+Lkg|xdk@Sdg*#5&u z3_Fd4?=E5@HB4`2m7*Uh7YqIuen0Je&63C;>Ip@~M}hM``who!K6IJEAs3z_+4S{w z&a}06`9l-9E_@KzvZ@sQGYRP=z+BrJ_Dl~DhFv4W zWVqWsjM)iFWbJ2UWw51>O)jAYU#QC+VmtbiPjK$z?lbH;uWUkewFs<1k=Oqd@=Rt= zmE{o&ezJf(&`%{k$(^tMP|$4T$ z4Rf;nm@iL7Lg%|0ucB#|4}k*2$IF)F4j|A1A{%eP(NsBVS!&FT2E1){b064wIjAUl zk8};sMe(?rJ>2o}R_1W=S|J5%PLVsJS)u`}RF?Gdsb(r?$_=VTy zNyAk14Yn;!X-?)Czp&B~^;}X?e4oUznG%|C?M(%v9n_)NiQMg&-u=DfZ9|$d5-pF0 zNrX|M`(1A7C;=^nNVt`}bFf(3X)Vk>4MpLX_J$>MH*KMx+7p%PMHZPo+@Y*EM+_pG zr&qOwht1-}i?n@17MsMiXyUpQ8EQm;BIw$H!m_hc2}j0Ygn)lwpt&h_%w}p3)O2 zdUNCEIL?|We|NHM-%O-etzD_8T-(|@GIh@C1s7UO@+Fnx>Ff%B!XSesed2onEF1DC zL{R;q3VHO(`+lDdiKugypOBwgB7u^|f&tDxu4^aN znEUavguME1*L@}qh7h!p-`1-MP(Zm#8E#ZR2V%f)s`*_DF@3a7jjxuo8U{<*tI3nA zpbT64*tXiRxxDh2CgQDd9^PM8UKAtDZXag|$bPdFW?KZy;&utZ-Ot zMxIOnlt!^39&Mabq(uY5^nX8jf=$3Sg$U{JhAq2Jh?qY;wi0x$R8r0|+h zRkQb4)sv+K6-SdrLP3@&%5MeH+ej!S8F`qBeqY+RvmI&C=6g5$(7zde@g9Zzsrj=d z`tWB|BvxuJ)dJm;_7fs9q@@eW=|iSm+LsPRH?beSgmb za!d#H2e)tQ+9}EDO<`WBx zi@B?Imw%_o$H&LxyVkX%=%^6;FM()IT? zPMH+Z6NglcbhX*dLf>a& znT`Uo2l$iBx{NO```#3^MFtHFm?upZfmG2p7#5f|^&otPd!DCoTiJ&}X-J;UPgH zr{{OhpnU!yl}mYi;^ifhS)I5eLdP$qN@vhOE=!`;1X>G2sm^st67Qgv#2>os>Gxg8 z6`Yhl4cZlW3QYJh17KOl5-?;!L{Eg8CV*9V%nY-T!ZWK*ml0o~AGq#gN?=17aqO8b zdkB}*b?-+=t3{0ZT6inp6+rElPmH&Fp6aw+dSK^1&fIEZB*6j@I(iT^omd!J7-ZSh z!SuYbs38%2p`v5lb@W8RgmYjGY&AS-oFOJ9vW+wb zN7_me5LNv|Nuh({)+M$asNfn=%0=OWl%eU0*=#Gg@Q4T`?HDEe;sdxN5r>3PD>x-| zV)J5MLP=DQ_Q%x7Za+4 zK=SFR^CfzFn>-QmhaB}&&H8?f?-SIz&*O(E?!DhVp-(sNo!e`Ha6yiN2R8lYzIRY% z{Kg#kQ+5r&pDvOA8<0mj@5k(cVsJn=%it{g_3`!WX@{r(`SoA>K>~&3*S%Zk81hr# zMaw@rBwUT^XNB@3;r!#2B6_m0baJ>XlLuPAc_wUWk%_4V%(_lA;||fg?*hxF^lmfN zJO@6URHCAL{+aq@Jo#?wli(*;Q&Wkr9v)&IcaMUnk8R<~xue}%ke@#$H@|K`0OQlu zgTS}j*7Ye{_fJxQcG~QI%2XxvwO7{%rBK-|1?PSvaDCJB+pqt|2RzUF5$!vkaT@Jb zjhwC1Dda$wNmOcREWPpWM65Y?|71oZmta{M8YC~2}AvsVzH2m zf#UdwNEyo^l7uziVWF)a0%w6qy(WM`vY?P|_;yn1yNpWWpa^&H5VS{Cb>cQLi$o6g z4=gb{MSqD~vTi%65~c2nriJ8S#($9xY>`R6OgJ@nq7yD19qk+&`3-sKkc=w8*tvlp zlXa+49j+-g9E@S9P0fZt8?sOksVYuoN+^-qY1YQ<+yE!rN#E}(Ec@as&z3JGE$t+p zY9u|qqFGQgwN<3*`gn>-u#976cC1SQAqEQw+WPlDb0nj8TrUr&W ziZD$6iT!`&;zR@6IWuuXY$Jo2h9SrX5|LEW-Qe+4!m4R$86F-+jNZ;^__=%>Pcd}2 zmiFi8i`m}T!Q<^?Y%y04@;c{27k7^xSTR2+%60+0UwUw9#S z#cipLFg;FNUWLee^ssbE*&fR26Hkin;=;1U+JvWh20o2lXGy#et*)R!tN%WLY;HsQ zSQO#N3LrtuyE+hs0!1PaFMaBq-@Wa8jio`X4)U?h3>rF@dvG_cOu%fO8^t9>>mMFk z$(a0LethUy|KPBY@A_4C<587fD{6}-9Q+KkI_bJakn2a2V2zy>cPotgq)3+l3~fQ|8%-Dor&z5Fs14&Ogy{htYnunD z3j?E28N~UEDpUaLiUv!!be68HtW1?|mO*DS-lONce9@TJQDWCEb*-#fZI1VUmFd(! zjmP3J7%3!7jCmh)jjCn!Ke}_xwskjUkUm_??-j$=vBENT)#{~vw5x8Zm2c+_Wr?>~ z*!^-utA86wA}_27$ntL>c4tEfTMp11c@BhXSw&GQpuv%0U}UOmYx~r$-}g6BxO3p- z1gG6Dlto@xTh&?(2PeJUzTAipCwIT5u0gzWnLH9RC=rWJE$#AhrP(V5VDh4&c+Cgu zqi;Y;grel9Vlj)*`o>MgG5}_QJv(#v6kwdf3ohvPvsJ28ZE`=tL2`aiG*1f87I1#Y zJ@RFi_ctTff~KA*yfoTf{lv0X*PwI%65gQ9z}_&#ETa3#`tHg$TT_NtgL~*`+ z|3vb|%ZpDZ1{pTBtp=viZhh-|0I&+I(L*4R#;9V}y#w8f#z1^f1kq-oP`AwK@&>H9 zeC_RlL)FyR+HCUyPY%kgcII`|dv$e)rrgD-g7NPA$Jmvk$^&vCT8vzLa8`|AX(Z7_| zuCWIpS7?=^LtLI;M}paH=Kc2YBr3Erqy!i!%M|*!)EPZ=II#mPQsR^4PaEHQB}6%QzLng@>P3HoCZ2>EC)W=EdSj5Q>^%#NgJA% zOqJDt{MYCpbKIgRSz|606pJAF%%Yx=w|r#=Ewa`JgLjl1C93eyVM)p*TBG(HT0WE8 z79Js1MPkz5DJi0>*$jeVwBcKOSzXpnW-r9@u>F$o43Gf-)-tghy-O`_3J zL7^L-<@&7@eJm-;gH=Ds?xyulW%cil63pd)w{@_Ww$l#fMR9JZX_)n}YTFEU032Jh z7TLz_ZclBmX5V}2yk9@He}L}nqGE{pbskgyZJv!Z#wed=s$pioG2^o4ZM}(Oxe|Cw zf>a0u!T~VUYfatQq8G<`-;??vd|=TOgaN8B=27b!VDC8p6QY7Ir_}oRx050C-8ZL`f$G%Z~yU+?k?<&x9f+A3J&A%`PRU=xEADpJZ*tC+QBsC9r~0Z>~QAA~=V zQyLdJ^o*DQd~PxmTj$x%_BV-^=sT^yM3l8frvl)MzmEH7xnp@h4pPthy@fr`rWBhz zG!c{_+`RVILE#3eUKbRgXyXM}m8+{+k*O&y0=mH&eEIihkn`{(-O>3j6c!K0c*Iw{ zN`Mo(L!79$eF@x*eiiS;)uQlLTZ{5(21Kq#Vzr{DPZ zBw!!t!YCu=97VY^q;O0PEgFi(d?EXfQs2Ndy>$yw+t>AJXZk~bDMe79{kEYl0$`*!Ej{l*%xL}7pDv<6b(wh6R(`t4YBF|AH!fw8`K zP`UhTL$sJ4SNF`ZTkf)X3ZnROyLYu!7&U&-M;VTd6B}M1+^<&O;5j+9#6)sre7yr( zufUN#I!|3FHE{lT=YBNF+0x$SFOmY<7*JZ&Shz5@tP46{2EH(6 zAow!*Dmk9tI#Z}!w*8Lu^=2pZ-e6?%YxDi|YrmhVhe^74L+{L;hHhu?sa;3!WG4Qt z=V$qtcAA1ZYrtj{ZD{Sm2Y=6d+11|zG0)DPB}NKMOke{ZXv^PtlZSkZTFJIG{U;WYhI!vmYnVB=wugQp@Orh2b`lwUuZ3hB?aBE4yO0`$ zsK4Fn3Vyu#Lz70c{zO_O;J0?lKTCo!@Mdlk_ZebDqgvX+kgp)7h4x9m(lm%dh%6}D zsGVz($DuXikhGC)If5g{-r zD2$we9*3i+SS>U+$eRnJz(M=H%9YGxYeTeWNnml~L_Y(E29p;OaG+4SP)1*c_Q?O) z53cK-_<_ln0pPvGvR}l0I$$Z^qi|r^QqCyWMC;ihO_okxTx37QhgetIF&*D2(m_7` z;|A(QRWz0xu)Qm`7z3C!fsK+C>p62a4L!XQ6}nj-o1F(u!%&+w?3`%E?3uxR(ThlH zpSmVqZ`?fY6hwQic8aAn) z1WdKfT1&Opxvwr}l(^u>NqeUKAB(&D`)Lmk9_5Q;EgV}FJj8M`#={P>&6%S$f4c;# zBOk;tCXw{81H!X{Nuz{8Me=V%R8jGfo+DGkH6{MAjUh5p2JqW#H`lj+ERw;I?{Yx_ zer68%FYzD{6*_h#Tp@w6!w>y&&(A&}YRtvMPbOD?sWVxWUHg5HUWfI;IlzMatJ&-- z6|52p3pGC^>{r$gd{~JnnhyG(t0ch&S=gDJR#J#-9EEfhYxS*-quIR8w3vt^mayY+ zhlhtPUPla%US6O=%HbqnM5%tOC2NAfL%{4SHQLFky?N@G904K97OL%tD9LPTCZ z#-r&W%Cl3rQ+FErb5J3$ZQft+U3AI|hd&FnJpBN-`(tVU~6vOLT7yLpmy{j+0u6LrB4L zJJ;xbJb1usRY8+LPK%aKL2N8zabUEdckoysT@SZ_bfRILdTwPY_9-dzt;NkLT`DEv z`#LOr@s3yP)pXL(p9smtIKxGCwIio?uVHt7HziNaTQ7)xa4B@-d@T*oim_(x?Jx#N z(AG;spD@!htrW`C-JLEz2`AgTuNv4o_&?h59cJJ8P5>(Lw@(;O$tN1XRx*@_^CewAw zV^aY7r{C`Ui3@;2vRe;}YXrD9_s>9>ptFRb$YFH1=XvaAc?2Z#W^tq!5f)o{!qw>M zKh<~Dg>bxOyb4c9JKTldkbftDq`9SWbn)!9-r*AY!SB@zDMY$RIBOs)S&J)1u7P`c zca98#2uY$dQOWo|YH6=tt_rI9lRx03#QG=jIk!!1Xu$dph(Bl|!V7SX$lrW(wu<-n)-d{6`^Pp*BjdTgRqGw45e06e& zM3x>~XP8}agE6itPQasjm;CC$jq>noR__NR<6FU4AMppXc&WJ65{VDgDJs%pmifZ7 zF0?1mgFn9ggcr61DmxzRk}1gz#mB?dXa1U0<(~}VI7v)!Wm00&qM`;%AmYRaMbT z-#My})CYayt!S3ZnWU8^BCRUHKAG=^6~+mgp~=>ljX*(`E~3dEbe9?z*TB-;P>nx2 zHhr5fNZ#;cz4BAKSlVe8#t(YL>GA5xswz34_i5B(uXyv3weJ?dG_xAD2#ARj3*m)h zq1AC>&(n<93i7%qxMGmZ;!#`01EpuABI3y}J77qKR^d<&N;n!pzbj;@=l9g&d!ot77|Mr{MzYWXTPz>Wt1X)BS_<2bWvj)x~m$?dym2c*^! zk;Y^tBiu(Y8{h3Cn~TSeF%pGy;~|9JlE_3&2gL;+_>sXseY0$gpltYiq$C}bR4CP_ z5BB~oVkt8u+@8WPSoWN98!O~;xIHGb1jg`i-ggBH;=R!lAf(>`~#(onh`fV-zvA6m59E4b1a*(iY2<) zo)y7L!SZNo9ku8B-r6$K?svnF?{-n^=@h8a^Q$VeP#ka`hF_<44wV74I|0if0Y!{d z7$<2iD?9t9+3%4Pcw!$s9$VwD4R62riWFHy{KQ*wv1nccQ2?bfHIJu5Bj20ETm@&u zr+&X@FZt=OK@Ot%XrNnizv6d~EAVn1Tc%d=^f%W}u6>O%%1C}%OQUJ9e~B1?;phGK z3thy^l!}!q47oXimHdkr3$~gD_GA-9I;b?~o6aN-E`;FE7M?Q>%Y@ zKA`MzY zzLqI6s?}CPFLUrTr~ZgDr=SJj5Wq4TM5xym@eolV5Vj@!wXTKpQABPO84*V5aC&9o zyKwNI_bJrO{Kx)OgoR-W`l;6RYk09SXcoFDBeE+jsYc@6Q6rNAsOVm%1XuLMjj{C{ zjo%jLD5xk&dgfu@D&{5}Y%gPpohS`Z&SLcy(ip`Fo8{RXF04tp4TNpy{8|fk;?wes z+M2Y)`Y79EI}j%=SBZX>FJ_T904|%N*=YuA)W5{I%Cf6;SbD8TZk+0zBV@^(kMlx5 zFMN+wrBSYp)R&rDi2FY4DGGyNO-hR~j*%fV5zOD~fe8I!*Fe5(`l{YR2W^U&?v3ZQ z*UaS|H`lV6L7r5rk|`h}^Sarhi;?=q!KUfOf6W0MketZzy9yNOVTYmm@g^HqPR?P_ z&k=@OJx2zYC+bNlT1FU!jx+iV#(wn!_bxg4W0UjK@zsZ}D{WS9-rAZj7XX^|e&oFQ z@V>wI8(8`TALlaA>-(ht`&UWa`%t3cVQO&d%wL)y)~i2;>5^(A%z@l|Vj?>K{q~!_ zp5YG{4NXnbt=fI{EJn*sHWB$jb0I3UQU1ccla!7P6Jr=+I3b|W0oP1mIyU|%yQxY2 z{KU9cCH(zn;stf|QW77N(unNNP;hiWKM6|%iz}v3q1GM|St?6k6M4>2GMP%1CpID_ zz0MXXS}8R8x4{V_rOrm)a1Cu0#`Pv93D_0e_Es zQ44ms-u?cVUk1^|l_R&lyCGWMz`-N^?>fO;Q-julFiH{pm*yreE^exy5fAv|Tt#Rb zLb+Ava`JagQpx~=tfU1;Iy^N&f^-iiDB#;Km9>c9jjVi4zvsEU(m`|W6Pvw3*w#q| zcHa5i&q*)4?U%d zloE^@@DS`lw@5eF6qb-ig5aQ&s?-{E&hukx+T4vdDN@YV#+qpM#K6 z;B4L4p1X%@UIA0zE}>SXJ_o`Cio^T+wA|OdY50P;ulSq~CtqFzlv-sQ)&2>_`8=O^ z5M?6y-0#07H-dtwEqt$yeoLdcb$Ni;bohOUQk`Ux_87&rp5Fu*C4fGZX6Lmp@o>}1 z3P2=6gGQ&v>+{{UPcECBq6LDm{u)+F@^m+N*8gvHjoW3?amEe_6YPwlH&P3fCJpZ) z?)fgkawbAxh>fYlMH6qfZ)l=4+_$a45K|DJ%rn^P5ykn9OSH%!<#XmG)XhY;%wvji zQ``)69t=zJ$bc}g7S4!7|6y|-9HNtqS};#Mlqi@LW-9OH&Hr5EX&@nAfT9 z^mn$=$wdRACN!84%hGW})Cvr~N)*KrwKfq=GTfig5I-0h7S5($Br5D7x!-}kspBMm z$*#IY^(5E6-P1t&0$d2vMY13S=i`&jgfy$Q=RqWOVV1sgV4#)?3H7%yS>%cV&=8s; zU|0qv_Mw!cW^u>pIF(6xWjgfW2dD-w(8a)2A6d8K74vy}^(Gg5G)GV1CxZc0K3hF~ zgm9GJ?H|D!kVoXN`537;ip2s=?+=-50;H0FoaznW-?Bn)^+Wiex6CZK6E&J_@W<;> zSQ1%?P-_joLn?n(GHlzYndsTt*)?=_PJ&kq>Pk?=XIE3!4}P1?;EK2oA?i9Jmmwhl zsv;NzrfL&js<+}xArpm^!6TAGY;uyykxbHIXkz(nQVIDg8NBa$aH5rH9SBf^g{bBV zp?A524)*hy)7O(`c*e2hlmT_we2P=Unxoaj>5VK@RGw}{0~mY_{pHDa#h+GBe=%v&MjV#m~p%C5AuZl+1yuDUPBEbwI;H5@XQZX2yf#q%?=Ym;%Ukh_vv5 z^K>e^9jHoUrqlnk9v4RlpDN01;1|2^njXD|2Y%guDJ=p5qHPHS{th%+3d;_K@u{!f zOM6$_-yZKS3^dVXwBVq$0Nv;NhV7o$CXJu#lN>FD6v6!IZ!UiRV%-W*csCKJ!$Kpy z`!{U~^nJ~ze{D&Y{lg(;m`@{$k4TE4hymDY7LG37!)TM=X5JNNX$-OmG2EY66)4cCQfT=9l12KrTmvo1@K9{nj&V{Vi(5)BEDUdRwhhyeA_QGBkcHj92lKP!>}20B>Udj>u&Zl|^% z7|0|`KX1Apz2~@CKa38IbwB_4$@d{vz|6`iHGj`k=%ZFaf;Gc0SDvRE>~4K0uS}re znOn7_YD}Vwiig`VzH21da3U$n=0&CyLNS#3$hl9|%f1w?!(bcpi7;p)-!D33$^+1S z{&1>Pus``vx7)p@Nf$|1DT$Qe6}(qOxfy@G#J2vtwp+!ywOjM@tH%9&(}(|Q`(N|^ zVY0>-)aXXfKjmyID-~)~n5D*QmyBjE>VI^I&brca!%DJmxW*RrLH*>tRCYwvoKZ+f z7^0QJnZGn$nbQ2zm3NFq(y=%~>{fTckmz7%rI_vxb zC2CblWh%>C8wG2p2^8?viBhYNIT8SC%kn#{ax=T7=YU^*%~;#*#e-r0R97c<+(z~i zB6iu#__cRR%^yf`KKIdY?(=@L`vVh}dXU<3W{lQa9;2wQq`*7?1>=)ofK7<(K<8q; zlOIHd`8He6UR?6W59XLi)$-k+c!i5Z7TfVd{7q8}J}UC3y3PyIK~U-FI!aR32IR_! zACpnwf7mIAi1A1|{Niw35tj)DaqUKW%D#P%Zn8T&Z3saZPl_>R;DCvi>i+cFQ<)Xj z8ln+PtGU69aQuI$s3Hf)}N(`me z$am?vYr>qBW=rAL)WkS6>1~EErwbedizyHlfe9)=a~vF)Bv6pT2`A09KHv0{qyV$M z$#&aK>JZM`Kv@SFxZY@dPH=1v)S(P?`_vL^0es;xH(cxViTm8apu@4;Y2(;q27gto?Tu#c{@gNPFO+}OHE)> z2S8<8qM@?l+(E=x@GC~8Z28E zVt}Qpu_81jrkAf{m8SIM1$*~!v>^PB^NlOq!i@*a%97^P$?G9|G6`w(i6Vt2^HmtN zasfp~K-mSZQcTh}ms0u^2Sr!U-#{0XCmVS>$EL2XYYG6COMhCnfT57t(YSf^EW$M8 z*m;%UjM(1Zz2{_q1`tRIS5r^Zx8;(??m^wtB$CB+n&?V*0(Sq`muZTdi8-I_lJgN_h_bF zrwj&Of(H4ytgpNzlajGON>KcIi&EAPE&7eF(Spp_fBclr3j+LR+xo7iu)7E3z)jjF zlQ<=(P5!;t7rz%hte+_lvjy*-R&t-1HwuhmTw^T=v$r?!6>5G0E70CagBel>Y17^e zJ`$Ys*g9z5c0D5BU2K5y&6X*mRQtw|t2N+TMi?b<4dR$ju-^l)s&wxsdk|x^^L+#- z+Dp-Ft}o>%5yo2?4V91on)3^%P7{lVG?+3N8)PXai39M8IEqy&4%(rHWun{fBq=Pi z$f9~uIAGU`RA^X^e?L4mP~WzF#%tup!jt1MJ36zwv~Ovi7B29YQkrARC$TXc&m$qE zD`GjeW}w4BxEF~P>i#lItMDA$W6dqDFMsL0 zuCsOUWEQ@{ssi|bS#CorYwS=$NozX)eA7RkJ#{Wqw_4Ze>ecQX5^9w#U>-hSbE8S6 z)7+LV2N;PUA;BW;JQX_NO8vL+4AQ&6qyX+N4M#~yn%V2uf=5<2ip5iqYF~$J^oM+r zdsy2DTC*Q%-WyK_ckAq(>7ZQfQg7io)mHDb2(d%cV_!e4X!7;xI+3whGcL?$14g!E zj5)ZF&wcWdwarn=WjiSm>E);eTD6)(#b{`hHc{t>n9>-Bhw<^TQo@ojJnWL$-=oFz zONhhaDCXd1-hN$8w^SgT=@S17%|0V4CO3m@|BGYL67}oqa-T4KFdG`_{_-4$QU2-p zkhCnE4i0+p-hch;RGB2HK^!ZJ_)yX~hPbS<-fb4S8CXds(HT|+qEQisN`wVLLTetF ztB43%EKqODe5F(bk>HAyUkYf}0|j#e?FZ zCUP2k)%smSjI7%x;70df?{P(hraklg`S_-~^nppuA25*v2xFxRRZYDu5;#y60v_eu zzM;;vofiAe_^O}g9?zd5?Sw|3YrF#NM{da0v^}n7PfHJ6;Lnp5zOMwsU?y5yS0{ua z25y)M6oeH=@Z5WW|99$+uH$y;&=g(yf%{ z1%FW*bFEHF#Wb$OK(t0+WOROF5@i_G%&g?;aH%_AfsWK9N=bx-BAh*N=f9%g8n)(t zan{Z`a(!=TtLBxpheNXd`?4F>YcGitf|Do(F91S?og0MoYvLoa;yg(GmAcj_+5#v; zDDFhL-cMexu5Pqi(0PUgd9xN{U~hvdig~Y6J5tfPP8u@@8|5u(&e6POc3nfe44CID z(CoI!H$`?dRdV9YoSQV-vEGmvudZh-WOTyOQYvCNc{=vl`Tn*VJ8)DZrrY9@+I2{I zUZjY!rVs2fGXt%N=JCYo9R0QQq*KYhgZ=&e1ns#2sG>$gE*#KPILgWUF&-f7P=`Us=%P&t(Z_gX(R|$fp-U!!>e|M6$u5VLj?PzP^oA*Ai)b4HZ z#T$xxL*^|1D_>RZ!%v(aYPViGZRe~DlV3ZY4>Q->u@&v;cUCEPM^J`oZ55AjQE3t6 z4B5h!3Z+e)#4tc`OU}n6-L#>%``OJ8nFll_oLuXt4--FdeO}E|a{y{gc3T0@9;R@b zg^!gJ(}_XM;l!x6+q3%rp9Oe?%KVaB*U=(er?G$Dym|Pu>MJ-^!SsVV*Kexf`SZW) zB*4~cR{!+4?7Z{vegyG~|Ee&7Oc3Ng*-}TBlB6+p{ch77%Vf)bj9v=-1wX?K9_-YR zFH8xy*pd_p(yc?;U)|Cweu78|Jp+TIr}x;OpB(2PE!4=Z>vjLHD#%M3av`KkMgR`p ze>^w>c8(o>J%28cd8auP6=j)jxjyq1t5seNUp}E)l-pZp zHtZ=k<=WJ@cZz_Sl!ZaOcxUh9Wml*YZIL6c-8Rq>4FeGi=v)1?i2TZFcm3k!Cz?Q^ zLWeme|CQi^*m0Amz-r~6duEM1f;=La?0E`dEi;qg?0oj}kA|+cp~=JB4@4b9Amc)d zg}7klA|DgW&Cip+b&eK7`r9%Zc)DJ07=6dq*9nRo(yt8gv@=>Knxo@e|GGX7s(^!}?#dIWU60=M2+w zOzf$uL1c#CeT;Xvv7}ot zXn9SZ3MC7n$rAOWRdXlqmuu)ew7q%E5*D!GO%l;}JUi$YXyVB}Ng2YRk}@F6&lh{N zkFNCM_B+M?NR2CJODy3?AE-CM5T+?qluRbs{f`hyArM)rPO?sAz@c90OF6&ZI!%E=u^ap7 z_&(X9`pV-u+xPRz;ox73i2*xvO{`#H|LExVhrgV_iMs0nL~~%bL2^EQ{l)|bQeR)w zeXo_hvp6_1O^SlC4y|=MA;62HK#vu#RNvJl56C~DQ1#f{_fr4b?wH+i?|swX3keW1 z-M=3njMVnpx;u3eKlFX4KjLyWtwlgYRNvAfS*G1rt|2KC!|@l-eYWIjseMF3DW;3~ z-@FN=nvc#o6fyE9&Ff#wAMbrP-M5e#@C-<52WURdGhKOy+TMTa}v@)>}k0sMPS1OIi$0IX zEXbb+?5G*{SnMGg5bpeN?H#-E9K`6&bhI^RPJsp`nm2vD$uaDe85R9NfJJg(&GBHn zJ(webzO*xVYP|moOEY;PJi+%SVQ+?>}BS$-uaRK%=QukpRIR7cIU= z@5taogqn@c&~q%*l=1Hy`F^fZe?oC2wi~Co+;n6ygfr0I@_U88%W_^t@{Vorjoqbo z!E2;*v)wAxqTPEW{WlnScn&3=waj)f@(4~&#^>|B`cKhb0oobo>I`Cbc23Mf@Ynf~ zC|NpNxNO7<=#aK|-hh?Zm7gFDnz|9_vnoOD{daAvjznkE3-Za9vFdvx8Pb~o5@R#7 z547}!OmL(SS~9mZ7A$7JDXv&Yh5EaBHu7%5rGx9e;iPesBqi^gQEKl$D`w8^nxD^; z5AcBw32wDkF_#SRq|8^1qSL^!v^0tIs_n@{>4rpD45_^vf=Xy^7XhupL zlGmFi&gMArtIhUHgEfv$+t^rvziD6iAA-PI5<)OEB--N;Uk)@OLATkwU}bgF6mp^* zgZ$wNw6*+hxF;W|AklA0fVX5im(Re?4SNgXfXMKy3!0Tu^GTpZk+^5%>gKw&cBRC5{(vLP58PVi{#ti-48F$n>1{13h6O z5+eeZetZbeWa`7hgNP`a!3j*QlZVBqilagU- zgi40oLNq=M^`od1oJABHZPRFdJg%yIS3Q45ae4RCW-H#|pMw_3AYXs@7tAXblf>>y zfzFSsc#cMTDT~LCogCDayR-d~d#and@z*V8+xz{!fmFegfMdau4j{5s#?rOFyj*2V{Qev4^OjcQ;G z+n^0^FU?%yXqf+8G-K2E?^kGYkVbL$_K6+(q4k&$O5om22AmI36yon}N217g5wnQYO7=wOP$ti~of%RdJqF8}} zRlP#7EXjcYu?We`j4(tbmO_fQMeNsa9uVG1+50|wOhJ0{xkD&-XGVlptV}zPpHl)P z4IFfkLI94Sd&_LwgT}~ShVqaO^Vb1_7&-AYz zYMLTJ<7rt^$|7OZW(D9QCKw)&iW*zQt#)cfD6Xd{j=DVC3(w2#WZK)VI$QIQF?A&5 zi;YRQb-O9ddbuz^DmYpk%$XVig*17y z>82M>Hj7dO+b;Ngc51C1YMD)#In9%9P`h)NcDBTOetN%{(yn2dyBHWcUs*^{XlSM4 zX$tdP=r@!f(|c41B;xI53^Q?k@z1q4oWs5dJX~j z)xhg>7RC3t5De7>^cs)%I`M0a&`P+8V?hhjVc94;vb3MD>}|P@LxdR+5UeO|JL*Dg z1(Cdw2+50I znVP>bsNvv63bq*`Y9f?o1Z9LPX0rzL>rCbP3cI&RtlEH4T^WwdDLrH<>TDD~T|g=M zf$r|a1nnmDn+3F6#!R*vXJGjBQNWk*(Ys>5*rwc<7!%FC-M~xd}B`7f2V#^M4KJ#lv7N?=JdPR7Pw?UORIas>lAgwPJiQ8e2NqP(a2z^ zO7?ZCK7)Eq+hykqBUW{orS7lh^uPNaN$0ny{9CYBs!TrTQCS~XMxv(n2O(Z%GEvp| z@Hosq>|uy|J;ut_IoY^f9^UNrrWqrht9@agGJKyyT|XkeV^$1XvP9KF%foD92HB)= z;=@V&C@iE$q8w~v>9=Z!NXk+HiXJ#pWY;3Z#LQjAMkZWbJciC6ENtLHi1Ln%Gz&7U z5-3#lSyrwn!cTszfxZZ+?@1zyh#;qJ~j^eow!cJ&u@Lv&I&e6{MP}ymTJytrBaHBR5 z)7>!1df;^|J-lm|Rt^C>54|K-TT%Od4fxAw(AhNkq9&F|*%!%(JqarsK|-Q9`$0ec z3+hdqcrZW6%joa@Zwo@x!XR#;R8(&>F~Dq+M8=+OD25TzswGyeVITu?3!q#U>JHuG zF)vV*j+H?*K9}6(0+G3y)88do20WbFj3MKN76}4Y65{8_TAYP+!D-qIA3K?*zYx;T zLyn9SD;l=bDluh0pB7Iu$(A7a%${>t_*lMRCH|4PjD65?OgK7qKlqm(x5GtuH2Zv=wg@bIg__vQs+nsExZaY@!?LFQKO1F64r-7&DY=w|erV6~$8Fu?XI z;AQudel&jL;d%XY%KD|RolUfl1=2ABOf#KY%D3^D{Jjko6AGBRVy|6hcfA>mQ$<+FGqacl zK2t^U9@B_tk-M4LMW)6l58}zqT+Xg-Ql)G6t|YB%a$VDUKIOF6Nobg_heXlE`Z{9y z`OY3?nIRg~y~pl!up;jr4#rfKRyVd`UBnc`2?8BTu$yO*F?ad<CUZf zXb?%50GhN<`=&XUx2wC%?$`Y+0v{4COvEfCo7a)2xNAhXcy7z~Doxn%pa52Pf4^{! zmMz;er&(m+gV=tP`E`AN$HQUf>sqW%I58R-5QQ1=5qa5RFeJeG-b)oue954ol}bPf zAqCYY@N1*M9GA$8zWgx0aFa+eS?~7C{U=HKrzimiaTYy<*_ldpUa?oM``*edqS=0# zHSt#+lZVIS>kSIURGQ6SoeX((iY2YMU!S#0EuH=bO{ZxU;^l5%4SCVRV2j$eTIdS1 zUM=ocXkK`%{gPNRN>}l^VXphjv*jkc$j&X%#L4UZ;3MU*xcs$VmLmB{=rsD#$Z)0P z@2m!u(|GsT)vr93ARdYtAxulJ#e458Gh3;j$wX&AHFJ5JQBMkPOzFo^9rz3FQ#{C) z;MrnmF~umQLX%WXn1?amC}rKR@4=p^e|)P-xVg!5!#8}0WoA=_Bc!T!lSAUVylw~~ zaEKW@{qFryxQ_R<-23Qdv-GiuYf6ilVWoL`&$H2bxV-VXqU_m{j-{wWOIb)#XG=P~ zw46uvpuDZRZH^3sQpyQNn@PRAzHzKoSMhD4c+Wu>qc>4!AAw})M1ZKEwUKuVi<#Ss z?+btS$G^&Byq{t$t}@3D6c&SjZDuucsnNEf3;P6>XcSGxk`E~zJR+{#Aj?*|t=^k2AC+>8ON)3U=vSBaftk-7?isehkr`X^l zoiD1>o6}h%I`2IgnpH0RRqAT!qO~ItwIX4lf|w0TB9V<`amaXjES2e1bKd?G!x`zp z5iS}rWwmA*rlb`Q5`>ufE*#d0Np%rIel#3q6n0a_tX7zxF~^Hju{S}+u9>f2)U zkh*P|f5v0V0lU4b2#4>-_bqsr$<)j*P3#Ba!- zvVrSaY2T_ppij{=9Ll1*N_Sw7S_#QU6Ju7yNK6%X^$4Lu+J-g*&==(Q**)JHTP6~U zXk9r1`D*sRZY)1$UqUsu0i6FF8X~s)pV2XWG??bh_yu&}LSJyW-2G3=%Nu^Oc&9ND9WIjl;3(P!sRUQb~v7Nql*d4StEsk#v z31El@(T~&ZT{SkcgAcL;L1J;)lF-wC)9c{pz%0L7x3n87Jfj`;_37SziaB?>)$fuh zTV56gCdgpqVv1oy_o&XG&`*-an|}&OTzbKhw$E=&PPM(rdDfjRs5Hw3(@?HqntY{9eS^mj3dV}-@BtTsVVx~4__RT&5U5K&)_F7zix^d zRG5?EycxgH~PimWuBRZIY^jfhviX zaPt$qE}K`awJCak?)9(lVH@*#UZ3dIYd9hlvfAq+FA5ZwcPDhTYuaXDrDfwWx5^=` zIc(J$@uwv9mbNNvGOCDx>ccTIVcOz}l0+Y}k}57W4n+wNmIR0{G>X6YDlX-A{}*fH)DbeX{REoq{cPFQUcMCw64pAKaMa)7)YuGX7WD0MI2D>#hAuoZW{Nr%SCqkH~x1%U@MFt_&Ai2FHU{ zr)%1_!%S>KD(`Pw>Whru=9GtQnWcEFw-(WD`sqF$v?t#i?#(*=`Q_DBTC&DnGUzr~ z5Y9@6)_CI6Cg`f_y|8B*MwWFCZS++=9~r%i4Kc}jA6lo?o3_lD)Nh|9zR7)}Pp86U zupf3TGx!U3e2g4xG$P!9(^jdpe=7m4fj>R{uTJkt22y^`83aJz&({#CPP#k$4mNTT`5xuQ0e+iyx0|i|?j4P|&+>xMyFD<7jb%EQV zNl-$K{<%KI_!uiIR^cm zG)iV?D~r59mS=8^L|P!#a8ER_NO z1v<*57er+#HBr-`+KseYM?oLu8@{qBj+IynN%_VnNMHLq-NeC1@p=QpAONxlrFOg7IKKp=AXi5k1B%52G|^dT)OeUX4ey z2$wddfFw#~qqX(D8RquYc5N8h9~S(Uj{BY7uYCCQI6u4l+z&?9$1E$$;Cx1j)Otfb z`S|!qQlo?6tCOGKONOoiNJF>_>ehx zdj5jEuuuC?v768CzUxtzMW417=RTrs3{&0e%22V5#A19aoveoG+9X_sq$EbPboq<% zm8<%efZO}x?vR?B`bgz#6-$!7h@#syvkd0bEax7!j$itM_UyZ06u;{U&li}jp!Z5z zmY8OQ2;GHrnbH>r<%rsxDx2Qz07ZT;uk|;Jh+mCYQFt}hLBk+g3G#s3llD!MSu<||$q?7kJ+D`A6r*}+9 z_=T~k==>LTLnsIVNfRf36xAfcWpnXdP0K~ceGB{SS;feOkvzDx-iAg=aN$Ho^rJP& z1V!(@@~(FjJW^i7@!)62(a}n=tDx%t@)1tN$Kol1{l5uY1S^XDXJW!+*c0H&&s5(_ z^3zaRB1L0;J)tCpzQGt0<(*|j%^e?vH1*f{-RA|WiA3%T`r*}yRMK?nn8E)790P<3 z9A!K!M_@cxQQr3iqmm(1Aj!jr&r0HLCj~4Bp`gAGx&6tRCO@su4+T|$q!oy&Fcn}f z+S=w7@m75f#k_RbcY}X1&V#Zx>-3KUk64jPksl162V103#2ZWmbaPo0lweeFJ*e3- z1A$zC5(Vp@09OT+jD1YE2JMmNf<@RaIR_d?HG%PG@9M}HQHQFk>g+B*Ko z;58?4z-N0s4-RC2C^lyK$LJ&Q6v;Soj>v2i6IRz{An!b6^2@P|QJq%d{qj7c!4c-i zem$4i+9;;>ppf(7&5iIeMfV$+9c#y--}p;Xz`e2`HO>E=G_KCTN`R~=tisl3m$`l(AS5^EZ7jszhy*T4Z?VH5|O?^OxKKQ@yXE9ZdPr&1=rCT7^Hx_T1& zBeIg(B*CPSTC4w4nENVS5)szmQLz0;Y}*72BZ-SzTZnXf94jNkY%1h=?OZb%B3oxT zdNYLlWpnD2)(`jOy5qXW8@S*1Mnthr=zrYkk1z%6ss)_j#C+At{ZiEW%^cGYTtvdZ zCw+GySxwB}6?7b7O^b>@fypj%{;$Hj15QTDl;-lZOh{IAnV8H9-#AhE&}`Vn98L58 zvjBw&f#ddu6$S+uY)bQ9bj>4gB5|Tvmlq7CSy&QL(@?ya%r<$+FK~qk(U3$$4~!WG z>14>^8DsHt>oE?B$}!~PWxWLu%~i+g+iv4j5lUdN;c&Ur_hlitIveCaQLT2~4#Bj* zOr@bDaXZht>n-PN(}Y@u*Wt$SUL@)(tqZ1_w^8 z$2QvCgn~%mxIXim*xA+8TOtMw+FEM`X5IbNq}*mp^_z}J?bAx6$(cTyIC265jTWyv z25=GI9~bZ$4GjGtnNV1JsEuKdIXO8}LH0j1on=&&UAVPh5RvX~knWP)fOL0=Z`;h48{FCd#yX>oYymGu&ZN#<%dp5KG;L8FCeOV zLfYABR;A2$!U89I;T8cDwl<=|-SGK>dlmy&J!F&6)i zYimSxBSqH%=l;tDWh3eCaJ%Ja{1@8I)@r^3cc4ZG2z(OWgQ`EPd}17N;mz zPb27mZ^lrjayoUOw=utuDl-#vZ&Bvcqa%p>%43nY)2CP1f6O0)PaMP(2=+480UwuC!rc#xxPSJB=%$$t(a%sU1WB+s3^jQN@u`HVyn%yD zV4}wT{WB?!tKpDDaP;d{iv8XYwzR;QtQEg0ZebLHqK1Z^iN>c$xI=z}^$l1fA&)Lwn}?(Wd%q@w6q)*u|7?5#}7cMrbe9%Pwsd@MCz z%wk;V-yU_7W78tHP+`<9I1F~1x@JNTcgri;pD@%ysMETsDsAMOPm9k(wF}j+K&Yvu zwBRqT&$dlzF}RhiJ1R4+_xTjeaFL;Kombdn%@~1Vz7QRV=n7 zZIs3#mDefJly&Z+zg*r=gcKY*y>9l=_$E|qQkniRdW`a?mytN%6Y1eYal0`Hh*P$ig=Agu+ z%%z|m5vM{NPL)hlZ`J&4okHJ4(8MLdNTETwWOM1G#4{{A$dJ5ExLvGnS&mKZMvpj& zWz6+8Q@jcT7ht8|6r;%D6slPtI|~&cGioj9D%oOlFC`C+7g4|G4@Un?THqS0p7m$v zlLkp5-%saYb`5%mA?L1ncA9^<<7M)l9+}|dY)2CC8o4$4qs+Eb}E&nr{ z*)l@;rwN`X)qa7mH0D2?urR~AK~UoYp_zSk9k{ZAbCezBU!H7k>$IZQb~}Y%mhXrK zU2^}|v3}O#Hahhv$CgoG-Wulz4VQSD#m6}M-7Ow-=V(0TSXZZNj~e;mh8R%#0{j%9 zAG01G+tI%UG-B>CqWxzbsN>XDd2D*p&nE_*0Gu8vjH5}Z#>EsTr}e#!^G{CQPibJ5 z;(UK;0TOi=mY0jy&j4yFV%xhgXV8QnQj7ze=oZI3N)SKM>T^Zg;utWxD(KY;rjNzN zX0*v1u&M07bMy;c4LYi{W#5B;DqPIYVyUQ~Q)A3XRyOvYEzJgMQLR z2*pd~rA)V0|JI_(F#VxNHbWxRWp5%{XRvd5DYw;tZt;1@K|m<|wjoI*mFi0&g505$ zZ}XMewgLZsSn}PC>TbO4Mb_@TrXQYJ0SUUCnY&9a=lD)rm$iYbB*el<>ndZ{b0EE@ z;-S97jN!C!(P-Cf)fOJqGHr!<_UM0)it4o>gVXrJBHMey>w%+tn(Hl({c72P;EgA8 zc}~{BK&A^PS?iLt3J5p+B~GkZ@G7Q^;?I|%l{R_-QHe=%tU8CJ7-iW3I-TK4_UYOL zmyzi7kXkJw8h9qO96(&M2+CqIr&{0&7piZq4<^i*G>%efd?!SoYS2{u%{I$2_jtHh zUPI2utgxrlcNVMQ0!u+O&0>dI;M%;FUVyPk{C#+YBZgTG4W)EN6UIIF2w{_T)4MMy zL!l7mAuImI8N#a>{zY!9k4fzOxe3Z7pD+6K=uV4cdL+A8_1@%VT#FWP3}D=%Vwlc^ z99k=I=5ppwOpb@Y=P{icFEmgYibmUgd@9k6;v0ob98ewf5Ye8RM02R^H9_e)&jh3< z$*0y=EG+|!jy15W2(aOIY=TDJoR|yb?(0(Gk$USBNJnq+QI)ffn}tm-d}_rA>*%HH zb;>}ahysRz1Skt@YqhTHXyM}Rt6yzo{? zvv{4T?+43N%GAHIHC~+Cq2FW;ZjVMW*`+iIqhT(Fj&QNVLYI%E0o*l96j@&aknksJ zD|jbz-=$#V4$iCmjHJ`RuY0B!yM?gn9TApNu6dIwAmyoUwoM16F&`HljV%Vjeyx;R zMS_lfRPU#M?Q?ilF^l)SJI0G6qFM9!xsn1CISQu~wY{3IE7o8Wvq-~7Nwpz)V4(5z zH3Q*DYpm`~R}2Rd2>A@GI{r4eq>oP#{~QBLR=$I>JmGwqzXJM~NW^X(*LS+qj4| z_gWG32Gr%@JIVab6o(~ARGh+>Xp8q9d&$v}BS8su5A|maNZg z^g@$ZBAIm&Cj8c_d~}DHc3by~+9+fFiSH=_#cllT)% zri9pvBf8yGP$Pw1VDM>#LP%a_kl~Pzl9bLo8AlKwmKdWPz8HQdk%p5)b&}>62Ys;h zNv9b{>R?q}5qvRXJItmG*9s9;a?YWbw7h{TiVA$4eoQ4i8-FkGj+J@~@TQ$qZyb#k-VQoA z7~j!fG=G_WYipErSn97MLOkI8BXZMu$gZw4%q{NW_BL~@jBlTP>CQ^khe>RIWeeW6 z0?omD0k29mZr2s?m*Nv$$?x2^A0Kb`QR1U~Hvjx-k~?W_Y}^()Be%6|%nTejpIEB2 zs-SVzZ}JxAlimZ}lGxMvET!ksn?K(m8Ol6_wRsSHmg=;WT+Lj@r>$t=ePJvb%E~YO zg$*aU-~ICvEYLxw;wGTJt^of#P(A&_z%DQUPnR=^tZzb42-QW%o(ypd;*-v@$RQzj z^Yt77mZUdt-atU+D9CUKhzLE5S=m+j#V`pYHxC#_b5(RMx;~3|BJg=nj)C>R_ha{U zUj}GC5-{6A+1f8>An%pcAI>g~yCB&Mcx=2!nssFsEXG;uJj0R<@%VDSb%Z;ql_|)z zT8Yk;9An(o*TmBDn&xkvGb;lVEZgEc_U?V(jXI{)XOznmv1#V2V~*l7RN#%4+EX%$ zR{Z>}RUwtB9SoAQgVKFQc;e=36E%F_chyyA4I8B2>~%nIRBMnUOgfQc|ORD9<5{8!qD)(6$y+z`=yW6tzwu zqjyjlG0rAStZki`&Y1YzpZLmJaslzs9xXGEx;2^q>L-|rp}-)W$i3pO6#PX%tys@V zbF4I}if?9`g4v`R!4tvLDt4nOhdIEJNMve-{o7wGO+og96dgk3kN>urJ!@t6HZD=p zt?2iO&{fsZ^o}aw1bU7d4PU}5bQ`^s?LD|Ex;qAJ8jw2vQX^qVaD>DycuAf`hg zef)#p&N@axHLGU_j98fy`#N@2SK64p|K>V3Iuve_aM}6|khh~9y){iAE6I++T0-V3 z3m<*BC8GQ*nUngfCVxI0O}HU@R7_zwRrR;KC~7fG8lqKS7JSe`)<1S;r5WWcn_&P< z_ML&)?CP3WU;_h)DG&unfD#6*j_s?bVthiS{zKpI{RjMctRQ4=FV6uWPd!s%0IRx6Nvz6sTD{=E7T8+PKckA&t zzj6PZ`MS-LxV#nKXKVIKI{7D)d4j3l*SWu6U&{7k$5R=%+y=FOTPt>@?WSgxNVYeM zh7{SBYiZ7Dp4XeFUzk zK8e!a`yh(MshqBLC#ShaU0L+wn0>VLO*u~%WK>noEJiBlit>VSx`nn?9y!pC#RLaa z64NKmk5IyvCJ7PMCr=x$CY|L~pt4$XEuFc8?Xdl6r@tyaQz}U%RElX=oGMC;Nz##J zj{i&ugTC7Br=?rd6cFl=3>spllu7dMTIw*m)}yqA!1|ev zS66jdh-&V?ttD{l&tM$6;$)BDYnmc(z}WAo&q=O~hu)mbk*F`>I7}rJ$}cL|DR$3W z@nm!4j&&p&F{t53agbW?UGb}}ytHjGuVg&@&%QfX{7w zoM(A?S-8Q7VCvZ8@b+)$z8~0eTdNC%F&}Gb+iQ%^e!2UTv0N3yfEPm`7vLDs;D%O; z1J;i^$Jc!}S

5=pePogWUYr?)^})wa{}MSp+s-#yvC4i-jLe;enrxD`Rx^3L8o zZ=35bl6IY8KmQp)J^&nd zPmVwL1|rObLCF&1lY|GSy1k)i@dU?U|pp>90-$7ZdV)|ifwkd^CMomt6TC7Yj zce)^@1xGPnwT`qp{>!>NZDZHA9Ay!XlwEb>&YYG+CQp_U$)?0tA44tYLV9Idfg%d( zm?E*b^OEvzsbCo==kYn+9Jkjtr_MzjWq(k#LPR4P)0ijlQ;e11_U%O>zHQ_D;fN5z z%;goqG{)UmZ=yCXb5KH%PUTND%Iuh@irzxmmP@;(UvQx`;VCGZRMff9K zYE+2vupt;{`vrGQk5Nvz?G5MX3K!$w1g!7y>-kh2%VEorvdS}Vwb6I0Accv3nhK+q z9j>{$wP3N1RV(wyQPIQh$5b+ylG-&a_({CNje=X5F$(S#&z5J>G{J5;lAF}U%ZS9KY?lOBb_(ABIaNSkcKKFU{D7`wKsV$R1)nJzX8E z=lXz#N)P4GR9s7A(~Pi*69^0Mji|G;3Cq|eY&2KmMI*>WGa)LV>;3IM&Zj)7$AJ>d zJ1HOfhh8)naTQWRj6!gLxg;S|FpR46mXAh9vwFAR*AXseIs$hRsRm^UByCR>Ie+fA z7RMmC#JSA;F{ZSMa@qF!cv4dT?HZkSWG{UvW^_GXYUu&Dq!nReB!^rgW2icks&JXS z6y=C@?CA|c_}l4W!Wd=BiQyXd8H_^=O`X6r_}I^t;%MK*SZmGG#QFja<9lYlFlSF8 zjdo6(nsmK)k~;c|rxHcMEJfkCnpaKrX|HO(-$gjAJ!PXZE%tQpe{NP*;kmiFBRvNo2>{}K{;9E% z%d&CtZB7z+aFnsvrT2tK{FeL@etG*Oq@}bTzI;?I7fOnlKS0i`)SJ{3_ELp0_^9dY z)Fh_y@9t^36Q*ZqNh0$2Pp;4dtSlS4+6D&61HK182|gYw8zoZ9TId=vQipK|N3iU&s#W4GOB=}3l36>63@Zmh%X3@Kk= zg?$`c(3?BF9Q^MLKJ3^>i`l1{$U99IjhF7bWCp)OcvYmNkhafPGes3*qJfz!o3wF- zK3~Dsq~*RtEU$a{fPuN$A^CJ2Ie&uJz*Kukb2=uWW z7$KMgcPVIdx@WtEq-|OU>;>3^83kI-?aXxugWMAc!N3PF?1ns&+--uBY)Pn_=4-0w zr%X%~@C7%-gWz4`Zt~ycg-0|0l6CcUz9d{J?&rve;z>U%`p_{q*pu1*D<2mlIS`%0 zZgS9B)R+UgRsC4R2TQZ#qjK`58ftE%6}oqcq;Yb^B_hsM@$dP0YhL(!&5CT~eIUAe zma_!g?$X!kKiq%r+jKd z^ZMi`_DZDjWW@zc;`vTZxBkPmLBJtE+7>iIr&~*I=I+CWV}eyGjFBSFPaBPp>ZepC z!SWP$uT@bG&k~sSmr5()VZ4IXvwOem)a}A9_ zqYs^h5p7ZKXco=;>0(8fV3k1g(@nbCZGD}Jz8Db!`F=`TdYCH|XCU%j^n-t1WcgJ5 zteL1PZK^{Y@-Dg<140u_%}@i0Iz}5P9P+-i7#2@O7!nG%#jvYORaPj#mZ*Ab9u8>c z7g&ruQcIqYyM(7)dP|lunF!?mBZ~l~T=H-TJBqHpJ`+iNEl_s=@T-Js-}Ui)rULDb zk5b+I)y`v5xT8Ef*tNybYK5~Kg-#!$8w=-Of!#_q6xYbSX7~L3>s;G^@|6jA@$Z+l zSh|pdrr(O&jSURIlLtO>&~4L!EB(v7_E%t? zSR*roSYAr>^)6Go&(#?3{e0jPsZn4+a&Yh~q^SowbhD_*z;P#B`$Fp)nO|G2(^thK znpzovlG~|vghG5YT^V%;TekwojUIj)6l1a}o1~-$qs+)?JVPDqce9-WLaPn(2$SL;k|WGqHpye?iv<`=R6#W6+%we*fznM_!C< zBZ>tq7}j8v4!g2(`DBiMok593&9;_!PF1sTZ@K3^~q+X7Jqrp!BXz2dWB}ydq_0X|wr_@`I zk>@ASjK;|};y7^YFMqW6wsZX9FTDNtnwW%?j6I(wuSq-W-{EC_VV$$BnYWBPl9bPO zQHWRa?Xq1lm`^lPoFQ5U%?Eby4awS5nzKVR-*2pp1O*ZzjFaLTJ__vD1XS3j?czMF zMrM1iN)0*ozrX9j(ny-)kq<09wBxzvwj_u#O&quPB_$T8ilVfV4Q=LF*NN{?x$d*G ze&6&zFx|!5X_JPE#qQp)=@%Au>7FL{MlVK+r(E~dYUzA#3%0TR`XLTCQV0#c4q- z74~swV1GX42!$vD+`(Fcx5K!--C%OtAOojzh7PKW1n*_um$8n9JOVaICotu%(yZ+tijm!E(C3IIaEOe0s=4@wZn`o9Sb02v^xTzlc;ijV6TAGnqt zpRl{BLsUG??#eQuk*Zur_X~NucY0EVaz_^o6wDyG?Ac==Hk%CO@0dZzlBp4adbP7t zi1kCe1c0k?>urzVhRQ-qwq&Pv0y3P~Da`d0`gb*paZ0K<2!kFebAZZFH6j_xn}pWr_J9t8prA$42~9BayKOuKEAhoo-G z65+8&OZeW`RfYt@Inn4T4WZgCl;>He-*`uR7XMEfUDVIj81P|vdNy17R0;j4_ zzHH&x4D>%nuh~4O*RXr!m z>OB3_vhEj;F7g~9uU)&9vi19SilCR%Re%2TP))W`@=}fx0l-Dc?nh3f>i-_PghRp{4(INpC(vIt0 zib)o~f1h4Xg_9RS%jQp}Pj064uD-255qCe#uWwfGf>UJgq-C9Uf)ltsm#k~oTgT5t zUWC^DpWYSWfV*X{SXua5!lWgf!rsy0B0KOImCh)4L!#CH1d06PIZV2z*I^&#B4l@N ze*L_k{COz$m=~e=)5!^oVc@o+q2Ci~FS{iVxY0IWRlDu*n3=f+gBxK0YBzt-CrlH% zkmKaEx^+|I)arL8{F%evXmRf{)y^Q`fFau%cevj*QgOh>JF1Ki`KFVH4zVTBB%< zaHB<~Ztk%D9-2KdvhmPxs5VmVrix&^`s3U7i-8iK(t}~fK1>#ewLT-WzzU6qKNB}e zcHpl#?D-}+eqt29dy^d@3B^nj{E4j(~ zGOnWyp1;)LT$YJaR-fqo^?1US&y1(6gL;kC+DK$A&9~L3TcaZeu3gGDh?Os27`6fs3IS^Zi)3LuLTRnewV8#ds!wX} zJWR1%s+q~0o;P;-VA@V4HYFhVUhy{`h5%N$l5#vhix@3=evY%Nt6He*SVPQmixalw zzZ`6WVx|c*@+Z2j?7HsFKfjxho+>>Y*mc69Sc~66`QmrkJ6JyYe%a5z?e~xV_ku=ooe~8 zWIx%+AD)y?06_ix2ktf^ek5aGGMCPufRMOxW4>Mj@w`$Jax!+Ze9nA*5@Bh5oG^Pw z`@6~J!<6FfH#*-0PDCBX3?Cf4nI3v|lvD|S+H|x;BEot$H~%9c-|cok5cjsqC++^+ zGh6dMey5Ta{BWC@6Bp?lAQcSO{1Xn0TNwKo7pl6TP`n5HvAg5$d*UK`s$s6OZ|Xq( zf$$??X8Y~*Vh+?KUq0OnaXSI9%GM4#d!X}m9Lkm}?N2N~SJwOK+4+4|Nwt%`^Yzg? zFui;8Cfxt|e*aU^@(CwV4XEZ87gmhHC2}3>0l2<*pfDb8K*0_}34cY~NN9I#2MBUA zQ^>1t(NiOdd3v#N4ve zo?YTLA@XO(++SAJ@d*oAyg29gSPu!Fbq?mgY)ve72gXAt5W=Er#vGiZhTR81!I1y) zh7eHV7+TI&N|%Yj+39k4q#38Ae0OwAj506Pakci%|L-szWT89WjsNNSQ%x*O9}-A% zEZ`RW_O0XQ?{S~Y8&OOtN;~OepywfyUo}i;(ylunHF}DQ9YaMUBXhkvc3KELPhcJe zDu&I~+qLa&W#K)LTM51P0HctFr8U#MpKWfpXjWEq?hmh;y*!!BI+a=mq4S2@*-l-Q zEpfT4Lc(|F;=<26>SPee`NX#KchKErj#&XBb2tUNLA!tE?OI^Iev9MOiC^8(rn5|% z1;pR`fcN=kHf8mHcj*J1Gk<@(D6Q*X=6jP>{LHuO|J<0MwD~(^@dC`pJ_JqCCZb`6 zkmOVM;#a~18)J|b6`{3@Q2dV1$j{rD=AYXmaOl{EX;!Ij?_b8-b^8(hmQH#{F7_ZydDg6!-N8uN$x?7 z{GI}I%6nfR=Dt~+WXg!{@9n8fv5R8pdM<-V@bWQ!5aUH{kXX|Zbifoh0FAfK#1o^9 zw?-98bPvDemsdf2V!j{RpU|!hQFP-PDB8UKyD+b3MEDSVAuIItFegR5jF!SP$aLpH z-N$EttjJkax^z)FoAZ1lMQsit=~C6r=+8!16!%--h-k)UuX4-p?l!|{_`N*u2en) z#-~zmmCXhBqb|{0`X5!3+MwkdSNZdXIQ}gzD^jM96`Msa(|@d;1lGp(-9ViD*S6gw zXqBY!>Az^mDumT6IL9~Y*zXdTo8_Yi%{0v;|D!;F1(vrbQF1#LD=RBW!@7Qw^4%Z+ zkWftbsksh%C`e~rQ+f3rIZw{-s^&7sQrPI2xpA?Yaa}(pH}Jm_hRjE} zdd8H`tX|>`L7yD*md}69N>PS}?nqj*IQ*N(7WH3=m5ST>?>n21V+lk@nhD?SynQ~x z4;&+&Uo)R1<@inSdE1Qm>h%sqnw>V=#Ufi^zhK}EWhc}l={{%u<#hcn@MSb`^Ddfg zalv3e7+qu|J@AUjFmT@^$Yf}I56@Fz|7!ga`Q^{?y7NoVt2OVFcfwEoM(3v!>*az3 z2}-n&o9oZ9>j2Voc~9QW2njVYvx|PY29W~Lo&^1t+N;3Frs!?vbmxq!^no4}&iwn-?5Uj_F2EM|D0|HN5vn(IS`ZorCy+ zcc7N^OP*N_iGO)ie|}njWO3@a5%^aGo_mQ)gsg)M!N<|=M`R$_10w#I?!TkmCCi5w z%j?f+|IEGI!~c>lU#`ht62Xh~Pn;S~9x!ACatS9-Ze$v9IPXrJ0!L%BdHEs2TmOn# z{J;x*|G$e?_GhQlhu3!-6T&-C-Zg5k-k1Bp7b`%MUR+(;>wa*0*7s!lVCfJLOs(j% zzj}MOGoyTeIa=p^cm8Q+h6|kBvcPV~4Q4*EV~TKh${_v}L@^&ykQbalcr-D$%bU% za@o(V)%Uo0saP-RSvyXViRGm%!|SP%EvUid5rRbx>ndl2qYJ^&qj$w=`@>=QNmW?O zSEo?Ly8PgSMhjk5_d;LuYX-||8d>ZHmpIhdE>IUzz zq?n0BJP5LGULtko+k+Ho9mI1*8Ann5Xe?nVfgoKR^DZPY2$6=?T*g>gLLWP6k~yJE z($?k*%oQ`;1Q+Netrl}2j~%{IYz?;^cW0MAaurlbu>R}idKCbPJ2J2&0L*7iS_WbE zI8yY=x$4s}Zl;nyKLq#jCk`51KLz1-vAedP2Tb`jA?IW7vfJK|6g@Jky6Yz;;p9Gre|S6&y{)5d{-TEqid&E<>}pwq|K(7Y(+p zLP8dhyp0FLo)cgQ`^;vW*%h-49yl9baI>RZD*s($xP{%;m$6Gp~H z&Xm9O*bE@L8NW6%_l=rN4N+>lTd~-B%dL|AJ-%88tFB$jFsw*W*Xq>k#PCem<9|DU zaTDR~7Fu@t|1T7}p}PlLU|w;(n(O`FcaGgRMB0u9W?o+CCOCq2n$7c71j(PrdiGGl zg*?5;laZ_)9UG@@UG|}MQ>Qs!{hYrWbDG~CvfhgLzPEt(KE;b{?Tb7i`a-sM4q=iP zajGpKMD-8m>9T3lODo297T}xyD9|{S(D?(qJs5F`sMRxPPu~6k_uy7zLqm{S5}&M&(K>Y_mYM0}ce*Ip%2@;k=c8zd zm*>p%yXFuVyr8bL#V|D^y zPsp8q?}H*O?i(!ZlI428^e!YRrW|{VTl8MI%I+9W^>xYC2=rK?T>VHj)FvmvPQGTU zWY@=_%Qsa%y$)E!`bMG(p$$RIuDXNhba4@QKrk&v=r4W6qcPv9oy!PD+>%Rnt%6t@gtuB+a|;U#)F>iS`oS7W+TAydOm@d0 z2h!PfsmyK3gp-gXx_l=$g?j>wW8H-`9S*MjVzxN2WQ(WXBlIxGRqztQi2~sPn!v=c zTkIv|k;0rWFTwI5rksm$mZ%E2;|9%qgDH!LQ!dPr)au)tM?fBX^n4ZeAV=`#r(t)w z8dWn$CI%g%Q|A?08;`w{BXEWg#!7|inJz-~O~LDU=emVV<%%q=^;zAQDrb5I2~{A} z8+H}DY!!QYOkSfB6;?#7n2$>Xmx6kZkvj?{6p=~;8iqjCuT}eT!Xo3@9Sw)Zc*CPMp^~3LZY2?t8 znzyAacp)_6i5VymQK8F)bA9eAVF4|3_0RbEoTRiHJ|Tt?+-cqr8cp@;pNS(u(>l~k zI<5{wZo%WI12`iFOziLqr@z{03YijRm@ca0Imz-aDt0I-$qWk+sPY%mDLe|FW+^mG zGJYeNN53af8K8g;^r>GCW9T9x7GZoAML@5BlVc1~QBq`ij~uE7BU%&L(%wUz*X|dx z7{WaoSwoqe1ey3cfZ1BsH1iA__tf~YA}5*=goFXQuvD=u0Ge0g5?!}H=+-Df^=P7~ zAQR$@!&IW*yzg=_5w<{h)OvczscyWpYPR2|_lJ%)OpCx~YlWq03)N%`!V6|g0XN-j zP_$fF|1>`M)v|q&ap*1wB<5`c8I3v1R}bH>xuJ8wcnC7^L@_qr2+LKpZOcRTc8_MO z08s-N(1GgGT-THJ@@zD3x2+G$2oJ(_rxLfEQqG4w=)7L%cv^lGSi$yc>3ZXql`3#OK-}(}g&Ua;_aEgfDKN zZ7T{}h|ZmD@2q{d5&6tyRT+;?EDe9%%2~=CKi*ZKfw?ToJX!gH0@@nT;Z4O{--jg+ ze!>6T&+qcNZ>u`YX|26K)lOR!n3jUil4H~jJ3S(`9qkJh;}R%Rj0JMPwscEdK?>Uz z_x8s0{U4N{Gnjat)E*AMK^6l>p8UwwY$U23YW@+uFVbJO0~1ha;j}gw$dwr^XEL5T z1JIO}beGqty92W4Uv}abgbV;{QG#~=FTvtlTV-FcBo81~5TYsjUouxYiweeWu~Vbo|@i>1t<~_2dQ-B+c4FGsa9Cn0G;%RLA8JlR=kz z*pHU>U&C09FArgAC&VZk3G*zK=$K4pXtWYE)#*73Ic#LjBytA zqJ5jS-Sh#&SID{@$4vdL(U}{ov^{QB!=B$hV`DhTn%-gQCdgi8D9#;^l zIkB|d@o8OO{f68Ie5v3B#iHL(oa4c;j9ym-ysP!TdY=!f#&z&o& z9o|LwKWACA9QQk<^{?l&1P6R1-?wi7Fj6dWRqb|%1VOc#^dZ~#1l$V&)d|2X zis{9N=_T^F{qlZG`&E$M`!w1efpCLw0W8(}gvT-;ZuK^h*?ofY6o&?2Dv3-LLsTdY z>A}RsJad}~Nt!4cKManEMWaJ1=_k29`zc-)^l)X{oz4YI@3mN#aC$uV zUAOdZSB%1QCDw=dQrHP1@!G2*%iPK1n*(>y$p?h}z}&vDR@yMcx$lt4{hcOj94o1> z*u5@|#NVQOBb3h!@SdM)Y8`6+>hl@hr5P_qq48>-?e~13LDQ>ODG5j-z53smP2Qi(8#BMrnK)hoOOw&w(J4{) z$LS0mV8KfRIVO&XM`Qz372=;=&z)`Fyg- zPz01W0Us})x_6tFi)X7{w@1*(qV!7T2&DRELcl1! z8~1inK%*Db&kk*vPuS0ra!AeAKYpBQd3m>--n_UTFw%K@b~zO+-4w56&7C`~jwJi8 z()nxm#Pf{M-zON|G!A*orsYB4A9A_cBkj6~^=kDv#_Kw}I{hZHc`%u{W`dzsqXi!3 zw%5m7FF^6Nf{?hp^aP;Y+!*{|@!Gkt7ua>`ehILgK@?mT^uJvX44;!jwp-;nxqY+p z?Upj|srwl}xF-P|k>~$Tr~46H9^RG=g+Y?vXEWB^-p4g96`FRxY&F4VA5$&KPQ1o& z5H@^J`f(=yC34F9=XEyk-P&!JG|9w)yAlbEFv*m#z}DHv^H}L$fGJ|B-w>QW&PMO;| zB>Q%X)@YS#)lj5vZLbdccRXYq&(~eO>3(5pZsDTIA+VKJN;Shs83>k?XlUJV; zf>v}~QT6njJS&-#1>aQ-yDDhWyG5hgBoZKIq5Q}2E-S~tJfu+BtuwNm23sm-EWWv@dC?qJ+Rx0epXTza(B`}F8QVY;IHcbd%$rm1}f9A|U-ROXvV^l<;I*wpA)QRBE9_D-a^#_ATjqxPu52x3P;_S?lS!D-TC z0TzOTYu~uzdMm0f&Iezzi&l+zmij&}dahIXT4kBf`+_~y`#y0$Syc7tjWqUz&wl91 zMV3QAg`ifUQlSC-1prV)n;bdn@%R#Vdsat^dN!yGqUUY|IcC69R!{LWT=SD6mwFMQmqq%gfHhP{$o! z`~7)%x=&dtXZhu`os7@C^MB_sQr>(Q*8WGM=Y4zKD=K*{#!!wW-9FoS=7u?n)Q#y~ z`IW9K&h$Eiy;XE!^OT+H>biQDdn^X{C`4XejO?!cZwibIqO$I2^!+!b@*R(t4nWHA zlkIfXf}KoV-)0iD-L|Mw?VlNKSjd9(pkWw6+)(qy-mk4 zr|C-%(Em0qJ0$UmB1CKxcI{*O3WxjoH3^dTrIKbr1%wV0e`5KwQQR`i$=N~~Icz=%LJY4F7(mqpxcMA>t%K;lP{YZSlF^)wi#8m=-x{c(_B9 zeh4>@d~5tV={x$D`J-Qzn(#s`9X~d|ukPGa%Hn|~;dr*w$6UaRj*E-q<6GE2IKU`= zr%I4ehB#mMVSlV;4S@ZYf!g%q`3?D3Fk3i1WWYPf$>StKDO4>FaPK=jWEf_ak^!qm z8HPQ@T+k4I3lIxr2Oaa&@vZDMjvY&^8xQf-yTM5MS+qP6_ z*>zk(weSDVcaOVsS_tH^lf`8y(f$_l3Bvl?2t9H2YyoFEBS}j<|6$IwEtDM(O#H1| zmcff_`0>zU&G(8$OIr^hJA4h%?Ibx6Pr^`s`}3($l{&Y%^aA`ru2T4vHQd~})AIp( zg=SUA$4_w0JiKi_SMcC70pYfv(1pG8Z|bX-h1Sbw?F&-|WxtI*y+J>R!~-?gWq9CS zcy*H=_mN`Ar|;-8$tkyM0r7?{@->G0e(MipAlZhS2sMdXbYEV~E0X3T_JuCd=BVW= z7R|VA=YECj-qO&Pk>}~k#;+`jDFVA5^8#!c+JoUw_A7K*HN}j$DM+e1uHO+pnws`w4RP;|Evn`YAm(r#uESuVdI;|YcoL`E7)L(o4<2Fuj+ zQmSH@W=^xK(g^HZdCJmo5|(qH`H#D@ne*W1pZCj%Fklu5MX8Zd^;#vl$yyt`2%%~a zgupR!FZ5v?H>yPmY{_r(ztX!F54j$sM0^FRFz1jn3AgyDmAEB!qiUp4R1hs;wvI7^ zMHf{Q!?S6wLfuQm#!Rx_VZ9c*DF0~~RZ4Z|iv50{H)jTJAZ0284SmULLkV#aWiW`|d&oK~!JOU*yzc(p{pT%_H0Uaj zEdrteyr4NQo(;Y{ZQBXbm;;U#aaA7rdoHb@bGLli#BIX-K$f~p?c23zw;XFW1sr%> zvM;ikUG{qutXi)h@Ive5&9CJ-PNpy-=O zu3sCkgfewD$wInSZS04@kE+G@h66ZOY#kh2Zq9IYCU9Xo(UJwC=wCdcVzM&OT>!@d zJ_D#&Jh?0!0%B>Epfy0sk}F~)keNVL#W#ntOun1+p+(OU%g6Hf`v2f_>J&#U+xHJ+ zxsC*8G`y&acaHOQ>w3H3fF1vh#k0VR)Q1dD8acFb3lC60H3$xgQ2UTm$xuy&b1A-_g9i3@`scb!R*jawiR|Y9W4sX-~RqwfBzONjVHF}3%u)2 z7jnk@UuwjY<3Os&8<9`00<>!#cPM8g=f^q`0z-tZ{OLOK9ZJQjP$9q3p3Qio&e5!Q zdeD7f?5bXs*ym@2K)8swIkM|(8zo^X)N-8g9WP&rVoQF9aD(s&g`YsF9of3Cd~INa*pP+N z`Q^2x!g(EIK1cByZrma&m0M~0X18;illBMD`TqCU4CV2U4mtE@N%aIODyPwT$n(#k z6Z{u|QV+_vXlOE9_z>n5{FvC7X5bP^rYpqc&orUlUE3Yd8Dok`S1eKcrVcjnQPuB< z+}=Ol{+OiSo(c2sQpzYc^O8*22bqJuQ`$B;Q0VO8Md|z@P?iQw@1O0Cd3H*57?|=A zbC5)5F&nYSY^4cBgax51$%<`Ay#V{*HV`&2Q7dBJ1`F4lgjFe5|Ca)=3X3^yqH$pAn4MuEYa!~pKW*?vn z=50U_!L%1(ZbA6yj4e-@2E~>qJfFHZbf2Y9TeeESV|3M_L!v`@e=``NAvP8RF*TBk zN)$ggi9!aGM8rSJP(F&rI_L~LSvDjofencAClYCuer35Yt*nSa6e=|=!DA0*u1+B` zhe-Z2mt%-GO7kEgsv&M|9x`^oC-!kPL`m5TvBz(uwc(Et{hMHLhI{WS)29{jYYJmlVTCV`7Qk%Dx zkc4Smr?_-DDzhYEoPD`8eVkYxdM*=YAZDGTPrMQFOCMZTiZ~5&r`YLRPaTXctZ#9- z2L&Y=W(j$wDB+aBp~=$Z*{~|dmX=;w)LCx1bK=DQTx^xlQZflo0x+?6U- zc(kGAMLN+mkn-|l@DSB6gME*zC`)89z8OU^{PNGQ`~J3aB|fj$tYmxQUd()ySaSKR zR-AY~W-adAt|{zL`7}jZ5Kr{xt7~hvS9ZEN{{p^id@u@L_~=v^3SPk(_nDAK466=h zsF@EW(*`D6sqqmx@C+NKlML>fIx!`y(X599jz=iDotx-;lH)z7|d36vDc(t{@Ad7Bw4uDyE* zXr1sW_B9wT&0c+A7A_(CTLF_V0iEqQK>rgZw$R}QaN*Rsu@F(|qTdnd^wi)D?~+`F z9;8zlqoSz2eJA`gqWmlbs>`=pzbnw?)bGo2R2~!Q4j(z-^AiEwyQctLb39sc13c$= z@|fn*+KLIt76U^Z)Y8w(&X3gkbuAs+6YXmsBd+op3lX?zl{y1p4dD(!$m=$#MCo0N zAYruhRtVG7uuF8dQZkg*DWE0u=Ks#%&Xw!^C?f+~O;NAp(Gpzde3cw)(pZ zya8WDp1K|xX~wKI{?l0CiD&55l5t=&;UjS=$2>c7c!EgQ(<{S7D>02-qUoi}t%ZQ1 z-MC@bqw}m3a(7weWk~D9mb>>@Djq``tgGo;OXHY zhvmLkBKLwC8iZhyeRR+9?Y9!5!yefEmR!l>LoX_4G7{(iXSBfJ3eK7@R) z-7wQl8fz5rxOtdBvm*dR~pD`1;E&-&lY z`Q2Z$H#v0m9;F&?Jv}-E#O%}Gcb6<4o$YMve|dNb-FLYdRW}GYa%0L^W!>0ndwK+T z^N($WfV=-&n?2r}g_8#o5d4E1 zOBygPc+x%r049Qe-tFMNcWrxLrQbFPG^NeX7YwnaBF|K#$it+EbbZqE!sv4)ywl(( z*0s7lDaU$#6maJdo*!pX5Xk+-zk0}1sCa|4uC8u$bcNyRbm|dxO4UWK70~{dmsc;q zP}_nn8g4Jhv0|t*04YJN|369+kw^T`BWAsG9VHc&)u%%N_jUvEiEwn$8MSl?>fxOp3Rf+dMTd&G0+`yEF<)IdVP9P z9gv-B&>DJ%t-{dy!(LhNEjS0{OW0MUJMVrxeL#o1?o{gH&0RgnPjZRY)`$VH;J{YP z_iucvj43>s`BuH*D3#65VRtRne#eiFr`gcOqh@J+W|4RP+1EnhYiAOMg*uKlKN1=k zNE5u8@;=!R!cD3zHUC)?O`UvH?Hv@jh-L;?8Jn;M^4XSy{`@XestbATs8lFUkWIAN zuRKm=h;VvZpMGZb*VSj6sY}O*9D!Y|$&pVFLhR|ZSb^hHs>RH6hgb35;DdU ziN}*5jO- zXv#$SsEA5I$Xmm&5x4) zBq4ixqQ36k0I=Bqq9m|B3UTvFYkO(1-z|WTYRyFmMzV7G{If1JU9mU^zp{P@6FQ)& z-gE0!IfmB}ZSe0ghZ=AFhg1t)sCS2A`Me20z`?WzjJ7o_>ys+tsfoEg|Bc%WkBl_? zRN@$ihp}r4uEpb*W0POFpx8<+kC=I$=%=EyN8S{WE}XCFr55SpzCkhDbQxJwS_v^E zXIk4w&LZ{uU-^&Y?kEnB;=gzJW9Q&d-`J>FznrU4xrqP_#Xk``Gk+&e*>hz>T&ra2 zlg3h6uxQyq=&pUqSYnBiC)gT=+n>mla)fsO{)$s9=`-UX565cgkp9K;|H!(?zuJ+E zcR?rm^`eN2O9zdDYYzu^OWK1gzmbi9CMp8W&STOY8VM)iP!tW8KcM2G5(qqBQIadD z`rj&vY|VVVO2@vmcEWV=^&Q`M_<6F_+VFAbhH4H!dw0ir(E2VUr{jvVPUzz;GK4D} zdUmYjKiY?YmM&kMq}e;-I^N;am8*dUk}zmuN(LrImc7SWk6h$f_w>_d1tv1;_mEY{ zio|3WsX%T$cp{Ok5r=6=SrVWfZ|t8+#Y!h)L&)W_WUpqVV&i1bu1}?+22G=! z#ssqEy&RuFvr|pSc3A6yZ7+zpd>)G9#j1oCGzFV!B}!MN8kEJ`>;k-C`WI~+nnsh$ zaSj%+(;i{j%oBo3XM5We;525|L9rBaSRkFF`K|{c^oLUr_m@qpu!Rg+Y~w)iM~;8A z4ILa<&luIq(_*ay5ipKSK0gHi*Gp$&X-PD7 zK2n$D-!vwLMhae>rE1@_AOO1p5;c&OP(n)!+)Yli_NEoaY{Y+m_V~>*0eqQSXoE85 znGZ&|^N9lW;wpbmj%picDUd1Qj`0uO+XkW!`z0cOWoZlTHn{YHwdL>M&!F4F$=i9$ zIb)mPfQd#gtGbcUIcIag=T|7NMbe&vk?*B^~iWSZ`s8lImRF(z)V;g~)1OkK8W~A9ayX%xQB_QSbg8o|^nVlr^Hv)o1f=zkQe%vvsU( zj1@EIFhyiYBKw_;2GfE#wRXz~4q#htz-6vrOsa#E{BPRlpGK3`a;NxDDe+MgCMt=7 zmT9s9IUS)$rqV$T`R~mgs*44lul7 zAh+*V>wU3-_V-mu4Oj2@;*IUaQF_QnrZ57&r;9MIg!Yl2tAS2_LWm^zzGdCApT z^EK>+0;YV~Gbhhs5mdEG6~$aZgmcSLR8Cc1#^{)(FIW+W{r;O>#uh}LH*pDOCq$Jl zUz414;%_Pv&`b+ba5t;&$!Fd<7h9aHw>JNYp+OmPxz>nDrW|9Ahs|GBN9IahtVOB> zY1b=ojhW{clWt(T%ywE`wA!~1X16DkKn_X57gvTrG16AjUgI1PoHk#xYY1y124csI z^US`ZoFwEg)To@X<<{2LHZ~s!XR?{MF=jo=G6MK2HuMZvN_c8Zb8jmpVOXCp1o!4? z%Da~Zb26*)V>`CUz*Bm$Z zXZ__5k?^1NcJb#zC96lyp03gb%Vek@gSvP3W$CTC)~3MTY>ZD4^32Xs$zVu0L;D}= z`sOFbAUl{{B)$vV3bLt|*;MQg{sC1~dWMElh&`S{P!SKAHI~!)o_gZlfx|E&PaLZw zj_pdACsYbOM6Dd>xj)V(T4#cPjGHjJ<*@eT4v{=;duc$QS>r{~R%1JU3P1d=L}k)- z3f|>ei%whQL;8Fu&6vt8mpM-+VA7SbTk@$9_d+V!El7MFA}MGh^1ayO%vr9EP5eb$ zl>Ps!s_w#MB6$H|mgwj=z<1f~{~+MdehLqEBHU__=?_5s3-7*NAG&bv6eK%l{!?j4hi@ z^uD<|Tle|D!ZAaFNy4{-NtH}vwgQ{SKMVnHHU@)e0*aiDsn6i6;$7ONl~{s&`h@@F zkk4I(gB|7qgY+gRv7$ApN7|dAVLeJNR3*XtABIl>w#T;hwXKo@k^Jw4EjWl1CoS&p zOHQ1duae|6SuixjOd$Nn7fXWHSh0f=bI9<)7y%E98&X~=%Ul**8G&xvrjfFyS9Fzg zqpxagsj^P;1!o4eEixy$l{|7dh@+O)m&v0j>Zr`Gw)G|Z$Tf%x)u>LB9v({Wr+_*) zf5b`lsv&p=e(I`L^8C8s>%X>l2CWYqD#!p^h$Zn82WiSv+`WV`mscZm1euvch1LM{ z1!00|{sAurgW2qQ_yOXYS1JY`%t50k%$B);DNiq zpQ=g>37inng!rL)^|k46^rm9~Y39DTv2=z7i>?Qs3GNizAm;T;1fRR8uapT?PQSnS z=Zu(%We9M8Eb$Y|6-ro+>P7>hynqhi73a-1YS{htD@|w)EZooR^%MtuurN@+g90Vj zl*FyG6cHBewo}_d>-{9~(x_u1pW^&dKpso-o<@!n+>9&u06YiIA)t#3i9WgD~bFN*Z;pk|F3WYoGPV@5UWa{hTLubgk@5WaIbw!6%WJ zL_jKS;~V(|7{(DjI+NOa+2P+)zU5I1zu6bL+uzV(q3fFZMJuJ8VN$Bcm-(GI%^Z|s z;UDQ4cdYblVsw7G{#+;VggD)c(OQ-ahVGIMH9^A%+Fwg?rpgOsV}U^?r4>I@e{c}R zNhhIu!VhzdkH^I_i6P0;$p}Q$kjGzq{%~V9ilB#Ef%_$ar4jFrCXy)cx`}z+hh-Mq zG8ofjv+OnGcVk?QR^AMv&?b2i0%BC-P8m&RF;!m(h@Fz;*RfJlkB@#+h#AiqM3(=1 z5vdpbsBPTPj#)>S4L;jEZOz0@bdmsFQh*V{xR0!5DY=dB26;1x?A)MhyNx|(mJ1s| z`6$1~?^elfRHUoK95?vx<)~~F{aIkN=nmm5_7*-pHq?=4T(TLO#*SOgO*6%|AR(Yt z)_u;Vl7J^`tUg^{IZs_%sF+@fDf)I$wzzkX7<kj&ZC<(%yv`EjCgeaC!ar2Wq z-oSDFtsAZ5wkb4L6>OHrPG3bR1h^eKPq5%7l^cj#=}!Do_g5^3oCW<_HhE}WdTcG>OWokehNmtB-SyR*4$@4_CA1n;&w5MFO^gsTRS7@!R z?O9mBov=VLMNJ$@D=458D0v4~qiD(C5i^b{hPf3obD5v5zA zWg77%iB@Rs0F#9uO*;VZdt7y$dNgAAaujVafk|D==`Kcf6PPnsf!UX+{eE^#ujRM1 z)BCADY~)1X^XXdL-}%?S+ZsI-HH2m9p(0NpOAYiUIxt!MP_=Sy9$wz1<#l5}(_pfH zJz^>5;OTPr0PD}DpK$Zt%V)>&v&q@PAr^e8sxiNsH22FtZ|=|jvwEK3TTNJazeezc zhc*ce(e-qyzOufez)?mL`>p)O`n4p)HvaVrmH(GO(z7XCns0;`I%JVkQK$}P;mawwWlXNND+d&CV5 zm1~jTZM^hVZ;v5b;T$9@q(Y@gIzwK?Q8Wls=EsE=E% zzw*)>DiY9K!QEpkV2V5S*Ed#{yH}OuhdthBx(F*C!pY+rE1TpYi41cs(?~yz&yH@c z8ASuPw`N{n=n0KP@v%#)vz5$=wqqb0=lj+45rMBuNG2z3hFjdq#eIL53;2di{dD?yfay)qE3*YNI3h290_v-VJqP|^9MULxPkG&ks*LGl%#B<{&f&R_%)!{ z^>r}70;E-kfh8z$C5dmXtCNNOrocNB0*D+tK`cRZHe&ALAt>7!1#*zlHA`$V6o+=t z^W8gPMn*;#w<=hQ>_CUIOn2kzQH%P3cJS{g^y3R}uu(mGq(&pgR)4Il zY}*e2S^%%=pp`9qG=h=*GBJnYO|W)EJ{fxk5UnILYF-zJ+){Sl2yW~|FK+xCj3xrK zB$h<{*jJ+F?A5~ytEP9xel-Cf0NKNa&jytr27y&?767#nBKo1A#>}3J@R@Zyy5)X` zPxtm{o-HI9%z(*ivR}_vc5vMNjROdw!O6?FBDXWK&$tZ#QC91s0X~jigiGr6w{DjE zC)6fzWl~rU zj#}4Ka%bgcMc9%MnJ(kK%7lY|MeUA+A`VzThQG|WE-iHA@snuyLaAhDOivrR`%;~&tb*NaWh-wl`kS=4XD2W1yF@DLsjQ%R z!jA^%bDbvvmy{arZ%nB-7W;~ia()5vk8tdTMwT?1kmd@uA zdRzS*DkMt?Wb!U?W{(^o`js-uZLO`UiI)7WrPiDWm!L8GT;H-zBD1CCd;XG={kw+A z5qcTTrXNYJ>F)TEiku~`>8p1wVW^Sa$bmf)raNB8Hv9(}EwZDWZejZ^qU|I7cI8Y1 z9p%(=)RMown6vxYw|gn#O#Z&mj#5IDu{d+N%OC&M*KAs?=WqH(M%0#)F3e2IjL2?U z`}jLay6XG3?dn{63FFr{?c4s(_kHvS{=%30L`sIIs~6Od%hySFB`D&@`Fo#U%;FX% zzov|M$z)77Yj4a!0U>2y;iD<7L|V{;U0|ePMqS8|sCijB1orZ4=`DF?4o3Tn)$@U};>mBt!kd`24V8Efel2cr2-V z+&)`=TypNg#hu>x7F=TXsyBmn-#Ix_^JzZv`|J#?{Lo2qFRWMPmaD*6T8ppD_k2VB zK7=;D^CdGq^+=-{W$KA(rRqPO$Z2>=jxbXxH68SL2`~TnWk{UB$9;OQ6wukJ{M|)T zHsoxL%nF+4_C*a-iM|kXpBSkqLEL`_eltUXFq&pUGTXaSu|tEhRP!_+9S0Ax;(OFRP9(X>06Lm z8zotAb5h6Dm)V3mma(jd!BOvYxWLR}*a;{P6E`=v^{C7Vi)(+jt}q>49X^yot|{30wZg#ir0`t;5bfgwKfNW=Yw-@Hi(*><78)-As*=3-A5Wxh1Gn1BkR3?A=NAyp zUp!(bjFsN%SHRTSyPHM3?@eu!?Eoya9jM)`c6?ajt}^VJoY3WM0cZh`S*Vq(yR#fQ z9-KW*t!Mg=C>L6Hif|g5j6{X4al(S(5Jg|Y+>|uk6x^=Xl&&WK848l_W%0WdTTZ6? z_>=_|e|tfWPL{l&XEL%xxi;~~pN-Qac37VL!>jN!Dca z8*R7d=z~C{ZGm+GPSG_Hhf>-F_HB zohkuUaz3*%b2=;gp1?n+fkO9p`v>R4kY>rk_5%n-tn8zBY*y`p4B zVcHEUeUU<=+BbPi7c&zqYaM<|OnSusWQe8UR1&D@%T(b3$AvyBukd?YJqICK)F^Tr z*`8L1KFQrrP7lf+MJX6fiQAFwf&Yc)*wsl@@>45SF50ZqDqS~2c66h7-G)7Mjf?pp0%uwobtpj|#B*jJ(GL3A-^ru2?fb*R!KST+NNhE+dn`W;UBu7>i^7XoWh zapaOb1LHBIBH^3656GR;Lww3kg)a4!)vw*g48jl;@_tQp&}T)=lCdvr;O$}k^1yGr z(*Chl+`3Hh_E21!i_igD@sgT~o?PIY3Z#-##30xvlPaCuTzZG5VJA=1_I9!@g)K>v z3RmBIsW6+9_z&y*Ck!r=AU1ImJI~jc)vi-bQ6mNx8m|$_7mi>zoi4L*79yvh2>UOJZ5S>}BaETc z=(r-UIVK7GDvYmQa-bqH;E2&nTP|e7 z(<5yU&usb5(4ZGZH{j*Xj;;NFeJ;SG`z}W zip;kn=eq{tgStSycF!4VDCh`p4Ep`|FIijoo(!33IjI79?R5g_BD`e>o$bk{eBhsi zG9a4(c}Ysw7uEg))&38R>poZSArR)*z>)Uct6klB8=)k86Y~7)*@7P&{83l**SBMp zuZ-XI)0m4PtI}CUa-P+rsN~>%g;^BC2cAa$d`>(!I{5UWit0-L~ z3sEw+&Y7*VQK!r%>>gB`Wh9K6S104pl zu3PypKC!O1`2J5Xmse7%X6D|%%HbS;jyh~b8tZYf-u`kkb{-41R&=~@G3TiXp6peh zdf481CMQ}x$AGzH!_Cise@f^I-oS@0G|uW5(F^Myc#fgAxHsFF&PDrZnD1>5(hD9qFS`Ggu~xF;4S3blE?S zbxZ(<5Ii|DxHx$D(&Xf#)(SfnjSsCBcG5NCRp_DlpNkMM?NAvM&fyH)g~PIz+T5iw6rZ80q%Bs9I^!AFX^8;}pW%gQ8M`;Yh9+qsoo+oto zn>HidnF%zi8GCFFw~UqOMC;Dz&hCJc-Bfyp4Eq-xP$LdWjepe_caHIPNhS#5I-Prs zPyUIdWBbP zRM1oS!qzBQLgOKRe841(kFem;KC!m>9M(zR%Wx7Q=-RH-&DtT^k?@vg`u-q8InyM z{maIVLBjlBOTOmKir{lnA{BoB_J}KcJ%G|N}hUiq(?1_EJ;cC+??+N zt;Y*uQc_lIlO(#+kJ~a=uzP;msUA`L3(_HWCt~0X?_F5XSZMRJvtxFN2s33gPyj?? z)7a)F`H}l7ObR9f?5seSV#_l|Oc^n0NiLTxkCOb){?p2@ap(NGgJ~-+ra-)*=lzoO z1QdAbi!=@h^Dh)BnlbJxP5v(keY|iGK%?NdK#zX9Jya!DU{s`+HWho+Gu=F1t|W>4 zQW?L#zOC?3B?rGzO+&u{P*1`y zAY{TtVve-IgtSi~QvPZ*+}lCvVEqF@D6tH@-{FX#tLJkS5$Iy(;azX-0otCv=U?FJ z1a@{1mE`08$TK!kshe|peM$*Q4mM;BS5NePT5S{$$E22R_oc&ZF$$-a+wzW4rVJ5_ zcyZv0oYD`wgseZlwQZd$@%z(W^L|cfU=OLT*EzC`OR3=?sP4mUdtmJtDu;H#SRwh@ z2EW^H16Hh7xm{nSFsCzLC1^9-O=Qt^>9oh9_siCA{>Hq$)*Z05vnfK++8Xn8#K}%7 z$KM8B_AI!$rPz+&jB{N3__!;bUe;>qWvpJ|2lJ$`UG|so$eA7XUV;`@Zg}SR{C0JG z)Rac#s@>OD%AuXs$1dA@p=|h+99vq*@fb79gTsx=!X)JP3ruFm@>T9E2~{`ltoBm_ zNA~-cbyO{A&A#Tpdi`C#24e?OTAfqnJH3ZI)b3nKNSl0$Vo7gegoMNyg;W9tG7K6LG&}SxEMcXV?t=$oS`JX=9Xx!r^dp zhYQANI4sO-6M;7tZ!Id)FD#;BB*QeiWmUx_&Zy-mTsaCI*Z z;fQpJ_x~t|=Oz$Z6|a#aq_hVleQBRFtopSm_FwUHhxNA-p}e8^LWTiXCelSMCWTMY z_AW%VTOhfzKUc!QUdCAORW#empf*kHzlsD+oin{9l3{~xauv34Nx7`iB~tthA%R)5 zz;@M>-{Rf2HiFN5?orXdKk|J(iO5EGsyv( z7vdox(XtrTFZw>>m0V&Nj)&N3#qELN&f@8mh2vdWQBl*{DqApPWa<|@KM14{jNcF4 zq5^MxCGScnjQBvb!|aiJ-QBsbedMHXfcGKx=Ih)9iV@;L@6!-^4O4=|#Inxb5d?Vu z)=i_~%^C7ReBE>!b6j-Kt%W^L`Ar(g-3h2Kdv38Fh{UV^hB_t8`mZ=HGT5Mh%+K8t zsYlG27x5L(!Xh}f6#O3!0le^Zt!vP6%K)k5mfXewMA=q7c#Z=er=B)r1MVrCx|$UL zI3=7}5Ivb-KZY}-@zUw?-0d_!vk<9%o1|bSF1YW%&f7CN5Pm1!_Jdpj$DzY57#wyr zUz$>2jT9zJK3VsNMSwMiU4Q0|m3b2o?qFK3NG z3l2|Nnj?}acFT4%N-0`9ACew{721=&<#TM1c|pf1EVw(zA}p$zWg5>R%q(~YM{zYi zqUeoa7Gl;}$HG#RQ~tUR#^xf$VR4wiJXCo~P^+cEW^s0;XJm4efg9E<|L-uxII73S z(){v5Ri%0P9(BF3x;ag~iKd393!lKAut5DVp#^PdzQoETKDXwWz68@91z*4asDF1}$ zaN6c*cr})Sh=p!5#{RoMP98Jqll&^DRSXgjM7$iQH#u$EN(>WwcAye^%EjZ(_2}j_ zhIdjk#;(oo_}3MtF=pdBLFmc8^ zeWG)j66pbq)~XK^f<5LGQCppjaNj1_bugC_DmBcbYjHEhWTPB{V@*5;B%8lA8 z-{5i#?q+gHGD?Hip+sZiWoG6-?a7VtGGuUph=~6|zLxgIeHi*n1JtGLeT$t zzXuAS#1X2oUEK3dl+y<>)O%nK_LsV^S@ct-)0$Y#T`CCR!*>QPJ{i$8;JM2Z34nt4 zXy*^hr&D3z=$M#LU@>g{b4#qN4%+=Db(s3J?_Vtn70S+ZM5H;2DX5W(HK8VV319P-o=BmiI*|Qkz;v+5iuxArfTuf*3J&_ zfq#n9$Io?}!^`_{J82#3j^KFo@a~G6-H(vR~inLlfEAczW2l=>t_r zV50!$o>{J*tH^1|9K>#1W*rUDt-RBb1qyO%aBpd(EhFYXEd{4~qZ-IVKW@)0S_hQEQtZi}%r>}L* ztmx&CF3%M?mzCUiQ;b*3wAq~WiPKBWxhKyf@Ql6>~G7GD4EbWg)Q=&=fe5cs;k#$;kU;uZWP0q01?3>$kO-NOp*|9HN_K@p| zruA_)<;s^D723FzrG_Tiax#TzGnQ9drLvzK&=-iP`d)eqh+2p8j5cnv!Pl>?bbtQd z*zk$rBiSoCq2i!0WM#sY(=#f9Bk6opJtaj zX~LMs>tg?#wAbFNEe2S}FqbGixiY$zil}V9O(<8qRW_!q48C;G2h31%ny6CvAXxMp z0Ge7g>VyRT)8&sfN4Xm$ku{;`(OL7*-bttaqA$OPvh8cTe+hxs*Kah4*VV8{h~=uu zCeQ!{>@1bBaL#jJy9i&d-**cx!o1{Hsff^tJ)pMATpimoQeNWq_iUNJQtfMbV#>)R z7(bs%$7X(v1a&@YMPMm7UhC)s3YYyU!=Gy{=fH6bz>DEZ-KJ*uBSKIzv zXu+R30sd7$PTb380`gJ6f?zyQbO25r4x+@ZC4)Clb_q!+6~ z4B8rH;>@H;v1exQM4VobIU>VWz5ZTbE{(Rv*1+=S(c`yD%DN%(?jpI;3+Vk`IAjA8 z#Z!aI@z%N1U!FEm&vK%VUa^16$NyW2XbPv`&9Ulu(T4{C%vmP0*i=iEKc`K6FA^(V z*jfBC>|lJv!PI|1l8B?AO`g!ubW=#7bpE(_pHD3qqu|@1-F|F5P z|NmNmIsdPvwUT;e9Gva~q=ME|Wr)&IG-2Pw=he;Za2U87qNX`SGqH~38;+p)1}`2@mGtV96_unoB7re; zsXh_*rh7_#A+Fpucbe@7F+^U;qh`5s7925(5K+QljY}7DZjKii$Z`n~UJ(b^;0p~(+q)bo5aZ>VIo#dMHg29hCuTxF0qneV}t7KpDN5zBHn>ALQU zJe4O$JiB9zY_v7bq!VJ@kqWHsuX;gl>(H@m+iS)FQtqZjj^|ED6UX<)6Zt<{z7rye zPMg}pKWeN-{iKsOOFi~eOm;GMI}@wrhTYxb^v*f{$fY+SZDSs7Da$p13eXN<4IKt= z=>5s;XLqYc`9LrN+V$BOYx;ym``IWXcwZX$U8uhR73)(oGs=5HEfrjPT0^0=NiCD9 z1OujJYspHnSo>tOQ*R8>^OCl%uklg;93QEa&x6>-&7NR{@%?kGa|4?HV0uekgx&l0EEwjq5v>} zKw`gjhDE5@x=cRbWPabV_SaT+bYwO60zuejM?(rF*fGE%VUD?R<7@vuD{;-arTL67 zQTH)nLt07o`z_8X@=qW%0`+TwsC+^$k7l1M7E=Ff@~7MCr_qT_Ua#xFQvHk5Qd;e9|^u68f!z$Fv z+`FpZV_=TN2RN6XZ7g86)VI}3G_B@ol%r#j;Rs1%Kgdkc_}7p)@UZV9t(DLdVlpw1 z;tFdM*AJiM75{a)H4(CFl-7er4=72bbO^~TXJ1a-BR5{JA1wA{*}lgZCKQ>qgn0R^ zXoVO)Cbn#BO)F-fc#vv$ey0618d|0_I{<*cdWy=D3^X~6yOA5;MK^!kyRC*6s02T2 z^>$)R#eD_+2^YXJuC;vMPLYg_&0R@_>`MRAK3>}`sZ9*P*$_pg2ua`yOPVYxIi6 zuGs$6Axo|a)piL^Crra1Uy5^8RTGg=1l4Jnp)ZGD?3S9#Vb)J$j-3}oLXL8z&YNrn z*O(4d{E`NU29b5%`N@4aMn*uV2ty1Dj+52OqbNsb48yKN=6LlgluDd}UBxJ3v+*co zOC`s`nmA_91rNz#1hp5VUc>1(y~1WAh_p3B+0lIYr31eG!{AOZnS+h6X2;E`?3W(gL}F%y=uwkx?h zpY?~r7pU=UCH9YcP?h5jXL43yZ0L@%Ivnh8ubAZf@)4gsyMfnQKEiZB&}9w4!9gX^ zbC2iWzv$#}Kz66s>=>vsaruvHaQg5<8k5n6ey>RGUhDJ>Wyl}j_rd+#OPySN!9Z2I z2LM=ra0F*Wk_yVhx2`I!cJXl9%|jQI%fUl_h3bSiW*^Yu)fjNV!2klrCnde2HOfbT z$7^0TnGCf8a%$H5*He5ECI}b{)UO}m|6}z02cpp!cg+)S4kB?;^BTCn$VF(@vuy*+ z56}yM3ISf2e7aFQ773c; z4ZJ1ce()D$i+arjj5(lWh3X=VMQi^4x82)jZqWB{)H0rbh8Few95r{<^Pp)Y`PotE z|9GAQG_nM-v<<7^4dlYpMLK2Ac=~FqqVQ?9K+fPOh}?03UqGMA1#&@H&RBj)s194C zEBbR`C!FH~mKiSMgwm~>G~Fiu9QLo;-hR&6sj3be_5|j{>RYQ@nZ!OYn`GXNcG3Eo zpMdXqyvcbo+@jlAyJTTh4&{rm)kWN=%ZGg!B@;YUWW*aC*1V6bkNq`%bA^35c74@l z@uvRsIBlll0Ko~~R-x*>bN$U-nW9=qPHh8i56i4jYT~{2#MzBra6f%DROri=(@t!1 zb;){{zwpM;#l;QN_6XeNRwiwUzM@eIo$}VeNB?L}xh6WugO^U;r?T&U+RBAkk%epZ zfpVFCeFu0?lZJO)NiNDxE%2103dRCvYy5>RFeyL3V78FykSb04pTGD-8K{uHe1Z>Q zeAAl@FA94rAX?5ZTLdSTJF$fYWktU1unB#cuCr_<78D;hn8BqszG6yqghBBZNsKL? zjNCyeez*MLz%__@G8Nf`T%%!wu~Ca{xgEXAJgm0sKeB{C>JDr~JER|cVOHNY%HX-x z(sKLY-W6M=o5Y1EM`4q5zR3vvNlVngDh)bF9$rvDF37^m%c~89#WALqC{P{Vs8bNdo_bLsA}nkH#x;Wv#b%AQ|ub8f$u#H{7rGwPj9fpAoIe>4hpwj?e1pRk3&K&Bp%jwFBj?NzS?m z0)|yeSb2_tq8vfNl!~@u)!NxPyd1ghRiZhX+J+0IdAxnIQ%p*aY$+Q@;%KjFWFX7` z3KATSzfWrw!e^~Ryn_lQ(fC@9UCxiDOZvqkDB~$5?Z{W}qRn9`LO;QMLpJhm2z3f^ z0cYNaY6-aMYBrY;xtdc2?koz*cExDD=qDC7&Xr4!01ei;M^+CP3G)kwcEbnLckOdJIK{m`AuB?U;qkz~2pj<*IN9@n5r$ zsvJhOjHVL~twz_1maulnPOI;}X2h^~#9h^yFwkO6vipOz4|*2DX);I7-6ciM&R_?iFiWT#}2l$ZF)_hFc4=0dyv48dmAn)nDyC$5ESkp6g z1yUIFB92gDPB@SD;Ag_h+K&pn#& zPPtAJxX-%54&3B=#SPehFyFiF9=^Cg0Hpz9cYAS&@|Xqtj~eXOEVs|qO0^f3ga;=B z&w26%@|X5p_iHD?12y>zdEA0~IOuTui%Phk!A@j9gKU8Oe~~BmmnC8v#$Vm`HW0B; z1_qgJ*S|{*12>;JuC@(#cS{f^r!t=S=U;Ypb`8Sf7<`qvKMKSGGPCXedcW-^$;*3p z#moC((eBT|K@D8LR`iO%pe?`N+6qiE+||pSAc|!CgjZH)W6|Y{b+9n zZ#RokMyMp0u0MpTpGj#QeZv@IDR*?IICUo4!uCTNozj(PCCQqlUJrv}U{`6Tt~zVy zh2;3I-sd*mQm zKtA*^Yt<((K2`|9)-7+KezWE?iaKkuaK(xb_t zG8GiyOsPCsh(~deqn3o?!Td|A&?iMQ*vd*Oy|_J>NnG~iT9@exk2|naVSTvGGIB^E zOQQ6nF&Ka9OtG=$vux}6+RLU3Zv;f0q@Xz?;`o8n%FNDpDpAf>%-um%JQPtUY1ZK<##y=aYdFs;v9${ z+nso+htrP(1S|o8;;q0RwlwaF3FgK<_l)fa!ig|CK2;S$j?LkORU1_)RWEqwr{*8| zG*SuR`QXkRw{9#K0!wNQ@RNXN7OZgV&On3=tX1&>k)I~kaU+ zflZgxhx5}1E=Y_*viJSa3iQq=qnIhU`;j>&P$lzbDo^u{2ej2UvyCw=@ugm#A7>R} z2T_9D-2JluNUw~uE{8IH>+*Ww=qb`E74%Z+2Z;F6!L(ze4MqLliwoko!HT#$&e{zQ z{RlBt0q*(5&lVp(mU8Q-BA3`?Xoox4+cy=T*p=18f$H&mfGM^oJ}w}*=f0?rd>qL(6-Ss@;Z-C-=-tBju zw5~nGf(M-D{DQ(t;|MP`dO#PGaIRK$wP64jdbl|lcLkK#J|OD>W?*b?ZXOJ{1%${^ zHSk*Vj z;R)Rf1mA5EfvoD;54-Ka%jbdPYxg@&0J6XD0$CXkF>7~+Udwl@K5m)hwtEh$JDGR+y)OT3W-d4Thv|R9YhLU} z;g_&d$x@G+M={p(TwK_g7z{;^$D^ZqtBDKRNhuE;i)>jvPEoH}pWDX|fps++T zM7}dM#yb%8QvGp%viLT+i$I%{ihFR)K0EqtOU&as2|H8i@&TNdfrRf+>O!h;T2pdt z9q3MNh!mY?fChD;`$69y?x1K3h9#MSr~ec_C~(=>Mi`sN5w()rH9KH3l9=Q(^N{es zg9vE8{1m<+E#ypJGP(c5R&#emL3!Iyg|5Fe!>`?-J>$%2!ug9QTLr}U!;7ou3sxMh zP%0R>MFg+fAd*KDf6t1@I8?XZWvp~gvM|UaT5c~6@6zk*Q|q->mp3;0qu>+Qzrr~> zuM_V-PnK4;jcl{%0;AaHH`rdJS(2GAHoawnojbI0#FO+;V4k=!D^0)Df-i?T8j!GBSiw z0SH<^NE*l(Ox6GcJ>b#7VDP4LaDCm>vZ(Ek%5C8Z>p%ZDShg5Fl}^(+^jT5g_hit! zGpI0xZo7iI`0xK`l>n+?3GDCIWi_=3fex@cgQ-##Gobt3!V^agbfCX!c3wvUpGtv- z*UUiw#~rvweFFQ_p2_59Y)hS1CX4VrIJLQC&sVe$fP8m#;;F+r#83R+#~-lu_C=A; zm3V~Z(VvE_r~nlXz}vSK(||m?Y*zP&aO2<{2u<7CRP{do`8Z5A3=oCWyhbmlUR6|R zD$E=`ZwfpT4ZNO_H3a3xASI%dnd51YO~72es?pfKZJfeJ z<%Q2*?RVbW-ETSt^g0Ec*{%BTzJQY|=W}}hWqlIjV(t4%U{=>&^`ySu0}*_|pLsj^ za3$6ZaJP;)7110geV!Y4f$|!lj!DBoKwk3|I3FL^?j=9HILey|`370AbpT4BgbFdj ztwP&?Td`2;^RmQunzw%I7*|p|yho8i{BM$XH)^HiH||3}FALBqfDt(8Xa7ho{z_P6 z=jrpmCkh3SP$`mNex^bmVhWzU7r6ZMUn(2Ib;*b+T~5FM*fD3yX#PHAn{8|NVh3-h zuuvw?Ba$2a>$7QVUfd6!g{CT@XtX^j#7R(U%Et*PoOr*g%~o^q$Q66ug?~Yt=cg6N zDAgF3?}1XQsf8;_ujdBd^MHXKQv-rzevp)%$E7caRJfwGm>6BCW4$ij(8E^xt0K+G zq4c{nX~oCSfui==u_8{TFsfD9%OfFWakvlM9_3y7VuT^^88l@989HRp0M;&Ld_!8_v(4&^<3*^Z{Qvy;lYoa%8~0e8FeXqX}~fo_=j4Srt2}iB8AHcMwZ!)0(d-Y zrSt{?As=0UO%BYmK$mj5AY$kCGwqqxZdr6x!fkcS^1#0(O5UEu3X{J{!xnvxDmyv= zzZ$1UOyz(avaLrK2i7Ridf#ml?~`el%_0(tO%ky`+)D`oi#V7RT~0QnGh&LL&4z4^ zq_EJ+_kfoGth{-47d)Ah%b`;&34PGFUGv?< z+keJ9J=vMB(1t*J0*0&`ZuNjR-MLiNm|z5ms?97I7v$gd1a z=bPT0F#{hx*jn6$YWc^q&wHvO(IPhXeok7|a?Z_{YMadeu1urZKOS=)dPu}UI(pW19oS<8PeAK_%#zlnmr7Nd175xyLBBaZmu zzUOY!V7}cjFi*E-R^JHgG5c;Q4^`Y~j{W-n<3h;4ropncf(9;XEheGwQZm9(=5`Ea z@r5!P5iDAyb|FG<^YQ41v)n}`zvA2QYA{;qWkuN5l1FM63Kf0S`83<5)TLxH5P3x@ zaZW4oni_(f&k05UFhxqk*VDYi7H=E6tEakbDSbciV07tFwp}g0G(SKm6#Am}#G-D=Q|gFRm08!jQWK8$GRrI`{F}Zfj@`389Mr2!l{}hLY>q*U7Mi@}nt`)oFkzqj!U^g|ZR(%$u8{cM@Q+ zv_3UsC;4;g-SSfeHg@ArhUC@!Xd^4 zUH;z97?S2ltLs>EQ>Q(Fdikt(G#;Ec&_V8$zvI;csW>wfGL2|SPo(`?8i3A8-?0V^e4`R-Z>MMAuG4m`uUpf;C{ z-LOf#T*v%7#qmP<XtU|z!cq9U$u>;NbPHnb*bax$_h}ESGU*xCm4hRGTW>9c}zRdM=O+qj?BP_Z=Uu*B= z;081%w>M!FqPa1E4^d-UVnqTgVNsS@lfQ>Jln+VtAahfn*Jo!zQ|=bE6( z)5F(tOyh91qj$aAG*7i+sN*-D!T?=Ev?6Ny#%}-oLN2{<6eg-EYjbjYry=p*{B`M< z1_(iG@})ZE5#RQkOsk}L@Ki5#jQ#4!D?;m*EjY64w9cnVTEQe=Y0 zI6O-&lX)w^dg=cf6#=YwHPrh&k2p?m6E*R5|jq=i)R zL7X7Ybg1R;qu|5%VT%#JZx9HYU(~D4gXsE}bNPVvZ+tO2Uw9uEe5dBfZ!j47u}K*p zt`HrGMBjsr9s{LOQedR&`K)&CW5iOZZe8$6704ysPzwZ;zFG=ZOF1^qz_XRM+RX{oro;zIqaW4!J8rLyi>ma_@Id2>A?7{*O-6nb?6gQ;>2Pm zkTi{e9Ry;V!CMY!8U#oQVx>UB>6o_&SnjyUV+8{5$$>I+3yjC<8m}-Vzg?7q8Y#=3 zqFtMayF&0m*?1c^+3($dGk45fub-U_Dtbk{HH|nSTb~mzc75kY` z>!RrVRIfPe{Kxmt2y}FQ1D6z#X#z|+<}9Y{xg)-G>cw;hNRc$Ecblthn zTLhrLNyRq&54D$rR?T9aXoDobq4h@m#Mz~8cYvcMS#eCexj54Ns->oox8rQ}^Z#oB z>Kn)`&4U4~0+gB&`JYs*s^^0l?luI97wTemF3u;aYc#9?v*PS5-nnMQoep%PBU4j2 z;JaP<1r%TWi(5wlvJcRPz@8;GxjmX@-B9LW5y<&-w6enjxc#pDRHi1Tp0;5O{V+_0 z_$>7bU_y0zwUJ2FJS?tvc2J2p47X+sfY{^S|E1V!$|7`6ynJFuX7?z>wC`}0{ix%Hz4LyqQcyquM(I|oVCAK6qx*pkP?6$n z73$?$0Lgz_U#-yoX7ZbuY=OGv5ofkaIzw%=Gc#_>xxEoD5NvGp%LF7(Sn_mS|5p4M zENWLyI88?~OKbXYFIqb_drmF+xxW6kv4Q!AMa<|j#9q~B%vDIrqLJ5F+bPVXW-G$w z)pF=dHpHL}I0s|qH$MvXB03GTWVXyAWT~*NqgANVyDdUUUM9tU zD6s`OHvMCDa!MplXo0#Mj==PkW^>1vnXNsRn_`1Od{bI_XM=%ycTGs?bSe@71efWP z{1OH1NvamscSs6$i6*W_&($Y)AxlwGZXqE5Q6|Q;Qrh`=lw2sFO9ejtAFONaP?;D_EBU09qvA_7hMtA=nkr zM`&dgHf#|D&j=0iz8+14DL&{(nC!F$BUj<} zNw?AS6m=C!>+&56palWSt8q)7eWTw5EyUk7S~Dt$&R}BgmqoOmxi2x!`#a)iJ3hEq zOR8Z2q$eGz5qQ^HY~6kVEVrzJAEx(Jvs7Pp{D15%u)hJa8eB_&?Ij6Ir$v)bWOYth z5a=i-y0+o}If-E^gWK}p|9;yE8t|le#%4f?%)Ewv7Ff6PG`_;NOEeF#!dhde8rq#= zxWLQ_N&(B^Am#>)v)vWSr*T?sTuj9J#w>D3&_t`DBq&|pe}Yj9y@ z$=ugB%(iI6-I7D&;=iU(%i*otTQL%NHp#E;NnFa$8s$~(wUV`S7Iwawx^H|!Upci6 zm*fVFfNK>e*WWV=?)R_~h8sSp!jNgo`DPZ9gYS?J@2}VoJi`DJ1d_sl zMk`A=Fef|Pp=43iz{W7YuU5)3SL!~hsRscAr-3I_%=f5-Hy<5UGO?Jks2P|;9&Q33 zobJINM_^=-B`1HGCHTM?eRX@j3rIbLJI27NQyTo=K-Opq$Y5tT6qwu@kU4)*Nt~)- zNgxef@|oKQ?>!v6%a#DGXm2<2Z14gQnxvc!Tjr7j$oU2h2R0Nh5f~lFaT@l^Sr9?1 zB^LUm`6i9=gqlWP^QGwO?)s*G7sHpo7IVyeq$wX`G@~1&p-6?E1R0^k5*%91L`nAC zsv&55_^9U@>zkNVMcNvdH_kpt|C6O7{3`L-v2Ca1$;X9y-zd|2twTtkec!}UFPA4~ zuER7OG*qoY<9$4G_o*tVY?ezRIsu0|{JTtEJr`0ZSghyQ$HslldX=#1Goe&C2= z54Vn<=4I$3sskw*>pCsQJjf$FTO|wZ>brz*oE(AJ_+^p9L-t*a(Kyy`F}^&*rFo*S z80~(8^Emd)JoIyj1xO5nVn1e12MLF!KMIO1Isb6&QSkisBz9l=ca1lI*Kde+!CL(V zdVU2DH9yD17&yv+5Wd;*8|WP!_On%QQx`dm)C(m_;q`e3L4oc_KLuFP-JL%|;#sdh z;dsRjFlG?GWGw)kMsDuj);EggjVs{h1G*~E`;$K;RCo5SJsJ>+zOmj*#}pFREm9G? zNak~FB$cL^W4mtP-jBu(0t*~1;A1Pql9ltI5wnCi6i`LA3$(GD_U8RAW8hHHHz-7mxz|xL&ejz9# zWFbJDNdI+T;&$Bg50W7(eGzRWii8?NtQmOBn}Gz?=}lnL{2Skx=VG_fr1+j=34YvmqNMEAs9#o<)~k)A%d+<#vB7_{L|O0BB@Dtm(wg zsSz_4@KEETGfTsG=$_@p-Z=Z+J^1=Ibzn%LK`fzRhz=BBH>s>#N z7_>>8XucX&2K`GhmPw$^`KG+FDeyt`IfV#f#@I4`*fs{U|6~X^QxELS)RA6I;_qGie@aVkKT6QvATf`JTIw(@mLwLAU60*NFfS5o z%>R{u$m2ipd`Xowq}_ zB5?9|44p;0Gmo&*`VcFTyImfegWVt1&z6O>V}1Ap#f$}I*;J$@9s^#V=IEs#>7xu$ zR++=$9wWBUETdXasS2Vv>v$P~{)&cn$50fecWYvLZ#_=l@kr-;-y9>U|-zxY_UJG z2j~6SdOd0aZ5zU^ z!qx?Q?n3EjZWn z&uZ`!L1Ad)QW3CI0%oakDZR%R4Cu7-a9sE&9;c8fbD<)}{V^9Y*^myX>ZR%1>Vf?6 z8r{9?oHCP}_h9G;A}k0JP-oUIu-4{+>{)@>$G+6DgLnXKgF=8ZLSrQQ5mr!_!$17; zZR$L`Thvo?_e$fxuzcJ>!#3xHgK`Iu-8m4ir{~pb1fmCL7G}>#aQsT3Nzg9bp+_W& zKs`qPs&Z~0u_c25W6{<#l19;+=%q%nk`+guoMC<@X#`%XWMIo2E!M?v}F@aFpg4^J=8KP8KcZXjS+ z^!gW#=;cpj#9r<4@MBz3^rV|b9gzz6Gw`l55Qy-OTSs*-Pgh#O{p{vkH5vRA98Mx* z-_mQJT9wOdE8vH;fx{^9X1{a0vGa}%4B`*97naJ2h8HQjN2~iUeJ!O9>yas8KX|G8 z_fk1|6Mn-LRpZA0$$o$OCm<+N;!L!zKd7&XC%s;QsT38L&~H%Niy)}XPY zn4+a1N-i8A{BC#G9{B=hB00_%6GpK&{>3v)GGu_;KxpF^>+Ph}`@DH~GMzer8aZ*7 zBns{+Mh+S2mi0LKqLv2@MJKqoSkK)0nZJ5Wq*&H}ibb>kc7=D*hFat0|D^tsrGBB)~LKu?5Ex<&V@D!xUf!4J_v!vvO{WP=5W9_D7`N{fZn zpK|7yV}<20OF3HoEerNj3%<{`xVl6`FzTX4Cr{MEf3!tTWtdp%xFI-{e&Z8@stOoP zT|$M&j=m#kg=b`XwDUqw2lUIhi0!ba-w)yFn7D=UARWP^} zF;tiL2}XGguzak4VpXNFVYqdgSk%WDkwW!q{zC)dCS`r>x9KXX$S#8(Ski{K;6K`8|4iy3_XjW`@c&jq9NT zEXv>t6?ykBo>2ndMAfRv3^9`tU3AGNxnAyy+1%ti&W&p}fSV-Z3xv*Jh- z0?56zzg95%MAHdBBGu;4BEEbth&i4jNf?&8?ER&Kzk)|>l1}J@WN4q`gWwti%K6nq z82X+AaIa0QW~_9xZRJc&%;^IElUW@CZd@QOL%XSa<>b(;oZnpt7ORRf2-SVwcpUitU1@(& zIa|Q(K&HKyubdT?;o3kiRj%JHSLe;G7x_h8TB_T%zFWq!a&7V&P^1CPSmBCoZR<_Q zo;TF-Z;>wH45ihJfosRSm>A{zyUv@7+meTUv6IoxE4u8}-+tR}k`;Vsa2;JSJmVpn_-`r9G5Kr240sIBbUHcBeaP}`9q$e>O-qa)!!4_>GjISv;IsS2=VFBm zwk}nHUEaSoDe2+4z_1^+4;ssK1FzER7TG{a8p*S#W0snU3n6k$k>smZGc6@&$5xdj zlh;@s##z^XC)`o5cG)hpz2F@~`wu_n?_EX(Gq3%w`8ZmPChyzC+VhRT;nAUpf0fK3 zn&+D^uREWo8xv*r^qRVW8I3rL!OcpO_}}nvhv|B@jCM9NtMGE_)CTfy0ylaV6b+_) z{cQcxn9TYiOT4;cEG`YkT&Df}&xYBR>6rUpv#1+Pc%pJhiG>ZfIQhUivcYc`UKa5U zEg3_vZGuHH8}^bY>Pbo6#)Y)q+vb1se~s{Wr~UW^bXx@;%Lwph%oan|zq2#c^Ppf6 zNcY9i^FHDJYi`Ow4vUKA&f;4oiB#jL`!L_|v#d*y1majJkSf7Ph8E$98y2U?1vkk$ z^XdLkHIf5qL{)NpEzeF9F5ZW$hx`G$-JwHYCIt(vTVI3zWEC*?SH?3QO`OIX)DgP#hYfa4o(zsODvc*)v$&HE7D2oT746OX+G6_it)_q3sKA?$HU)rLDWP!Z#YFS zU|8+RZg**tSxG*=I}WP8!)|RC{}@kINluYE9uiMQK=#84V54mLjMLr#R2<9%>n7sd znRyEKvbh-H?{Bazk=XzIXdbaC_N=)jGboB*7A zfQp#14&e$tXcy=eB;5CW*%3AH-imGWdA(a~NIZl@;R^q zAwHnY#p`ex+)}Prf8Vb9?7jemq)*Pt)-ayv{iQjeDFI*ExcV;YO=Z~B$KYUOP^*U? z@j9$5YgdW&LjSrfILf7wxlA9!KPx^+pL}M&yn0%XDweu#3Q&xv;AK>~X0Wi~59~aK zm%-aUy&kn;U5sSK{pLarEG+E~=OfIoK>74j3cs#FQ1>EB;onD;8`wSEwM$%LvqR9_ z&mVfHq4Yb+0-S1b#93Ktuo1%GJegjWn)<0zr{dqlrN_8G8Bu?8TR4!xTVJmRY$`h% zcJ$a5gpTr6Yk*R&hs#fsU@RJpqu}6>dk-O9yLvDbq(V`H#?yjIl>ijA7NRa!*(Qv6 zz0KQ`z=Pj>0Vnf77IOy}!0sE0?>1g-m1Wh@4CbI9Vtl3b;_`e-@|uCc-rnhCGxOEe z-ekZ4NF#T-jNW(Z=;jE#!ie?sx(Zx=7!Q0ns~nkRFWzss)ww^m+v#sw)M>JY6@R{6 zp#ET~2@YPu1C=-@$2BXV(P|ZxC4pR3t;#w1nPex>d}EGzrk@Q&Lf!XNdKp)~@$u2J z=7-B2k{N}-7-U(?1R8Kn`Ln5?NV$xGO5W8wUznX5vl%xDh}I6DYHpMCEk z=GHio5;xh>>;FJ|NKFVY`jhIH5^`AD6%}ykRi6{s=Q@F>;FmTUSRUJrPQcuD?tE%E z*1tbk`?vUweZ|G!3i(NcuB*It>aqS@K5D(f*BAtLd0J;<`6ptvXqc*$stNS6B+9Hb zW_JExb-cC9@KzlctSWl^rrV%2?)bG;(jo=tC0)WXNB-&x}SY>jYSt))+j&3?6@ z9AFBfhRP%a@ey-#Cul_Be|xFvH29+hIZut5K6amRZ?{uOmCNTNpCJ5`D_v;cV0~zM z9j3xEOlnq3saA&p7kwY|>xA5Cw3ZbNjXDwXm2<+hte=GPk7%akAuqp&wP|};Doc%9 zaEZ>B?1)5c<1epBcFXIsyA__I8+x-E;{_Nle{S}OkzyKGlkM!kw@8`J!Ap(?UKiLang!wVw!)><`5$Itd(fw;e) z*_p3Ek*oUQMYew!YV5JE=5`{tMf=En9V5WUe|M=tq-}+opzj3uS{z4IEEs@Sa#e+5p83wKySLPSjw3;H2u0qg!Dg zL4lcgs_>2Q`udl^j4$OPm1?CFj42}D&SxPg?xwa?-NqQneVT4|($iBIA3kKjIln|0F z8Xc>>swR2mf4S>6pTIM3$AfSDE>Ck$tti@5qd%*cx@|9N2b_!=A8*|wAFehlcLpj| zr#8SMIGOy~!wb*}RPb5?;&n@<4Ld#4N9R|!j=kSU^N>>0H(=YS!E?3yiOrq4#pOe* zQ^CcSb9HEwhoYB(7+S0apiH6lA5W}9>WjzV%1I=k3Povfvu4j)DBY|Mt5UGN!79*T zN0bQlNU<|FR9HLyD&Uw|tdrX1;j?s8XkZ{{rs#-k1xJY?tZC!kqgpMYk%(+kmkkoy zTQl&)q}z5#^OG_$`JWlXrQ-Sy`7+zSX;Vn7Opr-E(ENb7ZaXjQvN8=jFS%(n{zjM` z=YTLJ8gCvo3A}6aMapSI=LF>YM?YKVk$eMGo)Iqdm~2vOnADbePzdHGRCnyvEO9>orgm4j!UY35q(la4f@4 zkTQs>f*(PUWeh^xVPtu(!Sbxla}e`{#h`cy_0HlCA9*}7+sF@p8o(J-8Qe0ID*a2^ ztZRt)Mg6B?RQNWd=@)6`jJ|&=^#6D$-QuH%LMf4)2k?F?ZXGOKU2IfMT=e0yylV;Z zyT{=`-#gr3nY>ydn#eV>x}nnfxqPd|CjS}m3F}j)&TPxY;MuHc>Dd{e-<)EMe?pqo zt1p{cL|i^xi;XCSWHeEO^m9 z=!u0Yis}T25s;Z5f}NF>JWXX*5)$m_&7iqyn@n2Y!2uG$Sw^TlO`LUyPXu2RQyR8I~qp7UQfD8g5 zyByHtDkqzFOPel z@0C~H=rx{uR(d(Et#{tfh@BYUp9bzMwGS$mj8%$WeUfc$6<}&|_X&%s_ppTsvAnnk zT0o+X`#sgmf3I?nTlYfbGmx}1r9z`ZgD_$W!n46v^=~Kca%+YoBC~4sO*ft3@Nl?$ zvPl`8GVWhqj@BcE@cd7O-v^SPSxpFr;7ci738f|qJk`s&x-CeOusPaD!P?jhUCZBW z&!E-y9)?XIfBPS7!JHM=Z&2i%)0EVMS3!(yEmu-?^J#B~pDc|XZ;;QHom$pArYPyd zLy|SMnVuv+-C4@BjCL*|WgN|jVZ6HFWxYZ-MqS=xLIpi8hBIc!mapK3-ruBsEn;YTg10~% zf;%*1AUB#30x9FQj&_=r_0=vVfMG&mA+7=ruhCfPpwdz=gG746UkpBwWC=m>;F zdX<|*ehV`})A}nmdN>`m24h&GJl0stsDE(1JEbcc&j&(MOo+Lfh7X-?^AX(yNp5;n zzmNeOUgkl(jx86?iv9r?NxJGidmJ(vcaNaN4llO`uTX4EsZ(NHNpzUx5Ra?X>paI7 z=#pQduKg}m$7i{MwnksSGEo}^a7Dy(X=T zMp@B!eFcMYRq*`!H@`o{YosP#xz0yjne-<0d+H_F-L(*#f7kDvUH+i^n5l4*Jhlz` zomeuF9$d$3+9pA7CyvlQ2GA46_3a8WOC}h|SALGM;{x|MFv7y;Ujb?}~j$`V{uem1Dtu2ZsLKT&Q4!{*Tba-3Ktw}sTloIhucD+`2Y z$CJB0pyvE+o<_pP;B9cMrwi#a0FD+{&46y>-D~0(M6aIggs?k`G6@R_Z4Dp33>zE_ z*-~{}Zkj+$Z3bfRMs#2I{5oy9|F9r=gq=v6iE2SJ$U8K`>C zzF6Jv?YvgB{q|A3rlnyZ4jeoGtFAocd}iSoica+8G@2>Au+h>DD><_1en5NG|5WzR zYwy0sDe;^ZbvR<}%{ks~*B|PVax4k@3`QC<L#*oM{%{A@m&eLGLxE54%x{dk%A`|0>N_hDVGBm&c|; z)`rwMZ^>C#s2w@RM-O(~Z<8Q&G}VxFm{M?!;x40z&JjZlPWJAG%G;deJ$8 zae$Qm--ZpV%B6lm3RVeu54sesxPqZXmnG6~q#hyRT~7W%0knw?B%eR_5*rf{hUPC8 z^&VabV{@0R9;c4K&8dvfneEy6BM0@MWnsQlQQx64t^7I8ZR+u}<*$We8eXZm}QPYHd` z_mOq9En^zxj1|M^*%Je!Th>F$Po=WRk1;}I4FbCRV_A%8MA9SvAuEuTWvMPPbKo`) zyo*W?5?~+Nj6$bEaUo9&X>uau+iGsytMXRNNb7$$AyufKlNYo-~=5^ynChBi*q5zLtN z2xBD!OSW}xXY&5f3}{&nzx4SUQzldb}WIG>uE5Z+0f zZyAjq8aSXJwGF)X<(7Ezxu;GbHl-~G*7jD83PnWUU_`9dMw-j$n_JAE9w`>sl? z5hI3dSLx#<))>-PyY8$JD&g1nm%WVzEeqQJhv+l6xeAQ58ImL?VC~abXFcAWYu?#< zKh@3No;^BitBi?j1UIJTA2KPAhq2bo6)ntI%rNOuK8=~OE`43Sm&JgBQ8RnByqsT5 zA3YhJvY5yaPp+I^!TkHR^s<3;g9Mx)A#n?m#WI_1YG6|F-H6g1L)x)=-0jTqQfS%F z`_E@B!WM`HIb2g>HaxtrPa#YTo3CAH9z8e(l?h)3R>mVr1|#%ofA3CgRfUyY=Cfo$ zuEE^dq4R-|k{0U&o3-*|4YWcW0W={-Yr5`tdhbFHM34pTeHC#^fTNVFS;j7Sf+vKI z(S=~-TjCcK6$|dVsOk)HnA} z?cfZ`4iX=fr>3p3R1I)vPk7({;+oJ0#n{;s==)^*AZ}sR?^GG++~#au-2H%n4y5Kc z=d=DqN^4@#@@9h7^<|G+f*BTj5abz8zEY)?AI_9JDYG6#=fFE{LNb2J5r9s%4K5G> zc!8Z3Y`G;fc?!Z3)E*PgAu3VQ*pd95byl3qvdX!~g{&@QJ zOyV!;kL|yTkri&HXL1AADck01Sj)(xDjw}WO|KGfYS}&d=>4*(KQM$+OH~}S8G0D50{+}viH|%fp^RMYNcrRXQzSNrB03#IlxrA(Ci*@*7Ifo3I3|{ z&%rhJ1zmf=6U|sGwYtd-)x9HPh)wJxlA=o`f!RXHgx)UMw{H>R0KEpc z(NC9_?xtUXWoqm7K^Wik8^wzkTt~LE9+z}Oh|fu0{@F-GQ?Hd&9@v^NWi-@7QDMyb z$2={kV8)v5E@SrW>+oe`KRCYL)57izg}vgXDxi!c7(p+@<;~#x z%{-v+Yy_8&mOAx~L=;CNi?|uGk70Z*4s<}^z>lAE`hkH~fiWchO*U)R1KMnhv?Qf} zc8$p{U*|MT|5A=70*Nky`hz=CbWg*xGgkU>T+6*^k-4VjysUu;VyS4UkBf!6xW1D+ z-@T1yMPlexalfE_A*0?6@5#!yE@MZ3i^U01<5DkBZm(5XwU*#NOOS`Y`)dq)a0!Ll z*kovqPjo&PnYRov#6eOz~R`0rGKDOm$tK0tFu#PKbBLLm&uWE!A3-i=Fi zv1WBsg*GGZLT~@qQ)bPJZoACIa3@;ZHyCg0Pz85Wav>K>>SMbc6?-ccz{wcICI#GJ zvL!QUefcbNwju2N!#@vc zha5K8Zq#6}3=Q{8l+(lCSz+3VAzWjJ`GdTiTO~5l;d`m%f89f4f#Oq2?9k;pD z>&lAy=}uw{-3?Dfr{(bqzuNy@FhnmxUo%#j)O!CXv>h*9`h&~(AL6r*LJaxtyDzz&mCbcVUy9&K9QI6nn{F^(PUycO_hmq+-^I?OFH$q{Z#|3%azUZG+#uUW7$_GoI#z-Qc1G{-5 zsaZuPTtEBERL}&o1>UDEN)&#Wdu!-sB`X(^QPEt{X}uH`_sD595MBcvm{R4^TQJbs z%~yi=&HARL*W)5ei*%J1g!q-asFUEb`Y;JG1e2k)M_BM2AXO_HkSUr27&&pb7V?iKIh~FeSmYcv4yv`r9gx02t$0tkek@iTNZA0ls7B>nyarWo znl3C6gfb2-TZus>{t?m+|1Eg%J;|97Q~0V;&XU65Qp>uzwH31G{_dNAukE1Gqn#d7 zgiDM+GX;HzG1i(l^FO{xf-F~7!*PEv_Lmrbo^TbVPnMg>6X_xE>Ht8bgM;Mda$uLP zabW*Zz=dG$-Fc%(z~4{z@)QMpry>%$#u~7&*$sVxW;VT?1o~0WG4Q0J!(JVYz-4a8 zlSIfH*9TUuc@ZXOk9tMmFA>UQ=b$k}j+p|)%lXB*fT$4qJQs#azMEn@Jb%Vk&F-C7 zaL>S~pi`?wd1G++X1Hgov|;Jv{%7A!%fNp;v50BMeKQL7>7U@kBJ1fZ!A567<|1o; zf5OIiT=te=iBJkm6=hvTg2yV9MLj~YsoSDNjcSA7? zXH-SP=yhi zlMxPc7F3X7#E<;MI9oxBTSV)^mJbh)Fq6))iJpQHt%p4M+D7^cdnJeA+}7AU^r#c- zx1lL!kA9&C#N62@Rx7!AH1x#>JaiVC4a>}wGv$91ZwIdMEj6*3f4F9f=SY67FH64i72|YkOEX&JV8qV6jn=!A5V`MPHXrikXM+dH09zm0l-m{K#4&=K% z6QJM3Sy~dV6LtWrbvKYU1DC?n=P#>TTchBM^InAIpG&W7Lec4(cgWbgtb0KP=8Cq{ zlED|@8D44mwXFX~)L8~)`NiE@5RsB@k?!v9E@|m*q#LB9yIV?1K)OLny1Pr72c)|M z&gTD~_nZ&TFwV$;&%N*ci?yzG;-G1gW7q%ix>pNrx3j`|`~DcYtRQu2v@;caJQZ1efJ8ynR&D-@$j$DDkj!M|PTIh81LAjghQk zsx@ZAy9ENb&pcY|NRDTm7@_MXFCVC)Bu#(;6j`cVJ%8G2+L9f&lx4{h8#nW0+ZnK; z`f4K+k#w}lfp6P^dHV^>{I6!`y|0(o&acXKRyy2csajgd2a)nWru*r7pUBGKkHW6n z#hOo-BA3^Xn8W9v6{|_97oYxI$5t^(BsXIwV3jl1v{t5t25*&@oDU!#y*XLq6Whg} zPvsw8TwUF1%z4Bv>FOa2<@oO0Kex-tRbjAmM6@bAm*-%tmC43!(RFv&60y}3qC)E( zkYlNH;Qc4|toN&Du1$Ou?JtJkT6`L~i2uYt!R2vF(nvVi8GO+J%O^7NyXQLrnfJpE ztQ$=y??Zp&qxF+gDze#|>~;}9zOj!VzWxNU3c$g+O!8l8W^#nInw12p{{J}zR%h&Q zU8TZ%tz1&m7E%!lW;_;ehgeDbz_C8;0a)lA*D_K#GzVPBfyU6??T1hH=#3h=lcM8& zrgNw~axvn(C*Q~e>uZ?2wTA4(N#YdH7vU0j3j(9gp3;)Du$st=%jbM5%8^VfPHE~j1enl13FyVB@03bY zB$*O2p(^^15lD8t+Qd=kKi73P3*bg41W8Bn4&eX5k&;ZPKkVp)V*GJgkTZ5%z` zHR>G5MjWn0N{Z}KQ-=^w6XYl^t6Vu-JWHngR|v%jt;-X76(Au+?@zi&Ag*%brh${v zCSldorPY*DM)9Pkhp=*bROHw)E0)RzYvL4ShfU*kelY3Kbgv8TU(X(AbLJPH$|_Um z=jaW*Rs0^)Zvt{tJwYQ33{Vh|p! z?5UHRX79T+aLJ`!MPIRUu||*vp#sMvm~Y66iX|zi%%Z8~ilVhq1eRKNtWiaff*1&Z zt?I(XIMxfUnd*;_B|-bi8@hg2U*Ljc$m4c6@&N5wT0j~>2HG?A(&X(Ups!k8H=g)h zA4Y0mt(Xu*E&~u$4$O%}aChPlFRzx&%uDbt5=M||S^Y7ub8%fNn$$28+_p`mhpLYY zce~|MJv^*Ko0FO8aC5BZdy%1d_jj17`D&B_NC3J4es6joraYP|K0!z zL2aJbWalAQ{NK61TJh=B`szSt<<1;8KuUM_c6%m)lufJ6gf-zz| z(UZrmUHhg`5%3xEu4(UFz(TfXD4q`k^LL)w_-2WiY{gsuIs`K;%F)UE%x!Lp6YDhL z%vpzbZ73_I zb!~QZ3d}tH8eFt19O4v0lv|pvN!gXFXetKUmQB>a8_m!JpkWbNHAbbT5?-jOZuzbX z(P|dVpFh#HFN$I@bRs2qM^hC~js;>9x>yX)>{*aWu`sxF%50C~2##4+eUPSeHOy6t zeHFP9)IC-m`o_3tr0eJ8DKS9MAFvXmzdtyjF0^ES52RpI>=d;jPEv14=To%;k7_P0 zvQPs|Q>q?JQ#TyKs#6+$FR@dZ49vmvLLC86H#>jYyk7QTK!F3KKC&fKU+(znCQd%L zl>Slk8dw(FAf}BCyXnDWmcU+&M@2p!kT~6R?M=<*UdqDuR0AGNYMIk!ZaLu|QGaz<3Iys2~!{C1$J1}6RAC`rJSZ%sa zreAxOCHjTUR~EM}uAd0JXe#lvQYLL0K+ZY!zE~6h=+$|oZ1^s9M6M}5XZjxPzb;)U z=~YZI+xevj^ZXa$|I)caB@V(^)63F;>u~j$7DUlVwkdogzb!y@xBCdzpZvX3c>_%U z7-Y~v2O3Kxw0nKD?0t5J^Y4Dkz!`9*udi=#Gm)gHF-<-W5HP?N4F9F1!HSkljE;6y zSLc-`nbc;(kLBLaF$`cmYn}CY%I+ol6Ry31(tF-x#hYH!*wX*!m=J9FD6^80)pZJz zE`JHUFz6j1*S4UL75-MV^H5f8Rx|~YH24W0GA&JH17?kyTb+|9E%`ytw332!w;?p~ zI7i}s9eH4I9I;QFS4*vE?X0K-n!-V?l$T*y=GBMqjPisLbj_UKtTf%?nW~CU%9S>* zB;(I^##a(I;yTGCbiyep>k}3bNYO$gbUVu<3?bJmM70irneENllrA~dacmaFUPB$@ z4{e%~|1&muIg2NRxpSCLc;?E~NPTFV{OqQxHQjpGL;~whMN%I{cj+lHBR^yhI(J!= z%c8~01xEaxX|Xn)M)UmkJ({c*FaF|RL6KB$arTJDAf2;7?t2opV8UJb8>*=6D9Z{i zfXNw<#2CfI+KqT4a?seX!y^YLUY}-f**q)3#w-p#TZ)Xrg%wEWeaX)p2yICmX%|m8 zn}}JYFmCujphO{5;`<_b~i5~BkhMuzXjgU z-!+lr*i_vThMZu3||61l4Mw5yej$M$iadv-7Yx(;h9kMJW!xR%+ zZaZ1hMp738s!a3=MjBT{j*j|^v<}czSvq4_e2D%<#TL>HwVnG%?@$NgV5I*S`}5Hp zPt8hXvbj~nFRxTx2spdovU~9*w0nCFHeBxQS(f~8UixyWm`kaj+l9D+*=$iBTTwR$ z@>c#Q04f|D(Fu}@#EbD%B2uVZ`rBO$p%_hOI~%Fh3!UZENlksr$-={c%gs=YDuI z@!Y`otx)7|f#{<6rXBR|)V=Vo3z9<8h}|q1oWI+A^*_fvS#NG{!@%2w^PBXY9Z(1} zsH>|NbNwxr37Ym)>f{Yd?3hP4MYAY4hs^v4?Ir;j`WMoiqR``ipf-Tb_y+X7-x7WO z!e^iriSHW5Ys2!x6pBX2#*jh2H5D)2zwd6pYV3X^v&gT4{Hm)aiUXn@f=Cm# zWx4TVo$6^WSTcD1A_>AH)!#2qIejW9EQ;Cx=bN!>@Rxl5ba|h72btNi*a!1`g_c>~ zEhQkseG%c;_CT;4|5*9m|7&jIsz$(h4l=22ZbegU^M$_N9@Fl4cH7bD`)?~ef0t25CBo=Ri&y^Z1s#kW8-m^c zr0I+f(YE?(Wl3nr7MmfD$Y7l9{hQZNsbpv zI!I}Q#(vQzl3%a9YUz7)qil+bFnPQrahZnlmN;?SPKoC)y1_3rFnze^>?C-x)iSc9 zTE<9d_>n!Z`?XleM@4tyqEmJaB{!UVHivP@F>OnHSB_TM15Dp4KU^#YQTHN2jv9ad zxvHr?MCWNV(8px-L_FVc*s~Sk;?&$PoA}%aJgNjA2*GxUGE+=}-oPqlB_p%Zh*LWe zk^(HG3G8OfxK)5A1$JpK!Z)z~lFS!rT;2iQRem=aY`4DY(?`2llv~9xD%wExwAI?_5)m~_m58r(C)11Aj?gT!p^9WKIQxs zq_{$4Jk~N@1B03(zDAND>k<9&=n#cS{om7vi^B=C^^uRec`Gj1gWosP$z__HA;_^r z0_L1qlSi)2po%5(K85PIpOso^1}__n9oC2qeJv7S<*>W2pWyswQ@XpwULY3j|IXzE zpEsRBHM({R0E@sqj29ikeW0XrcjDo=+g??P-SMox?B2z@>4*8hT7Z>*XCEtc+kqt; zwN9aOXes9o%; zbuQiG>ntw=|8XKEjk?z|d@lLiy*xG=m&ZXg5X>t2c73S~RY9;tidO;3AV-aRYZWGCRs=(>4BUD;c4O9#){k)pENI zLYaS^KMg^Y%zQJ89JsBkx?aJWV{r4X53brTV4`KoX|Rk15qYN=TFHX{FEG)(D{KWYo?HgcKNysp&(hh2vvn- zGcK@{K^-v@iyNNSsi*#XL+?E)(ESVeKxsu7QrLD5223F2B?=pxAnkj|a}uh`nTwBd zRx{&Tu!wWhOLE&Ym1Ao6>`9}#{;K0@z$H44SCD-2pv71CU^MKWPb_2p zpBc>IH#oT9Nk;%HHn~(rsF%(M&=cr@4Gusibs;-69pZcEQTWxGaj^6YMPtwOLl7oW z+qNzgoXAmb3DrOx3Iw1d14k2Vy+O<}H#fH-HvuEj2^K_2pDvr50+kzZwJa{LnSg(yMg86+Afr%+G#uxq`$E^5mMfq(OhHK5 z)FHF~=TkM%UcBL!o{oBZLv;EgTZg5(ocm%Ev@#}_>ZWO+vjvcr^rKJ3_Ikv!HPrJV zz-QyZehzbRwEXXWzGHW8zOl*uSrFu&83TU#4;t))3(?>n?EHP_l(r^2z#su{o(kQz zuFvjR)(rWRX{)OOFG*+LMn1Lgm=+-Mmc^7IFySEgyKwH*jz1*}JzuPy0g_~GeSL5g z`4|tt5((W6Dpt**m1(S=&3RBK<`}m0)@Q{w2^g(A}xSRef>rAhaqtH6FuKjzAOp5yUBih z*`@lrq)7NlcdMVv{v1c>4*sO=f$&PQ+djj&iG6D_zkj9OCv?yyqR?fVmZrF9?TJ>q zq-(f867^Rvn%2T}ud=+}Y)N?9x3XMQ`FIKerpV0WR(gCoQGaP}Zyp84>!DP-M$K1r zNyx+6p*s)BzwgYjgQ*m7OtTgC)Gfg52&@L1sHt@+xo71KXq@T5M&7Q#pg`0=&cIr^ zi%!6&${Kc>C9!{P>ab#3ONZ*G*Qb(NLo>|?R81O3SyGeYMJ)L_u@T7;%GbJiRmOJq zx>2N&EaugcQ#86t<$bu~yQpN+vFMZ!VoQAJ_3Bc+zB7LVYNnaYtD)J5JW~+#xGI;E z&nU)>oGOoN`|^T>d-cP~3Qr@{%k0HDc}L9JBnmME8?lYrR;yj$_ED#5FqcD^8f15f z(c#{7!I6v1wocqri(y;JN5SPVk;73{N%;M66;zm)A#IJoGeVo%EVy_eQ4#D_=+Q&Y?tOqxmb%L$xulLcCGJmeWfY@gaqUS}MNlVTl`jtf+Y|KUs@B@Oa#s)q& zu#d(=w5;-5gM#~b`&mnG`IlAVn=BkdM#@h=ub&16fGPmw!S{4NLCsg_=g-=KS>|ZH z_58x0MRRxi)b`{2Xk_sRM1mf~D+`McOO{}zxv;vrb$w)i3uN7Z@W^y~IlXpzd-ftp z%^6&e$o#0dJ(kgm{Wi;jPn#4EiFXEprNf~_zJM0Rz(541)Swgr6x!;x`cbKlr?C8d6LU7jy_Ag;$7uDI zQILFS;(HDe+F|m&XZz!K@*2=v4=tkRUd7OlN}JPo{!mtdLbv_^900%qoyzBaQUgLA z%Xg#E=jOOPP6APG8~yGyR$6XeT}&kG;5nAZC?(Wix%xhBjNfrRA9QStzUTV)h0mU( zzOk|Yh|j&r=LXs8TZ*{m1PP-R0v$L?sBn2rl9i2p_kVfg!(@tR7RhP8P(p9eL5mz< z``T2;P2e#J7r*H(XTry_2-EyU73>ih%(myka(bC|ak-}DyQ7-zwd7NUU#I@R8W(Q} z^-S>?N#@ySwG1)N;BLJiQmGTEj378#o0b513#Ms+ixcimyeM^W-bcMkQVRi>XH>oq z#wv=q+8am7ov~uJ#FDm)n9AFYlHZ->jVHxM9qhY?lCh)ZTurG&^Bfk0mA*}xd9v)9 zOp2Kc)@0JDX4T``vMdo3%;e+OhmguruxfkcTvdX<$)bvljuX+qpArv#P2wZ|?UdYs zM;)7(EWF<1iUGQS%B8J+zVz!S@-P$sxGBhlv6wHD;Xey4L`|W2Eb0Q)r;NJnsub!t zG+K3iEdri8X&Jo;M_6+1qpIdNqy-VDiUHIhMs~8JRysGV;P+mXDQ`~}0m(8$P(lxf ze>^%F=GX?COE5W3Ljg(bH@f`7GCcxX zm>3iAtSNwfd^!b^RJQ3q)rpGCY9*XjC5(_H^g=bOB3*uPF2RMmu(V=q;v5Jz@U@ed z(Q>?0G6`}1eBh4#pR6HZmIa*E!3%GhtB$7ZqO4chAvmikM7*@DH(o*YDeQ8<=)K+9 zhyvW!yc(OsVDESin!U3f9E0SIc2l=mr6mo$Co&4{CQG}mFA|6G6eP8SwP`grs5pRz z^yT%kXwyI(q00Yuei~^UcPcOB=FbC1drrOz%>^)btH{CW`G41?y|`W$+T2Ms*tCDX zwg-3}z`g^p+(Df4Bw32NpVsVLoB(GBn*X_jgIk^*&BBEMhzP0!aP2=`1fqbSO_eec zuL65z@oJ^%48FtjnJZIphgId3_uAHuhQ5d=q4s<5rco$bmhdD5{ILt1v5U2*B5?e< z)(X-t;6$U@fxzDLr0wQ5cI`3c0fo@e@mo(_tl9ky(l|QuN09DY|Eo`D%`Z}ev7_(! zQP1vigOjftjb~#^rn>C2keZcMY^yK=6k;u}X2>FC^1UW1-D@2q91Qc#i4O-G*>z1q z5hj8pF?VC1bx;J_%-wsD@K{X;;z-0oDiQacv#MaNIPl+a26!NE2~Lj@Ze4RmI|XN^ zis>j#k@XqV!_kCC5&vE%LA!$vuE+nSPnCuoW^NLtRX<&iIL1ifoT`{Ig*K#3TJTkP zY8g*SNYCs@6sypu;8R)<+-w)2%3Xwbddtrty(D5vdtkSCU*?8a_eMxDSB=<$|B&A; zr~++pC7u$Q%mp_$C{+`qb|j-dfc&4Ek1q@r=?`~Fu*Lu_yclxA6D3Oeva zJIzPoCP#e-_)G#HC2lx5MU_LR ztcg)Ps=BZrr_XH6`GGm(qcS>7#lpj>$L4L`*a*s*PRN_u&DL#k+7H*)*8p%1_6W|K zJu=$moWM2gYrn3$GSyUWig%nTD@V6-j(z^7q3Se8DQY5f${xTwx~vjcI&-jD6tI6R?nPaKB;46@9zZSv=O(PrHr z`jxfq?b%^bPH-e}-45}AEgc<-MbkW{`I+reEYdVY5n?{YM|49g+o^|wHx#Ftam{ia zmllJF0&Qo<$Hz{O_wN{WJtk!qka*62jp6Q6f3iV8#f z?b{VUha6ysI-8UN@}(UF;L$IfwPV4LX6`eN)l`*5c7K|Mx2R?<%tCMOHI8Sq7;^xQ zc75+N(qLo%MVq1HF~%3*i9th_J z+q;B-TjTV&MaaV4-9ElPD42V0<>`_W5bkqoo11%4d~aWmWeJ2ry0y#udgW5@3;@;& zV)*=Z(jy2p07Ny_E^e>fIkW$b7WbsvYgqobaqs#fQVK2wW>_0R#fG%r@lV0W(>`V+ zaZu`1JWkF05GLL4z%GYqzVgc_qis&mh=9xoC8(F|lVHKn3i*3?t?O)g8-`=M@ZfV} z^U>91bRB*=^=uND!Gd%TZd+mgm7FO-x28(1m=n*?kO?W@@t1S_-+?~;L`ES@fo=9K z3|B*l2pSsJRjS|lR8Qm%M`kl zR9$&l+cQ{u)`1+@;pC7zX`#>)IpcBOH@4sQ!|8nMWRA6r#~110j`SsofcCyX3u{l;ak_Fwp3CW05qjBO3mMSf7n zI6S{euu}lpxEo6z!w;;-E`d?`LcK#)0Fzi;fa5i>X!jbf6pfP-fikF@(5Oh>(>6L` z-jouFBxE1}ErMEEOFMT$R0)$Xekh)9zJ#k0ZHw_y2GA30$gi*y5BC@2qDOKl3qtpb z-xbe=0H4y>G2>|TI{-EW&gn!dMR0qA@WGM5uQMbM6MG6x#{Ru$`g7=1&I{-pe=(UQ z0pAY3J8s`4VlIRk&Wb%ljn>SmnSe?m+pxT$4}>a!oxRZ9mpkqBI3WD$`@r zB+Ft(O3<1~IcdxjZOcF;8PM+5&^5c?5OUeAtS|Kgzr-W&%a>zWd?0tYj^~LI z1zx5_32J#(XgxbI^?@&SxVrt%`c$D@>*bVO>uDDr|9H{b+Ey)Jj^oi12Y3zY_AX5O zDzWl6a?3``|G)qxPs}-HA8rsT2x%+@mD4)Jn+sPhp>?QQYr)XjdTZjQ+@CrsPL}bP zG&>6JyN5&mrg6X4XKUYU`{$vKe}2y+Vbstuyp@Cf+*CRwdbrB_ha&8MHxO%O2$w;*0Obn zh);q!TU~dxx9!`<79bdQ=e6!&FS9)9s?LWWz}Bv?)gmuVD= z8x67^1T=4tyU5&T)WM4Zr@_#oWx^*rZTw{A#{a#1kqj87EEv4DWvs7w*ha@WL``gw zB)dF*7q=;L|4n4#b+xlJE;ti`lV|m(!65CsIror|%WY6l(i6ju*wd0PBZGlWN6nO^ zA5BojDkr;x$sRG9OnXJy_I0B(&B$7mX65(v8;!3_j=d3@*!tZiEs+iqp$Pukmcnl& zHLDUd1H<3U!I2NOp&QRm4#SGU$P)WNRePOd$$sY#S0WUpmRdpBQEToJqbxZ7DG)8) zY-EILDOG2@;)pu<4{OdgF?v$7jzea$z#(N!-LSk9-+vO@gkh=4Sl-A?^jl%Xy2~F~ zZdR_hoDG(?XiKC?AdVD$@O<^0@JF{EV|5iaM!)zpi*kpY8Rrjjq`A+ezcr;s-=lA? z1T-Wp$nL6d;tXNp>kN1VWWU25gX|ebO(5D*!jETflmzCZ&0jMGo zf}wYu@YZgWRgB62=ME(QCcOKjx9uF;Z}MXrPrKz{>8C5}@GQ|7x!{jSy!J2Nj;tE| zK8Z1*v{+L#3l{6%)pMVa8kTKe5KhtW=XoBw5HlD4fSddR^vKiuE|wqa!Ycdg_>L|! z=&*2yZ8`eTn#%*R=X*gK@OD0(#_e|BJHf|GRiG=`ci{uD`*C}nd&?H%0~-)IQz||UyCSBIgE8dM*&nZt z%{AZa%GT#Ul?!XDB(j7`hq~*V5Mp14Ef(Z<**74t03($R(So7qw zBl`l{VZFlIC9~%d1zIx5>GDTTH9sT&f60v8MLDz}C1ePH;G~U(iulGdO|j~cF@Fw9 zzfhrF&Fm*fmt~ntuOEIGx;qXAzA2{i<;C_-4upDMBW^OdRq|5RR_!R_!R(J3jMziE zMK$r#TO?$IO&mMx3K>^ib7-H43hT(Y91-+x%DyyhYG^j{n|&~%4wn1Lp^g^%&5#gd zgtW^ui0IBkGH(mjiUS%&F6xs1Ux3s2kR)-kPHPfzq2>a^@HPc%jDdpZlFJmHMe`x9 zW%^VBZi*o9950=YEeGsYO0Z6D95jUpZ7@6G&@J@=lwFr5G~BokVQ?LKxH#N_O^H|_ ze0~0Tq3RL7^&~H8gh`zvMDnMid~$?l5n;m|sY_J$$B9HJbJhZ-3N*yX26VE5{1S|- zdJ$B_SZQ3BT=~JZ0_C%_aJVS*lj9;gQSaPT>3*2;kX{H^bUtUUV)vKn!xix9KRpo^ z8pn%P4}gnuSx2YGF=@o>8`kLPM*4S&&e!`iaY(OJ-}V#;i_?Vng0l-BU>L8wc;p81 z6*768L%`8}i4y~`#C=zJlUU_W+v#rshyMND=<8AV9{%w1#+-)9z zbV4gn9o_-FXnt85Aj7!0^CsC2-&*j|9|}!5t6Oh+GAeVdhM&tT5S6x=L|%UYkCnjS zLPa&$UxD-yAVkzgu=}O}lYpS^c02J!Z$$ZGmWrUK%`mBn-8@|)YoK=-t`w!Bq4E=bk@OY=sB zmvjL)Fovuw497|{yE4;QgtjicTGF^oOHG0oS(CItRMukBCW>;7m*h*9Stbj5;fi6W z0Mc^7D>_LT_#rW;g3o0Cx0;Rv((6EvOBWOEA5<8k8afuy@&vz42fo)!Rm_PeTT^!g z_2iWgySbY1OR3@0!N+a464a>mRjQ@e-Apc__T%rsdlvv4rlZ^7T>0u_>JsLA{tPlH ze+S&@#eKE~BC>fHUy4`}6SXKd$_B(x+`$@OW$idh5`ERXnB*Si5pQf(yz%sLQt>1z z3v_Gq1c>@3xtF?Ol5=r&7jaN$w2|wOJEhlnNlbaw@XCtBqw%>F2)IqeqH@!;Mc0rHzHwZg#YdryveB zy%^-Uj5=mM5G1M)|4~yY3QOv*{TtHoKc1G}pTVLe3{1N~Y%WO6023Mj9|3U=zLg#1 z+{hn?=u@|(m!;$@neM|M3Rv*VKir}B194uGLQ(BN%?ijgQleI(O~vl911cszzZ|>9 z7GhUb(HoiFAvWW)gOFSG@goSHm49ne0x{g)%>&r)g0dU5(EzThVabH0{-FWRcd4?o zG-asdp7Sw%95M(wPogseBQv1dC<9C4(sJbzHE^SYm=zmN6V`Ncp(1%o6UqF^E(M-? zWrgI1()1RTdPrE@`N4vp;seVa=b7#Tz0kn~uQ@w`<4YH;*V+S$<&yco0P6!P=bmMu zFBxDES2+*-;5Z++y|yK8>t9)^89zAw1~caY7vB6?ULfXW$r+uL%uga6ZTk3;o@kyU z#*Ki4LIsF$yNm}tc{m$6Un0Z6#E|Hs@4fwmB`1(tuCzbWymZ1_u|hxA4$xpX*i1~~ zHd+F9rd@G)L|vZ^a{%{1;Qi>k21V}Re@oiY=J_IkV3|6OCV>XXhm#IHro13z&8e!R z|LG5M;2EYv@+x8I6kn{NR4ui_dwhHAI(Lvcm@vgPD-j(IBM|E1St8Q3Qu*bN}U_fPaHs$}!1Lo~97~Ix?J$c`Rk}#~AA?72?bV z4w^pq0~hR>{ed~dvc5bP4{4HW(!mKVxt}UJfpSIBB0Y%jEt{+G6zZC~uoQVk)$_>L z&jV>D{#Og&xei~ZPEDSzOr2XLX&7BAs!!3QVyq7*9B@uCq#`>9Rfr#BhSEt|uJhW&91eBAgljW74xx8Iv@xh;)#~Dg%KJ#&Bss?Q6tXwf1TW20d(ZE*nvN2{&f3*&e zlK-ynn?(q_3(H%l_~3&F!DihU(Ol_56(CUtRMhGw*sm>aAeA3ZQDi3Q4s-0lEx&zkVt%pcB#_ec&El@=UV>4(FKyd@ zg*4vA#_lvR=U-6AeQC!ga6&73Zj2y~?6SR3m>*6$#(|FyBt-#-4Eh1L7u>+9T4&Z> zjGdkUm&FC%4dKdG=h$m^lMx(hOa#!|C#i@lXYxxc!gq&hN}(|DecFoHzH#w!6H(V9 z*vW`NO%c1-Z|wgrw7xs4vz(r3jO+M3CLp*^{{mkNR) zR=HHBi!naGE=9k4DjW8L;>>}_ zW+}5amjwUT3>QX&&yn6fi{Oa3id$I{ywLi}iE4ai+o}}ISo|xfPNvqllQdcsp6I=l zc>dSN@ugdfa~oTG!;evF*oEvD)RGvCLl=qLapd^J@y%A8<>Kpf5(>0Qanwd}oatfp z;byg(OJsps#ZKi|(wpK?8Fj1LWyz6`=E?=}RE*!r@opkap9Z-%x$6DhkS95nyLg?r zus#f!Vlotvr$F1j)9#l(@c#r4Z&O7{QD9TU8QDh}-vyfsJP zBtHw&-KaV<8?nm_o{n8oYHvSHt8%zNyGWZhk?zx3aAzZI0YE*L5vL?f!0k#qarQN$ zsbHTD9b|fMNF3S>d2>=_Dlkj(B|Gv;D^iV1@LI>kTdvWn(@UrpJX(Xu6x_@GE3cWk zx#D?eL~GTxo7EMIZ?>LMziuMemDG0;z?smt206Rb2Y`oraBu*Q?n`F~uJ0qa48U{- zAEV-bHiEjj&_gqn5{$&F!j$p-6DgsaPa9e!lkKwn!z;bhQK4WLYf5-XwC+g=CQR#K zM+zh*)1T`T^1_QAGz*~HXYjRYBp6fkHR(a%+)Iq%q$OaquVlK8jS|rnVlzSm;RWD1 zAAIlScPKcr;dH+kUK&-e#C9*!rWX3EJ36*uPc;4}{owQvKT{?3$jW3H(27GTG_ z_os`_lKM+ji-6BzGn#A7lr@W)AX@31manD7@LOXM#>gpC{be&DA5HAd^#TqLs)K(*NQah(chp= zU7VitlqF!wV(EW5;`rlzm!S7 zn4x0#7kJm-<>HF125C2&ysK|Tn}Q6iIEE0S!kJ0- z7Sjx8inwj#3=mHTHe@12z9+8eMw522HWKob4rZif(kqSh&u}Szm-5*K-B;V&ku6kP zW3_L5nS^i|n#xqY794BXs$5WF=+#; zmW~NWzL8ClTW45Uxr*=D`3ej?>;Oq=-?$H;QLQ~))3g^#heuhJnk{mIIzsWs_=Q&bOS*T7#_>Jlr zr|aF5hW4pLDGVvzKm2^C?u|kQgOV(@pNxXvQd)k#e)2Z;Vd8yVK_AKWS$L-{g#ljKB8@5cL42k!F@d3CZxcwl`2z3mu zn@1TJRVueOlNFX9rBX?J2Vn+3!^VEr^Qb;GybC_RGbxo(Z}YrxIFr{En#7PFB(#T? z&1UT3!sf##Qg8Nh{aGIc~D_*c#i~SJ(7ma^u4Y)WD7}U zY0mHXL&FdM=bGKf=$~RT_f*s_-p9_-67+j=yeaPv*6D8~6$=p}G&mfQ?=vL-tBVfp z#7lyE4IkoTO0b!MixQ5GPNRocE;G|mtrRpR<(ZG{i~JLjBwn|`N&SDG%i2M1ncU6+PrLDg-;rJg388@(>8*q zIc?ui-OIK*`A@0}$5BCc>t4*O?-B~o0S{8vv5Q3U}^^@J)k;|544WrNosj0<|Me$ z-^Dz;>iqFj#zkoLdAr_dSbV>?TRs2g>AAXXRxIP)8M{jek^xiuUY2%E-DeEZiTCgD zV$3~Q74@-bQim3F3AJcN1pDnOhp*@~nw<|Q^X)<{IXg9nkDs83blW1%jq z=@`JnHeCAXV?a*CR@$-Q@2m$D05~0V>2q1y&dO=+y`G~4?=)~_dhvN3{^?L`Q>Q>O zmxr(fJB3=G`lz!$F;o9qvU5`_Fj@fgx2%(4`6aXr+#(5XB+U(ZWwr3=## zAI%CI2>Y&Ypx3phP5nAp6TMCpUn&S;D@*~tF9??`j+&g7N1c=;Rdw2; zv3v=?i<%UHU7JsZtA<4xGvD=ZGDYfU5gVGjoZU(Ti7;2-WVM5e+h4-V^*D+ z=kLl4<5_&7RBZ1^<_+?>e=Hw3K6k#3C`3>GoD7OC;$%~1eDwFDru@D$->~O1$F0y_ zh4yg6tMHk=GNGUA1M5w&KLsjkkbDCsS^yXb&=I@4*g85Hps0c>=lGwzl<9-!uuAS2 zuu-Ot0JABSc&;2A+gqt+ipc(P1R=XDzr(edhlkW7i`Ze}vHMevNUFsgsn}3VbQ%gH zT;r(Di&isEda1Fs;HslDkC`hd$B{MlG3UaWE?%Bb{YAF4mWd(9R;v$_B?)=x$8wH14_Z zF>;a2rHP3j<~y#ukzMY-u11$>S2Fan21zFR+tDCStVrmQrn2oCpQ-f}IvX;5T-WS+ zfeoJWj&=8r#}7HHcTs1it#yC71Co%2f7yl4*M09kOZM;cN6gvd;lbkf6muEx^uJtv()ZdiD|n>{UvPfL zpOXpMpbLiCWF}2hJgrXSCXb+pMycx^$ND|aRzH#P=I~mQ;LuH2Qa%vRSENRrZtHXB71SSY5nb`A)kppB(3l`^n$K$GlICrA57|G2nxtWsUf@O!o+7m5V$$h z<)llcAyVHP3+p3dUfBaPxLU#MUa zV^q=C=nQ(ls<6?6LOIaM_zN&^smo%hrE{*161Tfp`f!hNyFIwcqq!{vkDj~fkkoJXy(J#){JL=f}yv2_;6Ix zmtR$1_=8Y;c+FYUC-z;au_M)JlY?iSJ`1#Nv*jET_|9ByG`TH^mu=l!B*l#;7*`8} zYFg7JrVK2WfGG-8%|OppqDF&_sEKHV3p9ZMF@Kaat#Pl98xl*;sOcytE!92HqN2rW>c7I?$VZ+(va)y5OWmU_}#&*hv z{bdzoS+4^o<-4^!OMA(}_VES&{CIE``Rhk%>}dZN8f%P8+Kv-w^vv(L+SJ8z^f}Xy3+6? z9;>&iCVpsT3KH~O;EXl{=SYZ&V6#(}CI41A*V^_WqJ_s*pN3|!IMD%etvY#0NX0@NNyUZ@`+XEmwxH-RFRG(2U4%&e)K`^f)lrEX~* z`E$L3f`}P3r6cX$X};S)3K3Xx7woMBp@S>redv@G3UjjZ_~U`%h!b=1h5GF<$@st2 zNU|@(AsCorf4B>E%0D9d>+O|E&y=78KRjt?9bbOS^44XQLhjE2PeFfWYO-n>m{b{x zAE6C&6w(ss-uNb4xKWPg15(DpsD$cYG~amOTW^`F9fVC#$0VBlYQVP@hU4e2J5}}= z6io8yGGvejj)MT`_;%CtX&uk0RJk|R$z6`+*}|S*a|p;1k1xdcBW0Xq>X(m`(y$P` z_u;hPQO=Bg#-sAC8f0rxy{0sEs(}Q#rc8AO^n7KZCOIwZ+Y9sHq$IpTyMS*Nh38LY zA$To$D^p6&k|M0hpPRPD(m>cI^L35r^mDDe^8@+PZ&QAW{%;<*CO9rGqOVNJZtdUE zIC>`iM(r}=fBh1W^b(H^*b_9V!CC z4^Lki7UkBqy+s;9x|JNdrKCX`Md|MDZlsY;3F#K3YX~Xnl7^u{TDrTw#oq7p{qu(d zqsP70eO+gI3uWPap-_|so&gY->sm4d$VYB&o|%P(e1P~cBm#{D(C2`~7TC#wm|o5c zrvCLOKa0+5o#U|imva3gvg<;!qn#&T_3Z78`;L0wQ9H2%13LYN*tTYwDlm(uymue3 zuIS`_xT(AnWG>Rg{K?Wqt}?jk7;ai4Q!{G}_E2Cy0z5Hr2GS-EGEX*%Vvg>fgW{dq z`F#m|TiFFkh1#nhP$B0i&Dt}k2&UIdNvs$5FP1quI4{j06jO(YixgtmAa3b_Sgk=dfwX{X1ctcpifYNu&S+o1c}V&7bv5U^SR&Ea{`8| zpNklA(XYpOSQr|r!**UQKbslxxRVz?-v~>K>>E0|GyI|Ir=9bM#?>%5Ogl4$?Tckj zs2w~Kzt`RU{cXC(3g@yffQ+tJUJ{=1EnJ;pbY?sU+%I6ioegS>UtA5-5DP%=Q;i%jvOV)}aU@rGa>?X4!#E1%o6Wp*O@ zw#AIh{|^$S>$}vtxUWO-le!M3-}#E7M${r28I4lF3B3yfzFLD-)gMC*Ro$3;I=q{Sg_|&sTT9GvZ1c&%qvHSXJlPA2wf%_VS&te>j*p+lprwYNWSa0tvyUEt%a8daq#ma7Ln03c zh0vgKoceY^0*T0Ap{wd2s&QPcFlFq-uUDCH>A{sM`iU<1L#RR62U|dP+|8CPasy`) z&$L9nMqp7nXBgF!iv@yl9m4Plo?CB3@FCUT-sw5{eLymZ# z-#hL{Ygn2fjbj*qvIb*;j8N&#llNdhW5=c_1@tjRB^>=C`%6SCVjl_SCi4>e;uGZp#vpQJxLi6zUgB}fdXUn- zHNGKdZEX$SNkE|p{$RiPn+ObvO-)Szr5U$yL#8S`i&!JH=dMy@$k#U2A=zazN}jJ{ zu;Fc9>@dAfBWit{59{b51dAgGasfyXR1@;zUGLXY)Be{+TzA3KDe0%%P)eP;gm}dt zL5ks)(1FXg$IsxLf-41J6aY|aJ;Z^31_IpL?SFw#rEHfcyE;gfnzfe1l?Vx^?O<~x zT7*%4z4iREMKVI2a@&A;v4tXv3&PnO9oBH1OH<^vMJ`D|*?S7X@ThsI5(ED1%)+0^ zekG6xkmBWbSXI;1`S1XmBbev*>q-Vt;cfySawnP?Wc*KX3luF3xGJlv`b`yoK!F4V zhz%OSTx&L*o}*f#)VGx~^8CrkH^r!Sea-6A9s){mhSGSpU*5orHi*rb;%gAK4!Xx% zDZzv}jCo%V#)oPP^+vF^hH@t<*u6i@ekr*|@nbzgo6pOCVrxVnSDA#XF7<Ew`@X(~|4+SCpvKf`%TIC0k6Ee-K}scZU$I+K zhQblP{N{>5_r4>(5$CQSH=v**rQdQB# zF*xmy|5SG;_x=R8avMD}$v#e;UmZ;dQ8+Qw_9?@?63f9ZF)8r&7M7yWquyeCPZ}^K zPD!cCu80zg&xpgpYm?_v{roGPQyeU=rIjkTKzXLibGAz#N;MMvK9n+Tw4wha1fs~_ zp=lKerChN^m!y3yLeoQ2H%5<_@%p(1GlK#XBbpGg==)O0n0H4$G^CH9X#E6N)~ZVk z`@3-xW|x>DguK1xHH{iMg9=+Cak$(q zq<5_(Yy2$8puwHU3WyzK(n`<*N;Jz@nDi!?hC%v-J+HInBK4XQvi~O;G?(Hd;Z665 z&eIFIdDzzBLf?@yh2UX+f{bVYD6M0;ig9dwQape^-t-Yb9AltwhJ@aEk$}YUY8wQ;0caM zW&t)Oq8B#{O>QxOS#ml&5d10V_WS_Ayj%VyGi>-jsDr)zZ#*-gP~suUK&Pz{hl@Q8 z`7EK%%^t+vD3{_X23h*eQ$P9oPT(&j^SPopyuT6jIWN(3I9w7$4D@fxp=DU^e*0Bf z$0Yo}2l~j^{_>?8D|1bxI#wuXf+$Pp z@%g1tOQ$ujq=uY8)|imF!&(ozZmWCrAZy$Erdcz#R7We{tVJM=^4LdBn}Vy*ZVtsp zWKDInA2n!OG~$aece^qF?%ec**pONUkb~mWSVs8YG`2bry)pHYlO4I_&_bsUkC+lQ zq1Cym-CE68k@$2JZ0fZRM7pL}5&t)^LU=EA{-*^1D9=hsfP2^Bc9&8ymX^6OLC0uN zWi4^ZJLJMqe*MZvKj_!Oqi{%MLYHbzY0UvNpMfhh3c_Jq1{*ZG6R0{1HIxaeVZf)R zUK>;Wj;fFs>;9MUd&{?_rPv{#L{DW2kGBcuY%ua5$P@y(Ep=a!lyb|9miQSr;a}9?C%ngjNs`1*jeHel&B&xf1I zccBT|-mS62F0%9lpfk#qR$*uetY4Eb%gJ3XS2ynf{Y>>BVPeDMHmL_Z12Qh2Hiiu$ z>txTfQ~H%+C>7MRWhuaY3B+0$8G#M19cTo>jtK5+*1cr@jOal)`RcbXxBOq*)ihV8 zenbW zc+KZ9E$yG~VH0MVScKg)6+0<0eiyCS9D+dUk0a~Oi7C| z55CC#OXSw?kXMplzYUN0h*}GF*bfLGD`fTxAU|=q{zqW~5^Iw(XWl)-86#J|k6Djt zEda6&p!jMKF`FL(wHPJ@#XAo%kGqfJbfM3O8iXH`EENi6+F8;~V>MXa1 zIiPFM!`;I_ni_EXyghVLRrrw-Xj1DtoIJb`mnw3Ej<3=y7?GUi{fe5gh>`rJ<5hM2 zJv0nVy9+F&^NU8dyMy1_^5w*i?bA%CC-2II5!UpB{zy1(? z;7!9uzlHAw)FO>(N3isi{JGQO*>3LJZKV{!ZXy+~5`{WXRK|2ScGK z+he$<{n<qB_?8RcF-jc*!d;^rU4g340sYQm z74t?wEq8l)$m-}4NZvKKA@HCWxsgi!waRYpx5>o;)e(~_i}96qY5e1IkEas6s0ffc zWQ{15OaXxc`HOdm&xfqJwbDDY+%g37x$9jGarkjf6UM;I8| zq%+1G20*^3ThZ$-0E*Sz%lJr1SGP+)n`f1`N}WI>zj_EAOLOq3sG(BOsSW;T6=*&5 z&G~xc4)UK4wX8zd+#MW4MEl%10Ir1D>##b++IBqrXwzv3vKv3`b1U}5q1nZD`k*KsM(vuMk6TBaod0Ru z#F;4xO}<>--N&`(D{aj6-o(h&zVJOx+r#F-1jkN6Zm*3p*^X)8MGXOchX8rS4Z2@1snbu?RqelW+gG6Ol_(lCbshdn^j=GlphQcVDb*gU{C>1a@ ztc^v8l=Csiv9}2eI7%zcP1rhuzoCn^Z%b=4V~;i3`{BOSb$Ua{K+ z=JRomUWR>&?-QBC?3>XNz!5Vne{I)jvy0mZr}k#rbHjd=1FZy06;mUMfn(26p8J&& zlW89vMKpq#*7Aq;c+FTXJC6*`xFPPmZqzqThC(T$;dn1!x)SakoE(i&g&TG=jDW-< zJkh~Tjay5BWV+k)rj9i1xA178aI)84q%aiH&$`=ueNuiUG|z`Zg6fE)+$WODATfqX`+=asrv&AG3r^K>Ur_ z+tcoJPMtU}y$k37Oow3QXBq5Ii^bzYwNGQ}R}Z7(jv|A6%G5F%U$)5?4RPvJE3Gp2*bM7!{w>cdC1MRF-go`9 z&9}qCCo3O?*J*{XW64@BUx&CIjM_p0%g7rI6e4s#LUWOA`JG{l-^Mw?S7S>X;`MOt zD9rlY(@XYACr7>AaNz1L;UL3{^I!oYij((@P4%iOQ-W$t%pez0 zQPgP*Gh>)S&#)Jv5eBjzf===c%taGN6QfBX?K45%w$ijjB^vThtdeo$W5_uf;mXQM zkWZAQVOpT+L4w=_0T%XwO3DxQ2Uc!&tyvNry6a5?7s>{j{tJy)u`i}e@q1@CKSs8U%&Hs;@dH%BumOfLZlkUidMJgHc4nO(< zr~cK@&v}#}o4a9gO%ZK;JARg$Rw3YfK>fihhs&kUC)WLrRn#MnNrMGAMx_$#1<2PX zSLNMJcGdqBTAFA=TtN|onVA{L<^pXWoe!-w%&&FOiDG*2470YM-Fb!YkYUxCP3g!$ zE*-D1uo0lx){l*Vz18Spv*Pg!lAYk6_CTbCHs7qZwWfu)0{IjBAj^3B(hE2NbLk|n zT=Gj2wv7i28;yn19B%FsfRpC6GEE5rsMJas)=9qqJ;rt526E!J$o6k4Isc>{ zev>fOrA}$U&OM2kq)w0JAV$il>6vx0^eQQj@q4F|&*fQyDz!N$&Jv%{`oXb|-C)z| z-D>)^bu^}F;OHW+o1F?TjOvy(aQc8}*E*sg0gPyw!oI^#gxA5rYmi7S>I-D+VhmZFUaWzA^AY51A=-H<4AV=;5NA5^|wX|E~^%(NuQ-HRVb_l9~FKmYJ1&f zeR>^fdl{Os`0AfbAurj?t!bM`<}MlSVpvRcG&qCu8jp3e*0~7`cnzQ-eAZg^!N+5J z$Fk5ulVPU5-T}u~mDxfgPx4pUzye+P3^-^2lRWcmQN-6}ZuNcxds&cHjcm&&YR9LdAGf4xD3l`*+WCp&WX=dpC`ou>dO5gfB{OW*oapmYwED+s}n*$6L#GZ&d zz{3Q^CsZ_L?~?~1TU%S;^Cx%LP5=v<=ug-NYU5V>=Puq+!CESf(}~lGs=jYB{u_~& z$d#*C+owmm84(v~8{=4tj9y>|p5Z8%88Cew?bb?NSrzD+3%{B&*;AU0CZUONRBWp}EnRchp z`QLf0NMS7mq3V319V@7VxKJ0bV@i#y|O8L{aTenDoNmLDab+7vneW-;JI^-!EOCPatB2 zuv-!;pavxp`WGhNGYBeZs%rZ$)+OO^SR(F zUXC@bAU0%3To|<_L++Q{P%ggujaH2{=jIMpyNsjhA(SBfp^zpgF@sP{!VCjdIp?2U zrHXy3;>DuWFB&0iyXuUK*bFq=7&H7nzc!BIyZ?qCJ9m7YaGDzma;3^8ky>c-iV+x8 zh+92d59&7#=l+>4+~9NVxaAc!-9C6bdqa(C^g<&E#K*rC7IuT0U0xFHHKe9w$S2P_ z??}I|YBkgoxJ9i}(Yp3sf~e-Y)Y&inJ!UK)?xb@HcU?4-&XQS(1@M-(lv`C|f)zefYU#NtC zicoVMIXEZ>D2KuBc;^k=!-#G;9o~8b`h2P+yGn;;+d{~d^<>eCJyi;0LH?}0i`wPI zMS6vM&e*0(-@>%ort0$Y#X-#4xBr@3YEnwFN)kNFGQ1~p%1i}ZUJgu5D1lV`iEY3i zdh0w--cO)Lalp-^RKww!(J<3cozn+VB^-fW-|VS0gx9BGf;?Kz4Tp>4pBNjW;LHCz z8KmNGO8&*Ovo>_zZifE!xXBS`SK^iVfGHDoGIpbKcU5r zRuL2%dXiG#{)kPplsO9BrRIVJDH-FkL=p`4*-Z<-vzcN2xIb6P?O)xY)KU>MpIKZ1 ztwW7#;;MKUaGxrCh^RX^k;15$dr0e{IS={)Rv2OH23nZptAU-xanztP8lEYqX5wYN z=5V8a8u9DS<1fQf-RkIkAyesls|h8vSxz$tIj)ApGHD&ewNMj*E@U;H`dBQ*y3nTQ zlMk=(JDq-SIMr4Wex;%#^)UZn?{P8DGb~0F1u=pS5XR7I>vA^K%uo&BiL-Zg|o z%|Sgrn-C{|Q)ke#nWbe=jBQXfm6geVu^vXEH!t${CbKp(-x-#?-w`V-2 z=~UnyikX!~*)ap?S0D~Vv=CA4(=OHXMRt_azRByF=uXpqL!rBY;x0`4D^*dD39lq#qunKlaQzi;_I8^?f*{z9NRcb< zmN|zB$zATw>-KZunUyu}HUlmbv{~h3)_!php% z+)N!#InG%?7he5f4iz$=x%>b(Z1|hzS{stDS4##hJ`O=qSnA{%DLC>*OAlrLvNDBP zfD8CC5JZa~fdJD4sTc!Y!Jy)NY3Vhf@to&gMRFOJM0Pv2|5x}0=CJrW(O{C{PDifjAz}l-% z_e+B`yTS`bivO~pK~;82qgtQ#`sno@Q4K>C}C5?3MrT&evq?oqRVA3weA$)3AeP9Wl{HHi|1DCh-E)swTSwR1MelZl zW=mzE_G*7yElsbur&3q=Ph(?C+T2-n`l(v?wCIaA_j?|bmT;@yo}{jSm;C0i%5qM> zm&N5=cGd!KcI*|S4*83XQq{+G(-0LFygUZkZ!ZgUmqj8C?CgHFxT-_#p0d$YY!Jq*jva2eP!86jwegaWj+|H3V0XIyn69x zg$h2v8oCPB)(u02Ww$n|hWr`Q#tIPtX8+K_sd)c>!$JTKum#^sYr<-xTXW$1|5Hj2X^1$k39d0pAUb34kW+ncqa?A^XaY)7cdPD zSXI)YmVZ$z>YEz=4AR%6;}M5U1A%-4lp(|_#%_7^D-3PEk<4RPQ%eStFv&ax4_zdZ zV;i&iSZNm>ie?&5I~(7O*iS}iT3k+yWa8`&q!b0(xAVz?jdrL$q0FTtU3t_ld2|e{ zb;OuAJKysRD)nE?%~Q6)7zD+?{m`5D)A1dSu;cw7*7eT%?#1)PZpUsr-&=b82wneC ztaWS++{El^>c1w_>sr!AU$`7d#;@KjYQerXmEl_pJ?!-y=H4Z9{J}BQfa4kC{=;-o zYHu03Q!Ku5d(jiJZ?zKqaW&qr^%)OlV9eR zaNn3NN-3fSCD7%B8jI)SD)J5*G9nDfW*rrgKB5s)uxBvaa?ffvJff_W)JTY|X!6%9buVXs1^^z~CS&XVUYGf+8#>JA|Lb8Ix`NQwRaLs*L7_xCrF zYgl<>MFMUUoQp*-KO3#KqyIRZhppD{*+vnQfRW2m@|RlxhZ15(ie`&KlUvC%T{7AG zXI>l2u7VK+J~#0$u)vOg0iEN|eq`B&76TK#dRII+a|+4owdS&w48~3K@xwZKvLC;= zpjL2W?`CJt+-bTPHa*ZqzO5r}K;TKxG=rB5qPkzO?nJNYGF40fwZLmPx(HJcoze33 zis`Ib7vu_SGjmIm8sQ);5e>2(q^kP=AxH%6=)nxO%sk%2=8`B4b9KZgxSKd<8*i^O zu!_~OegsM5o9B?qSS<2Z{-S^LhUycdao&fLHaR{LBUQObPIa5|`gT69IPn~7vG?K9 zkXiAsAGk6S#m4?2St(MRmZX3MiqxB>?WkmZkS3fjm(diKJi#9_+03aBk$dZdL1ot0FFstlF|`eH4JVHtA!^j2$s>J{t=mzK78|O+t8FW2Jx>`_7P-&edz1q! ztL)hiOehk^=Al}Z465Sgx2X6hNmUge)j_(+C+1vT&rqR*(x%-|$b>6xRDC$qMG_ZJ zTs0?l9j3)X(pO2R-QE4;^*AhdCR zxO)o{W}#|2PCnm`M-NE?0wxIu0kgnMTHVwn*R*H~KztB&4b)*4sh)}1!g+d0iCz;; zdM?CHgLn0ox0*gG$U&uZ9XGqM@_tw@9q@#M2OW$i7S!mTpQYC8Kvu|0VDAQxEeO%9 zYHAuhK6cQ!VP*32*q)5mNJ`x45g1`~ajjq^t(VzMo%~#LY+2jQhoV3)Q8Jr5u^&r~ zA`=gwnNNy2lqw8;;79Qa34LEa#Q71rV%|43g$IC8CztHrgP)o2X_)XM;+vTlKQY%k zDjyJm_I4p*D{nmQdW}~4`TcpnhS%z7_-GsN@}iqsxLYmW`n-Bk_V4_yC%oWy_4786 zhS4$qeY#1SVo_{{HKRh(FMZWdh*=CS_7WSN%w_FdikEYxZcW`e+_RGRI&JAtA-eU% zp9X@{`RElP`-?Bc%bzK4@aG7Q`>JBM8Z@#l1_=LS?d%4zQ24VC@1cPk%rRRf?_TnM z%Puu91!!d64CQT7XJah#_%xusqkG!LVb(8)<|AZp_mD z1w{?HY%Lv+a<+#AMe<-;?;l08$n6{GM(6Ro=t0Hk>#jw~5iT3tzc#U%2O17%t>9*zCHvc! zoojq#<}xk`h01|+MV@fVcxn*Vle~TaN|pc$;@nieWLr4#OrJZ=0T2nGiZG%(m)gOs zMnfjM06;5lD3=-MnWZ=ix;XRj4p9|kJm-fI(nC9q7e9Mx5=O=)LFg7RyZd+ya{&mk zuQxs+7c8dxt{~R{5cIV$pqhEA1QU9^b9#C`l&P8sE<`CN8jx8-h_<;d9uqIt+ z=JF7)+Bp|H`SQQa)XnzK#0XZkm9D3L_P75W>{gl{*yAa*`yU1mVQ*xonJ0edDfe+> zw|@>!|5*+D;0k2hJ#6{$3}vH+os8Ml{kq&hx zv6t0eo3|J^SF-gzZ9u4=QQud~`BWtWfg?gIIlNI7hQM6*gInfvZwGd^t@-BPm*%CDxz z2=+Aa_UDZrylDiVTwK%vP&|05=n6oY$x~)*E}g6+?*}Dd(g#vcAV_xRTO@al$US0M z`lQ8kHfgmQHEjRzuqJU?kyhUODgI6LT6{Ko0Ut>em~OvP%K)J7sTmhs@&J?(Lk`as zK~`H645w5rQAuI@gbPY<0T|y?V>a^iu8>$6uF%ih8}L)z;X0j)2UyR|l5Sr3?!ZDB z@jrT(D5oZ&3u#H{(ZTgoewLhOs#hWUEqq7V zP*4M-y(P*Z#ND5#8}?6uX0r6vZ{NMm!-@zle=8k9PS`VO_Q#pN@{4}(oE%v=yOBbT>g`wD}egE^a;ddT5()l3|jlDd9Xe-0kyVfF~O(E9) zJx2#&4DQ79#N~3NoTsn%%w?gbXLrqY;4G~-LXwB4@Mv~`uz##<+`P8(Q>i|?kJFL?tC&|naFSo3vB35PNb$%Q={?ONHJqDTSgca!X@cL#N5Ty z{DvIIe{Akt2X&4CnF>J)T~M5U#;amnpLFfI5|`XE{sQ7a`)an-NzC|y=En~LQl zly&#@AM5F4EEqWvgK-D2QZoDSkb`RV6P3C&QN;X9>Eb)%Ds7$d-6z>JYqXY~ zd%veT)XVq0@d4&8+c#B|mf}U?d>qMefe^|Qo0q%jsOxDXuu)VC=Bj_vD%6L*=TD$e z3np0R=1Zu+%s@JZKYsKmo=l*sU5H1`b7^bU%5lbOrc>xUHKt_7gm8EJ$7laFNd20! zegFAYuZnC=geLSn>X#?ncK5v|GZLY7=!A1WaL(|OK1I54l7RgU)XqgoiY09jTD2;_ z=l`t+m!oB|pR6%~XiFukr=51TX&kU~7(L1C-C|bwOHf!Cn8$%(Ku*kUQ3{BQIubm_=Ic9&0KnTkMJQ4EsZcXXm{nPA(`0?W;IjK|NxW}rdV=S9mCLXy&LGdB z(F0M?OwlxHd5y>%Ko`MD3vAba=P(Zne=cv&ygu{k6e7puBA0QMOcg7CHq*dR2hM|$ zEa9#7b$Fu}4x~7}4k_aLWz5t2!?fuigjrjKS{Zh{yrR-RQ8-l$w!cey*Wl4nl9gX! zbm%n^)>zh4rh9ZAcDKJ~we6&ZB>XQE(-ToiW8IEU^&+!Uf?NkrGYBfwhcIq-u`IBO z?Eg(|p&66z2V2g8jJp1XLUY^t&{thsA8)_NA9JU~|Hg3Jm3Eb3en z-Du!A<7BxWmVm<*Bn-3iae4KQ8IOXZ)>H7>K5sFn#jvGo^K49ONn?%H(7;zBipzjdS`1r+c3(*i8K!x< zr1v3mn`?M{&?46$Hn==y232W_I2aM@GNO_8=aG(vn{q{2V~Mbxfs96>c0Onsv?D4c zNF15Rr$&rlEmhycGNYhYG)H{&FY0CMivjImE^J0>{9yDc9|ZjE5o98?Ag%NZ9{Jgo(A|6HsJ(l_Bm$lH=`dN@`NtC!fP?CZc z>pn6;I4h5nGZb(;cRPyaL}#E1+(t}akT=j5-x&7PTa|P zX4dMLth&2PmxQ15R;V+rb9eQ1d&xXWMX?`vnk*4dhFS=en>=)%q8QX@9Vt zv)%pWrD-)6#IoJYrO5eG|N2{{tJ|8gE?qboM)(2=x4bctAIJp@W<#bm$}@;AmteCT zGQ}y-uA+ZJ??7}9P!5SJfO>!pM-7-8Mg`{wpgSx`)ujiJ`=6E05b&)4{R5`?TjeO6 z;LBofsn5ETSKq60elNCOhosG@9iRJbT-K9O8lKYJ4EWCwlT_AAHB=ZdR_*Tg)^jQS zHxv8*QpahuO7ttb+uBKN6q(*v8spNv(4Xh5pSxOoIZ%d+eul9eNWfhXdm- zTTco#+IA^QK>|4h_U%OdOX;j-kN4HQiJeuc1HQK+{8VTS)g)h$3hY+zU&NB3$S#Vj z6}~lM^w)*^p{f``9aHl2g1_-7@6H%%h=aa#C#LY6q% zGes;3lp))!Tps<|9sO~Hp6U7SaK#+PAhiX}uu4>m7c^gghsfdQ;a!iD+lW&eVoHF9 z3=^a#*JM%CyQ4wPTJCiXd1`70(!lrvO0^pY%)~>aPUF)2(wN=p{hi@2U82Dfc@A8D zWiF8S31o5_j2RhKzQL#s8-636tAqj`+JgG4a~@Ph-phw=YdZH{j`t~%km6?wZzwJ4 z#NkzmOQ%SB2d;1x?J!@ds%!G_=gyLsmSmJfkhW;X4;50EBp_?WHxiGwA|U!pej;aM zpxnL)^WtCMf1Qt$ue!m`rmngjUQ_cXRVE-ler?SNOfr?Q>?nu)-bDRY?d%q@`W`o= zUFKgk?}5so0f2&khvTSdyzUi0dpbC5Gy9upkj*kbTFyK4!)JCt+Y7c!7@bN$81+PE zaXiOeOH1_bAYx*HIGw`qP-Q~WszoYgK@)+FuI@Mp#D!|o;entdpgbs8ehLP)sGkSb zt)O`B5G)$T8a>W@R3DP_2NSM4rg(Lj@WCN6t6}x^)jD z!^mI-mP@tqzpo+$WG|ah)HK==#(8QrmeG0G`MAr12+cI@NpgG1;)il8)&CpV53#LQ zhuW7;Zq*hfznQ4RjH$246RBA1vts=hbUtQJuRwNHiVXY?;S3#>1U;SPbZfS4OHB&S z>O8YgoA2J!1t(BsBM~^RzMd<3x56wuEL=)Y`y&Elh ziG0fX#~%8uh+KORK5N4%E31r4p|TecqJARK`>o@$e(**`7MllK3Y(;_CQ`q~PRQ$U?W7G?F?$QPaHmqFQD4yR=s+H@sJ9;P`;{OiPxk>k*g6mOx&mu4F zdSQOq)CB};8=RB=vvgAnkvE&d4;Ba9lN z-sUvo>ZjXGO|lq`wJC*4YmxWeBhRH^C!@sHkph?S5-=qKc$12dQGsJjUm)1(-UrDLqfXly4l7thJqjDuf(!R; zx1;}%Qo@vYM_gn1y+QP!er-m&AWBO&nVY8dmRH}<`_EA6nd0F6bJ*C3KYrSQ56Ygh zeFK!&PVONBPQA14NST~2K@xxKiI-W5yW|yc3+C)NUptt26e_13fLP_TZ6%&%w&91{ zy4i!W`PCaimp7SB^3koIGk6MWuQuR$yj>?w65C`I&k!Q6^0g^o#U57ZnoS<*&^qNw zU2Sdm;P2V<`#|aqR+9qM8c?}t&KbHEh@F^s5+))On`G5AdynCtvhG+g0N&hiOJ~K*E-->;7JPo*{h( zKqbgS0jh+&F>)E~RbCdWg&v3Z@ze$JJl=>2E~zz4PSpF3{Xm{HRS$j-K zV>~i9ey4!T#k_tFygYB5B$JQBE3KxyY(Br9ysEP=Gc70KRb}OLGiW}Lxu!HZ_>k3N zeZMSz4>;(5&sNVR36GMgD;4kA)M>0h9Esw!1|xBY_60E#35R1aU7&gnwBSCPOsNct zsYhn~&05ynt?BII(wr+bJw3frn+a34+SmTq*fDzuQiwQ*7-8l2>^{}>j7h2W%(MJU*5|Rhe{JvVlv3H1#{v{58CXBxAstDF1P5e1+yRDP~TEc+hpMW_-f(tCbRZuD_? z_lpm|Hf&#`jY*L&+{m{A@e_G@R2UbR^tGk}#HUxsAch>pBNIm=UbJoGVTHo&aFJFP z8-EbtW2R5LGdD!b1YDJ-S``_4Qd#)R7#Ss6uBz1ZG`UhNzW8*Wu!?eVmNR8q%> ztD_o@<@ce6Ylw0)|4n20FxD;|Rg1>Ma^7i#g;)twOlsiD%;!SXF-= z1{n)^t)aYpLWYO^IL?`0zcY#-fvP1Mutl4CKpp&x z%D#=i1UZ1n6yPrccnc_}4&wcy=<%9>Q4=%Pgs5aHe9BTK-fh?CI9f+2&b`z2^2^p^ z8W=zm>JNn#`OZD0uP`b^`nZXojN(r%$`c3Yp0%1~=(*gn&?zIzf-@JpHzxwDZ8h2~ zMCel5x;h*{B?u-@1UGVzjPp7#I$KBm0A7cA5LW_(dw?AQQd!6#M=gv5qq?Ity2T@k zSnp-|*T&boIB&J{(}=iPn-tpWhE6VSibcm|@pb>dPAK|=;4if;$3;+N&C;pV*k1)h zkR&j-k<-d%qre)MFm@yp_<`*$szNL=FeQ14b0dcI70MjkYZd+28RQAn{2&1P>JNc% zUQPX=qtKS{eeYwRV^#JjVj}h4(%bd+`NM2+aS+~}hJHZy>ZGLY-s&L>xJPI{DEXW% zdEKoNwCS6PPZEn~0g2B?17sM%-!lTJPN^*@ORx@S~s%|H?ht{Wmh-BcXfU7}F9I*vV4U;n8l} zBUhI94SkDG)}`;A5a2gogVBE58B^?Nn>Ooc`C*03{qBl=Q9k6Q(3Rgy;k(M;lS8NJ zBSQBHdXJktcMq3sc@vh$4>3z19MxC0Y5pAqJ#wn~_JRNI-tIxz=k{eA#I~#X_5frC zPsB8UR*)!OgGP1x!vh_k+nBbE2-ep)GRZ4V26@J9X3w_%Lo{1{4G|X-KdX;x`MyUg2kDT2V|Y1$f7r;$fg*xZ0Mc z-I~npr#nG@)m?s3&Pj*&3_G$$qVD_TH6OIf5x;*9IUi3Nt%LYufMtaai-08UPZp$!cY5=|?)=JPtoEzDWTqP0f+`dg7JokR@_eZJ?O!zH$q4SudHw zZ9MKW6U9ZzMGkU?IzqYRn@H02#g-F$vx{A8moj=O%Ooj6OWXgFrWJf+l7Moe9{S;! zbKAWst1|x~oocgs;Fn)7ms(41lWh|XZRGE@Z^FZ7BKep}DS+kc?A-Ox{tQ`^N{09C z+m*f5g{e{IlijU-Re>p&>ExD^X00I-SwjAT*VdOKHiv2oEmozfjDW?-I}UBR7X*5x z<=ruhdLml(S%#7Y0-J4X<<`^OgT;r+-!87R&sp0lmb~4Xw&h#O$sP>FF1w5JdF;*& z>@S+>H_4P^f7*x7X4ioOE3Tm23XZ)zc)RbXJQw{&9X(@HKhGJD82IoHh4>G67$|*y zE1^JMVA!b5mNBf(v}vrN%HaLHpJeCIvP`3Zv36>=-0KZ%2rEJXZiamCl$b4NhK*y% zhmt8Kl{)`E8>ps9%RIv|$#95%1yg~ujPzWhj3u|0pVBG|KAKzPI3AcLN>=bXODJj@ zYhZx?gb-Op>S%q&LAD6POk>#VH&&eEsh_t=8cbjsltZuw)HNQ1@c}x~cM|U2G>M^- zWse_OcZ|(?Heb*`=0r)GZ7|yX^;_}sCor}9jK2GS@+@5jv7rqTXGcY5IK5_ zdVXgw9Yp@;%GB&X^@Y;-IvlxsQO&uvoPXMQws6Z}82B)A%jTwE2q+`6s{9$%xMdMY0(!b(Nvp=vtw$N0#ro*<*Ui z7@n%8>&EM*UN?2Z&aFaP!o1lguVfGh9-HNJg_GcSJcT#WkH@E{Z!_H9{>tZ}ChK_l zezt9W=OmI2yT~+zKjt+X2SOXb=B5r$4@QJmV;;MOw`RZ6cFA)5J-_-xD@-w>D)9Lt z0c4-8WEdR?yZ>?*c&gS53g@1y`{4TfQ^`5;U&M<^#{;_CS0rzqR!^S(1Tu#k z?Nr9wiA?$fOCtWuUbaM!Vu2^x^KM?EmBGDx<3Ew)Sg)lpx*R9nvY?-QCjNQc}_& zE#08N0qF+mlJ4&AZul1WzW4hLgTWbR@3rQ95-%pweox#_c?X(By%b|+GXfkN!j_I! z)Fq#SukJk%gh=9`BlR+emiTuKFx5UvRF_d6AZDXP#mgm8V`6R_yw|dd^8*B`hp#`M1+fc$fMxMxkC^U%w>S&*5_~%1KsHN-E8fQ%VY zPv9z-e*9_p=C(zPOKB2IIHdr5<^t3tR%EogRje%!J%Y@=@)JI#S&*5#Qfm=m$e#)D zxBmvR{)dbySrAY1T8$ob>s4+p?XBo0OuR%8P+ z%Q;^I&(@+Bh~x0@qTv=Q3$eno*G^kqxU1a5S~n#PusYWf$dJH!&wn>Ne7pU;CST|I z%;10$$FTKqG%kNLx%@=`d=mW}SQT5l?2(lDye8~(@idPBjqm&l%;sFa=hMDD%g?pT z-&51XqX|wZeJ^?*Mu&X`%f|D2;XxQ(>%*r0se0=J`T8jq*#Z~;+VW#pYwo1=S>rJO zy1)bBvtRMRz##OU!SIz2)R~8!U6N~U$1#CGLHc1FL@iJATidKadS)66e$-84>mz!7 z%|l=26RlSHMp8KJ^JVK3+xB+h!&)KX=?>)HJpD}F_dc^eO|KlBP6E$_PvS?d_Y9ty z-u?E@eT{@qfdcpE0%lzJ=MTH6EjJGz`JWGrGx$7Z^soq;TrzpY#nHOLT5soDP1qZa z?42`xAMKtgqn12U+m3z23nz(Zv6-ZlpQfK5eT}(N&(__RHjV`%*CFe@P;Ve*x7w0~H#Dz)zYIh-hPhH}ORl7kK1&Ar z7$uFr((bOE{`q1XSZxbu(<4fUM^Zbj1k@rPmgb zHgot5|I-41zFZd6Pz-+|i4+JseR;GF-p4`AziJ441(B+(4<(A3kFZD zMepXf4_YgGe8vjg3L~R1qRa!w?owlWT>>3v#KphT#H&h>BF|0dv3(;MUSR2tLuCI@ z?>7NOpEg;HhC_~5PVZ2p5h_L!W3r)gKPX-h(|U4ZJvmPeE$~~ zo%z?s)dRa#S&J}`zo!V7Ueb5{rSMk`KR&Pa>a8CXtCoCtFOdo>`7u}GBOQ+MTd_{^ zR|H$cB;RE-$l{*7VldLg20myx*L;dtYiI+SpPXrFEC^|YizonD`P7TT-+3lJyUy`MOkK5JF_2won+T&~k z7BdMGX4liC!*HuuU(>GPPeBBiomuk2MLNBT@eXi4;UR|Rgn;FoWe4dc3}^9riBwh{ zSSH4tHz#*iy%v`~tQ>Q3AlI*MZ4zft6}fdv{I@|q0{bu zo^{{6&0;i9tzIaIucyL3Lqdn1;FfsZvy{an^PIG%@ErBnBi ztG=uH`oYt>jjW#wweNE<{K6)_DX}ZXG-j%_;7XhWkn_rls4I>v8(@{@tWwgOzv-z> zJxTz9A*vYvNTAndRDV}AXE*#=8T5sr>OZ@7nzNG0DxWod`U+~+_AAskpH$@)9X_sV zR)-H4c$Sp3%a6Av>;NQ||bh)A!>Z?Oa8uDV3*HYLxCFxtSrVppoH^$_n3eEU@fBW zB&=_eeEe7O^_T4(0>Z}wv!>^DxB9v--J3hq=~G|9?~_u*K^3ZR=W%a8M)Pmv`d-18 zelzxYt}h_v-N%vd9>P9ag`p4Z0?_QyY#eR&JUZO*TF?8p9fxoX9nHfvF89j)7}#-jo&F$-|}1tK6VmCYhe4Gl5*2o{O71 zZ&nH`k^wuKK_bcNH?pSI_W|TeUgPIBVXbC@j#H3V*lWbUzPA^93*wQwc)czVdyvq3 zdORb#Q5hH*CDdtS^MHkKz@~Edv=^!to{lu4~HkWECZ|G0ImEl!ePb zQ}HylB}OBA&)w+Bgqw|Ne8C#vwMiE&tWCeuP82Wn6DvEl@Y44M#=&7~tf0)Iv;&rGrWZjeNyLez-Y$%Tpyv0fP=APBZQIOi8z*)6X{kU}!=8sH z7+=76w*P4~!ec&2sMqj|hm(v@sY~ko<-d6;69F##lGFje`oix)NDuJgEI7?tMxRl` z`mmDeLvu08(aEM_jip72GN`6tLQvP_qKBS{PYr@q$G(!dU`z z@VoDWz%~X4JU{`4*MnJQtyj~+(@OEiRx(&X!s{1P6_0uZbCk+O=Ms(fsAV-s$T4%X zi@w^WE>`_UT_){os|w3ABhgN^TxPGlTGb@BbC=o^`CuPJ)|?PXFRHsAIOT|6<^-o| zTawT6$R7JJH(#@$rckvc_CEd^USF9F(?gQL7B$WRCF!k+yQrcFsRif|s+q`*tU$CQ z5=>AkQ7eu;I0T3-`7uZV0)oFyN6C}|G*Q2+%|w8{Se-!^Z;R#nO*N>zdSeRFpc`_a zWgHPp+OX9y<8+mx28nyWXco7uiqfQZqJKxHmX_?>1oOkP*%ph~&wSnqFG6=rphN5- zqq05crPMav5Y?keYty851CDK;{N@@;?>ET&fbG+_uu>J?| zJ*smnv3iEz%a7iPCYpk?_JvP1Zqi|}iZP7D%=%&%WM`z}Nt+B`@-YTPCt0LHOeS^o z*(Vmf^H)#cO;)F^c&tAk{p*xuTjE{dWto9XRzn?b>Ex6o0t#=QfLG0WnQ?KbKIhS` zs}CD*wN2;>o&`LQFUcii^RFNO{^fHP%cEPIbnJ|p!zTFtW0o9)(+rk@5T^VO*MoE$ zrcv+;ysKZw8+)^Y%PNL+ZsB^?MlU8Oq-ZqN$&b2xi<3{2q5U#QNN!F}$Uwlf>{j@L zYU`3?c|}~{iMiJH_-x+o3AfPfoz8r7*R}7-N881QuIl~iaxM4uL5@1tb?)cgW1qp} z<@>MWl^+|j3#<}Nml_7Sz=TQYbwk{28~sQb-FMcM5nnc#%((xG61c4>34LXrb_fJQ z*;31v467zZGGqd2L}NnVXJZc`_&I)p z6EO56Y{;p&#@r5_Tka7kt2-wj)}=rb>rk}sjdwqtA^&i41iQje3>kImJWr>$=x69W zi>=zpLq~V7zkOa}c1$Ztt#{2c18H&r+y$V%*?Jus@pm2&kYu4XTRHAa@qH;I$mvfRhT)IzE+xMe3aAl0(BZyy6rfyWi zN^%P)z~<1I3miEal`~L|>BSUvu7&wK#<1{l=KruYvc{x^E>n0J)F;!+k%~`s8r!`_jCVEw6oN`%H)*QAF zO8Tl%tXzizlF$cc>bLmub+kHpU6w}6nmUOJbOpaTg~!Mncu2-5J}kDd+nHk61hmi4 zM2a96jf=Y7kL>!UCK7QY$p*nhp=_d%L?s^Z*83`1J6);FseiZrv9`VohPT zrxv5Zfh3(6i6*VWzIP=(kF6zRo-TCnqdqxwo%SUJ>mJkchG#U$tzU;RHOW94zF6e+ zE=xb^W!9li2YxP_*7j5lG>#<$r_WRh1VS$oIBFgkGID&|&^+kf4Z%G)b+FA0^6w!d4+)CTXY?0hMZ*M!B`I~KFI6F|O z?OjtOYa>_hKjvF1)fbWKAn#6|ON#7ib)Y+FqltP)D59~UH9J7i#C}f8kH_CGOgHN? zBmwPSR8$lvFYkqEkw28v?-P?7!jV=ifT4UH;5EyRzMS!&TOL$&J)jotTL}8VX3o&tBj-j9Z2(B!0BijF zPchpj7GGAWG7*E|jLC*%A9T|twm$}Oh~Ylmh=V>k!js$W%<~-}EHNvL=$WU&C+6PT zu&z!oakFS_eb1oh$D!1frbE?*!>simN_1vs$||)32D}EIp6y#( z-{r*PHeh#tKn`V}*3?_q5_sHx$eKNL2t26s-`{-HUmg^k#$vCny%}hI+SY0HOr70j ze%=JQHxhrVeA#^AGVV$VQ)WgCo!qB@ITqygD!h`r{2_$pY~aou|D z{c_M+l{I%i-XnRP3^WYL3%-0ARqns+RTb{){U>d@husjePlC;)LOYe_UROZb`iSvo zjtwds;g!S0pz7VKARVUIGaVGyWv;7&6X!4==d^dcQ@LvVmX; zoY0IxbqN|yBz)LRf9wp@*@TGTt6~H#+#=r$9akSv-`%76+wb=jw6E73t!X-Er;r6c zdv8EO9k5DvoacJjo#Op1`DGlY^=Un!t@|3Na@gM{lu|^Iu0?fm`{i&C*~=uH)u`>3 zs?_g)h}X!g`YskffNjbW-1g(=JTY9Dskj0X4SI-e=znJCe8$0aa}dlNiBM{ z)R>D_X!i>x(}72oa`RlNl)v`8^q4bCLv?^bgHOl&tQCz6b1yI&1U;w<~*GNq{HtN%V&80>Q(D4%zD_xk>F*#U1_ zYDQ|48wCW2MgQriOgR0`y4UR~d}Tpa+ElVuk8Vwi9uE&ZEF zJc|zr@bMk&?f(F=IPey;N?WNqiRNV12A7u2)83s}3@|kEmsErM7(|o;-w#mO0;`*3 z?1r?S4SfszO+$-tX82!7>(8mu!-3F+aH+X)(VDUu=^IVt`h88}ZPj)NP3?aUh^iZg zwc>OMwQ2?ahm&i%%D_}N+w%J6E|aDx?$z%tFcqggLk5S{5Z%7t% zQ7>=SDuWLQ4=cTmqkp2Jx){YPRlCG8ccYe}?A3-CR22x|8O4*xjx+U@5A*q9I%sGs zVZdo8x(wpKBGZ_W+zk;zriO(G;{q|_( zoP(8$DI+hJY%ROf%^V<@Nhi(4&%fr*OA=<(;DA{kmD@q;>SjB(xKrT^Sc^Vn1UJyj zy@DsIc(P|zR$kxOvFqIL`*h#hV}f0_w6tFKw3hkX%_h9rD)sL;6vy$xMxnqHY+18w z65u`g-LK#9-(SFEgvV?2m@6(cyQCgJ9|SjfTq7by5u6?!^RI*t^P6!EV_n=YG~eU! zX!GRt`MdetFH;}HT5;%asz0CWI~~rwuW`NRY{)c#=Hu=l&Rn{Goth^zT=1}2_5`Xf zZ9w2`-_><_zKv@Aey5G{47rRQyd>AD7miS;ytr;m)TEsNXU#`_c zQXkeONel7RwBxB2vC_^h_059DKBJj_bAj^j>V&i5eN`-@Ko))uXE?gz-_9ZPjs`_~ z@@=J-yrW81gpg=kiYB!JbbOiMi#YZY-*ijjJfaj=-&cf*|pqK01}cjO#M>i+&Z7i>a^W{$$yfo2P_)=nSdMu?=DC} zvu7naa;EA}&@FAJ^yWR@SWgx?%5SMiqUX7GZSLly4=3iaZzBvXYWn>!)tj(x^pMb*I_WCb=rE>>bN?U z*rsjUMYMV_EV-*s4%k@nz09uQ0AQpo#rc#r{LS~tuRF-1I9dW38>CsSkIVC~uI2_e zoi=mabjka+4?jN)bMbI*oHG*GJ39Yqdm^o{?hHQm{nH_ST^{sx{I40T8a#)*t>Hjy ze_&x<$%1m#NxUnB38?nU5QkKwKJy7=5#7=i6b_QkOUB$ecP?n2OTH zd}`3^&SWx%%XEY^n`~Xd%T26LM=dQ*c~ntd-?zw9d;3_Jd45}%Y3M}EBK*hR-Tjjy zna=$DYWI=smqkPlS3BU?HyPj(e<%MzooK3}xgL}YEaaQ9YHQD9p~iiNqAWBcv*=rF zEUR=nN7UB#9AVa3ZWLq;qsD|kyNys^_6lD-g=Uw&eTa+J#3Lx@ZR`@bFMNK3+ku?A z4*IWP1@2Y>-uiq{MpfaDwDkNvn*Zso;OHSzGdf|Iy3Yy5^9G}D=n>VGz|DI??+aov zTIfZFN88~2#zt#98^fxtzI95x%%e(~Am1lOgvK~n&(u_2t{F2YyJ+>R($kf7dEh)- zTMc-JCW^dA>N0YvalStwX7}$5=T)gV|L|?4T#N~3D&afDU->93IeF|&Y=;SQp{6rb zbhJXfe~K03`wbG>oZmT%rEYXE&tAln47?Vk$->ivSa_dhhEO`t#al>bprM6|%Cc&a zI4j&)oaU8iZ0jfN^>e8Z*@iC|y`o3y)zzoOJiWAVz}c)aBg`jZQN3x_8iwb4`w6!b zCym`NLapTq;wl&lGXy7UNG)ZDzL)owT%`P}NH6yfjQ=SaLw8(vVgtS*XGE4_Kdt63 zDdV^B>Wcnqt5{X)RURxel>FTe!FuwF&UDmVqRF`-Aqmk3Jh1)C=i~38WFZWz2hNeu z(9arxgWJ!arw@HV6u~ zXa~3h2S0P3nrcW{d8|iH&(1HN%f3&X8RC)~Zp!)FCpD^`9SPyb9p1|==r2yIs(+k(H`8w^^>Y8E$#hrKShJo$F(?t)^A9l8sT>S5HySC|X`OvC`@pn*#be5LRcgexYDSU`4g8AU+ z;AA}WA%dgz8Ka(dCmQ;|T8`?>pLalmVY})4>UgHvHL|hnA=dZ0_BjeCBnK9-v&y<9g9e5<_}T?(ZNj$L;dd zmK~t(yl&cpz3xtX*pjtt%eNe+k>p^hARd=Pv`tsJgePE8k@q^L6fm@61p!=pWjA)| z1g*Z$Z$1Z^vf`E3R(5Q;zp-uu#IPBG<-tl)QpoZGrNjohEUJ1H8TMbk`2W+5RZ_XiTD3m-?-$${fgYpXO!m_`osba?TSi{8pb*59 z6z~vDF+;sol7nhAjqF-+4&1vKg_cPk#gCxo@x~ihh@SHB7l-v1ZU51k^&4?awExUn zl7*0k3SBFLGATibC)fo}om)qfWU5%FODlfzCri#>sB&^G)_&?v50q(I&j1{?s#-DE zHUdpvVw|b74Jw=flJ*aVBjy61(VMhpf}~nr_fuD$AC80ZMI!(s68R9lWGJqj$gj!O zkRXdmstiq|LMi2ELJ!5t2XZV{G3=@_PKTY7;o?P-H7pr4s53SD61v3ZNJv?s#}fSs zuXBE_3zSF3_d&VceE5j?7V&uX`?(L(Xq&K$N`WZCW#hRYvC8pmKd~Ue8R1TKU5oF) z7jY>FKg8x!13R;cCW!w>c(-&_4dkcEGQb`ONHvi)##!wQhIb(#bw8t28H| z1ae+# zbsO=iv=WZou#(6zo2Yaow=x*550fCRg)XG?A(z1ms`IGGX)c@&m@L!`k2+WcWd~3U zHPy|E|3Sw@!;?O2x1KYm|KVT$x?53A!!m;b)#nIO1^+l3gZ!j{N@e~p&wTt3D{nB) zxdvEQYg=!RXIP9`X3uB>lzPVz)U`Uf<>ckux7}KWEBqTdj+yqZydO!e9P**I0~9!k zH5uHWo3D3VJ$b!OfQo~mwy(iDnPg)5a3s_y(M*~D{)ChuHG~CNHz<@+B<|znfQ3tAFr2*qexs`uR>&l$#_d zn9pQHgpv-jGTxjtBi)>IL?<&QnrQaj6E;PMqsLh_?%2v?WZFM3dGkM?T*rq)y+a~A zSrT|6RaDE87N-lVj6;1I5Lj4mc3WD#xCw+T{s0v3`MmGLd-)8!@A=rxPycKa9bGw4 z7#T|Q`&@j5xGirPJii*)jG$ua9Qt4t5TDrb=)L57%oiA&r?EoCwIHxEef`YHf3re5 zgoqRh%{R6i5fB{xJ;y*%EAbpEnvj1B3~`3s=@5!g$ET_)^y>(8jCxiAp38ZyXh}fecDl|{L*CvoB&09c|_>f(>=F*#6=?a zTD40GbH$eFlup8%i=S5SGHF>j&ZH;9evi0VE0VsRf-zN5NQ6>r+EB9~G*i(6*Rs3g zB#HScSrDS9s!IxGpi$Ek)zyYhP12RWU*>5 znT-z2_RSk|zY$Eqyv}^-{w{=6IwJW|hltVAJ>8;)4z(hyPo#=6cC6nHb$?_E#(bp} z5-6*Rph+WyZBwK~K^r31{AuU$4AT4``R93fBEAU&rL%XW{ zrs9MDAr6Rsy?rqr2mgWXeD z4~z2Bm5ylstF?;XAbuVsv=4*YWp2}yP;p74hiiH8rOP@{&F^p5Wb?|iN4Rn1X}_L7 zIZHR=bc5@`$LdcVw0$CfxTG!MrL>LGMNeop{>*$)&4nSsP|RRb^@F z;M=F;OoNwV9re*3B3ARW_+Z@MLtQ=U*MAcDn|;o$zG%p$<1_a`V}l%DHtt;%S`xiO z-|HlDtnr?Zj-PuE%De96Qij#tk|K7-f8E`pcUMU@szulwKa9FhbfGtV~0e4Ui=D!1uknwY>bu;h}$r=@OB(VW3p?d z{!;~|@Z6c6(*^s}WkA)8h49VV*47a?CLGHzDkGhSl7v2}=~8_1qN$~|n*JMfopHt0 zve!AOdM2F@_gJ&S!m~Uek!p5^`g$jP`}%>sbj~*a=Orv{$>eXyoJvgLc3IzE^ZE3) z2g`LujRk~y0L2V{&RpNDX&MlwWi?-x=I39SQ-JXSK(ZU_jCcFyrjEj@k`A=0y!;n^ zeW7JBJo*z?gQ}?y%;piJRy~MH^YQ}l`sng1wbBpQ!uchPVL7h68gv+#L!#lw3@r>U zNBJg4+#W@W{klX-slNL~SDoaVI!PW?>P1U?(2x*4fnJ(D7trIKWZU{*oX~u9Z6FKI zO9ge!v|{Dy5nQ+r|Aen}nw{aE(tMS`O@m=)1n>Il&BpKl*8ycAX&ZpVWYP@wnMRM!L@YIyGY;V5VUH zYCmmw!Y!(D92G=bSfVIdoLqv@nBDA$tHwOr{tUiqn-%jhaJ7_zmDqZ z`Z>*v`Lj^j^oGS=tb{yvtT(7(lVCx1t%Su{H=X+*E3uITZWl6NYZI{x*P|$Y+jZ`9 zexfFPeEOJH+0t6&XFzY7e!M=6;Y8qdhb%>B(7e`;jqpu_`ir6ncdC;wbFNC1X>v>w z2E^D-k^FZWL1D2ut zw);fZEk6Awuh97}J4_@UdY8x<#?*#hK%o&2M9yjCZegWiI~U>+HLeb~X&v|C63M}j zmUeIOxH}S~WTYG&(1Hvg-4gHC8w9CKLeWAT_4sJv=moC}KhXxTBhQJMqZ>MJ1lyu< zg5l`c6V(INf>8eY?`PS~qW-FxxT=f=wroh7k0vY1-qIKUY4X=_&p;46NSAU>wn|6v@1L2QxvZvZuo;hh4%f5EX`Iao;G}GmRSM4PV z$BDy8N~(c^0D$lw7dyycYXBQ=!X=`F;!T?@?CMf!EqMEFT!&YI7Sl<+%K4 z=LxPP7hU})K$V~9b5%Q*XkNT}40m>~qZIYS+fLXychT38u%YzyLiIG{r+D#(PBc1+ zDn%(|i^EX;H(GySH1>PbbHBe17Ygq%7tJ%Sib7_NuUDAE z+wRY*82S1k=&x%ek*H*h_J?2;@dQVLR2Um0IBov`9oSzQiR?YxA&vazVP6N~D7=*sT&CwYT0i9`JRAblTFz5p<8DPBjYc6TbTUoi;@Dw zb@BF_5~X!Z6(XxgU&3#xlVGOe&lwj${dI`eUx2Ihx%(hoh;yt)~9U z%GblRR7pr2Ry0{S(O{gs9|Nm=M=aIb>d}4CGSUSH-7Vz)%?=XL(am{wggS~c@^pzQ zcS&tK?fe)kIW5c8wI|?^tl2?dg6(ocmpSX&q`H3Y{5~jv@9PLg;^gKwDc6{AEf^fx z50kJs5GXlki9_A*xp%&~VgEB}l3blgCTW?!X2O!ad|X*w-Q{i!#QE8DQhEJTKN(!x zAIBE-AOCvb-0G1Nd(ApskPPi+ZgG1k;&{1aU6fFeO~aAh+|ZrteKM5 z)>Fkm{kcD;#wb4#g%#b5?_M|#fbqr}r6>}4YI4bbM-M5WmM$E>a{6uqcy+(Z&}(N_;F<;SLrFjh zQ_7^{_}B`KXF!t2KmS8$x68NQU!r?$!y9gt`QwHPQlGX_qrO40v{tQdKr8kLBH0t6 zLiZRj*?zdwV(Py!h=n8O&@_#+%vYQ%c7`n)=8Wpd>*kB=R<&xqzrtDsc+-M^#&gK3PFZ5n6}~ zI!&!*DCKIS%4rSqA>s9Q0I94t7xJD1gc;gOcZV`N{d+aI{TqWmvpzr6s+`x)Q0Uaw z;mE!|GQGn=H`lp)(o-;$S+6{xGl88o5-U&3Jx3TnMh#WBFD)`uV;_LFdRxd%^=8yw z$hS$>tx7a;*gFTWg#{9FeyP+2&zKfqlJSv8l1eF(;L7Vk#{Vv{eR@>%{uJ+KLl|v{ zJB;pK@$Qb^&)@r2Jc(2O=f=gon8}y#AVO@ioAbo+86&DVRnr-8IE6yqD5vta59=|MKf1X;QX8!6nvw7jJyFgyO^fBY!uR zE%xBm6b7h!PCvA{YbGEON-5ZPE%lqR)4NpNxopg?jQK*KvdVI4{FssRR9YfHy3ZyL z2EG6EYRoLY#0!A_*%>T55D2XiAO0<&L@V8@o$VMB%}_3DdwQ9TQs!MRudC2H^{neE zpxbnnVV3%KO|ji+m4@8vymHXPu53CNSf_Vy-X?)8fT=BvX*(S=H?yR%M35(P_sDON zqJ#z|8G8auy5KJ3;^A2b?IE{bdIIwOV@5XhV$S@BbquNn`i8pqF7|@_7N*r@6;)tg z%lrqeWGp;~XrRJL2V>X;QM>9!*q%C>wxURPp3EuT$)!Lvr2rwggBz7}*eU)jfGCTA z>7SSIva$F!czmKL9vC6bL~v&!_qg5@34Td^X;dRBi*|Kb~iXE}6(7}cf%^i7x|dHWA}AXQqe*HvQoliM=FvKBr?UfASQ(PJ5otal5YKTC>`8VwxkUNicX zsv#o`8CykBn=)6QhMDj!QV*f;=a-vlZ9Z(T(Ty)l-+R3(lz~1YC;@JF(_h6Hw;E^v z#xR^jNg*tNBwvF;!c6(Enh@*UA9LBjwz0an__AazZec&-o{>XDY@5T=IclO$(@$MRi<9%Gf8VcL(d6(R%&V>oL5T%KRq2bbqq0EkGCA8c<*7PRJUH+XOl?~i%{c5r2#4zfb$=`F#v8=`)-y0qCVN!2n0hXP|fSUxdV~IK-&d4P+7~O z?vKSNuhe?Nhy&&331wlggjV z6t+qUu(taa$WHYSRLi$Hql9ZjHKk8!;Xhm1c(02qMmRl5OIpdIB{z&zPc_seodm5) zSI~h1o{5c8?$RnmoYYYshwmxQ2J;s zLsgumAK-rFz^s|NQ6yG2(Rp(xr{3vltWQ%l&z`bDx#;)1thS!}v{>eTM7s0{?4~N{ z>@o1DTQBdiyGJ%o*`9}nH*E`^U-7#hL z494`H${2ay>c%4fC*AjImYuQ%^@%B$`4+ z*ZSjbs|iJk0c*>t<=JQoRX3(s=bv+ODlMpx-4r(F&)y$yy#Mhyx^>E|zrF^=xo?fh zNKrIugL*Cj%fZ~id~>9&VV2rXzy?YRc#cKV2~G_pmUcZ@)F=8A8b+fgL+ZKwnsxgV1w~WbNPfqo9UFrdNr(Dv za}D=Le!(d%ZPdMiO@E+ba&BM?b#-=@A-qUwI~;4jwW~deYR>rZ|66xQ7zVGvnnL7r8G>l3hKLaBo@V1+ z+)90)xa#wDJU`d-v?})6_7(P4@gSS1t{D8oD!vOd)(%G@Zg^^ZDV!jN%hQ|Uk(vB? zPYaUq|Gh|z(KPkaWFK-eeg`OUaL7}Sk+Vx@U${7}ue>I$DDvHh)fN7QK<@t$8Xsxb z#+n)Hcx?HHQexEDDz!4awUa=sIFOmmcc*VRT}YmRE`m6+UhPcvZO=v?{U$y z`PM^g9T3s&6DU6-3np9sgDxSmnXWRjdTseNUnm*r7s@MLEJ`kWaw*SXoI<9e2mYPsbkQ)m*3(uB47wC8@#z=Svmlf9o{_nXi3$IPBb_f#$}XGi&+y zbfXUyoPYFVul86diy!->3+HUk3eYopu+JX22l*8vxe{u%hBRMtrQs{+z*NGFg#b=f zbK}<*;)@@G&M5vFUw_{DAo*b04IKOLn@G8|e#*`fWth*4_Yr|ctR>m2I zjquLe&hES$*Uo;u`@L(88&(vroiaH-nWU0_AxLt6>8EOK)sL&!Oq{&`MVH_m8zcWz z-^6}=em%i)U!Nn92upbv2(($iN-;k_4}9e3I>lzj(mPMorxjPX`6i`B702;q-V|#e zX+RhX6BbBN1JNd&+j}LEpmoGd@5c$03L4aZvYv(vMkra39VjWnNY*$@3DMADbrLsI z@O+JpWi%7>Ebe6VFaLc`MZ*OUDz5f#SG&V1mA9u`OuEcI)cZ<#{W6@`bUsY5n)VCc zUa$~0B--}T(-=KoslUHWlPf5f5z2DB^s#x36?Uf!6ZdN}&olpx8nOEg!bBVH?Uo+u zf1cO1pp~4p{l*(n`$^_jJcsnjo2)MoAV7i|O8lOW)))4dZ3sEEBgc}~_!VBt3kUj( zxFgmO3yH$|K*!7~Mrn(DV9XHy)U{8{&mo?@M}sOZtuohmO}8U!Iy)XO*HPrnTA!4* zRtb8VvH^Mx8Wn!c@4B%yXY7gMEH*z87rzA^)i3CHa$MFnf+c(0HO0(JMF_Cy%q8e@ zxM}4r6Hq?)YfU**$WkVOhf~iu{xK87g9UIZY`O=BSCVLwCk#@6_-zGAAXd z<2`nz<99xp(8^1NJI&ZHtk|O?%c!b}KqO|qJk;UP(>xHD< z22(7+WyMm@Q=z(wrd+B&1x41n8{X_eG&2*imeSDmWuo|fZB$MDrfNUrpsy0pOKUG@ zKKf*?+V|QsnN+O?IfJx4omQXpQ+JS?4T`_QDzd2H0P6W;cpFUC{|$TxTe@R?9#xpu zA9dtzT6oi`y3}pR?Y#{yBlYGYVl3I}&CL&74%?UKKPoz!8lb&dmnZq9DN?(M^OmPQ zYjCEvSSeK1uB14|AQIpo@OMGZ>VHRV?c42dXy}R_2}i6YF1u!}xC;BN)90hm z$ncS0F)>;C7+tlUBtPohd3`@OlUBi+{|1?~yESENYn+<;@KZU`X}LGnm!{}X1_>2S zOB|-yi%8nbY_y8(u{4NA#o!`Mn;N@%>Sq#Dt%bMDdi#%d!w+d1RE}XLg2@yBY>_5g za-V@#Qc_s5RHv3=4f3DhGD2X4@RF_jC+Jv)*LL^s@POKeM-;&x+Q+vfvwTme zur$Ydvee;`j<<{WISHbxBU10ecfxSgs7ym5)VGu-2kBYV+{QM)f8lA7zqngL7lP#r zoZGv;*$Lqt=HlX~kVRSY+LxtBMa`M%vGHss(6Tz?r5p}d^;PUpCF|KA`A4U(auV#(yZ5=n|&F(0)McVV; ztX469@o*4a0_ZM_jMS~Et(~2l`-~UM+SFkg49Zw*=S}%DfmRWKMkJCb;E}wzsABNY zM6R3CvJ>?kYSApW{iQSP>*4Cl-`F}??=X@1)LzyftP9T1}_~IQ)Mm&6` zwc&0ND;{3Z1e2{E{PyR|1 z{Ckf+%g166+Y3v=?jLOO*I$~?WmV{7=Kt%3083csv~G_}{u_-)wMq9POBX++A#V?_ zWF%c7SdNbdnH9e-9SXF5F$}%i--F%s=zfm%DN|`?G`?u~4+X;e<}97mAytEvu!sd( zK3dr~ToGy}VCL(mji82l22G^`SS2)bO1*N;Xk4%MEY#m{bU5MPd5G!pf6*j6-&xxn z8;-wCqL&;GB$4+YEc)sc;u5dfc4qB2NWx9?8uG|4JeHy%9fLXZx_`_NPCOaoXXlz! zTX&H9kW{Esb`<25k>5;qE)xSBnQf31Oilva)o|OGa=HL0JB%9bET@>t_*+#^sVDji zI%XgCXb&s>rUAm4?O0wKB6a*DNBFup>+k!V7^U@-nvs4QCO;z7vaem5c~wgUbNxjv z42YC-sAq68q6SlD5#KESTBc27!R8`cYbuaQk99@JC1$0IQU|LQBh}q;pRCK{cRAk+ zb3ZC@OjCr6aauGC=%CiLBMW8a9r8w&|YiUr6axweqFSe_8#YmyC5gr)#}WR$iUo z;^n?iw*^8U=5D~ugUst(x`8>X$Abe9HH<>Q`FXIldGCZKyiHSF5v|ifr}{vtIPCvt zfMb@TlBcrd0UIg>^;NuFwz(hN%<^dymVW0&3ue|{-e;cV89B*_t|}5v7dP=AH1d1B zwJK?}cMEN7Y<&NF*EfbF@nt!a2O4PZ?-r{5-P$}1Pl<(B8<1-9X0i}UCX2U_Dx^~^ zziC0<+~4|=PK&sy->;C?(Pyc-QCSbK)M_0kghX*-tSzOe-K^l#hPo*F~(gx z%%7x;QS_UCP{2T52a<wF9vRB8Av1Vcpek1Rj58ju68u128f z>6s+u`pS}cAI1Xj znA&rJt~yq;(C(${a^zZv&6h&CvLxKreYRyrMT_EGF=IMw@NixkM10-r;T>Sk1)Y$_4=SYO6=Q|; z9~N2ePYpfkOduX5Fs+=|faM5b1^>NI4}@%4mMtq_cced_NeNCpJsaZr^9GHb4~ypw za~0#`DvmAEjO;nOV;J(8jxbQ1YIEA+<<*s2$`($UYJQyczO4w}2px5VPTP6$0V@-p zcL7xQQteLDV*e?b{wW{7;L|gFy`qAXvYUE75kxsS@KsE76n9NFPNYjAsKSMR*~t$ZE2}kFFTuPyh_z?j47W+))!G-erIEukrtr{L&;QJb~Ne3M>NKzJ*N4k92LnFDH&Bd zXr-YaX2pTSj9ekd1+xgJM3rhtFKIFiB~m@bU`?z6yeiBVX>)i;0-+M4^w-Mw`WUhe z{;~*q44PocqF%PLR_6x%(pr@cL<kx?-o!RDIT#TkLM4!W+k3%g zCH-^JOl=9;>XY!JR=!*jM9fz8_SelBBv@I%eD`~~U?|=&-ZqWe+q7-9KkBHt3An0x zo9_#!0vlhM$UG<;SPKw1Up^{Q-v1>0+Z^kbq3|7mjl=gqMl6TLqoqDyz0!71)sF+5 zo00LkKn=%wsFcOi{#3s%WKTQRc03-!H5=Q%xfQg+hTP z9+33MbN%av(lgWT96WmU+6hLOD|#)X>&!{%4|bPoq8?q%ki0K1gFA!=h5Q)A&_D+T zXbp6{YPLF#cT%9q5<6u=YqB9tDfMH>k^S;T!xa-P5GwaK~{e1rDs2UCVZvlIh zRz0y^Pp+d`Mm|H^HkOm#>9!L1KD^6&iDZJRjom6nxBKt_U-oRP0*!&LKNp2EB>WAMl4+Jo5liJtg$d^1*pBLV6pPe47sW<| z@SoJLDciVf*l^2S&KK2&CuJAJ&kE0k9FcS$+Y@|k^2fT`f;B1`wIpOQWZKMNk6M@O zsourYGRE|{Tqpjyu`VlJlhJ5Es3NaVFDPWl)MZZ z(V=EbKNQNQo|XpO%r+?cO?rAnqLRmrw_GFZO3$7e7^UyIHjhf0;bLY% zxW&!LOsZ%Rz?JT3&h~L&y9I7Jpd$hvlVIPq#UO?QQKVU8DbPaTvSZ`nFgpLY3=2B8 zyYjx#G;4{(?%+znv3IeF(x$1g5{o$W-$-n3PKPstt?cKbdqbac7%P)RIuN7f`ZPMatUngK#9U>q@dBvJ6w+gVHs>E_%4SX3LupR(QoPciu&1Y%IjItU zQ^nTV08_!<)NjXCK|%CJY{)yus4?&0u=vmj9yef_n7ezFf$s3c>)Ok82Bnez2sp%d zb#gb_A8ao1yV}~uIJHE`{TzHifeRRY17{1nX2$T_97q2w7v40r88L=JIISdq_1ZIW z5xVHfl!A8=Krfps7=lLX1$V>wA(gZpi7TaSWR*vJuel*g2HiMB!$$l!I{Y$G&2u0A z6ow&3^=1_tbK!`^r3NLEENmId2fnX)7}4|huJs2Gf2uEvig8|HafVn-O&uyzlJ=+S zp(T`}X?$Y6ZhAL4X26TRn#tOiDq}%IHg`J-Q_B_|k+F+#hmoj~OJFiK5n|KzXV)ys z)F=DjClY^PV36W;tIE12U#}%jCAE_wX4CT6%Igf*OB(7oRQB_O%O-UxE(K@nF z#zVJf5v-rQKx@7^sF8!A%aVgW@LO^8uKP`dTVTSr(A_c{TLwy$2p#blLVhC3yT3S- zRiwqUKJkJdCkJzh85r|Xi{bZrQKaMqV@qjROQdD{=keU-2)F}JVY}aQ{o*W5pfc*` zmlimPC2xW30W9$Cu-a;R%(PGDw&J@O5}_|je#vdC2G5H*!ZwVB>|4XV3$!c4 z>45>flYG-|APL2$(^y+-vj2VH2+jH`)23w%7DkXd^8CsQ8KOY=&|*hM%dB_s<8los zGXCCk-?i~vx@CwLbWcvAnVXyA;p0`N9p=ViL?9GTsZ+)8#y5tAftRhUvbwr^f8Q+Ug(VBFOJ-EORXGRFdvNdo zGvTQtr*~FHEV!sb6O7c`O&O`T9BD3|lN`5nnFr$s$?JPw+c14VlYjD-h7J(DqQvBP z4P>1HNi$g^sqKw%=gXL|Dau%D*<3P%PVR9w&6Kz1-(I@CBBU_bRy)x1s4(iBsXBxd^?0uptn!KH^r8+l=!SG8c*&)ueM!=H>L{YK(i zHofK1AcT~^`6AXVg3%3^1lpKo226>W7&5+pZ*-$H8AwbFE=VjfePci%cmp@4JJqTfY?fR<$m84XIj)d z7*;T$Q9_7DvqWl>{Y?MKrts6RE2OY6DJA7Z(LBaDgJ5a2+C&`Mi5#*|s*@=D3RNW8 z#FHVU5uGGD`bAJfG{V{-MtLTB);Ak)|FTdM5aRm~HutxN%Q7vxjHS0rBEvJicD$0q z=U7C|Wzq6a5j20IAP^R8N%f9Z zp$vpD;t(^CQN!y|iuX2ECHJfN3TKCRs))e0lsdE~VAli@yXKT@RMvQ4&17%FrS-yP zY)G62kk-A4A!XPZUQ%E;EI)r`@I5daW;kZ$I6qYH;}mzY`zEE@;RJDVzZWe7egvor z0yd*r#8Lv#f#?>P=atb^u&>KtwfyVa$Rx~YjxRs>9fb@>Mskk!)#l7NDM~&qR?PPOX+$ z2-CgIscTFXZ=W$+bfSuXhLvTJYYTzr%H-u5(%09=@3{!FF6tIweWOtPK*$9+a|Sm3 z8jmjB{+Do}i-T2X7r{tgy0^=|oKh3*+T20VuRI&mLcl%j4*)sHlJ_ zYmAv8S7X$hmtH6@QIE`Y zzZ&}XRY0HAw?#{}ckkdRMRSv(x0 z&Cllm;TV3@yGy{Q%HRxo#i#V;!F(>)`(wZ+vTtuX=l4eYk~-j%Q`OokSu<~-tLuB_ za;RZsPc-{fdDn)v`k5;^Hh1c6s1d{7)aSpzCJ@A@-Q2wr>ZDel%v2yI)K;!j%UH}t zftn$AUSRNjCp=-GjbxA9oO?Y{JsQJ+2x3XV)vLQj9~e+P>sS;y1A3Ir(o@YNbUT z#miW$X6VedTw%R@$TNO+;s}_ra8A4aMW}QUH=1du6D_DClR`(!AV6`M%#(w!u26}G zv6R#u)33=6K50SJ(A8XK3?JG5G82mPd3}iNV-7l`5AD?)=?JS+O zKDG9`lz?V%i`1#)`F=ci7Q z&)&Vu?#^OzQf>3u%b-JtoX)6Q+iu<=S$W%rc|Xp2Z|5QN3cBIbcbp@5UnY4ErCGOz z?B4!$*Tm=Y82ozDI_7@TCX?Q)(c~5g>^{d`j_PKMl}f=t5}(VZ^Yhc`Tb`#q;tetW zHYH<2#{^|wd^wqt(XOEsu{K_W~HMW~w(>RXw_V%qUFeO0i4qrAT}FP8fx()wbaQm*5uWoOYej90^ay@=fI(_xk*3-@?3 zxm{n(I0C#cvAttx2sud{N?ZwZ0c+rWdezLd7-qJuSu0L4!6`K+k@+9wJFXQkLHTkU zBg+Wpk7>!k<@b;&^2Z%E#*j})A_=1jZI=&yw${7iAxr}S#y|Zou(0jK z_NZ^TOWPA*a$uF3aU%nl8SQpvFy^Db$S{t&1((H9+`*DE%4OSzgmb0*~LtfW(gs)VsxJsg-l4*TI;=8N=Iu*WV^ z75%8Kwvk44+G)?+JUh~GW~csys!}Fh#mR>gLHJ#nY#%*dEM-yWf%e}`&esjaXDW+Iu5rkfbh&4rE;!t8M z;3(#s55>m(_z8!5rmZC5`#^pkbr|+#yZMV&O6>E5*-oep@)WC@`Od!7Js&WM*3FqW zaCJ@DPQX-BR#I720r7TNL%m?u_tZEJg}w*1KVV~k;P9MLB!QyBSz+wf5EPhkUcLe6 z?sD&hy7Q&#)wN8|*q@KC1L+A5lDtL`L$3Eg8(}u(msEGw&|q|9X_&azfw6Alb-=U3PApwfa!!7s+bkyhrG<9_URv?VT)9pCQ%ddxx>w4D3=lTn^PaS!`O-GFy~H+7szU!XQl z`hiNs*|{{P26N5N$xyARuI#XxRFJ^S2F=uW)qh3%I&VFBAgbXHo&!!0;j~(WgfZ0S zYV^a;1O$*M%(Aua?~aFe$cXnIRRwF&5~x<@mbe7kw8*8RH0A2*?%C!5-tiGJ4RC5r1mCiM!lOF<5J-6anQLwBG}?x%Ul~6lkPO5o zUDhdr>zYkd*{gDJ3Dn9J z)%ESt>4g@n9RvPB$gY)jfownA+N9axo9uV#0HwJMQc(rSlQOF}ly8IHTJU=H&f6Qi zZYL-=y8I!^T73d>$v-bSD>}|Nb-8rit&d*NNdfg>^jhzu(BA2jgPOI$q+GzHEoA-NNKB zc~-Khu!KmXnubR#+lraKh=|7J)6#cTf}~PvyhC&P@e6&*t-fSzTuRst3OisaJgCMf z6*@Y!zy+s8fmuT$S| zRwWtsLMF@-LwRw-?Cqk3xAE`dK5e3@n-mO51SMjNV;B}s=^a`!)1QiF@1*W7 z-ypscHR|Y!-%GQMtD&8M)(^y;%;@*>L)Wpfs-;U>IvRplf7oytd3t7yjY(l8B{n*& z6J44`808H?|4VP*Q^<>Oq7zP+bWxQ~{56U{Ru=f@8lD{AZ$r(qr`;=U+wEFZd0_=5DvEvjd2V zVHJQq*%;Z8Q;Q2N4GjiwK|El5*{}oiUhpnt^t=Z&8V7f2-?Uz_!a^B@FY;^2d*#`& zwDymG#3g`XiQTLasp7%La*LmpRE21@KiJT z6t_7}X&_^gOwN)2Nb^Hm=r_$q&y*>8?Nhi5(arQJ+^zr-X9zqtXH3V+^yX2iwUff%{kh8%pc zIz2c4f|7s$90SL#yr4m!J$gX`;y&cHRqL%h2s3Cn4G_fX(fPHziOjnO1mpS)IN4l7 zx9@iUnS0xpYqp7lP;)e)|8h!ByWUFX!Y7zTfPLWnA2aD}vVfn_?PAAR&{ncxs!N$? zmo9yGI;*uG6avL;`{Cq-4OXi=kH|c0SJ>Lw9$8~G#;$)Bz^m8ZyFbiSXO^Jr-3dO? zw+>z%b_b^(h*Mg}ZCVE*9L(`b%ScyO7y8f=k*Gn@+@pPE6-RYcTR8{Vb1ZS3m!y||c`*S6u)VZ;}(-z1sR*2iQH?94N#b2wvlsI50xcZ{uc zz1*eO+Iqf~c@9~Ae8qFKM@(ir+T9KFF)ghO0$G2})8>UdejOvOTUomhW|7GuP&2(T z`}|kt@aS+77|ntWxIm7NGVtU+FyjKd!TRFq9ynM))I|%bnTSIJ1IcE+&v82*`sg{h z*tY=qwbXq18mOrN?8OdW1p^=ocyhw)F#S!Ew?|URvI0A zZL+&3&m*f~ro`@ih4(!0eAR&-NZ4TQJp{c1vpa)&sM3dG%6}~@HY%^AkQsasWmFoH zK@^#;p{%=Z&F=;hvJigB)a>w-*d~K22Ex#vmAJpyx2eQ)8G-9cb4IZLi-k+Fk#}J% z`%+MgbW(Am_ndD@mN7EE;eL#rLoJu1;@Zv$=uJY?hQ~n5A?+63PoR2<8Bh&p$dK_`gBw*QWeHlDFL2e+A`F#-vQy(q@Myz_&1z1#)W>= z{BBBzh{54V6=rnyBn*;@m!(Jx-^^YwAe2ocE9gfEn}!*GGs!41huHr__4@`NE(iB2 zMC|1s@l+STkPv`LS+UP3?q$@;Kq=?Clh@!%Qt1=Y*46T=Oc6MRa3bR0Bz)l7U9I*j z`y1AY5Qs_9R=dQcdCRudxe&m-piCcYbNpiAk83-ihYZhKi1MS- zDv{1m??v9Nl<*j5uQIZVJj$@lW#0hDqlJY7lU$^ZUgLobSM`X;<) zRx1re^?={_cz@jl=(ictZy}eAVcQiE74xPZ^o%?IxABPhp&uEz-VL2)HOkgj;aD=Z z=eIQv_bF@b98Q-$jPO1Z`}$m%Qv(+mUUGsQ`^J$jz96lJfiaMTaGXc0G@iNs5E%Aw z*>UfzQZjdPt)ij6Jz5Y}W@UBS;_dknSw&rQ-5aD62vPD?%<8(jhIn6;YM+CC+FUl+s4(R01B2u^SR98_EkUmm2l*+ecncWfO$x&tQ2Lugb2175`3*STG2o4cT? z_)nyF5UkQt^L(`$*DFM9I;~!0kNq)Dz5;%bFfnyx$G~F%a$P7wOj**>x!og~(~MQr z)QH67+}e0HZQ;5p8S{(g=9bo`_Y@z*J3$6*o7U=d6J%ONOVjXT^g~%-sd7bCZKGhv z>aPFw>TaG4FW<+WnY@AgJ01{Nk*~v!KLJ|rO&opN<;>EL7G>)zZ7qmzJaI2Mr)az- z+GIt@u_{zjoVn5vtZpsuvV99Bi(C;BA25DKxJ?}@J*7AZu&4q==U z%0Pf2A3Lq9G^X?$lLa>iNy$(7tkT!6$QTV>hAdJN3zryCE#IV8et$z$Qb=K}yjVom@YM|q zS8A|ingoYPB0)M?m(90y5<%I2k6?*IdAz2rF<2p1ynw$>X?ucr*8zQi@kjcvj1~HU z)BGF8B6Oowtae8~iN+geJb>Qi@n^jIUhxGC2INYo;Rf`}hTyK4m>%mGq@D)7(Fe8< zWqj11wyrph>)iA6yUV`O(koI57JOf)qou8?uTPBebo5vqxZwIZO~r?TakT?ZA`o|$ z4$L*)`129ENW{WIE+4pcqfQnn$+vMz?gfaHI%L?rB#p%A1!iVgB82@DrZE9~I8H1; zVwO^NBW+WGX;w`F=SNDucW<6Z6qv;UEM%1Fz)tR(CH-pN^hDh}WRty=G>Mb<#w*Kf zb$WPgXp^_8hJ!=vfqZkXxv;{_ODNI5FkWmuA#`_}=_2ggJ zn^)FYgw)ff_k;HQ5?4?E4w=7K7Kv1e0##XA`L92YAVk6uYa~M;zo^mUl8V0VoC&)^ zW9O`kr_N?{V-hW?LTmkOg|77Az(u^ey8VYjC^FAO^!@cQ11@6BHDYC%g{KbRw zH18**_LG{177?5uGVWBUa^FjoV#L7@xZSE5XW;*3!RGoH@rB`A(JJU&CuU-bs1MA` z$}6gVS=rAW5qKg;te-*O-v_;|RZhGu)qaXq25JdYSK$1>dc52r6I=NEBa#{fOHPdE z_Afd#^Xo{2a)tf+q!67}bMHBMRyIVJ0T)%83|vvZQ~`welGpl1fn@>aGyiO# zD8^OgIq)yr$6}rm#O`rg84UOj@ega-YW$=9 zcDiA9p;?;+-~`w&pa%JS$!(9GwKIR4HTySFsi`IYv43rtcFy}o!0B_kw~i$zN)`tI z+YL(OICY(|F!lfHS$6?xwgieZ{ecG)2d8vS#iGzrFJ&EOrZ2uO{I~!`&(p$I6MeS@&2^6^R(IhEo~YE3hG5kf`%syN2Os+6>E0;%gu zb%l*nL0*-oi@4wi{q*H31(UegJsfj__vF2CaF*yOZ-`mdOln1qp@`C&VWqlX(S3lM zl+#^%Ep$*7A-Y?Y(|x$7XF3y8Zp+WCD7K!6x`{fPpQs=x9+#42*wR)wC2et7X28^S zY+3cSj_`eRmT+7@>X|`!sQ!1w{JIoQ_n%j+aJA7UG@^kq_`+_HG}v~-ukotpGN8rn zq2zHP_NO8G-3$gS_%&7S(jfRv-#*T$W=PLH20Vu=($X*w*F}>C=5s*i1#p*QC2DY#?q4>ip_5St7Pv~|;A`53pzDUY zqs$_!MlQ;Sk^kCKeRfm}U*+&r-Mva!rWU6J>jprPpyzK}$)2|WtJjoe2{`$Ql}__h z0zG87h(2KK*rucW(0}7k2xzrOM@K}IFcfCgyhsSKuF}}r^(oeGp&UwZF_$rfK<;8z zCl0`Yy|U@T0#Lcc4fjj`8=g!ZZO7J{EZ!b_;&YpD z3bV%o+uq9A&57mvLvF9|Jv^eP9p&E%GRqgH3g#A87U#nw^fgXTTnaEhr*Xk;niUAI zy%i;_T3~oDaJ=mP4LI=+k!-C#Ep~KWyhtgsidl%kRV$V6bGx{UDk9=H&UPqeas8h{-$41tF*M z{yaWc38E8W=xiM14Zi7v;Gy+ABy)r8egAn6AOC!wJd5E&P|8?V&~)mV&7cdrfu&*K zSh&ry+f6jR^{SDpVZz7RicMvzTC9xMiWma`y4#Q7ObA_ES%K1x3CDFJyIgK7-<(g= z-`w;dpLu4HgzhB4W2pl-S7kMBOt^Tt$aX|J=aZP(W6x^@N?Y45|f=y+^ z`1v^#+8p><-nV1CQ%4SsHtR6nm&)FKePKyA8&{TK6B8+2-WVjn#nq4MX`VptqUt_-H00-ZTmlNMLWK9 z+GiT4haFho z-5(x(`hHPbYY}Ev(A|GWrhkIw{PmUGI=U*Ko~@wGS`HP$ANXkK=={VFENv<(t=Ave z&5Z@cskj3WMHBic4uTa;5jN)6mIT79;BuDR7cC4li+`X07TYPrnenT|mlN0f`1So9 z!ej_ph@9L<{lI=I|Cl$lEUIp4#6zg^j#fDdV;Bz1P~Yrt?AJK2DF{!`&Q2MHD^>ZVCTOvEwphGtfH-7 zb5ljK3NP1q)Yy`Y*x*>43ojdHyWGORyU`HGb2r|3h39HeMyRZ`YiI@p9ud(^^C-u^bD^K}7( z-UKk{RZ=oxO9P#g$Ljbo;TPmj{}GiyObIX{1WWHnPY(5VT*yJF+D6}sWYn4|To*a* zh38`O^Y>`*$dm9I! z08qMaWy!sUH!Df_t793&(+S>b>Pj(O}58^?U2|Fsy`xB%6V4f|G>_r*sryzP;oZyTkq zXz%X0ovyg~^U?ZryyMoG=lQ|Dj1jmA_fG^kuehc?_Pl=+_7|h&{yrd&ky>JeqM%T< zm96wBVV)<&qQ%JwhRHs)9Zg(3Uk)}?X6-F(dlZJ>gpLpDuam1zoYXo_h;UrSz+%3w zAg|PI(DU8u%^ol!eZ0&%^?qJnwcP|0S&g)@ z1HKu5zJ1K2y|4_#ydhH!@-dlJ;{anl9xna%l7x>{%IAPG87o`5Mj@+>e zjDKDjw!4OYYF@Tt>q2)$YZTzfrjgCf|hPEEW7aT^5$0u)? zisTbLkDCPRlda>>ho06sdF1){B@Fe4)Htft%|xauger(n_A=lH0iGPN^Uv1Ntr|L? zWDV(y<5g-6d@Tw`RDUg~Qheo9B!t-U26j{VC!no2HMhPF zNu6EHAat-dmmtI-lCMP2MP(`);M0@kNBd4#`BD~7*FrqqOmtagDS@qChh`GNW1Eoc zpk5m<*D36n zUy5#H&4{?0pJ7-W(=>T_M9Gll)r9rMpBRzNe>Wck=FJmVLtDkid! z8I->g+rOCkr6+b+bA07rv1|<9LYKt~Mt2@m+ZI3p0gnA?v#RFiVeq^G&kB~$2TW8B z90Q_N4q^*>7--;@08|4S5TJRW2o;S5DMzAH@hmOM=a$$Q4rDZ5WJj8KQ7^ei?)UQD zxAyLglU%iKGAsP^29nV)0k=e{G+}vs3o%|Bj}E<`D5n=J~x(AVf$!6ywr z=1gDSs>Y8s{YT8h>$?z2;TfQamFZ*l%H9bmr$DQThm}F_pgb$fC&FOG{B`O<#lJyl zq67x=i{MXwi4ocl1#?t6ajt^Gx>_bfzxd&{_@K`Ur(CO)d=1WEf=9DUud#MHt8ENQ zGqCfS0e6P4Uk^`?VK%qX1-*R>5H~vzCv&{qHj?qxd2W7rd!tXnqE_v< znPdJwFkuW1Dk&Xd!mnv*7y;8|eanQ7o3M_x^yU~jMW&)(JZqLdzeG~3)a0@b(|-QT)=wG@W?a8& zxp3JERS0!tM1qE{_B4P7#-#luFaKRSN5K#$s80R`Z2xN%{x)-WP8QEb^UFb$R5UfW zCj-Mkx&PylXWc|{GIHsTE6T0zhgBiVN2DT>325VY%ArZUwCx1NePAgYNLETs-J3E= zfEVG~dKr9N7b$Pp@t3J|q_oVsjJN=lvCJugWi$}G%Y95b%~nycootFM0@j`%<8LZV zi^QC-AA%!oI1&tjL+mXY{OGN_ft-L%p;3`R%^tC^$~3`CcYGk5@bk%77;RGRcF$G zedh0@P(&g&YQsW;I8dHwm8h_HXhb&i&7TiH zJXzn*d{r}kpt!V;f0x?foT)u}?CkXjy35V8WZ^u%wiOETkf&d#ulCEeDY!6G?gjkV z&o9^`jmkbf9_|U~JjuJDHmClNfatlt$DA7;mFd?MGF`(Z;i^=c_Dz&V+}t2tCl5ZK z5$zQ}(*%lI)SP&~*su<}9y{(t@vJF1ZR#{`J|zj|Fi!qVvI#$0q^#d4=a}EL4y_oT z{qqwyfK5gv=rutg*{T6Mo@|K%pmBk4CVcLNT-gfyKj);-EZ%Vw7NQU^lYjs5;DBP= zw~DLPJ4<4hzOucl>$b-Dj4MjIV!(yThy{;f&%yPtP1uo0RHMxfqW9BIS~_oy*zOu& z0lNG>1;;BdNop?~p^8NVC?~vxz-Vd5_)F8}ErdL-iG$LN#ukqm4-t%yJjORcPMWGo zLzBZ9QQTQF^ob|0E84BDKS3g?(d`m}Q%co@wz9pxe|?1qWLh)gBbv_a1M;g4I0Rct2cL+@8iS~%m498rF0(oe3>Sc8>6}ukC>jJ>W_-9;+KRaLYosLsQs2~(ZJ*+t0qDsVIF$dmKjY!$RJL@ zg(7aW`f^b8N4S>*%sT-qZ;jd?;Q?6DF>NsBg~OVLn3<=i+<_;qk)w(_ldv*ywHP?M z43l~RwgKgiyq{u95q7_+v)>qOl}E$r#!!7cFc#OM305$Qoc+Nf_N#<1A1#l0WY4dR zg#up5P~hgntz}Ls6b}FEqse={9c*|C4OMi9(BE$iEtSHYpIWfgQEuTv&OKYrUOz~t zxa-}I9QV#+Vk(WQx_ihaUzif?oH*GEP83DxGT=n#Qvybsv{K^MVUs=JFWap@ye?w| zEt$<6NB%7EVUMaLtHI|kAs({M*li}iF&j-Z85>vEow2mcnZZMR1E{Kjfv^1tvX`yo zOJ`%cNu9ZL-+6BsYq$Ll^E$T2lh1VlBIbN8^~7fXLbXi^{;{leWoz{)C<-Jb zBx)Cr_uHZOjpAC8|K030rFLPs}8ER{@9Hh}SB{0{rWxcbL?#&r>q zot@473XMI%pHA)i-jmnf>Kw5a!!%m#5`Z#d*Bu}q+Rt~h9yjYj4)2lw;NcO~8iI;j z*?MWMsG>s}V_?bq)Q8Wy^XZE2ZA(k*#bUz;2hLUym8e{y(dB(>*bIyV&FdSSt7i1% zl2D)4)?aaLSJl-CrT5A>3ctpRD+F&EKCfFZpr+ksd0k;8m?eneoVPTruJ>H?W;@U6 zI$B1UCsmxzXg?qlzFv13UGIANyt?|#{e|~F9NI2VpxxvWlceQ|8L$RDTI5<<*q9o( zva_)XCV#EVnX~!_h2l%ejA^&O`?c%Ib;oWTa45F%j#8@OyFT?fyW>=**Dh3p^{7nEeOlppFvGBRpw;WNWbY^p!^I&tv?;`xqa(YY&VA_Afd8 z*Q323g1pyucC+j&8wLRECoW3WK3+GH)a3RDt-Bj=Z8E^EJhcIxm||)KCnWIoejOF) zTDGsS|H;8~XAe-N$b4!Z=`ig6>mL1L2OrDNSU~8*&BY?I!x3c%FFkv`4AEC=Hs!cx zQpA*8X&e+3Se|yd4gJsc-fw_@~qhw;@Xym=Jelr9SPIzD0W7QDiVNLB}=Ev$uB5i7K z@9Yx!qNm?MQ@hTLVoI`URW>ckreJfBv|da?OWiGJjA~y~zwW*`^?R}Iew?~p=WA?a z<$7qFSjv5riNUP2A`_&+?ab1|&~j~@ju}TnIGs8~V!(pO6hhRmI~e#5TSZGv55Rp^ z6(ch<0>`T@d{)Hp(pB|cQ0v5uWkjFjQ6dcRYYoo=-C2pWq zof|`aD7iigbLhaHrFZ_8+(ZW^m;gKloi9T_1KxXPWk2lQ8*#3zn~9jFjlqLG9pl2% z^n2(;xm{uzH)k-F^~is9hb@}4yYQ&=#)Vj4T%poHmg=fQM`j24tV0%yYk%92KjpZ| zJN_5KQ;Vy+Q@l?x_jR1>*-_IVx#82(0q@g~37f$#0+LXEtJT|BFPup&t!_9zv?5@5 z0XQacT`xX~EIphG;Qu}df9ttn(*3kT*YP;}+y!)xu~J(=Og^H+um#Qd>XJD?lK#&X zk2B~~e7s;B{PppQA?RtSF!M12z*i@{|0rYZkyRx-6FouTZ$S5=@DT|y5%l%=mb_#U z`Xn}u4Fe(*0X>i0SgA-{GT=Qqv^rtHd9OjMO}*#9`7l)h)CI60kJ<*$Yx~x|i(jQaM@u(IbWHUXQce>LYGF$LL~S?pHV%4PC%pgK0vdOpnZNImn{J25 z9j=f~>K1RjzTpjkEl1DT_-!0zi8DU;4%kLsy?ZCs$%Om9>0+zS! z@sMJ~ZNZT8_!!?7&zLpFLYLk$;?ZdTzY_$Ic0R6`?#-L}@Oo=-yCWy;UNgF=?elIW zc79mbjLx3-fmbK7+!mip$ECetN`pwjMT1a+vS^%l{8X@H>QEFRbPMgxBXPgbT*Xp( zdDibQG2=E!@u?<)e-qdn(nYc`;Dk@$#OYZgl=K1eg#i_-fB$qqZ8v*$(h`drmWW0= z+#iKX=_YeNBPN}c66c!jb2~I)^P=X2{tVb7=^ve_Jy>Be(8T!?523>0*UW%Eh9Y!{^%3j93LleO zm2tIQi$vwCq8Ie({S=PCgz@L5#`Y6=h|)XiZ4m4JyIWID4X9%B;=9!j;BH2xzaR>@ zwQ2EfL<$pkGmwPl<~~_6G&-UDe=dNQF?QjWWqGUPa=d%}LIuHn=D^%o)F&akA8bO9 zO%iFq-f+njshI~<+NzF@lMNKPOr0LB+}^2wgY)a`xaA}}pXAgtALa1)xT>y3 zAic0x_-n#TwDF5mt|%L{$s>o#ncR31Db{6^Zov8uIw?K8GkcGW44fafcgDu6vy-xw zARF%ZeBX7MQfz=dfYnN?7~a4wR4=^if*WRAA5y@JH~H!P&DKSl%1eHP+A288Q|>II zHfffW)5_J&mF2Jbrha^R-(fSOa$#D?xS}%^j3cax>EyhsomuZi;>Nc&_H8&4i zZ0H~n$_ofWi~SW|{5?n39LSz-K%{{y2t}#x6!McsCt0H`f`Y(8Q0#~~gnl2MAGzg$ z3n?PurvTuT9A!XVzF0T(iVgHQVmL%)eb?MSKzqTLMc>gXl{W$VPAt`kkGIIDuK(1; zJWNC#c|r}HoY6Fuotl=Cc_Ps8*TLk0)6K@ru2s4*O^FnID}c{`eR7)PT>?|zB9dO3 zVYaX^%d(69ZkToU?Uhq}?UkokcClZ=#3%|>iunr6;_%q{4tyilzgs2n`t0p^v>&P- zOhs(|K2Bx2)Ohp!vEU-dK72h8wz?wj;d~>1++^yeJ3q4%W9!B2{enHrFkBeN*pkLJ zRFRSS*imULrL9^{Mfn9RX@+728*T`xIBQjAwiw(`p89sbj_-UQd_(m|DLR$9)B=MK z25Ws;5X4@W1x-Zji3SM6ZHlTFRGDQS4$|gbI0s;Un24L0;Ab~1cwIJn^@W_$LY96O zE(8tXw8}*V<4p)4ZY;Iq#I#k;pRmb)@gIV3Yn}O-L1kaGyBv{+_ra_twSgI-heLZS z-QP}Hb{x<-c_62P5gZ@oK;-2sBw%%2}1uVwz0ph zCUUn6e2OyU!#c%7{(A0@k@3~-4=y$RUG=z>$J{6zww50JvYc{DmIC>6W5GaP&T&4( zRh9u&H_mYs$Lj;g0HEnCG+wBeDw?w3)?%rZLCWl&pF9CmP@?GI(3t#BFY2n^&nu{9 zZihs|-W1A!jGSllYnM=~X-g4vDZGIcJ7ytqJ}|0KtB{2#;UEPKKoYYYvBr=QYAl&L zM4r8`Rt_a1H`T81g#?XeG&H$ol0{L{`9ij0W;rJ75-VssZlAimYGyAvM<%%?25?2i zNWP)j=j|S+GBXoBpu`9$I=@0fBY4TkTRE?($RQ{!Xm~ugy0S{==`6mAPHw9404Ui2 z8U^z-&`DL-*7ok~kb%9YK!GkK1GQmb0OS{?j}DS2nXmC!(;32Aairbk9?{viBJh4H zqmRn26BZ9)OC=Et-b|(d09*^`!k~v2g<@jLF5KT^nn<^P@ck+Le>|OKRF&TstrY=D zrON;g-QA6Jmvnb`hcwdC9nv7pAteQ*8v!Y4kd7l=ck}z-d&iJ3;t*7?FoTjlZ@4AGkdoHJgc>adZ9>g_IETD4N8wd4)2kSdn2LDN0F zE`T*WMV|Hya$|fKIp9py*SB;!=EL8H6u(%?_1FD-J>R=-<}^|_gZGg;X`^q+8n0UK z7VI{&iSQ;61*E0=ux*Xcv^5DyZ-OcZ_VEyq3b8aP;zR@7w2+kB4Wqm*Rraj6*A_ysvvO2Yes|$@I^5#i#0vSb>4f-ERIfd|Spr6T6h_wKhp* zhLJ`5n+q9I=>!5JzwF$J!Lw0W9t74_VFTz8F)V!y*?&v@x2XG=c9PmJ8;)q9l%yc3 zmyG-5eEKwW`*5eQ{pdb_n7ia$gG*pQ+{pu@i&P?iF&P0 zuwDVy74FG<`U8{kR#YYwu(K+0#)gDxl3c4GMN3!Qa7&}8G#_(jl%bd^G)YP9Z`^7c zd>?2jr1_DVoL@qyNtNRvNIm>m1~|~Jrfy#3UKA$$b+5~A6sG8%xk{ryyS{>qAK)~= zgP#!{x$n3WG#lJXjo`Y?IUIbU_}=`7kteGn6|zJLlEIltm_{$fOU>sJNELBa>fh+# z_N5f)7YJO53gl(-O*Ugm@K|)_xXL1kwEO<;vxp>+B#C^n39k>W$Fj1K!i0zkXAl`@ zu15A)+kTZc4MMid3Du7KUL=c?GjQ&1(kP$eaG=gOmgAm_x})=04XLejHEsU(=y#q zEE_|2oN>%R8%FFl_j?W`4%vaI)lqhSr!<;^KPG#|SAo!*~%|FM9jtz1C51^3k6J!3^hMGY}Z8z#-o$zdfxdmHHEI`Z&C@M)yQ|9*#D|H7rQbqg1FC#)MHtU2ItA%$e03~1AD$8UYBl=4JFb8(%y(%V=4P*^>9vjL}< zhnw3F7+JvBOhG}BAhw^JmuJJ-hXr5T%7_%V(mm>r=$GUzvy{{nO^ z(YVPOrv-1@k=cY@cq{k&KrfzeJ#r%;`HIYfFoTooGh2F#oZ#4{gfz+!b|zL+b%Xx5 zs!}pDU!s6GEyM=uQRJv$cIp9D(%w*5AxYC#QT7YABep0q_o8Z4N?l^UD*KjoE;)@2e7KOAoQcrr)dqDhQ7+*D z47C7}IL!~XD)rKsGCpsVJw+!dT{*~N%~EKSBfAG~z0^u&VM@3oC7!ot+>GDtYF(YQHC zcsc(XJ9f~zF|TC;6RvBQrDes=c-WY!w3)IBEEaViZrjLG=d!xZ8_&EJZ_Z<=T0quua`G`7lqDsLJgau~ncrP1gvdWZo z<6nl0-++Pr1ax;TozvU)ESMBV3Y^V2^~_3a28J+T^#RHSKnMY3lvHVk%@OaqZkX~F ze_dBR7h%z@9p1slv0viu6SX>H)SPiTo1Dgp|Gw;v-Wqz}c;rZSOVNVXhh9H@-{(-f z0%lV$tBBE2^eThap}syuFrot8Y#_;LD2+vd>n0IHc)pO9HR7i=RsegC$dnPN238|@ zcf7Mab}p8%S9654OXNye3QogCI>!^K6raoqmq#l*gNcC8`pzikN76v$aKY~n-vWT_ z5Wodn+|Ow>s`bsxtkM3Zc5Ld2h{IKFGU za={O4=g0nYg=+^M2`DN~6e9=|Vx#PeojaT~V8o+wGJx^WCuNQ{_e zL<3x6fI?Ppof0C2nzDmt^Y>PD)AqgnzYCBwRv|4;nHKi?HxxGSo>u{#gmFlp47!Tp zq!cow4uhy(VS-ZvH4u%QK-QW)5Em(lY?96R8j?8rr6|p7IHn>YNZ4Gf#l6bD?!>)8 zctZyH4QY**d!t)nV-lg3cgI#*CH4^KrLE2y#zvYeTgi< z-3V;5AO&CyAVnA*bjoKuLA(w?wRu(kjwVPSgv-%UO{%^>hkQmETyd7}Y?1d>y6i1? zwZgy<#~f9UDpe=T=?k?kY!KqUaxoWdqr5-=;59+Gj(-;MH7Vn|Y{vSjz62_)nQ{$S zg*2&H4ut@q5Wo5iYG`*4k0)7c!kYHDxiPKV5B@g83OdiMWD9>)r^z;szPMrloCh3D zNEW!`m3MLGL&i@*m%y}J=XZ<-o~#8 zYs>~9YMa869Uflt-FcTI=m+9!A3Po&E<2&He>7m3|0-N5z)dkP9|h%duJ0K#m%|@Z z7n5LSq}o0VDi-kA$ZMleX0Q2e{@XVAw@v+T)kb+lWyLp_`IJEGu)`I36m)Is67f=1w==^YdhFs;}2`1z|)i`;_ z1J0cd97oigHtCrjN*H_Y_94&>srUv=F3dsGTxd&*UUS-f=MtAi=PldyAltpWJr$_O z|JzpdUysDQTI8&KDhRTGwk#lZYkc59GcMP~+X~I#OG7FO>CJ*^&?Uu2Ep( zOGIZlWB#0)R_JGv-d}w1%bfY|AyXJ^$>HpU5>jjj7!i~~IM|9(=SfbiM%E>oX3R!1 zqr6%>BZzf>^f{P6d^2y4OO(_1>eIRY)B8~>4})6HT3VF~)2^3*LbWD=d$yM{RG2Jz z@UWX6bslBo3zw?z3maK>8GEQ%JGYGz;iDpI3?@;qgmgsGS4c#77qxssA30}VWI!oq zf~LH6u@sJVpZ{>!T@sm#Mfkb1 zqha2iOCQ{&`=@k{>ou{XrG}I_7Pj0LFG!K&#xYxEBDs;jKXCwP5;}4l0)wD^6KEN8 zg4gipPw^*1`gDmRkAQ#~|9iIV?{bZ8^ii%qUUWZ*?LBL3?jv3*>&6s%0u)co=%V+; z0rg4iOg^4?bZ{4D#5LFctpRLbYBT4vY+@c>h^q@k6_2eCqn{-ZrIc$Au#mk`1-zrG z-rF}V7ESL?*f%X-EZF%wJ13MEWM^doJ|>{X1IFUiuWS9f^TwpQlbO^EZAP1a9~|Sw zTtnwj@rQk)?%YyFmv#PbX)SLZY!bhK!OAjZ9T-2kn^sZZ6yL= z-8^xRYrfaXWfb!J-XxVM=GJxk3qRJ6d-9XYyRC(fZM`_Tf^hL+4l~roX13kqNW$Wc(?x-;oZk29)VkrN2)s7i+|lYo z`sJMVAzgm0G3Lh2t0AsBw*D59@h(5}sEv`!>@?yL7~{pr$_~c&|8BKl70qEoxZW}L z(&uS-+GhW%a)Qqptz-3bOgrfy*V5#dkU|m_BLGpXv4624*v5d3Z_|M(jCCIk#@H{whLkY%ClKUfYyGv#f>B)G!aS97Ych5lT5Qn+#+!loac$8^RY~qze40CknzRrC0tPzy)9DQ(v|)N zLv)Yoptxp7d@c>)=<3=^c!a{#N^S&DU?v z^v1oL3BGcs@RYqeogO+xl62sg-JP>K$#}zA zgSzLva@;)}%`(&#G!?zQhrkvOibHL+51I4y#~LyIj8^-(TwskHLF49u95J=YzHOB1 zf4)o1P|W*>fZNwcu+imK-^*nIpdcmuLe=XeYOV555gS$gzb*A)kR(uvI%5=Xe}8|e z*(tlp;m_ta-*HV#i*)te2bl;plGQ3F-xtKy)#wp35_)7`*;3@E zx%x|!D67e4i$rMJ_3&65)tSMTcSkk8mM7_!j_6u_np3Qv^~#wSj}) z*oSi-JBEwFC1GRp-2axfQeJl^DxVF4X}Zo;wD$h~*3D3}S4s(0E6R}uNuekLrV&nF zQEzyiXt+@3%8a&bM(@9uRKIRANSbBZNrjOM<(SPyGYF#PYox`#nP4ER@)$uVqeloT z$ZLX#z9RXxCV@a7>lu`_2uU5t$F~u*r{vYIJ!LCJGz0&6RhCJ!M40nN);hs)3J(&= zNc<*>Rcq)@o?>Rq{P>%mc`D9kSo`_xrC5ZTlX^Adg4iFPSPXT%H`=zQd9UCizDb)R zaXyoee1%n`Agmn%mq$+hoR^G(LF;^BWGIuVEFs26VoFA_Tc?u6Do7r?W@0)~-t>)nQaT8kJ$R80b)a zBE{DZKg0c6=-gY_FyfOno_OJh?KEibQs|{lwUBZr@;|~nYeguO;4**ZXhEuCUs|1c^Dvk8yVz!qcWr` z4seQ7LWj`y!(T6nMiBvFXS4s7=@)-TprgIGyd-=r*()7%?rac<7MZpocX2fmZ*Y!XT}obb_a&|_oE0BI>zeko z&8;}?*5~0I7B@#JxPt1kt;?2m?AyMSmFlZE_+tdqqop$2HMz*~G0A#9=Ts)*I$O4r zi9|hjrjOV)Ys$T7p*a**MvuyXBHH*57dwgGjq%X|V=gng$n`BHgz5Zanp$XRm7C}{s$bSY+RF*~%CzExNz53o z8R&ZrudwY1f2yiv#uXzwWsrox5$1;$80g(;h4&ht4PWrI1T6^;OIfBHB$hXo!%=zB z#v{E5RQmM-Svi0cu98A#1~~{3l7z$~u|DifV30dUR3Xhm&_r9aI{T9I_%pp{?W#we zd&_}tm)RyFi8a;?3I>WOCe|-Q>Bh(_+}5V+GN9@16?}6-Kv+1V<7(8uYy-4KqT0x zn#qt`xNB4PhAO=ezIMVEHI#R97?y(NzlV}J^8v{k7^BJ17alPZ{Y})K zf^U1cYu>j2KQXTv&6&#ix?ST$>E_hA+S-EwZ#9eqA1g8w3 zW_r4OgAvoN>(IlG=K$tz&P{~pVfS3+irO1^slg5X`lRPI(0qV<4-5!*VOyyNXD4eP zKyr7wLNUR{{>F`XO`O)D`lGE&8G_4UcC|%@Ue9Zvun|Ef=O(423L5`2lQr?N+xA5> zr-lLF?H}Uzo)4!#(c*P-9M)NLQi*Z#{ob%%(J@I1sOm1dNH6W=OsiP3r>4VFy|N%; zJ%e4>^K@Bn*gen|Aes;t;jILl00E{&;SoPceKHHRFqrMkTunMyCs!R97A;S$2tm&j zKXtW+B<^(u3u5gUVV{KY#755HF&wr{5sC18xDXWrVH4#zs#0_J)`C&pd8Q)xhK&3_ zarFz`hfKy5*+J;cyn$*apu_3+Eo8RRMq67XVxw)gy zVz;Z~>_;3lG{8fI#UpEgvdu^?00X_yS{TPrGzybO6ZBu9@ti`PHH17mC}DgSqj4Uw zmo8>*QI&P!QeTNsLfmY!zl*_-$*5{$(1yx$bW>N29IJqv z#nlyriPVq;>lyh_yhz-p^jf-W4U>F z0G}5K=JXhhO)O^3erg~5q)293cyL2`UwUHFos1pbe~E&4 z4~UmV6g|&#+r|Jm8Pu}j)h&jXOtMw&NIBCfYzH^6{2b`d9P0Z{xh=izgT~+eD3V#@ zcKo@a&v#}lY3GJ;x8!$pIiO_57LYHp{cZ5bS?vO{qPb1W71Pu{0{)Ttqd(uzr|`&U zJRTpk3>8p>7;vLH6L$NS+dle!&pjN~GMI;cQEg-6J2S)VSTBGuL(0W17?9GvSR#+f z>%wK223C&;Eq3rzyds&JR9n6<`D8eE2zQKo@o7-Hg`zmTMftwD?(->>3q2LxlGmX# zmu+YTKJu&7qjB*~kmF{>?I3*0VYC1_l$cJYEgQ9T#P&?L&OPiOi1Cvmkwboi@e4gB zHi%kG3|U>C1!Bhfj%1q1iMe|gyCR%aUJqS|B2ETkx|j494ataK^_dsL|I-5a(PsUt z#gU?myPm+eLD-GZP-aajbR5JWP@)#ol*BYFAexmBMkn1PK+rC-#5IwM<0Nxtn<0H6 z8uT%Tgz}NTzwMp&Ll3l^6{qw&ImJ(@sIoVve`keiFeyCf*}MXT-62=rC+s-!3j_=Lk;O<}(1WyYDtYd|e;DkLY zd$Uk3T-FUnvHGznz`qj;s(JH#5{E?Se5tylQqoCjyG~gTup9Am=^- zU(7_WhNzrw=lP5I{1=n$Xxo&>b;h%r!u^!Z5Lq@tFiej!b`H0690wEI22jo+8j=?! zCkp9a#?{=(?KRip_gHf)&^L=yJ4b1u8;&Ulz1SzPqw^p&`kw^&xly7SKHL0SVWm`J z40tqRYf|**O(3meHgETl9ut~V%UCszH)rf8)rbReDA0Ml>ZEz=vGXN-yp5SMvzaYB z0khTXLnw8N^7uvVusuG4m#(0KJHx!!*vRb^f%eWF{F>P>EIFRVGNtmrm@pD_;_{N+5BpHp_YMk*>|%$j^>1Y96~i^&3}j=Ylic*5Jsg@mk=; zzM6GK?dCjB(b|B|?yWa69jMz9Kdjc5eLFwRjCH<3*R>ZuMDTyiVt&&`A#>dPzG2h3 z6D}@6yIlgzqKpFKr(i4y^Ql@wk-Aa@hc-dHKBcw|rWeK+^qiXU#%j^Zs`YQN8y0@? zx-GQF-PCqvS+Adllh|WKu|VWVq>!UY;R~5dCrFY-q&DO^6~(lxm3I7x`3XiLu!<@A z4=PuFb>&k?iRZDs;m^uNPfQtq2}?*328L&$L&(*s{q=~V`aFZ?H61j5L-$|Im2^;5 zHf{OBDtgVy(3Kb`yT-&!6{nbaZH+tBQ|6JL}v#TcKnW6y`u4572iCinri) z;pFPtYslQIEsMe5Gh@fpv7L)WIG9b2JiVK=>na1Fw=~j~>SRc86%B>jCiOHa11mea zapMK+?Zhi2xtD|^veXtK?j_TMP>0l%lqYWPj5WC0hIb={!2G~}4+Z!)LuOO{_fDRk zy_W2zyxH6HE%y)4YIsC+t0Hs+9f}hi&8ymqVI|!*uZU}$eSJm$i;yOnu@%@RJZlm~ z_yV)8>tr!K+Cm-bM9K;zEDZoezbAMbNUS+^9ohhsk;`Qdpl?Xfju9m(^6|7T;Gx@5 z`R|HO+s3PD$e&#Ue1zGp9$G8E4ZX}lXBs$W)iuD%%o$;DR|?Euwua5>Z~@QJPlD0* z+e_e~rik5`$3{|y1fr-jddMU#1?Y5%D6RX$C3}20D8Q%2Yj!AW_ZK=Om8l zd1fh9y(8v_402@3ah>69B@9K4DerPSq`Uc?LgKD7w>A@_smEE>mfc22Khj_#MN{YI z{Wa;QL-Ak6+Fu#wrQV;bKtA~+em-k;C-6bqK z$K1Z&yk>j(b+8cMg>b-YXEF-oI~)6nnLFqucfbBgcpiA*;Z%J~s<4$yH`Ea`*W+{v z5j(mQ6tYOVDetX~Tvy&j78FM6CUJFh{1|Yq{ZoAW_B(VI5;{Wvu70LaJ2hOevwieH z=r}t8?}N-xNLfl2+ND++CHo>ek)3oUgVbJ%(g(2sD=Am`0ytSRw79(I448q!2zaDf zNdUm`cr{{7-fenNnuvf*iYIT6wa5*PwovX%~+jWST%m13~cLp>8o?9hen;qv0j$wtBr{DCh0$77<0LB zn`1g_;#)O=QPf4U9bPJ4i^s7bVASoLCQ`{^?;NOi^DIQq5*%mo`y9}_AAa=T8XDV3 z^%?;e^|qFr(mlSr;#Gc>vpNsAU^5&=&pTj7I`-?o*rwcnvtLm`5Br=C%xSk`X ztXa}Dv2}B9L+{FmcJt!M@AjSK=g-tz`O11RdDn8fmvQ_K@t@KgJK$;O_`2H`hxph} z#L|0tK8K955-bVPys*wIoC%i#Rl;D}Z-QLAEaW+4gX(Xt@6vmEZ*$qxUB0afLHFa8 z#Qs=_nI8o>9nni7-rVRT2x&`E<+i9Do6@2OVVF(XsM~W7V{zzvYshR#v27!-M&G&i zV|l$XXGo?$`<)zDbKPPmaiIm6K#tBUW#wkYNusp7JK`du;}FSa#_CH55k=lEqX~<>3xt{%v&pm27tx6ytw!Z$??Vneb(QZ};lV z$?0g^Yq5h`pNa3_<5=$8t_;iq)n(=MZk*nL+2`?XObEVq{c<>Vv(r5yR;0K<=c#szH!dAYk{98wo9f#9!LTEy_uY_1eS&)Vv|{X= z9>E@Iv59Y(jeEa%(J7aaS=qx~MG2&l$THTj;FVqj`2|ayMLDugT;uHb09FqPheV$5 zm=z+C(IFS-0e)PjdvA>hu)ZPD?GsFjPWMiArSYa9%2+2!#ft_@)skDXQOqEhsavwc z1z*er%g<_bdrq@JeX=cUf5uOyFUK#MU?pLR8Hr(t|00SkeU~RnHEGjL^sSiX950$; zR|-Q6t8(DC2>|PP#T##q>Fkb`}u-$H_GWa?{M`aT4F!iiTJ4 z$$0Faxu%z;)5(11F8RsEkv_gCn#6e}g4zkgH7iWgv>|-;PT9k;W_;Hw_Y;8ikOR!% z^gaWCv5i===g-?>iDS-cgLR#zP*PadN043qu|4wh(eM}-YhUx3w7&g9O#1LhvPwLW z#U)*tQlM!6_g`tYaJtMjY}5=&J0#os?PzCbw&u+`sqi9kj{r1PFgdVK&IEjQ;3ojE zApkstk)CV6D=SRhd_Q@d3(oEl;GpvHxdrmUO~03$`{QyQL?mcEzUYwcDu)MfhhjpV z&)^zvQ=CrHZtpYY1&sKnixdQ9x2nGyp}7o0mr697*QWNIK=dtPazWA{D0=d-ir+;t zt%1M~(h*9Xd%liEPjjfxj6%;JVt5S6$QDR0jwA+nbwd?9wvv zZP$C9uE(8HRp(f&RWRj>6nuRG+_5<0+TEOiuN59xR)_DzV%P0B7j?A^*8OkpI2DQg zhI2cvg6=^-m-pw)90~@!p&m}VD_W|H9I^;40nL^Qq=q;j8d# z+tGujpL@|&|6a9?5HSIZ^`F6;;)A(9Gn{Z+Vu#=sTO|(#3V6_pD$WQEWt7fHP{0Oq zuObigtq)c%tS!_(_oY=z1cH75+pF$B4}yHS-7h8)u$J|@Cdmz!7l?A{Q__5{HhN8! zju+AilvxUjge--b?pk|{Q%CiFYOV>`?M@)@tXRLCEMz1**>poRWrhY+l5&*D!JYvU zPy+fXD-Obcx6z5c#3j$UAx)E(o67faAXd#REq0=i8V&*>zFsDYh70R4A&NoJ9>rS` zdO`{KiDA&sop2|Lw{?MH9a=M&4?o!g_UkS+2>tS zN&zXP$#}Ry4;~D7w(~bmbUh&wL75?c(h^bx8sTw;5mc4g1(GDC;vCWLgaXQct9V>& z!C_{rJ7Fvn`E%myZr!^*j(P5M{hE4Wz;&JXc<2i4>`3h8Ocn0dpLN+^}8 zYG09hFl-n$PQy=4BNJ#nR!6RSbNx(CGTR5o_x)epE%mLMX>0C)6LD`8-^!ylY*c?V z^%XUyd`rF0MNz$==3iC~R{s%vWc1R5WsNVx7qD@!x7)%bS`>R{GBYU@|Bqx#LrnXJ(f@l6DH`Yf2{C``)1fi3RaV)J0{n;GlhfTI*`|yO8VfH(xcGifq!k@92P7%YxLTG*TcjwTxBQEBl##%%94uui8 zm(X2hJTB*I=)zDDviGYxk}ft_OIrN(yY4YRZQGAm$uN`O^D|%5Zf(sU`BxR2-6~l? zI!-(}3&^Ujs5){4fCG?+iWD3Nm`4Dz3+_4p$rly41qH#in~hNM)5M1hEn1Y7Ii}l+ zP4Y@~>5S$B9pYzG_8z4id-m`4*qq%e(kZ0Z#E*ty&WlQ)hN7@6{IADaOZ6Qax1D;w z=}^(pJQ>QZtUxk}IDl*V`K=-XL8n6h3`*lHRzC~4EhSE415X1FKR<9~0}|-&CD;bv zZqGMg*;98oRLPq?2upv|O`*A_+4dvoxEFHE*9rB1WjcSEI0y`904lxHdfc(GR?z>; z1~U-Nxk;I0hqjAfaxW+J-22{_wP_$clmyALLAzd?A!D@o3sS<);e`s3RWyY>_ByvY z=yedqq$w2tTz6(vy$p>#&Ms5FRdL}$$EKqiX~N~A5{(4}c+4FfzU-O;3!H_SSA=@G^wjZAzcu?F{e^dZ z2Kr6#b1*Uj>2=K6(JTv_uL1~P9+r2ZDvXZEleE1UNh&pr7_VqZ5k_JT6YDobbBe>F z{ds%bCf;*#eG~hPkAefaJB$%JNs#0wVif3FSjL%As&8TB6;H>tvi&ek|Tgc@&Q zf%|NM;fUfLaf2@~kzfP`-@oX%-_}7a@x$s&V>qD7WE!bu?D^%rqg%3Q=H`|R-WI?( zW6gF1uKHNT*och~h4!AQDc17xa#vo||Dr6Hz<~lt1PQ$XW=^&JH#fZCdzN+tF=1Ib zIlz(!I={cHF*T}mja*z3k3{D%{S#?oB!E~i=j5Vp8G1beUJm$r*TPSf5)18V_gQgrtofqy)Sv~zV8BT&!twC|jP|#zL@~hY2GZK0 zEe+BPkxC)~GhvsnR<^*@hFz|E`aQrNxfKALN z{)xny#SGyoE1%S?NQfPg|E@_Vb;DxL-y1C|g$uDVltYst!8OF~CNeEXN{A=i+A1FK zwTX>(ZE$7iCNQP!iGHn)4QIoyZKIN%AKgdvA(Emtjzro?By|XJK+PzoS36OwVW{C8!DSmVvei# z=E!LLY3~<~qN-*XADGBLM&WH+tg5^;!&FQMn{>6i>}BQ2&Yc-?vl~sIt9<>I0!c|Z zsn*5?YL?^Mz&4&t*jYT9gDSMj#~5PLD7(W@{#uVjOs!rdYnhUYYv+BO3{T6!!S&Op zw+!B%t2CgGGG#R~%9Ctb%$u=x0{br53&BpO;O=Gd`Tib+Q4hXb6aR2W#7EX*@yny` z?1RuzyONA_LND6O48UF-&9uAkr$zE|8>oZ zb_P^%Fl`6-VDJ)vuI_8z+b8S`(dIu3(^W!c9#pM_~jzx!OMJdIG;xmdZBq{8pIq81|Gb!+e9XJF|*JrhRTqV|m8&zF_q!-kl1jaH32@oT9B zcxg&f7)0ZL(-GP>Zbt73r?h!|0-lc6gQWWlh4 z%>E+*NfAXC=GfJOaiiE~$~|t&Ba=(qJOpXWuVK8SPv9Vt)AN=JXPG^LE zuPm0#>8x(^Ilzu8FTo=&Ufu;oDAU7@#>2l7A*aiucZE1$a14twxC?4p`4lBl@WYgK z?MKh;-8qy0+CHC0oJws=%V0^a-_Uj+r6_Ozps_>5%HzW$c;~`563J%gX0H#Rir1SL zRKNB(Kn~SwVgWdkoIZGwu1cMzt5k#gNbSn7i+S34r&q5ot}Z6I{$<4S``v;aeVhAH*TNK%MF~s@N0cHssCx4=UQa@F?2CWd@XbpP(D{x3v>Pac=hFR zb#1zzzW)1Cn^)rac-=3kf>*%&x7@V$}!1j}3rz<3%? zTuqu>ZTN%pY}NXC#!zIH(wbYJTo~!*S&f-Y;|*T!&*2j-HP8Dvr^X#@jiXWeIaXCJ z5t<y-1-VUolIgiLvo$06uUl;v@cu6r-PQB^^%!?%U^z=qM9Y7`IdC zWs%DArJ2v{AYq)8oQRp0(LtsehW~I#ag`;oZ18VC*N?@DC*qRSiUu(Yqd=Ur#Ng`P zzLTt~2}I)-&XS-PQj#i^AQ2j-f1M^m&ZBaEp+abE8_mH2$<80eF)6VWpkP6ch@IpV zUrb^zFNksqOwo7bf!3lUs~3{!VVF`{Fi?n%5;aIj{YDGd#=_LDkgKKaV-^3ZtSqJ3 zBqmB?gZReU){vy;Ylsd$f#lfu!co31Blm4rQziAedBsm6gABOb^z3*U{k5)}RYH?& z&P0)XnDBF<&N`_{izQFCZ!(+vU!W+mJCi*y>Xi*xg3H6*mfPshLvEq5HMuuqgYctj z4y@g7>_ng|FP2dZ&S0>=y5zb6pun7tsU5>;QEIXZ8X{wjD{su?LgkB?RJd{0fSu~q zk7fhesn=Rrs&VAVJ@Lc5hpr3kM2xBppbLOVicKjfyjf9t`6YCIwGw)dh#+ELNjD6j zNW=f%E(jEzV0-dzKeC4N`B*glgQj4T`teCtXZRQp-1DN(BsI`RE@jI;iZensI(4)I zA7M>5ue)4Qx!d-C>bjvJ6ripHN~yQ~LUu6PJIk8JB-2wgq}*PRlox5uo{5h49o5#> z9>Wm&xpiRLyGco*Gy-z+>$71daJpDl z=K2TV14R^oGh)F1`)_Q)lC7YJ-Yj>#jg_h^0QaQK$m_oR;WhpRmUFlj>e^TXN-ZEi z1)zK2^XN*RMMP%LKnE^Q6hwW|5n4PI~g%hj272u+q*f|B;=y3gQ z@YdBjoT%W+X6n_1!>y_NZQ{326jlDl60WbLguerngp;Jx+{Kf2unV82tC{M@7z5u2 z8l&o%IOe0*p03A&uipzm6jZ!rqih}Q>%M=F#tBmPAMo(#H1S-pNU#iXa~@}W;r4=p z^nDEX!t#fbY0=`U&1X!KzkO1r-qYynLtYwnO`V}o-K$D$u;^$sUeB%Ey&?AfhqaqsK<6i*2TXZ` z$J7;)7lXu~9$yAAf5j8mr1v=bv$k;lrtN-q@ovBKfesXHclQqdCT@129xLrXKNI^6 z0M5$Gm$yVE@?EkJoIBEo7aCRiPZ3|HekR$VwcNQvC9hIt(Aig# z`)SCLdG)kF@__gNu=RTrv){#j`BFBwztrkaj0!440Ds|d$y#%ilKBM#shRI0AW*Jt1@VCib_vXhF!HwNC5Eb(YX7H)U zl7IV0&u4b4{{+p;-+!K+VFgddJ&a*TH^>#M_Dw(WYOOiu|8#Ua_}}UXw)ka&hW^9N zPki6=^EoN<{Wov!&cG4&4?2D|o%l52+@+4u?O8mq*-Ik*V9&w& z7MIE8a0ZTPnCm5t!NZ}0@A-^|ris^$YwDmYYbK5Ila84P-&v!&lTbOYTlNR+PS8tz zGyUI(2sF_O6-!d5pdTnPVz+Ya23xo%MdI*`A7(8zwtGC`=BSKJZH*=9wdo}^>zNBh z6EU!(Xsj?y_L1}RSd4;RnbgBEIGI}UBfy2AD|P2%OC}*%QM2kn&mf3maI8PE$SRnk zj2OCQDrTg}`()y4^}S!*32?_p-^XHu)B2^)Tl#G~m`kRCxIE2gGE+Ka3) zQq~M-r<9tcbu+bp#z~V90!^UI$BCAf#>^}Iqk|-BL73mCZT=9!x=V9+il9)yD@Kz# z$>6Jgg6cy8?KR(?MR0NPcqrXLz`Kp2JNy@IT>!(Z80Y@j*f8-x#ZGE^r=7{Gmw2C^y^qpJ+bY8 zXi>Vxx?9Plo>U$?y4LGWb}oOmH2yu!KiVO3F+p6}fq~B?jx8oKG+@U916H9>cUSO+K~r zxTT4UMOad#ce?}uVwJ=;``AA2s6}YU*Z`zOufCnkwLo}M``~n~zjHN}_%6ZyS6*30 zMg0o^xN9I0Lk<-N=2or6--cE$nKknwgrmtei+6|P{_FeIoyCL*^*(y)oU@vm`o?z6 zW63reyTrK@LIUE4fZtRLUqk8u^2LG$pu1sEwygYyYUacQCSzDcU?Eqnb%%rDh1XaJEyFH740Aaq5iAgZH-{eyp^8?fE7fbdxfT3Sk z^SfZSlr3Gs^K6r4V=!rB1G^9fxOYXRrN40?fx0?>@z6MC?IHLU*q|nC8$EZjJ-~g5 zo}lZ`pPWQW&aj_=T&J?s0^?Zubjbj$&7cho5O(dL+>#KRmfE75hM~ z5AfeE^Yx*Bx<{PA-aBd@++@GBdU3d@X|tP~!}|Aimv%j8?`hJs>M#)gZVZN$w6?l_ z*8{cb^aG#;NdnHlbp!9Y_qza~t@*zEN(KQ4kce>F3ZC+L47&CqC-}Ad72g+BnzO&Jb!rRb z%y{F_F27oI&YR8HWWNmHUV;?zs-SBCWM}+d|H2DQQj5OEJaNXG{&+uWFTt;h1PBK7 z)fHgZ@9o=01m*v!=}7M54L)MebB)Go$NS1AO^{+@Wfn?}hAD$tLh}?ne?~dzq~`;I z=S$L9S)IR$juN0C1Yj3ZMOw#CO`lku{;9jv{&zcGIQzZT153xi1|}8n{R|<20EJr3 zsFZYvbQ_6yqym5YXbqF_V`;ZAoZ(yMbglIF+uKLmN9LDHE=O8TQNpXY&#T)nh`4h6 zb7WH)q5d`FE~$)Xd*#*6*F(64D*tZ$l8#A}Ak#!e{6Wkl(W0-ud;x(j8{h+%B2AB` zYBt59zBknP5sRySwO|r2apeb}q@lTX8AvF-Gf+LD@+k3!e#)p!r}YdUhPvXNvS zD=Ha?B9dgbcDB(pd}i@jH#fcmFIJIK;UG%+-=xxRY)xX;@wkByH8~a$G!Ar*m~?Xj zgEetdt%G^tt z57(*$vq~9|zKFp0f^P`;y0w8UA`=!*L`EM*lYu;dMo66>Mq-JS#7V#;QjSx=E)kSW z>v2FcprJ#1UlXcQ$KFw_v;{dE7pADPHYcx2qj5oJ)Bg=&>4qeIKD$>zzfIq8H6q=8 zph_in>Q6ptM~?l`0lfc)9T4r91;a=@)<>P zl&TdRMX1UIVPIIsAJgd?KfToAHzKad{|FVtN3oEMyzMafh7R=1K+@^nDi4G%py)1g zh-Ufc-OfMXs0cD7LGSqe7XS(aQ3t@zDV;Flgb|e`mW<(*VsqK5YhRJVNr!{cjro1X zViwfwp#PoByH@@jCjZl7RB~2?V`Nis9v6|FbE2AP)F}r*8Is+uf~KY)xVah zG<}au`d`p-^|XBx%dFX}yQ+buy}+9eMW7Ct-sN_<6X{e#^7rC%YY2?8Eun8(rvBJM zS5ecALRWF(7C2xtxDH1v-e_+mZyKHM@l0>%C% zkTQZrubRy=Lzq5Um`*9Jy1t8(ZC0gFT?;RYh45UNpr-MUdHeF(HeEGqZOSFFpxA3l zpkgcSqifR7Yf&%2gl{`1evHaXiZ!HqeTbxN{t1W$b5Acewjdf25gIv}>3rA<1Ht|8JEBAswDC?Pdc6uY*rN*(=<{164~ zutb)!Ndl5@b7fpaZx7yK^uOjgJdemHO7xU*_zkLG!~#rpq@?2lkP@2B{1%-sRsxA8 zBJsD@U+pN)jEAq|T1~Rx16OtcMq7uDQ^ezyj!{$IwJDcW;9Bp~P7-Rhcghfc-#qBr zw>F7smBB095bD0}IRr3v&AwYG_)G$lLa$$GKF`$2e4Cr&2vVy+LLEtXV#uy*-hG!iqE~-AIR|bcb|5`U?LrQ&{=N+Fv zb%5i*eXqUtT650Jw+pOawURM{Up|QBpb52hYh6R|3_LNm=^&iJ%01dPfUNQImnBEh zoC~M(L4A6umQLxkb@@7ikX7>J(WU3<=}Q1TfzV*xlNpw`N#;*}6aEW5U8e-29?cV1 zAX>ig_LFSl%w+v~ImR~!&Whd?{fz`AA#y}95QRw7ah;?Bt_#OgF3(Wk7E*udhNb_~ z+M9jDpBWzY;5+tc$~7EVJLI@2Da*#05nO6VUAkvbDS!taykABx+YXg;-7w`vr4j!63`nMJOL1OU=p`uJ=}l zF@9mWLM<5g0i%hjT!q=5rZZyX`=>Tk94$3iir;^1OaZ%621_K_v?omhNu!_p)HhJt z7}}1UU{nKZ$1zKz8D}JMTt=Qr!!?IRne+ki6FhUh!X$nblF24328qdf9I}YHFQ$Mk zU*|r#>>DJOcS%^yY@J&@71hmZH86;DD*~d(;zD!GiGx!qp1GlT@SgRbwXxUXvh%gw zSa%(pwOFLB&irK5(88=qC@}E9PqOvW2RXIR6`s%bnyrMf{QQ;}QMa_=5NR+H@1XZ( zZK0mAPnjB(t_tyB=eS~Z8EdQD1zH>-%lahDdN-_UywFasR#uK^30+~T;2ql3vOLo& z_8!KOR~$?)vik0da{n2u5U#GS8a>Y_z;0u`D+I;N)&~GcfX{Pq5DAEud@m-YAd)6h zdDd-p{>Qsw_QDUSP6x(1Sq#?z(4%b=NJgeGok^xQygR+)#P|1ou-OmG6xXzbWr+=# zPxZN~YyUtYbOdG(fR_VD?y(!NF;=kOv=ip=JI z3>D&z*Kc^`o;Ric=UBN!V=E8St38a``jQDo!n0oMg^~9+w8HDRyE(L|l=f@w3h{+hT0;mP$Bwr{X7+8)k)%((24sc5 zth)#I0MR!TjJv?VUnad~)xL%A=UfGlmz=D$kLIuFy@=;<%Hib!LjwPcjt2ta$H<)1 z^-$7t;eac4#qlv%j1>i4+g@RaOc zELOR;+xc);@LhFYzs);oIE6WZ2C2jUU=9rBr))Vv9rC?6>nA2A*}?5fY4SXS0htIF zlav5?Waaz&PY9mDpMOyYt&jiE2I|0yf@lqT`YPp<7ufT~7wI&qQ5D#qw%m8Am;AkYtgHuKBx28vk`^wZj$r%dnizRQET zw<0UHKVFb<-L%qAUJBIDA&GjYyq z5Z&4_U4yVuJ}p;u0TBw zNhV!eg$+IZ13@AOqLp$}{HN5w+eA%rj3F^;v|K7#FHNNM;1TZ|jGKD&b%uhIbsr&u zMQSBvjoMkwD4Om(W#s!07+*Gi4 zT3pldG7f+hm>vpg9~Zm}O=)tmv_Sec{JU%eN%%dYd(MmM)3%%4bEOzeM` zOQWxOsIN1HS49)C`m1XXMzQ2jT2>?R-q+OE_kzvxrFRg3^Mc{jb3zU1-=K@Y?-@^( zCKt_kowIhj?S0HZb`bHaJu#4R7(DPjP7pvVhn|0XnTZZ%}^ zATFtTa#2*lq3D9P#&f?LIA=ixz6(>IrK}Sc)M3-fNlP`%Jqrs9KwT*Ad;1zZ_f#?) z#^^JwU4?>{Z*YG6X@odob<0px#)=Bnm6RBMge~!Il-0b;b zSJtzzm`u85Q+Be6_K$>tgu@6%ZI_ zu<5`%2?3VAR%=K653*kp+07e0EtB6q2so@33*&5m)~jSVv{n?_W*N`WF^i=8J*iW5?z9Sjl0WZdL1!dDuE81ayR)uKEb zVLpUfP3WMUv)$w1lRk(HnP@kSpsD^kqCxc~^y(8cW1W1TiT@qgj^J|gql(u}dyeX4y&QRKI$dPa7$YYIqOy&71eQgksRiZEDMUuvq=|0|g zeI^xLAGXpa`15DO!s_bI#ZzU+rFFn&8`G|;? zo84?G-j;KM-=TI}^sX1!zCS*sbbx?%CnJkcaC#(p=PQ;j^x$`!vUTEjGXP_|b^UYZ z%(GRdd;P`xah4pKijjUp9#akiFxntcpph@aisxAexlU*&%XC5Sqs$Y={_!1My6xBV z;qnLyZUdw|+o!!|#G<}N+fGKGJI7!`R*KiQ?db%O^e$txD>oEkc@nRYDr_O00 zX9}Dgp1W<==u?6k;Eo3#&RK0H#$=G>t`;d9d39~y0b&ho?d;DtP~IC>--!I$eopm% z0Kw*Zn}ywC`}II!p}*cW2FH9PWb9*+u_6`o{J}f^%~XPU4u=jC7vEcEL67j=oPg}0 zATc0X7>GZ#d6L%#MHEz0!07X25!P^X_@o@)SVVSq|KgLwpBZaJ;a}28OAL6p!@a1J ze3#{p`?^`wsf?Zbu8L_ozVH9BP`=0#{X`#rjy;utXa?q^!?5c}YNH$6u$?`WZ(qiR zQc>Z+#5Kc;XiXnEQQD|jKOyD;NlSiIflx%wJsXDUjeeNo^D~4 z=r`q_#f>>wBPNROt=>>QKfN+`t63V#8M?IaY6|j1lJ@r^gb;;6TbS%l?`TwR(a$W1 zA96ou7K|RO;cyLyEU+gzRefvAqH}>Bm2#XOdekZrWi@c>h>UoH_nE z-PwFGLmGp?G_O$0PL~eNe+0+;5q(SIfr!r zV(r>%Jp>PUh1U-cArB7^%SIOB#QhbnG8MCKe%e*ne!wE3^lBWM`MQ+L?Crv!DNLhE z7!W6{L06otgVfH`KKabJ_(T)wo$hkY8khBLRV0O6T9m6Z93`N@0I*OJeK**Z>G~C^ zfK--U>$}Be%~5vy@c-ZHle*R0TPmS)i`H*0xgP|79?lb! z@BMI~gH^Y2P0y>vR+6dPh2iajPRJT38T+|JlD0ldwLa#Pp3fdFT@;zfr^gi%EH1XT z$A}_^U`DWnh26(a#GHy&IYBTZz=@{+v?;vNaete0HtXZS&c{nZqC}>6#ujCv+fm?n z>CnH)s%~kUo>wnPm;lU|Upn#@wX?l4m2l1MtIO(vux&!{U<2W0eq1RMbqLkzt3a{> z^-A^`f|JLqx6S!48|>R;Pq`z!(f^R2H-3|lktv=0fE+%+HZ_QEl(lcd7w&@d`470G z8nI<<_>7U@!8*m~3B))FIE(MEl4R)Uv|jDo+&=)Ez#Q0Tb!WY`j;r-Qc57K~yCVlV zZ&8Y&9d|7qCN@49-fhnnl??P*V8n01mvz4C(*Smip6xl~mja;2dVcj=?tB1yY&6CG zJm5a&sncEmBeW|bpQ57fv*C)<1kd~aR^f1BR>>{y=zV7r=lnrVu~R8EjF4w?={kK^U_t&7B2 z?MTq)flmZ-O{9US0<5miR>3kKA9a3pabxlFfP?6D7a5hD>erwz2ke2hwaovOr-r50 z`}5)ZGtviEaKX!6(WeB`S4f}uGg-x)2Y;eu<~d4FJ<_}uq?oKh!}7uyG%9ys4Wx8W0{QPF!x!sVzE}t=I2_63&7*6R`LIwpL}`i{zvo$}EEkJs(XW zC*A!_Ic8H)afD@wX8ZsUO%NEpiy@V&LlwATJlao+9 zibe}Pew(VI+}RiIHDlQ($>2e8q(0-x3|^wU2Ve|JWu0 z%S_k{@>c~BAG4k3#6`dMP!agU>TemjMhr3>#g9j^mk!#>8e_7(rBs6-l7d5yBCjU2 z!EPd>p4!qE_lO66otHyW<;PWt*vm(v=Kr)|C7X zX{(sDCg=OSsnCzRo^m-Z4}U>=p?oE!H3a^ahM}K1_aqD(i?iAgE;GF$P&+}A$x*($ z4Bt;}CccBWz*#pmJ4*xXN6%dWFbAHUvG(`Vf(t@j_Q(+a!fpLx?L6x^MnVk#RYcyf zrdYBWNUTpWB#QxC491Gy$jz; zq?$Y_%a^${Zv689+0tjf?9;B{0bvRNbPX0$WQarKj6@Bk!NF^9#f6F){427($+7I zb8=U2-|(AN?0QvvyEm1`mTG4nduJr-_@w{ zWinbrnRDwCKJ=;l=I6BqH4o_augt_v{ewI{pLLOF|07 zGaEN|W+AEKS{Y1>*0bR!!|R){$Q0(YDLL*zHifu5p{yQYY6`|FYv9*y_Y7a(BX9}` zQ;A36uUJ(P$U3imx@8wySu*qS2|a25_f{=_-D(q2jq&J;FyL}7K;|QqS5RPM&fzhl zbB`cxwh43Uttl@?B5xCeg&X@6$M)%;&jEK00WMmLD)Hve`J?299u6tH2A|`w}HLOiJuJFJ098CC^7E+f=2GPXM;!wS#Ig&xLQREOKY3! zL7_m?4P52Y?A)wtD}Lg&GaEA+`s+X$8Hz^Y?CQF8=*9=+)_m8b%NFG;MGMxsQBGQE zo2KK{0{v1KU+1plRg&UkYrOy00szfM&oo_wzJJAChie ze%6Sb#%UMyT=uz|&Kg3Pa z6Iu9ICHJWfXWdCk!AY4!2JPGe?f0qy zpb;h$sOF(LP&>Kn&JAk~#&|OfXx#|b#cjRYwi|$O;w9jO zOuFYTJ~*Rred@nR@YJIHQoc|0(|PSiG&@h)pip zi?R^LVGz;I6Ad&kEQnSd>A^-XRK7)Zvfsw0^82_j?L7Igr3uU_#X(_);$|gQ`hci4 zp0nZS^B@;YT0uyO1s*@i^ucB9vm%?9{{UFFwhj}00K)(yVKCK`Fh5F&Tiv#E`F$)6 zl+}xy5Lc$U>*&YFQ=#(DHX%6vDXALPV|~umeGXh1g*aa6MJS4O4EOp~TNij|Eo?;% zu|le?HW7ANul+(n?k&iAkR#d#D}8JUSpSbSCsZ;Z2Lgb<5@(;le(jdsb-qwN4vDo$hOOsg=*{k(2lAc30AH>th?~>6ELeiQgz4 zMg8C_k>p9kp7l-)DFi89|6{hNhmHpiZv-jd`_8w|b2UenEznn?%vGGWo%qMtylD18`J}OA!_`2%_YDC@acAyzs z7E6}mb3R3je->bLLsw4x@xUDo%nAh-SHPAN6AY>BD|kic>Zh5G28zxS@2-Wn&yyI+ z>X+_E4W2k<($PJI9`s|{R`kXcl_vRyZBjJB8c3^X@59JVbBmmDr{)!YR+f^MMC($krXu*b{n@eG%}5w^o!d7@NgZ2)bHXsOSVAkAC8cOy5_n^4E6f& z_tj?<58K~`PtA@Wu7hX1{X!}c%)^rk{T+{EnohAOkty)dVM+x|(a8iz3%U@c@W+rN z(^anMB9zimGYaP!Lm0)hbyDw=?K#apHhyah7V$!d#T>`_Aemf{mgo?33S!x&^&{kpJOb!*FkSJ#}M4oPny+?pCg#aO;#>H(P~N~wDocWEB^ z_R6f?N>*;gg6CKKL^)>A2x20Kha9G8B5sE=Ht;lqhXXiYRY2_Vanml?a|59XC_~Re zR#0VuNjAOl);j5z-_Q9AtR7Kb5ql=ftfYvxuCJQ(;b5uZRYKUWPt0E%&2+nc`^c;< zb=R(hE%|%D{+t;5GUVWrFY2pY@TFkRpsC7_UciI4w-Fo|4E^H5E*oFyJ~T`$oU))f z{<}|!8#g&D$%eZkm zjoTe~m@TfAGbDmm)wgaaS3qio%IvruA&lsneD=5Vm5`=SjN<$s{`Vb2+U4OhbS*wU zhbN?L#L@Usw9l8mE6LD|_pM=gu$I(+bKLf_Gvj-a@P|3F9i1I}vX&Zd$4V>D7Ka=D z+Sy~FNgcj@7J&||_*`qQt!@60v z_sx3AI2Uq`{j`v2$TiDnW4dR%T*vy34s69i{8W?Q9jJ>9UYGo9ohZIziY=`VOASp= zgS7JfSdiHl(sW^6pg?16N5YcB@=b%4j`QvVnkAP`>&5x-Z^G9=Oxy7|TG`}r&HP{# zGdc#32N25jpnuz+Vepi723L;^&?uwXukHLjMHfb#|LfZ5e92bXegzT?Cr++CpZx?b zyJBMiOWaMaLJ#3`Z4qp46Uv_iHeeZJZjqyF1bn;sdB|Iv;3$ME@kDHtP7+o@I z1=c<@7WeUHGk&K`bfsdj1?xtLX?$3Ht^@n(9Ni zzJh7|s`mkt(Bq9s4Tp(9wj;=5xh@+9Q%@}e11b7J{*%`3P_VoMcS1EK{5J@$p@Lkq z+`K}38`DZc+ZS8Gz-5-WYhAC~>KK>7ZBW#<3LMhGEu^d4llfA(BK26@23C0S6T&gO9l16cu8YB{YKk&Y@x<_!4BcfUP z1`i<$M8&~VqRLv84OZa?)1JPHAv;IPL*E9~cH=gk1?K(5S>TH@5gim23bS?m#&5w) zJC`A{Gh=;XX9-MFQmmD(P#;r8%*Z^hid4?Dm{6^a7i8F?^qE@=Nf=uH8b=3bEc{U4 z|J?p3t-SS71`#=X83lQ zGhXQ53eqvM66J0Ofj{~FabL*FJEX$Ie{ zDo?YN$)cHWN3}oshnpIBjclO3&F^@NGVZm8qwrE>Y#bH6%FNPKF7NQ_A3 z3HF=peovmQr@NG#^PTYk5y~G%(-8j#xrRCF>GY?|KBDDz)w)gc5UR93RPX2ZbJh|a zyxk+hkDJ02Nn}x2|19)|WWH$%(RrYF1l5o6^`=sk`X;-PhU5<0&JutW{d}pG`wIjA zp^m2wJVffr??r3i?1%iqFOGixMm@s!-NIxcWLb)!_j3tns5C9&EDmyv-lpE#U!M^OagM$kSm)R zp_1~DnCu|9gFoAyXwO``99eqs#h5_M;D*&mK>H;w@U4BRO_4No?E^4tzBDrQ-!^U_ zA@`*9;mx&h(|Fxf^a;YdZKJ5|<51F?JIj=Shkz%XV7V8meSiRHwD1!>u&qt-aWChQ zE{7+Eb#X+rR5WRpnU48_g(n)}Nn4_h|2TaT!q2&!j;r{97V7e5~Lq4iozRSIK zk8{%Iv1DfEO@f#T>4)@DmQ}kFX8Dp+D2qCt9P5#+27E|2FR+qLFCu>X7CLP3h|uwH zw8RW@VdAOWIls`V&f3@&s4Tbn#I&_N=$0QQB2EwXz*(^sBV(wLg;1P|xsx7E2?~nQ z4SKTm;dg5_3==uDb{>K21!5pu+;b`(VKm~sV?Dm!I?-p^j;R!=@8+#S%r3!I}y8pf(c}LOG`_K zhlkHu;idI`J3H`TUmelyqy%^2!A~sM960?at(-|Dp#$Wb=k73T`>0Xi7X#w0y)s&UI|wHF5GGIGEhuG zAZ-QC%ZyILFxGU&VPf723-{SiLhDYKfuyD1M#sg@pzOIrNR^mH>Nn|mo-x>$g|t`} zKi5fn5DGFC+T0$9m{PwF?;RX4|}aV=Zp+{Kw!0+sSL;0F2JjI_0l0>(|&<(u+) z_3u9w6c5X8~3D&&O}2`rp+ ztYflc3Q@2$qkl7@g}Q23}Fi(nEeizM4pOpDh!($(rMtr9)`t`x20? zHvZXzgg3>|pW1Az)KPcJ_*Ke=RA zRcS*iPA~iKGcKJx)kX2l3y!%jnbEPwOJvdgaZhsiZPZUM3jKkSo#?BvzM|0k22nn^ zio`z%B~@QZXNbS++?T8UU5sx{2t1bq>xQ0G#!;K?z`98Ij;3-4vuG2jxb*kTm8xB$ zg1Fme@+YN0RL05lo=Q5~BC<=C@8Sh7RYK(v(q*_QiM~Yn1!CX#6dO_8|Dp)QK2VZL zBEQ6hOyL_%&L+WDbBQgWGUD41hchyMpP&+r3*-BKF<3@{m7YkKPCiRy7}cj8l?YQv zmAlKUqRP);NyjKl2um0)nfd|}QwNV7T>pX~_)ieBnc|^r@Cmt~MLxu}pd|@2QS#=v zKzp<3-6B3W9$qw6gMFUjI#cU1hLyh>qhA1`MOvA_r+BAb2}XOtkM9hV@cx95cX<82;62^Knbu>-uTlA8zhMj&sB?uC>*AH)tQQ zEmR}c;nf>)b2n(}*eF-dh3AEV**92H1EDz>1A!5>c;y^J&`IrLTO#zFqVK_V*9f;% zaXOL5ovRm)ptOJrnKF><&t-y*vi)4w8>Yo0x7oR@x0a%jHl0NpXz`w# zOh+DL9(+evU-5<|w+hFm?T*R5QDOSQ_cP6ZA|G-nU3O!7a3aRpG?r|m;T~mKGlUY8 zQ4B<4i>X|-1phu?iGgy+x%#la#+LU<-l1WLu$hpBX_1c6_X*vooI1K#n!yQ0Ln<0) zE2;il6!kPgY#h==SMLO}jY%q8VXZv>jM28oZS(~1cWqdGWR-;-SR0I#;Z3iByi2yY zvMGn1N=>azx~Fu7P~h3BCSf|&j9nXbRN|sNkh)mYDKH1acz1*hv9o+jcdgCKtix-r(?ho#4Ww1=3!b*pp9FRs zlCJ;Zb=G`)*!Krol{HR!tPjrg@?Pi?;-k3rlG9pDl&rlzUd&isquq&)23`15o`Hk$ z_gF>WBDCbU>v)ZHeKADPY!v>kr%wJBqteWcgBvGd; zxHt`QE~uMD%#Z8)%vr%)hK*=|{#&35Gr{cdZ@R=!_Fov44Fy?{A-}wF7gRjsLh+3*WWsmvN?1g_ge1BQ)+=@N`V(*HjWc=o)Q^?b&>k~_%!af~ z~VZP7W-k;B-G-?%n-s%ad0-y;lV`pMY=IeuDLtTm+q`A$zY*t%MI|=IBI5 zb)WXKT9!>?^Gvy%%%!&p&yRDV#yUs0@fMh(fgDiNz~H?NuRGt{^wFIWK`9$>nt;Q6 zWo1Q$RsDBImOM>?RXVAT$Y9K=63G5tPP3-A$uHUn`^bU{kX{^wQRjLe=b_w$QOn_qh7cnGlIfG{=j8u@fR4Iv zC)sWwBNCwKv@HrHTxM##W^=4{&93eWP3?{N@gy*!B=e_kE7K>+)1@Pt@Fp~54lDk% zi&S;tb#AC!$(SDFEl4GOWS|=`p1eYcrieWXL}3HM9R@iaN3F2TtujpQ+HqXBfrt)% zwjZ+DOz3vE9%)OXV?W82!m|C2?-y$@=jj5)W=KBOoY`)B)C}BITotRZ$V3c@VDFk9 zx4gSkg{(M3e+X(%b_*DCl(wm5YOtbckDfU1i8i-NntiKvep$!#Nhc|Fr>XYS?-(uO zi{Y^N{`WhPJ{II}%#O<5^7G>2hrkkmEwhH*s)=)d#I8SFYZ1-bsADX$_|8`E7%n`>^YhCB7%eBmQX~c%pJKUV7 z@ra?tadJ=R1W?NN* zXBU^jnbXwF-YSIuNt6$BEqU`7OG7&2jo*O~Wq~L?+IIo;Kv~w>83^Y{iv_|J)LL^QtIVhq{fH)kySk!w>KrlOY^~UCiQ@{O|4eT$Ug#-U7 z70yQ3Tm)zoR5h}%Ozh@{^dcX_=Nt} z$PFL2a1Gi|c3~1y?L9tJ&TWF>2$;G7HzROo=9T#9@bG$OcR|e+2PB;3zw~-o&O`(> zv2h!G!d>78&InS!e=jd@;q?i4M$p7@WkY5@fEhDR`_CJ5^TLYLZR0bhdd65C`x{8N z83BRDgWlx<+8YWqbD1~>)im05T)fCUGCPaTaN{NGA?+kICT#RiT~^1K$+W_>gm@Jv z2{0GX-+N7BCdWhSjmAxIL01ML2Opv7DM1_3|V=f&W^V3hWI(T zrRtN8#&QuG1$M5!pLW$E-JNqqO5{1Pv|G4gPC_HqGZWNe-R38$rhf#*;R+XGyQ8_un>mH6TQe z$L^n`oRy6^{Tg|{xLa#7_TYaUZoGS9oPrNU;H3nI`x?13+ktLX`9JCp^lECfwp>UD zuT}Pp%2dO$?+ONNHjJyaWO0=S7q3OYAqzloXiO-d(mWI?J68yOnVvCg~GH!uS3jXkdrU&n(GDnDa#1EU(w`m#i zzc7zSW}#d_9m@wZ5zX{=2&H8w|(pn;O$h4&1?`~_QB(4+C-{E*L_kaFBc_8 z_X>Zr3&}_CdX+mNigggIW)0!6%phkw-^=EQYJZ@Co^*W+kwD?U<2NjGG#5^Tv#Uz$ z(~fH)ZF%7H(R>$ARPI)G0v0onp!WaQ0)$gquc&*;pi-YVWsDvbL!W~0enb}o zY9|m_H0V99jK#CBpzNTG6%P%%ZtJX;5$zv)25WYG@YgCC;T-Q!>gC-y-ILjb=D>~h zW|aPzmk6v~Is!_Fh2>?&Bu#Le1iA$<>9erV8yiy`_72-T!!N(IAU^iWII@oF`|-Ap zYmu%2`BOy+`Yo?AI_yi3g9h}9|E-;wtn0(H%OzV@m~D7)BYt%n{xbYC@a!hC&W;+rp#m!Uj{Fwv3;We1QXzqeRFh!pBL# z9ocj38Z@_5PMkj?-Jlec*Em)>}`$JeXgqa=X9xwU|+VAPS|pRu(SLX_p3qh zqO03Pnb(5zx5ccS^NhosEenkG|EHY{1EwP|)dvUWplP7W4_A7fI#qpKG2O-S`<&Gc z$w;syax`LWNP?b-|8a!VAb(fyjjMHIEYsVQ+6uRq!o|svD zmVRc=`@1KV!R#Idrr2G$j>9|IXJ0fvGM=nhT$|mJqD(p1NA_oa9;c|t`I%L` zx1R9EZ12Ia^nqW>Bimuq3A!N559P4CyjQ2Nlh7EG$Qirdb*X>F{MoZ2%Nh%M)W~GP z;X+X2^A)OEcgC@MYxNI!n$|S84o-edwV{4Sy#AU^SGz0)q1)G0RYcrb)iFLc&uYR% z)LCs|(V53{d1;=by`s38evqE#*v2Vf2>ldh&P8RfD}qfwatwIQt>)VCv!`b)qWP zp2opMtcab>L}n`R&~;Z4d7U^-kj0t2%344pg$GXMi!3$$rvWu`m7pOi&D*EiYjXo< zVvY3O@sVZ0pCga~xDUp((oV(VqPh|)zg6hJ*Q+ZCTkc#8U+~rnT--~sTkN-G{{S#s z6{S+iddqTprh<3Luo37oFQ^d7u1DsVS4MU^!MCEI#6m*v>AM+w$%c#O0{-Y6dz^TL z$BI+%gu)Y*d`qtq5Bo4ZSfeBzu7V*t6bNCWsvWNQb0V`KRW~~?@Jgvj*>_X6J?+dt z#n;3vN?%@NM#9*VR=H;f*C2H7z&sNg@e>&1<|C7!nU(qY)Fuvn#{zrYK1o=4b)v4e zu_L-#P2kPk=?TY@C^%Rb3r)+(vAC7axr}mCS66?AUZe=Oju`U18*(z!h7h#G7&U#= zE&f2a+w;eipIV!!hLIr~t`J-HJ4KE?XXs`er4*0z7NVS-98jAis`NGms-4fys*C)w z2TZ4*Kl}RnXta`}>muuM^GC%ML9jJW2i+B0g9VOrOa3pZyY(*(=c@A6C?fEJ!))iv zGRLzAZty{!VUz<$`p6FSn?OWlwMsbfZQNIeDGKLaqWcqd{w33sRewng*LZ3F5I}d6D z+Vk251rUvz5Sn%#hMSsRcPqI0=n%Fen@sjI?wYK>*bdHAOTd_)k5P{P7JGcFc~mRK zd#CpI8?_Q^uU_PSq6w2_K5Ji|F>Q{S*xy!H6R&i0={@I#PyMzgL$u6?qao2G;N?+HfiY`%+bRsQ=azCI6ThN`1ilwDyOOTFCS{V zu=1vk%z~+6`v9Ku*jLnSz`JY28Kvn{{#wdKvzXd@v8}J>Dzp(y+E&3~RTyMG+25v_ z*UI9yB;$sINA8j z4W}HpwU5&#gXowd9}HMgGD`C2no%wbtq{KClC%sOfMtVY#qRNvAEmlrf8F#!TZWN( zh&{D%?>9o%$DJ;m&*(#5=ZJId%86uxO*D>ss@O2fNh}re^vrD2af{g3%S)CF{f9GH zQmZkHFIL#CAaqxRT{kzPoC}{^yRTf}21(G}hixW6U^>q_rdWmL8|WJe~*O1-n~nn{S{U{E1h|a7Ab0 zUfhP<@yuASZ_RupPX^7V?jE=pQkk@wi~;n>!GR4(G^%QD-v9L4+f++7y*a>$<6Kj?NYcICyGKYLDLEdt6VsP|p zox?vx+7PFFlNDFu7GW0A@6o?j9zU!RV#82xNn+#YdD{Y|#XwO(2ylt<;?Kip#P2ip>l zNcy5>Q4HeeM7h1pMd5Kxf3BY7qT2Yy`HGJ@bwJpj7mjwM-!?~ZD9t$H4&zfOg2fW| zG5cPDTGXT>1r`8yHqm#=Ue6&~l+04J3`wdOh z%s#}TZhyRl zUBlNZpR1xLn5caj#z^rYZh^g`T6yB+l-zxYG9p`F+r;UPjy)>BjP&xdA)`tkNjJ|M zhF4u;n-f{0%)UFX5HH3AVoR|+YJ8TXVBI1`u2k&Ye}IltF#Kf+FR=X+Y6%7sEqS?k z1TI0-lZ8Zd9Itw#Z%1G0F=8nTV%>Cthuu3yNmKl^I~T;dFS?$g_}^o-DasPwsf$uj z0ChbPFPjcwRB!xNJZwl6rkTk;S1vjB>p~eE)2Uu1xmT7!35v`zGW6mVml=q_U5->e zCrWp%Mdlph$}bThSBm>;m)N595VZpEZAJ<&(LcK+-O_?^@1Y}8rC|~06 z{iExyTM0(V=w(7>d z27XS-d_@4zksUN-F*GsBkNvp1xJaR(`kXncrDbGh7GhtC_MuYvG#UY0JU-ER%R4JC zOm&N+4`lesWEwhM%1_r((f1we#4^9Gq+O|vrM>ZPfRb#b7o{5G4OOH5!hJ&t;+cTU zsq1CIKVn5z0-qS78Qy{D5z;RoD*qenP#|AVZ1|t2OBhW%Yo1072?cqMZ zylncv5M*#x0!){wmim~5NwD4JN#{WaH_h(I>l7wQ+WDYdDreyekHnI#;gyWvS;o&t zVpd6XNItJ4@iNVrI@iKjmBy6)%yRN^K+~GPafArV~B3jpKTn0&>ErlePoP5jp4DZvx>g&x7@IIEZ98sw*zd}#&*%wD3vKe%J z^I0w8T{LjGN988>)bYPvJZcK8!@)dfv|u@8zfgfVZ9q_Dh)uq@rUHt+VgQS496O)K zR#2?C$}LCuYIs%G@$t25I8xp@{eoq%DKSYiCF=*H}7_?|ABD(pj=@PU1 zmQ<36y8~Z_gJdr?W+_+^O(wd@tvW(y2*@>#VdpTO#t7)5V(yaSsAZ`{k!Xd9{WmFn z;NZ)?quWN?x^7B!iog0%!hkDpi+)L*%bqAx^+0a*bJVeF(2zPmje!E&36s*%%PlJE zqZ1^GqAo<_7QX!ZF zxlY{7O?Mf16!SH`;P&juu@R;ADY0jxLK49Q4Sd zSicGk57vuVa?={&Xl2J)1&NAn6qK*v4qn#k+LVYB!(rMJBg7q`em!9vX6a-dEKTR7 zeaG+ad)tx`u35U6*l(8c>U?>0eNig$Yi8IdPFWMw?)A@|-wa}#KtD(Ja?!<(4+>>u zV!~Cf1)MZft!J$X?l9OiKIo6@g|b>6Rd5Zr)&2MkGP(iP2GBP_&`9mV*5B%Uj&y|@ z#?4NIahBTU95M?T_1*BsIiJ$nXE7>8yjY>fW!f zf^>tlba!`mBi$$<-3?OG-6h>6Al)V1-AH$r()Dhh@B5qaKOE*B?z8u~Vy(}z7@e>g zzcbU7+-9Jo1MhI!tyafk*rs0p1cy(iK!DquP8`^yzFQ_8aH@YLxZj5Kcm7v;(?-QP zo*1<;^MHQEyUuQEH>7147xcb&)cw-SE&c!4z+2KY6{Y@*(bP|dJk&g1vT*Slyd*u| zl6OH$oh#I*SYk5Fg7dqq$N~cg=#x|L01P2aBIuo(2$^GXR< z@Sm7BPxxIFPN8LXB!2zI5pi*^4DLX;BIVGGJ7xN*%#02ZTh8ja0_Q&J-#-~r)!{PV z@Q_S8RM@6~w|2+N1ZyP0Df9O*pR_*@;hL7RmEnd8x~U>dj+-;uzhNAlCogPr`MwSu zpSXxwgsHc<@@TW%wVnY~p-T26lSch+C$be6Q&{>U)Ub0ba>2SSE|GvFUSH42JO?!M z0K~sO5Zf(9-Q?mN`10IMcnMGt)ehEyoIW?aL5ts0e=_s3hAU5ro4>CnZT&Sj6Lisk z+EmewO5*zXbd|Y#zyKzef&OY%w|J=ST2LE&FDy*KpqBZFON2lA)+0@Zsxh&G4X|6_~&A|t89^B zgTMv3juuLL-`?~Gdxfd$9(LijSfY@98R2^4ee0{3W(oXx6#BP4FezVZ$&?XQ`5 zb(Kg@z6!#31OT56 z!Q1PMA(Pj&dyrc}EYf`tp_cpye{k0NTXSOwuO<)9ry`+}fwHog=bw7tQ!M+f84baF zKmq@}_5=^<=;bCKCU!nf%!jNUp-hvQq^!3v8^_(+M}yoj$dHsBy!c4)Q*1MNS%sWh zyTS?{Mwa6ncABjUaXs-<#yEX@j&s`a#yDwdIv|LnbkWe>Ja*i3m$g<~K9?%@HQ=2C z$l8Ik9JsK7>Thh9qRl2+zoQ={w)bi0Qqgz=hu6B)4uD=R>!z9HiTg~rI>$vhfyKyw zN^L-Lc8VM0)w}oiCbz)UF2@w1!LlzTF)=ZPN4p0PN;;2o7*In70W3dwdKz6$a6vT+ z1ZB+o$RV4>nt9;$7#-8JH=eau@p51Bisc`yjsQ16=HBah2b7_tCU3F=y32qdZ`Dym zo?eVB3e^m}-_#HRA(H?*J$J`OEMpHeBZxEnXC*X$Yu?HMn*@OIeGgZ zyF6o&8y20mYBA!Rez0I8!4>@=D!}jSG~l7TOxDOyMM)?r6fii(Njch<`bCJSBd>lo zm(PhM+@eGI%~kA_jmq`)wfj_QR3XV}DVdbS?YN5&9E~qbEq)5^gqQ!Js}Y++vn!>w ztjf&j)%Y2?_MBwnx>v71i;;y7rvMkC)+18XZD^X=G>4#5YPoN4$airQ@z0*yrMzxT zh2O#5F$wvjiHBo+sYXRiUR!Jd-@JbDlvO-JB{b#n>HFnu*XvCEZ6l?^4WA?a;r={# zTgtwme8ryvx!TX2K2@dfps9;S;7uw#s{QBpT)Jlk|CLl{=Jho1d>daj<8JsVK-iET z9o@EM3hqdo1l7}kD(iQ^0qA~FfMq^9rfkdMzCMDZil4I?GF_zjcL81T{I@8wh?HpZ zj+IrJ#r)L&iBMu`0vRhe6q?-EOTp#c2nygoPc=r6>Bk$hg>N3E4 zR;e;zkr_`R-&DlCc#Y88Zzrx?U9`g-kQ9zzVq_s5zkI=f{DmSgrR*CPYT=yfX#KTZ z7>eQZuj1{=LNdqqnCA2g_!&rpP+pR|hC`lB0c#6}#CZFn1(2gDxZq!%1cH9w%87j4 zFg4!gFU+_$HNR#NF%MItBGDbkpF;?V2+|hR(ugKj5tXP*bIj&4xoJ!&`DsBp90M>B zpRh|Rhhq9u<#w^DC)9JxNdpSh#MGNr+4`Dfb&Qy`Nx#N0|H74$x0l3kpkH47Gb|<9 zlx=_(r!VItKKY_DR;IN(F``7GC%F*9r>G<`K~zXVu8b3dBk}dCp%mjDQWMpK3?zhRab(Dg^w46lN0jisrmbTQX zMd8xX$jjf7b{>p@9i0dNl62%TLs5U|!v;JOK;2E}vyThxeV>Gx>~`J>t);8|)!W+_ zoieHh!29ziiR6P{GoPxfMJoP~DxfW$a3c{4jEsyR)M+Ey<=;Rc^9kYi1I9#22!q^o z0_d;-8=oIwG)7*tT|vG@n|?)%MY|T{;GRyM;$pPzk2rG`02nznn#~?U$w}L5N`4zP z#75WWiLjUA0qwy*j}GAO(hUw)>&TIcz97Y%IB(geAtmc`_Ov;$tcKgOZ(|}WH3A%= zIEGD3F|zWI0-8@k4?hevPsua1StNgdf!o$&X3;9c8EsTl_=!-47u zwqad|tIC78sU6AEZ}#69d&038Dx2$vKw6D#QX%1VxM}l1tI9$~%g+Tx4_jUFius-H zXa?5(>#%3ksG3}i!}{;nNN+`8ETp@Zj}eg5dBjVVZl1>7qMcM&stx}==3UXgoU(_n z@Ix(LXh-0tN&d>IOvEQcySmrVsGnx=x!*+Rb@-|kif7v*J#)W0-;QJy6YeRma+Z< zU4+RW$8;XA)R&F57Y`&x!kksJO3&kBJjjCWfhyx-^eKvaKN6mDQL)H?K3#Ytwv%i8 zlQBLrR52#j&wGnojBm3!l?l8q?Lp_)=(0m2cw6B!oVCh5-nYcVF+QmkHO7vn#5F`! z!k5$XaQ~Aqk~dSe+y(UnTFG<}QT#LzrTK3_*_p@bRUg$t|B{ZqB@hZ*!HE-d$w49g^Gjc9-i zx8@aQ$P9@kw-P>TIAr&K#mDk)cd|naID3 zvGEBuSVNPf7r3{JY_PQb`!~Gf%LHBwnID;Y$l-Ij-3;PU#urjVul(A0sP`hSt>fjV z74!=Q!~D@58a)1dz5Dn(c|QZQlDkstZfRRtqZ@LdaBN_j6i5{^ct$xp?&S47PS~er zVq@Gh;|r-rgTe_;u9_J{%2wYHr)Q9kdb-;k_=mUNoVI{#OsNdZc3r7q?s7sD`6ANR z(|_FS)I8w(Nx5}38+nuw8et+${_@ou^~fhqnSGqC>%~4Z!a8Hm%4X_Jta3+i6?pv@ ze*XOE4sdAuR~`t^-Fiw|YNG8`bECaY6!LoBz3Qb}QuNRz+o0UYn-t>`_m=GrI?ozx~^G?|g{5z7B9h^5@~rdN;bF;3P&B^=M}X!&^E1(Tv9 zZ$&_Z#daYX_v4{MO)J1}<_fj;J)RB17UcOeXWp_|&|Cf)QZcw_{bkAwnC72){Op3@ za(fD!!dElNf))GaXIQF}%0Z@7J{GUYKRDlht(NI_NqrdkE#-JQ$Y`a}-~ta)CzEoR zW$fjEPw=I8Tsl~kLBCllsU=irx$^kZ$*LJ0o85zF%~^Qh%xI+#Pqd*y)YT(gHd*kC zsU=>E5x-*w@+6c5GdPrJ~T4;I_kt~ zS%7!nE5(0&TJh`e7XR&Uxa*~L4eG(c?QJ)152Y2ue<$975g8{u^OiR+&%bvt#7~}0 zIzH=Hr2Bu;sWkn2rqd;S#M+C|K!|?7Gf<g13&&Z z()O9R{rqwmU%&x-!x%Nzroy5u@P|Xw7n-8DiQ^IFv=Y)XXS5NS@9Z(*4xF~a>}Z)@ z8{Bj;h${NtJ0HBCDmu2Y1RuC<+wLf^);zMVX4w-|zvyo3@s~8+7%AE}5m4p1!BC*2Z)=R$I@aE@`v~kpnmwHO(opOm!-#_?PL6V1o~|HuDBCo zxW9^B&_*jV5h}D(sU9;j9A$3Rd2vZ-SDVi{j2$gQwoFOWL2SAED=&h4ve*dG-r*b&8h450Kw4a^EMtY#505HtUqKCg}J)k`DQS3Pb8q$sY~)QOu5Rv z%vM@R6FhinokQ$WDog^w4h1>^{TwLGok+yvdJZ)Irv*rCSp0_9OC&FC!44jDX??G& zaL=n!pWVyZRFn+M@b3iWbq#CH?O#O1Xk(0VY}>9dMKk#6PNE0$R4*+F8cY8j& zU{}7e*&7b{S_L6eQCkbKV*8kMn>@q!x&k7?qMk@m~~`1i)Lt) zQBGX{E)C|Py`D! z!l>U}SN8^7P>F3pMbS&6fqE3^o5jUWi+l%GX!jkbYVf&6h*nn3*#4K#2Y#Lo*ZKG^ zTs9m?_%^vHWLX(QJ761Iw}Bes6`fjE?k;`Tnf*zd$%Qji;6Ol^QSelLar63aR4irZ zqAy;#dGMo-TTI}%fBjRw-C4|b>(YJ~9!?}Z?3Ner*TjXkt&f~mR@V>SuU%n-63z?E z*I(zEQw4|$Z?oLbg)`mn%`@+hRoJxU-^?J!R3aXx3wVVke|~Mume;SD zj-JSRxu;3JkFUKwsPey#@XGd)+cfKmPjU?3^ego~e?4RuxAlhrs`u!mkRf7d{p^zK z3T35P9vC61!}eO1bKEO@-Nz#crel1+vsT@GeI6ft)+qsmQ@806Rl+ikst+bB9No9B zkPMA3F*G;b`DDPo8y|aMIW{7@-B`>R(IM~0Y1Wy7=eM)rtNmib6DwLsy`2UILYtVW z$Vz2y77eM|7;IuDBk%816&Hzi9^)I?{dN zo*>>*Tz>C|9LkB=2$85s5}EWw4Xm^t>7f0c?*~7~@ZT{0Ao*h3j8OEr4?9^$*Ddao z_K`~X?SSqO`?n@aJC?Z;6oh=DYFO#j^$@-;{GuFUq7sCu0!mqTM|!iZ>n$a+6g`26 zZ!EiYjOkm1K|cK;?N+qRFd;0q{Ry$4s;RL7Q*rJcp!rB?9cz|3E41~gtEE21iV(g3 zg0N`!yYf#U9ev0?>WK(*y?%}HT|La*2Qul%?%?S2g8B9yqi6vrKP8e1zrie?Z7sPr zeNmdVB=itnOWJlR^q_xelg}lXc$As1`_zCUuvByU~U~@5dbzA>u4giO4 zz%1nsjJMpbr}#d%-Gq%!2WWuyLluSs6H(=Ddsrqt^*Ne3m9Kx8z=OA0Ss>X4tTq)e zB(W8pTBLLl8;Pi`*@kE$>b{ywRLtl7Il1?2`~?AhU`7l{8I`r}sOS@A3u3PLu4Yug zm?*Wk_x<73{j)W%2{wu{%HY#C(VZe?RJ8$paQfBeEckTo%st>1KD@%Msc{5_ z+}hyKipw!p1k*iTvQpz{p^6}k3=}Z(_I9j)F)TL*yC|TQ09ML2edKa>u;c+Eejo+j zzxoz zZNx|O+7|zT*UgPUB+NhE*#mY6!veS4*zxm)yl70Z)68cAZ>}1Hc+#O2^`hzB0s!^a z=(ztN_;jFX|G>^F0Yd;e&3vg~;Gp}Z(G`xGG$2F>J3y7;bL51L5&te9QR_wi@)%xz zoW8!rKe{}=m7=rfX#MKXwvdbFtrv#L(l(DNxRlV8_{vW^SDwvSSz zu!x34)V|L#wWkr3rq5yL6y@oVuU#NApPwY@-(R+-{|ZTAFI=^n))NLJ7CC?gJ19i!Bk}D;*q`pl(0g#Ve<~2>ovozs7I)gF4TxRoexe^a=YJ?z3CRt5`5gi?|9tlxcm%Y zC*5GbvV?uv8u2wL_7bh%+2V?)PJ8q6jbxZaH+qATTs{e*b6KS(pd2*kCLJt=Z`OrJ zallZ2qM?Dw{^9|Krxmk6M8q`SasKY}%l-V_^G%0hn^Lz$_@{aEKNh^6$2ta*pS5K% z#PPKRhGKW}()m4-us(anW&z&xE6gt>>*;t8ta^wNdv3F4Gj^&{9bZjl{A4+mNbscz{MpA zh%qp+u(Wh_@nZ{+t&@#$fa(|==e9#X`u<311y&WNc#1iM0w&OJ_av?a)}Z%u|C6eDol~MJsg>m+`ks3Rec|e z5@>2W^-{8ekoaDO5AsYHoza@f4$#G=zp!YEy{xKal9YR37;j`*9BXfIk^*aBpD;^g`GE*JXTImm~0G@qPd#}(v>cStJ z)6kp^P$|Zd#Pi&MmR8Um%=NHb^H>BRj~6r3iqqOwEtNl8StuV!-Wkw#Jshr8O}{0N zrKQ@vwb=fEsn``1LO(?Q<=yAUDXf&VG=KxUNc;Q}1UiM}tSYYH@-j66^&@<@17`1$ z&VvL{-Ee-I%6vzgPwJ3|t7IBG7MmwFiW8*dhYGhP-D=^WL{5yEB&KbMuu>Z>?Xj@D zA;w*- zJ#+kA>nsWYx0u)p{B~!@MYSJyf0cC#mrd1TqntfKQq^c2z@Du}!(P zEt@Bhu?cK(Kh)_dB1x1%GW3YC-x+e3q`e0v*%pHco@i15-}QpggqOPMS}3c&IgCmtnVq3qIjkvZe7ojc6%k@eS??JZL3F)BU|as&L%sdJotwRa`83 zkbCI(DSG+rf8cWs)0*(^=P^isIPiFMYs)4Xm;EZAvTAx<0@?HlG^+Mzl*i;6$A#!O z8O%X+qfA2h)ZhTy*hKyRxRuk&N~Up8Vt`PfZ*5V^VSM8USKnUOJRrTRuPS?ePnf9eSJ~1Jgb+ zGQ^y_v$2-+eh^e-Zt;)wLgWVw6*+s#PuQ)H3_Qws7Sbb^lX>8vhNttmcYVZOPQStV z878k>CFpEqSq}2A4Kf1*-E*agg9Hq_miGgg$enB%WlFn>C)65|qeea!a{C)dWSSrZ zQFrr6=E1fN$2M(PFYH6h{-WA$`nfwVbex)tn^paw&(8G*JsvVzvyl=*39;zMCPDA& z)3Zcoh&{wC_&^s2L5M0$J2UBfxcAdNGaVrmcA;bKyIjz= zwDcG-&Ym6#Us>lncY1ne3lD6OS6Va&=FeW^MS~Bft1IHE{^u6%p3d z)JbRVWz%)RA>dN?(SF;4nH4aDRY7wNd-y6@& zyV5_rFp`y2y1#T|kq7U25n6P9IDHrMALS3lC7JQ_FS3WnCXP|a!YN0nC!VAaEfE$x z^FQ^Mo9x2yKr%uUdq?dUAsuQ7YhTWB_=p|EwqdAO@K3q_xpSVPJC5XQP?(`r8A{|2 zm_Q8q9;VJ+da*enq&;jaZL1pJ2oe(Ra1o*cQinvUL0zmo8i}NH@I`M-9nxr^G#5lv z)!7`gbzuy_3CA?sjjr0RU+R3b44fCl)P!Z9+|DV=++0l7-|o=&%(7aLoRXlHE)0l2 zqv^X+BALf2Do75Li=iQrjDf)M)0NtT5yC+XK#>wM_{1Uk1HUYM&Dq^QT%v?6L1zYY ztYc2ECLylLC73eP&CfK;D~Ze=GOKD1`Yb~K<@S%vqvMVW^Jd4t&@FX&B9}*NW5R=* zS>++aDVk8z%Dxg4^16Whr1LI##tEAS_q~k2kDGgfd&wR5 zt7+`n8_y(EqOQ2H5K8?7w$h;O9&MVHMVfj#P^8QTxA<5{s`6%;(%PB1kwX9EFES0b5h zEz`zK_?0y^-9Q#{baW(6X4A1&wB~ALn_5UJTxQ24a&3d-{Y!Q?it>&fyPEDbVhO)_ zkOJjbRHfRO?6?O8a6ebmL0d5s2X6O>!0c`CVROO4?+DzOIzrlGoWncVQ-7*prneH(K8uauUvKl_5# z4abBV`Tt~HgzXuJZnd1?G9<}KD^^Qjv~xy4$&%_VBkZ&AgA-^A$BUO`&sR>!sABEh2T2Kj!c<=Z^PF?cbTq zD}itB%!o`TmMDWRBi&wEa?JUM7T3se7jeCsNYt>rB_BCvh>|ZkS`v&u4$^>YJ+_st z;j{oVlsP+^ESVQZK6M^-!Fjd6eE>7=bj?V9&4`tAv0jGp0w)X}X#fSq`&c8C?YTIk zgA(~>!;D>rv925_pnQsY zEtXj80Ktg4^;n09-4W^YZ=~C*{gV9o0Du95@Q%zNhj`}$281^T?R@Dn{OstyMJ)wNm zirZ^|3e1>KI+Gl#H}awMtkck=sGnhY`MkzU6D92sk&~pH_wUEu-QAGfAK%J@!Z6&EUZJ|zV;p~Ubab08QPa}!0C*%H z+0J3x7G$lnveJXKtwbD|m{LR-WTb?D(<1jTF^&D&y@L@~H$c{Hkpf}3c1$7vNe_@S^~GdJeM%Z+}N@?|d9%+%&}e_Hlpe9TKeFhd0OEl^ecr;}`(o^4^TJmu+c z>RVSucbLVDqB}wQ3$Gx-Ew(lWj(IU>NIbUi`iEdEn_oa|)!7$BY6p;+z=d?#WH(KM z^=l57u2^d26Wi&^wp2A`3cSsFXZ~Q-hdF#5e-~j6dFxjL6JeR=#S^R2VIFUjgCv>R~g&q zr>qw&+s8u<-4=&PE}0k@Nl14}CL`K_Q~7Sw60DYa!j{6-Xvb9Wjdx?8jr)2!^ht$& zV$Pk*XXcD9=9Dfc6OGf6+|@q2BCgEr`4^ikkr(U*^#>23o-@{;plUFbiOO6F#t>tO z%Okalp-W#Pj!OObpNEr%$H>Q2qocKNj~AN{KQ`VNp~(3MwyH?NLlq!54P|_ia>d0eRJh7KQZOYi@a* zgGYN54$Tc2%4ICx4eOnn7)OmjzRInB#Ye9}2@hF^#c0SV-LkPiYMVK@8x}*?i82#r z9JhU(?VVLd{kNqr4;8mhXFlV0T%bm;f$@VAmI0@t_2M4S%Gx%^Ss|$qJ1^YK0wpl6 zV2r&y1rrRx^0jOytk_EC@$j{^4UZO>8NANlGPa+StUauLKJSTFwA<`~-CZh=RYw}P zyNboOrDgVprx2isKaHntO&CKw`T8^R_)i;O$*?4~%ZGU_-R)UM@7R}}C3XQZ`Z4H9p`oKc;Ra0$k z9SIT#z%EfMDY6(5g0tX_XG0|VLwu7_Y|~tGz_EKK7SF6behbVWK3A4OWrH$cod6Yq zw|9F&{CQ122HFSepl=~_4AP!$`bE>`SjLFK-6RQ~9+rRh_UMn86ZJB|6wQX6B9bQF z%CWpj3upm|uP?=H#xOJ~8Mrtgz2cNQj4v~TEE=h%WG{s0dj3<3@rFM2if zbCSsZxwtGWEt8Bp;(|<5gEFHVqiaKLM|aVtS2B^+h?JNouIc+4r%T+koi6PP`R!?ylP(U ztoz(uv}!_gyXMfm{dUQ+Os{RIR~9QYcR`vBFC<|>e*e@W#s4?sr@rF@m3Ob*fUg}a z2X#>#X_Ydun%_@Ob7#y@9qU?|2@;yi9g?qhl49!wSDHcy`&Lq`XCfRz2N;18u>RGU zq0UVdAG?E@p|(Ec6EDy@t~BBgug5DtS=zK^3#=&A`8Q2GQ(KFFNq*bVzJUQkb|I2 zUC=dXMr6rhY7U%()$Y-xZeuOHYI5ja(vFJBDVPuQ(9`p2vGvoCcV=V=`>ciiG3FQN z0IYsUv3x*{u<`v(z`d>du~4U&LxdwtBUR*czrRSDVf zXp&2%CifK9DkfezJ0hA{d|ey0*SLrCL`I(!NdotLvxcL(&H>@AGg}8_)eNKVK-F1F z35upeZvTo;#<|M#CH>pBeS#UD3G8_{IWm5jYcPsZ*eFw|&C!C_Tx&1SH+P*r4{yO3 zcf8T<08J@>`FWZPb`k*p50_}3p5K&pE?l-_=KB+>T+&I(?BreIQxl4#9@xQPwmN&BR~KJixddjFCSVWbyGIK{BYooSK3(%u%ni3S+VJC(c{$kXB~JhP~duwmg8n&t1>)?|3o24&6FJ$mkg8nL8@KC+uK~ zNNWwP%Htm2=+tP6cAQ<3IPrW07Z$*E#j9Cd_c|FknWAt|*mR;%GMkR2Zy$Yrp?TQ? z6H6X!yOTpT^*yHh?EmdECq>~SwS4-$Bkg_UYI}Kl_xI~%3E6t=0xo=$fxe?T?VDtT2L@%N-@>FL7Ua~FAzVk?&QA;~R^ zW2^QClnRl*xnbUOcYFz`d`I%(;@l|uvX`+#;%MM;wSFBIIgy=+&z<)eS@W}wk)s!c zCBhuGqM>H8vM@|?|0gbgAKi+{%&el>gGT6Prssz)f8sf1w5Ihr%;%Pr0uIL3+jq9l zyPS{19gnnqxDm;k>Z<)iEIcLm$*?{p?N|v&)-KB>$M;UB3FmEC=hEYtH@g`XHVJ5C|%Gn7oBi@;IW?9lCAk zcw+9e$(9RX=T?_0V>hE^rouoY$B^MFSzHbzYu0sq_q$}5+g$9Ea-MNe2>VQ;Y_|zH zjrl};99t;4|YzG8d0BSt7P1gSUoLVKN8w( z>$@(Te!~k|Q*Rr@()SF7-y8oMESOFz>u7O>d&OlxH8`ifZOxx%(y6^+Tu-h}g)&rR z@H0;3G`Nf0OdK16M{<9enp115Vic2GUe<8t1!rq0HIkw~3Ur@)S$nq^Tif~$FU{#g z1Z&Wt&zISU9saRF3~T?V1^ANwSeiu9hn(@aB$UMM%=SUNWegubD_sAJgolWfit2HW zxHLlqjnKWo*W-OiE$;Y9%vw?>(>;^B!}<0ha8Y!4Z8fw$^*2mv$CJVG%$wy6)}+&o zdN!a0;P;baX^B1h*9Ga%i|12Fi-7cEu&m#(``rKvcxUr7h=)CR^&)~~4p-Dz9d}h~;}KbCx|Ro=x&lPT z?UKk`n1X}{+7FS1!=b#KoRR=41r{A3aUEPL$}*RHMQdlT$hx5+xK}MD!7|vd0T&d| zee=1FDb6kVmEsdSbpH?tYANwT_B+}gLBygj5Th0^SI?V20!@X#GQ&^-5Uv+<#>m{q z*d<4_f!_y4h+t#)pY2PZ%%1Ryhl)~8a_L^IzwR4qh7P%35ya)|dzY6uK&PW0)$_C_ zYim~HGZ0#2iT5%aRKrzQ{I+47J5RxO-w>!zVv|2`ajl%Y9AO=Qb*!Xycvvbz%y+iR z6*cn1gk$L}`*9`J{$ZtKs87i{%dR0-HjC3F4*Y6wA9@!^?pm3{)F`1GNA+G@tVAOB zQ&Lw9I?>~JKtaS(Z~yU<^lvO3ni~K)6(4hwL?n_~bFS=1oQA zNZc-K6fchdjyvvNNXk-{SzuUEW#6xMV8(uNboLj_5FEE%bMyCkzGJ*?Xjmmt57QJU zQzniimLN&^V{6LO57U`L8qEFh=-7HYh2^$g)o(U3qFh-J53?hU-0*!TPtyIcr08~e zTJi5{)+(3)<%+T4I;(%GK8@ECvq@~keZW#6E9N4`e7KVScYa!ExQVK=?0&peVkgVg zWV=jT2~(DQ&Mxx(6ZQwgcXaU*KjSoYz>sD7!nJ=&x-#Q9zcvtn~Z z5q-Fk>6+%_*Hx!av0?(VpQ5Ji_*YY(lLPH;B0(It!W zzx(nP5tE{!8^}fWP<-vXmE=5TD+}*PL>+>0DD`DwEc4id#UosfjVHwrz-1=2>FJ3j zw~!)PB(bbRjl^ui{OX@zRq3Cgr#<=I#4wbO3R0wr2bAI`;vrQf*4>_;GqK4LDawhkkpoYbzs zqk`ldvLl88&i&t`elySZ2Xf-mo^oaAW zuKat=kN2%DV-A8O65FAAs`VaTU~Qm~A<)bCe22A4pifAS{?lPRQOaT?Pq*Mjj)+P7 z)shu8o_4o;=G|Wqj+J5wv;)4-Ke9gC@%gAZG>6eN*?M(co0pW6L&nv#E$+14tZoe@ z(wZ49v(kxGy~U$+6vYb;>7)vKH5Sd3OgruFy`}WG0BV~LGN#0Uy4=o5Fk&%5+XcYmX2;@+Kf#)t`P?2BSH``Mgtcc5Jb)< zstL3{5`()5Az0yrlL|s(C!SJ<8k(d*WFN}7&;xOv+_5y@62BjmBAZ+;8zcT8Yq65Z z7DUT~84sB>Fog?S>fxgggrSuDvEp!*wZhngLMfJN8XVpm{GW#t9fpQiMjW39IL<|b zKiNl4ez=IFBa?*HJ8?XPg9IFk8H+ktNi}A@+SQNPYedaHT0BB&7)Go@c_hQfy7AhZ z`5?$XDPDKPQOGZGjLV7*^c+n#S;ikz!qM^JZ`zyn7zD2NI@U^bw_G#3c)by!AOt`{ z?yFQxy+*i#bA4#G6d_17AVKOa?+ODjo)Lwmt1JPm6W$SC;8KWk7${T=WRpM10Kn7m z7q0C?@ZX{QFSk7e6S9aTMt8^s^tOI;#lmmZH}E<*B1OPnBU3C<+A>ol`nWdC052R1 z%y{{1 zrLhx{7byt-UaT>_JNHNan1WZrvd7@kQ;Gk{4qNTB_}dnCyxw0LHtDG7po~%L=+I!e z;Sm_b*;;LTnB%FQ(DY3NlAXZf+0az_TnTu*`9USKd`d6bI0aZy68c#71*hL%Of#N$ zal23Gzh>qhzl^VX)N48Dx@LBSNI80`Icua@_@6@IBA!X1pa@%tNwenZMY5IN;n#fr z;@Z(`af5!$SL#X{Nu?B%8C#1x8AcF9#%BQRmmLi9V#nbj10xdxJ$h{Xzmv(B`( zCP9Msn~%|xRF`u7Kl7kPJctLf0|9f5_?~yvMh>OS^?XeH7BJJZwg&n$ zaAO74o^{Zxzb92%-pL)+B>#5KKnqJO_(0%w%iR80P;~d;b9)A$`I}_+L#}x%D}+J z=fAOAn=NG^G*ALtm1whD)Y{69)U>|GRlAvRB(0mj-1}Iqipl3=EobMCYXak-n*10? zR^ofpmv^Nw)2e>dTwrG^WGyo^l|rH0Xy*$};PzdTz&oJyW^KI5(Nb#Xa)!5`l=m+| zj2cIP$wu;NQ%}cJ!%LJ-gUv-v)^h~FWU6Ag+s%xB5_GBS|4CHbrgyu$WMRdUQrTA5 zI|`y9%zE;o`TM37eFE!hEX86ScpQmsX}8CV%gN+|RDP{Bj_KI8_tI9hc9mAN4?!Oh zHlB|SW#n}~HT)fk%=FZ4Rc&z?sWT5S_s{5rTg{IQ+?ZJK*ky zQKon45&xOPWX_#c8VwlyrcaqPaVyz0b7yS;P70K5!0C72Ca|KP?9vj6;+IPWLXZqx zU6TQe`<2?VvQqB-E=EUECHFAx?i+i>sLzdifoSJ);X_SA^*!$!M3A@e^wb9TmN2sK z-@|)l88Gfyu|eJtB>}-1)yqvG!Q0(PWn2h_D2Y2`$Mn~n3yXhu0`x9ic6_`kyO}>u zGk21-V~Aa=w~T_-3 zOl>y{vT-_b{ajf@v)cMv?T^|Y32!Dg-{|-dAr#SAA{6rEZ>iBkS^K>QT=Lzz_bvla zYCHMgo1|3;jZ5!limy8}PNd5Ftnasq&(6N~jh$7EP8Xh$zI0q!O3Gj(-MAaEZI?H! zimXR44t1ITNpwm&Z)xE@K0CQMq^(d5mOSaEC54osxxTppe;}Za`b->V1dXwm!rK^5 zbj%JB9{T?2W<%#msaRcgMXSVc_oj%nXa?@#{!IMjh04p}6QZN$o#e{j#ne7cp^!Vv zU}Bc6bL>&hsj){MyWx$tr;Be#3KC~|9Y)@ngwFj~(NUxPHi`y_3_KfeiG<*^0*N{L z;_9`58R}x$aom2KAB*?~Ur8PlELVW-Z4>;SJE-06 zihS-(CGw;Ts4N^#e)pfrVF{MjVmZonyc@@AJ+5T_u_lS+V`va)^Y^JgQAvP@{t~|R zfgP%Y8|iXGmghKBu~6ga`&L7TigwIgV9Ts>c7aGCwS7alb-}j17z3pC3`<${DP>hq zQow+Pn1FF@O|P42nkOF_JvxaEaZ^)4V3PySC~RuQ%2%2XObtZ7c`H7E%%W$YM2zCGHZGl0p^m0chXXZk&? z(#)W8D7T%3plFSBgT;E0pAIM$sdUw_ePRIH8zaUTBK!}HC;>WU#BfyN%kmM?b>hWhs^ z%mgPP7ks09h`UJFw@B{F^h8$Q-RU*`XWutdWz+rkkZj>Mt50&?mvyyKirt<`Q2~+l z$XJZ}Vz;g34xRe9(lNa}io?;v0;##@emlj^gZKAPYtMVOe@8o>Z5@$U6rz%-h-vv7 zRN2vJ1J?hQsOUD`z*Pud@qp`+J=6Ps_|<94W=&kcN$}(1C%>jhCRREx5LiBroiX8` zvS!FFHnuD6jFpc)5%X0QY$CtI+FiyDpTsR7+2oQ)Cg-$W0dx#?4UM~}wFmy^b)Wkz zC8h1|Z#qRLc5ngyZyfh?C(3aFq|LVV0!q+l<2^{Ke-6~pcMo)3bq9fC@mp6tPCL15jg8nw|8)(^%IdazhJxLC+-ph!aKjL6Jl_3fC@_3~%J$DtnA<)ixLgj6 zpz)drrqNTGG@@RVl2hI+2 zJSZMq_<%hzHi`$9T1#I+wFeTXlZ@5azOVZpd2=dndqxQ_@xI=8LLwnFiw^sh!1UO% zvavmgj^W;E$M$N|0Rcpas`(@UhzYpPF|w|JQ7JOVn-S&H!51UTDMOM=1-N=62vO{( z{K`^mu0aR+8_2-zd^U*X-8chQQ=H zan^wL9Mv@&Q)I%XZvV!k>=%!0AE?{>Ial4{kLD`~4c!+iVffYOz58l!e`8C++9$k$ z75VBWsEqWROoXd|2}OD*q95;!+SfcO7K?kSF~&kfCc%F0RKbj8RuO%_eE1^x*J2#j zyC%sqL&=X(XOR0(Oy5t1i8%4=$QT6cE(~_q#!6RIz2*lTF=QIPl;xbmHQ0^bPZx1~ zD|8mudPB^&gg-)VQt=VN<~mKumnU%6vm^X|7-9_{&cM@*Cj@bro5x-2PaC zV>q7!a*?>?#W-e<_0;5--N`q7lyDau$R^MoKOgwyivIkY>#}{q=i~Yit(=TMDPsSJ zci9@=_SWz?KKRQe^e-=F?T3R25e96!x~fFtsW{cB>nx6(ma49jgI{*4S zac*lxF|hkQQog`8Td0>Itny{P;J$Dx7~CC8lh8KWZ(-i(Hg88%yWV^nfDv+iP8knZvKpe((6q&?Nk z?mT5YRbWLxOLZ#P#}HNWk<3NrAqV4O3NAlzK-&RcTS_clh?ZOyFZCvS}w{YZL-K(FJ% z?I~HVtceWZT=1m91a+h7Nsy`gCaN*$lj_>czd20Otng9M#6w+#Aw^&yYwODvPJlsB zpL_80nIzFdaf69n%uYw|9%7D8UkYmYL`#<6Kt*vqCl> z6Wux^bl6~NwL0`WbH48~ua7LUxBuH={JRc}dYiI>rT}0}h(P5$$TrR_LS#Ql;1Wdo zt(>8%4x5;|K;)q<`*Px{&L!5G{+)j%lpf|ji9bt4gfH!&j;59W1=N#;QUX;0uo+ja5`Ne~WWz@e=BG*O)>b)`AIDX4oSU!Y`0IaOyLU`;qk^N!CJ@7f(l$IC;<_*V4)qv;%@D*wN~-AtTZ zlQ}innrz#)ZM*qq^Hh^<+qN~?wkPZU^t;#p!CB!!YjyC(-miUKd_4nRbj_C7mj$Oz z>rlJi<;)luUvnu6=gt92mSlRrbY01u3(&RBwrQO5L(DW0Jsq8ETs>yMf(LBOr?|NN z4&xusSs%<(ye~8k)c3OY8%9ewn2oD8ixFRR^!@CHt*SZ)V|-tKzF!l5#Ob~7V6OR{ zb~Ik$DYFD8`$#K)a+jRkKd^ag90N&=>(G@+8s~EWn}yjM(5@w%^iy z&dEHTZ@$~SAMw4S`28F56HX^_2@uKKZu(-x)j`np;MFA;pWptxatbu#UXZ72HH#vS z5g#D8_tX6#!KNA4*NrQ9Uzy0FRJ{p1!WWe*ESJ6_BAVamj(H{0+S}9)CwT)c+j#|MX{HT+r=a zH^Xw^KOfz@@Vu^I5^=x8>D$5>U{UP3IvXVZ%#RFJ4jhOlk-&e@b)V9tE=zCI#I0XA zJ3m($2^He~ZR(-0M|KW~gzW4vjo>q6p^c=27Ss+W1te(06O9PFdIDy}*L#19<58p?O zpQ)SORI;;MsaN#3-fb-yGZ$J&{UD`OmS5$GJ2|R&aP7fDFwPpYm-o%CcfQHJ{FM2> z0VnK982S#2Ytn`);cu=oZ

hg@{DFTX}`s2Ln3|=O3+eKG%I$vgFnQAU7(I~Z@bFtVqC05$bOQS!Od=tPyNq^G$lPta8qK)#s}z0b@a^U^2H*o415UWJ;onh9LStce+mi!bDA7ow?2R{$ zhJS;H1>T;lWJNz70~Sn0ln&i2dcIrufQH1ByfSo`E1B;HArOW~8N5A0NPOdUdT&&# zz`Cv8CCeqFKxIk6IIx`{_V=Y2U4YS1KAe3T-|5Vz24Z_uw;$3LX^%i9K&0M0$UBwV zlo7gO;dBi%0zr`%?s>v74oPJtm;D%zc-lw2HtORtFu$RH0Tnxf1tYQ0IXUU5BAtJT zQHgX$Re2D7RxpsXHfhNm6?}AW$=W|9x@H+oVNbj)41$6Z55}ZJA}F*}eyCtVfYWH2 zA{v=#@6FY*j&%}zsbwN8#VB-whK-F}yQ@r6Xsos9J1!IBB3iO*yEH9`V`DZ!Fe9~Xxf97@CjmIX8DU%cw3aG-l z+P>0V%Nlro>B$b%7)Kr;wz@)#tFuV$udg0nO6I4Rb@Hb)J~I>FMe)Sa`TQ~uGrgiG zDztza?-U@LQ+Z$LCa(aah9C})b%;y~M?L0$xA%rCpPWh$dC<^ak zb+1tpSfZl82>VX$y`NHb^_URj1WY;uRE1Hm+>Kx52NaxvZz0zRFNL7ljI@p-8yZ89 zq6(c35u`%C_|B&xt!ahCLXg^K=GZwjA&?|mLW|M??`PnTDMwbercc+NhTi5D()$*f z-__;E?>Z|h7|JyQf`x=Ecjjk%BJnxUSTdc{)2xYVk{VW&C>>2PYMqusUR2Mj%#Ya7 zAi2rf$XXf>w|DNv%JnIqhjq36e3x@f*@quyccub}6*)8QoJ5rVu6 zQ$mZ`>o23%ZKP!IhMXU0?-O?j`V{~V4@IO*SYbRtj(5bK9SEoT{kLtt_gFNeq7f03 zofYwO88Zojjy`TCRUC*#snqW0HPOJCjJR_faAPObqh548=prMFp~NZH&jzwY132qM z$bw&q@rz;yr9FS>AMcyp54i3kbqCV|XN??4OrUrmk0|Zm4Tgg0Mlfx*7q#dWT(97557beft$EaFvM(m5GeUAgahx zYH-Zkpg(*HkH|MEzcZAr`+ktK2&H$ML?nQix$mBP-EPjk{>tj@#4e`wI+5Y7L3hwt zXJ_GC3&%@%ovw4`>L;*qxARg2R0cL5pl!QOhrdt`hvu&q)j7srge6Gt{?TTa|NErw ze<$4?8jlq<4|RhQc^@|TQ#0Y4ND|6vyfQ2>)(FBdAXUWp@k=r(+c9wR#|%kn6e_J^ zL3NO*<~L#@CL9Cwx1C~RWbuUpE=6Y8S&-68S|mo$d75<~6pwbWe}q7y=tnA+v?&GoWLNoWu45j)%h9-!e^g>R(ML#yxYEAo$NjCU{rqxu`@fbbE}X-vX^N7L5Rm@8nvwR}3M_(j)DWYvfi)nH=uBCn zsqWMk0`uQ3?EGCclAq{_`IpPXmMY$%ycq7$laYDs&UX)9W;#P~flKR10SN$VL&EEA zh9=_NHo4olZaH)83ecm_VRE>U@kHX_j5IN{2{-kb2%O#qU3_16v*eQ?%gV}LFW7vO zZM(F&AI^wn-fYb(x=0jg*P z#ZSNPx=RTjXNE00&Myg6Am})Jn@%%^9U~@9t~8k7u-j4DT^mZ#(UiGB=g6;s_8D3| zcph{CM$lD!A8@dB&sfoEu->xr#v;`y1Au-tEJ zao6rf*;{((-?8G>*dSJTZnt@#Gp7k4M|b`XQtZz7FNyia8GUdQpG6QNR3FUw2U2Ah zIatd=DiwA2IF)R!yLO zVlfF!nE=@e13SAIz^XF(nU#{S;UFM@Nbdha zY53(QhZlY?1*l>nJif=RfLD58NXBuy*CQ|%v<#w9Y%r{I&yL%vGa&h2q+#uK3pDfwDuV}wdFfH1dspla=?lmcm(~1 zATBT!jKMpg_^l?=_J3IbWWkU`kr5yc+r(-I^stq%#nDBg9c<_+b%gh+qovjU?-;J<@k5LM!tj~zXtrLsCWSC>(kXLt;Rc7Y>*ZG6q@jm#)SVVRe2jV0Y z^KX`&t+oB_GgJbwrYgf|Q>g9>)k1Z%Uj6#-_9g|A2Qp4kJ&#fJdr7G4iYT%BwHe=G z33=8I@DQYJI1O6W?wgQ6g@FEIHdW#9z5^+nscyoFlUE_|ZNJ0yVBzpp`+Igp0ZZ!a zVNiNYORxgYA`be^Hbbg`bs8Dp-JBD0mCe@{!_FkQ9FRDXGUhIDynI@7~J2DJI7j&>FX2<=xGuH(roNUvNV)6ypVgN|*a zEFi`ta&Ar|71fOVE3PujMEd6|*M``o&CmOL^QfYJlQ0Unl{nI9)IyEm2Go3!(68u+ z!@@?@OH0UbN5Zs*loVtfX#A)|<<6m#?cyrxpYQzj4O341JeTMk;fQoWw7uGX$uM-( z(_1g7rp0)81F1lJ-F8)fbUOArxNnh%ZqbX0xj~`H6#Yy=I)&BvlBh`I(P5fGoIX-b z;^N_d4AXnnkw*v=Er@?ga0W9e4r9S8s6KJYkb1Bh9YZWN>Xy|p{moFAu)`BSL)*SX zMgEOArwT*h`)H8qeIw!fUYAwd(GZ3fOGc?F32Q}JPiE;N(W;}oIuS(~i!DS%llrXl z$gD#`GKv-0K&NM$)Z^?wmU1enLCAig5ikQ~v$fJ-^$J{g8RdBI(8`KT|65z;AUJpk zIm@2{S!a+hB-CJ7r85R7qA1|aTsVu*1p>LRfe1`sv8Cg#3vWNHggBi&2NjS_IYzo{ z0rgL4;7VK9)g`B}=Y0t%lwo>+9F_;rU8a&3;71Ro9p^s%?<)}`u$p~l)^xiLZ^kW| zom7!>67z=tYZ85d(caJi^hyR%+np~LySQDqT(2WpuM!BIEJe@$0h;QViW0WgYg>B0 zkMysAhE%Wp>NZOW4f0$S7Xr;>MpIo(Nah^gW?Rp%bZ}HeA`&1gi9QOmt=ityQ%~fJfm}w2bV-z5{>8JBP!tK zFuufz85pT>qN9+QbN$2&G3)b$%}VpI$fL+zJZA*@JGJeCO^X#LbLXzWMdF_)&n(NG z!RhX(IGOvlsRm$g+gqs60w#`B{Vp#qYC6sxCl5WM85crIV@&tytP_bVzKzmZei-nd zV}29T#xiX=j>2s>i(;fG@HR&jQ9uKk9PfGz0fRaKBGMuiRRpC%6^@crBT3~F27@;v zx-O7uCHp1y*f|^&&jQG{A7vIarN$Xhx*rPhoS*?NVkee zB-PbkYAZXqqm^Zpiszy*Pgbyt13Yzj;CNm&(sSmP8>E9%m&n!)pXw>?YizT9(bP_^4VYdOy3U3 zLmsv`{HA!;yzZzDfp>7l;->vmQ9I3ywAl1s?}Qo$*cc0lH%buq)GBF+t$qSMn@ew? zH2_jpJ#)RLk1aw7gHRnVs&qLZh_<;!V@lLT$b%@~RDPDQcvUPL67HWZ=)i0O(Ngza zqGP?|gl&0;>{&sttZJi^4*mBQ8yV@(oqCzs^PgJylIU@864B+|9LVYxad83^QM6JN z%*MREks-pnC=y8ql2N}>i)m2AL2&?U(HK$kXC6E*E{I~<;lEswQWDgF5m;l&^rR_q z)97fISA%$V(Qje%q)Dh!0ulm58D^ESsDWP%kQ-Ui8i?3zm#hoA_a`b4xImC5KWhEM zq-ScUlrw+S`M}NztU~;R7nMbxL8MBFcZIm7Aj|lwBvSqYl4ckrjzBE6;zu(t;Qv;9 zbH{43KUlruDIAn#1h;76gg~Gk6EW#|K^|Dc)+?fMl#gGj(>6G#_s;b3cKME>gqELy z2qRG`Ro_6@@0dzF3ljXB*@6Qt{EYG6ltgKTYl(|w)FjUzt-T-hxZ|ascK}J32=Q5m zz{?bo=F=8JVeJ7H0--`8$M?S9RTEU=A>IY zTv^coIkp7W9fNXd{z#JpXQYIe*S{V~YTJQs53T^AS(@y7c@6OE>-U$-y0$u?jFf*~ ze-bi{@Jk={WUsT$`EjW}`!;QJ&y4Sd5*Rq3$TC{maaQ$u@roq>zT=(@ z%nnrTUMheffvyTgxI{uAMf8#LN;;2IQv2}8t^ctz(|1%?&I~4OIrGaV?3kg*;Gd0d zjV->rob(?%CY>K|gww~)&6k}o7zh_ErRu4JqX&>e}v8YSY{f2*gB=1NFP;0=IUoktGm(9m0|M-9I2d0gz=6K0$|{D}s(isPSg z=C68s3EG{`DFB}CkJVx&kEULQC(} z=IFm84|{oTfIt<^?r}rXb$4cWeNtA%!H`@y{h={!IIlR@wqsk^ck<+bzJ5C;=6ja; zva;Ch{lxT#Q|#3n&=vOW_gT2 zWCthr5)(MveJFmMMxEx-9@qv4^kOox!}2agZI{z0^8yK{!>J91OUH$0+8nyY^$XNR zNCCqb4Ttu%w|?LF`iTgu3GIjuE-~obG?cC>di}ECmm#wPJU{q5-Y&^t0RJulE;E+6 zy#3N(+gG-9r3kg#^3JiKEGrP*$!mBaow-aT(-w(fn!EpUB}qF@vx-Z0Ht1e`WL`*SlnWt zTGgQ6AOOf>@L-cM>8F0B?WVPVOt!5(>SuTn`ZkZ4b6gSIllykbC(QpDOTO4%Tfw<} zd$tL$Eq8YgRbaF-Wm?rk9B=qlh3@j9a(b_Ch3MS~G#WWvXuBzMsF#aU`|9u<8&}OX zaWBdr_j2Uuhy^+625}u;p^`EyDHSZ{&5~v~liRU^i6kYdC`^7h zGF9(zd`ZI(QdY@OWy~4NoJ8SWuzBpv={1&oeGiK;-L9CGaEe3|Dk-L%k%9vGA0*<( z1o4AjE6+NrxyY&<9?P(iGy0Msdk$Tpe|S~`c@)BeWUG5*M40}HmXd|$4I!p*85c%v zUQ5Tkjn(G(%yeYNeel#Yf^KoDIicbr{^AG);}rd9QLefJM;s|R27zSdnCjAbKb3h< zQWFe`Abr`|CeysCz5v`=fHLulvH5iGhIM{PWD<$?qy9^dyaQZfy@G?}!NZ?!F52G1 z$zS@As#f)s42{B=*aOb+PiUjPR`#d%DHE+)yX`5T^jaY#o_-&-s$7uc3|YH?fK$sv zsDgCPMyDno_`tBhjd+&2K730XW!^5`(H7M zU*O7Y9f4-6%Uc!9Z~8SKqkp=kFWLTEOJlRE1-f7E+=c75YWVoE4iBk{`5wQlV13@v-XA`8{dPw?9&&R< z|M30?*JAVw#>|A;r#ZaN$_%KlL}~G*eNR|rCtYa8vk>6G5cE^GqJlK}F3%2s#Z`_^ zcnqNPNE+$`j*((6BsC%}jWVwiBFD{WxB$OeqE0H$uIKP&;FY&(cH zX>_G0}7Gc@2ekD0(6B%llBlRw5O+ zKFJ9$2Zb@?Ph2c!zET8!f$@j7;=@`0mw>N@9E7Q@CE${ML6Y+v1v&-l50-mEnKcHs zT3lKOM0=yn%oWy3*ECf8W1d87l=T5O?Y3DF#J^o`b$^rv`zRVJ{83X`Z`W3%%s|1i z5p*f_E@P$0YmaYJM4Z3qSIJ^Ue@HBB&+&lI)0-a#2hdSA?hr)=0MY1~TgIS*bK&e( z6Y^6 zccq53isr61W;ahohFFGtw4cK59#WgZT3UE5FPMjS5px2%#x6c$`SdvU? zQm?OxzEqWbV;F6;w1YX_Lrjd@{f5AM`WV44VtMd3;o7#=(z|~n@VjPd&?igH@+SP` z_A7?b_3PK|_HuB&d$Xz_oNhnTp%Re^_?yfgk912T3TFuciMF}zf5&qGB4%h$@E)ON zD`-3QA8}4-s6_W~)Nqz?#vsId&I^>OuC;e&F1p#{Z^kM59a z7h6)wns6%bpL=N-G7rz-vxqc?-t+JI+H|x;CJlP5Tt&wNxbDolA^NyJ*xcaC`Q7UE zl#B(H8*13<6LHs>(yA<2Ip`{BmR27Df7h~b())Q1oe*K+1cjA}V8Hh9^wN{V1lv+y zni>+}(Tv$=yz7s3uW$>q@!+!MDjoyWTNo*&x?lv^v`Sg0!Jf-rtr1$ZD8lX$!4=R{ z6in6{7eVL#Ic0=MDEF7o>x6X$4J?$YFP%2Sp}7i4SI=}B^8=cvy-?5Ej+!FHvPcb% zsH<9{LpHD|UuF-}sF4M8L1YW0IwsgKM>ywTt;9tPsr{C)RunGVj+Wn#wBFU^f#El*j!?j>j^aLR#-wHtfT z*Ui$i%~uepH%P;Fc4dX*6PJ78wT<+|qiIUVrI&UYr0QQk@!u-6-Wcr^zH$A2-A;FZdqx1bWw&~d+em&e{5!xvKzhRb zlWpbO*1xOEt`FZtYUY1t02y_3pBhN7YMx`fz5jM?6Nz`$3FNY394ts@TJbnqZ}tcP zt`M$nu1^ z4}JuANWfA0U_>)uffuRuLDL4P|1(%txOjB-d3YdFry*r=JDJ|sHY&%fu9W^>VUI2o zZv(~+4S+#F-6}PYbtnR4-$+JjGNoGUaAZXH4WLRf7=;Tk%A9rw5rX@+;Ttheuzy>a zQJB}5s&=Lgy&SAQRApcgyp%UYivF}+ZymThT?Fb&g8QsG`(XXl9scOEy_4;A$OHZwS8EV|uw`@g!lu1+RJU+F_zA6*?bEN-92(TJ2*0{iW*q4e0T{b-YP( zyjWQ21cc|^=a-FH2PZcY=!0reT7T{_KGp{vh;~6j%Hu;cbz<<#Ql9YStu%R8h6?rU zWNViqR&-_@=&zQ}wxdoK;K{#lfDi4IqF_YGqmq&+#Isiq{8g<@e4vf0L6Rg({|dH! zqfR2R)8n$LY_V3-X;^7mmxafUY`LYpDM=N0qgG#uuKjqcY!u_lpLONLUf!VDQW7Xg zdF&MPBt*e$jJhDChUjlche_=nS{HmnM1gjwMJMPJ2zhE2p{5?<-7x>1ne#{=()}=` zr_cK+P4%CEnNbOq4mOE;Ig;10*Q%O4j0Vq-d}jv}aQ=grqV2Rt#$oD8ZVI#V68H49 z-AP3>+!J(ulZU34@yOX#eV>W;+3b_R>5CVxY?!)>_t*d5cxaI{|V`Z?=x)T_5Z0Ia1GH^l zzJvEfnI$GHIrVMd`UV)Q*vz?acz@_h`Y1SKckOlaq%dXCDYZMtYX5Z$>TnqlDb9Xb zPjqwn>DjLxu_g(p*}-{fqeN&Fc})Zn1wDQiIXkK@mD0v-G8m&F9Vw5BJrdruXf@DK zJPmx3-3t0xnF28XHJ!!aA6Gmq?>EUq-+xcv{!F;o| zZzq$8$2RH^(!*-R2Ump-K$>wcvFD(1uqvEPAx8vjk+1O~`D)Rzji(=1AKC&mL?7Ot zR?n<$pU2i$bDckC>eND8_C*OTRWtgA3rRPBEo2*AfL1{f~A7B=(%ZOT|#GF z0GafgJXSE* z!GonH@tfK_c@}yYI8$fE{czz%0fm&ah9@{hG8Ku8)}$Bg>oUJ*L1)e|TzG9Un7mbF z)=TXySIHnj9hv*s&#lv?)TB6iI75f~QFp4~Gr?CkoLt293SoY}fQ#Tf*?8LPx)%d~p!Y zL6yX1P6e40iyJaYHZA0a7B3n;jY~}Gw2rqht2G~<_@sAvW2cZn_f>}EAXsVl>RW^< znaL&mTba%jBeD!l!cjySs7;s#S?zmzyoS}A`I9(G(}CCpyYWS0Z|}1 zSePqAX$1R|GDskTGS#PkJzrm(EO_tSM%g1?nNHydqQPj`DQx*P4mXU3ww7Udjrau? z$o|#vYjxvgzC-;7GjV2Merroo|Q=sfGo@ z4TdZ0yb@&*p@zt{Oyd9Aelu4)wSmVe_EQK~Qr1zTrIeYWf}4JcDG|s$>c4>pzX%N`Ft)XMNf&(w#!H7IMz?BY4-a45Y(K_oBcq~RfMdR`o_>G2xQEk#y}Q!X!4L6#L$Y3v&DX6CIJ|MrqzPE9)C?c}eP+4vKJ# z0!oWAk+O9%n*tj8s_KS@uvq`MH=hmfTNwiHtuL(sy7+JTGj0&R<7c2Y_iN(M{PPsw z2RGL$*ZhW(OCSCxkrP~Nf4_4vU&jVGWnqocRIT1Zq>l}$I%U`mnxBU^NKaZ%gUB&LxBY&ouO zZonvmiJ4gl&~*(Dfw*eIzHd36_Bbnl+CGwJXc~qCB6O2!cAXNbh2@o%pJvgoV zEmkp+Gd|F5KJsT!M0~#o+3Z?Ljsfl$uq{!2yZM~&z@HO*CWo z>x6PrsP#Pf9gNK|7a4Vjz}m!084<6T3?K57m9^4of5S_HOJ~}oVj2;QF?YvDk+M>| zr8fYHw|jpq`DvcsZ-8a$A~eglUANc|dV4|H!^2zWn!rdv!z}OQw>$C~to#*u8zbA7 zLk}bcF192LW+NV*O=@#bmPw^yYz4|A_VTC(%WmwSDX>e8vvi(!);xh}a*D9^3!oMJ zfAupk`1N-SluVE+ev;c4DbnP|9=a3w%+LqEEU9)zSeG~y);P|PBD#2DiFZ24e?LVE znwp}LBO4pMUS3}2Hu8#`B6few2D6>cUwZ#bl8HgY9;B|fm6e!>Fb=Ai_k{-CsVZMG ztYF&@7oz_VAiI91JC6F<-nNwQV{4W@h zNXkLSHiOx+krlDOf9H#ilm*^qWIiciuckCcRa@8uSWQwss&W;z_3eSkF7FIFmcS?H zvg?62;TVF30{y=Ra~sN0)Bw^!Tq+iBtRTW72Da4gpfnwCv%kvOSmpB&D!wHd4W&x$ z^8~}{c36f#;^XunbLY8Y2c8@g2b!{q7 z+6p!=0@v>K7PYtPPkYL$nXI{-f9hQ&HVjh;ilPWM#}*YZQXFgR2h1{Jai}!@=k&XB z!0rn=ArQufm7r4G@Osh7{8-q$0`laT*b?;(<^t%!oAeC)%41VFQmhjILB{YDz!_Rd z2n+9l7teyt*@_7)l-@I)a@$jVqjraUBt&VSDt@@D&J6gXE?*3dGyaDAFO-Zwdh?WXwsu?0H)* zA^PHOZ7bR|tu*V6m2ySXWy>ta2J&DvZqB@wY8p&8QLKlU-0!8bFblaZ8rbGgRgOfb zXo&A$xBj0%X(&=K2LHwE@+!!Ce%sG_8yA zbQ9o*@OFN+LzStjfc@IdKUUrI9@P>=W!y2hy2fz(U$p;L0=Y=mO1oH0NWo@iKZeS9 zV&T#2;M(5f|3J{ZlbIZSK#@^dq^@0O2tugHI{rE#>lI|@bE;KtSFW@NX^~2YMsO)D zr!*#HqTvYK&UV-f=OvfVfb$)tMJmu`0RoZEEBH{nW)9RgagEx(6XKM_`;n;|9*6j> zY<4rYO#tuBg;v@tEN9VgVBKt!Nxk%G=Y?hZr+tLwvjRJQnUfc|I3lfHnotE_AEJ zQVSE$bU98ST2|b59jlx^C8Ou(HC;_p3-_Ol7@(gOEQHz1n{P7DYwTkllgb>e1F=B> z-s&bAaxmVY&il9p4tPR=Sr4dB1>xTkrF@H%wVV!N2Eve+>IWaJ(Yo}RrF{nXhjjpi zzi8*Qdw^i)ay0^oyP*QR{y1}&>RCUtEI+@t8KLJ9i*)gAy;~vKpZq-@Y%;u;D2nnI zH>mUP@_6@nzqk8{PS*7yKX6o`H=1mY+#H(083FiuS@Eu zaf2lae3x9V@p&^*|BRaiiyPXkgk`_?VSb|qdhDs07H0GpX09iSvj=(IKpAm`b~E`n zl_C%Sl?SLX^AZ{NaMCen%1e})aa*{a&WKXGZ z_J)cIHOKy=i&NYa5zuXZCUxisBA?s9gg)>*Dxgh{YDfYK2%j)|pJOQ!iC%zF@g0c3 z5vr*ANs8o4^a38TF@ULj!OyCFv0Y2SfK_COArNPSRDu2X@ban+YU|{sr2T_t&RbAc zR60_?h~eF7ZgoCNK~_LelH4+(zXpkXEW}v)D^YJ;%OsRlIoxSVGDi>{6xV%T`ut&+q40jp z86xmY2iUK{(1f0`Br@q{$qOKnk>^29zxPAG$*9xC47SSf?rwX(EZ`Lkn_1Fmab3X& zg_{0-_UB}C3UKm+fQ>@>@+MX9peyw$XHQ)4i6K_uap}asw|93N~edv z;`P0SL#w93(zkUo2~~6sg#)sqe(LG=klpPf{q_WUl-tbADlKi%4gji3;gL_e=UAT6 zJh)cb(tuUHqV~*P%ZSd7RY@9XWFy)fzLU+$;eYp|iTF z&r-Q&#eL)~%NWy!*Mm;yM*tx}65%5c`wnQ(0B3^Ra>_+qd~82YzOz1J6r)wMk3xrY z^o6QM?efc4D*pB-o@#jyl?fAr)136D`)YRd2usG7as-o=wx-Ji3#i(%--rtTSqQp= z6Sr(da`k~>ShEOLdp@HTO{N#NvHVDr9+3&Fov~hnKuNMtFQ2fp`PJPE)%R<0Rgz+* z0t3j{R=wSzOKP>2lxv3v$~Q~)WRPW$-EavexB4`gU_PV;dr_x{~%aUpcKmCeaq z=p8=6`a>_5U2?1w!#C+scP_ST?IZSfRj{YziEtq}k=5G$Da(z}yZH>!H$U&9^jrwe z7BR{fvh99yltCCl2x<`@&xI9$t8<2FYW?K!iq2)zFGmeu6G@!$61o?AiQM!_iw?Av zV-$xEBlvCxTt-_oj3Zr}P&`CeY*E5s3JlG}lQHE@_2Eh5bB9L?dd|>~@`Xoao|oH( znZvgmh_o{-OnFk^UH+ITd<psa4VVHU*v^KzHt&b{1VBiE!Oe~l^fHe=mhQ`haC{Yk3G$6i#0`RtuS`8$I^6hun_`lAo5Px{UvrsAthHjzZ8XmWxw_QA#lMvoo*_|3v8UrwpsfCSgqK z1tI>;K)ES~P|Bl4;`s;jv5oW*3WrID3R&R6fMYpbG@+)Aons~p$)HM}{Zz|mtP%*C zJe@l&lsYHAJUhRrZD`O4lHb_aFy+Q!PLcg1U3gUMJmcMdO~a2j5aus#!WStCbSX`lQNDlnAB95pc2Y>zC_SteBFy_GToHi^K zxNWX*_ZCyCghBLYzA;lqb?5sRyUr(!bJa8@v&nIs>_AqFzKRK% z8=9ZdMzUEP0m%M9R}Sbfw%S+X;_|Y*9*V&76#7j#zcef~FJ1~PJCC}veCE?sR~$F$ z;;y04X=hm~j7tv8C`o}ED6kFhV<0`*3;kO+9p2lDorx4AZjaNAooH%o{M<(Y77@BT zSBf;w%#^i|nAYVl=)IN}pChdPH+yFirqn|YU|Tk?SYBEJXnV1R7CgmHd=W=^FyDGs zD4VS>FS*77kd@jHdu|z_U)(FbiH_ajJ`87zI<%=zJ@^77bsV>MATvErD1k$aP&^s5 z)!%+ikPI23GhC9cM0_hl%V2el zL&n3V-=_!$v-L;`tE2F%>ooq=<99jW&L0?#rfD^}`)#+T4mLp$m7Gpl9FJV(ef$BC zu;~H$KQFJB#2s^mD)&t$)g(Fl`*G~n4mzNMt=n{p=8aMQ3+9Ujp40ISsjU0H?zx7& z{O(1$A7BOVyMMaH{2yC%xz5UXjuJ*7(*!uqkj>Tbg-Xn_7%*VPHljkU^FFM51x;wB z0g;?Ex_$`-f(d9$jc$)$@8vj5-l!W=%lnmMH+XSmpAsskLp&_!oqh=duQP?u{1DKq z9aOjTpn2mt1d=i@Rl2(XK5s>OG>{@3KxQs_JnbiczM_k4l>nb=68h5bH>>P7%ZeW4 zc21;)4v$dVqhcx^uY|}T)v|&4vWMG`x(8jIcs#Yt!>MtVqtM8|iHW%oumugjsVHhG z!C-&O++Y2JKTJ@mn{@8Sb;`K1<{G}yIt^M2mBeM zCEJ{eQ7RoAX%O=q%`k!i7Dv>OlEOkRls zO%XT&Bd70t(FBWbNM&@%-eMqb^;BY@hPc$YViuz>}U?F~+Ws z{6M#8VDF>{&Dq+--@j;ZQc~Rit~?|YnG}p8iRYM^$LYtJd4I{aei>?^bGy(b(W9HO zw#5-@trzGU^bAn*eP=qgI%Q!?^M33J0lqvcgp%$YsW8Q=8H%qC^1FJOfb9h<#8`Ip zj*p{#|GvBDNY`6?B_y(m1oIY464pp-?P#0Xu>Y%42cQ@(GfomR9rGowJhG5IH(tJ& z6WQ~`94}KA78a$XW)|vJ)jec(oUJra-yNL0akhVKcyYgs%YD8tYHExYLVF(byN=NY zrG{vi=@ZP=g{G|U{pBfpDFkzB@IoXDdUFDxvC3iq7knQ$5|4O;DrCjCzSxu$?1RI@ zkwr`W71S+P#|5Wi1;x6umUKX;2Y}fBAkh7w* zQWm!Lu(G*Y2?cWJOf?yew>qK>`(`V3&Q|I|N>VI%yB;}m7NCry^p?%cP_^<+>}QYv zg^2UPHC9hcqKM|?RH4Jt_9qQ%S1?kNf<%kip4-I%c-k-8Ku>k7L2+Ia#lkl0>j5{n>9! z57+P_q@?~1TAr^|xn}I`Nxz7EzvOWk{la1moYVFX`3^sy6QB%cQO zTlF&)7x#6iVNpXz*VM=+1CH=DRkkh+R!Ar2)OAIWNA0^S1lIRbPlep;Jjrc!R%V2KNz}};lO|BBfhfU7kcwf_3nHP^6tr} z3KPIFkO(wEq1sJfzPtrWB!BnKa{!gcU}lgN z>}(VvUrV3rvewKYY`p=tt%#aN7L8IP*p|cG=H_`S^Uy5qw7i0D_cYWOc?&kecT-G+ z=z)e-zC@WKu}qoD2qLEt+ZvhUi>d^ZQp#2)e%l`!In!X)y0jSLXwxH{|p6!qNb zGLvQ2eaFNAXhZ;kj(zjABhO{qn70O6xM59JPD(J+m%{eBkm2+?s&Q)!E?{WYMuu2x zb^xEcy8_?LKWy_%1V|dlVuw%y{8+((2FBJDHNFNC)R46CPw@oP5)t`N>AUO{1;hJJ zd$*8|Pu{Th`Q^xlWkTu5`dosk9i(Tmv;X|JtA4{xiBQbdJvOs!8c%bDKJEM6|it5 zmt;d!>w;`nm!fmre^J_$|D7pax4ivyaa`U31}m5b%?b7qeb;y2s;R*PvSi+mbls|u z)7HmMIUnzI%Yxn%X0ylF+o=|y_|6nfC4EY%DB-cnl$yqTzCsinMZ)<)XK&x+tMu_ou4ySsFj41a(XpJ}T653M4b%Tv{AsoFWO2<+GRf)1YXckUW9*8jS(=aN;!Mghb=zi4}HX{idqu zl_*lo?QopWrbTId@BR|@hs5iSjI!YH>l)o;Mn_i7%Hyz`vY~)K%ZWfuW9KA!mhWH@ z@E8p+dig?4O%0HR0+_-gQL85ZJE|H9%?6_xpK|)}dALn5^OY=``x!3Sdu5ty zQ7Ze6*g>?Du8XLor1UwGVf1jZjs{CMBv`j>3>0~Q96&BbuZzy$;9#*b6&fsLKIrw# zjBghpYBN@tCUieE{WY(TYEmi_c!9E!F)uycb?JQQC|YiFqvx3Fd+-5nT>ufPaPxAP zoi5Qa1=uZap1dWOpXRdO0|9Wuhh&r2e-z5At{E8MX)AyS{vm^FXm*y)b^Ki4(J@|- z*RIf?36!6N1{yOVD=IX)(npgX10(iiN3^u~^sKqZ-y&tmA%vx+$pA4jfJyxCS%+pU zSDTKJjm-?=*HBM`P3F_(RCRm1VBI_!e@y>Ff1zC5EAQ7)V_vqSYh@kg>|7)GuFg&J z085bdFfnk(Yr%2N>wp6UJtfpWJPuy@yvB~>AYT^V|TcVRkzncF%~R1?Qi$1 z?e8mA?RN`W+FiaGwq@VxTVP~R)sb;aml1Wb>WQqn;z!s(#D}eT+|60cW>d9RQ*>X^ zr;(oP+wd#tH?!wXQ(to>l`0ngq^28sI;H|MBVixUO@3lVP5~5=_J%>+9y{_Mq#k-A ziUIwjAgp*aNn9hdN_qW{?SQlOu9y`3x_{3+c#Ap8bWFUAvN^Fs4%*hM22Mr^4g2V< z3%JM@%Ejs}HNC(kmn=&4djZIzYZA`VrJr#9T6e7s>ODG@74A?zw)xs`Rpy+`a(y{hhEBZ zW28y;gI&cH30BI=R4|$%gS@JiD9nd#qHmWs0nJG$4*0>}CpvsjM7{^Od|HPuN$CEB zXV<~Knf{y>Np+Uh?s#l=*cB-8tZk@!usmlA=oDX=zWBKW0tk1p4P0szrO5y=%k8jA zK!&be>q?e{Vyu-&bb5B~R>$=x=l7s{_3G3q+_-y-iXjWrqGwYEaCwrS)HlSbW0bpmB zS}i{zx2857?2-*0rN~9dy0oLVsDN-QT+XZc@10Qs;1^(+{hsK63h(9Wmd9gn?_1MF z7II~E<+MY?Wl;d-w{&cnYrDvhvimO*Qwzm)Za-e$;-$*sl!y>9O?BBn=zO|TfY{0) zqo;bZhzIsa$|SLYAj2T?@l_vYOZVk&>w@46D&uU5I)2Swuze3}bdEu?Q@GLMC7EZ3 z^3f$ctu}#_-On|8-~P}c$`Z*QWzio|KD**&(!Ir4Yc_%XYf&eQ%|Q%lELa~AbDp|9 zGI>8xEi}&aRP>>BmSG@Rn<@~DC@)fu@{h!$CJM_^ed2`srXY`nk$EQxO0#oJU<;+@ z7-{=TQgaQU>ePRyXxUfRwROmgp!^{Ui-HLG#gWJ3Bl7p$7l!(XF+**V*0^1Gj?~$9d)cmAho&*yZHH_&=*Fpm=dzf8T^* z2Bb`;zCx$p@C3e6*^hrf3q@O&WJgvoQb2~d;?=~t+^uS#b-qKpjh~y{=dLlHE=$qn zz4!3bb;0ZSg}FeK|APMxrzoU7IQrk;`#5iXu&t=zmYkwY9eZNz@jQO0)HJdkpIo+t_!=q}{&cFHWiM^+&|Puy3%W&kK6Cx%;^tnAVr%?SFgi4$THVAcSG+X+JPhA(enlw zOY0V|?T~1F_py2-`~=l!U1oh`Vl+Ub{3Y-5A8q`zs3 zVdpz@)jYo%?q*m({Ee5r-on;HEd}sX*twd69v}5@eEW55QwEU`gH^=%85Jkk1+oS= zZHy2Ia`0gqz7Wc_a}QB`@=4M3PZ53KTt3#*Z|)g>LQ0s_s#Yq|Fm|wj=VMXXKst;R zwqLUx>-;(Am-TB+%szk~k^EEr9_IGe&h(t=gBNBV9%EI!WK&CEFI=pZ@iF&jU&ex+ zdZEb4BQpIMT6((-i6$iNKbJh%V!B&0LN92+Js)+qcd6+%3rgZJg_o}qdc@_!phR3N zW3~rAo$fdC`bDo}V+8vW>i!)4bQnqgeEX1TzZ5-ZL&*OleWIG>`gr7A zqIPJL5xrbkz~&Q|atR_%=_<3xi;@yD`DwuHS>_zibSFn3?+`JJH9uA@DniTNHURCe&s0jDuh(TtO>^9Yr?!tMcw4aUBr}0xPlcbkrfsgm^$Ug8Dsh@j4VCMW z%(cjQajbnuicihgEN2(ulM>GBO-!Ady9q#*q;64LC6Tu+HfQ7D=-u8XpYyVRhM*#I zStGs#Fnp_-mj8)h^89La7HPll%=oEqR&%IY;D)qdrlXE1i&CZRQY3u(4Xp=CYjR_W4e@zSapu;l>AZ|7#cws(U4Vn8^Nn)VIh1Ifa*mVvg# z!HZytNdl3J0FZ)Ps>)c5T?1y{PXky#rqY8sjuS93xd;GsRW zx-d^%XGB5G$~Q;Vn^&I`lR$?B@_2!S@#AAuKt|sO#MgoZ{wUr_C%7&gl!~5JRc{Oz zY@gw;cKDE`3xwxlSex11y|U0ZV$lnEk&sbN6Z?ror(~&-QH~tg+t7ia-=lJ`S!#W> zF&v7BH~oKIJ%>*ctUlk{qEBbMpQrl&zA}&dGuTFn$-w<9V>J$7tDh{j$BA#R{T8i& zBEyy?DCP`M!UcS;&3>zM>j#Yg3?mGcJowm1QUj3V*<)AdX2Mi+3a0MmWqOv*7o>m4 zwAi0N)0=|6rvHjI+xWcz;d8#BJ(v&~?dkc@po6+l8<9+n1j7;PWT4A4CdYxqMLqwJ z{+1ND=h|jaMtBgWm|YHZy|M_hIJp(g}A8@1imwZ(><<>b~Qvi*ZXX#cd4%IKkqNE-!^O=N1X z39?DX8KPg1MWqedICkE7;u<*OLKAkT7R#RWi%YrX!p|aj@Xa&n5UtWF(yWkJ+MgLo zi_f+1lCG-7g6UT6oh~c6wnWDzc*jI;S1SfaJXOL2d2f*SK_U2i<5sko7`PCVz^4b? zIUTOs?byQbu228K{EUXJ%9dYmQdj>^3s5IjGgGv7gh`*2cD9^SVMS!TM4W)ObI8ql zn9h#?i^+rn;^tT3#650_$F?EVi0Fi(Dk5|qf=#({l!jf z@(B9kh=BzQGs7uOGZKf!Ia|``kk{KO8;b`M-718I{3mVUk|W30T;ul$ikG^vp~%XRpl5ODC9F2Z(g8qR1F4Zqpj!kFE72c(UMM2QFvb&mON03y+V$rK~b+ zA3Dg>H}iExg@9|B@D4s`%9pqOwRpabe2}R)pwT;)nf7s^gin)sTT(8 zsT4VBRiKKy+$GD<(k|Rk%YR$TR>)f1Tr1bQ)Yo7K^KamKez$#;x1?`#@YhpmV>bO| z=3IVo{@QsW%jf3vgs@*Kv2`tfdko)iHzp6k<-5qFjFp^a<;1wOej<_-JWLsLJd2;D zoSBcc@HwAqLdGmA`b!wnv^Q4svnxuPPK_o=PHA&=e$dacy9gY3?A-DovXg20@!=8ZrDKa{%PsOy$FXMcA5aWeuOxxq*2fsYvwCndYW9bP<10GK5qB!wU zVX2Q;jj4wDsVruK)>=OGZFZ;oT=t7cNQA{XUvxna&`<-%#$uiFLig+_!>Ib-dh-!1u^3tdo9yPs`NyuIc*+nf`Z z+N$1;vK?4`hsF_YC33p0Q_*U6ig9SPzZ%iSFD3_(foukBaDWL(|Dig~Qmtu(Nv$}x z7z;u~xGHD|A%ubKobu5KtAK{W`?x!EJXWd%bTE1eKS>USD2Dx~1>6&pVy=@zy(gbB zG$dz}LZ52BRfNbG*i+a|<@dM*z^}ZwAg~HkqW~Hf>(U3-u8;% zzJj1ID_f7VFOC;k72m9^rG(EhcXMz@T_=~Nti>>G1ys#OmurLhyi2&JH8HD9R=86& zLd9ree~unR0@ILC;I61vrJ|~J$1k$C)xgj#;ygeDy%`^2m1fQ(q9J>GCVuVfjJMIB z*rE7q^-9(;_A3BhU_Mm&Rk@#`1iQ*DDrJvAujPi1fB;nj3tvidH~^)zHMrob@-#`m zXp^izNh~RW&&d3nj($A@7$dHnLBM{i#OKT zsE!f{PlXag#|#z2m&1jHe)Y?;-kf)v zv!D4B-c2ICH&h+cZBWy1Br>a0@>~X7l4{dJ>!fce%gTz1f18>Hfs*t2(+Q95N+O+A z)+BvU!U4dBoU@tx6N|8upUKOE3&zK4sAy1Lh)$*+ORaqbYa1F`+S`u>v}BEWkj&DN zW*2`Q`KxTvy~G5aBF8#nwXjA8aO8ZT(~*NgvM*qaVI9&{nq5<8xghMubV}s} znxnsC9OY#xP>P)aU)cRYKRTRp7za z_;P#{myF}BbVc}jo@*?#FLZ?}*ol)K8yQ=nKl!hRiAlD2fvB$!;lwp9jzTEC!1aSk zZTN8$-WZ2%Q!w4ru&UgWRIR3B4?EWF;H8k2ja|I!=3o>ST`LRto+;C#k` zE20qnsxOr&aMF|7d1iNDSkg~)ePn0vI%FTW<@`uk zH2{|tL%lAYWYQ4*!>;9(7?icDD52&f_xdAIiV?aGGfI4`EuI~txbLL0fEkmv@1 z61&2DeBC=cNCwSi|AsC$M?k7Jz3lvXF*O8u%bEb+FpB0+?7G1tkZvPnikuCz7GAU4 z9Lx`q_!!rmBLI}KxDz7Jf&lCB!$P$||7Z5`a@&jutRNdX?B`!$r+0BU79BQX;R7RI ze#OR_epM)~)`V8&%`H9BL6{Ji`kAfUmr48QV6vT1$UE{Ai{HS$MN}^5eH1pVv1sRp zv4dY|5d`h>U(o@d+X?#p$=V1oZY2LgV#SV_HFguo&UZy#wY|pDAa0J2ejdr6q2t7v zUoMVvh7V)hQ>vbcyYm)CybVB>&Hemn1P%@Wu40J>bD(93=ZnuMIKu%)qUZMqj6hWc zMvl0-fHxg^QcE~t9&L+nhr|PAW$C#q-Rm1iWMO&##9^L=N`S{G=P_ z;F#jUG3XWz$Ff23;iHda?8fyvpBBixQ)%-FZqk?8#>W>Z|I=hykqSD`vk+V{qrx^HGtl^MyIyZ4>^P?s7$NQ#H;zxs zF?)>bo3ok8Q)o?l*vHy1^R)-kX1u~ujv0)s?J7CbJn)sO>YPaTiF+{zFSs2n_E?`` zt=rjcIah|wYA}PI;uc*T@A{ILB&?Gl23pg*|LD^$85gNOzS4F%+1Z$y4x;1~?eL9` zj(-RE!Y%E@-)aoRv`XPZ7OgM(F0r!t+*7X)COEi+?6p{=qb!>K_6l*&YCsywo4Mro z*!!I$fax9@F@Im&`xc4E!D(Z&-y?msJ=xb2Vhe3213d(C2~WL>xrgCz9X&wmCIq08 z0yc5)Uz!z7xnWdrl`zHww0RmFt*(fp+BB@fplW-x+rk~tlJ}>6pTHaeH)r6)nd=P{ zW+2GVs&qyM~;s$ab?9t6? zwn_PGnHO!SGmjJyqC*vU8CA6cFioNZb(#0r%`Oj%HeTN$e*o$_bR z8Jb{%K=O6Zj&{MFbqDl8D^nRw!g78?TQ zlBc|~1TiAJjk0`ydV5~-xW!?vX~d{jnrJ{zrBwYaFA(IJHJq6Kh?Y;@;}>U8_OYEg zxWh>{#-|u5dTZk^9gf22Y5ER8M=^7<9$Hm)Y}7}w62&5IY+f=0kc@ytsIL#U1VpDi zlenbc`73X_T{~$%cMkmsJ%;T@AU24qDtW3xr((;K83;qvV3-p?YhmNlm3Sc~1(CHI z0J#yuu-M^}so0n26dJ!)77Y^L6uKhog^bO*dPoW7ChEtCE5kNY>AsH|i9{1o#vGMQ zA%6AO>lUvaj7Tb5WNQqf)zFd~U#-$TnY>lVGu#GJWBAVfFN6Vo(XKNeOiN#jv)9EZ zWafXfa^EX7{;c5@&0Z8_OTU-IEc>Z&d-B2iKl_Tc&RBSw^Vx@^7i-Lf{B$y7`5Xm| zrFJIQ2_}c;A;*e}%9yZz@{jnifu4^*@fYP+qq6z@5UA35zVrObsU(#yS5>^@(}gI@ zg+C-fsFkX(vT{GQcE!>_=?t@~2R2fWw02XP!?ff3`C*W`$+ux^-k)}}cUOv8^*7(&cmS;zB=>X2iT9R}i@7!Q=*XTeW4e4X$ z#{K87B!w{TgXli8=G^$A%Q%$#x!*s8mmJdJeeb;4CG0jnmKnq+k4?cK{HtoKh60FO z16)0sKF}yuR*Yn({jxJQ4NX3K?7p3GmS3cQCnQv&mVUq--ouoMCEO}W^9vnN<@EQ2 z-~5;BkW3`ejExB^EVfx@s`}<3o>wZP` zu`sQ%zAdUe(1-Qm&=Xk2#xS` zJi2yV=QygD&y(hc(WRZnLyY%b>*~0sys>-*BL2ms=&rbAWapSWyQN}5V$~}&=x`#n zL>jdW^(hJp@Xs8G2$rzu0m)-E6rCzY@P{ARf0wlm28L0!ZVNW?BV>PG*dZxnklSBD z%OyBdj*pHx@2>*Oupu_!m=6-F`E(Xlr7))R-M*z1NgSF9Pe{!deOUApr1kr0YUqrV+0Ekeslge*)I5c$DPDgPWD zpw&xwNQz3!#mNxr7iqsv%3=Bg?jnM04OA}cYw}aS)%`LDz&DiTzAhL9#ku za8BK_SR+yL2f8{^me{t9czsuP9-kS9xc|o3e-0Nbp%u4Qs@2LQ=&XCa<| z{(l3hLNOA2sMlGg{=!M4Ocx0iCnXS$Zs^JxH|B2lGRwRo z;^SeW%UEF>S&h~H@98VilZHATsR-_fo5eSQ$pjZ$e?tdVY4QPkzX*^t?Rn7+k5}im9%7vY8T0VCn@uPAEJ$)lYOX z8m~;5K>~PY2nti;lJONV4-{hY3WKGO5q<=iBihWdA%)oJ2;hh%hp&?-_`-q}32l>J zV4coU(B`+;A}6LOx3R3VDV<2a(Irxlun3y(VsXe1c*~2+M$y_7xFRdTQ&C0=Crk$S zkmUytNZAA`1Qhuuv3zq^;;cqM58f{sQ>l-}%Rxbo!;Dmg)p8@L*d(p*YY~|Y&w}KIdzMZ`?B%N`m!S$K;v4p%) zSTgcx>Hdk$Tt0EN&H&)rBV1vGp{?$PAzQV8A_PndLPYKnr5v$QO`Sxj3V#vyD?@FM zg?1@IKfOoP2sf9rTZqwaL;J6ZS6XIq;TuAQ)kP|B58o++&wq+W;(LSfg;|f)sKOi& z{9!HZ-F^GovusqlObX9*+4h47>+AlWU}QfgGV-;evhr378j1f4TZ(+hR_@E1{M{Wv<2g(xI|(e|Yb8^D6x6MKUd#5@k{ajYRy-#FHJjb3QG`i{vqDix9FuD5fOJh$?HU>RQ0kMYXxm(J+5)g^^)t*xgePH#JEg)~@!FS3bDBbETRkYNz5{zed?_ zbYksoIyCE^rTWuRv1y`_a3{o~TiG;V0vhMgps>506j|5p^yKf~vpjgR<|RwZgTXrb^K)>e{OC&Pv|26^4J%DFMh$H5B zIarLx{1o?y-^teWrD`Q7L%|uhZ)nfOXD4f86F7{uJ>LnuhyaX&t=@Z);^w73Fd>Zd zVeuP^lu`zBBx*hgU7C!SI|1o&bAjaQ=(xsdvri2zSHPOwh(c8d<0$<`QATT7*-XU)%<7nxlHsmn*EM$I6aN4mCP=x0pwm!Y;DPmU!VWi zQGQDZqtkSj#0W0vnRddDjV5Qp+a!_jbr&$Ncl^7dbdt(9BoQa1*kI86jjYpS=Sw9E z3k*JF%y@-6kR)A5o93YJRCuGZ*`RY`e;>|x(^Q~YtfW5TOc~{g9w}kC1XTW~sa~{J zqtDIG^m`m<0un8@P{&_MPjT2$%bOSS2G1qxs{BBgLdRf0q( zDLa2PMKR&$j+UdlbS5@@T_(A#a`caafk$H%;y|qq?qIhSTw-yxBgHBnvK{+=#AI4N zGiK+pnK&Y!6<$UruY$Tu6{bvNYHXa_D}#0oAdK^_qZT%d_6Csl#6OZTxi|{7af1_^ z-)EAIp@O?#Xx8;j;*N4REKS@JlPt$CMBbO)dw||T0poWhK4PyEj9{k6&bK&`gPk}( ziL!-WEIx@6mdb~D{tnaW1?>x34mDT=x_|J(2F#F02=P{{{|k1U?`?&LCp>mCWLWUB zs%EFDHI~qh=vY-^wXk^IuybR8DpTA{U4C zE6Gt*SJjq-%$AKEHC9Q(r zw!C0y!(dHn0%-Cvd!AjpRK+VwXKG;|l#km$G9ZPE*$z_Q#n{=Oe>Y{?^z`dV*zDtD zxgZ+IW&$bO3G!9Q2SCIIvvkRVs`c?6Z$?yZ)qZQ1E#jesW`tr;JaK?(P5D^8YL$OT~ZD^C34~} zeb{SKAwyq2iGLLlE>ze^mboff!RI={k)5X#3%2cYfPj&OR8*Hmy9mB>YAXC5(2S%O4++|!f2;09xB^LIM zEd!1pz<2y*I%p|Y?3*>}Zptp6@_3;pL+uou>Bl3SvEE!qOU8wW*k!rLrw z+bjInm}1_wQ^L+n-YZ6j5Ol5S#c$V-fS@Eoz5(zwpv*-^aJuM0 zB%vq<50Gn_?#BD>bv3Oe*%Vw=qkK0@uVz*g>M|q=h+^vzyQuclz)LfJ5Mom1tet2cp>l5@QBXS=20W zjPKV5!HAY?06GwL`V^2Q{K(&FF3eCeAdeP+-vSC`)Yjc){;aVvPH~=$Yq)?|dki*p zMI=YdeZ9znwE@94ef0McH?tS^k#kTDi)qzc)<>75M7z8H-+ox38%oH^0!Ey*zak8R`WPSi8HtV0$Zb)Um?o7XT zs#pGJ4k3P;7>K9cr6Q)?(QVbYSS(ln)HH z#S7NHDY1X-B;HL6C949P=@b^yP#R&^)H!*0nw%do$6}NusPO$QXxYEnlADw7G;rSx z`(dlne(~6x3iH?&*w}u9A6FyfP}7mSi6bmQ#Ljq*t?ph~^8;u7j_?(7&^0gYnM#5@ zZuvi`Bc-sj2wr0?9~0bslx4`_MQ??F`$C7)CFxe(vvHXQXG zy^s%mqH>DIs!V)jVBTNir%s)!tHGkUix@}0Ab8@Yyy1uRDPHO8BI*%?NL+?NOo+pV zpKY=>BfY@P%NeC!p$F1{+6Y4=^&#L zw?>a7jkc=f@_1jn|D`gQvB4q2`?p^C9w{cHQ!ZIayv%Cl^WG)@o=u8ZmGVD$!o|is z_jSLpI6vP&hq9~OOl_9FvtFe=ice)x9@2l>f#2H@ycwhXv^29B?I@ zKsjfgz9{cSHrbQAb!+S^*2K&K{&(SGIGo_N+bF}U#|8%3DugKwdK_Y}e`NoeJ%RYs zEizIbXxLFLh_`e04d3arJ-9}!j~>t0e^fFc0D}v2au6!7b~bm_uh<*zdc|j&m3J`NMm3t7YDk2bN3b~u z^QQssR2-*lpzbJ^l#t-Y)=90Y&p`*g$IGCYn+Fhob(9XFOK6rX<*=tsy*kOxGPbe# z=_4FB=YT~Yql^$JWhH849F!_q&>WNUFSk}Po%csHnl?MJ+|8tDwek&kbUj{q^C3T# z{@UH*ihNrcT#Hy+9EVQCNmTz`tw#o$3=R5Yy<0*+5e%UZ;TmM#mvM^%5uMG731K@e z8q)hg(X1L1pUI1sES|j!lMjIk{PXAcLq}Q04e=2422M4V!fb?Av!HP@U1rUV0W>Lo z=0Gtgl)!o?Bd3~0TQX8a4?5jP(+2$K`||?;U7Q@XKT2|`zYYd; zLk3=lRR5(?2){j;x}B}cHLfUakX&f2uKOij3+hdjXfY;E?9qLWijIp@XT+iVtU&#t zL!<96Be0YHyM4NO7MfpB+D)5xx8TB+{j`!|fA#}@W#0%)bC3z`(J;*$I|e8eQ{+EZ zv2PxHS?vT;x|(YN{Spm|gobzodQfu&3TDXu(?cKc^WB;RFt-pz@fzGRtGAc13}THP zlFxb$akH``6)#DCim<9Jfq#z(StAS3K*`4O-H7X6WF0%^BRsTHA0&{0UIEYi>-Axt z@bLZV!<+_MT8=gCGTJIth9BaqN-j7*`@vtoa!Q83LJ41f{v2#b;?lm5Ac*s) zJCsfLDMPWLAIV#X!u-0Mz=V?7j`8b}rZuL6XQPHi(^6gH1ghV9TkJ}|8|9Tjp`Q+= z%Q$ZpF6p<#iG!g%6n$shP;1!A9bQ1d8QK3K)x1Apm-@Yq%ARpWa;2p@Y56YkrD2F6 zqHS%Jlk^zCs9gHyNf&h=9ns5|FY+;|lz<9AfeteoosfP~Vq{gs=8g9FHLQ!Cd{e48l1tiZ%D5-V|t#*d0Z28^Qp zP^uDh!?b%6{u^SQeeXl*9lVi+oN>zKI_5?ZDmt9>lo^-Mz9K*!~o%&ro=uk zqT5I#z`Bk1j~u`u*t5rhr}!lI=MPse^LY(+)?uCj3Gw40$He5S75Wodf@Wxox&@rC z)dkneDUo=(UWb8V;IBe-JZ%&ut=iiLAQbyQm#QPTnpgnUsc}(;vSJW*TvKGqx@Z`7 z1(n-IYZ}SRg$f`D_0=f*y?>pc-J8m^7|ETW|2Jr(apg_=nWOdYX7E6|(^Sm!cVA=f z6L%oml9u6KT1|)a;^~fzF#fjSjMEQ#`ZW7*V4YwAYS_qhb1m8bb)PSM=8k zr+}6S^ysSQd~^%{3dAZE<0XlwG zuFF0b>(4j*LY(*$PEZ+ec=)Oma2_SNmHIdZu)C2TV{-)u+<}3K;p@`^dI~u(#iYh3 zl9t7uK^AzlsZyRi4w|lXbSM<3AVDAti;X*BS7v_cc=G!5;yNIUF%vVOW~25iyeEEa zfWM~g#^tj+6MLuo`l$9tFIsu-B}1(5anKbJpiQ0VF_r7t``rD1Q>JYI)b3@@@QrJs zMxW;2jkckI6g+iH=XscHv=g-)U3~V0*}ROPET#0v4C{$h)bH4}O3XC3B+YIdrizJK zoX|7DisJ)KkIRxNF@7sxd$+UfgSfYUalC#nxVK(8Lf&p1LR@^fSms*BlG|136m;ol`my0lw-Af2bnXtuG_>)-p zJpO{~WbFxE2eW__GQe4m#P1lm z<#B1u4FNQ2Y&!!TJtG^N$i2Nit$`+NfkTX%_HL$5*<;*)d``RGtMBv%y5#Hk(O3b& zTH{=OIMBwE{k7t4g}sVYGU<)lgbdg1H9`XvWy*D0LBx}Bas0-X$7Y0ka79*u$r{5{ z76Zo`Q6DwusXEw2t0(E_L?wN2kDG?H!}y^O@v`U47BO>1xc%dXkJ;DM(WTv3FlL9W}w|Fo|w^^8K&ES(i{`-rP+nRm8j1 zkY<~inbGTX3i4{NzFs&=#HSgK7UH*)ijIy3a>TGu(9nP#9`Qz)k{ho{d!<2J0J>0X z$&65jNgCsFfG)#Nipn~PRnY*;hzBKUH6NrlY}Z-Y_{xk=P9dB3U1dUn4{s_sNz%iEj*NOkrKqGP1R>KE9E@e;k4nI zgN*vzaeizsDbmr0d^Ke}pn`@;k%unOdaTC~!+SF`TKQc(G z1#etga}wa=IslH{KEM))CE!>wCw~>xc+jJ?P0Pp0gwiI5Z~KSlAeW8!3$ z(Z$7O7L(Qe8WWfG+tGoHTJR2kq$e6?z|bVf)Ep^;%b+TylA--kdF9rui}1T$R`9g) zah4i7E04g)^ftNQ2*ktHa*nZ>eUocFv1MBOj3C?L!V12{?-=6qIBeg zi8{eX(Wy%WDy@VN8a;+!fUOs%LRiMW zy2d?WN|`zoD2p;J9-b~vHxbwymfj>X)R4hoBu5Al=jE=Vowx4a-i2bh81nuA(In06 zDgQW~_`~hT^xBF-GiVBNQu6u7a#uY0=s`iL@a)*e+6E-o*PGAdAL-nlIq;GuS(Veq zYSjPb^c=jIMAs4HnazKKxazk&KjRYN85`xRNEJCEpvS}6^L{^^hJQJ|e@i_qw>HDx z;%kN-{p!x0+=i};ZbK1NPpKmE&baZ^*x5TXAtF)R3Nx2+1dSxg<2h{p`&Bxzk3P3H zsLG`>zLF$yDdH+Ws5r?F!i>~$laluDtny;x{i5@7E971~TX!Ep}{B0d!2gL}FoW;|=Cq$4Xyc#M-xva;maC{;|gQ z(?-v`N6YX0u5StpdS(Oep_%G30;0ozay`U~YUD`P*8OV(c$LWsvHzGElT*y(r;X|$ zhqpn#89XBO>PkPbyf64~yGFS!(YltvTBL+8~q>C31z=$ zAU}CFNyP+*utydzC5KDbX#(sA{I#b0}R;qUa!As8R&sH!#;;oPD@T`D*SSy zW!$DM-D(_6i)?!sPJ7&Ud?mk}v}4)aMNg?9rW!$Sr`wHuQX%$m1< zUv1{*D5r%hywj=N)d^0^XqP$~LR4L(28LcfrqunZ)!BJzcK6)Aq099;L-C-6;!qyR z0}bkW#Uu_qRpesR`VNgBEV(?Ox4NBgJq)R9q*aWr=WWCLzx(c&T51{SY`r3%V?B_0 zvc&DA%j%2aN-j6q(dBE=Q)5Ff@{4oFntwnRY#Mk7DbmnVRLd8t&YFI5s$-<}NnSm_$(bRQRxWO1#j82w} zBN;yL^ZfeZ%Ermxv&ZmlvDJ~p@Sz7;@P76B=I-tTk_P9~ckF&^NoIn)$GU-TT6vxT#_1?L`YtZeX_T`!@BQEJ`TSmZ ztJ5Touo*r~4R}y2gIfQgeQ8mP33Rg$GlQgNoD59O{E*dco~~NM#V(@l0TV`s2$rej z?XNbww7osq!Uo1AqgC6Q-xSN>;S$t`y{Ry{kPj81p&u_%La$(;e7beEdRM0YQbvn< zSGRLPmMiS`lSR-ea_jH9Kp|xb;2(=4vSZ!TIC zpZLf%yyT}ZGMjuyZ({kg$_vm7%HFWay*P-fU<;GVnT6X>GEylxrNCQP3q=?vahn7c zAtWpEaH-hOn=|FztI(8Gl_=@9>JSSYF=Vk{BW8zg;M)v_*2wY((MVkDkHelbsf(Up zcxb*me`b%2H;`R)M!@G5oB7E~s)rL0HTUEDHlb#A`7wnenZybc<)Rknu`4i1vPV1h z|49Kso1D@g1Sh)fbE1$P!5DX2`G2ChJ2&;dw_Vjnz5Mc}fI}sF;+TJh@_?2uzOTEfllV=F;Kgu5v;EJ7-p(A~Q|D}OfDysq>W%G?OI8&e3`~&V+k+avKr66u zNzGDM@)Iba)28N@m(zXT{}NtE>m>e30u|0Ob!aRwEl=d=BuU;)MX|_yCZK{80VMhZ zbrAbOEYWZQ3Y7YvPdVsdZ_qmI!wM*0uOlCd2d1StS4KFmsG=guhb(V50nEry&{3s9 zA8{R2U=D|A#E0+!{}!&nODV_&P$AMlon=s5UAKe@1Pg@V?(XjH?ht~zyAvE<+}$m>yABS)-C@w+4#6Gn z$yas%rl=G{%{hDRUfoZ3?b-V6wyalVO}x3$;I005J&?Jz=2l_LS8=Twft30vak9mb zA4EW3EQZGyo{T!|giS~|2eJ_uD@Gku1p-uM%MitAX|fXhN`W1d=3+r@61LSnwRTP1 zvElvUl8t?Pdqu{g3&IyCC)SX4w55UOs0ydtNE-qhwredh@9%!VN`pE@_V)HxnKlI# zd0F>I?Q&9?z8FEbw%pBGX#NGSg`?Q^4jPn+iH_&>sM_tVdvWL= zg)=Cv-SM$8R={~v#aX$+y$a{hi||%8U|Cznl39%zdrtkVJuWMdhxYA$;u~{|Ni-X< z^q&5BomQ`;Ta_-M4mEQxedEFUB4$8O(H2`NEG{wxk;L)EcBaWz(dV{aqUw!8jjMWP zwI$}XUDj#KFo*q19&12Fr+w_XCG@x~J&%pLwab+A{nB=Vy= zErBK&&IWC}F@rTLqE}&4iUs(Bir0@_F3rv+v;;DL`#x0nY#o!bPk~#>A-W|sbk(l$ z&Bws|Q>9o>f%DbUxkG9lHa_l71^`y3W9pdzf`Z9ED#~Gxx4CU7G3}CmN5dCO52=V( zYfu6CC@D~3lM`S3K|I?6M?Zw(s4lXdSPj4O_8wa4W0(Jjx9h{L<8jvmHr|Hpk8&s~ zcg+kP^Mg%9wkQNwH@Aj|Kc8aryt37lvWp5!qqAJJv^B{QA#3!zhJdF_wx{4f1zU)r z#}q67am>AILV>p~+qLGT|I`f2=A_)rBStfLu0i;|V!si;A*oF4NBkGB?G{@ep;J{e zF>BcpE-LZW9zVCN>Qz#Mr*{(@V1;0kpo z)7k18Q6m;}DrMFr8|sL&7Okl493SQ${IktY@q33F*A_HK{|BM7vZ_&am>+>GgE|BM z7wTlZazO(R9RWHrgq8HN1x$y6Tmu8-9RDL$4lR*Y31qFyeQ)*s*|J#QQ5*DoIPULj zTCRneRUk0WQDewzs?H8+k4hArJKwbr{fu!&lF>4vKi4(2&~R?VEMAtVkF<8@&(hs2 z?CD8MGk9VJ&XfU$Q`te)!(j@oT~#>{qgKQF5guQv^AHOUU(%~DUev;k8md}NGLPpo zdachnhN6%gZfT-{e_#l_#BcHU%)@Z`DJPr(aopgTVsYye5a6t;I;$=2$wFW$!z2fOs+caGpKR^SS-E+2>avjcR@Eknf@%Iiaz@vOal5rFb1P>hQ;l(V@pJl^QM~ z!Ti_EdFhcNbbfTie*wgnEd0FvvuMMQlMZi~QcC#0PpJRnG$)_Zr&JIwx(KpMI6d9# zH3>`a^v`Rw*eYpn&kQ_e^>y%jL0ntqAD$y|P{k6Kb)=7?PL$uu+G{3y3(nmX%zf&= zNq&xOf{u%vz!PDeT3+l&GYm|*S@AX$$|q8;tzl(mmv*xXd3y4k>h??p+VfZh1*ZTh z+;2u4E{a-pmOvCvcUWO{6qB-_SyCE26dIrNjyJj6eBP5lt|pz{tcyCxB2pHBA$OF2M7?c%^6L8d*BV=kR&V&Cds!X~8!)RAi03nzmSxgu4><5W|%% zS`RoypMqRH+^A;3bK137I*?1&cIG2+ze-EPh6%l+lc00`mn-~Y0{PA~K{TDfq-VYdDa%2rN7&9@V9`a~{8sHW&z z8cJ5@)Nev{W&gg&S^N18raHnci@!WGJ?QVaHjhFdcLQz!Wq;7WzV$78dlERjtuVqxJ<@)Q)^JNe<#D_(TZ8??UYT*C9 z03fhz!jr-@#QZeN2=lLYZHb}8>@=#aS#a#7Iaa%Q(Ec+m1MGE*A~|Qh&8|+O7h*Vm z_x{efq7PV34$*KJv!%%i-qCU!4lQF%6gh#{R-4@QM6_rh6XsWVII|1uXZ+8fQiF8| zMYuVg$fOKCgZIMmJ}FYykp=D_)`^x9OoYHP`i^>$^!4|na86S1Y!2u#`u@!QCdfa4 zR;p;^*<$Y14$iV3qb`g?d|RDE6v_N z`l~ePF%lBwGwJgEr}?1}a#qXxUSIi*uupb7Q*wt*OCIk00S<+1@qae9NIQM!M(^&Y z2MU7Ee}V3fN4(Z(tmznwGn4-0$iV>^p+Lul-r|W$`nM_0*Ix{GqNU2 zjA3jztT?kqd6*-O`(gI;8{!|Qz{QWZ9|U?F+Iak{s};YLqebdmLyt0n|>`F?0?L%g+s+o z%}QPtV*a_)f$LTLrULKLdq0pS-l~pb8j0o6CDbdw19by{z!n(z32?)fEm;$N4B?oJ zmNF3imbnPLrenSk)Y#Tp^q-Dk_nJDrGe^qC z*2sRs(c-Ws`NJZ_ha}F?_A8|+;yNCOSV`WSx!iniG}@!!lTYsKtcq8=cbzj*K1@MB zv2s{H$P*I_E55!+qY}k>kckcm&=n6-Xm=|CFv5*~#W0j9&N$JxSvR@OZ{ zgAd*iV->I}shU4pU>5D$7xIxMh40j{kP6!k{kOO5M%aMFhy!Motyk}Nvh}t65&EqV zf+~z1z9kt4Dp5MD>C*;1^<4^Z2Y;t**_~0LWnC8%_E%!^Ot5%eCD^pdw(v3vlm!Ll znDB9XJ;Lz~4LR}$+JF}{Dzd!~2`Gn#wX}3euUifIYNoDe>!QDZ*K$^8p%)Q6oL!rr zTv>4s?Re&?Ga*`L(l_Gp$c@{(UUdL&WyHwH0DuIg zy7Vn99m8`vJXqSi+q!c0GnY-zmqV7e&M!~*k1cW!p7+OfeLhGcUEu zU_7ihIaCB(eS=GOYoi#~k4A7UFmVlLT!F-#uHWvj#>Q)r*?lX<>2$lCQ_LGB=%H)Q zk>$z}s|JEqq|w9nWF>&rR-eP$RO`=eIfMTiVEuxfrs}?uNlE^Y^}G7MIV{>8Y{mme zPk&xzbW99?`AE#u~v zvA0o~{m0a7#9>+frd>-cuD7CaZq?Mi)m6Xe`)Iuo5adFYn%$&Td z8ljqr;$!J$l)pQXkB;zYC?+M7w5x|sDk7Z$ZQRV<9A?=K=-c`S-UJk&9grg4T@xgi z8_MAGO;=wrgWSyW@-Q3Fu?alZNl8h0kvRh`cD!R0NCdnCz&|H(UxbJRj8vuBl?d!+ zQwLI0M*CPd^FB~fW#p(K3f^hQ$QFw_7!VZ~7>~+ir_hU#7#O;qY80z!y0@oUcyNQ? zP0>`$wJ>T zawvw8c@`>eFRqLbVJt#V;kQmYCZ2B5@~H4a2rs${=L|O{jiX|-0CIj4o9e!yd_g)Z z=_vh1Lt35M!W0_1{mE$ddmZ=9BMBu{sprS0nX^tyJRN3u^?y^iRmon1d1T+!-SJUg zx*=T(A?RY83T31{Jg|V*D!11joK9=3_1N^;u0%VL&2T3%Vw?Lpt>eMf7s#a`F=F;dX{jB z5_f^sP?nl+QCJBhhLLVgo?jTN4>ov~>pP~m!$~LDP%0?G9^lNDT>E8|X z{lxO%^oDOQ7-3Yf$7=By~sBXkKdFwKjL!71}~`JTB^=hSu65M8;Y*CJ`- zX0n5*HHVaWc+4~6*SxVwdo&yngz@~t0Zo8eRkAQad?3syUED-cCHV-8cDi2rUJOkE zCltl0O5azg_>hD6SHzsW$kg4}vX=XpzAFGUxx;?u2EI|oHBu-jG!xmUr`t529Vs~j zKO79Vs1NvHCVyuKBe6oMR-DrBqo<5-w=)`H@3a#>`RMQ0O&(r3^8^b&STTYu^5ZRj zT88Tih9PV0{3=-@awLFVtLG4|ybho{6vV*MsaynV;tI5@Dbd#{9qc$!TlH(_t)C#c zV{>L$fRDw?%bU1-abXVw3yVXzDQaNANu?G zX7teTyl~v&vzDN`-+u49K~Ygy{r!>yXV!WLSKrYQbzx!Q8TJ|=LXiV=1reUG9ao}X zJL$xS(B&VQXmT5bXBPHW0~#%d#77D2<<;b=>3xH`k(S>bEM%I(N*1sJ0&mIVDeh4C zMe}0jNd2k=ghQ7byVLKl)7<{sKF|A~KQqhnNS7;KbYHUhd1M0wfCH=poXrO4wZ`VG z?iIsynQ)A|utU(l8FF+KzNEA?g|+D1Hd54$;megYLt;2+tl@L+;p~cq%m_$oY;Ii>Z5hZ-CsdGGv$A)yYpa*q{67SNI(J}pYq49C1nHU^8P!)8hlPede*3r*y6(SWnwixi zMRHR-YH3m1ZJlgnUHTGJ6SigjcUCGbBR$>F-8~fy=GozsNRC*jt2*_|*Pp4j*EieSXJ!t#HWa;F&_v0`Btw(J7O| zSQh&&(D>^f{k|-$PD?CvdxN|{^zm9lNOwNT=JT=5iYn{Ma-W=mUxf3hvAKJyc_lP2 zk+Hvl!AWpkf{{^UwJig4{8J~`diIMCDXB3I3WX>0-6zh`TLt4u)C@DJFEaU>f38g8 z8Z9mfoe2o=g4#-aVASn<0T_^+oSe8(Fa<_#DiT&g)pwRe$wrYaM zVA{<5(bNI7bZ}+`o3y=c)XvN2_FnC}Z`s%d=ct=jPhj$T_;DjNZ_7Tq?~LdGPE6%8 z@?^#WpNH->-?1!fRZP;$WdxYnlD5R?FA^5xogRU5FZA6n!ISm7!^b#t0nXl*@qP)| zrav?xjrdM-tK;Rc80*V)H7VbO)USk~nVTmnA!&f1eb5 zm|NUh8)v7}s&ZV>Bqd&)qDuvtTw`ftePRpEq9fmaoT1wS5rq)7-tC*^)iqQsNA&li zZIXh?!#qNRO&+XISKJKON>-yxgB_8>B{G|A*?T)D#QHEEXqU(%{p!4nO*UPSwxctXryp!NE z*R$HDuE*FX%@G2+yZt03J?h;~3GXlX`lUf}Ff1%2LlTl>?5Zko2sEUx#D-pesdOHU zS3@8oHnpy>(*tn3UGzn+ATVj}ut!CgS8HTsi*ZhSs4#@ANXN(LCf4SOd7W3Z z20xFXzYs+FsU30rI5w31P+qHRH&WEh=BKQ$l9FIPHy@tP{G)TtIe*}-x8@K{{nvt>On12R#Qvv%;U@uGBgQ(@{M5W1Nqg9g0H4*C|#6PO-~ay z$tLz7T@C;FUxlab=wCuUzcQqa+s!tspi>|cna5TYCvmE@8DUeZv}py*%v@#qRDxfs z?BdP@V)Uw;dd~HL zL%^fCy?<_wwX*Via2=eO#DgASE7B@gtzBL{v9$#4QftuEHw6K|IIvZlSzMGbFd+J8 zF7j}jS2_NrTCPlw*&LK5eI3UHAiRNP-Fo{;2AvFh&E*UHWcx06gnr80N$YgEe}v6o z;Yi8s@yCCsFSRfe-(d?DdKjC6-N9)k}4)go>Z@^wf+qySx<0 zR-OnZC51YFjki)4z5jVlZI{?Jw1SS2l9#fF^+cYihqm7iqUC(F_tp(*2x`&c4-urP z6w}G37NQ}DWB#}m;4Dq8zcZqpBhCqQnRJr>v~Rwov)=8Jb?JB6@p@Y-H0X}s&-~AK z3DkEavxNBMPRYUo$$-Mzo;bU;7Mj)8+gp)DWaT(A60rhmb0?>Wf9>CImmdLZt@d-a zWj;(2U*$2rc>bqMF_?&&IfsoQy3$~V00jjF zyb$XEIH9Z?MgXvCSIprZGzmkR-Kq`19v6uz*K`x-eNd&Aoh0Efw6G`vIq!eLV$$Dx zd)Tr7{G2H%6$R6>&VyjUTmR+BN7QU}V`H#fjf&g#h#1JGnT?N7kMRlV3i+^waqntH zK@0c_M4zw9)T{1n?tOmvQIbz$wQxfGc~Uay3Cu%z5zEHKHomdu@pu&U&5|QiJ?)2M z6b}&Uv52-^lYIcDm__z)i*J-B*EQq7@94a{WJhTq+t}75P5-O0HSJ)IHQ!F$MlpZ8nQ%vO*%dSa^L@% zQs{k{$m!<#E5W4J{Ol*5J9)Hv3JQ^5{69WrHuFZg+)S+ZOv^EK4a`pqMlGvpXgjs! z+MV0H|3cE&mx>@8j;(8I8|b*qF4WNbevTipw}$8T!@WAC{S9Fda^rsnKtQpKD3X6q z?HaNq77fT!3$Qn~^r$LgO02gzI5MZHBHK7XiHFkWh0u;m;Z7Y8ou91Mi6MzJsi?;7 zc)7n`NdOcQ_fk9T)BdIygYqb|C8WN+0RhHN-(3Ia4x&2#(lRn8f7cA_@B3^&5VR-dNuE=Ox~*$>c@u)eRkz?&q7MbOyd5 z;A1PsY`*E+g=9!_dO4iF<@;Rb*7w2ViSxO4e3Lv5lcVQ5yw_c!H?*9fu55mn%99ge7aR&Qc51WPUsua=aDlRkDb#A8`fL=Z5;QQji z<9>pkyj%sJMG&A%902lW^LeQ48UOZi?C)|82z10lF1q2+sgwa}nU0*3EN|l}wqHIW zAOt%HmDeu)n>F_6Fhp@~2AO)Kl?>qd)?gwS8|+(J^Y}Q`X8Ea+)K?Z&fNx&ZX1?IP zPz#Zqro55@i=bazak1IZ@Gwq~OIiq63s(dIFVF%kEvNF|YJZW$3?bJX_VeJgg`l{q z;cwfJRS0YeqTN3>w`}!DBRTCtlTSC7S3mr3e#lSDH)`wc0}09^?dlTtOx`?~>h>`p zmXgM(XKLse?)!3owX*#ipT{S?=Awoi_hfr;cF0AIOHU|@eL2_Zi>{{bK|fFy(fKn0 zSaCMg)%60UFl!kp?i>Svfg}&evL#7L@bUdHMMMwcqgo*l6J80+(=rW1s{on>Sct6h~oWn}6N? z_MXtX<(KsUye3W->8fg$nn<{p%1!Wt&5n<-IUpIvcihVdUin3Rjg3iAu=g$irRm`Cpx3FMe%JAa1?$_nWBq&QETbKHaH_F~ zisv8)hin7V&_OUH+i(|v$n(lOKyz~`R4?)dS#t$ zSfO{44FRlUY6Sk}VHaQewf+aO3k3$&R{r5Pkd|}Gm*3vc;c($@oqo|VW{CTuInLT5 zz=?$KajE2J_ey(MlWUg3L#wwTzm-WTq(_=Jz1_~4T791|;{cq5n$^nyU-aqa0bavs z)cViY)KQOEWU%jNRwe0gp9q4{!^@3ih~j7&E4d3|DRAK+yTn(C8)rc%aE00NO?fWZZg;P?>LV~Ae@R&zC{i@nO$*30)Of9B! z_cyzo&Z1Se8sr71;)pWvBuM}Z=7jt-vyhNf;pVSR<*B6cak}9AxsIf8-ZdF~4#FlR zLG_|B90v%xLC9XQbI&+hkZvrnx{{QV0(blJ0cBnPatRiIUJHEd5?wHUO*4=a+qZmn z!fyn=tz*}$-ItY}nY=<4S!n8zw`B%4&A2x=H=q4}71j`KDyqtAGZ=hoOAV5l1r$@J zL6j@C_`EQrHiaebN4yPlhB8ZySNf5o7ut#z{aUJpahM|Zgt~v`??W2&FSzTI3FDsd zKP|6iymP~<)v7Z(J0WsUNt{VPZ8Y3Y!W7B(QRR4ZM4~D$?_EtEY;$1fA*|3?ABJmG zrtB%aanEKPJkw*_jTK~SH_PQKOP{0{i%e}=ke!^}AF15w^U!hA>SZRWBI6luxaqmM z$FR{OX1Z_aVvTb{T}KunLDH2cB^xDTfdCC`A872(*QlH=c zfA1?~_YjPvFC{r)n0kfhjqYhYDM4;jzmb=zh{lO-ozrq6Z)ziJac0(8~_Ghl_cgV+aO6 zb8~YE@u$b|JClvd?S?dG<~JxPhUNd?3-G%UAe*Jo{rCyoBAQ-PSzRd>eU<5&TStSm zsqzu#WF?&gEh`6MF4;Ubd(A<|o$~M92dfI0<)6_gzC*5An=WxftvV1p(Kq*l0{bu| zvaAm}O+WzqkeP+2Tjr}O$oB-l`kd>lw*<)+bSc#W_Te@72t$5p^gO9Q#@@;Y?g zVg9H!@I7J+eR<{qROle6H{Kn`6phC6i547h>B3pS${tw$@^CzBI16}9G44`eTs$r} zfB!?W{rU3?(y7tTQhxyEty)N@TEp|Sy7Bc7?AD=_&@&2`!)8%F84MvMF*NtX zRobIT9S^t8VUAa?bQ`)F)siT3{Z6opV_9`1TO5JeE4Yq2Wt`vrh$S>MjIbNz zaNl}1vv|6AztQo}jH}aXzkd*;BQBDR`*lfvKX{dHzDHHKJN@u)0@O2pg zFr+*?CxpnrWaV<3?>?`K+&m%{tRueEzQ7{qwX1u%=pKI@aL_p)OsMVgURwz;d=J;8 zjg*7pL~wCKZ{Y43ncn=Fbou&Z;Jkf)BR&}}%Ba*gS{dG?EF?7$p?G9yV$?WX?D=5+3S^!bj{FZ0uXqEv(veMwoH>{NVtD`im_^CMBWpa21oqW%k zmP>=g03u%+wNc7Cfg#FXiA09Fso??gRuj2=XC*qKAA8L?vF>g0yTn@)Fnq)sJLgKB zg+*_5{kCqd=+&X&Fw2%d!9YmKByJ&3h^`L?_I-u??vE^;x`G5zsyLJ^u4m>DaD3%* zjjKC3d3t~N{GYL2{}Od86>5-O?mOu*u^0wd3-1R+Qt(WxC1lN!MjIChH#F7tR|@&X zL}3YA^r50( z>&=#GjVr1I3UE^n>rthMB-2*uy$3u&*W(7;z+4op2?mRPasY%W)^tI6!%LNrEnXiyK`pf5cw%?YSzj{D+y!6 zoU0VD>N#_EnmEhlYoQUxl4_(@08M-je{*`Ck^JA5{U?DD3$9s8vt>-&9v)%&`|S-- z`QUQ6xqSv|Jw7=ywH*fNll-GSFApEFCd08R$5s4A_BPg~%j!^=IAVDjw7?nlZ|D+w znityce?s^oo}DK(yMa4dm|y*p;lqV>yr;UsooGE2=VU={m~ro`V@qt`L7 zn82!c94wFTC2ro8o|Cn|4)SXjY>>)c0=84P9A!FJZ?xBT007 zmd&{I^h_uW8x~&130*f~aQFD1$T4GO(}>w_GgT$zU`2Z8`bnc2Z{(R2*}C~-1+Y~K zFARCx#E5;)W=I`CD{!_Xb$SRLa>8i^A9gT;^d7heXq6+U85Qr!+H zT)K-FPEkMmNbh}u8)X89#3s}dO1N4GlmwX6kL~{b&1da&z|D58`Z|s3tE9zRON5%L z{i)T3*^4LPD1$V4idW48Iv!IlsU8$R-owOx(R;)^BF1_ELWj5<=j(`=P^$O)`qpcNBml zEZbsWgx`s%(9q7maT!lc4?W}sw1w7^y2sSSkME-fFs6-D%ogM#cN*1O7Uv%|p=A!n$Y?Hl+QRTRqcnFAo@W z+K@+Krsa*3D}an=s%lt~W;O8+8?xsP!)Iw1fl{ zzz#ONvVy&MLJO>k!5|)OJnWK~uo)Q23%5(5@+N}6oX@*dofZWgrii*H%Lb|N`-cfq zu+EFER$Qh6dpG_WcGtB!4FSEwC<&e%+zCMn^72xkAU!^h*^OeCeS6o4W;;8jK<&!ZozBk6@13(j@Otm%zlP=OF&&XXA(bW>zWq`M|knA(hTD~FQ9(`Ci z#PpS;GY?>6dwqqRRYmAXo>#=rcp@#D^38T0h7pO8Y?M{L7;wARj0NbCb-KYbo>F#r zYbs%}brf*FrT5nn#0r>Yml8R`XP%!kr*|g~ZS2}Yt7}Zl#e|FhJ8uupXJyrC=pu-z z*Z3l^8q8WZT;>dI^s8*cR?mW@H!-qgYRNfP!MdPwTMGl`!lu3f-8D>X7&lbS#@aE|FIDA%>h60{Kvhwmoe{(=s{sN zTC;ZiE5=QSE^^AaegyEMY3fxqaCZby%y;I+k(vv|U#(IvO?aq!d$Zy%oil-b#^F*9 zH3M|Nf}GxfCZAXnov|CPSQGn=_C7p^&b}9{O{zoBF=8g@=9KTL2UyhmvMZ#c#uaV@ z>C8x1@ClHS`=qe37l#AoXtsE3HA6wh?z)9aW|Y8ISTID^rRAaLP zt0|$!7k}bNv3}w|DO*3GTUT;v>h0)jXFWP#ydGDVyT?Y3;QSxMK4ShQX0I~fb#*0M z?9D#ObxAe#Z28v=cVqCta)zQ-0*n(1na6M$3QQ z^b|5G>1*k=go;^HN5jKojUbope@gJ)^Kt0^_Y5od5D=~R{^a|{OF{QZqNqw;1v$T4 zBEZdJ#F&_5&(C6so(gD7L5yJB{0!mm$8^2BQ#n2!y0Ue@Tm!sP0^?FdJ|m|>zA;<| z{yAAcYEd3P^`nZjhDwtb5g+cM@3+9@iL*8m&Edj8C@#z`7-9oy9ffz9RjmL!c#TT8 z_k)hDeLnxIwAaT)BB0qX_LRK6O4#regeUc-4n>rwH~r|(IMCsKdyC$W+Ez23Q96Az zv?y1oETqLE=RG7}b_kL$z>cq5ExY*_$9tV6dP4!!=b~9l>Q&)MO_N@K5_CZIk^M1Y zMcbp%I0)PW+W=(UxLnkNh7C|5NayO|K~^03d3G{7qI?|pDdwM?Ronf_dI_{6k6lL^ zCnvC)&4I~r!3z>_ftOOiE1qr%TW9}2Oj5CG`k2#ltFQ&9W*|?m^l>ZpzWni;_pj7g zqfw$*UG)#1C9>iM^^$i{9eRpe)y*3yR!pj1xDmWJHz)_VFg}g9fZN^ps1$Q2n#5=+ zzX#Qe4JC{v@B?Pxi;WJD+bJec+8PWTG;nsdFSC{AkW0AX8Xs`Yfsq^*b(%+K-%Q6S z`ewl9Z@!hi#*?Ll;sZ5O=#T5&Zb=%AB8sB34QM9ooP+5`cIllKW(A!!8WN9)KmEdqP zYtjOHnf}h-vLwA8WZJ1=adO1?khaJi{7!idZU6oLQlr~n65*UUt5R0s(F|m5S1BUh zXpfPqMZ=@tXmMx;f(HsBl98h@?Wca%JBP0f=ROcWKrlailFP5hpba1>kmgC3h~Z7E z)&0lk!xy;b?$Yz+9t~&SMPyB&91xxsCW<>>?YkGv_30WrnS<1~AUq4;{u_a>a}K2< zJyW(l5ELH%p^ZZngOZUHX5#OiWD>2LoHJ znfZAIY{``t1(5F0P3N8$l(m4aX`(Y3-iCz^XQ~D1yaeQbILg1P>c6euG{>FMcz&cFc3hUlZdL=)30rxBuHLPM?V<}JXha8pw2g&Dq|IAYW0SwVMAVwF`O zD8pjJRq%~hreeI7$c;4UXKP^V(lbj+LtnE&9`uCpos@cV|AnDuaTvk@ucQmj~ z?-;O17R$D< z0e%1wngBURthh08hAvIEI2frNz%HP41GE#MZK=kfCwGP=%dHvE$hbA#eav6>uuzgg z_qiXqj!9DGNj#-*4a+nBZibBUpInz)FC=r}P~rN+fnGMC;uLT%5f!UO0ML}ih6YGc zNB?WVYT-}qsnRKNRSH@{_)wHJ%^$uEW0nGxTDoiFZ%3^Tt%-2ex-A>a5bfW(7HgNt z-#F&Q{HiHJ8lxK)8Ox0%t6qH0ZH%iR@W=C8OVdiH`6ut~)|L(0ByHD76BCPzF$CM4 zGw`?^ELYhAr(%OuL*|?-ETJRfVJ4urzGdWO?E*`RVnAK9TN|F~Y&k`&9*ueTzu#<< ziQS#Jc?C&{Z@O)@$pjEX{0HfvT(DqXXkRXMLfE*Gqm}hW*+^tOxnyh6BNAuco+aQb zZM~tYRwNz&89u)4vR|c4bVJM20{`NrUm$j3tY1V`wJ{Be&eYsAG%ODQ@_r-`yClxe zqKxfFe&BvQwfWP^}kPBBQh>Rl41Cznj4 z+40cYO9ET>{CsQCZ3Z$Q4P7UvMkSfl?2>{cW=iM^uTAgnrqnOJ_d!NeF8WATH_LbI zRQARO7&V8iyqrS-^RLjv1U*uM_dHg`(D;|}&YC$@iRV4o;^)C%qtLK0pa32iiNk=R z+H7jSfARajdLjvVr~CBnsz^wYf64&bQeRJg z^c-A%ykGt^k(}aX`R>lX_?0G!S!wF%?7lwT04Sa}3>_UEpF_SaBXj#H(U6PyJXSR$ z#!H}47R7#}t#9tUBbg3bR?IW982{WotoH#vC_py9SFPj0d1u9mv!w+HSlBk>t#`P@ zji)iXygj?c@_*p}gcR*SWgR2ko%!`?aN(9(DpnxqTCYEr{3!Tyz9d|ns%N_IORjN~ zrm4GE`gQ^e=Q5V2o=%~@12c!f?+7e?Q)}y0>W`O~WCHfD)g`0Ts`R+jBq)dF=S1H+ zl<}7bo%H@=CXXg{uE`py)#A;hR~qkl%%5J*#mN=A;usnlCf2B+IDR z;(WZ_ZLDHqP#eWSS^7m&JivQ&&%c$DcopFUHLinB87(0Z(I5w2qQS#~g8acvFR1zF zER5(z37}VG3waRs;3>OC|L89KYFJrHp}lHooB*CLDJ)kuLDS=`?v5S zxykYWI82rbMTQTv-HvC?o54Mok{&+W0Fq}7?M?mH{iv~7O0(aI3b84?)65%X{=jmF z;Pdivfw#=HNuNiJtHkO;j~1Vx?KiUzpYL=4cY6$<$7LYr(@*xyyJn7y&92|TrfI~J z2j2>DTO2o^J(gX?*J)~!`_j4U*JUI`Z8p&0sed>SMFo^ya!Rh8nId#3&X8*;!_y(0 zX21Pa^Sk{fv_A$qwKPy2NpTFhW2CD5+dzPR@G5RX8Y7Mib1Vx5PZTUTsTg*1$jHLV zIX3FhIi*I1f!AD+=(hP=)>3}$+HvpE1>gTkV#@Ct{sx$Lpix#MFi48nvx|%}8h7Fb zVyvMEQpHp*7kF;^tY&bhT|Ce6s4~)V*m{!sZ`J6=Uj}-IG?q_$NA|G)K?H<=&3wcg zK;-s+;UwDy2+bbdztzH!N?fTBNKw<$31xm6A)X4o98W);>o_>Qjk&4+8iB`>!qe{` z(9zxp3*QzBDdLdBQgjv$aog=9wE3l#EpG2*D3#f%gM8jehn0L{$fgPQ|Kvl-Pbv~; zFYpPm93(RG;JsR`Z@415*mz1L&@KcgjakgGskA`s&!WPPPcw6}OiirQ1CrAIPU&Hr z=N)dV!(^kYKMID#UU69E#sG#4*|A9X$e0@xM`ssVqWGaTOk{8znH;aGqrthK7fbYbIvw zyiU9|nM@9Q0cfhVy(PCP) zT>a-$aT<1odSZCgW*@G+6y?wmxWj|#NtdvW*>?$iZ1fDO`Vag~^nd-SK&S(#T195% z+^ZNcV&=oFuU~%X&~0~(co6!T7dP!=`wO}lN2eH8_ylYe@s)eE28)Kmlgh#6#qH|* zz`k6X=V8uP{YS5wyrPor&8M-WfQ0_Ns9JT}e`6!CExms7*?~LW5nPX76DwK>5b~}K zH)4Q&m3_c<#0d2*r)%qJ@0;w1%I@$XILDybBS-LXP_3;g%u+Bd6}x-)1+q!y9M;s; ze?LnXBh!k0kr!v94YW(^@1vpa9EGz`!UFXK^^{6>EELc|iTPEtZU%FUYylo~G#kjH4}=n6<_Mjk~!x>D-6UVlHi{>1y&DTJksceSstZ?I2n zmnOuJXj!Df7!?jn&mt`loc;33JaTdf*umejeMdH(3Jt}=i z)tQ5YtdBVDheU&zctBh)nNlCaj)$*!ezY^6B@W%vOMa_6qqa@|$X=|60MxGT$f1fQ zCnr~%>l3QQRPMIU)+1(0r^UVM8DhRTr2~&Rt}}EP)I3lo^T;w~&^ZQM`E4YHD*sP_ zGXOHYj;ZaL>I;HxY5s1N!<#+mWAs^Pk=8=!DH*W2 zu&}ca{5^srBP%>xZKey{!3VZg%G9=%H&?ROh#Ya4@Lxw>$$xVsIPJ{cCdErNsI3yu z10z=0rQgG}=LP5xwJD5hdoYnrt27}+mIg=;4FLIi1_lG`Qi za>GeE9$x5e`n|LQ%W@r)D0$H1z)xzgO#J1X>BF*QI;G?jSy`(>0R;Frg_Grs)jVJ`D5}tlORTOPSzn^s5g8(>)o<7dedf^Vbht<$r8p8 zjio#6=3P87Uu8wt&1uX|CK6d}>CCb@cKJtv6rE@{z(+O(8YzyCts)1Fjf>*Gp60}k z3go`A&D`nGGcrMg&&c=yLbU!1X?x}}dae!iJ@sxl=Y zcN9eFK}FEHYM*b}3`SAJfR5`E@&%0v7iz9MbO#eWe|R5lZ6|M_FS(OIyLONORV#b_AyMlctpP-jhB%GEl%_cpt|fQ8)$OyE zKqU{+_3b1 z((=h%TyEL6t)*qxmTlW7+x$NL@cj#_=bY~6eqZnFx?b^ak*Ol_$yOefks_-av5~3? zigC+E>3OUNy5+*I2xoK^p-!*>EYnT8UnH!91#g9%VBW;j$PakfeSLj{ZbaV2Rvq<_ z$S)C5NLR@*sCnFFMIUw{uR`MyW#^idW2S3?-J8S5$28UcyzxOtB0VW_7?h z@I(u=nx^95%2tsH!|V7)Rx0Eh@-NRkabew$j(c~Pu6IaPv`Fyivr58SElhKlK=*MK zitxHg@=9yv->TR5A^Y5uIdn_h3VHnkj}sRw(-@D19navP>@Y_R@DL?#l132=jRA*` zFo3HeaSTGbosgZpqABczBBjW*O&&d@ym3dYN@1IvP#O}3{~K&j_U~{A{;cy&(5~}^ zZ!Ej@Z@b5x!j7BiKiI#H0+-GFQBVn@G~pOl0>8H-)=ldYFrPoUqA}=7N(Q;^&L(p^ z>@bt%i%C@&LAq+^y|}M7`=3vI-uTwMj)42AQ5}DTx*#=~asL>{MM>`~bm*xP z&a8Px)r6^uxOA{lWzXRuui3cgP~_2-yn@o#R3d-nLWtVoMQDqKok*Q-_#}Rc04-pDQ8!g!Ur@E#*rgh)yOz64fF<5 ztUaxs-5+yY8br&P|S<0&W0R*X93S0Bc6J{(sS; z>O}Olf0_mkqLmyEXFS?2sMfc}JFaXxUi)N%f`)_Ee`FH1io}JZf@czjWXucd>d5ks z4tHUnVC3BW1{Y;0&8XaVd$F4zmN?elRz03?_1E%dtyRnBgrz_FSRF;a&;|UJgf@u&B=5#yV7u_p+UXI0 zx5n42UN76M%A$gzBJP7)V63Q_%D1OWF#ive2-paD0_U1ei)U!{1&gVvnS08Gcem6n znDL!={EKJQCt>!USx7FohE1Zdyhb5I?+5o`;W)vhqN@jCv!|^?X*EtNh zaMiTc4BanKYnywnuTP$_AMt0m_0_Ql~$vD#;ad>IueF? z5D*b-f1U~U^;7*I;Hu@Usq<1U%krFDLZ=r|8iyv#g$}^u6l=OLi2TwBdD!Xt_PU#S zXMbr@)E8W0!*Af|96NW(nt8(!G?5S{5%%Ecs~rhdpe9W*0g@DEEky+3lJfh~cbyxj zUTS`5B%ibuC;tc%9oA0;`kh2z#nrJQ#;I$^8T6504LAJy`>9Iij}Yc*sZl2)p?Fm? zUDS#z@K8Rvs&1H13u0pj`b*};QZrl>=FmYClEMz4s)!yLk~8u^fmFz(zG&RTq895( z8%<1$G$4*D=LL@!>r#SJk!xYtmkRtQa>N5bP^A;9xrLJ9Bfg2cXnc&wSKlil{q(K; zJID*A3OIm&Y~aXd=H>63?Cz&NrUk|H<#Mhm7ldnqqsAsDK~>qFnUSNEnT}k4&$eJC zXdtQ%(Bi0|{k$a`ag&9m4^`z-HA5~j9uD7NY89Dg-QQs+7hQOa(}lVG;zBOLI4 zGqCZ>Y}Re1#t4^0TB)aF2>~8|>^OwDnoQ6G*I0Zy)kjGaH|mI)jSaj{P1TtqiR7xd zQn#SY03L`KSqeSyvTj0!)YR1kN6cYk`lAQ?plnAxY;QrkX@qI zW|j!MYUP|5rkqJi;+l}JbJVSNHNty72Bx?A7K<{$*W5vW#_=vn>O`g5qo6fkWnp8* zzxR#r`$Q$Mvi$CwEEF~}UOiarS$wZkDb%DDOk&~c(BSQ}$Wf-=a${`P8QVclin71Q zM3ds(ad7Km-sr1HuUoDti0aYvcSdRGTe+_)uDEUY6}z<&w+SYJMdYtJ!zav{w zh>eZSqF&)n)70!qcWG6qPzT%CL|WDl&COxeYiF9)8h$OS$00HV?3xeP8IxlU7N1p*osKdpU#N`9O6hHz6boL@;YF19(zK1VB zW1qKhh2Bv!lLwAv842nmOTG@ViqQl4@PF1mr{FmgeUE^p5q}~ov*YAS1m*yLldSUp z%4(+;HFovg+~}2?uD#Zui@#PxcFFSz_e|#Z-w$^_BLjT6q9H|JU-Ri}65{@_z|li2 zY(_of*IUA8moEYFTfY{QipHb!?Vl=oQ0_l`xx+GFcrGN7&JC=k$QMC5uZLtq0Ppcz zq$5PAaMczyP-}Neafa$9=Zs6$+9$1O`bGQ(%e@X^?=s>v;CQvambbM?Jq^;*G z^&!(rf+iLRA69LDkrDoBZpcGm!nRPr2%x8@2lm6%$-~yx*2>ga52rsnhik_LmzP67 zgo7w!qv$l-I=g@@F3_4d?z0ORU&V84*82WC%S9F@f{R=edfytD<{9G(-PIv&Y)jlB;Y`pvwGTnTIn$^axaCD8zNf^Jn{;K4= zP63afA^5@q8Phee0TX_RP>5h{w1RQ)lJ&iBZzpi}WYllzdAld}83o1^zP0;3t_Pvl zE1$htJMG@Uo0hZ13DV=$#$cd~3SjWKM->)+mfQ^Hc{1Xz68}ay(h*hH7Y!988MN5y zL+oI_fM+e<5(<_OleDKKOx6)pV$A0HBN^L;TKVl>O9au7Kb``X0tcUPmkBt;^&Xe5 zidGqoD+ukEAIds`w zsS~WP%g85bsJ1DTIS;#Wy!t7n-1g2zvfTDazD}b{j~|>El%G$P8ZOz<+Um5ARr%b~ zdEZRylaM8644^xIgpPIdW@T@Ov8mYBoYJHr6az2qvwrz})(k8|oZ)fU(E`XzZ*kMbiuT2m%w`cVrN-qTDwimEgPvCsi2_uv>)$Pj zQ|5-3&guce7WXH1-e0sQEb1S|vfpTWCynqv(6N(4>cD-x{zzJQjP}P5`2>94Gu&{! zPLzBUi;<{?w}1TlR5SJ8E|Z@}_1_SGLLi}CA%4kHi#nC|D2W(Q3>i!kzoZFFXzG0# zkzSZTP{zVKM16)oT}d-@bo95DN=wqQxsskMYHm;4LbsEL*R>QCdAv_mFWSko2^V^#K#YXUQZ=&8F~MK z=F7xWjyTNdv3=~ONmc=n`DN7M9v1>KpI3mt6S{&Oz(f>cir|n_vstj8{+rtAE}}`5 zq+X%tB1Qp&E_D0Wg^$qk`*#@Dq=+A4l0pVTy*zsw>KYHd<33|R;lhPZvTbpC#FOGU zLKpMqCjiA3U_$0!KxR*v3`|8+Q)sd@+tf4q8cOY^?YoXh4{-j>Y(Um|YUp?0`^QZmA(RfKWN{2wY$u?oL@We@Q5nI@ zAxh+jLxLnP9(Ldi$Pp!PWef9uSS|@dm=34{WI?8dXUB1s_5Y8biB8 zP|;9962`8{|8Qd(g~*qQhKqSBWipKj(Eg(OhSaL9=WEE+6D!} zT}o#do;<3c@xzT1E_c^k1>-a~_q0nQ>RKvOC!Z(uopHjYIg8^=+0?Gq4X#8p^E62I&RKR=rZnR&l9 z*n8qmMBeKt7}rFs{nn%fatTWx3tJt<6h2k6$mhf5Pv9)-jPH|m#SBOyQbIt-uHIhX zh&nx!+T*)W@!eNHI%cro*v=OhTwzLO;5q$GFgpyUBPxg=lpL3nLV6zUmL(7&kh(J^ zQzPu}jYV=BCsC*Z2S`!(&QQf*|pq-QhPW;^jzzcAuF zw;BnTmB?T1P+m&CSR*1v!u;x}&n+Sl1!k;mnni?ZeZ)%UJ-9$7Z?d_*E`-ZFSCbO znTqLukwZk|%RruU2t(pURcl6hqAwPJ+=tKr55tKkZhePG? zzI0&hB&o|u*5+T|7Xr6i=EPjq$UQ7zH@&&?5Wdo6AFnu1b?d-I6rB1nQdg~4<@j`K zQ;;w+Hs-K1ppxZvs|B=mHM}+XV6gGl0H@()`g&XM!xi>ox%x#L!Ty3%vAmPsO1Gdp z&wi~kEh@}^4Gj%Vo)4^@52JP|X=$8&E9K?Q==eDX=GFngj-i46B^>+5~jS3nwR11Oap zzVm64?f+gpzUXwghL(oHscWda`@~01%nFzM5CGP*lUc{B_EM4M&A+ zMa0YEVA9yRl9uLXnF>Ad2yy>t;uIg++E^AWR@hf*ivXF#O^V|OaFX(#MQV4?gq~P7 zsBqs!{@S%{vVfI8;zy=b)=wGdj=Xl2-4p${G~(BDsSJS^762ej{VB@HzP(LF9B8r{ z({!WyPow{;3RRobDcWXy#lWyM5#F40nIKKDhpwuv=eQDg#i9C)q}s7EQw_Z`N6YTw zbotETU_}C0W0S4HW|57u*_@v1@$l=G!lP(Yn&G$vF36B@{*m2GSs5B-B=&L*!q#_< zt;%%$koq%cT{Fgouk^R(c}i+(5x?5M3!Oa0UusJkUJg{E*TJ;7Yn+Z0uZ{&`W9R|0 zD(k-;_pY_NNd6Lk)aF7g*zQn9x4U{_W3i*KT?}9y37a-D-P3P%?MpzPgY9nDH7%EAhAl zz#!}RMn*@0n^h`6dHgbdzt0nL*ZPs3f$`$jZoNpoES3o)q>Flxqx1uVQGRCXm(Jzg z(@Z`9HkYVfVY-vS9h@^Ji{8$bKrMb^2VL!%8&Siy*W0QK@FICU_UPYt7HfRiPgaze zCYi*wWsZQV)%JWzx6%U=+M9Q32_&kdzg zL+HpXi1kb&Ko;cq)8VzyE>x3f&>4+PZ2k^a)IR~X9{_y*sj2A-CeAW-Hws!j;AypG z#TP1bso`jak_?hcA;1TBtO;{i!jAul63LfrY8J6_j4#plkBX*OxLk1@zZxp5Ql(9n ziI~EDpdUQ46bcp@SX#ovX3{NasqY2gWcm4EbN2VDze0)MvkZCEM&{mIdLLbb#X9d7Y74ou8unwY}MG zyM7_Pii`8wM2;O+V26}l1KNN7770;tDT6~0U$BoGj%SLyy=iLTSA`3mFG=(=!SoXS zh=Vl&QuhSt;D*Q8OgYPls)@)&vp`x_;N^(t^C)imS|VwVpI%)Wf*s10H%liLb~0$@w@)r3z`JrNQl2@ ze@{xxSccjQ^0}}?M&H@3R2ma%@=hJO-UriUbI867YohJ+2^qOrgHMG&m7~ZcEZ<%} zkfg+EKhhq&-1pKecV~nL;MiJQ{{S2iyqSzAipd|JkePwm2^c79Yin299g`DhF)hDy zq>aLys4uf_{W|n-SUkvWxf83>$wG@sS$zgYG#{`vSa4?N#0BH96LV~KQi1n5^I|!2 zLjQfIw~zvno~{&Gr~43}y#40aW0CWj@HDN`42(8GitFrXH5#ucK>+^mM@B|~9~;R= z;*+Q%T;QQ>5$E}-5n|^*1&qi{WJ=Kh7#d{4k>8g_2e@Ol~D3+D01dM*Y%8*on}dFURI5Kt~^Ys(!{De3H zGFaJOsHeM=LRETZKCaR0YiN(VQ5LSobkW?NA%NpmIqG;j^2v53#jH$=N@|SRo)}-<>G~s1?KPdt8D=Ywoo7>>pD6+1eo-O$a*lKyP$Fhqx>6PinRH(5+ zK=JwF@HQVWkF8IcnGTu?yJY#1L{LZyyBBM-&jES(;;^hLjpLe|UjnJf)YKJd;AwW; zrsT3+?Q@22it0iB2=uy+o-A`I<8@K@-0(Y%34dT%)8Fw&7TjrFf4fVNq%~f6Q2R%= z)%>xLLIkDS)hE{D=UE&R0vlWX=UJQDmbQVX;R)K4 zUM%fY@d~D3rIcw9fz}7nW}OD2H(aKlncrZfp(&|mfVSGRjwhnoQCe9G9VxUx$-#uk zh{#p40%n-Q?6>P=4B5(1ESD`WE?FBMn7&$N}bejCcPBzC?~PkJ&VvAB>Q4G`xUB?0||>%xTQ}SgEm0cP!;^? z2cB>GEmKxmk2w{>35Iq)nWGCpJ8;)-!RsD=;E9S6XDrLqtvE6na1IslcLt04Fe9Pi3O0W1l+S=CeI-r~CBpen~dB znf*bCE#;3ScJ!Z71b1HwWrx~xow}sfQAkhEhiZE3&)qkd=IkdGl)&pB3+kV=Ns5x- za|)moBCfe^BO(!SzbBB%^2soUFbCl1Oa5cANv8bPsM5JZ2^Oaz5PCKYi#TyB8p)Pny8Hl) zOx?q~$|}ZE?9M;r%#jaX50Pi&S}HK9(ZQ$Y007QCU!-ig(37sH>|3Hnd_*=JO!FOPPi&X6Bfd zcfcnQ0Hv>@--ctd$MH;o&Eh_3V!Xq~y1%LN>7~lfkbsTfW(eXDhfT+x6Gf+ur>aw_ z0xG`bF@mHIHZ=7_X%b1iQW_3-Bq(7hhM9W!_4-OsAQffmWoz|EUDR<0tuCs9X*Gp;;reC0D5)urOCM^gT zBycXPoJt>qk7Yhj1;1?WNf0Y#9+>}E1XL${IHI>EN&P4_b7^c&fKeIsW0G<j99V_Hx`J5OE=!y=r23Boi50HT_Pp_o|+)_olJa_=dNRqNZ~}e zN&r3Ar~kWMyF}}1ktTJ~{t0bl`#kkXT*4m-g&}C!$5$>n8Z4%MlzKRy>`3Q;v`y@)rHJ)-9xczz3!sK~9 za3xY_3+OWwRGnGpqxPi%`F|s%wvTEcMEWVI<0R5vfnS@ZBz06O06uNJzW70@nhlf zlXp#(M;`;5V*5OUZ2TBnE7S1M+hvkoaJZ1?;$#YbaD9J|2wkSDR7!7|2SUzb4Pvra z@ZC$HeoQQPgD|5+Se89I0p?#{43kMv@@Rxj|(He2r%uaO<=kkr`>R znOHYQ)sXOmUi+DYC14?w?`~ z`&6?Q>G3(eKpJ!%Kpnas6k>n=Dn9w74j)nctyG>g8?sYY<#2y)n8(bnNQl)Zw(wFE zKfe%TMe9(|V^8>8IbILQk!}2P;mEG9t^r5V3B(kV{WcO7Kga>9ohQ&YX9h6I6L&F@ z1ifNJ1?_U#zfJAgbf-QL=h`R!o#o_}lO|y5kNkdB&ef2Tm72@WACP`09io_o?Wg%A zsm>YbO~lr7^#u~Bl+EmqlGRlv)dsnXiiDrBNfC}`-+7~)>9{7EojbF1bzeT%GD=nJ z7~9Sh02U53JI|LRfLsBHQD={wLu7pFrIiL$L7K4VI>Go{mFV}rzS7gQ=$`SDQ`(YW z;X}5h&EfLN$N=3#D~ed4YkvTRj0{r;I|1IDLwlvkJDpC$)?xS18S6|aXZ92{Xn09f zBpWP3mhx@Y>E%BrNVUhEEj*`CT-X$wburqfAAtCvuC9@qn!0&2uV1W5OA0NCTUL=L zX>BJVq@(PBbu}NiZHe*NO=i8Ul94E72lvkEt zY!knR05wZ&I=Fjd&xB)H4=Kq&Eo4>ut!h<|A(;f6p?OKytJjn3O}z#XUtMW)ir4uk zCi^*5T#LY#6k)~?=M#5Uw_|_Sc5kxY-a+@c-}W^O)4~lgjmd3xVJFZV4HUwQhN~K3 z{6646B3C3Iv;KXtObA$TMU5othN$A9{*hBAcggU31w!q94w1(H{FC8A{2$)DvE&+X z$qoc3>Y2(QwGzCUKolUh zqzt%rp26bg+C1%#DdMUWHeUF=Q2-)>4^XIt^ zis(iA+qnQW2C5S}u2L!WM_*pon7SOUEsCr7*}zZUKr3kv^4lwMv;8jK5Hc=fA}rKL zKHHgBTnO)E>&G`&qw{TSM+8khH7mIWiJ|!qysTHsF^utnEGT%P-Ah~Wov#N>4;v?6 z0eU+C)p32;)c}MUptlgI`fNf3ry6V}dc@jPd95fTzf}|L-e4TjWsZ}UwsB+Ug?`}H z_Au`=Jnnso?kPmV6k!jvJTFZ+X8vw5;*t99O_55+hh&<4F)?_Qh%J$KZOfTX>E1B; z_lkd;9F5QA0H<$iW_5Tj)CtMRGKpO?{%6FtY{r?(dai#2!nbn;?mQOeqR1l^7|XJG z*n};>K<^1)-E}&>2}#A{q*SdGFqX_asbW5GEd7z3Dj;nF@<;C#R)(8IK=+OtyTa7Q zEEal$Sshh^347AeH6Jg?ErO zB9Gd)tN||ETGxeDd=J5Qr0GaLA!S#qzG(V@*~cm?^5(|3JBL1f!fqOekkI7q^#!Py zFGx_b9r20)F&xeNNJ_%1r!jXn4Q%aUp$BL6uKL7mmh$A;O4n)?>)K7(unz{4Qp^_? zh+XoETH0ik*M*|QWhsc0CSIsq{=Fd2I*P-0E*Wt>_I3|4ualuGL7ResB4^rztX4vL z>($J6f8t`_wmkfpK@k|zGK|^%&V+T$s8>^x+EwM1H7cv@tVyGezl~a%f<_bfipBAC zkoRtn_gw1-pEPVyIq@;ziNv}wp+J6ruApjRK@vT9dIma66HaWS7RewYIlvb=0xeP%)? zYkqkiZ1@iTP?^km)gkiFILg$(i8k0-9tP&EFB1R#+w%Mj5rSm?Tq8vg z<)5#8Oc88us)AdLR)xLPi}GYNo2C*dSeJP^DVqb})l*I{jH1#B#qI<_?7Y5#Cnht~ z!sSdKm2Sxk^$7r(H5k_iZ6=)X6#tqCrs^R0puFM5Dfspnnxb|3W+9gZpEGWMgw0cA zE>y^a;Y%5Ppg4kb`^1y7|J3=9r#PNwcc<)SAC3({k6_t51$7OIK=R~q723oSwID$4 zFf%oMH>(0)SHP;V!`eKI-iZ34BKRD1M83U^w;kL{t(cVzXpu4RbtPHH57bcTqp3289RYkWj# zmycjmDOOv1Y)vwJj1C4}mMKrdr4=Yz)UO_>H2)EC-qarIbQbCV3NOH%ZSlSg_6hDqCc z96Y@DI%kJcV{H@&gUs_L8)|B*S4%t#S9-0C)q8{iXhsPDYIN5~5W1!C9ofVehao=% zwtwX?hnc0qq8X*L$V-dhzyNj>pq-{4P(Ao>u0Kp8VlJM~y7EW*&N-8BgV8--ZtVV4 zHw_+4n`wFd8IWM0NrY#X5Q`=uG!Oa%eL7=0bZcaG=hq?ckQ1Co+v35|vogIir* zNvBLxwhiY5$rbLAvq170;QyrgKwZvl{N@O~OU6Jz{I<~U5hWI!wYO4i23K!*S;!t+ z-h)b@N=6`q^T`|$AoESes^HMv?QJO_y9UH?&;8O^w{!ruFF+1KA&P%MJR3ak8`^{> zgGhO1u~Wv*mDg?xqM}!e522s>#XR)N+=IF?Kmdg-<%*TW!?|vn38%U%^SJW58^`EE z!=441fL~_+j_9aAj`;G^Ot97Ocn-C>k;^_HLP$8|}FhY(KO#@%7 z5^ayeHY5xqcFL(TaX4|rgPWA* z+($Mr+Q&vSgb7rYe#rBpk}~bzEArrMkEGC28u-GR(59$(@_gyIf49i+>WV|x?EClp zO|^fc-(Is_AsTO86;|`g9nn+-1o_P}5x#sU-AuZZ2e91NcqtJGhI6GyuIdjTThLX{ ztX1^cek85Br$05Gs!(IRFHV#Qc}5nF5gb3?R-26z0f*Ya?m<0?$xUT6h-p#c5H5(S z-);A1zJvo$oOf%c^=#6T9ag2!f@V_tD68eO5M{dG)}ZNE`1c}qpry^k%L{S+?qcNw zq(xxN#XVp^Cpzo!pkZgSOHz7NH;9_2{?bN!Ob!PYrZGf{*wUk*vpu2Ll6(B%zVsp$bu)1bE z;u#>;#YX1HKwr!psHLEPZK1r=Ek8mvFhs8&dzt9;kiZF0ZjqF`O8t?$0 zIfpf>C_Qli>WXPoO_;!N5*MKxrs^faFNmFt0>z>FULHu=7;CYya`g0Mq2=MA4PfQk z`Xiu#pb0_sJ(EyUaCLFg^}7Dltg=qAD419Cr*(_JZS%y4H3FqE{op56jQ6Bu&@Bro zv~kH1NOkJYC%B=za2$_D@>0l+F!Ym4si`FtB=a#H@?;eoMEZ_s5aq6UF)bOzy4{k5iGST;0*o_r23AT>tHGeq=oh zGFRaSL{$#!;)Huof0&2VDcE0|AZ+4E8pinzfH;sdf){X^5X4$mkz}nLY{#;y{HP<` z?}Igo76i?`6g;5y-%O~LT-DyzhRqsHt}nNvf8T{hNFXn-E4d4lvR*yEo+Qq;Q+Y~P z>6t@L4{h$!ZqMo-(0|r`z!Ws*XS1t=nYXtW;2M<69Nq=KYo^A=0h5y~l$3qAxVXSW z9VjTQMZ(Bb3?3a-;GE-H_-&&FK7|2t3M2?2AoN+{?t-HcO@!n27h1_H*|bG7{pHuy z?x&}34_iYGC609F{Jza6)x%whjCNS>!>`l(g-uX|Q zJf^ukQDQifPOXFh+Y9JS;*_%C7+k+hm2-EYs(RtgAY#o?zff(=2A{?F1r2yC82328u~XJWeA_{Rzivv}RzVi8KwXXTy^&b(8GuEsbt z6yLtQ=#;9Vm6#NQj=XTWNcB3~tFmB}e2YJ6^Kv)y)6H_U!~%E;X0hEGU#bJca+kg5 zmem-^b{UjM;3fXxxn@mBh}`pQKqprIN-RtfOWb;7b?G;HkV+7XXVVU9<5IkzXti_! z267Uy@()MA27Y8iWnED1EO}PurW^~U)1TW=A4m)xYFJYo?Pc?oH*oc+fzSF|qo)4% z{gLo}!~*jH)X&swc=E=|2mp>Z0J zN}PBJt&EA4Yr652Y@q{X|eYkAp8Cc0uu9Cd)YnpXK~z3H#bDI5s}+c(tcM#IM;02XY7vT791XvT8hI zDT*`xecnFQaq_kcs!&q$n2Ld&mnyUlH08?@x9#5$7R`;v&snG0onT-V;Aag7s~pu3 z#IQ((af2k9=Mj#3 z{i*3a;{BdtSUSY(h=i3P5qVlUo<1>?T2N2h}GP~6I}mx4{7wbnpFamxaG z35}~NCQ7svMFu9#Q#t)Je;Z`~QDflLM8<$X!qi~{ucbVYGJCw*=}iz>oj8Z^zV^&3 znXBW5VJ{3*hsw-C+O*0v*^?L%CB>N`VQ=hYx$SOw{esKqiEE|P8QU)=PUCN{YnWW@ z9+;4v@7X^1+EB^c^Fh1_pL$X1BBr-kq0PIF)2!b=km7V~y+|y0@N2yM>FVgj4m6cw zN8eyP70|Ma4RpT&Sud4J4Erlk;zF(8(KhEYCeZr7v;K0>nXgJyt+l#y*(+DqaM+~h z%Wd>%zd?YGi`~E@fk+GYoc*#11ivKw0{H97GlcyRgaVRY9~ zUO|zSjZLgjHHy#1?j)S|)Wcw$3nWGbUX#C`((HFUd9Wrt0R=WZ2QI$BuY!Nh!Xd{F zJocPTE6S2iMm5}|bux$jup!bdW~!;|lv-{vA5=$Xn4~33KVx5*qmj77X`5YtSI9sCYOvS= zU&4Ob&gA8%Az+3@jH#t8u}P9cL3svP8FbV$xA{-NXzTP`#XMj~8=h$vfb$Z3oAkW@ z$fB4#42ek)#r_Bl2v=j2Z8qOcsh+xR>y@Dt3nf794v^0)$*GGJj}Xl$krO=L;1-

;UZXY+nO@gEQ$K=Uh28MJ#|5dnoV<((H1A*Q|ro?~Gs> zzM8Lsp_P_B8(6xQyWU~_+5}itt7OJ2Bia@n)Bg^9!EGil@>(7c7a9jUZbCtOhpgXz zP$-@@0efXCje8BH`#b^7;}Bx}#lD*X$R)I)dFEj)X8*~en{Yj6>|fwjYFe8p33C`> zJoEFq=jIbI_^4AMAV4J_xdDt2oIru2-kjBAV|KLEw`^l%Zxxf`>cw0JWQ`}!(ji6E z#%u|**FPK0Hshn0lG%$3&syOPHJ+vdmJ?oA?T-55*_EUnvO(*U0-pPd5@*Ia>lGglPc~x%@G(}X)3NMSmY4qlc3<_{g#aDOniI}1hl+%C z4pHuiJNd-1s=aFhqhgu_wp)lNlueOVo#tU18^lLOl;@{ z+_3tw$4eoc6HLf%FF%J>9_1w%ovpP4>RIq~ zvC`KHb%v2%Gb&a%r96+SUWD%mgMK##6TG5U+XonxQh>JtC@nC{vAg8?n4Jsa@9&M| ziY0o^xHqJ+UraSH-3;OA%OMG5-p=Dt!Laqmch9p&`M7k;Lwkgc5&1JT(}yNf*eo^v zL^6u01XneUU+|@GyQv38kX4)oyl~?C@1#@zPL%F?&{;om{i{swFvF8&B8>n_434WT z=^qa=P>qT=3SHh;SHy~n|MEEi)8uaFbMjk!zEre83q$H1K0ZFs?~ui2CMao;x1nYn zp%s;Y;qXANuUNB=o=1YdfWX{WcdwkCnQ5~5>IKB1fl@%gBtY&~?jAOWg2(H8ywAd@ z(=@Pb_mcEpQpF7WLw6f>&gVz}e_HK$-+wqgn{922B3vJLh*l8#yXPo-Y zPLkX34Kh_o=lOU*1?>xj5XPCcs=LVPNc$=dol9`IkyH6oRN;Zo8Tg$)A)sT>#h_bI zP0K4-5+@5g*A4-@i-+?Wnmk+KQcY%+S-b>jh5(Le!6kdioJm>qAVFY{T0CiPOu_{A zdwQ$BGu4d)a@mmakrjd4fq{{s!dubYUtLI0) z9JP}_C~E^D2HZH8he|$uj!d4ZcF%qDK-oYJzYbqR6L;cSLc$bJPNCvtk{NESG76kA z`2;7^JrpKYd3og}mCs|b=fML+2kaP`IJLWt*71Tj;Gp-AoPCM?cEi-<=;4219-$lu zm_J`%KLF`er1>?UY&zMgeU~B(g44FxdOT!-YZPSNmY&Pfug1ZtSC?47mDljC2B#9} zhs`QkUQug$m0;gUo9~H1;Fuoi0`1ttf=aymfhOWn_LmrXvs<<1*psDEi z#Rg*&rLwV-2*mbcze~CYFl?cCy$;EWl||7_x1_m!kpc_*MG|&GG6K5BcugJEZWTjZ zrv&Gtr~2~QrG+RQT}nD@0UXh)ZKLvlQsW{n{vOxndCqu6Iu{Q=f6pE+pj?K*qN)X6 znuUc~)m?riN{=`5{KYvI`PVp&eRQxk>`EH5+NKC}mj~K+`p*A41FmaD91t-NWrz0_ zk>8n4&)2W@mAX4Y-#qh=O*k#Az zlirH|6So-rI*svanrg`nUdivVJ+2ZufY#K+He;80O=N8lM%_ zUtgy~H+R(*n17M+a&p5mr>#~H5}!g|%A+^W7vd`h`h%`m_Vs4*k5Bii<{?SO<%Afq z99IzR#G0#B1nE4__N41pNH$Sde5`4L3EOzIB-v+2UEgDD0y6mf>fdYeyS8-GDj~@#%G9qAc!_i-^|sy1z_@DgREM?(T`-o;w%t3U%5pnY()#y-aYTk#J7!SQeIq z?beI4qBB{rx1+S6MK$S{>J{*)e#wL<;wc1S@~DVS=-K}HGnLo6(#6>)?)+&ePD{p? zLDDMV;{!!O;tx3C=RoUXKGmo|PFz5K29PenPj`(2Y=0>=3BeM6DsXe+2H=2i5?Kl= z(xlu}d@9`&6lR~me40lQQk+WF+hRs+!W1;3mcL_{zUK3D3=qE>Q5V)33^2?`m!2o| zV=y=JKouLG)g4{CD@@h(nHLN?$|V&N5Z%g5V^EMr;agj;Kz4~=QqH{Ilr(kB^NlSA zdRwl^Ww}#!N#dP+lRN50DvmTBHZrqoea^7>o|YpTPXFHjDpL~bw(Gp+7|YhBibeIG zjM1JFhWmW0&%T;;_Vn57b(gB@9H0w0EC`WTm;`=h0__YSWjcZNxQ*3#eT;h!i$$m^ zS{;hUJ(1$QvY&3?>#k=UyElIUIlJVS7Xk0vT8)RzVWz7gCH+mn`huj+6O}s=Ij-N| zFSY81%NB-%0O+SHCT3>AiL;4lB4x6Mt@kcP7DMe%cMGe_6mo2zn+cR@L^rzOPOT4^ zZ23mpJhw0&xy>&3+95 z_xdWPh)_j>=uq5eglA2T|MJW=Oz6b}=f5Bkk=j+2?spak@8<{p_v$`rj{?coNMqi^ z3KxgRLrhjW-wY-O7>FONDz3&YUUDH6ihF=j>5vGizfq9n;|*V+buaMPp7 zFwxWhxINYan$AuQlke!VB>I_#rqC_(F1Kv6FroGmG#`YIGB%aj2#~_%RN#Fl*Yeed zrdkCOe5}#wL@h~20#{}1vw3j4ZA>s}umg<<_&22%lV&@V=zIk&-Q?*kXeFmC=$|dX z`&E9TnXIk`>PVZZcVGJ;pS$QaUeyC1Ui<{z(x3y%PqnIIN?7-}3x4TXeO~3M9~;WF z7_2BFn&JGL6z_P3sI=Ka5C_Dp7Ht?Rz8 z^E{3?nJk{hYBXp_P;4?@8SuWq&2_t~)WWKhmC!;rd2Z)m!j5k9b`Mg_L4k&0gD)m& zwW2Q1)Qi2ZN;RQmICrtZ;P0>9z5!H$XV67==K%FTxtKy0>Er;Z5>`@cNDFp zo2iIk2ZYHUFF%h2+UQnAIWCK>UCf;@b(UKVT1arh)NQ_-qADqA5qnV zjS-zS1)`jhT!UA#8UX7!?k7k9dmnnDPT!4Q)o~chVrQ+t+!|6e07m!UU~TsZup0Wx zbAtkh1ikU6xp{EP?}4_}9@+$4NFg31NYS@aDD(s)L&UHz2SH?h{8-QY=LrX1gqEQc zRPB7-=jj!t8(g=?)4%*>316*~J{mOyZVGf7$?#!-feafCVGhbRo#ACtqG_Hc!*`{8 z+Q%TxXktk+HjEmE+qF5Wg*&a$N`EA+xhY=|NMCnaCITKv_RhCMvZd6?pl~|T0J-ds zMITy^$uVfO2Y901Jvj*}^d$u+0lpK(g;8v|T+RKsk0z0gqd_mzRuml2AU(G5u8Y`bn8iuLFsOrU_ zzesmX;0l>p(!#o-CKTi@V z97amYNXEt6(lKeGRw{w$o6-i_GnC50w%T!|qAQj{7xBjR01!e4@9Wv+d7C>Aid{9a?xh@@_1j&@!jWKOwaq>)$e)rJ5zr$y}S@5 z_348giKG+SH!_xiNs`8vJ#4^W_idRC_AW@Wf1-EXA_ZF_OLSKHl!$qr$nnc zGZtF8X3azH_xG^h0_$vMw4pC&d*_0V$8t z3xk1gxfq@nrQ>(|DvFHKdh6=Ojy^i^h0#$v4U3p?WBbLXIUYNXtCMQSFuLbX%)WCz zx=*D?UzFg8Qmo@=#p>rzz7hJr!2%?j(idK36K} zoFDeZ?yB=b^J4RU5euV|R7-$0Bv~)RMdgQqvJpDR@K-g4JW2MD45Z882g3UB^&vk>i_b2wAB-Xdr{xeGNPX2 z8I6_epDE5D{LkgruZ;hrP$d*t$I z?%t+jDS&}nf9u~yE+(~-5=IvTNiB0p_@!-1#_w}$W){RGMHQ<+BE>mS1IEra*IUd> z|0@A+Z|}~>P4CWI5bt`Ae=bl{bJ%@x<+!koKlC&tcLTW;8?Sd7p9zUW9>!lzvmD@> zSE$eoai<(2vaDIy9 zg}2nv7blks)6aQz-votWfcc=+Zo|mmKbK8bQ%A=|V{Zd;adB~ZbJNV-yj2qF)8O|i ze*TV-{Mx^7XBa*q%%VnO!Qz;pQ_wXtIJ$)@%|1Dv*@4z$?OdX}n3m8FwFEoC8pV2K z1>Y5;m&T-7{D{}ahMyJh8B49k?XOb~Js;IG6Ny!{em16drTiqNI6`32zrZHte$Sat zOr9*5_xZN8_No~dA=Gt__MxH*VrE5(xQj*_gxkY&|c9Npc+ z9&5UWKRyKR&ECPhJCjj?5o{PuUT}Qt{qa+(o7aIT6UKc&eo=Fhg1eQ^-iEnE+{)N# zH}CXpplz9KcqBnMiid3O3wg$MT{YTC$Z_s*%S7d0sB>fiV3wzI(iK^T2~lPY)%(L1 zu#Mo_7fm@_pg^sJ$IQYm{s(s8&XvrfWxX}(k6hiQEn+mz?0~3lffimd?bYC*Lz*e~ z9{8_tqj0P6wulHU>={V$J&hkEd{LU%7gtX@5-|z2!=$6Weky5YG*k@Kw{}I>XOms(p{J35YL#NY%=qQg zlO2v{#cBlnQhp-oA9S^DiIjr4`*BZi(xglGP=rYfN3uDk+lN4SsEXaN?cYNb$XR;f z`g<1{IX8RcQvXm-kj`>ZBSC=D;Yaj-JEsxtOoZI7dwgPgo_Mwi?M)@FMFhm0!8a!@+uCxEHz6Ft@mbcj3{DVoMS*3GN)-BfF|vm3NCSdx zwDH8?H5GZ=>(P1Z*3Km7*1v~yZAqH)K}D2e4sMuzsz9d<75m~7SL5fN8W9VHC~mHs8%;&gH@u{zwX6wT`q_NB33BfcmNQm`azbZ?wZ2OtDSWE= zQ`wUkN|s0_&(IdT&x4S9Bcn&s2Pm3b^muoN&-BqW;% zKo^KReGV~Pbbo@?evZ?_*L&xd6z(|~zTu^qM;4BP#Cg;=FOi1Vx7G$JVOh%2mQXXLM7K=X$Ri56*NvY0P&ejmtv15DStJWlpo&x_ z@yKkVDf(c7P*54ZwNGsD$zAColD4lxM-VGICa5b5Ka&N=5o0hC*$+w)S~IhdN*Ibo zW4cC{8AhNi2I7#)Mk4!G;U`8gE0qwl;D?I084G)lHS_UnhdgmK4x6dYxt%m~4LcmU zQT*GxOG3(v49G7cjz!CiflO?Z%`CoqeU&7^HczF8wpDIHM0_R^d}EF}Bsw@-H7@2G z+e?H8QS_>~8~P^H^0|h5-pBdJEN_vIh3fFRhf?KuMGoh9fYV@LN){Bc&^E&RS$qFp z((}*u_j@)4Oz|R0mE2*A4sP<-;o!gOs6@1$s%C&&F`!0bY;RxdV6>#=?BMXvV@E4S zOX=1<({*}JuLUP&2mvZ=PgBl4|7RjOM4R6i5(-EB>oL08D*!An*bd0G+%MM6b}yhF zIWLW?#H7;n`4Br>kuNY=ly6zgb>di${y66d`(+#ciz6;ZkLnWh>H_M-sqS^o;%EPY zmCtetO>o{;%*E=>`q;T@n{T6NbFO2KNyEBLU;T~NNxB7?Ct5f-j~|ipMijLgl5bt+ekn4f-;h}_;nz9Z2LW|E^77^(9xzYo zdK>u3FIoKVv86qCrip4u%h&JGj^;@aC>?6cOqi-%^AQMl9KxNW!f(hFa0Uih6i)oGeIzlL7uVv>o)XmF7!B5&4*=pxl& zJ2goP&1ZX&SsE8YD)8spHyODwmRRbo9VA%CF~b@w4~O%J1xH;+URg=?iK+jjuw>J& zs#!W_tQKm3xbqSG>Y+surl^{pfm3_32{SXTTIh0sK-=Y-nyPNul4Y2zl7#mYT|#-| z4n^%pp_;MbHM(LKbOC%(viI0lM2l5cR_S6*lXEPyky?f^afPyd4Js9*psy=-iFpxI zljRb9jF@q!(Ks^clQf!$rh0h%#1M`B$IdrB|8v*wmp*v<2TTRUv$5n9KbY-4h~ghj z6hBK-Ex)@U*Y{b(q=081N)|E;8yNTAoX}!1>K1I;7=;L9*J{9si|l^Rq`GjKuwf^f zXR39@j50{W1viCDl6_lmcMbcg&gkrwf4+*5d;%VxRga!mU-x&ly^;K$$IIhLj>Nit zH8B$3DiR&rh>I;#N2;Kx0lH5QYrivMJ)Qt@<>?<(;RZi0tx!fD+?{?!l`7UGTHdpR z9D+b=G&3go-caJc@vMuCdH$qut%Qgqq30e-j?aT7q30Q`dah3(pt+OjnsI=`xeQRx zbCRiryG&tJ9W3KAEe^%}lDR$y?1zU-dTK#C}4rKR~5x7`9l zCKiR1EkM2GW=>^o_5~;RXX;RuMFMqU6-hjiO-~^=}KxLx5MA(%XANCh6(rEzY9)n;I(qe zJUWz7r3_ab{<@N*%CYa&N>;kV^k&PPZ12Z3pf!(MVaj=BHIL5=_qVa}ia)(%rgKMw4G^JZN5%9#h* zz363i&=x32&9;azOa*djH)FQXYU@O6J0EC2@9jTgQBu9^6T~}0qRHLd!}?>^?k+b< zIF9C&;w^$2_F)Mx{7(}?<5P8TomfKMLSG5gd0%Cns^Z&(t5sx}w4v)6#ZFEB|7C ze%Ctwh{?3c^sYFv0o`duvroNiK-B^THh%*Cp0bwtN)6a(MA{SN}~HSy#?0XrC)?1xppiOh9{uAtq|*iP&53Hpy> zby)j(QftBSTasu7ca|~ah{u6XkzKg9qESs6wEosx#)6N)b@V7TYz$1)Q>?)1XaTu) z#o|v=F2~&7>UV4eXd8QbM-Pv1kh2Pkhr#$yuSnqiwB>OOP-!EN zgO=&}{Kxh64F>gr)k|jJD>}t@3+@w4x=Sr>H3xE4d+*jIkyl!YXNW$LnUI~Yzp@p- z`Uw%`2+(L8B3aYF*0l$fj{75{>KJ}e1xl^}l~Ag30YCvYw6$qKpf6gnCz9tcIF*qX z&cGPc?_P%o1%16(Z|@%(f&#V_R}5P;eFhO?j> ztT0bj8iPqt#AM(cyfBQRPmMw;I+x^9N~++4+9l}7+nx9QNVzbQjXRANPTd-xuWrTw zAtG7QSkWvg-89GZ;wRtho3os!Ll$XhqJC_$FaQ>khDr3A6B`Oyg`_SoTe3piR5#V! z3^&SF_$BDxJaeQoXVWZcB?a4h+`*bASWTU&b&h%XUGIQS|C6%NB4X|FMd9?dJ)q6YSF)I_|;7G94%h9kZMw0>c|HVI&g0zwrg`enAbmm9ZdIi29C$1W0c~T=-I1xsl&1p0vWh;`I-lrMw;`V%Gb$!ejKr3*`c^m--h9uVm^c)J&nU@zy5F4 z`_lRGLAUAw>bo%kf`=K-+5Pi%oZrNA*muX59ZgCsb>@)(gY!4;9Pe$qw>iN#vg2Nu z@}jBi{l5Z3*r}kLgBkPOlKN$`I8_t^tz_lD=3m8$ouek$NGBCDD3$b3kPkeyxO&AR zwMqCV@^XnHqNqvCO_Z9ZU6#Cjoy50E*>B%qw4t*qBZcxF+n&!R^sgJtgf*`WW7q!dY-Bx zeXTLCYIb#hv{CMutDP!Vxw*|h%G_qZEz7Q>PC%lNxO}jxrg|1Jp?y$OaWX_;X5l#U z{q5D2f?oOwzvtG)P?f@kqRc!o!i;62n1?fUrGb!bfuoF5H>fB%MbcG~=1;KK2RY3M zA|{q7Bjv}AUVnNfDF79M5wiQ%Z!PD$S!$&9Ox8ssR*}qa%Usx3-;F1?w*#~)2U)-SWz1ozQAW~%vbmQW zn9sl&`CSsWo?e!odbd7%5ZrXpm6sD+lol2FQIt@{n3YD`gOELPkDb<2zfWb|)D*OV z_hXq|L&RdspXzS%fk)k2%R^<0?t2?u{Gn@yReYu?$mmPa;#1ch9sas3D=#urNF!ir zN24dsv=|VYy+OcnVdvm5{hg3`h?|6_yyQV0yXU5B_~i=nXEM5EKGP!5ztCjV`SaIU zUI*B}=llautUD1@IeBxI9V3m@+$CwZQqqHbY#)}9iQ&qnatZV6UFJ=0r&fehs>Nd} zaubocC4mH)*jC#_^|#}9{%D)rJ(;;1$b|u2+a&HS9Q9HJ1XM+yv6!JY_P_gI-Dh|o zQFfykl<8L z?h6l&=4r3am#QNdwUSY39N?fZjBcVCGQ&C+5Rk(Wv%$D0{*dIvMuN~=_2ZFmMG5c3n@xM9kZh%~Qk)m~e0Sw9d zig8dqCUs0&aj+6s8l)(i_VX(~zq9Hmy(za^an50z>-|4=PTj*8yd|LJ<~MQqanZ9o zkuk?s5dM7H`lgpG3YgV?&7GE7wyx^6e9uOv5*;{h!Jr>4lKHn88PU-`rZDkflWFMl zMHQVqU({T=tfkII#={5ov0Ul=&>Z&jcb+`!i6bsI$Jw^QU)$C-mkwRvZ>eZ3~vC_$p4?nOBKHL~CK0XuRU>`oh&xaphvfJk=DmU6F1~*FZw01kv|ndfR#Ryp^f4aOe}>8%n^?GSa4d!$+u(Zefzq%QIz!S|7Mi$ zV*jwh}o-cl1qY+bmwxA-AN@OC(flsjG-d#FV*!41i`k4c{UvLVqH^nIv3D z{eA@hQZ-XVg?4K{7>PMfBSb%Dfl4x6NJ85&TK+&1C-{s(_~#8mF*(`mC}Qj_s(6F~ zLo5;?DKYAGj{K*)bkC2f*i#k#QAE00jVVnt9F5C6gQ-l6ncjz|WbIBuB^6VtUOTIO zruxDnQBEV>vLsYMld8V-ylU?k^;*aSUAtA#bwf?5C#H3%T3y9zZh5+cj)9q50vkiz znu;&f2jgPd`NxhQhdo~!jKhn5NzEGm~b zrd9+e>Sn-C({hByDGIdEVn|z++v%wE4wG2I!foO{K(eB`3DScwvVpW6c2o)0#qlB7 z3YRr+hz1KRMN|&*0oHZCs1Q9aJ8DJ3#6{*zi|gpZJ$E)D&Xzy(HcpZT2Qu? z4wMX-O>95titSI5$xycyxO9URdfXzmZ z8v77~gu*hjzNcsE;elgP?>F_ec%m_gfJUT7H$qskolsuRO>0KiFScx=M*@EIe_4Re zt=82oL#6N=Cf?Bm^cHOeJ!z>b9Z_|ZW`Z$pX(Tp&{9BVnPoCzhO__K8B1r@Z-7;Q2 zZA*K0>E}6xpE6tix1*`flzrYJHSC3K#T%zLfED(N=ris!srF+iiauM5zMDfrkW=|? z;*z^6S9@Q3!#*KyctGho=)>Q<&Hsm8^e%jG9DWm{;6c`b-@#G;n2-d+(y`&YMK%Uv zf>8T=b&N>OpVpozS<<1tD{uIopM}3=#B;Eum&O9W$2!5U*0ppGu}%r}1LlN|#}*VV zrlm;uL0{V_F^z-0mfPwbs-nN>KGCF+N;cPinUR%eV6xdR-FNyK(jz4N7f?7lY}NI%5i`jnyd+XYErOb*Qv%C8bhPMLc`+s3p;wi@PRT;lOfv~L8CwQj z(3eZ1J%B3e8P3$2L>z?b2im_M= z>eRMUQi*lbx(0v-e1G56eB_(~Q{l9ixT2YoAdVX!q0RXa@zwkF4(S!R@O5x-_|dav z&V~P?)3)Db#GsLHerC9^l=03!6OwerjL6LaAtJ8G28Q(R8A1DAHFM~=9($LDAS`rc z0LUY&s;V6J$1whT8?CNtff=J<`WiN+2pNb%Vyz3ru<^w>oagsKHY5PAK# zp|-M8yVBEtNbk9abmoEiy_iGETC8UK6Oboe?o6ZUA@`*ylj8>bO(_d43)vXsA_(crEc3xp}?34!;x~hJ;AFdfAFTM=*X>HhNLsG~ZlH_x-{@{6%)J z*verqh#5BVQeryuNgb3}c8{uY_f{eXPV-SG$eYv1H!^TPq@*fW_NqCzc6#0i{ddRp zpW)(M2!+TC=DFpsQ8hevMyZ~H1fMtrUuKYS5TOU8&hRBe$(q>bGrwV`VQK2hT#%X>#&}E6}gmdqs%Wdoqg>d1c)9b!_1NYTUW>E@kd- z+U@A^eb$fE5*lb|U#K7wz;LNC)W~P&AoV!Opnf5Nk$yhl^`Ko|Rq>LMjBPB{n7nNP z<0(#&e|MdoMF~clniQ)dVlSlHX9}Bsp=2;U9B+=J$Un6EgN1*YgL5xK`9RDuIQ$?w zj;O`QWSZwu*iV$pB(O7|*~Bw6vPk6M3B5^dj@3s6-bO)3yYw%+T9R@2PWsjhU^qzn zd@A*M$J@$l?L_Zp;uVyTHNU@g_=i{4Z1n~hkY49^f;DJ9a(kZa5ng;Vr3l{MRR_1z z89y7#ynho0LN_}OK{1)yKh^EaHVvk-5Mz>JuoA{RtpV$A#9Q=i)3t;08H-F+*M4)UFNPhN|G7&5LA_WrZLLcPANf zF5V3g7v7v*tLIw;)l<*Moc~S+FoK;=;NF|Xa79e3C3$}hOzAx?(TOv>Do)(X5V231 z9TiM~ z+b3}zjVGI9l@fua-{LZ0;{!1a&waZNsV`A7J|~Vt%{XLgjULPrW!A`7#g1|)or|nO z#J+2?Pb*1FJs}dTogc6)3_Zu|@BoJ3gS^>A)GZ4}@u9Q$XXxN$P<+(j_OnGDcb`e@ zRs)#L3Z6bBBdxj%PJ^&Cv@Ke2y(F{vim#Dd_!&oCkl|8_`L{807(=E$BYddYuZK2v zYjp6WMR+jfVQ|bPPEcWdtJ^)WncI%$bWLh`&XUU5h)Qm5k0Z`p_z0c1&CYF>-|6e{ z*^$eGAK-rXXQk=CLvFpT!p~2ApND99Th0emz+UjbK8qc2Te%K1$_tT= zvz)gKnEr(czM*{Yc@x?6J0!4j{6?~Ws3hczit6Mhi1nfb&-m!N|IBR~?A`3OiC?ZQ zV5N-lQjXT*E%)3zq9@jZa8&~!ZMZU^^R?PdO2*Faz5Wvw=)dh?As|BU@zioDydSh_SMA_ZSf@dndqz7dp=to7tgu}*G;`PIr6Hi1|Z)#mJJ zi;rA*5XIYAy2HPHO`PK~fA1#WrAcrY1>f($Qh?t2Kcpq`yVS zrt^PHZCIF?$ij911yRL-9MsOrNhlAaW21K4mqw;h&D4YvOUIca0cmw>*_=Z$BP$ZY zGw^H(!Ae?DN|5fpNtsPB&QMl`>+_3o zT!Y&S%fC52fi^3wGHOWR+4D0ESBJ~LmnNb#JtAYIsjiV0j+-hRGJr_hHuiv0pI-8&>H;j0aUx$&D)JRkUK@ysM5f7fe zCd)W~jZ8_dUpHpr+j$OVSrZ3-Ng|$hsBLk$6|e}(W;^%;gM?(OQ$|V|ruQ#8Ke~6QmDPyLX_F{e1GoI4`ZL(#pitDgz`)D?YX z+!`uU1d>&~2yEZzG%V&Wyo!KNFH*Gdqn zCH2EVaKFl|77l86WnDny9sSOBo?cQP{YXwKjhz$^w{6QOcZ{y0vAAT zPuc?U_FfA%H>)OtiR$?DCo_Pft?yio^E(S9oMhj5C)<6yad|bl^+B0k3|Yq8A3RGU z-@vdv+ZiaXuzgih6DkGC5j~q+y+QEe{VMr&LoMo}4}4NC3Wt`>w9$Mt?I z%8Gj|7@11OCRf{xicm=j17VBG4NAGhXK>AMHzibKm%+yO!kL6Wj`|ku#(eXoN&`|d zU3!IAnV031Jo?Bo}q{tx^kiYirlhr|nsCEAqX;6Jpxe+n$(YE4oC z<%4-KVGa-%K7L{e%|9o`FzOfKa@{+3w{w3~6`Nt`MCD}jRWT=5FLC~`=d_P*&Kjp2p0~sD zz}uMTeplT5gi&CQ`We-E)d#=c)80EY*-=)eCm>kQWA?1LJ;(J%OFVQwOii)uRzZJz z=jd|NASkC_(yjd~v>asn&&Me{saO+blBbrM1Y(Rw;sID(m9E`~n-+tL|MkP4E~t2N zIM8oj22w{J-+Oi5&2m1y0|VKAQo+j8%7KU*3mmfs8F|FnmFqW0d@^Jcp8p{5+1a*< zMdGce=q2|>;^BNMO2D3Od20*s;4~^!F+QYPw3uHSI4X&axkwzI=bb!7q1w4@K8iUC zh1}$2PHcd4GvRZa+EG$yrY4$&oo#FpZ*7UKWNDF0HVLKUR}I0*!XDG&-!-9Iu$AK^ zRFF7I)YqvU&Ke(bJA0;FNN3ltQelN*XOI@Te!=|6V650aN-v=ue==*&~}{ZB-vczoa#FMCZqE(ITkV#e#CLDe&@F`$4(T>I-UL zey5nCC;)972{PkrZDr!irDY zHx4Dkc@(_2Z&3K{Py8)knqsnjR+1A%QY{-QjqERkZTwD3`_DxA&p<-aT=vqqe^i8J z6a2iFn!MK)$pvba7$D?xw~mpZHM?d@wi7ly*^_2mVYns^U|X4Hc50CO-sSu7;D$qp z$c4`pWS3bCnOMMF(j@DdoKoSe=OCGGGVZ6ktKHm)bFI;a|bH3<{1KVQL?=eYmve7YQ6vvFld)@h_3Gq`^O|`N8Vn z>N|0CJcRPY>y-t?=Sl1eap6TbqUdw{5*NqFnt0(g$Z!xJafmjJJN-wtx3Omt!nUZg ztk;8y6{;VL&b|K<`4@-v;=kc_4oGrP5R_a|>XIE;uiRZj9AjZ5pdd5{>T)i8> zeB65GMXoJ46~e2bK~>$k{u(R_52n;kL^8T!JbY1b!+?9pqobk!Z+;flG58iHN8tho znWB*(v%)r(aMSqped$Nf&z$)&xn<%CsBgl>&JvCr&as{K1P$h4Oq)Sm`MOKwA%|9) zp?|$Z>eNLw%#ryPB96(q@9gVuKNyF)zuj}h2QcgkQk@8x(Xw_RnGwx0*fh%83=OnM z_(X@Q6DO#(JxGlpa&UJ(Vy+Rb4;R@d470oUgrB6ZmABx}P{U)#q(+JqV}p6Ikt(;2 zdh24xt+!T=y^@M@CR-=KB(sZhi0r=}_2b=f4&f87_s)W?^@U|mfpW_xEKLPLX{A&l zXX71u;^$IZ<}G3lSh$O*IRa`bZdrRw)>XJF_e>%<{9BVY8k zxqX*Z>3I9(lzhw#uGeY0o1c1^abx0@Zjk&xkq}ms*xL9f z@x5oFvi2?6t#b6Fy;-Wo>ZPGsVX}PsjQ;9rSN^8Z|Bb{lM^W8%i!yD^CzUoP*KAu( zhAQLq#NhoDwxnk@(+mu(5^;rRsYvrAYa1rAwVahNnmN#}bsSIypR0BJ*n^qT89o*j zHI3sX+*GLL^tfpMe!X$&m-czp6URdaR7QFKWdKG|Px~|?4i6n3C*y-c#zqZ4X3$H}WXTP$iHkKVH z26I0t-$d=91l{Am0qU2xe2}6ny7vP3AAia2o;Wo|iF1#2^QNwtks-F=B1|cxB(f?- zY1hYgUiT1iJe&rbi62DqA2pxN>8U~6Ad90rybkaG&a#7C8)-I1_Xkg zCPBm@rN>QEl5h%SU8v1qBVfgi$%cc6Ts)*@%zNpTJQO}Iki;;aF{AfF7=X*LAPd*Y z(cvvJLn^Bm5zY-qfjdu#=*z#R<2wy9^%EA)JSn-frs45VcWY}@fD=O>gdx{Voe|{v z@$Cfxnz7WVdWKkbHQGqbH~**cHJdk?&|)<9QF3nQGb2*A=Ha$8Lo$SEDaJ+d^N9uR zeZ!#d?l(MPn3mQS&)rE*kNp(&WgysfKmgt>;m4gIbhQ*nzc9Uj1I7Kk`Z^!2C3G1i zFSeshu-V}r_aT&9td&hGXjol7Q9gJQ@CEwx)SB;of|X5s(lbS7Lna9wzkcJPL8h*Q zqH)(lNfVu0d9rg~NBBy4j9yP5x)7VBI4P=2jwF`UJP&n|Oj?!9IUB$17Qfm#ZHWFZ zPr>d@TjQ1}SD>E#vtFYO+3o@8)ych5$YJPcv=w2+Yes?}tn_XU*9Q*~l; z<7n}Mz0_WV?Hp$}g*CJxpLoEF^JYD*V_egm$|mdE{VTD_P49Y6v9)n%Jx=bnz^C#u z4$fErCy2B}Z(Kh+fJ|rsWs-vD6sghUfJSRPu3*ZY4C9&$9xcGA61u9ciU}u-W0v8b?kv-#9WVhy4-pCu*WfaoSubK1y({S z&TIh2%-7&D`S_An7qJN1iqt}~YM2WRN%Sn+zafLc%A<^rt(yUCp<1G_zfU1u@nnb% zWrB)F0=a{IhzLxV2g59fxtpmot;{Xo5gn)$xWhsQV=wx%)eZ1PsukS~`qFt9>XlwS z->@|U&_&^lqBXgLSfF7#&Zb5TT-sNXse6rC@C>l+W{!D3VU4`YQ#! zW770Lm}`4JpuVLjDAy}L8Adk##f}0ItUIGpfqvkc$>25Bk>3Yzy?6N!KYl(5UM*~S z`~o>G*`^kNA`^c;`S@%a<17A|GcoS>w(semv?fxBBSkH*n-xm>{5b&_eOEfPQ5*mfyN(<@xCx_Kc#bzwm^0Gv8vNQ9$;j+d1MM3wWzuO5&;cY6I%3}0n$ zm+zbFRUAo&p$9Uyywr0_Fl7YC#5`E(uqTRn=1y)c?Aldv;>SCXBzKJ~QE~H=&lV1q zE*|Ud^3M2eo!3I~L{M5kJ$>ETgBQcWJ}@pabgYu-0>*5gStb#> z(DN|9^!&T$!+P^+-#R)}q;sT^4#wv#LH;NVhQyJ83eLMY5&4(n@;|+vIHF~y!kSac z&=M2+g674i?zqc17?BtyO!V=6rwAo*o1BBcM9kO-$f$gr67>oL&ivDv)iJV}zkj1| z2q(^I4auS^lEWt5JiJl}X-pfv^6oS<78{^LMT6%mSO}LF^35b-34HRt9p`@L^4+eO z(=5>mML9{(^c z@$VVkRp(mD!o*F6&bHZ?KBwBr;}qR(pFh#|CE)rre2`}dY0k6=?xCBsY+v5{%tyWGC8zwbP)tJe)Et7FLr85{(<3<(=x%G0 zqyazrHiY{zkZ;`r=8>vSQy$+Zes}Z;4SdfK~2 zg=vALot>TI$D4NN^P={8x9e}e9*KI5B6P8?<;J=n`5K}yLZx$tz~B@U^UbSEuRy0_ z0n})JDS${IFmb(`o3AkOe&UPM*scTB9Zx1SaL^UZk4sp?DIk^(+{4KV~H zShZRbsBX|;nF1@63x*GY@E=SJI!ALbhvQ4s^npwY^3ELmpQa!IQs|Tr@Ygs-=El~* z(bpz%UGY1Zy>JBxi2Qqy>KF+d&$cATaJ3K^BGhmI>BIec3<4#LhOX}R&Hi|_I2bp+ z(Qc3jM{Qi;ulPs;yXmoUUxEEgu;A#vYDeVQ?BvcOSqp>5y^0cd@?oRRUqQi zZ#=EMM^1#r5JXk%&kn9p)dm@zXd$wQUzLJv2^K8gve;m|wVBCN8h6=G{zNt&f^N?3 z{eSD#N-Xz9|-33uC)pzMFzy7lrE%^e;qqhI95 zM)=Rg=>MGNA94Bzh^&7XX8WjbOp1XbFEJW__Q@fWi2aW{eXiX)T5`Nr&6AIKu1Q}> z&GE2~GqrGSZ0Q9c)W95{b|-Ssy}z%b6XQBfIN$c8-yijL`C`A&(wE4Z`w%TtQRklMa72kXOaF=m(srIhEit=3FxXJQ}9X=)f zX{;#O#NMY8E0V8Kq*Sg@y9B5e@@FjS%>8~j70U?Zw)&`R_^NTitgNn^_!?&eJr{ty z1bm@fsch?#@iY-Klv>2^bR?N3L-h^yhZp{nrEI6KVT#E$mR=1{?=qTbJ(fAkNJqOf zH974}0`@V?#&Db7+_02rA^-?aL5fP>>+ciB=0HmdmOYQ~FZH73WeL-36lrIqxg}N` zyZ@u<9NX*cwlLbDY3#e!<4|?7h~U^PXdL z#I|sp)#wj335I^q#Bx+&rjLEOtXJZYPQkrkSlYo~jMVN68F~u*AXRa{+>TO0&fhoA z&>gyXL#0HzG_x93`WKFMX`*DABnfjp{kv}Byk*OSQ(wna%TD=RZtOMmX=77ULb(DRlWr0Ro2`U!Qm~TIq6ss)Lq%11 zsyG^RXY?HD=}Bu>*ss`xs&pph8p&^*zjnh#b9%#7aaX{8jvBM!2qNq;6?Aov7qkao z?1;b%4#w6Ug^}7Ca<10MzeP&3xc>md@t{fyK^1Nd*&!rx;if%|+iM}2Q<8!gvHVvs zQRfE7sU?1TzD(-Km8nvW&ub~ORpw^N7vU_`8hVgU1wC^t#X&4n;#ta^)NGF)tP?Tp z{Zm{Va<46rmwJ@KOGQ5QNnUc#g$!Q47trMi1{|Hx5ef`$i^{qmE8v2|0QvD9LZ_Qu zVW2xZ{qpzs6mB^}nn)Hz1fo(+8W;(*0wppxNlokF@sUlA-vQm0!pb-gi2%IWi7VtR z?9hLe@cYBc^JMWz);-P`Kg@Yl+0WtK^FWp6Nz#Y}=i@_@CeCbM&v#geOVwJS{mKac-nC*Vsd`j$cl zZ4#%M1CtO<)E!@R7@ki$hSzac`ST{+OiDhr#C9*X7Y#SnTD@v~lLhC+d|UhW;Y&n@ z_8+h8=ImCj9=Gh}b)L&OdYvwYewSY}Gt9i4-&A&~Gxlarw(hS1v%CV3O8^Mq!+Igs z)!`ENqe+s;Ds!0zL>plyc=o|tL+FwT%oMrBw{d7MTXu(Bi2srJ#w2`K{UD_IYp$Tu zbAGLmX=Q#;KQoPK3L`@SD2UtPa|fmBvqdXYodkNN-U`3CfkJ^|;c@6~F7eBS);c%55Oyb(uXo**viL_Rf(J`ps)ThGSH|eyQmSkYxlb3 z;jH~p+&EXFR!NjoPd8-cb?ehCe4c3EIx;*=5z>b&4hf5fJwR^5Iq~&s$aJSVb_?w3 zRly|OK#t`uL6@ptgj4rtEPCu&ZIIoqiy*2s8D;s!(=~oBJq>m!espDgw%F5QY%~dk^*j&g#@4zbMd&DJJ-iW7*a#VF#Zr|Ly$aZS*Sp%CF2+%-FNH1cg>pL&LI__fdklFI1Y~ zF4UNqxj)CH9S;E3+-x?^I32to)abYWETNSX#gt5-XmFtsM5|WjC2xI_^$nmAEQ4;2 zJb5^LCP^Oa!@&wOiiBZ5T0=De^<#PgA#rZkQ>Nl1#o84MHk|z<=fh4tQ(HXTH0_Tv zya@f)feE02lMwJm+A?iliuzLS>Al0*@r`8LbZ4h)ngUne&PUrxUni&zDy63PfzR9m zchRB>)dMgy0V6qdkZ}!xKCyAPT_LIJZ;O$ zaC}V)Pa0<^0KM@0n%rgg4MpPhQ}3rfs_1el7(G(eXd0bA(sZT8z-#P;R3i~-fi1Ld z+muNLTMtH2QI2=t>uj#6BIz9x&IZ_aOguXfsdK=jKQ3~)-C;Fbe=T(mm4KkxW9`vE zMaxg=+1X?LhD3MUZjpaz5OAZYcfl^4K=cnRj$NQ$TS;}yVAY0%MUI)n;x{TPc_~8Q zZ}yr*tKA?-pXi~G+vsSqpuZ+*HQMCX$6Y1}S!D=2aT2|eNAEsfA8Qtw6)Q1Yqc@1#?P%f;NMP7PTw)Odg^0-O*bA~zQRcWrv!vedhy!z9?832F zduevQBa=us@H4kVwP>%~y<#9`svqMNW5M&d{-NjD;;1=a^$q{Sp@<5(98;|_t~?0` z)rC@cLwdB4`>6crQtq=)7-c9_tz%(TFD#HRO6^co0$l(k%-Dv>oIKoUOYgf*;`uP8uWjwDhB#KJ znFB4*6@8!F+K;^$HXPQd6?12sf7pMK=?eq|2gX<_pVwDxm$#}iy7ilZ>;{)5@?a!PjV{|=l@W+ z^}zkK&i(N&DQNWmXa^fFt3Xxr<1O%M+c!pbg+aAS4K!Jyn#1D~KGY?fI^pF#yr**R zC*b*sx?-|Au@a=;+uVVjpZWbYU&YXZxCT9ZwaqXoau96f;>O z`&bRy<%=s<@axN6GKr8Z{UX@3Jo(>@FoKZBGOb-j!b+m7lVU;9=od`zthYIC91OdN z6kbK549eL;QB5QfcG9o)M6422G(&S&|44sG6nk9i<5YB%8-4;L60nIcY?4=Z|qyb&tMA`tQSD;fRM7~lFZQOs=C z^0>77)V^MC_I>SEdL}VK-tQm~{8%B}e+tJkshZalCs^T$RpIlUR|?4j@vD>QATbV1 zUcm3X9dl|4xI&-tKn}0^7G;$i*N&{-lqpf&3=n=eyzIO)Ou6FIoQozhQY^0 zq^(pJsh|LLEp1(NisfcW12vu_JZZRV2uBbrnP%9Ks0$rG+sMT>>^kl|KD*Ter*c?g zPO6lquqCu>B$NA2lgk1RiIfpC7c|RohjdI?l_JbAr>#B5+Pd}JHBwcTh4I;j_w%sZ zh!h)lQw6dLNr8e;SRg8cK(s%)ju%7*f*yymD>8f(0;Z_Z#r19dy?*V39B)`uS~{u` z+46;Wa1`m*=%hF9b&ajV5G*w{d8u)dPILH))ZYhK)@Il+8HBU%v-3u~sml5&XBfRx zXdMJWj<-J&?4hrJwD-|EbPkzJJqcB9THxmYR~sF1LB3$ZU4l$7{TcE%BK&p7kn1f#7IX6-*(} z`uOSx>~`?LCyq;ZIyZ9j6ibwRg|?hz2W_4RjI?vk+}>;YD`1Ji(r{mu@|R7<#YM)A zj^ZphL172sjCs##L@J`!s4jb6$X`$m6$lF1$agCN&^Z6Jo!73N@_MFkfdp&!K&H5a z)T8P1x_P~6ogT1l<5g(h{BV1N=*VE3d-BM}Va;PbsNk7eEk{QkspodO*N>NJ?(YML z_i<3oI=O(Iq%d*Bg+KJm&eIu^E&9*6DTL*f3qQX&V5SCK-h`30l&N6U>6Gfr zJ9FfiTUjsB-wo%HPYz}k%qXc9%m1xGy!=~W7}twJXBkt^mMgHd*Ajl(R!FTISeckZjI09ayR`eVe-X0KUf<0NH2X2CQW;w*;+p#HMzhQc4y0dS z2cO9d1#1Sm0#bMRkCuaXR52njP}khojH@aAeI0cJGsQB>e3Mi`H-^)yOBuY_Nj}`i zJXJ}%j>4*@zLVyG3ZHo!n>SRO;9yGoXL#9K!_#Hf3207|DnphCQYU-#?p2}9CXz@9 zHa~H1u{Czd1{Dn(;<1=tg?3ip^ouJVA}wqld-xo-+^^~p!|g&XhTS&UYDq28LKG}a zYIGX#YxV=0t;;`BWi=+ye}wh{iS}hvDj9ruMjTR_DeJBTe(W>f^^ng(WFh`}W;lRnp?9w#NwQ(o-wUmd%bbW9ucjvB)f9fLfrhUYh*U~6O^qJJ0p+L{kz%3X^!~!$(Zx`z14GY# z>7OlpTFfWit|8G5POLIxw6StFc!>lBEOt5rtL8O7dWMhx+AV9??;YcrpFH0Dv&cWl zvdG&507-*bzm|T#U10_gQl2y{T{87BB{<_9V;+OL7(WCikmx0yMx~Rqi%G+3zU(3U z*bRG4`CJO@JVyi^27I1Uc6xjON9)Mg!3ekaKj;K}0SWcPQ@5A@j_z^-pXB0^`1|SC z>%H?tozi|n;8n7ymq2GdpYTUi=}35oyLT)OJ@*{zNVEQ2H2?;ClUG^S^q$1rVuJym z;!b1o(Db|Z!#k*)11G9MD52@sDL&z5(QT*hfKU*E6-AR`&&~-@x7k)X$ZaxvMH7C; zR{y?l2cL(=)sdGE!HRF320ySbKqMYIjzm6e`EeAQ;W&uitlC+ijKGa*`ccv-@}Dm&beJe@-y`7j36vuEIs<$T z{{-J=(_$*I=%}_D6&by=*zaB5=Nvol%dOA(pF6Fd=hgSFy!h}pua=Lf8PkRCjaF|zVMbm}1v-{+4fKqDyD zWFO^hAuC;~avVjOzdKu;Afj;D30jb9|6<#stM_&TA<*d@cC3-2jI|4G<-(wt<}-iN zieEW|o{lmFhBBp1UKJ6Xj7oWDxsw#S8sV>ekLMgMLigmq9jXV=&xAhPR?HA zaojScu%$ZqNr&BNR(m9f^m6;Rc$Xs3)pH+_%005J{KiE0ZSi6-wgPH}$}EF@L?!BF zy6sB)X?zkLiaXcy1ny%~y>ET62|0X&n?XG2;1WfW7ER)nJV1POCyJy)-Uy2nLKz2uV0cG}AIYgc-?Qd`Zk~QD^BWkyN&wLJ|_}k5A~Ie;R4p z;s-7+=!UUqhQQNgU^HQT&-M=r!bGX~ydkCv)=1Uxp(I!mQD>Z}XBeG*T+;HpUU+8k zdBraG#K+BMmL;)bVWLE5HvS=mlWn>!Dvn*CYh^tRo9b@Zz9jPuhk#ve(Wd#(|4fQcvg~Gw%$KnjL`|-bEz_)HVqOMp%a9DI zz^u3_&ySyn^ac9YjvOCT*qonNRoB*c*Y^Q2j(7bT30UlB4!_W1+hnk`E2Nb8xNxU- zD%};xF%*)Dr}zCo6dX+nART1LP@~B6jwrCve>?&OilmpnCgbkQV!e)kqQ_4655jDX z@vTX7DRP8eqTOg}!^51imXSvGNco7N5s0KwYhYAxAQpG=+y0Y<*Aysdb;oaE=$)l; z=GTd2LhNtu!cOsPaG4rHtllc6AKYDfFa9R`4)#v5uvL?#CIQyrrvGrQS1?iXg5i6QPTQn)obp z;7o|(k=&rfeo2IHy|zi&DQA&R%4zrx_5EZ#TA#dF*Vc2W=`kFc_^ZAG^TsdL3Ju2} zMBqY9qN$EbRDTX4O$Uo-S7JSUp-vUAn+gI|R%fFrc9*MdHru@7rl#Ctxd%BkBTZx7 z=3De?dN()ekO;SDXlpyhY|u?qjd8Q098~M9iS9a5mhTlL2=)dXh3db!xTv4=+ZNGC zqs9Hu3x0S@&vLqU@36IFw`$Q|5A-3!E)?Ste35bPhfA_PRgz|czABa zIjzxR1_dM#fkfZv|4QL+=n{X$+m`>L7osF0c!P}y1+D3{TR6amf%$8C5gSDM$auB4 zn6-e%@1MGEOP@l?$!Zf@fBSB_7!O^m*VWKJA^7?A^X4*O_tJxLc5Ric9M8HP_0{@5 zN5DIW|AG5&7!B(X4qP+TgK^rDP3sxF_i2|8x63}Wc_ph9JrUDphf~a+W2oRiZA&^w z&*#}1XAAgWeoeiu-{uWV2JsOi02O+82ys{^g1nXXYe|V!@`CApT6Cs&Z|8}rYi#sd zj^N^;T;FYdPV`ybq>jyf1Hv{BJRN;)zqYg*I{Dy7(*Pxeg}x2KyfTNVM=_ zmZm6K%sC@20nE%_1QG@EZ?;vVaWS#DZGJm{@>9Fnab@Q3Kt#~c;!<8M!>swQbO!GS zwYUA(okHFE4Nq3t_X(3;_Ep=3d*flUZ?yq$1UsMQ0mnew(}W98qHvh)-9N#g^A1*J zRcUdC?}@IttMPFSz7o6m^yhCLzW09%nMw=ik6!OfD_YuJafz_ssWTuUZ#AbhtG zi0YoYdNkiiKu(-FDfp%G_0b;PE<=)#e;UrFXFygkAj`a59yy$fGW{13{uKNycXek~ z8ow!GgEI9nQ4>3e`aA686h~%$>oAKdwYM3(i>#tjwVHOOK>@(tXPRF(G&Mhxzi<=L zs@-IJ+tgw&@3|-a=Dcq8vYj|qwUJPqDF6GTev_t*%9#>!Qp}%nVG7$TAh~H7z-Rjg zq*j!$hi+6Lu4};slK?pC;EXB9G&rUuan`gWFt){zX5giU@o5I=1+mddF?*@`XnXJBYTI zc{dZ;N~EMNucHuVPI=Tg)f^rEEPfq6NasgG-KOD8Ayk-lMA8K_6TS$$(6LApYAE!1 zFLhBDV#pj0HF|x~eDEJ|{Aj7HZ1DLF3D#o>6=v3j0{xwmHgyr|k#Kv=d6~uatEXk& zwZ242)#hC6$nW4WB7Z%RtU2vaTzB=Gn2#*qxkSj zz`o5AI^7Q=_`eksI$i!%w_bwHJ1-hY+_MaYX-2Tgt|yD<&kVpVNJuCWGe%Fl1RT8|Pdzhv{64Ea0fNB3%NrZ6 zLXfFLyfk+-tHtz9DdRiXXYqo$pC5l?fTTo;Nw%-;RoXb!?R(TkEcUqv`S<>2XURgP zUN`)fmKJDmK`RG6N^;c@IqL6?aZnQz6O+@^MV)d#v(WKIBh7CAfJyGZ3go(HXLCBt zTeXskZ$i9W7Uve%$^c`444G1qYK>xzN@a$Oid5Rg-|FL~sA0xIBHe+B!9>tj9=gC& z3T(v#k<999dXCnXRcns32OszdQCG`iv7zB_Ec!^!zWnlU4RGR>r0Lw(m0igYT4kICKSmPNo%9kU-Bq#^}?0~ zLb>6sx>K1A`QS9LY?8Qf;)-&VvyfFx>-wcyl2lY^(zyKJxMui2xofsMrp+s*ks)1m z@V5i5{QzKyWCDTNvW@8rrCsPhNEa6uzT3eA_y~y39NAL6VI<$g;OA#AnlxCds9B6y zQXKMP_DlDe75`_P{|@4ZC3YsLD4FE|UwaN190#WEIJ#Mz7O&6TCoLU4({_~>o>s9l zv#b=M-6K34R#tR4Fa3{aSv}7c?@EE!$%PyNx8xUFQkobT}*De!Et zUTpn|)OB5uPNch^6td1$fZBb3+Bxv~1pUzeSW~oO=k**nGBgA_I1dl(Jh==(E!<*$ zf?w<$OAuUWlG;@EXfl}K&)ok=NzQft1N-~;J0ibpB+y~zbN(jl1QUYqgV)yeGH;8+PGfe~ifXoNp+d&4>@jgWFep;m!I z>kF|qtragrp+gW(5uU#)XXIq5XawTz+ezNZ>*qg3Hcrk<8!>nUaoD1&Fc-ZM+aDB< zJ(--=CIgmbb_wY6%;kv(CkW@y$xHgCJEbYt9D0p%Uq0-nCR&~a@Y2z^4N)uO*YS;S zcV$i&14>&i)GW`MCv_|6a9iBmzZggEV+Py-{IOMR=<)i!F~!(_5~S)xHe5_=#Za}=Uo&fKu^>A-e0DR zY_I3&ZJD?Fr+nGUc-G{@;Y6Hn2R3?$q%lrA$D25fxOJ=$7|!PBsKmERgotzt1v-2W zkT4N*4`|Le(amET!`Zxq6nyAd6_DRQ|HJ=uO9iL2Id%zSZR^9!?OL*Ool^!dQC#@k z`F$^L%Kd9+hQp_x@?<=b88fw>vF=GGrrAVbqf5bkp00}pcpKmOna|OzXj25S|D)Lj zJb46+%=q7-EibQ(`f%em)8~*G08M8N)gP(YC#{!b%3L5RuZGITg&)NDP%nl z^*0s^%MV{~DWp4^2sMtM;>eKh3^KHh;h{;y4O0`9Va-u+@S*F|JVtEEqo;F&c{x@) zGQ?Jk7N?Ul3#-5Pq`)Ahik)Jo-p@^-(};xTi$?>oU+CsA+2I+u@pq#HYEBDQ#pWfV zz+mG&g9GycINM_PiNt&QU<5zz?eumtIVp6`3I$($y?VIY4OU@&NNbREBx5^ctf;Z3txd z@vylusdk@=bYZb066Q;0Da}h@kj!VlFbhzPfq{K*0Bo@;`ITD~I$D3+SO-+5oGZ z-j_&mVM0{J3+LdpXUI7CyHxoG8WB7`97}1dndtU=Et5>kX30;$=N*m#rYJF(jLwf2 z+#Jg*s#ONjY|xn6MIw_xM6IK?ht?6+qk5Gf(o*mO^Sf^Uy=wk>ZHkTF>Vf z;8X&#P*>yEm)fgh+fR>tE4IyTUiTPV_8CeWbqhM@3C$jS1qPIBU=!Yb!vvf4Bp&|$ zz|G+i;1mB+qX7i8(P7{++9nNij#51<DjC%hF>~l0E4Hh$# z<>bK~vKaE@mxGqzbq0V=Za7HyDN90{T8Km2KJ6at$b`wZ)+@z zPtB^aX+ji5j*qWuTSJ`{NGh{B%d=io;tm(*tgtpqR1h|t$+V`2{Tka%&hY5*GsOX~ zKnhd+QHh4QVYbo8q<0it-wRB6J;qT66e1vOgP_w&v?&rvF$|9aDgp0{XKy>`pm^w< zc)dR9@U8pgFWAu=CkapKk?-L>`jRXI+zL(dL@KyG>c;q(gwJix^}2nt>|1R_bz!48 z){o!dsvG2~)3ij%cf+C~!>H8WJySzgvxyN)$sF~*;af|5MD`gloYkvw&=QcJMfE$yKyv?{a=jk4R4l z+?TH`tvIYsRcSI-8!eKIE9AGnh`BP)3fG^ggBqK9ZrEaFSh(R|&5hJKT!w!*@8pCX4 za%B{d#fsbx5g_rd*ye;-JgqRnj~Hr>IE{L7XR|uVH16{+1b=~w?YnoTV-y@LJc^*s zFc>0?hbEcW0~Ny1Inh}1#)&}i%!UHd4fJ@?E`5{FZt_P4`du$rvBM-}(s)yOzWIc? z(UZT;Hb4!ChgaE)Ov0K%^2dalxe%e^yn~=rCCj*e^mv%Uq1!JnCWFEGa@b8Fhp*3) zX@9->9B6Wn+mibkm~*9-bGiOw!esnm>Sh<$^L`yLaW+D5ko|dW+eu6M+&Qd@Tv3az_dnK=Q?^#n^8{mkeRJPO$g9`iF-k1~$1jy}$QU39CZkjr^zd91O$LKw z0LWccRZS9F;<5WBKVa|c@A!er+FX+|J#na?M&$*a2JShhJ<&Y_Ya{FO_!~o$4mC6*DihB}oJn~4 z!e%Xn)WyvoK_G^7P&PHwvOY-ty*I9D$0@IR%uc%3wzz*Ffls7fPeR3I(L{7IW3Aofa}W;`U})GI-+loz5D4Lo3gQ!m02B4jU8@FhhMhZTkc zsvkLL6_NO3ZZ}=;0|Wpy^s5(s%>ZNKH`*xx6NECe3-?+@_VdJpMpgWwz1uyIG?Qc%Dslu-@^MrU&JWI zh~48UwXVzLyFJAjsga5!Z+coI6eS_{xP~cu$61SF6aCJ2w{`sgT!BFD3vkt-+zQ}R zmo?Q5Ga1|FTv#w7>u1rGztE}NB_dFy7|X`7Yi zYs3Ld1^LljW$fhCr@u;Q5qwNMX+sLRJY$;OcO(zqezpkYDG!L0;u=Y~68RET$cUcY zzc@!{7?rjfBY9iD1)wvfG6XpnznZc!%uSeR)1um@@I#DxF~qBk<&k}*GIFfTmkC7Y z=wzBVG?g-xaDDab5Qb9@I(S|E93^SMVnO{8UM5Qv-o_n7>l_z&331Qa0D|4_`>T( z=K0NT=afR--o=bx1h%_rw6S;MB71>O*yCTsB55?3gmd9&H9aq1XkKe}$`*gkDiM*U z*km!YY;+@;$E987@cCTP?R@qLHUdO4N3Mo8`T|j0byD~N*Q|u7#T1CTT+B}n-n(O9QM`6#zzGk44;(QgiLYcQl9wq} z>mO85<{vVC>@$M0d!BK-pSrHeL1?SrGwiYF-eNfVT=Q8r4og7I!pO*wU?R}r17Iq! z|COJk)85o@#A7EwSI_S!W5DyoaV&+V$DKiSU?lq~_nD5iMW3V!#x2>$W*J+iKGzY( zoU{YxqV*Oo$MGk<{z9K9RQ%8KSGsEurBY$9uF>V+YC$96BgtGU;zW@M3mKt7bAd|G zX4gwe$hOI|BrT}gF(E#j#0#<7%i{tXf5Cr8YU+pfqZW>`UeuWI*f42DIKqju28otM z32yLSPXG03o$#f^+tXKmgntMmn03I3qx~(g{;S_u@o`bBdI?}6m9GWd7<$V>jbar~ z+SG`(b8Y)P{eT)M{3;YD9Vh^?+%HR=+N5z3b;t4YV~i?5?QkobJts;URvI}RRE+Z8 z2TbGVc$$QMA2?ciW%2u904rtN{IRiMCROI9Gy5by>FK`~&9w}6dO3v$!5RxD*lMG( zGgds*&nZd82kH!5vw(5nyxj(qsPsyWqEfE12ccvFk^|V?6@@6xP~{E%@Df! z7Bc=!9LOb|Tp2%#gZ2#AXWqOacu0St%B8Z6OYNCWySg{~Z|%8lbz7u#hW20z)s4+@ zUu)r|Y(l>?H6t+EhUo|!_mm(Q1-HQBUa?Y}>BzUN@Pgs8E}uiSIUP{c_Bf?4l+P$V z{@%Fz&`vh#br8_p1=UM(yWPPv5_+foC$m)2{p!76Xw-0jKJAg>Y2GHY`wa^11#h({ z!$gvBe|9hA&>0arm)lZNc(piT>A_9k8z5;I^e6~qB;1{ryeD}+;B3$fBR2r{yyts| zV!dBK@#5ccXFx-NU4?x9!2Wivpe~9`c;JfrQvRmzMPovN#IdDAlFt_l= zP?Li3@KK?_iuWRgdlYwHTf`|~1!b!mP_b*Lp_LF3=2sxi2gj#2Haq=Onw#Aozr%5n z@a$Tg#0EK60Img59HYJ zRz^IF@ZUr^I5{d9fxCKTo3vOY?+;1r1E`dW{7B|LE;R%1Pc}6-oQN3NbQNRQ(J5Tc zHrG9p48ga=hy=p0oW_Batm6(QUfzkUk(pT=k2a@=-(Lqy#YoUTC?-7_hhFDQ@l9&K z*IzQut)nLAoRh#qQjoDJ{|u_{q+PyIqlqfUQ-U%RGd4)v{)r=6YJ&TWxMQ%%=w+hu z5~Uf1VTdQ)%sc=%u`{#s#gB3zwPF+*mZdm9>hpG6YqkIq!};smZhk;-n8%K!We8gC zK~rQ~PhDV-^98}?iIHu1$ZZS+hQS#JP`ml27YrSt-kPRV!BT0A86dGQbRl<*CcbwW> zs;wY5U$8o&F7*~Ut9Nv4cP6Y^>sBoI7v6ACD8$%pA9my4~|44G=2xGX78 z%ND2<<2Ys>Wq7b8N;#Y=_N3nA0G5>&cG~^o{+6DVb7d-YpsP#x>}%9fzJ{;lo_ng5 zL`%-az~x1yNzHgw-sB*d*8bJCLW0wFfjwA==W+Yj5{tr6a$CXB0b}y}W^kW70yLNm ztRA^z5nrRqDj}%}l0%$BxNA7Q2x9>Y(!|JP{nMTo4V)Kv?TFOBn=`a=ltOHyDXV_V z>ZFo^xqjrLVk$fwO|0{WDiS19E0+NskFRzCa#f4DM8s5{+`s@juUH9HkGfZxOQtZ5 zBsDn*-IZ$AG`vh}aLz2%eJtzC47{V&!KgesJ~{*$u?$?QyOSFMJ-7%85%eqxVjJHy zr?J0bs5Gc36Z9uj551lbua#9Gg6NBnKEnH#gKwF=5lp?OD9bmTX!CC4zA`60@@92Q zw$46gUz=J`Y~Y)e*doA$=la;eJNbrhp<_vA-RZ#fz)OiW$tE?4G>=6ZXK*#`9WPiD zl+;@&fI&|2K}#Ym&#e*;nzpQP&&FQ=P)w)W2cO}J*Pn&@246OdvNN=K{i*R^s-SHL zxXVESge-o#II{Y8eUq8$vHS+uEg!9^Q(HI6M0XAk`$-2NksW{FxYz$Ro`8RRu2|Bp zshqdUqFMjwc}8Gn2oCeVCgOkE?=NA#ea3(pJEiTq$P4}2aIK5RrX){YN^)b6RJ(6Tn8S(Eeh!{frx313(c@o5k z%eqxSFw0r{5DRY{*0^Pv=9QJAg4eNzA{oRK0Q6^na+A8eBz6spZ0eYpgUA!1A6Kqpb!JX$3Hx(OnY{81%fyau`;@8U*PaU%tGX7Bi z2G{GMnA-+I+fbxa&a^T^To19DgZien!IQjzJcw_I_KZZjb%A6QHK_j;?$?0d;{IAN z;LM~JLAa@1CP|E9^aCL>FxgO2>Krt8;QM}VU}5ARq*BWEF3vn##;yXJo}SL-c|!yU zmViO=Z3qz$pM~&()x%fvT?zBz zsbzbEB3hvEvX3XMt-%eybrfM>Hk@3hcaH80Yx*U#>agUBt8es%vp}bB7U3so#P>|r zU|*{FXE#NRk;EriVNz;=fbPj;7Aw#XN7L(aPODzFyeQm?S6w*S0=;Y8;;7J}a{;#E z1Oe~h^;mTbw-`6n0ICvDEp(GP8@bA^I)TBba->ta7<%(c&X9B$|U%2XfV z6V^9k!YSaxX@1z0G|<>h71i6=*MzJ@9v3s@5)@ zHm|?krD>iaywF|g?gK;7u=ZytpY+Gszs<}+hGonX3p4x^-4L&;MwYRfRXoF2n8jY9YU>!eYNB1jggE3Ho0*vvt5QO`o0?Y$Lz`akxl2_{KVUP zz^Bi)*EwH^e!fn9EK9JEjowIo5?s-{h)EhLVsf@7kdJAA6$Sw7H%CCgb>CKCT#rDx zb7^AoNx-(IdSQJvSZM=GdYz0;JyMSCLNTz)g0#ds$bEd4%ekFjCQI+iQn|W2im6B5d z_PEEKrN>*|n72ag3Tc3B1$(W55|MWqaYlnkA?Q1Epp*timKy!S3kOThNZCZ>0O<&; z0Kt;$PIOpylg6^musAovy3jAu0|KLO0_@&Vb;QJ|lFp*zi2I79WGd3I&m@hk2*)Rw zz|K@f&g99zxI&W`*JcW2nuW_{ zOZyEjI1=o!?b0|3c+z71u&LKdsZL=O98xwND>g7NQK)}sxcSCkkC7&wZ&v+rUjK5D zk4Zs>_DiA#vxQPfk@!MK_UBDl+QfLzg+il|AV8DVxH^{hC&8v+8Jlw+QImmHDA7a| zM{~iJ=!W+vD%VU2VVq^*_$ik=;QXs#Es#JAN#qYbBOana{K3cC&q`bawlX+=h)nO> z6p5ay?CEZ0Ts$siM#e&!Q{S=fWpA9NG^lyG5UiEgG91|tJ1Ur~ zB=Yz=ry|&cfE~!+U2t5VoHe6?Wx@U^mbRT09z-z5Ci($-X>xJ7;I2#+kr|tuglA=C zt*Wkex<8ixIYsde5pPtWw?%XUlKmK$?*nwe_dJ}k+1({lzECd_u;wM>t$~$bYxK#Y z@p1SzUNaXPVXm=OnQClq9-cy}cxMstc*6H|;esv`7B#HsD{+Kvf=~4&yh}iLib8ja zenNF$`ja~Qpl6DWSRC0$0~bEt`KA*Opa%eDHL%sLQOV58I&pC!S2RhFVaGPa1dSaZ z4vfOHky@9GP5eSM0Nc@419iG@K2y_E)*zZ@*>!GWU&BMrAxX~|TNHCFwybGR#4u0By z@rY;1I4$SyrX+%r&y))Fnt>%9&5GZ>m1T7fMrxIO{+!`9#153lpKY6BNKDzCRMc@nVhu2+d77Impn+b&xiAt51n z+|HprZxcO-W0d)uyZStHI-E-8_#;N1mYL4&aug}TB%=SqW>WeaS%PscazJg&WgJqL za`O}eiZtT8uTn>3;8_Z(m9E?S-lT)W2bIMfp;@+Yfc(b$82&$3HUBf8ZmYv3$bXy? zmDat##OA+E=I+<6Yv+Su`R#yDvS#ng?qU?|F;Zdg+&g?6SzWt)XM-fleBb2%-qr36 zS_D{r@BP5J*(51NG1>Srgxmd~`2Vv2;9B}xyT|_!N-(&_;~RC&Fs~)wQ|7V0=f;Mh z1_OZ}|F`3WthSbrkO)NQ!?AKpj-NR_zDYrS!gpaJ<#F6EQB;AV5rh_oj)9s6>|j{D z?sA#ljzNm(cx58cb|qvPaL6LgR~OvJSJO#TrpiHVefD#tZ1}H|Y*6u+v&#Y=4m)Q4 z_F%0?Mzkqk>B8#C#gmqJpzG|iB?-JjKVLpSG=El83>hc!`?#A}uu?;xmV^kbi%nsC z_i?}4uNXl>W83hw&+c>1k{d3Zv#$rp6vapNHc$E#!>#ou=a9|Lj3#J*uxQfT7Q2P* z%+|0xOPj|yh&VoeNb1qo*=EyWJGT=c;&J_#7R<`Z-CL9_=e{4K^sI?#kZW=XXqRI) z_=2xgsisxAbb3j@&xHXI0s)VR;QZ82H}s)T;CG>nh{x00dqZ^I68wt&4PA>o8<45I zyu2ul_amJj4&kqcPI8-}Z-^B3uC8JMwjxuOX{b6++^zC#us_-OV90-KCI;#TeIDue zLa2&WVUVftl8pS_^BVK>j%Lv!){-ZLmKTeVh$^0-@DbNVxF=daK-r7GE9C$c&C*1M zRTEz*1WlD01~%=&%FrdIk-N!XQIpY?;YdO|9q{pD(Kmz7na``^nqlREZa&FK4iCL_#ty95zT-o1FtlAI}D!mxLclV{n+a8w90!B(PD7IJ#O~ z=^=^3ZhPN`txlf_Ai?65An7xn{9ia)n3Qg6{a-gmlTZIah?fNNy#0$1Jih*X47fW8 z@Chk6GL|(1-;#Rdnrpx4ag+(RR>AGS0Qz5k)x(R;)ae)*v2l&O81!A8e_l2h3=WY# zPdC(7e*gDoDKp5e5sA$6{#NYfS^pAn~hGg$Q zW51^gQDbgzpT1%ckV~ssqcn;+yUv9jvg&22gZhCzOoHvvbnOEr-|r!O-0?W&GnJ?C zZu{uvjs8EH&MGR7wrko6?jGFTA-K!nt`Dxk-Q7a);O-VI1oz+x?(PE&?(WXt`QP;& za54wXtkpf!``&d`l?V}?J)E&mJn{ngmsDSFej-uR@JswITg+J5=MqK0!P5oFth1|D zAlU4IjP7y>(t5JC#2Y4QpHzGMVPilH#Z&s0Rlv zVvMkqlF8E0uRMI4iYYX%XhKnKB_dG?i=joK!A65HM+^j(3e=p zgUTAmt@1=R&i3saNkcHLcWs)YWt6gp+MF(xQdqQ!5@1B{#fCl+VxJi5`=BL0b@9tv z8JR^m6s49pYF|#nkNTt#E#`zMws;unZmLUWqg~cG%)=BG7l{eRHGZPUV|(Ru8Wair z5qG`;7*xR=NUPARHs=v8J*AL~Nr*Bt^~&YJ2GXqi`R(Tqoxd}7OXA4-eoNNOEE2d^ zm)kH%BqQCMhb7}VQqOuE6PtmlStk!{xi2gd1Oq5dAnUL@>R>DE-#jZ`7eZl+2p0=b zmEo~B_9zAVzo$|W^~PIKto^bm_d z9Gq}i$ki4$udm(e{z}W~rf_mdR7BrPe54v5)y4<|hbdqX2O=Y@S zD|UcPJXqM$k{%rV5x6^m9Pa-;Bl$MDx4f6rv zID5Y=$qd{3Xu>6Gpn|BBf8o6Shj;8>h9gv2S&in2Cu=v*N$3TY)OeXs!0xb069$O7;%R zDNK(T#V-p3v^}Bh%a7gXh`?-N5%0vQxaE&(!Q zcc_V`0-9HfiD(+{T8Im_|2eX*Z9Hvx9DP9@<=~#RZ4#JoVg!kMa*sOOWaR35sh=H6 z3{yhE6NS~pUK&MLL&r{Lv67y>)QQVUWMnddtg3@ehsoV6gxb?RJLMbHLhcxWTbMp2 z=I;}o`)rL#X3(aJw=DW$P!I=`%X9Oo(DfK6N_@Df=KscVSFlh6S z(r_SbaR5xMk(>5&brdMFCTP@T88FnUD1~R#UM673Kt<%>Pf9%>Cui1j+qD zgA0mY+H&{(8F&<#t>aG=_PIvY0!oUqc}n}>XRe(ssP2#7dFMZbLzg`W6KPNxff#J*?EDqa=m81x65@3AupK|UxR}1$vYiu&;x_Cj zUaZYDgy(j1cQ-SetU^4V4~@uR#-~65dKijxjDC;`&HSs@(Bin(v)LPwne&eWNf@`p zjFc3+MRj-6B%=cCL}0rgvp~ZX;V#o#+`z4&<62vPw&)w8ezU#d{@7`TTdo0JV?oWN z`TpDf`%BP_G3)hSwo`q58x+2&FbCt&O}|S!C`_enKs-YcT>;c;uve09w37|-PwkD! zFX&!H&q6)^NE?fMPGjnOBtWJIC^5Pz+XU%;^O>M@TPthGWyKKoG#PVUJmR44+93H9qUXF<_ zX-i!WIdzGFd7^hh@-RdGiC~Sz-+`Axqizk>fZ0<6Fw5)_)GQ9&WZ$gM+2xsl?;KE2 zP}I*(&7L1T?@rf7Z*EXMPgkTqC-+Ko1X+dmKT4(H;^|gt;u8{YJaA4<+49sO^8+ts zWanE{bxAjAS=|UKb7^3e7U6QKjojpYnCIp_YBJrYo;@sQoQHl~lH{(#KAVryh$HvE8kBVlAMXqp^ zSqC?ot6U6n3>vOvcT6lx6_7Qpi+g7gY=}QiizyT$6!+9qcb(5x^YVE;VKWyF?fde%-q62p z8+uH_R4UcDJ{4)aY(rk5%S2xySB?mUo6Y1kLm}AiB#_kz?x4fX6LxOQOqU;(AO*eu z^{nHu^j53921 zIlb@Sf>*@Fiq_1J`#kdkp9t>Gz%tD>7>i`*m7UoL)|dFm(5LG^c{5u5(&y*@bIYy4 z4(gB{U^vo(xh5vC0#^suD}-OC=QiC+KblhqB7Qe9BfU7BrV8Spo4)1nT$wuc$xEy; zi|kOv#cV01z^*3&e8rDf$doyEdZ$tXzunN~roOLv&O z0N;2{6;k?{nwO~5vI)nfN*!~4_!A)uwEyAkf|4E=MFm0bfyLn4Y0UYWd};BNa`qor zn`1bonm9HCj^u#dXR_ z?LlcutlGt^yr7cLy*IhA-z}uDr6hK&e~ReE%q;Z&_Qgo&h;uBkA-^G3XEU=&&a{Ic z$h5PILVtk6XbVXXT_BNh!8ihCr^&_df~H-xWKrhoP`F@l#r3yZU;`C4TX0sIE`*}M zX$PfZZMvEX;;>q--E%|kZh?c07*Hk5DHcUdn-}C5CKd^;P+DD~BY228%nml2a2qmr zGqQ&`-^HG+M@t@g7evi}gI<0TXIK4$i7f6$*U8gKkVzktgb!D7e%sG}XUf2sc?>RE>Q=h%JF0gl8g^7inzy4cqHngmN zv2nqiya(+>)W%-EZ)SYA?)cG^9OL4jSIpsJxQMC{D9fzynTxAWfvvNzqNZyEIOHq{ zy3V4SpBcmx;bISWV^v{C*-Tv>d9xlhwM#mk11!bD`pKn@&#B89NCC zo<$}(wr=)|QI2|rE>-gMQB!@Me)YtzE)h65IFuMyo(MA{cYF$%ynVHbc^!RyGt<9w zJ-PY$Rz5y}&h2QsDSd!n7|V=?jAcmti^@)CwddC1O!cT;^q8aMg*HLizDUhP${;TV z-c3=o7=k7*H_4#zF&DX20!vm7FI)}k1%uSGu6d{_lYw=uRdUu=mHB1{!Yfv#W>qMl zGV0XxtF*ouRG2_#XEC&YWhzWo1Z6Mj;{MKdF!iafHt9x!3L*4_uT2d%Ew_Y*#DJ{v zIQYD(n~aF%{fx(h?mTGyrhh#sIpBmsxENwB54LHGKXCxJTs~~}?p#Y-r`)q2FqVL* z(kJIDv|Ifjkw)i{;u>oKk9P#VB_o5y5w&B+$b6?hbzHIJ@82rjJ&Pl@VJaf8q3Mp@ zjgNR#rcCa%a9xuR4}AY{cXRj9$46LT0`DSQUF0WfMKpw10N%5C+fS36+su>?v~_it z^VeLh25E-vp8w*F@fJM*fQxpqv^vpSZs9yT0fEBum?xLxjfQM+cnS<2)sV^C(g#`w zA#ZmrE*xmq$#Pf(8dywUg~a1Isv%J2sEg zHv27E0)$i%n!=Wv^s@ZGET{KrvdclpqZzZ{FHU3{^jU5Kv%uu?bYWvoVeavHrbQhigT3L9 z2z=)ISx4@Noox++4)@H~M<3=x=ffGPr)T+-wWef$)9aLU z5A$pFXPj~$Wvh{o9NQN|)rNp99DjM~a-m2kJSibRoW`P$Pek}v+LggA7ywtBvS)Ed zJ8w`^m+yx7g3lXfbhcM_U?-IG_Ro5lgK3t!?BG?1eZGUtb!3r2*$y*A_Luo3%CQRr z8=1rA2j^_F5J-G#GR*qZ>uvBEUT#?V&}!_M9=iW=%2@t{Q%lMC)eI8egz?6<1{o(G zhoX-+0!=Rd6(=+HicJQ}peH!))PJ`GkKb#PIGt5_rg9#$aP~8a31R-}W`80wB~Ma# zdmgSDsu~%SUETd3qpq8IHqH(QoU0yhzyGucrDjN(3qJBXDsuYRB$bz!|BgEtfWE6p zO)288;r<-TnsMox5^}eqiL34X`YbADEAFHcwcm9kl(|k?%<&P)%V~9QXHw3+6s_XR!_Y~yqBT6#nzMCkbEw=`{v>tC#*25Po*{bdR zddwqx@XjNH@0Mc#ZLdCor55?(B+50vL%(8Rx^M37OQHOQH_uVjK_UmyaReOlwNuhb zto|3AfJLFWW#kC^fuMv7qI`WqLu&tyDtU>+87F|@g`xUH`zh2KFX>6CdHxobgk#E(+tItZC3pg z6c}3Yj|aH111`@qks!8Kk^Bn=%!4@BeYu#Gk_ZYp;|M>TLwbPAgbH|xD`U7@kHMD3~I>Kq2obeBU8F_0-C9RAvT%TBtFV zn_5;sm#5oZuEbdTbv@#yf(}`L_b*x#)#{&F8*KsHJ46DR?ag`v{jG@^2S>KG($eF` z5`~2;dK6rjD_z20(jFxs4c=Nk+}Va%oLtJ+$B!L<25*Hm;w8&bdB5{1@LB8}TF#B* z^O`!E9_>(mnO0|ra$1Jb+p-&-3sPfDx#p@P;0koS=j2h}>Efg6t6A{BNg$nhCrv>h zp!MasK>eW0x@cDadt^86+|hOxk-{=9E&X3}rb2Y|2a27Xs03vu1cB6v%(?buMf(Gu zB@dAB0Ob3RYmfbaqg#RN>uXKz3LL?sK2J5`63dmeVav>nB_Md$t2N-6C-3e+vn=_} zJ?U~qSy}n&@AJ7E5UqhmDj-H%bWqxeUzYM&b~(+&-1}>hOg!K#(XCc7h7{BhCJfP! zkVS5OgMsOyosupbGUp%`a*ynOVtWs>%JUiEb44ta@)r$d#J$fk(TL|3)(noSJQom@ zJbE9u=A2fQ+urDQ-h?VDqB>b`xX-&sY)65T4wvC`Kfv(2KeccSjO!26{X>~NZlcfA zwZB;w6NK39p!sNH#?e93YiDw_f7{2vr+ z5gs0%0J@rJKd)EU?b22;3tl!Cqdum~AHCd3R=EPg$FzwB15rjNk}{^-7L*x({P}YS zMQXqw6x>jz?DjhIiP**rQEJ0ClHA^Z6{**FK+TbyTU%Sp`+Y|aC{~Tcv)p_R9vm4# za=UipY8;&()z;C~Mch{`3LpttmRdW0py>%vg2(R@aGuFmnatUIe~t(;IXgoM-luQ? z&uN^fn^PfDXW^at0&_>~@}rOKDQ$(F9ZC#JLz{XLS5ADI_V4PMtjYl$1P@z1cl#8Y zc}cVIq`6~M)|~D?M55lg3i)|OgRa)CN{kgun#cb!gT)bt=bD(9*_bb;zXmfIm20=Q zH~vxY{ElMRd5BOgd~js2vv^@K#^hp#qvI1Xh(@|KOeN!eEF%gS+l}{c%2lje4234) zjguQlelb-rk4vFkTTg;sKEUVu=S)|bJ?Is^ zq%5p7<+&eK$#N;rTGI30(<+IXq<}$~OlI%j7M;W>gSF!H8gwg2WlQI52Gz|w@nosT zeWN+^^GpY;f#~2>DVu_rA$s!>vG!>-&c=Yqn(ix)oXXyycc=H*px3gXzl*Fh!v*#c zV$amK6unYKN*idVQ|JPpVeAUDYA79|Yl2=afY7-YhVJ`V2#vmMiMk{051D<3&VIW5 zz@AhlZ5>1X61rsMhDi{e;#g8S(c#&rr~X7VRP{PqN-!1;KAMC5S?rJWQ!>0Jolp71?nT^1ImH>J9C)p&2o zZSn`~%lLiQV7LFf@y~V-V*C0`=4Oi!<>MyHdA??cn504q?J#jP@dBI1tR-RHuD959 zpWFDZ@o3|B#`-~?iEDB(+otMlqT8p{R=1A36+3|So^fn9)rBIs66-lkq-BPMnHkHj z;nss!!(t#YJ}ZFF9eh63>_$w1`Qk~cJncj@l&2Ox1m~wht>2$n1;Sr8jJ~C`UlAcA zoGdwMOqay?ldX>bm9bZt1>}VZGKs=Z;SG0++X2qUNc~XT*xQOqN}olYY@?`NCdQuV zshC#TI>{SHWrGn4KPAH9oi1IPy*%c>^6NJ{O6hJqBdW>?2!2jX=Q%>hcjpuT+8511 zo(kO=U>+{R5a&R%$g3y_QP2>W^N+gvP<5dO1Hz8%v&lyB`mqm-ph2f&x9XYQ+N%4j zf(ZdizF){=6b{OM5JYvk_JJY*YIl<%o}5S(e~7cbA>P3cm`yBP{)2|tQrV;1lR-Q# zo2+bipIGI;*IN3_{URT(OrdRrm+n<1BKi(nQhQ1_Xm*arg0;PE_dovO*%e-h z)u&5!gBA+ffGsVnxn7S#*D-QTST;>2ASvi53LUyv$KVgOz(mN8fzi)EIYIfxjHJ&5 zMd4hJ*5!!lP0{yTnfle7G5Ioff-A{uiwbJZ2B1*z5nE0?Svr)^B~)p!q-Y#FYHrk zpJw@?DxvIKqXt8zTa}uLf-hY75IhU3VfNn21X$>G&g_Q26r2Z_UF`49tF)G}W##l9 zBi-N_&TxSNWzR4T%1q)CSXP-8oa@H>ZYx7bVtLI;qaJ~^FH?{A-uAP7ff>J**EQzu zX2*t$aJ9oHnfL7!)wPv4{$$nS#7IC0{>Psr_OAiCl!)X7tJ-@^K;f|8-3b6uBLDLp zctHZvk@wl0t@hA9H1C>#86EXkT!>%@A=gSa*;5qzZLFuB*K$aUV5|)Z1&6nA! zUi*IdB98=!VZOtSA@ubzHjH%s`0WilJG)r9<_|z(shj>R-$?^}aCLd&!M`rVAy>1u z8cuV%x<-ZSx~2{esF3^e>MFHzO<+R-tUIQyxnihze<4Q8?)@i&k1@QSu6!kTotfy@ zCXn_d-|~8EbTitc<|KJP;j2vXON>5<#=|uL5G8{n99r^iNpe76swt@A_qZ}C_Hu-+bODgZ_!hjzfA^zaykT?fq(P+J;+mRL!^?<)9dp4Bu-wo0#zkrsl< z@R90vo*W?~FK=(AWOOy7>u<0GJdaa1moAt5Fm*)!|FHnN^dF(2p@sZj_`Dn;n*-xS z)ILhtI*p$#eP`D{EII+1HiKhhhIgWO^aTj+F_D=^;tzi2_~;M_kU;@?obbW`IX~Ul zl$MnN_tEca_!VgDlPEkB?|1zyf{p^Dd#sX@smg3Bh7pnaC1tF$`aU?)! zPMB@e$SJrbGdGhvbDI$1by6;flCL>MoD0^hLv56bo`&rrql0f4r~@3&Tk}h*TU#ciB0ldg(WQfsH@$57i*c-P+ob`c?6t5M&T3Rfs0lB`1Q{(-4orLB0ek zUgU`$z*M$?q2>Q8NoZ(g`3v(2)yZ1;JbIb>JNr)EqjNhJ&cd1l1God5)S=Sk+dtp? zFewumHPZ~^Q~PPOm@2%3hnvu$@_mbxibztxh}o)^qLi5{$}_> z!LvmG*am?3jjdKztXP~v>=L`DnBM;)YCWU{tF-OrvXuypvVrg0lm_EfQ+iN@dQf0U zD{p=5nWIeQL1}6Z3{#1go%7wS8z6}*m#A+}#DdKe8==#iJrO0pCJhkG*e~eXw{tBJ zZv4&Cx2kFiuK~lM#ebMw{9PS?{%xd^C~o5M^r&w=;Q65w@*eO@;nPIW3j>V93u`*OFY?)@@k=etis;5Ww# znMHDG39`35p1B~ceuj}+j)nBey}s|n0X88)T>1Hi{RR*(3K$R(RfF_avthMS*9fp; z@%DGjTMrIQ;eaSz<0McwhSdlM2ond~;oHS>1K}bqWu>iduW)YH*GtW@`##=|oRx?K zXWDt<uV(=ZIeK>QFq%vBZ%&<-AcyKSrW>%GMM`SNzx4% z+Pk!T`eE+E{z?!j`}jU0VWj5eZNjGwXQp~qD)$m|%a0^G7=Y<>8RB;q5cII$RF zCiTWFV#tVTu)7>FacYEXpi-f) zXACpV^<1^q*2oHe^f-A5FqZen8AKYFOdMFzQ!}4n*{xGj%K|Wonxt# ztc6ao4sZpmx4&!=)WdzYb$OitCLuH9M zn7Ml(q|iBXY9o^z#<=YSRN|bNo(WsRaT?t8^O?INb7m~QUw$!W@oS^o*fJTS9g$>w zzop2S#VbDd%|+?re*1(_s#YIE`+4&an|sAB6qlX_qYDQ8TeDaT>?v+!sdO9Gbp5o$RJEAz%p8gq z0R~SnR0W+x)85vzk|cTJ)7wWkqAF)>KKr9oczJSWNQ z_OZYcG)rdKx$OAho{~sJ-PXEb=vKWQ{I>P2B(N#vLjJz}z5%riMy*gI*f-xW?!9u( zL04HY;s=Cflp|6_-V}@rI1%*#yyupo+MpFsvQ^lHIH1HfXtY)SaUI zMO2Ji;~l`w0JTn)Bj}ZOcxY3sIX1SsI}l3*l#g%0t0j~mB-3fi=to3E5Rj2sSzAW} z&j(=d9s!)1>Y(H602?h|@{$1#oNd`;TkJ}CQa7IEKEKBi&cB~GCZS5i}4+iNs%wzeJ^74W(V#pORTsHs&^4PycH5j{REtlQV&+pj#+%LTui!*ONnb zR2q(!@xOzK-u*X|V)SP3vBDaqQ&t2{cM0*X-VjPz=p1)?{c<`H16uS$iq}2WMoS_F?)08m3&oC^K#D% z5V~KPWz16LEqxUb-&C1<(UI+V(Fydx3us_M0up>Bn*!~@_^QmKLHY0yan=<1RXWCQ2 zHuVyi4|xc8GzTLul>2_iq%I=(Ci_ip3=axB>=2feWzyp5iEE}#M^DGxd=z0sS(q{K zBs^BWN!i^$_k$MGCy|!}3CH!WSS%oS;YVZNpgD}J#ef?8N5Wt-vCe5pYtxi>)l;m^ zoH;G+%yvPAhH3Kr(ae2G#Ei?|9^*d06(a`Vyf^#teloMn+H(Eo<^(E{DI|#$bT2!o zKIl^tBNJPgAXt1@Db*Re9Lh8N$4D4IA1!*D-?P?dDq6>!WmRZqw@q^w+5f;#t zQfD%=`Y(N4kk zoWEdC9RmXsQ&UWEGqxtI>4Y~0Y^Gv(%(m(QQ{8>ttI&Na+x5+**$wKA1}X8$PMPzY z#(wFB{MRa)OON8`m6dTyfFuxa;W<3uVf|S0YuVw=E;;A2Q+^w)T8? zaW)Cr24zg+TO}=$%uT;2K!YxRB74Z?|Lz;(Soe|1K7Rp<#2R-G4>0^7@m51j{O^@H zI-wbKUU8&4FgxX`5D*y-ARK+8H7{s_UP3+abddcJY%=G!RUiLJtEx8XP9xsk&)>+y z?{Nzi4{pp4S#CLmxcd6~U?zp{iDmKymESKgN?e_;gkTwe;TQ5Iz;SPYEL@_{0|S%d zMTPoLiFl{;;*luwi-Z|E!J$QFj)lpSW`2L!1Pp&Xr##+H21p(cFu4|mp*1~&sRDzo z`aIJoCIuG^7XynVTKnSV#cjS=oec~qy49UOGqY7)oVANu`G0{2ILm@2$>Xo&?3Xvg zy8=7;p@q-Bevb<+M*a5zjH&;LJRL{??XHn?SwEFY2*1?^=3<%f^ALbRvT_hHQ6Q9Q zUohxuP{{2CAKV<5WoL$OdTs1#v>Mbs4@0YvQi`rkD`Vp*3 z`r1n~;EB#z=Y(96$m~!dufdC9T4gZluz5qz5f|djJ?;rz1zpTO3=4|Hd0|H|rAP%m zA~87BFO#19k>)2XlbLm_tT)KDu<;1~0>Ox6j?`qxjMb6Uxk+!n+N!JJXmmjKB5auB zbimDa*b@ne-%S;SIVE;v3OU}N{t_j|ymjQ$=$3tCo!gVh0sU&BcS@L7TU!z<0q2gq zc#Q!Hj$tRDJTRaAkQ`j0n!#+a%jEnQiMjF*oC+4#Uk9X)Qc2!F4qu(QXLx;cQfBzt zKG6?K>3r--I=-Pxe*Z0pl}mBO2yQ=xIScf29HGyoQ*$ zo43wyP?+l2G={3qJ)nUvDWG1A0fFZmTq0p_>`lS`^g*fvSiqCMKrVYSIYEHnuri?~E>C7J1t- zQ_kW0JD$x89NWCR@GKGamzrHTp7Y{Qmw-&T^zFfTw}UB)U-R6}4&Z@2;r8KM$;{u` zOZp2=e~trwLWM;N|>FO91*Q*y!vo|>lPYxo# z{8o}D?9x{Ew|Dgvut)KFr*<-?)bTVN zk((DFu6a()q2;quGE-Trsc$}S*gwI4vfdQ&xjX7;m|X{-QYES@N6Aq?FRCt=>oc;4 zM@f&KN0vy%chZy;2XSdWzNO=1$;h*2e@~79$sTAH_pR?RU+4tT1WH08kT?H<7Uo!A zI>q~3IAY=fs7DC(N94>7CwrCT%{SEtp$r=%_xrgO!hxKQN+(ep4;*!(ulS zkVlO{yxF3Dya_h2EY4nCacC@-=@=T81Qm2V;?17c;>4dpCKIVt+>YjKfK-&&3jG5Q zSeWDm7y&WtdHC?*;pmRHr|zo~wxB4`rW&zTgRRJ#7l+D_B{Q&*7y%&t!FVz&-zT_y z|Ete4_H9!`AI8rdS@bMu4HzU4$ZCWAZby@{*&M8l@Ij8PFykY%mc@o&*4D2|rhfGG* ztJ4Tf0W-PVSp%umf&CMOJRIBWsToVR{kmd zfdz%Qcm_A_15`8<9^K<&(BnsA-#7lNl2f^-4B1$#GFZXK*$73}(et2dbb1^l6ej{8 ziH)J!INx&b%uuh&(whm}oo_{OU?Iu{E*#FLomB5{@F4ot&{^)uN@w&S>6%J;3*MkS zr}VyFY$omQP9!P~1GJo`mAu!bE;*=GBNXmxj#~B)Xxg4jC&##;t?hg6BxSGbw4MyQ zg82+SKgC!Kwt!2RhXj)o55%Q(8Txw*CYR5uhs`&%7qMB}_Ku*d03j|F62Xy$tu$`} zx>se{Nabwh@|vN)WoQjfi;jWkyMWZ3yS-PX-*La*4&+u6(ruHMfZzu%=WUy&#Kr1V zH_FTMwjR>+wl_8h3Ghj1lP9w|^+!CE6K~E1`c=f&w#Ugj|3cp4yEo5r+pUd@h{NIr z|HBYha5CY4Nu3d>qNd@bH~(2A_l@1|y|V?f3;Y_*9dQet5?MoP<5I(hlRgD%h8PwD zSt$7$x#%dOSOvvW1>9Xcew7YZ7ee`D?>lq{7#2mlZS-I{MF)lmn~uhw&DfR!)Td{u zButW|#8`PmS&BLb_|4WzW|r&wp!<7k{i|`Ow~tyA>m5G}Ta~;;LiaP^AHM_x0+-2` zXTI*|5n#@59J{&UqEqRZ%v2HWum9&^kChJ5st7B==~s`+ZTGxdb({RBd)f~I5Ow5< ziAcHFl*LQTTS{&O$wO^h?NG@zo(}-HZO;OLizu(cXZ=2;-L1GJvgsxF*#EF}BvJM~ zgXEpIHg)TQ9p4LN_0d6VJTb+b_rHVO_hu;0`W6o&MMa>^zCQ?c52jOQQrLRo#mm`1 zvCNv0-fDRD9uDLyq~LhxO#)g~tDhH7qD~1&(!+9_r`XDHaIz`2Ux6(k)zvt&`w`r| zd3Ord)Y9S$IumO072e5Z*O1Y>N%dWB_Fw`xJDGW#hgt#OQs6JHFcI^rA0$LO?JT)# zk0oMo9=UA&r}2X+IAI*r)%Rz?1*r(^`~-KIL%Kp4QsDr2_~bufSzPf(5ifjXXm{4( z6*SaRG%@@FtvNoZOc89o0i`Nb4|E8jOi$dCyWR8%8}&WO0)fDQgeVTnw0!9|)KbLHwT zaNqZzLf@b}avv)t;kd>+Wyi^5qNKJscW{Ymc+a_K+cu1F_C{FyqIQJ$kBxs?z!lcg zzvg;HinjA={ZDYb>T$M~dDz=WuUbZdM`CzN>M`u@=A4a?hutmR{{U9gquBb=|U4Uxn15&?25<`7C`40}@~i}O4oYMs2s z1O4H~2z9*FpEk+o>QgR%)M+*hpr~aA3Wz{(+j$yU3NsR-i#V1uz%kM`^`PNuzEcy= zE-;j7%$5}uYtKTqs&U>Pfqi2*E?l$tuMB>24x6ifnc#%crukHdI! zpb)sKz5^(_vrUyQl50@2YN`iqcrCKaAvzsTL{IRFR+Qi71q%!Cv^)A6&T&!jOwe|+ zMa371@KEymH6Wpg**G<69eSDYSNsuc~SULE)Y|k^{A46{I=j#hl5HA-I zqC2at*W}cbq(N!Hg&*BbMm|VgGo7XPCmelIQHcZ69BZxaNkef?Al>)FI zWM-Ba)d0r3L$U*_FaF=`dF-It6=(oxbLe*GQaCwwGGxq(%lJ^X9*1RY?E0+z{Aw}i zbx~0{+>@$A0Lr;ZnLY_}cb$thN7?kiM zDf6f_12(meF`%mO{G7L~tgNhM@BXv;A~ZUxFh_(MqKIn&Rb-~inKtlE(l~OR133Vj zW*34eCH{UX>ydIQ3vl+b-Bpbr$F8I^TccD-=G}05isl_ZHwg9KjCnA|B5AGv&^)s; zvCgnB6w6@@diWdH_|Wdl-kPwpj96b!h)zJt95{2{%aWAme*W!x;1+(zGXyPv|gl08g@|VW62e0GmPG1yu z$II2|O`1F{)oq}D(N}vBg;s-79cIEvA_#q1wqW`!QWx+rL$SkpN%%VuI4#S++X_?$OBbe3SHIhg4uH9A&G zz)IurPb%AAKYgTKq$&rCreoJ~ft~!X$a8y9faw|IMC9KWAEUk+EiQM?w#zx5|Jt_DsL9g?vZ@GTvHUZpab! z%F`+ejxB$;wAZE#mBk@J=BYxlb};F}Or%`nr%;#lNRMHlyMSIzQ`mr~g`Qq|O%g5v zV>KqGgUl`r*S-?*Is&yR?qE)@1mP}R2D|0FJ(vMt&ZU2TPAbLccl?$wTq4sXT$Hex)+hs7Tvb?EO>og} zZa|RNY!`iqckZHz8J2tk8MEujqZI)ukr_~`3#c*d{QPnORd5Ht^EUeW&^*t1MN!b? zq7wy(Gk+U3C|mwVak;{pI)c>D(C{-4rE}NFT<4Zb0Gm?!I5Hz{!T2G(v>~&uq0$e9 z;x-n(h&s9-pR44k{ai&Ve^cD?Q=y6>~kWKTc_@;2N~dy2a2La;%F^$f~;TNipY zE3zko3@j~t&I>qeWuM`zbm(l8FEWC!B4ED19*QFY=nipDb9@l|Z=|`Wrk~0A56e(m zT8u9zvAmBhWE~T&oL1H?D>`bL4a&S-$3~QoR9RrQB%WF6A6?YPlQ+WTe-=fme3842 zWRO+U`m~T}sBve^FX0OPu@1#eyNg&IsTuoY5psd#QXDJ_*sia(P0~ykVs^y9Rtp!y zN_w!PJh_wa%OwsIM7!}(NUj*@;uR$4Vis%;*@p)vpzl$_g8UClAMc3Q?YItx`0J-{ zWIAFadE`zE!n^#_x=bRgP7w#_XaT_v-q>f8iN56LqFtp{1yI!s$ipRFKnr%bxB0$u zcr$9|K7To!)5WUCHtv~Stb8i6)x`CLzSHI5p^A>K4mA@Au|=V3In^)DZkj+%;QWga z@J3)IDO_Py7T6&yH9NI?HH zl`HZ{l&G89xFp`M2gH|@&_Id0&m%e$M{I6l-i2B?Uj4%|uo@mBftQ%ByV#5A25_0FO-!p|#u}sYVI07RGpRj0fu=3Bw3>q1% zFg=8l+(L28i(|7~^( zxZFY&VRU-dyOb%kQ>?)}Jy|Jg1R=Hjg&5?a%h@j<+!baWp{pZq^vpw@$j{(i$JUHC zCdRmU9hE*84ZCHzNFFGeP287U((LTdVqLhQKW;xJr3sC_V%T#DAwUp8;;4nJ>nQ4EQ@K(P3zi8&=}K`)iIZGieqtE__L3{J$dFwI}>*T#7cQp>&nlIqfbimQO9jS zO7y=6THwnz+4P~i&k-Qcdx|7NsDyLuHU+ZI1$yIb+wadT9RqQzxQU3Kbpd~fn_IGL z>lk1%b#rqg@UI?{>SUrrx60E%h&>J!ifwdh==!U`*4-!iwk>*fIY?GFZ>^K(1|t`a z^64;n&}%7p%zx`Ph=gl{dw^dsrlFx2!Cqa@`}}{o8#>HD=|DzKj=8Vx_vK7oBv`UR zk5i#rq0oezXW_OrR-iRBHWpP6*bsY0YgI^9%s2Zu`x*8O?V)K9jD0c>H|RAnEDo}& zFfmZRP!V(lZ@1StX|4H>5Lv_H4SPdBcMqSzhM&DN=h8S$??;I6Tb<$8%X5fh+?G34 zyKau~^Y~@+VSn$uJUv-%iYKTU3DqcMHV`Vr;Oo=F;`Xzzp8r`>Jrl_TSb+8z8x&K2 zDW=kW4c5N7lY2f~iq*87qO_RfF7G$RR}dZ?iTeAIOW;+e|NA7;w?o{uA8b5pV3Y1Dv=JrxcBF9OFnu51=y_|U}i$gW32 zNeO7x+P!@>%g(j^JZ=r1)t?ElG`Sl8qZuYfG(Iy!`7f~yNXa@`?~I6w8XAk1zNb^6JdM4i_0%M~EUgr+o4B#4QZ( zbXT%3j6J>0nd9d|=zUE_Q}?SF-du!ibW)wyHFwDWW!ot4n<|FM=urENd3_~RD;t(7 zPUaxkiz>HMQAmz-BVeeNrhVYq_WP}`K;O$%WP&YnPCh9i&I|xUhcaiaez$dvt@kj` zxHL%b!KO`bacn2n@}H;R{FcWG`$z`FXP=9{RefaQ{4rXWzN6|FUifPW?ry6Dxg+3# zy;BPr&pGTPwq?&Jp9+Nu40F-Qz6~n1;ai-Q4)Ce-?Ulve{(eSI?iZPYuP(2dFJouf zW}f-6B5wmFPR>trHUhb5`1LR9Eo;s3V06+y6*`_Ri?fwZa||ibib|Sr&))W_aJPD~ zS`FeQI$t1p!Z>?no~t-8o&++cvQuY(*BR)okSh)fTq_ZLx>MY31~VIYw$GXZiF87O zQswFc$;yN}t_GERUJZOeiAZHOM)BS3a`*ClJz_uHXfNTr|2A5)mN{5>*uzX|9O zsc%~Ja$XOp-ri(Hw|4yKtSgBpid0^F~0rD%uy`puXDh1gJ?P}s`zptNxG^Nk(}YhL#s!3fAsYIKXBkx0`*vXkezY{w z(s1bRk`8H*?nd$ehYsm(knR#GX%5}pNJ)2h_q%;({xdRul2P2}+0VW1wbq3~HL;X% z*-BI4iR;hV zIpEj6s~uJO&KuJ&ndaNjks8b2^2AdbnsfK(fw8>cXE^8DtE7lkN1{*{au460galR* zk+H^{XYqI4th@dQrzHke*#C(p;C)?(e!4=rS_T4P@`?&*hxpo*Vx1ZVU5`>(z8wP+ zMcu#xct@2kkd8Eh1UJw?e#JCc`MwW{#?rOtS@_SkK|nWiof=gyb#D=iUh{MhVoFRn zh7{Hpl!S8`s-yYi)BV}B8^6@l(Z@zv+i`!C zb5Spfx9yV6d6fib1Y4b^7%a#_U?g;JmoP!II0&C_&%TbFNtX-f8*d`1oEe*DJFcRo zOWnQU&5Hg@raS_10G5Pu>s^opktm3&-yP&ViALWb!$g4F3~Fv2IMSOIOHe zrBcklQOikUjQBF>GEW^Njb6F-UFtSkiH5Be*TS;z*6P|Op8HXXzRlI^d&a=f&d7wm zf_Y8+K6F$jOG4B$JM`?yJ$t7#xK$0Y=3hAo^5Gi$lI3g#Q zEcS39PrL&~U8d40vg?;RfpNQ=luFi2AU?ss{`^*+#mKQ%HuZI1i#CVgThC1cA9Wzt z_TSF6ObYfF;hFRuE>R1N+21Fb_%St4Cm<*LDW*rknK40XsgX}0AJsf6{VBR*=~At3 zNG4Uyrj{X!16HguIvJ?^95EE# zWMrrT<F-o5=^?B!0M%-{ z<2B{2JLe_zE%@!=X{})MYq>EMI!SuU_@y|nh0t-coj>$}ua0}@vG$BC8J|522RT8% zWiL?(qHNGOyOGlIOwA(rCTOXcv%B`Ps`=1m_{(zL( z3@H4!ChiCQ*_g8kZv_&OYD!@&UCQt~7otHqV@8#|Nab#;#N3L5^>S?&A)>W`Ju1We zB{6Dn-oCw1x*d09Irtu_{M>b~Qd!tK zmOM#IEus!{3QVOC*p8Ey5Z%E0;3n+bJ#rC<@fV`;tI9PxI!3`FIgAHNYS z`K@n1zDn-KN%UDJ-0*iu&@=V}CNa+s3Iy%A$9%04Hdum=tV;|YWA3PLb-h+!5L&y) zq!-th-Up25W?4h$=ai_VlJve(M6<#~DRPUE51cZ&R#0P%@X>xE|BZag1|j-PWm>{@ z-Apo`)6)4wE3%IMwvHa^Kz!=ob=LZ7zU?*t)%(V#!_ruPrdDC$!i6|P3H(zp{-~pH z(sW>Li&o?TGjvUGbSw7lz28HMUtbTph}*Gu!y@>hsZt;Y z$>v^AgAB<92c+=7i2w9djvo~k?9($3P;>AZ&B8{%Qa-S;GIt{Kj-siF;aOZxDF_?U zZpJJiNgAyeO#W+gT} z9TQATbJ*XjudpyBAry#2jTL-><6CM)`60QVjxIAoD%m7zI`>h+AZxG!(+eWVC)t%j zjfPw&K%O$LXY}yQZ&KfBt1dfQbK7gSN?YhaG@2y71fOgNE-t$^VNfaKvg0 zn}R24lx|4xGT|9o1)r$#Z7|meSvx{9Qf;P_7!TI8WY&WQ5}kgN8lWHC*TT+?6-au! zCgm$W@7m#rtvA~@cJwy4+oI%?0@c5I*PF+6 z=pgPql4Eo5G3od6(v=fop)vpvLkYmrhg+t7>bShkhY)e|Q^nQq@3;>JZ_H zkL8JQ`X|IobektOh!$U_ykqhHLm5HCnQji=Uu)C?5Jik#%!V$X^V`Xkmg#AyuIumL z0~_`z|HaUPBO;W=tQ!VT7yq-MEiV0q9K6uQm0Q=}wNBWjZXB?}aV1~zb%7lcG$%8k zn`~aGaCnjN7XL7|^N9903k?sp*Tm>nMT!=hKV9R-?Dy=1zbfXN@hwZ&B~sYXOv?9- z8Q!5HdIStygxsW2%wB;*(^* z?eS!dL@vRAP^@NZ$y!t(85Ux57PEA0`$$(H0(5WHONNqmfSbKStg}}lxXtTMg&r47 zY%cUb5Hm{hpZ`Z|V=;`7_bJT!+eLT=X8EccPit?&92~Vqs9@ryXX?`6UM+3c%yyK| zrN-vjinyKv*Aat0%BqeR&*o?y9;u|SA|n6j+vQbN96UVIre*QTNEDc83DVIdrj&4% zTdZFz*xA_p&mLsp*dExH(i)WVT0Lyf3$YRuOU8iibN7?kd62s>!fAU(l**|6S~z$# z3naiP0}`FOOH2QyN|$mm?IHY!pQGVBSh8PAt!$Rp^BVLIfhS!yyBYhoCt_iI*FD%% zI%j#GrMC6eQvuO&MTNTumB*-VCX_X<`qMiY#@%v=)qX4bBatJ2H0GPGI^VY@i2O9U&XUqbCjU&$ zCB;T`1bE8#^navifF7wcIOeG$>LrG_@yDO}Nz{3NPLl-(BN_lN-|k@N>m!oq(gZGx z7(&7Zh3{r8GkgVs{$mw@m?V{8sAhs0ZWS4oC4dfWYcOAD+j_ ztmdMYA%H{})~LxjcCjy1h-3a4A#H9Fpjs59s$ndMpYunE@+iLi`=0_08QDB#BOrl0 zY__S=G2@XuQ@$5$a#U_LTk2{Fx5k zmRQ6o$hRdB2ThLVf}Bt9&;@0%s#X-cf^DO*@4>QOFC%$qCFdw|3L)fn$++iDG0C-R zC?$nX3*Ltd&LmCB%*+G}ApN2O#AEs^X`&+r*y) z^X)F4@ThF;4_ErA{MJ@1*geqsL`vsnxzHcq((zMNk}l}tzu4wFVABO~wlEc@9k+gRhMzl`g1(B-(c-58cx&y#Enk^Ra){OsJR44h` zNn4M<1V3>Fb=sk4>9}S<`@}m)`rLKqJkaIS8^5Anh_mG!wmYc>&(vuCm_1MrnwwJI z?wI2bTnBnloVEv-o*!p5@6UVCp(}dP0CMNQm^NAT*-TChjQRSdGa*0WT z2>L65;Ntz}T8ZvU3o#j!qE1;~33)~_6Y4NlO1}H)D@Of<2NLpmTCq*UU~D2e_^6N>M4^h;pU`FPx#gYi_9-wnKEx- z9F+3y{sK&vd{K-T>v_Rqbp9-m8XkO;Jj}e}`44O_?+6Ig;V4{`_5H1pBy_QEJ_I4t zx`LxSuLO~OF{`%MQ-q=lkg|kvOeEN-Zeb~Kv4*}6>QgvXVmxK^7R#24>nP;h>;c}s zNviVd^q^{@`FM4DbHH>mrjZDoEgfqU3v@Q?=DM#ZwrSC~eYAE(1S|sH9^Y*f)&$^N zLfN?UNy^DJhyAhDer$$j9lae>I6H8gqjo`7vt&>x(XvaOqu4^U270S!)r#UqvNSSc zg`eYcUSE{7^|g26fu{ZTr!&hMe!ff|H=>;Gb2q3d{ZbkhyfSjI+?8Tv{9b>ITFf4i z+I(l1b>~%%klT-c4A84%iSm57_QB`C!k>fl0F7sVUZ|RD_gs0255B#RWm29;al!9?Sp3D%}zfQ zkbXdUrMPp*rY0;L8SNN$;HC|M&e=qM$&tnq%dH<*wKI#qjQZv>P~M??T@}zTy^Ac> z%Av{<-rE%Mb@^T~zVwolL(SP%A|d<$d8Wkz6IU`3t?j3@%43rhX6mP`Tv$cwgkEu5Vr=MB7~ft~pCv!LNi zTNS$iPYPXQ9p<1!1L0*nRMf|f#xTsdFMlqi!Xl%`;nVJb$RiuTHx?9K_>T&VV`*x< zBapbgPUuMvm#eH^OfRpb0D!UM#SGq3*ANL7{(d_@uAN}zW9tIG|4ukk2!*a%@L5dT zITA?;Rq_xL4GrzN56f4t4}^}eN%Y}!JaZn8cuHH%%s_dJ;O&AbkiyoMG#u6}@e!EZ zW*-iVtuWqyo!YxlsmNrYlXOC#cIpwr?VzXWQ;+LrPmuMx?50A6A zfcl6L&GefMSGLb1!6rz`)crgUL3^Q=NLzLts%9B%%e?o&#gtxl_tq-rBln+!9w)Hk z$+6r08;yM6cNBl%_UVK)r&<40l>S513|;sJH`^@+=L}~d5O0n}yP*3x# z2qPwkKLcn(T2)of_vgmLJM3aIG_-H2CZ*qxcuf(=gViQ_P>cEVPS8>BqPeSuq?2!4 zfA8}W7MSW(&^WY$!y4CoBd_)*um>=1VgKqfN!S+fk=T{&y%U~nFQb�C1n~eaMQ( zm?`w2#sF6zm?h{(ZbMmCZkC*+kcc4RkGC4Bh=D0lk~Ixxr~B_)Vw^WMZ~$DuUllw` z6EPl&IFif=C5Te^3$Q&ry|r$Yl~rok&)~)ssspYAqLC8VFBwkP@CbEYS53#VQMjqBRD=v^HKRt zTO${&G@|_ccPrLYOM0QvghBes@Y3{2VYLKt%+OJ~>F;dS!3tLbotfOnUm0}BwT0+0g$YQ0`3%c4NGgA^m^Jpcw~MGZFyF`NCoDP;7Z(`)9QTx&LgMsPL7+$GW^B25 ztV1730#84ZQ~5y!Um3Xj1JyAiZx0jyl3O*;=MU{ok~uM|tMKqw!(c{luX_Hzb{{Vw z;$rFPnI0aFL_?1oQG`VwztTgNOA7br2m;{NepXaeSGNPHYN{Ah9lH$ldHg^etWvX( zFy3DA4`VMjZ$c8{^CC}t;0o(!kGy9ce6C#`PPvxiOH-f7SI9J%@ehQlYE}#q^ZYn9 zoMnounHKBFPc#mX(GHJ>|xA4u}GC+Cf?$O$X! zCx;7Np&15b1YiG|%jyq&P#vmY$t-|f%ibvQd%OGBCta96qnam?r`)N~`l5ivWSgKG zaq>SeKwsLzVY}Q1D?JkKRXR}z7*Vd%#lOd&=aHaHp8D{wB?JP8?+JZ6{iM9v#7oxy5iKekiJwZ#e&>Nlu9bT!)=4$1j#ya`rSk z9&s%dy+3O=KV|_vpF0cWb!O4h-*t{1>w|eRSgv z{58qbVEt|_{lxNQoEoAt-uGnwF|t%-i9IMNJPVor^iIsPoRQ^XT;S|{?RCj-=l%j4 z(exaroVn`!^#a@bC?i(+GLjo&wJJm9{3CQ*&@m~}1qJ`BM2jTFj&V{=tkt9(c~UQ& z&u8V2Y}9tnWBmM7hi+k%=-S^~o5)bp0(-v8!Uu!_K}BG~&~YXy0V!7os$q?;a(A5= z{vE3f&O|XQRrXyAE}V@=K{JniZ$?F-VGwe(&MQA&hf}R6V`IY!Phitc z*56CEB8<@9kP#`ZcsUh$hJ8=I283PqgzxeS-D4T2TBo$c-O$eT3-vM;R`M~v_jCq+ zP-f-h89F`vl(dysFM+`P(m>IRpw^2|iv6_z8Kc52Tp%4Z*&8n^8;K3wT)gl;vdTn}ZlraEH9thbPYt7y zs+bnDT~4*4$h!}NmTz4knxN2w6*C}C%j!`K3pv(`_}Y zh;*J-F5mzHEv&_C0r8go8_&8W62J{&Q)a`NFNL*uW?_!fyTGYFFP>(5E<3T;fLwvV z=XDida@)WH7kXZ5g&4sv6mZpQ7c-$4-5`eeD3p=N89_1aUB6<0j%|~q3MblG8Y^M} zu}khNk_0d;BAWpAWgDRDm}t4MTV_nd!&T4K&~kXngi zH58gA`eiMDB19D-g3~8#&qH2Ok)4aH5AZ?(PEUCyB{k+0x{t_Bm61oyMyPG}u@<#M z{k!n>o>@Rd{_&ANx&j{HrIMl6UJ6YR@&4Jhyx~&D5|Q14)b4fd|9KIdXcnBn8vt`> z%h46K)?2(XO~n9v%%5AF6J*_<@bm|&%<`;4n7=U{z{Xox^{4QVnO-Y|@BtTNtj2QC zM(vc&#`5$)UEl{33KML0wyzfXs%F1tEon1i%~F1xMt487Q`RJkItYOPV9G#;tq!+UUrj9_bB-lFa0 zuC4>ShzKy#?%cht-=$@zi^+ss?)vJGq{FejGiK1BbeIkisv$eIqJQqg? z186_MvFRwpQzAZC9VNgR`j>=oI{rMg%3u~9B~A%{{ZnjFrkv51jfMSmnq>mU)ZYh0Kz1(Jq8 zd|5i0`(Wb5T+6|d{H5Wu38TXgPHVK0#l#xZ1x;p$eA!OM*QRgPgE4K0P0 z`&Nik8qcP-fZEQ1pX78dD1rdxyF@dky}5;ECqFHjDR2l(l3nU#q-xamRo|_emR0xZ zp0)O=`CaS(lL(U-uw~{&2N}_*(|W8CKB(rQj^D=f_Zjt`xX2r5g^_njy^E~pV)k`O zzasVSWtb3}n4**hRvt3OR|9lKaWu4hg~&gTu*3ly@B?m^gTaXKgu}}L-BQ?z;bJ@d zeyT=6p9T<5H4vxodi0DIIBQP~bR#jlYj1N6l)-yg5b{=z?xK1+`i_lX)MZUp!R)>A*Mxrp{QcWlV?X);=^w64W32;Gifc!}Pb;04gsuQVl9~QWxOt&OI#SrK?l>SK42g|GER0I-PvLIw z#zS+3Lv-?2Dymf?n8e(|LRV=LqWlFT6VYuroLhJGb~t~$^IfRsf)&@pW&4cxNsRR3 z&Z#s~pnCUhauBBz0j7T#CPf1pqE6s7eh>rgQ##y+|D}FiT(3^v6Y~m06oU_Oi_(Rl zU?dEGSrL? z|E%cPV7!eTNze(@Cym2@Zej6osmzcsM1-Y(HYD?=r7hfLyy=e8`|{ZRj$aHTkGi)K zr4Q?L8|QSJ^Ov9~BZ&z))32EK!Lqv@Quu*?*yKXPeoHS~Pp|1nHxgmoi1s%1;$s_! zy=#m1BN9f5YLoshA9Zx%8p)8tGIIv8=4wdIs)ah!($Jg>qR&Ikac(yK2j{P!0(B7&(pk6221cM{@BAW->9Aah6(4- z6+#pkV+wbx_vODB*Rrvxg0m^xhWq=DXYgwuXz z8NVE}1q399jz<}R+D+gU$HB)Je)a@1H!sLHBtwOnYdrk(ZSK2n+5E!7Lg7sPLwX?D zpnKx=9k+oQ?d&GvOJ&OW&)pNZm24%7mLKq#P2B97%Q^yYAy!drZcogaO2|2%>f}Ij z_L!!{siz7BFrlkbIf_-`+*oNeSXF+qZz!m^(7V@s z=VTA$g$;=sf_+?39IvC^GBFW8LwN;;H@}LcUzmFH=ElZ&*acI8NWm|07G<)N=rup( z=j#m)fjla)kY`evW);kkC`h&cwz1_*FVa73E3BgbBjDuN=^erryx&2%@X0aB3sM#k zw8~vNt*);R-r}9x8fThDc|z^E>^7=eGms)4;JzHiCmd5S@VS|lCwDz-yJHvO8MwB+ z30dQ*I+OoErc!tS@v8f4H#dLO3f}*a?RCm$;C>+q2)LC;Xcl2b~brxYe))3GekPO`JvjODQ`3Y^u7`BpN*UH_p zLcLDWIvxnejx%?wIjx4~1P5CxNF_|M)t+QPv}s(Kp+bn+Uo$+kC#uTr)*>o5&Z^?z z<`LM?0Ld9%k4vf&rL1lUN&Dk$RgK%30nvvO557L_d_)5CzoCS2vQf}*<{Dpi6`4tN z!~o$o-&h^H=)^O>PISL#(^bzWyEz_i6&XR`#@v;NhL{Y>7bY@`y*OH-dZ;QFQy|=T zYqp)6zW}P(azP{9VmxoBNPRDH233*aACiaY@y4_FD#RUXRCJ|7xsfe@UrKz-lRvK5 z!h=u{TAtJ^Peuf&8F_%yC>=_-Wk{@qVG%6sIWdAvd%myJ9MLGXCj}7LpZ8Vq`;rWivK8b!Fw|t7( zf*jn{s=)M*EPz#2!b86T(-Fq}k8kzu>W` zmd%2RgBfsgqGDNKiJ*OpkBAxv2SA|(nmvQ_W3N?Rkk}SJCEN|} z=@N5JYH$V(W@a$_UEnBOJG(mF02&*wIlSGk@iiwhEo<8)q3U9E2>!kCmB9rO1Wx;$ zGnLDuz8}`?=r&#RjH>c^0eVZv0E6{~ z5Bk6zf|vHHHd)rzgGk?cgPq;b(u`^ZIV$IhV(9D+E*bzRwgI3O0uF6GmzOm{&JpGr zO2XsGG!o33r@v{q*IHfPh6Q+sd+~M7QJN~b=!0H_3GE&*21NPBwK#)#V`^Vc)vVX5 zs?RJj-=LQeVskmi0Wj!e1RzD^MQ`m2B%s5ufQbbsM)IeE)c1MwX8dJls-y-rQ5ViZm2dm_&c)pMXWDKgR>W z6kU>CMQTFyeq)RwPfmWB5G?}Xd_jC~hgpN$TL<}$EsaPLfOK5@cNhMK6Am035Jq>1 z&vQuOr5n_ypc4(@CPG8QrT2wsvHfr@4KZLav9pPe97)ky*2y;}OqGpJhk#CRQ(N33 zeC`-o-MnxuyC)NUx|^iU9`P|Lf*^c#4a%@mw71<qioi@M z)1Y9-xynE=b<5e(#GlOd<%`Hn0dTNs$*TELwKCaND$_XY*X#n-%r0!Y^6wNh zWMNOeFL6zz%9q~D-Bchy(AQu}su;RlnBYUC{cizMDFzF2w`DkeecieOlEztfxa(GW z2;PP&=hXJ^Ghq;Ux_`zEx`gjz4h!o@O0ZLXWRu$Wjx}@j_3yTl#35|X63$YTsG2F5 zk3jlMIGdP?wfG4%^W0!fit=7c979Yb0Q5V=@O`|x#Bi_)K?%QtvFm&7Eb3c^>-zjy zaS*Wy4t%(TZck-QJUA?ZsnyBPCh+!=kdvEyp9~U4*1L}=vv!iGkS>M{q(*|sBE$}F z2(uI;$HqRma=DtLG3+=|M@}bC=c!t6HOB;3a^(_Bwye;gRuuf20&Z-z(420_E*&zZ zP18q;_@YF;#(5^LJ?>MpGiBAhdK$!lu4Sj?JayHNAv`r!-{dwu3{=nXkfhZ0wyNR< zuot!H!_Pdlv!{7u4sN`F;Kt*NFqoKHWeW8g)+ozgFD3d0V&L}zS@qqs1BjJ_rm;f( zjqNu~r_d++TOdXOOphA3;AK&x_U||l3+Y|Ay)BESHER#R;B)GN7~t#lvC-ph#f{Hp zA0m9e4jkDz7C_s?e7$MTPSph8pO*|84g-<+;!ffdk}Qr(zL>x>JfLm@*hUAamIj?Y z{cHaf5CCwtjKN~>i*UfUfd&D-?{sRR(7x$uEX^uCpkOsRdQ73YjTte1Y~+t9GwID! z%jf7vilm1$6^cxq66PgUIs^}(_-qBUZRexU6y26KM^Pd^YJ+U9aELM446N2?Gte)J zt3(vyWe9Cn?!fFVGG@piem*PBG<-0*;&l*w@E%SoqvnE$U))Ozn(D=`roWBYOhAg2 z8#A#1neFyz?LU25vRS5P$;N#eRhZvH%g4mAf|m;R9WS@lcNM^vV`mtbe+3N?#s5{a zq%9H~u7@3$afVmD6?tKfMYpu;$ zWpxomSLnx&kJ|eBJL_En57U6SyAetXei$|nXqxC`h3hGwGYaM48#VK4G=tbhTlzgP z{#qIm zQLKE6B4B4-P@C|Ls^0|)b;}v6&buR79PjkqoY!9NE;?V(9f9A$10-&&jlWrKlRy84 z)(-)NbtkSs>L+5%oSjGH56pmytRWhMDZ&{?cF5XL_tv(*kGYAyL*r7b?>+`V3)%qo z)jLD9+3QDZ_x!+9MOx$(Y+PZNR7aVNI`enNOXAeC@;|XjD^7ry!wy)H%zzN1xI^nW zF#DRB+eN!JTH@vo_rxojjH<$h{rQvlsuqUg5mw5`ue=cEVrPPqK|_9u;Id?wo{`Zc z=g&QgFAg?trIfXqp=bBX5`MZp-kF9*W{Nn+7?h#JS1Y1g!_0B&P(BQVWhDuCNMqZ~ zeVxwJ`!xv^4S2s&XtL-7^T+|bK21p(ckKP~c4|J{g+?L}sN|mK(K0LrA7>SmGgSgw z-XQPSXWgAN$ys^a(YYim)ZV|jrYLO(&7UeQaUZ$SlRD!Qw1}dr4Yn(fHW69lcb`jZ z_1aw0W_Qfnul~5XZ!Rf0or&L}i>JgCq$RK{f0h;#c;zg+b_GP zsx^WIhka5#0vmKd72*)jCvO&Duk&-L;arz9re?h36T9KQFOCK4{0XsAlj2Uk95S{I zvtd(jQ6!$nO|qf$`gow=Ywy-FWMYMw*YSJkr$_cArvuh$&Spx8+0>H&chE_sV8B($ zxYPd4yvNqfJfFuiTp0sHovs}f)*1v{6c|O2*+-X1q3RCiG**uY@yZ?J$N(sLxn~p&~pkb>eI5b zfp+5+@injZV8!I=-F+95wA|7{&-9BKS`wY7B|(v)Y`*L+iey!|~SR><)58 zN#X9Ej{bn%ZYG9I&rk8q7K{6vOA8Ta!GMtW702bn!Dr$$Qh%Xw>gWNTN36@*e8<5e97`he6c!Y4udZK9s<;h&jbvYusqB2 zx3;Qe<^d9>Q!MgM%*D2K%J5Z28?2Iy`|$7k4&f3Lv6qFk3w_NaqpvjYMc&rlvgq{9 zeK*OxEKhghs|5Sz{mx`>KSrjpm;_1N9ns(PQ3q&59yp~1LtoVK>`A$IKj!VrV{lSD z9)WT3B1QEkd;Dm|IKbebrCY()!OC;%Zdg@?Es2?Z zrbeH9p_dY1xB%{ur<6b0J84P8f$3PEIl9#{FeqO6rdF8*mU7=vEa}h##a z=L@0838{ih#a0DcHy7A;?kpWRjUJuQpUKiJ3yAOn$}k}7vvF}rma2DO3Ci_h?Z~C6R!d;O1H-3I#gAa+%J~D=W+2Rz zK34o81W7EPcld9jm`@Lx+tJU0toj}F>u?@Zb&+Uyw$sHaSKm*)DbK_*urcpiB%&qJ z60Or|uOywEpprQu@P}1q!O^>h@v6pA=DZ5_J#kXse}Kq;HeoMApO~Xm<-hJ8U}FxZ z%H@q#>bHP{19dfA3O>f4Dqqmcf23(LohOk`*>$8Ni?(UQ4*sNNhdmq`>(@@R$0U9V z+(&YVuqKc0?$-m+Rph|W_h0~CAttlgyW~^R08}c{MwkHfzZo^PQ4J+Eh!#s`h?2{<{5YVHanwD*GmhB@BukamI*S!b`&?l}$17N7* ztKf_8TDK*261|zzWgS-^JEHL z@<VhHaj~@m9xNFx8cxjYmt3J zK$}HRG!zw`rI?~v^2MhO$fN_Ym#lw_H9_Eqv)t|{0w_fHvPAXV*Iq*3ZU}EYvsh8- zK1Kj3XCUF6;4Q-(quP3VXan48%p$r~nzQeQ%uX{kle;`^2f*?rOB>G*DA%4s%!ci~ z0@5+(lj4TE>s_$dp8Bq5t7HDK2!PGJ3!J5w=NhFyKplN86Fk9+`g8sWsFF_}NdcHh zb)yF}B|t|Lah5AEMX@-0fa7IsOvshRu!y4N+b}T00l|qMYA}r2WU{SOsl-^G)+uU~ zpIY(APrD`{wSb zEmTgXqsZaC+-&Xxfw;=u;eDgOhE()>$u5PY38^sHd3W+Ufu$W^xa2 zwRaYVPQ;q&dlRFL3zT>A#|-ZSazUzCUw)}Vaw=!kEQ{BQza8e07C)K4HhE<5tpL3@ z{659ab-zJiOuX+zGPZDWY@%Ay|MLQP^|wEmSX>#Me)<%Tgz;S_Jn3?iik-5%XJvW$ z_;3Bw%G1Bn{F9GSpNW#^9;d0~;`e(ke#-a*Cp5kurEEVYX`5T1Xvu(Oj(0!0?=>u8 zBnoG`f`RXj7f=&KOgr{@{#&yL9ds_gzC5BK4e5AgZTEDg<=V^Vbh&+OfYdMPD9NDA zrZ&3{0#73g1A}Fn3hI+4UEL;qJ@VU{9>|$Kxm)dN3{*I z8K0nDwuB+0-kz?MWBZfe9&hA1%gP z8D}(uxcG67?*+U!dbA|QK9vqauYDLE^j1tAl7ss3n$5AU*6KnIdf6UOw zqbk6oH!4;;6ggk1;=sxHp*Fi?LH%aJR6tB?cX4G*sJ-=#8sQ1Ss)*o2XzR>h8L!T%KKlE0%vLf*5x4{pK^~Rxdeq z;(9Qq=dyWgqwK;W`Dvs36VKbQ#TaEAb6NC%+&?t5t(fz0o2CaqW4F5>PhMcry7e>v zyT5;>b%DfAdv^X!#vRua=^76HZ(B?r^dw;-K_z9yCyHHQmMK(j{eWbO+=W|<(m1$l zj`kRq}NWsm@jfsgSE8Cr(tLo%fMlG?v?(%d^BXEt*S#US9 zyh>8j?EarpC3zzEg=5C+s=nt_3svBI$V7pPp{2(K>W&f8fyNXZY6ud~?P_8DY@X-0 z_x#7ZVcr$CNGEv-u?)TpffwUxQ2rK|{IoD&cgq_iu`9|`) zrS?n7Qjs1r_;Ono;K2caVKYn1y|6MLUGvpbK|N^_nFCe3tYs%?<{VS~t#yLdk8mp4 z-{v~gHLRs=CqJzrQr40<(!dLm#&qNlH(~Vs^~?k>B7> zg<4fi|7{w0cdEi3>x1*f$l~3v&KmJWvTvmG&PZ}at**C#EL2ujR$f`Tdn-|`2&q~t zm^t{};qamW3{3VVU+@*f3c`3}PTU#bkH_no9JYwR+3c=9Hosq?4V8F4-Fs<}5$2gj ztMk9sIObKJQMHyFW#r+AsdawCH~*nfEF+y{&nsa(M#pc5Y=uBg;OO~)Gb@)|%U~HM zACQpV`9aG-uRoD_>k&CJA4XM$VHO0XPEUr1H2Nnt&0zurKBidTkJ0GR8g{9xllM-s zJ6bV2OH}>%%`2b&-;enAa`#jHm-?_dDllIm_8_U?W6~m3ZskUc%83Goc|V7o(AZDY zXC)c&4oGnsvTV8-u*0C++dE*d>>{8~Ka1>dn6Kin&RfcgC3@*W25L)upY(Sdkr|bO|bo*ywS8K9w|m%Xdl^%7Uy{06+Q7 zQ_w4_rdRqIgN0n-4QS}|$ub)od@ySZ?`ka}Egu{I z@Wo}lWs#rvF-ja^&GP3h9XMX~5G}X3#r_{nXBibo+coQi;K3mBrl2YaAluJ7~QV_<^sVpq4jB;1^#4jNBREdY+eLW zvxtHhG-)yqT^7A-4F)^R#;jRr@k5qigrZDkkH{ib+xf_{4fLdD+0v<5^AUVtfk1o8 z5LR4i!JiciQlx5fFFH|jp5hYFyq}Zk)NOiogo?pOvJQ zC!kKp{s&4HW08VAEEZ{12X8GcZ~WT}cuNS_AAIJtWe!Zedwvz@)MtVT7RR%L6yu@` z#H-`s~F@S>J}aj54RA*(DpDQGZWBXn$E*uFbxet39A z^}1hjaJd?{Qdg|Fwg|Yy1hmej$P{R>o%(l{9TWF3jFuypE|&uiK+mZ5x<6~SYSgxM zu%9_@rWs>RlSwlNqtuFES(>{XYqIesl*EVc$U{=h@<2BuL;lTXjO8SqgjrSSC{X0O zGHDpFk-#YVawm$Bro@=>co>oZtx+;yj3|}69OI@4=LlR?xGXFv z!HdU>5LD0W3C>oJ14btTOa&@m*BvTl5XOUm!jDUuuz~xI)X6SGKdhzJm-9Rlwi7aU zz4;%D!ZGhx?=RgT)bJhB{*g#AYN;U}^jDP;6(htbR|*Ny<|PvckA&A({*zydylkJf zeTlM~7ue`Vfx7QYMZst4f3IilVo7=%Kz5fl8l1|_Cc8f!TNr8IJofh1)yUL6xMK3> znoGqI@=x#W4f37`bX|N}YP97&bLTC^n^>GxDN9`ql}?^Ma`n6cJmc2m6|6}tNX6zB z`T+zeQ=PWAO|HvQQD`WDFU*=g7!d4D?q<6OVDR1SMk;GO}2uUG~vIl4#ckEt$$J_0h@P^+%Bm0m-0B2RnM? zYL+?eQVjX@Z~1PH!9Q!6gZXW%-oj9O)>6pL%GS zh)y;Q9rLlSct*eyC)5N$qa|D#JQbaBA?Ay9 zl(bz|-sL5JjAxv9a)Ag1zX*9$oRHBDyo=nJW${dl$ktC5;0OODKldR05mO!gc$( zBiH{PEr4KII%BB`8_15y9*^1nFBDU!o4d06$Vb44>*u=FmlcgzITDN8kq>M1KI&3Y z?BQaRYuz6CGnV5M_?#~ITyW@dq|qi4MWiX0&_`0g)9C!srXlysD{BKDuTZxy&A9Un zBHFlU>eD4<2IQZ_LP!c!YAJhJ3Gv0zcP_c6qFwo?CcRGc#+?YZDWut4D|5dlc~)gC z$;u~(W^>wK-0?cpH`ENbULX7grZ3=V(72?(S1R}_3$R%OA%FN_^cAqZB9 z@@|x<)GyVo1eO)RsuqY80ArY@u4aK6;{p399Wr939DPf7d;8ek9fyyPPr5&Ublu*8 z(xzt9{uIjR-W!0aFh>3OZGVHwI(0`6m(71pu3?b|?7VW4RqGP!&z&wvgdT7Uc{>{y z_yYp!y0^E(00O;5_4Vl2>f%qL`_X*FP#g>J4D2!>H9X-6awW?Km0x1$50re0tRVL! z3@A>ij4yCygt5sj4_vI^3ssH~(c&4Hl#x)N3g>D++u`b;4@6lFJE60d9A#P?Q-bul z((lgQ=jI8xs0$X~f*Xn7Bqb(@(QmppH(&F6Cz0X1p=)DASIzOpE%S`Sij3V?w~&G% z(c?cbhn(rB=r+`B=jZg-^_N`uc+=w;{Ucd9oaGUtcG^IdGZH&oj64%ibc@i>exvn_ z6(wk1OrLM8<6XIstd=A7d@6>8l`9+9*+uOSErzD-{+R1eWT=cIx82Z4@}y(`QrQQP zbPq0BeGzpoY&?WOn0#86&??tHLrmN>QHZL}Gr$Y0w6Ze`_lHdROAfBX&mQwk8D&?0 zE44h@%XWe5Tma3yh2`sp`rlVtEbW}#Weu(Fb?$94MyYvzjx~bubp0x@E6~HdK zZe7&S2jU+S;hrPlg&Jio*vcqt6$q-GA0UIN+ZUaR$H+#uUpm1Z@_I738?RGrm?l9U zRHqWPvMJU4&CBv?hcxLR zBZU>inM4r~iRcGCyu?f`udb5+2&HGo=5pJn09vim?U(PJ^dj_|hu;1%wzu=1-rtoy zeMwi>u%u^HasYS-qoK+o)@gu~V={+FeDirgS?**rP!g56w!J>Zp+Hh&3Dp~*{yG#g5P5~ zVaoTPxdYQJ@92<(`N>pn6-D{t!xqyKduB9Rh_ID;)6>YOD(V$kJG;jKrui;A%cD!DK#`eCjqAI5aC%=&JSXkt!kDoEV=exsW&xCXN`D=7>6j@M2z4L z9Vp{cs82;>sb-tAVrh-;_pS{spBR`8;Z*0=qZ9{8ivQ@#x(4$ojEbNUWSyB_omP(9 zXY**dXwtqK0B!7xD?Be?wnkc&54tvX!Xd8RYL)6*+Pa0yw!7^`Sw15-o_D9Sch)9n zZJn=v+HjQ}=^d#GJm)aj#5L;0=qT|AY$ztlnxbXVn%X}*+G3j<0^9!<%xjWZaa*GZJzA4nEh@vMh2QnmUmJOnPSe*@MOC%s7ttooU15H4JvI5u>C8w_TKM zkb;#Wi8K;g6p3O{B9+xZyuNWdT`CiK6_YJM%V*|kt4@dqL1g7cH)ZcgVF^AAW-!h% zX?FJeXLgbHLqOI@q0l(Iot(ALCpmtCHvht@-y_@Pw8JoJj>?3~Y~`>e<`>IY^c|sc z)KX6(i&aS!77n^mU?MGZa1{E5|H6YM9!H=OK=4=W$ zUAJWObNG!jyNeQvjK~Z{9UH~N58M8HL)7!82Xc_5Y7g!uNA6@L!-gg+pdSNBlbc>* zTcMT&+Ecl(Cc!V%*idI&TwsjftEEllAw7g zqz2XGr0ixTAp(W3e})2fU(X#D6`$)?4V#B}nMv_TS+j?*69fTCeK0{`TXj`gZ$bCs(B(*1ATq+n6 zn67R66UQPfb0uV%HnD@2Z0q%<2WeRX>^v48w8y)0iq>G<2ov2SjMU)Z$(*H-4OrT7 zh{!wEE2_A+5iKRqh2F z^}|O>4cYm76;*YD5l*@@0wOK#`K=NiW}dQ_W=5Cxdm?kb@YBrYZ{AG_@nND(aB@Qum!)cS%H`^Iud856z}8QrL8tcnI~_n1 zJ5gcGU~tLj2vyFsI43Ul`Kw=@0T%$M9Xi?C@B~N2^PQ{~A3|t9FX_e{_!BcILfI3q z;wV16cs1;Me2;D;|LmG4M+L|mb+xs^Xwau;XSJQ3{Oyc<`vgN*>o_=>!WS_LCb>MK zB)LMYMHZv*v}f<}?v6-Yv)Dx$Wt@^fqvT>O_nTqWpfAboxO1eBK{bj1{b_(%nEgYefA>~u^ zLZkxcB|Vh&36X?|^%;U4R!PJ;u=DwdzQIPDEP|3v zIb80%)PIrf9d4y7K*SMc_kOezV!@_KKts+5r>#7gR|Mo}!4skGwil|&#fJ8X1vtp# zn$&FPl1c5}_0JTd%yu-Hz%y|G6GdMJB5RG$_emhlfT=wcixnJ+%}w%SqPF5Dl$x@y zHh(C}7(@IpR-OVTFBFZ->LTz%GELCDQCw}KiQZ8E?I#_LajDeNoa`_T8R0TDnX*TA z8OpLxrlWaeVJ2mk-~mJUlOL~)O!2Y9{QlU~CjFqYswcQMPOZWKapY7kRNDHs2qqnybvjkKo0nKPDxq#Gt3FG18fnKX% zgQ4S>e#07tgQet{>ri$O(i}Pk zg9cxETRQs%OelIw3pdyrL)#ljC=1M}>S$C&PT#u~N7%D>idhd1P`9(ePawWLR7*j45bxK|5r)%R@c@zlRM+9rxa15-p zD|f2YRVl$_tT09O0yOSci}x_OS#C+gfm+VllqLz&qvl=|P8mi4JtaGdab=Gcy?jE{ zaGt8@WYuO?Hg4v^7t7jdM~+b<$rP{*{4~!>cAN7V=%33Y)68yEQi@yQZ>gd*po*fX zOpIwsev!W7$-r_%Dg?$-M^cDIq6M&u$$5kLNsl3zclXRYC|$Uio_H)#b|mqiS3+a^ zK}FP|wY@YU?wGEI)BeGTB6KkVvIlrM?Oo%?VR&iZL&{>K)-#83F)<6p#6&`w5kp1H z@hIvsC)leBxeTu1GVkL?o>htwu(IMTXI~STdBV^radGQ~Rt6A_m|3OkLrpLwFb z9l1@)QKi#7z|Z=rV~GPdY8G5YP@DwF1e8F{j>lm#<)(*?gI%_CLIXa$hg<7#3US0( zx%~^w6HysMOLa-8NHo~p!W)sOgR=w z^U~;Dz#>tTuu#)(oL_n#P^L*HZM%VQ0+7LOo;vxI2*kQZCMyqID`&%YgKb}32_p)y zG~4~zjoFFz?$5dN^xk8%@&dM12<9R-6gSv5z3qu!(#&j^tla>{HXw?bdU<6zm)U+g zB!m;Zxa1=)`ep=TB|w_ZCw&#pS7;s*J_%GP1)PqL2|~NVUsSO8d`k|qxKC-vUjhv% zB?(zhtazTTO=?w;o@ihZ%$FY{;+X^*cew8*skw;{UiL{{YE1Ei_^c(cni^g3k#l+E zPk$J5+UFgRg-!fOrp2?KHDT+QlVY|kr5 zUl2s-bKCS@q#j@P%xnwNl6xbU*&NZc++}j}{Qc*pB5C)SsdbQD^IQD*ss?obf!P~T zx3SLXJk~_lV{sQ_TX?-kNzvcpNh4~%rTA^DwWbNh34-#vi{+X9iyiH&iZLsq?{?6* zuUeO<%7qo}jQq7KqbkzJwwPA4kcs#K<8qhjl1TYIy=j9wcwO@D#KlpaVwPVIC-em7&QvcI4Pd5-CkK=W zpg^cnf9#`r?m)x+J?@QnXbM7nD&TxLzNK35COm2xsQtN0$V?DEpd9)E-%h6-uq#CF za8WpoJ8~6lKv)P+n6&{d6nJAb)fGE4tTTm(w}K&0K3IA^lmDxc&|V16Q^uOL@;GeJ zmXk2ixo=c6wgZ~ToigR9P9YE-W_cNvCbrp|jWw41CqgHJ2*8?jHOl%KV8WlDZ$2>s zZj3QZZb_>D?*+(UnzbjsxTMZ!1;sNUyJ~NMmo<%kE}OcUWhs>ZS@-eK)U>?Xj?sAB zI;nQK@6C8f`|rJUTd&Caw<4eKiAchVRjTS*YC<7xK$mAtSJP-z9Hv-GY$H;?L=sd+THRA=Hy|q@h z4$oUW4gHR24M4aNkrB=Y4xHOQL?E@vAvex;5LNQ+deTR1on(-Mw?XVr+0Y59w!`OoK&+Kz0|%lbzdjiyCoN8zzWfPYKr2)^kA-Q=lj+(_lTB1B8N1j-krBpw`v@-7U zX>5D~DP)3PP7w3x>C}rz#<~HD7I{TsP()FF%I3gMo&0_zC}N5MhUC+*@Y*=7pW6P} z_!9AsVP0vakG9uZqb^hWk@yR3tjx4Fx|(ln_^`aAP53Y}`a&dT1~#{oThg3H2CYMC0nyKn zP)!LMbd#D!ePs6lQlrr|k&iEVUP#9FC0GPI%h!|XUamZFs=V5nd^g{|+6eL37duY( z89K6nFjPqk<%-MY{uEsYh@1o_HQw40lHx z?C%{?7O-X~JHLx+N96y&55;!r*f7xh2OT5p4ZDv7iAen;2$n>==PCsK`1hW!rqGY|EzM8)Dwq3G82ks$gh`BMMeVwRi zh6eQ^lj@`2_c0R7jQ9r^ zZ7vVjTndiGDHiI%>xv0OCR8cXc&C)cDyg*uf5!`sgVJ>KWM?1E!5Vh?HJ%8MU|2` zCHNlf@y{=Vsp}y)?iTaqrc`h*qPkn5kiE|-Nvr+7rzB+M9_g@REt@;M@1=bAO?ifK#ovvjFMtTV^XQgZ>D}-9Vqn|M289lAKO@ z8L}Bn*T**1&Rg36ESFB1;BqenuH*Jj$M<3j4xW@N;Ek`k;|j65>k2U@CI-G>_3Yxm zQm1T#_aFMrAzumAmnJXr-{%5KfIhZ^Ny4|2jdy-HI5?|aw@YDoW>z+*5!C|UtYLn^SIOu-A4=4u62ycBbZ|9J=_^}NA&40PiYfq=x#Op7S5%X}07zwoKdf5or7aqu=$$THW#F2U|p%jY?eCS>InY!O-P<5y%w} zJd=TaXXWC@Zm;VlG35cE%Igt;1+C^pcW75$g)I5^bU$*whv%N<=FBoilgqO36Rjd^ z2;|8VfwDffK%tqZpKTsKUbELfd8zl5E?_I_6Q_<2Ta}WR?>-g4h#}%QhQ_$(ifS~t zc zgv88;BF7(D2_aAyvz@m;FF7p8rD+}aUUZqQn&f&%s7kcD9@A9dJQavo*dn3BLM*28 znl-RkwMQ^MkNA3!wRaD3CGS_8Jzsg`e~p-$Lh^iS8DA+BJ&`(4@4cW8?pBm7dif5q zpcHT(f%;IK^ElaX_QbNp;nfpZDLvA#C7#Xfb|r5|ni9ZCoDmjl6FO{Hene~GwnvKo zr&D}|u_&q#I=1Kj6B;Wqr_iWS5KLcPJugNu>-j9}LP}{_9$!$|67Dlm(oG~-k=_pt z1vZL>hezGg@>3JK{aqxRfu+)?$aTQME!<80gW^@}q~z6KPm&V?m#t zS|HJ1y@>X+h%Kfcec3=pMi=xT^_Uwx+#V{Jc-J{SG4)0qjAJo+Ru)+#?%p0-W>Z3R zyE!k{7$XRJ{PE^56aju;Oc5>;H1xh1uDroCguZ+wD~gsq(z;@nF0vcrP|RTV%?Hb$ zw)-~fY+P}!BOeZZ^QookW9>eo%2MXSgvxo?OZ=77<@F#azHo#`TM>=>*8gdw_`5JF z#u~_Vw?H&R4mw_1Hq#O($Y#o3j?`pj5}AC~nXDKIN(!F_Ej1C$I(j{$l5F{Te_vek z>WZzYYR0D(OOqW-ey9kv2|; zC}7Jm>o7jC7(|CZ@gYo*q)BtUThmfk*8m~GoG zkd0l*hx!@MDzF!ac4_MK@?$BzUP(>(3rnEFRNpZR1Amgghk1{-_9+QXZKnA~y3BuK zrKXmak(pVV_Jp~EMJzF%XfloWD-nQib8nyM?fqDZHJmFaGIq}D@haM+V9rKl&vMP( zHrM$2=uQh$Z?g|E$&z`qjec^J$nbxzTSrwLB_3O1i0IL+QNY&WHOlB**ZXlB4jvxC z9%>a%h1};+TYo_uJf8=R>fgip-QC@JUTl8MRT%2ZM*Si^~K`i%AR=efZ0rTI-$9W^nu!a2A zoUe)@llk1MZ3^pF2{s#Zx;swEtMIa5HsQ@Om2MM7iacl|c!Gytx4x%c`k*U-nb z(0bRIflE1kexD@bcz#7$r5_NrJ|R!U|B!57+JAn|Sg8(J?EkwBFI5{H^o4!4b$}R7 ztJ!?3(rp#_&jaF+z?|dw`sAkXbM_qob^{20&%r+8`}y8$KzdE`;AWdM%}HOGSvzP+YjN2g6-lMLx4GMacS{Cp81?T zW;l9f$frV@VqHc|aTcIw?#~}_lsiLxRB9FWc%3lqhqrni5^Vsm^ zQm%z;+#ZK33p=}VuW+EEcTmGMf*ER-gjY6>$L)^1)uO4BLoY(+|eh5 zHSia;R)xb<5JCog0x03{1IV|*k)^K@w~2=DXQCxR5t@uqAA-?+V2exOdGlostB46{>e-JqrEDA_I-kw_o&DVqWnMQ@<6uK*6#~LU=yXhEE`rQ} zWmZ9Crus}?a-HH?X&?E>5=j#8_~$f-(ufjtGOswRpCeL!3?H(Bw&-AjpbxF|v>2fA zqOchezLVAVWnv;tNPC-yPisnBFsD>y`zl9Mxff^19m?q)Mnw;Gq>~h6KW)^-V_W ztNPh&1A@R&bbgS48Z4k@iEmOHpKX!aT0Ye!M_bvc#JJ`ZjnS3gzs zM5HQ<&34dI=XeklE~?|=$44{+xj(#Z0~RtRjjmtW@!YH%=_btk(~)Um=;_&kEjD03 zWhOvjXmoC?oeB{}iOQl&e54#Th3&mJKhGHopwt24efLtS;2|3b3D7RZltWeM2tC}- zM(WPkvOZ=^bPQ1o9!nX_L&(^E=Q+5mzx~{02H#!pXkG7(zCo8x)?R>^HEbpfnGJ1h zVgTnzZB0#&h|9;NMz@)guu;{Kv?-T{0>h2{+rKI<5;p(c?f#oRU0m3{5zIyl4Sl); z?6JVhCbfEw!sq2no`hR~n{1aK_kwuyfreemKvF*cYoU2Om-}%s@6+{AjOX}9cY9{* z#?)1(g}wBQ(<_oetriA`APp%&g1$o!Q@|yxG{)5{&g2E>`$_lS+7V_2JKjzEr@ptq zvj|imd_d30;Bxl@qu=45yAX%@u*VvI@-Y~YE2rM~GGeLFneefx`*h~KV(fjuH<7Zzlh`_6Uf_J4tk^aFT@ZAKu|J>bS zuPbB#c*6s3-8NsKIavR{xb{ZJE&fx80JTEiF8E}L+vy7W1RviL{2wb2@JeHKKRhx$ z+@vTTy0xo){ZdF{%8G}XDpPC>zh5F@}SGO4eMUy~BC&3fa44H-8{rdiU z-sT(Bh6Ou_6e$OASpf%^sJ=*m3(Z0luUuQAY~y&@NBK0yzdFcFg-EVDRHR%@4(_+) zGG-@0fA~0Ij@jALv$#*yXdS2D{8|Vx9s1Mkmm(1C{KcH&Tj}j!U)2HpV0qMcqj`s_6bDQSzjLLdQ&0BI{F>$W(?~ST=L6 z2|GR~rS^mR39lrTTM!3URhLdRk&_C+2J}`6iiSSyT1@hCgg8~VNj-y|m#@@`F)Sql z5)Ujg5}>RPh@p&Jz2Zb98mGA(f^$Qr5K_M-Ibnrz(b+dfQzt~JEbdwF@WF6l1ahZ_ z2qhF1FPfc#hJnqWgg9F*prgd$l+a0Oi7RN6bc9RzTj)QL-s?4|C5AOlj(~X?DSqam zs`nnc%EXa?Ij^^cWhHJJ#S%xhNDhi3^F^|>h^ii^)QnUN)_E#uy$p`|EQP*^?^!cA z37$N0aA<~-sy}i|c)*Z}%-TlHz*qu#(l|RaxpsOnitL2YnyK z2H?c4-_%SZnzL+(W+xWcgj!1V3 ztV^q0sphChZDAiNvU(t$y!#O@qB7D}PEia0ia%6bZp5QU(Ndq|{uHwOHVLvRaf>O{ zYQIYqSv-50RgRnHTgQa?6NsTXL$Pi#<=~TVFw2I3Ac8?1 z%`5{-5cTd9Sa**RS458s2n{LRl~Kn-uF?xgBYs&vVb@Sk6c#Ge?Pbbfi4VEq(?M0o zRWk;m3^wrayJ!2zQK46z%-J&5bk!>4gaS?yZUcX>j1YaCt%p;{+4l2C08YW@{g9|A z_!yc7C=gx%X1&EV2@bF$=X(4jMWO~(Y8n_E%mW@@9>3`Bm$7aNX$jX{=RK*w=B z+NR_n=HH$?TWvr=0ih0^)+<(On?0X$d>#7=sx13%L(j+v6|B=NU}52dQ~B+`inS}S ztna%|H8T;?k%v!3WmPZ-U&}kC!|VRiO~faKeC~cA^Py>=w{tV1O3<*f_Hscr!)0n> zk_!MFYZ_X_0QN9o%yy{>=t=v^v?(=vTx${U5)CvSDZ9!askDMrFqE4wz^X`$CzTd?k_MWAH`Soy=Dt+DE>m*o+io(^ zZqLH+#i3OR#c;te05PY+SNcTS8asm|i^I|jGsN(}#SOOVBUm{}v`E&y-OE)#uMDG; zlO4b2*(MD!dVAzBWvmfvtg-}#kC_}eif%!<7gvM>6rCbBfI<2(Dw4%Gb|)6T+fXGW2?~&Gt4DY_bhXhz z!ymQmMT9V!4R@8aM#dR6oJNjl=We)5vmi16!UM2)jyMH zjCyqePuCuzerJ%54YRYX*dQf4_ITrR>l~Mgkt7vHm<@(0D=E=!Yi6vqS$@FX6=3!q|CpEs!Xv;buvNE2jc&%4y%k`v z1IBNl0GWfc8A$z*BlSbo+ zDv})87@@0S4*YJ?`5f9fzhqDuB{JX%EX@(Hd4i#6w(;;5zQU_6^aFF zH2~qFQ-3NQBF*M_mP0>nf)h*|eKVTHH*xCoqXv%UepF!l(W862z18`(WPcwb>D<#8 znd>L-&6sT=j(Fps8h)PNr~4*4mSkAPAi)&1lL>TqV^H(?UL?xU7O0eI`oEn1?F)z) zoUD(fGC2tV?e{?mz8)ED zwk7j6JEZ)|+!|i2e|p$SIJ#?-8v01v>hn$n_xxN@?XcMfG^Z(&FOya_n-W?_sbJ5$ z@&A~hlE4oyLVw+2b`v5*CNgg-OvM0W7 z$8xN-`bBU>BMgzhJ#D;y`8tOE;_C=k5j;S3%L7tBAZOX3wg=PikZeOlW8J?K?w{Zxr{9RBj99^uGvNZu71u< zF}dtV0{5Yvg{{(DTg~G;7?H4Q!j^b^y`P-5j;!yuUpI zxHiFqPLB<i$=uq`Jgr zyU6}Ox8z%S$Ohp*=!#CWKYNhh7I#;?c3*y~2~N1Tn;JInb-w1+hDG>G_hrHMHujhI z%FZwO{`A|wTDCtAZKnIQIowVa1PxOF7JDKsTYi6v{A1m$I{pG$j^ks=y&YO3XhbH>ErhOOk-bBZ}MHjfEXcg;wB; zu!!FAgW%Hu4`m(8Ti(!&4;tQ4Q!#eN5D~bQBqWhHL>}+*|If3%~8SEU0e%{f<6Ct8WoFcow z6MAViaLO*hq$^gXAE<{Y_WPniL`%|BR!n-=KG~v=8-G(p9iLQ|b*YFKwCx7>w?Lke zkCo4vZV0M%)@IZvagjtmh=w)VQ5HSC;Kg2i5p#m_as8?Y~*7 z^3E;U$)d?7r>2$zx~48KS%!v&2nYz6*YIbL+%20|8hGuzJBfg45jbYmTZjrgpR#Rp zz2%*6!&-7luf-~P@{`xdQ2KpY<7u_aXGS`@ZF3_@A^+zhd2Bt$CEECd9as5Y-lgB| zoGbfG``tQwtk=8<9|bXkaj`}&(mBoYLZ@253W6G82U+^kdKSsQagPxEVdEZMBo$>) zG(I5#7bOQ%{IB(leIvXML&G9{Q6x>Y)LiN^ppdX{pPt4p+e%=GyFHyn4}8-hs6%#N z-PG-ZYjL)-UU9eg&%^m!q5n6hU64t?F+`>w_O8jM^D%uLg2Q?A-Y&;uAib~7sgDJ7 zaBu)R<2x<>>q&smBx_&yil|1x_&u&k#nbKamXnXWSO}!te9MU1gTi}S(~laKaof|b z@Mw!s!}K+z@)@Bje^;D+zZ}cR-ls|)yvq@MZig^#_Z%}=>h|UQ>CW~V+1`GGAjGb} z?d(M(A0qClwe`vx=l8u@9XdZ72*`=knGbt2$H1A;f-<}-a zuob;>a&j)VB#CP^84cEU+_V{FMMMn!yw6a4UO&!_gwFhdQGtgN>>)|Ylbp8Rc^1%0 zug#po%{M5x4(_?Odi*HbKoseqfe%S!SCHCCCHqQq1!Y1X^OysCM6YyoPohc^Q-R!+ z0owYb@r8*q)I+!DVmb+F@$@|`@u1Xbh4v7}9JZnZ+R@FtmF%|PN?u^HX4P%?zgs?% z*R3|A{9pU`V&IkAYZvV5vw1gYzc*79{AuzjM?&y84*w_BF~QD=qZc+*cfTgzsLr}5{Iz$9{#Ffn88Tz8>K29-=f_G>aLN0`Gg1sovuWGAto|3 zc+=r<*^e$E!D!boj$S7u6{iGCI%cUO_d1mhT_rq^{`-q`yE9)ool-_~$9|0p*g&sV zPsc4XIn~*3lhiJ7w`SlfGb|b$)uWCuZ<-o{t_D*VS(1N6K?+bQZ@}r8lQYL6?(=8`jle^2lvl>3Rz= zKocPY>i|z*Biui_v4c6exomiGnG@y%W>my`W!lXEWGU2W7?|CjpP$`E&27%`vQo{o z2w^((H);t|mTJ^0yA#In4wvqZPITBf5!R2pvS$u&Ely6?WN7=Q7bGfG=xr*2VU1mW z20TeJzh`4-)jQVw3Qo{#R%uDSnmFhnE9idbe&T)-+32 zFZJK&lHc~e2|V}vwXLI6)`T7SXqrgZ$JW=g4W=N}AEg$%c5w0X?rd)d(~ljWXiOc@ zWtYj8>Q)bFfc81e!Zr5ZYV6!}+Rx<`oh#+8_ownF*l(D0sF(Z-&ZkF(3#vMO;hu~m zG$JZZ&&^vpQ)d_6er2rPLb@@3yI5&&h3eb(1P(_E~2G5D z36DeX*MclM<5`pDz!3d*+mHGPF#R7-0fx%Sr3n$g?||T2X@DtD7Hd}Q$aT)f``i7? zY6Ni-6|RU33TnawkiiZp1=O5p!IwNize|`Hvzy?Lba5QoMa8@8uO3`ne-921BU3D< z9G{ylh7m9N6W44*3WPxM2I|{Q@%Z0?q?K)(nC<#G=^s_T$KO z)Zy)l>2Vp3_~LLzbe7$W`H+nOWuz_^z#G&!LLM@^pHTyb^537PvSNYeQ9_h((QUH< zPJ{pKDG0)#nj9w3%ge#b!TX6|%0BIira~V7L4Lrqj=<|KCXt}`fWiC3#?=YnF5#Q_ zuS?m#=V%1se<|Fl{M?IkUK9VvdV>oCAlx0yfUGx_FL+R1-DS>^pHggvdsZ{V8a>^n zxo}gyq*xyYT1jf*J-wjXoK5lk6H`IvU0d!^`eh=rp&ibGy290?UBUXBMy(FL2Isd2 z1C8p-p~&C%PG;lJKb5)bach4k*o2CFmL~m(E94Q#(;|8BK>GH^venD44R_BRLVi^s zN(M#7hq0x)sq&AkIAv~>y_*5aP8scQYP!C022Sw~=G7(c;{(!{smrU(9#iO&Uv#%B zduc9BRFWK@Nri&d4O2^2k(YVxudlmb1BU`0BX{msei?C?y)*N)hKAst#W{ zoSFddTTC1nkRV5hIrePo9GGNRj1}rE-2>fA%l}T>Mfmd%##i=mf?{{tv>EtvLN6W6 z){<1w)98i`8IuaP2X}69U5l~uS(&d`0(}o+*RhZF+@%HyQ3@`$6g4cF&~nB}VIsIu z4U|bb;xXjbee3G5x3kMVsbW>w7%v~X=Zfk*0&Q=lD#+?7vux60)*8Paz>o^z#?;|m zK@&1W4w2W5!0)pSvogcXavkgZm8o_XEPt+MuUk6lR0TJ?>lxNa7>9|=EHfkNlwfLj zxbP9VI63wHr*^KcnlOW=&)Onq^s6O7;V-ZMkEpkbimUCSbOQl`B|!=e?(VL^3lHw@ z6z(3}-JRg>?(Po3Avgqghj8}yclS6q`-(wT?eWTzxt>!6*?o-%rwNds}{pBm`yJD5S*zmBa@7B9RIp( zHjkU%|2GYi-%koOI;5z1vKRn|%$^$ssl~vGUKBBDfmc032NxId%z@OoD-ubxL*rcK zGbVd(NU2+{RSmV?hVizrCxMyE@%*giq#{H7FYkNFTCFS9`_8=SYy0+YL&s@u?@YQDVie9RC!@I$%(CocQ0>ge2p-hS3y?>X$X!SNd`tOB9A*Tt6)rm58Y!d|WpwqU z4489nYze&sso5^NZV0+Aj6VPE({HGRFdz_x8~y{lzfgjS<+J&SWpA(^i1noh72s3Q zCd?=QzGec2)I@-mc~H;YRFP{CRajO`Ob14~S&1}eKFp}@+Dq7cj~;ZA<3+v-9KcL} zG9Ej6f-OEgd_4hxv(Km0Xeo;|R3~um^!s_A^2igeU~_z)fv7D}x4GYm$HbQD*8(uq zoqA;4H#&--_wx>8$UHd$Hvh(vVQN|@(JKD(bgkHnCF}a?;=O0I9=!ncn!6-IBW7Fu z740B`Jm=>>iGP6dTV@y?IPa;$Gs&Xkgqhp0S+iswkH;C^?{9I`Q;rUH38i6PUL@{%=ZI_}Pnjp&nYkYV6Tz4YGokSLPXR&?kMhkJK# zZjhHqT~4}nF)=>3miKDkIC(Y}#0cdSAz?Vm^;lJ zc)y}>bM-jghx!wgB1;BIgsT;)HnCsP1PVz72=A_dHW{w!s6~}-Zvzc)Gp)RWv*csl zBUxa_EDNSk7l~wWt9Y=yhg2IaI$OaoU zGNZctcLI^2^HMWj3^aH(b%IC%d_=5;Hv46!>+3(});5WX^Mo*zM5LL^wE2T?UjIb(yJ78x^NPr! zj8OUvMI{9gl~ga-O?dW`=nP@V?d1b%bS+RPe~&?y)&HflnR*vcy^OU`vBrGJ=bsas zIOQWr+xr{j2aacC6Ge=ZPE>GH^>cQ12+|R>%|}oN!sW3#(<*=&c!W7ps<7%TQlKf-esWeKEo^3#4=l7z>U_u7H>LSx5C7`R1b@jVh8^6X zY2BwfqHi0MpHE64;P$27`I9K}6utV6TchxdP*;2rLW!FV!B zAaIk%iK6Iuo8kqRrcNt%Jsl(tl1O}uVuzj1@%hM;zvdDLvIkw=E$OkgwGhcF&XH}q z0v{%y?bY9Y(K)Vf`!$ygD<2gL3k%y?+j@2SeWczt=c@OG(5~j^ckEze_aWc_aZe_e z7BlC_y4HI?c@I#GrwR|v+h6>%e(UG_rw0>)e6y1IWEISyeQTF&qKrDTs2)#d>SP}c znz3x0DI!XrcE4UonJ8A0i6e!{)Ybm+dgX`+Q=E@FEhi6zpnGjSHy`V`wqI`(`D86Z z=p$#z><5hb44v%dKw^Av_gdFx2Zf;;uyQco(p_!;cq);}Q(s_0t#*@CXREVFkub1|;6^ZDlBw3Jy`}Q@rj5)kJT|g-}?s zrnq>yw}Fge-_Va8&Ts4VHt}ntscp?Luxj@90=dFQ=OXi{en{m;i5KIJr4KA(H|&eY ztf)YM!E!uKN9vWZeqb5!)CO&BY%e}i<5X73ueid-)!Z-1QfxS%`N))t7U0Jb?k;ju_X=4{PTMp7aje3GgXHO(@VhP15>teLMLG72*mgn5aGi zBH~zoS71H7q?q|7riVg}5qJW^eSX6(no}jPBW+9RsuOYIz*2Kliyt_(d7pQCPweXP z>tB{coRgEe_|YdX^Yspv9w*5tNr|w_&XReRfv=?BXk)2BV`9o%EOm<_mRPxK z*F50-5%kch!#!zzNDNq4GkkCVJPYf#_^I63sm9DOAzkww(X1*TNdCBop%R+havMcLDa+qy`^>;`(|kT_%(V*%a{%4F_{6v@)rTIN@0 zBI&fjt(OJAZ-Hg%-7ZOa7;Nskzsb&wSqxaxn6l*34Imml`)tw7`{?r> z0On93-ron)r9}S*z%+w~a`9x&8%s;BX4Nf(XD5!SRuu$y>uTA<|Na5~6vY%K*L;+6 zhC5tBDJ!uBpc7q^qyVT4`5nt>or~b^+Pg6=OwQ$EwtS@7P~@V1D7(hE3A+FhQ0sK$r3cv8IjB89Ph9oy8W1NE04V|n%+C-+oYjds)Cy8?DO5Z<#YJZahXR~MFB&7`El zlg|4&x?$r!s( z5xsnlz@R3Ss(xgI+uQD84iv5tQsOnZKC^gJ0H~)cnGMt;LO}i>XzA>6Z^(2nZ%5Tk zzI`r=oDqdjJT!>Pr6T=FId5UjS&qz_M|?tQ-)ENNgNPZ)PMft_5&FV537FRkE*xb! z<;E4x&U2ikC*>^3zyl8T6yq#&Y{b*on(m2G+%YB)bvjHk$+3Dfc?HEbM@SU4L!|RT zJeBOz@tW=9@e1n?#LwoCqlPte2=gME1gd1b-SfIwr>0SjxKSmLR7x2{ZSOrf%H`zD zoH%C*(a2sVhSb98w18%(<>gZ4%x*or>)6OOMfWs<75`(+rGXE|$$!4iV|l$za>5tZ zEXEgdSE?eFf+AKj1sMc(Z{!8Z#~sXe=#=!Oh%fnb*d*Pq_x=}%8K4+Omga**CD%!a zq7>`s^5@T5YAf>6)cV~At!%L2X-%vn(CX9Pesdrc6h$?iWGsg z+mQl?JzO+em^sY?CO30vMB!WnD>><5Py+hxDYq%d(1gT@xl{={8LYt20ux4bDw{A@ z8gc~2xvT~Vz?XnnhA*CxV?K4fj1RxQE)m*Yq`ZJWp(-$nd&Vw9%la|nMh(GJT30^* zl0w()dKfHQf^iW$O@1r*;kGEE@znx4@rpPlRi;h3H%K@Yg;qFRCXOEIlx;v9mVy>V z7!^J!k$4UX;q{BIbgm|Jb)mY`eQFaNS*3vV&k?#));rGz6JaV6O%F-=>E(H)VAF6i z@mP{VhJ;;q^<|d$#OJ25NQV7jKsOn$2vLGqYc43CEpj)LI7zP{Y=>%`_$7nVOa#Ki zD5wYLz85joy1XSI1SZP`SBI@*Y;Om5w|!J7`cO>a(0DmB7g7_kxkf2g@Rw4WA6IczjFH3c+l4=*o6L%y=Eo_)zKhWC#JrgDqt3#kx+y$$4w zvw!^u4SNl1^;yz>fM9>1A(tb#kZL>2bau9$eZG!$XwwkORwGv`8yQnv#PYXUS|F>6 zHNjEP@h~ZjX*EjE(K8j;Q0?nBeg8bQsCu+h&EMdGTjfr}5suPbWd^pI%}-yl6yVK1 zL=Cq2b8+{AN6_~7POe?Hd$V}{grqQU!(!g1F;-DAk?h>7OP`Iv-ri^G=?S*}Dbl=^ zZ2H=P@NjRV<4xR5+s3wYGuW{Cu6-${oa$A2RLiA>J@akrdierK3cpDm*r=zwEdQV7 z3g?z2{1&rMe`|@6RY}5qBBkzlv2-e^<#DgJPh?|+8`tN4fCS0v9mJ+XEcH)6lxeVc zUMLVIVG>uu4v?&$^F7MrD~N?BmW}}zTTvH|En-VtB19ybzy$fNbFs`eZi*npvM@^a z_>-`L7L!E_dr2<62ut}AwQ))tYX9;%8Z%<}u4 zvrsW|weVvM{Yh|9ah-T`@ZRH;syu)UD@QxunIePqy2YbJ^K(e8ZCzEGfG1)FVV7Kk?T8i zR>(!)C4tz*2XvRwSB^Bq(E<{5MA9+MTJ~?23VmDo2th>`8p?6R^Eg+3xec#Dc{rl1 z9c;pX@l1d+cAPpHG`TieLTz5fwI=R&em};Kuc|%0{oa3`SNMJIG9KJ-|1tkj=;ca{ zf01s8oaK-(Vp>cj=i!KaSxi=F)za;7!LZj%YYs#O=f?(x(1Ab%V#tGYKSYU;!m44- z{i4X-%Py}4vevnGpA38nA4htIslqlbx1C`FVFS}mc!`jB=w6{57mSYYQayBtD4Do{ z*RM5!eN6o|HUBMg;J{dzQ`}33N1axBnan=OZZFY%?1eo4cg?;E8%-!24xMUU7}FiB z>QP%(Bz>TKwq~8=z+dB`S1U=L@mWWqu9-dQs7dlUH}FZT)56GS?vjc#+JUmE>Jm#H zUY4b2`nFHQfu0h}sxiuNqJ5NuB1jrMu*yb=Xeswvxe65h6w-Aoq2^9-5je&O>HwR` zKs()p<`d7_X(}h&!m7d%f(qjFF|QGuMf&1Y21A6rX!fB~JOAn#fT3d`nZ5Cfj*dQZ zYMUsUzt*0@ap1_P)O#d<-Yzp=SrY%FJ1EtOk|(3{hfkJzVXesOY*EoDYibTr#B0+P z)m3rvsO*MMPddN7G7O?tO*pzH>SHUNu^w6F&78iwGbd1;NmX^+HGWZZQhmpRPn`a2 zyHP}Yf9IV8h(iCPl>f6E0eYZsHZerVAIyX3`&7&2qWH3=0HE)_LoaYXaOAM!#$fA2 zrcM=2xdXf!Gr##D zJFhjpbv!qnUsCjy2Zhttw9;8s7d>2?j|Df?T6>n;2oN_1#p$^Yota^Mi;#J`Zjd#} zzh2+Qc$oSx=}PF4riNdWyKk^7 zDpXiBk7USHkfnZQ(OfYcn{#dwN|xf2&kc;BCrv0+zVimEF8M0haNt@NU3VW}<#=I8 zWG!}v(vKet6=ldQ*@_IuOI-a`i5PJ<%yncl-e0K!y?eV)0(7DAM%=jv!Pt!@>D2*O z=qjH1Nq3ob3gKRoLPvVceqc$|YK>W)AL0Mg0x+y?E_lH#Z8u%yf=B^;yfjFS-41%T}rxIuKMgl zKEDz#!_@NNLd>61phn}+9rU?~iCP6|} zeuPq*o={&mx%bSveKK<12G<(Cf+7}SR{^ZMkySYH@UPk^aGOfVa@&!jx+NCR30TWS zhsVTV{I*-1C<2q@YpsUw6o?~X4@snLWF}19T)GHJl)!*hOh{-3p_U#6@h?~nixY!*nYeiG+M)c79^%ezR=2boRWg(h+e_Xy(Iv8Awmj5URH&iTy+ zCWGgiV~PFWY}K`<*oUtdJ5|wJAucq1qJeS(;C{2F}Hu^W$@-IIs=7NLBu=>c4nxbC% z@+x|p;WjN_`HIyiLK&y1rsRlp{TX^RY3L0%=2|Vz)?eTHd*hnQ!)H_uQl-SJ=KdYH z>zeM`3vSrN04!UF)@l8j;-!=Mi-)TY0V(d`Q6d0062s=q?i4i(a^K#ARL%}*3w`f6 z_i^_d(i@*P8OqlZ?bRuatJ*Ls9Y@fHBej#O5kg69LvT(%p&MruBhZL=V!+!|C z%Yj7B;r)@I&dD-*7yCmcyG3%HIvo(J%TO23&W3emb^F1E^*yyR9tMI;s%e zhWGu&iu;x$-s?Hth4xid(^&C%7KOBFhH?W&p6(JwpVZ`w;A7qn7^=8AcW)hm5TX8)pO8x4L2t9W=YaT)alQVGT>kKr#0?2Lw!eV^K< zhGCVZ9+CooQ=bFz5Cod1@f|7lBvi~i#p@^~?QwI%X*H^8G5Cx*_}>U?4Khebg>{-! z;lWFpy^Eq2l{KoUpH))SrMF&Sqzod3B=^C(P^m?;CeD=QxGYijjFPS&jK*r47jZnL z_m@C6GI+gK7LBV7R!H*h=RbBw46w*Mj*FAN1yrsnFVqXM(Y94SIPxbOnt+?{xN6%% z$}Tc!Z5D(+YcxOoUf5i=OkSX5>~1c9tHKDqAn@UHt?S?D!OymL>GxGH?XX%;D$)BA z^`;gt?C7jfskHF397{tfc!R)tp=B@m;2&syLIpK9X|Kj4Mj8n8PnKr9Br4!G7Kb() zbxQLC#$<4|Myj-_DzJn-zrQ>}1pp_`&r1$VH<(UuC(oE=2zr?BIuBaquSgD>eI^rj z0$h1>P2&a`sbA>+e0iyK8kt`Gdq*i`Skv&=BVuC5cqTgjrUr1z!Ed30skd4+AX?z$`3UTn>4aFe(Cz6 z5UTp0t-xy@D!%EGWVtC!s=8;kiAXX%Wvbm=J^kVF*mRF|3OEpB&q9tZBFq%wij6V{ z`!+~S4#a^8rnhgDA9#LNK$jwirR_mfqg*1I6^@e*LJ(Fimf%{KaPl-BBOP=!X7Kk{ z)uHtqP=k=bzXhhzk;Thc<$yH zRXJ8ZP#ZCE_r`31?cn1wG&_qr{16RTFaR2?*;(RGpI!h#q65y=fA%0$;TjB>k(2MY`A~kgnx_p(QiSo7|Bqzp=rVZ& zbcy?(p13uVD@~wkqRgf_oF~2_*$-vT(<^1#`aH;4pHyAzXxS%a%*H5u zaYsKt60>eu;nMzz)!aJW=z3K6a5wg0UHLdY@Z9-g=Z^Cse8O3kx;{I4q$=_^#KWjn znl)@Yy-r)gYFT`|Ogu$7Tc^=g=U-{y<*~L3Zu^}l1Q$`8UU{u1hSOsGxI)&*qn?rm zwRmOG5@KPFQvRn*$y|lLS?;{da(7Jg6Q;8u{5CR%Vpx=%w(VTejc?7On2LIYk(ii9 zbw%WQB;wFT$$F9im_t#RST zbS>TPm&T}*>{sTnn-(tE3p)*d=&(0m4L{GSAac4!oKR#gXjg(vO6V~bnq6+fUB3xN zw=Zv>Z%MH1N;wqz2wHdeF4h@WbjB=g_LP^b4ZY}#+;oNg^HNj1_U>+(a=*B4o^+K$ zm%Vvg6rnY&h#td8jh~sU{BR^x9@71DV(ZHDl;0<1v2z%71{JnR97j)rgAz7_ul7%Q zCum^D0A5sRnAM57gsdnv3srWirXKa_5mbZ~s1aGsT0s44Bo>ViDEAgH6{2TX0uGjT zalxtCA6TahqH2S}0C{QxT!s_8-|SMRKh=p6^DNF9+%FWdRsBqT<3V@Tk^1tg6QDvW9s zY*v1xntXJA?2ls6V8dI(gE`t^=^AeAGd!dUi;;q=PnA@M2PR?vLV|p)S06aca3J(; zbSCjd7Fh^pt=edm2=gn6fJ!~!(*t000nGn=B8CBEoq)YiHr9Z>41knj!e+^mNtL0b zJ3z|gs)B^KS&5vi{-G#+*|-w9^%gmyz92>Z*tWrtC6_@2k0KmPhF}lu<0IUaR-fb| zFL*J01U|SAIFQWg&4V)a|3ChMt+DJ4^MUzV5T@x?;E7}aIN z7S1jGci(`1k^8S-{@%UZw&4R10B9uizgFAy+AlCU<g)) zZF|6Obq!4>PJ;*AHQG1Eo^Q~6hYzTOQ$aH(rlxoB=$j)Ym8KBQFP_NZC(hB{GLz=Z z+Les@jho9_F@+*b9OMw!BJ2xN*II0C#LSPPwIJ$+NZu2EaXVc4`ZT!N(SPOX`S>Y) z{*l_zQH~-7J1xF6wa*e!OCKt%Pb{KMhA6R+Jy78nhAOQn6vg}x-w|?(0Abq5E7aD4 zP+~3hI``-)?PIfT*k2APxGRb`#%ni%jY9%S z4bS5)QDi?!ibp63Pr-8yn*|Odlas)3|FX9q3s+RG_&k_gG%qT`gi`MA3+rwX9$JJV zqcql%Iay5B4>4Fx%xoFZ461=b5uPQh%GYo^qYHMm`+o5ks^P`BOe|c20u)s4644mlr?yB^N$TK@?6(lg zCnSLsK8QCrQm7^#P^lQK^x#{OU0Dg)!l?WEEqv84fx?eyq|Tph6gx)ZgG@0xFh;_K zH+SX&M2k+V`2IvaH+){3#hVw7Zf-rsdQC$9X&)|5)vx0vsh$gZ?1DR1MP1@C{ZZ0DQp!@b+Y2G}G8^G9Brlt7Q0+=3T} zcQ|n0us82DEI%}lYF(QlMFlI2R$;7h*gRm{q3kNhrA%9^cy!aiXey=pU@UGZ`C85d z;+AG+9MT@dnKia+$L^Sj!??A$L^=B4ddZ0T%AYL>tU7Rmb9^2?`nDk z`xB0p_}}ZQT6S5>4H-?%Lq4)-b`iBrxon&nH3tZq#g&lk{9NQEI6*D(;Tj&jRtT$e zdi_58=%2~omiq>ucN%aN6*z3@vu=a=D-QYx$L#9d9~J~sJd9<#_2fTwGV?KtixedZ z`zqfFL5hMJZ`O6)b;Mw8S6o^Zev?vH{W(#r|6eKB4S~eOUF zwpz2kvgL*X8_TEn`e~^Es~B*CpTi-5BMd;p&HauTR81y@cnOmFfYvZ;eqy4ECvYFbU0o)Ar>xo~x&>1*X4h5+2XGT#Zzo7-K&;x-ko-YP2DNA2;!G;nHe$O1vIBuy@4t9MR^rl`Xby5Cuw5-Z^{iylfg^Sc z(bUvVv7d1yt)hQEX;mQEs>$a??Pgk$)BGHd!kGzy)Jg?iLFFy+

9$;rB^j1bcpTS)5P=SJ+~8ngHZO6X^f4BS8;Wr9Gf zvvZd75kA$p&-E`d2mG`Q1}s1j1r|T7(e`BsbBDw(CNmGyer&h?^RLjSYft6DRHPyk zCky4GL+9Y1OK=ysd#f471dHf>(iH#ZOe`6J-DpNan^2WHV>ADKDFunMEaT+e{tziPcm;Nv=rM>rIBNjy^_D>@G#o@I18L zU5XWM`ka<1I#w@?(J$@e=iKiOf0I5q|G#S8FTC2~tUw8uPS^D}kNbVyqYc@)%CIiE zovqs;NtG;XEB&hDnr@0#$BJOeTLB{>gj1lps}jFT`m9}OT$gA1UR3IvH64HLpm=-P z?P_CNb25vY)|wu{rt|r4v(k#l8s`dCz0F&X$-lSbhpkqa8k{{=ye`)788W5+rTdft z6y%;ajRwu(9Y-yLOpZ7mN|Rm$|`&YHv5Cd z;;0H*K@GgYRiZF_gt!qCk&tB2;S(P6S8lKB;r4F#fqX&Uy!WQzI`64ouC_lo}C@#i7H+&&up?vY03L>bTGtOCdW*bWe28K~nrX9Un=p!~}6zr$iqq zGzHAWo4`0Cy1BKl_G9dAKP+Z^nQlqm^wU0#-6U_V7v5BC#FODAOqD&>e6s2L4hp zxzNp*ZXDMlSuJoY!*P6V!`CK2s(h`&weyMXH;-=TxHO8YEC%R7#-mFD8wU9I!JeLY zo4kPbM51{qf5B$n(iJGXdrdpSc*F%w z&ekZ7#|x;ud)<$v`Z!76UH|L!;ps+cMf87b(SA3#YqxjstllePDRhwZw}9waYs0wF zV?{+sTwdaT`FVGEOW29@_A$Ihf<%M_CtflJIY!&VnU1RO*BDsa!Vx-S7B#)A#>rY7 zQyx5>&Eow`ZpfW$jV25`=R5Lw6-1=1TwOz?VzDJkn%JW*Yoq9Zc1cI09Jqnm?dI%#-fDQ_`Mtt1l~`&5cT^M%5tov4z!^I?`vB9CxlH=g96!za)fHx zK()bmiS`egyqoTrIGV3jzc!NKO|GB=EH#YVzsLH@Qu}94j5C*g_r%Q)SIl;Z)1nTB z0bA6gyiA;l9CS!eK&4$WkqEC+`*GzP$y;1?$kg)*q2_~8{|N~bR{&N zjV;+&V}(g4&?#_yx5zOz2xUOSJY*i!79pV~iPHH_uupZO2$7~mX(H)f&#aW(h$rI6 ztGJ5HLkSml!^R-$`_kF(85rPgH6x6aqwTiGHT+R&VLFh#QAz$l%AhD8`3rqMX;5d}Mq);%tO-e&P83$2E=*dI}#WZ0YuDoG}pBiylvZITO2w< zUKP8}4>!RgCRxx6hEYOVYKQHBceS=JpE_Y3p)Xi&+o0wcx zik!*G*?oM%xki%~UuCc?74Y6q*OR;ifvmnv$JOCei|IGmOz z{$_)%&PzqjH`Ea|rYl#NNuTEOD6Lvd)cMpo6|9blh32e7vNvsiVCA$z+RNmv0z@mDxr#voXUs8C4R z*=2uh**4MzCUkVvO2!hsE-U~ctXVVynVwA* zK2U{fx3xt6gw%TLxDFF)59r8>DeI$0$RShsJ6WQXhSU*AQSogPdq*tAgY}5KC1>s} zoJC%vVdRZE@yc1y81qpOTEW!H;tYxnR7`XFNn!|EMW^i1WLQvfR`pxHI5Fy%0p$hhi&~_aC z=Y#~<-Rgr0Iiu^=AW@VU^ac%{+H=oy`9x?Ma3=~Y5f3|uuvP6^^S4k6bV z)t`i@F5oM?IIYF8g~f%y3Cfpb3LzOGzZQtC*y#Rw(K` z+e&}f5?54UA(ed?jm%k&EmnK~;VrhsKNQrQ__+zqLxq3sx>~wy?>RMW$XV@t#jx_F zJiWbAHAA-=h^KttSc0zYTI2x@$I=-vry8r67ezenxWh#ePLixJV8vs?k_{-{Ql}5; zlBM&ggum&;5GRs5j|r$>1Ur8+ueH>cz5nA>*z#@ppI7Gyi=8*y`Q71W*XG7h)1f4F z5DJ>o6rhV+RGjHnzJ31U3dhUh`hO}0_%1DLRB0k%q|lYroed^wnw9ItinolkQlEeR zDH2wpHp*CPKNWuE-@3kIC^T!6%qUB5W{f>M!)1Q)e_Nk&mJV!eMAVJzU+C7#<>*iz zgBOJ3M_$GoEdT7Dk-f**^`^4-bkN$AWww!Mr{Xz)8|Qh35-MKN6JuQQ-$punWUv*S zeO#f(s3z1JwzMv-)~*>_^~)o1z(+WMXY#xJX#Q~d^5PWp4osX^@J5pg-ux32wP|Er zhC*AXR?vc2G`8;>#iZP8KaL$nZpLiIa9+G+UUl3rt2UEq(U&$xSV_W2qI`!c>2!z+ zeITjF^ereLkmk26CCE0!sHz<4#o;Dw`?o6A!mSURfqV_XESwxRjE8fx^I3+jeJ&rtPgCLEHLf_xTZSTdRW5 zC=>fk)EpyWELA4BfP_4WIt)CM+QCTM+lXtz7QHY~CqyM3X%ZBtV_?;cV~;^f2N!{X zo_MsoMmlyc@Fj#RFF?AQ2(!4etu^Wd+WQ@U%O0eOiow!}1j;G2W7dod4(>I`nSUeB z&qv`$TMp}qq(53F680M*n>(m>ukL~$rz_BP-~6eNM(Zf7MiuE~FRkJ)j-*j$xbCaW zMFw)uDjw4g*A5ICQ#G(-0%zs*qXz7fo+>9rz!~_G%=BRT70rLZM%@3MVC7HHOE``1 zAfQ@TzZHJ-+AE`=SyA3-iYA9xXC+*{1km6B@v%j-CcrKpOF}GE^u1_*?2<2E=zI8B zw!i}r3^gmKjx17qs)x<_G>HTqi;Gy@$%-GEB&4SeXL?-&2IU?bazs{N%0*ICO7C zY@YqKVL5BrX#V>c07=p$(Nvuf!x~$Nr<04?YcG2~9Nj%5hkOLa{r+RlMS|nWC}*5F zXx(k%_`S3F4q7my4OI<^3EKYvzjW*5@-hGMKKd*~LAv`ZrlYlV8hVpOdY&_Z@+E0S zJRy0q@j03_UF`tyxOy9|Frt~Fr-M5i6ios_6Vngj*5Tx~Jgz#ObroQcX`C%>z+%(gVvA>HYcWhd2t)`sA13FlO*!>G zIW-(YoUgoOr)Lv}`46YhIp1th9fh4$J$gwKbo81_Deeh4MLiHbAMa7s37^wr79~5zpcW&){+75&AghyJUEn7xj#0!fNDi3hXpuX!DAt z7CY~Zh-vFud!rzI9U*Q~ilJ3x6BrKX?)keiy} zSMmzzx**3p>m7Uk5o%0fo{H}~TO%K`g!rV62)K< zCVDMb^<>71!=lk)&^Ukgmu|HJLyDbFjHSxpMYW> zN*njALL%MQMK_s*1`fjZ*TcTVE}WuL) zrZ#(WerJ+uxA1=Td3i2kP>WexTe0>^I0G4gBLWnOV}<=eEr4Z|C(sCNRV>o1oU?2M zc)YnAmP*wN*V-*r5j1p3yHsP2tY1TrB}C-p4rm|`m%&7zsUTQMT;Z3 z7TLUMYda?It=Ug|4tTdXAsw!J%E)ho+hb<#wu5O&rp`Y~2xMv*sWBWe&NDHyHS8G( zey5%7p_{s>PVKlNy=0-yDlHVFB$p-+WD8EQ-mKlsO*Hw~*u9YnbLO}~8+G{~&_};b zxbuVzUSO^bH<;cEza%Pp1-K`?eweCI#p|gE0$DGu4zgMkW+|i8Lub=Z3x7j3^ieHx zpT6Fup^ypZVOiBb^I}n#3ZsKd(<`s|w><@6`0rHmI^lv)zWgnCiCouogPZu5BX%*d z)D%mL6*Pbtl*}N`Lxg|n{hFkrnUSH~4@x$aa8NN{7UxW@%aoZp$9Tt%o zS<1HtCpyf|S_VNx4A=j6Y?SVAEN)>W9cm=RWR#;zp zH3Lxf@d1tHGeZ(aPIr)>_lWpa8mGIuz(9rLec*Hg021Y^5UyRYpG0cNTwXJrD z&^~>WuB)ZM|5nEoAVbtBy!|Va?=TO`T=PU=KYaj!Zcd&#nj&H4G^yOyND(!66r;J- zy0O>rJGP9_W*Nyvd9Qv&@A3yDY4fpx3bb&QA>hGIqD6^H07V_mHF!u2_2RYzAEN{# z0%D#^*XUgF|1gM|ykh1dxrs^e`7R^hJj_sv0SV?yHZr(@B8#j*Bp`~6B#Ep)vcVQC zffIdiUy+dDAeOz+I>{oFWoEiKrm9~!AQgoAMUzLJlgPY*s#z5Q*E&**1TcF}DiDs> z@PoQ-$kC+g%@S5&aF)W13j4(W*OeGAK<>u-TU1TaND43it9!Ad?!4grml%Fl)43r) zVQgxM9Wx9dIOOEyN>l-79%ofGH4VN0+yy6_wz$4bsz!L^PYoSV6jM_2@wov60U?0$ zF=$>ny^eDuaJ+H_D}&G?$d-}(@KlUBrbvUgMEg58qN(&qm|;Q?G$p9i)zvA$KzPMj z@0O)YxO1B42%!^byKW|d9|ajOau9YuRz(m#0t75-DuqfFi|VQwOLhy6jNfJKGz*A@ zzY@#MqsS!{<7ZQWAy0j#EnsY?zyBl8@Nl3#IN7BBbx;#xmHV2!v#!1{Redx3S&~q! z>tKEM@34=a`p%V`_D{xPHub^u*CQ5k$L*`7Jv2c&y3zIjT{6I9=Ou#mZSjV=J18t2 zg{qLs9g4QxTK93(5%{G&Avr!$95``@GxYEbdwt1MKRl=kfj2~EA%!OfuOS1%wv*m#j8Aw(mW83LGUxWE7JbDzKxGkxbtd&@ZOq*mE(;Gsh-HeEer< z=Vgk*f?u(R>0E|AFnw}_$IpQIlhcgJ4Bg@oZh8KOqcJS|-*1*2q@U}tBbb4upqMZ* zJ)*(li}?{^O7$4^HI^Sc}og3}rMJArwr zWzc(R*Qpj)gRk1~kSlM(eJ<=Q`3@5v5fVG?PlX_vwAs zbp98R)DGatd;}0$1+1GgIX*X;UJ;4sx4FrOL-g=Wxro9`gJ7&gBq7*Y^O@yVu%qWE z+g)gd*4}~YcrJ3oeRRZ_ND{^>yAQ2)jGSD3JBU%`ESYS=gTx+a%yL7blwT#~3G>?V zmHB#SnX4o(MT2RDGy+Bxt&$I1(gts+zLM3OLq=wd%^QA$_2#szYu!zPXyx?`ja;J~ z)<_Y8MGe2F%7!|NR!|z3Qb@BnS=NO4{w87Z8v~Iz$Cif3;Aeuj2GCd{>Ja7I!1BMK zgKlB!_$W#&jGcY&KbL02m61_81W_d6q*0A%;}}@U(P?JB@~t?I3SvI%y1ULvtnsXJ zgq`sae~TR8VJ;u|4Za#Vx@91*4PlJFJVUMG5?aO<^6$|P@3Q>^QH56)`iqP5yk?y~ z|B-wC0F&4>kWN*A7d?S;3RK_;T2EK%{`R+ zlo>5ZmB&4cmXNY!Mtv=>tu0!~8ih6mTTCWfnp0%*Bb;fYiCthXGcLX?{EJR-F+TQJ zqOczG5#&B&un`JuDJ%Y$iK<4!j70&D$$!{2T+yjz)WyA#?&rf^8o<1GmjNH{{Fw_5 zGF)c1iv`EG-;kg|htA-OPwqBK)^>P+0ht9yI$jQ*ql1@l^(JqEqf7eIEnlzO!Sjpi zQ_L`}-y!0D{W#wK78k>iW*u9`%Hvdp()+K+s(ZCacQe)Xc}zQ(EZD{S+U^{I{y;?l z@1tyEuSb1|xNg~)Oq*4Xp-F3feD`X*zjyKtf-sCuk z$J}*f5bg%?mgn{N#LV(>Djwk)A9vfo(p?$zh50tt>wjWKGN1k^e0{j(BtW9KG<7;$ z>~dqKbC~>?t1o%*zq{(cFnW`AqL>d;fDXm-Y2B!+M?GT5KXIfdzq4r!^79!<;Cait ztD||CDV?aH7jb40Q%Mtz{5sX=gZ1aCU9{h2+UuPIfQI@jA>W82FyO)9pq&;Zj9`FO z7p-wBQ%Y5f9l3xFiG@#$jlnOO3MoItS-er+WqWoV^9NdWfPHgg_E*)UVy0CG2Zu4^ z__gmi)(2}^%J30K1u0@ulBJ*@Rf$w7(p*&mwZXmmJpfuT482FORGBJ;_9?I|Q60t} zG*5_}8i-yHuUw8nvp~~zk&E{ULf`+-cUB(^5_7Z3uBL+bfBKbABrCDYyn6)?$^BEJ zRK27iWe^_v#ubi@;U2ENS*Tg6NR#9cpUTIx@bD2}V*{_73Hj>P>!%Xh95j%$Fd<7O zz)+KAA1WYvjqS5Y!8ZVYt6=P4Q3cT=rNCIO=ssuu<3`*<705Oc1&!ip92N;96 zsDsQtTj(%QK)^?n^kWPvqa3I23K-P1Ps~$hz}TcMP*jHiQD$I5D3|2*b>g`4n7bSc z3U)s85DTDJj}ZqdEz~1xK_@NB5EW=az*NoA!vpZc{XlG|6C%|r+^I`Rl@u$?k{x+; z=YjmGU&Av?b|7o8KDQbVa}m} z^5GJ}DGA2&pIU2t#r07Zx8fA*g1=irr}<{<4*@NDr9Oj{il6>xt_r&Xy2)Fs$ioF( zV>?uS1Nw+6>52}E7xg6nA5~`=Rn;4Hdqt#?5NVKZknRwWE&)mDknV1!k?sbO66xkh zcXI@!I}V4C?!J%z_r7D?`++YE2PfS7*=wyi*ZgUHGoz!ehbVDW zFh69`7DlSL+&V5!* zX~9e=6gu&dM&SrYTfqmy-;Vl2>F3`_F86C**VXa37s+FGV@rFj)KBh!V8*%GMKd3t zVw8h8&$h4)2J0y%5Y%2@&ok|91K4@B?T?NrF1*7NRK@lwLhKxvx_aS61{6DOm{}hC z>HDU{Z`I@2)EM<FFy*9%m>cn2XtPKg23>16Oon zz~RJ_a3_^oMfPG_^p2L!SI%GlHf{;7>*Hs+^7T>hYgt;kbzeRFP#h3mcwm*9IQcS0 zsQ(PvuP>iNE@N|FZENG2EB{nRFQ0rAOXTrE%tN_tf$OH==Fz_{|22Bi<>$)2y42Pq zgPt{*IQ!{-mPYr2SJk~lM<=cr>Hk;c#6C}uL5om>v}RQE#%4`1PMph@7tL9#RcbgU zjZkk6%5`hosM$CL7yL!mrV*S3u1oLy&SVn4t6H%~mu0U@GIHTX`WMu`{hh~tQFsM{ z)C%gZMK}ngjPE7lpdd7Y@@WW13WFRwofIXiFc#%2uXpC+Pa}8C{_5!OM2%!@r7|Tk z;HG1-L`J-@!PKhMUn{O`>xwR}P%lX)ik4XR+*rBZoLmt0Jo-H7894n(9+@loiHb{^ zEGIbJC<4`)2q^~5mw=cX8q z4l8S56CU1p_=vx9>G=SJ)1A`)C{tiYlsKMd*!sY{><8B;Uu=i&?h?OgKf?ua#Vl4S zW1&&$94*JwnJwqjAGPznu8S*=h7BJQtn1|omH7pQ*Dox<(me9(lhp^mX};;}xzfs$ zI~OR(Cz>XdFT|ax(BH`RSb>4Wrq|c2L0Gek^P9=QUR6?@Q#56tNQc^fJ?e0^e|uQ# zamm(pSXJ=%M8hetE{Jg<|r zn!GmXD&QQ17)^e+ybf*G__@9}sL9sJV%LdcYlW$XIdhfKGNuQMkkOA0t-Xh$k7OSg zJ}x$S1%Z_!z{HlSo$Dd)Mm~H@0nnCMzy!OjsN&?=m5A6aT2h1-m5PAH#`-F?VTWa79>%$Tpl$09(9JjbNZnD)-PYd7tDsP z$i?3`y}=9EjCn3#9Iw)&lI$33&}orl6PsRH17FVNEEeav3y-#U9$i1 zC;3ZBVNF~?D3xIagY#xe{6_+-L%pKv`k;>vILI1m2vo3mhFnE{v##D%yyomuLKj^Y zYKo%3JSrYqlN#Frkdoke^|>zKYhv(~&R5A$Q?3H#c)D)MRf;O!ZhXYKmV2Ejo)9KJ z>RMF$)%S*_E~gQ9Wa?5HC%7Csi<(_AYwdWMf^+I%%O4ag>+$ z2R6EtN%2>`2u2h))%SY{ku?J8%(ZwTL>$7RCKCdm503ScKmJ)eliu1380v9;YLfo5`YUc{{m~aq9)waaHPFW`> zU!Va`C$P0RvKIiN266O24W70u8~?&CoK0bcmSvi_;KM&gsOF3%Z>DFP3SLO<+p$ig zw|G*9&E2o1TsPl*#u8~#QmlhYFn4gTpBJaku4ojFj!3_ z%en0}pOr*xX+6l71 zu0I%6)3~I90qB1X>LG1TfmSwdMi)+5Sy@#>gSd}*vUUAfVYypIIbGY{x8M%q?)f36 z%v5))vdTQNFq$a-rgrFHCuPuD_|`5OwB<;+{c3W?^P!jEm;`denHfwf<~gw3DSFRP zQ2%Rex(~^ww3J^SCt7B46!F6@|p6gh(-P`+alDje<1lDHO*>~ZZ{s8I`vC< zjC#1$^2A~h{?jk7zeS5@Ms=_z&S6k~TQXSNiYC!(_fPKb_S@FJ`!>V{6;nvEj)_sJ z+Q3#<>>4(~Uq&Dds$Z20`&8R`4vxK>Y1RbpwW}+_8Mo_Rn|2DWjP7npqzzGdx!rR? zr>rBRN8aM%;*eII(0Y96<&kf!q6Ih!kO5~!bAh?#WHJ}Gmjn2k7-IMZ1;6Vtf%1KlUGOx=m?2rG}LMINfe(S1NeDFMgz{A(mjxB@Lz5-&Q6Kv=e zNQVmB@?&@T;^phyH`hts=al#@3lh{ za-V-ka?YxlP%9s8FhS)dm%L%8n%Aw*I?jaUT4u=dMEH{$ux z%?(m}UFJ-CLQVTTQHGRG#SKGj)n~uCK5j8yn`3L{4>-!I^7htJk`r;J$0^;s>%ZOJ z@O$@2C`P)rhqppVnz@eOQ(lKOBVRDO^x>QA8pX+~h@|qSb*6DhXQij@-?C~Sm#|`k zma#1uPfJGkYz}9*a@srUE;GfnU~Dv7hWDzUztUJEw6U%+5kQX}$q4djhBQ#L0xcYe za5o5}2q=e%H)IOzL*3QX(&K*MR1+uspd^mOF)Bji6ryD(z^j=SpOwgFt`Y8i!bnlw zM3{$WO$U8WH2gWXjreV;^=h^g%1_m#d`7D;QWGV42G&~(TBGOpG>|mN_N}TKklE0}Vqn}d^CqpKF zu4`{0o~`@Q!ee?_wtG+pstTUONdC5*&|c~Aq&30I!|B0;I7|7nYMY5a4eG)l(qkVF z9<&Nu>wLCN+EImUg`o)@qOzFToco%E1BncH9N-Xgc&^&;gN1oI&99+hTj5jaxTS1H z5k}~<7g#UA0Ip7JzN}8`2jA`=YanZ(jecVGc=J<}2m_gmc?q0Fe)@Zv5CAbM6|&uI^w)Qh?TFGZ=Ndpz^Kla>O$2x2mZo_4|yR) zhnxNc3uUy6n+u*47}$d(y?X=Y#TQ}JbjGrzy)<$UHGOzrSGp!1TXruv?o)T*{ZkVG zTeiNJm*M@%o^qT1xkj(OOcbFiIC>PPi))h{kAI~7V`M6uY5leT-%sx@jArWjY~dTU%5%TCK5Be@bg_G87IP^PS5Uf5+1pD*{9GWJze7`5n4 z)u_yC-+`-0k>5y^oV!yE%%*bIQia(qMb*kw6k;kJPgaAEimdfu(xvij^>B>OKyZa88^b;AIe zx#QyJPox({INnRW*Nip?KPxES3 z802YIzU;^8v*hLFwdBqKbR$saW7@B@Mep(7i3L1f+S=PY!!OAC@^KE^FUkM?sG%5m z????L~gnaLg>4Eao*M}r_I|rTJcWt_br4riA&d;0p znPxXG`v!3!>L!*bIUaH~!%?#*+4hj|S_E#QQ7d|fhA;FXv zf16@1?ArttyPtdvdwtb%bccSo8A7nVLOdTIpASqL6^6}yD|aWA zbMwpJHA`_rDP?4kqxyi(q-@!stJmzFt!3z!Oo0-pu?N0cs9XSG z0$j3zsNR;Vb(JR9Yh311=DXO(V*wCXKRSx}Fr51+P-g~+RlRu6NidLV57fOak;=I7?v=|~z`ps`yFzRR;Hb6l56;ad_VYc*~n zX<{=9?Kx|g^Ymfi^DZ~{3WvNQ>|V*6M9OYgMZDsk5(;Gz+p_8s@g3iQX+Bvi?3^$( z&frXVcdtiW&bur8j|rCXapBm$N=3MJiZ0CN>3Qbw=q8BbBh!#sBLb_^b3*PmEh$(7 z2{G_PXggN(oPJAeG3l39G2k{Uv+#z`cDDVbj1K;V;x=ctrv zxIi)jHeTLm6j*TD?5mU&xMrE z#Qvg-$+>yk>R^QmdMMFpC;p%`)dUgMi=%RC{j652b zjU+%Q#)GZMGgjl*@q$~aZ-Zl60^THdCz&lYZQ7hMEc>Yvy(lVO^wLePQ>sQ*i=SUO(Vet~% zy?^W=4NXKMS2dj)iX&-3+7_@e48#A#PjZ48t;ZLKiH5D~BJ@o2cg9Kq(=qopOPQ%x z`TYqa`v12;rft*m%rgF?w-T3_J>fDp-#VZm7LZJk>l3lkcKR_!sMw5Islsq^jQ&F~ zST&LEewyod!H5+Tt39{8-gWWZ|6v{~HxYaf^rYf`->YL8ZmoI5DbCjc7pRX9HX%k`~x13F=5GwyN zL!^ zVgwoIGN5^F%~^oa0|CT)pZJn|(Sm!#r8G1VwYXScUc3Wr;a(mtb-U>6%@j`Aj$89Y zbjR5TeC8n1s?=NS8zs?$_=W`B89qh=VrwD|V`*urXIt!a#vY&j@5A%=QU}^)Qj8(g zWPxgLYv)#XKB}0yN;fYRY5nlghe|RH0;-+o!8M#;Km??wa$B_DX}tQ-GU^^DkBVw*Yx}-L^LkLlzY8{;`ai3N7NS4&t^$6_YPT#KSB%{jU6}o64-iwv z!$*p(RuA0?HtLL;4K%>TEeJ~fI--_FDYTmMZN9^<;{DQM-mhvUFFSM%P!bRKOi(5$ zD{smpvpREX;T6@X5$d^CR7h>?V8s&swiLf(u7R4B2~M+YA907C#STLt=7pYS&=pi9fc53KHuD#RCh=IFn=~9xJ!B zb<}U|l5r~Y6kbnh9+fer9z3CCDXJLD|^K%llTnYZf;`oBC7Y?}Jrc z$8ab9Z#|;s2dc1xsFCc#gESGtUdW{mdgoVxyymO@#+$#d)H!t$K8i2{0ChpE4Z^xp zUnc<>`9lSCn?mvu&znNl8`T?yN=EoZ6W+f6CjJRBlTGJ>|*_Ubsqx;D&oLU=c!Dh3xB7&cn8Kc4=y)`C9Bgwq&^k)Z5c4+VRXeQ&lxwFvNfwR0u_E-jre*J@C_{3HJZ`TK&TcXCo0Md0ZV zCKcd(T{G(Vwvr1|B#)K`74tfSGzlgOX(6^6Td)S)oc&_l#!+sS?fAZHakRr^To-yk zW~c;-%I;Cp-iw0KFKoSc-Rz(|-#-QiE1JZPhVSTyL_vo`*; z-a6U6x%cKqkiNM1UjYibqo}E*boK zB;+~)mqYdIr`m|=UjtT!UTYBe-27~Zn~1x+`!=Z?;fqk$m>6u7>6w`(r&FX%5)wk2 zCa^&T5_lmY1xDPYr>mW!VPRny$j`uLqSB=AH|po$0NWuQ-zft?#z3{N&Lw(3qD~ie zn+ZH1-Z0ReCH|Yy>Xs{)sP(-`{_%ksQ5@9{0}JZ~#1HQAXRkg>)_?7}@C3HRV1*Zc;@h>6b=EK-fHFJZlxn>7=V!t!EpPm z6S&3qFoJ`e@usXpmX-iL+rbHbD)e`0f%>at0u7yldZ1cFsa9oGvrh!5N$e|!AN-YT zQsm9+sy%at!I#KfTFTJB2J+Oia&i*Vqt+Z{@%la6hA%E&j7q!-PcO22~)Ma;uWLTjbCdZ*nx*yVelKDY-?oc(m|BD%^wuiokNmDv3N6 zS?-FeEA1rZ<3SX~sAwdbR?~!K9Ct^IZuL#G&zZqjf`buyrA}WL%e%%j93hyl4{x-j zQMpq_tjiD^|Eg9_X|EWV-wq+!5NP4hb`SpOW*}k@zX={Ew3`g9!iekZ#(9;L`aKJ; z-ONb==@rfDJMCoS#lSKR!2r4F6jW(*!gP}YarDH*rp;^HVzc$K?e`4aPi=7AkMFe0 z25x;M2w4DEq23_=jn=o`530NQC3#kHRnlgB5k0&KIQ^T#`-r`zUOQIgdMXP8LkyC6s4213`p~xH?`FKJn#(z5)Bo(=pSt!&Q zHYm$8nY{;T7ry^^W=512Y$`+(Hx0Sj6;v*iX2L6Rlns{rN>MMRtY1VF z$~vJPJm?tQTb*GmOtYIUafrB%U4!SU8KtUNq1*`h?(tJ7OCS#KQH0UqYU9|HDuz6u ztd^^pFxZ;FQZl}nv|77{g%*QS4!4V)22Bz$#QOWmc=>oOE6YIR=9DCnB7Y^-Hl^Dt z&5sHyG+_M!gWj3L@x2QW=^jPDkaW#2yg{|i=rt|+Fyq0mJmJNYg7 zeq%e+XUvE`K9^TV8?h+Jlysz=gf9kNLz5EJN_sA)@l}?Z}n?9dPSR7weNdA!=dBCX@9!Mz$wZpMwKjSK~htNWd1nNnGEyvDjYpM-x7v^7;s$a zm%zyJ>jl6(1BGXtj9lHp!R0=k0KHiv8rx-9f)NqVn&3-^Zo~#tU`MxVAbZx)HQWOw zKm7dM4U7fE8N-|*3Gnx1m|l*LqA?psXX+})e_DwoImU+!V9u2N9 z?0%fM8JP?kR}~cjVg7gW;@DT76=6&$mf3}RzgmU?H@n{34_|70KF ziFJADb-CmLh7I2hDr*~l4Mp$qZD+gxlOdac@|1h`}kkrU+TdN z@QVm^8ng}pRLIvP+A#vn!HJS@oBVrY8IJ@@OScrJHe^2$Sc#g;L`=ks8E*@F6C9-;OvMY0XR+ zdQJOD-2hJ4xAoFQMJAF9Yu=lEOV zi)-h(DvZg%G-PNVKe`++UpyQ?mcCPd8zo7jPn99pjw6`HftO6QWt^5Xf{VB0@hnvX;P|&aMrxf zjBLTTAhJe}G^3^=j=)D_B`e#&`9u6+nisH|sT4FMSY_XvZKAocZV`Dh+9nk8$Y!s} zJJuvsdC1R-gc`rD3C{X5Vf6MJI_}Jv?Be(LTs7C@KmFBUk7=@tGRJ1;rs8*VwZ@-o z2%$#e1k(dLDIBPhzgpRl!;ncmVjzyjVdeXFKc~RenV0k(FX_jWwJamZ{AbT%PY=dG zhPWuho4N;`4*FiwqgrKb^0xJ5VgA-;STB3L;fZCk*^i>pl*d8rRP-wak<2yetY;&< z=Q#EE>8$>COa5AED@X)6(k>-?L=5ThXMA*qy@cwEhqU6W>ZMcKI#!dw2+mCmgbeF* z;$-JnVkjpo9~B6tfKex*=j?Wpw8_h0)BZBa|Bc7z30>3Cv$=%Cu^4B3yl!+iEB^r8 z%UF`wNVaPZvd7naMRvL+!oa+K`Z=*ynPS-g6pKiK)8l`pT0n<*FeYAZqwpOt^Hx8i$FMXWQW^QQ-rs97=zvz2F^l+`!zV6CxV(yk4+1$)kV@ph# z4WCQy@O{gwrZni$)YRGyHN0k=$%XWhJRS=ccbgLLv$7fd`qD7D!}*2%nkFX+A!$H= zwg(c#7^8w0q(JM^Os_s$v!nPjJzTlCJJX>pLhUOsZgqB23JyE!r!t^9ks(7%91oZM zUI=2%Hd(61Jc-AVqJEp7)Zs)%x-y)7z*3+S%7MTR!tF?DOFqbxzV`6+bR6&$24q;u zV6cs5Qf|yndelo`$W9zH+x$;X5_#Baf6!ural+Ihdiv^ySwZ3Zc=F~k)9~?T1}Jjb z0asxGtMm0XdcR!LCll4#Ls>?zruHgbE{ESh-0zXzv|LeHWq{!Qo`)dhtemW)x#C<< z|3a#2yMe{P3`|9xOM2$#nPkFP^`OrvL9?E}^7?4m=a7RuR+S$ptV}R8lD$0?%BIsf zyBI;4zXu1nVXF2VcC6>R(WB9rzANy@`@=^vQw)_A?~L|GhsWr>naXi6&R|Tns?QMi z+rv+Nqc6cERj+33XBzb8jsE(2NThGPKd7I#JQ@!HdFk*y+dm@%5?{s2YF7yQ-va{^ zheNiDPvtg()0mBmX0BKgJOzrY zdT;}huGrXCXybjzU0#j1RKTr=vu1~;LeoRa(zd&uI+!=O=l^IFp(DS zE-uuH(Ua6VSu1pfw<21rUrYAsxGpi6ouA{Ytv8WRX(mra(=DVn{Ad`a;mz~#mG22w zERe-2L&&4)dd1%sq@~&PCCC}GYZArKR77d_lXg0QEz@P=G(tjZ1|#$V^Gu<;BqT3e zuuqYi=f12;-bg!J9u z8{|uE-Y8*Mj&Mq8xb|Z@*DJ54bver)uR4uVJc3}(x2lLPZ2PCCR6m&oqqXvUY)l6U>y`IJ&v+c?aFwz@B z{lW&KpFkbt|1Z&7AioqR5*9f6X=8n7`6TV9@w<0pN4h>-s%ch1Nn<`qaIepf9EPb1 zAe8*{nzS5@MKl>UvlU=WcZagA)$cD|B{PrUea z&XwMCtD4w^pSJcZk2%b0ZP-YGtg5# z2eTG%hq>1(rO>cgaCK48DB;#ke|CAyuu@7W0QAFFpUdmW_AB(14aVA1WH7p`h-q z58oA#<1OQ}VGD)(o(xt(e*H2@q&f5P1BQoKxR>6Gu&9cP_iE#ZLJB8S);mL{zxypm zKed8s0bF9_GNS9VX6b0>>Sqd+E7+TW&PuU|S6Zp5XM*}j_oAwJ#!-1w_FRN#Ue_nI z0I+7tN&d1I=e6Gz<>OlAV+M$c^sP2()BbJW$T82VS1%RzZwS(UGu%!!%$?e;psWJL zmiRra(FVo~rYuX!VckK`KGh0jj`o$PB}HlwhK#ATP429Efm~$E#*bywHc=c5h5s0o zCZ6J;9a=s5tXw?Y+Uzl|qp3S$q4Skz49^t0V>Tu?OM?G?chDl5_z=yWUF+vDrX=3i zVKU`0oNpD`$=Z4BPb9v)mZ(+uEmjb4Nx9!G^bXnM=(fMWI5GK5C*pH5hHS75l`mY^ z%g3sU2!UXaHz_6b&(#j`w0gpzz|IwhNL!C`1xgB+*{?1rE<9Li^e{QQZz%!x4!n5u;8f0@E8X6X-i5uR5{CdXW5}=YPZ27?@(}Xh$Tm|kSyx10%fyaI)_39R^ini ztqDJ7t?LF~eSd{;M%?y=Zw4QSLrS?zkcv-%rMC2WD!u8aRE2~RN`22Vdep&1$x2p( zqPRZEIf-;;beBPSYji3Pg+gN0I0#z4@LkoH72B6}f|hSw-H4?m$lqwaSF1)KV4fj{ z^9o$hun@3RgtDj@c5kCiU~UJF@EDQ3`m1N-u<`1U_=kqVrP6Nuuk#i%zF6epV>1q! zva0ZDZO*K&S73TuR7<3ls^#h<;@t`&{=)cU0A`s#258hEv#413JHvMzzHK+3MS-^N zojFD=EiJ`jF5XN`tAx0M3QW#EBDJJrrqZ2x6_?)DO6;*9Rcu6tk|zYr9>U~YxzOy7 zMjvTo9N5AfB0sl8)67plbd}e260`T=B9VguUN}jxIOwf0ULcW@lK)GdaTN?U4o|`b z!NwW!1&o>Jq1Psz|97ijG3`IHpynR!-gzj^90kbHs8`x}AlRFa)}MfcLt8Au<6l4A zW2D};j{LbK*7)9JDdr1BrWmft_Js5{>%4@lIQ%iQ|DW?ybtC&N#}2N95!YxbV0Iqg zs$7k?_5&K`Rc=}|-1V6SB==Lsh_+@a&*Tn3O)Hb~TJpX8PGQDlSYuH3+bZ;puxkQm z?wB^K=AwY$mczqFfQews=G>v!#@!idcF_odi)JKkc~j@NCEBmVG^Mne=eRbU#WfmV z!40GmaHCGVgbx+F%@XrH0S7N?-@M*S)xo%dWNrwFs3{9oV~6r&Qf+OmO_0-<)v40d ztn8fQ?N;PFn92jOr1auJ9E+A-PRrKr9jP66P7-&nX>k;n*Ar$*o|zR-=jXJ-jg9{x5T43rvf zNygr90Uh@~mtH6N^lTU993V0)C6X4L9b2^!_4%AsQ(3UThFwA;xIf~3wwQXb!_?~Hl}L&9v2x!JXIG=!$vrH6XsA2iUSyK)McgaF=AWXrU$PSK*@G(E6*k$@%^0%du zxb@o1Vp<#CwvHTb*$6xye^{~{@M4pmC#qx(E(w#TV&)OQr&YqeLS5K8vg>zI?443FDKr+;WA_#L z#3T3HMXrIJ#wEx=UY2G;HfeAPEP7Wlr8eOYtp_qV_o3;cM197PlRq$-!#d7jZILFy z;gwZDm?`ZUWZgbrXXQjGJuat9Nq{-~5cVwmuNPow^DmEHR+lfr9Fig$oz~XYaSpm5 zKQmRVxl4vUsYvqc6{?rO&{1`)*dwzUekL0h{lW|=6xb6zR8uLe0}@4*M0&>pCit^v>%>o%1vit zg17vA+>)KtfGXZ|h(|RN+~g={ zk@phzI(aIOX3*w2NZ)>q30|nryM7()|8`@EZaO?(91>#O=;`SlMH=1(2HeBmcs<++ zl=de4zU=J!S5^bmbBpJ3Ah%L@cQ}iZocbutae)5yBXJZ==CEBQ!(2}<>-6&Ra^*C0 z#lLHAjtJBND-T3#1?W3TTI{h_d4>~bDsymgX#Ws{39fTW5^P-vHHfgO!UuJ*^JV(@L~mh)a7EW-L<`@L&iFc&62 zJ??K`|F<6^ASTp(Dcr>l*3*uc^JU(tj#$^P&%6%ks`Njv^u4%+rlk{UrzsX?wfIL@ z3X6K4Aojd8X!QlUu336yx0{<=@AaHOwtHCa!&&j&Lcpy<`Wt*|PKATwz79-J)BJ-wM? zW=R3ay5=eOiaa5^32xXa`0d@bOG@dhX}sgxuTqAp@!qfAG|%c#-PD$Z{cFnl^L)eh zq^O%(@qT_CX$*ZeCANS+QImhiv>qyWSu<8|8%phrlSA!9!n%ECMZS{n0~gKS@Tq%o zXmpoWebG`nGm4 zgqpiPLLPZ%6-wGf@UFN$ZIE^sOHI(E)*^8{XS?2|H$FLNsS;* z$Av<1`tpM$HaE>roV9wI8p}KV?7mbzR_-cDw*?0wJ|8H)Z;M!kj5Cd2O}FY&dyD zc=+GII0Y)9f=&e!CwYocS=``(-~5+lnzl;M3zvM}C|EgaNIq)Ro$=v7UcD^4AJT`E zb;MV9d50@j=h&s`u@GjDVxzyVt)k(IHjsO_`=@E>>cHV&!TV#hG1y+bolx8$rQ)Gj zB9LI6XTI(x3~`^W4@>S?wwy}pmq$UkmR_3zz7_WnF#-msl8&B1mH+u74rIq#VN>@~ z6_U8Mz}+Ecb`e6 z;yb`z(0NBR({d8fTh~W+8tS|7v2Er@b!_G$lh#V+8;@q+g{+z7Dm(N-yf3dQ%nt&E z<%WC=Uq10IJp1FB`aTizZ>aF^xIV~*;Usnvneoap zdad4_w$(JF+yPgA853b&4~#w^`Av-U(g*_oQmx(wDrz4mnbK8n`(0Kl)X@3&fzdQ- zDt$2vfkMJ)DA+5Dn)B^hQ^gXCD=RmullOFY@ATz$Ll;K)bSm(8g!T9t%`X9#F=+Oc zw}Hk2J<0x4dGF@&7z6Tp^W^V!8C71Zl#}&dbo^ledKHsl>NVlnxE_Wp%A|Tuuv(f; zbEYd_&p{u=gkc=H(DczQ?F~9K>5m4&0iE9UTXVJW9#zEzI^p{}7mz-rlVa?f3y0?9 za|InD6PjvQq-5phy14HS(W6M__#J2Mm<@sD1Jt|EN;PYL@3Pilab~qo5y5j8AZB9* zvucb5GXYV2%vV%~Lc3B^_;x)#5;@4oQ(*J#9F>3oZaZxwT!<}ElQ!mgGiRZfm0PPl z;^OfefsrOK>e_eALG(I!rqb~AXiX9^aL#uK@MbrT2N+dmY(xWYh!T&}z>!K_XvCZ8 z0!COoA(Q(zBd0IBHz@e94>O}s`Vh~VYPfl<@(<$rRo(5dM z2A@L5E2lnXe4w|mUSRH4(;bOkH>N!T7xuXTS)h&r zuK0)3x&+L`+9MXeH<>H!#QNihSh5pIJGQ!PM&;AY2x6=2cY%fhcO2#JBw(*~-cg`s z9sCAnB0eRue$l&}S#azT7S7{Zkn?HI$9 zHm%!7Hf@JS&>cs*npK=-DZr{wM_+WVhEI>{&&yn*_#ppqkEJYIHd?w9*Lkyk{}fKZ7>qUX(h^$rG|J+AHSGcNJG(D4N#RJd zZ-Y|5qy{QhIS0j)M9EiMhZwI7=oxcNd^bOS@7!C~TN2`dlD1U6tsM8cQ5$a9m7D5RM(ld zjA7tJUNCZh#`&UQmfqQgN@kIirt_CR3Jq?EGG#igUba%YeueBOVh31$Y8)#D)v@Y) ze=Rw==#cjh;kK%}8fQZtwQaV?3Q?=4x=c|=$KR1un`QP^Q7XroG$04+agb(*f~sj8 zNY^^asJEbryAx8k%PfmHJtPtqWmm9N?gOh4nP-ml>otsaK+}-$%MBix%7>UN>lRNd zO$5)mhVq8OOa@KbjD&N3@4wh_Yd*UX0Z;wWB6X;=Q}F96&m0+$e*|pZd*^A&#Ur1% z@FSn^oo9@Cchk)!F-_{5ex+g!^l#Vt^-5Ddk4q^O4IjOy0hXg#`um%WG^Y94As7DauxVD9&a!+o)!uX0255Ql~n( zCO?7?ME92fbavG1--#XD@0D&Z%Nv1iQ*b^uAQ`To;NE__XpbkfKT*%?dw5^IGD~bo zc1>s(CLHpnQi(4*U+Msd_E94ubq|0sKPay`)KMx;u9s!k-Mx1tF}~lrD4$nu%fxBFC#2+){YzynzkuVI$AvZ9f6RD&iITHo`Sw_^_dhtIkAVxg%iE;1w>XU zfzyZ#60o&fPz@#0pzfJPbTA6mIkGL3!C#_EQP4a^h&G1kn1=KwqM1K$`ydO0y;SjN zqzbO+jfW(mXI=A4epuNt8RwXxM)@u1VpdvjnO{wK*CBb0%jn$bLq{L!mg8W06!a}> zj>ZLMpFs0Y^)DR~#O6(Khx%7`jA{_ABN)4rS=_Bp`efx&r&6=*JapD$rh4*99T^XnM~`M3ajw(BL(EvO{A~eA{$8%jlHr*KS?Io#mNGfOpIxr z(`_&|i>AVK8A`-aVc5_TyHAb;ig=3o0r9+2AhBu?J4!mNqHsf65gXA9V=0(M4h12X z9pmXq@3*9m%W+*(Rt%(PbsS|{rHlI+%&$$qO3_3z;(MGte;eOyHaVYEk=OxIMhM>^ zG{xv64D7HF&8<~Tam^&F5a8K9dk% zEn2zn5rSo%>eAEkPLAwmter(j>}m<95nbOA8J>y~ zi84|xtkRXAHK%y3 zJ7T5dCAT?WU3qE4l?F_#Qf#T!?s=j1U7Zkm6%41#gdRue3}O*z8>NV&K==TN!}beoL4jP;iz&;io-eMP z_rH(R{JYFe$71BsB%q30?4vbQ+ExwJ>IN6QHCY@O<97xs4C;(gB;=rHFJfN+=T5=o z{_k*8-xUuRwsKG>DAgE4v;jq>spXg1|6;&xc~NyO1WKB-g}xNd*`6FeEVaY)V?{SR zgOGt3WL>}Y_is|bO>w~b`QFUPr&DWuX1`AR<>5h^&6VEsL%!t6hAR8Nl7+4X@z~$9 zg78vVg>keK8-?V*C&^$Vx(bp3iQ-;77l{4;!K#qosRpZ|(Jl$UQBotQF#j*iJ6&;6 z@cvo=C>lT@DRbLlFS2ZXN4vk^`r&eEF+l?_az@x(Uu+}nEOhG1+fhAB_tL+mgm-DW zZO+;5oA>B8x&4GvI zoR@TBYxW5Y6?V+!UKO!Y4oyd_wA?`MdcT(eu`VXqsl zoK*PvqlfaQCz^pKG=je%UQ{j7FkXY9hU`mFp9mR-W|mK!OkBswelkZp zSXA(+g(8^6s!x;X$afrf8300%-@`kiHAg|As;u^L|;L8#eCVGJ9Sko7FFBY2d0k!LeqYfxE2QRYt=S)xKWkZ)=OR`$n- zec!$h=R_Nv#*SO4ew&apV>87TwTi>mr@MxuN>oF~o=vY$JJpW@{a%_jvWiE^N(QqO zvbTb3X(DZ{MN6TsX@0F``N(|5ffeC;IAUK;hrFhB+VZ}LT#P=iSasZLw$Y@tE>8+{ z{#a{bKCGLWdk*ldAZ{tk1%>p)q&EuU4U$F;duzuay@bbUO%$r^Yw|A4LRwM`r4pPN~Q z%sOImvRN8&nzYJMMQLJrAWOKD+vm!MJseb@3T&h z=&L;jyK0x_Rw#w??2+9Ki*~BRHc_eSyeAc+jP?yYu2)@%>Q8DVos%Rns~p4_aglK~ z?*Xq(Wf8YWQ63RoA~hv!A_gMuv9Z3cw~+afo~ShYw?&ai2gQw#eD<^ z0n6!EJ62!}RcF{w7>QBO7?>ETUJ)DNnPeTGo@ zQhq4HDt*&~M6o(AX`(63RB-L6)P12!vQ4)(M(?kR_JgtFnczJ9N zAYH)lrm}+tOV1*Qr!MJU;_=ti^aw^dDDwrVic~{BqOb?|G%1O?-3)%SEthbfl zPUW*Csi1Uy)8MD$)M9o8y{f-jjXzv!p3;44%}&;fTMo#+DJ!PPVw-7bp|IDh!bSwJ zmusrW&rX#pEIzMdRyICue@JtA1rpZvIt&g!>LSi&^wU<>qjBgz)O_p!z; zC_yk8W_%;R6H7HZVxRAp1XN`DtXe&~AB7z@i^nu09riI0v``u=&b)$~8>AOUba`}& zLh}=L+sSBci0|+Ab{9_H&nL5CGa>2pIkNg=vQ6k{-SFU=Mu;Wl2%Hz^)Ze$L2XNW^ zQOfPt=#hIpzk}3cuc**t1<5Tbtj`*pqYJJ7IQeBhM`QCz#|}Ml-JZ<-q|UbQAv-MM zXi%3CL!2)1M$jv)QEc*bhMT*<(?iz9L6(JEyuO(N7-(NYhi@773!#E7OcA*UZew{;n~2i}6i|bOweD(zyLK_yR-O|Aqt+<5XOUMkF>!N-B}3mp#7_GMXvUb|*-qej<2J-^^F`ty3rSfERyv^wq?E-S zx)nsmFSUa#-G&aA4pA&jkz#A^N!z44vo~AexDpTQVKIcf&d&yBCc6)Gq00OcGUdao zsluindA)f#T>&QMTVD%al1GVh`v_~l=8&ofm4)IF6Sk+_&2VJipi`9|w3j%5$W5mS2^d%4&;)U3(nuBZ%ek zTlyBV*1K6u*6|}*VXf1zILDOLM=${&&XDP-1^z*uJ+wQwtXQxg zxHThw{`?Pc&yV{hP41ezay;t7hL>DQWs93Bd?g^3mVe&{EN3Zrl;8__s-8jAa=X*> zmTC-tOI6Ll#t^l0W%`)8kI^`u=pHyf4%5!TFpnw3^w-`>JbPZoG}j$9JIW}%a}3MJyGEz=FAx5mJ3u8-Gn*e zMEb9>0uQLrtfH)&o2+f#$Oo(5l8g8xsd~!ajLARD51TMz;Acxy<^q61QQQxzxuvAN z8!3op%Bo4fBh9}y8MxwBahh<%c1c~OFA+`SdC7Ga6%z!w;XX^?yEl9c*G>Mm>R#6^eKQgmJ9sO{+JGHfZ`Y;(YI>F;R!{NL%@sC?=i7?7WGc+z00+mSWkb^1h6`xO6?Zbe;H&y%@`}!L~UNCwkCq zlShTtq8W+(>32O(F)bN|2^wK%_9K`YnNdKcK!70m;e^cfR&M2ZGfZJJJQCiCNc}?{(vY2BqIS^C5MN! zfZ{u6C08w_tCMsuRnHbmWBl2GdcaLj9Q(1O-tn#U+#j!^9~m7cuB2{!U5Z#MsB&0@ z3bTKi!w;uuXyrd%J>Z_<^QQ|BbEJqLN=)uo#cc=mIr{qqv`kE$WmHeZk=@^4@AXx! z9!IQ3H3*#$GMAsOwMd{kyQeLJH<*4H6tZ+Mv~eljeHpANXs0P#@nb{kGr|PCbP^wM%QnMCE|mG7lrBQzhw~ zVVJ>;FzuFR4&x;6@k9PxsEw4-S2Nn}P*#sX{Eg$rLZS&=FAt*2ek0?ka(z6rM62X78IT7K! zdyjt^tGYs7^U;IhA{i}=5~=<7(0;9lv;{R6xXG>+vGFkPe_jBRtIJ%*!_1?HecPj4 zv*)#S*=w8o^GGH)N&ENnb8<#7)6g`iKmym$3QLFPm#;dkUv;WlhYb(Oxrpe{J$O57 zh=!jeOJeK8B6Zr4#>-sf51L7b>wP!^W)b+ADJ)zqh}TFh?x*wz`)N2mC}@-^@chT; zMzI0~$)oyf@bb~Ya{-r+)>IXlT@PsL5p441q2qJi!SQ>(!tNcjc2D}-EkRBMHuqUz zh+=OB`+Tr2ZWLlfADT5O9F+DL7GRqJE-l^+Ccr!@-yl-BN@~ZwYfB!zM1enlj9I1@ z0RYIVrGzxS+K7a366{nzu`R@<)0e_1(B>&ajG7iR)|WEst?d80epr)l{O&AP_K7rC zSgZn)3pqv`0DO~^7VO*t0tG;RQW!paDiZ(1NKap;cxZzcF2QC=K5_NfqPWyXxV>_23DD2X*C zf!0MCLH(FQALH$s>soRdIIlg$risJWz86xB>gN7k%#Wh?%#YM8&|Q2wPqbDK3F_T?V(VB6qC9 zG)F6IXc-E7IrIOpR~1?Wlb$XXVuseHp$6)wxmAd)M4})>vV{r8E+v@pe&ydf z%qJWd6F+P;ofKUcHf>mPP@CZnC#2@9L#U=6u1g9+-Kn=LU&|aeW@b?1NKCF~mu75^tmkMbJ;ykPwhX;IG$cw&}yPct}seSqE==)Z; zj%I|}?FEN#tla0-Y|g1$(fSt?84?J8v=4L-H>ivi2-38eQ8%8 z<`N+w8%rWHhlNAFrnZR$s3UI=*p!+El68@bB@OG6r$aP;83!^mwsXdors!p|^7z7F z7gp*gi89U8&NocC$x&i9L|I#*-Dmt9+Yi4B(K1?NlKfLSZy0G-BULpIL?Htn#W}0K zzP?y-`86!is?ZO?l2x+k-04czXnbg)u&MG@_#Qy-e!q#~o+54?2qu#DvdGQIW`q56 z^^R?Bp(PzfH_f53V$O2w@AxqHs_T2EH|6FRXUav)S%AeOjFC<23?O>jFQHP}@MRmFoZ$vKmbF2pv` z&olI4rMmWUhDNf-wpBfDy^w#_j?l!wd#n5QS{n{gAmw6l(wLFA)Uswz0N*htsx6eX z(?l-t3tnr%&?mgs-(A+ieBCC&-d^jY_-@B)6{v!9sE$f!uu8>_l-*vE+vK)CB|m_9 zMnh@ib)(Wo8O$jGIJzl9Hs-L`S>Q^uX8TZO36AW()rzjl@s@!1d!Z7U+#iz84ndJ= zrNINzpU`NX0dH{+f|G9rhX*G)7-~K5;5PlS4>vul(*o{r8MO&#Fnk4HyXRZg&GFow zJ-%9Qq_vJ70cyhVSF*+KWD(;sN-1>CZKU`i0Pp0tF=NAi=)wnB^l!ZMcr)CH6u79O zO#(=IBYYCTJW32z!N;n!;oD*Q9e_{_D8FEeC2?+4xAWIQ??Y)dv_!A7Ql`^2g8D(7 zO9Q`T6iG?|+rokfxHa7hMLHI?f#rPQmo2MQa8LoAeMhs)xG6wnUuwbVKJXR{{pa+l zsrh$fNP&OX_2WgTR!4^GaE`g96{KZ$-SM=Z&a@6OJU)XU%Q5H9nLj)h&ygcMnv8J3 z1<|9fwyN!^2|9Z7u+!^5TCYv*=8QM@8VyzNL{=N;{#zO6OdxIxvMe7gJEJmRXXFlQ zywL{RIoJkE@%y(ky{)KwZwRV{8uJzBLv`z49*3x_mjd(~YFXLRSGIt=y}kh3jK}Kd zvwYcBBunp+M7zesI)i*p-w!m$kOsZuf3~500ChgQtUFZCkwF)(`z%84WZU#Ax8F84 zCxgbX5tG!L5NmPhf8lTz>)bG?gzojxQZ18_Pdr_i=ENU`|`8sWwIARn>&a3>-v-U2|84U|ZIgjl(Tj``}e_XS;h0UcQUnHH$Eya4C=*UNr#ql z3Ob3sUOPWRooF$-+ki+sXEs%&FK(FkbI0fCO`h$+u{T+gs5{7d!5>$0#$T7reN^g{u0`E3iSGT=; zUq#SxE9=2^i4^K_2*Feumk3I9Q^9jI8EA0uLm*R5DqOwJo#DP=F+Mh~m|qbbnD!I~ z*l{f!Peqrfzf}v=gKX|X+_G~1s&HpJNbbn(DsJlqjYSO` zj`+g(s|-*}1+c0Za!r_i1LtF)yciyXRKAtfRT@7F5-_-ZQ8oqmFS+_A}ZkFw@H^0U-Sg&Tu z_;LhxGjkCxhNs-BeR+}CU@`=zkwycP0ICRXa8JCJ1h^aduQ{^Z^#A1sg2 z%M-K+}FaJCnQ=KVi8W2m6EMLIya}x{Tvd{;r$W`lvXeave zYw5_o1e6hvLj1;~-fVGo2u+2K+=;$#k zY#CD(7~y|jY%@@E%2_sEZZlbvHEu0&KIFPRT?k)cEc4Ylard@`FllL~>!B$N=L9>K zrNhHaf5;Yu*$AFI5iATnx;tELQ8-@{!3z|T#fhiMs#7ctk_d4E=~C1?t#3ixO2jlH zs`1P?h(cm945&>b;D<~lyk+CTwYqAd`E%RQWL#vIAqbPc?MW7tTO%2em1Hzo43TV*sCYcCWh@gV&qLVxRhWv#e zgg?qyW78plU zqB!1l72Pkpv*Rh%{^`*8{oXkU6(s8cl$1@q<>$|qcQGhYocM?F+G0mJLi-?Hr?vGQ z1`qE0En!Wlk|A^Sy`C@X-zzq+2-KY`@nnw#=1)*fINHw}-0X0f&e+qgE0Wux$yjCnEFb>{xMb0Ovg5dfWq~q@kdasjw-F zQ6GU3JskWz7gqNu$8|kEt=17T`)?WeW)s(NFC;NdhcgzOJUEElyaHPf2g!}7=+FW} z04|wG7!FJUY##zXb0=5VArF3YV6iG~Oqxu?TBSdSX}Cfi&Tr-cL4A*7jaJorxvVRU zQLl!6cT2m_@<_LK!Sw7N4a%`Bh8E&R>X&R!{~UZiFCowMFGFo(koJWplqe+|_hNU(0Tt(Gs z7&GS{c*Sh62ImM8%Pm8R%EV*rNDd@Geg{(^A2Ld~MDp%QSQl|H1;ejT{oAP9Lt%2& z##QOgRlM6SmmmsFR3f^wmuHc`|I$&Vz~oEQ&$FYy7Qc`;Ko$SYgt&`~)A(#C24S>c zyuG~xGZWnD9(qq%%z|}JHcM!UM;pR)i{GifuX~`q9EL+S7#kfMyE#yLJ^u0h>Fvtk zt$W8u6nDp_kvjhCpA!dg4tP^mx~x@=u?Vtm^aOv3I0-FEe^pzzTMI3`5O;nFtG!?) z((aO@J4>22<{x!nWbLpq!0>9qgFQlPEFwTQaBf^Rn)%D}vEOTke@g=#tu$bZMv2kTjh& zy^ig@J)n0M15@Z{|Ju#71gS_QnPGSeWvnmY1tKv3khmoqz!^&mpaB5WtB=4vkM98a zUZJySQ0pK-H+=Pz0O!42jeKirX#paN*|QTG(rgPA9yrVv4u5%9-@9)t!dEblRKTq6 zZ*4f=65Yw;hmgPxU8m>J5TP^;{E_tbS@Wo7PAD9xSf@$xPWI2WU;gTKb1;=Vu;6d9 zs%Q;5`Wym@+F>=XAKE8JE|ki`7Fpb8^>Gumi&}RUyIRZ|ugJQyYte#v8@#?dnA%p! zA+u{STE^dYdFGruT31oA-iW4zK<0s{Uy#wAJCJ7wjtZ5Dr(2y zIXaG$k?|$f0Bvj>*PxYzpYJ<%km==5cF+)uX(B=cdlHlkzSW{fVs33$;@2|GSGCYS zRLib+5{l-~o&k)?0q=5#VynVaLb}<5s+7d%QSmAh8X3&8D0hZ3`5^!!4wzN%I(2!~ z6ga?0HGe0^hy7lK{O84Buk|IXqVa*b5V1m7nKRE$AxFn)DLxHDb`!G+9LSAQaiKi> zF|2&u8)1O|)L&U`=eIbK$~@6Rd$$n#ULbG6yvI{AmBO4FPmE>2#S_|R$Dp0j!A9eX zZ?V^4VS}v)qBzPB7_v`fYiQRB;!o(L_)wgh)5UWh#kBwtpRJPwobn(p z`!ygDa9+EAyNX&Vy zn12%4ePtkv*^#i7^XP!pyFLlb4iIo+jESUf7QLJrxRcI{h*sBSHDK1nbW(HPXamhhce!#mP|RXjl|vBYv}& zRr+y**Uq6inJ^%5m@LLv+GI#pFk62}XCo$GOSsEegCq(CRQesW zX!(t~AFuxBe}8?_|Er)e>W5=2PiU50v&J~InmKKX0p6mJpo3}{kI=z3DYFr&vt`rf zTXJ30-JIg(EA0@$R6*BoA`9CsQgTZy4A9{A-dd<&7NhM|+Pd&E`(QPc5<3!^POIZ* zI3iQ;6Jrtp%4sG8;~V=*!8N+*PDC zQBqXs%(+GLud!gwqamwqtMvU<^I|69R&lwQTc%gglyurZ*Tc<3^0!@Ip>+COvxSi1W?*hq;GagZcr`%TK3 zm;sLp;B%dh^sWBhvRbXlpjDn^!>Mz{Z^Dkpnl_#+OD$Wd0sy@mxjPKmi2#I!nG)EX z)-tska<+Kt1}Hyv_V!IpO?!KLsmJaM7-myJZkR#b(T?&;`wlU5Z$xQw-{$+@!iM@9 zE=CFHUB59l_q19aENr7^f%#k zsN;II_rDVyD2vp%o(};llhz1^Z5Q*)6FJtw#bG6>plMs z#LsPp`u+{)fzGo*0uIu@^I$>gx1)0Z?UqEeDlez=q&NI--d=|xP2WvK<3dQ09n+DN2Qo3?Na`Gq>eKu$x( ztcHLhk#ftk6xM%I%%lU+69&_V7k>B)d3)?&d#n%{EhT|>KLJzr3A|6+mJNv~kbST0 z6;P{B2d;7>@v^AkVX@|f-iW_lCbcCdAJrzWb(7o#m1~45Sz=Ky7d!UtUyt>XS_vTu zOO7Xe{Y9Z$ok+ZR0V-?lE!qP3slOKxZ?j|{f=Rg$Z!$@}EfN4Xs&k8iyxb0FR#uDs z2CBk<9V<~{47G+eWzAdDP5x>8J*T*l+J}5W+>Pnj(`v&@^RcHaTJvwF{qJ&75374u z`CL9weL|^&3+N$@diE#K0~7gFSk6I_s%3YgAyOgk|4MItLFLP+Q5um);=44p3(+WT z`P?;`@FOm_FSA;5vDLTdRpCeIF;}IQaOOjer4nkVfMI=H(&Q`q10#j(H@a7oY>6yn z!lak$z2ggiVYPQ^kyQZg-h!PBL?-ByrG-Hu)xEk(cz=IiMAxz!-DfQH!U+)1rr(5!x z-COp<{9qV*+}~)bny2P9nE-r?{3I6^>ofg0TioJmQsAARqh$j@w>5VU+^qxqA$Ffv zOk5UR$!TUEsD@Usmg`=CcM4D(L|+9y@Uy5(wfwz|s$*laZh7qzObQt+%P2&~B#4n6 zjhWEF#aT637?@F+RN(mPioWLIVsn?AMR1A7kXy%&|4!~&qcESAiq`_pM zyE*IV{A1+p_U&c8wWW<}bssaF2Io(B3J6Y_j_i>2!!+@u_zMd^q4uL8kbiOHdE(}4 z_8aTcYQ^qsb{a=oXTJ~0SAS&)aSvOz{n`KW5i@Y+OTZGmCqEeySp`d})7GBxklY5X zxQPRjKmF|YlA#qv!Z-jo7uO8xbrnqzRc1pO7^ET3MN}lyK>LNOl)815;L}0|DV21y zzIshEZ7|9@anyc7NwXAAqTJDv*5Biv6E8jN^?aJZuyKiij<$FgzFK7@lFf%mDG9s9 zGDoJ2+HjymyI^XY?_iCX?%KkOH%jO|8Saw0zJ2EUal7+KQ-Hv}Y!4$6&xWJjB~e)| zKQ9)%!W|hBhA#Snjf%plD};Dyke;*Elztt(ifkIQsuZr#Xh+}q=x;_C5~{WFUBVWP zoRpNWwQvSH@IE;wcm5XU;xkG#!+@8ML`XIaBg0hwE72@irY}#anq;{iV~&BRH{ehXe=*#NFQE?FBdKKKA7IsO5plt+c*Mlj)$h z%^+5~rQrkniadPZ?gzq6fC7jnBd+IxgX@kRG7X>$68c#MYZCcGA%aAl zMZ6Wwy!L|b=w<-BQNguQXz8zuGJ<@s~&7MY@ZjJMDU4=nb8ysJh&d5e6w6H)NH%^@KhP- zU@1GLeu7}|1u;bUe{SORtC;$Y?`-kO>$g$}q@YI@G_sKOfJt|ZX(=v@68lOVt#hMM z6*gco^$31LCtk5Qm6O>MqAow`vc!V3mBiI?wc&;dXzwr}l!tCo&3ZLD%u@68cMy&x zKbfSH!K+BB-XfY}%JD>Q0(qaXv1zru^57hXhy96)rp9z_clJQi2 zS?d(*ku?zd;zmQxdvs4F=F^wC3qqgyIpr-HH}*uVsnA=c>&KOJ5ClG!!10j6Bq<{W z%RBP+vzk$VtKR+S)|z7&@{W`qc7<&tHG7S1dZBj(rLs5HaBz~hw1QVQ->t+7@=Lz# zx33}|@+GOsT%jHvFJp_cjCH;M)}?7_Vyt3FLNNJi9>cn=*6ImOlC&ZeB)~XP<%9tI z5$8KUYDGYodOLE`la^JYC;M@+YHNZqZ6xI{xG3@7LhMLp1Ge@jBEm6AN-|o~xSy&} z(nl-JbB=l$)Ee-Py<2d4T~3Y)POn(y>)m#rJYmh0Sf4U`>*iX8Yqi%@&Q{q@7$XdL z@*om(<8U$eGC;J1AvXaVktf>%j!0?&U>&LmSUsf$fmv>%;XL&fu_((KmJULm`vQQ! zKBu8w<1WBbRCvvEJ)=VGHiuJMmAn|=zzK)b`yrk82f=>PTn$<5J}xj)et!10v$JpX zb00fhW%SH^uNT6EmtgR`9B|Mgd;i(?O>3W>EUE-P|6hK|bN{&vynIq( zLv+;&{Q{0KSnC>CY-@YOEvL|$<=WxrykM6dF|h3Uyooa_gT8WUon9VZlqKF?Q|12W zCO{nMEfctcuk7~V-Q4P<#AYrZ9D%ZiqN<_&@jCG~%zVCfHN*VP1WM+Rz*Eb(&u^3P zGE}$Kh22Z}k8_*dL^!om2DFEa%sXg9VTG;ni7+N6Ts>XXtW5NAd3dTXCl=DUy#mzb z4;Pg@A>EqNRoo_YP*bW$kfcE*(Gr42Ov__}xF?5U)@VtBIGU;=YA4$8d=eK*&Iup5 z-Ce>6_ll*}^-ACdxcAnL%QlN{L{kdo93G_`WzoMZqLC*IPD(gZM2)O66&qjwJJ3;; zuHSjUto!OJkAq078&ZN%QFdFx@xXOd_TlgWJ&^IMs<4M~_89U4QV9dcp~E06`*wRY zRomm%AJ0(GWgdqISTRT$5%&W^8J7GYPj;+|+sg*_V|KQ?u^#J2!EnrTD(X3Z3OzlP zQxH^b-uQ&}`dO8Hlg!T1m$BQnL#N|h0n){|@pUf-#-Bx9l0Oq;+0g4p(pwtv?F=dw z*G!Y;MAfkxpTRdw17{z)5ousbuvjG3?Ca;X8W~-`Tg}kl&%30WC54(HRt-Q zewS!`eBbTK>VY^7NlFs(i`yMbkI4Gs<#&`=m0Hrxt^0TTSsQzV6y7vP{7nc)KHPiK z8K)2-HQ1-k`JR0}Kq3kEC~7X-Pq?^w?y)y1GXlQ$v@u{v1yGutqi?;&fHzS@ACzJa zjg2sid(^YO7QLzE@arm}SZ4e#570K}qMB(LmyuRtiB-*)xV$Dl){6EM$=iJlB&DW~ zK94xZ?F9g2v^B@L?hRa}>elH`k9G9E2F$|f!MT|dY1;WZEze_5YqfK>vK%v^`ln_t^nNR)T>mj3Lfw`H9=Lahh-k6Tb9R(kI`E z^A0li!Q6yl{;5(K*(uqlbF`A!(MQ`SVi&>zVn5E~QUyAVZ65yo!;+rwN+CT=vS~1F(~CQA06Kv~^C34!nR>nWeA;5lBZ8vqCgCaV zuwZ4{7Q~{)Bk#}^OtC1j$ZQ6qw#Cb{F~%vWpI?=r@KwS@qD1maRkISI>gkq38Fs&v z%g|vuFa7=MRun&OHyvANYvL<;;AY(@vn3pEn=lRY0U<+~jeI*Y$XR)OX(Z<4!T)Oo z+!9J9RRV`dn^|c^%8>%%O|;}WoTh3s0{s3C@1n~(okHR zmTZ%j_kE6vro(rB6Ju!{3mpuLE0h@caBk9I(*&8p1s+GzpnPMNFudB~6rGvI=|}Z} zMs?dE-O!0dozz$hr|z92?*f3dKl5eUuoLTeNEek2ey~zsOi%1Mn{2>#_Xedgz@^Ug z@d^8Cp`&xFU2UfsO*b61!s%DY;4Q-Lw&y_2?%Nupm(SzD{FMo^>42DM5D8qeEY;|~ zz`898^p58^Fi@@1tX#4|K`lk1Q-;+&Z^Q;n%~E7Ugfs9sYHDjUs?t=(fO+=q z_UizgJ;dX63^WlrlwtJLRtw?a{6rP;Q>~dB`sqel_wJ8_oA(MA7p)Z?CsW%pKdIkp zs~rE(X{FW`uMqvfTf?S%q;+YM`lH*~jQX)l!sS8<&F2Rn4kEDeEO&Nm4;l@Q)-L>C z1&DP=Shdknu)p_5s_G|mX$_*EV**}e_?o44WAAHIY4|j7eIwsi_n~u!#gt#9+!u2P zMEJ#b{0JX%?TWMB0X2lfZ>IV^IFtocY4lDU#hTt2-Ufwz{pJPQbV9I_eV{z8PFhXbiVJult)lpvO$Kkkh z9^t%*Vy(Po-cxwk0<*2|bnd`*k=msZMh=2hYJ0=m;ibgyD1;fcx%LLT1iDa9N}NAW z()JNIadun4PrIbwZevsioJc{DmOZ zC`YlX!54HvM%>-)d!J+i2mw>~* zPa%caLDbHprqV>cJDe0>NK>E_)FgM6p@`M7><^NPYwkUH=jct<;FW}xgw>1@Lgqsi z1o|9tq0>_X1f8p0`uto6%<;@(BG zHD+qh`P}Iibr0uOf*(k6M0;mY_hcvi!AbBCv+lI4iXon^L3nCxky#vRxz^N?Uly+N z3pn)1UMEzowuMP_yO!~6xoaX;0gWmHwYF+E*`OS(`)QsCbb}7cB;g(qZx;9qxrul` zB`tQIF8GKxJRR%+f{7F!3?Xem^f<-#l_<3jze)OuA##+(QkC#d`Pi|ItQmwf!#+n9 zbU4sE^&Ybfqs_IXf&c-Ig-INge0v*moORDoL0EDe;DnE6EvrP+$3$sh7W9XdqLVBc zL~*;jLM2^3q*q2KP9F@~N}PldCWVcHjoiZ?EpPwsbP0tWBS}f&8luXmMVO?E6bvVR z>FG3Ql&(<@Var{tSZehi8=H80U-2Wv<&#_=xMsf04&Lr`yQT z3dJ=B5L5b$yR6!b+tw<98RbkuH3Kr-?&C{jd^~!=4E**~7!3mJJenBmwP&Y|8;izkxIeAR{E10#h{A;wm8mjpqUkt-DG=I#<$JdCq0-2;btk-e3C` zcLTrwgl3|=kZts2Jf}B_DFMs{L29%N_8`L;g@{678ZM6lqUIwA3nF|^r6)6hEd&6{ zGeZd;C?=6c07(Wo7Ytd7$mpSijNm5YoBlnd{-d^j(#sbn7#Q6ze0kW8LHtM#AbRZA z+KsAobBYtpq;SLl75Vy&&ep?3Ipi2-mkV(hOxg6AC1j$9M6+l6A8cp{Rp2p~?p5cz^8qFND@w=^d>&f^Z^m zWR!T}OtyyLsei4ra(@l&N>+us(?mn06{vOckJV6!+VVNDx(%`u3^#>evg&$G`_bL9 zP^m4L`E%qohf>^{Y(ecv*MLs#WxVPP8*SeG$?soFHIW)$oG9KwLq0}Ouq zUtGoyUq(wTLPe-%;A;*e4@c=OqHu=UsO8YWubE?RBd@Okt8N2!9pBrQDwpgQZQU~! z84;v4p#0i>yuC+UoK8htqa`B6MdTF}03Nrf(roM}ze@xb6GSb}ed8ZOU<#mJS2$T? zZftAW{rflb)el)v$xFGJ26BzZdQKc5qd<3ea7oarJ!4o#IpKW8Z!gT;fIrny`WJdu z$tcxfC~+X$x%>~c38EtbmlA3uD=_!~5aK9E-;Q}r)d?Nu!WGq< z98m)&qO7}MS#V6oE4UxeD5;s-zq5QBkpDhtC~QaWgs-$1t82A2q~gg@Wd?0EycjR> zIidvWnT|An!k<1G$Bab!03m>^>r|t06~wSwgM|1z1|B<#esvRT)~Q;zmx})?mf}wj z53TSyf=oU2dd}1? zNIIlNa|4y2uF&o=%)YxWYt5MU~Y;4=MZQHil@QH1{`+I)p zyfb?y|K`~M={f$V z9dMogK}rX;BKw|sNaxj2ubw{u6G7{KZ6G-w2I8xKN_aT@|HLN&-<8*OZVEJTq~%Fd z@TO;?Kqk?TuUI$JW5REBwjXY`H|yx>)vsDg#tp2S)lsd>Ug&-9mk1-b$;DD}dMQdn1XKc@e}%iP>f`uBrLZl5>k z?26~ZN)m&P_89;3RS4jXYx<~_QwMdJo))?Nv(hhHR>gwR1|W3Sae`M`uV#3$>aU` z+HF(;_2|CM%j&GwI} z&zaq~B)2`#*uFMhu%1J=UY|$3vsD@60^P>ic64LZ+{K;H6nW#=c{9d_dJbQ@klz(FW+Gr$qUGf$Q_{|>=5h_Y*Q?wFP8Sxp$46$T6J%o zn@RLG>U0?ul8pw4#@o>HDdv<$vNTQ;QYFPQ!z?73`Cy85@`j$BhJ?VJ^=|kv{P2{*cm9gz)qz7u9@n!An>|@_xiDJ_AAyK9s*)(0JfT`ZQAn;DIhhK1u>#-U%s@FuY}~r0zhFEAaZ3$- z{a=m~#tl*%_q4pN6}`Xbp=v>%so{h-TYOw^Z`(iKW_dtGkp1KyD1aJlE6|{83(kS5 zDI_+(j_5AEz>-f|!cvK?sho$*T4GGl!N3|oI7|j!a^UsBBl&Dfrq+YGB-3xzES=z) zxJQ2cR#o-VmG}BMhRc=huE2xu0MTI?y3XY4*#gJ`#tgq^2` z{T~2R1x_%1CPB!sysMxm;(xole)IFnQ-=<~*VEGG*8BVnWq_V5w|c=V)ehLXvEzPE zo44*CzNEFU<6U6EJFoL;CMhOR3~A|P^0ZxOqeL_=EZGpPaRu{PvIhaD9zeXd!~cPc z*lF&C8_z@PpK+>xb?yQ~c0fl4!dt}@Yc{PlE0=)O(>d1u zRy2^#J^xY@e!2CFr|2PQ4Qai3_51R`amUkiSXs$?yq(fd1LucQ}dFrKlSR7pCKE7Hs zfBsOM#~vQrVBjEkd$N2F`u0{;ZgIV`imV!j*r|;Zj(oF||9BHkN-i~42F6=@VcAjS6oV#H);~0z@%pArnEQseDApLg* zI|4c4r0YzjOp*d4_0(ZMNgw?i%q%fEzF5Fsh(5Z3VfX+zE^HvpNMxRpkBYQJv4T&p z(jTtyQ;dGa0b-<-Ok|i{Fbw%4ZY|R0b5L|9Xg`P9ys>JsMdR4z6svLRlYmencIm0I zi@{WSNI_asPIM|F10L=@O2wOemPqQJF#$~pMNtxRgTxZ%w^YS4!gDI@XRnX@S90RE0eZ_C<=9@=}a30^#PiVD9d-oyq=Mmgddfkdvx6ES2?t$M?Fg_ls<$ z*W?~JvFCy3o}=%KJQv=pwcSv0DCEL(*zwq5R$=RY7m(#7YEb206~hhb46!4cFqZcZ zF{v}i9Hbe9Nfbg*5QYY*Oa_WU1(b&6Ntw70t}GnY_WMm~59T`2-cc2F%wpnQzv{Z( zCERW?n`A~@{?)N}*i*?@ndv|wnGiUAd)ausAk2oFH1E zJK&uL_Kkp>JkTn3y1B3zuxGNQ{)FvEagvUs1P(yp3wnLe%A?i^r=Ivsk+I0DTy zK;Sl3++E;dUC8ut{5TZ_o#{01N&^ik)ud7dTY!Nix|pcJ0C2Nm$z&port5qDFZk1y z?%)iM zla^_s`uTOj$nUt@c-}F8_%<&$Z%04|o7X1-oLx!9OOH=?C9he;FgOT7A=uKO#Z-mv zQ)Dfj=*NFge+4Yp?e9wXb@Yh#Tw(hG6$S@M0wEXz0I6(yJ`yORs~&Fv?eS0SuZa#3 z$c1OG{p=CWvTLL&V>;S;W=^{NmbdC6hhFrGd8?I14 zHR!}IFq{7qk30Zkv3Bh!cgs80hT=LDJ^?CQRhR1rO8JYfFtKsu+0?4Kp8hfT}66vMA zxcM#QiLLOZG%G21Okk&GD_u;huHNDo7w_5*$T=PP+}+zs#@)@G=&*q=-g$}3%t4E= z<1wqX%es}fOC(wUWaGIW^12$Hf2Awy)IkMO4}%}q!*rQ@pu9I&@P}653WiK6MkroD zR!`(tlxTfcA-QSJ&*W~F&K6RBK9Qhrb;OiEz}*AUMQDm(C(ot}Ls}jP#me3?q=|(C zrY~`%q$((wp<>5F#}Kp&QXGTVtyZ=-W2%#Z`jB>E`}*CuE|7OHiObh6g!5;j<5D=J zd7N7LG)As^pmJ3ZUuMnN$?axZTpe5~z9_geI%+go5S2)t)K4ZDn#efiIAtYssZa=M zk0Ik=hm&O-aFZ2!7oF}dGME6SHbc`dmgu|GDD-O-+39wx2AzamUPSW+j)=!_kb)sp zlJ8E6o5ePyPMxk4rA9vU;BsHlCq}p^_WU|CVwtF7zo|$kpe26KrH5%DS!j;9BY?Po zb&~BN6p{NT-hL}*Rw09&m1wPf$&Wg>rT(}{p1J2dRJCcjJUno|XOQ~cPYgy7VnLG? zUNQ+My_u$bnWv72Nt+2O!IHWjzsc_`!4}?_HicMFbw)bYY9UzjVkuUwQGqt0481U} zOaT&{A!K$Z!1RM)=gs}M$J82>C3At{D02c#l}MFVLXCX@wrQ`RLmz4Hg_@=HcAfX* zSLh06WE)DON5#NZ-(`ugTpg;yJUy$CT+>8BK?zv4{ z)WGKShi5TCS5+sYMQ5)U_kEd;Durx4ErMOo!GUpp6TFoV+t-L|=?%|5^UmFe!z7@6 zbgnnZCI_m7y|)YCW?mV)(o1@2K^gi#FF@6(-6bv6fwgianUeEqse9&0LPf=`4J9Ho zDx{DIdq(DDYX=aIyXyzk3PaYb@tC+DpKQpW36S+YizkOOnEpWS7>e*~Xgx0i3n8+y_!DSpUsMu_VbUb{U_6mFv|_ctH8^1()X~>2u}kaPoU%?j z_bdw?E@i&k9N(o&QDsUsH$k*P6P)H3$4o`vL)_z4I{%M;v==@&e0G1(`-yB8-hb=$ zewhJnb7;LnVKwPC_gqPMv?Kz#=%)HM+ph1~-DS~S7_S>{ zVNJX|@-z8}c`xt1@{7uh=gklQ?!)vHgWQflZ$j;F-~kuK*---C_sA2z$P7nj+!v3{ zJD{rb`J|u8f4I8(t-GtgAWdsKjgGnn`#-9WA2bLM?$ow(dklM2EKx!~7AbWv28f7! z{5bGHaT8qMBft{AcbDaSZoJVCcWdvbd;7O;Rzk1L_%3rl4? zOJ3$2ow#t;V#YXY6toIi!-9frvF+@=`b^nLvcy+>17Q{fHUG5qDJDe$sJri-aE*@o z=xkx!yrtz)eO#E!bYUz|%C`3>3Gw0J>~$fKl7;&BTpsHd-VxMh;$3CX+eGX^U_g|c zpnVKNVuqG)1*iP)GNH78OJvdnicDlia(z&+CTG8=e#tRgGSv-@V2;O;EJxh28CBsN z5uno1yNk}tjjJN~?e^2Tn|!GZ%FEmmYMcJ++3m!z*=BRx1z(OZLyKL39Ew=dQsh5( z;(2nSblg!PijW7MHG+s5No_BwPGRHK26_>|wA?O?*g#PgiNmN^<~VcV+HvdQ&f@B%e~i?w@Ok+Mp3f<6Od1Nad)JF!gAKEy>yD`@(6!nZPVJ`4U~oYP3zT5m;F>K ze~fH+^>Mj@Q1c3Hb%{rt`7R>g6kreK!l#>ZlF6{8wbiI`?JC;)&7V3fG%tp@2GC~z z$D_q##7p>Xm{}41uOBx;>g1pQa1wyOuWr>c4MqbfH-J8EUrWA96=~Q^$vid}Z0w9N ztGztvVD)B;^l6b}^_QU9+qybG0qTSFWCY@3=i#z5Z2RNwV=HDnngArS^k{mmaQ;kU zyd?KE%8D9M!WhuWSa4rzI@;f-cpNkwt{6b3pTqRHn=XUCBE#xh-QAD6${--7ql^Lp zf^rYme=O7(a2W$dNUj(V+lKa-{d-Z23RXD~`e~PIk?k%U&Zkc{4#gB%!#2pJaQm8& z%5}SyJ-Uy)W#aZvi5x49xR>yL!GL5`!@+rbx>%_3AzNp3-J9?wldyDx`y zCdGT{rcs*NJ0!8E;jIqd-F4=t*Fv&mYQ1sgC}UeIr=hIXIg3gpbfL0>=!h}BkXT5g z5=KFcU1V)7{2n5Kh(Z#(r6yejnkW3wy^@{v#P{G>&h_wUh``NL5&HwxA_O zZN|fGwifBQW+}UiD}N%b&#Wkj0*?mojIP3E7rdevf%IK0r==%158d^^Dl~uLCBA&5 zzbOjwD;>D+KnuN5`-;QuArdnMt@4y!1aqUIP^Y1CIgFXry8wByKm{LU$WTd?!s_1r zNUJ)r@@_#zh)%evq|nb&h>QptNAanQ1P3%OBSwd&2v`a-bO~y_3I^;WHs$xg+$}d_ z28)iU1v-cK#pZV-^;B&M-+6xvYXMWSB$^L}yg8EOGWMz`mLUb&l7vcSVLpZ`qUjgS zN+goRu%$GZaUc4?1HdIbZQ=F&O0eGSK1MNM7P1c4CId5AE0eoIE~>@CKzdWgw?7w^ zhp0M+W<|hh{-Q%S*Z&ojB@In>I^++QC>0}iR(Bq@+zM)q#Ok+yFw`}_QnkAaRcoeD z%|;dAcUgp7WSo~je?Q-PE4_2?w_4S zBm;gqYy{vyFH;5Sz|O_ABf&NFSdv>o-k$UZRk@&nd;LiSRCC5Uh=M!*0Pxio|z@8O=~!8&G9u$138JP6&7k{XOoSs%_27o$8Ow*)ej>C?d!dmZY{FQ zyq>NZhXX`z@kE|V4!d^)7C6y_qCJ7?LdIS-q73YbC|z)uV{pnw~Wo87*k zNsRu`k2*1hGr<^Iaf? z;mep>WI09dIP+fu@xNkj-u)jRY4+`Xn6OO~Br>+ggvo{2>L@wb;QkiE92SEwi@&X0 zGL)6uwNUe`faM2cDkKxZFC_SDlvLK7NTEZ_J4|^oXeORh>LBR_8YLPx=B#c^e|64q zb(0qhCa2S@$zEK0sszox6Nc*p}t$$LlmP^)on(sH~0j0xb} zrjc+ARKPf0CeC4;YaHK~({aI_ydJI8*#|0ctqGP9FJ(6AZq}e~SLrxSq!kEw{5Jox z3_7vm`BFW?#@%z|H`LvAX2O}8v6PL~5atygGsC2I;N3Zt6%54B|^&^O4u2-J0M2c5-WF3qwDiE3gV4}pyV8Mf-gNsOT zVJ;C068rXs$!JB|P0Q7-pU0P$UN1ZwUH? z9az~sxvv{wwW`j1_|}auPdxG62%E2d2Ot z{5I&0Y`N*iIIr)7pbYi$3+Mlg+aDKEi*B+>Se7n4P3hmwlD;(VHuF7#--W2~5*qQk zXJ>XbX2A$>cI3&W+vfa@g-}TNW!waONlZ0>H$yNsy@)1%wggthJc1;Q6fkT695X=6 z)J&`0KF4Eeo@#CfHtZ~$&ziI!q=bLPwuvb!s2ND%eXX>PAXpcC?Izruew__aUyOd- z_nwpZ_;DfEMR0U^`nZ2(wD(0daI2Fbd=(^NEXZnG!n1iO0X!I(n(N z0=Ue}e6)p~q&;A{L)dR7xE^|Y8u_dLVVn8AbruM4v{Y4B|Ghm#TwY$TSU$~~IRD@M z3yQlD!P|7=^De#Df2aN=b9TNJ>gET5>o^rnJPiTzx^%%w-9t?Di=t0Vml`hh&VA*X zm3O9Ss}wHV4nNL^(-fAXIj&!4FmGWw_X!Djot)lF-SN3Tijb%O z3i9*)_7c*$b^J8=o7yeKD^`GSW4F?GSE3|PV)LqDc_RG42R2fZ4va5WJH#fiUnIxQSX0F^VQXK=XN@;+rEy_#_^+?v6 z=KN_O)J5x-RwozT!&(O)4fm`E?Wa-Raf~aPkr6yeL0oKm$5?Q=#eU!aX4WmFX znd1&~cqfbl>IITOu}*GIR*?$k1hd`~ezAzX!9|>6c2aCn;viv}1*!Ziwj%Z+zRgd3 z1W*Gd?@uvXcQHIA$1RMn4WxHCIT5x9qg-Tr?n>`j371m)VF^Fr&=Vnz9tK|0m_PN) z1eliqAp{YklX4;9GrN<+J&wM0>douIYgvQEzI5#5q)ME_O$5T!2a>}UJQ!U_iG3I0 zC#51;sFB;udWvb>2jQ_4vKua+Y0!c#GipK5k2o_)KNOf6SU)hgO1|WgmCM}=H`_;d z8&UB;s%&L=vP|-tYQMKy!u9l`hy=2;F9)0#2crG*yPTa+3>&Z0Kd07{&M5<~#KC8r ze@jta9yaa2opk2=1h%_}v@;(E_jUQ~ZYt;1R zC76>oIy*b3N$M2hpI-qfo;*A}vcHp;+Hxm&0ba4C$B=(8a+*gS5WWCd)xs9xDiQ7C zav}#c!j)pzZ_&WU5w*+O<<1E$d{)P|uR@nnzhI%_OW27(;F<~tq5zujf0${QsHmtG z2N2Ts`-KaD00V5D01Iq&bv1YSv~ku?|VDGInaTI|)f7d2n=M>RAMog$K`-$2N$NCxzXSq?F@dGe>T zsdN}5;GNEKva*{l|8gs1eIu&kt*mnf4M4tOdxXtvv}R9JQ56HeK_JA`WbX%xAFGptI0qcZ{eRD}UWd^M%>~N)EB$2J5?-4c zB<}Q3{Bl+U(5BgHbA<1)309n%o?1FL%qR%Lafh4Ewmg}IIb9@MKR0z@K#IJHu(S}} z-w_$FLdN?v%A(0@<4On@f3kM!Pg*=ZZS{{&q4DxRd20%^z*v7!-^ne@H&*IeeyePD zZlFm&dh@0r3aSt~iRP?cKjm?2jg@Ga-&3Ibj48l_+KRk5DNE^D_$RM@nVt#hlIz@L z^(%+#)GQ&Djdq z5YPYV`~9#2^V`XB%FP)hACLb5WNTV}7*yFW5~l+rukW=zCUAogErcECO-bI3N&Kse z(qN7vUOHHj@YI2lWOL-glyIrEDzu7!1IEZk$hqsV%}Pp3#m?<_wDwY>5hZhDgxT0* z62OTYH8zhM`EAM|Cds3ItLr;THCCiV%E%G^jA1EmPA5YnGH7GRg1P)Dkloxypqr^k zDeTd4<>QQ)SLE9o*c0^7FLr3|W;$D3_o}i{urCHzrDz{1d}g!{Nk=KkMZxTHyy}9p z+C0KV2}+4DlK*O{xTHU;u_Gu-m*AaM&A6@Jw#V#)RCO%8CH8sI@+_}iQUM{VO}&kx zXi&nGCk~VBy>f7vxb-zwmao+fLoydd*f)|!M&oDFL^N&G#m|)Ng%o2^6{@2-g=vd3 zm437ZS|L?f&vmL;k%ZA0b~~Ta8ES*gA&66HGpi7!;Fw8Gaa7vN*g?L9De&1Xw!BUV z>#)vn_FM{F z=w^7Q0W)ewM#ju(Ye#nOl-u8E&M>LC1XfLGo{B~lCs|!p4GT?%9tYJw`K+m>*^17?^)T`xYCn6SXm$oo1+qSxgkO?0t z-E>7Tmgs2r^&Q-9g9T2KMChNRQ!qc50ySf@%xAq}E5htNhFRL&+rsNMD;$SWtI3>7Wlp7I%d;z7L?S2#ylh{-a+ z!mcvMYam{s)uxwyhN|LX#--?0%p51V?OVmK7iUS7j(qm8Ej_U7VJkQHiz#lTsIrWf z1-YrnJf(qTOy}a6Ur~y=Dpmb-R(=ufg;p9Epb&uAKoSpWFj!DchmsTn$IZ__nkUbQ z#8p=!1)36DBhPt3=N)fD7H)&T_~|(qJ@&bB@i*OWYD#0UKVh@DSK%6B{v9WzXS4eM zB5JG`vEd}&+BO0m){DBgi@u|>5arxt&?eEJ#%XCcV3;1{Y3i!jw3xWcVbZG(C#XUUeW{a0@8OK;3<3NnG#s4HmaZlA$o(`r z$jNv_-6B0i=g}n{56cpgC2_!0jD14#m4;Rk1-_y#%1OOdQvUoCXNUhgrh(;rvFfmw zFiZeC3>m7|k07hO{s3t7>u!k)Pg;@I63#Xb@Z424KS%6VQ!^-GTq0kZoLu@}m)}6` z#yl%+pY0&Hnki?;>p5n&(CDGf;(eb)*Cam^O*?|`h5;IJA+M5AG5EO?%w+Dtxt+4p zgz-$hgE328L)Vwl!ANAw5@sB4Rwr}!buKUHIj9LR(%>mDxfG$1f~GnJwc=r4D5MMM zGrp-b%`{#0G)?Qn^Gj5zz{bI7Qzg{L&AU6u*-WQwG0rFp>3|eqCi3#KaLzVz)X+2~ zQnU<=BZ$AE8dcinga*X;t6@JPH9FzJm|M^U6eNU6ikDPKaJPxGwgut0mTa&PD3t{y z1}VX02Wz#sH8lAaKm^va21zatv=wAUrSf&i*ttQ5!!8t7i(pMMXikGM;HH;m_M_y* z*S{LJ;-eufTqSSq8qwy}*0L{C2Xr^@=x)Iv{xhy=4b)@u+_)~YV*T*lofBK2ynF2& zS{1;JTv=T;Gv$1J=kMQ%@#?-LlR=bry30hFDEa}=g2!FDZV9ZnyCz+Etw{$U8E)jH zpoCjO7{P@{kdEw26KmBTZX?mxDjU_7k{8w$3S@fz-G(nx64fMF%NjL|=M&y+G9=3o z@_Vd^?p>Un)igH`o0^Cw86&*-7a`TtlS#!<)@k0kQ5U9#=vK0Y59WoMGtec=yS8f7 z-Obtp9n_$`lx7m*N=4()6MnvRC+bb4byxLc<5O!>s>E4SSDl)OHj=@O(rmayKXjt&TSI2^0nCryZgu#()c-iTK5_|2uFFhUC3;U)4BrTNuMSxP~#~eLH z)ZU?M&d;sQO$yohpa(v{vriZ=Osa}E3x7V8SXV(k{$E|GfzHUx{0n!6VXUdJ%w~sw z+Xv6c`gr;HN^a*Drb4x*&en6~$bFFMvb6)K=l^Xe$jfWG@hu%OS;Yt&7IuDdsQ%x2 zB%RfygM<<~w2#GaIi0dZL-pmmPQ1%ZCK2YylAqA)kI!Fj@C=FLR%3E^3IsE6o@43$6G(_F z5qv!WK^R3Wf6mRr?{;5m!SXgu{e8nS6FNRuwW?iWO{YW23R4LQXShmd(E^#YT-a&Z z|6utyXCZnT;!Klb_{OCaTt4dR2mkVa?J)r=GIYr== ztvp%TBJw3TT2?h|T7wy3Lvrj>`WmKSQGNkyTHfFCWCCr?E|4Bw_615^db>rdQN!zxq9URG;lcL z`wROOoWDn9)p%ukousRj?ZFIT4aLaiMh6I#tmEy1yZ8+BqmNgO$mz)G@C)mfQQ42g ziJ;dusaJ5LL2WL{LuxR^B8>?u!b&hwmPUq|F>45Bx>Ng-zA;ciTtf^x+M4p0XQ%y> z#c005IX&VUl_eG>e}Yz}Mn^Mgkhl5#|NblrrY5kvxe9PoB1`rwi3*JrUJGD7A+Zcw zLLzP&T5Y6-dua0Ju_|?(tgA{*go1~+XCj|O2#rB-gUHL|Te#r2Z;_E5lNR~@4Iy?q z`jmRI&=wCDJ*rC+CvuKWQP=R#wibO&Lk$rx2wuWs@w`oD~9DHBuPuF8U`qD4iow%rR9UQTEWEi&c|R3-xk;^ zz6*!8Ruiiq>dnLqK1yZaHr2ZALl+m;5W8Pzm_^UI+x``d-lrL-LL);0Ss3k)7dM@k zp3#q6?$Llr#@s3-!SaSd*rXF}C9C2VLg%Y0W{#>+y<>WY_pE4s%#5Wpgczr z$F}CczV?7SL=eM@h6>l`R9n#M7Kb)imB^D9g+QKtt{f)oM^2Rny^<7`P#OC8;@G`r zwK3=N*#CI}qUnelw+K!IENvg84wN!IeNU~^9ZM4l{Dr3guKUaVsZP6dq*wR0XkXE< zYM?s*r8`Pu3QjZ*oyiMLLHui@UXB5Dl)&qWik7E_8?I1DqWG8R<=#mM4Gn#EdFgPv z^c`@mQzzt8n>&UMvNuean3!yIx<_}vl-t-kJ1>d8nOjYr{@vNSg`4P%qig-2=kLiJ zE~xTpFqLDGtaN6Gvlt!|RG~l~x{mQDvT&(!yRrS48L4WE=zGg$XfL&eoj!K5Ce&zHkS)bubV-tGQx+4rlDDP(Y-4uU*X8kBv$$DQy z_{eZY3f(G09u)X8Qt-D1mTUQbLF+Yskw$?pZrpcwXn3(GEj7st<|qlsvxieV#?BQlQc zR1`%kdSl((-H@FrBn~8Gob0Tds}GSmYP+^72sO(~|8(llVHx55Ogs@x9L$4sxV5U` zEm-_c>d8Mu9Dn+;WB5-*Eh0@z6qk)~vJbT_Kgubs*XOrKQb$E z)^JFb2Iw1OB!<)|!r39mMoI>`7p#V;Zu*ro;L(!z#fimX%NEF#$b>y(dwN8#zS@vY zMWKvy)#=2kLDiN@G7l7qufRzK_T^aGp6uBBf6-qmX`eo|UEepbB6SG7kBysBq%aiX zwiUE)iszC(5Y^95)8hWuJS4V{i@b^J`?*Qra0Wv_Jb^3GO26DhWEuHT(|cr($y~h(18Bgu3ezzu1OkFL)kZm(C-rl zPG>jb2THw_q7_$hPS%Q0*r3`C(Ab~?>3;2)?CB7*2JQcmvj%D8*7CcpY9;5dI=Tgw z2PYl2ynp6hlc$vj+Fo`qq^V}0jY2AmWo%_L^Wgm$VF`LCTvf=qLC3*MSST6EqbY67 zog4CX&>*DNuxd?(D@ zv9B7hScl%d2HQNGyU%)lR8718YE@v2Km6~r>J-=Xm~Qi{s*b3c#@-9pfR&CX`soC+ zdf#ghOc}4k-AL%P)e1n3dVE0$VgQ}$GZ9ZaK+`*umWB0+nI3B?FJk;V5v75e*&pKL z<0~wqg~spUjd!RE4PewZ zMeuiOYm2bIH>THi25c1gJ9|+A9tBZoud4d9DE^Q?d@wFP-sobpeHgg7r)7*75MC^y z&Mb^#q_|V4+yBpVlTfI;3nlt7O%pR0a_koGYFs1Dqt0wy+Qx5J_J)^VN9IX&>t zV+M-BLeeGyDq@Yn^cxAOx}_Z+|;F=!{!O~yZMq? zHpJr1SB2TP9dLh#BlU81KZgN!kPhUZtoGNWIw#{FyN`Axg;rW-@G%#|=}l?Ijee3$ z6VMxNPT{OF;KN!d7wCD5r&9E@n64DxgHlLKdmi)#JOyHXG_vv>Yq*p z8yZReT5u6Snwv|~GMLraWj$yG*~A{Uy6`&+GW4axBqT&JobCqqTiJfNe&1bRb(IKyMPHIAneqE8(4sRpB})<1h53^6 ziOyg+9R@>(t|jX8B~>tilen3~CzD`hn`(30q=m=uQ9rw3nN0bMV&cRwRmBk1Ksi?{ znrKt7u(FnhS&d>)sl|y>J@zzq0^6w2KtM`rO_mytAuOM-%EW)=2_s8f4Vg11<3M6CSvtynVKe`W;%ZZ_hG{}tDPe?3XLFV zK`T*-z1-jD;gS;Y9hjxHSdXD;H`UoFVkKMqK)C^H{&YI50Ygcdd|phhtZfHcLm1>* z11O~-Q{8;^pv8q6T#Xmc&~pl;2+A*-WXu}oI@U{R_slb?0_h>N&?oJ@ji?OH-2E%~ zB2!}*b^6JHE5^M)fB}T`85r>(4)Zs(3p9u11oyjEk!k)MlW9pyp`X5IqVz742=j|Z zy87CdNzU5Mm)0K++T4~_iYz46FGs;?H#}_fJn(V9BJhVqU*mpb=esf2*+@ELIO!M(PqIoxe!jQWSI&W72S)fO6Ps)mS3u~mkaV^bIzrpGx;HCfY>Vgwd7(NFaw#=a;?bF8Uq_Dp~i$ zrr~l}un4HRh?X^#ZS1MK7Uh$PNr>Bjho4{AgQ7ua_nc@qUTsx$HA5&8sMFhRVoAm+ zD5a3Hgu>7#ZLJ1w>;@j}fB3UGq8^c{a9v(s_VN^sdCu1&YtFpH6-BF;ElfE?7zQ&l zGb#P(Wd!;g3blNnt(((>>3|GZhOqcT(7)8`*IcyoZAB#FNFq8Pdb~ zOZcC!C?>w^_HcuBMBVT|81Y%zPX&22>*Bt7b<1}zQ;qAA(+k$p;(~D;Wwcd==7rSJ zYtm!NTCZJcqC<%(DxuR&O#v~Gl!!C9!_0u1vAL;RrPn>Rb1#BaMNq@DCMIT;we?4& zF#4*pEDSKYzP~-g}iQ?9A`MX z^=!G*CicfySplM}P>?|HegEm58=p15LwvQzLH5nWWV&hP-^Was=jHC(>SzD$PtU`8 z&H8#(%fCy{An%nSFD&A}3-xUmR^!I-mlAwG252=;!Bngeu)_iBYk|BRHan{yyH%II5`s2cViiWK~Q%d`_LL1}bGf+4K zNtexiNrcbsFfJ&di&=0HfnC+8!f}i)q5DqusW!Bp+ly4pzNeLv#HKCwjP!-7=n^t#^5R;qz4F`{mIaILNsj zpS3SH6|1W4KU6C*F^1Fb54`73UV;00fnLUsn`GC$$Z2N6Z04-#rx!gh0xQJW#mT5s z=P1idx~v>-e(BW!1;iX*6Knh%#*g67Ecvb*7AZ6yP?n1pEluqbG3sxrG4;=*^0%q( z7xj+k!*rmnKPvY8Y+kC-qE{5oC0*ewjdr!k9)M^){vh1~g*fS06G+#jE6Y+=U3gn!QjX%aIyP#w|aY0~NkrvG1UKnd- zh@tEsBb6+)Qb^yg(vL>E5pQnUXNTFC4BmB#8ioioNsv}9C96U|evh(Y>KF}y%RFd= zdcxI;kpCI@8FH48@F+ECWq&bKKYVwN+DhchB_u#`Nr|vBDy`8k6LY-Aw+~ixBQ8S8wj(i}M>Qy;p9V zEq*`hVNouvf{KV7R=Dp8&7FzvpC|+-Y-q{h+_hwcoCGas`>%rUP zsDhgp8S^KO>uc_Yo!K^rESFzevCIUp8cld6gd7h$BKfbFZ;P4{zV%hQkoMM3^AFp6 zKG@vuhBI;#E4NB2m1ZdGN(BzqXfZsWsDFlRzi)0I;B7yB9rBColaS`0l+v~Iu#U=> z)n}d1?)n~iJs)a{|7M5pus4J#p06lU%!`e1d~aVz|40vU&KJq7Vm#=vL&{e?4C!er0N9&A z=!Km8FhB(brr3bsg8I6o(O^P1R-e(4%n|zuTu4AKji+Z9=X0m`lJgCJv4-t`Ydq_0 zQBhI-oTB_$^o`Qw+Y}{$5v<45S#p8^TmL>}lw9;0_UHNkA4!#t|1~MDWia5=sM2en zx}6r7-q|5x?0#dZ?zn*iQoqT^?VX*2JU(u-O*pah8V?VWe~}VLct1gVkF4Gy1dc0; z*TcLC^)we>N6CM=3!Fx-v0Z5?(1etcC`HE)(VZ!xDeMu$bh19c{_JSPp3q-^Ce*5_ z(A9nk)E?#|H}y53Smj#*6)yies26zP%A*%cW>b1%|JE1y+yBQv;6I!0PfxdgUpilA zd57cofSZ!yUmH`KFQ#ib;MrN|Gn;TCC~J#;(HeEKrA>)!Gu^vbXG@N~|DwoD*Kgb4 z6TgQi3_F|7EJ-Mf7|a@TOtm-;H|io!SZpb>UapCowZ7RWIYAqWyshNUYCD8$3c{%r zXt-<4M-Z6w7kmWQj{>ad986 zZ$Go=S9>FdUpwYC&8v8c2>nR$lXKmOU9_9xRb7RwIZN7$c7Hdn^F#gsC1=au)n zd)cvH5T|QB?ULY7bh>M$0XV9u3Y22j&2Bm4?F-N}%8)fY>`6naUiRq3!e_l+Y{w$L zV$(253zE}}!y$-D*Lt7(EE@J2b`ejrG>5M!n+`O#)Nd{-YR3yB}R=mf|@#ykASDwAE?)B!-!G2;;AxMEU1Q!u9`a{ZW=Lb)F z#mB|>kKJ_d{`5-w?k`~ibFD)6F>c{b)jMWU%| z?;4Q{m=yR>mZtK>^>0IYg5gr-!UQoE=^HKI@0p3ANR@!Qwlvu;y}AAF*nk))Ohex& zJShruMQm@$;@J)Y&t8P;BD?)-ETn{!ZC^cX8OpLlOWx@k|Gbx5m{D#GdvA>42tgnV^umKrVM}iY-b9O# zP_*zJjcB&cgk(z06+g~pERc=5l|LP^A$PP&(+5|8*zn=pnZ>(!v-Y+HmCz&hokP`l zS-b!yN!nF_u9teOP<)e-W_#Yl;LgnJFfw~Lb)S2be)nVFs>|h4dto#|wdvo{5x)y1 za_PK#!7CTfbi_($Q?w*0Mh71OU8X|#C@0yK2iGUhdfqR-3Q^zTAluv9 zJznnRZ(mNcNu`wX?9K#6WbHpI{SIg zr>fq+yK8sVef3(`f+=rq+be^wFW3BBPC11i@14l|(jvp;@mrZ5cxO)k)->{^_*Hr2 z92?YSWuJJX6T>;#AF?ASJqbryd~tH={h|jba45kb_kYE;&Ftdhs1uT}q5Nqi?sbi6 zT~!@!4*foY=DfL0+O=69UDZXvQrnk_s-mY(cJPS9{=J~8nvc8DH9LuOSGp?%UYZ<{lqh5W*h4~0*N)USMZ1Uxzt6sqQpr7H!dtUnGYbQ~; zfk0==y;4L6;=`#U`VXqBYrpzg3-`Z1E0f-b0+QiGBf5t2FxiRw+@jWUYHIZ9(UiDt z)Nojt0NqC2R@HG+EzZB=B)D8L&%%%R|1yA_`K;i(&7a){0AS~X(5WK)TvYx5ID~)_ zR3K@NPe1@nGTU;FPEu=h$`=3dVq)fUT_an5IFWeQ`+p&d+y!L*=pD49sJjd`;uF@>Y2$n+F1VF}YA=YX<2KnWzV-!dI-mMgc6I3IkSgBdAwpjZ>A z#|zpwgYq_PQ#9?Bz|Ax}o3|tc-JEEVtbYt+S{*n^g-cD9)kB-N`wMs9>_F9aHMcq{ zu_@v5ji#|^(yVh{USuJl3r_Fz_5?qKb23Wl{{O}TAbpdDiD>B%)>1L24nak@Uye@!VJ+xIEJHbJd`GcJZV8- zr#;*`1==eg30c_O0qWAJ@oA0UZ@!{U&KyOiFtz~9B&$m|Jrblehwuklyh<|S`-T1n z1yPx14qNAC#UPVO@Zv|1q>xP3SjQutjrWfY9^33=|G!)tajyBaHr11}@s;-)T#q}k z>}N9=@x=&?X!Yc>ddcOm-Ya#tuSDN0e)oVEbDvkCPu7x4w*6p2gEvV7N>_Nb~lO-#u9;h-YgL>VP@(}S0}Rw#?RkFeVn3TwO1({o$r z8JV*wEF>RCkkT9ImY53hkVF8{_;h_V00~FEl2BXM8fy)^Y^<3GhQO{qEHJ()>4m$>-~v zOMqAM;RR=RB}qK`kx!UD1I@89X8TUDAfMZA5+lk2D|&*CoC)H8Eqj&>nwKYlwz~Dd zD3?MIa(`{X_c;OHH)^oZedSRl`AHATN&F-e#$xm$+A(w3mMjY*9qU$D=YXr>ISFkH`Y`7c9u52vmcb8ZrKmmfu}ZT zs5_65ms||09Ua9PvLe<$Q-Nz}Y;CKNB6Y%N5vpe7q-1Dt6!fAgbur3@MLg=YD6EBb z>Qm`#F<_a&F$Zab!osy%P{feBJ6pz7WbhbfTk8)Q-sC_lQv3P zcrS|uui>-9jJIuq4tK053=|939z@C>C)C_GTWxba8(`L8wQc(}|3N$~Wey59XzPwg zAw9LN6i6*ZYmzDybC?tyy0xC$Wo7p4yNK!5u_YIxOMHHFH18xA4Wx7qaVhyM8`K|> zpIrDChjO`d=g)W!?6b}_t%wA-i|LQ^&V{W<`IkjGIiGZDgNAeF?(XsDEA@^J4*g$W zg2nR|3{`ZBMpm_WAnw49N?@RH{OD%4dpxiUN^b?2AQZzX<~RgQf?wNmMW2j|{ne~p zi_6?zXJuaujVRUp^y+X3-FaJ#Fg)7*Z0fta@b%l0RPzrnigiV-ovMW`e0+GZFGuAT-}Xifs# z6M1tvJ)45RkkBVcgzR4a`Yi%DyE^k1VXMaD^UQhPq2GPZRPv47-B(yZAKnqSoL8qB zwRr;6t*4C|cQ4y_j$d9n#yjzjf7cefS@39k5d|L^*jh-Xbg`ArEsPcMAn z=>!&{-G1lT{_9xo>s9ER0s1h`ZMHtM23#)$4Y-=_KLIv!>3=_z^Y9294a|cBG*59I z@u1cqNAvSs2o%p1E(>T~&Q0D=JlD*!+yL;z!p!?tL_mM4aYHjP+|2Hk>+j#jpG@bi z)ctNCp#jF8k{$=g4=0)+#*GVxHnDZ-f4u@ZA!qhh*E0LoX#Ql$x2dMp{%jYh40NoC zm$MqwBQ&^J_ig``jp}soankGz-tBoe0;_Y2cAbN+molOa-9Q`2k~VG>CY(S4+o()! zf5B%(3#ec&s4ZS`Yx#RJ+S7_@i|CkjGf^%mo^-PP8&Q;|1RV&*ojObEXuUk^*IuPT z{2V)5MDAxhVNksLHT+r*r4no;cU_mDR?U2WG~vpKB6?t|A$@wN z!B_`DF5?}E)s^-N2JrLYuWP7k6i{D)KZ=Nv$zlgeT55CGOHDC8xRa{!zqJ6~JX&XN z*?iEsr0Og{CO0#l8W;%q+h3Sz5(Or05ohOp#+@4L7jntuakJ%LyS~oH?S|e1n{$4= zmClMMY#j}BZMMwW%BUdjab4B;TVMTyij>8Sy{`mv4GXIphk_6*UQfO%CPy+o&CN#+ zSH3G==B3wef#nPzpHWS`pWAgs1adwnj7C3yxT^+-KI+&RUV^yyW!;7R6v_;gSc+=k3fYDy>=L~ff)zU2f zYN9kT)C}?wF&Z%*6W^h2*Q9yD(|-Xb&$y@mvZ4p&oM}@@ZD)$)3nr+U|EVfTCW)a- z8FPExU>;xD_T5~_`RzT<-m2t#Egf~WqQJJVO)SiOuYW%`8+hcto}x-dv-saWwNuCK zh+iUP#?I<)>#Cr}+mmTHr!0wy{=oYgM8U$iQr;5BCn60h<|lt|dnRIYenQiI%M{Q7 zbs(&3iJB-pJfTEu4(phg@PHptjfR!Dp-WX`%}~!&d-L3A_Sva(`Y*ITz0S8)P?>&) zq_m`D=i0cokouR6WrOQ`?~hZ9k=lOTNEEmhaH-nBqAIOgO!{<=>e8}|dhCm`p-%DA zAZ|HrJGuBM!qk5%^TsrFjfYUb?201iNekQ3VpLe;#xH-8mWjEE z4u!-RD|^d~YE2G)`mUa;%XArfhp>9NrfgoT& zi6r^O`t?>17;y9h@7I@{fLYd|q*Y-$>`gB$*>7er@?(Tb%NdeNx$1`S8yMq>tP zcFA$DZf->#OBXrz)lVJ-6>i-#cA1?!&btBO#JKjPRjZhc_z~9?1eK>l1{ZrL45yT# zpo=Bfr5jDkC;V!Gxh{LEum`WaWOH{rkPAFtscUWrj5@3?xCZ6VwpxtQJE39>Hf3D2 zRO$}LP2RC}h|0HiygX;FEJ9F%)+ICSHXRPO)8E%PaY)+c3xs3_`RC3y+?M8hQ-&}qD9kQ`%@{xne$(m|9{wEyy z|5x+hEbG`eYSL$!=M=A8uP$Hy>Uwqk;c^`(U|rw8`M-o!uc*n$@O?eHoU!H6Sc=VS zIsa+fgx;HljQzg@=1(L~5G&(s%Sng#Vt@MW0jclYZg&rd2M~B_64V78whftPL?=%# zr+MF>FP1BRY}!Bk^f?DQCQHsEVB`FI{+RVb1SRmQXr5Qz-XI~E%W@c+LaV|&!~RtO zqTIQH7Mz{U#aa#+9b?D^O<_&615#nd1b(mO{z2nD6TKVlnK7f-D)0Z4 zHd-VPKH&01zxCQzmPW**FZBQ;8h-ae2gmpA!qO)h8jNVJt=f$lvy~G`z+Iw{d#8NY zHC-u?sOb8jT&&y>;9Vz?QQq58L{8{9>2ExO21(11Cg zX{;${uOL23wfPtS!)#R*H$lEfc%o5D_b;?j#vrVQ5r*AXPM~rcGaAPdmj(Oj^nDmL z03B6%m>!dE1{ee0Orw?8%(ZU1N<@qRq>l8y(!WprkH7AGTUf;4V&dU2L|Zklv{PP= z4<>ctHMuq=vp$?Y;wzA8hS;2kI`-+_77R7rWx>K@kw@mh9|`s@>RLDd6WmnOvii zE43S?!uO7bM2cNU8^U{>V*R*k%VmCOFVuzdh3!lS;wPp<>&f{o7o7Z?{<_borT@{* z7vp8IgU6`!6%cv7kFZ~B{*MNW(dY)BXBspUXk-vj-I%d>q*91TyV~{jlao(}_KSXY z_Rn&T94ieF9+In}I_;b;U(-6Xcclhjk}*#b^jPp=pP>0(mmK=uM{4@M|NS1-1aHT& z)&Ok^YAZgUOy5b}*E?k7qDYXsv_% z;EC&6f{5}l&?Oj5@Z zDIy6~OO@8pUs&=v%OJvZtPY^Q(Y|xmt(RuN0zdaZm1FWBiYZk4=*@*8t$C)u*O?=I;eE?W0 z?LI%nW$BQXOp0WMDv8l^ulh*vW7lhosCR>+x33u|@kNH9JzLX`xDv5#WC?NW4>Zb>sl-AG zTl^L$N$8f{-y6@tO`8(2+tdR8xD9K$P-5)q$PgmcO56gnET*RJ*o2;&dwkB-h#?ua zpl~rnT7p#*K()Y<7eSA=>gNr%O9UCXJ>AEHpUY$^A-(WXr^7NlMYXigD*G{$Oj46p zb8A?5;%{vRl{Lhq;oxeVl&TX$Ay5`# zL;X@v;D@!eez#C22f+o3>{GdhU{KRV1d3VjFHIZ`3kVMK_r!a85XmbT@`QJZW#Ini zAl>Y5dxC6JS+dR=b#s}=6gcv)biMrNR*hTDv0jEv)Bm^N*WAog)r^X9Bk(^`Ot8(3jIF~|}v1(4PhN0r7;E&;|gr*Q%#m8O80*SzBo&}NZTQi0U} zqX<0I#d;hBYKgE0R><{;6Cqrxr-7!3`WJ2fcMCNf<|IY*Yfk6v;wg3J7IyPs?ayGO zs`K?Nz%q3u4Ew&aR0&$_#-6Tk2=AKB`be8iuLM@@4_*cb$6dL}8&%pt?O^4^9rC?@ zrw7~;G|=n+ZREOsvx(!6l3U6ER;)SyrkJkH<#p#AFF$*3F-Jk>;$iU(+9BaHE4phyVUX?7a8-{{gysnfh*EB?8Sl zt;OAaM1ZmygO6dR+i82hWTEeSA!h?=k&={h?6nXq!Hn*&;K*T51DBJ|_z*;W)mgF4)D@iF;z*FFfJ@fYV-_Y<71 zxNe5}E+ui%{a_TEgML@Hw_(?plF5oo#>ac}+W7|8Xnd5hnWXC`?_8!%XQE@WPhU=c1{$BguKi^+W-xSYwfcSxch<;vLu~J^wo>ptO^lv@VKa%I9C(e!! z>)I=ueZJxE$b=2R^VN=jU3oAAkov)m)D|)3aZ>{6+s%-mZF6DDq ziuFqMeaQ8)Kl{O6w*24?RI2Pjx`q90q7V0zb#n$5d?IO~)1|2me1;=aSHV>?M7qp$ zHAL9+S^aw~a=!4njSZ-B%a*m{f2IfAodZT@{Z3CZnNC#Ix!AiwSF6vnWV*+SxuZUO z>81Cn&j|JzfIp0lxX~-&eC*k56m9 zSK>DQVomN+tn1|{EOac)!QmFy4k)(kUv>^)>MTT!TguPvdOW9m6KsHrc z@bQDV0sz0E>9&6Rdh+~wx6S0};x=))aee!F{Yl`Mr&12vnk0snVh-o%$W{dDoUPp= z_t|n|z(u=atKj%|3@N5{!3YC|XID&&*hnNryrehAXO&FeSd6rBg0~H2O*m+}y!hI7 zZv$$mH7zV|Iqa#sXOZhE!Pb^A+E|um5{*R9AXT|2B4N<5g)*RxQ>@J`AIIrbJG24Q z)+)^$zJ-ywOd^6rnwR{tRI{473`)&d?61T+no83z8aJA?Qk0+SU*#sqKckv3qIeQ> zi!zd<-o>6E#?ehR#L&gsh|NSyex=v9p0n#U{|mlcUK-6~DQV1Ju8|WOZSm)@B^mT+ zCC0yCk`1CZx=uFCT;@Q& z5-{Om=u9h*?JW(W>|S4RI^oR7}7Q1){GQ6>V)cU!3nkHBDd<%g<^Krq{9mXEf%4bWOH=PxcA@9 z&v^<-dMBAD*E!B|T~+iOP__Yf0nCVt#2`T-Feo76QKU3c=)?0dMpUBt>W%lK7X}5Z zs|tKktC5jg355i)QVftuMUZ<^V8kL#^KCZjUFS1v$fKLtK#o#DS-F>BNh{U!KI>ri zy=V3wGc*-3LMOpR>-6d61{{lLUhnYEr2pvqnuw%YSi(b53rzIf!4!~%G@vlucB`+6 zJ&F`&8DfdxGCjXG<#*7|ff%eu=5bS%c2y&!QiT*|)2dC+RPS)L$+Nt?eEMv=J&c>s zV5!tZZ*K0LJ&-qT`46Xqkotx=$9(_oBaRRxQ8}rM1|A-so`GTh(k*g7!pJDFXTY%E zg1wAd#^)!y^O289xMp$VbQ99R6`lPZVj2ii?(g~KKc(yM}}Df@gZrWqhvfGpjM@W^Uyq&eiGc7Yx45i`wvMr z9$rkYcFHnu36L)fvE+31%*qw3W}&XU=$dB@BH=QdDZ<47VmeXR01@wH=&Z4CrEU~8V!Cv@67%|78+^?d@}d} zwJpW2kco%8)4Lmwf&dk7wuU|YEYE(f9rjKG0RnVa|W+Ns`tz%^gD_p-{n4X`J*5QV*B!+i%C9g~lZF-e8Enhem0t zli-mzC$GK*cZY$?Q{K(yq)C{$xWG$Jw$!>D=OMkND-*@U5;R3sisVy>5lw}nfjU3E zFSRAmRLUn`s)Jv{Hdw5}2%k&CxKdjR5zydDq!*A7imW?RwbI_76%3j-uIJCrXPgVv zb0t5LGdct{*l-81+JagZDQ$;QXf}4?-4jwch-pczsA^g?%=;;w{%bbBkD0JI$%vr2 z V9poROi?Q4V7$CcgxL7crS5*iF&C>RPIU&LLuqC+hA;9mX9v2zL+{8yPfdR!Y{m*>c) z4I9k!>c1PX?Cj`~7jEaE&hD)54o|=OfB+P7)*~vRR~rBCXaCuEqE8SiEW1kg)O+wa zFe8thUaXFn!0^}CdjIj3Da{K;MGSRHT^Q6Z{THiM^I0hCkK!}xA^JZJy zG6ePqjrWK2H}r!I+qw#Fx8MxE?MKVbq`Oi7uks6|XAhtz-SaY4gC>ebLc2WNB{=w6 zUyuU?f4it9U;>*}&q!9R95D9IxcO&G!5{>-&*+wcx`D3IxiX40eWljPW;0Ah(SzK` z&4oGk`DvD)a4I(x24WpaZK3V&t;N)Nx&f7eUn-N}Gp^OAy8NcE5MFW+|EcmAW~bsI zwM+=4bLbFtwsQwN#uys4B5yhFHH+^n)u!Kuqu^7aBv0oYMdd~B#BnWtTaDB5^$@?$ zo}J%I?hpQWl2TH&EOK>pPj$ZY(8(q0>==(9BRFI}Jl%P8FacetP-K_uMNJi$q?i@z zVw-W1IxM7UVwPfmo02B912IcYciy~)Vt*6%JSNQ)5iYi5oHq@|V;0$2a1rpuo>$i) zV*gAtjZ3sXB33g255A)xwLp}Y=ZVn(U2VOOxS2u=Hs-_lS0yGRyNlPBC|*~ z(kVyjH#tXup{Uk0$Zem(?xfsQ>b9S!%#H>vLMpQxLqx;EB21NRgR5n>Pjyjs_t*rJ zA%qknDY%MeB@{&sJ{WA~wwZm?z`j>F-4YTPqbV79$p60C7#lL`56EAI9P!%#w^V;sjaon4%x6z(4PG4|* zGSZTlp-u$|5LyG)wjkWn0d5Cc+m){c>?E*po~7i8O(KvmA^^bH-5slC7BA0~Dexqg zT2xQahN6xdJW{}KZs!8JFs*@yc+3cyn>(~@IVYD-9@dKhG0Gh$t}(tfj&?039UUFM zkYCQx(GhX$sq>MYot-wwh`^tz<$VF;BSMpKy_5FNwyw-20*e&^VyLxkxYIX|S(h|#Px5*&&JT+?FDB@E;Reb0j zu@X{kOBws$frHZQ>89hh?c2Ehbh8hTKkW-g9oS90y|d>n4*O~4)Kbtre{WbRg?w~t z<*D!rPX?sA+68EW5k;J+GK-d%;w-ufr)Kz0ALYg{8#*_YC9UwnFEo*Onu z=AEcBkWEotb^Sf?IXqheFVtQ!>;u#hNDd<~pATpwcX2w0OD3kuJQ3R_t@_P5vp(t@ zb(|~+zc%9j9+mxGoRTJ-nA(blt`pGdrH1>ToYnxKSAtkgKaFCs60%L;+&BNBr5fJ5 zw@Y4BI5=A)dv@v6MN?Pz@Nhi2rlzK$rDbS;pR`t;j`=olj!Tj(J>H$&%zHHM9uE%> z!3{cw>VUYM-&x_eoUgNYvD@E|511)|CNjSNE`RW+Zs@}qK(U@!+ZK$~o#_3C^XzS` z{~Oeaz0ho<@#yB@RFDB%oFd7oOE>>b|0nkW^rA~{Vr_BHZnO)6ue@Vbso(az7ZuW8zjP?!n&3p8^^M7}AiYTQ~(?pU%Dsw|M|I`P!z}7uJG#%e|h_~jdbDZ49>7t8%C(rmohlVtsd5-mrF9w7kAB=&=JqFZ$%Nhmq$wJ5k&8O|{*K_&D-=9CXH#9<8EG??tll2yPsE{9TG(E}y$U6nXG~ z*~QVo%ErvCUZ=F|d)}{iUY_gEJ#RR$wRuL$YGLerZc$6KC9(P>cOHNd+xJ@%!+DW7 z9GozNi$3`$bo}dk?GB3}j+!WOW422Uo29yJEY9dO-d5OS(F(p-&AMwHGw`!QqfaB8aF!G+l}8rmXFui~SU;cSxXYT| zDc_%wGZwQxH~sN{Zsr$%zt4ijB1-KJ20!1f{vbL&YpuSxyhu1lD-r8FUp}aZ5jFu~ zSoMcxC_o3J5TT2d%JK0W^`Gat$s}<4zypiCyMA-L6i{E*)wFU}wqE9B{r5!E^-C3= z?vT`+Rz(puwDGPc6@;u5vW`WwatTaJPH73B6RaSXIG)p1i3 z3;D-ko!*RUErJ+YDs7RQ*n)fnALbMV+L#n6X{34wup&EkHZr<##S(5F9ww<@5XM$s zbS+rc&2tST*v_gfFN`HcEtFM#OGF%137-TdMf?*ER7BLpIN-Kf-I=IF&&$Vw5>{NDYUM!}3$xC>XPT z5e;w1rWhM78a5IqIZIjq3~vK0rhC+ER~GS5JE3kZ9f_{vSoeVA7wvEA(n56N*rtOb zb#xqEU)x{`S7_u-=fEG;^Enkk2(D2YiK8Db+a6u?byH)C32_B&8+T>+68gF;$PT~>j;-!VM$ zC|CD!hMVoJo~A29M6%)_Xw~5`DNWez5NO}`K+D@arAsDTE6K<{lJd_;l!veYI$O0H z54}4(qn802nV3kFL!tmRF7})%FB?)FhyQ0Bil*c0Ef_OtkOycLrwOFRK%}#|=S3m% zon-zCJMyM4(TV)l;F%Q>f*3sf$8i3)xk>vUA>T{?g7BYRmeKOKYh}qKyVqz zn1N#o8CNN|!@J!DdDFJnkS4Q4FTgHZ#VoX>GiK(H)eF71@;3N1mHD}(i!-eaF8t#- zmp`tz9-K2^#G*vCWurF1z|qk$acM~nIMtM7fXF4dr~DHs@V2$Nd2(a~5h_^V=?Til z)|MNjkbKfgdb8{-6@?RfquHf;0*b43!!|wIJy*UwI3%wlpue)v%-N1-Xfi zyu@;_kuCHKrL-veD9KHKu!-^n@y~OSRtI0((iFO4>7T|{yx)+lAl>S31rmWNVP-O;~8Jq+TBQ<6;!MQZTJq$mLI#cIzD><@h%r(z78XB z`Sg8Nz&m)na0H=b);Qp9J5b(3k1Y|F`PQ55dg`Ocvrq<4gCi-zDOe7!`nu+BL%8RT ziaah!I-r)IrK{YuYybJ4s=Q#QQ~7r4f@^Yll0RO5(o#n~2{)D-!YYq5FtKW`g?X4P zaK9`=9giIw7VB1DIT6)Fix<#}bmXasw98wY1@jEd65Fzi_w!FIEu~1m_F<8tEw_Y2 z2{0vr0EX}3#)7>A@nQP^WP!y<6ca!5&kp%E6JKpKk}*Gz#a;Y&eJ$x2TdFp*Z24o# zdtGC>z8_qgPlKd#O6?gJBi4W3apZX(;|M-hDm3==$mWo%hsitaw!O~qT^|+`eNxZz z-^)hKutQ&@S_|FT8#jC0m=1#idY4qzYSYq@n|2Fa`QN}VlHuu#sSh8(OHk!G>k>C= z8i`o6ja%AY*TD=;E6J9HOh5^XMJ$lj)@C^rRkLc?O*}=^(JdCoqPgNX*!{Rhz;Zh4 zDqL{z1+FRi+=c$#AJ>HWZQ74?xuht9;-lSLtA+!x!_grPr=-PcP02`--Lj*JJR%hQ zkJ)^l6u!rT;8L9nerfVAAKic7DoFD&lpUZ7y)3um*xTwrN2SOQE=*{zBxLDLg}+hD zNF1=N)a@9WGZ!oxG;~5Bi}HO~FBUIBm~2;a)LSCG_!0&`2yLIZvoU4)KjO9y0=l+x z{gGnp@w?Z+OQLUvg|%=dCKN5_B$TZbNkzp6C$zH4UOE6g@b@r2Gx0 z*V4$7UYaCkDM}xTC|2Q;FxYY+|7j!F`Lq@#Ft$B~{m;J1Y+@?^H(>y1P_QH%PEKnm z(B)L5>&ImFF7*tT`B5L7VEjbGL6|7z~(phy1>;;6dErF@~7!Gg@4k50@ktH_SCBMUB21B``BaS z_5S0FN^mBcsdr4lz$5b1LYDlj4HN%-ux&+{($$|US^_>C!@GUT5vn$7DpginaImf|ls`dwnO^-IRyVG5IlvIO9e^K2n! z!473!p8>z>lmU&xmkyo#p~^!-OPO)Y=ybx{&d78(_Uhd89p~!Rx_>IW#$_+ib2PC{ z)4yPFadUVOucZFN?{QM2qt6jM3SY^}1Rb@Lr%Eula#FhEFG5ifYn-?>7K6IHmPL#C zfkaS6sT41bB@=}ml^8>)Y|6AWZR{_$y?%oW_s<sM7*hV(Uz5VRj?PP zgynE%{!55P;-N#QS6&b~aNfj}YLpxd$N;r<&SXrtbWR<*NMxnt%z}Y0gWG3L=v-U) zRG$`TCA#=v=^L2hLw~Lx9*n^~o6t5vuau9NfMHXO@e|k$Tr~H%D~xye*b&O&q95=$wm4pm6Dkyj!C z7n#QCPAj7*El1IV79~;vhiVO{QnZjle#tyBqTA<{Y4CN&F_X(DQq54IC?*k5p=acP}&P44N|c4M`CL*ki6d%rA-X=p#3kqOASI! zp2n%ls-Z}-h3v7S8;f1~f3S&4EVG8ynme{(@GYD2vaWk=tySY);GhXZfKff_>qefQ znM)j0(Vc!VsY@7Mz4~Jc|0v9(2W1?tE-xK{HoH3g-icTsRtP66OJ*saN3nf~L7>u9 z&ulj%c<}d1(uTcW(A;npgyD-X_xmO2swShU0RV(@_?T z$|qA##R>Q@B;?8C5UpIZ?C8`OojF}mQsU%s1cXjOl#$c(=Ot#~FgfHUwU`q}`;R=H zhy~RXSFRI5^5y@n!djF>$T1}FqMA(3GNMC`8NF~$#$9BN`}iXzKDmr*`)ti^xbiNsEuKHzw^=5aU{_}sd^~p%_OI+2P2G$OXTc5*hREsc zxazF`Jo_z!@}Fk#3%A4avN*apxuqz&xQP}ac7?uvpVqO=Yn#P}@s9?%MRo{87v9{2 z_cgYO#k6VgbCGq*x$^-75;2&VO4@8>{=aKe*}-^T!r;QD^Argpl3fo%t-DV8rDfrEA)g`RXbh-1S4p)(2A07llL zd2W9yaT8n9QdxZl#<(;nW|`B# zs-v#g>E1x^XKPIoG^!XlGY z;CDX#nQY*6aJ5{vzdaKB>hrruP5Ym^LcIKgD;&1$i+K=6gF@87CmaBan-Gu@3{*@z zSAJE2YiVqXb6dQ4j|ol-vBl!`IRv+G!FDU16gQ1=fBO0` z#?cjOdDKy-C>{@yPE!J7jY5(69g_}kEjH}6oRW{sKX#sjHn2x$6<#_5rBPE~>u~m9 zslKuTjM19+xWK??_)b0{4IyS$a%Ob9uHE*xC#K~@!gNvLGJN1y^oJN5Grp^G( z+TPvZlP0M0cCUs+!QIEx4EVq|%)EN^pBXozn}$k0e>V^MT9lf4QaiDW2dBbqXjpQ4 z7TNFPr{6;{5efK$1y}(en}!b4eIL%!uZF$@=_3N|1g$(G6GY5cXXCljU+EsN^`evK zq(o6$suW;rB-NmsbT-)@!$o!xpNGqXzjB(VRYPkStGEgOTcYI33f0jsQ-2K7@ben51pozTZ2 zPi+PRhBOM_&5bRJ4m?dvROo8aj!7Anhqzsmk}t(9ae-bj3kd^N8>~pUQPRe44s+!+ zs@i25qwAO!HPrMnD{3r2ltenG#-SM;JIDoSs5OIHS{vu{LHn2+d_>&4!|GltgG~@h zRBEY$;7CgWw~#~IZgoByy5oB_`tfp7@8IelU-5$s z)5~QY9-$2`DKMyVC?zrV-``RlT+Pwm)Tb#$(fPAB=G4LhVlK$gw%tl)FakUi+Q@xO z3Cl9IVGHZvmHM8UC2Nh&qcjR_%YC>iv%>xLmo;Mo!T0&{m$P_-U1-1;&*#Rq39>j3 zK_j_JSusHwUi!QaS4CT0vb}ETdHo*?tSW>meA&POP*Z1X*BuA(``&hL26z$_N=f9p zh2A3sdH_opOgKrKY&nr)Tz@0T+ zhEV}~SkVFsPLUMKZ^f(a1!^bdw8o+gO!QLQVkHyM3I0iZ zI=J&34K$^-Hrs|N9X-qLD`htVlN{&uwBVY+l%G>46HiA_Zu~2VZs$7GuQ#-%#FoP) zm8O1=@4mp@AMgN&SI*Cs9|bcUVb0W~G}TIxZI0oe#YPGTf=1_~35+`3&cWkjN;R#} z*3vo~#c7+bF&^PEmUgRh{bcfSgzU*DqDjW)PAADaS-(m6RDY@`3A;QLdTO&BNWPP> zfE%cY6%*{B4KnQDN|_K$*IkfUw}Y=frz1E=^rZp~^u!^SUVSEJZ=FldEr~iHe&zcU z@E3a|nMKKD?O6XxO(RQrBLG29ZSRF#`d`aN#*ry}1<%@X5w#VK8FY(WuB`3Rf`w{o z8EvgsSU(h-ht>wLik*FudXjW(|E=vxq<-+|ZEKcYpvUO={_{=Hzj-$ihxy6O)$VEK z)#h`S<@*Fc2qFduKSX3)wFwTlY1w?tLL1f3T7}Mgxiz)4j0_EhETS%=c531;rkB~L z4jREWrHI24_0vXPe_Q!7%ID66v=&fV32uZDm0zb^TncUyg=wOPe>@y8Kq0q8i-V?~ zjN+fn!Z8la(+QJ64iS21c&>gb;Pa?Hc^%N8L_%RA+>W|LoUNa}+Ql z_T2ishDgWU)s=(U!Ph`lhQsM{J^$8Y@M;DrTPH2DySe!f@U>{ALEgCaO|x&j`vlB& z+e#Y#pQYgj^Y8Lk-f~2CEERhr#HY5}W5K_StVCMwiY-m)E0&B^+tg<~QKb9iM}I39 z`EQ4Q==S+!TCdoz{$uBP*89;$aJ{d>S$jIyOgLZmhxSD_$hqisPp7*)R6kvk&@%)$ z|BXOrVyL2`sR z#{{9mg^)8bytH%S&g)+kiG`GvU>5$P( zGcb1MeUAb+k@estA&0hX#-+-%QM4edjDe1{x%8scGbVSgSHJ40nb>8{-I`lT2#miG z*Q5d$u0sg@i!Q2&-Z^=%I=O&TY+c5efWf1)!G|#VgO1q}!Bb5{O9XOayu>@;PZmw3i@gkqy;v$O#c{hIR4O@*>;R;JviU=_@q@UL}him zMQ0rA_duWCS=|iNV#nzL2xJ4Maqb5+QUA-ewD-Hu?s?e%l_TJrwc~xkA_y!nYHn$R zN*uzj>8Z*V!kE*$x>-Glzdx(4zgzevbTm=VWK1hpQ#1$V8_SW|IW36DXkItjs|}l< zz8GTM;;bLG+K7`dA?I2aslhQK<}ZL4XsNIzZ=&93Yc2v_8b6G(#0*wk(Jz%0L)9GZZ{oWk#jUJ!V9XqzPC3y5p zOK5w__x$)bl#BRZxz78ijh8_pe<&rB3%hTHCd;@;x}+9y{nw9NyPW>uYDWK_ISWf+ zT-lIRIr$Vw$1Us4riBS5I?*z)S|0&ksJaIkvL`rw{m${R)<>N`CDTecW(0GEEGyFo z0f}b;!y()SdwV6cIQlsLeaqQz(-ye~-YKFVCjdRsxqDJt^Y!0)# z0Yy1?=Xe?~=_mO|3s0Cz?W0!~WBP&=`C?;o;@;#5;(_$Es-}xD=w(jT9@3?3B{exy zZ2uM#PGe$ng1}rNE8*VY^}1>Wt1#GToPqA@SBD8E|Hof`PtExbvs>n;Oha)4Oy_$O zTV6~-$?yzb!xD2XJ@(ejUzgnh(^!DJXPYZ@H(52Xl^&E1GWXSTKB-*hN&J~PAbDqwCLh3`I96TyB zyXC&?d*o&Bjei8(O_#iC#0fGBr!53?ON}@&*jItqX{kKms430&u>9IJ$aHEl1C*OLS!#^Zku$^cF;>=X8d- zHvZ;3PHuq90yn&D?sGPf(Ig|YPQ&T}Y-={b)}5XBaK$9iU`H@fT?-Gq`h`PP9bees7aS zCbpA_ZQHh;iEZ0v$C{WE+qSK*@29@E`ug8pU1weU+}k=R&(&Iez!QSX{6j&+4iWV8=0+a&tOtAdH5SYL1;*r11G`ObN8+L}Z8o5t-_rFFY~<-9MnIQ}=PQszNLv_74pZE~jPAKT}$afsWFhZkRB!gG<@ zANK;jNsRut(ib+@3MuG{)laX_=F_3%6{@OYW$XKcV@Y(3^a;gJ66E<-tT9Aer#D?g zE#L&-H>e*MtC+91O*2WYS`0MpeL-SCV3 zliO2>abm=aEsac*PzaHfc%DL$MkTl+i+`*_F>#*ohd^Jzp4T_}4s)7giib1~b8!_? z!34qzo9wFe)V&u}&`8thg0FHLvr37(1!GHxuu_?3&pW!!Ylsj(#WhxA$y5GlmJCmV zvaG&fjD4j|5zQL^$-ARDxaCM$LWaT2NjpBr+&)oRSPtXlWXI(iNtx%9=uPOq6EN_G z-vU#rjjHGSsybeHfLZr}M_nz`T!uBR_Rafa|1*Q)gTOBY(E=IDbYdL}IJMI6dcx8F zeiOJWpyVIrgT=IH(PlAWQw}7BXlm^kc)w~3?!4+q!mZOUpo%2=qzVCNZE^qCCiQK5 z+-tRFxM@BN7XW9lJ3WmsBk;}peY03MYYBLLrLA+a@y+=S{Hm+llzas4xQLoujicQ# zf}=9VkC5+%S2pqB0^_LHsFys?k^2jMe*BV$>5&Xl-ha#KCz;cgMH;%=yhimLen}#xki`kdZhA$a4YHM1+Rp6{cOX zWh&as?eCM={O`LXF9%74JE9|IEdSU)%P3)%W|W00a!lHhButOX>(QX#d4$~5Uv7R2 z3{Nkyr!nXsw`2MRO~RT~3FF9`(r7c(URoPcg_fd0(8G&khYJoTQmGEstQ-y5l8=fK z8wW;%lVF^bLmzZ>wFz@r&9epwJ>vweXD+&@vvht;H?h%=@;Tnn-Bsx4gUWW`O5g{Z}GFvi?hEpQlp+sU5#EPtHs8ORu zH%cH}a)Cw)VJcTj+bRz94swLQ3u;x%SJ6$08K5qis-TS|Hao_lKxtmrH8NBXM@57z zUgtpa&Pq=D*)dL}C|aB@W#kfpf zB_;~2_!UhfvZf#0jMyF^S^!*1HvE!POBU)IkP1WOeT72YaA%~P$vsF*^Xr%QdqN2w zOSe>2Fo+*M`*^`(B(_R{(ZyC%OXY0sxpI106>RQc!F|Sugc($HU{5m@!}~4j7|l*G zD)yfz&2J1FcyBQPhB^whjh%G~+VMmR&R* zGMYy3!$C7^7^Qk(KW6jJd z$}IQMWosmDf$?ADn3$NsE){8n_;3)@uX&-3=nIm0e$KUDp6{EQzq>iudFH!I?60b> zgJZedK8}Ltg&hJqlg3MIgw+)=WSS~^PbOPzZ-T%Jl+w)A+keb&4S+~X`|fdySA?(p zRIOHnw}yj*LDF=BWE52@`46c-64W^EzB}jLb@%*QeFGpx?oG zM`+H7ZX+H|r`obCSE#q%ELI(4VBxqw4*lwl}}`DoPO?!IU> zhB(`c^erImORVpF&wqUA*DU~A-4V=~$1U%%N#XnX)^TH6*+MbF3>@DjjSY?ouJ@L~ zOI|n9QAZ{61^`-2e%Zw;&%Iv{+IV&lC}Jj(nqytO$*~5Uj8_V)zz4J}TFqX%XkM)A zoQ=fd?+-?x(lIj5pFiouWACo|8Vno_Q)sWV-(*YH{z*UV z=D&P{+Wi0@JO@~u|DOeNHv{2xyWso=%8D5`T$gnpymSjW#lIki-+mlKzU8cjPp^hH z3L*_5E77c7VgNSXa1}3dR*jBYJkk9FpS!OSzV3iRxf%bjd&r>_e0dXt;*9rZ-|8yS1u#CJj7F{ETSp~tZ`XDE6JiK=|q&jWSAQ3Y0S{mkA<#nnv z$3{n{+t;iNdwBm?ww#^+b!RwKKjuuHZ)+_{J5)=h%}7lW{$8oK0AvAV*#D0OXi%n7 zTT<85)GeW*0b>X|{pjw&eZt5Lnt`pXi9$9EaaM!2=)YP**nWL-?+X-V8@*&NE}&g0 z2O0{7QHo7-LfX_lk-0y)fQz`?iIGZgiQeu01IxD#te3+0b>r9h3LX>^B%x z@A)u&dJYE4~>AsK3Tbe-OI0?1h7sVf!fT@u(#eu zb+jWu!Wm=;k?fGy)~b@X2HIiZ4C8Gc9SPK4yL;RMRV%|BJ#up~?aw{$<~>!erWwiO zJ)Ya$&v%f7-=KaEIoB-dHrl0%mfbsE2zakKjb@Z?p(aNSiuP+_MH0No32s$W23-?~ zJ>R}xZ{KfqWR8=@c^+%*#FYJ~i(emTuD5}Z@!zl)wwHGsaek9W!w?CudYRxVh;5+` z6BIw%^?CztRAX)?+qsUP3fTRl(TL@n1o|+gP2sSF@Wy;aiWL+#QE zloT*r5|alcN;{e_R0@Pt1`~kO$MR~VB;;V+EG7cy@6{xqtFe*SjU+-NYH%3s;gSFu z;o_P$Ark}UX^*Q{%#~GagMiR45_7xmlzBk)n$MN2udgl`^*g1&9a>Zr?Z=}2C*jA% zp*r?8f`uy&d#`%}YROW6DXBJt77h(i@+E_=$WuCRJ$qF;c!_2dm;h45Dz1{;I3O`{ z=4uU3UmX;9owNqV2|yk+!qsB|2f^FWIY+q0vVc_kn94bXTr%9x+G?oAMItGu@Bs+-^ zu}Z;A9yHEZBOYHciaaP7-7gIm)|vU!3DkqO3nktkV)<#xMsn(h*b3;ytBxl&xE8Sj z)uxaMexqz?W~t8?YTkar`ZcH&iA<3jn8o4UQLD#pO4@5@onOXfw{2l4LnTx8B|%Z- zTdf|vWu`&BHK5JZ`82Rz&Kz9JqVzT7)MDI(HE=w>JUmn`O|MFpCpNrUJQMr6GsKpsukea$ZdOVce_ z3N_FYxp$DG=T%m(*DX{sw=-XNn}!aCE(D%p>@FMjS!d_J76lQwKPHo;zQZfg*`Zm0 z;kQGma}iTrYl%a2V@oHhq4{x|F72j!4hnstwO}6+g4C={Kb^}bJty%q1PKzPZ z#%VxbcD(BbiOWrW?>ELDFvR+SST8G%BAVEW01R<8j%aR}PT3Z)x)#k+fdvzQ?erkO zEP*-MGD#|d7TDPy3OxU);bZ(c`FOYXb20@5ebrgRKnv3J=M0tX{6b(mAMhR|k4Gs( zfeM*_)E0UY9XH#kP=nSD*_xF&wbi@?1f1P#AhmrpJ;ZG_Q%}ZAi7RQUSpVln6jt!T z_wPJV8|lFFC@B2QQSA?3Bvd658}7=MH+;xDa~eG1Xg}?eR^qxJSxNDxow6!U2^o-$ z23GLUzC1twh>{ZiPrp31D)jV0RaHd{^1ri85)t~q<~Ak<9@xjyp>i+^8~C%>*FAqk zdM=i?KRxNK_ewK8yH8y^nf!M9@3CLzl^@MiN*o#jm&@ay8cU+I1ZcD5_jTIFw1}ei zH^!!Nq?=p}|MTPFjvnIjZn@E}TQ1tPb3U5PsL!{o#lOIN)|+ve-oHqSS+e%W-Kh(J z@_UTwKCku+>p=!V7lRuy*85tW_?Y^> z|1P`_k`I@6JjVx+;P(&KeTrCm{iuOQK6v5Rm*xcAz+RhHVU@y}6jRBBV-rm? zQr{fX`H`OQUvAbG2!a8eApk+S7yFjCwg@= z#&LYp<7bVo<3*<~+Cbq*bxmCY*)RUIDGOE;bMrJHEf`5c8Hq+)1v~)s$j{s|E<)&% zZ_>WNoZ?uem@hKu62yOY?rqwX175 zOjs-ByPT0HjE|andWD--NyX5stj8k)U%&K$Z<+SHPg+q?6+0FishIKuzr7WqfGa~0 zNe};?B)lV!OrBTVOZd-SWU@<)kvKwQPty#t2uJ(@2vW{gS3X155fTQ`EQE5KW#Mcpts!<}N?*e~915;0V+s(DGXa8y8Z=5^ zjnzm}MY@@w^fXd5tmGg+ z9`9WJUW&|L-+SLlmTNZ!hmg%@Hiyf;PUf@QO&7;xJB9kN-m?+bFX`)UzTO${j=y(j zUgj`?@A}+V^Cvg=(H3w+)j6T^(MB8aQBL9EKT=jeB)KYU?yQuo1}Z^<23iXnaz{&0 zJxWWw-R#iItkyyTgTtiRHx4~aZWgk6O)GHMLGYPk8$mFlH_PkhhKnEGZwt1Eze}{& z{o?J{aI2h{B^iaBL`PJyHKm3|XNt=$YoRY(j*AV$OFb1KvFsls(Q#9hdub&-5oQXb zNHpW*2qcRBbSz^j@2(638C+u%-PAwg*?CZhs8TB{;%I%FH!M7@Va}5>>~?Z z1iP6Qb6dk-6Yo*IT++GZ&=hpFRCS5{5RD-V%>-3tHwbOuT#RXjfGB~kMAuG}Yx-@E zS^5$oV)npWq!tcRXA8H!O8U{n47y>yWb^uQG=-mGz|u3r%NZjR}ID`D=|iV8hMtswvC;ABY=Y});Nu$egvqZ zxRlG15CgvQ+1c4w*4Bzgnfv08x$3%~a2UHEQ0ij-#I~4@G-sq<1e1ZK>e7MD7w!!K z3nsA8=TRqy2z)$TH@O*6HyfH9`mX{=Pw41x2KVDg>*elx-{&yL%CMCrC&-?H+2s;9 zbp0E)k2l)yb=n*lbKJrjM{|@n8qb@RH|u|bsUdYC;89G1emQ^J@Ne(-Ko7>;D?x=A zM_saP3;e8mnLTyk^nRiPY&c2($UMq$v0wY(3<%(AA!h_V6UwWsrlLJhw+Ha(^tx>x zvTZoM3T=J_n-9T0F_Me^h&cP5{n<^8okIpKEiL`us21ohlSr0q3cLaQr-_-Wp)Z}E zWFA6*w&QAi9@x@FGF|$+po8s=y4&XNbIIi1-lU4o-#GBYR5hOKwy2b~8j1ZzND@8Z zKQ4^6J*yPU#@n`}!t{;%PwfmU4kff@qK2D2-ZB7GsF5pT|Hm4P;e7Qd_P>}_3cIuC z%+KNHiccH0h;7sNI(1bs0Np?F`I+~?+x3ewJ=;EMdGGtlf2(`G=f3~8^B|r0(s_y+ zkCXF19z&Irpl8T8ouP4N&V#@=tm#Q(@Rv*A+U+L_NwUn?Yc$rI)MO3B-*teV?Fwj~ z27KP76=`0Kkt7EVkBuw231@*i?|SINQxwu24BuX^%O-;F=Wj$%#NgtY3JAFwcxPkp zaJqsf_%bH=%!YFC@MF(n%i=otR3#Go$!b=MvmKiZW%7AIvMxdo@Ow?_zffXX9UPE# zyXubB^j(KI;GY4UhhV`$*x1h1R>_wY~>NoD@kS2*jDUS_c7nEuDPGPaijOq5;V*?`=La9>F0oKzjx{i zQt32Z;oBM%uIDv^*}iFdvKBjsx;H70W5O%eO>xTy8yk7LlMF+ zJ_en(K9M+nmAnC-XRB{4zfbFD#h(NgoYcHOOmG8{gPKvDZ+G9hoY%3dSo6VvRXLl} zF?;EDX!T1)u!rs7aiWeTM1l0Q7_(qqY1oKIQTzcw7? ze|cNv~M}1u4RB+L&P@Y5wUTQfb}!l_AW5cCR~Y zYbC)K>fKiD$$0SeN(n;rD8rSFm)N zpX{7uJSRn&yAfNCa9aQoda5 z+zkF+Tn<~|$?@3Pv!QdPG7DDL^%uo^cE zpf#9{qfvvWBn`<@M@0Xr6qKQj2S0TXbUb7}j;p&r*mS=;9T6COja5(UD;Q3V$b#Vk zquNPP*E^ihe}nPA=kT9sImacdNp=S09Y53n?ruadC5?rut;}^Vds`GGx?9-zUq}2W zIcHvn4wqlYCIn2G@r#VARFHVo#7oE;OY+I7M8!5@B)#eP)IuWb1#8RcNEMc7u+d`^ zqACJ)6oWZkJNXSj*uvtNA@R7smvFP(<<=kq5?y=l--fe6RTlb5=W5I^yH{IO$!*Nm zP$E))i4V){V|XqIKcreP*3I)dW&RkS0$`l7ySc zm|%p<%(P+~>)Zs?JLis8B%2dYNvX^{QLOqDGx28*bN>5C&7V~XFcS?HERqQoHkN_4 zT@%D)v2pw~U)IR0c3d9w*3jkrsR&6E44ox>n!(ew>2G8+5Ikfp%nBQaX&58;5}$-v^X#eJ^pniU zvcgUje512_BBd&AmEMUNycE63!6>Im`us};vaTvnqwj4T#5`7?Y_Cv&d>QZ?2u%UE zr3zR}>ZzKVI{C}CQ$GII&QVnywN0I!QHhaqfC;7EnX_@4OSkSHD{T#9K>u581W1#4 zYVGx`=5_j7U|cGr-g~=s(Ous(as9riT>xhRz4D#UD4^$A-sYlvdi)lg;Pc;KAaL2i zh=*c$w)6^nPRsk`-8;fM0b^;Vf@a)|;JcHreaB~b#PIov zwI1bTQ0#Cj=Odpa=Q+4@w<3<=0QC5gDN6!f=?{Yp#Rubl-8N4*(2zXV1B?Kt$vJY6 z)Ft3h!>ACTurO$1hS%+$3`Zlo&rU^tFSYNZTjc8iE)RFvfOY+4rFOP>4M_3@mdeYf z;O?LN_Vx!qS0S2Iq_9_t9c>OLl+(%pa$+XSRlrbsJHV-1C;Ldb5_>!o7$NL&DoWTB zuI^&>Bt+{J>JA3u{rX#`V<1^Zbqrtfsmp<$?22g#f)9sd0Nml~~P$IHXNSxU` z6IvcKnNuJs2T7+50dE7^H|*bX2GpvW1{xvWc%^_E9IfiOUeE&a$tco2pMFff;q?u8 zh79O6ruGcy{Z*~nt_pdwHTx~8Z?fi71iGgV=r-PVmeW?sD zBcgW?EW*I)>gw7W(2Ou`*TDjPP)cBX;qqvTsly*vY2y2=e}kj&me6Hm@_h#<^_}vg z^G|%&Ud(l&$B#%$B#Wwv&!|Zg2SLWYUO^{aI=-bpTi(2s8>2)W1M5C}>s^ zZ4y)QNU^VX}fw^_-3o6Y)PB@9V%%Bjfv>HqrG#|4yV;DXmlil_PEv>%_|1*3sSJ z#KO62u~q#!FGp?kx2j~I_enxsE6< zXkiN#1%ks+>xQw^>c#WwIh8iqhA}o01tdwgO&Y92E4+#a+T?QMuHT zNYHwox8z?8*mE{5F9)D`W``?Irf`PqDvCkz&`47J&!J%ofr1c0*SvR7n|@MFtAqJt zvf`y|Bv9GG>7}byN>!m^nw4%SKUSHJH!_-Rs%uG|piBc)mNMJz&O)V@M99CsnTMmA zcwM(DKyX>uC6!7`%QQ8#4D9?6i0NAjob(6=EQ3>&*IL$fmzIH7_YKiw_OB{FI-UnZ z8%AqBcs%^Xr33Nx;G+7}9!H%rj3p=)%ZG%hSv$=I=r4!UFE!kO6A+93PkUAqvp%Bh zgvjJJ*wBg!vB{CEZPYr_VND$` z-tp=M0Gy_ZCq|C<8a&GuBO~^q$muzaM#`V*nt~TZ5FjLCVnR!TByV#z3pS$pm2fc; zWi&b(3?YuEv-c|~^NwC@0jQPXM++{y7&I;!7Pht1?{=Lruc2ZcaOuB>L0loC?P;+egu#Dhv1UDK>7U{F>VK zI_B`EfjSd6`Lq-Qsi8(LP0A-M;@qZO+{25+>gy!Bp8%!)!;~1s6Qe0DtCpuNJC z?GH#%SN_INIauTUeIqQC_$VAh=iIdq7?!B83Pya2Ol^u7t@L3yDez(*z5@dZnY_Q! z^j2CdcyOoBZdeFvv(>-Yk_v>y;+GXPCE~*@P*|ab4^J!tD!>(#sjw3%L6Wi>+6#-7 zpU9tQ$z>kzS2Qb_>hC(FIkp5zWv=!fk1Xhsxy?AEE%jx%J}*2GrU>``Xxo(*@R~M2 z66j8taxI{71?gvd1dinTC7R232{N#-ubl>L8Opa-J!sk zB?m!Nj;!hhD?AN7VPYtgaHzdIpS`E&$r%TS$}u6<3RV*s8HHOZS72s057DrmqXpyb z`ZHd7rmaF=BprNnpazZ6v8&o;Jqrs9@Z>b|x_e`u=U`Okd!$dp*OKmQh_G?u}M$JVBmvzSYN+@V}GgorX}Hk)_>c(e#NCg%p5P~ z^)|?WB=88h$7H;72YSMMyflp9#nca2;6jj;doaD;*C1jilSinYco!`}lQtUYF`+J1 zoMozLLcw+%-?Au@BZkfzm1G-T3=Al!s!-+M?h7WH(lD#ELs2V0 zL6ZEYGTjdqSF{!V`K@M3GF1D%#R+;rHzWQ7$(X2eF?;}ux>(!#Qm@1S2dj>egSxjH zcoM;`i?@#Q!lIuFtj@8w`LGFtuS1gam0r7O7B3_SLIo<;;xuy;5btyist83E9ZU$o zFqnjiFS@;aZR`$>-o5fUp$39rHgluU4Y7zqi?`1)FQ64`)CNIY3G%o8Dq-XfD1`^T zX;zH=vaH(CVq>U=jDclTuoTfsIV}32@*AiwFJGTy7+x%?s-p4r8ME6t23P#22Wxq{ z)MOYreIJA`D4{qQ|7c*#rd9)KYTbh4S$o>Np55yZtFGsnLN^hK)#aI+M23<5s8{@z zLKXo!Q zYrrv7XgYqZx;Bm#zF!Vy-_qPXy0?b{bRKT~4*415_4o1jI)7^q%G)QuHgJRk?66x~ z)qb?)4y>nPUvRVc_@(<7Hhifa00<_1z4vt6K9A25mai=;*9I$9dNGZ+S$5xiSJQxx zd$7u9_ZBqvyl^i#^_5e8qFbhBMRHM4_nfT#dqd~^y?@Tg8Ptgp`$H#hPY_&{uwjaE3_naLRIB56s)X58gUG9uX_le@hfP z`*hw%2*qo>1UTAb^lfaSsK5$fBHN7hDq&RhTZ}}xcDB5ydh2i5z_|tvOzFf8M`Z>S zo{`xsrUB`ixkXDh1|Ybk=mLlxKTXlVWY1MefR;s}7_A7^NA?3ZIB8B!f}zAyYT;wu zhfRW1iqr79h3nYhRM`22KRR={zyZT|T~?#fMW@4Fz}V@YG%2(;*~iz;qbvY@qgK=Z zu>gD!+eb0`&O0kz3CGZysS4%eF)<^@HQ3P&Zw83-#~@DR|4`!5O-mc3gbc@nyL8Pi zGigJ}1OvlI2hv*>;q|y~X@a-ngUp(wVh}H?TRb02)L(An2=_mRqCys!0!cubZ8vsv z#yu9P$dm+Qg{)vfz=TOc?z*2dD{G{%`5Fl7xX8Ut7fI_pAX+;;kY?W>Xbp`+C7;(; zE${Cp81I3DLDXU7-*LKOV-AriQl_N&cKgR$-+iASpW9#fxaV0|im6>|;I;|l5%V5H z(X9d9=D0V;1=#@jTn1nm-_+qmnx>Xs>wSU}5Yzzf`X;0qdq$_H*#U$Ca%J8r;F935Z0wP7V#Xnx8FP%^@3^#b*z>+_bbSv0y5H^={Z3DElWZ`htC30W$DV_d z>%FC*)Z^~2NGh{zE`=(>(OUWFdONfBc~AJ=w*LueuxzevZ-fd%Mp=0gL<*h=3NOhW|_bH!G;h+Ry?y2|}c+l<`m9{p=6kbZbMM%e84V zmp9XrcZv;fP{ln`vx_u9=~#I#WJvwz@Aj8rsft83U0lLRfQQ_zj6J8p_#q!^P{Eia zcrkE++aht<_b7wk5iuNy8-5f=l;wP3k{F{mee^oftnZ&>V4S1YBi4%aOC*bI-5|aC z*Ce}yrfJRW5LlMzDw-j`ShB3)0C5Yo5HGpHy@=HWimtPD1+{gt4(%romy-J7sf7&$ z6-JX{5jNsMkPuD`E7wo1VK5U<8Sl;fnFqzo^uLgCPBy1zXHIJ+CE}R33PK>}%Zzt9 zgdYLsdR#(`ry}LpXFnqdI!yn?6B9*3gFuNL+?hwVsL6|m~7T0g!P9(c+@1I(MG&8t?@iYC<~2ViMeQOU4+1UZ$wm4!rMIT z{i-wWFC-!{=qc~NsQh%7Xmy(Lt08;sx zn*kT2d|w~R%#^F<>QBY#y3RW$q|o;D#xM#kYmh+6RKqwX(Cx{<&Mvm1f;w}GB1U|^ zLj5u`#gtmI5a@*n9(woG3jf&L&>+;g$zb&HrqP!)ar8cEe-!;TgErZ+mx81Q=MCES zUvv3if0@PL_7`PEM6F2Dx>5`YBB@^oi!bG?vg|Vw{fdzuHR(1|R6O^-wI<&1fY+}j z>UXu!2s(zk&-nU8p4%^p-=k3@No%yQ>Y$nwCS&JqZnO*(cXS2nf^=P#X(_A-p*&9j4)j3t_)=f7O%)h~c zLSH>gwUtAZ0&gFp&{*Spcw6wpfHQ(P+(F}$qwV?L_|}}ZmmFT6w){*0Mkf8Fr=cPLdOG+ zIPXRrKF@IX^TuC5&zCIw68rejI^)hF*T0D2cuVUGVtiMRD?Vr1_dH|;%sz`^G~m78 z%+L`z$9g)4E9%D`9VrW!rW(!c1$}0s&YI~&01*)a?j*a=>}(!$W9w4BR>o|hQodTA`oTQ^L&TR! zT|yI6$2GIRQ|i<7f1mU$dG_4^6Ek_fscCxtIgir_yAQ0Khw9FiLr25hGrXT@bzL7Q zVd_WWX=OCQBAnO0pxglGlK9EVskc__+_Q9n0IZ}_X{#)<2pbiDrz!J_gPzo9x>R`iv)E@{V=Z< zZYPEXPitjSKU9QJK@5>tJdPv-8YuB8v=D~)=n=>xD90SP7t4KEoMIkNxXmOoG72I@ z@$pR4*Btbpx~|Br6|$*!I5XU4;b0}`1g3P}J`?0%8%TP%j9F0)hwM@c{y8FfX6b)S z_ytAzKUk|4#yhP|0OMV4wOai~3km~4R!cs^@tu4j!V}?{wW#o90@_4atSzZvXv{r)O#WQI_M^+AE81!v=xfJCo@UeYAq zFuBG)#$gNv!=Z=-RABv)y@LDGMdjxi7~`P3#qL)n%(Ks<`(YP=!~qrAE*rhkR)v*R z>IWSNXThF%;5q!U!K++DQ2@i_8B1q0pvHk%8vCLS^io1WpW~|B?|$*6V3nil=Ha0W^|yc8ei( ze#4y4;CFf-7GHn94o^pz`ZG`+*!KTQ;f<@SQZ;5ImFYK7F@>Od3zQyyajoPIM(=It z6sl71IF_+0y&L80IK_<%)-L9>1YtdF@>%`(RE?JgkM!!EzPO-sc6OGipbIrmowoz5 zZf%vWpQg_AteKpr#sQcquP5rHX|lT9seD;1b$b6YBWQq-z7<>9ERdKRca%vQOTAPw zqoIvUQA;oC+}1C~8q!pXfv0N^i?(?25n?WbdVk?uyPp1R7cUYjn$1^h+IszZqe<7M zH-GGubeZZbFG3dUTCXISj1qI^0^1Vi6O8xLi+*uRhq9(FeBhmkIj*%35l6wHsqv8?=F-yd6H2e#nD@a z(BgDizU*-tqm6~4v%5832Ev=t7;Q-Khqy*93Ye7RvHu_Y-PR@n-`?J!a-0C`9k*|iOe%BX#EG|YqYIfk!Wi(wEA~TrWXt>yPta8 z!r$w~*CX#20*esJ(VyTZ1`2aQIpY$=e_t!bKU%fJrEY)k??IDc$>v(lksU&Azw=+Z zWog^BhZ;AH(48pPP+k}B^d|MmBW;ICF2Z+voC*-R+9t z+2IK>mqvprAWe!-&P>l)u}7$kGU3LXXOtv7h2==vp5E=%NTxIs5Vg1FhHx*#L4aZz z?YH4bsY@8=#elqNBGXd#4M!{;EWJzZ>={KSguUPH_M&t!n_|H*qHB(wL!H?96!6lg zF5kV$M2^3o1vFg;3pTX1^%VruPSP{1c@oX^AAp0#%J#=TqM+5g($tzxUKO~|!ZufF zRcg}JB`j`_EF=aEaBp}MXs-3(0FOy@@B6xo)mgEPz3uF|+po2en&yC1CL=O48a?8~ zGBQu`Kj6yJc`p7hgsM(PGD6T*vsej9S$OD?16ul0Ldez4cau@T$w`!XF7PIpTPARU zjKX{Yhwoqt1%=0!DN1!7bM$VPkH&^xs1m>))Wt+|3whm5p&02D?N0pR(XS$<7aOp5 zuR)kt%4|aQJudmVBmgu&AzWs*5!ZMG?(qC^)oq7af)@N0z)~jP)Y78L`)k4}k+mfk zT|-M!wSpJi1e@$LSz>6C-Pr10nzay{T{MSv(PTBAZi;S{3{Dufk+mQRyLp-^*!Ip4 zH|OHt>Q=}?ei)ZaC)_f}zf1hNEB4aPA#;KkGXF2g?;yyl?kvz6ZgJdX7vCAra2!xA z4XvlBD(jB}bNM^{@7><};Z+tHMtWhiLJ`v#Fc-P1St5DVuY3QuI54L^AUa+~wAUCf zY!D2F8xP}Rb~^qyAa45^S__utgV6u=n#=nZBm;#Nhs_CEl9^~s*~uP{oVj=uZ?Qf` zr~=;NG*IU{gJ;QKH;<;(*c3H(R8OkHdQ~df`FZQi#u#q+k-o@wL(@t3K~-PfjZeYC zaFvf4LOkIZhZ^YKMA6#K`HGd13;|GI>D6dn_zUl-Tmi;uHMLi|J>k(Kx?7N=o~&VBf5h3KX$W^TlMcN77ph?%!}O zm9u6*M{O;jRZ%>@7>^ZTOJ&G!MZ{4)S;rADwaeV>axc9i# zebb=^Bl-mnq}agM;h&OT{zzktfdJka4Lv=QNRULhvvHN=3)5ZkpPIei=sV@2B{1Pf zXJCe-8BND80^fIaC(jVTEMooA)yNU&BMO3;+15Y66~ybnwQt~I3i=no|Fh2XuA*#p zb*pgIhB%ZBt2(kwI7L{iNZdb_Mz@Tng<$FhBYOxR`g2m3le?>!yDSozjI8W0K0aG` zux2)4>BNw!7}<^-22UYc#_F&&g7=j~K4X2qdsCmo_r=yMj`-@*^W$~*Ogiu4Z_G_s z8w6}z9(BvohN^hTjLhjn&bnb!i=uApk%m*Q5{s=)o$kE4# zW(ms531$vY-uN>8+Er3iMpeg6bFBYFK-xJMQh`u)nN;nRKclJ5{n1WTLhG}yTQ=sD z$$s`9e7!#gZW&3FNB9Z%7v{g-6WHmn#E0R3;O}UGS5BEIJz2wBYAtEE+rc>3@By+R zL+fodsuqE|Jz$fAfXCT4FaQFa{jz4s;_j~oKJv#|CMFiM$2ugExp3nHw|e+kJ(8W> z%7cH0R?KB+_EW~cv#5Gyts(&Q%P95fx=|GwH=8{d6aPIQM-uIlLK<52oVAWOJCQ9b zl_R9bJ;)g^hjpCR>eBuwKOE_o<=?Jy=%gPV7h|&LiKBn8cTRprN&iM0M1aRyoxFam z)>#*EVwQnYG2m!UdGIN0G*aw2_UrcG7t^b&INLZ{Aar=T`?!PoK}=542BXB*dRTwU zUE6wn69!ZFgwpBnwXVdMpL$K-X2@q<3`Yb^EafpdMQRqu2^2P}@EB?K7Na4j6Mf8S z2#aTeI%)0fx_vwUc!;1(&&@CbA{VnJmF6{(ZZ|8kBOW{bGxhD=Lx}z_BHWkkb3?@` z2s%JvtC6j5idR$r#Rp!XN|AB^q*Speu|!hH0@R-A!Hnd11Yop7|fY*VQ)M2u3hiamBXfL=`mn#caBd=J; zisRxJcVXW;+tY9gT4@km^dsU=!+Z@b4TH*6m&ox#ho>$*Dok0f8=BzxCZ;r|UM$;d zNu^8BMNhXNGj|nrOSdx3cESCM9vi)4rT+{A?fE{Kj;C`dYdLH_00RbnX;qWK&)Mvx zCwd8i4M2j&p#{9C`reu=?}W_M+BIc_&^tQj5xz<=-f0;%lGwC*ZuejRU%c)wZZk7; z+Ye=9EDC4?zT}d-2dgcZbuSb%Zc+|x9O(+i{04;Y8e!Vx!k4A<&5g}s+Ejfrl*%MW(3~x;y!P}ble}P zSXx3!>P#|Ctiw7SQh?xTII&eG5mnPDP(U9bO>*_*UNys;w;}ImHKD zqOm#aHf+ck>~{ZBXFtP0T+)|ikB+aMs4pkfWd0)c z?V1zYPJAg5qZLrQ~bE_Z5z(8wufy0UT1w)S}E{?R6&;ns-9Q(E> zR9GUyiiviH&h8y*- zK3~P#u5W39e0qHOmzSVUUcsUk&}%Dx@{$Mxg6uVZF-N&rs1ImNGv-tbd&F&tvCVfM zdlmJ$Li_yJ@A`agYDkRTq8WNjEF2kL24j|M+l;@$`E!^2s{7NfR-Y^KUo1u;vmy3R zONgv>+gv`!AWERrj7*-m^*%}lzLbOP^g#k!>0&_C)OXIUXK*OHRZ1g<>~|X{rX8ER zU(*%4xGg2TDp6Vk&&1lD$-F6ijLY2SI%1zGg8%frX`NjAVh``!%qKX`yS^+*P{3-Q0$66h>?m9iyw; z4>`$iLp6cnb$}&v&cNAcf~3-a`0ibLTw9VhQh0!9FlusUJNPu*I~<2v87bme98JH+AjwH0N4+% znOS>J1RiXOyy0M@`bi(?A|C1C#&`Z-^JB|gsnXy`Jiuh+=NEWdK^@}s*1{)RmJy>r zc4Bs*r4H+zpHpuPw1=8k@mn5Feqh`ihrF`_(M;4j#X?k|<7FLu{qyc*ZaS3&B6oU`;%Ujm-$43WS*lz=K{wx{#HflzAO0F!N&ueqH zSB`4Md3PE#(vJQ#gPUiWr<-JC;t}w6wKs&$xr{CHUv+6_^w#IE#PFtE0P88qG19`4 zE{LxGWp66jw6%AbbgZ#`8gB)!R8*oIr0UEmG+R^xG}grUvv6R-z>u%>lNrbz;`e;! z{7%{K{JFUInrqHuCZds!#%5j6u(G8~ zNwdN9zZU9~fC*R16)4B(nuhLURo?k?n3953p{n$1)@ZZonf4y+Du;)Io@t{mgi}BZ2%`lpg#Kka59Buuiw~l#Fs4~K{A=~YHx@U_QP+^)CsX_^D%G8Y3|<0m zf$>TSoX?jYgBc@O)ASx%NRiSgYMO)4-}iJ?EuTG@%fYc=tAAO+%3QMa@XRzZeSEP5 zq%x{tGatN}Tw0WLez$9OfbhQR0GHax)<;RGRHL5eus8PQhQ8J(Ws+HdXXWA za0Xr;_!mXp!$)Jl(yM96YNwT2Z_gyGYlI6hw@b`KN&m`gRcKhAQo*EP##mXE5YCp_4I51{V?0pso;ohCU|~a&hs4m6h$}=`E=~_HX3x z6tf(!=Hr!R*{gAzfcLQ)v}%=`J5cW~dk!+Wq0>!;6jsQ14F?*w2D2u3_$L>u6#3)xS?e8Y9^o-rt z+%3AKkrnWc?ElXTfIsqM8wvK<%wp#qAbeka9c?2mpZ}tW5cJ6Nj7L%X_5EN#`Yw=M zWlY(+#U*83bJq(Utx4NlJpOt{5b-9d+B4{>*_u2wVAI`OXH};B;hxUB*XJdp8^B-X z7|>(2^nYuAjVV3o9nR@g|9nDO&r~@%?(?89Cx!i48B(%@QcB#^#L=+K#s}Lc78ik6 zZB1(tDAB$qF(Mr;|M;e-Z$OLD;0epoiLm{?#CCGO-r&;oGDh&uW8PFNO4hiTd<+s* z1aaB%Mtk`+@!<%?o$c|cR-7&kS{mE8VxnJ>ze&|!u6RP55it&j_tkSj>NW;w!{Pa3 zLq7RuGu{e#OBHlUj^c>Hf;`u~h&7(NtCanb<4>W=lV5iw z?f#Cj`HjU}f3K_*iSm}Qa|3l}2x5=Z9v}_*m`vl1VNz7+>~0stZ>b5e8I!qJaNyXf zJ7jN@(Y4Syd8IFTF$NkWR4h&c7@*aZVA;{FiZ)$Jba>YB9hsyc!@mX9-W8rpt~DB1 zM?yGA_x;Yf+N{-|rk!SN z=Ze5SSgN0G7kzR2qaJ>%XkmzjBr&6b+_3RdTD4Dyl8=JE$+e2ZxA;w7nL!zrdEo>||f z@GEuh;^lKYU{U<~ka^_w~4O6N%4*`!bJL3?GVdC>I7- z@CNGnOQ5`3oLfGia&+<>?fq`!_nlozC7)(C%hnw^{qBB{^gs@L6%lM95z_B_j?VMT_I*T%YwhcUOQw#_n{< z1t%$4s3ub7aGz^4oR78uo{Q$^?~YgB;OOh!-T%ku(}A|y>UOdE69V9#`vA>@LGj^2 z5A^bWOQ!pKb?JEM!FZY4yFdt3sEPPa>RJcE*qfUOt#n4NdbmJ8>RDlkG+%INi}0j?Wn@!@p^M~LeKC4?#VNibcqM@pqEd;{@k~?y zbW6q2)^_ExyDwKS%xvE1)}P~z5Ds@7wP_+33oX|ZKQB9O0ydtu{xG8Ae^Z}&6-gHR z`^G7Ss?F;b&NiJ{(#fK0?dBHOc_8shr*O?KQ*l&Ox2`7oF=jomb+AU-l2`n*{CkG00*N4)qRP_wC)|V}3?+q`R2i zuIb|`Dh#Hy+HC{%(>$VRLJNJdyS6)zkk&M)eXYkTVU^=&tK}R)GzW#YZDM-Z?CF&l z&0Ee?m8Z&X^R8K(|8Y$YMineAD-0rQEreMf-&`TR&1xe_hOq3Rf)CuLPUlNtNgBj! z`KnX*vU4M{gfb=}0q`79hDFcKVwL6~CDJ@^Lbspa2HE~ z4&P~j*3MnfRc?)B%W>&ylrOS-KGR2u1OUwX^dge%o_)0W#dm4S3@x*XOO9MkVbQ4D zA#b0IyGEC-6^Bo|>Dz{R;17_X>g(#{XDF7>o$`NC?*C|icm1;g1Tfn-jRA-faH0Y% z;c(X$v-EhQ-`Q%?Ez*(PI_pONne4h&a5FNfDz-ONnRNbCkPwXxfL)rwTc* zXgOaS$FAFzR|S0HWMsw)9(R*$FR#npQ(>s&mf7UKttv?{gxPxcHzf3XBN`U9UYoN8 z@8e&GI*i=hEZQ>`DU`7qzKNG5;Xe(lm-nOCwy8S`hvu=OEQp8s2E-3(k`|4)kX72W z9!$s9Cr2I$bgu0a{$j%iZ`hAlHmv^;P3t(n)tWPF{_S+eOxN`c+Nr%gd;TmatVF?t zuO*I#E1!XAXZ6vOvJb0UW%sEmVoC}EDvUPtx5ke(Tn~~GTb`-42zF4RAR3?8(_Ees zb6A83G)xxsCpBXs2noCdmVFiz)*}$-F_G<~=jEIn=5?ogND?j)qQnXCS6Md91wFzr ze%a9?*c(jI*?U;laaxHLk@y=#q)-XTG*4r45a&Uo`od`YQH%TBhuPf|!fVf_mW+|@ zk8zG{a7f9Eq3Aj#IlV8xh6Pad+1)qgLj5JWsH~LQd~Kgc^zdK*UD>}uZT+DsQ;X3d zp%-D7P||U)Zfy=}$ebIO$C8YqiQ0VP9#jF zGDNp=ic_UxiY*dcA1=G&d@5)^x^F ziWPdKK63KmJ9x7E<3UDAi|q|4NVw)P=_rz*K=U#Umsh74IIJH^-|3Q<5I;lQ?5gs< zHQK_F2D+l|5Ekw{^K?Y3l;Zlhhq6qntt5{0+gu-E6y;DoecQ?K+DFx93vPUD1Rgep zKZi0E0pCI6-ISh%P28`-D2q=Fp#dJ#`$Dvzjj;B3ETH+u-_;aMi$;rz9+t2I6?G}m zjCGGWTy#|g&@nb!o9qle^0Z|stCM1bO!A)oOh*xoH#GjRYk~C>p!9>M3@@mq2$D!a z7RdGQaXVVOcerYdu95mt^@Tw)00=fuYFau4IV-N3d0?-d%LzldPOxkIWkYkp#|RUP zWX)30rjp#6a;uRQd>2xx83tx>bp=l`KGU{2%XI9)uq}QmPRm zrz(xowdjkgX&O77qSgB(!!ZtS79oWgGby0O=~B(=%x6wBLpbuJ+^o%Psv6Sl%hNP} zGmIyi)F(t(hzmx81?Mh(RmJf=ujk);j|ujAJ+6$6n-D}u5*DHx``Y>@o2Tlo{`)>( zy=@;qEN|=n{a$%$X3u0x4eu-+r|OIpM2JKf@QvskOE;D@lglGq)aM#{R&n6U^Ra%S z=}4|jL`EdrWJzK5ApmbOHZW)q;_~BKbmg?k?JUT|b$p+e_l9;HnW8Rn7{5<#@nd*4jboe zkLaxtD8%ia-K9(jd#^3D!amR#iY5G93^~_Ju&Hsy*j((tkzEql;4s|52V-@?LYm_5 zzk6f|yAa-OlA2L}PO}I=FrP6o-x>vAR8lZGWTHhAJ%hwKdwkF%!#JiOzDI28r*(ah=(@Z$r)#CoH zS)i6Q^2}HbzZW#E2jlhGMJu7JW;|&OEAVB9mF15joj(v0z?Q8ZJfSvOxnewdiWNYG zAbMaYi#8AB7s+-!bzVAkZbm);9|IhjMWh_l^lH&4@qCo(b_uxAn#12is!24pi~sGQ zb3BddaF4hhCaJL7?SZGzYVDoO7A%;vM3yvSq-$6AhoREh-Rudg7{BGP8hMHYJ~Tk# zlCX%!qfpWeW#@=rJn&1$!A=sM-b~z016EoeA?V2xUN-_NNy!ECSyP|C|CW`00o%=; zkLK;E|C)@KmdK8$b-sa7bc$JMtgdqM}JAuP`2 zC||I(OP{2JSKO*&osaUbMsSDH%-^1LExHbt35oZh=;Z^xOtM^5^mau z*m#C0DYxq8x1ZnXVIkLTBm&OmVr@5&`3mCJ98OlG)Q{o$(S#e+X(AaQeyKq?_-R3s z7fkr?AKp?Wt|rB3IWc)(6?z@uAC?u@y=`7HE9U-PJ_r6CC@8(VyQ8M21}Zg$>Q_m_ zi4$)X$Ckv&#~J4qh6XoRSM`8X`r*L|n0osUL=#HLlJ zT&&-XS?RGR0osp=N45xP)_ib#F7NB~P6^3eEgs zEug8ffKvJEG5lr)vURK9hlO<6lXBw%omdB&n&|yNY6Qn6^5{i4oPuUU{?fr z;|(zCLOK^_Kxv?1`#V0TJY8{O+iI zU{`dAO1`qS(Rc9sK_sB`)a>Z!2ng5-io>jVAYzNcQ4(QF5oqs$g``x;hIALAJt+Kk zlGuG_hp0>vjwVn)c&>hLw9Z zQ}iqYj^MR3N;z4Qd29}+h3Pp^t9;NQcPD!gMis|5j~r++0`DR;a5-Pt&0QAp8F6d$ z&pwS3kFmwu-wAUleQuku=RbZn^2a8q9MdX<*_?1mp~^$Li_x9V{vcxx2(2)jq8(RY z)u2d#<@9DQ)7}@L($L5b_g6`5Uh^)c(I`&*Rfn6KWGCkO>x^_piw4bIInaf#7= zSq;^OY}p-^SAz*_2(7V#gV>bQjo^d9<`zJ0$d-lVgfz>MMOknk`PyG(aqBea&mY9+ zBjL|0(OJ$kUFIJaaF9jPW?P%pMXO9F(X4Ow zHmf+NhI7F3IrK-d-3HNl`T(AYZrFCEumJ}L?jBC0|k&+&6ypuJ_+|Ot|y^4oOq7T^~++$7$GjBmUuebMSsnAh7p#%1GqlM?)P8BjJ&bl6u`vVabfJrJ`e5rf9U5~j5{aZNXU{PqwO zz?>XI?{a|E#voW`4xNC6h*I~6@G*{gTB&8+(k9c<*nho%ZQRu6`5f)hvY)KM?x-84 zt|({H%H>`?i-QzN)2@9*757V^kBe*!H?=~10!=L&2@5L!k|^PU@AL4xHF%Jb(4yHG7ZpweA+}UKXU_?EaCKcI?9QYWFz^hG>5`2htPlSJRqclm$&V ztEt^Nfav|~<^9}GaC25(T~|YYB|zG;Sxj%5#ejAH+v6ycCb#Ll7;O$`MXdeEJTIct zYPP935>v|xiGq|;Hc&5+VaB@I?O*NiNz*#u29#^RqXp&y=PM9VPIQO6yA79Zua3tx zi;nBQhiTj zLTP`$;pq0j_#ZOx5BCFFmNgVSt4v;m;J@BmAK21i7N{|um$o<~j~EMXdZb||3=9la zwcla|Ti-wcQykzD0*3Jspu$Nk!O?MjpGS%@2UKJK&G)ja<83hVpIP-wwjIluHlgLu zQ~yq@IU{|0%YWrXSJRZm=8D|*rN2B;B|4WbC){?HGdvVQbR}8vr{Anzy_+UWW0_J6Yq&MbRJHkX3_(8PR z%_B+`<@doBsIdbGcb!Kg;ChfFKQYk1UQPSpqCT)b=3^F6(OA5EVRtr}0C)&fNkpUB zV`!+d}OnqxfE1CV7Q_pRS?-FZz-$T?VG`l z#uNW>UeNpy&G~JXVEp*p?cOUypF%k@UbQVbSghB989Mf~<~DUPwyGTt3Ux$Qs(94I=#0&X9%f^R7_{bafN#v1^LG+$D?w2VID{1d}M8Y*WG%5eoj5^MH&f7RBIp zG`U$I_dBz>v^CGCHU=if-$ip;?^N4b{4AAH`oDaPSdXX8oS7UR@haLLX^0ySM2cwW z2FoV3w!sXL{=T?dclbO&w7b5xt2Yc&M}OtY;p7C_n#-94&`%&z6%shvP%n#?Q!3>of~B8++R{`- z++J|I!G=#`Ex6NTvCi_XQhSNLE=eDxC)IWmF3vX!^9>m;NW0&pm$1guW z_uNCx$z|al1jcWjIZLH-MO@|OrT;LnZvSqE&6v-et1z9rM(--V2_(VFN?<_sYdxqE z78c_b;Zmg-Ix*)6xuIU)tjA8_D_PDu*`1}M_F z*$+E!rC?AZd4*R}E4sXj`cVsMLRr#n$AoGAN#zC&i3wIQmx_r?OPCXLvSu1+%^D^Y za(s_Em&*(>&ZC3m9D>Jqp~8YFqlzoha(JMnX0bzp-g?_Ic>e<+3r7gN4-xTvt7QdH zAc;nGM`YS30j}kRGj1gd@XAh1P0d-dMz|`gCC{Eet!}ItIv6AXFyOsD&=5p?ePj1< zzBX6CwI(A*DFA3j%&D;se;3(0C|qo8lB$zxaCi+8d6$c)qWdh{VcN1kg=l{te17`$ z3i!Ki&8(6Zqnu*n(@rT62)M-lqVc2E+CL*fsI>b&`CKC);Bk%QE{h(wTEK~;0lO@i zKfE7spN}?Q(KfuV^iE3kTlIa9dJ4W+&L7wKodqYJN)%VGGV%1>O#N2#Ok$&nXgML6q#?DUJp?LR~;cnup@dPme=U@l>A(sst$c68qg_ugFn;bQ)fdf3hr%%?XJevOE7zKSd2O-ISjUOzII^B+kX>u9lWL@RS;2vdy0$rC%UtTcJ zQEM8_%T5s#y;}fATM8u4Don@DhV*cMs+t`E3yd{kdsoAVIt~$3p z0&x~w9yXjH>HfSdcYh6Qx?PjdLrDE(bLHQRaS`cw?Tgsxc;twuFqxud5-%~7l8YmQ z1wVBhGi5$ndthK$Gs^(WS^ch-~JeaXt6OLR_Cw`#=mHsdv-pzs&@%H(TG{&u{PYejI-d z+)aO_Zk>cGS4t!OGRb+qsYBQs9mvj`gGc!Z)9<_G=%1Jz+^U^$>0khLvfE|B*4VdY z2WHst!-E1H(0+SudmN^Dr*pnix(UV2GgrAHBJwka6{z}ge+@2{tGvuzec%HW*J{s0 z8!Y%>A%0cxUuIUR#tMnh(Ec^{#buc?;cj%{4p^@16ItU8G%+Yaz**VSSyXX{CyacK zi`&4N)!M4^7t_iL<~09bVWN!&>XeWSvqoB=&&4irDl(i!oh zsT;pGTJ^g!r`|iuzp}fJ=_D`(enYwxP*i3A?C@3|Gv50zG16uZvT=BL=r8jdzW=u~ zr7yFz_74gg2BW!Gg)Lt7pHd<)tfq=RheQXzQucI7=>MwqCS zSd^{#($+M*;v3l9U^oiQIrHaEQuv*u;KqBP^2SHFrT4~7suWbyuvA!&9TEcdZ=+QZ zFbH%0=%csC*0{_-N2jq>`_sxP>qc&0^yAJJprCHDeB3-qKHYb;y8kn~GQPqIm~yb# zFjTv#6IzpMX>T&x<>4Wjca?3NxTDVeCafSd_}eC`iBJ|?k1tn-o}dgfz1!?CrC^}U z_2U>{Mb`L|wxN4sudJ)<`KlFnTS>;h<_a`Q)=5KI-C>#2JOR_U%E!jqvm<6}-(ZL% zq>d}2J)fY&h4x9En>R!ISKT*cEM&rd4m|_(-&wJxR*?)+VlY8{sgWq=RaH0|9t`Ne z#mhxZDkbYz8+yVU{+v=|cG`|L(ICMO?fkNB2z8-&Yr z-kubA9@U5ZXCl6T;|@#&r1rH7R$|q^!_L*TjNVh7>oNx3YiLt)5<6wzYW{Xam%|(z z)$0Dsch#K@*u{u_;1Jp46M%A5sgJbWLW{m!jczrh*VV2?x7)`v@97VW4OE-To(pn4Fq>k;7e!%oAN(1+!gzf9-3Od||`4s9Dx; zLO9}LVl)-2c5r&E;=Nd+TAG)Cp5`3-R&c6CR<`9;aU4&->5@oZHu7_>S?W}gX{nC?pBJF^I%NA0#tR!{cgW$=Fi`=%y|VX$V)WRl48s0FlUH4K zV8(LEY+*`|Hd~Ox-F%l(5fIj0xsEiehh4cK4FDKlk#aS15YZfjB9_63qf9q%u8ZS< zDRch1b$wlj0G{w)|IS`eC64jd=bfJ-{Y3R#C97trizt1+8uhm`@;zVK_ za4nl?vQC5SBy8w+YPJO>`MJZ?)YOTQ;x|kck#q|QT|Smgn_CwCs?;4^yuuj_I%d{7 zwEXFuCnO<3B@#GbMG{s2L0nk4S|K;z6zz;Q4W=}V$4HAsB?}_|A}~5U2$hS?nMu3O zm)QF&$qi-DcGogRy>ryoQK&?rWV3X&twG5_pzrn-c9YBK=^wWB00WySiJ`Ts4KTvY z2~TD5PG5PQK0R+7e^E$gkzvQSRTyMgP>f#dBKqz`u~px6Uh(w%d_;5~B&F!^V+o=J zfeYx?P0SVH@>!I_1@cRV$)cc&2^m6LAO)jflMaYyDdQ9b?JO>9A5#H-oBo?na^82n z^b3qQXgsFYUqjS*!`H>wP?OhFWO_D4=k{^@9|# z*~>UT>DKOK|GmMf=rjZe-ZZ9vc%SwV6ZMKQ>LwqV77<2O@^XCD+Ga`BaDEcrh@uVm)T z@0`G3Y&Tp{kb)59$%NkG6grug1&!eOQ}S=b!)`-Y*P>&cuHX?O z`7=*qUp=gN+vRw!U+eBtfM;MEq+O1Tnx(g`j9{=m&8%NQK&yCt|omR*hn+x`llu9Elts@<`Dv z#NwAB$6-*4_FgMNcMs|xuF==AGNUm2yZSbh*YoBz>Hi9^wbkvX%#h^sK|MIl_{4&c zFnaDm>RX*(@oie%OE?o3GV4ZY>t&pw3qt7?r5cOU5fyvJ#$e^}=FOWUd^x^lo$LGj zsuXzpVwO&mDvlgBAlrw56ucbAe*WWT>&62bxCiF&m{#v5^}_U|Hs(+UbzxX18%-Ef1n}p0cTdmGA_GP!ydOViub!~s zAq~xpKP-pPA~hGi&a@j|x=nBR53W+YzZxMOI?=Q=Uc<+H+E1X3>;c+T5gN*} zgLa@bD#L;8c+)<+4X@@iD1Ww3#5F0l*4g@=LkJ=m)bq*+!O0+H9kV7Z8y#asR`zSK zKViH<${)TJ1KZ8Knadf3poafrzbqp{2GF`ZLA0aE>cpR za&$}-KZdP->sa!NG8%eazyn3-x-MU_>gKK(a1gO$LQM2cJ?(}b%5`bC% zNuBi1-=f};U&OeSL)QTlYLU`3X?}gJ{Jb`a^wl&-T_e>an#G!cyCj;n9T&l$N5ICLD%2kb;(4IWi_wrN|sP zE)2rPTI>>pn`)P(m)5y+O7(=1*-doQXbzY2bo%-#ku#*Jslc>2=>8;!-zid`Orv_B zls`rFes)7?tSh!&F8I0sAC6-nFP>-?x@10`Jxi&mF-mS$CExrYKH7nZMwl2fkVhNo< z-=)}gar4L@A$*VyqYv5wqSG{r;$D_c1ws&h2DhQA>T0yUp@qqcjtk=T;)I&4Rg(e^ zAAXe=!nMvHsOuq0i)lLPN{^xfE57xOzRVi61`%YE-}zO)56p<6l~VzX9krrG30Zkm z^6+8&_P!FH53_9dGq&fM5MF_Td0PWSKfyLo@FtE{+kJ$B(?o*L9ntqgzzF@k)SNA1 zA=um=C=2pC_H4tCerQW)^+q<2wCd+yF``8N&{#g0LUTsR?{)=4_AO(VSu|ZYKoEX^ z==CVqBt-_JM4Js+DbDzdi$X#NX`&(}R~&C{5}h_Xm3 zYy&g6cw`(=DRU_CW&^lb$E7-2_ZFtrq6?+5+_4g^@p~Csa#rpPsu(=T8n`JMDw-e| znJE&pGR)Fcfihc|3ai|>$q25Nu|%9qN#Q*9=`MmO+m>OC7pm7W!tAcEOqJRajJQcc z4EL=Z&r9u}+BRoMf?P!wVd2I~(D2)8{jQHk5^R48et68^aOx4%6j$wbeUhHVCw0*%d(lorH&$>1;uHPkj z_c*7$Gd84)q&|AkV+Tx8>*7+X@b;=c#&Uth3H<6c1h4$b^BMNX_VgB=4R7v3qew2<=yyP` zFQ-l?Y93cf^#lSQ zCTEwY5zRM;tP~SvFo~cdZe7CZ&dH)IuY-%UGL{`diOe75gwO(gBmU6P0ka@>@wNa8 zwU54V{WP~w=y>QN${A;BIkZW?lwK4*L{Ow4uCY5h%PZQan#%`0SoNj3H>;OfL;-vv z$tHymsCH4S>V5ODy`t!wGa(ljXkIsRxWl6w9|zV!+3Rh6$!7b$qlW(SO(HehZ+{Mf z^F~GC=&W*0<$19B%q@c^`XW2Y==c0-2Dh}-rP=O=AH#Mz}2m@bnU#m_Cn46WuS=?WRcV*&KL^K%`vGFq(zK4hG1U>=C?>ZJnzuG@0 zM%4e`^CF0Nr(QFeN+JfAhuI@7Ts5E5I+HIaUy@T*3JOBZ1?WL8UxU+%yzS4OFVk3w zc8-k#>>QIXzbrF)4Q0AgF)8BwsD1l7zBv%FeO{k@It&G|u7T9#w>);fwQO*fLs{F1 zxrcNvrE`r}1{{E&4+gLcm)7`W6s$3k-|H@hQm@H3omj7@CB`e)19CzPvM7TYNByjq zoAnQ>q1cv@9(EboF%d-qeEby-Tt2K|;RToYfdM-KwAIMVQNz9&?6@rq`k|IzW1+_7 zVY9(%93<0BRhn+8Mb^#V;weFHhsjZD8a58Y5V>WNOMu1$e?r3Xf7=N+fy`OIV};_4 ze+#G%OO|goIq+K;&tn(dq^??uV$#XN>0Ws#x$wa$vJ;#R%lSb&X!N^ z;_TewbxsqFfG`r_nSzD7K(F_s;LK3O!2X=#JMvT%?F>5fN=uxAyt+$q6LKOYv@B&! z4*gGh-D6r+T^S@6VtluIhKAtI4=-)+L#4G%+Kgkm+`B~338$V0BtpfJt)=yj=eY>H zhiI(mU`s0-;Ahf1fz77F%t8)FgJgl@gubq+|`f_Hq zPhb!oBi?*|vyD->%~$4p5riZOgsVzbf!*S_Dz!~22tgRRtAGZz58!y}EK_9YKifLG zTM|0-==+^>VFF@>h4-+sy=lOjhB5DrfCmB@K%}8z!z8J|x&-*Wj6YO46Oryk1-H67 zg^|Fiol;b_G_q~#3Rf~jK9GSbWYYqmEJn}C>G0CaHHAo4bxe{3Tp~%vP$xhWR_z~M z{x`6OBG%+&1QpyA1aiw9Y!W0HQ8ga%oHCGto!SlxZD-Hy zY8cz-N#DY5rR5BJF{JO*0v8L421jX}Ni1or(T4Juu`KiU@Cx}%6s9bx?|KgJEV-S7 zs8p)1p}N1IJTKvNNX@4d&VvVO25Q}?d@ZWA{$okdPIKLPB`YsgY|+y@ERNIr{X6FdTp7&Y{;K4iC=tj@MhN_m`XxllyM* zmwvj>ym`O2T%6|ll0ZDhtb&77^@Rh$81B)*@f6eMb+Mmrmq`TmY+Syoc8|9Zea7FB zO#{d1$%^>wgp9JYa{VwGp4->5V6&QZc|B@`2xE=qd??^S(hx>qQXv@f7s)iWNz~R! zx7b58wTGEg(nzK22nCF=`#Zfv-k_vhtnFOyoP=y*mTW~#%>O=-H|%qKjbD8_c)yY4 z?8ZeL$F9_U+e+EbsWi7nceth{9`R-HCkh5xyN}%s{S}EM?@*l%xA;0Ij8Vlf*wOS# z0%Zm!%@Vw^${uEhWJm=L#^2=;60p28A-eQDVDKmI?}!m9u7}4@>iR)fa63?u>$&mi zn~&q1-6%Glyje3{lu;pUQ0#ch3<|ukSPnv`&=FFy#>VcTSi@E;jTO_oc{UpquM2|b z1)F!W$)!4ocq-JNp}J-iyLopRp6|QE*gvFSKDA?H>IR5l=1Y45VOm3B%McT=#Z07% zQTGU@Z5Y;8{b!NPVPZA-meC{p@NPFSPNJ9{^~Hvn*S_Ps{iA%CTpRLE((ZQ}{L^Z4u$!2xb^$3P$U~7)atvIdzr-tg^f+Z;W2#Li}8m7b* zH0n9VtyV)S63 z?F`+YLbYru{C$g)vBa^;$FzT!R;{$pO%pKDijp&h6+vyrhdS5cH;EI}pyLZgn%f6} zbF)$XJG@~U1U>=+0z3N(P;jL(wPSqQVYRXGtQHLk47DY<<0<=XoxaiD{B^of*n)uZ z*vKdeAPYrDyC>;lm59SO_xG*V($8gb-$%<1?mzC;$`>WRzGti0w=sqjn>PaA+XSFV zz1c!-1&|aklr!85WYB~I^~8`?cFZ$^EWnyW`iVF>+wt)JVXC!sYRB~I%06=i^e}?0 z31u>}kM8?ip;z8++{u&ieLMUeweR&j9;@R<|3pdwX>XSuZm&UyCxtcQaBnFQTQVSl z5)v-HgRrUpNzHM*Ko5uc)ib*JgNJ;4uk`J|Nmu4Dfaa$jDIvTZUY(tBKorxtW1Cgq z%52%IVnsN~qRAl!vX)D0h*MwKmpW{o%Gl8qMMi%U zmf|^2cA5#^Y_mjUDR3O6s3gDa^L{p4R^;e0M7K11HPZg_qwU?u}z#zuAj#Q0v_kmwTcD>X0<+ciR38LCs{tLihn;*5EQRh))aRb=d7*?SY^iM|`bW$#JQSGom6UCo%7V@Syk5nEGq5RF(8cP~j$2{7 z^}dZRK=4DW)RVajthr+!94hf`V)KD1BNvUX>mKEpHq+qlUARylYxnP!q3=}jzkmM# z{{!9iS$VZRU`TGUJ@qd-QHp1)>h6{M3RSNRW?c%aa%jhY{rE3IRG)Ed+N3eagyx5V zj(i6G_fad|$M~kq`@1-Uj*3fffOqx!^V67(hsE+)(m9*;?e^DMwd+j~ruaNsDQUpx zH(x?{m;fXq(*C?G0%}wCKX(+A=S?jo^IG!IxMJV14C)D^YB>ZT#y-UkeT{XTB^pI6^cuP`=J=_sC zRNvd@u=8M7wpaJlt~^s5S%Ko4B=&HvO1^bov-CQkHE3%KU)|zAxlBicL|p$(Gg{rA z9%qj8%+A&}R34-fI6)hM9Dzt%g&9$0fIDN>e@#QcXGqxHx{0`|jqw#4XA-rjGJK%7}d4QZ$PAIZYF)kM` zUoD)!K$AhmowWuN4Wy{A9}kn`vEa`*w@UsE6_4)bpE9m%Nu#%)4TUtcREr^OT-r>~ z0O81;TJ=4TS+k>NG^OhvBHQzp^86f^>vd$&fUm0iu2ZVy#N58*IRjkFn#+A)T*2Qo{R6!7<57;C*AK?Rp3S=+4rwoTyS5avCyx zG9%LJ?AL+!&Rd&d@K;6cmt;It%hXc+_Q@*!a(J;8;8=diu+o9DEPY2Pll7QkY;;If zIX`Wj(pc6G?7)y0Q_aINrPw*Rberm>n>?VR5yHqw&h{h!RdUl-THa>F`1o&sUfb9k z-QlrV?wz42%w5RWQM_#rg0q(jeuF!b@dXJ5Nyi`Ik#DLY0=?;U|63SN!_h|t@m+vq z1}l%j@IWM%vk4>*7yOjbV>x=o!)?HZ=apT@^|qeN`BP5cOc1qUERCWcUQqfdFwaP8 z1o6#t|FrwKq`G@V>QAT;_%C~Ax7@VRNWuUyi!(+6icv>Kl0QErqsG~%f&>PLJ|=3~ zw+%Q_S7oC9k)#qsF3p%z;Pd!I|0~GRZ%c7-xK=0@rAS!GJ#%WPC@_j#DDuj|?RQ)t zzj_#ba>45Agz#9O;iVjBd={gz;yeD8hx`&LC8ZbJYd$d;LRSMc8HDtqA7&faVuGRv zI&!f3*72US^C{?E+@?v}CC{DJ6UqW>PwR&7LR3>2%EMF?REhfk{wOHZpbafV6h+Vl&=lzM;)*+Sdr|z7R!`{? zeNnN|H{zpxUA4y&7pipc?)Et>O~^cP>$>9#BNDnR8$+6=T`t8SXiVz z8Hi*cfrGS8rOD8A-Yz|26zqmFOTuY93kh@OAUjh2r%emo(i-q@<*9lB`gJKA><1$r ze44aLqEk2K!_X%6R{MEsJZ!34qic2X&H8~IUgTh!1Jr1;l@cQW-6YiFiS^&^@<+!yY*~-uGncV z(P@~f%#QeF<@+Sp_@(aOdMDr3*2u|@Z6bx0u*xtMk~)en=go&_ny;QEz5t;FH4ha$ zxG42N2U7I^m^urlxVkP%2MF$gV8J1{yIXK~(zrM7?(P;`f&_PhySoQ>cXzkB?>9A7 z^9Lws?(K8-+G{<_sKcWZHN9;G_g>gNL?!P4IKbCNJ?m|JKptDVXM)Yh!DJd#+f4&$ ztQqAMHfWUf*R0FcY>#7Qic3~l5+&}9ypLoZ<+B-Vg~W0htRcVP|r~9R-a6t&R7V5ZUV54YL`qO;-NRo zu4|xeS;o`Gv*$|3}6$K zr2*J4kP9&Owr=MO-%Vf3B(Pa+8`ftM`UF^t0CP;%d8v0YvEu7xsNn7sQKugTlm%J? z^A!uJ)vx_HaLH)lwQ;PgBY6g-(9KlBJbVEhq}tem1zNyVgQ@Xmu_MR)LikQxhV9z! za{US4`y8BW*&(H*7Mb+t%4NY-OdkR-~LSA6;Xq}JPjfvj!XwTw;`+K=?m2I z$$uuM7AZ-0BeYdaz>RquyHm1preM7|pkk($A*ro^&!jjfyC8g zlV+4SCa7F09?;*u_fU~9q_3Kp9!1ejTFEsGnHaa0A8vD*mP6U{;bDX_YY@5zjixYE z*VM=wkM3t4W>~UkXt&t?DvR|EBaeYs^>dK#Ua~T+1^)%yVY!B5^%r^vud~gC3%uKh zmt8PitNjZh5j(DlyCV`1G&4d@Y>zl zG~6x_ff>&wxwy8ncXYuwj>y;{q+I(Q!KpIRU63#qv9ydB4tUEn=}C}&1XZ(5fwGv> z3 zy?Gz_+kWij!>j8SQNjMT>rZ&?u02YevJ=G&`OWQ^%nDdc(&dh$dCpuS0rqHxDfKuo z1sH=YJah1bTtw_@x-Q|BGZir4UtDj7U2-j z^hd|`3pu)dIb3|IDLn)MNwUTe9zBCjlVp*~yaW5sPiY3FX^wZGRs)d`svkm_gjXv~OKS*D7@iy4} zEt%kD{XpK?2S(G+`Qq`Taq%W8YyZy+z*lUv%^_@rTi+u8cKw4K%os;k!IXsX9V-7H z6~9;vh4G74>KSJo@cf5*2IYBM)S}=0GF|4~{zWM;apCoxeK}MR$yU9$K(EiMP1~{jXv1k}44hNo zKPM?u`mxH*%{?8IDx&Mo_gcZNY_Hqea%WCqi8#cly4lMPCujqLLh8mwm&bipg`4Mj zXHk0nTyU7G0UJ4vlPTN`ekS-(Q6Ex_C*zNb(9gK>AvCfdbqHw|-Ca2At807Hc9N^+ zn7FqhpES|>ttV{iO8UR8x_kE3@<$+W&pX@xqe1gy*A#iCu+#GN`JN zu!b1VHPGjxgR>B>g!yI2Z_2IjL$9%HxQ^Z z2ia`2h@D$3;90Mf)C(h6T2tDO?KeBJ;UV{Q!9*8=#FI_1f*2+|3e7Yyp#k%W6A#I_ zGUC|Cr|(elTz}NdW-J=udg1&)JUtC`5dIv+x z%M^JDf5W5Fx~QHZi7^Vo%r^%taE7+F|J8yP)|Swp*u{DuVU7S^rYB;_qez;g$PGOu zX`s$5Y$u4X(VrBQwT40E#rd57w!b0u3Ky$1kP!>LO z7B%tUDAnH$c0gg{WE$@v5e=tem`J7dN{ikM7%Q0#x;fB7NYsMma7 zebCWLdk0Q#_OUy#%qDpC8Lk3w#H5#|=k*qu%?|T2NXahH2@u@I-qTYA=|_b19wKG6 zqPDisC|`)vT?f=DLY$4CP6MPp*H;GLB*=>jCrf^hwElWlS*MN{MxlyZZ8Y~PRdK@ZC*w9zf)sM??C>(N)55;^-^xpa ztqvo2SsA+`pH9Vca-yaO5@U*9eiE(Yp0Bu1H^Gs><~`B05Kiuk@jZ&9;$QCY1Z{oDbI^$a1=0*$4@Bda&3<-)z+<8J5+#l zH7QEIr;h3L7g(29RH6@}XWC={3OC>$Th25RV)%J^zuk|BPjDw$n>bfrPg=SzQ#pDh^Ue*{vc&Qvya%zDV#Nuk`)<`>x0YFRIE=Q;7ihbAN3V0vt}Ll zdELprJgwc>p%irYpE4VQLgniVzBvfbjqC0Gk(+PI%CDhe*0>yVEQdL3B~9(~`Wg#l z#4qemDpttr(+i%RKUoVS%EGTpZY?A;=pqK9eJ%b%^(b4_nc<|GC^TmFIloMRH zb-C%6!D)MaKd%mrpVep^`=JxiBvu$_S*1(@jHD^P&n$rJkxTmDvS~z=M4m%Dq%aQp z=i^WY2o)x3fUJiqf67X+Y5@_fYv08dKsUa) zu|f$4nVh20^n7SEYsu~)CtRxd2>}ukUW3Rx@#Dt#L-3LF<5->EFhThU9)*Ak4;``WYbG!NIL z?+cgs5?nZI=D zO~9k)7;o&plRw?yLzceQUd5JOAJBUWpQ7!*@_agao^{Qoe~fL;}~;((`Qa)r(J_MlmVl>z@St4mBf9a5)m1j zQF~JXz}OB7eqeu$Rk9;dEC2yl7Ch!r)4CKMtV4&TUjG^+=1h59lxJB=*7zpzvMEy8 zFChu&RG_~e`L)zMlje=fR^?R*>E&)_N2dxzeOnT$a7SG_h{80GtyQB@j`cUcK`S|g z5`BM&;gRf#CGFivzQ<`Dndq<2mr8Sw-1w>u=4n^E#FUK?s-81+=vES81Y?n?VDc0j z;mOP{F#cO^ldY+iS~imJ-e?*qwpT>-JkeCny9QOU-u_^;_t}#!)!!q=K!$UaX9|HTQ4L;J-CU+3$-*%~E5ddhaZ6-Ee89 zhqC&)|6r_)scWau9NoHh?Xuf80;fKSd#559a5P}w2~{dB#?k*UvjX86OM=~_C;6|a zeLhq^64k%>hp1ZC{h~{@lnW&T+Uwl^OE}rT+^m@`)P>gQ_x2YwO^CU(@+; zU@ReFyF=7jRHu@hok=Kc7@x z5xw_*j7NX7O@6`cB&O_Gafl}`T(g-vatR|n!N?jnz4hQnK}9*b^SECRao0LJXnO67^cviKD&HTAEkq~QYA>FwQHaOG3z^$dVGm=CLgr(xSgrQ3>E8Nt>`6h>Je{Y#d zRxQ+8$-cbwPnxmO2(31|FutC>bYDQ7Q^yEC@*ZYnOO&r^G$!N)YMbU}4+muPbIQ)&#W@cs|L!K@UGFh(2Ex9Eqj78tBJ8l>jXi0P63LjjJIxva z!)c~G{o*mX;2-E7cQ!f#lHHrHNW;u#nd9}QS4Za*^IgM3wMe)$Ll@VeA{2f!Wz*&s zX%p!7%;3CWC_0DCN&bX22pK3dbnSc2QRlChcQJ?fdDgS8$zTr0e~E$}nd?bZSXrJ7 zzJKx5I5{sV{ZZ%I&Fz!jg!-obn9Jp3R+uJeDnlVjDc5#z=sdN2LPuDxz>>mG*yA=p zL+f|_Gp7RN?ZUQG0ZxU~IFHZT%JPHQ7FU|<@+80M)hgtX5TrsClD^Y^?iYG?&Gso` zxL(NHdZA(`(A0c*QMI3D(TodjTm)AH9He=sDIDMBw-5**q9WcN!?CQKT{>;IAijd6 zUP7#pQ!QHK;GgeF_|fY9|mQ|owH13x|v`UX-(G`XDNO$xlw0m=bzPyxa`2n6~wa~1%c*CIFt zv&Zu!vqvrmxej?$+tURyw=o{4=jSZ=DDZ**l%ZbeCXb@18rXy1xZn+rmI}~zc@8c& z;~H(+`|s~v?5+QvyvzU~*Up#LPMM;W?@>KQGb?6+iX3IT%XcTQ;~MWFw%#vV$L7%4o{6VB1jObTFDnI&wP&tH$t_%1cMXkr&mdGGZTtq>?1{%{TP#yRh^l!9wX z%ZiWj?{D;^L5hMe3o?H5CZ#ee9hEwYic^9GJ8C8Z7^`uX--!L0Wp)0=-zJ_&Ya%?Y z&Wk?OJ>uHU@{%HbwZ}&*OWhe<`TaX_%PmTIdj1Dx{^{>yQ*wV?bBh;ZG>99?ywBzY z(>-RgSu4#X7c5W_f0%yqnp}Al9C{77u?S24H?KDxa5dmXL*sgeN&rikf9X_kB@0$C zN_kU4-^Q&tOgLoH#tToG`~mg1ZztMq zZog_Xz=+=3mHigrNv4f#*4M^bf+JxovoVTSfg|#j+E2SGxwvwvbZ6vbfymXxUtxXp(>2Gh1;^zM)I+1Ou)O`UhBd-2}@s5CGqF zdBey99Qu>~rhmgXB9{M_iM|9)-Wt=Yu=2@$&%Bi5>`k6Fz{1qVZx&s8kP0IJ&fmgr z243D^$5YwR%aj3T%jcUFQxOuWg+sW9Psow(*!l^7gI-H-f+f+OYt}Q8g7zz#lr{7< zTz;)^aNpt#bg;lEWTE*4RR#+iMi3mjwBNsCZ8TX{Qlq$-2@nF>@_Dv&la(I*kVCJi zM`tU)>A3x`tYHkEnAAL`GReSxVJEl#i_T;Y2GY(K+5!?SvB~ z{tTvXw?ilo!>IQLzNjeo^r;zgUB>eicZtW%P!7QqqG+UMC8@BQmR{%Gs5i}&*`!!P zS@F43Jfs>oMUhkbLo*73;|jWN{(0-@$}}<;W~4BA5Yj`2L{OzjR9CGj!7#aOU%K3 z5Fy<^rZo9DWwd5xG|h|%>6a((P~az}r2O}oSJ#gf&`~9$-lGDw-Z2n`Y&B6T2p0)@ zAOG!oV}{{9IWKK4V?3d6I$j#apz4&Rftx;Dw;3NrWtO|{c;1PCQ91fMG*hl-XtxlDsaIY9 z;U#_HDE+p0#_}`><^^of0OgJ$i(o8S(=$X{MMI+jKG&uEI7#_VNg#0k@bmyX#Q#)j zy7ln32USxE{9WtVPbOm@4`0|iQf8W$12BA+I)fnoFn^V(R>-;9EWF9UhP|OelG+Zs zawH^pGa6nk6!LREenHtIK0&%o0By0xUD?ossn(%BQbpJbKS+A)(? zFptVYclHE1UwIIA3^(N_MsTA6p-Ykf6^kVH=7*PT+m6FTfac?0R^?tQa#@-@_4^z%J3LL&BcPDESco3G+8e#2a!56kvO!5$(lMJ ze^bw3MfjTGPptfYR!Ar#^jV$TG?fufIf`f@L4PW2Erg|5IT;I-lWXS2l~CDWl)CzX zrTNpmoUZ%cSAgK)UPHH2zo5GVWQ`BT(pa^d9SZE49*gDlB1aoa;-@M{xf`3CrLrth zP-BN`f13-`>sQw4zu7V6teMXga}EWUJstkm6-Lu%={;X(*m%Ehd>Td+ob6eIjRVnPKAM{PEXH_>f_f2v1g(|HOFi7SmK<*j>$tJpKp_;WhE^MlFbRTG)|o%ZqB)i9cxXo4gqXqDtDLf?6IHRjj3o zRD-X{hFcK)>hAICG*o4)uwJI+4zdu+BZmBVNbbql9<&SY)rG3xYYUgLd{Y;i8B~rw z8PO$GV+If-MRJpl^CgJdTQ^SbiLf}HWyu#siT?=6BWbkVaOkF^Z_yc*B&NazZo}}s z?|$v={G`}&>o$$n_ZNmAaNSdX#+$;o!%Xv}^45i<5KqlATQ@VOsjW-sFVr_iBIH#v zNGKr7Lf0tU@f2#K-U7W*P*5u{+?|5~*Mz0U;cvdi7yEQmz@Lb6|G>@Ta5o87aY)FU z0vOrjbmMNF8?yrc?h`~i6_|sJ zx*tt3Oka0<1q_tgpKdcJhz@l;#hmq!01HiNGzcK!v5@tIrRVz&s=TnRb+Un1VMTHp z5jEbOhILT2B2~)t9AuS>_53am!-oa2c0D?=1onbU6CH&^pCc|8u8^@lLb|KJ>9aft zQ=iDq7(L|5HARvZNd+4Rl1=m4&TM!@9=)SHO$kWZ#)|V4Rul!94;a{r#?wsDRosNf zdd1&lpvIZNB(A}cn`k_*XW05a>0aSP+QKmf!5I!2jQQ}`=(18x$6fkV)6IHZ__^Wlh^%{hL}%?xjpKB^`h9Cd9JM|; zy`r(4Dn|{S#3UddUb^oy1u5qAyz(4(S_8Wr)YnDFAawbK<*}pHpERc>$+D2a<@LoC z*3;UW+rY}LzrvbB&o^+gQkO*YRFP9`heCVN%)z{%f6E8eyGepJ2EAlJR(v-P;%Q6Z z>74`LD)56}Ai!&TzeERHpSV$OP8;Arv3*T1vpmz%+nPU_2X7EU}r!aq6q$DuvD zjBo0@W?y(ec(y$+pF|a5#B-69^!M2tpY&i^(UmT?PV@ahu&fN++fIq6eE8ZgDj#?|>symQ_i{(ugpyyW+Z zhA)79U*+dX(2WUJ% zvIqQM9_<1LJ7f5Jov`MiKQf{{ot*m4&;JAe;1lAr$XJ_0UufKVf`8#`y=gpnB8;OjMS>ClaN1>xaI-XW%nbDC%9H)pNpWFvb(E1r0MW^?Zp~ z1jNvHLh(dbEwiogv**o`H3IaDl2w(PHWldSZY}-)mf%kARVax2DLJ_7SIDKNGEeEu zxaK?s3%tgBxYK5ALp5pRrwJqCC3$F4J~TvJn+~!+x!%h*H0Zb8Ab?LBWzf-z!e(+@2@BNZ6b6plA zUw$)oH%TkgsDk8R9sH&R%1W3p1+0q_M$q=gweW#VbX2`v%A(N&My4~=2AE4j2UMgH zWUWw5#cfMg1AtU4GefFUJ!KZx2M=VWWE*El;H*sjrcKzg1XWYIofr~|+yufCzv_ch zR2elri*|Je+Kz*Y+YTDhPQuU&LaQQV!bc`~<0JBB-7!YM#cm&w<-)A6Y)@6mpfH=+tu}bf{67^dVGG79QLHiltZ;G*=ub3yL&rgIS}GlgK#8V z0EZ~;Z0mtJqcv$SOx_eqs}?6SY$Gv|;mxef^K?SXe4wDRH0gntvh-8(q`$C_Jh4z( z#EsOl0FUoGU+-2Nqwmuwkalx;e|7(FUpZsN5w3GD1T0~k;<2ovbB9a`KXVw-jMn6C z@QvSIUrP%oRo0VC)^00KUp#=cbc~FQ@^aKT1|Zc8aG26$OBPPrZl`5lcZ0LhV1AVi zrY7u{lF>;pAfka$>wmLIB z3k%pj-{nyEle;KyD_X3NvmCTOM+Kj23TUZ(+u3h9fn~mU#lW1I6&Q!?($BfvoithR zeNCs1V+BA6RhKH*xJ5T0`iuI-MGTdwvZ;_+e`8HcVE-IJ*26^XoHl?($7I43w!kge z`*v_x*2V2rawy#iGwzjnxQc0=>KYVjXsw32W3nj?D*d!o8)Cgv;2f?wwvY&lQKm+M z$viM_J`1dcWYKEO7e=Rms)^a#5@@vc~t} z0oDDaLJObZp6+|+H{MQP+l{4$0-~50$zyilraQPaE~mk}irLLAAt3>5Dgeuw#;4Mi z71zaepNzab!bY1;u^dQ>1ZLn@kfktcJ%}BUElMzqL3Dq>-I*-+^n7V^e}ieXwfz(Q zCwUePZeRxV7>Bw@wO2OvAcOYNvaVi`1a7>6dErfKc5jiC1w@wO@&nrqYjxC4Sz;lR{w2C-K1TN@ zSD_$2I$Si-W0+(BI4;2OjqdE9h3(3V#pNmw*gQG-lLAhi^uKE1?|7LsFjcO&ZBskV zCxVl#DH{@*C~@3_%KBQz^TBAar+XLfBzMKpj3;asW##qiQ?;K<*x2oAS$GX#MKswKv0dN>}e7aFSn&{am&=kHim8d+q*7 zgUBo7=!Ws;I1sknsxnV)tjTrk^6*oLH_mO&!>15b{beYEK&d!xp`$2$AQZ_5uY?vK zH8?haK{`n}c80D;98KOO5rF^?87FXfbsfogvv$!jv^9n9t~f-O#S&RG@58cedIHl? z@T!LEuchTcGvxJ_r2Laf+i0sF?*DlK5L8W}ennA(D5I{lyYvM>zbo|0U6a~B^^_1a zo=a(PbS>q1zB~YP*pid!ptcQSbC;%3Dk9(5fd_jG*@j98gT6x=CPjk3*Z_Ii{k8X8 z4@HRur&_0P45no>VzFwPLqkV>S^;azsq;}!$58etU)bW(qDWfA`kzlT-WmgBDofhK zA*>Z3)fgFLhDR!(k~n9{%I;|TyNk{+A;8W64lEEKSr(9Yrj(^f=t0#lI?D@f``CR9 zVcZq*Q8rn6t-|9F9DB-~}+-Ejc zsfiaUAMC3>f=ruV^XGwHCID8HkpZ}_DymyrMwXZH&RklH7tVQoQGRAirWXRaF?o4; z0Qfa#$_jXw^QOW8z1@nZmVF?a;V1d&vsvJupy7ou*ZF8co9Eh=kXMxv1-{gmiFjKo zN88fT;jeq(RLt41C9~|A87S2kyxFSiju)j{U-Bgd&=YzLAHd7prTG49F&iH~-rzN^IEUhkGQj9jX&hZ_&i0*vt+Z}nU?fyY%x zAgJSc5L56E@dsd-1p*mtc+rr4a|28n^1yl#5ad`2emc&Q8sK2zN@X3e5=H|O!|jW= z*9K$ml2^)_YIMv*;`Yei=xUoghJy6JXM(DaaDWKF>3hR@bng*dyTWxK$`^U`@Dep( zq?%m)pFQ{(A=(2f3H%CK%LSk#nekB|GLjnRkI;fh+*N;L#t%CIEeytNcn~3)syoy3 z-+|!NoJDnYGia8#{F$mCG05jhe6w||5@E=&?k}-hHnXHFHly3k)N)@W zd+e}bbjOu~(KAA$2z4yKG$->!kumTFec4Prr;>Cxux{+QaI~}Q0-h4!npc-j&!<7l zK5CWOgP*E>fAAteNlA%MNH}$tm0Mq}+ScKmzx-rO_Lek~DhDnvube(A|C&K~ru@#o zK_;i7>v_f=(u?j-)KsqMuZnv#Ynmfw;8gibk1I|TM9GdMlG1EiMO`J>;1<>YtR2}7 zR0)7Hr*O172bAh9lNOxnzO`s`w(r0k(a|tHC^64PJQ)!=N^h;ATY4u#ra^f<31eXe zJnbZ9r$FE*QQ&4QCi1>VME^x=wsmIsM+(Mfgpi1Ezg3`U*0oR2GKpZTMIZ0Dz<3nM z(tviPzP&|N2})g1amSKPk_W-T+R;DYX8T$lq@tlH($04WUulcHj~yuo+8K~Rw#Bu# zdwRWhdS%)Ao@n(+jhV5DA_(II&sw0@YZ@<@;D66^q#7$!iK@O?gY4)~d66%(++ooS z1>T|KJ02zDgQ|<>=d}J7O8|Ly!1~b(2BO3QedlwQi-e;O{zUz#xsv3Wz4uy0R*&>x~a*EQqCQny@o~dRLBTN$O)EM)N#5_4yO+3C3c&iF}jK=b%Q z$Bo>%GZ7OS^__So9U6I-Ftv*MHdkID&3#wAr=~NIF%HUQO@3Xc0cBLsGK-VGp;gW2 zHgt@S>}9aI*yyV>{9@;k4TPyiO2Y}4XNgyey*gr^f%TL{y)g6`WFq(yk6xNsm_GFj zcPn3Eb+iey-tB&#)ob^_=U2TrtZ0RqHDO3%LXu_9!nf=F6cAD&S6~=iz%!)*->0veBb3ho$aK3 z`orGg0Q%kI=nwa0=e_I4PF{5A7lF_0c$VKpwRmS;EA`cRjB)Tdci@qG{>AWRErP(5mu~f*Q34W2JJeO>`qR&4bl4X1i=z`8j#&^ zefTTW0hQ%6v7xDi?pl$`JYQrCtgYZff2%LilP7)Mz=WuD&pyiC4z^1%J6N$wcW`nW zYWI8yOE5O4#ln1jLS_)!a4%W-1_1Pcqz51m8J8fJ;zx)4&dU0C@&MSBlK9Kqi{IMZ zVu)Drw?!Csi$wdlCw+g`SQ(~VNJ;Q#pKS7NYJ0@f$)xqO*3CC$HO1XTsVgoHkJ=?j z45G_)D!rRoro2FZQ!Se_{QtX>fUO^pYNnFj7dd&Tfyl!UpMZVd>}D=1q6EGb0IxL= z5h9n5@Oyl1D?sfXV1r(vL-4b_eLWF*=N4Z>^_cK|E`}sD^wS**)*i|mB0H^lS0cqC z^j$Qh`RKfPkftV!NJ^Fk<2GKbg2Aq+K|mP=g@ZeCw7l6{On< z3xhWfW0_gMT}v)+z1sqyiX##UJM@&jq_A}eDZ``hNAKEx&C_4Ro6zaftR5Uh*CGTM z?Jua4c;$0Z=1n9D>Y#`;qY`#3RQc4}-6rM)M(<;P>dAmgOD2?0{4|?(!|)@y`iSm zkx-{U&J(-1u*%EN%}>pv={mYft@UO~Q{nSz^Z&EtX?OaxKgwnGr%D_m8nFJJ_|%fi zH>uAAaFcYwwzjB#nic0=cp2_LO=C1ioHE)8Az&)%Dyk_)o-Kh<8mKQ{|9H=?t#_$b z^#L9Tz-%=Qx}cj3D&v~xn*@7%XZ~luy7kPaC|!~@s&Ix+q{Gj}Gw_^PtItlG#w|=V z`HJcL7}++8BYya^F1G*Sv>b4x;yRD+ZV;h9LPoIJduiJE%^7ot+@Ep&`Ok z>A_syjcM$ki3si_sz}7;JFl;<@2s7jRt+`~MfJJZrj0~->Os-FOE(h!U9ghW!H*-}!(W)l10Yl5M(LlWD zzit#Qm+pk1tEg_Xq4#%h0A>RtnUHv8e2PyRp;;lGP7b)I2X?9vrQc^<@JzYsixhjw`my-t2gqKRiC!GziIv>A6^ zh!k#hAR3_hEFf)mPPn!e>HG4%OY2=-N?%-v?pYzy>CeQq~t(vaFzIR zXfbh*Wu>Clil~j=_clPDm^M*nGz?KFRj#2Er-b)lBlofE+ttqoaN;=smuoomr@u~D6Iu;eN)N$V6?q*``bG+DFC#!+}f+-wN~m(AG1{aEEU8&v>%z; zf_S(9$`ZdwLentcvqFtXvO#Ei;LvT_0RC=cQeq5}5~8hojjINRnIyaO2Y8B(Tr9x7C?ViZ=-qBA10?wc3O3H{Es5 z1lzVp`T@Y;ySMdnp0$ERHkn|SS=;LdXHaWVQ2rSk!JnleKZ?@YuN>=po@|zTcFLJz z8hufoj(AB18`kYOga);?kiI;Lt<`)X2ZxG|g-pWfQ&?AW2NT0ThQ=kwmnJyTTXLUG zm8yk^c%g&gX3N|7XbIh-^}HURzf>1>RuNAJV)TO}@1s;kp)Fm@jEQL$Vwcu?#JOMe zwTw%t$IZBm0qSC_>qUIuReS^gGoG(5Cp#X1UFHF*-}nGom=8AaPXYWH0D7M_N#XX( zG+7x7*1)Ff1C9=birtqYzG8|9()97diopst^K>j9q}Jhz^T8D8s4?2Vd+_L(9xhky zs~_R;R6qZ(2n7;1Y5damf{*R8Dcp=>=Fm(YoC?FaG2t`>kH~r6TnYp>M$Ecqd6?gIEfgvHg`sD}|w%j=;dVmie(`5a9J|RO#+b?|*M>=6n{9smw6|kuul~(~ngOYB_twG9eREzuNv5sWHiRL(k5)O}apJuol z9e%^Q85#`7P1R7P^Wd;Boo6OVraUYXn5r$v?=27t$XFdZdlFkA%bXo=NKsz}`T<#T z=$KfAwP_q;6QOgT-<^J?fH`XX^+tMA0R>(Poj9oR^(CMdWE`pUTFjM{>dWgpR%iEV zo9}G}H)=@g9A~uZn#3yQpurLz#ldIh#s%@{_vk1J*T*vAv35(Fm}aN{!P9R6u6$oN zRA-OP!z3`=FA^ohx9UEwsxhTj`@d7!+;d=veV))c7V1US)!`l{x|$9Li+%2q#Sw~v zM@P2Nr-xqR-8694*7MzocB@OKNBdSWA1#|Lq?X3~TozUU z4-j8lsMM{!>($SCZ#B#aQR;fx`0xQhKieDcD;uOpP$yna3$<{sOP(||Zz=&VVj(~5 z8~v`RZIKs+-SkA3-`^_-#6o90q@$<&y>~bCb)Pk;=!7WgN2t% z_9o5I3Drt9N%PEXcM79INtNJ(7obeHW{f9zhl^sgCO&3$(~m}J^=*4%_w=(+L9uc@ zP}#|fNQ9F&HGnopX2WkEx$%~{vA5uJwqP~zcQnhxRax0wnB7hPseOJxw`?Bo$bI(2 z`M(40YH89Z8C%z_yGD>Londqs+J1;{aAo@L0Oh!pRol;b_9ULcyYlM*CLLDpp%H7R zF0SXP>UUyt;8wQtnD5!(h|NInd~1@@(C|sBY%YJvOtDN1cxPQ)Tmb<1JP2rD|Ew-y z3X)DQAh#Fcs;dK5(xiSzPCY>GAqM=|F;@mk5BN(Qg5>o%#zp{vAhXFMh*}*tqbJ~t zx#5ve!C%}~;C1fiT=uWOf7yHEu<1B>J9~+zLMmRcZr3h=29<^x4Z8RdG~Rh+l7~M{ zV|NZom-X)fVf;&f@Gsp@`LbXPfd_2giR^b@-+@eCPk?Ec#~OVQ>~%{$58`pd%b1dNX4sg$>?BLklA;l{RtwktPK=oTv13rL?6dI{UTJ-BscShrk^j)xIf_qU0%Q=$zp8=k}2H9K%> z2u3oO?Fy|J4oIv+eIYXXe8sj?$4M+Fk6Q|_^$vp!>a`82L^1ah{^JzFoW@&-Ou^m* zv@L2-&Jp0GvEgR-xCt8CQSLv!T>b(#K3#eW%8u&6<*=PgsCm-aI>7XH`)&PI;L9{r zhJrs-C5v)`_)M6FUYXSr>XOzR4i|1Bxj*-3snGceZ|dBn@0ntT*f=Vahyo!@3whV6 ztITzMKdk~qgTWPR*^DyjcFQ|fZ!0My#eFLn#`6sp&KeGER7m+^=YbT+P@LE@LFXDd zy-S;<155Cj27;~PNH=FGsBM_I8?18NdroR5p25_5z=P-rkwQ3<8puFBuioG%WlnbB zlwp1CB9l>JNkR`+`t>A8sBr0>os{%-8x(c0L`Po0BD0cVIy5v5Stgs19}ex!FB8ld zMRVw6e^UrIf!T9re>#Q~7^Vv75+EXEU*xiMu**?%Jroq|n zB1DBS8W-MCsoZz%k0d`^1J^z1h{(5~6ILVOx|uM8@f_%rcH|7hq%%EWGOi10<2RmM z_P_QZScjhkY?%{>53s*~JEe^q*12%(*Pt|AO8hr?g(c9~nG4I66#=!sWo2bHlPOTm zSf>^95LKFP2g9VBAb#+j`+NJU#I#K#{f~`hybAR)w>67;;N|YOweC_fmwEE>8({%b zp|+iG9HF5Sw;nna3E}io2lvqZ&U9BZs!%dzQ3BZ4hu4fKW5J~u7E31<$idR0jf!ym z{bMcvR*X*PrZg2de7@9sMAv)3uKoP++bQ)HH5HjiKb{bTmFE-?J;&|`S=~2$HOa!1 zf{TrsAOWG`BU*#hg*I)?Oi1YcGlDv|`#-UnM(mXeLZ>?x04yL;UH(N9q**Yds&#PO z>0wIm^Lo4J7=F<8iPi*qALih^v=|q1lt9v$Fno7e50{qN@0ePxE5J9`w~{mXpa(l| zj1Yt2ad-JIisxR*4iIasV_@hs2gGN|jyW;=%~0rs(}ABJSrx1%KPE>vvLNWX5NW8u z-Elty2%2`pziw*Mrts5|z(Ji~tQ|1EZ!@~z&1qO6>m4P5B700V*V{c)0t0_|9+CFl z1T;snoOm%!9FAU`<>vW<-tze3Mi{$RUunS|n$731FQ{%i(T!aEXYnQoBz$~FWclMX z9N^zXNmFUO9&6P}(@}$DCrX<57HI{`4yw+ycJ|5Fx-YMzUZdid!A9Zyal)f9)Um{Jp_p(+ICVhrx;WBDXik-&|s2ZwqFt>Qzth@ ziEiNj9qWA^yMxL;tFR{YJY}|7^9W#ynlR;s^S^MXs=!|>9}RbS=xg$roTiPnKB)u& zdju848dX22j6X{Di|UmnOJ@IZ1}nAOl^gVi+&|SEpJuMWfd~}qtbzLPPV7PWfkS19 zJiw#Tb*ajHc`1(8>p*I>vM14ySgfu1}a9wa$aGee)qdmeF zE5?64zK^m*aeVeKsGlUut+3z}tGEj2X_}ty!NQ73SImC;Yj%&XcvSOxt##o}m|2g~ zXtTEMJ;^7xPdZqpv=mDN3A(j}5YJvQeDxHCsVApC?rc=L3o%<+GkTTfWO zZ@sgHVBJRM+8uBWv+6d1bQ##vjy~hv250xzGhpDYH|5D(exFZfP=))}Hm?gxL%jde z&-MkyxWQ48S}gthV~G%)T%qzb8$kbvC;tH#mfNLVfWVbD{`fx1cs1AghM=(O0Z0@y zFR(9OS2B9Lg1+aIPs+L>pX%{k@G3qGObtQTKt9bg5xWyGqCo$=Tdj^?CIY&TsiNVu*BRHp&A$ z`;T>lD=)T=d^{wGU)Lih+0w2CrdD2yCVi7r9(4Bx#>usJ5Zp_*bym;Z7of6Z65n zeLZKXc&2#H8peczDeZ3*3D0-62&C{Ygd&e9V|S9qqI6`r6CC4b1joFs#Yt)d!qKAA zA!#DCKWILiw~BF9-b7z`WgIljH#;={u(?hinQSN_?5gE-c`PW(-kj`sW*@WreDxWI zlIfceM?p-k7)(#ETeINc5h@i+ruBDptpEc@&jiXWkAQJt;q2V{@YhvmbE`p>qc9K~ z@GaSPKCwK=qlP<67qTXD%pTL`o6DB^b5TR;07yV2vLHWlsVU801q_cOBVX*;CX#<6 zHjS`av+`{)cj8#-M;m$7XhFTa$u8Y#4Y62uAjQ?*sL+au2Po+pydXO8N&+Mc;J^cN zxp;Rxv}Lq)nsP3TdM+Fj0jd*vbBN6- z-aqP`VQi^i)mk2_>TOL%H>6-q_s`4`pz}(j1xb=fC7SZ#u^yu0AWMin!Be*f!`GNK z{ZAW>O?XvV_&+qAWl&sQ*R*jD7Tn!}yIat~CAho0ySqCaJLX3xWjku z=c~7Be#6v(I(zM2-B)wfHW@&IXG@VkbZRv$xpP)~JIfF#TI~cnMQAh4`49c_)b7j= z2XDoIOZbvCCm|5N1wx-^XJ>Bw#A9%W0^IDj4+rmP=8Tm86)v!610<#xOyIzd95LuY z0nuA3Cm9gaAPI^5f4=chq8xdlL;xxEMlmZwX^}HZjcM> zQe6I0KbhcqKbNJFYYToYr>E|9L1kqe7qM|-MosYK(Aqj5c((j5F>>Vcu0UyaS0hm#xo6^hLRh;Jy-j^h^Z{kUS>%hPapax1i-LVhH@Nx zXA1l-9K8-b5{*@VrUoD$#VpKouCRFz1VQM2omn>4&|%9{5JR9~8R6g%zM4ONbTf@y zy2CD_Zl#v=mVt2C?wcxjKV0#?y8Ak+{b~DVq6uXi?TCo`8*UtTTZRql5mNSIhhD61 z`TuzV_~wQoXr!|6brihqJj17W3e4O~Cj|dwkT#p>AqW3bn|3R3Y-)oX4@}+*Gd8_ z3|Mif)~{UkLez2wJKEj>%5>;=*Mp2{_(nU|q)@>ZXz?Vh7SDiD1N z6}hbH@wh!}4j7n}8CzQun&p$t@r$18ttvdYy7N%6sgKGTTvF@7UYRBOyz>x(MuN$ z%U<2Oi2K5KiM)GZ_`|h?F*HWryCC;k48g8Y6$6jri`(p>WL9qJ#A)+?Heetpod%Dl z2+ZX$!PWKFoWT66(JhG=QIb7F7h4`PVKxoO$ux_yVw!f=QzjP7XR;t`_lPgF7%;+X zspg^?&~PYiqo&D+9|(K0vODV@qs{o*-*JAGfaujTQ~<%i(d#c?zfJoMsTNoav5nE9op>lE4K*xlo12>ENi`=N z%i0)^FMZLpTKY2082-#2UW7Meu^}L6@?lm``ThF-O@OF?sHxRGdUI;M#<4Ed3=ttT ziNId9tQn|ZDfhcPzg&!s472@YL&&5I*(;X$aev-_DBx*eW_ygOB6I-WTqhdSZ|mU? z#w7#LCBt=a_2U8_^P5Htp-Sr6M3XgdeEY?PmStHYIx=YptV5L8kd?SauTeFvUu}zP};|4s8csR&#ReY^(*O zw3GwObMsb%0z+(8X8$3Sv$^3 z?l=y)XnRcbR)p1xt3AT{tNUh=DQRz;6-(L&XDOzu!EtivEd zsO@qC$A;!^x#sy2jaaKzUCx|O%K~{t5x(@)gdzUcV~<9x2PY?hHOLNf++_}Tg^vjJ z@E*(^?_(N}mm|W3fOr24NJWk9o&_%tm#!`@Py@@$ z)E*ul)~(;$gd5M0?Ky!B*xMU)Su?!~*41#W?tiM|j9g9|mb;4VL|t#d&Z0xBb?f@C zv%9_Tnd$akS@S}U^$6`AaKOj`{G8uiEhCeYRkfA{Wq^e-K`DXnJfEE;5j3fsY`d~C zUVq`od;sis4I>2iXaY_>k09k^e~Z^@6l+wkE-1Z0E}s6Le9&Yil&T=Uu5+5*1U1)J3rCxCJbLDqd)wLDCW0tc*;UHtr}PfzI=Pg@FA zzzcEm^o8Pi1@OQ3{#4BBPldm-9+V?Z&*&RccuwMWlfmj}@617Hqu4;$$j?q^#V4@Y zW@;I(m$Ws_tgT_MX~H%xP-T-ZK}mKxgU=LZro0mx%|F$4)!=xhCl<-z)IV>ICoUc^ z6yuYA3&_<8B*(p0VmaDWdh&EWAsrdq9(?Gn!9epDR+7{Sk?+f<_yvcSQG?pu5VcqcCAJp-gyiM$BlP6dt(e+Q|Zaa#}^R(utKjv;wk2`;=i_TV24p^NB z?PK2Zr@CvnKOT}KhjSAi|E*(3UZaxOJz>k&Mtc=T= zK!}#Y3#a8=CU#uKaY4fOt(Je1IebPOyE1@!D;hwG`UK(0OmhPdbiuR9n^eb{aJ3%~6RJU32iy)sB z>%4;c?gOjbN>h*arbB_I1DaR&iUnOgW_ZTC4qdSP;l{&FG4{hYDzhckx{eFxY>0+W z)Eu-_=*zH=cwkIvN*W()w&C#}oS0DxWV!FlEe%xaXwtpt^niRtNTpC78aW!@Fb-SR>2zO)ow^b0I6gH}7=_m5<+kQRbc?$e^OniDh?l

r7_2LwizPd z4cDQ?{qJ#GVDhTk>G8FOuFhbjB&n{=X554ssDGO_#s*+a>E;N|C}+3Xb79>@Ad_Y4 zX{PfGtAlA77JGYsmf1N9JCrn>B^R&EG>6=rjYEppGBGs{cD!gGqK%mw;PWtlgJeF| z)>57)i72|T*+Mf4g?N4wmPSLxPk?Ll$a8iZPssOip2*pjOn)f$%G*vYGGy3M{6@?# zq~1gR*Ejzd126Ov-r)yhV14Y}^qT2V5YBg?d$HAarNjFMPBwSmhHIQ%4nKEAMlmH! zThNr1$Z1Uoh!L3c5+qZx=~!phn$7NeH{qG8>Yy8R|6;C|hVfo47yxPWcESoNo6o8wGY) z8a5&#qAU2ofAFv6B2S-F7~LO+>ON`Xq?#il#2+I9LAu@raqE%8JmP@M?GIlEq5F>N zQ5`lCq7(e;IL$4;&{_X?WWOuhK!v?8iu=N{fZWq1)@(>uv{kf!O~j zv1Lne3N9#rmcX$6au(G%#!GVbXP$6ew8(#EZOPs2=T9%VU~#;7%WL^pKgDicJ;>;5 z?qmMuLe@M(!Ac7LWfqDn^b&T_si^7d&yh?`7LiV_nd!BJob3)2y1FM7qgp@R;QC^c zPs3y%AXDKV@I-!7o{mg!)T`b6m8k#nT4-H^{&Y{4E7KS4wr&uQ|*4B4)_I|)@z6#QQz#i4Q;nun_SZRepsXTptn(U(1mmYKq)d11BxkQ9n8|svKAYV;j!uJkEB+Xh$O7z%(u7<~zkS6kW1A5&dzYv*Xc|0K*Xr8k;NqnOg!>f(SG z{S>lj0}>g1IJZL~nR_T4kT z<4$6gC3b%~?`8zo@F4O1U*hAWX5WwzE8X8JGKBwXpipAYW~ZLavOh&Br2O|%gU|O( z_&D5t6A*qoRa#x-D;`<92_d@$LcHR(Gn?J*h}Dqw$7|niJVs2)h_oPj0q-r4nNU*_ z8o9VIFJh&bQuXO&etCK6d4IMAysPX4i9~l@>l`^fWx>v2!pM~TKVkLh&EXm(UhTyIQj(!suY{| z`P941JWc5i`9G zsN3+)Y$ea#$DtA@5H#lT_huR?^1f*=@pHRpVC*jgDQOzy75@lp=+ke{=D1+mJ^7JJ zwR?Mz_VV!1>FJo*4rF-VUT~&cxdfRwhRoPY4XV|um++Nn+N2tx^Qy#1;ba!VfC%qV zJkQp_{W*a6JUF>P(J`m8mTz7)d$>k@3+Q*@YWsOJJ-4?O2W^{PyIJY({?(rJ#waLP zP*gL(cHCOvT-!`+On(CMOKwyMQAPV$y6bZT3KT0)L-M_3uH|kn@(uEeu?(1{T@P+b z7gX&TL!mnI;<=|HR)>0-NN;qSp6;w_=M$uUTdDC5GMTs5a@aubRJn4lT*Yb^mUgS< zEbQuAwNi8p)Hyn*%#ot-@d_HT;uY$h|M7drb#2O0n-WLG*{X(_&R-$zydhsP{r1uK zDPOt7I^tGv<$cnf<-SJ15SZpy?bc3wDgT8AX$zY35&_d9Uc7XP^^lby0Q+LcL&Zy! zmJD3)N~wZCsXG2OYShAT(eHd0;*5I4C>tGiOW34e>zo3I9hbhruCoSHmuaa z^YpzVUIc6f>t&Hcy z$zt5s;l{~o9MUl{%}=XB2WThQ-R3Pqs|#aC(T!3+DMdnGoL}A?z4^A(*Kt()(rugW zSz2+7%8>(t8j?MG3NH;8Vqbz)%i6CuoF*C-E-@UsG|oqrDAGu(Xn%#BeP0r8NLAf3 zQ_eoNI{%0bJtj*{j6EPM1MbSLmPPc2Fu^Faa0=^5!HUk{lJF<)?27OA#%^>?HQGmN z;h7gBq-HF2$tbCim0u7t@pFrOJmD@1l(BaS8Hbr^h?ju{#s3SX?-LP|Qz%ozieZ#J zEikK@+pT=)$=rVW9XQJ(auZv#%zsZ1hfK!C%)%jE&mqRoe>D4XgzUFZ+Bd|@SK78n zm7z9TOu}WO9(>*-XXgjnvVB_jR`M~jk!g-8Kl92KRl?538eTBf$%GN#wH5nypDZ4n za`LOtJ>om!!eW%yh6O*@G%8_kegeV;TJi%-LC+Igz}Q`H}~H~ z{t%^ze}CFkN2DQU<0n^fTQek;CEQaFAtTr*^jJhHzeJ@g44qF&WIAH5=u$zMpl|@M zkS11f0>mL`c3h+^%yLT92qA|=wBObso4Cf)hGhFNtew@GVY;-id{Hxc8aeX$LPmFY zJFFqx;RV`wE}0P-bHE?vz^P-!ZcWB9{hD@Ht5CPy0ZzBoJo<)_-p6Lt7dVjlairvZ zb{|Vc$#}v-H>qniHcerEdi0B#Rq^nqw24luEc%u6Nq!Rg_w_XkuPB>iGUR~kyJ+6&-mbWJkkY71p%D(yl&5@ zcL3^}GgBdX7jjO$O-Wxn31JT3WMgj^O>7E8I*toi3gn>_6P19CDUa993{Q64*khkk zpJ%!%KTWkCach?}p~9b_KNT9q^L8%B7y6^A^mjg+?%&T>Ol)Md&T1N4TU(W1{5l!e z<-XNI(Nn8nHEyl$Or}@=z0d>tC}3d#Gc;fp-2>+VOdcYDLY3=pptzulT)=`WdhwqX zt%-4y{uN>j12)eWYjr_!(F>F^Y&O}%H!VPjGy4VIQc-u!UsYy|fa;&1Sg~cKd{Y}b#eQo^!Z4LU zyVjzKzZPfym3&SNU;cJra{K>}+@4e~`K#$LyJg90=vQTo@id6zG(!l7mNtA3cF!7I z_43aBHTwwSbK^2Bm0FFUyd@o91f*lfqd!pI`G&kCPN;j4m9C8)Ufw3&G=S@Qh%Re{ zLvWTh#;*i0h3VjHswt5Zx(kwDm9&sW&S$79>L{~Mp%lNzr2$HpB3n)J~G<0 zY3?vc)@d_yl1678>8R_S%p#@}oi!VNKlSFGkm4|40>VgvPT3@%jnd^T%q;q-hHL+< zhd6A@pB$fi9)pxy5#?usW4!Y`#Il+7yF6-L4MQi0XGuVKX+bEVnL+EBxi{xgDvSx-+72~s9oO6X&3Ao?790ys&J z^F6=11m~~jQC+iD1NBMyQ#je0@@>7sH~S#o!iI(6KmSB1W8-zh+BOQbuJc^o)Dh{s zSa@kI%eZ87o%~#;uO`^u#0nT^kYe}=SI-oIqRh%BA64u4#N&(lb(Ai);{TA3pT{`- zW<9e*uvsoG8XamHh>g;hQFXF>bg%`igi zSxbf-mtAmd1DTb9r-u5GDc^Bzz8ogmm?ykzbns=M z6%&moKY1B;-XSn{Md~jkHryfdm~)LBJRD=Id=*7yWDSxviG1XueeKiYRS876;bEy@Sri$ zz+A(RJHzA7AbhY>Z{1J|xG|J7C6sa4z6@^_FQsfgt#*W7V7jOJ@r0k%TGIkTxeQtRvHcWksG# zvWSqp61rrSN=^kBhW5;)w5p9uL=n|gJHeYG|H70q7#4FP>6Mj>ETL0Xhb)Vtz?*Ig;k7!g zDG*CLo6^1%8}Y*OIOkvvlED8OGAu*d6U3`0$-|AnpNYs_k73Xi(eEAZ(;fPcLO1eT zDaT0#LJW;$ ziu&k%ljIaw`S`uWD4tF6gJEYZJ#~{ziA4pB(t~#vNoH4p0zHoo#kAc!Pk)UJ67q|LDm%_Zk$9Hts z?Q8csz29O5B|H?i!==~#X*|y7#QFT1+i`QfJkZU=5tk$>sS>~Pc=U)Daz9iSy-(_U zmMFm=k~nrNFJUDik61zh&Dl$Mp1A(I$@ZrW+>bbidP9v>I$&5G)~1mYvX<0F_2r0x zplq)RGadlnqZ;E;lr9~5YbQNzGwPdza|L-MUAp<=Z2l9UfxYl=F~IBrBw)=1rF=+a zQ&{s98FPNR{ed|1#OW56i^DKON|7fIqqhMgL4rax)R(!ywiyXB7QlNuL*ho zk`gya`nRlrZQ|j-W00_1ncg|wtQ@$&rjV_fzRHvhEvMS~yA96@*s^)(sGnc=|!2G~w{oI4F z9zlW&HmW+!guj*l^6@b%G!!}^Apv02!^XR$&@dx(s}fAf(0sFy$ z;6*WJ??-;uf0u3GQyC-QVEq}o$7txHnWqwdS%oI{qXq#e(@W!&{U?-Iq4D$PCf(G4 zXSR%Ob5YI0c^a@6*QVbuEFzQR$43l1%l|KKW&fVr3B6~`;BTxA!1u4b{U2&i8Ha=V|DL5+QV;6Hz2pa;UHIKP++61pz0?(6oJEfcpvlCLlOVkiE7%_CO_!v~C}Hvzq8(i> z6^$iv$5fluE_&YywC`~wxH;N)V!7ll?mlL>a^7S;^gIK$qdFdrRMWMyTkp0`M#Z@s zRj9~P$U0(vnoD7hB+||HJnrN6zYHes_m2l$jbZ*sqz5%orM5&a%;jUq1`&!D2LGw6 z>t$%~mIx!I*kjh#-u#3~U^^^m_M@8pGM*5FC*$+6C-@RZv{F$QFR4^iE{Al;DzcZB zsqK+9tJYPkZUkSkLK9wAnC~EO<-^eK-P8*9S%_^#-{fNZpYNxj=Dq@R3Cu$(hH{z2 z)s8JGoaVJwG~8fGpP%h1aMj49^nV1U^YB}w$o1+aC+Im1%LIn$l*Vjq$h5u^epYxn z>d9+PgE)ejtAY9R+AJZtq!-d5yvK9!r&f(GGE@QjsQQOs?60QOR8t^VuB_VF*QiL5 zdj0Hr&cg-Thaf{Fawko@Lx!!0y-xL}Z_3?I{S3G)0Q*Qh|JhJi8$HzGpAg|1$%OnD zmt?Lde>vEuG|$1&C}a#J5&qfUN*KZaUDSb{3b%nBST2T>Mu9W2Fz%;%VB19Vi(W z=nc`S#Yv6<{lneu8NMkp0zi=Rv{d<^rX`#7h#-bN^aNBiK3?9P$H$Ji9h?QVTVK%* zzpq7;9MpES)2cy;+;fS8Qs}&XYn~zw0eQh0uVU}u266Cs5^2-c zdzr4EDAB*CmI#0-9~qIVa8f0CrZ+Q3EI~hF)G&J4_llXIKn6i>(2rn-hhxzkA|okZ zPPr#>y;#r-UOR*CIu8@fVVeXHzDU+#F`rX@t0*E@Dr=xq&Z+X2Y3ijljqnvC8e=Sk za%x$4PkON%oAZ-%!0L2RA;oI&!^+?rbIDtBpeCTH)Nd`L@POn#xOI zK0VQ_(U~`xA#eiwXOK}b0wF#-%#h46t9jn%u;dH9- zi+Mbm;u;WI8sk*VTF~=^ZM@Pi4rxyffDG`F`@tl?wSGmMn7P!r1L{ z)Qjz{Mx=x-VZ(yC31_ErpkGZb3IK|?a#I_jf;xbay}z-H3MhzOH?2q~JouCK}CfK9_F?jKllXW6RV;Y;N! zdhVkB?43Q+a|S4}A;6JoQ7()!JDkBjk?CQz(6z++&%LXPFD;k9;7J0hgp6hh(a5zC zuaP|~S@h?aA|pY9X5SBC;9#Y$c%wu2q?gm4>^IXki}Y@RDTAknsm+*@BpJg1w!@96 zOW;ae0UeE#Z+Bk1V3r|1|9fBmWjN^PUSWXFGiVe)Xaq3hO4rZltUYCPWKZRVa%RSF zdg4Ymx3?`lJu_b(Jo$u#jQR64?El#sIQ{BG7_U`ZEjWuj?0O2Gas)JA1KL~5qS*SY z(4`|Sq_DhB8HDNv9g`-UIk4IIu-Ek`EqX&HIm-Z)Oc58gpB-mv*OS_)c3&Bzbam z#a3=o9p7{Htxn=+TAo{)F4&9xqCE|v(e=r3$z$Q zZGOvZDw&7d*%>4OywEs+O+5iR*^&cz_W|}lH%*P)t`o@5wsAL2gz>z>e6TRU!_dm%bJ>1yX4MxScJcwN?0yD^so*YD!dg#E#otJz{L^^)2w#m*nqziXRod1$>7@ zBU@5#;3v{y5A)Kg5o(GD#d9o^*bcvJEhSNuF9YAEML2IO#ZEY4_IZpwNY}VndGPMR zcm1{LmeoSSc&_N+U0a`m)f0UA0Ko!KTTO6b=Ln%`<0}3Ai9%K-AFJmeZ$l!lgx9_- z4JT}PG5ki4yjj!Dq>_F*`rQlDf(@B8o+Wxcg-dk~gN^At-GyJ?h6wqBK1jOx?{_*7 z+H8`k$NS~ezFN8~qr@cN^EYa29UG+6ijc{TZg*viL8anAzK`RrP@%2&rFCGHmzE6I z{NF}(QLU!+*4O{p_KhIDdFsI%sDJ|6Zs?bvZRrX)eEYV;u};KqcHT+)ea@J+)>oa~ z%8<#mvJ`-o0j1(B_@rgs&d$N*ESk2%|Al)!lSgQ-wUFtsqt?Jnl2!&$oa>8r|I-_> zQE5_(E>l|@ciz5iyP8x}SQ8Wib*T%6^>S!OfFBIm*JX%Sx@dgV2)8w2_*?ozmxd=# zN+)lH!_EiYX1HabC(71u7unFr)io8cWLR+EUVRCJ9)z>Cl}MhVqzyOA_|Ibj#1i0( zu+Kdr9oqM=YpnH2I^x;lz*6Q3KQ2I-OG_lqSm|%1l~J5iS&GD)8c_%GI*7gB+EI_S zrSgIIAO~O_m)xB*FU2}nj7;$4M@nw*noAh+6uh3F{ton7cVG6&eJ|@Hw2?Bb`r3(D zW=%e))7;)Z3-HHi{jW(Cf)3AV4|m5|##hmzW}_`FRF$SW(uVWf%FC z_&;cwE}%zokXjE+rCxwN`KHz%w{@9C;Wp$yJMa+Lb$*Kv$ir696`6|;8Kdf3&WbKqE zF{fAqsC5urW*IPD%;l^>5s0xPI2l)NLsr~B8fehjKC@fSwvQ07h8K&75El$uAxTch za8h~4(3tYi%r!xzQraoj3?Th<6D*xWvPBM?lfa0=NfM=DSLM_R&L}gt&C8E7Ge{zJ_(Kq<^1#7K~6k}w38Og>S;wMwl3}HpJl5uXay-dc9?`oo$-*YkZ~;u9YCyI!f19D<2=3I zQ=7dJ0BqE>%$p@lI?7&`lxiFnI-fwHGrWAOKZ$MzrZN z<$FKl3%eYnf+QuJ^)BoWb-J9K>z1klYCnFT3xPXJg^4^oJyk$_(liCn#@snRtnFmc zsWHwa^HKjgp8J@GA|jG75>yEpV|I+9+1}lC0&5U!)E)XO#1PO<1sQ0Gd&CSu@V}mI zH{P*CjiCmmIz{M80WcH_9CXA_a%Ze=8YboW@@8#l7{1K+lcB1Zrd)Oqv+VERzm0f_ zfX+cZW<&iXT-f5qVm$Y*t%akmv{J^yx4h6Z)gyGJ6e)+br(dSHLOi@O$X}F`ugyn* zwjQ7AYC8u9HoUsU%LglJCZ&~aDapxZCBvRbRwR;c z(X~IGkUAeY5n3!uMbyqWjT4iM(Wq9a-ejOe4|Vq7&S4`_0(c^&n)#|2hOa}ok39V! zj#|2eg%q8lSJsoW0nZ%oe`nw0fEfp#h?LZ{_W!pC)oQE<^DfK>5(1^tj+efx zA6sDDLk`NsXc>Blsbv+@-ZT`6o%ZYucq&>r+^Yfbb`3|69dfr+MwiPs@g2fX>HcGi|y`Nw7|!&TLH)R*MibWvKa#Z z?178`K^_}HysQv*P0oWu-Ro9n-!Q5F+nL*?n|=U`Zg$Fzo_lGkPn+@~1m`^Tn-Iy&HcgVuLn+t~& zw#|*%tRzZ!HJ_4HA9L%%XFtmF237f=yNc*0AC@XSK4rzI4+EeyXP}Rw5}x=|C%9)Z zzSzkfP5@XoLU~``r@qdw^n-zAA>zem_w3*xq*3&K7NF(S8FnjH9|lpEVp*1#|0N}A z=x;x!yVqp`NJsdnE2p(}MXesaC)UW9mlsXl-LY&D=e0mDUYDMabZ9I{SU_O^slcGlNRos3DH^pu0OQ*sn zKwWM168GI%Zc`{M-u%=c^Hok0fRDuVa{QzNBe>Ue03TI zkLKb1u<1E*jYW+OG&cqwlPq4rgb(->Vh;&?ny=`$u;}WXpn#P~cDr2$CAa9H@I>Sj z%-pG{bjUPI^1TdkR&!LEY<>rRFCU*U`IIWrTRrr}nZaf0XK44M;2YJt(8FhqOJvZ` zu94$~>z!Ll0s5ebGM&V;H?{t{*Pg+I1}n!ZNSk}|^~6k01-8yn9Jo~7n2jQJ@$TY* zqpaVMpFp5AC~PrIWK1+EUb~@Xx^khB23TADcVm05Nf{HYMrDcd1w@MgDtscm8j7#F zh-(DXzeO{|5ALfoK&*>NhB{<55>j;^)4avwVmT;tCt76dP^-yWrxe`w2Qt#i%zWV( zUX%B%O*zCGA987;4i){2rZviB*czjF_$p)*cH+!B;~u2T+^2R1Vh(x~+WqpjZ%8ig zqF7_h3Q}w|IYi0A9aC19LNvafY>@)2TamYE5+yAPF-@?^O9>!s=pqOt3S<2eTU1G# z2}>Y@6c>DQwW`!RDMuO*91lhh_hd)6aq#OB@)rjyd2H>?2LAJWJ@xD#YcB9gQRFc( z8O5R)lF6J}I!QC}K+1)xf~l|C{X@(|V!|qkz=PUTtd*}5hao=(TfCUd%fL&B9jC-- zX&Ld_VASKtyFN4b0;_8iIva3X?RO*hVgIdWc?(0Ois!#o+-Vq?u{hmLxi-u?f1W|rE*V2E7z^&ywV*qf zk+$MA&Ec0x1HY9`!<~>i%$Pzb*fsMzN<5h~RB{8Acwy^+je@jn7-vh81iKVMxY&=@ zozeJm@2Avy_KiN2^UmX6CF48CB7r%EZ#I$h&fplAIDDP%;ykV{W9ppxuG=%y&Rp*? zE<~-_wS}yQL-#?5Z5LEF6)536QTjIT*-j9n*I0a_%~UaZg7+yP`*6<8gu-bHyEiRtT~k}% z2~Cv_%psbd_OkOWF=?JPm@@HC$G;*)tXpSdxRlp$YK( z{;Oo)8HC0i-y_~_ByZJewvL5TJi0rK#X|}Cd8#VRs~ysbJRHBR!;DStgr%@NpQ7a{ z)2LyboV8H=nR$6{%aaMmuMNiaf8Xu!s#MY29DOvTC922BBljkD@xkjXzJSa;3=6|Z zC_J6{Q$-P{6N~V`H!{`2q3R$y`qFaSn(JX5J497;?NQ*32GBS#Jul2ED)f&^gjf{k zeP7PopWYw(XGLCrigawa$f^p@N;arJ$-+{iIZVp`Z}@X%+2V=q1HyT++LKhp-y69iM4^k&d933B62e>XqrDU_KV zAcCx9sg9Ypk~#ukc9uPLemcd*N(kYlZu^`j>)#b|V^oKZO2@^!ulmDP-Wl!)kGE3j z#aJrznd`1#PCB?)5t1p!51G1lwg4MKZl1BoK+J~k$EzeZqw*=q-G1a9nRszKEI`{M z0B$%UA0sT|vAL~-->YM@in(aiXJ!5J#qp9Oc>9%h_-VQs8>;Qk$t z*Lmy8dLP$8fLm=OHBnSL?o{3jG-Hx0;Dq?tFqX;+iH_apD zsVfE&7jm=urt#!*`UR&x!rHt1wR{r95E>^?u@)KeQ3jFyC^e&b!8nbGd`ulG#@^wGtuEfzeU89Ksw_H|m3Qu6(f9ke7_&l?Vcnj zqUw{ZPPl>kS4>S^QwIwTk19U>=gc1jf>gyA($bND1Muv1$?y$(Z%&|EOE-bZxK_9S z>$Ywz*!7~f{ih*GVB}@sLpNAf7PiVj6W0`_nbG};tyM}^5^HSO`R{4)=9apZ!uO+Z zVCuu3$uEB_`hg-8g99^d4$W;d!QERsiR5G6q)By_22N_2w1(F`Hi=*N0`0<}Lzgww zNZVV#;WvP<=Bzp&M^HR*6LRIX(NK_yO5P?L5gWKd&ePlqM=psEX)sG}_0^3ZSHN>A zSdU)PwI0>CHz^>V)x6I{08NXLp<83SDlwNfu<$!0u~~?N+wPhMexXgC`duun?du9x zw+az`S01WuHMCE)|Fxi{dBbSw`6rDCe>X;qp%kjd*f{BV42WRF2U` zYCO|Jx_Pxbnu@f?b~gsv;XnFr#=D#TOs^4Qk` z6JH$Pu>53w;-9vZ0>1C50Rv#@HiK*@E^AQ zQ#acKCQH94b);z__rQtY-u3J!m9810U@)im#x@lsu)i;&Z4dkbmix)(KvOz}wEwS; z*>?fj6Zr45fmdHP*1YN%=7L%o9;FJ8mZtdJ`RrDT%Bs$WngU%0)*n2x2)=HR&h`6+ z-+ft`h~mvr;NumrV1TKe$KNleq`)tZ9&Z_`g84y}4W7pH%}6a*j$llGjg^-$ z*UTZ+URT^)^vesDxB5rfq{`Xdgktx|kyHGZ)4=KkqPDR6&fBl0P5VK<5X8rI+MqPH zOb5N=)AIboa9k1aziW*}c0TxNY}k!%&jGM6d@jkfvi%7`mi4$RotGDL81jx16}oi7 z=1b8XcTk=eZDUgaPJQ7FQ^4`^P^V=5>$JZ^oTStRlqrg(rRCrA%SK^6X@ux2-|7_b z#7PmyDMcf1KheIsF(TdB%BS=5oMp_OL`L#hx7Ic-(?%VhS=2-5jaa0Y1XEqag!HXX zBLrcUZdb8Z6$0m|d5Yz$@d3zZ2-vI zd7`P;mCV1G&@G+D4R1gPIvW5 zUtizcyga_Kh1Aa;o}^Ar4T;NTcC+5-ZEO8FM`QYP7yN~~o@s_@G3NCBeT;(}eA*?x zd`wcI4+gpI&0w_gv2d+fQl|eTS>UUYmP`}&u#!NvFe|r{jX?S|iWq?Lp@&QYlCg~p z1izOm+(a<2&mH%1z}a&xu3{B`EgOi0Kpizf(qEuSR4XuK$pMONR1VJsG@mS#tZpC~ zRG_E`MurD7xI!Hoo_@uP^`GWzZX15pPEL}@C71AchYJooUiRHZcF^kwXZAlb@G#eN zQ%fUGk)BVNP5-uo=?o`a7SmVFz3y z7aXh|GN+zincjWPw#440^dbr(v0AKQD}+t9n@do@*jJNTNNUok?A%n6LRdM=A zs|*nP(|cVmjG*CW;?H=z?kQ)lrx%qt@KBVKrvjfkpo`d*S7PopNW`4_Tq9lp3yETa z5+2I3&2u&rG7{(b^3dw|{G5fhRQHm2MJJN>;~`7n#MTy|Bf9<%a!5XloR&i6JY>gh z%AXA=3|U~B1Oi3gfh8lrs)l@%vxFx6!`$0|mqnj5^{U0~0-Zz#aX^7J15xbM+SkWt za`m**6bqp+wURpjOQaiO?@NWRnv^SC=)s=56?mtwkT`z!m?A(R50%GZ>)_#I=i$Gg zjgWcWzOviXtRA>8M`^>%)N~UcT(PPkmjqTpc64;SnJhOTR{&a4!&`CeiDWEl%hu1Y zH=1Xi_eW=>e=Ty!A!+Gb&pYUw@De2*!#0-lClr_M)vHT%bCD%b#<2}MPlMVQ8MWv` zIL4NjX?pXgz5$IoDyf~Z;hY_HC;>%`JhekCNW;=_0-o0c3pr@0DqaB;A2~euG{((_Qb|jL(76;8~Uj^~-%2EtTYg(;rC!bFGZ+#6| zp%6$vS^Fz$Hvk4;MB`=Dmw>p8+o3u?Q&BBBtS@_X%=B*6xvO^tW83yny!w)$>T79w z$Yr4UI=OP{F5X>H6$%IhGTVz;`FGYtH#j{Bd-l`F%9j*11&AYLX3n(_{@R}U`f2R$ ztSYb;d+=lMF0kU4Y3TZ0Q*{96Xg6Q%D4}hW?rbLeEazSxP761)bXyEDx69UXwBSru zLRpqPWsM1Up40i0uHTVd!SRH^ESV05j-^DSDCp}HNJmCzR5H_A3IB^9vpORl6CKh+ zeH(#2avYP^d3_VthQuzBbKLfspoCbk?aK^p-F13>Kr))h2bHtHC@7X1p2)okt1mHb zR4dcczzAKO&uTb?o9{bR$;c>NvX;!w;3;I_Gj6@}_xNP)QKWri`TCBC2fcMOSmBTs zGgRbDot@m7@To|8s_>Xb=SVN}_!3XV)&3Bj?ieCH@j64P`Wn-ss0};|Nilw6IIP$2`w^ z9*#=jfI6MUDEm+GnvQ^Tr1ttPGPV#2+i35hto7fff!^51;mZJ`YQX8M29qHni-ltzN1EeM!$9~MgHk@s zYQ#>zcW4SwZdMAs{`7ovQCv-==y2Yb6@FP|Y3!RHi(w1rGtWRQ%Pwq)E?|ni?pj-O zv160!cH`4={n$bk5V&-9a&l_CL2&$~wwVw%T=S*K%a%HtKbtN}e70%hKSFkNwGuL;KlD zdbfUNnWSxv^KsPXrv87$V@+`~l~QJx#RE~)MvZBuuW}juNxHhR;X?3saAayA*)Ot_ zH{wx~pG2*lsOk$!!_Z}@ql+ryPW1J)&HYV7XJ$SvuMj7#pSsDuc5dT+{eLvQb5Ny^ z|NftAtIaky+t}>dY}>YLv$bKfwb`!CcAae3X8U))-rwJ6rvI8bGv~}X_fyyPxDv4~ z3rFi?_@^VuhN+ucdWPR$AAyUb8Ep?dkH!&p5i|9BuHwvtodDI_yUuZ2d!Na^g586vp7QiN$>`!cTv)&(?;EDlrz;W(=8&niBV3Q)7>Dobi&T1o_;7k>G^<8N&@ zGge- z%HbwF;0f0E^>w6a_`2QBp-ce>bo`%v2t-8~IWlA7L*hyUheO|hGDm&3s=K7u0fjjOGi691 z&hYo38U%CGm;9&+Y{-;oPJ9C0m0CiY@l6zEQVnYcc^1mFO@F+<=+|h(6(fiXwVXNM zg}u!pqBeEv|5hWeuI&Syh6fLx(33u=YrR2CE&$IwMqLQ zcBd4Kj0RG}4qyD~#O|kp3xA?S0fS$23sXZ|+YZ6EnCmddv3s$FG2jaS?Wb##KqdeVYkUxx<4{ghZMYtdvdg z1UVTY8;^8)wkcu~IFsNjtHJwQT3elas2Z{}SD58K&mkQ3c0v${izI5i4uxp;xJH?)dd^Jq(zl?9jLexgjzy{>qH+LF zIML#FdXW?*FQlJ2PnXApWVPU6&&&GdwU5CYf7%NpdW2fj@bj~i{bA_NVXy%H-M>I~ z!+FFxL>r-Rc4BkFu0B~-;|qZ)sKJXwxtJ3D*&Max(bGvasqW|BdE0V{x1oH za0muVA8n;_<7)*_Stec{K+ome9)ZzlKoUdl;mu2eLcjy%+*`7U0(E8444Pfa5;wM$ ziyD!w%~$cnUld=oQg8kjF8+C~5il7H>qBDQwtPm{`gPUc5e+Und+93{?)5GdLp>)`0=25bNt7Uhr7sO&Z3L(tE5D^XPoSxU+(cYGVW zbgGse5@j9q;IH2TTj}WNfEbt*K}I}}#aWt)2ns7y8U@r`?4kzT2G^n49n?|_Du8+v z7a!jmuvLtjA*cIszs;?}TO<$$IaYI4RPSp4T$;G0&D_G0CleY8jqfrKW>Hm0>trnz z5nMix%t*b*m4rNp*!{mzsON|Ac+-lARoOQ&g=Iq*q&h!=xw1|=F_ZTC&CmIFHW7+S zFuJTHteBGvgCnm;=0xQL*DR5ixpOpWadUWNL?}^nMV2#1ac(_*Qw*f=(+rNPIV$4P z#7*g*)0Wz_up=&yx-Hv)%9avZjVors`#I6o4tEDzyN2$%ld%eXY5L75ccNB!{dc#8 z;a?HZDp272YKbCcx2I}d2Lux0 zcM>UcU}`B?F_~sFg(lgzW0j5bwBkXbiSNc0BXQ` ze#uT`AD@-SBLNRsqP?%<;31>Y5XBhcN_kDNKAmW#ZaX*i@V!9aAKW{G>rCrUxbA3A<;a+^CPIr1gTX-Wz9b6y(y zzQdxX($(vvIBo2aQjEhzPt1t9zU}pl0s`C-ONKP?eh1H{>&Oe3;k?6B9gE8e^SanX z6t^p)QdBxoxiuSDKwHY+r!7yCU8<{k5AhJ=FQRxi)TmX)p6`p*bK6)e`fQfC{`K|E z@4WE$PVxatT>BPWq;Ok%yVOg5v2~~!M}a;<)PEzGQpYi6Mw69bMfKmB$}rFPiYg&|2t8=V$91!x5(0wiZ!&&RJ3tRjNY7MHn(0Cqy*>~DZnh(cH(#W5_h9EB~l zv6GiBX#+f0cx~;h5Cd9Ov7un$mBv@jNAQUJv6_g=Y00H*lJ7zAad8UET|MIf;{(81 z1FWHjwl1gYtY7mg7u`N-9$RZWPya&ta2kQ|0(su-#Ir2T!6Ne*7McW9EolNW!~QI6 zhzKFE)-tXm{<;0Q;(S#crSs#-<~AJNGow`$Gke>(UU4>fauf-&sy?_&O)~a5Ug{+t z15C|)mV&$l9tkVwM5nv$kQJ+_5h#Yl1g&W1p`&LEd5^}FLE&XEOTi6iw8&&cX(khCSFA;?7~qOS}3#ALdP} zjJRVAHuWe(Is|&2Z`}APggA`~(e-G>CPnH46qWAYa+e$ZS(v_uF1b5w#Gi=Ml^frF z(vlB!X3&DEI5G?DWB0sJ_IMs?ATk+{oqcf~SBwbK9iqm~4;9+WIsr68mB=tN7eCbm z6zp7LK;U|i+y*EoLmd_ti4bI{q?NKgWL07ra4MQ|w4+oB3Z%I|xf>FOeeXo4Zx@;T z)BTy8PrR$}-HYiI8)&;@Z--Dn(b4}JK0VuQMHJiu^W;s4i*9; za-Oq$d6@$4_5#b3qK^w!2gXl|YSj&^ics>312x<06w}(n6RJ{^^aDbL15z@t(HYH{ zTA>y3kIGExN`9B9?k#F!*Dahh`dv6bjVkDu&X5#ZvoCF>Butf8lUKppG zV9$MRD`$TptF6P)xy*Vt2XVr$`zC`5DoN{MDCNlYBER_5Ir8TF#JT@d zTAk$+RDQcv#qiP_1>sONI@oxccdazRZFmj$)yq~mQ5FA}Hw6gWJ=seZ?U!70pcikZ zv*Ov&MNlMJD!Pbtbk+d({=9XQZxrJA=x7MQww0fj@4BGZ<0D!@j_)@8PxKftxeH>A zcDc$G6oP3|S(x(MK`bK^Z&~Zb>G$N9SOS3zOaJgixp!=^Vqd(x@B$HH0Nx$Y`~mn{ zQw)fo92pR@ITrtccjDt$0KMa7FA-Jgu$a;SaLD-gFPVP4^H-h7*eRki&+ux!yzKK4 zQ%{rO#hw)A_`VwNS#rk<&&+Nzu~9bXQ4DIl;1jW(wWi~o?*EfEb|RO@^j}OHI=XFk ztzsZu3GrUKQmpw}!dm`_v*7m8>?xHjWu!uWlXoh&87UDCIc(&d2nAY~B= z&a&chYbrc4WBi9MhL?0&v!#5pME(x1&AUKV5r;=;VW*1IM7Y2mqSYx`WCOjp4J=ft z)tD)(5kHa2aZr5s6WLOY0i9KJC<-7*)AzeqtJdoPjkIW`8Oo~2IG?Yo0sI3EUqW&6 zOZSM>1&LorZIGOE7{wI*JAv^5Z+q+Q_fR6VA&8f?Q@Dzxze%YKug0=ry_v9p_;-Yv z()P5vVmyUeasmyJA9f~{>S2pFZ}dWg5SY`Db4TOIVROpA7{C5Dwl6Pte%0KIS?j$M zB!*DFH&+oEkN^`qyEXp!P%ItRZt^qe=^N!0#?k0 z)4vW@55$_AB5n{0$BA2h(VWRYV-t-u6_W=I9w@}^{icqZQ5U=u|1)v`$2pXT@I&dC zwdaPP!|ZQOzO`(_kK01?+2D5$%GT@F2_<`dDO{%ji*T;37tGgJSR6aTdGOZ9*uUES z55=6?D?eFkp_czyGX`Tnp z*J7#0tr6h}b1NHOikXEDkg!mP#4z)~?cKDHF@*JjTMsFvY3J9?{cMvlwaibKSD8W@ z!uSQjO5%}xq87q$7z*pMA&1)gJh%i-Twx<7#z-!=F4Fi~S#6hy$TYjzDswc49?{FW zGR8Y^8LEQ#E|;9Er8h^T{>K=UU5W^5y&X z=dPvi*lG&hZ_M80$mvgfqfn7Auw(EvfMGr-r~90aqlY;8I~;cyemKW72mSt}L{JJ2 zxgH_(#igpDImGuA3=`=@_{18Z=J*y;1I+YC& zqj_yE#yA6-Qskw`RXzBXzQ&G$b0iq)q#ud%sNYFfwC|R~pX@M4SQ%t~l1eg*q8kNP zwjp@Ba$_eLE8!r23s>s^ZP98!tuvnop|XOFAGqq~HHV)3F>cA_7{i1hyYDu>(XmVG zBZ)#+SJ%}yv-_UinREb;f3>8JR;c}Dgw`*}=Ye136XlEKck(|zSOjhv@+B!hdvwRQ zE?K7W0Jv^y`#t)O@*~dtG4qjSCE+U+NpcaheLP1AL>`m1y%GlCEC*Pi>ZVia^-#i@ zRJ|~YXOz<}9twMJx)z8(rQiUnw^c@6SCd}7`NDzI&C$0iEPVV-Kr1k7phF&KQpqu4 zt`Zj?_n%ChGc#3=FFx3c3Ak@O+a*}vXK0L%n@F8UgQe0^`el@4ow%N6D}9v_r#`Sn zlTHG#1Dbkz#aowb1V})3A#mjYvYVyR(yS7LOv(XVw9I@=!#rD@f;=}b@9x!A#QZ#f z8T}#x4>(H3>kn6k@M6ky*QRQ6?|X>3+TC$OUJc|wPI}kdn|5=5Mr0&)UcI*Uh;&Bs zb;1jBpAGX-r4VoL#cvL0A!TvdezKiR{O=C)Tq9z89}gE5$E`V-3b(J>+7;pp`Rg-;&sL+#0&@qX`~xb#=@extWCm4pC)+ zVdP|(`vilA7{mvd+YGzFmmFnSDOvBa(6X`)GO#fT{2Q|2HWn+069aTm$F`pC)5f6C zMFHJ-g^1X)sJ^PANH$jyNtDfY#z9ttuin0|o7lOO8|DSdpb z*mC`yB;ri_uFJ>Et+$dm4MSec8$3Ixm}g~6lbowfF$QGnC7*-8E7rcAhJCkGaH`=r zoi*X-=L;Xg3WYMNGLIp)AwQ9ew>wZT@;9v6aFANP@8MhQzk|1m7P4Sf=q+?pZ~1Ywq?BfG z79f?a3^7}|-x*i9qTl=hp%~FDi8|ST=P^+Ci%Q1ntciic=<2SK1LN+Cb+1PJ%m$eY z?^~Vo>frb9jQ?%L1;aoEIeG|3Ks2|Or3;PX9Kr`a3@!gz8|*K2TP8kyF}h|j>VxkI z7hb^~LMt#HgLtdikWcgPxwL!{CE`PV2pid}$A9Y(h2zcUJnJWY*WZ!^3m=9h(e#Fe z(DF)qmH(>0Y1Wur^&9b2$XVKkrcV=^ooR7y%4KIYG=w)zFB z-#fSQkABe&V3} zCK(Eu2-JS1vDo7$Z7tC|Y82}iOE7f^h<(`ZJAey07gnyz33q~WP(^+sW2#B&0rktJi683pSEXmTztDI(&HEXt^?groOL-J5i zwZB=WC;Y+ET9Bx`i-b+HGH4UGIO9F)vG__rT%=a~C%Tkj_L zaoZKyTynr%#8ic>LfF#Th`H~{|Atq@PdDuQ-yyO3;1Tk<>zLQef46s&rB4IHKn_#R zJ0W9Ll?vGCdPhB60#-g$+mzSd@%N7-Ac{b6^O>d@d-jYX0mnA~uSAX)g$PL-h*s75Fc?2 zw8Ymh>Q?bZDt<5;yH<$S*N4@kX=&cwLGidxK|)?>$W9{_}EhOeR2bqT40W|+@ZM}}nMQi6M;;8eZA+wePn;%4gNO~$#MHP|r z{tn~6jgWswarIGJ+hFO(|()F0MfJbo@T3VYefaH3}V3nvO-}fBk+Yb z9o-v1NoG@8-}VQ-16tIlrx3v50Ce|&Yr+I@KRPwh$iS|7`&Bi4^$}l;yS1w%H;A@P zmW4m~{M^sQnyA7Z#Df%|c8zx_D8h3j77IOvNq?%&!{DOjr(5_(UPGgrKKz=kf)Cda<7=YofcH6S%RhUljr|y?Yj;g`z}oX(Z#A7 zj=2gV_P6h8z;ac(0uHW#)ORzlUXS|Y3~2Cjd>*u7K!EGh*%Tv`t`_MKL^frM+r{!2 zlefNNsEZ7*mF-hdz0Lz^UqnWqy0>St>GewJ{^ZpjlR(ATulMNC3Y7|1ez-qwA zibS#rNbZ?&t^gEUN?0M-ahUJgHrZ`#shCJ>zj0Afp*qsW9(ZolT*u3jF-=rKOo$`u z-+~NC>{h!lHuE%7@HT|FgON7yoRg<`D$*hIF=SOTE=S@pE14DyJd4zMQu*@i}oT z!G~t0l}sX8BqZdg(X*P{J>pL|JbjU9yxw(si0;uQ#?OcV- zk)C^$KUBW{`df-;Mg`FQ^QRDnUuh%XMScYvsF_~rTOZT^)ZXwr%%DNBq`>=eL53gO zs~t)4&3R=SJX8t7#-&oSkUmO8=i>7G`eDPv>+u5VgnpPBxqcbK>^8xE`PmBYM8iR8 zS4$nv82}k!wKqkbRFY~eSvlwzcf3PoS7p|=OQ%*E7b2Ad48oxFY?kl-e=QxtXM-PS zN?(};C}b3*>e-5N@@*wd*~oenu;$e7#z<*_15`gs1NCgd(uO%NOBUgUV{00#=L0L# z<}fO^&AV(6J^TGR@XZWY*d1o$M3ZGq z!Oy98=bAV+J6>J7-&a5T0zN0VESetKkFls>BU5EN1NrCQ4h#aq1wW^9ZyR#oVz6`l z5(S@!a<7VQa_trrA|S+IIGyn`tqXTKIqj9oBKWP8G)K9cT&bWpFti2wMMDDgEgSEN z5D$3Q_-o+k|2#OTsxO^4F}|`#r;p5W(qzQiw z7n6>O!fc=?zfY_ty%$lHc=vgLv110zmpi8^HtVhTP+hUHtGM~y1tFYJ8D?9UpdcqR zoU^-%Z34GM&6*Apig*8bJ`Vx8)G3^JD#r6DL1GYFOt|0r6I*IC7N#V>(-{^WU4;}T zY4X*xFSf_$(BZdffmeDFq0|F;Vn)oWTBPVOf7|Q!Mi8*O$?>`1;pDVlc*Uw=dg_`A zAfRH&2Ac69V|^KtmO5d0)uLlpULatacLPb8HikvcLInvKxy|E}2=L18dtJ=6;@o-) zT|5`||L39!Fmj%4o6asZ_4?tL4J0JEc5KW^Q;h2-SMtrft}HJDx|!@9#}P;FqNOvy zrlFYFpaq(52rXL&*c!95s6eR#oO-oA0e?qFX&SU-P^W?l`~_-1J}>*PfERzb=?!kX z4K|$}Qs;9J)D~#fW1*hE&voI{UV9r{HHXYlLz2fXPa(Lz}s-Z#Q9oFWYV(VQEyMeuR9|%5PYc^@iu{`%T(=lPnZ8YFPDSB^>Njd zgSbMWOGf|yX#oVDDYl-5xSsm3yA{0`4!kZNXlZB)UGRt8G-{r``7+~>CBJ^H5|@WI zaVDIAj!>1$DE?1q+WD|*^Y7xEOcv*{K))W_*I&s5+fQ37|9t(Z+5C!LDcgmwnd^@8 zZ|0#HfflcV^5zFICJzuDXx$PwPT?8-xjg1303(~|_RPdv` zjIi#zD-p;l8_^^0p0IfFrKpTv7~v#}9A3>Qg+n^M&jqh_t^&f-y+(aOQp+a3#<9!O z;KNxzdr>6z+@~s*joPb+`RfD+1_yOu0j$Hzs4J=j)k zFBi{$@BR+$xoiw!J6}An>EmZRDn7=i?!q%{IV2!gr*zRC1}$Y*_U zg-}EZSRQhi0^oA7J)aju&@CMwQ@c^dU@nFtGJjF zAWKLmq1=>1<5gLAHG&{}Cy(ZstvO$@c80^NkWPd}pq?DL#jq)}c=@7K4Vhv2l%u~TNwKM!S147kZxAxDiBn8n z#6imDMP8hi{rWU#SY1XQlM!gY7s-`+^_N*`5Srtm2t^y$GP0kVKhyk~9&*Aft}j0x zs|JX3`0FK+82Y#_N)}Zx)-Qk)QN@B_=h0KK-VtJCqJXKjc$`&Sx*Lzy+j}a>U5F=| zV}T)lLS53tWvz3hxEmuuDKZvS?`Q9m5=0%PMEfU33Dmw`LK}tBcOMK1^L^x`@F^sj z8qP)Wbpt$#__VVl_!+CYQIs=gIC7WTr$Tq(K0 zHI|W+C8A|EqGogKrZDWEniVt=7Q_-RoFdInVQF;+VX}ZEYVef1UUA-)-yN zUF-cOO2jbH_7;&yZABAc)>ZDnGS zl(!XBojLFN!D3p^z~yi7lcx9}eV50FvXz}Ka{ZT~ao?Tk&t!+LYr7k#slx}X;1fst zvbJ&^FclO#xPb-Ml7uKNjKm6@U}KoZh)6lH3Vu4or6B5ZQEhAxJAK^#y1GsS8{Q`nFgow@BxwwS-VN3(dUfn!G%&a~AOEo6wD3^i5 zOkZ&yI`@6T;%WWz6MVY5l0=!fe_eAgGqKf$*#}x~ZLHidpP^Lz;o-Af8b1F40z=B$;!TfmLdL|Tjh>ZV~ zvoVhy%z!0;>N1&qm@;ejVEp8&TJyTOiDtUab_fVh^TMUn3z1W84?s|Mk@nQ16iQ19`T~TU$rRPa(y{X3b1?4NYA?ve-=+M6(Zt*A?Y44=wSh zCAX1h{9}%Y0W+5_uD%1nO~lJ8Qtgt*u1Z)Y zG^w7pVo|2e{T%OH{dM8GfJmcTtq+%v>KD!HYuqYRpg#B$?|)0p?Laanzy@VzV-xM( zaZXL>*Jzh>6eDTket8)bDqjQWYq6v=$cn|J#ZxUh-yhcYwe&XxCn7V9^;IwN&yTTm0@J;QLav|L|w8yFJsm*PoBr=-ix$JsYgA$axhVjMA z`-tk_n^)`2PwQmt3%WlX{jt&PKeY6;4ptW{2#B*24pdr>Du#Yk-2XApbL6`6u+zmR z`PJ~U!C76-7g#ICFLa1>Aa&vlQEC;%l2G);DJw9vh&`ntPzXiYC|ZI=S)}8DEKgly zNopR;2?Je{#VUz+2;!`4bC;@~P;p=_m_>zh+@PNszPI-dH+>Zb2TcJlFqsOMGcwS{G>O{eohFiB3xXR-f>olDP=>kF zsBVS&O4mNfB;8wxo+lORXh4WXcWr z>E75E(DDLq={2$i8{hNs;_-a@d58VBfnZ=RGIc*5pI^|ria@(4116@a{Fn{_KdG5! zs;)d!kYFd1m_#FtRT}f_x6wakG^m+H;f)}?_G$-`KLKY)YyW8XdNf2kOEuzeD=ng5 zMJ(rn7q;1YBJkV4#)9SrO~HM%;+f)-tCR?}0VcmUbl+`J zVzRylaQ4*ul3PVKi|UGpw@nX59iv623$K%c?YWe3-8T0o?@P%Pp4cAsVe4$!{>9;H z=li+}L69GoxOYh?kQkFn>6JKL?9Z)&#~XGxH8nmy4(y;Bx|=03N-XWD$AkO>{sR8O z;NCz$dRkCcZvdNC79PZ_&uA(6Ux+A+snfj`M3LG|ZafO&k>pX?@$VW48;vB2#Vvs2 zq1)}7E}O;(tZ$?{7H?kMbZ1%4>M58I(uQ?yfT#Vi%BKClD12&OUh*Wv7EZ+)E!8oW~a$f&C3Y8DrNPm-p;SXPSbwQZbR8HNMH+ioW#$(^O{ZiGP}a zii2ka3&iAZaP)+yhp3h{tl>opvC?D_oGzY|eU zJsO?VA1sO#A2%~ZrZzBi2-9<~(=#}=SkZ{iH5U_zVnh&j{n1Mb;KI!>KXPiEzlsG> z#uVEt#PH*NnWaVDtppbyizLt7$GxBo<5PYD*ID){&S)o^YpJ;&#Lk3Zo&M_f*8o4uzaYYe^- zBs1xsCAALxu+w=v>musyOIVm$x7xbbc<%J7V7?gaeZbsmx}Qp7QO^APo8P!3W?Vot4ZGXveOcoF zZ(RDOvC>7(Ly=PKog}Z=id7URjFE&$z(*Gst({!U62IbfT{usU%n^ijXTOFIcY5uG zcQ*KBnifY(Qz)mx!4K`BOS}Vg6$t@`2;0oHmWQWed z_puCs;C9x!iTdV?41AgnMyR+^Q6F4r>X%|EYEzkfG`ZFMu4ZYQTj|}Z;Y6GGMEWZ7 z_VMGgg8~~j`K0*SLiCc?N1V$|qs{=>Z^L3M5$Zgob1KGcqN@tO!H?6xh7Q#VU z4GwEFS|&CcX1k#;rPmFKWytDJnM18pvefkk3pQdOk0c*u=6VY-cwuE3udMFLRS;+a zj|_pBa2>;U@QuIxnD?-{Z^v2blM>J3rV5vNdukBFF-jnsAe??#=Myk2DF3UA?m=BE zx0g))BfZhY+@*mVtbOwL+EAx~B4Q?8sdtUc;oIE1<)49Id(tUio`9aiE<8c^UgCal zn9SN?EnO%ZEr2ViYieIQe7cIaVUJzKpsgcgQm0;!1ciUJ%q`x;OVO8vC%SrWOb)%u zeMDe`3R1!y#?mepR$$Y%>X>T_^!jrgrB~9h_^6 ztXguE;%p~}xngG9P7wfF`Z||S?ab$~vzRlPB{Ts1tFor1FxlA4D;+p$)&dzEr(?9|@)k(gzeuygnlOH` z6wZ!RDTGS`20|xbcdCSespg`U$`KKB^>W|8RFI3DbuQws>!rXxt}L}XK$9tfpDQ?~ zj*rjIX%JGX5%uR$^rGl6qNSIOh^uUO8CNTlXj!l$_Ieg^ph*=gBUj$-e*s@W#+PK$ zso}b(g`Hb$wv7f&R1*EPo`19B>~4KeYh`ZJ1Xs5UZ9yq-*0hSaTBDXlipq*nc8XqL z1A(-XQfS++u9hsAB9rUauV5C}oGu-@WetWOrzO415XyOe)r$Bx-Y+BUHohS{3Rc9f zeE;}ao&A01`aIru-lopifVk*rfS?*x!2jv3@diP_$&^37%l$2iJgVOG=u|DoclQg3 zlT-faK^uc|xyvuj!~aPXSTj>c@2<<9_gzZ#pIYn(EDgy&{`V;!0l_Dm%9o^=1=gll zo?HlRE?fAqzv)D6e&ieh+{fgonfAK_fmQBA5#ahy^kw;LV?FYpQqGJM+cCiT0W_h- zOJ|_|H$)D3IHd#9@07^p$*S;H|JL0|X-BKz?!o1yST5zrEMqPt>%4hQj3*b?YHK-` zg2PCwqQZed*)T0Ie)M^Tyt4eZk2~FzvtGE9 zpu@Gb^Xkw!Wy?t}uPk#OlMC+1x=GqQ%S2Z&B3YvTP9?1(dHX%nj1krpvb8EFr$+L3 z=KC)JgXb{~&*y`h>#j?`c=jKJetC#@y;D*If0L-AG`01OflUl|T${@y}7SORU2V?P>s;4G%6`^mp_f~ZAi#*uVB~h^omrm=erUP_-m^*AcnaHZ| z4g2*h%B-|Ghb|sqYRJ-bk_&z9gvqeCpvM-#(cnJavZh~rU#+yOYHuA{1%p$mfb$gf z+DP7BcGs4L_bEy46Q2t|D<6J0Wj);94xF_VOQP2xv8R@R12Q({OJ#vW^#>Ez=f;z} z67)}^?%6J=KLNz|S|{HS_NHNGz-1uAC5Qj>wp+-@$xG=lpacO`-_ccWRed0Ge3~Jp z_jk;AT8;Dl^{|yk+6Fa>C!)YzS)Z}z;{~C<=e4;0%ORa>v-)f#lyfbv7U#fzhWuP{ z7G}b*?n6Nqi18~20s7CvU#$b#>PY3iIO zie?=8zeS(&lzJyS1oy`cUSYdm4+Wi*_8XV@lHJ2VY_&Yi6TQF-kcO=3bnPf>w&YsU zvlWhxCQ?x2FFx`^3c-txSx1k`$~d#CFbkaabBkgRflC#O<3yMR)jQksTj$fvCW90+ ze&f=7K7qb}?1TaVqf~-2_3h&RjpGIZ2VVMK_h)kE=mqXkC@|!dtWiogjnY%vKQUP- zv8oU*h_;S~Huw*Ll22m`0i0aqtE183>HMc@p_0^BdpC4dS&tQ%rkcrp zLkF_Xfvd#bD-~k6sKS|`DQo(Kk!f`KjI|bj%fuS-4wdI-PeN`wKgz^cWbQa)pc#{u z1q4z=B5**jAb1RDrqbmtxJ&gs{4m5_JAnT%ZpdSkLW?Ug1NZP)31DFaabMq|KYRXg z{NUZVMi`QuEI#VUZpuyo~8Wh^wmCUQi-Os@01*dCOk zLb;q~4E7s*1&dI5^v+wVal$YvMSAVEBoIn(04s-Gz(vMeXuI!I$TP4@-Y!S2Vo3@2 zZ0$ikG;$9k)|q0d5bVRwp1u5!cUALo8twbKwq?YcGl9AM?@{J^bL^7E;t+mCA-6GW z`b}ofd*)jvAk_1gl^v+s&tLRDI{eZ7G{|&w?%k(!cYc!Fmwc^0!U2#x6|nVmPnhm+?QsA zU>u}>!?KFGkHYL*#toVC=;2GmcMh$b8pJQ;k&|FlmqSl=dR=64}^>abhGYarVw z$^`ME7l2o0MtAd5V!}DCK9Q_e;tSCJjW4%va}dwSJGtn6AfDy))B7eQ_f)Wgb$*5VvcM-1{R~SAF^e4}ug*nxLcY zys+_4RLy^zWhA; zgm$kami=K0O@Qs*``-2aZT9%3ls0>4_9YTcA4qUa0w6M( z&DL8iCjT>=b=(WGmX5n5tdieoYq-j35zb+=loD`?iTJr>B2jQgXfX^d>Ph&b<}$_= zC}L$Ue@kQ}>#=mK$LOh;N)eQB_mZvIK&?KC{yt=x7 zWf@=7bEEe0ge)*D&$*kq^-1)3Y2f>lc)jBXuH^5L`F(`Yy3$hbvQi=ADpDr+xR+tz z5Xmyis;dqoPGjs$qe#}f8sYKq+WBySSWGqIESF?aWF{edG*vE_#u(KIKY-%m;~#p< zaVNABnNi_3z*+tEl50wE@su%h3nA9FlBo~B9~-6D(J$}sLnhN)P(6gz_o!u8!xa1M zM45atj)0**#Lf8LpxIM+O2C%X-`^kg;mn!cz8<1AWywlT2mkW^Wy|ONheRQPaNM|= zF7R8fD1Wxr&C!+l8tHX+$`iTGbLNOr=SN4Dx1lt5hoPRq`7g82(C z7=Kv}Qs;XLsY~WBYMYt{0UyJ;e8=2I1F%l0h71qxx3cW8xv|=Kg@F1m5-^R%<)H;y zkt2$1j=gyPWajK1STFCr+@AsA5U~IWxw*My(GC1*QJXDu^7jw6Zz^dBkHDFtzaJ8i zN#P>F%9W}F(!L{kTIdCYG5_W@RK__P`7*J>N@QNmQ&GkLJ91mZ|G}B@H$DtDoVvO? z@G$a?`mg72YH|xf0gBmwnToqjOZxxOOemyvkqFBvfFaBGv`yhUQo%py;J|E`8#u#W zpH^&bXKwk%wrq6^6AWAEeoCjRs{=_2z-`?IKqGQ>U*iFwW^=czuKz_Z0B_B!Mj0G) z0ru_J9{Q&LtDVH&Y?s4O^WnPBPrcaM9IMOR9#Q?10(p`45v-*60M^~k1*oL;rYt>~Ts z$n@6pl!xbag@GA65qkLuu3}93qq)PIKo!=K22D9Zs|iE#tZut=`n3N8mmbky$Mo+l zV8BrHwE5UQtYP4rcx}0lE7RxV8cdF}M$pXc&|JGoqJ`W17TY(@E&W^G;tm$FvAN7} z#n%0Y38G9n0p@+%W{$=E%nBJQ4#w8Ug9rDr;C3iBV88Lp1~hgOg+B;mF{vjZ2GfcxHBnXpkJI-ct(2_=N*ru=i~or0o2Ut&k+4EQ4ruL zc{&3osyrN62#~;!8q13AX4|KPG?Ezw<;yyf(M%B6*46-xP%Th9h9ccDn&y1;pyD@$ z(tRE;z9T(69+A6NoH$f)kl~y~)r-L`udi>v+z&6WuU5af#u3F`b)6zZ$QcClH~01V zJEINNUcqpriLzB<+cU5vYj;d{5Nc47>R#lr{Xs`+kO}Lo`cu;Lkjr$R3P?7@PQm>v zy02cpw}^i6VRSndhlXWx)72|HhmkhuJq}z(_@x; z(yx4gK!%!U4-2=6PU`(n;gPrG(wHo@NIjaOg2fmFlvaXLz*bH2rrkyj^i$dL5hh3c z|Hfvft{9+E*wT?&-!JU!xBSy)J!2S~#zj*~D4c@Ok_xCtZ#(fmrIVab<|uPK|C^e* z{Mvp9wbU)i0I-)%0B4364vEaz?v&qzpKEsFtYKAH;Xir{kb4LLnzl5fodbHsZy_JQ z2ba=<34V0H``}9bscBK~Ogp%xtbC8<=kJx?tHwKHU}5d>K_O&JxUob3E;dbAvy;9t zBym?An&p^T>Y<4zao@;OOxBC0ghczVuJugE;!j!a+#JwRNJnviR0c7Vi%Y2CLmXd0 zH#e+WIV}H>aell27|leB2ARvhP^!#DUS+)z>Z``(YlR(+V&z|@J0{!pMIz8hIb?8? zG@0=T(diCu^sFHhpYb`CimOk0G`(!L**|u%Fg=O1bT(yj4Tg&$Ez59FLzjOMd)9Iwo zyBDtKbv-V_POcEVCyih+4JL7E?(yLUgl3EZ776%~?#LOKII|4o-Q(5ZBG zx|}siFq-XUw03ZkduP9>$wkj->%M>ae*QehVb|$%G0?(GAl@{++Mp^`hN=grmLNhS zUdGQ%?__A$7dz( z{@Xs(7JpAIN1`tMbq`7hAjW%mfOOd2pFb4wA7;b(wUc~8YJ_yePwOyhF6pTB%htTx z)*Zk-&rY>ZvDU!o^bm#+31pv;+UkvBa~VW0!*WV|%>ucn#B`j6wTu$DUz z6eP2bbpehuBsi#%`qF$nBJz2zjI{=S>9vM?r%zU%c(Fs0u=>}weBF`rtecve8gBR%cX3}x zGnWnwpnre=b0zTYvYUsteqv_JiLE}%x7A>ZmJeq`#t_sTJHvRWA*WqPyb$_kZI z(tdB55*M6a>aefPlBER3d5PHKDRxPr2I}tBzof+fp;Fu1!5QUFgP!4dx4K_~S!V({ zp|uy_@*NJn6?X#X+8u=Kyn8xLx-Jt+QEvae?&^z6OL?jSjHY!l$#x;2dk2lou@Ex>QRNDu>*Ia5i`jw}LvXfAGU1G{qp%~Z4@1oi5_ z4=;+Rh?Nu9S^fS06kI?hXw(8_X5s_?LSss)(lCM#y_qks8?XGFcI(cKGXi)&aknhN zk~tRi=DNUZLj2GJ_ZYPC?gO`vxFu9*X$>3IoIC7vw%RtX|MHmQbbqExOi#35=B1~Z z%6jeZVZToundNtT~DbP2ZyP%qNUfA!j7?--U! zlqicVRZK;`7aseaEcnVlLg)crCE#+p)feu@E94?d!Yz|~f7J=cb&yHvVHgrdjIsFS-BYadjvY>k08EUdmGhn}L zax8>0uymo*jKg&MgLj93hy-u$9K0OH$9l&xzsC+nNB0xTjqXdHHq^t$7^OsI_-Iws zU$J|6;B4iE=_kIQBEmD4bWQ5KpF*Ek|w|9PeDqv z)J(Ek1v$NpY{lM9X|0|H+*sHx2csihv!guwe0_Jz5Mb&_HIuE!^-#)p32d^dMKh03 z#Ivv@Q4Q~joq{$GabiU{;OTw&K`_5uOT{TPf30@izGpirllZ5`@0`2ia%qnP1vih( zfKH$?ejjG8nDxD_sTp#HSQT68o%P+I@Nk4^MSEqem{m`8T9=b{`6WEWc z^|}TDhAc2~17VtIPMzo21OHw?i9x$Fi0!YY*N!1ScJ^w9=lVZC*%%sQ9^w08PEN}*9mARsCUkJvZ5=4 z?Gqq-^LU@Pa$4Km3^;<|&&$qWWm*! zI!!%2O1as#i`)Odtr3g&t$#+s4v1urHB7sgUpemLp&~4)+&Jjfx*KzwtokIVjlN)zjVAa%!gVO927}r zI(wu8tqPG%^ug*G6k-0t^!}WDw&@?s6+8W%G6Ma8pEw^;KFz-TkEy0I7hWg&PM})wX!4FM}tB9lRd3z7VE9ZZxB>POEu$I1Qb39%0m1mgUw*`{Ser z6eyI>TPstxEsvXUIa^ssjm*!Tv-}DX0BGfr=@X^^ zTllIet$PrV^3ekNl%cM~l`is7{K8Q>-!1YNXWxY}JuHBVhl#e`v+Rz}i#_azZGFG# z1v7(*A85?q>I$Vtrl(1XUk@eS&s2U={3I30;tzzXecl<}mPK%>6l5;m1rk$hYtOQ; z%UeP+W^@ar%1W)&d;hF1&CL?5>kXh=VUE@IB^BE&trN%93^?3`0sQ zaU1{PVYMu+E>{lPly)`U252B^V!rO9tnZ$`zY%i@2n^!LV3hIXOK`=LkdUy;wLocz zs)7L;Bp;DFx06+*7V)^FB~g|So!yz$mfoNSY|sb0jn-b;nx7-iEGBk-alomlo~~fc zw&CZ`-jr+rSi`?f-KRBr`5OU1p#D8Q1?qGnR0n`EuU7BJNM0E&v)mln5&--eRnY&X zcosn#y`ih?*B-4pkUOS`&8h>2Uyo0tHCLQ|*L*`mk|_;?&MXv@tZ5sI%TFLg;U8uI zv#iVO-u>>o*~5d=X!_ea6q1;5vYqk9G5^#@+! z>Vf6?w$;-a@5JN31h0@ni^d_6+XE)cmCmcXL^f`%t+ zkUOP85wU_cY9%u)r8esLH8@@h`mu3y*Ii5x3^oJ~G`d~Ei_0XM9b#_JG^gW)iA63F z6v;G2(PSgaN!YB;9Q|0_rc)(ct&%_8;9}4EAK>W`r#|O9N?6Afl-_z2LjBz>O}47# zIP4*%S%9Z@cx3-Vn{_!HD2BF#qk{7nX+-Jw+-b$jF`VEpNx=&w-jkDw8Dp$=<;Px1 zHVj-h<{Wo;Z!F#D@p72HGW00l*X+2CCy^d|^MDN!E&_2sYB<0X_v z2*HG;)tUG^qhk4yG`vVeCSZCQMk`9ltfF>MIU|s4au_Vvak{UHyC~x?-w_in66+Ym zZc7v({Ci;90v~Fb7hfX^3$mbxMx2}iFksS(cdYGS717?b^8=dTnq^WU{c;r$x}lvo znt*Cv<_gRC?JSaduq!T~dH|dz-Tz+sDNw0^3x1EH+pMkU=La(dh_0J=&PLTj8f391 z+s^!1i9ds&p`v})OsOAG<3HVyigzM16~3aNrwth$9oWg#_>tj`#YrQvv?{iy-@%M9MA|@9-7vQ8pstOf?pOBGP?3bC)2m7DORv9bM!uT-ow)4(!;u9LQBEEy%NatBvyirO?rrbDgftT3&n55Ysyx54Y#{u2-@FHF<>q*p= zb$8ng)QjV_-VYDUa}?dCOcDcaQR}+y^oD`tDsc_T8!?){eHp5ez((i3QFl$(M^T!9qHjAHEy20M_wW31(S= zd~p)UMDr>}U0*zx&!$Br6Vg7RVOGLN9!*Gnb^*6_dqBydSlS03DTfm~*i_7}Vvg(< z;z6g)$w-le!sW+A4o2!nGdgc}7#Gc5Kqv=_XhwlRmPxMhpJv$E@+WSpDEX3|nL5Q1 zHE6p{*t!T8IbOx*wDfynq8eW!b z-tclB_7q5poRxOj-++70De;jp-(C#o`eur{e$fVTu1riK;uq^*7kEgGAHvc5=0V5$qSN=16wKl)G|;wFgg83L_13RwasaVv=Tvi`mFJYo<6UT%%&-P zCzv``Iw{pi5hw1|V}7oRP6n7FD}y5INx-UIFzi|RLcm`LFv4EC>jdE03cVQLPxucZ zZcI_qN*6>OM`7z}_u!51@52HYMGd-kI$Y$T)mDd~E&J#KmUD;O<*y9-KmT?U?5_sm zhx+T)j5_6bPK|J_kL)H2v3nyR4pbh9Ob!RU-o|XpP)7ZGw zdjrw?-lY^WLGgX=sLHKf8}M-ZS|PRdu%Q)_N;Ps5+`3#;Xex<~hSufGMb6We;Qa91 z#`GByG7U|A(~}X{Oj>*~_$gHg63F1D-S*Ah&EPe!=Us~MM#;wdnAR7J<0m8M=IX?1 zU6Gr4YU4gk5=)y1>5L|ikKO-Eoo&w@LdGVX@3k>{|70nqz0$># zt_fWtq6iaYy=p3vmdZ>`F^t%6%~OaIi%S@jo*f-OE8yuqe6yS0Yajf5ytc?SA~r;f zdhgV!)ybb32TH4hpvd4nQJE|ys)ty%#CQB|LR2ZZDIUM&$HJL)s!rNrz5Tkwk3HYi z19+HvRO-DC;z%9>UnYwu+GZr_WKOPFu@i#Xgvpt!)S~oCL;))JA8k|Mif>yYnMmF^ z%ORb}B{@jlXD*i~Q``V*-~*~*9CyMvffEjp7rR59bY;eSYUG`fTmc^u*v3fYu6p!p z!ENGe7oGj$p+Z{|+Npvkzo<>`XZo8mm)KP63$uwOgLzA|91KN1mZvo_TpkFer zW#OEC0@S2TLJ%G)_E8*!F``9gr8Mu!v`}{oXavAn52gOk2{#4ppIOJVwmY2^O9$F( zxubiyPN!=^U@9-2*yw1CjHvNzfb_&gu#p0yt^E&%Nv|`Hk)K^$JzcgaeKS}SeJ0i4 zX;@2F+r-HVV1s&VT34ecKk{iDJib(nsV2gl{Ibun6;sVVG?8 zOTW^HfTUYifLm1dP&NPH@{{MD27nVR+>QM_HNfW>c|5${> zUgx8;gEcv&I_|Xp*>FQ%@}q1t7@J_CzX2_&g0HiJfHJv+i)`ZKZv$?U2@hE-mHu)~ zbZl4&<>9--=^HfZbLNDs>M6u9RZsn}6+?Vg#OM=|rtkTCk6@0pTZho0K=m(DR{na@ z+Sc0`(dE0APGKmV3$0b)^+a6q)hl}bG_;43y`Nj!N{bz*qe)j7@4vy$)(HF|H?U`U3=A<4jRTLTgNOc)7(#Zl_6l4!++{NvvLbf3SaX zWB+s`X=&c;DE)NOOQ_3J;p(E%rxxpDJJx<@Sp{(N;MNB<26qtd@6T8dQKs7Y?sI3@ z9EG#pT;$1jX9EKk52TWR0EgsA?Y(j!dBYxktDw$BNKMnXS%vX388c> z#(oQ?8Fd8Gu>1%ve?ki2olkl!F4~tq#B8LD*TOFO-2@pG=xF0JXZAEOr~Y>DbLTVQ z7=>4jYDZFPAf@@WM@b)EU2LHJP+>;-=8o4|TRL2Oa>D6~W`jGrJHlZ|0YZE3X%9gNJ61xFpOzPO$;==q$tblwT zoRP{BtQ=0>MqYZ?>a!`!67%zPU>X|A7Zk~g$UP9_cSnji8u*FZN!*_=YZeUQ__e78 z%=E){nMX=}5#GWl*;a^fb#Aj)Caq!mRx`m&w%8~dREJ)9rF$g8S0`Yo4vqq2C~2eR zp{9Gjsjb=JqDUachRITLpPtcV$9x)?B{uaw<$0x52dOtxFViO1hrtXcG?XRJlJ4yA zOFX-MJI9JfL3`E3Axgsf+>SvGMnixTkVe@owM224>>f$B5GB&Tf6-N~)(>%;6o-Ta;S@qMM6d{AOe0njrdUxN>b>X-U)hh4 zI0$j=p(&$4){+C2cox2IH9V~j)gs_fdz6p4(_~Q0P%FiXXhk+jBf+kJNGU{4g4vcx zViv+rgEdUEkjy&0?BcA_nl+F7BVR8?*sx$pEk?st5z#ey?0*J}HA<pc#$~}h^zjUfB&%rmGZ_|!-WUUjR*0}-;yRiw1)41_pYep(Jd z?`wl0N6W5q*#*Zn$%l;>nW$+Kwr3OJTV*zC6DD#wB(&9y%DFo__5lJROZLq9{TdL* zuz(%*4Rdr<##i^&NVRaI9k z^ex<|_j8>7f#6Hndx~v|4~@^nw#Ng%bh`1fA=tO z|9Js!wy3YlC^L{$2Dt@!k8J?YvmtJrBvM$xh~658QS@w7YT7^Yfs0Fs+Oi0~+>bq^ zPyi;l4zxNBE5$~6bTM)btJM%UwH>iGj37d2U6|DU)I`>!%-Vbi>Dw)qW^?E9J@ zEU`2}g#I0!jk0!SLn9-I05DEx`KMUR$`^S<$UQ#{-h<_D1-#tcTfia)NIC$UWC*Za z1og%*jn%0hDSs*C`C8Khz9@(Z`E{Q4L2cGqq$A$1`bu$v$A;}yILFPddlWcX`z)U# zgTbK%q`rT!Tfs9?}5edRsU_@OnKp&d;k++Kop~&*v`+n(Go(QRZ{znZ5mr+*wEOceb#f7@W-`Cq?$-yz9Y;UP- z>}Y7_8V7in@a9Gs+FiS33IRuiy%Vpwy>7 z?I3Ala_wK2Au61&MT2#qc}0AhIEtCZn*Mdx6TXV_F0!|?hmAzm zje>V_EUP!Av`DJS>Ppv;H3tky1X(buIXy@Yprigames^^c@HiB7;vRz4GBltCNCz4~SdHJS1_G_H;}BNA}g1-N#IXHZ`E zOl@zuBWr5DaMxt7o70r$3n#H{9nbv(KFz7C{e_h^n#?xQ&-lQa!Eg zWo7!&x0Gf?Pm{PFkM=yAvCP!e**V5K$+uJ5P*h1)T$pUG%fYvi{lS=xsEx1dN8+NE z48|{wkNsOX07GE_`RD`W#Xi~Fr=qyCg+ZoKme2w;nOOvf4AdcM_SB3?8L)Wrzy!|D zr>mKFW6fChSdYA8UO|QRwnyZDszCSUk-nLc(WkuKPMAgf&=_Xq@L7|!l5w5~okoKp z2d>z3s5@eYZJiyj#mP6nyY(08#GUr*mj^Vo?+IqvKDpCt=0Xs7r3i1A%UM}jW&i_R+`;+t`aOM#o4RDr+;!*YTLKHP0yB+^*c>khN6V5w zqTD?U43oP{tn1ce@Z&r;d9mI(jgnSMc(kn>0vKA%A}2dCiArf@Q@3eXx&q-ns0NRVM@o)nBltUm-ie`?gCLbkO@KbOh1PYT50*(RYhD>{rGL@~8l1>?QgAYTj=z z)9*D6Nxw~aNj`m#dq%4rD|iY%CbXXmQL~AV(eip0oQs4cGY0hKq z-k3)!epzzdpVV?o&@mgu2i2;1>%GSgtJ@LDqA~Swu>)$e_V5>654vc}0DQK@Aj&5Trc1?qT_n#~V0M%{MOavE1+hf0kP+D8{fM zu?L%6kg*|IofAn8MGqR8UULJh@RIk0F^>ToPZ2z_6J|j~ zd_F8ok=lS#bTnIQc)l|i=p{?(XxWx~oO21qK0sXb4};Su{&v#*ORbusd}fx{&Jfgq zNDV`@XiAm0n@l@EmyWGhir1#)J6voRb$ez>5=Wqt6e4;{y_~J-d|-J$+jwPIs1a1M zimlfC!+oVeV)p>R(!HLaJ8!eQx9;C_HvEQvqvQ7IA z^&-!xsaY<#JJNzfPNliU4d5!J0e8QrSAkc(9KCMhE9;KhgG;B>5|umGpy&JZ|6Jdm z@7w&&1+IS)Sn)TgYo_8DDUQrNcQ4;KF=y)x8x4Qy)j9C4uK7PVh}_TTwexwzxDu{R zpxf#MMiE{C?GXsxaBjRbG+lp6x=jD=yv?5R7J4%F@Mz+u-tDU#T(*GzB*YT2)NmaPgX_RfO2Np*b?=QGAPx*2yknH81~XXPDM&<+4?2#FOVltS48nX07PQ|bDhHZ3G@E$T~Yw-9BuX>Cwq0F3$ z23}Fx>681@`H0G`3Hwuuaz@O!900;Sa`n>bb_jCKAVU>%5J9Ip91bG|dU0YhIgf7J zAxH)FcM$VwR2=^K4?Ui6W8-42z@`Df_e~@>;KH$g4gu_));V3LtTRFy$CD@b8|f=$ zNY5E+v|A%7qc8h*ZG- zglPi^2#xsG3|V}W9f_)+h*`F7X~#+3>1gYV7(_$4@F2lH3Xng^nk0>??DZ(Z=<>~p ziIF=m^F2z0+YN!wt#DIZTwg~hL-HoKYt{frrRkFgL`=wNR}IQx3hRFRIfp^Y$IHyh4ZO5hvEoa8>5u;5>BokrywUl-T(Q!V5J%m)bs>l+E5) z3XRqM@J$&}OS&%z4(&QTAGgEmq5QNl|IY`GpxJLz_|oqiWNN@jMeJtZ+o~hi|U1BSuM({Z$TTk_Qp{Bbl*5@r=<0HX>s$Nc!gTpz%FkERP=j8?OiSmzd~9k0ju^)p0H?`*nJ~@svnb_M$bb~sj1>6&R9OUbWym(w=ROg(dX} zOqo-mh(QuYnW1A z@9j(+_5vFXu|}p*+$Ip|G;qYEY+y@hSea-=X643Or9RoALwRD(Rf?6xZ|EqBxQ7-J zS*|#?HnZnLVrZi`v*QLNKDNtJR?39aUtuZsWv>Y+hmv=^c4t3hC4G^&-zdT%RGg4l zv=)i{a^{jpoks_X{2s@|NvT6!OcdNVyY}3~5Uh?3S!rM^IhFzm5;m_z=FLt>6URw= zbMsit#Hb5Z+XkgN>=uQHE5X^Qqf;oVc_x@dup(+WlYpTe$Z)fXSib+Tr};u8M&B6S z<9WO#HPomL0(*Y(NC~T@8#S?nH1okjIj{^PIl<#T3R>UEGD8)uUH0%?PY*1x5cl_VAa{Nw&}uF?Oazb)n`B4-*1(pNVTvSi9c!@ahu*4cKG zyzkNJV=Sm>&R*1Mv-v$4iI0Y36Z6Ol{4Pn86umr*)Q^OMQsI;mrN*&PMO; z_klamPR(3Q9%&eP;hlTzHkWbm@sbYrw3fa!3$N^*rWw1t(c_gYk_=!|0$xV|#qBkv z4!_NHHAXBM_K#tKGQA`Rp4-q0=2w%Tz-Me1#*-r#%V+&lHX2bL zsvOC#r|PGQnO89-v65K;Xp^MfV*76;f(;V32}2bD`hPaUutVT{Q`|&=-Dx75_vK+o z&=knj{Wk71{7Ev}(2gu1rXiyY>)SO z$z;v^+Th^-Zg#+!klwUqAeCwdz7nspG0VGrWEH zu0q?hmDN$kv2jAuJIOH4qqfH=<954&E>v~d<8(}#LMe})SSV*fz=LxqQ^s6uZ9URe zQizm*IG?_(p}0rkI+0-37B`<9$if%_I7x0>B_N7?fSWD`XHyee)!mhyl*(mw4Du&Y zv1@nCx$?x8>*AnmpO+tLc7Q7n)fp!7fYSwhPPRRURFpu)8W4i zl@5|I$3F*eVPztW_5n0tYMgY8}eh zo3^@N$mT6toi{TwQl#!rN7`d%PN;#d9ly@b7=Xc+UW<(1)WQDv$yOK&r?Q%aaE@p- z_gq!MN`-&96BYo7SYueI<`?eX&{t!*xg6nA)b--IYjfQ2zMgbH@4BC&L7;CQvv1#) zQo@C+C{4Ch*dq}C4j2s0DI&~7W&}ijg|^S3iNq~ms7q{yUM}otjABv8)c=TH;kZYh~j=10}Ta~G)A{mbL_Pd#G8sNYWr)4&JRSrnXu`YIBQ zUZOc0YQhGNk$uX^$oeU_DQ4X9;&ZL@2IY>Ib&eyC-NSeop;9=FRj;%^ogOrnnBL6TXf3|A5aK1>Ru``9AUb7N{GK!o%ZSkNPJGn)r}s983V&!`eWPj zji%|pkSTn!t0mt`{Jvlr+UyQW8b0ROGlYeBAR>a@I zl|9Y^;y&x+>o7Q2Q6mqHMudu)?39!TO3V+cp>DJgcxsxI=%jSR-UhK&c<~2Lmek5! zpt*i%$xD2>5)Z}vxcV0(EiE3i^*6$qbKJ{KxZ@3kn#uK4Rbp{;Ts3n>#^$&^)viWVzv$NjSAysyG!{hAblOvP5Ne4xD6}^*WRD2B@ z{ z*l6KWF1q~+*O4vor{C6NL3q((c~)V!@*r`G)DzJ?c&B-DhKW}Vxd@rTA55HZuOo;b zCM5lS=QgMkntZ)3-*>hb32^w}p9T-AGl__=?eO|u^NRA$zwwY=<8(A)l6+SQeL^Q? zCON9f?etT-YH~c2^Ra5<&8C|Fk=*YB&ada6ZYc1u$)M#W)W4Pe9^JsTbIq-8;<>^M z-_{=B&?`Ns5kxN$@fjpQ4O!^s|yRaKXc}*|Fu&-9+1%H=4(q7Lc~ymlxoZj zf3dc#&xBR2Edf%W(2=@iSyp$9HlB&NE}lEj6o9uK9JGgVM+avuVSe1gR5Z&xvB$(z zd1b717t&JgFh9WCSg5*;Z+1MuArQ!@Z0?byKRGB!Mt*{_U26vxb|Yr}2Y93&JUdi~ zW4Y`)0uV1?@rY+C)Wt9;r`Q~-Okrc_=t?6^EQa>Z;vsXD-Nfw z@kUnyrnMX%M@$&>+d3VOe_xWGcl(9WjRO5i73wulr2;O#?~ctsmWdc_xf|#W(iALT z*ii!^=)@fc&L$WfFaYcN@O7YC#jhqS1r`EiZblmi-8rXNimKp$_CcABH22Gf9KhO0 zObQKbRe)H{vWmmtXZNX?IxwMLb9^7rF+$o;iI}l@%p4|E%I}|Fd7cW|Lo0+z@Lsgv z?q2UVfLf~Cw12rvLpwXhT|pG-{1X{9z3t$-vzXuc%=2iz6L>N5N4K7Z*?)Ln%s**L z%&pJ{3D1Vt&a}InEj9?*vU4=eOBF#{1;cysiVP%O2gFqmEUzA*yO==e^pf;E(Cm2( zT63835wYd~GIex4-3fc^NYjZ03ZW7?NG2#AStXUr2x!yP2tcyRV}>!&R7}M?;H#yD z)NN3W`;ReEA4EG&1s-pY<`dy_XC zDAY>P<*^5UP$0lhLXsQ3&jLPr;ofmL|$McaR2m8Tf0e#{zRV7YpXUJCMxzF!}Tj*D;jf8 z#tcYBShh%Ua^N8G_qq|LXx(~1Ev+(n+7Fo95wi;X!b;sf`~ZZL=~%;;K)-&YE&cwm zcSJg7TG}au0c(ad$OSgilpQMUNPGP2l(Y9M&DQC0h9l^WqidZ~t62y!pWL)L-ND;= z3}_Hg)M6&Et?lZ7>N}9LYtrI^Zg`C5C0;e)!`&eOxKID^do2r>KC`$Zxpw?qJjUMc z!LG3}js4%I3NnkOwwSn#3x7u@CjAQT0?Grga1)&VB86JtdOFWw&|@YjYfy1<6JBp# zq+goLV*CQkk)E#tr)v0C^n$NP9i6WQEx2$@3!D~vMN^AAZF`qAEX^6+sS=}zIw|Xy z!Axe66kgG0F16vgnQigiYxmwtvt0`+qujIU6*Y8x=|?>XVZF1z@Kx=7wGJ}1<^|1J zV?eW$>?A!JU<0N3>C-|0wSDq3!TGbd`?ckLkTuJjP5!-MTWzDgw))HFNQ!Q?&eGm5 zY<+S$6$k()*YhYu^4UBwZF&%Z_C~^$BC_D@JVru-F}A`>H}kwP4Mapd6a;hw|*%;G8Jy z;SSwXyK;Vcf+2vi4lJZgYilM>PDy}z>Di^XnEAj4n)`vp_dIF1Ww8<$7x!J3a=lk@ z2Jqf7A<7@7yp|%WS~nlzmiRC@F6j;LjP7XS35pTSEfc@7i_9%3l=p1RZNLSEY1oqg zk2)eEfPiqx-g}{eOH4=x(TN;jE-|O3)G4BjJ7@Eyy}5o5R(S_cLkmVOZJ~L7)6`0}4G3f+2UI7z_sgqHXTE|yE z^|ko^JTl-1;HYwqI&zN0NK~r;u4~mg>Qcfr8#@S(&<#sSR&@O_q|%AsVsv?|v!Fy6 ziR~Y1lB?=ENo9=5t{-GFTcYdpUI-EMXm_ylkmk#qyufnHba}+pf0u{>$CDx-o`4>){u~9I)a}KAhP3Wxl_>znKm0 zByhfk$qC4Z4%I&KsT0`Xxs>*_0`?bUK2xScz^yNr@T}7=2eFW*6%(-MtsXQnH>$-d zMQYKc{f}r+phJ(?3<-LBmUdq<`*Z<0Y#@w2@m2kDP|YAXXqsz5>ZMu_a5+?;lcMf$M44vIEaFI zetuqUyZ(@LgmFSw7t1`an4ZWt8c`5zqLsJLs_62zu~PuJe1Oa63KCp@yw^Peg3@>~ z+pc(M-M$KYIs)kwSeZrvo4&9V7n$g?V2HZ)Qcd~~x4y4ANST4kf1j*gfGVPi)1|OF zmm5W``wE&0D?l9aKxKQoR-DK&hB1A7|E8S~IC+4x8b7#9@azj7QAIPEt zr&kmTA&MJ+N)B~ABcYYbPj<{;<;@n_$or$rC<+h$P!wO3ChM<*MbQH))EByG`ft#o4z6#gq3`HtY? zG57m7!gbzO8M6))Jo&$YeOivJgZp2e=*M;TFyO(Ch*XLUBA@fJ28R#&;b--nAkFXMP4VH$BQ?Y{%%-Sya<^TCj=cY{s^tgwXc4D@P)i|Z zLMo><%9xdfS3_N~m+RxX)FGdL!#&vW=Bo_}6>m)r(X3yW?mm7aaXAxD?aF+h1!2IFiY+*JbGwRUAav&mc$-o&;{5FO~qC{%RyFq?$sGpYr6 zXoKP(G=H#um)DS``iAr>ALiQ~7yCt#l%|^v!()(6n@M|2Gg;vN=57%7lpMkNh=_zf z#zbj1x};%K5hOjE>`EmL64%49wte+)OnTB|EcX%GBiO@lcRb9iV^I4n?W5C*3QG$- z3v7KUO}<;-k;%c9$&eP2iam+!J!)+snLCqTcO1Fb=2g#CH|qo^5jR@wX;$MbdYV4H zlH6o3^NT*bMjqZ#vwmZSO`F{yxVRc+yz&APu>i2(1eh|&8N4G{U5Oyt2Lgq9Ky&J^ zh3+?AfSJW`s<*uYu$k^R{BowvcP~wiL_ML1k979ztDPMK&$fdcyz$*%mr;+xU6=PG ztQ2aSxZcdGNXC3Z-A5+M1{IPIZxNCJE3) zc{oq3W?*qEnuJiVWF!_Yd&BMJA!>&0N$8)9@Q%;zv5(f|e|rh6@8gs_z-Mi`0_bd~^-X*-C##W^k?pC{RM012 zNqITS@lA4D_b{s>s=#)m-KdIkH)p7O67buSIis?YLba+9x@i2{;M?64_Vd=?zX2K3 zv4R>TYRhbyEd`&m!8M8n(PU;Om*k_j5J*#se8KV8w_Bkk$uOpj|1pM{x+-FxT6oeb z8}r%Cy~>d}BVH0r6Em-bsbl}$)!YzmT;IN&gKNiT`w7V!wq91!iP-b6 zbxlh0Qs=VyP5CP)-(wgg!kJq5=`9uRSc(ISAl13nOmWVUk{t)rG_wb&-q_=GNW_D7SrpKTf;<{+- z{_>bwoEtP7nlI*L1F~GbK~Q&hceN8RBikS#kZi#6z1Ghj^@^9{PN}z4sYQRU`e$Hn zHHRX>kWRO6w*GUI{y~NQt2+BhV$W=b*<(Iz>@1L=0Y-)*-D%gi`YaqUqI6b5jyqQ; z*Kw0w6%X_J-cf>&vw~Z|=o@1%a2Tvmg4bhsQkfGTyb*_Ih1UE1+g!^cJ3~0!oUF7S z#xAhPm%!2Zc>hsQN)tQlEK-nV zH3)#cc@9EWS^#vVZ^(ERp{g^{AN4M^uE>j@J19uEQ~LLnn|nktV`Kq6;Iq zIG@$mBX3C?*fiW#LTJ(6Q$dfGsuK?$*V0C{i_Ih=(Btnoa;@?1m7R1CVC%g?G78+Y zbiC3|1z#0uM1=l7p58JjuCD9a1%f-l-3d-`cXt{H9^BpCCAc^4(nzpicaUHqK=1&; zJxBu$!QIZz`_*%*_8$tW>4v@6Tx-lR$JL;eaLY9E^g{hA0f==4YmyswU&P@~n1_;P z359qozUUCq(Y|FwntHP#L0^BM?qDC8gfdjoj7d#Zw~b{C zSx;GB!SPCbpVUlS210@>IeM_oG3E23eA>!$O}~!M7uBtGTo8w_PbstoB`%)%#3S0R;Si4vgtkd3h7 zw1^mNq8qzmZbcfhj$3O>8#9)F!mag1a7a4pn(k@wS9gI<@|z^5UoHAmee)f@ba2U* zwQ_$(I`PMK-_Jwx`D<-kL~N4icW)Sfl&YqY6%K9H{?4)au!!MQLr~`4m(4;6vSmb- zc5{jiyB=@4Ea*FjeY-efb9Qy%A47Axde??kS0zR(rKg51^PU1|l_v`>t*rgIo(?OP ze5jE8Q{WbwiGo9QmzRbM$N>`-Zi}Tn+jK70`TbTmL?gKi-jfTO|X(X_s zHEim;nzci3qo#Nn)TDcNl)aMJj`qge#B4L&5Q%u$OMUo7%+nm$NAYjMP`|L`#*R=G zFf7{HJPKf?iZoQ-ouv6{19Csmyw+Heb|9?D4N;jXXa0F9wrg3!LzXNgBKGHH<6rVe zTzQ;nlVaVxrMC#(v{!vQGejwa$b(}3G3pW)EU@*beAD!2>?r-fnqw64NHI~vCaj|E zX3EQE)L#s+1+*AUJS(jDmP|(knmhw*`b|b38FIG1RA)=MI!=_DKRrUm%ka zGHs)`$J_nCl&f0nk3AsmvMdE9X+!^&Vf5d%o_))KJ1{~~NHEn5;rj{BWN4OG#wPVD zzs^_GDlX$bV(s4qpZIqWv31D8zD*fADz8chsEM{)kg#PVw|(NSX2;q&j|QX^ATf)( z$G4>X=kq>3ak%IV++nbK3_&}67OpBpkM#rjM2>lU1)q(}u02Bbq(ajb0{I1jo(tU` zkD2bZDBi(Re({`*;X@(a&78j0Vi_7veYjrfhdrTT^kQ0rml_^7y{T)XTAP4*awL(z z^`>Wo$7k~aWzSjJ_LPqY>Wn!Gwb!2cD$iZRn@(0alM%9JAISo1MY-JssFbZ)h)eqMOlA4sN=dk*n`Sr3ZECZ&oA-^5@ zjMx31YARnYa9me%w6Ib^z3WJP(jnmjlE`Ho#DdaY(FKrPQ?h@ zILOsurCN3#evFkrdXV^}i#yhW-N;#;??*N%MKI*keQ&P@TEzNBsTnuVxlylwSt?bU zB~$GnF31n5BKmYGUA|(}hG=lKD*WbKtnm81X9e@0;pBpU&8Og-R;~wTHT`FXiGgJ0 z1(NagZohw95OGu|wf8D3XNeHn4oitRI&}(pi50OF|NX=2fQLi7IJ!x**LkzcjUpT^ zgcdO?p1kO|b53AP<{PtP?DD*^tC$xfEO0?swa%@GUVTpF;?C@KWpN68eF<)12NK8n z#$R5jK7_R{Y@LB8reac}%wWm1s|MlzZp4i!owi6@r6uyzq!vB4n+9lb&hwEU%5+05~d4Is|_u-u;qO1yx9qp;mCC8&HD+WgK2My@lMqmW6Ve%Cq*Lw8Z3#NdzWJft+-@CEEeX509HQF`NAWR& zkz=l%hqJ5{46Nk%DMgpzYzk5kEKjD)YtPvia~*v^N^ff|K-y}&YhpVKS?}&HoJyc$ zQ`lr!1mQQZnhZ9b+QGpZ#gUPx&DTT8^9sLBCKdYsxZGqB(U2U_qFRt_V);_zSV9`z ze%ggnc^YE{dWi_dO~}BdU36ZQ=K( zsU%JiFRe7%>*DX&fMx-H%lE=j3f_~h;%T<0^s zXER%fx$x*pzzb0zNobok)>m6l8ahdSy*b(pf+CRbqp^LyUyZDzAWg1L^;5O)_`3`r zOvIiC`GUNsl7>9va{j=^b>S8Y6TEv6?3G?o?rC-0Q%kBYbYuNE$?;?GKY{B&Ew@5F zO;;j^hOhKyL4SA_i#sNA`Ysp)d$31FVxMyQ?l4;J2_|^_dNfxT+1nB-uUX*Qv)eb; zmFKn?dZfG8v7O~2@4o@TQ2|?fce($tAgGM8m6x*Rp49Ki&MM$IsZBTTpD#1BM`|yR z0$*z`bGkqc#3A(s1{~1lig5D4n~JG`D{;Q5XGHo2$rDe>XI-#lEY^$F*v@arg6#s_ zM;1mE);|n4cpZaSz#!T3@;X2VnfsRvyi^TF6R1c3$$^fu1=yCEGUKZqBt`xJ?)a!E zlnrjg|Kk8<{5tUkh$4nnr@O|V<2Q^+H&Zv<=qj>qFk%+oknQE^|Sgx=Q5DoRk| z6}cqngdb=>c@S{tY1~cu^$r@l^$ewkJz43NQfaF+1BWJ9Q&=%Dj`cyateijdJo@x$ z((nI%Q1tYhEX9xzG}+47xZq!G-9N3evWOEz0W<*a|0Nv$d#P2ozLU%0XZn1t|7m(q zE+`AXwo>4_Y0>6)H;pJK|G_i~Dgat@TFVKkoI9L7ti+OS5HyDxPSF{E$>kEeBbIN= zAOcmwlFNKjT9}2zDJ_7+KTXADja3Hax0t!T!#0LICDVD6`@pdH0v-_7^>1?_cK&1j zK|;>P*>R;HoH+sTt!x9EbXLK}O~71NHAlMBJUukyTK%JW^QQtRNmt^Jy3?d(uem@0 zGLAI$-XiRJFu&_cg;RZW^bjpzyEfXV(&6h0kaQ-`VbuV1;9J<~r^P?0Q7E<z=`}>L9~x`-Wu_*R$V~1;@^Au@pa(gYc3k z&EZt14ocfY&M0;??M-Om*s{Ghpv$u`YQ5)$+c$RV%u<0?bO?CmJmF-_;>HWJyZaSE z1!av05JH}$`8_d1_*5Qn-?v-d^d#8gTZ;*dSRZ6f_y!pBM3;!&=dM7h=yOAPGiFAR z=j5-$Y`+61UH+QaWbX0K&n((X;QFMxx@poUAG~7PxU|P#b2AJ2jWAe+#B=_vBO{O~ zmDXmo-8H~$u>0!XJ)9{D^p#-D*ul%&dV~x;6UBQr7Q8!qkd+JEcJ}WTww>vQ z?A8l0G7WQ$dU9=9xv~rZbLTq_Jdc1gWB=>`S4VFq0l_IeO;bNQIQhSnvwAp@rgw&4 zt$%sag1)AOh8}u{=*of!)_Q_+#HQb*SUNDGiOi}oS%EVEM3`->p?W(9S^5(-r>jeY z_kq&o1n<{7$=9aWDEV}H2qwr|Rcgo}k+*lM0O&xworbfqB%{3S3SWLkl<<1wJ$61h zBR6~HuxCNH={Kwl2Y}Mpw|~7l{7Ql)WJL$QtU_b#N_J*%J{Wa+R@2nr_VT~JvAcV+GyAiEzZl2rXoD!BZ4j;<@nHCS6Kr66Nt$_1f^;SF zv29ieiE>89ASR6*_p6pX_C3X3X^}4;>vu!xUS{#Ns|kxHy|6h`6rM9lFMqJ4*D^r3a)|UmXeGG5z>iNTq z?~?^jr?0E8WBO)6c>@a6&ipyCB8kJ!xZXT4u}0H|JUhF>_o;<5WzUoKqWkwOG9a>& zNaooLv*&p;$lOU9R5?-vBjGTYgWC@%Vl z6nlzJ1Ie}f>wcSifd4OPgdVKTU!Vda0JmI$`knB12c4&12_iaES$#sNs>&NmV#EF` zkz+VfWPw_o{8x@r)T;j|)RNJ)tK)B4qHr&nDiT)c>14NB(yRgf*jGNsr7BC{VAMb) zDk@6VzrJiCL;*D153e77cX)c#{gj7`Y>+Udl*ne-TIzyu3*j%HliT zltKOPzyIz5`}9YJ>VGI0ZnLwk0r-)TcfhQEQJZXa=B&n?dH)&B8GxGIy^B8g#}qPZ z5CBs3e$aXLp5xqmG&yRgm0G`+i zOXc&5|GUaXpE}g14?Du+5->5E54**G+dp?zhx786ep8cfQ5a<~!TP~(gVuGw77k<| z<|U1`B$YFNZq3f_!kt;QCN|i(3{>_1HS#7sn|by?DL|m#y{F56DkaMYC2owtt^w6$ zi1lXWxO*zb9xF^sIp!hl6ayjFMh_z~Cy{=*A&v<1a)n=AEg z+SvugntmMtidz7z;VYn7h9;gbL9O$rp~t5unG9$rzCdEfZECVOP7^Rvmu+|7FI!&d_+l+5Nox+3jTt^qAFcCCqsUB9{ zzYGA0JDtFY&h2JUYLK7g*1^Gh6HP=%+f63Aw$&XjaSQkP%gEEH6Wc)e=Q<<)H>YmpkqB)!qpR`xD;@~e;c@=U}m;1s}gSi!H52{%7IX~Ji zttyPof1CW2R`A;>Yz2#NsN^#w&UdbyH zYV{7isETtS2knuWHoo#Z>7X;ukerrQJ7F0bv_e zPhopL|E{7!fGp3ZY~M~-n1l;T(&(-U#hE!VH|9WZ_!-?Vq^Ot8o+JfkoF)5d*Abl1 z{AuP~;_ADFEZ6*R!g*lUF92sAx^gkCYK1VJi>MKVAemR_+*WV<1i$gC_hv zfp@&fbZO0zKey=;=aIo-DhdQj7LoW;^BPdO(I)fa4}G3AE;|;nDj1|MWIMG-?g)in zz(SrB^7FU2188vI3k^i|5%D?y&H8nf_Rp-*BB-@rrYtVjV50k=%S7WKEIO>E@AUZt z={9SwqZqfY&NLq+mYcdW4B=xgP zUlucUu`M|3=Oa91l@eOu*auz5>dc-H`p)N@&W7u_c-NNeo8Em^AQ~?{I;xG)9f00P zbGpg;i~GI4NSr=3Pr2@%I7`QJtIwk8SUv|Kk7Uq9>LWV}tvKop-Tisss zN|viZFR@vMqHDow0ZR9l*L2hm-C2AT)UA~I;YY*rK5Y|GtB2l>N7oGv9Mo6oRlw;; z5(i0qfkZaj1~4=4Uk13RUHkvue0|;otkI62_gMFmxIY1XsSE~tN?@hU(+ELy%eEmV zS%?Wfy3lG>q^#lupykz7_2FY*eqRs}ITYCFX3DXtcT0P07s@KfG=CcS#nq^ut_@I- zmzPLdnwt-yZ?=;i3DsL0dVF3zI6VLVp*6ypJL+#T%$5J{Dz32m@u$bv`^`+>S+B65 zKr!_GIvXL1*^^2fq)!O}1KZo_)8|XD4DSrD>4H?^!otF|Jq%y2lMLVKz8h~IVA36^ z56{w@P1W=JON{}1C3uQoH@8*$o*-Ejt>=Y6ekhfR(7f&G^$Dgg%=yY4ubmJYCN--fM%fOw6G)U#Z|&UM1_m)m3k|MLPgFjCeSKuDU(zd1$qk9pP8%{>K`rqJMO zo2$q+ZCZJG0Uu=sQQW*n-l)!XI3?Jim0OA9bYyzv#MO#LHYenRz@hcNJ z(?;;KY~TEPiF_6k+Co^s|1mp2ug8(qIV?i=!6EW(-R8k=rDJx8RwnhzRAq-c9ttN6 z;0l5dRn7JRSBrCTi!ahE%Qz2U#<&~63GF`|MKdNZ*a$aDz=pB$G3EXx}y^yxr^^4tD~n*85;Le$)kLV5k7u8 zFJ#~-v7?j+-4za?4)}{*D181N6$+xj8^PnzS|f)w<+Z&90ys4#pZWgb>+T?S#s4r) zeHXD|cd<#s)nXpktP6$@&%I$xS-b|5*k4v+sk-2b7ZtvjwHw?wB5>!VJF6y~@53tU z3l}1^BmZ;UjxJ%5CmC`0I{9V3n%sx^0_m;viX->IwU+Wo1w(QWE*!*$JMVp0SpUIP zNcm{tiRr{A4To`oyvww*Y`n27rS0I2b#yTtt9H-NBOE8(U!wJMCUw=d$B{oWI{Kg< z*2FzOz4roal(t@UcwPaIJWV}M!o^*onKc@LM@Irzf%1*ZXReUahR0gK2}tp7kF18p51Idz z;1HE?r3kfD7m9;6o;Tv$OK|>D;rWf$vz98=&IgRO@LbwP$Hq2|Ob1N`nTVMLZ@;~5 zdt-^a+g9ulIHj=PrSZ8>!9tGUQ%9#5m#NUSS?KHI(_YCd_uO6~@)p*aQ}@h&iuK;e zpWe@6>UNr#ce{8772vpSc20)fbG^pgZoYUR*|0^oU(N!kk%glX^*)l584${P@l8f3%C4udZIxYa zUS632`=0>Q@3}M10*BW@@l#s?RMMr3Ty=g%AH_(KW8t``-vkGm+EBenVXw}<%&V+q z=k@$mg>%xxunaT24*|cb5v-WW^y=Opp`~D&RY~OWD6$N2__lX+{QUi!AWJ32vRSEC zw_J-kw_T^iu+?GUkAbKy;H3wA56den)_^$t{QS%?yWk@pys4;?SJ>&;PPV5Vuh%W# zw8)4W$^9;p-sDy(l=?!B+L!j{FQblOCxbbz)ibXok3o<30r1z--#rR3C3|QZYyxn_0 zG;4p3a|^R&6~v_phLwLW zrU@S7@(7!ZSk_8yaUn1SynISJ`M%Jcy9<9V7DhqNe+yP&^bEirK+_ZrCP1%7KK*uy-S>QFWou_Ey+pCK zBeko9amcmWG+N4gHAn=`NC4XZzTMy4F9@8RMtFQiFtHur)@Njcd_9^k_5VR@1%E;@ z);dCq^y;$0(FV;M`PE3ytPgy&2i=<9fx9{bB5$Jy2k$`uY!;^XhmpI1eR)|I zR!{mN;Ujcgz&l!2qGV^_8Ra)j$0X>`2ti?phrFnKRa+^e9{6_YIuYvWWq10Y(*b}C|3*~`)uMcbNSF{} zXn4W6$IFv&~TGDR1Z&fER4!Ms@lxL7-T;j|odoB-UF}75o;czskHWd^gMM%VoN(Aa=rY z6C6U=;-x^l1a^DiO&R$3kt{jHk_ABH?k$~vaBTlv_Ad7RKA_R0=leXH zeqKq5or6QX38x}N+cM-C+s}3L&+J|zVA(>y50)`|UUQz3(P8W+bxgK6;OXu*u2fEW z;^eu-N<`L;!FJXyb;m;x^PE`N*HX!cI-z9A`Avw4pxGbeq@8ev`t>_De}9VS*C_tD zx3RP8{XN9HaSm0w(nDE%NnOho*}fH{&*yuCjMt}V@~^+$rGIFlGPXj^y< zVQa5nY^#~*_*b(Rfx5)H-5!d;^K`lZu5M0yDfOJT_u`X%0f#n?ABCrBobiY8zWd-d z%I>1epvb`YY9p$YJ%s$xO216Jb4~e$cNOOl3w)Vz>m@X1Bb5p-ZWM(qZT3Yg*S4WI zZp!1ROjdiyU)%-C+Tr<^?y?o*>B}+$7=00b(+hQws^=wKNjWeI9>Ch1oxbkB(h=XW zQ;SYX$@FSh=r)u_%W5%iWsjwC;dW8I34XYXrjtUWW)vd`&2ZvRvV0omTYp?c(^XqK z#T}*%VW8rCh2j0D9|JWFUSF4xz%15y7ovTvk!CQa4MpSpOB880L(QM8e zxl+nTU*E5JpVjddGd4;!X_*o7<>^TUWzsHibM<&7f0QwxqaYS1o{5wA)O%6H5n#%I z!KjXLzA!U6=Xqy$9s_!s;c7ziHs@` zo(4VD>Q5{L86r!MBo8cgi!7D!JCF=iMvw<)^Hf<ax)hbrRea)1fMi6P+_rJ<5Ip|zQNg?4?4e?eLFrbg3_&> zV8UsaTlqkM9>c&`Iv+y=v8F^Z{T)H`oB8gFFGb(5dRqB{-9{oy3{5I1W$XO1^de-# zyI-^9^0xG$e~x0M@99zE^`hiIH4~^jdBK7p457Hb;al9b%_`;4eao{ySw8XwvwX|-6o~_Sd%4G-FfqVs6K#~5r*9KiOe{UYS4rErVwxF6y9*XIAV zeJ&n-&D^4xCCkJLw}xpv+~c0*53ymsf#h6%Iw#D#Ck<)ZLG_GD|7pn|+#{pt8_-)l zxtiyz{pm*Q(DsK91;xm_RGv-+MS6$&Yh!X%^cb=0K;U#Qn}(rXT7Ze{SsJ%p63sL7 z-*V0ZNG*aoZ5*is1>zbkb3gr&3Gpk_dPck4vSU)DG3M*b2d9U&TNG&#Y=tjEpZKdK z3k^nOC@B?0G{G{cE=srJsV1CC-)^sQz1=^m3m1B0uq{){Y!NmSk(JU3I3ry zRed3!2foIgS?cI;UP~iNLZ>g&Pn`V<-s1*}dFa}M9~>uI6oRaN>a$#=@!Q*$WJ<`+ zfnA;L$NX3rMOQ_czPn$U7yIbq$%cJ3Ujta?q?pJP6BAm@1ZO6Gf9%OI9{|$4*K_Oi z($bQ7Kmgk2t%B!X)d?eR=`b{HvRa>0|L%s|O^Y+@YKb^4*|BxjSs(y7se4ew^4d+g zKizp;#LzhuTVPBbp*3QbdcYQ3B)VTno5El|tXZt>Mm`5$PDMCZMOTmiI{yRlXcUVL z9P&aVNHm8>FIaI=@sWHUemiVDP5E^Mz=%{;6TbzY*c|EjT-=K_!thjU;U`VG%JlvV z`P;?WOa1Rnhlq2H?PW}nIy0cl0#(>O?9o_-bQmoiEmeDz{Il$W=Nu91bHG6peaWi5 zq3WxXL#bD%n2yfeKfeHg9MNJYQuh4A3OOvD;e&!mW)6LUES+7zI?jJxE24AFqO$k4 z_f%70N+c3kA|Q#xoxz7Zt*x!2n-n{x&XoDBR{AsmyAOz~@qkWIj_qBzcgoI`A=DDY zSf)cDjGU(5lz{!q?r0`rL`kQB=rp$d{2My2*0AX*6c#Jjji<=uNi5TE4|Ke|yh161 zfIFNz?1{T1>>O!N+c4_C9*KKPQ>d@Jc5SwSXz%dx1SW_Ac&J7;{!)PmfIl>`P}pB~ zAZ4PX(UyUkD3P6mqqVKl3wQNDk)RuPV$MS7a54<|j0|ucuueITq*F52<*5Jisy9OG zJ@HeY<;iGtwh%OiaRwERzRM-xD-~j9*zneQreFJT^=M&__C`sI-2h&kO-Ry&0`@sp(`up zww|f#pC^L zORT!|DopF}?u4!C@BtyOb;jJyt;Dxly-cfAuMWhbpK%Zb(_N�?tZRGmboQ^p0~n zV5bk|GU*H}1Qz?>QiQNPg-;OE@_c2>>wRgNi4shDz4KHcW22ex_fdxD5>{9Pkv8Z>pBNHk=#Zo(QV9^wn2DT@Pud-h-LxBaf9}y7vAV7s*!gUe3|Ybp zj&d{+zwHjL#`}&Aq0?K;uF>rqOf>73;e_s7(M2xN5@X2F_#!s{JVT57y>|*&%!5OB zywE!--f0wWwJ-J#)otF1wC7>2YI|bq(5&sMk*Y4OEp45Y^vHi*{fFX#3?U`NAiNxG zJ67ITf_29TU#>J?!FhRxz-nDkVEpazujpEDNaAVeZMWLATI!8~5!eA|@z%h^WDB6V zTD!U7(0aQ*U_iOt?=SWk7CD$h_PsuOar!XljODA33zf!L$h9s5z?vD@HQaEnpLaoO z6qjaFKE<2|PIfhtZ!ZthUwpRj={=81FY}}J1ofwnyO#l!m1*OL;mDa1EbVi(+g^PY zmmar);=oKL(|=?+7> zuO7=(>1fqPF%(p*mx}>yFEft&f${wQ+Shwkvr)ZY>^U)I1uU|tT&;+Em&enBa$}bX zvYKI_QOa>4H=)KAn;tn=CV5dX)6Pp{byC9`%oR#F6W9D&E$nQ4IzFo?nVb|wICvGg z?B`7}0(XrtGEb8tMb5heDrGG485O0jk`iw}c}6P-Pg#(T&}z|$PQyj-XfqS#=I582 zaBc@Q+QRri+t0e%1 zNs-#gWa;;8*{lmxQXg8UQbYd(E+LYd4BC)C^+!1zJp{lK9t_2Y5jM#7~AZhd!Zv zqT@?q5)v8*jRd>4%0fy*b4N%2(UBv91e)UeU7s?BRBB141UePSTi~o)B>}<8^bKhS zxpy^rV}iQp_xC3Y);dFC`<}-8c8@!~)HF5o+D*((1E~PZTJY1k+x_(G{i{VlKwh1` z8G{)!9R=}r(sXMlgz?{@mn-ze3qUFVBLQ}}pCiZ!ebRWZRO9RN!(V`GsPXncvy705 zV2p~ilLi+miQrrk1(#LUbneKcYv`A4x^?5(x=fQ16~?^yOoa(d;pt13oN-{^plXM9L@i|F z=qYEy{`^oTA|e*L{$3l+xlZ^u&8j)cM`L5@y{3=IzqcUubyYpD67%C1h$}JEA9Wbv ztWXxa`{As-X}~ohFO@Y9F?&V70k$yzx878;u-4%UFp()t^tA7l>ML+MO?^2?%`KX% zr?Obu1M*zO{Lj*~YbOA6aOcai&v)j^^}nUo6BEb(M1_BOuex;~06l!tHj_C4fHv*z zj^f8wC!~>C*Xxd(eDhE5_FGinXhFCSE~Y`f+F-HDs0n>+$#aw4*^$Ddp&(emvo?s( z9y>7q&e*MBz$_Q9T=ydyYL}h6d#jvceRDnt-}lgsa<3gxdvBQi=p^QP0^Ekf7$cgk zO!}xcIYQVVIaEalbmu(=hnNt_U)UN|?(qxDfzP3D8C?&ZkbYqWDZe;b?Dx@Ah;0rI z$(P2(p$J-O$j*7m zl{!Z^5!A%)M_I&S2L9WVQ$RjaNRi;{B>7cVMSiE)_k%!+Kz!m^?dT<2uiIeY|aZA&*F+ z10U1sQbU3XBvLX_h%4#O5prz3sLL#Yk>s~UaBZy#87rjh%Z^}MwZCmEfY{XfwR;?p za8jwnE#2&5wYjIC*4TlAQ2Y*|{m#wQ6lZ}kIbbo+0Tz+GJPTi6z3LQq%n)yixkKNM zpi`>HprB|TTU*zZhbz8zl_51QV^Wt?f)v?yJu6?|>_8vSE|M4ves@G^&Jm#43VYqK zbM<(u-+Gjjt08#7)AFY|iHBy*#?r!et16eRWGo@f;DmhXkHX*!8{Yz#8(+a%uqPND z9%OdD9n>d{O;a)r382R|vA*&m${`X8d*KVac(+-Bizv4)(d&I?HMsP*W2-A4z8_Bx zqz1SYfRn3sZJc(-d^=%dk9YE-*(;IskS0or_?pV#vuka6M8hOyquDDMh&=;_qdh3F zw3HZ2I&MV1TiE)30wCRwg<=62z_3~B>!#!d(6ai{+dK9B34xf))Y{gSY0fO3^>fjI z?vcCK(-PSxkh}X6dI^lU^_lzlWC1}Vo`2U2Jv$4Pn=E{M-^MDBc%Wi#@x;3d)@h|w zDJvgcGtk_Up3G{>t3OiE+bEVi_E~=ZuI%#i=(zJrxO!_=PO+bsUZ|W*u`k5E8!cQO zW#@vp47DDxfGOoYKcW5-&)AHm&}d~x1dNY>cJ~jv8Tt&vNlw?rRm1}(5qzr~Dm=AT z@Xh*xy)m9w{1HPMVo9Wwa!(5|12)(%>0-)_gr(tLC(rJpo!$Sb5+<=2} zns}m!Mlb&7x0@WEr~e&RsTF?zoR$$HrLR(xT3RAO@sVppe&M^xE{|WnHXRnQ9AI{1 zN^n7?=vVm4A~rqb(XQI6>rgBT8x;gYXCp&NxA>io^D7NfLTt~|>M2i@57p=47Y!1# z+w~1JuV@(;X71T0he^gsC{Px?GEuqbmQZD@?ZUoheb9z-6`JMR`MRcfb|ygsqAk4r z+Z6>Zt)j_aOmLM)Uw|Hc&n*=IpzTO02%kmcJY&4QqFwKQDhahs9u#5y?eWi1lbD!D zA?lk{o44XFd6-{$VpVQ>bK`5+=N0?>jI7k4s*Jz>%y->#nj?qLAc^zA#4Lw|H)cSa zfG5Sngn083%@h9LiKIKITc}aC&^tX@dqP48<6s2^>rKj-kyc+hFklOCRn>b;8Bx8j z8ejpkHbJ5N%{wE8hKAb<4ZvHIty{MRqSUUheELyH zc${+alnw`z(NH0Id;&!rlPBR6TAL>9e%*C+x+6F^?S(dXb$wr1A&apbPzxcq%-$%_ zMid2_8!07111rr|qaD{`>N<>84pS(D*Yi7CqRpsn+dgh?IVb9r+d`6pnh;O+PFb5z zW}H8_g*buIQ(w=12@D+TupWw4iv)fEayY#iDzzCLJ{~_5BK3Ihey-wk{m+P*5sSY^ zX{Bo3)#LRg6J5= z8~kkj@;((72yAU*|MhbgO@j!xF;g$=!Q+g;EA;O#F!epnHyM~3R%tillH*)h+oDIL z(TzqpZHiJ-EEq(L;@20wBU8_GYFsTi^HxPVCb28Akc~$|878W$M@@eq9b)-eiFLA4 z^S6WQ5(8smdRm8_;LsalkESz0E`+%5`%|x)in#BtHSo& zON@JLwf#iRtqwUqev94_dfFGH-WH0?%gbY!rS)J^ebCEe*0rki;}7>J#R1u}dAg@{ zNRg$o{90}Fg}J}odgsBaj2`$P&UUz{Jbs=TH$;IOka~2?=LO37UQ{5IqDa9~9wDa! zKQ@DeRAAhf^7k9!~%0r(N0A%*T@$8#nr?m5!_Vqe`c&^F#jCF+A(sIuesLtox3MqBj9Bz0@el*zu|dKrVzAnV zA1ac5*J(zF8ay_q1Shscinh?`Oa1BOdzV#~uxi7qJX9$I+CBA++8P&Os`gsLK%9vjNWz{=b zhLtY)U&TG%E*$!a{+J1WA8C(UQBDFuMwLN)3$Y}?28l_1ddp(@ZHb;DIt}zjuF9qL zSW3@Ya(AZZ@!z_?Rgo(3-GkygGaWjLP)h&h8bge#-g1iCt|Nuh2DdQsastw8b~*F^)H-ulchzG?j+%!fCXzw`wm$d+|`bSYK1GH}IE9#r~r zW;Gmol*3zFDiu=v7}}^%>gfn(^mJ`p)d<~ieA(lzPEJ!(9UQa17t+@|oL8wH)15z% z#6oeePeU<71V7cMB2=QrzPCkGi#Dx0Urvci?&Q2)X?}Y+8V3SrPB8c5@D?&hEe*Np zGFN-`n$GRQZtQ^dwJ=rUDUJH|Ikofr9;^2}+0A`_O*lcmXzE=;`48IF;?1mCyULxB z)OXn0|CZBNAojcD+tbDPx4S=y-`tOoCb4apnj0$Ut^Np6iQYl5?RV@>&?r5W-eJLT zVskP)BA(IV&MQMC9tBCnsnY`XYv>OKriE$>?ErA*7(}H628E zSk^GC3Tw@xW_)wi?I4Qm!K=<)T$9G{r#t8H%{{$v#=q;nM5^9HgEXon*?F$SQPU>+ zSG`+8*^mU10Khw{jgHMyiFgUJtoN0-wQu)Gk`H08Y$YKNEKx6Ti$3_D z|Dt^$3G`#rBPK`K8yU{x5sn=CwUnvyM`VQ=dM|PNcYSZBLh%O(Yzht`T3&6p5W2T+ zYm8l$EjIdN0A*bVc-vn~T51B*YPka-Lid=w#sd6OtAJ2^O2o^h0y$u0veIaAt^Ex$d$9usA9>K>Pue?+NI?cprj|p+y?-HjG?VePxe6@d_vJjbYExYG;zt6u&Q6PdR2X+W`^ z2GzjSbpM~QbkV(eepJ`Q;Qc~0F)89!nIiumH}6S;z}wXx)&xu7FD1|aQ;0oVzMmT; zZcJ`0=6@$eY&TpVV!P0~F4DKuLvHQ?KyvOo%lOAh6MjXTXv`_9+SE?*KK+M)Rik+p zc`H^D%$dq&QkkLrx+F5hQ?+^eulqdp7u$lsaj*r-WH(cp%>Lo)Ixn77H1wW8m62j( zduDJ1ka+BZFAFw*T#8eqix5Me8|b^q9ES~D*<(04s?!P=jin9^d-zABs$!UT^IdUl4_){?ch&K;i$o;`=(-y?l)SJ6IZ z_NN{KwGg8ZdY2|Of=~3->BHiU8dONI0WBCf+P^DpPc~OTjn>^Fd#}fe93`>c&!ebj zba@qJSw>I2gISt!Q=k#B9YobwLBIO8C$`McqjX7J3txC7`uRPj*Ro7fFAezj`}z#o zdZ77NTPlc3`hy!i0!$+dpB~F5y&V~c_XE{rlE(@o{zMj$=zvhhv2^s9h;{CXGw`1H zQ==inSZPB#l9tQw7S2V=D{~rqXTgBrSMEKNJZ))`*tQv;U1d>_o|*gG^?49y3IZ)3 zO_f|>=R$b0%67_9OtgciBE)97E2-9>)wq1%Ke_x_gK4#Rr=tvOL;BF(*bZ?aq1UTxk zb8%g+I5jnY`O^RJAc8|JE;p771Q-t`68mtP3|g0Ii6o997BMzdk%^9A^`!b=XqzCR9iLH@#;h9&R7l6u|MoQjyIg0ePh4<^>m&wBb~J?YyO zzvKRTyOSlhsfn6mJAOURqp?|k8~3g^u_5d;lrd##+F)NgBP9F(qv5!K0F6jm-=@gLemXPk0mIjdy3F+?c&J6<6U1#!~_Zx$sIL3A}*If5~<=}QCzSVE> z#f8JFQ!wb7Ei=Yek0|}wUn1!?KR@*L`y(;G~W3*VAG+CAPfPECO;~fVr(nNzn zLi2J*8@O0BA?HQ}Yd6@)1jL5}NhCodm$C%mwZacn_<2=)|GmF> zkBwF(#-%+%i!@}_-BLFvt@L)%PO4Cgp{lIti0eA4{i;Z+>b`DyRV?=fw^JsOpD+i7 zPcxJA4>Gy^v~)vn=&2Gz(Uqa~M{T%NB7>{OyPm2$*Uir(`3G#d6tG`p!jA86{3~D? zt7lYS_l1u`QDs3aMXZA0CSYh}tssnj6SY1v7vB=%Q!Rh=cnr3<1~9R>ru$Bq*K~}n z-VLZF-rnO8$d&6hcHW{u2E2l^I6fW!>X2^-YRubxCBIH!hK=$z{(ea+soR&Sg=byM z-dDO^11YJa!ylsim7hBYm=WjrKbkt#E*$4;i(zn}<=C@@>1Fx%^jsWQEu^_t(c>cY zDLTlVd!3mu^e&vy(1>Q}lXK{!-{$dXn_LBS2Waz`?$|uuM))p27tJ>d|?bZ_?lARV(HY1IP%r>J?mgCnXO5 zvSJ4V@hk~gZo=W6YQ#N)s%Ir-K9LEpY)&iB94)BA){iP92X}7_4LhMk2OCLOtW8-* zOmb{}^Y#zgfj$4(o6}DY*I$tMN>l{saI(j0K(X*h`tJtEo$%4N!{}k9W()c~40vZg z8{h?<9F;A&{R1+{0W@5wOv@rDsL-g(g^uMYEroxax3LDtha>uXZf0V(jQX*4w3jYP ztiS&vW#Hpsqq_A};vn#)3(;~sHdwk?mh2L9L+>Rl6pVk#H-DUrD=67uK=d}>HBU`V zH`8*Ks8bH__UalnBbfTk1$ZfAKRcz0jy!9(U5FMU1$Gs_-n+}c`lU19v$6_xO4b`f z5)z5225TMK<{;ozeu41ltVFaQfj#`uw2HEXEIFJuxt8xe2%*3tlB+>j{B!u$aHQci zdd0Tv?+SQ-YW3Oq_L?7ZS1~1z-06g33<n!tjO(91fHM}de* z1EqfHyAVn@5A9j2(rP|Js=87E)uVojYpG1pjD#dP6MdMe;w6k1RHafp;an_$rY~0(VrbMX8$zl0gju!ATzYn(Mm#a2HO^GqwIjGluEIw9q|z~KS@Fw zk0-I63m>Q-P6&x1Io;M*7e6i{^meuj3{oU(JgGdjSfwsaNjr#VFDPq%BY7;H`Hu0X zjF_GkOO;A(L{*kQoT^jTWXN+&B9%fx4?*&JVRdn1N=ay=3q#o0&JCmqY+y9H9=$V% z&}FW0jlg7x%cm^gY$IWgeoe|uCdy|8sjwyMwR_E-#oM~&D zy3WHxM&YMZznx6C)tnhCRoZQB9bFcPSZEY`_*Q;;d(LfmE2$XREa_{%MQ+nq9 zeY{*a@r8w*JumYB#&1tI;JfbFFLe7@f#ba<74QNo&4A!MTuiI<`Te-|Y+^&VPJtcN zEQx;pWs~y$yq&dR66ZvFa15S$-bn`c4{^)C)W3pk^&uqzAr%Bu>{->TCb`tdZxR;m zRe6=vvLT!n*^p)7&cx_#4Dyf+!^A5#KP%q1mH*Rro`v9{tm;rBzPj-80a~^ZjRe&a zi58)x2L%KRBzuvb@y~}qZ>ResPlb9{5LQP4%^p#Tg`ZuV9G|;d>8xL_h0BFwAT}#a z2fFtc4_7$-ivEbD5NrF7GJiI;@BI3sR6Vr|UqF>uU}Csu%jm`M^gO4-FA(w%Mu9im zj`9jKCF*ir$H~yWz;sxq5$M<`vG6`BkUm7l_+xd^jrczqs37^f@7t!0?YZx3mX00O4a~*iAm8>R*K9Z(~KN2Nn zBYm@V371w&RP0r$R@J7r8RY6)yL@t-IPfAq&?i+xTd12e<{y=*%{IOg{d#;4xC(uc zx&U-al1zvk_DGh`iw23lid^vyzkFqCH;PNReW1;D`KW&?;j_@WbXQ`s(y{E5Av!_> zAZ&PKWI>awqL}g`crJkE_okY5)5twvF#YeTqmvi3`1kLSsAUH|X6U-0ucChKEne3P z^X|Yxkd>3=9G{VkJAA1-_O)%1mkd=LegmpcqRWhN0I?6Kjn5{eNUItf2f&L%c6}qVt;6$4*5bkjsy0*3-rAWWsfe5sH$TkWtDs>uJTBZUq zwEe;Cdr&;^Q9~+fC1yB^RO6uUuDJ zN7V1uk^HhzQCHh`@Hchn5>2>Wh6y74Z?sP8wP+`kZNvx47E0nh_V#XRUWe5rXOS|A zu4BF8{W(KVOPu68-hk8VL5>Im^e`im3C(WDRkgLD$6jHuX;Gt3_ifK!P>Pv+J%o0D zMC)_}d0@8N`(MKzeZN8u$S^`4cZrit<21l0{y_FI=r#JSSVt|+E_>Xcz}M(vbf%10 zv4a6zTut*1A9aw(LzAYVGou6J9pc^Q%gNsw_e*fo4gk&sVCq~i3^m|Rx(W5fuErkO&AZa6)N z1ui;Ld(K2E_*EeH!RxrCkEZQD(Kx5Sw4!A&!r=a`wRP#ulMw_%O}y_LOYX`tqzr5T zzt=oM5@?jp>MH!ABJh|u-pbkpk@zX)dH>A0no-$Aj9;z?N~?#H5aDgWWIpUk32zn& zKhgnzy7%)~s}dNA3ZZ%xYd4fIWQI*vi#6xQY)RQ z%ZcLP&fendt}+F$G@fvvyEtvtRPW&Wrg_2MsHZHED_M&T2pa_7>R!#N1Fv!=keM3j3W>8^nWFwZfX;E@?~lV z#&BiL(@F{|R_Akvu?m}P*Yz^6?t2WlSmwpd(ng(4QS+>wp9UH>RA8mY7KqBCRFC0^ zrE5$TE5z~qiy@SkI$*i@l*@01HiYzEzfjc`RXZe5tG9O?^19SWx^aPba3_3Vj&a1)KExK}17CO&cd}4%saLh=&nh4rKXOGxz!YVY!vFB+q!T5B-z{rr#|-&fr`9VH@Q(Ub zR$g`L9>{`f$pv(oX^TxuM`?)vgvh|Z1-np4r`E?)b5rIlKe-zwWg5}Qr~{S3^6b;fce?BQDn9fyxynU4i0&$vpWsd19!>;t_6( zK89JYD!Zt{e!S6BO|Ul|4mcg=HDT(GkxdJ-Ohx|lo-K-PYeQcVcazFYz9#l-y}9Ci z=U6efwGkKsgdi^n+N0OCHjo$`F4V|m3FCbFyI%Wv)+oSU!w!T7nB<0l0RDiLW4c7M zw2nct40bYvJ_oQGAos%CZ8bhzmj`^mxrck)JRxL%_+J(?Y zgWyAB3yTnq(r?GNzsi5HwN-|qQnJZn4f43mj}CT{%ld~?D0uvozvt;(ccKqlbqx~7 z{&0ABc-B$j2jpo$;iW(K^=bZXn(uFsayX|W&5AY1>Pqu=Kt@=n;<2BGTp$ad0#Q$p zQUBQ)o5ffb@t~Yd4@~3eyxPScPA7TF*bBDsFiaG!3XhCU*HE~IiuR^Ab*zT7dQJhR zcen`oi;%WGYTfCp7V3p#xGcne1UPexT`g_>JZ0Jq_ovWJ)~DejESL7NF{K)5;u1+A znwg>+hShocoXCI09F+>xY}`4t!LJ11EHC~z>tRtoQX~dOz!0$Sx$e2}iO*s5!1FI^ zTe`Xi7xZ`t-A_x=hDCN#)ybSmhIJK*g>tBV!WYpr39sk6in%-DJTIqm2ztY}W*a$+ zVuC}Sh%fYsh{a)2uR9|u5p+=3ub@>go=?4Y;MAymlv|+1kcjs&$_=II=)r^`4P-D zz|Zz)(IjmI{z&5!X((Hf<=P7={Nj@8Ka~Q=ahl{1K`^RlFn`HSVo* zD5bz$o<`YbBMI(nCn5!;W!v9C#fy69L)2HG#R#TNBu8E%a{2BEj%dY2<;Pt@yEBOJ z4K$Dq-}p<3C9%tR)q0gfuLBil0hf+fdB{PNjA<4{Ro&h-SzY&vo&j*f-(d>h4k)4G z{Bp^i#Hcc?zj8dzbu!uQPuHzSMCg+cMTbx8EuGr``g+@m7wzuOKRP&>?dW9**{)5? zr+R;PAF@>uSB>!JdljFK$rE!PWpH)#mX8Ya>&{lP@>^dg!jpxXWG*pQPp_MPKFNaG zHD6OhYxzCsP1<7cuGiE07m?>}6&Hz}(tV@IIxqmX@xmxhwqKIlCVL z*C8iiGq{H)Y=0A=-bpz08;&T4#SPPjAPAi8J|{2K?iB5CPe13#ofDMAnOX@CKrsOP3NJ5rSY-_c@ybFedhXHB)(X8TqsVY`NIA@1;DBZG$?LYu_Vj~7hd%->8~5-N7&Uh}86 zdvfxPW`(|yuWy#O5Vvut5;X&jVipyu_|H0I;5caVESm*yp`xh|beWp2KlO{087(QZ zq52#^kHX9U>c}-tc9Qg>(d(K?R(5ySoY!ZULsj<01697(ek}-qwLxH-D2MzN>`L{H z42Q>jsgMJ?IuPck%@D@-Oqkz#rRg#phQ@p~eE}?tg*D6*MG(C=6`59#pssCn0epX^OEAe;cgx7zD?z4S8 zZ~e1(<4Leg1X5T*GWW}8J-CV&G-4EtmVT1^7gI2b)!Yo2^nXlAR&Zh#kGF2G98ridC(8y=}9Ez!meoEeh`m(E!$Ek3^21IIw;pFek`TArw_ue||a!-g!^ z_E_0?3EKrvey~*WI^A&)rV~0Z+PtEgIGUyFbkPIfizRT8Ei7!5{azK5l_^loQ7xg0 z+wDSEq;&S)ZOl5@&|%@WxbkXOZCt9KQnb)Hj-@DTqts1AZuB~4;x0FUOyu=pJHoYI zmf5kkRet9&LHg1wQ#v*Oaq+?KTJT&q-2xAGoLX^B*1vQvOtNMGY?1CDlNVqae#IU6 zm=@or2NcNCX?#EapB8`^b~mk!7k=7?BkdvP`BXUG0;5CV>WM}kCrP`e49l}ob$7D| zk7+a@3%@Q ztC!DPg}>AX*Qh9R5mX%W1Dg*YXH!%Ph6ar^0Ds3F-G+w8%;v+RQ{Au2eJ0JXSQAYU zCUo=5)!8gv(LWK?wY>H6Iz0ZT%9P^ZrT zLoOF$bH$P;$Vy>JuNGzA|4Jx?!b;cC-gOgV#fH^0v>b3amdkf@J8r?T2>IPY?Rb_Jp82N}tzpiB3 z*e>5>xcQwr?Lt5@%Zw(E+Y^lFIy)l5_VU9?>bm8sQfO^Ozr1MPxpWBuKDeIOZb#i{ zv627WpJ$&B0XkG*&dk*_IKTm>>z@qFp@(i@SAbQ);O#jC00b|bdVATY-(Zjg&|yH` z*B`2ijuO^=;WDL5_APz}@!QYCSC{N~Vw2y+y|U=eE6GZjFEb!6E9XteyaH~yCMH+Q z=^rVxcgREZ?miB3rzf38r60y#;0zMIm&#TcZwee-J-e`R79H;-M)&{UgJd+Fgw(QlG0)9AT|)hVNH zyPK(a3E#g3(11M=9-WJR)xv^yxt>?5o%a@@Is=ZtTHeB!vr>a6;1V03^UC7-;?*kE zq7NZlyMZ^jzvC{R`Rm@QR64WUa_!qwA$-GWu>2rKm=q1Q@;~BxAXJ1b$<)s;W=!bF z{yZXGx&W;*F6X_I{HlPQaG|9f+F^mS1a5Ef9v@QzOQKfVLu{}6dm@DbYf9Jr_@D_g z*4bc({^1MMIsI01+Cs;-8C5i27-UJy3ntYA%giGPv)6u1eEu2$0BNAh{hpn!WC!&o z=w05gt0td+D{W&Tq(0rv$E|XWx}tOgWT;_z(hSql?M`}|JhMM?VCI|@sPtw3QKO2y zAMsjpbruvaL!?E)Cty+QeN$o_q?{(nnv;tYR>cv%MXsaf^M*4&9LD(~yKx>SPRWdR zD&(r@8+wi8GN$PngB(73DB6m(20GucltVWe5$G|43YFQv%EH3EQ;&!9#VFJky3wC= z5k)d4*a}6mxqsK=KomgsL#OOBCH2>EnfJLmcP(6iCO7f&0!o|L(e0eNVI#XjK!=Hq z%xi9L4iHp9qn{T?HWJ@CbLmniVUWAspN6&{*@Zt<4iNm*=lh7kKTTb6ad>BoylHwo zGAYUs-#i}R9 zXe%8^V$gIy=eGlw0@iDb_B;+X9+9-6n4Wpxnzl2{VCs zM8G+RoI4aG7a5KJ`=R>E0ekWbN2A99HOM5PoTA`#R-l(iZNYKY@ejcu9X}pp0g3_g zY*mC$NRIySs`AfXSyK4lINqX>2zqw|;@;!pgq5Fvsk=&^;+tI08$4#c?a2bUX=@j7 zmmr-{|NR)P%%8>wr0DoT9BF8LN9YBPtYKe%do+q3Hv;MNi(>mDdukhaY-raFrxuWwK8JP3_)fow!;xie1GU;e3UdigGsNJ_bMhBisI zpZ#JL{5Ecw@2Xo<8Oyx#t!q=2SK>j_OQ1x_zU8XNy^YZ01=eCFI#5Hc6=~6?I^@Qm zH?fU|i+xT`DJiiWz2(zz?8$HS zSh9BX3o6l#^3145v$1x&Yqk&N+s}%${4jowozp*i2wjg?XN43G9PDW_t&u3rIMLgQ zrJDFX(T}-zmW3pjWt}yN|0DIOC?c>6sTzvbI39{z%FAe!Itz&nGqm-zpSTzVB2<&U zXeU5e5Vvf3)GpZocjXK09)2}~ke z;NP8YegIDRa>$ew=fdjhCa_euKdq~Bi-6WwQj>5WktZvK5w$yfvkJOfuAf^ zlcUfyi~Xq|?>mt6T3RA86Uy+sVa+qP8FmmvtF*PXJ#+KBcLU5m;hYn%+drbU=c(hG z%7!0Gdyd=M1Vgcq#^JG%n#xL%I-P=*e?XH}6+T%X>W{hPiw~2-`GokX4vE5$B|yRg zs(oS%9k+v}Kaux|0WIL;&;M9W!1(cg{t(Z=IukRsR_5^jlasXop;y!QAKxP`5Li7= zb8_YFKYTfZr+-0j3oXp4CHEqikzq76=l)Atepm)Iy_!;A5#`Qrox_!`#>ue0n(|N( zvc4H`hH4N%M>J=UKl|M+QtT|WA0u=Z`q=Wg-4Yy`JVu864dNcQF^w5LP~!f2rt;Oh z1ZhWO9s{%mEoG?M_YT!^MO)^X`5?uYIOyr$o?(x}6Cx*=AlbjjyH>cf`_s0o#R$ff5Y z5B3?{zqPhL5Y-p98Jc0_E`3%(vi*$-2Pmi2OL6{QMhp+jW4-c+cS<1gLIK$M@lWCUM3zC##1@x==<-eu}sK)?XvMs$JT>?PP~FM?e(%C`)KdVUZE1nbe};$otoEQzdFppH=IZe{DnJYdhTi>1;gJu{OS7Y~;XH-adOZ}=k4@(Xe1ug@ZswTp4Ap+_c| zA_JEK@|iVvdlPv87y~XuGk64qz^bpWO)-cvPNF6!qEuaN-(xZsH0L~Jt5N|?>WF!u zWSy*f!pTz6WC~(rD7!o&t?cHgC>zX~b2(J?*0ZhgR}K+cz8Tl%C`)ZBETnjuW)!8f znut!gqB2J^6a4S0VxXej(fM&Fgo>WkIs!QY!`4v9!bY?sj4wB%`rK%83nQ@IiT zcQIC3>A4S0w(fpK(tuAjA)8~*rZQ=Bxi4U-+i{YGtA*`HS;Ji>xbZ3$%Iz%|y`1hypme1*)n0`D4CYRGD!j;|wPjtZ_o;FJI z3fgtT#CXYN0k}I8l!SIC5@;?kE}Z_=Y4WlODzIhd>X#yT(Z2ozVMg}s-c4&_)!J2O z_`u^P7~{-0(%k@)Kq~Azy!e;i@AAoj)#ZjoO-&6I6?Lyx=t*1p*gDvesS1m0-}&vn z%wf<-3uv&o*&`2xg}u1GHnFA=5B)>qg}d1DV`#2!^)3?6K*_-?6RMeS=-b*;UN)gy ztd}n@wEfjP(wmP5f3hhJlo#3WAqNR-nhR|)j?c>X8>O=hzFdfN;eJ*kmmW@MBIw%( z$riiAAG6Tm8?%VMiIMvFz~x_HqiM0p7#NU(q_`n7x(l4WgM%p&Evu>b z7dX-ulY>xuQncj#<~4&(zJ?+n9`NC_AgZ*qf4N*{<|xP52#I)}74& z*go}ku>QYT*IvqYClaKfGI)K02L@zb1j)sF+)is&Chr){%?o*-gZc3NTu&(!3!>gJ zF0zHM|Ep`i;b?r4`FWqi7%uP)p1YuV@CU*J@*ToLLx(TvRwU}R1^Fuw$n-Ff{eUzz zH3g1AaE=I77t6I|-Ayl<%y3gJv(|!tZCJl>D>PlVYj%N8P_Mv4k?g?wcr5%Wzd9r4 zDsIw3DuJr-Es|Z^C70q-%ph`J!d2u4%~)m0r-*SHgqF7mj*pI4d5oUBIRY?g-wVUG zcm#Yeg1&wG0JrN4hjeEk%l^_=CuJXaUU+4>)ok@@WPxFAOhsWvH5qXRA%< zU07*-=;D-_G>a2o7IRNeugx_Sg`B@l>ZP1;<9z5oEiIjTnn1L3MkO zViYf56xQ*Fjgh_bH;QzD4QgJ9x|I}Re~Te{d3m|x^AoJ3q-6h&V?%Ua#w%2lV>Wt` zrudOE1)z|^Cn7Soa#Wq#_{rNyI^qkVLE_K(>>fj0q|OMufRP7$T2vHxLzQi){+aR) zpPdu=fnO3lKei5#1zBL)>B!Z-?ls;lLzw2Z-SHZXt`JxXHo**g;4gT;J!ClW}NzsK%-iSnB^& zi4#bZN04J5GbuUSq~#*_3Lq`Bibg z-r>Wx&ykRTg^G3&GPch9$;V!=fxEFh!V>@D@)G1gc|1J@Vl;Sc!Gnd8CP6U-bBd3q zHgr5n%3q$G6V0Y}fmNAT)_oai?C{fsPt@CLlT}JYr&d>80x0qXSeA zqH(HL7AOeH$J(8Wd;NzeZ%gp9zHaJ_9sfIWUu`nkYlo8CN4kVhwu~Qx051!9rcCfp zb19Xo8L7Dn9Xn9+DpR7aI#j|@oK%{Bq%NXqz?1^AmWozv5B^2*MF#U3zJduWV|_b| z)Cvb{RNONE8h&3rILn)4NYNPyQ{&pbylC%EZ>OJ(^D9&BxyH@k&>!%k>MhTysL#DL z8GFTf26mXK>=d(pV{Z$Tw+>xxPngey&kq($Xg}EcjGpHz!2~4M!mKdgE5}G#FPHtf zkumb?QIL50C@g3vy6?X5xE53$QLpo!MA&0^>b3|K1JL@WX>MzReN`rX1SES!tE#9X zV%h8uWjz%}wdzu`;mseoxVVAg7qjjD!43QF-u?0NKX34Ye6p)tCgwNS9}hp@%&<>i zU{}$tHZ|gdR@Bdx34bZq8t<`xFZm6+M2$6gwT==qH76OJHVA zYHDVOi(a{2OKCW0HiI{58=d%v)itp|C`YR(RNJik1sLO2UyFc@Xshg*xo zV>&Y|f6Oy$V;3INA8h(tF*Z)nx@fgbx03xjGax65)qHht{QXrjP43W!FL9Ss`!ZQd z>{T^~LSS*TN#dF=1*^P^;aLfb{FE3X&gBnUh!`^0n#s)7IlZ>|FW=U<@tDw?G%sJf zPZ+Vwu)MM0$L};ZlCBj=)P|^VbPICZ>rHpM?`_uS+Vrfkm0~$=bAEM^fN+Q4el#<8 z^Ma86REND?bywG#&LZz%!FhCQ(SX?bo&SDV6TT+^1a8O9_3;YiY-h;(oN!HbS_KI$ z+?fRj*06njoJ{y(0|R{P%bDqUswK2PnTQ>~?1gG!;3*M$prXnf8K=$a=Nadhs9IC8 zT^0DLpT#6L;h7QHqd1-QL`fO(s%Ae322}zcSGVEEB&TT&!QxReSC%LgQD5Ra@kbm? z*tB^m6+As5oDB@-Z30H|6`IgDlLq*~CH@vo3Q30O#h+2ZTZK$qTzpU(FN%ZG80zr5 zm;(#DewD3AlmR!vgl9IIt8nvCr}Eb@qqm9S@8r9vl4OOp3h}UnbIVs;=jWHVM~{}k z4D)KJ8eAsdg9*kH?~>wFjlXj>W(g!DB!II79P|g))`<*euYSsRvDh!76A}`-XN8z) zW8X>fS*@$k<7(^bbe;>G33^ad(^O))T6_fK;IFbWP*@X1^UlYoh3uU;C9FXsX%Qk}Sf-RVOA?cy$VZlh&U;y|5gdImh3Xj*1Hubl%_Y%KYWv}NC}eNg zkMB4seQ*d?Z#%sfh~wC2#_l&|r=P3XVrgR;16e-{^I8xu5F?I76P+-aACS>+lo)2! zW`w`o;1T$u{YJPZJ?XtYCrT9xuvuXJss+R*HvB&iJ(-ft96)Y@hNcD!s%YKx^7mpVgG0>h+-@O2iB!$fCPJN%)22KgJhNw6*=)qZNDl-Uki36p0!q2lHBEz6 z{q?r-ibVv3gy6a_4iye^oV8yx>W&VD`tE51Q-FdWESgi%-hJ~*knd8-c@B9bGN82; z=0$RpB%7*Jrr4ri^!s;8P7e85;~yQr3!f~8z`OfP7I}Xoowz>>nJ3aWY7}wnNt*gO zE4Jt0J)racLmeqx*<+|w+ZYf`y&xY_F(hWj#sNbq%;ymX51d$7TQ7xZFP_8I)zz8j*jsqC3KVfwJ-!|u>Rk+xL$BGAO$h?HS!P2T=!bLCs}*wO^03z z^Z&tY@S|c}iYuj{s0gt619x|xm6C{1;$%y}OaAF$WbHvI88@Z>`s(cXImT~n{>FWM zkLp67D7tN0?GwefLce4--DicP{M^e}e3qhTm7l?Bux~yPuGrQ!`W(D)PwO;bZj!Qy zam~(-Yr1Jt=3vwKa1zXgtQ27O_RrZF!*YvL2*@jQyx&!Llibt2oe%$%2rJ*O>n}?}G>`i-QIgZ~jSj==S_PJ#2ErD>xY&$GR@K5vm+9vn@t~riPtMKZMQC6@xl1zI zX8vg0yBSW>k3Hu~m1SjN>EGMKA5af3S41up?Np4FrV98;$fu+K2By)syLnmwU4@|- zV?FplpJ(4x*-FCh+7IuEAL6IDoo4$ctTB4@$WYDb7#{^@7x~i5c}BfneE$RW+3FI1 zD<-1Rp8j6-vE&%?%3wlA!eemI&Y@d+Wa3Q>2SZaIbABU$;3%H?`O-U_A>a@ICT!IKkRhF3Kcztz zM&ac*o(PfrDr{hUEtkZ;;^rQ!>bTvH3C>@#4LFprPaA=47M2ci>_ubXt2-sj3=vt! zL_h;@>cN4vP7yN;2ag1O(qc9-9oKV{LhpF=iA(=6mb|xl?Bv|VGPByKrqAx&iY9`{ zKYsx^^xZzvXo)hliR`9*;?vS59BRrX7e?q_&63R;l7=Elf2Rn$@z7#&|HAnJp=zZ| zZ^9bVU)TyN7xFBcpGSVHfFQ3FIvhEw_`#*>g)ge~NddaNzTfg&TVL`a|G}%giISxJ zBcy7fpih#0_^avHb?e0Mn?&OrvQ}Awf zZk9zpK@H#>yqq2F?NG@!M^%y`?d4>12_^vfA1I+C5%e9tn#GOYVgahr$w`Xf5{l-j zeU6q}{ooL(S_gH4Cy;;!T+BcjOfD!xpJ{Aw7@GwS9ACj#6QglgqS?7QI@}@f&E`Ym z3W{=g**n|G)>8!;3HfEFAJI%jvON6fM41P}8S>2R(DU;OmNfWrN!C-MFb;i`o))&cDFG9wiw?_GQ z_hTMTm7oe%WRm%lPvP$%EsuTYG_f2Jhu_j=Iy-|&4B)IplL~iK<@N0yV^H4a#)!%; zDyFZj=#?8Zj{@%Fds>FE`)Ba+a0Cn{iU@Bw0`ECH++MSyC4_|`ftQT?-38sJ^z>~u z0(oIO=UO#E3{?MAc}M3f+93u80ndxr)mHGG2HO)!@n;6{h+5>!+MoC^?U>seAr{{G zG(!g6)g>%~@Z20ns1Ea_+9F!5d5HtMr0IKty;UlBmhjv_KxM9SP zUfh(?mfyj&7&``W$N;cjob-IY>i&F-#3JTb7%%%!AL>%!FYu;L+NfQqXU9$DgkKvo z*YUoxpvrgUkFSkcSF}h1?Gx}Z0DZK>{gn+UK6qISvd6ZhnBgqWCB^-F!h%NcEy*O7 zY4zze0X{nG8*a)}SVL@w^%pi~xKT)9LY zbch@MQ}GYiLUUXTZuI)70vdqQb;^Rx7Sd!y%L0WOw&#SQARl-RdW5azas^4btj-LA-pjYP6@=iNvIPo$`=_~bz zB6?><5{#RA{ZK*Y#2a~UHqqX|xZ>lC+!+s97UfA`7f(G#Vd%P$Wsyfq@n!A;We{o% zIxw$x)xwHiK0pqA@YLPDS?h}^5q*ATu*yPN05gNu)ybytWog$f#kVh^PsyF{Ik8pD zzp82?wp>^p^GZ@4JWUhA%0CQ_CuG>eHjv~?iu;d(%G7Y&0p7#n;{ImNX+Jz(&d({% zOOnphmnDdl6|p{(EMXvaWS7Op4|wR6rx)q|PYXa(qG1JCx6NAOSc?9&gErWSegnAp zZ#XCvPLy?+6C<;J=JFq}mvRH?CFZ#}(TV2}wzjfiI-8uE`=5o}D?_uH_-x(FHw1kd z&*s`#`W(iwHZE4%ehJbmc+#gU@mYM5M-HVuCNlEDksYKMOD5+HMzwGo*kj=gQ@>3fWyo9&-Eg(3ZQ~4@4+RblqFzf;RZ=1S!(m+o!`dz@8dna3nOJMp)z)VjX9-a$b<3D zDx2oYX?mSNlO^c&#nlxXpJymmk>c4@_ERG1^91R{Qo3d^WyKIYE?v9RI|hcKhaH0_ z;fKdHzxJz9jT`Ko$RXf$+6}}IT0cy!0m9Pg)u&YpTZPU5aJ@W@#P~(Byn3knB{!{=QkEV0-{Qd6;e5^XHSHvU+S-wgqU!l- zI!J6s zM)ggJ1W(0u7FyNsGQ_d+jSDd~hV4sTJr` zJ0ogabjvqA|Jtw15J;dx9C?#GyB&b^DnrmK85CS4WO-v~bcVxHbrfX$3Vg6%Hot1>n_kpdkg>Lo`EGZ{x699($edSzl>kHjOSb3> zd-ZhP_A+jpGRKQf7sJGg#lCAIz0EA1kCumrhZjNAn45LKxIqHkbVpp=W3s|)7D13V zrLh%=@uWDjaku~_f%f%U@Hc(a+;`A{O5G@IkIgy7@W~JHy>nV?AdL&OlTUr&KMYou z_kn=4rBCYSP+*jU=4n;)-)gEoKocl&Y|)^{0Rk-TPoF4_7- ?WNsGeX!)wNJ!ECEnLmFioW=Zu6~hGazC0t57!+>8N%!Lg!a_;d_xMr-O$ujOX^;l zO2(w$+HXDm@Ki)py03;1uL@_|1U*Ah@92ErLE!xl6ony*ICoVah z6?XFz(G#6RjF7v_a6j5kF3Uv4%-3Rq`mX3dPLwc-FGF>gJfaaV3|d4HqJI-lFp@(( zd^sf!3V6)A*?;%ocg%A%QFbk0U%^D&EPN(jI+LqYqRNC2XIUJy}_x1|!jczq?ym{u3TenJuugHD}}w>GA)D~6yy z@|w28DRX_uJ@Zv7d+kN$Xu;z98H>O22TOLSQ{A;TUp_&;;;Cq`R4JL3DPEKy1 z{5MKKn^Zz?04S?T{mxj+A*Yb%x$N^kzXvr`IZCWdx<2QH1@GYOr&A@5$Edjm?^|Ty z`-QOv=lwSa>DH#I1gKMp7%7W;R-vIPSh4PWxpRj%f0h&p;P@VtC?xmSR|PYPnB{2m zobvR6vU%K=^OUYid@C|CGE*a5d2lML%%{Q^-|r#INBEc2wE>0M%{B52ch>S8`rM;$ z*-6h=bUlczKfx*D?~3whArtH@q|ke(h85eIs@4ur2LN`5J{OM6FIsbzLrG2|r7OLc zx~SqRr1u^+3RA{DPEq_$Za1KB2VpeJCk#|Y(dhE{WvvQ*_{gMp^wF|=EoU7r;my8> zd~^&u2Twm(u-(tLSzi#wNxT$%Qc}orqZ40@3rwGbeIQ$%(Z^gmUE(CX*9A-Pmcl{V z%pcdA;_&!Y$)E3J3p#ruvW?Q<4+sws9k?2%i%>3X7=xoDQzlKme2L7;B6*pE=#&1w zAuhaY)hVk6PbE`|$q$wv=+J4aGu6ZGbRs+N)UR*1u%OuePn8JyzOfzRAj82?1>_pf zTzm38=OvPe1wCR#1~IS>D+ZpVaO27-!K-^t+z{vF-SYJ~EdE>z6lkT;CGEi2^@=X` zXsi9x-Ew~|BHMbo`@7);Fm1X&oJEK|MbGo|bxVNCp3^m=SzbQU>EQ+mu)twbUnMd* z9uW0b^sz60jz@E=_5I;b*MiQnRct48P;Yqefx(7MgppzfURj03N ztSdlmPjl5!s&zLlKYo=L5zgm%h^2|+EP7!<%BZr_jj?d*x<6~lQmN>e9*;1QEF>JoKX-h}V;xijq|->vjY=MKOPxy8f8Ff?SUYI)YuVkDm5&4$J( zToxZW%3$+(T=-s*s!LoP%qOxtY~T$pL4kQumMI;3FkrNROE+S50?eUCG+)r8NW$G3 z$X{onW|#%p`ZdqII8~00^yKAKR%Nlj{|&_NK%KZ}5!<(PrRbO({7*qKTb7=|=MtVW zn)NQO(xEP{CzK~IFPkA~9Z2Pt8yo_G=?LsyTU%SeKon^QFloA?6)3GY()kD>k{A;S zL&mA_Am(E8#ZztYyeD;mgWQp})00y0eHQz1U=1%wKOrD1#WM;|jK2uc`$T@cs(*lm zjpIR`AU)tx<(i!>1M(ANCV~;p{j-kg*i_>Wq>M9hzMVa1qh3P~> ziTPkGu6nl*2YBANx|Av^&sE6>P7;vGHaE(X%hUC5hsAnxQLI{0s4vwiZr4n}J7WC# zbLi@-kN}+ryaAT93sWU(LQV(yOOPGFp>HoMp74+uI=~D|i+#uPs$t@qK{XX93WRRA z)mHtUAz&+9tGbV#WMs?rtR(ITInqfQs1YbE~&#v z^2bDCtKqZ}+^(*!KaW>#l}A+1=P7O5$4~!Ysf!Btm{G^q=3>mWzu4Klth&DU7;WIO zGits6=a!oBog!71LQqL+RJd(awAnA_>%WMsIsHHAUPE42En~hX-VzEgf*;so@&Yl>;o;^SQOlHRv;wf%nY3G0oHrgtB7Lg??3aG$` zuSX?U|BIf<_G9J?oP}+h_gJ86IGvBr7XQW+Y@MSsB@T6Pek2@14D}LkJ-xA%u{ujlza-{WxH zf857CbX}j%`+c6T$>jRS+xdcL?cIN`tXpSEtg!)Z!@sAiwk&HzTN1wzV)`j6@oU!G zX+Id^ct}Ap503tYx$DC`uanx{KVzxtXH?l}ODw^f&TmPU)YfA3- zU0naUYhT-+uO}|lnEvz*kq~_YyOb7Z+4HjH(l>#GU2OF~h5yL2bMm&0XFkKcx*doI zQbA2?31suhj~fynZujB|->Nd%)4d}unu)z!=d)GKFlSz+x^jJWNA+7mL(QLJ$Klyb zB!PP|AU&mxr_I=fDA{0H+H7Q1R&50u$kQy>d}2Ozc)arPA&C;2y}DmzU5O4#`liLL zYLo=8cVleLzq4X>QB?&vrz$w`u+fRmitMcXmVSO6VI1BtrlBntkJro*E>wOp7oS&L z{6LW4B|}scj*|}VRK?o*x)M^lVr+Y`zQG#3QKrzv{M7)GxGKp}N*49>WD^^|T7b*-CFsZ+ zFYgJ*bQ-}^2Y&l7lLB(m0;G3GtMy1j@@#C}9jB+<5Z(%FoBjFWL*=Jh$Oj((f*!qB zJs}BZ>Fzhqd#+-^(0}y=hv>Fv`h$rW(bF_RE+XrE(kScU>Vlj2KUlL;l!rPxIyt%p zLl%{UQMBNmZXoFPlx+}0r?j~^p&BtAY_+IW2n19s&@0c(sTe6Qxx_rxf&BB)og zU*@vq7v*J2umF7pEI;|XCZ%ER2>#$p0fD}rEhacRt!$#$I5@}--Pbe-4$!AmoQF81 zXo(uEr#KUhZ{ybn>(5u?0A#7ks0N=bP}QRB_?uW`_CJ^+WNGC%cY|qAI*)6oqH3sgF)g}-<_ zpmL=7cUMVyw|~Q3_$4pCHfgHm!rDf;NUwU>+PSVoYN~vmRNjzBJ$7#4WJuNq-h%(~ zCarSdX2|CBWo-2gi%kUG5i&G|sJDWU1+Lc~ZZNsGK& z^7w9R?cfSg)RclIu$b=e+at<@7>j@RjE~d1G~tZi4Gevs}RqqRN{pu~LVhxlNJn!coV(6HG51r!Ow(R}o<0^-1E|1hr4_v>^>u zwTF07G%vO*6Thd7@4n8~8v>Pld=4$S(J^%mEj?q?n$RT=?7LBH0=&|7bP~J?EzUFv znn8I7SWLx5ak4oNACmta$Q1daY@Q%2o^i%ErVrzq0`w{UO)%DEP7*ORBt#27eAA&k zUqYyn+u*qD=&;iE`#8aWsyt8hQe-_S%;RN(tsW0n-|67X9M#~jYX|k>XB%#p2(27K zF1O3nSTuy6kNP(GeuZ_sEbTf>%mA-mo@Lzd%s~L``ey%QemfmHwqqyp1vK0kh_CII z09Q=E@3o`PeuUnD8K+w!cTscKBqnUWH(8nmh)jUeiF+Cqg$gt5dqwwCo``r5=wrg* zxu|e`n#a9;AN&v6bzVUhJ$t-UD|jyVS<9uY z*E!z&y>APV%<_uH-z}pVHv;4~Igc4C?08^DA z%~d$masj`o`CYxol^a|0OUIo?~ewit)y0 z<`v^ICey6bhwBranQtLesjd6R6mWT2txA@YhZR2E1d^!SgBi)tZ@{zmxv=uLT>^{* z!D8UJjTr7u#*mBZONA|c?I^Y4B)wGoFr&|+C1@e-$7^8(yJ~}eHz$#qzd`}U#x`;T zJ;&)L4@WIp)RJ<+*jLrf??qPg?zE5S6T4tBP+_>g&UpBYgPT~HL*fgh>42PVi5o7U z;NW1%9A(TFBD8dyo8jRv;orjjy!K0BZGrfaMIc+c9;%|ldAqb^2vFA}zlJupILURz zf+R@bH-bm)`r3#5>5xppMAMyW=59m{4;jD5hq^j}wsyLAY$)Q)LL_b@BlbE;;fVNxTG}3A~u@6-nBw>4l40 zQw#AG2ObN9Nyyy zJtr^Jlm(&fC%K9Th1);#M=iqTRV8fiM}Y8&(~d0RWI~>1MEm5p&U5XYH>x?{4lWyZ zfM%h1?dv>M7X6g_bLXR}46cm+B_&Ewx46E(jp5lA@lNkTp}x9PSC)1Gj{KLOYTky z;~}-y)_Ow$(ZS)migXTjKtRB_3jl7(Y@~@pR<;*AH|qqu*Y1&->Lz$2B4jdr zp;*`vky{1b5d-nv<|{~o{`3O)7LjOJSXk4wo=L!A&Uzil0qBj0M^wlV(6@Aq2>D}f#^FP@K<^OJ9?zm=vgQJ8g!iq(PJ>d^wrgbeXqxc82^f@~g=`XtV5jA4l zNbzs&-oEmij8c%J2#eYtzjt*C4f3=(A&2N`?w8J#zA}Hj4ZoIm9^_X9&GjoOinq-X zg$gnTH?)=qyi0zy!PG!3t~CPd5gTKM@3=tF9lh7{H|G@GA_I+E9B0%pUY`0 zlq7C3qI{PPhe!PU;zEtkmW@7^zWw6_J736G4s_*mR$ervTJ;tQ)@!Z2T+(E^#*@q) z{H>?r9Y{u>&oTAiZ4QjeV+Z&7+I+kozliw0rzJF;wssagffS6LYj)~>dX;pqKDt>T zRE&7jxoXx7bcUVrkm9qv6m36+BhvgIwZuer*?R@qM?FP9UpBh;{=kl+;O~OhpvrZZ z0>SeD9+SDC5ApmrL5DP;*80Tbndn3txhh4bP+C{f24)O|1M}k z8Z(hMj;eFf=ilWK^pm|f4^e7>qGiWKH;^i_9X#a{-i(`Orhy{k%n<_1ge4F3AhCij=7 z$oInh*0C1tRe^~6u?-Qcjte`puNa1mO=SubQ;*}tu^fe9dftTDb9VNwu%&kQt8(>{ z^9y_JBnezf`>U0^JAz)K)CmUv_V5vO_tuuuzcXE?W?^EKyg?&J!-#0X^N$|cjU8*; zLAeo2B;4trN6i)%-W~psQz>!#ZC2ilp12mG-``^9g3eE$k>N>wj3@e;jRL6{@#`UW zO$8=lvua&G^W(j=$PgJ@znlh=eHk*;qbjtat{_HDF0>L9QdyErM=vE6HIh)y-ORcXpXV6vhp#trZ-dMF^q?|=Mz_}c<nUhFKHS{J|h^TwNGqEI4o_ezrmy+T!yN1{OXD6xxvRiwv~arqn|MZXNWIS{l1%H3x6SLd#eYZ&C5I6{Y9 zU#&+JM8BM)1q(3@3>^rEVC#K3%$C>AS`j_+II~0X%bYO%xc}JKvYaGpDMpe$Xa;M8 zGF%inIZTv#Hi=|e&81H={U>^W9C}07XYKyyY;u_mL}RUkgXy}2--8|*O!i-Fl8$?2 zdjL4E!BqN#O#u?}M_eG8*x1xGNxDk5_B9p~E$&0nBN82KzH~YW07K6-tB99MxTS_p z#Q&?V4%Entf>(JrK#E9wh!0b|`s+@>NbtlHk~w@1QuQ3cH-Z_2l4}kXd*c%mxysCj zF-9gUsI_NQvRL0nbTqARf2WJbuzKldob1uVFWYTk<`(*&g5Il9Ed~@tVh`EchJiK1 zWF=Fzm$7fXtloot4H&|Rj7?P!2#g24A|YsaxHf)jSx-iZOxc@ne(EdQR4#mNUO6e$ z;+8%5S-Xhd?#JL~uDR?+Y5${al`pGQ*kTw0+}s_#q+D+_G?#lTXQ`8R8!NWPtp_5nTq}!6zX)-l+WcXLDSqNf*KkFRjnvpIwkQy|5FJW`t%tWNvF=}bRrgH!3 zSN?u1B$L0V3*fA`(@wfaCy$8rR9vGBeNm@dTvl4zWSZgKmN_UQD<^NidwtcnP87Q9 z1@bk?9902(!9`io^MVnC@bt^<*Z58&;)gtloC-+OdmkAI-)_grGEwMu^)1g&8DGVs*3gaPa1?C-Rr~Ig3uE z2{@*Jt-<%I_$DDIM{K8OW?@Ull*f64P(-8|thsPaO6A1CZyF~#8Os}VQxnyGe2i0n z);mZ21XA(#&o^xchT_{#yq8WYYCp}z&?6uUk9HF4Mao&XjG(*se9A9QtFdr0+EBCa&$01 zP3Q)dl`>?Fe*8Fa(1Y*`A4T4Uoh{5LE;d$QJXqq#cHr!TtO}-D0qJ@LFVB<)Hd)#3 zHa0onJ4s1XzZVxh$*F;6v4`pPgY*kJ!MbdKk6c#4+ zJ&>qa*y{0XUbOV^<36M3zfWdQ5F$kcGz~3}(>1QFk|#<9Bg6X`U)2jh&l^w5Wy5yk zlnyVFZQU6y`1Yvsk`lfb*}yTE&*bDe%(o>h!;|5?nprZJX=aVegYr&A~d=_0px2 zVwvGVLJ{;faf!7}<^i*x$*DE{bJr_e@1w8{F&gDdI#_Sci>1COf8w_H&t3ZQ<7da^ zB0;itx)HAoLu?ZsT48SUj!js3`CX6-%F2=JyBU$aOg7HbFm^XipZRlNzCd1qv$bWs zBO;*6(<)Abj0nseD`ufiRO z;0R`BsDm@}C&u-}l#C0$zDr0jzW&F0183-e^ab++Kf>v^kOGK^GO=+g!6o%c@CL2Z z$R8S965v~~yI5hqe}83Say)Co#(6TiJg_Z#fRL`n>n5j~dzi6$?KT0&l{MB7yQ)pi zM=G@Kzs%Hv64$$bFwq-FOx0@R!+CUH5BuLs#1}OLuTk_ty?R&N@TkE}_WVSh&zHsw zUulfH&NDQJAJuj4hwX-qSIDX$JHT(j&_0bN4RI9<%^_A+Rs&N7?-f|<57{TQIe&Nf zex|}xCS{JDmx6@g0ll!mNPRj*{i^+GGh%;L-d?znfXac89r1Q?H5_T=Xi9zv>`#{E zEWobtz6~d3u6bM5wCaP?&-t845{D!2EEEI2NW@OgZ7Gyxew9-ooYG)YS`T%b6 zH&6Lq#B#6@Qg5tpPpa~T2h0H>c~SAwsXr&xK9fIxbs=bLZCz4V0<;Wny8iiL-RJi! zb=luC+ch)nWryHWit98%bRO;AEbQj1Sq^V7jOB0sI$ZXoKO{mJ|0E}@{u~O;xM=w; z_udaP^6w0j0@kT$72+7oD^eakIZG#tzsI0F&eb8!&ziNgQfUcYVu)PQ-A3<3^~8zk z*(_}aDxK*3PAQORW<7m*dqg_nW#umY#*R@O+((KGNzi|31Q?P1VOhD56DLbW5aMj!m&K0!0PaCIqVVUgl|$-{$sV4I3plN zd`_DwA=I{cU;q#N5a4)PcO7n#cM9`4LO&Q1fA_?9$MxQr^O4u{V?}Bi1sEBC6*RDR zPB@B$nqSNugD}n7VCxAQ0x5!uUZ5NyJK?+ScNo^1*VfFC)}(vcsAMzm9-=`C1tOJ2 zRa5Nyh2c`P>3521=AxloRfeaJ#_bJex9dc}^#y|52;~w{-ZYcL0W*mRqDSK{WS~Za z!G$5uZEF2D)1^|eE3`PnKU1RGI-yOdFUq#(Rc?!^ETn|&!N2~`d5Fg7rIF$X5t{Cc&k2ci6 zG9=89ynL8{@3+SeS($_>JXx*mV6mOZu7j)#2w*v#2SXUp^{lmr1TcfD?-m@w_4C%$ zGnG-jc;21GHg^bf`ng;J%A?nxf%51F!2ob5b^VCZ;mA_`se0F!A#;LGR7#&yEl>_T zBqN&#rS#Y#9hNB3Eh+2sKXsbr-L7SUzr8A$(+ks`aIq@%Dun zjdH0nb6ItTc+P8mJGao1SP}H6&#XzC@i??tu&{6^#wW6T&0=P+1^!Kt5!~wj`NK-) z@1~Q^B16RP-cNNA)pw;0d#gDEj^k8zWQXLqP*HWDusSh2kvaI)aEh~NY0-mX9kAtn z``)_wRRwkH7l93>%z(hGJ4x?0&M4OR^%Hv6%m0`jHzu6BJh;3k1- z1nRKvB67$z3)x|a1Pd53DXA$K3lR$E(3%Jpag$&l60xlq@U8_ z=uq%B&5q>_c%~_slHX-r*KWJwp?^$1qyJ5H-i0qu{>$%BgB!9}W4jP5K=}-$-Vory zh8@o}>lOgW5COm%LH#OB5|6(Wrzr?=K;S(oA%n=;b+mpFPwITPjA72;>6q9 zHi-r!;Ph{2tTAV9_eIor6%|CvFdtvwriWWPX|6pUKAw8Z_V>ZpzRUzxW%w(P{Tw9U zGZ6^HFg{jD!sBM4C6E#i4skyk8T;kw8U-;iCMKpljw>9X4S$r@hq{_KUWG6&BYv)t zjBkjlwLaV=>Gb=~ZTkMQmL_oVZ&r!N#(iM+Lg(8E8mXn$mW}no&neX|;|fkLgmk87 zqU@8PZ@Nc;*wvyK$lIk0W?lydG_~N-rZbukr*e?Ukwo6_%{2&}7>5PuXG>0Z#vcbu zqd1gG9m7k-n6_={I zsUuKiqJ9=6RYWJDXG;m=KcEYHdA{d)mlO3Du3yR+G*vy$i+9Tik)Mp{b1-=Vu+y#1 za!>{dx2aq}hgH5QZVFP{iJfmYAoA_B$#R?iQ^g(%Tu zCchdGqumM+K`@^%zZO4tHH}gbxc;ahcokTnUIeNU>1^Hh)?%6E%(R5P6Q`#bLZhbJ z6ItEG3;8d9sQ5<|6oInCf4-+(unbNy@{1&{Zd z8p(lZ#4uA4wEG!WocB-^J%l@=E}jj$*;v~sF+F8y<*#~tGe}K+<8o6y<#o{e)Mr=* zNm8O{Kfgy-Myz+oYBw;rn?E`XB@wfuaAae;#xwfb&jG})ykdLQ}g8 zhn%j#Y>9{Dr0T;pg^4KZ%1_}^f;mZ+Rz`T$`n^-cw(+c=pal8z=YN0NE}oOf;pb#yM}}X2{PqG-2O04|@bB^VOT;52>?>HM zjjQ~XZ`#M{2VL{;&{r|0Wiu`sn!5i<&$IP8Vg$7se41o}F8*VB_3x%E%EG?X543j! z6%u6YeeXRROE=ymhRCf*Skgf71-A?+uc12va9L$((9Nv&r8QSrudM7Wa^n=bL~yJl zb#PM0rXcnwpG(3aS-ayc^I6Yb9gq?n94Nfe(K7M$yhWu97(*qG`{EMy8m`@Ljm2R zh10NmhY!xzDTx~nv>8Ueh5vRU9C54Fl|UDQcmPv9Ub#BDu_K-ET3nw%m-fp&?efu+ zW1^4g0!_7dPBcF1y|wmEgY!hGcmxr+BBGbs09UWFH0Xj(kLIp}bArUqFR}B zhzG_gWsn1@E?&{DO+_%3m)h0YnJA1Vz7O_A1Ta2%WC<7j?ZCGN4sovwAebDY5%#Et zh9s!BLnSFcI;9^S`jm>aqiMvCm;P;_nKNA3x@Zrd(aj%Xphiix8mv>tfV!5iXx{ERVmlF~cSo zj7z=6!>lO5(~#jnc8WW zzvlDWi&16hJv@}f3)|)vkO`c;qg_jxnww8u9?M%gf_bda%s#=K@au(Zh$WZJ-oJw4 zy`8B!swDXUMW_0jms4K$>#oyPFWW2Uu5i|e?R&Iw)A6{AWTu?=%%jx$)Ne_QwU;u< zB^NueU7Ss-bOOV2q`mzq>wKnkq$Wr-0oaKTj6E}HOM}f4R=Za5vNTT&f3SGwYFMDZ$bH6OY=i2&9i_K&*oglr@9j z7LfaI-VWx;taYdU>bg7YC5a$#Y1E2kcB#E zQ3(slg3kl|ZsqNJD6M;n){2G0c)?vyw?#Z#-_c` zhvE#6$4KGK_dvaFdRDcZ@nCb1nfZOae^3v1oc!cm)Kh#`rHp5n^p3#9m20Xp5Fths z=s&_2-W%1jMSPJWzIv3MMh5-d9w|y~G5cyG1G|31JfH72H^@)EkBq+Z-Kt%6G&*tL zJ>w~H#Obg{lI^20<>rvUjw5F3eC@tn%}}#bS9P(tBUoB_Tz5oiSG;|6G-)a0kie|; z!76My=F=y(25h#D5@e3*L7q=PSbg#oxY&rp<7z8MS@@W6luy?0`Rtzs-;o=V%o~Eh zHDCxpc_AM6WR#23ZEp`bSvD9NHtk@l^{DoYArd>3nzB0)-%(un*_tRLV~IOtfu-E8 zxmVejMcMLurkSUq$Wh*}c0 z$AjjyJVPG)4JeVdB7QC_7FIMSpR{u57{0Z8C!Q@_qG)Vrm}*BO%XGhaX@9_q^J$U{ z5^4Z)b@dM6Dc)Jrs;95BvWQ2U*p0Rj^@?)-Bi;4BDl0t zn94ya$D!l8b=D%TC%*HRo>CyS!pD*dsYDM7FkyuSVT;?*h&n=85i9wQ#!xHQ(vr@K zi~MsZTZ~$Q9ZeSmae|?Eacb`Re%bTqm#2`g-*|Ng!YWGDSq!OIGVdu9cv@xpD-uqW z2=coHvkD|M$M29!CEq8pnHVSdUTnLkcO8A>Kep-|=TKdy=67vVIA zy-@$zWor7QOkc&lEk}9Rn||_Q+wz6uepcIP=Dkwm2=zh?)+agb{q8km^bS@p6I?dcJ=lYCYlShuqfI&h2@Oz3+zIyR^=S zye~Gge}~XZAVbkV>OJhL~Tmq}dX*KY>(9+RC7Rl)qGA(VJJ4C%g>VxI` zC<;&HEk_Al6&f>RDH=I`3i9Z&#~(s_SL!^cP?j_sBC;$rD#UV>^(`&C<&YkCc7$*J za;tb5v3w{f_Btl*;+u!+YMC*O8VFQ@Q|{TGs+7u8(MSyHU(Fdc15+LS*0vJEgQw~Y z@D`IWmzUi=5}!dXu5deC!_RR@UKlhaBc)vJ35##Z#!naU=_yRri;=~A^<(nu(8v(; zu=WC;Mg`W&sKpBkevcNq46h~y-*c6XBi;o?;^;9jR0}5>BWgNK?uo_f{7p8q#0lMg zXCJIT@O3PfCV9J%d}q%0U3>O(US1j|VIrl2UyvHlkN_ZpsjY2l+7_D5%rih*CeoNV zD++W!efor0XDerYQZpMHlYZ85x@VV3bd)}_g9%1UIBavc&ia-G=E9Hh>7ZtPE_3Uu zKn&8M{DbfGm;$>I??&rJN6lm1=J_;NCs4HHGk9*rwX{?ELSZ9EgiHiHiByaX?NO2V z5$zBS2AJ!3Bwup%J#oc2z13o1FPs_kgLQUnKF7t=B|TznwRQKv@nA)6 zOqf(^__B9~y_F<)rm0?fi@BO!E(Lx&SA&V2gQMlRk24|y3#0@FB^n@y zn=3Xbkz`2%rCQ+izVy-HexFre&V8g5F(| zlV}OjchyEPf}5H=YP1cE-EaFgDDY9tNzn5Adfl;YlAP)*KV(J_(JqyTfI&YMrBhT_ zE1zEJvM0;g%v86|UCqobo?IXxudyPX?D~4#;(oeUKfSGUM_$nozG>vRo12#hyES!E zH`IIn9p0h%QeRJ5Kc@iBAHZ{H;wP3t81X(j`d-u;%EvNhp?_wPZ-V`-Cs6%`>dp#n z<7Hj<)qRiDdwQAQP7!p9hAXnkGNg&By?E8c#{61+v}5-#+uZ;&8fgv!A+^9sEj2YJ ziL<(2KRQfk19CS5h4J}xaY2(Jy7Vk-kUqKRejL+1%pgbu>Eou${L0`NgrcI5@edc; zL#iCYG8^^#(gXssEVfK4&;CWQo}RT+0s_<0(n2h9>q;Y7sCLlkd08ub;|bD1Zq)Md zbuQR_oS9~UqO+YHil$7wIBFG!hzi>j+Gdev4$`{_BbBCZ8(Ru$099LiJ9J03;{yA4Et3e5U1#IdNM?0S6AFYGeW%2r-z3si~Fd6rGe0AXl||_ zjHndRA?dTaT>DkEwY_a^VBxBv4;O}y7hvH)VJcNM=i&K~c(j{(?5X=jlHpldPf1Ft zftY*qMrQ$%ncx7(-sFWcq56KQcJKKo@)Q1wL->hLXz441oi_!wKGeq0gc&J+U@u`V z5sx9<|7lUqkZ3+QHYVY#Cs?A<^G1*OW1>bxN*w*kTbV3@lJB9%BPn;7t&DhIDSUb( zZXq&?4ks@GYpQ@W{w7O3>H74-$xCM%|(xG z3dII>3)7XfIG28QzT}LXW_bA{dfA>(;=e!pn^`J7ROA}0JUmf=Knk3V+~wq~ATM^82t(zO=yb&@otb7yRf)h?wvrmrGWZT2YqHbIUTI*kP zPlR}%vEG@sZ`8guWZ|$e{4~5Z%QCNG_Y2P1xN?5W;vxY8&3j#tx#^KAcFij8gv-R6 z^FZixpNdmP%*6@w>(i~IDbcCK$R`+||4j^;(!?R&RrO-+zu?YgiP9Nty64Zlf(Q=P<+$(f)AN8 z%nh4KYdnPn4S*QfpY~fH=)qzSO(}l?PCdP9qVC^3`U9`|%1Ul_o%u-r{o^)f1rASBg(P>*1L6$5g{GkRkGY+K zpq;3}SaRZ(gWw$a&x2nK4>O3jrbXcU4?|9SkvJMB9mw1nyM4RYo8ierxsgx2A-~4< zHx2a|oHB+)R!u7#`n`9{8Y|@dGw}eVh1DE_GR7x5OMy3idGe{|WcQi9m;cd`^Uic_ zciReDO_h$r8ETLLK1P^$Ez1YiQ7Z46gfQoo4}*h-zi<46OXxK^z735AITVEHrxZC1 zlrlkrX&mah)1*>nMMB$!8prlC?P1iNuQ?YZmC=br6*cTJc7^dTCE85N7Dj{9KY2Al z^ae~WFw+o3w{HZ9(fv;g0Err{Y(VoAmDZIs7J$9JL<7+p1zDb#0?5bw?(D5?=e(s% z2f*yZMBib=2}93?)T29XO3@OojZ?uQ72^<^O%TQgf1sTmo0BYFN@p3RnzAwx4wBa0 z6GRE;^a0Q4=opB;A^V}MqM}dB);j>=icYRwDw08%24badz`W5AoR*6!{^r5#q3E59h1EnHUl%EVQ^! z41)-uT>`6T2Rw+3HL#M(*y;&t6pjoEtsub)<#v>yp0E0i&x5ZMqH#K{O!m&nEZ<1! z8yd#1=RXyw*?&4U^-%SVzL(eg?j)9ovo_>+;jJj}jDmhT;qM5T1gmAa2{Kg~_W$;# zzL$FsHLZ|nudb+;0H3q}0v>X^?p)$$eUAK5(ytV_q*E{X;A@_5z)S2mu(V7CX2GR` zU9v)~R=LrNBVX;?wCCQtvsPo5(l;@Ie{I>5mm$W?pwB~~JqYUokNqX;f?^DWQUkQ7 zMD(z@T?R}6D-+MV64*y9h{Tj8x>tGZ7g28o1Qv#>1hC53tH% zi>yA+OhvoyM=(29wXg{-BkBc1a?PPq+3{}|k+_6JmG7>=g5<}Nl4rt=F$JHB!1-nI z0=v0ka~}^UBviDi=-=@V7g-6u}3!W14sDVprYMja@F@proZ)0=EiIK18G{F76PxQ@?$K z;LFi5F33SA@FbPWDkzA6HLm)P4xAE8?eWlU0tGK&;*Wu&l27NADtUxX1By$UcqtB@ z$7RX(7~e{np0lwbP)pbVfOP}h@M#ib{cGbhQdO&~$;=L6B5Om$I|5=*n6X5ZR1p=F z=N=c_P_a^?v6b`6rX8c&KISvcgmUT!I*e2&srz5z1MsoYq;li7c6R>3^9lG-XsZFB z4Ou0`3wDxtLL9es?lI^uFg+fXNZdZWYgb>r{7TIc13y7JK{?;aOveV#2vcV)fAm|? zOubBpV<>Ntr6JarolhZ8c+tHKY%KD}pU7OwtGwV)Yd(%R(TqC(J@LK9Q)|lNr5FZ* zeu8+m)T8paM>}4m}H#fH&qyLLxEYka2tjQ`@Y+ci6s=n37T4jq#GfJnCYFT>L7Dc`U8Ly^Z zR-ZB(h59lCqXp-Q?h{k5E+K`=TMRW#@bUH)k)NH_PE({N%h5vZ*8|^ugvU1IQkO#P zb!^(*e?qNGwgFQ_GRAeM|8jpQ%G2y!Tw&whUBdcl5iPBeST*M}VPos^gj7|BZg8ZR zR7cpIou9uq?WODKR+}lHlJCSthW}16ZYf!Q)ZivD8EWO$JX z6L=P|s_idYUXLtpPDdu)nrC%p^pYCKIhf6l*GTZ z8y(gJA!D0)#bezK1L#PR9+8j`g4{8+=q@WSA5Jo)q5_DAmruQ-iZlU5aZ-^}N_x63 zbu2n8<t3<(YNnb%X%1t!}Op=<=F^+Dbr(eR5Ru~vLAHi{kebkll?iF zDOri3amiD2ZI{3ziY{6>Ia7>b`}SgEgdx@}&`O|v=HkSCY4U|hy1>%))y3EF@czwK zPG;y73}+g41`5a|+r1;%<^5KL+-?I>?X6pSH^R7q<{Y?BQhxgUWeE8cSSk}b9&NaL zGiq}yDelky@ zRX?WtbY+J`pT-NG8NwZ~{zd~qw%ke4@{AoqaX&r|cdHeEc^TL}00Mt;uEX6Ak002% zY=0l!1#^$Ix+_1Asc5Gb^KOiRnr zEHu!hg-VB&p5*5MKA_a!!qKXT-1^#NCG!rmln_RgY}zrW#e71L zFw}6Q&_+|rm6q2=exna;raC^x{QjM3KR)9+5Li~CNbyJ~xfQVS_#G_bA^cpvv_SJ(yGY(WUCK>romfAN8_Kr+Tv;JKz&q0Qg9rmVBv1j%4Uqq^viQ`(eJR6~bvvoY&kOn0*&&wQT z8{g=Gf1UZ7dfMUGg08{>jEH8Ll4F{+8K26Gz&{gO2UdfiAfP`$QxZ< z+GOcJLqm^`F>%g{b#330(5B?#N3^bOY&Zz@CgJbA&lM_sZD?Eks_->kQa{KuWMsN~ z`dLA)D4#vCd^YV!!RPjh<33&Nr&mK93miXw_Q3DW?R}2z(M|rRfc zXx|C=E+RU}k#?z@4l5BHyu`ts=aVEd5i&41T9lK3li#U2LUFI48_!Ae$d%v+&3um6 zMAGanWIO2;Mb*lU?ztM*3|W(ST!GVf2$ipq@O%BJfn&zBTIL~#G5$j5@<5vO+C`*F zn}4T!KbTXEs5?sr4H1Pi4^}$=IvgG!{uvn&<4vQz|KP8#m;APl+C5YW(&_8Rgge{+ z9+hT&E+8qDAeb+=E`y-t!q@j~NJC~Rkyjx8#%k*R@i>lscLg(z%$BFo8<)*fl3YJy z&7y>QYDP(ig5RMu9dtNrR#X0DCT|Q_%9SzB8h zP*VUej@|wHKmK8HQ>@)bCGHbnslT}lhF8frk59cpM3j%#enGUxn3LymPzhTS|xZbLjRSpQKs z=C?(Dl>ZwP<_x(>jq-w{w%I;Knh+sH(={~ABL&ySVlC7#9oUDOC_eYB%HC% zs&?UIyF<#M;MI`eU)XSOBi!Ez?PGKn=Ka#|U*Bqxsq&X6ByxTfezSPw&f|ED-QE_p zfBbS6G74MZ219s+pZA;4-^YT@Cx-R)44O?sTI`e7zuI z81YvA<1&*o$EjPS$uAr4x+f~yQTp}4vGWFHgzff&Qu7f1x|>C_sg^oBURKMHiw{-x zrM@O0i0P8} znMU!&=3TGo0^8rM`LQ-1+9)>5PWIi2Sjb+s?|L2FDylzw>E@JXpdZaze;Q{|F3dqd zMT{NWi>cVohCNozL5NvZ9_Fm$N+^|Ovj+`RU@5lyb(dW$QRRzvoRTV$np&0JHFci6 zyxkS)*xK%H*6V_WBM)1M^+Dgu-T4EIpn2E2 z19DjT0>?HTH7#V?S2^6Y)})V<#w_oV;%xsVzskM$YWjqrlWK(Q->i4Wa+Iwe7md+F z8mVCu`MjauK7TPcu_BlXi|mdUZ~rUD>|b3y10=1i?l&Uja>>vTJk-?{Y8dL)gX8jo&!J!L3fBi zIix|e4~RZ1gr*U`U|s!a!|e9GJC`(Z7}eF)@FAIcT1FUA`w80pI#+#dr0c!?f|iaF zEEzIYOl^p-S5L1VDQLSwc;^1>2V#Jr2BFONL6{-x6>=_Z##>&O;)sX{cmN-;>d_|4 z`hPJ@qIWtM7vfzd`4;nHeU4XNEY!0v}(z)9(Hm^B1SQ ziY7CkWMAVG%r1jNQzF@euM(e_n537ecQ~%cA=$yZ9{V5PbyMb-7k4Ui)$`IMOWy~| z`mna+`kso=X7FVy(%T*PATR)~q$S^*{+nd*QvoCg%pY90qUFj$YOP*~7(>8ri^2Zh zYB3u70ym33=+Wu?&)PmJy&)&4nIZ=hqTBHnSls_%931qY9S-$>Om^=AxDft8%Y~J7 z3w_bZ^?JjfD-fMdDjV^1eb~+@)09LVaj)a=lQ(PKd=hieDZ5VM%Wk6&(ASXFMmGjxX+Dg zfKxnjdp=E;7J~xm66c8u_i~^ahcv(%&^u}hEnbn4&Pm$FQxyfTRSAhQ`Vqfc>q-5M zH`qPN?nJ$$FYTF-d2qJlTGze)JnuH!CQ>=D1Clhy3G4wpg z&rD=$v)qfoDA*mnf;OPZ7NFru)yK1yYypD|Z3`q7qT92WXiBDw?;PMrfg4sipHLtJ zS8izU%!}q;=T&8%;YKXp+pm8Xq=($SmD_JZTJ`IbKG~aDBAP0su8(bR5`ol#JQ;6Y z-z#V8*teGX^S|qss>mJYYcDB)_>^Zp;H@qi8XN0|(D6pQ0Uaw>292o)5u4}hj*ST9tlD>$7sUM2n}4w9DPxQ7Q&pcq$YY??=g-tkHMQBEJ&Y051| zZokzU8?i`bK8Z3ZquLO3wPG`VldA!Z7iwYREti94oMywMP^t;;TG)SJ(p6PMq>Vc< zT*cA({2voSq(AkDr|E9{?WU!pw<&V4xg;lh%U3BcL|Tpk`_!JjsrrqGrc;59@a^F^ zy+D1EL%DR0HZ4WO;LwZ$82C2_e=x_34}G36<9=7v{3}6dkVere<#oJ4j--u3%&KE5 z786qunP1iam={~Ytv+9CI((~2;z|D(pQQ8FcS%22D$uXV!wYuW!kv;EFAZ77JG5!i z*`AY9ly4Gaa+>+eP$Q~z>TSHO1FEWc-~i}AnDUn-qG4IFq?C#K@q_%Lw|VwH@IaB`*=MN$HQ`KrLnu!t$A`Itz=SNaaPc;LrH9Nxn zC5HA+Zv{5#S6A1pZSJmaRXG}QK41QaD3e4iLW=Z1s!O{78%?1$d~2W?@~Ldw3zc={ ztM2^^u?p5$U8=ZR<-CL+-g__VS$L6K?oXeUCe?mK*|2g=V@-HD;zn?%eu9!^rR-*x z_11GAtsHw&B=>zOr;4hi8Ea%-*XiN_RskBTc7wv=%8UZ_;=NjM@yH~x5QGO#YRaK~~7wAg*sm z-!Z4HZauK+LJk{flkzw5cIQPj7^(W2N4&;-x^s1#aKX@#;gnTY0;KVT7&F_PB=^ZH z@e$+)azo3f`xssVxIiKZB^m=5_>h7`*!(G1p^F@ceRRtaLwFBNBa~iy$Z#yVSn8wQ z67sn4*!S=@OOd80Y+BmqejAj{%Wh2_OAiFCLymtx{131(2h+}BpuD`ln zx18#n^LjoXkNdRdTye(ifTt`gF4DyPYQ{KQ6=P37 zn69*d3fauyS?owt(>$Ta*CkqwmkW`g>e?7Bz<7H3xxAc~^^UAMlIF@!9>1)@i{GO& zN^C?fV_zdbL-_%CGhK&D$INF;i)TiYp$*sGhntg6wy*{<@ zm620>rb0hYA3O2PUxjl-0#E7rLvgVu`EeFjuVb=qF4rvOzU4lL89vzV<>$|3s--XX zFMPk6Y-3@XU34uBR~hgyed%RM&WnsUo2q$cKh`w8MzMh0RcfU?;|2XpuX*+I2ca)eH~}I%g1g}dXTBOXnx-=Ob#*C-0LGI)FC}yE0Ju1= zakC|b7+pjeg$M;OOd!6ZBanw*q;MGII_C!E-x;PRih_O3Lqt%Xi!j$Adyh41=G!+^ zSo#^#2SEKBF|qY&%J%EkM}lS4xDQqLLYqb2M=QNZPI>tu3!M(&G2JP)&Td&j?-Moy zLo7La`Z3bwBhUQ&d?rE#2=V};xz-NBMVd2ou9}DKWRM$=5QA=eH&Q2q-#)I_cH#IG zY;Vhpp;(i((oAHs$!4JaVod*}!Qyn#Ap_|qVd8j5wtY!=YIKrdf*zfoXrWA&A{OXj z{plKQ$=0{O&jpm<)Y{O&g%6@x4uop^n5~~xy6y)7zYmWr zh7S8m%4v+$IqpN9oa2PYiUQ6wYHW9BTN~bi2eRhqzK0075n+svx0DvZ?x~vJc$tq> zLEnB}K4JYUUFqk6K%guCv07lb3Ilh^{h;EG`Ur08GqR~2_P5rdYGUC<YDv!9i1Bce^Q2Y~?6CU2L^NEzN)c&Z) zVL}{+bO*PxK$JL8B0!rh%t{9^0HArFap2n(JT{EFeh@ADkc1?+yc~Cw_rOcEFpY{F zJNC`_6kMFPe4wFVDqduv(lsKOYtpa?e^^VhEyc?vTKYQ$YLHy=#O$)@sfZ{12LpBRLj@v5sfd#D7ZU01-^g(GVC@wRGH8c zMdfUgTj?}*g~L!J4iGE+T;LcOFYm z7fvj??X>1XT5=am3n1I3%j!=YS_9kKrx8msuS9*G;_82i^zT6;w=|N+6-m>0aWGEO zI$}vBZ(LeZoQwSw>qm`kKZs#}l#YUlj6`WdK5y(AQF(_i;P%g)XXXNL1FKeiO7?x8M6sF=I z)$a?~*f}e!8X`w5xp)M6Hb&Rpgmo51V%LUR@m1PAvDAEgUp~H~LY0tI9*rQl)HZC| zeQ%h}g4w=YZ7}89H>e(+aVxL);{TwLIm2z0;JR*48MR?in7s0AgxXc(qg&- z;AZoff>czNjmUYDZD zG_}E0HDmQvE~T|g1Pt4|G?m2h9v>1d22uEuIw-KBqC~PXzz7&PU1tyLT}0UyVI&%` zc*kDRFW4W!cY*|24*#h`k%+MPh0XU{G7l!}$KBt*3pn{K4(nQ_zj!+R?sxBVUF{sk1ZMnRLanlv>!04%g0C#Ge#PT) zWED>YbK>E-$p~x8;TNVYa-4QH$O_=^3NYvFKO$EJd6M<9Paki46TQ$O0uCbN}2~MdyPyjQ!Ps+?aF)BS}#K?fqlyq z?2Jfc)SlC}aB_-wE>h$oc8*{^Y>B9F8J^~USkuieZ=Y4d{{5DGg8pG(#c3TmP3U$) znNIgES*!5$xfTvzEi>V(FeB&!hxN&rv-K$xnK3w4r|V?&H8eHl=@PyfKL_vCw~h{E z|3gN9Nt$?58`jRFHJ6Z1qabQV`8i%oUQ%8hluo<|^Q@uR{0LJIv6KQ;HoQCGZ@NrE zuq~8~rr@{2?quk9Mt|k&i?AnjY&y?H)N$H4I>v#e0g5){p&l9KLcil$RPRLL%4nVQkRKFjj!?L^0ACc5Jq>pnU?-4Df(a;dB&VMec} zfQBBmwKF5mN~KCt5Vq?ycIWR`=Ie*aj=WzlXYe-q^4z~S>`exscSDVxSeon|eB@>O zE-HoN02D5-TwPHIsKZWO%YzqmsHVP3HMqnojegW%cltN`pGo7W#Q&Neiqq>JQj(f@ zTcDGsTYplh*Tdi9f06ODz@nNw3;bNi&fz9Xg8mWp-V<@fI_$9lrMo#|dWAd&N zqnD786sT4yCqQFO-@PMHTpam3t~e|j$z11{kv{y_s3or@-{z@^P*EWDXRjp68*zUr zGtMDxL(aUsyzR2m_?h1j`~CCtSUj?Usl4QKjR${6c<;B0%ZX{xk?iEO@(-+K&AhVm zyfyt^ir|1yUw(Xm;3A%9DM zLME%W>(8j*YK_6fi|=*v%xU=xBcag^8*75sXAHKZzqRF_FCeNzagqsyVD1nZ!IOue|t%^i0H3lVeIpBRO#d@+S z=0IM~!J$`PasDE1%es)G>dWGdCz1;f*c0r+2@48$j$lIOY`TlLf+h4_(kX$HY&gRK zKJ$%9hlwpWCquIRn+nHvc?OWxj?g!qI=S_!gh{v$J20D1IAG|DjLu z(Pbl?0?1cPxc{m61;!|synBSsL2<4cII4AZO+W+2sKVg6w&M=FiU9B-yP}nL73?Lx ze)vI13wmL>OuIJT7hW4XTWBG7PJwlSTFhfvawB&(gAywezbs0n2gjC=m825rUspqv z2M@GowD0{Rh+=H%sCjep$04eP=LmFgYc{3mbnY$IyrC@Kjulz2xM)`S`ki^7sr zv^ie}O-}HpmGRV>Rojv<$l=G!r5-&PB-e4cYQMUW!w2O?PQ&yC zMD@^R>Bw|Y(e{DAlG^5Y`u;!=XcdC1%xJXg7DrSS^+;5?-(P|08*+^1zhif9Th zD+0F8%exWtsia&&XizA}bYTL7JR5nsVK%;m&F7KWpMMUNKW4H%_*C8vx;VO*>HQ!2 zaInWf7p`yno+#gL7v(kW2opqeKu>3aLV?Fl4J$gw88mkU1s1OF>DaEW&u4$FVldEuSD$8+JY9=A6kU1E@`+60~1M!RQZ zfPo@<_P&1YK`3~&s8(>ye8Bt3{}dM=E$p!P$?j?tf~CxW0GHr-qejsvj% zfqvz{t69Y76i}I)5AQ7=A=^F*z52bnN)+nsc_UayB%Sb6S@mn(bS0N4S1YCS!o_B` z{Fk<|2Zmd1pIcWmTP=?-HL1yOpHO|qPLKZH`bO@=`FN^Tne2;wO$OU92d}}MZz(Q+ zQnEWh0RzINCJN4BHH*Hl%$X>AQ&WS^|8~g{sSyc)45L%}wMqDkr{$}aXl9tw$9QQX z5hN!fZSHO`;9(4pjdfjKirnn9-thA(Eg=HtTW>B}!*jhu)QYC?zM(ygqo;G1w-tVo zl`PCLSsQA%i=Gp*Q|>aB@XB3)#$9m~-)&r{k7B}joI2<0Rq-REZS4UHWcz958LqXz z-@NK-ZaMma$R+?MU+(ozVx)Gm3IE<(DRv|!e3Jq>`zY_U{LKvCPfbrtjcEXj4MkBNA~9uKoP`4Pn7m4Ps%+rWlVT(KSjR7uH}%nq81!x6 zR;oYz4P7hdXNUcqaGm>X=}rLYyi9p>Ksh-%2^ebJfceJmE_4r#f)L!u(C(#jw7gTf zsl2@kdcv|Y3g;I4#d&Dru!GyiNh-Zy?YQB6Lld&N5HtU+Ki?YZOzF@ELq{!!4*G1$ zD-&jjj{k~~q@h(Osz8G0D#%M+-Q9#0h8ds~1W?j8j&?hy_QC`gOPM@P01S9~uu%k}OE4)!2 zL_QKOrI@Li*?pPhv;9t7kVHWy13^?5!lk{?i4J;~%Bw#+S1DsNGXoI>jHdv`7QHB5 zZ`dsyLP6q)8*9jen@EvC3T6uzmtf<{H*+_Z$uX$ILyCv<^uti~hu?$vpn;g% zdzwH8rU`^KALMnQ4Ln#$;Xk-Q0q6W7zyB3K;mL^{eFBta!A>XnN$*L5Dfn+esRH3a z;SxC*DJW0PU}wZcMS)d~P%}rHjT;mqAkF~^BU^l-0OyoZ{p-;O!q#`t4Ju!lErL5@V%fEEZ>mJ?%PSpd20M+cphkO03`cz1GVWPER4xXtsWs zHe6%F9hu;Q%hBL)`ZuU=J8ce?YTy{|0GmHE5mrx?G|zh~Vhp?}2p91DUH||SBIJni zX3PIF_Hu#pnmRLkNyvy;J3oSrwTwjxyBAq5iqYiTVhX}U57i}5WI&0i%!CRFV^7Zr zkZ!K;Y{*LHLzc(Pn3B*84il(6_QkIc{XyIRhH=r>oDV>9qP*@Hr;S5;4J9Opps#Tf z#~07Zc;1>t=p+`?j3y~8PH5yVaQSH(fk+&*p&xZ{lr*{1l{x~c+FkkcjVc=&zW@5g zd*JbIWraRDWdfKDlWd2#v$F!drfFyOjG)bT*`7oVmZFVW6prcMdXhj7cUym(gm~I2 ziY_(r+xg@35!d_jVS3En5S{W;S05o+g>gxOYQA9*pwqmOSDv1jGVu{z#^4vgLch~* z3WF<%gCHpD4FHGna$jSx6X z2e1B1P`pF>7o-s|SPo?k8Kp6}9J$z<@xUbkH-BYwl8ffsD%6HD{JR%#x;nIz3pIZ? zgq34owEf!&^qHFj0*{>W+lMI*m!qu?9`;+WOZuV+HjNy_ZKJ<9#Exe^WqWFsF|-C8 z9_XFI!OFsuB=YC=v}lM&E6ua*ZCjVUS>NlEz3Z5T_~+M9hMNi_Ffb05Bz%!H&0O>f z7(5kbI)o>8M7%EFAf99pm;#pqjvN-qweQ%&4X_*KP2=6fp@2^NgC%*t^P{t-o~m#B zb5}$IvgDn$ab{?-L$O0^?g~+F&eSI~eiji{I)>x~-jZymDyGR{$yQ(xi|w1Nyf>IB zJTx}JFYDn|%W2 zWL1Cp`c0Yd85OZJ@h^Pc_t;QW29Ixsl)LST?#n!sh}{&u(`!n@Lmns1o5XP>^nmrw zj_6Z$7x#WVJ&HwhaDV7x=GdJ~+raLE>8R$FYq4fRx2$n0Tn*Z3? z5Qkg5jJL^6cHFdsR8d;lW*5hPD23IS{QH&u1%3F8idOYPlZN#i|C(s+l=Tg}#E;(R zH8C^t&W_?gH|j3N8)}hC{#9z|yejdhAqHtjq3 z@FSpI?d?J3lHy?b0e~yjjn$n=TAVHm+YiBD^-WXo8&JXZ0E~HidqYWQtFf6`l0P)P zNKAA+Qli6$SA+bz=bA|#dfK!$X|jzm*67+BbSwP);~;-zU@gIdXF8@mhkD|qs-z@+ z%b}%rdz;13=lSC7OrxutOuX59c)AYHnkxGEl;D(k^ym@XWzXsA>GdjRzf-UD?CRT# z_bTrOrDN@A6yAwi93P#Xz-Nn+ZQfuiI;mTE!QKH23uujdO?k*Af|eOvgWIVf;oq^n z#rI#~lHT+C#s>l*sRl&Q-#TQX+~CtomPbNV@9LF0+w#2k&zm>|C7o}CheKpcW?Ji$ zZ0YU>j9#?8v=QeUKC46d7&mAsdb2&q2l+)H$EJYLjqoksLYEn=gn00D1gY~PK- ziUJiU;;MJw98^|ThGbm8K0b)Lz{42Ty(N>3#wExl&<48I9#fvnL#@{3lZv_iv0%nhHF zw#e_6q?l*u_?8XI{{G@~7qkDM4z29UroUxElUZ2B)XglksEGM{_jm2objGZHZfb7u9?QN%vg%a~R1^-IXmmXWVrXlSUXtNz;& zit-81?{_Xp0-#Kif{aWe*$g^e#=OY&|2b|hGv`(^-Qh{58`loMbvN=S@@F~_b$|80 zp}?gOlNi&0tL&+f1FrsPNR6|y(vBtW&mmz9XFHX>s*GZ766M{{t32BU8Rq2mDKz*cR!gF%Y3MtEc=d04ZrIi zE&h`rD&%-66!PND>8SGJ22#}E?Re45os@71{)UFl63&T>rlBK0M9xYQs|LY(LxQZR z*I%X-PEgN!r+0-G`21Z6PYr9o*lSf`$kMvS$^O~dC%adw0eL{xnhDgab+b(pK#wnU zT8)ouy)^Lq{&$%WfMZCF(*!|DUY-e{;Vw(xAN*-{j~xPwXJcdfOf!$6&jDKIyT5-= z_HE73CXRZ{d793~b-$?|y_`u&Tb{~JAmbM5LIpE!R#uNWZd;L@E97DV!Gf~wRbXs;bd%M5)6bLTc0z|SE&RS|w zd7Agxt>sxBG~a7%Cf;;I!xUM8HX9h1VO#`ayt<+S@AlSYEj-LL=>uR>dRnBBt5(DX zCp{!y&dkiPxJimAi%@h|eO4uzthMWM!6 zH=$i<2;Il+@Y^8vPyzQPqRPjV2ZV|qVgUskIs$X!)|z8adEfo2*a{1jXh;3f&pfqk zUDE+x?|8M|@iGzJoPxUW_>raUWcQc4GuWTr=ug}t^YV^_%J0bVN3oi!8Ovv9=k>k+ z+P0{Km^>&sZi!)uoszPgZV!`{pmUB?z2O^tI$F*pw@;sKwuI%Uns4aVkW&r5N?_G+ zDMVhGnucfy$UfXt)%#P?L4}T9`13G;f~-Hrff;5+nnx-1f4oD zZ9a+}OR|6%49A_{kAWW*a9(D5z^V7j)%Kl_*j(;Ax{y~NoZu>eSSmAL-;5GULo+L< zh$Y%?cw$u#drlSg#lNan?u}9G$|$HwVkjPU{n!jPe@_Goe=lttq7l(K7V?L@v(EYG z@=HRbuQBQt{tj7CG$VF%=_1y0&TZ&(jRqv6?G7qc8Ii(ov>z?OF%ePJ*_@s50Z2ZNGGl+fiJT%Rmaei-HDa}Svpf|g;6f17-V)F>qC95O}srmf& z&}?~!U)II8TifEQ39b*d2Jzkg!aHOF$cFA02Wet)b4BE+vHo>pF~RrF5~ik}UY={U znrHhXQO}xyV^G4n2{RrQ6Qq5LiXyK7(v5=Pb13(wiEndhmVKfdke$z}K%ey%4-Anp z*w}Fcrf;O}l9Q9a!nQYMn@nKBDB$#yKBfO&gfy2T3U9`+E)#EvWlv7YAzFZ4o4Ms} zQ`}`Td!e!#j+PGBun997%a zoj7LInwQ@w=(Vz2OD4jZMQz7cOByZpM&;=*_M|J@s;sL6qJjbZ(MA+)R5y8cx>QC^ zRuPCLb-vw~t^Yf3G~POUNm~OQ*l*Pf!ALrAD*TRd=<1A32XiU!O1c z5+DTkpVSUqL~LLYyYPI7BccLYyH4;wfG5M0rE9;^Xx3{B8Jzgo58qbfT1YX^`-pV| zo0dVI@vcGPoq|5-1I3rmEwY@}cJ)EeQmGi_Bc=ijudlB!*wVvdaT4V%)^~S};K{cx z?Sl;|`(yLYo9K;#$8TiwJ`fAHL*?hc-5EF`QB2`cV=;ta2^uj%zOqnsIzkiFkuXHbsF zhjsQuAHYL=z1{54`guGrEt7pX`rkjY=rMn^K7ier&C{m!QuPT=m)e6aHFrlmq!?F7 zPj7I&JS7@ArMx^s;UTM2t|^`z&oa1p>s9)FauU;ditXa!enX=-IGv%j2ULSEGub(h z=C4t}cOog4rF93T;R#!@g#VC>Q>fI_mSFce-xOQE&hVSdA?P32?>D@P+|9ICj?SV< z9AcICQxZpdan?@3K`qrdsrhkIa~Vo2MN+>Gr5O6OF9)MTSU{{!DWYc8&5hg7`NM&F z!3b~S)zuwHl$XwZ&el(3{M1L#sJE~BK3PE-@;%Y}?-uGQGM5q*@;CN2a%dB&jdV>3 zFt0}&_ozi;Kbql1cfFy#Ir|83v?l2WDF)_s) z%f(-;Z)5IOe&Lm-16Ij3HOA-m^iM%2<9COG5pHGf#c zTcx9JqBH8GA3JS0C!1@!1Bn)rmLO4tiyew5jUCD#Ot^u~b)~d!b`fTMu+1S{TZe~L zcdXw?ukTT2=h4QNZNb-!=)nUp0+|2=k&vb0>+1S0lVXfg!(g#R^@-$!8_12}E&k8zFeMZ5?*v z6zH$~MtB|0uNaf%PR+Ox6gcD_DtwaE(&8_eC0?7{=Xy4j3{e(28owEds+~RvSq_hi zwxzGp*ZB*Brr)>pL;aA7#84~l>nA*9)oBXs^Q?hQeYoy%W~|?+x4KxL=vmHS7F$Ru z5kOs_-UI{-WrT(n5Z=l7S~f~(={>I|wxp>*Z{`Q;4{+XgBCwz6y15p`rv_+?9{8@} zx4Uet8L2hc`aoF)i-(Wf5i9Wgh%|P@jSU?G(zMUP9{*%_;nfvqk^K(d>(zPpKnleJeGKL;y>qYY)qDZWDmYq|Nur;7%L0LyRJva$4wq!d@Bsl$$& zh^roIFEQc$!WnPLDn`njgX$qWI~(2U-zN=3pXt-`^EMh(pb|MCHEN^HD;R;VMdC| zN|i0OVM{^+Wx;kbPWn%|xp|XV#}iAHcN~&@J%{&b-~B0nxT>3g=y+Q_*_nn^@c)?g zJ->gA;2qBEF~&E zPmD&ofZktw0n~r=nspu}(y`esZM75I-FED}z#RIG6l-XG{f8#LW!Zo$)vXOpoH8ST zYp(noR$~=i59Mdu#-`5k6QX=Gr;VRxey4eq3t!`U-S8u13SXSWSIN5HQ2GCv>P~m? z4{uHj&nI0z^yHZ$%PcrVLjP>ZOn)H#0X9Pf8vp{4Bn32RhQ|&D($4<|3Gui8@gpRA zH>!{Uiq5)YDL|IpZ+O{d=(zDS{hb0i99@GS1fSM7g|BVGjy^mxB4g+u*xZ~IFZUZt zHX9lnliuYoaXl6cWfaAaknWrccP>+)Y`d@1scAL*CTthQzedDXjG!@*mRcl6LG-wIN-&34K6?M%Dt&F43cm}b!zX+INq?)~f55f{5-foWCqKIjA;5?-QdiS=dBIPa zlNuyF=e+b+YSFqRewe#_9A#!3T^zdJ9-4$DL_r=}U~O&RQC{zdoBn*LhTGCtiiAYY zE-(E=!zxMT>|*YQ0stEe3k!7pi3sU!JP|QJpAaud7;@kYD|;ls+q1s@X6X7^*v4Jt z{PK6!_QKA8G2m+k@&ZV%l4BtFdveTo-e;pUuqar+A;+e`kz$eEn)QgWd&D(bj{{uZ zpB)?kuAFmT0DKoJs?J~V->+>M9yJ3>6p9~!psBf5rhg26^)J8kUXkOkM?$;nCK*!?&X zxP`iNHCXTCM-ZRsW%_VTxH>!uNNqJtZ1?&!+xYX7K{>6@L+FzFb$Zn9_gMBZ^1^j? z*z4D?Q!_JHp%)cqo5VMaXV;Yev1&yjIa_aI-r~o0K|zmn9(Rk&%AF-fm8!bd@Uo3> z#@qnjWVOCP=E&R%6a3lO*s#96KEKnSa=PQ-->=2*aOi*i@5Ttq%qg31#9s5}^Cc~W zP)oklkFew-_mvRO7<2?#pmGM;TC@AylEd|R`PqE1{~}aVu7rzU-r8$&K~s8kHWE9# z1}6T1{or`lmW$@ScsY7dyO9a=eI}F0m#4{8_52n1#_VYPj9-vXNP&)``>o7Kpe+kp zSroNCSvS;NrI^wT`qeA)Wpu>Icx){Sp2y%+RaRn3(vn0ZDw_A28*7w!3k-5}c3u(Q z@mDZwm8~2OHnY|!xtOf&t#`2?CK2m{p;fNJ?$~!al6AvS1x?)5E$Q?~{KjR>zxXlP z1g2S)NhLARTb6W^mD&;*9obo?JngWQK=9sbG{5rEQP#}|=laj*F1!l7B=mre13fme z<+CO{X9OReab-Z+*7lwj*zg7wG3E+^9p(I_I`8S)l8e6U*Bu__@Q=&n0U=XP@Mjx+=t)|2; zUvNYwXuQ9g{=kVWaLH@VM^bFtBapL{4BODq`K7m;*sOVCS;=Z0isH<~C7+U{hB#@^l%!ea{Cx`&7?FUj#gw{VrF{Go;Q`S}cIpbP!4 zbXqw}Y#_9b!x5H<+yhHm3`Gay)7$N)H$h!5YPTtas+!Ne+c{2;k@N#2c|4y}ry)N! zbUp~SI+56M5LH=eD$`(@OjhDZS8sn}_riYqzYTWB{S|wWzFEZ~+AZhOD2FBa?>AHU zJ(P=0*W*u%j6JViKIXHEO9NO@X_`=7L(=O?A~g|LmL;@2-83?XYa=lE8_V;*SGrnA zU3=7j(&zoB(LXDG9eq|k0bNT**4&KM{=!O?te;EAyNuH(t}ON1SJcsR~kM~4psC)6;4A-wpvT_Fy3VcdQ|V&NGTm*1O) z-$@vqROtgOYo9_OSXb=&)C4U|MH#B{mLBOFX!UK)O&eg$4Hu%}jDD$*^qfR7JiGBA zg_K=Z)}d72zi&Xn5A$L}(b6yS5C&}>y~UDr!-J{gA-Jq^a*T50nIuQ|$;xY1aTR(M zrg#QBo!C*s$`a-1@cha|XNKVbS9{x_khEd(=$Ex-a&ihcI{~vO%$!rUVXzmme4;xe zlqe?%YDRC6B<90M?rpyn&g)g-DZX#DL@LRx;o%f(!xw?=V$Rz8GtAD`o~66Rj2TJ) zNzy`u8zD;B<~Rr{%|Kvw1p#9s%0h|xjg6!;U*a>7a`Kh}esP<~A7TcZ)}nNyJh+t> zIIKiAB*o;VEQPFExCLW%cv~Y&webZ#K4#Yal4c&2^uP4RwDB0QslAPfNl^UmNcLbT z*vDYeQz*>-bnp`Yjj}|b&!!GT%+h=V2jCZMY#bFeH8K_!PsW}RyfG}AcnLGGjdv7K zQbHLWwX~ms0{M5!4Q5)FfB8lbNu6wGM9eUz5DF0@@OIjYyF2odJdg3pt}9QOoi%`W zB`k*!8eSO}`)|_nksAmi1mfS2-zHjbD06lZMnvpLabz8}>-lGXS64OCiVd*1hh!ulp=BJ>eqkT0k9j;cn^qQj3$?F( z7DJYW=vhd-isZ^62hlU)u(IZ<4_C^B2tC- zPgdOJ++Xvh4JH|R(;_3$_0%(8A(3^_q-Ulf&;OZn@wq{tTU$QGBJnow9--r161yyE;>eMj&yP26A&Ta+GO)E4u& zU$!M48RIAHZjZP_>U-{h3FJrylzUiRAKgE7h=YF1ZI^iT`?S8U_e(4oS7xIN2N%SYtPReoiAuSn_9GDCF65b$lcOYG_8 zx!cLVe-DMZzmpcsW|uT#^?#A9d7z|z#fS=dxC5iE(HcAvcGK6F#$1AeUB7>mXq6k7 z0UsJjivl{2=PYhecYR}k`6UO|^Q#BsPpWE&#&(d>dneDEx+-6kf zjUHj89roxqDH?2YYSER51poOTf3y@DdCzG6AD%m+s5CFULN0c(O>*WF1GYNICau@w zcvpz0G<256x$)_7P_ES67bKAf5M|}TBR-V(v|3Rlbso|?6crV@9zVX{$BcsEsyEbi ztcQ#)lqt~{miPQ@`>rJ44c|Dv;A%?SG2PIM7oN3MebJ=+(9E;am&A(bD}h!bFwX*a zmYVO@mXpgz%rZY?@kC*0sCuJ1^l~W8ow>m(sI0oRrVHZnzTKRsw=V2mU+*3GC`6tp zsI*5R{hBN9YP_Y*%n)Et9PRCmng8#?WX^s8dxi>}GV&H66EJo*PCzV-gCFms5Ts_N zt#-yD#5SSvOSIU3|K&NS)JG3E1yGW+HCz5x>;E2ri=;oKZhNUAq@?1`pKpaIN`Ytv z5V06RIys^OW$X?}#lfU$Xvm53^fmw^uCA_e{VPD1`0d~Jus8A9Xec{$e*DNpN|^8% z$3IHS8Jm)5=1eV-WIoIRw(dn3#XWfbh3GWP(vf`H{T0zoKpd7(f!!vhq5#2IFAa2z zO-!VEDZ7^}8)EWFwZn>j?&apt;;DrQYAW?hr{H&^s94^S{;M&&FfXPt9ER+ewDhvZ zv)KT5t2~~6+}%1%zsmFO{ty!{TYra>h^taJuN`*h_oK~#a5($YvN(sOCeYISqgVMx z-7+BO59*(AEht!C>QCRLHwnf2wdt0eC29hJ0B2_f5D4Yv?cHnsNaTI`(rOC-dq9Wv zIG(cMcf~+F3JLxoz(LehHgLI_8BOy|=_LafTdDf(%jf-;^u6XBig}kaR8+w=_>3Xm zT}{wfODp|6$QJd{shAxzl#9Tn*N|UXT>~f? zEIb=Iyy*QyrX_wRT{&l5soJ8~M@8RJ(&!r1smb?YD3I_qY@JujYjjYN`EqV#6>k)Cv{QF|H<(h0W_r~fV) z@ndmpM_4XLM!5ZsOAHU!M`$4mEsEUgbw}$p+4k4F;I&zqI^?-G%>b2OM^EIsoe1&l z(jZo8WO}X}Ch&=JeT&@@=p!;;UtgETXdm8>GxjY|7l+N9x4rT z`u}b{jga11%0$o4+>6RtjC%JqCTi)|#`ZQ{hB9r)JS>EIt$rDjIX$UX_%_H@LEIFp zw{U{JQ0EV9J>Pq~?;Q@^Tv9_oz}^jb-{FzamzLL&U9HTtp){TwSHQx!6ChJx`&4zk|K8EUjh7{sdXpL(4lN zGq*)T@@ZYksUN$c6)jMYe3T#{iGQ;adql;hK>H*0&zC_grEF3mzSkIKVVk6Cxm#&M z;kIw9SI=g+aBOGn1Fj@PBJVvBCTYl7F8E~qukb$3+O0N~lm+oer%%X`GPf4IA_YhO zJP2x|lj85F9ma09^63xz9gIf|VIa&E93;_rvE7yIq@t>V0;uT(evO-c!*Oe#k-gOP zG(B0xHgXS9sS302%sj&DkeI-6RSNuWo#7`~u~Cmd;dbeD2-CQUo!$M9eQsHMJ$ab- zY6I~A0qr;$CsKJpVq*(Yz`t_KnKlAP&1+0Z6 z^uEPq{+40?`wp%4-z8`~@h#%; zY3AnyeW$aI&AtfC_K$mIkLTvOZo$iUyy;8&%MPH?@!A`v@p&FRA6O_D41nk8Ij~?OH1NHg`8rz1%F5Y&#xY*j;Qax8zQ{w#~JP`k@ z54k{@b@cCaoR;5M8oc2;GfqH%8-x4}@@KNqCdnx&yQ^rGp4RDXZ@|0dwQ)-D7Y$ujdVFumtFk$*Qd=@t9&?QTu+oxvCAi3OOw66PU($$ zjKVV4an_168X^lueLxg3sK5Fx-OdO_c4$6hnDR;P^9zM+&&sAtNJQj(1m?y{jlWo= zMCYMvT5gNN-O_FM@RS14#Rz^m6^_6AVFY@DA5+z^b*RmHb8Xa*Ot%m z7!+Um{ea^DzII>Bz>ezb`WiaS?yJAV=sM>DcMc0APC<#{!kOYjdN*5^4RcCsi3UI7 zu(tb=2lw9|BQ4?$+~P&`-oB0Z^GBMkbna~`^c+Ql;L4jzltimkFib%$$GgiSLZ*T* zqp#}E+8Gp{8P*1CQ+~9FTG1Tl3?9Ej1j#FBkzzOL-Vz|LlcDJ&V};Kz2+|16ru__)otIt z(Y2m-ah^^M`6-Lsv!O!f#5S-NtAFM1p9N>La=jj`4@kYH_&HV@tV#Plug)s56V-Bh zhWyUei5?Jn3JCW@%V(FdJh!{jqbC0i`OD>DoPcjnRYfaiuk!q?u9VoWlj*|W}g(QnUw3T2IGp&Yqeh9 z2Q@On*bJd~N&iM|TzMkg3)PAQhX0MtArF_yBP+AK^nF}Va#nbtxe#pLE{}?D=xjjI z6dBG+deqvNo-JX(9Q>ziQ(?i~ERQnWBo5^&hd%XbDP|^PCkJy!t>y3VvzDy2HN3Nq zT01@UunED!yZe&6R}2%<#ea{Zo*%4(qo3uvOD8ymuc8B+#E zUar#-MFqb5+CrjQ-_#GW=I{u8Ei+!Ss0IZsNP0!|wtzH0Qpv2)5JEAQe`4a z!jJUdYAA#9&U=!>6JR?xY&FjJjy|ra&((<2$&irwR6}mqgoGyHJ*-kPMpC2^R!P7J z3>6Kog~i!)>yy7s2h#cLea`G^7{;vu0(rzMBF&fLyX!L$ zsEmC761nu1t*X{QA00*bgX3fEM)cLIRo_V?Mhqff60>uLTBr#J#@b@=17@%d1edza zsFoK0A2$W-hnD&iOLTlnxj=@Glyn;o^j(xpsaWVEhpV_cu~z-||8Zf{{&Y4gGrZq2 z=n$oBqbg$bB++Um;{uSpbEZe3&-8vS_}WrQ!m|~@j03kVlBTKn2SyMcZtiyA9Bdu- z=6i+GxO@u&hhAe4O_>)w!%91Ia43JRDdLc19j)M&fiM`3k0a8gfxiN=VZ0uP3NHyY zh?O9}+}*v-dE&iNLVD&_wNM(nqbf`C;^j6QtYa(J%@?+|cIRbU_kucZ47T=-?yjcj zJ~QFZ=pIt1w-iWjkqHlsEWDZca5God63oiXn1wtD=oe@K5oB4ej;80P*wtTkpbL7< zs>wvX-VI6?a0YMv?Abd%JQzb7MUy;_u@P63QlK9#vLYF?)(p%F>x(icK?no2MPz4+ z)JtDOqcE&1xd7(?jHPhM!6~l(IWdEr<>LOP8+za?AV9sEmFITv!cPmv=;3y|0d=i1 z({J;_SM?+qDG3jGl(#eB*39t8V|tgukH$vs?kUrC4uDhfVb;x~_`$hn{t0DQ1ofpr=cq&dkA#j7nY7+Et+y+!`o zdU^OPmpe&)sEYPu0&^}m{gsEa5Aa?p35s-@6q@}EB++q-bn*;|(zNlzIg~xZAoDVN zEMHc4dQKW3k0P*8zZB$c8S=K!1~g|ZNi;-JmGB(|bqk~N2i3?sO5{pol-o&AfaRFn z8-bZyNvz+M%Ob@kn|A(k-TVZF+CU`Zu~=Nd(pO-`4#~+C%7`A8rMIV@DSarS?jN+k z;3xibdWJ??V!*{o@%@KgStH6!ZcQ0()*`OHdRLUtcn&`@u(JJYUmXvS5w%mG;w816 zUj5nijIc4N?fw+%Hih2x@U?W%bws_P}DV2~_iMu+PH+c|Tp1z%tEP!b>tcF91nCfD~;$ z``fV|<+l3H=Z8XNTRb=SVP>LQi+d35Mf2jVm_Y3mR;5PDBOO6CE z7KpWYCBggwXO4jXwTMZc$=kOv5PBUaw^`$rH^d|zk*z(Ktwo_D-|nf@pIcCXu4Fm+ zBE*7~6^1WOK0bcI*V_W3&CTn{2bUWkA5`7A>92L@J|HH4NK5f-{%e_d0Xa$4aDa^A z?+2tm!~=gzVobGR1=IeT#GOAduXuzM{Mi5IUci-DAFD4Hzns*tnh?9lO?y?{3(1OB zK}S}ln9|#MXJ@il$RanN0tWb}qG}Cj^>T0>f*rN*e2iQ0EjFU-_%L1MdRV`QH1DbL z@1MtsZD>~)y>&~jjCS%q`a-?TBYZYrA{VUG3u~?sH+^V((AL&_Wp97CldEuS(=si_ zO0wn!jONiZ8Ty2s27y10)6{N{xDhC+d$(RS`-%*iSQL;Mv>KGFL&`NT&U9_OT2-B) zk(=3=MbCvxYX0-07jXLj5X}sBe=HOgnjessoTh4#GSDicp5=RH$DcY1t@2bMR7r|X zC)~`r$814mR$J96uw}6=iU$Dk%;~^=vdou4TD4=keB*i z`I=Te>=JsNv>9ZSHko|&$Lk@J&g1lPof^(csk>hGdnd)}WFiu3;EtxyNjzDsXs`Y54CuAX6Y`)Q?7Z#$sf6AdH?_b literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png b/control/smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png new file mode 100644 index 0000000000000000000000000000000000000000..3a96faa8dcba1e0a11afc083379a5737314e737d GIT binary patch literal 36024 zcmd>lg;!Nw^zFHHhk|rV2uOD$2#C_s-Q7yZ1w2=u!o>n<|p#9&wbLjXT6iPtfw&cF7KyU`R&pq zXX7=CFQ9C&nYGPnv_;cYR&Cn0X}_2VwI+3f&uT}PFtR<)J2k<`C(A$0eCE+2{q`;k z56{ECC-uP-f*;?crys8HsAl@ko%)){k~}7s2cJJeBp!tDNbuQ;fzcBa6DOvbLrTaC zHssJ9@OwQ41|0cCm)HLvT}~YJUC;YSj}@v?zTZO^EJK8L1%3)O$A7~Pg?}{hD;g*t z=<5ri$I`2^iW={cmyeJ5zg9EWWc~w=_ zgx%4%%ungDP=s9PVtZ))@yyN5vGDLZQ3)lWQk|HM4Tl-u)eI~goJZ>FM47%T6p=Z0 z?(wf*V@RC;c^4TI69&fI8g#w4lIEKE(&*_^+)SS(>{sF8ZQs8Wj^?Y#$;!$$F0*rT zcFuaw$3;eB9R{9X9e($}3X1CW-Pg5a+^9}-X~1swJ8r)^KdkiLH3_&_FTf%s?4fdP zfXl-Psv)jq`w z&j;MqHGWBYkIN{s_4az#XDvGdf(}=|_oxWZzB)R3!A7!roAL5+Wk|0jK$O;Rjp6M4 ze6jg-uH$&ZG@+?U0xS&#d2LUHmm1bCB^kQNIyrHAczEpnRHQQ>`TRu0?})9bx!FJ9 z6K&v;hP;Bp(%+A!-6z}A`(TrpczB2mYh4}(1W1_pZwr=~G*jM!y+m#XauFd&gM`<4 zO2BERj`(!Olkhb@)$4DL6HDs_pA^i^8RmRfX$}QmQDwri$&TxLX^CM#gN zM($numJc30XhSD6G9!4?(cZqdS>C#o>AxfE?EKK?d*xvanI zI$h(;2`ctEOXIc>G5l;PhC7w6aW&Jw zv#^k@vZ-liY0}W8{xKdF7SDXb)|L}7yv}ETNww9K(ZeJig(XKdP0%r^YyS46wlzB^ z2j$zhZ+gvsf{@v8y6C+gq}@Vr)1dRNrTzEsNj~T2r`}3=ZRtUXE;7^Dv$M0WwBP&t zH{1g3?d{h_3lh$E;Oe^FRiD5I%)2L%-s80;KD`A-V4oe5ne z$CH(o4AG1`^{cdpmdbf|auwpL$fq~Pi?g4z?@wAL=%?@Yv3`2R7JUYcZKww(vRTLf z)i;OD;&+vG-Nu(<`e?@ffq@~@cdTj(Dk^c~bNs}jWU8>c8U^3*2O)YkHY`Y8TRVJa z#)yps=RPyDKJ{G+iYO3I{;aHIo*KbmFbG~(SLa1n{^iTY!P#ftnm}hQt-CAVKP7VPV1PvFiRN8Jh8si}4=Bzx><$awYKP$D<&m$2RUX6wg|| z#-p(Kx_LKo*#e{^oy0e9ps+SLScg=89e5>Hc0&UtHa0e2{7yAp@D;K5>`Ssazs-k- zmP12Bg=J+)uIen{vRm3NNOB zj}tVTBoIoSA(r;N=X^0k>CHCAiXgL_UH{!?TlbliQ8`9sSHE%bAg zcYZVtih{$T&!0b=0nY-n%BWX~O)qQMU^ja4^YK}a^i4>5IyD}R7)k5(302U=IxAS| z>82Ie$qMtj<6nmRixG4=`S}>j-Ekct;3p;~y8jY24ZePf3_O-S@m+zZvk}1bpX=yY z?9MeKmyMl+WBXbtsu#us-DfO5KN?m0+34-csb7W0p;IDbWp#gLI3tG4G(ck~JEi$@ zrxC2s8JO+QnVH!AVXR1N@9=Q*=%xVt`98M>iH5Fj#M+u28_7-zt|c^yTA-RCR=my*u#;%S z)m1=ecXz)eo<0w>1+)Kp0{(Dzc{w0K2}ZsVJ2hp{+0~UI-7`y!ilBXyA9#IzO@V}6 zq7>dHEq^ob&i{LL?EeKWkjShK<43o=hPraJ>8a8Y!g~#3GZ|0%>Mb04g5NL5~{YliJlgao#jqL7hVPx zf7|ftbcQcaq)eDj!mXk2vrOmf<$*KdHLCnwO3%frgY>Q6FzYkeLYl)j4TO* z(PvnLY@00UUo+DoQqb8c}-vt#}yO)szzYkqgw^|T%pUGN8$ym&%nua~?==geQs z{Y5$oFl8sOe#gBaPQYY|)QycFo~lPWEfsIquSl!Wkl63fP&vjkZEs6guDJ2y;i2`R zr*oF})QTVOmkX{JI{)gEq^@GXfd3)-92Dg->hNt_s%-S-E~dG+sbYL?Qwus&;dY@E zAP{(8wMC4SzlSyT(|0acL`nIHSy#)W6a^(K$(PQdEs~ZF`Z_j3uW%m;YNo2~_xAVOipyJYptH5ygdYWJ zbcN#%N1GFbAW7zR9Sn|E#VqgCNp_oI#vI74&RKbDb!?maYk z^^~g~ja4;W#?6ffqGw`49Y}iEaqxHG;Z#-A(a2LD5T7c|+E5CgvzO>qq9jP)h}`4U zgI8CBOnLY{S=5uo!qRdm#Ld5)X?6UIa8}h%a_IF%X4#1f-m&PW9wBq^Cze&+aTe(6 zg{RPlp~3#ev78k(@oyaIjIF{a1&aN+j@v=AxrZ#?jlQ7hn|HqP1aWwO&VSeZXzgcV zd3i*6dAVpL4k4kUnHfElm6wMOkR0W&Qp1R`vFC@5!T_p2j=86g1_wB{Bk!Y$!;L?f z$!h`{hnq`|@}^Ky4jr@cFWNqT5)~T+PKMHiEkSH$d-yP1!SZS^=x|85(&Ml470Bv! zw>OtC@`AwDvn5>M+xks6HPbE~gDLz&!L1;Z@LG1`NgVx@R21k`HWP}rZYT^`^UQDe+d^wOXB-?E6Pc3!ZsXdz3{q0G zK|w()3lF)uchk%JdV6IoEt$BQk2KFNE>c@tzyPdlYz(Ny9md#VS|=tZmWv89+u<-& zB64ypQ&UrFaj&hW3Gt5reP*?^(1PS}ZyAKN8gj))kJ|OyO#Lmv7s$I4=v?vbISo{u~bd=8FX`N+BbDaG<`l*3?&J zR4YzNNy+1TVD&6hf&yer!S?p{Hy=Mn037@2s~!puhC8%3z}-sE!qUAY`rt0>{(fb; zvOhr6dmz~@4++o916T-b7*s35>8F0HREp1^liYxH{+ju&>ce(ic5aXO$m~So@`FML z6sQx!H{*DQknpp`NLq06EmzM00i&aXoqd<>Hk$uokW_Rd_ZD+UWN#8VG?hq?rTQ&l z4J2C)4UG_B$u#cn-4DyXcITYkV+~3%pta)y=_^f5&8(kxV8ph(v(prYHBN1@6#Q=6 z-zJbl7ZnwqrM!(KW>PmY!uy~c-r3pdl95{qL&Y!y=8ps?oZV?}-;OMMzO(EvcR~Z> z`_!CaX;Db1BYh%lbTh{SC5^w6A6~o0r&uwyqHVoTv0El>A5^C8D#C%QIvjVK`a*So ze_y?L+~@ZCH1WfSaP49pr0Z9TurM&dKy?c8zk|p?tKXa>3oEPT`N7}G)?jG@Y7scH#>0@iY~*=y|KUS?fGX=&QXTiE zU0adq2-I9%(l`4FUr~M!`+)MX(yH%H005yPz6bZ`f-apoO&>#@FsZ1DTs?IzN3~I!+fubU(G<0ld zVD}%)oHq4zCF97mQ&sC#g^$1e)AX6sYdT3Wus!y%v%g32B*|14K%xc5piVNZ_O`zi zbX$3+(s|QwIk!>Ujq`S-orYg{2XLf9*a&az>P8?RQKa+8Ord%b;6B%$wHrxTgkl_4wApEwr{9(YK(-Ugv`ee2#mmx;k!SjRgH zeaZTB&`Xi4!x{wvm=Pp0zdipREcP@A+2>Ry#;*}qM^<&$w z{iE(ArcVIOrno078UA%xcDToy4{rR;d0OamUY@>$5Qvpd(>2@a<)B&yTtsP?u40{C z(s1W4c8|_%VVBKl#B3F2k8JkZ3~g%^L$^tYDCr>d*7J9=2@WE8+mXA@P{LB6jLKzZ zJZjs_C}J7|-qqD*dmI`Q87Tv(jnvdBS0B;fn*hL=CAWT_<(*nyG&hp_IoV5yT6N#q zvEaFvYm8J?skJ|@#>7apl(`i7J+jI53FcSi1^vme`?ggNzoKwoy+DJ0aD2XY=G0b3 z*UX74)#U3ZhZ=A`rl8bB)O)U40AgUJb>i2rOn$8A>>mLAC2wD}FU;ZU>WcMfl@I$* z13`lrR= zr(OPShf&%ha;xKP3#UG|p0h&%Mb_1YnolwS2eLhQQ0Y_h`7_$h&CT9{nE$dj^utcz zhn<)S;n)c!G$>0?41p@Yv!~~f3O%2w6wlEkRE{i#3U#2P0WCSYH4l;i3G!VULjw6iT%m`Btyd^za0ndJv@^vpU1zyfMStf7u zFwGTA#_7j;XJkURvmEBfCBEC}(tNpW$i%hO#&fJK&;mwCN+j6l=`(gp0nkPPAss6Roeih6T7f4ch3&N07Q?}WSv67E___;x_K~xV z-j<;JCYK5j`N#Jl|6}5_hz`kUXb>M991QlHZj9q1qjAvfwKvjJU7L^ZNnIal)xa4% zEXBWaK+xT{a^l9<)Au++`ck$Aicz5Zug_%iwnV70_64~@-g@;htgi4;AV5u-QQNHG z-x%;LRR9}+qpypFk-aHf!-7Hd@k&@5zc%xf7n+o9puYX8ftrz4aXVA z9UpfZ+zcc5fE9>}eoJoV_%+rP{P3c{;a1uWqdO`vdVctyHJswKy@@_P2%(ZYJUdcS zIw|9N_^EaFgLfuV9|f{f4|V^frGb`@A6HZ8vlZ<#O5&z(j7w=?P%0|HSbSmbEhSH^ zv`u3%Y~+0(F^yUq&x;X*iTlM_M63!El)HaU4306Jh6HwQ_7R<)r;j$3;2$wV17k<6 z>IYHYqKZFPM}?BbM5>;aH+m=uKnrf>J>uqxmX?5_aoGhEp#0`{=KF<*exy}#Rhh>c zR?mbbT7^-{D@U_dx-+u*`9uj+ly>&xhJi*_(tt1O-L_7dsyRwH+SECAH8jFh8qU&i z#G4BkGj`Otw^AHZYk(bwMe_Vxt24Xkf8)dX65D2A^u`-g(d*gNop=fv4=YUwJluev zNS3H>_gf6e%Zg#owMkjKbyx}3?fjEVXR-V5O1*(i~Hy|r!rdIGQZ(F6zTV_)U z#NW|lt>9r7^bVhVH;rG6ajvghY98_+>~a>gSF_D;Zb*bZi{h(M?k{$d2WH{0%y@~U z%v_2!rlWO(q;R0RLeu2&;QPw|Z1|Vo6A@cEaneQBM<^q0rI*Qc0FDkj)xdn9@$<$T-8!!mBAYto7^s|iAr%j`b zd#Eyu9#7+@bOOHe6GA*M)hABmwv{Z{_~EM~LYv;nqY+-Zqn|s9Qf(j^hfi-@J}GXX zC-<0or2lv0@4xszYAA`;wnLs`yfQqV(Zr~z_<}v9Q})uaxTa|Q$`%8D;@w`2!7qlm z3p1gel~M~`|Cs(RuVlqb2f0fRpNxKOeiTTLB{_Y2`Yh=(k56tyXBv+l7i(+RC((VX zxwYtRZ6n5GOo(SEcj#OCa1?T$d0QUKM^4;YZLbBfLx0$)nPI@4$AvNo?p5_u{rEBB zmzmo)RrPHCv~N*z)0bkUK=xS{nS7$7Xa?!O*#bXBBKvS}+7Ft;&%Sr#9WH;s@7{XXT7Vx4^YXsMi24K za*8ISC}dVUk%l>(|E_y`UeiC~g(K^$;Wz9dvz00e+G*Qu2OMdG!AU3xGrDiS;=HP` z>5oUQL`&dy`e_=`+DzAgC-Q%+Zp6%;plg63(v0Q$p%q=h9Bo&)^14*3D_PpbAPf-_ z>TvZk2QQOWIR;#pPz@R2_W?Y-fp8Hl!Da?wQ<&t7^A1q2KC=M)p4AD{U?%GI1YG8hq)@xF9>&zBj+FsHZw zLnJ-mC3};E>iniu{t3f1qsk}(587Umk8&qmV5o%Yh!<27ya}ftMm8SnKRnWc$nXBK zK6GS$m2SfHSM`8BZud0*r#m?<9U5UCieYBs9qTK>@0n?Z;wBWQ+Puf#Uy*DRdatn3B;M|&Aw`|F~(GU$As)~yDaNzJd`Jn+?$xp+ckRj zhU`5KY)A}MS%nT!R#KNwaXXtq2-Vs62uMhZaaB>6IbbzQ7PseHdV1%*>~2qYla3Qb zb;J*ub9j|@LMo--&zZ&l@3C_1s%y_|`Y9#e<9NOvpt;v~TgOU=@pBS&zpEI-YeVqk z5g{hzB(y#Js76E6@e2KZ`}{@g*-?yuDk_rgyr}Q<`Zwi5M;CMm&F6RdBq9SxHb~M4 z5Ar#vYRTB)XWhn5*ViF*E^gD2^YqtrRd`@%t1=>nII^&TGO&?RgX)_~x1e$mB?XF% zupNf6hASuEn(M~y1ce4HbMNqZ_Begj+p*W51(V#{ez^v5m7+?t;bm$48-8wCS2FDA zu-X)pvxqcW{0QZJG}Pb`j4q2n*jXa#gv^VXLetWy zY=W~x54^W^c#iY8*x_8lFKA~uupqaJim6mN#=9CMLol;Yd=weexPGIp_igq81#QS^ zq>v#BRhwe)a7|K$nxzMEm3z-_MZRzqWJe$SQWjYKIoY7?k8ah+^oQ@qYqRui;g6sk zROheg7JL&hF&boG6#C3a6fAB7NlLztB;ffL>c05s%@pmka!kKsVp20FwYMgNQ2W$@ z%J0@fsGJLPHRFSmL+OjR;-Mn=|J|-bo-Je-?k+VFRP>u`2DhRtVs!IbrTGsij18Qh zS-sbCX*>>o`^Qa-8=;A@Hyny|)^M8)+OB-)$Gy$0VOHMGV^kUY;>w*9z4u;dqTP5| z<4;DbMg&S9Dy`aJ{P0DBx>|MhaWoA9EQ^__R<5`yK+rH(nDDN*!fYm?qrCP?5vD$M@{=J5s=c`~^=t}gnIBx}VB?z|i- z#X250Qxg9AHRFSo3)YamnJogjeeFNBx*==35@%_&>AO^a(DNS2yi-kh+hEgZI{(Y- z@AF3_aa~-CL7B5+5z0k8k^UROxv_vrrchO#O>lCJ;v}&s!YVi zR4ocQ1bnX(ox-rKZb@J--f5YD*3uvSbWLJ}wjGbYgmv~g#OOR>^Axo%ezfS{`u?z+ zDrz^(egF5Oz#GlId3`7hT@ZpNVoTyfakBmUj5bi|V}nbF@6eu)M#j@!zh(A+FSHZb z*4oUiF}=H1^I3Ue%VWZjj#;p7$8y7a(pVFNC!_I+o{H>;ZGTAl;?;S(+=HyLJW_OR z6`@wzV?3mr;^G@vV*F5C!85Cgv4*G&3_w8Gg0VIC>}1p24F01zJyMK*YuJXR>8$zgQ?BE$p5z|k$ z^tnv2@WS(Nn5xYlOkyfa_;nI8NxJo+DySdg9M+l?N$gbUef*kfwR?`8e1i z55?hwg!Bmr!21kk-Dv*`|k;%DD?&iB_n5=g|c*IFd2DFA4c9zF?|+Kj%16PJL^TG6f&3Sa9Jq_`3tJF z5dN6WN#x266o15#k)URR2H8F1Ah)Oa?ib!hnuX)Pl9|IV9~BX)&lbwr8^>r5ub2Hv zM!`@mN3~*z{8#I6mCukUz3Q#NRWj6Mh%B~(YHi59A&O5V7T-Mm{Md#<_`rHScyEqF z4r%7-V{iR4&w+P*Pl#_0FyIB=sO~pV#gpQmMXhcc8BKpf+v`uCw*`1!s(sygK`7&o z2?tO>2Sr@y-}ICn(qNEzP-a!U91e6?oSNk<*ejNl$zI|T%7zk@$u5tfciN&1lNUop zxV*~`4iscZ^YNWLo>~cReJl3S!S|2DzsY*O$1{7?iqS$zdW7+Fy&wcvrPRp+rSy~W zTZ1+?oXX279ca23GwVKYCuSxsj=&}!m)8DH^uJp<1g)VC>tP5d6#fUx6hdIL&hP4M zSd%-4LF!X?xW1Omt@G!3B<7;%(N3kk(O2!!lWlOopi06%_ElbJ_X z9UO6+4YFhS_{tQJWk{(f#Tbzy-jaaX{$~!#o77CGSXn9g+&s@z!#3vwMQLW(2q3l4zhH7Up@0BxF&u^&sEabP0)&Qa7yJ7#% z=l0KxwSJmiWfC5~TlJqa!XAWvm?P`Hk3ze_ibKIkjfC`WVwOpUKO=22TEcQ^w0r|` z`!@{ev1D$QsL~od0`}&bZG-hhkBM ztDu#C`?bK{sQ{SEW<0&7f6|$m>zUniq55vb8U%GekViF)dXX}Q%JV$m)Gt7gy%Upa zg3g0-lK0q)ko>&`=_Uh8XAe`9KymA@k}g?{)Mjg=+K$n zd%lD})j_Hz*a0)t&=eOcR{ES)QaHV_=NE&ia|Kkwya2kxFw5A{Gfdp`-PK6&nt;pg zTKDSvtjCp#AhF zDaj`2S++Vo=o|n+h4|_wXg~mo3DC-j7zG}Wi+KF$^(`MA83_dq`WS9T4<~$04E1dh zSe5{Ky6*2tmQqh`lnKGjA7+%E&*9Ffcqb@Zv_(&9ja0Ij&4VaA(fnjdLgdf~QN$=e zVnG7~1KAUs-}@IH%gbj0HO}k=vX%NN_(l||)IdtRc*ya{g*6;*4C#iJV0>J@W6sM;(e##gBo#fUf*e%03GJo>eQ;L$* zFZ=>p5JQypmJ95F)%L_75|P9YfWxvn+@l~K0Ra-AcVcE{zL)Uv{d;;ozACNNy}doe z-eLz*ellz+K#6~Kef_W{ve*5|<}K7?fQluu8&7Y@HvoeYg(gw!BsHaFgkJ45f#`jX zipX~F4sJy~$6KI@dx{2k_(q9TIRY)qPyz)WMu}-FE$9Gch((x`_hidO5RsBv7n|Qn z%y`ns;N#1dts(j=p|K?&CHkGJ4))b(%OeQ!L2m2ts|OKBNMolNk%qeUAk^J&goZ-S z5rPh5D{)y8XbE#K`4lP111vuP=nVB5UOb4W5r2(I7eIuMkB@BmLJPyzhbwPo{aCP@u)R=54J-7j5nlZ__5)%_OfveJ zBg9Q%_Nfdz>{+Qi0U00aBt`hR3Sc%CvPp<&*n*+8)pc`|oeJ)9<&~f6hVg=|Bd9>m z$Pb8Tq@D)Y5_!jK{Ek#X$H8z0UteE!Hr1X+ZEfv3&=mqLy;x*Z2`B`R0z_ryXd~B< z$dZz}Zt@cO-}Vhv9G{_ztS{L34@(JzAJ1lneqo7ZT*%d7>{P{njhT`UKV+xU7%h~8 z*DebjdC8BIQ9W4ME7TCt-@AR9XA8%*tl%7$)9cPwdIwc zjJy>pfLdZd_W9t5^_TErKKyjUpAe*kRq5&;@*Z7c@Fko^%-Z1O4bc+Qp^_?93K1GY z51Vs)NaX-YTXH=$K(#B69xr>FAEGAq1WLAb;J)L!x}jNyy4A#pX>{@f#NLoOT048e z(c^M85>Ak(`pKHGBIc!1T3bdIDN!y zJ*f6c{@q0?zDFsO<;+2D+XqojKvUwVB0t7(Sc;oqFNee$O{RY*bIjAQL1=J|sBXy3 zUnhK!iQ!*0_XO-wp&ic&?8TTMd?XX`Sa7KDB3+0InC`?VXoM^ zfZ4anfZ@QZjy_VcJ3mM=bv|_zkFn57P%w?d3CfHg=dyKs27#P7v2YB|s?3+&ZA!+^)b zk?H>PTZ5jV*VTeQ#+HYFq9Tk^aAfX>S*qML**NwuBFSW#*H+hkjYYEz?y*7 z4E!vBf53r(QUevLai_`J`UjqfA6Kdn%Jf|Eyk{dp!H`e+1rys-B^%+Q_b7#-sgi|m z*)qE|MpM^e$$QAUmZ84*XDfflglco16ksk)(!G95g2|0$Z)gA5x0yGWlGPGp?*)UB zpnPKUpQ$^KiP1IlYQj`us0FyPUaQZ=j^1K=BTFlz_~+1_g}*R0!o0!U^~rT*vmT@A zBvWfVPLyUzq6KEt;QFA%puHpYteSe#6l?sdxDMjKIs!SMKmi3tbH^Y3g5MOVjMv0~ zV#O$>#l)pPyqq=uw;Ec1?vJ+KDY|oJr%@_rQ{%z$rxZ%^VIy663HSHlu%?O06}6gT z^_6)qE%847@@JVk7WsUS9)8olPtjnmyX%+C%mtuWHx5z(J@e;ZXiZZi3yqmoEAD+M z1>myq1J0OWEn{sCaa4Bvhqk_t_2|zGbMJ&zFg4z3^!(y>xaLzIvCQ)sa#MN+A7ome zWJYb@AIN4bkv54gU^#u~FXB?%qXAk;9rRd_3W6QA*+_t@7!BxxW=EgiCH_`CSZ(rf zPz^)^u^zc11cE#mv~#*!uGk}RAsS{>EGYL*D9p;j+vUTIoI6{@v(cik40@=k&{TvZ z)crKAeS@X5x8fVUJ_B%58gVarPR^2!WuP_7k_{_yf5MpK`4;EiqreO%aG7{tcJiZc z94KV!ynIS#Ix64jKG@}=caDn`c4192o`WA;+$*>ct|1MR?KIcIaC0kJ#zfXAvCpvD z%hK7MM07&MHShkVeQUVk4k4w{pfAk8!&9Nvqn6AAGck!hiR$(0-~0x_)lI*FrD$5* z4}su;=kXtZzeSM|1w1@#j&_Y|G3GAw@#H(h@IF)~@USfpjyQCB$`9=`oYOyz`RGwV zGp%Ar?*Xbz%8^grT6Y|kIB4e~fI^v=lyrP_;0|$yR`@#rC>HcIKzpZ@FJVQXSyo>5 z!+Y3^*rIh1s%+XDtMsu@AWW6GO0AshY>x$$H#J=AbOeY=!iwxJ_m=tDD9?ZbBI1{_ z;eb(IlBYnd$#BbG_=6rc%@;`p4VAku{D^6l+swaw$+Kyn{`&hFIbwa?lvVGR^$E`D z$s}<>lNcC@7pQk&#X+u0$HY*8(VH7LEk==4KpxF-H_k z!k0^K-@Ur@&+$$slusN*V1(Jt$#zrV$V@3y5y7BIw*V3+veeuDG?r-+8CnL_kn; z&Pzo>01kac@Y9Zx!L4v-_2bO1^&XLx9K9QIkL|{(#6(g{`o6#xkY_Kxd|`hT5n;Kv z&_>Q{@v4iAII;A@I8|+kXAKHbR5gK{smZq{R9@a)lqEAQ1c23ekq3Y|bzf#5an8pp zq2v zqEy2Pz&utBL7AyHT_OisDDY)#fR`W5t5b7)>H5Ul?{-{4ULRrU4MY$k2G4OnJVHFq zZ}A)M2Jzy(tj3v_Ep3pL4-OeiM8D+yTJv#e4>YXXroK74FNTvD99GNAXRws&KXpUE z^Y|55$ob)lG+A9wd^6k~#?^8|Yp1@@k?HUikqOZYZOfT?cDc*UOLL*@J+=|6ewuYnEudiCIUQleYC(5_$D|gK?qI}5K&V* z?LU^cdJ3ZVj}m@*cEsIl#<b`jZu&Lyb+p;f(s6*&y^<%npMHVj<+KA=dZ*thbUl zIgu3W0d%+#nhaoTcJIW7 zZldM<=8c606VcF2_}4e;`-)j!jqyW+9}agH#tt`g!hC1?dre(DX)+odx|m2^hTw)h zo%NkMK2h0HB6!Lejf;!%9j@GEI^q*Eqw+yJNMT-gw$Vu;j~zYu_9^u@o<* zUM^P%I>LFm1?};TdRh1%d{GCW>d?+<*DafOpRcCYv9$D5lf!)=Sp-5XJ^am=(0vSs ztw-`0c|L3JczcFrOe~|U;NyKp2VIT0{SImNAMU_R9rcXpLj%VOoqkxTxqR^5HS`zN z2EMOA1L(eHIq}m&W3HbeCghY#*G0{nk^-QGkkqDt95Qm5Djn!#7#ZtH(ohhEkXnHYZ1mUs#p_3TL~rze!Kp|6 zB>aCn_CxV*Z&^ALVVTKe-|JisS{o0nY2&uHzL#S_pYvWd4xXN;D6pWJ+c`mi;tgns za)ddDBQZ3Z{k7>U)LPDUcA%JxRTbbmsXU~^rm zSxqSq>Wp-U)cvKKML_;%HJQX5_ZXGOMb6PP0{(re9|(%BTIk5P6BJ5mKRMg15*Z@J z7F@FZkV1nVxGbZr6Af`Pc*a~{%b>BVHUIFwnfzSX31+;Rgt^Cw8_3}kc zeTm`Y$M%MNX|mMUPnif!!Yhgwx6bNmd_5wjq{jhf298Or45dYcqPYBdCV!&)+!+Tl zwgcR(U&MKi>nm=s8yu&kQ&)adI$^%4``IxUlUIJfyx!SUo+aG1?&Z@SXb8PX(vdiy zzlPvJi8n5lPrI!j5R+5ig#&1e`zzy(zX%t2PnL3CJ2+tIT3u6Pu=yUOfh6mxZ;U_N z((ZZpY+J@TtF+8y;)0%~Uujdn0=YawvGhg1lxJXjfV=yxTO{LN6fOx-^#;DrUa=(k z(UJi*TOkZGa$@&#e+hK5bh_ll^R2Tf39*_x_ia>kGEjg%I%XfpXAKU)yJ$w%@mGvF z-gX$5U-!IZvREk9Va%*DDux-P}?>P%$($kp&G3nl-@fs=b# z)xUhbF^C@%mzPS#n@&5qduz1v%t*H#pNc0L{SZg{m@h8_w1ykpJx({cZ^YN#=@2#f zsu|Hp#eD<;O*=R(v$$+|o^}Rgk|n;PjEs4MWIy-_E1!}rJnYNW=#XGF2nK-1`q`oVE|hMeXjiB4)G*Ag@&& zhTLj`G_@pDh-=MyK0~qO39vuOdTEzyEAf`!DG`m`%=8at_ED#-{c%7nSYOFZdP`QW z+%~x1Y(@Fu3cPkH1UqoAtsAeYZUd{EIlO&-R4}!906?UywuRKdkCDBVPaMOH+%I%T zq(|s1?}SzI7u=cO8th1adYO58wsnBPdBJ~|`@s3*vDQemx}*x6Px6(wE8W;6_$Cm2to9NYGE80in4h` zKZM)A8%-_^g9bgeG@V2^Q2bpv4!K_)rnZ4FxL%2mM=aW$oBw6}Gu8w?Ku&&ND#`zV z<2 zYJ$VfP0~PNv6=AE!cn1qrbDyCAka;ixvQp8dY4@fb-Eptr+tg zjlT~`M1~>&j^=lqTEEZczq3xRv?6mzeS!34I-5L;j(2zW`!aI(+O;37(X7PWO8PO_ z6fmcm9wu;LEQE7t4F=QQp|abowID;f?d7Bogt)zaK|UnbWAyrHgIf`Z5zUM~5nU}G zz8UCFv3IPz(;H!%c(qO%vik@?ZE(D<8)m#@<=T$n zk;dm6psX;PeNrFcnIu{NLC?E{ggqSYt4rwdTd?HU!OYmr8rfn5kb=?Px_laNIkzPY zwd+dV00#sXKvSUSu9}4T{uxrft|oPk22Nmq{gp@k2#9n+y`-+Cg&G_@F_#q4OKfk5 zPky~22B@RGVBP$MOkCsO>?XEopFe4VXMfd+9|ep7y^9apg^$_xqD52n1{P(tpV5po zHIR(GG8jLe-^a)J`8V{Ir;vVB7Y@hRuGF{)p!|8qsL`exJQuJ*rDFx14TiJ>S%c(MYa8l$Q z7ut`seb=(ir1U_>+Ie9DS>^ZApiD~M+l?c?IB@m3=m`TVRCjYtHmRmS`Pxuvh>HxA z$=0Y$?uUgU!rD+KufAtw5%$z2Tt_2zpxkcWINR{(zwO ziM}8d8xw;(i22tbjHNoFIm(5)~8te>`$2nIf><jp>26EJCg5UC#-8HHJ+8H1z^P=Mfc@@4eBhDX^%JZvoRHdEHen11Gq zG)&nV4=NUY9stv%GcfquhZfZE0Jju_c=_U$nVnGbG0Tok|98ZtCA+@EqRU)*Wj?FQ(e^d%^OytIWkewd|pQ;~0H#?%#UDzIW$E*>S; z-44uxLx$v}$Kw0@8M#CY)~y-LUnr~3Tx_Kvn_EBSBBH@fSg@4dtDe^Bgr!uQ8R_iW z(H(1NZk++>%X9XtP1D;)j*i9ORG-MdP#y8oZAS zDO+Kcsd?{+v#8z3Ixo)@UGUSLxt8G>8^8kYDbq)t4nST z>C@U3h{xtOIj@Q!{1E~KS&O-G)WvL)iWMc^vH;hwzOIg9Y1%O||4+7Gw%ot^-`Uzi)3m0B+CgIFSzcIPHYR|@Fj zm9X}u9C4*KC}fG;Y#kUulWu9T{FJf0ig;9dI>hnyhG*Tghy%%?;&(b`n993-o% zY&fA%v&l`BzoP}y6UIwX4b6!0i0BG1T@Q9uwTYpODLO(o8q#BU%{aU^=xI+*YZU}# zw@^w1cR@yyoKs&Y8eS*q7+w9MV=HoQlP;%twN7?lZ+ph7s7ybiHb^`qZ`y-C8g5X8 zcxbugcKd2B68~UjRk(y2YM=^2CH~zL?7g~7$3Y-lAbq{Oan6BZ_N?3tFCKeAfKtEf z*Pw?)>j4j7Y9I(0;KE;f)I{n<+Yg7WH=FL9SNwPP+vd);qp-Io>@YD8iub2BEGNyU zgfxnXc&yd$=N}#SRR8RAxjuLP2B{Z}whav60@Zv^maOr7QWpj24_7r0u@1QRtcue| zBhZ_}7ISsXK@|#u{L4OL4keR^rG5biy7!P6DM<&F1O)&ty+PHd3Pu&)wcpc#hLU4` z9xcP9)7Cq#of&nqd^oelCTUrkiob&Se--u?Kvi{b+~_`ZNk}(>0Tv}8-JlX;Al-t1 zv~(Q_0Vx#~R6qp*m2QwaD5Vl2N=OO_(jZb&_gVb^U)=fbH}@T9-Wffy&)#c2>xo}v z5Mh=#9MpD0pAG(78E|yM}0 zzl{<4na}T!R9(GtRp5+tYo20#-Vd_LFggVS(D)*NuZ@PV0vfS}8^vWvZ9+?1J3Kr4 zSaUpgOscF8W~70%O(or|$_;?5w{=JgtPuLJr5gbicjv zC#`5>vaSfwmcVo6q26n2jBve4Xls&PUTL^|qo+)9<*I3SEGMhW2RN)Q<}mrLPg>FJ za)q0kU@`}D%5PTzcP-cN-RaH$&e~6!R??#}ekdt5A|JlW&K8i9+s+-Ya2dL5;#$j$ z*aQ&q%9Ck04POg67lHvJ)2MO|Kn zfs_cKX7weT-+}yi$>79&Nj@UhzqHCPD#)P^Dedu=Y)|%LI8-~~8?PbO35bd{tlBrX z`c-N(FM*VWsQ=#^flCeK7}8>ZS-IT5-xk=i=W!) z`s&8w0#RwIt!oQyPl(McmvE#E_Uwj2& zmdFYP)#&?I7Y%X}Rf`=l-=$GypiLd(L&(_8p;T#CUpL%mF_tQ7%)?#opbL{Ak%6wINooJMCzcHQfgw851a8}%~O^55C~ zE|}-ESJ89P;y~b;^C@p#RP=SkhX?N6K4Rjz)V!)H;^p=*Ra1B2H)HpYdIwb-dUitI zaI5>9hg7fDD3u+b(^o~Rd^=)r0Gn!i62>lWH)^r>k9B)nSE{21R2tj|oGXl0E)^%s z`sAzk6qc8>K$B7|{&i5MSG#nwMHn&ZcXR?|WIJ|#n#1Awu%Hh+B5xFKLxZ%pl+JkPG3Fl2HRE*!sn7oV7Fx~PZw>Gc5P@Uh<+HMM-y zJI*(&F1*o|Uc!?Q9evi-E-za}RTcD9^e8Fn znN5Ls()ZZtHd_5@S8uM@}OxP)QT=$j&Jg~2=i`@`|NqY@I#v%Li^bNwal2|KXewRCjK`la)P z3ep+&WPPbn=eJepbHHf|C67wsJI!R)TBdwt>RTBWuSWdBYFG4+lhk<6TbBN&F{~?~ zPY5hw&EehSA_cLeCAT25k57T=_QBl!kSYX&F$dt4+Ml&u0 zlkn%=6Zr(6k)TN6R*l0frhHmDK!r*D=I303{j-vyUEepG?wKltFMSwlAwYa-hzjT1 zaLhFs5uhM4uk{uII>JvtUr(M^4DVdvXri(zek)w@3rbkR3$_ruC(%(iTi@!xhd>v> z=~9UUaf=&{j_={i^#RlXK$e<+GdbwmUFtUN9zJ>meRp#ucXv?~aU`62lBwl^*7f3I zip#b%$Rz~=LEU$Eb830LevkX($B#hv%>1y1$(b640XxQV_=_<;emO|Rz3HByHV<1g z@E6)!Ml%h@hD`4K{Io7<^I`c??pf2ebo%0_KkT>_25z22{9xW)4`nr5Rmo}M%Ilw5 zKvDq%${UO^NFd7O22n;@CMc-Dsa&%&Kp9vgM4e7?;|kTFoD8ja%eqRzMc!woB?7Mb zIxXa!;$KdDBd?biz0Ljo&e5HPt5ASw{6F0ceDPI*>*t4dKXJPN%(Bb5Wv(H}B)IPTMyfl;i=vp%PybI$S5dE;} z;ucsQ&iinkZWkkTb`vLLA0ftAa%H38aCoAr*5UH=`4fPstB+7vm^NG|Ra28}sgflx zJyt_wap*VibmVj1TKYutv}*Y{E*EabghqPTD`##L-ExW_{BY>lV|`<|nz-lB z(*~bcAEjsL#}O-$drn+AV0U^r8oGigkBT&U6XlK19eDzX-u=Gb#>cFa-z3B{E|_II zOIWV0Z@uh}seBb84LQbV`NRDD6$I?dZD`$$=Xd(NgxNOCbC;&gGTN#=q|+T#GrDBk z$iK(Q*x}xo3~!&}hFpYUV*d8E0`9g?7X19OR@iSoW8>B2)$cqHdpWa%6rZ1cHxT!1 zUOn^5sQYD>rSbaWi=R*Oc{S*5Q7Kezt6M~1EZId!zltFnQ{)6Q|z(25jrec^fW`#**=bI{QTFBUBD`D zbn$zJ*%3)TKiL9JC_V~8bp?&8N|fBr&O248F^mX$QuZ&iqK%Yf>UEBNUh1pZg5eLR zM)Mf7CMI|eGTa}SUgjDHI&tr`4KGxA7{R$>sHgk$yI6opPUcHfV3p&cB-%4mfia^6 zY+MoRQYnqm5Bvkm&vJU6oxOr zhCS$_x!TrpsRnCpS%D#_{hRZS-U1h8+2*?#Jj)*kUCmC3&K>6}R~6Ii9G>vvwYb+-b^YcG}!N!I*DJiL888Brbn0$9Ul@ho- za}DZ>_ir^%s}&{~FIa)x;y6~(4Y$1M>v#}~l=2OJi+o;!ks;ZZ)cN> zD=thlJ&)(Bu7Uo1nxX$X8yOr5wC`b>=sDHVbXiY6LN$`M0T830_MjRZtbl-lAhOr> zG|9slFs4(FxkF(cfHaSY^NrF$)#7)MN1%NyyucIIB(6z}K`CcgRB&I z4OxJkhM2f`d*`F1Bop{Vq55J5*KL0;Y-#S>ZWQI;2Yza6qMm{LcbZ87P}8zUoAMw) z+SVpraBReH3b zm++8*8)Kiutp>_PqR|b>3X;kThx+5rzX3+BH4ZZo-;BZMY(Y~?GAjwd@TmWwlxbUn zbZz9IoV9!gQ}_a1r|=x2mUl45U^g}SqQ9IHIb>S>Z}!ipFa~P z(V`D9uwg3&-{0v99(15x(b3@ODGo5sBr|XJw{PF(dYw%s%TEEY*e*o zzi8rqKCcFIfP<+z&d+_3z{*OeV#e#&6rknDVzF=-`tVXG2k-uUAfvY7RQPv66egkf0t|~eZ5+vq zPvxjg-oGa?|2YSmg-0$@5EzrzU=*vS_6?WAa{E7uZw}pAMt>_95%xl9tT zmz680-kVpRJo5gR&%fWtVMzDWSzu|jH^BXEmeIn`d(0>Qb@wd=LEHWBq_?Y@nr_2e z93OV`M=2$Me^m?&Sb{fxl0(Tf3NkiGD#8uH7`8lUe{O9F9A%t8(@n?dobd>HD(5AeKfA_wl4jISmN(-APJfMU~j&$1IqVj?Muj zeCcHV=_O4pC84lV>2J(mo26b#{oBn#%h18x#}wW1M{-;@B%;_7*ObTrl2}&;sERg0P46ZW<3X^Ff%?_Sz>oj+uPuRE*4ttnEA#RnQ-9 zpl8reGL*oy_4Hc8DH%Kb<)FX<*}|S0rn6NiBGqu1!Mx&;6|L9RJv>4h>R~KhxHPzf zDhog1jjZs-*w|Q5@@zIra2>8;uMJo)pUiCisKd=fiERkfGUWk>I^*SnVR;2T=Jui0 z@byE39eou@f$Y9N|FJ&g!^;!0jpT-ip#ceMaYz?$`P*f^pAF=^rRam=v?)}g5;(5L z$-rRx_`2Kc7$A8RZQ8P9Hj9cNXm{Emk0=<*YEVZ+Gl3UHMGTBbwV{-0KrvgBH|QHQ zNRMS-I*y-P0|&cLvnETMlQ&JD9=r`p!-KBnxWU|saAgvWBP54J zAL?{ON2SC8JP3^x_cq8u<&G6~FC);#<7;{cWfl0aEmCC|1bB_w`=fJ7nONK%r0EHN2on68S@GNXSJT{G90-Z)I65(nM?zwY8hb}(NV1oMn|yRygYSSmY|yXw*p!^1v3s{TxaBtlf%V=@6O(`WwA83HJk}N}(EcYr=@?LAQZ9oO`b_T2 zO{_K`3raytE2)@mkb~$7zi-%4|Go)Ry``pd(_C5O&}#+kB+B#?JeMlk4T~9#oU@7x z*m=UbqMP?v*Pa%K{?b(--5$7ajS(8_td{+kPJ^1UhzS%u%u z+W3>IX3_%$B=oXGJ32@Mw1#>lH&(vCJ}G8fl(l{p*tEo(-`O}=Z!G>aYBKKryLg?r zY6Swlc!}ey#~{}kp>n&qSp(V?T;y~-r5pS*iP@0{L3Rkk$X9ZHacfK2KKed>-*wG; ziamfskCVmu{vqo1^+t&gu|`Xf=niGZNRJc5!|)KvdUB1zGA|?{ z*|{8pykb~&5i~K>7{=w6PGbpDVpMNApaj7H3b35S2{^o9e_y#V)tXNK_IrIwgEB{H zu|nUNmFu|Pr#*W*-apMuKz}g;HXx_uO@f}{PB`cQDgzM()UZHSS_l{sqM&U9>b}eX zXsn95PuYCu3&(FtD>&61E(!Y|Ku_&`)G2OgSxT>oh{WS9B_e zNTwFYbAHND*rfZlIBW5%1EYV1VWpPLWb3J_hEVrYFj~qi9D(Gwh1!E+-{916zctCv(O8?Wpod;PrES1Y@ z!luIoA|xgi>0;M3|0!l$_9}i|s+cIGwaB?hF&R6xz%|uR>~~q?EH?W7@RV@{WM}gw zju=v%&3N5f**gsZAPSy8Gl+}%F4nFu!6XMdQ4`j88aaA#3+*|NefYSc0~WoS6`H`X zyx*UNf$Y*HpSokif|p$h@>Ly-n2Uk~4c5Q?B&t=y&_%_*8$j0N4%M4r7f z&&BO^vlD`#E(!2I>tPjUP2^Vif~+ORQPlahjWhS_ZqB6wiRRTjI-Qv?xB3Np!OY2C zD0$sWU$eM3*jL25AO8Bcpk(#bVE``Ax?`2DBXzpmQ@^`S57*P& z3aJXJJb&UVv|j}ZuDTL(a^jr!vMlIbi<(S)Rw-9VG24eS-k5K3DGyZTz|?6+i)mt; zYn<^h1pzMz4Z^n~9tT=MK*99+0=-Iu8sealbYb~3+Z2moz( z*ju5LcL@zBp#{Rve*%miL!^qJ-PIEUd7yoPG7wAF^tD8IQLtFq(Z?=Liaipr^{uUku#c3Aa~m zh6YtOB>3`Acv9a0zHhyKYt3CfxN@_-7H6*LC{sH4cOM2u`CR_#8Ha-;%7q)i)q0$&p*_XOJ9j`CdwRaT^{)`mRqqd3Sz)4z#?>oPvtu6K~lfBD~qNq+n|Jp#5!dIhmd+RsQs?= z*6*$g%f>#I8GCt!@5@8Kw~h}_U}wmb%hQPBsFq4M0ul{&L5@#oJb;<o~!QFgimP%*-`z<(2=>J0gc8cfnn=6nZX}G&DpSAFT0mV-cfqf6O z2BbX}2q^Ysg`j_a1rq;5Kn?_FbN}%CzNtK%gJBR}ko1v)QR5 zG7JDzY9a4(R?3R4`seJWo68d9z8NM9+5&y^-AC* z@edBL1yPU#=7`Jco_e*ASgv&<Q?jP41C5?$#y)9a)kmA!5m1`9MVL@{lo_A&95 zOA@1@rdBmHG>mM?%*slK#3x{Ft^r_uI1Ex0e1oM3xmRjY$X+m}bma=@WnSoE=DuMX zaP5lC2om}bAy+OxjX8Y&{DBSoG(GRDiHhm>aBOMB<|Y z338zz)Zb)^Gc`1f+TGbgGPD>Tv_5OV)uOM&o(_6mg^u5kBd#hEzJzuL|J1-CMj=e@ z`f;toq?Eg4ko_#_pSaI9W>Yci|4a<;VStI{#A)<# z52%#q9^u-AT=BZX?=|z(ZsD`d@`WhZy9u9FDZ_5i5Y6YkRgUqv+&zC-wjcz0@LNEv zr2RacXNfcgswq_HNe(CX;3lv1g>Xn`v~3LA5Y>)mxJUmG;pdm3gJYmjmmI$)M0CGr zufLke@F1rx=p3yE4?MVQ@lRw+6XZ+KRTQstC{-QDA8Al%emgazv9%bIqVE{E_z|d; zQG-B6^e}W+{_5?fbHkx*hnD>k9l=)i8g?Nx@EeBzM3y>K;G7?9hgSUlhf%F`6Ru^1 zDwB9P5Ax~__`f5PHp-`YQ6Y-uJ~%|2{E>!_;l2rM5ZVj$B!4Nz%QZiWF$?vbcTp!c zKEMwo$ZGiLS2Qnbi3ul8Ap?O@1aCm`fcd@2LVJR@~HFu$4=vut^Ha2 ziNi1dkm5m`h{T`Mq+#OWfUDHK?o*Z%Lcx%8>_47U&EKf9-s;qVP#c7K3bXI8Rh>&jE43*eOJT8MSNW2@ z{jleT#K4tSa{oR1Ym3$92g56ZhHR+T>>kVper6i{nBYid{^>e`iDaka$QVF`=t;~) zIDb~rm9siMB`d#5CNfYuth+F6fl;hWky#xnJLO$9e2)A^2pp|zEpQ{uW8>CIIz;EO zub**51PaA1JFJRagyDVwN}`0DC)t%+D6!0S#{zzO&EFwVGyLaW+AoR})AGdd@l4p7 z=&F2MfukB+?#gTtDb0W1+xeJXNuTMy&5Y=83MWi8=sQ$8%1nCXS><2fO7Z2Su)|U2 zgYv_)QnJEV`Ro7`zuM_M=%q>*fi;r)fdJjmAqt{@nw!KJz*7eP8gE|J0mK==Rom8+ zq242g<>?E_56l3g_%B|u89Mpm;q@5mwL8YY*!E;&&(V-!bFKNM(_XLEq@oWgTog1! zn@<bWp`R7Lf(m3q zoTS3MU$KZh=!#aRSm}PDoTCYIlJO)V$o^6}6py5&1x;XPW)M(%OWYa|M0 z*w_JOx7>AI7;eLoNKtuJe+)Y0Q0RY^nbnSwv8HA_7Z_C}^1&d0sAT{7LM+l%&b-3+ zb;OX}#LzkQg%%YS5P8;|o{9G+*JaqzYF#qyo#lOKz1PBG%s!Mye6kQ^T?Fj0@z7dO z0)gx!(F=bQr>ZtF442p~a*fF34Sl1&2?4`vWI{Mx-kH2AX}Gifzg|*kCw?P!7$4Z} z$0dr9#FBClrdR!Y-m{3PslhTzxg#Nt-+UAYUIkF{F#KFhcE0#(&NTlKwKBSlDD)+T zc4QZihicKRy7x&60>QoF{kzKq^aW}VHyldav9(e$$(*+37`}sLD7Q)6!unls^rbcf482pJiH9}bIYq4 zv|jD<)V>375Bd3FOX)Tl*J7zw9N#oELKBQB3GV`kE}XLDI=gX%pMPNg-#PYW40OLs zd&6yi{pNf{`moHvNSQM(@%QNd3W$Ui!0dE|Xv*M>3KK*TW*`Ffa6HusPj0^El8N0r zWeI>5;C<+77_%mIhrOp*;UUlt5@{S9bE5g0D?!?Z?igaOA4_CfAP1;^-s0NXHc~!a z5mF9ED(v%2ZX)j1ow5WtdjsIUyg977L4^Iu;pock_L=31uOVN0Vy)xEllPtGoip)G zh`JW&Re)`RsV`2SMC|jsB+@qTP#*k)2{#);KruP21l@{yD|82Zpu9-A3+fkQr0PSd zWZrk+RppCi)&E^AQ5c+D;jg^#05^WO{R7T{6@MA~WHKF^W#yaqSdEPjY|P&{m(bCK ze!^k2U$R49Awk1$tJp>3J=U=d4Vd&?ZMjZO6@mXuu8G5-%lh}X=_P75R|yjWJwuf& ze8DY1Q{pf{+E#D>xQWQBGzrus*j#7MLYLo<1>FAqS%`zXoLa{K&k)c(&`&q>caCQ) z!{4Wg5+kdDPA0v2(ZJMwV?rSo{-4FQ4B;(P#IDfs**g|Y#)eGf{RkuW<*TET*@fO= zSCjo^b`X6#G&buUcFc7W^Dh*5WwD4H6fQdmcyxT4M7SNgM-Sl9WFKaB`zGllirq?Q z5pj-qa#!-aa-lYBXf=A){o~*Aw0Q&j%KYTF$#Hy9}_1SncnzHS{_$ za=e)#@o((_?D_OwzBUd!L0$6z&|?hL$|(}-GrdEEq`_C&qX5a zZgmmu{<{0mYy6*3v5S3@spoZjEQHO?hvPu+B#K6)JWMEmUIS}I5APcp`Vm1o0}Yw1 zKEblm0D^xtKXAUfi>i5W?;bM&Rw#Vit5-XC&*L1jWk+?H)NPZ_Ibo@u9B2A84`8od z=C(^K)Ese%1R+a)ew3?R`WegtDowzAx!)h{Fk1YN<;;!Mixf(xg`Q-}kmg~9CuVtY z=nkfrpqO+RP8TmL4nv5Dlz&1sGE1lXZXW4tG2FN`6fqo$q2FMdC zzkWr4twoBQ-`8^DBRO{|{}N$L22x(WH_L^H`#wka5=gx~sSG~_%gp}JggRaUO4Bmq zQ^-+6ZeuhoHMkuWp~zLtu+r@ilzKQ`US4FL(B3{Y;`C_l#L-qJ%)sj?_D~GpQB8Kb zua^z;E~B#q^;ID2V$!|AhEq#m-a(8#K56vz&A7ULBY+^6z-426CI`4}fzSpAvqAz` z+PQx|Rnh18+E%>_2Y2knyKx~)PXXIwv=})OZe3Hz1@&#hK*r?)8?;ts5--?d)yF}Q z8uY}qE?f{-WTB_WgMFMeC;&|bngIe3h5@JQv=lxvH1prv{&e(8s=e_yOZs*r(15}2 zY&syM4j^G`Z?UTB&wZQSkJTL$kN0a&jE|rH{n#>uvlY+zCjgiN3PhU)B>s}z$5Jf{ z6MmRd6d$YjG**SC_`q-g__*L(XN?Ov(5!8!art7j8YjY1H1{#@Jur}E75Io%X9D2CL|dXeEkaHWMoMFKZ?t0ld1UFSQ6|Z==B^w{%IRw=>SvZ z-O=lChU3PWZF;Z6AjPmelplDrQ-&KmAFxXV5hLgFA}%lsSiob?QvHzPfj|VeuyX5h zS^3rW{n+Q;hlzmH5V#0Rp7ntNBRx2jtU5Ns1SP%Bx<4o z35@)<#A>N$;weJ(5Mm806c|V*9qc;F`Px|`B|p^bKA)DOotfd#x1S2FkjwiduSgP( z^7GGn_R&~gs{t(@PzQRmx%eRxNqd5&R^m||A`C#g8ChA)foogr^=rzhz*Y}uM z^;yUaAgTNwb&L=fo`M%bQyIq9Rw2Qwo5V_6-Fs=}v{#V>&oX4-(XvYekJY_T!oF z2Y(yoT{4!NIzGF1*uA0IdFZa=)0f?xqg}dTPC~@VjZ_e8Wr(x!ACLG6p2`j|%Y@Pr zB*g(3?H?B9)0=v8J()%bqp^pgQ0+0q&I^}vPS%%^w~)1-IXG}pkVIQcQu6$sr489# z$Bs0r4#7ksrTUUI0e=2W${%p-MG7PreLmzm_#FsvbcjRham0Lh>%L8F1F@Gx$evrY+@WF?UB&n%Q@$CdY zRQQjL+v}VhVyv+#bto)OOIQ3C55{nx5&lk92_LYg&8+4_8xqj^zkKA@9-9D!1qQDO zfwjF;tn+tx>$VY~*h$UifZXT78&|;Gye+Ojp zVmz19o`-1}Tr)BfItpH?;&yHHK68DC?58zTi03-{bxiJZmNo;NK*wE1>dXd99TJltK0FKtmU$jEN3y?k1-Uwbq|F%E zy*0t{v<$~ok#GEZ?TU@+6^oA(}bO={OYZlEe z8yg>IVP<|(kGwFzMAdybn($xBa9u4oOAPEiLVEZ5^j$H>hL5F zr>J%KMncH8DwF!KkCQKWIyb>MAc`#P<>hrxuv$t7l3`3tOnVFRib@BE*S@b`t=E@j zGs@R%*GynOidYOn#l6k(UXQs8t=yAweZI>?;7{2hqR{H>6216$Dtv0|2%M za0rGhJJE7~t)J1>0%Q*u_gey2ww$Z3d!{W&ijAgnJYIGQ3^r}xI_*=@LX~+pMHYrb zo+SU)=3{`R0_-0y#0P?`w;fRjz;BTj{B^+DXnipOgfPHyr#;QJ#o^XuK+s^NJA$pk z_5|lyWOWI&gwf*9r-=z$!l^^H7@+ZnfbShvGc^UmOd7n!V9f$&Wnf!gI-_H79qtz~AVPuoY*;-t8npN{e!r!bJg&V4Kzw0Kb?e{YX6c)m#Q|>x`#rdG^7QF)3bj{LnNz>FJ8Guvj|&U8AYU%< z!5P_RTimRAGr@yDAqGmEFablDH4JH0B6JiYV}ZeJQd1G!b*Z6Sj3D?0AgseJZe|*q z>p`7q^1cB2LdL(IyK7oz-CgqVP%%6Vo;Z-18D z*`n*96eYev4CXzcms;d|6Xq=}R}%=+qr%|r4P(OUv*1MZ-+_^I-G2r~QL(Y5L!+sN zaNQ7CVU&cdsjnPohCcv%K!8_%QBekLG2oiltxi?o)m(bh5ugoruVDQ7HYev)Ja|t3 zlvj+5UkCsnVdP6b4iBpN>NT^7L#lU1k=Zzy-o?V!WP}gV0~=y%U^pWo%=QGY$zTl) zjkK%GCwEfUx3_;(Pdxyz81g~`8$gtz%gM>LbuOnp=LCOJHpO5$Fl;= z3rPyC2XrC&I0{P2B54I6(g36nW=08{MF%(~!J5?)s)_O-V%@hHTfr^dK1gQ{JhtjL zPsqq{0M_PAPrey7e!VsawigJ9f=8ypqA19Sf(R9PPl1JNu!6iiH^^urM$WRVn=bc| zPpU3C{E2w~N3-VAn=|&;{YI)?m&clr8#(heQ>)-y@pW;y4v6H%8%Hkx`?c4GPXh&_ zPMpo;B5b)ZrdL!{Y`|Yc zLohVXGf0tie#*wld17Itek8rI*7@q!heDSde}0IJ0aOw_m_42ZGrSV+kAAmqjSP6& zF&7H{sq;~{Uw}j7vpO9e9TG@mL7!a*17Z~5rJR4*{^xWEgv8G30~tCUtigjj`RUW+ zEhZjRsa1;*CYZ=+xdZ{Os^9kM(?M2Y^OOGm{&#@~`ErwOcs;*+cGVi*zA;zQnYL=G zxqjL4oJarlq-db3vi9a03EYW@C^~YEyu+*0$5w?k_kkGlmfB!O}12x~Y>g(8MR@TvF(EB(T78xJSpVvBMcy;XQB6fKN_K z3-0kut$Gf;yfFZAstXGXi=H`i1%>zaQx{$bO}(4qlyZ@qvUl+IF5i?MURk4rhv#9- zgAyezp8w%V3@I$c)++Y@nS!A<2jo|%>;Na<|F3_(pXmF4^k+z34izBJA# z?I)p-7(fyS?!iA%w&U#VT-`fZe4QFLGOF2oJR>3^VAd_8qN0LYIxv{Ffk!?$WdV@` zjXM<-6u@Ry1t#*)qv?9He!Oe?7UGG)6q#60PY+?ZoO*Jnzn(P(j0eAm5M((7iC$Bi z_1V)##f{qyGB76At+fN+*2&&nxaV2p0#o2Tco-a_Ukyz`wD_MLAq5K%h;HfysTx|K zd&6S)`By^~K?HuT5(at35wPqm!D|nVV(r?Wdi4~+rbd(jcR;?TteRfE$_y5su%_uy zVj%7RR}lGplaP`=Nthm}5LVb2CFYX3MS(1Et*!adFc%nMUjO7lHhRUd^ajH)cy@Ei z`!ki;wZAXxHIE6}TJ!qHby{yBPb(@)hI*=R?c6_q=qaImt?2FBPYX6CHNHi^7Z-&g z4~mA&Jk?*v%d5=r%9X=J^w)9?tp;!px|5~d(~-ga3Qq~Rnv3%By)c=o2U1!S;L<8v zrT~xO)7013SHe>dhLBD0%OT~4uK=|JW4U$MK6hEoeXWw3O)g&+AfoThGqDdoDJ-m4 zv)s(t1on%ff`VEo0yM3;LTn!c#bHbLG!V7ZMdCHpx16svL$B;?T)9y!xRmc3H5MV` zOi=twP2(t$RHlax3#FoBy)HK|bhuhuwKx;*{w{s+;2_Mwg)2e1$NyFuxC2^2v_LD*i7iO-(##XM?hDELR5{>CYweN7F|X5r(2w-D42tquUIep-*3W4NThzh-9xdYG18ol9H-n_=s< zxqh@H;docroM8Mf3lTnF6)aRCNM4I^;#LS`gDZ~!Nk*tj+#trkfE@p`&F<0%I-pU| zz`})HHF}5B<@dBR-%L3GH{XNFa<7?>S%rDXY+l9tfdNinG=h>|OZM|%$KZvDkBNxD zyacgVIrCE4)<4h)LCK$%u5L4E`Yj`&ilP>t4_`AcoQmJtoO=Fqc9t5xrUq8%2BaSh z92{Vh3^~4)2-_0mdP{a~r5jKy7@&YnUUJMTj-2N#E|3@!_i~|{&g5~&3&z843 zx-Gv>nZ09r`SN97mFF>3b)Z&iB`gQjq(v^Mh=8$BIZg|P-b5n#R_{Rj3FVq|!?m2S zOO>Hf=kjhk>$I5<>~Y_@q88K6CL7~8s z@axwvqhH2Ih#VkGYbC`tsjE<{S%UNM2K<#hI}-xAp+?|%oYYC4?&(`B1=AfIg!d9dL*7*ym@R_%L3vWO97mW2ce!(3v1w0SZNctK7amv_V6>=8;Y72 z)FxB_?P9%K0-o$zS`<(~-wZwp^8)Oo7!8~>;ROYYMpK{K+T>jCWaNQ;Hxnf#oK!`NadpP}4Q3L<qCP5{%q>AkGXr+BT2I01{9i3ysSwwm z-ri>k(BNK_Wl3m`Qv z0!2||Qz>}zWMiDvFaY==7{l(ri_&~pB`RR-3ck*Ca%+7yf`Wn=hWH<#YM}{%RnqxK zI6NW9P)DEGrxh(IMlsqzf8{p~$WIW8uYbOmob21tG?$ur=?yp&+<_t+c`cxt5svbA zwG__>2dIT>EcHdup2r9X%?2kersVH01Guu2=5XAMC^M-KLjPb$rT{?eD1M?Jcf-L! z+0>LPzj{GN4(14E9DBdJGK#F5sM=CxS-~k>6&^KWd=Cb1&113b|KOq9On=Q36c*Nm z6{wNG6Nh32l%*I3SrkGX`mXicyAOHwzRb_3g+N+4@!&!mdjl%_;JgK9Xefkcq-~3! zcEw&4Zfc=|chd*M`1ohuf>*L7gn0Yw-F9usx8b<;wD|>&nO0C885UaJ-b`+6R0AQP zfpjZq1EF#tziN^rMaGK?Y1|{`IW*Gwq@~%|+1WP$Q--3g%9|_Rj&g9+i$hf^V)dQ` z@&YTU7Pk(AjVyoh184=I?o+@0^Z9Sf zmkOl#`2)~XZKax-nYnoB60q=APs|&;DP(45zRt@d#njZ*pPV=X+;*7P?&p9%nMD47 gbHV?6syMlalNNl=pRS`djlqBC)OFSJRV+jQAOD8)d;kCd literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/images/lateral_error_trained_model.png b/control/smart_mpc_trajectory_follower/images/lateral_error_trained_model.png new file mode 100644 index 0000000000000000000000000000000000000000..3396b9e7dd44400936bc12e0edb1ed123e09d9f2 GIT binary patch literal 26903 zcmeFZWmJ`0^gjC1NP~1LASx)`NF&`+(%sz+g0u)oiAYPg(%s$N-Hp{}{kZusXATbbaq& z?*QM&&9iddpjYa($$$Cfm>=%4_BakT;F*6Y_z@Ge+=Iu##l=+`G=ylWsj2ZukcGel zb&SFP_kPXP%oYwr{?6@?DOJMnuqMWCKGH%vT~ZJojU!2m*U{0Tax-)NZ(Ec)hPYW# zOl6-1!c)qo;B&?Jw>>POsre&6LPShV^%<87Txi}AkLv-kz|{(Z>`!i7S65eYem8e_ z?qABjTra3SbLMcg#)gl%a7NjY%6kq9^nqGuTi;0Or2+wd;$L_BGoo*%D!9#a< zch6!Z&wNH`@t)+!B?r6gPi1)g+fsamKhx;N1?l&Gd$BWD$v{p)VPIhqc5yhr9wqqj z%H`qq79zZK;PX6tWjgfpiJ6(1hL)C5M<}kOl+q>`5XIA%}l9Sx*2d;zSB=WH!K7ctk25%pCcnNZ!Qiap1zcin>+ry*}pTMi~Z*9+ttm@ zAZ)=q9L?gY0Y}v{0h}1_@+aRz=}k6zVrqQvd42EC)!%4UVaUtNLl9Uu)benDdpd8| zY%o`0VejZThFx&A7Qw{qyrcMqj0@}f`g*3!00FEh=y1N;=wzi8yYZ;7v3&U~=az8(IQaOq=9QZF7t?xv zI?=txBEUkQp$0_9#5|vwoqZDfQh}3O&(JV4T{$14s@h^)+}_P?nu-B6pv-KT63%~R ze_t!ZOR-43R2LpHxW75Sv6(K>8DEB-=uY+H{pB)v`h0Kl#-=?4n`mHgFsP?T^1kZo z%Dr`JN^NKMPp1`l{ahh;&d!|Ac197*hEt12JaT1|44F-&qA2;(N6qd3ZOK7G=H{=)#>P$t z*oIezQuuB{Wa&h=hf*9?THqid5fS*dwl-#iHpDy?`uppf^L=>86f+E@Y#wFQbBX zW51pp92|@kePr{&q=fF9vobRwh%^$}>*ApGWVLE!C#RpYRZ(WeYMptUYKeQH*ELBVF$YP;no3M${L=ivLJ6BBcn zbw@pRyuH0KQs?LA5k`WfAn-P1C|w~GKRTyB>%{N^tjhzfXpjDR~yaVH}r7OyrtNyBL~hlq}jeg{q)gq)kh zLiJKk%_LGzYgEYI!9iG2QL*;+`sN1ysx+tQ*U5=}R(vk?&y*Ac6BE@fmr|X2k_$5^(V_H%b91B+eFI*oEM1@&^(XPHQM-t+u-2(!tw^;T;F_=E zrM>S?yI+BybI;Q_mZPI1^YI+asiKd8z&P&rGcq!295=&9`##{ZCSly)UUsMXJy?{* zX(=n?fjf-?RA7y@izDBtr(hn}X zuLA?JS#i0U0(U2(pM!%ly)KX3uQwB)C-#?HPSS5|Zm#|r78pO~^184t(y1pzK*ngX zDs9Y3L++ZMo?f9;+X6S>{$K8KIheskCt~dAi)SeJy0it}E+!$7Snro6;Bx{J!CI_> zKr8UUmF?{i1;KlK5Ddl9{UK)80}Xd~_Z8TyAhyILCZZ@PD8O6}gu1a~E^yy>54Xqe zmy2#JZb#be)-yQZ+`GUQhk>mjEq+HZ+Th_t4s6Y7d#E$>eMI`ClVTT2qX+6 z**`3_FZ#!iaFF#J^%8rHZ#IuZL-$BI;hy5gXSlyz`g?VAL;7Xm1$BW8F$Au)-x?sf z52r9Guc#2Kwq3L=10UDb4oQLsT2^vIkd6O)RK^6Zb9#DOR#{nmHl_idH6{&s_Kb!G zfs&FkTDtQiQ5U3v2`;#C;SCE7&9e=QhzLwfOw5lkz{BvL)VH!i7rI1HY0!NMmN{u_ zSxLIIv~)AzEh<;wDvZEo2&_ZMyS{qxM=VoX$)H^_%+xEJmw9J zo3jI>W_Dr8O8_A`x_>kCX#J8I!ymjm*TmFx4Y=aj|R53wtJZq(*M0~ zX2DLnQ0IcKrlw}^>S`K^EsTS>vAs z>U?qJFdu>X6PdVNSaxv#gNX&5Sd{Nj!^8qAD%d{|1?}Pf2O4p45aEJ?f^ry<|Ni^e zzo0wmLC*7NG|3D*-lUPaN~_TfQ5299+Xe?QL4bYl=*S8^qoYFxkcAs+Sz4mR3qu4B ziwFTjexq4|>g(%U22K{_*VAq)znx(%ZKoQmX~qh>WlFRlc!{s%!p6q5!I)&o>gwt< zGc)PnGhr|!zCSG?A(%+d8+T}ENRd7shCGJS1WWyV9`3GTam4p(73J#sdRJmYnikLd z_OP0m*ZEaZaq;P>1Qi?vOY1P3-`d&&vG>VTiH?M`x$ONV@RVPF7U9 z;;WN?!-7UV(a%w_u|uMw6tepTEhk<9_+<$4vSPl9Mx`YI3~}vGm$tXI!a)Glf09e) zH2AkQ2u$t9XnQy<3P2k~aF8L|jNJ)uwNB=&N)4|6Zla>0wE^hJVlhVR?%}Z;X#cTW zY4fxMkb=gT59z`yw|>bRbLxbM?R^b@sS1Y$9~&N)A08gAfWMEH8%Y?Ont}u?PL-*x zt*vinh645U_qT%s`vNQ|Qznt|#wd!MCqT7OjRdg;37s%qui5uz8w(4|e6g4RIa5$zx~ zu3UkLYY6h=&GzuSe;9P~KSLAsd`Tc?r!9cG9pGgW-mswhUs6fLcY`!dP5qSDX$u3y zcz7x*Dqx0t?ON8>*0tRr9z5gYBLfg8Ffuao;S_v24J+%I{xTK?FY&wKfq{;qkAGm0 z0l=nKfFuAS@>x0Wb9%V*fZaN9zI1Z%Kjh7m^Yga^4}J9WlZEP|#adi}Hj8yG?cf(G zcXCxqD_8(nDr1jb?F-P4)v5mtesIXizkqyKq*aXtOdvEe^1Z#ieQn?iNGBA*A25rS z@$vDM%C#RghEr2h$irrXKY~U^6yJROjTlMF5s;nzBGq#*A4T_AcoTrP?$$sQnMO5j zt&eIXlvVcz1)k*hA+RX4hZ!cOoNcP{q1N?~^k}Iu0%isvghBq}xe8uIhkt#29l^=TsYs(79voz34lCnb6CccjfAOAC>PM!YM$?Da?pW%@j2cwSeZV&}1h*=E9vXd>Bz5mI*yFVK@ zpRalw5D;(zkTA?0CP}kpO^m2uJol*spk|VisJ@T)ZivXp|7A?ze;601XJ;KKRNnqP zPFpRLld6J>MyqW>?%=D-04-n#XbhH?zf$ml+xxEP$IpV zC`mh0>-5s|;vfugqzs4kE@C!Q3;^GrsH;y)r`f?)4%iIL#@X$b$P3kq+x8|40p&WT zkB{nmiHj)A?DBk%zETr2UOEUs9{`L#5QT(FIy*W!;Zji8FgKIqo~)!{`uhF>fCi)+ z=l{}8o-Bx&Y~Po%H?ja(%weQd6>WUt|9JNg8)p63*w}#10-rk1=q7*Xjsp%gP$WYr zOFR+>5ASbJzZ8ga>KGKf_yz_BCIYTU3l@88N*oi(N-ZBhegsa-k?Qy0@r9h{Z^o^J zganLpedl$d2bn7b;HlM4BE8S`^?U(=a%>^^zzS>(LHg9v()vIYNcqY0DTIPW9{LFZ zMa}&&o2K@`OE*54-m|8oPngJEh~RKj}Gnm3=F)e zs3`i|H+VKSHp%SF;^}m1fEYlO0BEr6&!2HWsb`{@nEoI?OG-<#&LqUeA!aK-k&)?V zjZ%7rpG`PRM@>B*BS{O~Qo`Ap9R}F<))e0wg7C=2#r1(GYYNW>Ishm$|M>wxvpZwi z5n(X;uL@HBSATzq6CpMg08*<5%FHFi7O+K*-;Lq@<)JBLBq{W3|wiG zGE0R%COSIZZ=u2C53&r*%#BIU=^$7@1qwwM;Kn$_#G$ZI(btD2cz^bxwi^Vmn%df3 zs*;it4h=&XWF5~Vf@21-)@ zR>H!&?P8tkk<0%cT-?39$j*IW`sw6nPh6-F26x<#YPUynVYpnfS_i@s?A5&hiP2^q5T&~Qb8c$;;KeVX&)HCu$ixV4>qLs z7G&jD_~DlE@nA!HCidQArq|Z;%vIY(fq=VPZBeOtFkg+WQ|FvN!oyCA$*9|a>gIMS zp(+czJ6ys3OigBXB9aE^R=Ni;0g90!axDO7%M8arg8z1cVjx2LNrQ zyqi)KWP@mcqB|pq*0%vtMHv|vhu`q{a4RV*E0)Y@QwI3w zeM|JrjD}?PqpJH-y&E<-KXCvS4h|1Tn|!>;flm7A)2AFybZ|>z93s@H0s4C)6RLns z(Z{3h?(PDlp2LU*iy{z+C{q8WXX*m(|HtHL4;KY{kmIGPo)QzI);7!~!cHiYKF<}+ z3UCIXzak3fjXWsl<4>3Bg)}$&xiHDW?nG5T&awvFYTNAWb;j+J0DoW`#OvQ+FR8qr z#PWx!TVOK*FjmjF2Qm{ZN$lw+z_zkLl3JzWFhN?Wa1!8m0C_@`^VwY-z$wNKy;Po6$diVic=co!o#^iS*zBOQbG<&q8h?VKddAEKqd^vdQY+ z9$J`~;lTJ)SS-dR=750SO9)J{D_uD7i-#ucJ*?DO7jP>1DnFN_U|*NOW(oZi^b>#y z)*Ble#Q!Q_Uu`TVZUgTNWYW|9(&o0#P9#iHc7Nbbt@}Wm zhE`_H(l(#rfRE4A?8}3*2SDuV_PBYp(aX&!^}jp*(v#-{H8wWB=gZ;*i&N4un1HUX zx6_P(HX0fh#H3`jb*jvC7ep(Wc-{U4NX>EBCMj3X_@B=Ra93?I6688U0$A@iK(cl zxG>4U?od_bkWOD1=cFB5u%)XjN92|WA7AD2e+~~59G(E!5g>&yG&IAcve8!9dsLhX zC?K9~D%koL4JX3VVPP)s!svfpFUdk`X=@XCqfrI{fr54FHSFRYTxLxuu76Xb!JP#S z9X--T8Z2{EvbU#wG?cHWZ+-g}zo)nkdJT{Yxt(`#0MynW7zZ4B(kjt5*XXQZy{B)w zMKxcj=a;z!H%Ud)H{$nyk{ruawk6X41$f@&h>MBE z)1bm{**1k@K6bS(^AC)b6Z;|VrLzC+U}oJ_dQvs(rB zl~;%L`K3{NvjgNG)UMSs+)KJn`40)Y^Q51Od!Oa`b-V=!mqbcU_qj6bUs)ZD0@0@1 zmuL`kMg&u;`6e7hJlTrwn2%^?G>#MV)1q%piQn`La^D$w4&wuW2f^G6Ru2G*)XYrc zbLs+@U_T#x3c~)S3PM&$k}EG6`M~ca5}hZY7*HNJt9QSs-omZ%u^iGpUUS9SK#)5 z&3d6mi3;MfT?mEIFd*NtZ)Jx{(#m)L$~@ji8NCVQ*Km0?Hqkj6Av4%DLnUvxLKG6C zo+s=qozS}fsIAcYU?oLIPcez)r#FSvva)5Ht-HUxfLVpclX+xp(3@&c?9f1m3(=so z&LPzt|R)U)Rj6>*`mV@60w`FBW8cc41qUA7RMKb!__l4I?JrlM%s@ z%87kWG#*oIb9m@#OP|(NyNE*YQpFDh9#1bXqva-_?5g9%dZMKz@;-Snf|sc9rVoU{ z0}Ub-mzCW$LjsV$iC5`#I9>U-)yXz(2O~b41k!K$+fIkg3-C8J z&r_|TMG=+oT@-?WWmgh1h3<^)H3WCB{`VhhWL0sp0hz4kI?w{+*$(UCcgKE@Y+KoRsh$EGdKEvK zQQ(db+9Isvr^A0x7I#EVMP-^vafb|u8=5>Q!2-G1XF z{y>1tHw+OV;?XJeWZgY@2(|IsX9vNbV!jzw;{D%$#zbuU@&;Ljkwi;E&6zEi^SfHa zr-Mp?mx{4RR44WyjOALBhZf)=L=Gom8Ky~uOPh5Y6s;ig%irksJOYh$;g^bJ@}1OY z(s;l@`Mu2wD!&jypx{uh-wN*x#BCTST&#C4_&QL;61Lw1IK!@WGW+1KmzoyBbl9nH(;t=x~biSbeWr@QVp?K}tc zq^(bO#P64SCk7wY7tYY3Lm!Hh)e}Oq`1(*uJFGNG;1ka^X#4}ixDZS$JUWvvq)DD_9~Hao4$KL;RClTGd|Ykm{-DA1@AVsyqg``&$vzQ z{k1bTg6nUqACtcz-`_f~#R$90E$gPxUct1kbs4O+plCk_dR~I(5?K!aYzfggIBs8r z6bzZeDKaLmg93o4fk8&OycG36b&`}@h3*A5VX2-8-*-i1?3{I3TycbtNCj%T^zO4- z)VV@|2&=vEyk@=`gvYjxp((06vS~#_oghxQJ8rUIJp4s{z+h-bR{ls0fZ(5~YieU< ziJojc?YiQwbSCV52|od88PRr!Q&(Q{qCs5N{HNLxH%Ts58=u{fIS`;bXZAVTK$Wow z`1IIF+m?X|y&=PoN|AOxZk!jCAY$uVJ(oD9V~X@WCNZyXz<&uf*K+b8X-ukP`sRQO0LpVWZ*8OV0gEDBQ8 zF)4bX%i#&4XwK?u`4@F|U4oQh!NG$qnT{O7kum%!4>DZiGJQK=zsIPD3bwDEu6`{fzUnlD^eWxE`Ofa`_3~@OId{WB zv8;}40h}QIk^IsV3u9cvsns{(s8f>wE{j%K16Fcy= z7Nzm=-Q5V}SN~?eqKO8CtGV;ZS|kk*W;{_%uk@t)-vd73 z2>NVXTAy{VkCz0>*HEzJBuw5HiyJpS9Qe3F zakOX_!C7TpR9oUL4FpBF>a=I-OiMRXP7ELk%I<_Nz+(<|XJ_Qs<4xmD)ZmwPB_-$A zxGhlua4@^Q&$Zg&^AA=v{L}ysKi%L;kzhYlL9BVphX$4SKIO~D@iy7u zp@%ww@RWOs(b;8OCg)3p^nI?HOKCh;ZP}K5a~*enLJuN(8MZHe14KrAw{fI6VjSIh z%?6rp`TUeO0bOe6a`w^kMC9JDZXRt86M&ZL)E|FfJEF5+u^n*Uu)7r7%c=NW9%e}5 zTOysI+I#9hBbgnNQTHN9)y{z2SJifNI-8kZs@7~VFepq{Uw4O5j7-R>7pmrsiqORq z|J2fKmFEB!s4r=S{h2(ntDCQMRkDMEJgf%cC7F(2BVj5wC5dJ#d?ewqb#16fv43|m zca{-Ch~s4?d!m88jGHx&8yVSSWU(XE;LJy{FW+T2o}|^&YzMWRlt%46HkO$)%Q_sU ziDm8|;of*E%zR8*S8=A-{pd#sAX3)wH_@v@Kb@6z4L{5K(w8Rs%N#n*lf$W&s;gVe zhKD|fa8P~3P1Kf|mBXqUZykpttF7=SG?)7FKc4OH2SN6=7Igle_F0uh2_KaLiU>l<6l&lr>- z?Qks2gY)^fgC-iBbsUgBK;nwqgmG@+yt{$TB`d{pM5kL++j2T_n$Mr}qxk)tn$&K* ziJn_xeE1qI>E9DqgeGUA{BC5`kN+M<8SXFkr3lD;e#Doe`%k?PNZ(+64cM_}{P(VQ zQPtYHFJX&!Wme+YXKxEI>td6lR`safUn*Q0JyiAg90J#$Hnb6$Xshen{vex-AoG!x!SS&hKR4d zPdix5g)vpvg}j^kXd?N=Ncio;xy_#PYAe-?b5#4_ejh!2CV@|)?w$4Iv2+w#`}c>|%A+m~jr>ybiygBieoBIi_3E}7jlu-&OB2}i6|HR*|Cu}yfShg$9s=-qJ6-B-;mJywt(|f zZIWy_$FN&lX3X33!EU1dyjeyWcSGa{jQV2iaeyPIxq=Nkn|?p$5I)+#KP2-hn^**= zjC<`=qtwjB@sUV+)hA`g%PMt*xS3GP}yf1-iGtexG`nD&WcY&)48K?c(=zmMIQC3 zF`h)+?Qd|zVb=bg_EXk>56O&DO1(MhH?MeT)E_h08UuXzCEQLxTDUB`7lGIHXi!SJ zU8qaMj8qeH47U9$K$KmAY~oI)@L5-?4e)R5MtQZcYvf{l6E|(_GsU%iheLXmqrWh} zu0K6=pr$A27b#u8D`p3NxR?9$2>`^wLsLDy)9LC@%?3zjFz~{T+8Y!ZRw6R7|0M}W z;;MAb{WekRG1rw+6)nm&pE%AQgr3aQG-2E&vu(QEJ zv0~F;*oc;6v7|Wbm5u zABQ)88ENr$axY&2D5-zHF+_ZOFGU_z7cneaYSi6{c<_BGOP(pLqO>DVnaRt+Er1Xa z4*j7nph4sRHv^V(&k-n|-^Mw2vze6K_4zEfK zFckWPG+hM_iUyQY4>Gs(*pfD4nA8EB7|G6{sbfC~I6Hv17H~rk+pWEsi|NUoBFKKlCt+WzE=^J0SwIjbYo5hEF#XrG(6Ce(aJ2!3^`~<}MXSh^n{`U#A z_(AdK5~4(84P*5gy$P5D3==DZf{Z(9eiz0JS$7zfCn~MlbnhL-DSZW<&=uTH7@e9M z)xVt>hI!lqOtqRE7=wKK<$jgco1)m>Ud;{&?+dbn0pbiTLwy*ngF2vydltwGt(2b>Q8iWOYPeu`U!s zS0DiC(su<#$>+>y^jVZGW=dbm)_dxhmGzjnr&r$sA%DPQYe0@KrW&!}=WE6hqzDrS z@)0azR7$9kYW3pg?`b2qZ32UM(8d7wEZ}AE=0N!cqJ+)TxO{0{i+fV(acNTj!ZZkTTT2 z;rhIM3NQm%gP@Rl{n_FbR{W9Va(y`)DYxeHEnChDZTXHKv?6)99ps&GFix;L!S1BRTi%t1>&&Qr6_gLJ<)0%Ts({`ALH2D2@zj=EX5Mxidan zWWB8S;36|KI?iY;4Sd+{6E*pGbnhNlX@^!TEBNE;PWH zKVIMbST)>YeGOt&Mg_B|lfnya>$f9dmrPk-7ZEt#|5`tz%6fPYB<)ld1@+ee?{seT z#=`nnpcYs!94LC;osBDeXET$}zi+-;L&qRyhU}WI=^%Ze@S|d4cBlU}VpNh@90+LF`M z8nrzhk)!0LiGXuU6v!Zdis1o60S+o`VSt>SO%j*jnD=H7XT=cREglKP1bw<#k>`mC z*SDlGKR>N2<$rHJWM$WcW6ej55U*m_ykeLtEN2t>+8I}0q5nxdg5mw(A>dZs7wAv8 zNpySCEZ3I3JbQ20nfp-ZjUqxaIS#$M-TaGVN4;cb`B* za>MmjGH9u3nf+r1D~o_WM#`$Xs9T|1-u|SIyC|?ReS!| zFmbW-xh9UU{Gk1p=_bvMJmHbaCJlcsOgzqWLW@cL;9t}r0$5F+ z6MA%t9%?ZmbD|9HieaD-_6y`nXTOcfT|tV;$p@e?yk9oOKK?TS2-dLMzjg(QELDcB&J-+<$W$4+PIh8~>pDAL)7v6jY81zOhWsi<2Fgbyj)| zxd9lSB_~!PdwAVEtEJCu-e`}>%>I{ohxuv9-+P&#=eBFsC-oDZ%eearU27T}fwyoE zzT(ppH)Wq*bMykXcLeu%o>Y9~{F>>~Hk6~=Fgm(qKjQkps0n+)4`AJ!RxSV4aLUVA zNm>o&A|&eAKWC54gT{EW$G1CM=M~Jc8Rdmg&oZN{LqEDmi|!ZOy_Re4iN+ZmKnd<+t-1>1Hj(c@BT-vn(G6bz!z9n>nrH_D)2AKkbYX@ zn{OLM^}e4+5^fo+pAD7m74z1_k{8civkcH&Hp$dDOL=p@tZSpY8!y+1Cx^k(h5i)2ICl zf-L2C9K1wtH9unuT%}8!Xp?$UFoe^+^T~G;ZJ?Z}nRutTy*>sDo_;A&Fv9;cTt2Az z4@YqIso3LIiTQ>#LhZoG_XZJ6fNgM-z6IsQy#aiXdQYB^`U5M~Rljbk==+FBzq(t} zoJ-6Wpe-BFu{}Hs0@h{CNZQC#i|3PY!|5d4Q*LgKl&;92|2X+e8SZ4o$Et&O;a<`{C*>_Mb`gCG^=eU+5@NVYS21w~V;uXaje~doXUGcTG z$%gOnebhKtz)!W_Mv|~{^0^E!EWNa{cGnhNRAHUQW3vaflDY&IR4E+9d&&MMI%F!f zUn*08uA)$R*%l>{S^nmXx69?iV`W%RHjIhc?#$|Lq}O}USlOF96RGRo9uI_2ceWa- z$g}Bh{l8GpUU_kR`vznIP$m-vh-J*lS?~M!AN2I0NgsnIU_X9Y9{|}6Y0G>q{TICw z6(BQro_@5Zh5F}9JIfm}=c=w%sw*shi+j(!7++sLdq0xEqu`x)=Rrn39IRvW-` z@}H1NYJ)%tZ%z0EokyOtkFK*EiRn!aCRq>$Yd*fTOl^||1JH!Yq>`>~9jR?|H&;^L zCc;EO0m{*_^r}|kuVM?rwx0->uoB`6KJHHSJjq>p($?j-UUqeCzwl->PBU-R@If!} zoFXWK-`tl~Xd0g+@keC+M-RZ;JU3{*L=ZLl6*LmjIa~ObX<3BI_riD+*zp#@=?^DB zsrh2QA6E1ZleAXFrVi-?F5+U|{7DCfc0KstAYe5kuAibb>wauYNm;s zZ{-xlXx^1zrr1-{S5A=jB@gXbJ_7QrZ`#~d#vE%PD`98N>qVwe^{+#sU5j)g*zeZb z%lX#0`QaMSdiU~gfnkeEc^N1Qy4XNhb z75~(@P;XGXT1x8{|6&WvI@ltLtF0s=Y{o;X`is14Q;teJXL{lLQ>Wj-Ah_J6SUW$u zR0XHSy2P8R`B~{dz4K%x)T0O$0!VqJE30jzkU!-X$WGDmzedqCeAr2WM9;aSxZFBTX@_a8x%*&_9h;;c+G{0GlapsR zS09+%I@G8AC_&F(4+-~UJ%2%iopy-Top@_2gyWy(bThGsH2{DgP%<%z*2Y{O8{^fE zs;vPBez(|4w$6L|?yS9v6}ig3y-&0b?#VT2u|WEn#a=-C`h23-LhNC~3BWc7%|9?) zY(KT?KL;g!HzoA|K+G!{D~OXp)B*CSJtHUPw&8dmhJP&*Y2YNkHvO!EEOpGp?(M5s z=`)USMrrhl)2j9lhlRRcIy!?9eZQ|4Y(Rm<(DacGN z3zX((s_oKzX@9E~b~gFkGTY2mutx2UWut=@>=4k#u~QuchC%?Q6=zTfsA<{{T@*Mg zKm5-V@lhtT_p_ScS9iZIxq~85g(e)3ltUGUh2@)&6HHlw0$|Tnu*zoYlp(^{-eKzt zyJ%_F@d*r;XeBdJH!BvFYLQ-IUB^f6#_Dok zmg?OT;-p38b#J}`YAGyDV$0Rv7CC=-sn}Rl)#Vgd`zS#TA*(hrTyT_isfHtKiqqTc zMf>52AqeSOA3jnG=OSa>v{GLBh53wZceEtf-atL)9-XbAWd-z0Xq4&0`Q9FKL3LDB zpq;7Vd`ipxZ|}=Uk9=hqBYpCeE*;ER?M&o9O<>adT2%DrK5u0^)e9>%HC3a+92Z)t zoYoZulaeQ}z826N3!6`rPZNNR_6?bv+yDv>$gn72OfRxD)%ODx=s6D76`vLjY--#% zTh-*hIXP^Vd^6*VRNQb-z%Sx)6YTVA1l4@cwD1vG>my?oAu(_WQ21U=I#!7DY>a58 z!8fgIinyGHOt%OO7cO7gKdA8zm?$?~im|~e2WYhzQhVBO&>O#krj6BZn$b|X!LD$# zInwN@Ozu0lmJLc1uH=tN{Xor$Xx&3AEfPd$y0yKzO$96hq-mCl$`IkVn#R&}ba&2Z zfDQm9s$6>d!LkzmFNfxxD=*gZqX&t9$)Be9T5{l58}T1v(ROm4Ssa>#OzF~B{H+pA z_Zl4TRb7Z08Pg87*dGSsPpofP<=>uPco?>upJ3Ew_q)n3lU+;3WH0*jRcuJpD~uMp znSqn|R8~{Ls>f9O_j8ggaAuCn%TVb*e^|RgG+Aw@P=^x|?7@Km5urbS%xx@1AjGix z+5rDnJ09c0Q2&1#i`MgVQv)I*&_VCdNTE6tOh^Kr1skaN0?t$Xf8E9=6a{NzlPQ{5 zs4R-1ngqkj#xpKzvLol4?E?NHt*n!C&W z$DhsdSfDn(EHJ;6?w3_K2A}qB7LA{b�@58759voNt4wrE50wib`-*-Z2hzSDGjY z)QP*-%xaN#Q9$+kg4-X%I~Ex?b9^IUV(Tn#i=^`(7~o)Un|v zLvF@m_WEky`yEg+V2S{MmY8adkUxB+K6CgSfOp7W>yD7#zEd>^2brK-;Hd7x9Q0Ci zcMHK;Ra3rfia&ZBl z4w0d_uUAWJm}#d1`i9YASTY3VBLcC~y;4Ca`>{#D>@y){0Us#JsnQdOh>AL#?I?k6 zG|Hr;B=hMK3edU##UsfP%(4_O&@F=zw1hcMF!}O@l%sEF^VNtsC|(eOt_b3ZF-%cS zb)Vg|xpa5Z5E|UN%|OlvvXJr=hR08@K;IJnc?gE3S|!q`jOA*6TOASKx~{9hL!^9A zbszx{Q+6MB2%>&7l0b=|9{cG8|J8=_9e24=ErKFoV<9Q=By=SYL;&y^bUuVCXGt=w zucxTT=u9|2g7kom5$l+Q@2a-7Gtwd~D13arAq&dx%#4ZO{}l?+tn@_k?EqyA)Tc3~ z@EJ>&jmp`$j#nqo&2asejoUhbhFiY5S<*8!{S3%Xz+u(4SOGFn_t4Dzp|bRA&183` zg_0Akw)L;KzioQoCoa!v^Wyq^k6EoYApZezwT3+H>qXP!y)Q7KuOK)J)5Yr>^D*6% zmK%Gbhg7$CDIo4WZdp`{q+Id8826-QOLhfgieNZ};qn~J0l}t~2uOvsh>G74hZR17 zp_0|Wj3`&tm>+A_g)RHSk>&cg1aB}gyF;r|%h*e`pDx$durEjs!OD+F?O&Yq>Ifni zyfamIql>Zq-}^vJ3)17$eT?KwYZ+Nl^_L zmgoWbZkrYVBvK4{G5pDVrn#Cq^%3m;mAkP_5kDnRud3=!ypA{lm?u!ZLU7i*n7f&I z4*D;KI&*;Lvc};J7G-=@7$hyv&~+j~VDK&f(8$mbjI-X-ZF2x_N^;XA`Y(iYnyE~O z>dWz3MA}zznB)b*UCG$L%=?SdlG=-~gd>iz-WvD&>9x7CPQQKRFbunOrK2&aOR}l1 zry+I=t+3imS1|KI((IqH{yrOiH!^5sW)j&6nX`DJ9FvmyefXFNmW%Ck`Q?e??!9$= zBD^`{e?Q_zDmttQojc*S`KO8bxLI+MS$2If}S7;lw6JR0)&uy>|&L#g5N95vWV zuj}I3_vS#mrV8i!@Ckz^P6LY8*pjH?+Kq=hW*Du&~tKiV7J(@LltEn2FMKa zoziQ51ZOtRgT^19Ycg?{!1{n^KKMNp-P05h5krwX$q2Zp5i)_rB44BWlI-$J$R?N2 zf#}$gyKUIr`I~PradSQ}2G;Qi`UX?1%%zIg=wc4;LF!DkZWL2Y;*eu=trf zK|(#{#0#&?wjO^2gnzd0P?g`dvwQ0oJk>PvMES{y>`N*Dk=$$DXn=-hDCEQiIs%HY z8!u5>zAV5uR6WN)B87uBGsx!N%-#nSlm_L(3QZXV{*-AHEn0rsElq_|H9yjWD{Bv8 z-dKr?aYVt5NXm;XPBK{vg0HX1-`n2d2BadD;RnOpjhR6-irDX|5yuaskv%?ELg(TS zYT^#iJ5UcdaIgTp<%V>iZ*Q>!=^kE3DUaY}c6k+BFukYpGX}o7v(H|`LE+Sa&O23k zMK*O%_wH&wMl@(;)_JD-@rOb88KnkK6F)6puixO(iyLT*(0t@D_P(d*?dQ@gf+o`W z5?x=O=j$Z1N6kDCSL)aHxJok!GUC0q|H_@|82~qesytB(b1HMB#f~oQWbdjHube;F z05$xKl3{RbDl-ISJAPKVfwfk%geZ<#y-AP)C+k4_QL#PGb zZ0upf9}XKw1k28jEt^@ZKqqYnWRCb@I_3R0UhGJ1>oR+Hrw>HiF;1XN5|$bNdWt;4 zW2I@^E_>DUTgksGAkbP?Y)L)mx;v%R8Egsx?>H-@@ow6_5xpD+Wsc!N)%el&PH*yJ z=0AEyGp{HGO#5YX>YHC6td!;;+kt!o_w1}@` z!BILi{sz^6VeEUv!E@o$wG~0R9gXZtxBbjD+?IK!4jP`UgW3&fMRN4lu#L}wrME!G zw{dD`Ykj@^+SR^)n#&MquY#58##!>Q7upkrIe|+pae8{(JdVGnNxIP&z z^Ww(TFf%+_k{0ywcFci{G`K={Wvb0LMfr4+W>TI3)}#`2nIhoB3+W%slutHV7aLkV zhY8PWp7z2zQ*-lJfY{&=CI;&%bgfpV`zzm?SHQ!nInar0_YXa(3}Z-}wV+aIXm{T{ zQVDb&0-6N2iPtyfuSU{sXYS^+y|0XSvzk4a3D#b5((=B=qi9#<<`1pg^|!6PIS;Z@ zVjL0{2Epo-cE)>#I59D*d=R5nRguW86fK?)RAe{xZutp7s$fc(lq+8g0p>+k3JV<* zOAm@Ym{urQ!7phzImo2ZYo*jgcUP>U04Wt=U?T9QVouXFk=uXj4`lFl_X!>H$eOIQ zFLl4xV;+ld>$k4u#p^HHzxRiW!&y~u6QqQLdcXDC4fia+Np+Uz)R{NAb8yU{rImOy zZ=AHAUQP!w7UX}52v=RvOkN_t6or-#mzcgEowTPPZJZ^JrAtW-L17m0PXGhgw%&V~ zc57`$1+@KEGrtfcE75Lcxx&P?akw23N1!HWC1$*PVFgvEOv?%J=LLD?+k*+RwJzaj zDkh)+k-A@yjJE}VG!CNhNXZ9HaiO2yE+}a6k!wX!_?AQ$1(7 zRiJ01rGKQz*G;22A%Jk^uid?Cnc#t*RJQ-E<_?nHQ-NDgNC;zl4-0h$JamurUvE;Blfj! zlL1&wc$eUq|1}#CFecGIYC+y@l)^Be|~I`Hb^> zNLkL8Lu>Bk%(%g3kj#<6c!u{udAI#W4=!xlG!PlHjm)m$6KL)?1QV?82j#zC4rJeC z6-V)dr7ul%GKZ;ym}~6CgpY6OK*RGCG>j$xA_rJfV#$--iA%4e&_`Nf2u!RXLU3M2wSqWE zF~KBM5YVdNMmSJPwQI*Ta$mw`F=$x+xAx9FoXU0YWs_WEVm#LW8-C zOOhgy5;A94sZd*rc4?vv70t-3q7oHSJC?Ol87f1DB~#~n>pf?m_gwG$&v~zN{(AR6 zdtdvq*7H2~bKk%D`&o`ki_oPI;~0I;3>u0a znTQDK5UDi4h9n2~lkXei!@T)OPxG_1s|rN*VOr5;AweJ&D8w$ou=kO7_x-pjsQHg7 zm?lY%W1Jt$JQMc-@sg3h|8f8l_Ktkn3j78a^{TOP0LX#qp@0092~BopNx(<*Fi>wm z@M-kxdwpFRLN=c|3-WMQ67#jFcn0G#rWUg9<=LucqE|-r0@ELz7KuXip?r6;_Jl$| zhqDUf{zNfyga~IgWgKg94Hd$_V~ynv!@_iljCSko9c;{XYySNYR}0mltV}Q)_x;?q zdwG#7fya`jeCSvNl z*Wa(B98NWRYXLAJ$5&fh8wKXWlvW}w=G>YfsDvI#LS{f@H=5?uo!hqw;02G?@i@_< zRQ-fmf8{J$$&R0kvw_AR1vxOjg&-OTYX*IlNgv!75$rJ-3=MUne=~00ev*0v+dvsW zN?TG|x-eDhuFpbpoAXatb#ehOGn2xqC}?ZX1rUih|GsxKY{>L3P{r}LT)(~&I>G`d zvNhdWcCP$WMD)(vt1c}X42!e6A)?Ts6Q&k{%s_w(9>H^>m%xLlYI+N?2!#q5mrE%9 z95*ND!=yZ7@`9}@p+pJF=)U>$dO~!2`%@8RYr${G%*>=H$9uaIZhJLI{lktRun5q= zs0(DM1=xl??PZBX;@H;K_UARl`ayk(kB#M_DoR2ImxIbeFahMH@$+l^ZEFzOPIAu& zzz~Q92X2V<;loh2x`*cfEUQa&<_=y9feX~>y;iP=$gWY%`GX4_m2?Sa5DtEG=}&=` z&0TI5niZ;d&Kt|;^iFTsT0ZEWgcs=0j|EHvk+uyo`UN+}E;{FADN6 z$yIw6oHSnyf>VFh>}7H*Rt!eh4E452izYl|X$1B(NvUe!K2CJkZg8PI$RCS}ii$`{ z9RZ`m^2|zpn=6);AVSFow_;j=NDLdL+p0BvS7de6Bv;qhZ>)vx_wHtR@S{mQHdGlg?1Bw5>6q; z7phuX=7CL9=+B(6ng4fk0KPLK%SaGFRRCFdFlO7K2EsdS8Pc zBSSCr5}+bi!q(tUjFX+u2}eckS?PyQk*6ka4a$+4p!V>qk);2Z)$u zW1PNZuvy+Gu3}aIgOpG{HTKNbFPhxjV>2E@5lffD#pc)T*JW8R)YJRLJPUHHg|Gwy ztj-|49Ik0q;gSDE@b@3ntN#CmuzUagn96kMy4Q|%DeV9HhXl||fIsBD(10EnxC90` z7YG~X07D|ZYLD(8hlmwyo-r&>ed_G=Xv($;Wv_Hh@fRzBt zWOMOzPO~={cbQkOuFJ8tzduTjBlqZcmrdT3n%e5sQV9tOm|1w`XOm;w)mpUTrxyOd z>E3B4xt42apkdL|<6Y1O$jJ}Kt^XiwU;8S6+?<}kU2Up9eZ?%%gb&fl@S)8+(?8Xp zJ4!%o3hL@NX!(fgjkgO1*vz}2>sKyNQqYFfV$ZEv=E z?p+{3=15B)EhtzHNR83umvVq%z_irX)iw1s-q~fd`|Yin6hg)29*+gXM%j!v_k5+H zhCfW&Gcc!;`eB6$%$ek>&$I7pMWqfv+w1ZCjMi8ur1mq3f|dfah?j!BRnXIODQ^Hx zgUIAnY_7;HT`ENE3D9!5qSa+j67A;h8upf{IP*9pmKbz|q%A4aprQYyZ2kXY20$O! ze3~CTK)?_b)xqqUV`n?id0?QkP*Q`kUq_?yQWc;VK3q(U-_xfE^~|$012rs-U(wHCk-?ai zX}xzO-b0A4WtL?P;8c3Cq#{5+CWDMi_gH$XgqT5%tnmDhZ4WxPUH`78SpSAdwHIw8 z5Hw?BdEnhrFKt#{?#I*x7Qtqo$;v;kBGXr-vsZ)<&vBx*;3p90@BFoY!m)83?+3_= z4xAR5Iz|x)fw#rieZxI=BqIiq0KlcLH#Zf4^&8Ib{PgL4s)K9v<;x1l9jA$2Dk?d= z?Ivx51>+g%=?QRLmCv5dMhJppA^<*>=LU5mN*PB#?AM_#82_9~Cc$v9g40x}qnwnWevkG)XWk_(l z+70=&pC9oUR)7ZZY+}vBP}fL=UtmeSC=T=qn;dTOER&f(KLPvnGVV$zxL;1)xiE^u z3>8MAJr?d7IT<(sbjK*{*IsC-2`~xhRjuKL60U*=E`C2{{#wS3mY1TlI*-(3Xmq+Gqi{ZeKMe{-WZvdI915`NWbbr&O;vIBk0#Cfj4hLL|^a-QbYHXOVO67A`tvnqWd zdP*Xxl);-@o<}S10R=T1c^qI}2r&4;w5-Cn-e^C7TjYxJpBNo5wQD+2(1CwmX$bZo&{v5 z!)?C{NyR_PPJaXvR*Vo$5jPr&1h?nqm4rt0w*Fe#*l1&BW~MwGbeK~T;UOfacN{%@ zJSrhiA$O_9t3;%vy;D&KpfLdf0m#WS+h4;lK}*6K9q3S04xD^}o+5#rA;O85^~a#0wDs6_l*fNUH5lxHU&<+a#f+Y${b zARTcZ(ym7YndjgdG86WkSIgE`E5GEM0BA9>$m-LIl`nlO7{6hkN6r>-UfTft({d_2 zn0qa>%=ex4m-cd5w7OQfKdC*rh1*ORqzfL%rGPz)`3f)4m^|aazJ2Skdx4h~99eH} zu6lcGw2Zov(k#F7N$peWE=Lxwi@$)FGfmr9iu8^bTb!a`s**_DIzIB1yi6?F&^xt& zO>F=>Ckm)X)Q?ZmKelnU&7VJCaygxXu_Uy+wDk0DH>}GUtP5T}N=E#61+^ao!fnP$ zJc`N*H%l+SPm=16#zq8Xug1D@mUDT;FJ)zAR1_vf2pN^Xfuv8_%}?^#0a1*?*f*AAhj+us({&JX;72wv>M+U=Tb zjQo%7vpl!ju76-)&PZSTva|Z(j)aKy0ttmpY1V4CJEs)TJtKTU911>sR#sL7lQt9i z3Hx`yvX|#$IHduu2fG&=g26RQSVkOa-%v6D$APH7$j0=jZ3Ig7KUQ z2;21MUS%ebL6O;x*X^fmpvvb6ZV~%@*X!+9{uk)GcB$z6`YS)etN4gw zQPrc6ii>zpql;0XD^r;PieBAxUVTs(K)^V7T|ivahFp(Ih>O!+F?>_jK)O0buH7WI=tJ#$}@#B&=4Eb@1D=yS``lcC|fN1(d_nu%!S&fe2D% zv8>dVJ-B$$B1v5^Y%ty_s{8#ziiAGc%a01&s|#Qd$bnk8a3RSEuWUT$=-rM|kS?cn zUl(eHIW5>I3=}ylanc?f_*#Vm4S7@5OlDbAnbW=9mEe4`*la5{$MFlc^doS+Nx8te zC}1X`9Uh*e;Eye4em;+>Ic&Yi*jOSi;M9H92vEs4nORtf;oBWLJe^7p-bEED4rLxx z1{}K5a0j@fi*<_&%}}=P8Ln9Tj>nKQc*Qy=cmEX9c>eIQp`4KrB5FXyk=HarTqEXF zZjgZJBI-%J`K6dxGJ+GAJ=p7Xe-A(AlB$4&;Bj+vbH|D0&98a(3PyXd9K;7L*93E+yuIj7<2kK4(%M2oxvnb4QWM8 z@d7+p6#NC$)zt~2vFyiGXiPX9!sBGwst-9zo34g0a|>>}ChIM>rO- zR+niPk;xIc6bauzR#ZUz5OqV?2IS}$_k5jTfu(T3X-M5NaCppJI78iyX=p>vU9u$# zF)U7}v|i{)n7H4Go&u1mB(=4*$7H4V|+0ePb+$j$A|^-GBx*?ylhxjHj=4P zuvOvg5)fw2pnxiSob=0448>De9(7JIeh&eiCpO5{G`JlN&!^&+8M^b4HS>_EYF@Xn zfw;0wzFWca1yqRd4G6A%$uTk9goOzQN)eJKUQQGYQ58HFiCa3lWypUqXrCEX09r%1`m6TV9ETL7KdWM3)~WTyUmP&@7?*XCM`z!KR|OD1z6m zh(C%Mq(l&{g2xXwzZ~(Cm_1CXoK%S*eTK7Zl$1;h13#ZacOVWbm)T&fNt8GZyS)v> zP{^G$ z4M7sD@Cr&s%~7CLJbjwG+Ke> z1Dl+0LBRD8uLwg)O6%Zj6SOpn@Xm1!_&tEQ$f@tM{7Q%ClGNkaF+l(aFM;?nCRN$m z>RdA3`{3}ABZsh^-bC-`G<{=7}SUYR3bV64Vv>jBdvn%ZyHg`2%fP?cfdHVK}<}{#`|~tV@NM`!!)lyh}{Bi z>yGIxh(Fw=kD!~NqhP^^{UjrF#HXM%*raTPK%QuW;HM35?|4o!nF*|yXT2}Y*fwR6 z(N;GJ6tk>hqDhqsN7!y`3v?w*o$jS==U*c)s`MJol=U2>~{WmU&I94 zPKpquj}dJB`t|Fn{Ts@`jTF{X1ScE0Vbq@eH}BpZR#>Vq$4cXGH6gL()1{Dqg~nR< bgUe3)<|=1}>UsE)B5J+KM&lbs^h19IkUBzQ literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/images/proxima_logo.png b/control/smart_mpc_trajectory_follower/images/proxima_logo.png new file mode 100644 index 0000000000000000000000000000000000000000..039d35ae44f8ec36954bc5c7b6c09afc2f6df936 GIT binary patch literal 20962 zcmdSA^+QzK_dg6cbPIxXsD#puw1|R$fQWQA0}S2WjfgaYUICTvZX|RDMnQ(|mS%vV zhWQ@E`@Wy&Pk81hnAvBqwO78@+Uvw>K7UF|L{Ef;g+;2O{P+bH76=Cm3!9Sw5BNsd zcOe4{OY4iuV}+MKCfjZJjXXN$TFAdl5PoO@x^=?>3nrQH@Hf}*&+Dd- z1*M)aKJC|nNiKd~Pq4tL$-MLV#uIA%gqWM4Nl4rDPI8a=od3DUSb2G|$)+ztTelUJ zTl~BDH`*T@eT(w{Umv=M!G`)x%8X^Dj>#GNycl$`qjz_SQ=dD!MdGxnvG+tbHs;Sq znIVA~UDmI3mgdTNIdwEKi^C#wd~{MT8pM)3k|*VFAHvp_fY1QJBjHu@!IT=($esd166@F7^Fg zfi|M@5W{40#lH_f)3jQ13Z6aul-W)wi#-=#MtffKy}d}c>w^#0ERlELgFTF~V?ZYR z^#@9bd+@4JM(IFD5OR*Rk%64~Yo9=#C#^ib5Rj!D0kifH@%3ZYTyU;cMJG$$#eM1B z>G3i6wv99fHAeG8G0jpYY5RO!77x;yUlDOkL-A*6%7Xld7F;EW%|QoE(FsN`&O&Ai z?jn2KvuWW+wQ>y#1;f42QtCUHk97I^Q?eCs5Ar?pfWHw;*XLn;p zBg=;P)((^d=uP4=Z8Ikx@z*-y!6W+R#HCsBO{`||{J7&y?$qH;A3+mxenDCE-)*+# z1s@V(RhwMKf{As@?yQ|vNDzW@pUPkJ^ZU`hFJY?~JrPph_qbf((^`^y!!gaUzgw3PHwi+1h>zhSkhc;QnH1%)7nMjVs+Bu#W`=j zeH8IDZH2&Pqtc%PSm}SzY{kM|96IT%!!00Fm0iMg8=us)-MBtpI%Qlp4A;e9+S%#n z=bpFlGkE4KHlHZhAHh|tX%d()qaNIfe;9DOWg08BZ>#&)DCmT!gAC`7_5-;IJbjtU zN(0iioqbaFSJm6L<(bEe2DC}dE~7y1199j4)F=~k8- z>fKe=myvS4?;&w&1MW<039-y5cOb#o5Ml|ca(&Kb5~b-#?#1Ko5d^h&u{QJw z=~F+I$p7Ga>kW2l2yHL^qCS{dYV_#4=b>7C2ED1t^;w4RagEm(y7+JXe)Qbaq^XFk z8=A~7{P#f|YKM%+8Th~MyE(NbZtL`ARZq)=_ zKZF=NDdY`Pz}qg<<^iYIp+-4J^R-hr8UBw~E7|`1&T{P}*ZM0U)3}%B!J|z=m<97!$*QFJ3C;KX(^b z`ZLO|B?802ef5gK=WOyH)w+1MvUcVMX4Ce+GBM#QKIXY)RBW6EKBjc!7if?8YrF=H@70r zY+HTii|rbt5mPJw{e5e`YXVeUna(ZsF)x_HjHb@3WiTf%Xs<0Hu3(!hy}hp4=LJ)o z(G=(6XkSLl^>&(fWy)U4e<4#U-*2dCn?HGT{e->=*X!~m+fv@#m-y>DOHh+Pj9E$2 zm6aM1$Z2wAzQpGoJ45ZgS%R8g|8)AEYqI2}z!x%|^3xj=4_)8?*`J4nS}}`tZ+%qh z&F>#8*>Y*yqWuk_z)!V3k$crXPOW^i0bA;Oem@g>@RK*eL!ka$OL+Z7Bus? zZ3oAcQQ-rc{k7KZ!`mvyoFLbk&t}?->F8fbIeFHKzmq^n_V{suiqE1+q{X^geeWX` z&viHSoMV6#Kt!3TJb}E=@^!`B7c{*rmbW}5r9DyHd)@uFyfn(iP*zmu(}~FkK%gz~ z9d5&%od_;(dfCjy21gHV-(eTxr_r)mC0>#L>lZP+j2yr{2Tj@!yhBe8^mqA`+%L!t@xLMMWEtj>LFge2E!wEck?=)AKtP z+fe+u>qwbm|9%Aw!5U2*XiG7{<_2ZFvnIfKmKTxVr91Dm|GV*4T+F~BW2mk9hU8Si zZV&N?m>5SggX842Z~8o8FORka=5-u1&`x{Rc-UYxqb!N=T<0+m?sL|td1SP6j>YZt z9LVfYk@kqm_Od-9XQ-wo|(4r5YhFmeC6l|E6+4~Q`$O9Ct-7%xC zQJ6q4pQYDuL5z#NdW$i>(AIjy=Fu4OM?gFz28X+=vHCndFOOQ?-~n0N)k)am1bQ8x zmZ${VZlwF_#l|Re=*m#3!oPC_;{0)xt1MrsYV_7W|L$9v^_88ncC@+;f~|dP#HYuL8K`!X zKwL2UlAa~p0@g}%!~3;Q2mnuesw2*a8WL({Num8e&GB znbv8=e6tqEnob6g$fm|#HXz9aY5b9Q!HC_onmw)nEWid<=fC-4=QZ|M^U_HC;pKU+ zwIRza>w90h#0(|M6zk=k6MbpsPw1d;HzNpN$R$Vt2C8;LV}i*yjwYT#=bgz;q09uI z_SjCgLZ^ME;K!OXeCZpiaxI(f)D4e;=U4It9}oo)2glKgRi4r1zn|B;co;;mo50Rq z&1~l>dow;VvG_Uvt^N23dXUHx?SAjcKa$d*WW5#Jy&TJqc;E21ove`5XXlm55Fm|0 zpWC229x#Wb+WNOM2;p}!xkyn{rs%)Fg?Vo9uDAP%&Zi9jjR%ey_IV)yKO>cRy0`s# zTN&CZ$a_KLg!n;;bhZYQpTyAjO>X{4S=o^Yn^pW1$ter-kHsUcV%q3{f zX;FHuK}E+?PBLmB&!pIVDBQTfDkgoVlk1CF62`8r#!uy!Qtp!0^jZB|p1)XoQL%woDs(TeXltTrxxn2sY^Up7Lz_lUBt1 z$)-q!%|I4|jNV62bZj&HH)9=1aaL`ipZ)k1I?KoVC_?2H zdI58O{MgFNt}QqlVO{lFYjk2|_KeOjJmhpsm4ae6v~H-!0TNZt{0BGGD3%=g7^Gh@ zx0ZUo`OlJ})4*+z&i zpM4z@+=^y8@9u5EU^zwg*1X47kMi)d;%y9J!ixuu$EQ_yoTE=MHKp5{d2EK}N!H0>hZ8^ zrutdu>oa%G3zzJ_M=$)SC{a(r`)w^i8fx4(OYOc>)4I6aVNA@4yGucjYyW<=u_Cl2 z`Bd!WrLf^1_Gyl6WW7H^_(-d9mJ8P*149pXj@)o^+n?;x@h8J=&kUW|K~2;y>+6 zwi|Ui^o>FxKWC&$)C8Mz%(xxu#)qu742DVO1yrP!cYRw+8GU*N)d{lv(us>zOD1lbf-!Yh(3P=y=k`1I$t$@==%+xbN9D;4vv?}u$k&Y zKL4?ZCV4le+jOyFPb1SExwemyW$p;E=W4w@(%8sXl!Bmjn?0zv9F`B1SZ$PxmE8Fz zC~iG8Q?cK3BHb!Cd$ZeB*Yu(Avc#33B7$%hC*4MtH#q zMrxV?!z35l(K(DXr`PCAHfwJ|bqBE6JkQ~~WtO^h>EFuP4no3m)*3B2h%OmrskCEO z*H8;h6Ewah!Ah_fP{IV~#N__){iV#<*Q#rt%ryl_+x@gmTCUS~r$)oza`2e-IiThT zwqO1lcVMW~9MQy)1%-?A0Y`xs#U7*MS?k>_jo*2X+fHUs_WhlBxEOq+{ZJ8IV}5f*iR6Q)%TXedyFm4<@k< zVF5_y*`u9~Z&TGpgXnkp@4yy$Pdw>YG`fa&Gy7Y)VTOJ69Z#DBq`B3Q=^`c5fE<|9 zcg{I3h-C4!Pk5VcUo|IiW-71myIoMGA2)F)_l+%t3$Puwn(MQu_;a=0b&hOenN2Y5 z!}JVGf_pyh&17y0&Dlby!o$z>Mg4Vv}h7QpRWOq_at#@(aBxzPxF$DtPi zpIU5iLRxvb(9`-C#9rH^>O<;8Up#mNaaMi6Gup^(JfrT|R^wBA*wlQv$Uj0Rs7<}e z-6HkmSXrK>EVD1ik}3+K5P>)Q9fkQb5f$C_yQh52@Vi*b8u@U`4cjpx^Ht(~j&U!A z+@_(vGYQ_#?xm)YG6?G64mvZwCj4{H-DfZHtX4em)Mwg0s| z^qVq;&aGonf)i|nV*t4%fpR!IX@fzp5p7tAM+v-f+5-)DOD#lirE>cW;~vwDM>?nb zI{(^9qcRP3>aaH<-$*xf*Hg)Jr6ZpK;bD)oj-g#_ZQ&)RGlJ#rZYeXQroTVPhB9)GOOKCQOY^+fL&VSeC24mX>;Mt zfWk=UC3yG9Mq#I7&0CK@S)Z)Wk`SL8ksK?Gqu$oN33yuH*DB zaW$b~0u|(VrhmMTKIbrgN%4BA1wRN+^<4CBa<9nVNUxh#;%6SFH0RAiG;_XaVRR#6)-Squ*8_wCUiiJzh4ejWzEHBNVEe#CH9@{=Rt@PRJ-nD_kJGoqS1x zzjiu#jX*UrzF6$jl`#nt4BXzBgyI)LCpE)DV1z$j5l~E#;JhFypzUPOcxF&*pShN( z`-;{sCm{v$QNV}X>kDPDHqW-LcF>I+6WL)_Ge2=JY3?ZD2f^uO56~^;IrDtDYkuEc zZPmQ<^K0xCWpKcQSpxjNrhA%{oLw7RTS_J(5lcD{T73pra@iM0k*CSd#+~qQz zS+mjKq_5eqeUX!gRrG-A^d)g(|KP7Ygq&IAQR(A(7(`Lvl#03Ic~lLa2=i?33Y|)+ zRm8N{sfd&DqAFah{*8DIe*j6cLZ?%e7ln(ZV>4TO3@a;iHSID;9gL6NWP&_p3@x1N zfE9&&du-yAO7|U1PN}@#mWNYBvl04Y)0a`$rXCOQEyIU-Jc{2-`w*|}f zYow7kdEzk9b$PvXcMOHs1qd={NBe6?kF7mJj(jAXi^sp8qHm^OZc|K?($d{8zbdt5 znOkTOr7W^P$J|B!)qu;NoYTO{3W*4gEVQ)$&Tkf^F;Ythnx;|>t{??MH(drA3)Vbd zIQL~u)V!02Dtu6pD0(t+LT$Mz#>8ynxlzqnPq3N#l@yNl@6O*xzhlds^(^$~rgFEj z=o;>zi`xjxi}h#;Q|R@}WcaOIx2pM6D?O0+9WolAZKQ*P7}GB=f52Q31ZdkXARBS$m7|SHiSyUvCExsuB7^=4V4hn~ zieP|eU35srP(dD{%7=be@A!~lz)Ghs9?EuZ=ja}|TKeK=-$9;ecXQ%C%10>u*xE$f zZk7=2tt|#fpVqv2&^GM*2U=S~V%=abLSz(UQ0ehqqp!~%+;hOgK5Y`*PL?zC)3KQt zvlKIb6+0l%3hS>O@Mj&f%!qO+B_Eouk%+tED)EHoDvrwHV$<;->zASnYwsZ5C$h4( zVYkP|Uo1Kc5sc#|_Yd#dkL1EZnu6}iRybvIiv@y5?rI;oi^jjtK|A!9*D5E)I47X6 z%en61AQ5Yh_*VA%-lvra+pINzhT9-Dh+m`(lPwy?i3;leDE**%*({IB_lBw8^S41y z3@@oUkGi+P8Xtl)m+aP zXm_HKJ5T)}>Pd2;-q8>z{KxTS$?x#{`e!XvIRrR-5fxp-@Cv8dMQfPX>_5wX0}%!_Nj31vrQ|Me%RVU^ z(oH3GpUiLTZY*`ZQdKsVf{;(uY8L8lOo-p+NLtu5ty5qy9q57j2lkophw#c_S<&qWmH7_{_F{K>DgSlp{uH3AWc_ z)N>kW>dHT5E6B_Cd!#-0?i|L*B{ua9zc-#q6DF;>GnU!SWn44TR&!X?63c2viDWFm z&RZHZZ1pIF_!$M-d~O$SCmm6092CD#h3c-)%aEL9w6&MZKETzh(e1oZg{ToPc~~2( zAkQ>{ya(w(&It1R`k$M_YU&W4xJk00r^(U@9HPWOd~nXw&C{|0$w?7u;gYvaQ~m)#Qvl!a)r*7DlY{} zWaKONs7c^l%>|r=`Gss5;0LC)bN!gUHFJ7T`*E9upyu^YKV|kG`q;uwx=?1#M62q< z%j3hhg7W^EH_&s>s;^r;K^9%MW$JKGvM#-li_Efpk7zR%f-p`QMPn%SkY!qaxJFc9 z7uQlzIi*MS(qofffzB5)_xsd$jt=qRJQdU_s63v4c+9f-pHD83GlL*@8$BJv{`|SL zCUu%`wF>fizH~MDguE5;@ixIQloqo!K5~!uWp+{FEwBjwY z!b4!w7Y0B}Wn@))Oqv$xGu=hb^&FXS63PkX2_#M!&hr$Q`AHPLejX~ULGc=iQQ+AI zla9PbOV83yagbi#5KR1`kCUq($Wt#V`KnoZ%<;!33KiPRB3}-~_%8KQ)9fT!B`Hp} z=m!Iw5rb*0H70SB5!kyof=hJ+`?kYB>yzZLQS7Goopx$2g*h0%x21b&WhleH1ng!U zw{VYG781Kl0{Lt7qh#0><2BGW&-+uC_aZiJ^#RtYa~g&U(aw|978@qIHEf!~1Op(2 zLQK1$dn+MXUYt6OmUnM}Iec>PAYE^Aj=t!88|wPgl3e)7@yIx0d|rfWibS*K&?GAU z?QtPDQYyREdxW&^)z1qrBLKY*X0iJq<~?M#Lg}JLUkOT=ZG3y%r0tNp8{X=~x2-s0 z;~cG2&nZp=x|;xF#H#3fS5;E*)M9Yfv}w)eU5Rbg-k0`_J6wNTSaW7mN6y>oSKY3- z5gu3V$u)W#_J+w{Bsd7m*)Wzk@jkwkT1?6KlaJyx%(fCrx&w7TZEpWSB%D(Th3XBe zbXN1c(hhx<7p;H#;Rz&!+LPOiHdH}gxQL*gyk03tcbnBorf6IWYl^*X@Sv4%TQzl+ zu6jVTks5Tj^m%gelo`u_P>HC2gZ1rkc7G=rp8qBLb$3l#klY+hA&_rOf+G~wRQ3(q zvc0id%;(}t#9*=!nN zWgI&T7rDdm{ITit_}e!Hx>(JEMshgXK2LI}rVR;GI%=;@yd5=~9QVO8bST1{(UcJe#kKi-LJUgE$urIJm2++-nz!vTQr2)GDISt)<-C!U(x5bo% ze14K99_Cx3vvk1{77z5oWP0-*(ws(kr*=E5dgOJT70*L0{Mby(o&75#Ce2mLYIuIK4JZ4zjtH@S9cL=49rs+4 zCg?_%={-gIXKUUj?nyLl%{^xyj)Ekm;{mf1E`FFZtt)PM#UD@}9!xmJXYugj8k9Zx zT?8}yTCWF`XUJ@o{pM%o9i@uKoAmjac&|*A6|$WN3YYALrz~>dKT2iZVf|CfuYTg2 zTlXQe&pWZ9Jd1&?$Al&kC~Q`<2M(;`$p(|ZPQt&vIenMht;CE;$}~3yio5Rteeu8j zF4+RUN68)M^;Eu^&sj-0$M^oRJAQ5<2)OaLz|pl|9x^1{1j;{Cb_TfPgg4#VPlObV z?B^WL{ae}UbqILx6Zkyv$_l^}ox9oJYThAo9Lw`juO;Jaf8{n#xz|7y`OtwHbaF*B zuO^=PkHvW*nRF~;zaP2L8htgwHtpeK4CXj2IW0V%mM7~Gt&0(FMKB&t1h`M0$V+p(ss zC>7+1=J`bC#d@VGZMt&Uuu_2)W*dC=CT6YH?7`uW+zStAOaZx-dN1b&gI%!ruY^gH7}0cS4-~NcBQX= zq2ibLHfTuN<|vfU9AFI-VQf&nr7*s_7h-6x8y51~`qDv$TsZ$}w|!Rr;aTziOx`^` z|E7rfdZW5emAo{f#m%x!`3LpB`k(1QJUR9R{0@X|K&=G}b}`=a(>sx8)nQ%tI%C+0I#23%kg)Ad;YOcG!x5#b88roO=Xa9hSFHr*DW|pRc(j* zdB=F&%A{M_=moQJdebL|)YDHlOWzLdOUn|{Rz<8_?5TU-eX7ah@Y2(-DI?uJD8!87 zM*?@zY(o4$gRJv~_7O(p=d{T!-R8?w?ZmgIX6rExNh1dlL=!A=}T5IGL#cTdKkvA*^0kqid9}ZJv>L(Y|QVA8vfk;5Y_w1kZILqixxF<2jGeX)}*SHnMO== zRcsNZ$bzgZda`?PZi>>p{F* zi>Oq91-18+qp?e5Unl48(bbRiidPt#4-(!uZ<01f4ZO$@-GSFepVNUVQP;Gejxo=@ zf&z!%D*ADOV}eJk4vm~HD#fvP?9+DF_ODvhz=h=1t!ICYaeZ{HLZ@TV=CZBeW|eoSSXfAEB{`I3 zMO}Na;URzL2N_PX-fS5z8X4|MhRP@2YcDE7K3R;we`#1|R7i%09G&Kmk5&x?CyOS_ z*jy%*o4}jK9At=5U6;HXV`Qloa%-HZ^LsA%u{&>FG84WAsB zpKCk{k7tLkgrbWgQWiLQz=LknA1uh=9%`O09A`BPv`KK+%`fDRsQyR6z9UB<)W~np zBP}ATE-!M!sS2jhxm*@Bq!3m)+IyKO(0ln#5PD+0*d7ktLKr)qH5pW+6gv4Bm8v?m zMhBrX9xV07&W@vc*FmA`p&|p7)!#L8b8W3W*mrPe;cpp}mNas=i?lL3md=S*%^$i>iDR zZSG^L;ZNeqQDB+d!YNw?;}|vsW4d4>nhZxGjQ8YNGSsPRKx;G++U8DV;u;{uO9eC= zvKns7b*`DwegRsXtQ%1J0pE|>CEzuF7faz@R2Ix#tL1?Q?T{gTu4s88?PB@(VZzc= zGu{3-6@5Sh&mC=j6Uv9g2XHo3J5fu3y6t6{fkLOHD}h31!FY0(5r6MxQl^C*Oe-*VNP?Dth$s^1tTeE!uVV_T7*F+5~L zhNi{D(TYX&d^TdEYIMbR{Z1vqDmIW5=M^oQFtNr@B@CW00YCkogZ8$FLwhXjx>a>> z<5PmR!fahcdM*A;E=<33Vxc!ux1^|aZ(R;W)s0qA<|7mM-qC zxJ%&Kb0L8CVe5t;c}?qn*{GDA_?8=mi?~q{D=R!}Yh={*#YHd$m^694I(&n&@=jhi z<*j&T9hu}7pqt^AZK)x?V7W(iqP%sdEZz ze{bzC@$}_=pO>C#(+{$GJ+k!sSXujX#NT%G@mRm5bJ7MKWdSuX$K?jJG9<7P;d>%O zCP~mpieQw=$Ft2K3h@X<%cdWDYS}2uvs4HIY7WHp+AiBOxMTq1V(W{yL#@JwKHy_- zq@*xo*`tB$qaD}IW{jlC1yJj)Hq;S!?kO8{GLBL!S#XO1H{bm@+J%RzjuOcQE zvnLpu8j|6LJ(mC~n=d(RL8|~jY!%&BrErley#)%OI(K8XVS{Xe@vsSJn)Q~8_H|3v z^^^H~+OIAT;wAEqUI-J6)3?Ah!$YL~g*|q7^(MucUQkfjQFbJLyiX%v><4(Qcn|dX zAgkGn*JA=oK^*6CSwF>~7uMfC!UitvrK$5nQC&G^V{?ySs)MYoY|l*7$zTUhfF^Nn zG#fs)K1=iJ?Vsi4jjx-C9m;cL6A2%jUnBsAWfC6ZEc}&~Rq@=bzZ6evl7D7?J}ks= z(VkJiir|H@SCbrbXMOUFKu!VB^Ip7A%%ro+5s?#Cx(u}xhHk&xr^&S7unf*f1SB1$ zbqEN=Gv)nf4@P8m`P)EA@*1E!K?ky8`dvOma|zcg+3%37c_u%XQ3&)f|4^=FW!?VZ zZ()-6_E-h(ss~t<=Waph)xcWNfY-oM;HN?xiaqMLUH~eyN(aVrIyHI>fS$@rz={a! z;+lN$w+?`etWq1ph6DN9ZV5;e4|~Q&`D%zkP;W9rHnZLyR(BgYlP76>GY?_cK*mon z|JiFzZQ_BvXW}$1MxtFk{T;x2de?8ao?vC5$aYISv>pWpaO77rZ@W>v#&Z~C#@?tJ zS!tMU@}jBAov*3d{Q#urLwb-$&Ib@Sx7~UV&ChmXG1g#62_qWKc?4iGCFZ&S z zUNqi;EjD`GPDu|c#Wy%bb=63Gcc(Qiju-0nB|0kG`|e}eDm;5DKN^$7())2gg8M>{ zISPNNV=>T`MNQttbDI7%@FVZ5Jjr%ms~dROJpgAnlKTvnT1OIH2NdImW!h{ge)O`V znls^bwH@&Skb^Uc$G{>#Qk-V>e87n9rEDQ66(pvG)!mUo?oLV zW=@E<~N^KWf1e`iKD$KtrJT$0dQ?lp&;L|0bHosKA9aF zbAaD7lc1SP^6pjw6h_RrfZO=69h%52Q?b^5E%w>M3%^ zk$t@7GG3D_u5jG9#?D2Z@XHzn>OQ}c|Iza zQ$o~Lf5bS?SS{9B$G=0KQwe;~;K1nVwB*ZBX?O2TY;{K9B2zq2pn;(iucAA`(D0 zn~4cDXFMnf`%BLuDHS%XYz+Ad@9wR7#YW2#W9&mS&79M&Q9b;K;|&iw80iPz>Jk3+ z*L;DAt%Rux!O~65E%q$xsy^FVMj$Ll9#VTO%D~5||dSa`=b3)LH zhw=a1gL^GV$yQ>ps0ET{(LzE*h@%a0L{*U(Pxg{Oc@A*k!6nsLEcI=V436_SWa}vzkH7v)S(i{F}7^R!RfdJPXkJx0WpMFduubg3u zZuH1h=oAnD#@}FgrtXA=JQ*UjCXY0_vY~u@&GG(uGjwYPlO4WlRkfTZpkV1si277C z8x8=^!4yB7&S*ee5u(Q^)~(;DOJPBos%Pgi$xtc~DCxwj_EN(}HSlBeb79)f*~SoS zEZPOT+JgrH6gE2{Y`3ugO7*xi8`6*;qS#UneolSDZRD}w?#;73)ykX%bbUF^%Qnk5 z|I;Eb!GQaxCtA}ho#(gomh@YU0D&H1Y?5-DpLjkKrZ&S5z{v}Z{Kt0y@C118yHlhl z5n$csW)v=D8GZD^L>d<6Z{^3BTDI%`}~#^5^ppY$dhd|?79ISU0?dzL@%b8^+XxN}7_x&Kg_ z+x0HOuV|L0YBR0C5K6l=26C3WW zt2ITQNlfb{zm_s9b3bF+TKq2t0Lb_&y+WsAWr+gHy|OQt!1YUb2y`ALLHtXkxCA(2 z8g{zXi_W7fns~c|`7M{d?Sj`X()8`5&j8$_F-?0O6e!08CL>nXJykN2;ue#QD-6sY ztC(MHUJoV!-+E!p$ZqyG*=Z0=fQ@sY3?R_`(5WTDTtWwWom>+9 z6ET`Nvzd7y>fE0Vl|xmPR9+vFpQXoO%uAZ6p}+l&3QkRVP?`H%X1Wd6N`kzYD|*x| z`e_#KNJS$Sjm}}XU3WPtB``4XSF~o3(yEFU3)(5?tdpZ;y~#BWqa9Y(AM`$W4^2ay z1*mQW(G&Mp6e*(&^3OH&i__3?AcK(hs*}s z%akZB=SkD3%9RkB#u(H6U$F-1S*E=?w-{?jf>C%ec-WzFW}Fvnwh?|$GKS+9z?GU? zzl)d>UnPCzt3b8V{BcXoRbIUk1*v_ckM9=oDbHNU)oerr32m>~H&+=3)$@^vtOAEN ztK)40C}CeY$^Q{2tIV*2S}uxzybfIJ1qrdE5C|=vXFf3;BC1Q|OIz!IYW`thbb~SR zl}WEyYTD6t6wu@_W&{t#$qBA~F4^R(xJRWh+Pucex0wCS5nV?gC)W*K@cR}gWZGk} zcHS}`IY03)5D5!0P_Rtz-yV)A$a25;;OOmfoeEH~_cS1g_dJG3L=*WETNc0Qak+T< z0kVy*-tJir{i8m!r2srIZTmj+_)+2GiiElD?6oES%()Scrpu1xLUh(xY4Pi-#u_qA zBQb*HBQSW|{L}eALk+L&3q%P|~vfL)n~9tR&hM$n>IMGU+RO)9gKW ziQOX%W$EZ^bxl`QqvaZ4OyC-Hg@s62lm)g)^7-xLfO0Fkhc8Eeu$u9{#5Y`s-X|HN zs7oY65YOjS8U6ZA0)(A>GvH0D?O#BHBHJc?kN zh;|?LU+85`eKBVAf*)DFELAXQ`z&e0eEgM5he3FVy29oL%U+AbqNCQ-x>W$w?0Ghc%`gtDkA%nd_%Tnufewf72c2${s=3J_{lD!&JY$4iV@-VDXu6}~y zy;s9epuyRn>hgIt;Ff8h(*MV!0vNz})6ol}RmUjZyt<4o={u_DKcfJ-hCgs3zo4{@ zZ+?Qmu(J100F;trSz45-xQcvnTAZ2xr=^Txbz7Y})p;$zIu-t_@{j zZ|ZRB?3lW_0I32lwtT1&TnN56`^JnQTWwi}Ddzu$5C~AiRUy1FU%k!44(Ur4ms$U*pV-vzIAtH3ZS;J)89bVe^KbH{Sh`vo2(d3csSv- z@2|&YR2OHwbqh!|K>jV_R6@e5JW8E1zrB-9(CAU?dy7_CNC}g*+!~RH<34bo<-|xq zeEAbk{pniTAJ{Z?w$-@RW(IjDDU!J<<`SbOGg8ugc$Uk>pKxPM!o3j$sf@^@dA7$Gj}JF=&! zH2KWT95W|Kvi^a#kL8NjXIJ2OarEA`v7PyfB6#lSRC-lOl-MVS<2YhnFe_!t^pUVJT9xwPj9*2&HI-B#j}=nmW(*E7~v^m;QMf@o<4izTEhs9 z+4Oe&sXXb*-6DDA4=%2b@rMO|%<0FUxRZNY2OZ)cm~XS)r(=I@tLXG!6+&RzY2egU zo@o-0RV$#l=n(J(c)g-K&HIKl4(5AS!O+hke}be+%~A)Mt0ZkUCHxRVbZy-XbgB7I zcIosUddW2Sz6xNT;^NayO`~w|4h$rzXBuXXsoR-~g?CK?r}>M`fw|@Cait?7JLsVV z0qSvhNV&r1{Pz<|>320MgCE}=z3>sDA<`+^wevV$HZun12Y^rld(Of4%v-T1L_Oz` zG$gYk-sz3X7YF_(6tB@^`J5+f-c_|4>RDmV-leBJKr8nTxEW(*4WI$ntzIH8=~it&3w8YCAgh+P7q=g(y?1={M#DVa&mon1 z4d2o}KU)Z;p6+4v>vb8Aj$X-Lrk?-*3`-UtyP<0ih@Pm4`~`K_g9I^xb)lEkh6|f} z;_C-t#)sg4$(UBQ?ExjJ$aM-15|X{>sC=a`qDzId+-gKOwJNJO`H2I~%9pKSS+=(K zHT%CT0CdCbN34}HhIe;AcJ!#pHqwWO$aacPj_lic-0b3O;sweJ9Gxk55eM|(WS_vF zyfgTkaBns$xO*~Ee{6976XmgUuE#gW)OVG~R(>75;H7^!UE0_XCPUS$|Dj%TociA6 zMT)5Am8=62qj&{*)AzSrX{8x8mPoWQ>)ma_4^`&70kD)eP)}Tfe_cte4!rTndb|Eq z&p)iWJez&q4raKl^jh>YmHgY|G8K0x?*&Ol;C-mLirBiS|8)`kfm;dZASSS!hQk>x z>}CnzM`xg0eQA;{5c5sVP(B|DdJxYvkWLgGTQu)pqrufCahroeYx?`IZ55i+Y!1E# zx@bv*RL{o>`WLM$A6N~4HwA)v&SBH|;r~vgNPyGLd}3KT+FoMsx7*xnw z;gA)xPC8N;Pn*S}8ou!n5hyK)YcldbMFAaSg5mR{CYV!1@W{wK(l=W`l$y!ob+PvdKZgiJ!?o3W^63(HX z99^z9-kiNPLS6{~7Qee1ME9+obN30?H^3=8D1zjQ``|}A8{CX8L|}|mPiupbKmQO#00tO`D6j- zl2aA94V&ZQPW?|ih}-{+`~wg@4Nmwj?jRg?2QAaL2fuTB_t*o5hGP_)yiyt*wavXg zjqT(kE<&)L0N@|(alU53Gd$owIiT-J3zTD$(^j1?2iC3_< z)9wALdwmPeAP7Z0hqeK5gTUpM2`T1=uy-e20MRccgTWg=SlxG#l?ky@FaNS36Hg&((s?B{eVf$_!c zCj9cy|JTd;|1-J10lb)RBUEaIj8#mIgOqQv`PLUw79A3+C6t^FLu_r0nQ&0_shHE4 zYN(Hnlyj0V&3ALOtfPY*HDgDj*k)ooTifT+*7>|X|G?+@<$1lH=X&n@x~}_r?$`a? z&vm`gb88$Y!j2K#JE&zn&d~1G>AP{p^?9B6QA(x($4U1rmo;$*DbqO}7W3Pi)dgVC zf|oQDAf*_O9JF5eS=5S00>P|N*Xbql!@)eFDoYZ5DVYOqrau!a=I-cEl}?DL+R4`| zGG%vty!S*II^RamG*DTETR2oNO6HXmEW0~JZ|G`!0K9mzCG7OY(CSmAIl~MIhbk^q za-K0EY1cA37VF?>$|0#4(KO8qL@k~IC3xPlQJAKbBeWaa@dxhRIAL8i?p!2g8+Jb_ zs4)))-yB4|;NQ7==2`2OmE3PC>kS{$^=*pg1JS6`5SktkLk`10SgdV|yX} zjVzn!-ghoD*MZcjgLhj54D2V+H#TC%k?r z?PocjxRbkXOi^L}r|3axOY{}Of-TPH`DOKvc7vWK)7zgl|D-5fkZ!}g4@5PzCTXGR!!Hs<86pEsvbLAGzSjM3 zSC+VLPnhu=Hd~LK>c!NUkxKjm)7jaYC%Y1(hYLB8qp8@Su7u+@iH?IWkUoCavgi5Q zWd^gO)E};o_!0Pdd40R0ECkuMdE@!g!%~;S7q?Hf>>#Jj?1_(NK3}(uQR>4iUAOOy z^ldH%6877_5KhM!S*1Cs(TOSB|nAkOt0?q#wM` zX5$+gEBb#Pw}1oNch_XFC(s`D)+Eykd7a;Z^p8j#Wg-V@pYVCLsP?-oBrNRjLg3ML2bbbF7nWVs-EAJiwoNGXeDH|fCNAQmw4 zX5Vv=%%f_WN&x(7BV!YH!*b8aq>_ds4Tp4q+^xrFuEz(x>~5TC+QeBMBUGpoG`aKQo;O~5U8<+seW;y#R{L<7HI~7sV!TcW@zLer{DFf$`-l6d?26FL$dS$s~m;7-em zEJCVzMb|t~M5f*ri+YUIfZ09FU8Pbt1Ok4kV+Q)>1cEaC_^Y3`L>8k*c5so8V^*FM<_ zF$Jk*35CEmXGAFNoPIJlgO%1IVyRvW7$D9l@(VXQ8!;d?V?kF)D!_4ofGR$*IwN#P z*soXlyx8>AV=8at{bF=^rna{y{!!9U+*DLX!Q5q5jf&Ue&p^WiANpc14$ek@_rc9D zYJNB3lgd_D0a@eI=Y)c=^IU9VrhRV>S``Q}PN+&QNcs3l($KqKT-80Kg26-Sg#|;= zR<+{anm&Ug37Tr1Tq{w}U<%^-)wSa1_|N+DPKY6O`v5oV0@CyDQTA*UGnSaI3V#3Q zE?|nc3W6+!IMq7$N#%M#ddxrfwDx`|7mZZi2^+DQ7VRQ-Oa4&de)3Y+=Z|QHbeH5u zmLDD%*B$pjRDJCw2e$MK7k9r8$o*-OY5#ykl>hfmnvUGMnZfgzqQ#!=ndgV9!9#;a z@UzR^^g8?03;bjzDL2@h?)zo3S$mD-b3~?_y3lU>muGn)$Bgdr^|~*%1*)h!DxcMM zM@CrjHprz!{wr%$SA!?v$@C(dpY1a*`02JU*#q#lR5iS95enu`PyAS0z>6&vV|R`< z*1tVR{7L0${~S#%fkNUO_4g3SO{cA=^tP4S-3AcwcrO1DZr^=xi)QoX2%M*d8)CcK zuC5%Igp6~mIKHDKcLz%rE;mKQ5qGGYEYZxL_<%A$LzD}!LO(6H-cTV0S1YnrO&Mz= zzJ(VzGJq9EQRl0XjU2yXexO4p{q#G{r`?j5>Jch|fd6WlAPCa|uU5|AGT;ABL!wXG z1a(3jRXJm=p2_pbQ(+q<8r7MI+M}3s^b#SvX2Ml6?hs8V6IrRptnWCSmYD6pN{rSZ zpI9`;AYW-(u5SNbaO}UoDK(2}8|V%djY+gySrX%~BF|9A z1o>rW1$>D?}{)uN^`!Nk6|FYV43?tgq~E6F0bGh5>f zW@t)BEM~OyPKLF3_f0&crF^%eLyF6z_#cMIin*)n8c{gl>Ix@^j z5U~K6E$D{uDMAnaNp-}*&=ZLnk)tJdyu{#-9dzd#Ja-B7*7deqRSLys0h^wFy2WeE no`nok8~y)14R`eSD|Ozk-=?|by59+4H?9iUd)U9u7nAiL)>2fF literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png b/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png new file mode 100644 index 0000000000000000000000000000000000000000..84e64dde20e178257b4572a0efd717b4ee37f335 GIT binary patch literal 492385 zcmeFZcR1JW|3CbuWK|R`l%!-uib6(7gd`&(B2>0yZxzu%18sZH$jpo)8aCOYA~Pe( z>VBMceXj5C_K-GG@W!S@V~@=$zjF+lW;h4%0biiyo2-EOXn!6XB{qD**aL68*gtBtUY zuoYh4c4NgeXFi68nIi9>V+$P4muVQUcSj7jtIWQ8xVQFU?(?yJ2?j1-%9{W6=gY(6 zhiDJV|M#D1!`I6NxBd5@Xb)rR_5bT5)MZ4dZU+4KAKr)uK1crhW938Cj+OoQr*7L; zvy;c@e|_wlFDxw2{`*q{0w%B1pZZ@PEC1`&|9`pi|DS!j(Z7B9G~*9OonZYq6U-q& z?I(AcTQP|B)XLx5mMy85<)RMi>v!(#P|(-sU}d0bN!6XI&Yj>3;Xlc6`SRsodOA@j zjA}yoIK{$$^W#?!U0vZhIqH!-TogHOIIgUwruchlQ9avCeel~i&n$PnB#pSbtaESG z8k}s3iia^=bsxmLQq zzP_vu;(r$G^rqea>=T(sf$aN@Kb8B@Y+kX(^L$iP)bE1N`5DdER`YTMJ4e3J3) zePKmEhIOWIf8V?wWGH#ET*-^YYBi_Ktu4}SkydS4yG2AUKYza0?Z=RxKNF`#ju*Z? z@&vDF2_6J@%KXm>ljSrtFF$-(U0GR~sF%Z!P1n?(os;uA`D6++GqaEC<9%nB7JmI2 zVz2lA*&i&s+oW=(_<;i^)pvI!8kUw=x#II4&@Bp2b46$le0W+BdFX2I*RLxyH8n#7 zb=NK}E#hLV-q#=xw%0&x!JNKcbC`FuM4dFT69-wnJPy+ z@}}19{j zmA78vBI=?J(}wVAuK2w$#k5}d%&i{p-<$6X8(zD5^>EOzuzo&s#+l-~p|7i|Ov-)f z&Dyh*w8BC{d|x;Y_f7OyZQNr@$HBqz%ysJg&-r<7DJhPp2b{x(9zA-rZTD_wEV_@S z-m*f5B@62F3$_!sFJ_dU4tZ@{yS98yM9EtFukT(~-`iP_3(!i|q7U98UEcTlrh1OW z$tM!_Jgrj)leEfPTQ}&W>%UA?k1;Yaxms6u!o}Uazub>8E4E2FlwT=B(s8J_CRE^} zo!ze{gYBeZMpOT%#PKuRb{F9qs2m)Y*q2QW4GxyQd6O7f@l&Uvx!Es0-R6-0A)2i_ zcF^$f@I=H~b1m;Ka$RO((y!LAG!UDRKr3DBT_yXn$ZL@eKX9yM?#8dN&zw1Ps>nqoUM(WLe=hBGp03hu4!;h?PoBnVTIC*2}Rt z`zm0KSx-rE<@WQmw6xoI?i@(4{O$HT-ZG-87+*p$vb8lVyHhu?$K&TktIm9NC*h%w zncV!^sR3=zFPKzZTP2ZRdhYG|Cz6f~SRwc%X-Zj759hhJVXr?|-^;Y?SIBYHQc5=* z@(lXZ4wh=Y`|q#*(?x2Y&(Ds>T&NA_)yw9^GWqoRv+vU4Jh!y8LGo0s?C;3K{;PTQ z^LHORcI-ro_O6lc;?pf3?rMdKg?B2KUT43O+7fz!$a3S8` zWxmhMpep3)xf&TovOccCZ!$13F+F(vxT3tAdYypwtLP&)n`SBsH4nPFyH|8|ZB|!T zH>-=JA{Ur?O61+s13K1^CnhGoPfcCLh8h_e*=_Z4_ef8vY;B`*n(p%z41Ux*)xuwW z|5Oq8O|3oK{Az+)L~=9Js#SiEAG6~LkUF=LL!6nOp59`<8eibO_+vv+QIV0c@s)-+ z6_dANyC^;}iowz6-#^0DD->M%a&fSZD^TS1>(@%>;*>+>@Dp}@ujrc+)t4zKC|q=M zs>G%+9WHU1phi)ae|=-!+4JXDFfuZV+IDkb5!bs#m=1K=I}bG_@oJ}TeE0r+eTk?0 zb{?K>yLPR@^Y?rDbo0A+@0eLxeY3Mgb=e<2eE49WHJiS^zLA+(fJU71*@d4I7C(HM zAINx0-q;|#nuUc$)U1xunr_gzQAbXW`r7KvH`eY@E~~3!j#If`iA@x##cw~V>EIwb z)>&}RviNWB*eWT>hPw3Z*)yM<9IQ>hFa2YqAn^sijLC$?O0q`Q0eLE7CThbDjE{sQWx#kG-I48D%tsK2GDhAL9mceYpB(d3lOGC7u(LUsTfO zVgi@Zu8u^}A(xhtB9Lp{!E-wNzPt9(qja5}on+m}`7uOcpIgX&uyije5$5JzhRe`X z{oFKiIZom^jc45m6pn) zdHG`TSy-tkD$>dYc)XqvYIbxQZrQbb#ftKp8iug2FggYXIc4P=sp+}1PR*X*-rV7C z@Jup(eWPJu2A6gs)A-1@aEEUVI|4&df?NIm1>A+=)VMxRSx zYF>W)xUr?BWw0*lYJ2fkS*_V#mYv6qzW2T)ttvEh-Q3LR&FN_e(!a3nd9@Om8P@Up z*2gHOY>sKoFf>6;Yj8ZBt}n5G?r8C&p`n3n#Eg`7%{Mz6+g9 zZSQ1ZS-UneCFN#>_mVEZ`^?BD2L}fuYwKOZ&cGgGL4pbIr;PRV*m%^!Z($c!U@7lV z4k;U~j}h~dF`sH%Lo^ZDeP!sII2R9=x{;|5+8Qbg%c*Cn^;cl?RU=MV~2l z3%GSl%Tge3z^ZpjiqqB2EqTY4FmyQ^8ymeYraY@QYOKU;>ke)H=eSQiai_7)qzUn) zu~N={8O1+c_qWZ0@LvRN7)i^tB~l@f?dZ{?2P0%WPn3ALc9wc`p3b#8q^wL3%y-}j z7dN+UXeL;$*RXP1(hV48Wo3atXsp|_@8n3h&sYr(4jO%abLZ%>W3M_3?Ca4h7Jdyx zP<+Nqe{Z>d{W>1imi25a1B%RDF@FJ;l~L*6QOkt}QYiysB@ru{Z-|PnZjci*E$FDo1}= zvtffjwuW(C-4s*TPd3*9m?=F*8onTG_2e#$qM{(7-&hvwp%LOwr2~H1=K=hQRBY-r%9B0i|vK6y$$2b@L@`mf&Hi~dy=%xQv7`+ag!PD_jR#`;~4#yw;A zShfgaZI}S^kQOW_Cl{HK!L)hv<|2<@Yc=DKy?nU$!n5=5*|77@HpD75yeM}2QQn?o zNlNjpjUv?EOTTua;`&@CVK$m{npX4g~?1*C1(Li#|Y$`S%%p>$a>N3c*_f z0oYb<+)WWSEcvtIV-%TmJ%B=vTwSqhx9g-S3jL8`mr&)n7H*~&g@qNUY*j&9i>00sM+k~9Y!6N0Tgt;eWb3wThN1U%2L+#*uZpZ5kFg$-W#VqvJX7AouMJ*r$YtQGUw zAphc_ezB+%ythL`LkGmO`p3tacJAEy?vWVd2H`WW@IKC7xUkc+WLbMp$K|{MJFNQp zJX=GD(e`z+OFy~MF8l!CNNeA?+lbqTprzHMxXE)j_U`J{tH~by@I>M& zKvfx@Z^H4Xa^Nl^_Fs>Uv^}St`uhHAVc`KFmleI%+pb4MaBkz~CQCvqNrMJZtqREd z;_oHTZxSbRGWJ`2^uhkFXl!KhUYMZu@bqjp<_j1;6#6mdy>vZ3934j7X=Ec-&&u9W zJ1t&Tmx(@_=;-L!`F4;6^^7ypZFB8X!u+AiKY#uD^y)ebUMLg4R-#Yo?1#VX#eS{IrB1SXe_{SpGy+G1T%a$#h9;{zh)?uy)RCS#!e$$(k#kNtPJ@o?73dNT#SW|8T=&wY ztc#Z}t;N1xtE;OkN5_RnM?+DMlB2m37RJ+TkZpE{vUO=`-Ztr7Ypag9q-3(SX7jb@ z&z~PvQo2*q*w_ff_w=H(^M<6PB#mEa0z#AkY$m01sGsXy7a97$eAxj++Ei2MJT7$8 z{>^Q!^73*yQ}DNruw*8HrK}mM0Pqo|bLQse~zMJtf+%zp^2dRW9Ic#Wi{Z1A{xaZ*TQw?gIxaFDpAJYTd3S874=U=`vwV zbr7XjFO8FZzfDL@bW98lB?@dF%ZNL4yry*O!2xhrgm6Z&K42# z0srHD){l0JiLC>84at#k8aWjOPzIdK9ZJQF2N>48EOO$BSHzIp#MIQiP^OK$4^o)1 zUe?Ibp_A=|e)0O&roE;=$oq*(NZ2W$^K>WBgl0$h?JSEjCLewbNW!W zqSgr$4$R1n-4UniQ4x!>kV`;x}fp799o0`sQC zJG|=AzAZmIJw1;EvWdmcT6g5GBmca3@xpk#yBJGN=u8nWB>-ew`A2p!t(m(jhpZPq z@YAPHS#IcCngX?B-4QG&i-6feYu2)`9J#aY$gBN59^9ek?zM9>9k!rBr-M40Q1s*- z)jVdG?rvy|S7o8R`c&aRRWuf`hI=_>&AN3v1ejK@UN0#rxlKsuxb_xi=B<#&_Z*mI0)8eEWeo4y^IXWpoA>hx)q@top3#tH9%*TC|zdzuF#QJ@2YgYVaz zY#lG04IWAN#1^&#m`xhNlcDyZqo==9Bf9x_V}e?Ww6mF;Om*PUmXZE`?)lDSgTh?k z_GrUWFAd%E=i_{z!w># z-e^c$M{EGJ6$Uglt^JA(0jY`V;1elV4Z1sdwPUjpt~pURW)mX3?!G=9r@W5TcWKRY z=g-%au%kerX!#Wv7mr9beU&&MT&wuVY~CZb8rYwPl4;SLtUnBKB)QAPm)RKIsZFK= zz(k|}huq(av*q}qqvYSF{nYtGKW3WHlKz0-O4_BfC_EzVK0{Dw;_1BfY%s-@o^#WO zpv9rUnhw*@&{W5doLH<~0)$Z<{)iSP#J;(I;n$SQ46A_lF}6c1D7S9iszV9#sOn5m<7^9& z_%YOcSX+C2Uw=Op1z1eZ%}o+5mVe%GuGoF{nxCIvdx_ZIy%3~)rc3k-Eb^b4 z-#-%L^1ZEa(IszTtgGY*ap2sBeb?0of?Ao{8Gpsot%%d02Nu?q!cOGXjK9^+Yklq7 zHBhStw|UnupFc0>FkMvhppJ6fTBa>hWkgAVh!BZ_tygsleN(^4Wle@*>5A`8ukNqkrAK(E zI7p*UUQ98#Y}){RWS8{84ombeYH&ldhS=+=;r{-#SS2!M@`pl!< z5v)+kZJN$!W>!!@K%leGnF*+*F+Z*7NyZ~07K3mGdO41K6gl=(avh|CtZ&pgQCj>H z!x^Q0k8Mj1{n1;YsM4T^pgH#gndN)V?*ne$5y%^g<(;W2EG*m!EDwBG*;VL_UUg?c zrZ@%LIBOQmrvfiK&O8`(A|?ODi)cKC2KVM4AD^8)4AE30P5*Ii6@YZb>(@uz43ji= z006#e@tk$#1Ea2ukW~cCISay5FT)82$v5Ar;VCmS(x%DZ*xY<1$D-LZa}>x1wX)&p z34U&cTRzOx?z3Z|LsTbHW|s!~2THaOdX2SeJlv8-gsAXvr+e~b(FAkK;(PZ~ii&5O zGYmO#rT51CcOHM@!z^dLT+ljv0|3Ga^mo!!bD6YSlZIsOx7Lm=)HOC92EaTwfrha` zEnMm)h!UkpdcRiBsu1NJXNp`dzk7EK5{c@l*MkoGnE@{ujq5={m1UQgsTVp~qn$~& z&H)7M78TVJ(D4kecZhh7O#@)@%%Yk9iMSm#?z-0g$)6fA-BZR#cby1)CA*<0AJNdb zE4o9+3A^#!bus>APOX0Yn|0AVH#dc-%4HpV%Gp@SvFn#n+C)wGvHPp8v+T^anLkXB z`Q!bz3c!Hs(A3cXS@E(#6?D^wp#-C)ONkS$b`S9n~tglEr%rbdt14F{N9z>WGz9sudf5v*GA8C~e!e*07A{{s>Co8(2LbKW2ZC#+Ox%BOnGjMH0rgzZ z$H(U~H_eASe*5-q9{^w@kX^Qp6Qe!2oe&`dz0oJF4#G9>nPeAyY)co{1Bm+p3_lXH zyf$7kzZ#-ujbm5Qlg9_U$MVKs*bf9{+gi4!KONROKAx@fc<{`Z5)OhEI zz$7n@wu|XfhXIH%Y!DJWt@GI3C%0Ap*s+!9z-SZqO^TVKzCGbRohwM$DkOxOvs$m` zIT+wo$bV6&yTA*gkM>#L0LYF3uBCK)X+uf!ItCfZtTBESJd{k-N2v^N2yjGzfF`VY zS{pkAaxo!1_vXI!_WEG)MSK5VvS?hJvU1a&Nwg+Kx+A#ouil zh(V!lnVlJFpWoP;w69gc!h)X=-)GNulTVhTGuK72O7EysI5Rh6V+E-d(s5$D)~j)u z!^ulc_4RjlJf<3&ZLjr|CdIC- z4$5w*fKFIi3N#)(lXSz<^ybCg!Vz7+h!_jqrlzL5n6m|@4&|BCsNTYKqgp^vP}mN& zl6lwk_kXqxbvIAnuerJMhK98eUoJz#Pag)|=iaqTHEjXpq2ZD$A->qeG0=c6Iyi)c zSNze!2j7_$TZq9FZ;lY4vU>f^^p-c3)}q^ug(Rn?(v%%NxpJXWnkZ8W5Kg5JdtX7pDp??SMw)gQXg!lW|5OeV#A< zfGV+Ipv6P+T>%h9#IWq+<;mJcf<7T!>Eia%I+Y+T$Yyr--?F_R5U z)iw?Z8P3PKv#AjJdhsNGF3$F30uESpy;ukA`asltZT#`4dRqsE zQQ7OW%{5Qy=@|oNSyb|>*+l7JuANlTuTBZ}v=vUQtwL7@PdST6m}pSAPjJ^R&}w*aC$>feM@$xcwKrtK zOL+|iOvJolJNbR6L3I|zXl~`u0-+q-Q|JO>+y^OD#Pkg_tciZyYo)<$Gxrt^ykWkhsE)WDu$-ncQKCGE5cbbPFUtLf=NWE*tk*{b}=cKt&j(bdhm zizL>rU3(F{k9C)xR?3eXtbA9X^CX9+)MQyE5dI1K)XdB*{kIZs4u6&k|FQL_{W762 z`uWkozk6gNt*EGI&JgN+L{U-Y?G%5;b^c`Q&V0MW)@-rhTAu~3Ij`f_I@+&wa6H(C zs%Y~jP+D!X=Hzu~BSf&p`ZVc#b)8dGW8L@M2zVmQa&KnpVLr(uc6H{`7j*@H`0zmk za;K!RiOG~GO%(Kh+HS~p77`L-mMg2S{&v-?^W9jx zPN3Ai+qWse5=r`vVh`9=H5a;yTv_0nX-oz}xyZ`Oy3|z)qL}aYBe`8H>05YWAUr&7 z$eD)@9dh|Gv<@CaFx-jHk9>XH?vE7V=W8;7EbRQYM%d7KSg0C0_0X;VQ1QONt&9Pnn_z|k#>Tu3!yTK zm=62*D}Jd7J!@`$9gK${Wav5;C4HCd>|Ua%)h)9xcx!`@x6T(j3j(Kru3nUo!w#@~g=zB%;iJHP?FrPD4z0qTj0yWIB(ZAyPFczH87Y1H4Am z{Yq4_xGWTpUWm_GZa_fyi(Aol6!hvu-yc2m>*vp2sC9oFotdxi*%v0?3UhWkIYEwI z33^Es)~xz<+G%=zzz|H`d7L-l8nq{~;i~gd;i-;HdqdBqqF7)D-r>`le+H;s*V?Lh z^k_h;@T0Z*5M;^q!%;M})`hu-W^aFs57rsvxB3@MDq(_migk8~6MdFamur1`aA?RF z3(unJ5M7j$wP{sTla`5wk41ZuNmY>2IY9Rhj;0c-$0K9{fr*vJ!QyYCq!TTxYoO|!yy}&JVF`Wl4-MxGF%HW`x zl>3aJ+Hk0#?w(qD4g#&=tXzNd<|rT4+seunC?;j-3bB${p<<<#M#T6X3Jr;^LILrSKn1u4j#mC^|YibX>QA-xH=z-n(^c zrM#k|CCBwIp1320o9lNGZ4f%*&JOdpK6#BNlkb{!=YjtayGZ4}P=Sr+4j!Hrc*}?J z&vR8)C1qu~iN4o4HdBYq-ED=<9(~9GG_z7PfkgC&>YkjXKT-u%VvTTcH2Jl9U(ZmlKvk5bQ za|psrihmb3VQCu+5`%dLrZGvfODw~TX!zg^F=pdk^I#H3Us<^jrUw$%K z>rPz7zA-J*Xl**h2~9)+gKp1B>kcDy4dP@g}i*TEAfnDL5;V~d=K{=U0fhm!OQ_7JHZ$b2go7Zm~(;#kda&TgX9 z#6V}FbdL=qg638Uw!&eOe)i4-?BOH#gT+ zdHXVov$ONhpFfG)0A?o-Wt8$pf$gER`#uQ8>d()sPLFl5qbd=R9C{w<5ucEPIXFeXvMMpH^fxi?d?}y2gh<6f!-2T_P2^hh7wY6Ayl{BTty% z9_))4Qj<^#0nt(IpPAKfgGDD}D3TZgN(Bk(Re}8gqAI~?SN+h{=@=RB4Vk&uTC`{L z0f(MQIKKH~M@K&dFJj8TBZymbHCx(HtN;lBBK1SVF~MSym`TB_B<~xsfXiqSHQqiZd&~kYqxA!4FMV2wor$40n`FKCcuF0WN+Ywup+R474X(+Gnaf& zEeG7fhND&VL+>AH)7A$B;;9VG@wO_VxW^!Z9ERjK+964a5TI zJlK0-HP9Bx!CAFu(<6RW30ESvzFaTY>NGLA|PR z`nq#POpX<}O`!t2A;T*Gy%(65-8nfc>$g0$Yg&0GYO z1Dae8_8c}|&q*LERuH$K;7YhT2mqP{(Vr^o;M7(y!BG|$A+O=({51`9~2t>sndpN1?B`C6YZw06K z!ex*KVuZsL8Ei>oM}?_RH#oqzX4vF0!i6YM#LigBzHcR1u>!pN-Jor03GKg{DuX$L zNq_PfHz_sV{K530Jcb^2U@^0&v_^GL;@5o8iz>%Kr{pe^x^cf$;-=V zo6>h69fP&Xie-RDxg52N7O5YyTi{yx#l?M54D^P$PKZ-w&}K$yX=%b;pt{^^-gLl8 zuqJHRO&Z4aM`gD_L!ri-_JjYa-SH4V4pB$Mc}yQsv5L2E8CS9I^DQZnLB9@y)NO>f zbMfNEG8j_oi6^*_V*HXMjGauV6ZqMU1I}Y*&CTnO3%#RIPwDP%h5vh#)9WV{8rNae zqSUmsPhY?C1U4-%l3tD0Ml=H0LN!F+zgy>P{uK$D{YH&;Lg@x>E>mt_9} zD&Kt?Oatmhi@sA1mi^4Ukq3-53TEkp{kB_(@s*OI`~qSz$moGO=$Rx*XDu4}r(}p- zX$0^Fav`EP#0I!jC-Q6zlJp%pQ`KXxRjS|4hRb#p{KV+x6`E6dHk?TwLtjf>7BLkko z950U*57~b{L+MRyhQCJAD*$}E#W}}pvwCVIMBX@AXdshAME_l`A%ln0&`3$Q!IMYY zhzW_JuLoRj40;k#Z)rh-L{-s<`huY?wcdL6H?kA4qN;cYxzufQE46;l8+?Hz1jr|W zs7l3Wfo*eE1Z`|Paw8J7mSpe=ye0d}-Zb%vG~8y|0s>|=z4 z+#DM;o)w_qRp_ni(em^Qa-rb=>Olpz^A|k}*&4FOE6kC>TNQL%R1OV>dz56G}r=^s* zgoJ*qd5M}=o6%!vy(0!ri!hs3^to@0}5<>zN0$4C05%{%X4yY83H9C|kTc49ntb$2 z&%TZq!NE-0u;+1CrsvMRL?tR+niG(88lj_*a(m^6RXtpH{=&F0Dt z11cr9p8SY?g7X}NL%|>!qLz-{Deg9HmirbiK5XCFU(|Eu5(f@cw6zsPR{UkNwMV&@ ztV@;u@YywAw&7{QfO(U79DPAnQz+{r4Ld#y~AWm~0jyB4g7(6~G-phJNdHGQ`DzVKN_T_s#LW@JK zpHo+0fB`ukO2?nQNcgOopS4gY6J06c2)$Ugo_kKitmL$Jsh17ocN zAtFu#Gy^!3Lcq3SEl?6j7!0qD+Qh^JLVpb2QvRhc%DJQd{{DxfPL#nAvDP&*+RDn{ z*Pi0>YmzNb8XF0f|K*!EbOciTUYeE7af8kN+J|Zx$@bxzzzGBGx{BR5V6_lu`~(`` z$B!S&Iy%@(^jmZ_4I>!iHNJPAM{etFiy;*s@Aa9m_ri$}ze+skpoq<}OrFQ9I31!vr$ z5+)DuOkBd6A>zQH=0oN7dH&o!x1+1TekUN`RT8ZR1tyWVyZ7$Z$11U)e^w76dCvkL zXs|VdGfYtT3Knu7iaug+GH}#(HqQf%GIMaOi8BbOZw;h3l9vK^h+0ondqR)# zeMX3*lDkLBsVQEpC0A`+gFlpR_395!J-~i!khb>XYZ1}$v+9sQk1F}S_ znymdWzoeqcoJ2-MWCjZR!C)itk#Ov904HE zy%6?!b<#QD2#bdb8*Tvy&A<5Rik34LCqc~+0k6RtFH4%}0^7N@X=oBCQFmyqJ!if0b=nm!wzX<|eB$CRMZl0qA zr-2|Kyo*j}m)p^RHwX^2iRah@AAARK6yfM4rDmW(`2Y(eL_dLiqA|q#fWW{bn8h(2 z1$CDLL<3OOc*sl*JGT;o#{`}pN5&{*9hC82zydI_6%;9tpUh<0V!1qn@|rXTtz!)b z$1PIrAiPV=1piYkFIBGj&xl>gC3sy$v z-)lX$!}kv^v9uImKgkQ}3NPFD=FOX;M|403m*$3rMIphoe#~i`L9rv#JQVWtu}N=( zI3%_;w-q`IV`}+!y0a0P>8QU3 z-7GC^x)r;elpegZpS+&+h$ph5oz)>s!uN}TLZT^Lz796$2cYl&{QB57_Ok$m)Jv#I zL={1tGsy!JSl|XLFvqbhPUGRQmK}_XQ_qa3;N}S5RK17SiU{kuLJ!oRH*emQp<~4E z!Mp%~Tt7@UanHGIEgM_g2$MbcZXn(z$VKmRfK7+Um%y%M5GTLn`gMAcMUsdMZTt8! zafcz*?X@kiD1|~di(jMwFOnIXvsPBOLPA2U68M^O)%bBgWxn(*-w|y?vQpXPDG)(L zXQxza?vp1^OsjRuIy`$`I9d{`4WewdohQIH%woCR2qFWc0WM#@{LN5ucd2ahrhh8M zm(Bm8fs#wOnF`PpGKGfU--HfR0o9OXfI~u9bLQ}p%VB*Gp@&FCsDNf&FLFfX-l5;s z!ImR|P_S824(|&YAa?vvs%i$K40tzd5pE@cT%`2^Q16K5fRHh9T+Y{q2Z9yHK={kr zzS?>&4g)}LKP(8(C;oEFQz_Ry*ofD#ZOyYEq773~z?|pQXUy@}A}-&JC}nt!ao>8i z8t{9LXpH;DL`PCabwftJ)DR@ z<8KdPvI3fP*nr7I3D{>Ob|oTO55z3j6UPC12Gp-JX)s4UMJ$?l2}8phl>>ePXCqoC z)N0B>G`KbF>^FhVt6KttgR7ALZn~=o`3#wzAeH0LL*ttTcJ10#cmh-JE<9gHB1JIX(V76RPl?i5k+8H%^;#k44o}18GAsB1Xfv zGy!@1Sm>N#C7bkNc(%59w)Vh30C0|S<)3<1VgVXuaSlT0dde$2{Nt2N#Sq98=|4C*|J6Gv^UmA)+AJk|3p($_5*0xq8htJxJdK>c6UNTwhLq+kx1D}7A==AGZNmc6yKbj9Ha_2 zKvvrZVH>UJFmNjIwA$v7Yc537WqkN#1|1Ebd3-{JV{rP!A?be=n*@l9@1& zp*^u~*e~U6ZMxQr*n}6{)9JZhVew2kY6PpY_g{)g9e7sf=xi`mM@M^6NEj1rM*j$F-g?Na2HpfKO>p2c2= zAXJ5w+lz}sN`Y)mH1D9kdRI&=1KZLW}OoTYE(*zj{Y}+@u1TQNXbZ4 z5`zdtzZ|bgj!yrD13jAGyBy(11RM}07I+D^D_`h-^M>V6>$AR1;ueiy!~*xend<{H zfoLtSpb(8317LIzfGd;COg`Sv1U5<`8W9<|*wum*B$ZF<`w3|?G} z?(_5T3+_u`=4yJll?m4;VdIT`k~NEhPVycE;bPS1$cq*TUC&4R3+=oDP@PDV$GqMH zY4_YpN#rCek@zL{K&nCE`fuO9A!Ye4vkMLk7x*wxT$t+X#P$U2h$@H`6bkt8RWwY5 zL;OLHEyaol=gGtf3L!BMT+isRBU^x^*dZ9F&=f^mHc2}0w&&RfV~)xQ&j<1|Qll@j zi$Ezce#b+Y0ccPZz7W%Kk|gEt>A4uZZwKGszF6OS>)*o+3=5!2k?{)Xd2n(|L_@by zFhrT$ER6i-Nb$pmo51h3soos;^2HCj)G(Z;+xkDN(USm4 zM4?p^+Nqy^kqT0p)@ijIwH_E$)oR9pJjwQQjaq(~U#|Y~#2n!hJjLB88|M6P34;Rb z+9>Uo9nzVAKrrHB>2JwN-d^z7SYRNC@Pa-2ShjM#yxe|HAw@s$8~b-@XsI z!Q++p4dF=8(a{|QAe$NMx``Z(MXC-8>bG&U+9T*V@YP5SF-w&N;Uf+^+4t>Qw~`+m za2(n$Fy2|Pm#hJz-TabjgRBE(!w-bwt9fw|SXU(mqX@3nO4rvlc?$U>21K9Y0|XF- zWkO;tOAAwK-{wBPa3so50AiUG40B3g{+a0M`@w5XCs_V20nc6k9+NR0%D8&90+b>$ z@CxolS}}GS7Ch1^t~P2oP)F;Kw{96D7g~X!xkI@?C{qBzD*NG7}zm{kl?a zwQX6)tL>JSmPIZTaxJx>p>$lP^frjbhrGUT2q&u&6DdI$y|cQvvgZPl05DJAg-f#o zgjiIW!@=9Q_xwtDcK(?7PE3pFk~um0c$S4VhhQ;MT`;|DM+Nb42^J(^7ig^0o6TE6QP57-nf<&P%&MEo)^KM5$Gs|mRb4F{ur{7;?#(`3B= zJs4%K=D!m+3d-AE4B=bie1)yW-nd;%GbZlqI|gU$1jgFQ7&}r{@_@tNp;ANx)knl~ zj=xnY#m@!6NFs{JKU0?;9v;1egS^e^fxF=x-^6qF46(kj-|gPbn~WGR=K8g{_!}Nj zCEj8t!iq$;=5KY9EP0YRbJHR=-MLuyQ4oFLL`TX zk0?(j_$oC8HrQ>;qU2XeWKxF<(r?F?6qd5I*7hcQNr81*kan6r_i15tYWA&#V0@ZijF zas{NCXgdQKJESyN%ufSPQ9fVyX@B89D+G`j0PdZS&}eIi zRnEb4IH;g-ZQ2WYa8y0wFCa3f^mTDYi=O>ayx6?fWJ3n%-(f_NQOwA^*Yxys9fsT5 z=8}CM0_b>WTR(pEh}uWbI1F;Npr9ae2ir=tU7;~(i%=%jU-~jb;89N>{u+;AA0lfY zogknxDem%pD;c|RTwGklbb%krSyIluhYyolNP#E7k_0u${38C-;uanwBdCi7rf)8N z?>&@uMn*CI}^GnH0dw25f}YeuiJ=*fDv8meVz*!*SLF@#_$;j7t(d zIsXakAj`La6n3yfGtBGa=Zvu30n$^7vFyo|hgDArNi!__zK?1*GH2HF@Y1d_Q)A2C zt05}@ViGr!=KL&jMr~Q=$eu$dvLDfOLSgbJ;u?WuM9NQ_9m@{k2YMm}8d?Asd;Kub z5NR1;dqCIe`_^_AdhS8E;nb-IR?~UVxTqCQms+2to5b6yCAC`?xh8 znh{YM@Zf86!{Zl2Fzydi0Tbw_!lY(pkduYxSMloAa(wt(oxf>!jKX+}|K}{FdYyFS zUZFrrBOCf@Xy^tUq<&C~XSum8r(_|GKoY+4cYKnBP@2+CZ@>gP#fO+>qN1#r!@i6y zNtQl_K+7;oXC0F2eYg~~g`{VpimrgqLi>H6ZZcxtL>eaA1O*iD8dBk8C!;}mgjnlf zG!oMV#Iz^5Zg6OTBAAJ*5ombr+~etwU=A63CK4QGX`RNq1F=tyz$qmvNt-}4g^Ym% zyvSh5J;NjLP|b<2#`pIQ58nhEiw6H8p%65EoF#J&yA8)}6crJHi2xsfQU$!ysEiCU z>x#N)1X(QWRUBl>GHiUzjrc;SLt{*^n+M>MhbxsOt=1FTqy9?tA#6&hm_#3d`ancO zlF~qD*ufrXiNFhTM0W#|*Ku+(VJrqxI>u_KKwc_v4$ukY%-=nc(9C^`sN7j>HnZ0B z&Cp|4gQ*Fg&Rq!%t6>1QlH@mbRYEK3g|nD-jvVWP!LzG?21+pnqv*yM+Bo$5{QK{i zq)~Q+5FSKo0Tf^;HwWS35^)mKY#b0YviJ^Snt=oYD8KJN0cLWb*eWV(sy@ZomlIC- zVMB)?(pt~T5VdR~l3?2ehAfZTD>(#lV;2Aqgap2aQ_EfE; zyP|qe(P0QkKK4kI9$VxvgmXJkBvR4{X#m|1ACNJ}YF?9pbe7QLEg0!p1A&6#1D%DM zLPSzljY(BXdqhs*>>ES71bczQp z3uPl4sdrWg{`ZFvI;N-eLA;L!--?EHRSwMw8}JB7l76!DMBfpT>mr{{s4JQPsXm776;EWFgC$;!O`9nmTGC&3x@WSg6AI+J89>)zz`x?4Bcj)^FSwl>w zUnk;}H3lLi)H<|(eYtOlyMK<1<2s7GscCGs;GR7iu<_{d8D~vRw_}n+-pDA@$`HH6 z0QkwG(;qez8B`?~3*9sT1^gzIeLBiELBV6m`{6v@iSXuWf8m&dN$o2LRY=|Ov9f zn)-&&VT4&{ekKtxz?;b`ArIde-NnKV3+Os<86zOaSsNQ69R0I>3C96&%>SKMl$USU zq?_n=`S}ktlaEz5Hr@uQpJZ01vH2q_ep&3o2~r@&uhF2Op6b_q`ez-lsnq+`xVwIITC_5wC2j{ffUjouo_Kp?$oi8e-=H`$239zo|hNVj7M@CcHHPC zXsdW0UX=lZ2JlUes;a)v47z%?;=+x;aeU}rgFV6jlE`UYOx*S3>)M2{!sT&l+5lsK zDV%3uxpt1>?-BR@5z1hbGW{#b4nBW@^Kj0Tcsv}v1ce@oPtEQ{ndXz4hQoo{U7)JpW7l&;NLR?)whsd1WJQMwea8xh9-z_>S!Fi zp~^|e{+{86TsbXqe_0t`E1DBAAJ)fY$2j ze|`7X3&8!tfM$lD{^_OXIikcsheowybJep2@PHxkDS>`yFRY$gZ=p}NnCl}wyXL;I zumGk%{W3CyA)RP#wc`s_1~lCOTZH(^xP$LR4NGz41R6&dh=v@1+`B&}Wnc(iG7v@v zj4){yx>^|I_{*0#rUz~jNduC&_S9F^ocz{Q-DO}ZWGD-NMSP0sZ;d3u6WCz@q6C~x zAQCQr1!_3kFtNMHVMtk7S1_VM&=G>;vKBwORee2X#SmG`c|mdu(6|}!Ygl2?D9SKh zAEpNJSMM*>fnploQ3Sk8B3IZTBq4ya*Dk~20bqz--;euhIqPb1u{22sgKH;Qb5fwC z(cw0UcM1Q9+$PCM?^07zdWmESY42nz3)PP}DkQjy5Qe$cKdYKocA7zw^3Thjv(-hu z0Gt=iAR)Nn3>F0Lg#mM7YLXUB_Y<)paQcX4cx%W1oI&R`{eWZhW^w`@k!iYT3PI?u zLN@cr-ku6|X7HP5yEp&ToF@XS9fBS$Y4E_uB)OTED}gXkY;3HV{ywA@o=CZ_1$RD3md#*2H*(_} z!LMIK-;b@YfE~w-bF>igjKWuwuoalF2zm#HjK@ao1%E58Le%9La$SE>Ob|e?36i=v zo8cwse5@OcZ#j_d+YcTDKukVtXvj$-jmTKzIJ=dg&ALUv8;3AXYkIE7V=8cD5yFg! zQ5l6Cz5|3?g&QN;S(4DjMD|XSnWkWyRDm)#&s1NbVY~>Gfgk3rwT9Zxf>%yFdvfXx zk`=}P&KTmQ*UmUYjE*F*Oj}}V0z6y=UO@@Ejx=DT*Ww(>xB=?$G((dUz$>kTmrtzS z3m=}m!~q*b%1%9%DVN5C3Pm3DxpPos!-_e@ELdTl5#!dF2n0uumVt_Vf@Vh25_eUZ zIK+L>TRvgjmwXJF%!ai<%ruRsxE)&HLbImCH3a@4>qs;foKjLo4%Y!0&Jq8Iz)c?c zr`q3XL2HDtjyt`wI<5?v9wnTBax#s>=Yf>#rSJ|Mi^@#!!DoNk*&yKEFG)+V+g?}A zCENw$VN_JC3T_DFfeVe(0vH+Jw$1^Q=vCc+^oSqnjmey+MH)XWfglT7U;!AF1h*#0 z$P`RWPOimqPgz-TG)O{H1hXu)Y;W;ikfJQvh_e8+;)dv`5f$(^7eMUpL26HLr#EPfHnZ7XO5o3dtO6%h0++8g~Tu;+7?OBx6M&Z=a1jR zCt zt}~@xyO0R<3l0v}a>5B{R0l^rHj5bhf`0a)muu((gjM!0lmKF)9}7a16&Co7Z&*$t z?p=}~=G773zKN*7XBThe$&$#-mY(a06SpZ_F%Wv`)_=J9=_gli|LtmY2mkMm6FZ#S z*oV*!fxQ63I2M2g%;p-nOU)436JWrkP9jABvlNRqSnBnc(a}|i%#(p*oSJk60<-dc zpNxQX%&HfAjN$`INj?V1 z#x6b6^7$zIPIAN{#RtE1v{9q@fL|MyGC7b2FNT~{h82PN{6|)&Nq~HCCtN&o`D{$L^!0TX@lTrV&4tooDU*yz`nLLZn zBF$Q7NgEYoyBCJPF-ACw@>#RYlMe8KUDXniNh}$1h89o}79|Y; zJGh29M}av+W^y7IULB^KZ^1wAEOyr!9>pX|1%gBXL*qVwoIQwz7Kx|`+kJO8H*yM%wl>DU^9u?-p-yT%#NnOLCYoDp zkr=1E8A9@)4~Q_!i@FT97%^^0zLviOQ5x_xA@;N+Yz0!6Z~{xJ$k(Q(CaVN#WQO@M zyIGfMqS)rzo^?(IB;^yb7tQ(MH30P2@Djd-hqdlQE)vH)aa$6%l}xbVYHwq0_Rk=^ zZiM41Fd>;V0&|-Zxlc|Hr>*)jBglBKG8cM6b3CtBHP|a=sIm9XeE~|TtFOo6&eY1q zNor(V2vIs83@KrIu8Px0YKcc0455jp8nLI`|G;O?E1Jw}|6)ffapy4(qNU^EB8$mk zXJ<#`2zVGclZ6HxTX&JbADp;Ejx>YJMmjt>iIZNCOrk>^Am?iUdXTdM@yj1`txt!W zxc{2mK@>=QC=qC(Rvf`?z$_PmcTL@gWjwP@Fv9PO0=!Ywj2XFU1cvNMXazp3A~x#;3<7Qte{9MM^ll0T?ILR*#(!3T zwB6#6SPKIdT#{HRP9q;L1N&h-mLBIxgvGCbt|=IF6w zP08<}QXW>^Isf~rD^3VOVN`B?a>F7y4-18)HuS7j*s(mx^apY=;nr7Dc;x7?v`?Ar zc|Q+jY&j(>HU>XS<)gPY#^0Y7$|N~ygq(B+HxS3G-mf%m14Qn{*2QUEVPlzP9r6v( z>FBrsnrTR^4GS(bq^!p}$_yNP0IT?&t4cf&Yf%yJ%)jZ997pB(Hsd zor0U-g761@v;yq~H0C7EDV1p*O=$;JyQ25_pZQ{B5J<6yC#&Wpbt^ECOka_80%cHv z3=`vc2uQe5xDIl}oYpK66`wsTL(w9pA(@i}nfN(YIQ|TiiRN>!pUka3xJxAPZ~x=% zVQ``d{e{!f-u^`Y$bvG-NFgXriR4oGJuwJ$TQ_sQ;%( zMSHeG`-}=5SD3IN&ISYG3xI<~M=%3+tnO1dFOWqb@unFR?Wc*#?f78Ro`rHoFofIe z*e(H_6LAN;IwTaS3Ihr=go2YD@$ur=H9L^I{c|SMC)r> zi@Z0F=6Y@0hd+iSDwIm3#4b{3&_qH=(L_ixl~jmAqB0dlgj8rk$vjgC8A>R2i42)C zL<5P6km+}v>VBT*x7P1n>wVX|*89)fT6^z%@0;)UGhEkso#$~L$8la*xnzkNIQrVR zOLjNLeS!57@@Q6fG|qIB9ncU03cG@Qo1)U8=i$QR^&7CZwnlJt=WXw~;lLdJ^r#G{ zKOC`yg{6X^uJ^(D<%7lQgFVHCl!Zl!`t%Nzk>R;wPsb!G)Z{I2r$Vvh9c1Owpl4%C z79@_UG{Aoiuq}aK`6J)t{mNaOog+`<|5pW3Ma|MO{*g2409+l2w#V~O08V3`!7xoy z{>+a^)GDF4>L6m~VDkqfv6@R~B4~@2wz@F1Jv|dH4&}eHc~8VVTZ?do+7L1keONc> zq5$P)s?z@51?xhH2thheUB_?7fW|>56sk8B;Hpt}H7yfx zJ9QpN02+w{NeJ}pgJx!IkY5u1HMbl^6O7nm)*ZUG^h|S1uRK~TbZi5n1T|`hWF5?X z@Hy}>iObvt119?`9}v|5^jw58&y)8t*i}#m-?B21Ju}p|7)9C@I{&Jwv?WiVkU~U{ zvJg6-^F1{Ghq6g6Xnzp;WMP?xrFS3Ik3q2|w7EFVW|Jhq zRww>0InP-i7DDdyr5DX}luhm+9N@OacbVmLIi~+C0ksoUO;z~wG{}+X z07%D?gYj`)?-jBXLvYx|ZT0rhp_99U~-f{14?C((< z`P*or&j*%Y9lsMAk_90#(a~l8Nj{eB_XF1IiZfJ5BZ?dJ@&rM}LAKTu*l^m|Pui5A z?av8NGd-{r9FUsmwK}U-ufFy>?)TnC7dsR#`$G}E3yX@_Py(xil8^XEF9r<&VuO&J z0?kSidSeNp4mP=ccK3C#0z_aQzHUs!oyT&`k|k46ic>}i{$NttYhZt?AWEbp0?4Nt zs2<0=3aLE-*9mG*AhpLKL>j|(5PqNs3p?J3zoo~Cg4#mq2MWY#*xf}q4I|BwhX9LK z!I57Xt0hLjIe?|DgwvA^<8x$w#*1+U*waM-L8dcwa8|v2OB&ZvkTc2Gt0W)F6;2?_ zR4(`T4^@2lv+Db8`-GPM#p~XW-`fm_Q?xzXkb3ZL*;X#Qb6{YcCl^P(gm$F2Y*a9+ ze?TE#07?#lWJgw;RI)=x?5FtkQzY_nZBc(8Xid>8yRXObBs6_x!5A=zIY7C2XV3Nk zc4Kk(y~cqv&A&!aOJR13(7Ni!qhre&0Kv)b8goRkPHhON%dYhZS$}x33xyRkV2=}3 zTN`cdKQ2NsX-PLPOwH<~QU|D_Jx5e8=qk?~NA66N1dhvPrdM5i1REi1v0 z#)bwBw-cc6fW1oN0pNUn2st!L9%aaI9yJ8xq?6Tni^DWB@*>`h#g6tjs(UZI1fT~H zMis|98%h)vbj3;Ui0+?j|5)s+?6K^Qx&Ol%srFTQMzY4ry?#HghXTSOno7btoXhq* z3?#K9IdOQw7I2BH0;n;}4+Wow5rE2`R2{4@qJ@sC7!^d8oeyEtx5new03p|S>+;>K!_(tWg~F51@fn- zBia>1%wRr%3f%)0){Ct|%Q4j9uL5JgQB7LSjl^tNT$9+EVj?K&kGkal1i8S>{{r?s zv)*oU=zTA&IM#n%ha6Pk*>NlpPCo!W1-JE@K)ykS7k;r?V9t=HiNs(iQYLN7e|M+A zq_s}`OX&zW7Wg?5qvF)Oh=QH=CF(gev@{%m`SUQO%mBo(xh(UcP){l7bx?#?|CDd2 zz+>?Puz3iP9op?XI>|l#)*H2Y=GAO7>dmqJaOrE_|76faT>U>XXnx$_+=~}SW_AQY z0=^`RU+iBMjlwc(&m}v_4Fb1hiYhMs2gb}Sn0-lSL<;tDfDb>{9+V0{c5* zy{Ic>1b->j4?Is95=nvkyR8@Xn-3!9vZtM>buD}1TwCj8GiqY4g}4sD`vPSlY^k21 z{=F9y^pF-o}EW%<;s!wf#4i6d6*n&FRTjaY38Y6iwNGd|1Gd@1jyQ#P@`RnUD z6-kJ1ILwLxgVg*A;3cQVx|}2&R)w!#?YzB9RvyK939c&Rtc9S$HzTP3q%ahTPf$?O z_uPN8Z=!zC9+HzY_%Lwu4w3c%B&LUSodwHNmi&2y--2!U--a}v4cnZ1bHJ2^x?L+? zXW1w&sD9}NG>&(;lJvjLAa`y(-5=%looDn$dFXX(L;1-bBZoaSIMpC{|5yJ3=wsLiJ!O(HamSgSaXd1uXH#TMS59!T~<7{@`-5k7#V zthAI6vB4=M4-9gg?aG3j9vL%bNI*Rv3NQZT0vRJ2G7yf=_Y&m{j9c#f84!d2!nxkUg#fq~w03e|WSeqw@oC$JZXP_S#k=>>=|p;*Kr z!ox8iStg_NQVM0zCD7^c?R>nvS5q=KL$1aRw`PA33l_un61RE@;5vbGpz)ydITg?0 z-;7YSBtZMs$*Hx|2DQUEfNL-xOT`R!fMl+KAVmgjpf9qaldbOL^!WJiXZXZ}I6W*M zSnh-`2Sfgw%!!y83byU+%(lIG78;`3ey4TuYeY(tT(s&CJ94~>)Yt-Ch`zMP@jM)y ztWM|h;c(iDI}t!61rmCqswfVcXkeX z6hz#nl%9NO&{l`hQ%*yEHt=hr`(6>2U)Naq{*kpkf&&7>BiW#qk&%a}Wvg^t(FRgS z7mIK$m|C|XGof@6Z-V3p^=HxIrpZsJf+1q@B6=mAEvu_s@ON8368&?acyB`j^#4;nlVtt>Yd%wgl&_zk zuCEE_VhoIV4z;8zENn1UC7Vq0aR|*N1c18Qvk;9)YQ^f#Zv~8j5dm^pojHsQkZN`k zQ&D4(6iJXNN`ZIi84|KDIc*F%A9WhZ;0UcQUj+8c*i4rZi4v0JQR8Iv6u7xUwc`UK zHQEo$`MK1>{6nKZ{B#|O|JjB^E&Xi#IVG3@ClbIFfz10ExB}D|#YgyJ&HDg~i?ud+ z>p)U=7A44nk2MDbEcw46NTndL795!=(ztI|x_k>R^O5CVhy25XXD2p`J#Vy1g>Z=a zNoWar!(9h1tZ{n1Snv^mU5TcJCeUTr(!>kj!DjPD>A(qs1}K#>iHV7-2#CelsWlBF zfc?p6z>}UM@HFVbW+7vRoE*DRkKqNXy)V<@k@a2&>7#>Z2VHZ~ZJ^Euj#M!s{=v5x zGKU}>rr7gST|Oc~S|^~dBV=D`2$JnZpMA?d%l?>rX=$Tm&Q zqO2BIUwi_Bm99Z8aB=KuaE{*p(%esH9j>;d;gm@=Nf|i z(3rx~nR7~FV;MSTM~*}%eubL{ydk*I-r`;w%i0Hx+fy`l(M`V=1cHVzYFT+81$s(> ze~}u#O0U-c0xPGqB9w!tS8+NUtXF7w70p!plX02QbbZt>efqR*joO26h>sg!b%TU=5{Mg( z`9XP2ok{>^M2QK=6gJ-X_sOa1@cxg_#lS0fbj^?CHUS@T=&ByR!dID#C=ITP$AWHP z5kqU#R2teH{%eNpl=J^ZbNkN+;-ABjd*879Wn=v3G2)+N`@UexI3d_7`NER|d zn$?LvTIVrDPMSy$Zw@+Z4GAMjfo1uTQUC9@-$$ml}y#kBo6`1__?PQUBvy<8m^ke_qpZ{mWdjB$~BHSJ#BS($H ze@Z|#9K$4~vE8{2+w@m-;<%@Lh29&EN^%i|F5AJs8;uWk$Qw!l%j|)H5cRvTKGNl2 zCHfRN8IhO><)!gYS`SKMx;g0~uJhz2X#>Kwve%Y=UFXuto4-)hax#DO#7BDWbT4Hk zPpnUsUmg%al*`2=wpz}BFY9Snud4k7ex{{d3x1e_g2D}1Bq%aHLuFPMwN zt!Vh{*nt8w3HFMTO_~}S7l4NnaEX^YN&c)9zY4(wIv_|fz~A^~a%=nU{#DZ!gU0Dk z-AVvar2FyrcP{xM)3Z_k{+=@qD1)ZZBgqZ@0dz$uYNj%=P!A$+^+ya~V*qNB zV*$<|ip~l8`Hx&Qu|&hewd2Ty9SJE}w4h<@8gQR=V6AKEP*$re{GuXcgmKk!V~qu7 zC;vclGmvcp5kLq87|t!XAfn*n#?bA0amfj>YOE zU-ldo*h)}(EV9w=r{QS8XOA}8V5l9=<;X#->qYBN;+_5Oq8T`sThXGKB0Q6iasBgZ zcY74HIp>YPYFYKSyzU=ppSXQ5<<-cGPFs3V%@}my&aNKvIWJ}(~G?e45~2)Y!np$&U=uPA)e!9 z?@98vtRG3ifvn+xpjHz+*j?AV_Y_%Sd{*?s)rF2HwX7Ns)xu}vkIPd8Q7^>XFAiup zT$uSMt9$C&bBXTm)jay#d_6$9Rs0nbWX@8x;aXrO zcr(bszgM;o>$j*3xh!==V@e&CqkR1Q>~LNrsRP~_viOXW-=v7e-ld}x1)!e;j-R&H zR*^i{i7`iH99+8R7h#n{Ml8Gh)yyq?xC-lzM(BbZm8KI702c4>1FEn^)*_Fmij>cKx@}c~W&XV_z48TNDA(dbmsOnV^>5!(gMBjEXQO=B&Z%>=P+Z zahZl@jeQcT8f)ULA_0OGn|oN8aafj^ClZ7su3JX;RUIi{q5cv@AY0ipAwfY?D5p3$ zx*Y9$E}W0S`5l1mXnquFZrro>vSD22&iIxT6GdY5QX+yA9=MASQUNoRe%hgUj2}?B zJw;20eCWt{f?SRF?0IvvhnNn07QF?d!XM3Cc!slF!-uoTYYBi6yiaA8V|HyRK={pN z>!@A>q>RCwWo1ADub`(R0$(%gUJ>yH@9TKuEf6&zS&G_sdDfE68qTV!6LWI7jCRPa z-Y&&r(NJk|^VH#4r{;t!2DaOO*ep`^;PUMAi(IdYAB?+}f(Cle4;g*rjLKepYQH6C zr#=cb3&q(c=IPEGaj!@uf~OUZAfN-0Z$7Pal->j=BkiI}AB8CK7WyFeV@^z{tHI?F z*&o}*E$5L5u{g?7d)?N~JFuGF_DH(~@78qW+a*S2y*xs`Su+u#T|9VrgQXGm)?dz8?X|I zC9S)MCyF>jFlvVS0O(Aa0s+CMW*G95!np&X1Uv9g*hEEq^}QU;mw@q{m+|e-U=BwA zUCtr?t5+xipCupe8l0 z0;pakkm-eVkN?&V1tSqG-Wh~RF(Bo8o*4QY`1f+b&&X=XT<~U5s|>@ zm)hIg8HQ}8(b8_1Sh@(ax#3X^t=_q9HZIhxL^l!2l%+0pZ>nc9D~xjZ;j~VqCCoM^ zTdI0HtP0#!1b}=LJIXLYgR(u@`I{8=FsXHdOt7qMr2h*WfDoNTeLhJ1pW;cALn^NP zfSEj2y~?3O5&ckre*453?)}-sETT?zv~|p51>JSb?M$o8LH7dTww13kovKdk9u{l{37Cs+QBjF9 zj}MH&vSY`*A%Xex7o)3ODgenC$&<*F4l59?<03%IcB8uhq;4i$4apSAv(WP~uSfw6 zf^k2QKTL89oCF5N6XBxU;B~Ev@J&Ud?ij*1ixM0LT-#qDfQL_=wk+c1s940)C);cX zi@RZi7+V+>9Zd}!5aJEq-0!#yN)L*K*-%8xf}=}2+Fs9UYxS-Ot=~l|Tkt!z0I8_L zEk=oRF_CVD+PoGK2e}xBU@;C%Pu?xCnKhy*Lth)ScGIIpS9%&w7~75)eDEE?3ubi( zCGXmXldbOHXa+ltk7n0)*Cg)WOY|D>^LApK(QfQh4Hp{Uf&4TX%kvtP8?z8A=YmCa zBY3c@MiW2b16I&wDAq2+@pbYm(3@B=xDzZ9=s511U7R!GHVL(wCiYk59Lp`V8?Mo z3q=HMV&@S38BLt!A76(qFAf3c3U;s0v5g)!@7@?X;yiQw)Z-JEz4N8rS~PjX9?s-0 zC>B?J*4>Y{n9qAV?8A+TfV>g^fC!})X8hmGf9_;{@#D9gp6BDuB`LT<nUnDN)<~+?6C2=UF!#ar`t``qf6iYTe7=e@2`Y z!=0r;%o+J+`0d@TGap_2wx&JFDOsYJ8D=#{?aPLbw~mJKscG>mj`pdLecs&N=sS%= zfY^>c;PXbC+@1VtTGibH?Kn`>m_w+UZ-$0S&7C*TH{#t7vzr89Apf7sgFX`ogW>H^ zx2}Mg%LmlSjOuwpLd%o&(;{A099${zoYZtsV?J~O&5LG{w!^rgbC#IvP0M z^hPFzKJa{pJgObuRx3(MOMPokHm98F}`GgGy600DIw=8!e$**{4%VmFOL-zBd?p6nCd4rYz#D}9 zc@sclku3}yf@<+Gl1?ptweLutM4466(y!BBBh?j3`spwKjrT-$=iKjbr%g311zqdt zgVMt$&fhQ6@bB*sRFF?ZFHQMxO0E^p)G>vi;`9 z-Yz?D!(@f2sSq%mp1BK|#QU?|NqXHk3(5h}`rw|Ro##cgm8#gMt9#ip!+-`+CmFAY zKLbcL-yu&zyg{V%<8u1?z1Lucu6mv`k3P6qJp9+S3ffO}&GwwD^nN#=1=osj7P7 zriWgwZ}DDz>)-TV>$qO9clcSnL1YRxA08f#Ko}hgpBOFuA;+{MC?pz>0D|;I3pBWt z-UN7as!4i{tw)b1OqCWE9+ct>JeU0`bb9&seO)2yhDI|Tcn4epmZv1AjV5gziNS{Z z*dW7WYV-v#)@&Ain_Vjx?d6{{XMe55msLAdNCKTdP?*~x?ew@;^)v{v+L4>t3&w=JQ=r|r|Nl{hx*ETj1I~4eAmXe)%)6@>>uMRU} z&T6Ggumvfj{XfzaG zRJ9Ukm?jx!SACSj$!?aNHmWfoe7#0oMrJp=$U^us$NQs2bs(uuXKcVCp;UmYbfDI9 zk>Kq#*KEjDAiH{ZMvaeehsxU;_;gzq*yNvTR|#0L-Q}XrFP~iZue$W8>qu;45cB?1Z1J$!!s`gM%!}V5l;x(^r61 z4zEW7Z_RIMM5Q;RxXT{;0Y!5Ojc2q<&gQ^j_LPlh6LaFki90RfsPDdZZ?RqSD@-bV z(|F5MU;UHkSUXlfy{OBVA&i7b&CYH$aZVy4LyXY_w(fC)wi`NcslBie7m_eEfEq2oHc2W}@=9$wIqQeNi#M zL|Tky=ov`J$dJi33xg00lTm&o^vpIldoYeNMqS&UO<4f?J@6o6Y?$Y6eZWUZP=BR5 zwu?#hMv%inh48|P7sl(L+2Q0c+;p;NhJ*jGxA%(%t6XCib_Eg1duu*l%~?~^v$fZD z5${?ROGzEy>uFzera4&+IgNf9me<+7y~=*3pvpTGa7~CDWJn4a$+kNws~z1{G>Db* zy4O35?lCqdO(gjo>DB4>pH%>dGRb&v%i61#$SYy@rtj>e>ZD;IgYVCsxZa|+8wN9= zwn8}~geap|Y6qc5^5EK6aRmw#YE{_6xr;m~;Zk*x7o0>vlFra)kB9wX+^=`7Tl=Ct5)&Jg(g3(%jg&2U{GRu!O)F-FVu)$ z2=(B|x7?JK|U<#iBzB29i(v)Y~=T|e)+&%A#d=#FRJ`{+eJ6LW7)Pf-}0#rzt(25 zhDC79X~&ZR$A5aRUf};WOR0Uch~=ef9g$_za@1ZrC1`Lh{bJ%gO)`7>NmEWu>5vb( zz4=5hy@IrK?uopCxyEO|EWsMeeLrwV&UNJ??mR?#z4f+tTDt9CWv@Dit}&k8b37uN z7)v9?@bruD#+qBLsK^CB{t14AoNg5*WDiNAr0AW6Sp1~Ei+2}m+XL1DT+x; zC%-nznDGVr5)?%Qx$=o^eK%?><Dfkojbl*r}_1bdT}}{ z1*We{8Ubh`1_K3|y#8zE^=K9exx9jK10rP$hoe6`=_7!PeZUh*%;MH_8CdeqKT0We zW`F=6|7x&eVUW`SxIUiBR@jN&%_ZP*G{c?fn$V2C@32C!d|^8?REC3@?$52{o;7Q} zICtvcaXvQv4&DnQN=cTAG47Dh_+Pld`UD>sEM$twK8^_vI+Al3eU}q9uhO<{-O53f zKfD+r_fssbD6^#E6`>JFTB~yUbY|zJ5b#ZEEJKkywBtm;(2HXanjORuEdk0z;A*bE zJpA~Bzr4Y~{No$vYHZsEHzAINF8x{w){S;em4P(135RpyVD|D8CoiK!&3hM>Syxc&3~O=wIe;tGR&>dunMX9)pgDYK0HNTju(H~_xCUe z%ox9F-QODI{X+Qei=e9FX?*!BeF|SI{ybUr=!&<&vaeg?egdTQc&heA1lrI!41*e5*j~+)YSdSlTF7PGiRVBYyIP#5j2aB z45Y}Y8ti!GBt4ZRy}Dc*tSH*qKwS7$E=?!%v^3xYTeHFef6MninGLVL#|T0q*I%B* z(YOHmZfdBIong_8^{wyE^%kRK#E8W8#N4Gmj3?WJdL@x`-Y;dWzZ7$ffsAjq?50_7yv2y zo_1Ux7REvBY+$e}!R$<`z3k_AQG|1-Di)_z5F*n@9H25JCX4pG)Ku?9BiqEctuJY!Hyt3oz!=kyZ*H2h^@P8}}R6b>RH6p2XvxuX(55^)$9(Q|cU%|pimX#l@ z)@8XW_rqr`SK%h%q$f?$JL77)T(OB>V&&DStd?)+Q*w`1ARR`=z(~#ACT8NenGA1&$Lh8?SDK4e{ z4_V+1SGeKQS<(Esspytpvkv$O3D{8>(&i>U3wX#XU5<11zfCx`!|#>8xTxKFar?+r z-N8L3r=|rr><%k4V|-so%lQSB%=~q;^Tv0NeLh#Nz{`_kItQCg-hdu*_^H&U*!mz% z@cPLpv|G?1;f2IoxMPzu4FZ|8P2o6z z;ltWqe>7YTARIMJ0NBmI(%oq@(qNTR3^q|;s|OG9YEC@)zSW}}vf{bm3y`U4C8Rbq z&QSlIYIz$@erM!q#J{2ur-t^g){?K;Au}tPSg7(A(iXu6u7t_irisy?!Sb60<7FU_ z1F82}sN;L0_9^qLIgbt0Ic#;SR$qFZ1}`Dt18F^Uy&G_R;0FOe(U~S!S@m7yE#6dA zI}GWcj$2+XYPkj!fm9T{bb}xdh#Q~lS&IX>+Ay!N5Xwg8;2ix4f4HJwv$-XNts zV8Uk}a{~ywQS--(4vt)TsRe1gFU78h9=OVVa?#b?gxFa3fPmc(-L|l;-H_G3`R)PR zMfjgm4O{Imm;iI4ePoNROJsW|Y#E{lG@Wj=rl3KSnV^>komfOntSI_}7dVb>9z2_g ztWAa}IBZR!R(h2qZNJ3hse4S=*)qH1HQ3}&e!iBcMST6`;UNq-CYxXy14r+=Wn$bh z!5Rv(C&M4_&`t2ppKp=s{oq^noEkD&8Fzr&mPR~~-~4d?sz>9UE*llq!YzU&>kx^u{U9N8c=BX4Uu z_XrIj{=wjV4rH{B4$J&*%Q;BGbSM?~v$W3o>xu9d4`Hv7VDA?ScV*%W9a2tsX-F4U z-cU7Mk^F3iTg%L#EtkxeJy;x4f4X#qmW$JL73(mp1(lXb-uULz z!{0jPqT!`jM#f3vaBQuRZE`BB?bA&MsV9s-)rOWCf(A)e(Ic@nmLX4MG8AltsGI)s zVuS{xa?4tu|cC}^KDBSf1yvc z6U){7d!8fb+I5UKN(bqza#vIBDVw^;*&V~(&W3YOpZ=)(9Fq8Yhjad^@KoCuqJ+B+ zS>;&hGc7SsKJ(m7{zAE13B^(hMTWY9eD$WFR-z|zEUy9v2IBiBDIluVt6x6}Zr_DW zQ`FABeo2*LvR0G{OLsCGqiX3|9QVY|a7CP*xrM6gtGRRLbau@`TIVfzLsvrB&1hj^ zmu1eE&Xi4cS2RRK8)&jNzteaDOVb6- zB?IE&e;UcL!|BNa$`WJJ4r1#Z#g~dk)W)HY3nG^-N@pD%9T9{~@cxyM^cfk^bXPt; z2U9#yq-74Q(zQ<*##`s3!Q4AV`t@J&fauTR^`E-tD+@#gx+N%$m7pMT-= zaD3^S)vHrMf29L5HZJZwMARUb?a|lw?&`86>%stqUjlGue!A<(pHFgJy>A|#YO+Jx zQg((ns_fwk94Pb*ykF#(#ar&tPiEWGIKah3utv5#)Ra89a`grksTdte7G}r(PS7`lwpu`NrY26*{A821X>!gO0XP}6`avw zmtFL}8?a^}AZVfKXB_Y>sQL3CV6zXxqo}-mCim*KaY|7=XbHa~XOJRiyVg%NsaJWpjbIelZL z-W-z+F4(Dl2F_L1##yL|NLS02@W&6-5igD}P-yv@`1`Y?vg3QhQ&JD5aGJ6x#V|4mWY32qG^YF8+a0XFk2DPQY3O$&qN7V{ zI(e1jbmSiW)HORLCk(XdpsZk0FkGA;M=qqt8IkGwY6&RJ$O%fm);}~d(#V~>kX!?C z5tBt|7Y6DU?$r~@}SZNsA2WVQuuu zX4BiDz>+B8C#bYontz{Mwq#cMIg|8g{+b5m05jroL3ZAhnzr((B(liNTiaUga@E1Md1uEGtAs*B@D^ zC=e-;Y4B}%g1dICvR|yKa`sFuLH|OLu5GGXo=;8Pw^a7;dkW5^xK6dRT6pt3)^ zwLUS8(Tice-0XJNy13U$RJ4l-lkDggrsV(T!j15y z=tkhOWXV_GZrktlHc%h=^lOV6%S<4FXkn=! z7K6P)LU}xpqOP@om5CEyZMl|}m6cqbz@a;9B@dTqhGu>~{@s-TiPrhQ_Pl5F-pBg` zJ|(MSPPk121tHg36dZ56@~kW^c|j!LQ5=1fjDybGJ2vBAG0q3wJ?=}Uq)N}-w=n~8 z%KtOUWje)AHd<%hcbgc;aHH@V9(qcZ&-l0lSFfJ3UH%#{usQAyL-F~q^?&^W%FIpV zc`!QR%JChuP_>R#Ka0*RL!gk#gEjSJnDDqCukVtDCGcQB5D^Pwzvvg>^X_Ak|h4 zpHp5X$h8;-8DJ^2C!`P~b5XE&9-|BN9UotaQY75@$23AdpvD2Uw>ozWkC)sjDGh?E z`!b{{WYb6!+)28M^RyKe1C2VPko<>hD$L<=|9t~8QLuleG{N4Rn(mv2J7!aH2cnf1 zwBXP^N%f8)cl&TzJd8?u=H9(~%=)I2YyejA^jR3H$@XYzoyS?3sy1?)qBY<2t$d$+ zBfno*rR>0_e{ejEalfn0ftf!B35Yx|Dk>Zu=2O6}F1e+mhxeA+5wqmY{8PKQO<1aC zbOK5zVi;m2`i{PMKWzY0ww^jAOTGVdy?OI!+{w?M9w8y8e(HfnGu}Hf&V!a6Nwg{L zZ4XpmNYhR*K=NRHzC!Y}wOf~7Z$oQja-bHxYT90khd-yP&++}4sf=KrF*}2HOCido z0Gj=j)13^&W1asZMH?@LZn??hZ;SaH;5({nN$>zQ`B&uLPcy271hMTGxhbUO3`G7O}!da0;9eDtVFO5KC> z^jUb~1Nq}%fuKsmZt<%5fm{T-8S_m}#KSuf}=7H2Xssol^IfW%(ZI=8Z3yxq;6$ zmzAO*3CYVM`Pc!4FpzIae?{mp1-X!rc_2V-{(Nd+qSrW~2B5kb;MS|J@2<`& zbnsl>J=GoMIUztpXz%o4@jZZN>0_vFg!S0)l(aN&vguczcPQmyb>Eugsj=8&*9lb{ z3kQ#G{C{KMm3;e?`NoEB|3Bc%+gKSduhg>gaw^?Wz>}*2FcBJpf#~Z|cZ~TWH-mw1 z@q9cVy$UF@^c8IIWJ<`J2pb-7dHb{{X#H|x#v|lPR2hFhB^O)MwKZkl#vcaPmQ(8A z;qQ8_s$@8NrvCYXQ-wdSYfiX_=+$gUS`m@CgO~kIDU)*>J*+SO?;*1yY7>mA*E3&y zM-YVt4c!0@VST-L^~!o>M>R~82*rW+EHgV3B&$S|g7mGN-jkI5%rqcoY8IKlovgp>2<&%*3y8rZXRfz>-g0t{Z_rqRvPRbQdh z#C~OdyvEY)3fc_v+nEPUuJ2?#17Zxu}2wxyun*b3uDh7_d4TqGti4+ z+;Q4BTM7qhOkwoubkIRV%E*J>#D15lnQHbp`;OrCt`zhmkn!;9`An-iul%Ewng`;4P*iaRoMQ&`mkNfCvxQ#mxwoT# zX|DXsL(AwH6mjR|^JH>fu^uFUvG=t6#5c+eFuE@l{ zeBNLQP12_MuG^EC?(HoXi2`3tUS0^AAH8yj zI>@8KUxZ{DUGAz{=s#V2)xA$|Uwdbp%!e;557Ry-^s;O-iu*V-jN8a>W>5_^0kbR) zSZ3tx8Y)-@oN7;;juTpME6qx#6U2%GPp=zXpDn!X1V_;^59p1Ai!}BIV8;2%W6y!F zdR@CV3k}!8ii(s!@-Ov5#Xbx(jP&RO>nJTI^B88?Ng``U3U zfs6w>q(QGB`&s&0T5{jck3jtqUyb0Xq(kD5;g!Fqbg{`0Vtn{wUv~MFCj9ZJ+|EfEms#iyT0grX5{S z$^%y+n9_V-k1h9)rDg)&BCz4z!=pSXe!S+dIbw=EK!A|-?mm_az|dzOjCAHm%MXvShMu-#wgugad8R~$!`w6|1>r5$rsM}f$2MV1FfZdlbtu> z$bo$2tT8lms;WIkXh_4!`}p{F%^gM84g`zH?(wi+{;eo`&fsF%J;c0Qk!?P$YS!E1 z@AZIF9YG`^=J4i;QG57k%udPsB^WGiWSOxG2{82vaTd@#cEDxq3?wm!ATmO zdH_F=BPrDRS97UEu3FV7LE%P0!w#Ry^nB3Fue;)9CFW;KsYvvmn=e>3_ z7AlUc=7?RBw#p(oL2`-REyR4-We6hsKixh15iACakp5hOr|jdL8yprH23WHcZ2%4i zB$QhW3XU{>8Z<3!%U>ee^%yI3uk^&{3sbVh zH)NM(T6{Y?HTB@clrMt^&YIS~YBn;&#=oObFts9dd1wJq9HCL2nURy(eebDhA$I)Y zka7_1D&q$&c$}P-Rlmh=iBYeJJi#ykwC?L=x2%--#%4EfUs$QMjEoojHZ?6PEi?Ll z*$iD;o?ei7R@h@AKvT6NI^K^<$EQkh+ee#yArG&J$jWXK_3)NU#wkv|JkUx$1q0X6 zXjdLm`X4`k63Tc?RuBq?+CMc_jh240ibarYgTlJlKt4~`h0Hsa^2Ee=4in+B%uU9* zBP+sk(u6wFKl(X{hz_Q?O}H}JeFI1suxEomp@5Dx(`$2Q1<@^-O817JOLeTNt>H#c)QTA(fiQ*O8l)k?KkYhsbz&DpQn`bKlW<0YJmr*EL9A{>fnCY5 zF0HzfC{T1QxlD&&mM@;Yu{r%2x{@qBX}WxF*K6I^8=P9GFeQ-MYHO!R`yIW6b#Zbh;uYBqELlk{4&n) z%guy1Cb%GE7S}C?kvREtl_$po?}t;Wz8|aOU1T`t+f?T99>bSHp5C$BQD4(7(%{pB zpwQ{V6dYZwi|Px{Oi}}|#`?fjYQH$o_@qPJ+6apCesJ`8SVEzkZ1}v%IN#fa~g3KGwopqjn+H)xn?pxBmNk zkmc~*6@^v@{LShvJMRlot&Se;IpJ0W+y!I!xV|=Ia8n5c+YZV^cVHGJLw=I|T{Y#! zL6Z)qTI$ax;|d>3HAm`br-9NO{odR8tABEC$+OoGi#Sd75~ePkdU=lff;*8qrO%vD z&mDajiiG!q2pL35C&h^ke|=a%nGabTKt-og;5tUQ4LHJQ>j0%uIWMJ%*LBHInv$p! z8ShaaCDo3gY1(ro0Qj}_-RuKzb@}`P7Re?EE63XF@9a_DWdZ&`$xK!y!>fYK$>@8} zmaNTKQZTOT&RrZ7Tx#VQ?r?Ces&xh39CZ0lzLy9+Zo4Ej*-Q3Y|Gp3@c`77FOkq;i zdmpTv>OXfJm^&ZX611E>U8@DF?{;tgm9w?Fc5u7>pXIC3kJ-9z*>fMK+)PYCe+HlM$s9lBX!N{{T*4vP(e0^Z?)k`2_&A+Kle-**eU5 zSB3RK=O%09>&;~l@~w0qKDrTOCZ>#er7tDp-G z3=Q?0XX4Cfm%V@?`!ej+?8n-ZQ97vOu*lks@lV=&qdpl~gQ5nMuDG~3SvtzNVCtMc|IF3{vQh*!gw{|QoLYuq~)aG}O{D8di@+kE40^myuh7TGW z@>~EgrL%W$I)CB9@1j>o!Z!DFi2XV`2l}YuhPnS{ToI|xab&u$ZFKMKHQzrMeV9sE;ns`wC+~TY-Nvgobk=(Y z-IkPE-}y_PU5o#IU1LH0Rsc8EmJYrqEy2mV>$xXe8fBL3ZJmcR90ktZVbwSAsIqY2 z)9NOhSfpXk(bFZjF~}6DnH(Wu6p4qe0`FiPv}EdE-b@Z~&){Fp0~(jAx;hO$m5@p4 zktUiBNW(Od8;Md0giF@R%dnT2lY`BUD!lCFAK?B;I;KU=eJpa0-=^>0{bj-p(;j?) zm(CRQBVXLdXh7O_RWD1hHm*A9*mqQiw(8ivn~@l=fmwN1ymzSI|}c9mVw_K&%j$l)&NQ4Vtx+ZQ(oscuKtN z;3}rS9IMe;pG-UuSelT9z72ZZlsj}u!^N^z=|Lq~kO1EQOI51r7|HP%9d#C%&H>`r zekmSUS)jLj+nHR9P7d`QL>=_Xau~b)JL)ATmhPt=QFGqNr zg+%twP!Jni`HwU&lR9$hK6SwN+S%FlWfhFgKvoFF&eifx`gr`|p2xauS?%H#_Cu0O z)Xu)I90y>+gG2_HjxL1o^R7-zt^gZ%|WkX{yE zHn}hpP24>9OzEqVL!|1IJdXV*RO|pEclDaH*ic z?P0P?#+*Ng`RWI!22)#tSQ5P?r3!w(Sk5q=95TFGBi{jYbrK*91VAw zivywr7fI2ST$S{C!+}o`XN){>aHP@vY+TrZr0W1Ng=`)_{ShWbzyvrm3PfEXaxj|V z2LTQ_)Pgcl2xylc3qvj^pp+%N5BUd1Ig6?5pOBK@U^xullP7W+nz|$aWb|wr?{M4!_%7Ce1Q*pu|NGqD!NHgokK`$abQt(yXKj<_ML-KN9$KX#)QIg9Vr40qYZ#1Aefj@Xq zZU$B3qXyjm&+nkBwBa@|cUlHaEt`U|(}WXY@?a_62#qw(Z7y^HoJVa7TD?F6LHkf5 z{;tG|#Jq#C`Bqy(kmw4NJ2*&qhk%!yjw`>#pDc|goS}-9k3xo}O)LpbNXfO% z%@P*&1H_F;0)KN7!x7zu3N_~Om*_ivND&Nb!`E305(yeCMK*?d2O#Iq1~GIpUO}c$ z=84FXo?@mQvrYL15Uo31;1aPgsIvfkA5e&S`=t*zu3yXIjx}9p85*$pHz%sx4UkmB zNZIJ1$lZgPz)K+YQVyro{Goix|Wp!GxWmaK- zZyN5n&bSlH8cA<4{-cy*7*hyU%@wT20}FR!yFd|6*g|stZ%Y`~n*y?Q$T^hZnJrca zZZA{#qoo%s&L+bcJK_DAPr?WhDK)+Ifn>%i9U>+!UTS#;BDTulaRaw`diWrU^HjoT=KWgS^&Bvh%UzmagRBGjab0ne$~V zqtgnxkS8=PxjFnOF#``38$8MEc8qL#6#LpfPJZt}-Wl5#-ugQF?5o6o`j*u@efXD; z&nV;+sr=%=m$AMg|DJl)Ar`sN1(HGD7rCu-&zCJk%k9u`9_YnR5SS3(=~#vVFgTHw zd*s5=f#dSq%BFNXu@CK>cC(XfOJNzt-u4!sAbaL9ZK12$T@x)lK8-*_Y=(K9boiDxu7b?+|$@7#c z7_I8Ee{*#ff&+LINSj*{2T#OC-&gT6kXp0ou+gq4?fY<>PjW5r-x{S& zGwoo0ddK`0@I25Dx|#z*M!-dbP|FXYA@b$mMz`@zTwGkJnJZi67A{sMpo6ayRBkkQ^rEsrvD3na9dSKAfC(-D?B1?xWJdS@gdu)(ig_=dA*<0@7Z$gEu z-F`{zU7tF%a+$k>TtSod#1ZdgeqrGmTKqkkc{o9YKyD;6GDLwiB*q+d3W!qQ@&=8c z7Z)q@vL^(tI06X;n$caK;uDh74PxTsxppfI@I!Xo3WEl0?X1^+{~#j}n6K@ou@#7O zLKGHf;3KhVcK62uB7?Z?071w9oNofohQ0D<9H;C}SUI;Nmynt+i)Fei7 zrZkq^AgT7pSk0*Y?|zGfoUU9jNGO0))CHe4x%pBGbDC&3nsZ7Ta=nGR-OXM7#W*h; z9DKX9H942bUZ9^nYp7+yJ;2QMkHD>rOc>68DY{mG8Hh?v0x^henD+3jRGAy0m zyG^)&+xYC5Yy|w^gKaPDtFp|1z3!g8pM}5!MXqoBby&qE{2-|7Lyaxtmk@U0@hpt9 zPNdp0L#6xiT`012IRh+TVQ3d3qy)|U#*rt8Qcm^End~UvdMsGjFJ6Q&D4~w(Y&!q& z^b>=vG7N|#2nhzYwkiLlMjbRHLbGO{30ce+m@9YN$j8}wZMEc?hjOOF=a${S!5zEG zTjEU@Z=7v`S(;|l$L}6t4*3=6#LR2n;2vZxSRrt*Yv$ax-f1SgrG7edUVXd|g9x#?Wvrp``;}2;{t?Yt}q`uhk14&gZHq?r#MXt~eKC zp7#9es^KO+L1)^QgD!FCdTu054#BHntr8|rLJN?dE8{CvR6C?)e}BK}uoo%{Jg}yh27s9V7$fIy6q0c!e-R!H|O)#@sBCKP&%RH*)mbCiBys8MLa}kj4~I zZibv2EPyrubXNUi$D?X2k+YwN=Xmv*Z$It~cjtz&PI{xlO}h_bA4*Moe*M05fFqSm zYUUX`5yL_mxHGBd;bS8=O$i>Z7VRCflZqm(&kbpDwgBKIR@ zZGB8FK++_X0WgC_XQkuE@7}M1aLV&vsNe&Xzh-1qcc0M|^z*dTz#PK9og82s(*dr>@gA0bmVWiU1;m zVDrO=?;!x}boD2p5oFs=sDDT&LOT4N`6Y94y1zT6CZ0h80O`il^Joo&)p!-0ahxW^ z#-Ne5@Bw4CInFbh-%yS|3kn+=Nm^SU20Q^{aL)sO6hKi+WPGajaX8COeL|I`>!v`U zTA5b7I$VuKtrtW@-W<4ix5|<~IQJ-1zF=jJ9SknY$4`EmssFL>))^B}HWHq>d~duZ zde~SJJxtCj$8oT_XfOsCh#FB2>+@hpb|)(XzyfsN&2~j4P%Kjy*crMiaGPC22QVt< z&_oAuP{7ZD6T7xmc9x9{TrI) zETxxH!6*2S{sMDKIT*4T)$0affJx0cO%!7k?pUS?^`Q}XHB`)S%NeT$WQ6haU>ndBS-j{C?_CCsz%e1#xv_EP zgqz1kW-ZQ8+@b7H^K!J4NY3_2aRRJFPBa_Wo~;sODCfk)!d_w{5hWP_NgG&U)EW$P z8$W|q=`@^25MXhDN?=Pgpu|KPlk4>RON>xrZ}z9KBB%#J%I7exj@251z$*=dY!h;C z2#JQ2Q}(z*Kb3)E;Dp_i&?L|f&%^YzjeZNX=~NJhsf5Pr76+(s{A9F?i{oeH$m=&e zdk%bnX3{B?i-|_eG(8&4Unp4lz~;bMH2c|eA~BByr*tM2uw^KeEsN`McUbcCU7l~T z?yjUbsqAA7ih<)9EycMPfnXQ>c$6&Z8@n^^#8(qdG@QRS=gtG`B=vtW_TKSS_y7O+ z>)2F6q~w^Fl9jA7vNDS7nXE$D*`ja~rHm$0DI=m|95S*G6|%`FDV}#WZ)gN`_n1 zEVvfv-!Q$(krE* zZrY$2D6=zylMh%Aa6E4>e24i@W0GxYH@KZaL5GGhq#HsD#z1C;9Bg1NCp$`gM;aOs z62px=G&Xk0_vBhEnk2x2g%)1|yaj_VIJI0&2X^g;&yGGSA`k%+M2R^buuK;b_&}-` z>ong(o&|_7u!Cie02KJGThEr^7 zEMKZW=XHFp#>>B)kKI$dTNj|!*w|P^NdgzO&?MP9lvl^);;{*Z9BpX5GLaVV0l)Ml zt2!zsP~?&vP*ggiiDCRvhP}tgz!Kj4cGC{BhN1Zv+wK9>)upePg#)67ygiU6n+)v$ zg3rLXbNhZYRS%$z!5a&jEI@*yDK0L?93A|xU%y5np@{1Rg9)-ps0Flp^o(IqXK&1g81gV9V?uaf0mRQtZs}HfQNE8JZeF%zbO_!NXG*S*h=s;fI zRp=rOrW}dOh&94IPVS&ER~hWU=TP_FEMxPxH;egPX4&b0C#e~@7W30v3^xG0$#mc! z{O~2V-r&6J8T>BODMsEu#>U>+ikp{?Jb{>sZ(xQH9h^nSK6n@4@j$FN^vSh=uHA+9 z_#MQcp$Y}k2#&4`!C&EY=qhXeYixe|K^h1U^6KyVXb1dwo(VUWoOm!+`5{^7l8G(jUz{K98 z$#5m#UhAywg=wEmBo*TjzSOtjm^6<&4`TDl5$E@yK;w)B@1XkofGry5?RV6 zjD%v*PJ5`619Gj>tk*as>`zq;cQqlUB7BQyMc1Kcyy&fiEU!@Vvf=~|9paajEomtQ zj=TmO-q~?hgF*Eh71N71G6D3x2D;wp?s=%$!vH%KmndRazTZAH|9+32)Z6BprF^)K z&n~b56?8c=7G`#RQIV0vB`zd>m@Qw@Z5$Ssmw|l+^bZf}ICozK(&7H5{j;W9gMxfA zr=mY6jV2PP2|V1OhZs-ClO}iUO9)@Ts>*~V4n|zdX5_7$m7Xx+a?H8WGXo1zu;BNxhHrxd~Wwu)@K?-|`RqPI-Tj)1njhz2uzO z`uMkz#0Fc39iQ`6F{Kwu!5deixG!&3bqVLv0-Qr?X`Tl%1hPS@0aq}Zy9)Sm{-6sx za(F>tOjg{9Qu-_qq7e8&;Q~k8whqnLpBCEA!Vq~0Zya{4_EypO@^w%n ztyvt~WgGjLLIYGuh7AsM%dr|#7vqgftuSJN;a#sp9ATMG)f)p*GVrSyL}eUuFPo7; z?Eq|pNJIInqwC#x)7d2anD`6 zW5P#JOsr@!wCnRa#M*=UwBnD_{fLaCAMS+kFTW}@zY-*&xMn&@BmK8Sk~@RG5upcu z|8%WIVfTI;^9W%X9766k=qt_B$O{f>X!0qSf#QFqOkPx7S7$zu-B2@@ygTAu295h$q$kh#i zdz=G&ZusXrz+9$Hb3t48$AKAU72wL~$l#D*vI|uQp{weKxfr5;HG0PVaxuO&m2~mzL-RS+^TrKN&C7yk6+-6? zZ?nE$G;T;T=;7Agz4XxiL6dJC7U#63_N!;tD|On}X&A_w!7aW5_7q@(k;08Q0#LLj zJfm-lmXVthiW7jVXfqgcV}dW#LZkVTgM-RJB3{Z1E)MJrAunE;=tx76{YZOVa()tE zZUng@NDGc(M4O?-tDra+$vp?iGYAS1;A9M?4-mXLIEuXex5I1=BIhkM8sA!BE`S&y z3;Y5?C6VbCIIDR$CiZM?j42_D()~}4(do=#i&{xvpGN0QiRP+ZSNSxm!E`4jVtKuV z65BiYWzS{T6EWx}`*GoLpypcHTRFr)@_A{>pBbjrEJ~5QOuD=7N0zwzIkNML^c6du z$GHdY@)UsV6U-p4NgTATY{RZ9;ctMn^5zO0=S7{|FM#c!0R|8o&1zud2I4;NOW#vj z?}JF%J?CxammCur>5_kP0ouaeAFz)#@H+xOVZ?UxPTVHCepuwEn@yO5PC69S`rpB@ zcnsk2Xt2d*0p_yj;295Ju!8B@ajA^+yZnBiReVOSnz$Jdchbc<&X?lPnYpN{#fD@S zpDRN?NBZqc$qSo#ob2q7>;kXZQ|Gel2DA7uay=KXPSyZP`EuqvqwC#xN)5wXuWr`v zrci$T0uJ=iU_1#NO?C6_xJkLz4^&!>Eo>kF`iU+#pnjk(l>%-8w1BsP%)ucMpmp$? zgIWCcU-9cS{*@?~UiABGS)VVNf`AO<&{Mo3HuCU!?FW5=O@ITX3mx_{9ygMqwcXjCvQ7;k%#xjGMB&Ul4+Rw3AOKxp4Zz>W*|~ ztJ7(Q+ZKFC=kx@c6VPt7)&?d(e{@~Jxpv5_#3w83)5Oq7*SwBG=TQ^mQ^&Z$uE%b6 zp;;6$&$BHOp`>I+^Y&GWvC4bhN5c!6a-D>Oh3Dw8x4r9h*bv9uNsLf&RvrA1L&+X5 zB3aSzRr?WGrl)=EhUI`P$)s;#Szq}uJ6Oa(c=m?MrC-GjBTg`ym!!?IOUYfHBy?py zhw_`A7sjsLf4PcD8o)Ffkcj4pZAUzFLh2|;w^3&Rq0$lweY--uwYNt&3J6h0rY;`q zbJa*5azMhLyy%oc*}eSYoSaUkL&wKHExULAJo3%2I!<3Ppb9=RM~&^vQe?o!zkA~T zEJ{2Y5Au|N_@(=Q#DxE@vhQ!5tzy8iljru6S*UQ=2ZcauoT@x!jmwgx1_|%yq?_^) z36$p4BXS^Y$zYxJd{9wtaTm@yth4WYvqDij=LLSRW57HX1`L2~RG!4L{hZOLFu_@d zHmeQ8Jf9)Dyqb{++V{w{~kzi(aWnD3iKH+b(33Jx9Sx3p4kopi~+ZNPA2WcF^RN9@@CX|cH*!(SYLd@V@^z8fu8fcAt2`{&T1VZaZL0L9q$-L2Q| z0DKdj3nr60f1#j(p(kQ0*@M>iif^%!h5U1mUcI!KX4lzLJ-91pPm-yHT-b;cQM5WW zW)|+G%NrGs=2u_KU#M0n%6pkl1MxK16t48f_csD3<7T19L`7@1y{o4s#W1rC!Vh4a z2XCD2OJkuv%Q0a|F2HR|c)e*w=5ET_TGaykmLf_;IwL{6fWxd5THYC%uBQoAFG=~u zuU6+x8=A#xbRI-<21tgg1G%!5)g5h6lI{i)sGxZYG(E`61M{HhAc_Jnd9`^~z3qUy z+OMlAM#@u^Dk_RXnDX`RAYDGQ@t<$)IfOr(W7A#q89(TD0;3-LKa^z5P zJV`53*mhHc>B)u@gYEKsQ@+LXAz#q^Y#1hda^Z8<1J9dvF4%gOCHCzExwzk#I7m(n z4YlaGUc=SLgHENnq|Eg$@?)&b$Bce4j=~&TsXb%~|0)K3;ba3Mht;try;2py9@fuZ zv||iun|ttW^H(&M-Zn%E%)YVttIUh&Wk8~>e*KbasZjkvAFQzv8nK!#T$XPk`%$>Q z7X=L<>`O0a^W1(*P^Las1Mse)t%l=}e^ zT-dF403x?OKs-TKQ5Bk~-@k{4eHh4k4HcE^T}vdHq9Dp-I*!D0rFl(_fk z8B7@hKCmJ9QE-^X)tR}!bClwPy^V=-zUZg^b3{K^0!tpmqrj};0nM#ywrMJIw}CIi zwf7QwKos$nJk+E>%`cZ&1Cxqb#f3axVWujw7*EdqS+k4hgF6p6{T=2DkdA>glM>KomhJRg{3owgUcl!)!w20sXz!nd2eMmJ0Cl6)|Jo%NG z!X6LE5rb^np7a?|p?rI&r&tY;E=unNl7aTF!Xh06+B$jbfB=*enFUZ91aL&CadUQd z7HKszHb(t^9ddJnofSmGtVlTo9AqdwW2_+?3$$o{N8lv{DPkB3vqIe+{B}=Bc0_JL z^L+c$slNY>MuG-IqaTJMV&I(@DO7gA#{tY#0-0veZ%2U*e$(dKRu>@vhy}r9Fytgb z#|h2RwWl+3$h48|U(ZUOw1cZZL#Mh*zb~;Rp29rw#*;l{uNS&{AtR^P56NWYVQ~dE z$UeUP@=^>Z?to`&Oz2qP+2GZp^Hj-Tfjzfh#gUbI!)cZ<;@dtc8=@{NwP?tCVB?;N z`E_Cqw8|+~n^*X_c(SQc>5-yOOP-4i-{jZJd7Rp5`NK}v9dv% z`KFe3fGP^<6u!eGpC@tvQh70CTE{?hC9Aw339e3`}#C! zvz|RsHopB_U-|Cis!fxzHS;b33>2d2?;K{Tdu`IhYfUK?o_M`o-bt^>oa%@&Gld370Cy ztEiK6U{V<0Ga6T-Nh{)3ILPvPlB;+A5B)J;nnvGL+rLo)Akwa8gtp2(y{7YH180`= z9S5rO2PO!yX%FQ-sl8rIy4TapTo-8hzPf?y_&NRA>5gfaL;^(xcM*P*9h2p1slvbB zvj0}8Qnzq-=Fq}OwQGNuQbU)?gIzKX?lo2~2B}MU>KX=w7piXkxs|tIXJr^!T7lePm!Ao6j{&fD*G?NwT{ zSpBRt>R}O)tC`AMZxV@o_zs!F-|KD?gU4#3ZR3) zbM)Ey3j}$Id`pIT3NS}X@I}hpJ&@IkvKSxlbMkRCFknW6Hy~b8Z~p+P^1sBI4f+B% z2Kn8ya&w=UKsW(<0R&>a1$FO~m1d@~OzBq$M1;7N+h9i`Zi2q=I+P3842mAHIzLG1 zz}kd6f^k_`;ZvW(Ullxg>$1os*nD6PAViTi*cGj%63A zdLnPDPV}0zDtzd)R!;gIq00_su28rvy2u=kj1{px5EQ+%bB8gU&AjttDJE8K` zAdVQ4tiC}dEGl^p@)@M?LK-^InK5y4Mgi#|{WcgLPqerfX}?h(6)blGK?c{$v^2EY z5+eYoa2|F%p|Kh`jO!u5^+Ba{N%e(}7cmh?&Vy3r8!weys{*~>E)?|#Ky*dlmD!Rp zR0M}nVB5uu2N4(rCl5kF^8!$ok3pRmpXQ`)Cx6yNi%t>4VqB<{Ls#JVPkdG6sHahc zsA506S3=wS-gs(KgReNphlAbjTL901ZzBAO22-5rgh8eqIjp}2$peu|4k`*@e8`0Z zS0DmZlTeHBIbvwr1^DO$x7&pe)$vFo>5UOP(&M{gczn*&W;H%@;UlnRHc?`hLQb#z zH=dN*>{rJrIn!d8`&$u$03EsT4p@bhUI=*v2X(sI4cC1S*}b{@&CM3C-e1)~-m8ek zBXu`y5mtdf@`@>eg9ni}3;ExW(&FzJJSI8>kg7*N zlY=Xf0v+s+!H9?qTR?i)K`)LDe38TgKzle)@F0S>kueCx8A4m(mD-2MW~7bSKJU7S z>W9?r;i12zwaF0s6|7;JRfDi*u-N z#2yK^E0t!BabmR53m1qmwrpQ0v&Bo^<=$B=`hM@YXi&V=K6O^JZmB%K^-F_F15fDI z)&d2G(jJxm^Jd51k~cQNYt)AiABOman`aK*0J;hp3V|4b%&P zKY&?CgzC#VO?5Du#~+2(uhP?@qV<+=ntn%G%7sHFKlUAZZFetsHz8g>{Q9JwY3r^f z#W0-@{0n^(s_Z73&C)W#Sw^8|7tzv1xE>b@U7?#^⩔kK)CX@+KoPx0JK)R3I2Hw z$fV^`8IR-=D|;VlIXo=XNsypM1eV1Lk|PG|>FR2DdF6L4Azqmax~ah8W1tuUb9k-u zm)Jf?9W*a+WQL?X<2f0~>=zjpZIa^9NpwKX?NLj?95s_@X2_jv$65RJ<(xSPVTfv# zrnhPs64TxoX!L(+jG?)SSp~QasI$vu_1N-gj z>idZeFBpk=#okVM#;D=%L&!&NF01)YM#fq=IMLAyC^AGsm;Q?|O=fJz$yh}MV#?u} z4`buA80adCKE?+W=7E@jIqc~5$-ozP^+zeO24_}5qVpwx)yvcNYs(W%?`i zKTV0tMqBjQ@oRbSMQh#Qi3Lu;WVGEQ@kT}Ry}nhca|8{{4oE`VWd zxt+FtIJuRTWK{eXuHqDkl?EUX&Zgwbj=Zb7XX^%!s6|f}EWLh|myAkau5r8IzI1HV#|Hl@zK|6O6T?bI~W#} zDy84cw75gkSG#e9PSwi}?k@?z;kFx8qyU6Ye>)`+0(!mv>!Wy5fhy{0rsF7`YHnjU zG3zL~?w#+J&$FIz3as3Ltt}(AP)|XGVv4Hq9i4-s)-J_*u}sxfahpr=PV6DZPbkbM zOK~D;w#uPBPMjHU8A6^N(YO>7%fk+cC|Wl)8Pw9+x*K#hoD~Qe!#{yOyqIa7mP7$2 zvO5j(e&lgw)1%nXYY(LilOpcRAeE=ams55J8(}WWQMKvI?>1g;cFek;;>%A3hi&5= z=vKEa{1BG39aGX)FZ?&b$sz`iCg3wAvIK$L0;eFoWDbg#Wi-MoM?B4~cKzn7Uv$xp z{&_V_qN;t*#nGc-Uj&MRYKzhvGT!Gkv|xnF-9bA9C#{<%W_%ei2+ZotEM&G4gMkSC zAaV7OlvL;6S|IyOfWS6MW;7p}aV-dxoKZ5{NnRn`PY9qoA56R3c1Hf(PHZ339@|g9 zVbtSPIW_AF3$!6;>5au+a6W(@=S+gc2Xzy4zk(*A4gpk8^P+fIUCR!bGC7yonsBYR zo%fYKW#+iH`~Wf&-sUH@$Ai78w;f+K<-B!T(SVKe1S{RW_#`6&`@Hhm#ICDX>~WZG zg4nO^hv5EFVuLU(=HshID{?t=>aqbXjGlepJ{G}ygr@Rr-GGvViS(~eQlnnBS+(gs z<`n2%x=*8##KB?U>7tOZFtR(mP5O6~qJ{sh_TwTX&s03&P}z4)^xl>vrYuTS4R7BO zt5K5L=+Y@*M4Kh<;F&rV{*==E!^}jO_srv>JzYmJ0@w4iyZnAnjs`F)&)`>o9Oq2d zoV^*c1b0Hw;miz`(`lWFLSp7_t24A2&3KZWJ2|7)_B}UPi=?V3P4B@q4XB&>=`(Lh zuf{yiIux#NqxaPM9R@`kESM1~bOx*jrlvG{t-V_VVB$dh^mO+b^zf)L!cUqCAZ z?J2R+z0)?4_0Iz9%RRlL^Krz-noKuWUv!TLCNoShPL})0-TB@sbePaJAW5wDErs#K zfz1>kRZK6<<(((~zNOfVQKBv_7$?}xPX15;Egy!Z8BToHf-|VMC`)zXYm+Va?hKO^ zr4M`UIr4h$%iH2x#h~S+3ppYnM;mZ#st}4=KyOT0$Vy?7y!qo7tY;bzXNL;j*)`aC zvXj|Kii0i`oEnhMc~`C#a4jgBWl0i$M_Jl!GerVJs*gm`N37eS6MmH#qbC419oxSzEg(Nqn4@uqQl z9yU*b^a6Bhu&JB(p{JLmuj~H?oH9XF0dv=!YqC_ZxJ><@fm}i_BRrMIZ40)Z`Al~! zSx_cq1*jz3+5n%o5-=Ps+Jwux-aO8D5j?9Vc4|(sTz{;0c0FAGTp1*%&k~ zu(){J;xnx@Rgj26sEd_3@Afm`YybE2d8KxK)D$f~K^Spha7lP~F6Y85fvwvZYm`b6 zw;6l9gEz)6MUDe&6YYHEcm7qL=@cDB+W`NLtHOcb)pFu+BDA2LfnRt$=(ki0p8djW>E5gR=` z1GjQ6HAW?T2ZycwCaie!1zWiV#cJ%fpLjWR@~-$-4V&)fVa^rPpYLq~EN;b(wSa;M z^goP=Im6aJ`AVM|X4;RTJiY@CY{z8?$OLSjdHVA`L$1DOr* z%D6FQe(50m^E6xf(NODVI@^G=8cd}*lyTONc=d8|ZDhI{+6EDobS5KA`;buIKz+DT zmjM&+NkTc5O1k{u0hVD;dgYnK)gSx7*ZTZ<&Mt0b$2900&SEqNf0K~QPJNLM>dORt!TTZq1yc6W3p&lPUBK@cn9aril@^Ph8k;`{G`^KhH34de#MJ4`Ft|e&73)A&FuRR#Ihmp zA}ny;1vSBSpp*@CoJWz43jocM(ry1c-(=FiGb~fAg<}g{jWe-FuDP`Ls5uCXlN(g) z9dzyvlA?G;Tx2joQT`H9CL^% zJ0rQMY`htl1yWSwE>e&pdW`SCfuPPX1FG^zUSYrFW{)2xOTq5DlpuW1=kG&nESPeY zqfTV;`B_5Opd9xx^>f*p7j^d&;;1`eW)g#L%KbGsv!F}Z&K?785e`E>CkSjV$(QM~XGDB_k{jOvzevD2ol!%@PDKc6De0s@cr{22IA$`O#@ z(D{9h&##(~FTV@;#b|Ksg9jdw?_h<|yD^n>_6-<;%{Q+ET5Mevyu$}UQBW&z@TH<4 ze;8mrexh}W>~fcW{~0(;CVp)Hmd!ja8a*mJZOgv`we9{6LyUO&QAlL5-F}tNE$-z` z4cudQc<(4bs%>ORcaG6VH8N(||D-(;M4-?CQ($Ns0)6^!*l0oquof=fx9@-1y^Peq znTF$P)I0Ch{to!)TD7OUk(K;f;x(sXyyzla^PzoDyLZd@HaIT2L)_E3U?`6+%Nt-2ypE(|NUaV7 z)i+q~20v+Rk~c*KeMzj9$Y#j3u-eAtxjo~e)KLubpHcTI#QJE8C!RiH_o~~1UnpRI zeH)%OlKA5`JF)SvHM6#ebPRC7yHqiKnS_B+1q@%9EqX5y?|>5EAlvCXh`4tN6%=iz1^mo-g@;eeb#K?WYAFN zqv9*_cwee-)!rX4LU6n26yx3ty+;Ciog-4l+r-?|+}io?DqL6#0#D2Ft1BW%-3)6; zK}lCe`g^2L)^ATg(T_Fhgu*!lsc$srE+JCgmdYu1&>Boxkln)pz={2@zsDlyo$V$( zLYC0=Y}SknB1+4BWFc{C5(k793gQenn$JV)V$;L*EIY20_&$tAro00x-sc*aEik7r zPiZXhhR-b_69V8KZM}WXXc;r#n~Ba*k17SYOm^Hf6_Q5xagCtw}R$Wm1~@d8VC&tW+<5 z6gq<}WOpG$#{yu)Ay^#&wruCf;xf>25hK-r$^jj`yGb^D0)^27Jbd^8Tw~|{;-pk+ z(iuEynvFbp3QuBuT)TUPZYkWNYtg8fw~|Yc*v+4t#Q|}@)5ds%zCs9SA=bgEf5SRg z6T-l;AyCkSf#m=|91sPeqRm`_+s2)$0e6B4qx{K!^5Q+{D@()(CQ0$SO|)N*hl(qU z4H#J2J1XI_mf+z|q;RW>*pma$DuSzv5N2X2rm3qN)3x~Q87G(=`wDh}ni4700FlRR z1FUp)8KHn@6@94+*`g^P{`L*Gdv}j-+&_@8TVntF&&)Us{Fv!!_2`pd>k_=QiTBQ# z?n=P^Q7f3el3he;x(m<-2>{xJdn-?}-@z4J+ekV~%B4jtne|!UsYpI&TF6CnUkd`! zD)^v3fTJP`=0Z#vU|NU^ivmH}pozfWv{vD3>L3wbXnM1vdUN?*xI(30&Pq7G3U&hnVjZ z!J`1_cXWX9z7dh+h(;DRlXzk+%p#DvQ_oTazIRCgk+X}=T3FlxeMMin4g`wWXc3*0 zvb!lguF;A_TX5jbEWdclDc~yw!Jo_V{nKkkJ>{7{NB5~eGWCtRXE7=uO6b1zsc9e; zkY4`+AkW|yKU-sl+}#8a(AfgeDV7zreS6ADfcg>yvEb1sz98n5La-`S*Ej>YZx-hn z^fMhylz*O(sp>Zp_a%Fc($#ErK6e%CSjS=Z;>xK-M+pubDuSvvA2i4W@_`p*;L8{3 zYK#zZ(egdL!Cn;_%AXp{)E3Vn-rl(Z*&xt@2$&j?u@K2=k+*ug{35g#>G!iQpOpW4gYPw%4TX(D2eJkvjR^8T` zg6==ZjNzg~4x3!#(&8eB%SS{1)~I?s$ftH-h~%1{c5Q40Lyn~t3-f&=V{>SHa6KXJ zOH<|WoV`x`g450|+<5Y;2g4}X((d&gH&i{mZ%FuIk%4i$qV9W}&eMSSO4h3J?qg0D zd1T#sG)zrRCvd)+HV?MOK!6o803qKwN=6`wJMDA@k{hLoOtG`EoreYorTYV1iWV`T zPm5K3?lRXSWQm)kAkJ0kbP%Cw*il_KC8ZMcC3iY}A@%R9Tz z9)evnum<2d$bmt>jMn!;dt;F;>Gh*t?%0FY$467Y6mIhm_m>KCTK(nI^abG%o}H9{ zt~O_J5i^y%(g0UEN_U#zn{ch7Q$q1GF@S%Cg4IFr(^}G7{IiH$2_Xa9HVjL7ax|0) ztBIwq&!MkQd!WT*VYl@iQ1izqI2TBTWyNC19VgcPE2QKYc+Nw2>hx(9Ev-8hT2N?Y zn)-3V9bXqz&Rve>g!rHe12xYyMr)zETa}zMk7NmK7hhneNyQ9j!`TGeiZ+KU(>D_M zeMjjRmX(wIr(&u^`RO44t-lSrHKb2afLx=D%=>b55TSo2QI0JHmd`yc%tn4Plr4aM z3etd)QVo1{$o3BI{lsNqA)z*~O819sZ9bN~q+8JkkIPcN|#3b)@naA6f+g zTLD?YX%@E(=5u%7sAN;(QxkdU$l}ZS_j{?tg!Aw14#+WIxLm&Y$-Ues=)n#l?+UO% zp9(T(nNo;{m|vQ9!jJnOTf`zGGTwPZG7EIE%D^Loxi=Knq5!$vi1NN<)zdO>#JMoFu*&`mEpc280K==eBQvsk2*GYlwHQoN!2e#wrc1Ai_pi>oH= z#@?DYp#uP3F>!9t)kn1yiVDzCNKM8_-qdGR*QU*K_k%Y4^L05}&_$UQ=C8A1RO?#n z;rw(T@tIxD2>geYj%1Jxp(HWZy?ei-2nUAaUoIf`0c<`%#TzKN3lI{ZPwe^ye!NMm zkotSP+nY-eiOt2e{6e!2C;=o|L3`yl6PAzZV(Jzh94^wl*_bgx>hZwI}|x zBn{rpE#IrhnM3l@{Wg+#q>f(9`(#eMHHvkoZ3q8C-R5k*Hhe=;gNcIFpVZDw0f|W_ zFybfOqmS6-Y)zNK3+JOsK%dgAOT&V8$J$4(^Vz#?!+)K^sX)}C|0p!>K&GXDnYx+L z8b{E5wQU`S^(&1M31@B^q-uNvLsZ_mL;(Q-j6fzU6Gu?o9_(jEl1l0wdy~NRRP8p; zLBm{<3U?QugZ&*7x+#cUO;Rh_`$u|@_?Fz5O{1eQSWCfSK!B}QqU*Js|JqN*;W#@{ z3^Bd0{l#bt3#f zGGy~vUjNCJ`XeDPEKUo0^`7gEpb9$yJ%7eSIa~FjA-)({LaY_ad4kvdRA^7s<&r7) zVve0c*oa`J>w2BE&QbrWJ3Cfx8oIw&SA}C;P8ow=B0R_l`h;s~!((8@&`70A$hv(X zC?X@~{|J16)X$kkE>M}HtaZ>PwSy0?aS@Vh_W^u@&Ld>eMBY`%RtCr2$%?*j(mVOQ z%tm<(I%572S#zTIp}}vs98^x_p8MWlsh7%q_v|s>;@)FBZP3vR^3T!-8mTJCytVk_ zBTdg)k}VE`6GW6ibl`mkjtleLGYDeLe+5Q=8(}#C{c6=ODo;#?qWTj%q zV9T~S+fO#vw#=fZZp)86&U;4{Q?}lZWSHpryI8qUeHJ?RGyHUsa**@e_^X;}J&K!( zfce&ef*{~yFh5;0{^c%>JS(5@gI;FHsm{o)7zJlcr}LWK-4i!q?t>ef7Id{_B%45z zTlnUd-EZ}XN7N^tkaxvx@6k(oK-^bZ+LT4KA^q2 zH@IpH&BV9>@c5;FyfF~RpCmjgm$>!zS!O*?;O??6>qxAn*Us@cvj+9N{0SgDm9NG~Uog)ur8grc2@Uni#!{@)!n`4Hl zT&Cw>6aF(Z`Jgw-q3Y$?nFCA5RiSC$3B>>@4OU(BjBtU)XD-FFm!@#M)Ju$iN58x#YCA}f*n z8*LU_z64SrL3AbInAvOn!gas=FL0cqn#nR^ktrGXROs)q^Ekxqfy37(u%f^!tn+k` zHGO^BTi!(8Yed8s+!2NXPvmUB$c4^JJkNI~4*|a1ykF%?0tUH!-n7|8(}p@s7*9>r z8lJRaKcY`BH?GD8LPBP|V^!HlaQ=)S(b9?w9G^RFz839E5rAJAdrk*`hQ zvvRhDOPFbNb;Odo;ai>-W?Yt^;>Ec$m78TZsMkr*BEH&MuiAPCOA|dl=^W#QP7pZf zYLvJD$+OdLCw>jxsBdgMX=u28Vc-C_0|^G*jvbU3_?5x)P|>>i{X^tFaa+R30(cNn zD-0Pa6p&$qVMr#35gFY-zAD%f3qEA5oQ6q488-7;qJEy$995>6pw>F z!*hHQ_Tt)lv_pxkhdtB4+C>L`sJTO5&hMC?Ym}1}gN;jsvbh7WJk7HV5kK+>MsZf5 z6#=dNlFT!8*6SBO(N$w}aS#t8RWO5@rnOT#XmF$bJJIZ3DRY!9K{#a&=KU#xHQ`Uh ze}G3%&8-tO+3lI1IQ6b$I1D?jrebV#sD7l#cZaP1EGJSepy4?~=jh!{#s$wo&--f{ zk5c>wzfAyK3zHIqgNe>quqMlVj?S286!+r98BCHI3N1{-piL+^pavs;&vZR(Oql|+x)4i^`oxonjF(X)f5W|L&?^U;csttLPyTxg4 zwjQAR$PkP4m)T=*ZUqu?_<+#)<}ft0v4I^1A(*i33>oa_(M~xS z;x(XQLDqD@^G;@u>bP#7efHeo6G0&`HT@M0{mrjso2=eE19=8;r(OM<4MrKxD~U}w z1}CayE(YWAUU%&Q%OD<%r>XVL2i`n=b!Lo5uW`?mTBnRC*q6WvCzHDc+b#HjsJhMu zC0Y7~1649!{;VM$^>gD#-CrwYVKm6QPp zg0dW8k~@SXMR2>LWbSvMYyrfFChEYkmahMR5jER_zn5B%bhWM)*&~5!oFs*L{9zfu zbpoZ89{&(9K8ZW=Q$GoG_Jdq*OD|49W>+^HkVk1rTEuAxH@sf~?>pn{)Dd$MStS;c zT+h~S-qJs(d8_X_(CnTL>$})-@zhbA;u0tHvsGaO>z#(aOQ*66Uei#g&p$pv>0GV2 z)As(=UI-FE>Qbm2DDDE;bQkLR??PUld3Om|jPBpNH&n{E&9Y~_b9!o)0>e2kAkP*o zWEPmL~r)c?uRgS=Wu2?{SSDQ#Mj zLoqx*k5Q9eJ4a=_J}Olv>2c08IfDgjJ52sl=YSjRP!tlp{G#sU*>n#J(p}nX(^rP? z!ADZOyXRx`ndb`okx38vi|p&~1@?fN?ma{&{rES}HiQ3ffdAt%vw*_alyTmaNK%5E zjPo5_d>EffPEt92fUD>JIq0kkzl;6W50@&sk8b6w`jGw(8+*|TK(LU2R^POheeYhG zc`bO;Jq@A{;?>x>bq(-`njZ zbbp%`n!7Tfxd;QDy9V6H#Tk@whYL&uqRJ-j}qLcJwTSC%yH6OKj)<9 zf!XQ4$6ARv>U0m|L(!YCo*}TuFVOj}*k0|#EcdmTJ`GBKR8 zp%7#V)?`}Pu#FL*MZtsq9YtWEKA+v})OH=gGq3A{G39onChe0tdYM~rr=`Ic0NTjR zb6;>%{eER#_Ll>obSGyY-|s$4h<&vLOIrOh;pjF%QChHuqqKAyPh20dplxs0XC%!rNvvi#xdey}N#s1W8{A2#ZLO5(0)miumgx;bIe zhVul$;b#%N(-cV|eaCrP!sy)_Z`aF5%=FIgx@OOY5kkEHZcHiCNo`Mp9fZdQeD(m; z#0-B2AYKU7BS!uMf5h!{&S5gkMlb)N{@@9Khb6i+Cc+A2Pjy+2=7pPRjM0#^ zb{dYoj{94&n);kvfD?}OO8)SoT}0o2B3m~ac<$1$&#B;^tV64_A882yU~r2>5`X2- z412_!Z}%Gl0q{n?r}uiTwj85NF+Uyt_=VjVMR_w&XkY&v&h0+;=W4W%GHsSEHw~%& zgyrDrV*sy#{!tZ{xg#wlMn(c;(8-nq{*WVd|1aEod>g+H3-C!oZ})kqPkvFy1V7!m zHr$j%Fu?U`H;caDgnL-Y3=2-1`yRrsrFnC9;}~+e+QJ_pw*+t$bhSWX`>NAe{lU(Uyk%+oi(S_3v$~Wgs^(DNr!|66zRb+<1TF zt`C7WSoR#jq*p`UcBGpM7UDdS4<>P`culysuE_b_i0H2aTfQe`Wo|cIR(VvU>G^?* z66mZ}dU1{IXuKuCUL^;Uz{dL8m7#0*?N)bbGCe2*{Ye>78~9sz9Yabh1I<+j3PNxD zbuLlpz__f&=b6LCj-3t8W*!lg)Ji1E1=5OK?N{f{5X51uaZB&zm*|0z1JGE#-*8I$~clH#*CKnwZhDTqt6 zSn!;XqRiEpJ34Dd5jDT+Y(<;(K&BTbTvaO-+7^S$qJT3sMP{~|mYWJg!m@nW!2-G{ z6{h1XVW3U=CmwEE=PDFsqNbZ!Fjs^Bd_qJyTQxj~1^Tb|$!>!LqZg4MVs^a>2XJ`% zdjcGMJ5KpvQ!3?&aOa`!sEbvDpAXRf6|xUBCm*&65cnaHtbWeL8&9glyDyW- zL%T7$6{pSMUHLv_#9{Xqfv2&olnRx^M&XBYY~jC4-Kox>c39tG%VyT8{OTBd%bT43 z3YiANp2=_X2f{l!@o8Eo~U0Iw~%X= zlThnqg34UpHdv#M-LqrJp$;U1N7eGzA+l6@-rM{j{O-hJDiY_O>7^w@Wr28D1jT1_ zE?O7oe5-tWuNvS`W!?)Wj?l`)34tuDm-D5w*pW-oFz~`H{o+z1n1~6vnUs5Z1{V6d zS;x~D%~ce$zvf=|f|l6(Di9ZZd{_Hmd~|kpt#U;9E3km6W4q=2B4$IpAqf2iLAh`# z=62HtBBxw-X1sQ?Neyfsrp2EqZ7;tIZJgOD(K5B)m3u~#7|kIW?6Xh#N5npCzheGs z-!i10XfhRv5JsFPpE)pk$=-lt&4t2Ts~Wp}HoTxh=6KFK7V@I|#D|Dp`FeoOb_QpQ z!ihFJTeKtN*&TJM#W!EPs*#ARsEFomIvgu! z8@?v%=VM0zV}WIRu$(PK8(SJFH{V}B^qw^s-QC--de7sb_af?b9>d913lQjHN&&JB(UUR($u*p026rdgtXs=uxe3)XN$`u4R$+lA6V;f_KB%Y> zf_KnLHU$OOb^n*IUpG{ve*H^}La=xnW9qwekg@;k>S46d!c#r^-Mcd@kBlxb+RCn& zcPNCCGVsw(BH5j(7MH2?4?OUqTKXyqM_Cz6tjZN*YOt&TBBoG69onx}d*HH<%70Y9 zdGLtbe@gNpJD&%DQI=@&lkltAqpYjzu_26^x!oh-nhzVAcREn-7Gguu@lM^UPy$TyXI8IEZ82PM$Bxq>RIB+$w%l zOWgFmLP2;YahSk1JJj~LmWAxBv|d+!S;|>JA$Aem2C_>F7je+z97O9?AUj|OkOs(T z;t6KPnz}k#WU_!D+ItYLjxb;#DP9n@0Stggk}+(Xq*seQOc?3v$KvKpl)rcqdrZbQ z887u;cB8i~ygU<1ezgPn#M9~cS@J<>+tD`@?ya3Ob>--_Fr7^nBv8Gzvxz1XzlYTY+Uo;6c; z^Jv@fKhxPhGB!4h5^ceWo*j4OZ2mSs2oao-;FCk!f?+9neB^7iPza{HbRB;(!_J+q z-FmQ=dt2m}e>zuA^82oikblzz6IM5#QK7>aR_kd#dPuaydJr7(MW9yQIe zqz?(%I@rUe&J1>#e_)x?9$2dB9P&Dx{WU zq6IVe;FoR9t-Vqlqq*P4?4acgOi9&(e7R@jWa#}p;txe1PBQI}p>QsVTZoD|QOo!P z-k&5oSkXieaM}gnbzt8Xm{U=pJfu*mV`R`K-9SOVBs6^ivgX(ere;Se8JErcd8kK(9 ztn{2|qtMkGJSSDuJj;c?EB|2ouqJ2C#!5}iNf^SI*~M6cKCF2UQ7}7Pwr?1G6Fxi8 z^p$(R8xMW>#n|VqzRP@iUS4CmjF)sh_)AY^)G?FwAsiQ3d;;vGCJ$;or>yhJDrOfRX26L~J zn2ZAe0ck?Y6v8}yfxQEB{E{z#t_C~|^4J#a4Y>lm@(o!X_*3xr-cuiZxrYS*`b)Q@ zf+Ef|;LmN@Zw!4w!dcgyRUGxm9bFVcE3@Zz$q+@BaQz#xxu0N7Kc> zzvEhM`}e-Dr_~0JTTHV(>UtiudFJYR^~-S&W36x-ZefiBHw|%niP;RM`7eas*Hq&w zC`|9X7@N!>#GboAb}mfO|FycM8ljKe$v`HLF8C#i6;$%GY+nu4&fr2J+!UmuiP%&= z1HSpW0e%WHL3edzg)yc0dHiEL;ruzYO~y2dh2$zq=VAfx)`3VcvFASGSm_Zo;B_XD zTug7C=X_4OzTCpcw45o$-2&V!k$XkG$}TIx%8V*S;Hj&c!9S-3{w)Y0{Q>aBOYq*g z+bKbMHr&oekm*T-79s{fW|`&pxzZ^yAd82+ssQSh2>Eku>jXVq2;7L{z+Ubq2J@J` zVTF!1O8WE~m{uA^g;-R%A%8$xt;GX^gSP&X{|?ovrm(M|9Gf}mK{I_1*m&~@c`!gADlKFZ%a*ks6O%d)|<4#m6h-j zTn53R(6nf0)pQi}z4;8Oj`CK?*ze6*! z;>S4opOYWd9jEEdlWhc=oD043>sR*oea*cqb4LB8hWhR5Gw!!lSV-@wFGHw5O6LUn zyJI9!llu6ZFPtwE(1nIeBxYZD5a$B*6HdMBAR9?B7P@f)&l{HE+we@3F314as7D(c z;yhDs?%aMsgIYN%=VC}s%Csn5q=j_mBjM*r1 z>~tlIYQ)kH#{=V$R9Ormg*+m?6XoNMN*T3bVrNWJ&kLVpx@k%gmr7xJL1zys<(#Zd znYkvlh>=foEmRsMNRfaIIKqN=%K%WUjloZq!`>(fTQUa8`X<>&A@~0%M>Kfx$}FqE zQwD23Z%0O^f(`{XCftSys~0Ucbi8UFKOTKnL|>@B&<%g4uL+jMdw+jaXZ-S^s7H)f zLOhmtc-o|9(M9FKlhhM-u4?eaU{D>>EBH@^@KNG&4${No;qdE@D&~%Ph1^l?kDafjr=(J! zzb{bGve+#B0aHA_&vSrr?8EWG6SzhZdUMr?HeX-@B!H_TD7k}>^x~TY7=PoZj0_Dy zRFT!a4;>)jE4TzZC0nKt41=C|u)Dp7GxYPB8tE$sBy~bF+_mZp-h+`&mj|Eo5(S%A|2C4TPlTgc6qp9Yy zNL3+ERtniwo7_>?Ssr+*po02*-q~AS&bw}REIGt^XibYU2L*`NoW(VAhJU!QYjXc@ zRl0Ad0|I2hORI=-67X_98Pe-3fbWgKr?Urvqhnz#t@dTOpTT6o?| zHWnKPVx(c+g!Pqg)K#r#;d3|3vY3A7zwwm7mTi)1O!(mJViV6fv-SG4^azymeFAJG z-LVV;Tg1u@{ebU!?jP4)JQ7fITY!48)M=!*(4l>#)`H1G-@sXX&wj2A zr4ZSbNi&Yv2ZG!!hfE!aNf%Vq4N5)+(7a_*4SN9VW7}Z!8wNFe)a$9z>J0pGgG^(f zm`W^P#Kx*SJHPH(uLN)!6gXY~A6?%aPj&ysjVMvsvZ9FW86hJwvgbLrWM}WPN63~H znMwARon6R?$gz%)k*s8Ip6lHA{d-=|KhGatuRGm2$N7H7bzSfE=I$>QNOnKxbLlgz)-OrEDrE0a?NZkW+^w*b<=VB7Jnh-@4|DE*P6empIP4K z7W7wJ<1L5DgfXqWk_sHg?MF@j98Yinql5f$8&l!ufc){9V8#TCx78g1nw%tf^wUU^83N=>(cm-MIq4w z3ruaVe3_4?5sU!;s|2v>9s)-oIEtl!!Hdzm55dDr?|0ARORwR_CKKQIB*=dQz4 z3S@U<0WAgOa$x110_=;xG>67;@c)9P-mRr3E(`K+YGEgn2bl?Q?wt3!Biji4=1Qjh zf)wqoE3NJtq=%aZDjFB7aN(;>Bz%w0xsVuOQ67-Q#Dy<=<6E8MjES1me@F8rwin`{ zHiZEzMlJ3u@dv068m#1EX9x2V3c1K9)H75PHQupL& z9Efv2YsQStAeaQ~o5Mji!Uq+JrluwcS`T0FQu3>d6Hl;v!Gf$s z5XFQ5AeIRyofG)Fe5alib1|$)`T`{@5hucB-REm{b9X#2c{ayn@KXQ!Wzvb}vCFXovpR7571_E=H zRokOq!})e$bOx?=k=O=@AEKD-3sJYydZrii#G$2xg->wWZIPl{liV+{65LI6cRca^x@8=p$1IjPsA1%7h%0ml*gU}67}3pq#iD_Mb9!?&XDD>6_n!p_0CW`{@z zqP%`7gb{?`K$#Lu4K>z3Wr`b=DID;)KsR%2*EBb03iWLlc;vK!If0K*8Jtgy@;I+m z^*$gk#1QCG)Rf@edJxr%#4dh*uJ(ZSw#fu(|BmR4{{($;6|>1=Qt+A7rCTyT?ph7d zNu2zBSk`*xwd4*bIxw*>ia{Ugr`Cq4ng?WKKHxpUzilEy79}ki&Vn}n$;KCu^eLU9 zL-DF^DUv**?Y3VAkvv|>XRMl=%GElPy&QaSN&sMcN9HY188G10lEr_|5Wiagd(dCt z=k6W3mSLiyFm}EduTagtoPY;r&GuoE!-UNS>TV}4{EW-Gf`tJTKZ>^ARgniUekhaM z7Ikdh_n7F1&FyC+^}8SdL3phf|JF(#M3_K?se9LMseTRPy?giY1u$=2tk{m?I>BY# zntZ$`s^LtSAL@Cd^qLAKM<+%0kl*x;go(M5VTyuY8|S#%nHve6icdU$pP%77m%-l1 zP)LpuTFUerz({mdAO;@dO(9b71qAnaMV$g27L&kZJyp*~5E2BbxanglusARzOsKAj zDJVKYUnqk_j*1K#!5fS?S)^VlxBhchOYybmaVE(uHJ$6@bqx(Y!91uJ9&3?Fb7m`rKiO**mw-GO#BzU@?a>6443O1S+VORywS)5KJDL zc1H~WyZ^p;R5$GviGk6cBHa!2CN!?mdyUPnhligkC^pdrL_~1zF{CW>2}!gNvGwSH ztH?r?d)~thzJF)$Cnhnt(iS6ScqPXoaw!8XAJd;*Z(fJi4HzwD=Rn;M7fOEj&R?vn){YN5cldRH^U3Er za&o&JsL~(H{*kAe#R4hl;=*?&a=^%et32Tc`$Z78L zGx)|xYjjG=9u_&J!{YcRk9gN;@x2sXUmdK7$Y;(Azw_zMw6w~Yxc``9DJt%{9(<9f zH%mw;W4!f~^sPfVNn_X*fWo&7&vg_m$Y5S*!j;ILm%x~!RD1@Akg*nwkP;Tn& zJUWat`j}i_D#T?QtYU7U)4>(UmLd-WN z1sjqoz5qe}k*cZ$Q%iMqB4C7&GgJrR24A-6UBUPrsy!ZXOuq;B487+931p@8gPClR z_%pcGwaAeKuj|Yw`^x-Z=C{0mYvQT2QTPgcF*xvHhMyne#9SK&Qdd~%~n`b;IA$fYlcqFK=;LJ__F+54IBd=^- zz5q3JT?S_qBOI!wAizTwqb$(vc4cSSzrm2l6-oj=)6e)=mS0ml!EvGkSW|FH_fv0P zH*zDvdy(~LiDF|%@R*AvAe9@Ml+Uj#t5lz z*00Zd(|se!e!b@#+Q|+Vv%OXdofoaSL3Bzyc^xG1sMG5JKi4Wg*e^ zV@1U)xoDbA3Kt18sNV-d)15u)!lQ4Tg4U5KMr>`~0s7Mpw83zHSQ>D3zZ-+3woU zon7$_7$5&L&_|;ZGzRDShwUo;8}oufqIvupy1B!i(a{k_b_Rv&1oBACWST;9z9YibId{Mz2~;hhBYYcDG*g zW-(I!W0z2UMg+k=f?Jz??DO`~uEQ;fvShSw$gq1BhoC$0QObaWnObuE7EkhdmOvL$ z+i&+(;$7m50oT>6B3D)ArYI+s_-@@A(JoJsTW6XhMb@#E@UFLA3=P%D36i>Xtwn+N0eI-?%a^8HikqZYd9YqEENb*p%!n0WC z7GtJgC8Cc!;sVoFbuyn*+t_~2PA6^o;S}}R`s%YiyDPYs(G>+Wo2Qw!4J}&Y{PBZ6 z;^xs6g|^2e1QvhM#YaJ%rq0G^P!eH+QT`bUsvcmHqriGlv!?ql)fLQgfw7cmIfM{^ zBW?gpHZsP9P6L1F8Rf{beR6{g3=Q&3p~z;(V>LqgdL2oxayxMgAp=l zC`-`YSB0{4+HCGqo>lsW|F)B|-tq~6?k1?z@AL?2=)<)@#+x0Vw5*30;%qu??p{X4 zTqTSw^e9oJ&{)^a)zn(oolQ5T&6iYPAFrN~bfqkX@YyPTwZ&-{XI zSZuZLMS?vV658x1Jwp;}T%&wXtj|AmU2={7QmNB6EJyTKAz>xs%kM}*)3FXziRi0O z6yofyeS|fFrmkmvei9Yo(_hKpm+hA!@Gm8?QK6A^Wcbo~1MO@F+Sttc358a5*hxUjVFv(dK|>X^#Fp=%mer(!j#Txj}-Nxzm%er=e&d1rz{4IswP? z!LXkGez*H&Zky09q`j1*NfDL3Y)L^Aoy0e&d*~)zVMPJ?B~Q)gZl{+A=7^?XdQ{BC z3PRcRZC@H8yWhKezkgd#*0|btlT%YGNK1E6j}gN3pl(kROS}HINyho`-r%F8El!R?C&eOxxoeOZ$fA=_w9 zu=e506=q&clY91B%T$Tc<+cf)K}oZ$x8KvRs%4jh(@D{EWbbf}Cp%?DjhXflVbW5y z;v!tP_$%)Ch@SDdC`q61%ZH@`5ow0HM+wWTITM<%i#`&8H;u#q?f4Zv*3njilSKVO zs&gcHz_@8%T43EGsn7OR>$`^APhc<`5bTD7^lID}sD!2}UH0%YS`vv)Zq%2>yG!FX z{Yiw~8lih~%tp=d($dNfksazYt>@tcqMy zkkbhCU8l33-j)_t;6hJl^6|BmN6+t%Yh);g5u#+T8-0dR5e9QfPs#)F5XM~d$48y= zjvEh5O&QsfA|Tl_dG$k8)gu)Z@$v?QRX@xju3WruczDPiZaz(~)A$_!7B2K01J#Q( zR(;LcPjvVcD1$pGZ&=!KIr>768KLWqgA8ZJ zdC@bsy%|D0=kveLZxLLQT_Mz5z;6$tnHSz*y4fT;nAmFqxI!D+;YaE(rS}{8yh^{+ zJXttC3dazegK>w$M1=G$j?s<&P49Fr3Yg$KfZ`AQ*f7yBsrMXJVbY?Yq%;pVCC0c7 zMK7N-gc&)&^kJcCz_b!mD1r&Pr?G4CKng5BW=_t2W=jBFfLwIY#GnI1f44)9RIQ38 zX0<3m;e^u6=ac;hOa0`WjtXZHzoas=&llmN`+QwHirUJpv(+zqdhhz z()c9Sw~R2@NwA}^{>4xZn?2@Y7$-m0C#FA?TX6hkxQ!Q3Bkl=)gk^u{;96+WZ;OPYfs>wxBVYh+O z=;^n&*g&nvZZqMn0H5ilMd%hQpMGb7!Iw3pE7Ww2tnOmcfkEIO0p=0lpK!3@f35@o zO9RZ6e79&W0}R+*^Z-7tSn-Khj*knQy!r)@mfVwgqoS{T%n`h2A_8y>{fbmb(zzdB z+5ao*rV7kVR<0?)ydg~V?bI~CdU1(f8n)FxpD406+eN!Df?(T-kR7H)9mFuKH>s*) z*m=0iftA}4VT@4D)KfDq)F1`m@zzpRANM?{0>EnVqv2z9^)`!SBNi_F5V+v3SmnMW zE)2jUwpDBEC0r&@s~wDqqoELu-cS?WWT_R>Zezc!O4uQMyy5Ji@ViAw`XE9&d$yOO zd;z{nhJ-Q0F_^+(Kq43f!iN70jL3}At3;q$($t%F#E)Y?nQt-%98L2`}tbQeGZf5)nmJUDl03Q=NfD5x4{U4d0nF$FG&CUOkS*$V^PXy(TENps& z$c6A5TEy0vZn~%&WNW;;Qs+BTtzV+sM7MwlX49}4WE!>U)LdgmmdX?spVZrOZ=LL` zXKTJKi6{3}t?Udf5?LrqB+!mqqBbzajeKc>S5Ty_ERw9NR7g@h@%{D#3g6613zib& zNqUZ)j`R&rrH0GJLrQk$R0NBjpOGmQG)l;-iBzxncwG7$nv;5_gHUQIN?qbL#fXIkt!94(u z#q%o}puNSkxOH_R@kMkXn}|ZKc>0zMq+scnzQ$DC@O7O2i~XM&UNC;9esX{XFO{(8 z)@{nj)nt~ZPoGMq#=-KGknej?8mmu?qn&b+9DuN{z2Or(dh};dI}yee2nW=Wpl69F z6!p7)CqV*8Bizt$5~~LI8v9r1#i%MWqW!>AgM{8#Z@1k}=mVrS0T4@3vW$A#HP4*x zmT>M3?m{`B3Q!@z3; z>m_6NOxT?L+eAv9kh8^VBPE3oM_Kw0{}jg+B``g@fkHL-t~7I{sJ?EDMs$X1IVwL} z^4RM}^U`y9&=yB&Yx(;O_KpvFmo{S^=}q6WCf~#}-(fSmW@qvAOQD3n7~Y%jUXHCSR5J<|oklKya2k3N zkxai$mBwF1_=K(2xBp$PJe$7TxS8G7r;KlRtJcetN<^jF9WRM>u}qKA+keo-QoLs# zcRnu>TY33ejqDivH04K;v?j-A-cix5%@iaz;;~rKaS#7YWzd_=J2*(0-!tfp+G;*r z@Y#y(9v`PoB|&}nh=16bEnOu!zQTv}cPD#yJUKvL-e>!{l!im8(C!B%f$e9qiC5Bh zeLiH7tvw6Bnk2}0JX5>J60VU7tCK4*E6mb7X-r~dG;II!g^t~>9;{Vuhz`({6Z04vT&<0i=@X3FerAucEFX3{+ZHvK%3S#sV0&2je z7DJ;04$!ho^Zc6UQ!U0|;!KzfhKyC~ENcld}~s%I#O_-*~v zf?YH5l^Ce(GR{dW=CoyNyW zc*L~Zk-f3$VEvH6T0@lg(e0*z?9h3yFv$;2Y447<|MHii$FdtMGs|3EU(BWda=JG7 zb(PMBx2*24k+96NWNfVcyV&j8fijYd-ivv-@|`Kfx=e|Rc$A#1>e?GML>)A7TABb) z9@7ojPYL{5U>UW+<3L6j7Dh52fnL7=F>ai{|2K?o0?Rh=c|_+Hw);$b^|Ya6IV7)PMPvCEp_z= z%F4=Z^iV(yOc~!agRe`j zcn7zSAB*{)NE)JB=pBhx=RPz(ENs0qDeR#S+Mz{bL;!&T2k zONO)4qAe;lI?wd;KH9eLIyH0ceqVj|so;wIs&m}V)ASby_*?I*X-lLf%m8xu&G&}u zuK(!X8>>(C*hxJyQhO&&{s-oZQuGZaB5K#{sMnV31zm^e^LVDde)|)h!e9SsVq^B9 zUdZCk^QR>2xk1edouvi8VGhFYS9KjqluO@`rFN72yGZDW=~A+5nz6JKT1w z!hl!*NG_Hv{+#)$c~~Mekib=VQ6$qKZA80r;x*mkDuIDUk!G*5K0)7wsn;9Fq1D<0D(<*tD=B^2N zc3q(rio$SuycIDU4cHo@52)8JYwJMLAfyXi+q(<6JJO~4=18U^VF!nfFptf;J$_&5 z*)i$IFQ&y|q@}y|ILPWE+<-ZP?|O{BC2J{tc{wnvjOD^N0|+GBTU`!c10p}x>!!R` zOAR3m5&Zi*F~k9AuNuHEbh#e?D!avRZHqMDua?6|7_3vgz} zF6;Jcq7S-}>CD5eTVFLEEC!PKJ0aU9xBdORuiOe2ehj)n^Uq-<@87@2Bo2U2ohqap z1M`0g@&vB!?Oe}B<5t(E$h(`k36XR#dkI3-4js~jm;et12gzIXLTb^L zte0XWxS$X;t^FueMR>g zSSxheB2b4%4`K)^PQ{}T6xgpEuM8w(XcAumT>bbD~;DdQjyos8^KWh%(Ij~6ZvMyNK=v3t2#IRdF;AQi$n}`??9|6g( z6z@sY=p~AG?+m1dRME1~sl~C?UsB&v*~8_0tkc%Gb6?l%0u~?iwRw+bBtn6|*Y@+% z%Vn^^1|4$DJ4S=y-;l!4jyc;69GfZnmodz#2Nr}KCd|FhNplE)tf*dtf2`16w6*X^ zldzrriAc$bTyOZq|JgN!+CWlU zLD#{2>VLmL)vwFCKL-eO&+g-Eto2a_kF5tZ5TKvK#Nl;VYOKKp_z$m)Sh5NlBy!iK z_GYytbg{wl&ic|oQXMQ z9|9y{hq|g}-!(5hP7M6)15FQx(t@e!4V^nFFzU%Er%zX9WN`P7Z(`mrkR3xxM{k>8 zgT?$dRDv*|yM{GcYu^V};nBwBL|Z_&VXQ{LQaXH#_oN;k!gsr8fuNkDuMfzXN9H#56W$j!U!>9`L(E8}V;*Y~Lmc$i*CIj~_- z^{SMd`DJyFC$jKWH`UW)S>}XL%>3D;N=u{kpM!v|7kZ8zvI3t3S$~&P^GguVO0_ zPBBms#a_wj-c`v!`|}9PI6E}J?6))`^PbQ%2S;PK;Gl$D2eTv_W?zRMCkICZm&B=g zW(PBD?i-WCo}R}M^X3fPTU6-dUstrBC}Me(N=S_cO2<}SpBcXrEq>X5@Q71&t!JMK zecG63onv>bb$l;#?zie7m-0vB?_9EHraB$M+Dg~sTAuOWk1dJ=7`!EYr!h1YH^T>-Ym^c@twx%^S6J>Nb*ia z+=|pm9_MOmu$GW?Bh6hrpHfBe>uz;&lOs$YK8a=(oXq^7Sa=h8oib7I-9#M0YXf%l z-Oyp0>=_O7<8yRM_wc7ATi>^%VZZ(DVi{`LvT~WrT92#b#z$&S@oVH1UiQ&6M3 z&0O#Ap_~SQaDiKNWzX%uQ`%hyc91@-6ew(D^1owfEm&aJGXR!nho}29ko2eY%8C_0 ziM}E3Z+E!x*A)!UN&_s8`O$YMDvH89wA=VEm2*9A5Ttu?dd?)&;a{E&=W84@X~IO1 ze(nz13_AM;uk+LWN?p54c^L2>awRZXEl_WY6N&wO@XAW(UJ?cMMB``I;ZPy=e$UzJ zrqA9bia9O-l_jP%b?LWz&W_ksKaUnfres`F<)SPe8@DuyH@uea6{+HwJnJ&MlV#D( zOFhLPT$)9)>N4wg96^?N{i7sRYC8Qo{BdkWIYR8V)Mr$rn}}1R_YZ|F)p|9%u$Zw% zI^iGt`wFV`E?MJmqX}FU%Enul$-BjGa})@c^-x@@`{ndS2}c@*Tk`3Ap<=^v@G`#m zrF-%gtv+s6^!IhVRoUx*KUR5Q`_acoO#*7M%q;j!l}hQSSCPhH=SyD}uFtk-}Ckvh9WZ<&_G{e1M?6 zn{p|yblznIjE(t_!q_Z_v>LwK*eEB1qk>{5Edr`Yh~V7sUv`aDc3DZP{;|QmG*Xs=L9OGV7yMF&IlW0}n zc4m`O-AcxBt$%Mj=@BUmzZF1PL%1J&fUjMEs(qTK%z}w>1cQEOSWh$y)EN2&zd;fe z*xPBfSWEqWG`D31Prvi^O^W$dT+Spe>|)_CF8pnkTAmSK~O7GoZ785q%+lnc2 z7ke#0%F;9oWeQ7_uQWqaa6Nnl2{Vxt66K?7qQ$3;TV>O?tGE^C1#6AJ_Y!o{WK7!H zDSAZ#$dt21lQvRORg|Nd`WWfErzC-~(Z%h_r@_KED z3J`QQ(M!SGMdi+?l+JG3RLe*HI^~7as~c)=NlWqR^jhmPHJ?K@jLqg(Wa|z0DAUF( zsutbss`keh*f$z}6&;zO{n zhIY_6-_9rZpm$*@!!wK4eReZBBFADtC_1}Z&ZlAr%iqxIF*u+kljmln*l)xW=L^i1fqj z+H)Vmwmpw~B%6-=R?0{#&VV6#`uVgb4yp{%moFL4Cv^neV;pOww@W2W0-8z*gl zthSe8B|X)tI7zSqM-ZLlh!EU(1yO?&RzG9O046`XC=w!^$8uGc?x z?Def!&$^~!WpkLpoC5jxJCm>VjJp5cecW$qX|dZgJVL`c3Sy7NzX`Cq9@wFzy3P-X zbZS&AMsFCs;J@^&1j+F=>-6e}&fZij?mNs~m$IG>4uwASoZ9)LNYlBhyQh5~AlX8k zzm4*%&@8ChySiWdl}MowFtUp%^ye-4C(-%1%p0_6aJl z!AEVPE(`cWL#X>4&}yzQ${$PpwI}Q#kVLex*M*wZ-h2DklTbRT6xUyam&4?Zz5j1ToN+k@n|zggVZ%F8^@WmLK4`T#6xCyHpEH zo>u*LzThgty#s;h_!xpUxQEgJuOG**c?w#HuTcHI5W5fW#AuNc-HsF85vHlJ{qE(N zgOslMDE8YnX_*v9gB{tz-nCegCfpL752dFM?Xa%N{YJ>r39!7J`iG+C2A(+Jft;Qk zf`1W8^&V5%Ty-#sAMgYIT82ffZcp8Y{7cjOj=o_mRM-m>=(A4Qi+9@b*(DtpUyiRP z=$Iah-JmFAFTyEtsDPVp|Id{pr~sG1}`f) zK`0SJOpp2MGX_e^t`|fSUts$C-!Bs*Q|KfcqSp1DeI39shD^McL%pR=#t)^MT8UL7 zOPAzw5^FtbI@?PEEUFM~5m(jmIPt%};0N;69dYp=o+6OkQ7ZJ8>zT|CbsOHz{cNAw z8$2fHN}OwpiSYF#Mn~!U*nN9%_=xXhJfC~+OYm@Qx5r)k5}~P!ew5IaTpUj17aoCEbVm30 zdt!bi@jGriBR2*uy2GWn6tC!3Ha|AVll$K6j5Fq5BLDq;fr%Od_X~Il72h}pQQ(m? z%YP+$V-b8dAgRV!b>{)c23jmE>(LTw5|Z}&VcgJl1VZ1+=bM?(Drg)rIgdJFPpTiMKIIoEr?}96+D@X&k076KEdYdkHtD~UlW>9{` z)R)0DwZG_EvJ#P3k?jl3>rp5I*+rI!UKP3?F0-$JhRJB!J2KxYH8_pF&;Leo##t)F zX=*$S6J@FU94A8_s!!qNpD$h0N&lb)iWp+DF}gcV!jrc`34o}0aFZpUEs4OC>F&a7 zDgaeR8*xk4y9wX4I9>N&6JFliTQj{d;q9thdGF=e`S@36>TofMw|MY6IAU5P)}VNA z?Ars^C9o-G2J`X&ux7;vFp|KD-jJ|Wc0 z$5aL?1CgD33k9sv8$>Rmu!Wf_^h>2gUZrjTiGxsvP#Su)r@wC`l1Pu(yZ-8b0t{qK z{{eI=h#&3%V`xV>wJFyM!}TqnAxSp4CI$x$Vze}vmy4uIVpO9|pQ3MuMlD!tnpNMH zv&GjbR%fH2`btUA8?}&3BOGtg)t*kem&N`BmfW6IvJ-E9;tP@7llo<0tU^A0FG01p zYTGhLwT~EY^}bAc5JG&54UUV3JGW#w<`nQaH|WaM!rP;U>~3+&#Q&xX_iZn$rlKX0 za|mx2$(nrIZ}O{V<{6)NCw2+aK(H?|?Y5Kqv9{>lC}w6Bx?Jh@o(_Uqx<0F)dz`P= zdpyprtWSqkj#abB(Rxv=2RmxpyGlI!V>s=(bVK6kHT#9Anf=L4vaX zbzgYgK&`>>%D@~>8p>d3kM?Meq5HzKMnV(+QJBNzun{l2Q}PmhB+Lv*4Gw(PSiKQk zWH#)|l+{nzvn0EyTO5B^>6w%VP|yZ^Xx}Yj#M*lJ_iYr2x;{d`*8pE^?Cf*Uur5aO zw9JAB5AYH5PL5~JErB52o@tt4R+Yla_xgF0xFJOhva}RgB9|+bKZuwB4cGjAO*ohUn>%AoJ7=%1=UR5Ve|HWQq3si()YII_%n9fU7p}VzqDzHFM`W=YcCCh3m zHbJi#@#KBqf>IJ>agy}IY#{q+s+jA(cSYCA)r;!Cy4tI0%4Af$)EMcm&Zg}!O22Q@ zC};htPfAbGLoc&$J{U&BMyW&((#5eksBD7~Pw_aRPv&Qe)9=$8!><|M6I`B{-d`g1 zKB94c$9gF-S7!N&)rlXjOLSN`Z%|d@e8>d3wzi)*UC}>u9{OV!rb|^yQrH*JxqnSs zEvp~J+&7DUq!d*BUiS>e_S(!d`nlt>pWl>QI?w33#quA!>5n-a_N(0^&!dI2#vhcC zELAaNKlsUCPS_431x!ny(W8R}a*_qm*)M?sy(PFfN~LG~H=vTH7{09Q)jWNO2jk|b zY9E*?ZmU00OWe{Uln!CgCr19XCZeMFb1bP5*Xu&ATk-CF#S~QvZb_9HOh2(z+TtmL z0q~=|apP+k2@@5cDK5-atl$+eQRwjj6u9?YpYiV`XVW|SSIoZ<8(F@Eb&Zm4q0950 zS5$NHx{=t>`eiJBC4q*O^Rg|f`|lTtyNtxH1)N0q9QmQf%+_|lmMy)BG&VWv_|dOd zLu(YdDWgNLHGiA;xL|!LVuvGT+OcuFR^svArtlx;tK2^`us4M39M2XfdtXe`;5%N7 zsor+dx;Wwe=gFsRF(JBMCVn$U#hT+6U+l>yw-#Gl+#F{3Hz;G0>7LP|m1m+DE}qU# zwaky*AJ?fEw6{C`a>QBh8R&Z4GP5zCmF_>))fLiRxl@}vuzr4a_;}Q+^ciij)~fD( zyHZ#0o%kWn`?dY{oNc4`>qL2CAM<5~yrlGsGIBkpS;F4xv1Ji(oDqwyR0`$1WlT%d zwsZCSq0N{Mz1h;t-K>imwF?c;gqlCyIro|4L%RFiJ;b|=WlegWG_(4PncZ^x%ffP7 zsmKLu?M)@!qs;be=0mEx#U)jx9eLZ}9!G zKNhDGw@P1z3o;Uz6ak^X0;UWFR;=tXw^~QOq-Sh+8ZouBo_VKs z3tlqWtDR{2cxV(``PlFnZ=Do9!M$-3v`m}l9VPA?eK7l130{+#;@gta*myu02}$kD z#*z@)k51Yv`cZ&2ntwo%tmGu;2=l7n65W@^+uNtaY?;faha;?nj5nOG2~Nb~=L&Y* zcxEe;$Pz(Re)7%U$KD+R5tZ`<$Rxj73P3cBR0?3Cn8DyXZhW99#Y&c)JUD{PTwJ?MoJ~~rN)O^CMs3#Z496#qm)-z<)8e6`YW@nWos&9Ib zAb@RqKKMYsRT5^v>BU=HF2Km_22;j2lKv79vjB(**ZwFJyUqhXXB}mNO z8aKt?F{k!UW%H-GY$;jZwdhgz8Vz0pVjLM;6gfrTWwx4$$)6Fui zs1q9j(V6Q%C~qymlzj=@YGywXNxp|@1S||10wRxBU|x^w>G5ABMwryGQt06vwhS-? zFkNqeDJ=IGxPtLpf4d1Wpo0Nlb1N!{n~l|g-wNUMR;@3HrE&WV@n)8G%@*SBG~8Zs zl&}@Wc90yj@GmPR_{k9RqhWs*S9HZ=d)}4FS4i#Uy$_+hkRjplv4BL&ab5SY-IP850eEZ;Hm_Kf88b()IFYrH4%Gifi0VspJ0 zgj(p&t2Y>w@HLhWY$Tt9G7rKFk{SFCuxs?!?Jl^02KvaUwnnK!(hRgD<@WiB1i2p; zzfYJ_u%_Gp^dYgW)b-pRY;M{eGcG|gUo~}CrWtvyq<>r6*09ZXwK(-NWn$6?AIEF{ zf4GvI-=N_(hc`jzs-hehL?W(b0$5ASMt zOjRriX|F9+n(JIE-e0O(*9~k&XcOUs>?PKFmovdk1w>bK^fTeQZzcEJA!<^4q z{eGy2nrryg1scBHx(uIsJIQ_H;Y2>2Iu}~nH9^zG7P~)3&$%upg!dWb|LwBR7$`9H zE!*%eMzm|qIQ;w=Ew91O*~C{(s8gr3D}3pa|GIo|M@wLjsi>K8AO`CL9hCD@#xsmU zy`#hKPTL!07K{i0Q+z?%qZ<94M7(2Yf~9da0ohBtTuTu9|LKBXm8rNG|36*uZ3EO& zQF(XB(Fw4|+}fwEmkAcHfnb!6YM^9V)7W^R$|4iZ2oaO+b9wMOyo&6l%2^U|j66TE~EP^Cz2S2|lfxRFNL(=FgC9TK?#szU^njAN3d? ze$024O(VaHD#)8JKg{fFN2y10vEQq5dnV++_GNA`xM z%E5BJqt1gC*8;kyoFTYp*tLtW^9iO@*U+`x^qP54PJ)+9 z5wI>KkD4(ly;CWQwi*rMpBIT<9o)~K-)HC3T-rVFnz5BhKi$uNJF@0X-|pl8r-ywm za8SsESFfQ;#do@~xlixh5Bcm``H$f^-lX{QQHG!4<#n2m8KlN`o|o@mPTKdaFtben z<(D5oQb67N1QH`GYg7>hm;R$=fqzT*;Pc>xs-bNMN@0e*UAf3W=kM4nh7Qi^T8_s~c5U2+F(6K{X+4n$V&;gw7(CRTYZDXZ{(MBxXAf5#jM{U7%E6qZmGOc=VnX3 z_SEye21i4cJ-be=O77eKFXaYme^0y2O2l9FZ8cAD&ZMbGzYk6OD7a7?IcyzIMZL!M zvdQewf^#yivtwPaWIF4`kfB~P3pZm_pFWGLLZpnBkjhS~6GF=-DIW89e~867kJbMC z*c!XF+52Km646mi=&`vOaY4)-!Qt>{m^fF{c@JB*^p%$B{mt7F>|$R8oCo8k$Zghl zx7L!d%&Kihie_saN6?b4i^-t_wuuHdFw(eAJ+&9*ytntt^VZI!u=#Zz-nj&K@}#u- z0%tmbmmX!vEf;rabB$@HGN&{z5Y|~aZ=~;@{B?31CR^Cp3SnhpdJz>BWuo>!I{^7$ z9~>kY^r*9v!|>y1f5X3P9pFE(JQ2VbfQK>J9>()>FGIv zG8l|1h5$V`QL9v49^8hNB*M23a@0a#)PNv=vU&QZ!8r-T(93YjlM? zTc(`Q%zFPWoOtt(9M~S0OLpk2#yC|K1ns|GTWV%LUPf^SX8-tJUu945b7i*X^fEJL zWRiV1;enYqC3N^bdt@Qpb@x;v79vL3u2?5XCszw=OFi<4xT51KKiD-j&6MGp7Q1=W zAx<~IwOHs__ZQX3)Z}L7t)HhDv>bBt-)8trIDe)vX$3)FlrHD!D}}Q@qBvYIeY;)L zM2cP|W7xsvly^yWR2|u(i0tg0f9x=4ZA`slVlAi2<+l<@S_l&QUipCq9Q`z-jRimBV8#L1;KfZZV7vrF?R7(QSOxW z-tj!}q20Oks)9kk45ofGEysWEM?~7MqM$bNgedBhvjYf95d!#Jt{63(BTqD1X0$4J zmgd-!4H^XC!NGK65XK=ZE+0`g7SI!q6zdRWsCGmAI0Tu+N@fMAG0VRE&Lw^=VCK9> zOsV=D^EkhF7mL8-%z1ueMsnmMlKF8)nT8Lpn&CuzlG)Mr*$tzH5(`oSyppNpPyVgr zj|SQNw}#8_kNX!1k853x0D_Y2{VJ;CA4u-ZsxVLjwD(KySDnh-Qp9s}q#G0%t2P}X z^F7=S_ls)I6TB`ML!`KcKmfgk_WnI{_#4k(sYn@XZ9Cz_Zg)p+%wpj+D6wLY39g=YIKlpKe9<`wlfTO}$1mCjBI*!>gl z3#UW0kaEwTe73PPuv#|+2+>H9DQnG*mCG5i8BqjA|upYJ%3r zqQn)!=E$!P`pHnb2zy$EjOp+wF!OFiEdENmk8EjG4eQBsnP;!X-Kk@ZGo@^zUQdx; z*x>o0cK%eU9`=P#^B;V?Tk)K;Jo4L$hc4?+{$zZ}ROLAv5O*Ej?wtIT&RKL*GiPqa zqfq%{F4JnaQTy2Wa?fe9P>!Cac18X=GDQ*dCo_2L)Zav@Urcl)&Uo#jAjZx zsISs38Tg#2UK)^lRZ9e26*8Rq^ZAdt6O_v-o$zGKOGUgAm>3|v9r9-Mhjp|J&8?a9 zu`vs0C*&jc^UY8X^Y;g>sU}6neNngI&@}mz`Uys8DKiXOn8v03?faW+u6f*9YcA`b znaSQ%JjY>|T^AWG(JV-*c-}#+pnJH&!-{|0gcQGiE4ZFG#Eq~6fPd#*lnxopn<1pQ zsS9YsyV$8oz|H5T0Kv1a1In~UUxU>r?a@L(z~Xn{qm;h2&bK#&?XNX^j{6HuRzYWF zdYlH0kQ_p~MI;p7e-GbefEb9w)4ziI=Nlk{Q;*%bb0;AqV|}bU6B14Ke>`LO$M#^f zL=U6d?9UWW1NK`w$vL>pIiV0bd|o@&SYRpt1>Dd)!3PRs>H|X=&xyC$vGsPB&)>C-{Ufz?fuOgrkcCg zf6bJII+H{-zQc>%a~zm6%0Dn&e{weI9*;V9)oYeaw(=kE&81d2DK-Ems}N%9Lmeb_}{7!B-g3_oXgv+sbV%0Z;l}feKxx4h&vBX$bF&sfdGY(yLl`aqSkEVuep0v>)4^t|Lx#+o0 zpSbdvwW1ZfLo4s9MqL@7$9P|KoSUjV#7?PS^X$-8?ApHpuJ&G)Gm%jn_a(jvlt^?N z-r>xgoyu(V;m3QDm2>Z!nR1pD+tqA>2IzFhK(2z3ID)s#Z4r?-u>Cxvv{=bgz7FdH z^T+UHnl`|txEU|I18d|&2~`wsNWnrl$vZ=T(^b1IVhb2Ls~&BJXxCWqBjCT(k}B8I zgKUsuXnR3YS!BBPm2UtEwiqM?ARZENp2G!xk#mC|NZq0SYIBUW<)wm=(FLHwxEtqd zvs3e$U|}-4y|du(=Yu4dB28uI5wOiCX3peJmJxSSjjmDeE$Jp+=9vB~raQ0n7A08Qm)lUW zgWw^Wx-faI!?bd1X9_X(>QLyRn_`*0UhFu6(8z4{S>Uz0aqcws+1MrV*tFqmqC~}0 znUbTfcBX{Ch2FV%|HS3>KKMvIhU+!;xS`pakxJ=Dch}tj<5+D69zW{dZ6oQCHY}3| z+vciM2MlM9pEUfYU4s1bCGI?R#BT8ZX}~-(wrWk4pCeUr&DV!C!VeLTr_+KLLeK6I zEZeq-XnAD3EwOOJiJ_R_1xHaeyY4xk`GyArp%W^xw~toxWl3+5)1sUJEGuCR^?}VG z{!DHvx=Hd`-p20I`Tm9F!JtXw^_47!*)KGMuJvwr zWyTZIJkAI%C40uKpHj)7*_$huh{o%_xUO{)NtK9aSe%oNi_f^O$?i)_3t*AI)DgIC zMX%#7RAnts>6t5c_U3Aw%G^_f$3#Ydf)|jr$2Wdpp<8yv9J;gB%U`T-g>zL*_

Wtm$q52k9ZdZPUbl7g!PKY>LKVM3Wx@-NYexKfk z%?@t$2oj-jCG?5nziM=n3WzTI>uV*Wfs^RpAn3XUV(QxfPss{YOD|BawnzyOsjZDw zXjGc_DKy0$0#|cZE$){3Y-%kHp9Up&yErR+ zY$JYyDLd4xt3%95F!lS%+Y zQ?~PpM{20`EvECm3zae78ugp$sk&QY`eYtxIy?1y?~Lki{W^$Zr&T}9r@FzoSm~J5l>FAyxU-@_9wT^ara@{B(r)O2B&oGdoV7%LK9f|Lbn;O4C#2ZDo> zlM`@B)Q=efCFD5_c7r#mcK^dvd)H| z2GyV6taC*Lf6~_nWERF|*fY=_kA^}`WH2a(jvSjEmjo%PeXF|w6ZlXWR!~P;Mda2n|(jt_%#^aDaG^=ac^X%u<-ExmzOVvX4XFfiH z;L^3>JqKX<=Rl=i>XNawzC21%JM-oOG=aUczhd4 z`39B|VJ?-wqYaL&&Q%Q2FujaNshqca>zjBE8vQ^4&b&qnke6AA_gwPKi37oXxOMREN0q$eF}? zlK{Wf)FDeaG08x_`WJ`v5%*73uMa!@+tpC&m!a~SAO5)Ls5rQ+T`of9=zsXu(eVqI zO*fG=Cm`q>Zym!AZXFOF7X*q-2RQX|?(RGwVEilIs`!S0ZykUI)-Go!pd|#j{|84# zDu6C)+7<8e%?k#D0RVO5(F!9Q8yi4azYqsGi_#$99i(1G^Glc?W6?Iwc-;8!1)-_adQ9y9FWo86Y$^w{&nlgnh4-i2MJeC0bRw(%=sy$ z+oS_F@W~sSm}~;03f!Bqf~QM9wpC&;UR(vGKNdsz)*lE8CTC_s(E;|ldCO?+Y9 zPB2U(RyJ#+)gMxh{s*YMhF@v3U6#g~3*F)4?6zacIuF_v?j-N#8EZE(0`ATTN z_C=+!KxTn)vMQQFn5PU%>%3kS^{;MXuA2jEJ_7Ts4&ak$^&hwdK;$&GNAUPPun3XM zydXwu2B2RbssQh!%MJj40`A+@@HxglcjXuR8CFBGll5vC10Za5gR0n-8gjG->WI8} zqvhK3>?F#CJOf8JyR+k%Zux0+RN;D%fa!LJDBa9SKw2XcMEOqZ!j6;#ABwcx1D}@m z`wfgfhj;HkuIPGA*Q=j)dENGL4@_*P5L@>qnqbF0phw+)Jk|Cie^SbE+A9!i?}rj+ zA?4l^k)R}^;ZafSRTteLD9ASYf6!B)=|j+1Pymtl09;4LNLolp>t|p{bO9kv0&u%3 z3ZpiBG@KQUJ=J!+0l--2ZJ>WsYiR3_1yEz4nR1ksU!ZdUrkn=|fEG;QK1TpBgXpNm z?(QxgId2pQV#JS*jvDc@Fzo`>5@6B30{Gb5_wVPx{ghKxRV6Y^3>IG&nooZXQd9sc zh8Ho-NRfSNN-?~dbZ#h=Lw{rPM}fsL@MiajJEoEmzU^7-TiC9?>-ORr_XGKg9GQiJ zE=H}-I^1TH-EBSyIdVkU>4xk_bq18%nuo5~&95`-&0g#(RD5XVA#P?{r;_>89vi(VB?2Z-^z)vEoq!xYw9Deu2sh*7R zWR|1u(5+Nu4yGDRe&sf`CL9l+NHYv>|1f#TomTOMdtapB2zx;)>^QbrzC{gIz zm++#*Bfj`dq(r&+VX%PF*{9S^wKr6}4v)c112^)+r%(5DCvJocCjjdM99ML01##~S zzER)~0@kfXQ}Y*Ap%?*pi+5Q2_K!X4Mb+z6yu-n6lqN5xXAXxvNMCOpd~6w>`aLVY zbM8u7&oMUFtubS;S~V!g(ru``dH*EQnTPuPw_`%L&PPw&ypmgO87sYA^de4)+JuMO z{!OfotFtG!9j@h^EYA-2?0^37{;_vZN~BNEH=&P%*9dSNydoAqU7p!XYC;!a5<3B> z0s(ORugkx96y3Y3tbVI@y$F~Hm36Y4J^M9C&jCpfI-mS^4>^wyYWtNdDKpyr=U1=> zyD7zQ&8Tjj@kD%Cou;K?y6*?F%ea_Nu&=l_bj!Dj3ahA-^F=VL@ppWSDtsdDYfM@c zO|>X1BCx1A%n4(W(U9#7Z?wS;k|bm(+&~~A zJUV)qfQmv54Wa?cNy6klI$^@3BMLuM0t}v;hvXs1$RpPC4k}(PVZ>;*kzVR`(UPPj z_YyR7RRf;s?*1f*^8JBt*4twfa>|l-A-}wBBBP?$y0IVddI~3e{||}J?$aA}IY=?|Dbc#SversB~?zo!0(g$WAgjvrS z7j>&Hj%u-o-*z0tn>82h->v+2O!!M{E1JM%@5UPUE+9+#vFnjA8Izbena(qBh$fZ) zH5!+32cz`b3a_hy770X9O0lhY;`#7_GjOZer1;GjbYM4IbeRLKS;^3}H25Vy5)k4_ zN53WRQPI+nysZMs+`l(TyZLWm_aQ$NLyAmo<@U8_eI9h`XlRNjY&QW?I)@Kbm~{4z zbGB;2@yM^2zy*D78jaLil zkVcI9%Zc-!?h~|$W2!1EmQHzjp+l9z7A-jAM|A>_T-LUc?Tp;mmn$ml5y6rD{wU*p zvcX@qIMt_;9P-i+^AyT#h%^4(Y`n>!Lg{R9)`U5o$LqmyKKgm;QsQRMUVDcFrmDWZEAw_#z?r{Y_f^I6@X#PXROqWTDmgNQc~AL_gIkQdL{B zlqVIosi>tT>TErMlznech^a5}&8C8f&mTCj(qw4a!sTrGT+IPL;c4(`RpwWwp~jElrrRYNGb}%!xjI%1zXx zpUb$@tF;a2-*B(r!@CBcTp%3*pt682Bu_{)X>h|~Qb~mS|7MvVU@IbrdyUOmRVW^1R0%{;jGAVxbY}Rg~3O(|2Tan;okq3%^ z>G#M)0u=pz{?-T}+<-4UtEMIvpq9X@e!0@h#y6#!dIyT&hiuu#=mGY?r9ii zH1~SuE&e;h!o_abmo5xojB3+Q*1p4A`JKz_c$`9trYu5NGJRGul7YsC1YZn^8^3mk z^#_(6HjVxe;w~IhnejZO;W*STfBKyJtlK&J&#s_ zV*l;MMGrG6NA--=c`sxuVKfwm^El7FtnZokf-M4y2*?`NOxdL`Ho@L# z>QJ(HS0U!j?RHKD8^1eQJnRT)WWdjP8U*(PfTawtKiL>u3%KvQ=@kF9t->k-N-vb1 zlM;FH&<`P7txRaUGF**ik+EmL`@uZk+q{_Vq3C7_I}BBO4cDSw3zl(uSoxQ#BBbD| z(hKL0!8a427BlNzoGUFK?HZtY{3|t@omdyGodjV%=8!CoKBa-Bk%XKiW^TUg(E?va znjAhuKOoFbJeTyYLt9e_OMU(M2A<;l-lzwUp3RNWP3AlI*7F;(NHaS3ULMO@>sfgZ zKZ+bHd@SV;rT5(!Cfy}asDZ%=!zYXWKjTw;zOMk!+{?1E;9r^ZPbrV;*8d8XWoUg zldR^2B$7g?)r11&szd!y`RC)~xX~&BOU}C&!~A^GNht#y6x~csF!)}e+rHE7i>FRHi5GPIpN#5&H{vqv6YFEWfDU&aT84B{ z6nX_n!nev@$(?*_>xZS_dz!aR$~41jg?w4lCtz@EEO9+QKndms>u0tKF2s0+jK{rb z@&Fr4-Mo_D=A+b-s2THbC-_%tey0d%`+%e0#g^ibuC1+&=XOZ{+|oisLXrnEk)8vI z9Ax7QFynbfZJ{8OM-g}#odI09AT`zJEcO;8w>I@HH%u`%rxeW5LdS0MQ-(aB=p=-rtJ1~F-o zs<$ixiYyt;_5Wxslw)xq84@y>W}O73uU%~Sk-Y+e^gfYENY@IF8u$qBe3L28j) z-AaA|{+OVEfDWKL@&JJ#B=DKYqzLLbEqw1IQqxul%fotr{0!aUFHw8r7PeF&?Y+Y^PCz<*n)tZpi50Kip;)O|g<9F*27|lV4YIj7 zfUB={Ah3Cg0Y&dJNHHG-NcK$N>QOAt zI5Bz*N%aX3Zjv)JRU zM-{E<4a9b=I(vI6LxRQWAElWlr?bdrCw2=XtuOXO>X|~oE3vNOLqeG1>RQUGNv+@4 z#|%zs&~^#(l|?9eYL&#q0zvvaqfLcoQE+G|;A$2_9s$zWVRXQ;g;|RZW@2LE$W4Z@ zh4>wruqDht0f#5?@OWiMJAh|8>)5eN!NnuF&JbS?4#grgBUcg%Y|D7DuM1OD?wk$f ziD{b0s*Z*t){4&X)IF;T6;s=b9#TuZqbFZsxIE6eW`z1_3acEyIS}_=Ne&9y=v0i( zIFJ@T6i*&kv5tZwmpI3JEI?ORMnDYLm@N+9QwzYISX0`5+M9!@>q>uC2s$UVr7DTb zCLVwtyg*geC?i23$d4tWxE2~14HggRAzXW--#cJLm&X8c@he|rMriT;F(hxdEe#n(Q_$$=X3l$^TD-GX-5K?VIIWi z*@amt`8w4YXQ6`+Y&4EOc*IUhK5b>>L1r|~g69Vdv}|id0axp?!9=CagzCF@?>aj2 z`744t=M`;jivfo0mZz72K^jO}Eh;U2;teX};atDYZG8+vV>%#;T(Myl)bfmg7;^CJ z9j7)!Ob70&>$SpQ%nj*anpb7$DZfpK(y?Tj^tKML9OD~iR8@?oSB35U(3Duv!`N(t z)n}Ea+YAY2^Lrzq?F7>`G5S~048iLC6HA`0|Ozz$hKL9^Rv@i?ujiwd+Bo$A0~8V zgOXFv0awA>MGz+dzlNIbK>TrB1Lp{qU!{Trpl) z&R6!QMC(&Px|Jd26^pXAQ{F}u_dC+3d6^-@$`;*Y7>}w0-Gpam z9Y(Q(pO7#O&;0XuEeoH2zZ_&ZHiN;7I`b|CoW0BXqy_-XqjUc%L89*|z=PC*bbd~Q z&sS+4d3KKOuZ?BMCh=Nq8g6Wj;0K8SCscW&Yz`U(!b65{Vr)!DO)X+uJ(1#u4UxY| z^ojru4Xdz?c~HsSfTf-set_OW?___2D+P$Dp7ufqq4hN;IMhs{K(l?`t{qk1X%tJC zfjMuA%A00woyIJDTh*}2_FucbFGNPV?`v~6JhNzf2B;>1W^IA`mTK{58d$BT)!EOd1x7*8 z_P5eSAJl#B-X_j-u5gR{C9oPpQRXeXU`s2lam(#1jc^&v67OK$-TghRS>UM zJ|czm*2Ma!)4-zpKZ1#r2yhE5YX0`M{M zwhIb>;9D+FGA?${!_OQ>t2~F96yIk~MH?e=!t!IhE_#;g^W+L~{2Tm7+RzvSRqTCJ z)M)8vAV;FU>CC|3k`wQ@{wM~d#7=LkA&jN`O|m_A);kbTEb&Jp%kC?RXf(!OG)Gm$llQ#`) zSx9EzF7_JKXvEYdU!5_`Kyf1N&I$R&qkh*~Nl6)D5Sbau_0@_FEeBAoiFETB~a{(KV4#T8$CS`aIK z5}uh`^Of&P^g|^m?3JjerSr>$JtRDnOq8zj22)eaOKnP+qSQV!0zph!W#jMk8cNTB zbW8ekW$%WdUpytIlWQ%?AnUGqh)OsM9eD7?I)w(tU@6qy1G|_Q^OyeAvrt%?m_kxg zhJH%5KD}NV(Dhf>_+7e)2Q=Y?n$Zdwv$(GAxTS1Y6fK#QM8bQ^lW+*rA(2{qBP@Kz z_5PFImIlU>aK$>j!jhMl3!JQeN)E|odc{@Gh2&K$WZb^r; zbEsrTHwx42WYgJ&i9-eI`q7B$aPkcuAi)3NM5e6?wY;i zAFpzK$9A_z*?hq;E4o-MJ@3Uk@rei+j%r-`%^=Na6rw{_f+q#WxH0VN6uehOk>i>{ zOW!D(VASE6x<;ud&j<5;b5mvGO*C?tTKr`l_*8Q@&snqH$KC?8*AV4+uh zN3AAGk}%({o%3yN-cqehAum}+a%%5mhn_nu#PDnWkkGoK;%aEy4mTn3T)x&GSvzzL zd-zOR|6~@>$Hj6#6&xH%T?1kz5lGJpO>(yr z1#(J-k0NkmDehwY{zEnM<4^tFF$nF0HmZp?8(Iu7HpQb6wZ|6?%ZJf5KaU*PD?C=& z+8SAz)66k(npWOmjZrxs?f><#=)gX|&e~VxROK;@fgQ7wE3>3SNlw{%G0k!+FGlm) z)!~jDBJx8XP1X(afZ}7}B*x)f-}So;?%tuqRdJcgch=!u6xta+BVI=}*J3*=rxG2% zSNL7bcW)Grv;o)#Xl-oaYQQwjvG%7Ao?|?~cJz*Z8Sv6IUw=b&nGUBEFH9U(EC7cE z+a{^HQJq4OZSu8EPw6!@#$y_F9NO~`doeMHe4DXr?NAzL^7WMPi-D!elAjI=3tzb# zlbDa7zYBwpKW-G~iK`EL`MwP`+|Qz?dX^!;p?|!MqgLh`2S?^^ljql%M0%W=RUM^x z7L2>xe_$o7Uu1GK?7hMayPfuA!m4?15xL)YHePP|Q(=GkTaQ8x z%1#nq?y0MmLDGED0dwZWXnUBV#WUBW9XtBNic&^sqwG%+eg>~Fu=hfD zKmLAZ!=A&SiI4L3PVbNmxi#i``m1)F-^TCg@p0H~L=j%ArA3MO;IHDL72jzaoSWdP z`JQx~lFqE;)8DTfMkh`nxx1#^(Po7Fo#Z+1P+u_BQ%7>HkQrRrGN~va*N~2X=fX_r zJwT`f#bG|cMaj>EWp~f&hFoFf*{YI-1TGBDXSb+89#d-rY`K=iRN;h%VJFV3$F~Dt zo>#c9KRez!KhT6%au$|+CzkU5dTBT9z5zlQ26pp%cD;y!QpO_d04{!)_^mxu(V*!> zyr|~c0k_N1ku~|^I9-mx$mhZK;FBK7U6Oq{5cmFW%vI1++2UP2MDk~=K z=%u`Ws|wHb`>Z4GlF052Zi=>K#nm{{;BOR0;9?@jop-HeK!tQ3Xu#(zp5{+GU2Iyv zBVaVe7gkxEB3N1!If`M zR}Hgs5|Vo)JqUVEnD@{|eQV?~FkOn3Joky+@gm3Z?k%>xxo9$#8R*iqMc^fLr)w<8 z)_$?H?AyBzUO7Pa6@WWLJ5ZxjB*>zTXC`-McY}_r4AC^JYRHx_v{85;;nsdj^UkQu zr);*HqX#vvass+if}XMgSkroVF$iL-cC#M(t96Btn~Of!Z2Pb99S=n;ebMn zo4xm-sorz@NNw3yRRFh5C=pHJ&+E22lPeOaAM|KVay<2^E|-n~j)9>OW#EU?N97(A z2&u_S#HJ`+9surG{|un;m7i#C@cGW@w#MUu3hwEK_s?&?d6%aHg%LRBKX{}>z#TY2lF32=9Q+XFi6nL!n2Ao$t`qOY3dqL*;aj0! zr5?p~;B4`G`7BhC+B8J;wCAuIN3KyDSJ3l0Q?+k8VHTrqEgUwULuX^_8R3!SS#Q0k z@7s3axl8SPa<1V=q@Jv|>bNlxQ?m)<10m_Sa$TOkq9fErxOhK=%* z24KYqOBd~MW;M2Xju|EPM* z#j_8CYkzV;j+Y3H{Q^e&=MXp5f(8M*44|rv)ONFRz5t5i8lm3hO=&Ifcj>0}Gi7|p zJH78KKHaE^;!FK9kwVXLcAe>dSnMz`M41>|J7!%e%e=MUxn&pjM%lXjas4%?(EU3w zlbhG0L_WbY(@(~kn#*HMJbMTt)C*3JlpO0hfEN?3MU*)W7)(TS<095JnOkB9)6~4b zT$}{RZ(N+x%klIU62*On!dj8qenbmsD@2rb#Ios(@E`L5TPZ1+;&AlLtqIqj1q5)b z&eLnN-e6j#zO=#o^!_uLE{hv6Pz3S9pk-4;GCxew+&V-PH8SHUG9d+*bSvStuK#Gm z2yByAc`oEPE?(SR@}H5Y8txM7s}P!wXr^Sfih^q#O3&74(RHRwFo5G5fKw-9~`{=Kq;gP@Xx>9E;TC1!Mh1!Di~X^ zRSBfv$%K|4!YVkbeX`OA>+Vdqmi$nEgO*8Ft4h^o&6Fh51QZs$%AGo0ezDMy1CfCv zlpH5Wu+;-hy2BtFiW6{=sVFNi0h;*ef#n@Hj>~Qwyn6JFPXtlRQ8Ik=xLYO$N~D=# zS=1BwkTvV|7EwOh5*cPLF7GPtDj+muP$@IGP$3fkx%hUfkH#r^YGYR%drtodKoF^U zd3}s#(#i%LLx=R22Mco2O1K90NAx_H-FYk$aI*BRi+0E4W51iCuCJtjgSU3*oQDir zeR*cHXQQ4v40pX&rIh2>?9p@m;vMoS@l$x}zH0LF4`9GCxA(_sxIc~wD9x+OwsXYKEr<7 zya#Rt<~Uw)we;n8&iV^+OF?>BA;1u?0@Rq0bv-~E(?5Lp*-Z)t%gedEB_X+1d!_e) zkGpT7LMK#?iv=To#k${|KMpC=3`ig3nw zOu|@g0EhB8vVm|!%dA4wBRx1Fh37%s$o-1g*)~ZyFENv-)2O`%DLe8n%tj~`_$6ETl;8VD_%6dJ9UNBe2E#@019FYd`+Q{o>`S3|9gJv$dn(gt zu9JUTP9cm3zSdTE5V1g{Af@2S##ia-plh+mR=Luq6|P7@5jbJ(ii`WCt;J7VcqY=p z2#C6Ev%kwc0D68o34TpZnh$AUSy-SYmDnU^SO>c}xs%?_DTf^00^mAE-?n>wcYxZM z2W)iBM90@n8JA~&@c!R6de;!wJVLUx1JG^27nzzFD#a*48#>a@rHYn4Knw*a%}@)C zjx0%wnXa(B%QvsY49#4&1cCT6R*Oo>w$FYSTxev#VS~c5sxxXi{$So^Swd?2RPKzeVTROgk@?G z#s2Ux_V~|z+aiuZeA#ZifYytTQ2H+}Ygp=>j*+B_;<}AFwtlUn4-or z(+|gVJyJlRPZ(NJUpiPIq!|BsjOG;xn>w~NlJ5Vc-|0?PAt2OajJxb#@9)328$=?% z6u77OMLAiT%Xu3r%t+GSA>o(e^uMOZ59$`~HYV)k;QHaX6yXt4{ha{zKOa*9KF3bY zc&%B%=ba6$T6?*3n(dd1?-v+``RCpfhI2lag&Q-LxMQeBwRu{bTX+7irxf*Hg7vL= z*d*2l>~;o8d~krD7mNr0(QvMX{@b3SgfkpUKN+c)G3!*}Dh2Pj8S>ERwk6}AokGg} zpIIT;q=#pkX9yPuZ)FHJK5)u`(vJ`_MaJpX|JgcsPiQX%03@7{C;>QGqsNTt?DUQl zDD@Io1+tq-btd}$%%b0aX0cqosDoWp0=`w@O1`@}e+azcznVuiyZ-bw@WbD}{*c2W z-dI!VP81OLF3f4x@>8KmlrQ+ZE~S53^zG>C8Uk!2L=+Uo0O79V&`JdOxAKR}0u7cx z88k$@aX&gPSp5tG;_~%yaZP33UA*aP8qyrNx9&tM|KIJQ!?hqqE(0)oS%N=76eh)a zNJUL$brcXhNzz8v+|jIa&V$2acdtT7+2thsqaMYD zu!SCtzTJ8ZQF8Sh;UfakhiT{roBnZA#r}tCY0}84AK%22*hEdD>s=q_PY`mZox{C=SwrosR#XRtKwfPvlWNJ)vp41nSWEOaI0fJt4+4F%bX z{|4$vlPDqb$NuRJQte_jj=-gpxKjkrpf>PYg&d zOW%!Y|54#csl!^0;P*v!*Y`Ihom?g1!PcAN=9gQ_FFWw^RD=)KI+=Z-5YPn3UVzqb z$P5m~(E+T{@lOo=0r@^~zV5B{fs)ezIBS;&%5+LfOBXu27OEC$<^d|xU2g!{KsJMD zPvdiI?~f)vQ#5&)vv?T;3e1wFZ}a>p;ob zxpEq0L5i%)$;coK?ggP{C5|y5H&dve=rT;@!4p^R>SG~Z;+7UhFs(BD6-ab{?MDc{ z{Lvzt|N3OokRa_x!xShzca=+$@!!i%^zUV74{@t;BW9HPnQV!C%1_Z+R{<`o8~^Ud zr++^|u&=+}BUZqQ$y6)wmK~-*2Yp$kgXJvrV*W}k$iGsH>;X5k3Y<_QS)phT6jG3Y zmrIx7RF3^uH~-2_zbh|jsu9pu&vM`Z3>$5vGYWyyKYCIod+F?gq#C6EnHdPTu(e|T zWFQQ<+#K26fQ>2I%>`3*uWH9VW!k^z6AF}wP zpK?h5J5Rn!1jCAO;|?J&3{_G0xZC{404hY^HssEHc@{bN|MRHPht&r#9QtveQCE%n z>JAW4u)In~OO-_d|08MA(jWzKjBYUnHR+=>tnxQS=S7dawil1Ax6K??xlhTlgMP5` z=i93t@LfAGw(HYHIj=<-+&c^X_l!W9*IWOdc#Os!(2FR*H#bu4|Y<@d}>3^c5E&@)W!-x%;4jPN(|Zt3KL{DF%uRvo7((o}RGQQ(8nN<{aOh zESc=r){s$6nmP2E8a$@OioJ3|UZjcF(i?rk#Aci;qKxg^7BP2P3)VISE)t2j2Vc6t zx^z8POyGbi`a3FXE2sYGeakR`$SgrX=da~3AR9mbnb&7vUP&0hSczt|({8%o_nH`9 zC>)xf(JqdW^U(0Vb9}@)^=Xo#+LhatE{8*$3WEv<7f&gqmzXUf)CTiu*w4Nboo!@} zdDu1Nz04{C8!LJTltUCBhfANbH*%K|*n1M?+JRE_IBv_sDYioi88cC>lRH8>^$q&< z*(dy>R*u6G@N{d1I;&+K8S!Uq#=h zIY-Y)hQ}<*>iX(M{BqGI%mbC815xYJBc;(T&PpW-QUAc@abfqX@yr5geFPN7XvWwQ zzO!`}b{!_T%vYM08OiWjOiWu0dy_v`{CsX0y4)P3s<4;dJ2a{P=-w z!WMTzz8MZCxyRFIn7uP)^YlGg60hb!plsyOT1vGvMN7t_8h^=%S`%|j+kB^UPqQZ> z@x6r@v_0D;`a;@&i?EoEr_ybe6uByx+u^#f_5q%`^(|20<7Mc;??@a&mEGuG;QBF2 z(B|7j>OIf*6!*_!$6r+Tc{fev9M&(cex#Ln?fjW%F9jUUkXIXFq~#OXOU%>84wGXlEq$lO>(Dj%n7~Wi42zWR%&o9r0NvjqB8C#dtf# zl}nYIRF4vo{Zj~b;S}3Bv5bq{&@xJP-|a<1B!fSqe$BR6p6HAQb&z3*Vrw%yQOtw#BvZ}@c_C`I44!v66@q=(`19nHit zb+|F7*8ElthuJY%)|;%QBi#{TkheV9Y4*qFa2k+?DSFv|+#}i;NJKeB=|&Z+$+@dM z8&37;0lHUjqVcs#W#v}Q`3+4*@^lDep?Lv70rZv${;@SvF?g!z-;kDpWO7}Qv{F8S zLgUf^HP+gO#O|*UCcUNlq?vZhs+9l*mRvhSz1C~3E1N&V7@25gLLGx_k2Yx$HIgd= z2@|u!C7wP*HbPU`1eEW4r<$gVX8L`V$_mt<4L`^V%wZ7Z)_t`goW(cbvSGKs0#2if zgXm@i-+97$(NT)e~9t1d{Ie%6fKy> z*jW3Vq#F-C3tfG7D+|+4J8h8#qUN|dgFB!5A0w&US_nMyw0zf&MM{c%WZ>u%$CN{1axKv@8^V=>Sd0oHf6iiu6ng9+P0uaIKZ@R*SEV}toBUflfteYI8mp& zx(Lq>&LxM;7@I-_*&NS{c z#-}niHaxd0@|K!Goyf93?HX*YU>UAUbP=Cgv|DbnSP!i&kA3W6JW6dzF#i1KtDi?r z1m`)jeMwPz(Ixdh4N|sY_4w-wC?Ni^Ot8jvOLf3Jx#P)wI68FR&KXxLmxEEk>g;;G zaZ0Z)Wez{GkZb~WQcko`7C4ud>_@Df&ZaBfdh3Jk72N~B-nZg#V6T){cJ9p93aykG zgu&q1C2_@gW?~Iy$KcY7ueHejPFs#9>oL&L$-jL0QUF>^K7m`cI;pXk54Oa8kEv9~dL0c5-#~Ve#V%gC z+N@gAe#5uP_s-t~WQ4QblT^@FSm>=^X;|9?qi~yvVLR%?RZ4 zFeZ0tUt@sPmc)Y%X4*zNd(;oC+PD&cGl`ZozkdZG)}>>hNkcy$pXO}%;@9D0PY3PG zdFtsH)luvovL%vq(04^tOw!j66@y!gi1eQ3eYdRPkBvtz0<~)}EUnj^PLt9z->re1 zZ=aDHX7Th$z7D9OkU=N?~8#;)VbtkwaSMgO@Nhh$PcLic^gJBYs{;Cr`G&v-V z;+K%a^GzS7Fai>b+o()%`k<_F;xNh1qWpnXxU2-vGZ8KPp-qQ2MsO@WgZGv?neOGxY|15p&*&vM>Qr9m6{F z?kXP5WTZCuxYSU#q2lR20B(=&lV8#{Zq_3KNi2glr?v%^zEWqzNl#b#5w)Ehc@xm4 z@2SpohgpZ3Db>379iN(u4&yNOXcmJ5I&=2B+5V;tkFuIeQ~r2og=!5W$HD+>hrQ`i z_nDjJ^PC%v-oUU9)m!fc3KgME*sxYkW7hD`BCAs$@(-YahKfD%hK4;GL|ubuwb4ZA z(5^s(Qmdf8KPY(Ug0Zj^C?S`|{)@R2~6?=3?0nA(XXc4Do zG5*ihX-OfW*EU|GH6jk8u5w5LI0h>d)g|Zx9xymC$s{F%i|f~UW#ZW8-?lyd`piJr zBAGeKDX)syT4m--rP{mS(&Y7Z4wDQfAwV*bJEsjNkrMUV~y3j8nU;c+|AZw5!JjCOzb1{ENF zf`ehPlAg!Qyu$76b=21AbT2S%Y{GQ4eO~U!l=sFhypbB$S&s4{iQV@b8uLc3g$(>e z=-bo7X4gs+(I5%0hOCA9xGlX=eMGiZqqR5#7~B@k4Hw@vj+umhd4lI%cc|1*c61Xg zd`V>wG!kea3YymOb#1OAo11L~BFaIQcQXd7&^vJ~v2%`1yUw@wl((WK4zafwv#|P6 zW08I;u6TAfbR;B0w{Rb`{Me^n4v0@>a3>0q?7w?xO@NKmh_01BPdt`G)Ja`j&^$j$ zvfktjE_vC8X@PT`M(KK*>dv=l5o8o(r>7|$-z~Uq{lS)96X=^N6iu|AADGV<9Es|K zT{Ol`>T379hIlswnx-@4p8DqdRvrgYkZtKBY=EkPzV&*ly^4WO@CI_j?vLF`QK_!6MLJ;@v>Uyw zd}tNWIC+$1Y7;ll_;H0~M(KR{m@=!Cg5T&9&=Os?!=5sJrO2pV{I23xyO*331lNi$ zkTTUvM}?wDV>#qml6Lx^m9!qG_+l(T1iU{Fkd8Z=18iRA*F(XYvL9twet{OdJt>T+ z;}GOTRBrS>1^<=p6}=|q@kv~St)%=`Lr^jeE<~Pl8XIl=n==4UzN))>t^e!SXrdG= zPy(nC1+t;v0XDr|Q0s=W?3OP+&dnBiQ-^H+6z>d(lwToj!A>=4mR}|`0RMFLR+*OB z$Nc@_@4b!i#{pP@%N><4oN9MmtU?C|9KN3=4^#Ymghsm8m^^$>j~(k0aVkeS=-g8Q zcf6vqA!9&_bHARAnKzAGSw(+s=hVDo6kimjeA<+^7JW-xT0?gO>PTp6zmF`Soz+ zL;A%kEIRugi4Qh>sv=r=D(xRB=es)#w$2i4xI{r=tj3ZU@2zsvlaoaLt)K_miE@sGt2APj^6v%2J{43kJP{D*Dv%)__=KfNF#EOLx>^bz9K)hEw$KG^ zS>!;Ok``{2g-tgpQT@kGI%X-{{<-7uEQKA5N<~&Ne19w|6k9Tg2 z^8ue?*|W0X8^MR$GwK1@Z`y5&UgO8ZKS;yOM9nZ0>Nn zN>rAo@ho3)0_gY+)n@`kDundxg7V(7b@H6pkA zt@nxa9MP+afvXh*dm)SHmaJlsxiI*3wrY%w0_^cEZ9nq%FCcf}iW zsh9%kd>0G^|k`a*%Djaf9QBY8l1OWjN$w_iJgg3W-_v_dF z`p5hAMmNJdt{mZh&pRI zk3NtHkt`P$>-5ELEfldDJLn$0{(J?E(GKO&JRQl=>WDAbuEc*hMvkMrOcT3R)rB=T z-#X1H(vHOGoM@-cq1qJmUG_lYSOZ+rm714(N%U?n1W9Ab@SxG=ttK_M1(ux1`R%&7 z+U)1G2Os3JxqnDYsE|H!=&g{pQQHdz*3}i~Pa%4Gv#)`;1XG)3=$hV!_lDy~jZ|c+Zk8V$WulwxT)DfES{b?Wj9(VLAE48-R<;yF& zTrD^fI&i6!kk+gxUSxPn}ht3uuc=S3=+mXLiC zO#($ZMrljD?<@;ue>EQOa}eN7==}%j>WQI`*}FDv9jq4@7b&W_mZ!2vXB+=BoU`cU z!1c@;-Q>q_{wWnj zF@3@JDC$!tMQP#R&s|X}olTAm86CAK?6hKGW>#sB4GD>dpr86pc}>ly)l?_WLW$Wi za?%FqLvX0~(M(Tnnm-HkC!Unx^RCZX6VFPBjV_5F7hCqNouLumo3b!nMOv#1ed|G1 zV|`QYzOYMkddeZeTJHYyo2)IumKLV1{I`zM9Nf!>N_t}jH%+K+A%%H)iN;W@jF(7h z?2|raS*I|C>oP$tw$y99SH6r#=qn8kH>>6cK1fsXrXdeyN9O*jtGYI)U48bq?dGj` zF^pU*WLLW;lT6P0tmbP>E^F7%rjt9#M*Kc)+t?F^t zWbR6*(ydy!`a`Gi-5u3Y)|UGD*3=2>F3&{f+12Sh{m-PYG~KmA8|3==yIJRFTdCWu z>*~Y^uZ%pXec^-9R!?$$`QVPxCZ+r_avVWhOm-*~U5(Wal~!IAw~Xi((G&YHUePDvwVXY4ruEcy-{-f*tmiKUsJI3j!9ke5nc6+;k)x-6!jnSE|CzD2I8n`r!Bhzm$cCd%Z@=JwDLT zxXsb?NsRvbRQ7YLx>}34Wyi&$rMflg<744cu4@yubz&)*nvL(p*47lVxk|%@b-%XC ztM9j$>zuEjlQ4eL{Uu}I^7OuwZPhzUSCYuq?6NHE;kg<&lcSYW3w|ojvr9G7h-eKi zIX!iCUHnQHEv#{XTJ%KX^XJubA51M(>|F0_`Q@wCEyT9Z{3iLG@_e0~G}KJp{nc5h z{EC#4Z;;olWZRtTitE#;y=kv|V#0JoGe<)$VrK0VlwapCUso-1J`lR~+4@QOq+SseeBQgEQqkyY>Yn%m8Y@2<7;g0?@*-?uT;s`+34 z+H77Ucs*sfYW&Um4ApGWteS|4wZh-`xn@w8-<2HG&-O;pHmu1lZ=g=3M)gHsm|nW^ zd#gq@`yeMlC$j~=gS=*@J{h6c)=C&mUVA*8lXTU0&Oc`B z&)-4EUph6q?yXlB^U&fe<1Z8ArL`jbZVqH=#;}iM))i;&%X}kIU0r#)jUq+u&g{$+ z<{jj+5!;m3&E0kH+a{LU8Had(p3|SkQ@ATJoTlt_Vu&ek9$5Vj#T{8 zZLNLoSGSTLzmOTB<9F(X4#t`+d*?sOE*n;MX+C|tJ^F;mwZ-%?`|QHK`ihPny001~ zTI$^O#U_j7*r_K)kFcFD68n9nyY))9O{!}1>0NgJ$nbZpvF4RK`^xD$t99n_oGUu{ zOAbFE>X6>LZ(?4__3@0+x6{brwxJRA*pXx6LoZxd4r;cSIz2qHF*q|dw`;!gb^{eu@Pqxsd za&YQWY3;6VNsvg&mhh!|m~7&u6qfM$=c%OqV@jTyx452F&wQCHH(uCm-lOKy^!AFS zhQhwE%DZMZcGLtiILs_=up#_ojCvLV=z8{bf;JDR%;g=Ddhd{D9`cHoRg;aWGD~u` z6tng0{JxRScqD*2k9j6^@+7lNsL|H#8Q=5VoGnj&&(ifNM*5PT`%U7s$Mwr2tcgFf z%lQuaO4mNPCQ!{_r?%JhVmej(m9on>lWw*@dYs9U)aN%kGVqy__2loa?w4nRo8FSw zkRwU99ig!dhQC66TC-u77yG=4dF!QwbLT-UPv zd66KdGWHxhse*&Pa~Yx$rq`-^e@zwSvJV^52#O*}`sSAYdv#>W#lOpG<6blKE-A~; z9VxeW2Y+T*Ey_CfbT5*h`ZtO`ly_5)yh)(S+D)l>$0#sZY_P0Qgky}OJ#mb(gY+Rh zyXkkH>(KLvy+yp*Nq&XaN(|)T-m-|nuI};Xxs15nU*6l1rtN#AY5YhNSI;y?zMyTq z#_Zqr?3)J-UE5LdTl=Ccyt+o!qAd0mgWB9`@wKuwSb+HgZZE#1(H;5j70;*n*Wy8v zko+y!w2RA)^|(7M{R*voH$G=Ek(15yY+LcqqnSv1JU@|l>|(;Y1T&^Kz0L}u)NA!- zlI=&Xr(M&$NRIP4L}nN-{90zH?emZO^Vz}?Uh4s2M|x2mshiDpJ^Eipm}P)kBR&}| zb(mkcek)T8WG<2T%QSZF(*9NbDf6|Z%C%=*g0ogKT~FQfEDI!jit}qUm7YJ_n*5;J z|5t`hb;x098=tQ3-(?fu{I7kNZv?=;QOrv8oX2Nit&!IIoHHP#WIxMI;XlgSL-FOGrX%+;`Av`SvkRF)kUM6f2yxd zm3>M7tzx3EIKPBk)17QB^4>i7gOQR`x{YI?%tIjZ5Z;S!MVac}6P8uCvZq6fB?~TD zk9e$b8ky(^Csm(bbbDBkZ<5NxaUuDI)9jb$VXc-)vRiBBFQ=-SddlB;tedFiI613b z@0h7`Gf9=1Pi6PMlwIt_3(sgAJ5wwtRqMP}t@6z-RO`zrggbR*SUyxOe^Hoe91}9t z%A~9tlW(GZ&p9vS=jJHX^c4GSK_m}-+B}|ObR&Fg{^_t)HE$aIUn^(yZOkUpsQz}B zoa27G`>vPZ_uY3@zj%j*hW>0deW=SAf!YDRdJ<7mH zV7=&Ct)hMNXot0@l8-g|Hh?y&Yxbse3RzS zFig}K>etxGV(_TLBi!X`-U2`3`LHs9OD2!)klAF`P0$V%XxHj&y?3*=C7 zI37`zv}vPAJhx!9?dO3^8}$?UJV@{F(C4PwcQIOV#dih3N)jFg~>q0vN~NqZ@v9=hu3m2SGFcswd(cf>qG^6$#nkm zCYnO}9qFHj-7a-xI?<@_HJ5w4uiN9b_GnRNx1}JtAjjODO1e;jEl14^+Xq{==2VXS zu}7o(ir-oGJfMD{ZgwFp^n7U0klVastmbOKYW}d-Fm1CEQ_QMT*uXcnmkPw~pzc?A zqfXV`rrGDAW70d_giK0p(qZd6dB3b5B8x&16m^?Z#{Q>Xh*=x^kE#{#zOx4f<&>s- zDx^RYx2A!pGS{M5jk&w7ALbjQlFKx&AH);NDLX3%%3}ETrTv3*tNBc`H`Q)rx1j7t zO1FuS)nOrsY5|_M`O=0XxjySpZ7TO&lyHpQfbx};=UL^Xaph8v;SQA67ZL@fQAc2# z&s4$xID+LsPDyT(WaIp%{pKJOy_e$T?*x^C(i*DBFUFLbx6Nj4qZei`th}0_?)*+R z)(v;k47056>?>N1sv+5R%Ywysv~Bfwv>SOuvuE#7>~Dg!)*TnjtkFysd%gCXCT^@1 z<-*zthqBs18>uj{Dyrkf%-Y;7U+U+D%3Jepr$t;7`AuR!$s=?B?S0v;GRoI3KAYIb zNUL`|Tfjt6gYo(JAC8%Hb!qR8@2k(k{ixKlz1Bzp%eQLw^egCPrxY-IN&e$4OabaNjOx$ue z=F{q=59CK?KFF13ZDiC;UtyF1r3>iY0!#ELUg==$CBWF6O$;E37eHb2D@_ z6f>6wGrP8QU1k^v?>9r^1sGn{evU^qy`dew;WfWkwR{%dT!BZK1ktD}(j?2Z%@qGFgtLI^h1Ox`r z60}55-sWW{;mvaHVfaU_p^=H&VVm&PZ}Waco4_%LNE^jnnFh3xMJ8!#{ceJA}3hc)YAFE%C*V=jl}m8bAY!k0PKEDr?aYlnYUJ1x`k<)m!V z!dAklDB?BE(Gwo(fQkDfp>iBbaiShg+4^E4&~302j42v@opvMlT*Zx?Zw}%E+y2y! zmWGGuI*dofDTODp+|)y7f}PgR4nLKoV}10gxT*bXO^{_H&5#OqO;a`g}wbqT?$3cSdlulK#5zn01w3H2O7AVhStNv9V&gXmF`+6W*1T>Cy(X@Jb4uluy#_Vy9WhwbCvvg-KPNOz4r zP0NUax=iC!hFX<@C$*~&PJGg~2-z7Lf9ul*N2@A(N6R{MNAqrNN5hGOjxDw~QqARC zH!77F@M;qtytg;FHP!MG(Yw)lGBr8nibL|TEAFIjNnMW6W{YM-BGgr%HI`BHyQjRH zI!~gq&fLW=y}%MDrqk4SM5gh0l&FBo%>w7v()5g;~InaH?tI?F|A#I9v=ZY6v*>IHk`F`1%- z)*VE(Sf2~sc=1;M{L`K*@J*=0yv1%}_g(axKK@P_%1pLBzQlg;@6)C8HP%GyJft@= zokqVUpre!+SpgBud1q$&#Le1wu`dtFL>9TEMblgYnvNhMA@k6$mg8(Eb4}T|?WCg} zj=JC1z!GdGF}^XZxW;kha=zK+21e3$%hV{h?$LqACiiwr>~?hR_{t)4nZr#P%|S8< z_6=-aB}Zh6j*LApCK~_w6wX#F`0LSF^rE=A^N6dlNVtQ}az4ffo(7$Bv7U@f(e_?mIFe}n6j3^LyX-$V) zJ#oH+tS|XRtX3aaAa2`axw<|0Av4QFG)qNqgYWg}#}-Cu-(C(C+%jB={(HKOVzmWl zTk3gMa>!!MT)9aI3a&OichD-eWK-d{bhEAwq-9b6g84GTt4liH7SGSZXEOV`z1eCbuA!E)eA&=0{k5{Pw$(ty-lh4=Yib5J69g|f)<5AhT#kOds{4KR8j?K} zG_*>KhE-)6$p^byVQ;TBEs6?iK6qZz5Cf1QIvH}G@BrA1tWwU8yh;jAMVYsU-ESn} zFg5SJr^|R0ie$mSl8Y=-@mg+9rhU{*X)dc@L!a|Lte~N=Zoil0m}Pg+-LdI<=W)wrT04 z-Fg%|XU|Gu^4*1LJJv5gHJ&1UBkf*3Ds;$bJt~z--Ia<0*_<llV`m<-Z zO_Rp`=8b}7)mq;s*BDu~GtI2`E~+G7#RpR;P*Q5}zKP$7zkb>EpUVXvJNj?=a^cC} z6OqKv5?@U_|2?+y_j?LOiT^gM{(a@#j{i2q{^v({|2BC4=R5rG|I=@x=C#QrV0%Rf zGX@oj9VdDphU=g%PVS~ooI6vAZ_nAkrzL8;#B4IP9hiuX87j)k%h5#pP>Pq2kI#d9 z_kKGE9P{BMnvNs6D~Un@1)b2Nx6*P!k?5LmbuD`L?j6Q#4X-Sthv?+VlaMftz(l)| zmE{zDor!)w^R5z`(kP~^o70U=S@{OEtfx+?*x9}QY^=tetq{Pe7+28sg}SxmW{)fX zY5aV0s;>RtPl?=W{3dN(PFn^V^p}Ku@t#rd4;^f-n6>gO=>M{dWp-e-~0RFe-8E#-{LFf@V_0|f4`@Q_dW5(?5+i0)OhK< zUYiA|blYOn|NFVP)W82iJk@vuu0IaxZ`aj--jjky z>hJM}f4`@o_}{Z0UamT^wGt?AUC-}mF8A_c*DLwf{ZLU32Mk}7d64k{<)KDKC+1m# zq0Wk_3Z|y1#Hq?BPiTF7eTN~ct88riB5rpgp9qASxSq-vK~cz~qo7NnCRW7F0phW& z$Bs#fi;EBA)B$AnhC7IUy21fQ78aJ1Cr(^UlnQLbM=d|0t$H`+G=gDiYB+&``E$>S zQF#!U%HCe_n}lbtC$=*4h*0u@M0X9s1Vqf!bIS!=`S|(OF^^fr#iiiL(W8zZXw*~i z#W+Fvdw(UZ!k%9L{=iAe={K~Ai&xznW;p+>k#}YA`V6UGcc?|{A$6Yt0T%TdRLg@I zMI5S6CZAwqtLbh~+}2+gm;LF{ar2&cK9NGsSvbq%fO+6GLk>&r-yOaxEI|TlmS}5R zU0#&Ee7W`Mjo6{8rj#9W;inpEPM2q37PNYM?W~m`r6X~99@4s zl%5$(3?7C&-|U}bj1q9-WkL z{5Yk)epq<6c+I^*_)MjV9<4r)M*t^bF7aE=)SJwVwAMWlzWI8>Jio&dT3rWm40_s- zwJ9tkAH=hw*8a%2W21vLqn8Y_(J>VSdk7WI#j~Q zhS`O#(gtuw?y21WWdqjx4yV-gyM<>r4FZVWLJ_!!`zr5lOmoNS+^153bbTGhd{MlZ zcF3;r@=fq3MRlCjWtM4ZXb63Ny(T;r<9{3N?< zX;dUJOb+t74FUtvi8viTJKA;yvk2GR$@!KYF9HGrWLt%f963*jsJrqjW72&i1i7-I zDkU2V)#_Az&qYZbGfHF5x_Lz{#=Q9I+x3!CQfWAkRmO*%5ZY$Z@=VfyScE(BbS3SV zZMd0RFy6Pci8l@08%q8)-nYXO6e+R)Yvq)Dl4kh9|Lr8TLMU;J>dl*T_!Kp>C=^%& z0=A1ifB(uAQ{zd*d^XM3zv4Y~CSF{}sUX7C9EqF{niKV*EONvwP_{E?6p5~ziAc3s zy1H4bXvkF^@vBI{jJi+PUVX%tP4HuE#Hlxy`{rGDRR`LQF`^FIOpTuD&1r*!CRt*` zG=>5FcZfasXH6PP&Xk#S(HasXo~q>k|MsqOQZeERfhSl$g|V^&Vi zhRdmn`~M$@x`#SqpFByKnzF;$Ds{6u`*>TzmT<2E%OzB?H>x~M6;*2UZo*JO(*8~YgU55tABIuV8YN#@x zUozm*I5{B^s2Mg_ti#dQ-*2~~luc{MLmhBBauZCP8jsTlkF)YmETy2^wDl$3eJt_p zc&B!^*IKD{6ik4yI*dnL;yhsHZ$L{-7@WoFK{IIam|#GG3?*{xVeLd1gfJjq1U+ma#tbL$Q?hiL=fi{hg-Ab2oVl} zm`l1&ZP!zJ#p+3B>+AT*PPG+P}Kp)D9|_)J~z zrer8!heK~5|1h)*Rs5(Ja035eC(e+`Ub@r*J;arRjJ$R@p-F59VvcST$y|M9l{~Rj zzD5?)g>YhML4TmGlF~yy>#k94DB4aHba7Gfv_ z2)t$($>Zqg(PTHD{s({kH{l7E|5yK=A`JCXDSU7MOd%2H?J6-|VufJ~>4I`tK7W@> zMeB>_&)*mHN16vf{O0J{v)>4n%>dZJ(rF&E=6@abJa22U=^`RqU~Vo?g>lY-7(qua zoU;p)C5tcy+s=17AKbEKi|-d>ZmA%8Q;Tme-(EJg&7i09v#r>{Pn)Sl;u?ikQJ$rC zZ>`V-52iS{TjIW3AzY@|S2qe(mG@@?hIKolqv?CGYW(LVBm#f`w&{Ic!@<3E+qM-O zYYGHyn%-^j5lgUnCfK~_Uw~G>@N|2{ncQRJ56o251D$N+|hmsm6c{tfGmPa&P=w~irhf7ebB}o zbkF;0B1SMYrA2bT?(?5NugNIG#at4eyg^G|!?>M|n=f*H_5x_#iX%akLewV8pW3V*DA2TXuh>N15`|BoCB?j?$S3danNm9N4^TU|7tOzU;T2gcSePt!%hyR`1@%MWQZ@T{;^8L>%X8%3O`=1y7 zU-Q$yhnfF>@+R>IAlO8BS|Y)mIN>>q94QSDe#%97HK@@9!Sn#cuo7W^hBoRfV}0CML)}{7uY#}Y9T~yNB*nN zJe9sct;y6^N1es}7yj1;hcfmCTI zVmezp{}M)Jt09Eo5*-mjOfi?G~zPFFd@}E?HuDkLhzWlfVXeo zJ_rnKerZrK1EEmHraX>H>P`I&XKmuKhcJC1Rs7CIQ$XQOv(6CCTC7wkb)9XLX7X@Q z)F)ESO9Fj+36jA$Clv{yAaE7ZjbYY0-OfoJgqf_OVO9(qILXX>;dr#oZK&SrrG9A$ zkfGu~rd42Lkd)W$NzNpMeUp-skRqMn#KU>keB4LQVXxUMzfO>)?QB7AHA~36(S~$ipeK^Wkj>=IWE$4Z_ z_ImdG@6SNxjD0V>f~-q0CG(5%*YxZ%EmMU43rX3?Xyg&oSK|#Q3VNv!^HZ(6%gQYE zy;ewsda~n0moBl?$O@>R+CxH<4v7Nu5aHysa!nGT00%ayK)Dzc!63Z95`+;kHDW+w z->d`1pj(%(%!zm4X<2$8&Js>KUDyh;T9MexqfTUT^1f3V@fb>Vg_u$T+`)p3@+tQX zGf3DIB+7XC+Nvz}(400g$YQuHCz+6V1}SBRf$;66Zu!{?IyyRG0s|O&a)8^I{_!+6 zVKXsqMycXZiNM5*L0=+>ZDic## zuyUpVKU=qN7apAi@$ifo<3@0D$Bz$$j1gh*-MjO;cAr>~gQ(fszJfAyDwGbiaA+WUJqeIg$Y-Nfi}4&z?(h@n_;h9*!wY|pt7oE?ZE`5}iT2&4qIMjViD3D3e2 z^qg5`z=0xYak^WoXKE!OW9YQ0*nv%@im70FUMr61)4oioM}RVOw@ep`opuohNs>Wu z97KNm>eVY(P=7oCjO^NZ@_5)G4l{RnStkp8*+(R*ky`(wjQou^j9y3 zs#m}tYz(j13gzZmTuXXxt_o(@wGs#lYd`#%yKaV5I$bM7{G&M(fr(RfqHD|cx;Aeq z;SMo<V6qokuVN?ywSdWqYYiosRhqvZl@Hh@vYl@`WdX6f8@GueRaX#kinhB*xoWzUn6 z4uI^*cF<45Iz-SOK71IB)X1kRjJOV9GD=#m$kC$}&|H6X{GcDX!5v3o>4391p<71n zmW4E^qQ{2T*MOE_#14P@hQx`KlV{!CH3$LfFtRXXFefIu^dcYQ*UGoD3}6t-Yg~mi zEgj*b2cPV@EZp$2%_1z;o|2MM>iqfJwv`8N&|2jew=d2e6tH`~i;>X^dJ_wI*yen?b9;KTnegv78+@626N5$5a?6VZ_Mg_XxX6Y5G%nj= zUD&sexEm<8&sZMhHV)WDL!&yR^&&a>AaG43f$B=p`|2%N>5|aj>jOWAj{+A=O=3!; z3!3%tbX@j0WfLD78cJ7ME>wSOz6Zy-_~D5Iz~vhbPn)ca=&x}hX~*3;E#!TP5o!%F zB2?U^g*}0v%c>Fp$p}U<-NP!P<~ow(ia}UM(wHNsC!|Vm5$mx=E?*O}D25Mj3NdmA zw^e2djf6qi#=|F1Tt3vW0P^U*nkg@y} zXe1SZjVaY&6$3!`fblehiiZ@qv2+V(9>dRwIJ6$*IbJM`wYIqUtzC3=isr zI#Krm9FuD<^Kk37)1MxwQ-=fw5wGzP!w3vQ!(?<;TsqtH4-vP(Zs(Vll<0s@CVc)c z2SFAY&=Fsmyp|I%y@}y5aonyoUi{A9J$n-4;}3yXB8Sw35}S@7Vemmj?uTiTLl|0w zsm|cEi3`ADVisW*+|zKUbGJxZ)oC#?eGm_c@Qy|~ZB4j1g3bmcE8`=@ zc84bsq1CeWG6~#<(gZ69M|j7W=qRUEzBZL#Z;D+RIBBl!5-2NV zBj2M>&nJ7U(t)Y8^Q~qrz2E`E;ClTST`wBvXkJRrX`EiPLGqr?%X71a@~U{EH!Z(Vx6Rc!-mD?{_xn44EOQX~;5E`>fP za-3-U+K0?BHt)8S^?mkSo|NvML}K3pw?wmh_cNsWpzGD3)Fdz{j44{JC`e?2?QI)# zA|e|mYDp&X!Ed8Qxe=$89KZ0kf)v(6EXbJa9Y=#2vGUl~1h&0+vA!Al&-J{bO&V9% zc3Tk_gmj;SWYTaRNUm(YhRI{*A<^FkW5ga9ez)y(22XnEub8(EYugh64wN)BG?L~M zkHcx9^?oTEkIm5wsTg@!8kCXKW2^M_?Vj*HVb zb<+)CBDh7&C>!=YXoYbTe(tB2fUwvwR|}o%&#a?B%p*}q2gL}YckSg<0^rlr>kNr9 zd~q2^tX6|ROF9t!^XE?oM9*RT?tGwru(7;dJoZHehhbcFbcVOLcSV=<&|u{gD!+>S zy-S`wJw01@?8tP85kmkY7(Xalr#i%~&Sra=!k=KJ-zv>(KKeJ7@oatRear-!=1Y*p z=7C@g0oRwHCZCE&M!>xkyZf2u*`;c5S6{(QCPTeh1B5_5=t=BCK2^Lbbk?eSXD#A zMP;6-!p*kot0N;?U99t33Ib+zBN>08D+NCU+T$Vf3Y3OJpX-&nGCZC}nyd!qe)i1< zY69cD*2*N@-VByr)yx?ld*qovhcY}UqsxzVonC7zvNAFa*h}t~FD}PrK^mDAbv|OU zDx>Fu0fX1_WF+^EOC+XzkUu+^M0F-grh_=j7OoMGgaDyd z=~;~km|ipQBS97cjku!9$LqdegE3`e@#lBTw7)dCQ!BRS z9s{n$6%?-{To-wcpxejZht z<^~)f5G27hpFOLAv@_*(NCu|k!2(e8R>U|m)KqmcuRR4&B~n$SYeLsLD*EKHIl#&j zz8uCMgGm~G%Z8>3n13b_ns(|9inC3Y`JFF7Hc0@yNjF;qo-v=~<7>$ugWtb`nkc;U zpGd>Qqk<1xYAs()YHVz*n41STUDG=WRE$zVt8EoS^6%fjWjn~TBgbVnu~#jiusMXs z{S~(0`q5sMe_(ZBxO?r;K6?67GPp0zq&(G?o>RCPqOgYi>F_iHTn6oF`VJQZq=*EO zLxc%w#+w&F{=Oul6|x4^P#(Zsf{P0+ky8YA?{I~qY{n!xnXcP.)DgN3K=5m27+ z-Y6TU&Xif9q)B(?s&`AKb~0hP_m9UaUc7h@By09%l!fD~#<6o6&sPR0*+H@Pbp9KhOrn^Bu zB(eKT9Z!g!jel(j81P(MaR!_piGP-d z0F_!$u<){mQ&u%tX0CYjbqyji2NKFXm(GfV6&112_p=9zK_X&O8!g}p@|EO4cFNQ* z*Tei@HQ*Vmf}V}~#i%0b0?3xNK3tg#wx@EBPU{$G2=e(;O?|U#!F-sV!ZA55wRit1 zjjI>A2-W-UycM|zGvl2d{DEZ#%cP7q7(HYKTHGl z)G-#|VR*Q4w9C)?WtON!aeX$n5330siyIar3e?-SaWBnJ=$k&x-O!;@1+6&!qs+|j zzZKX5G$L2#JhjjN6#>zK?f`sznU4w!fBy&pw5B-_fV|AAT9GJR8-92|gA1!>%g)GM z>0VpSKm6$lzjds&HoPnD1q5^2=clo;Ru{P-z5eiM*KwKVB8CO}lt;|ZGELL5@q-hD3WfJKSEfUFCTOySR z4S0KJle!j1?*yQV9{p|zM7u!orTDvJOreJ87Kt&3M$S7utprpK*|-gi;2mre(G^&u`@qV zUEq%&S9^;_vbd2(n(Bb&_hmLjs_i$H<2=zNrL5d2-t7jkmO0~5)E&udzFnpgQy+hI zsOjifz$&W?u$gyMV3NSm<}Z+^mzM~I;Dxoi;3_6!axou3t*y)wkdvEW#%1MvusseC z85tRc)hJ6}xS-N53dylV z;HR>AJ>MP%iS2YeDUEgw-*SySjCG*r8i6mo5e-i(U2>TmCoNq>B-nmqHxPGK zMV(QCBJiJta+0|{bF=2{-^1zIbA8-VUn&tzEr0d*Grsn)3}CXexAzz$id*2`J}>;Z zLmkkND9tppx=1|V&&Jc@HDrY+XWoVw>0n~!rat5|i4&rrF6i*s)syCbOLNC=+p>j| zqkMVlPP+%v7C(k$y2^wq=JM60blVoq8wavW=OQOD27_qR;J$Y4+VcU*As5`PHk(RWyhV`J_kYSrLI(~IO#`w{v;;!ZTj|Z z8%(&UmM@q|O8TIh*Pd^kjS;r&`ei!%bsdzF=7=VeB-5ESK$9V?U_DA5nV=d@g4z$| z0XIK8*pR4oWt>UY#Ka^?GfdEFGzGs;Ksch6*0OtTZ9~Myvyo&+%&%P$bDL*qX_~EE zw;c7)#dlrnUyDoblC(V?{iEw=hFf!snKnslq|2?P^O=}Wi&?YQjm|`?k=T?&&o*y< zt$q=jz#(iA%sUm=^{og~2iuH)Djewg{@y-xzHAdlj=n`|Xkcl%gPNKebN1s}BjBtD zhlbvM`=*f@cXNJrZcO`QpB;SrUPPaR>Sfm5q9^ulm5&qE9i!4wOR}cZO8CQm z_DA9QK^$m9@%J|evY=~l*pe$^Nn|4U|?n5RM!wS1Ioa>J~Ou4wyMl#?3`Sa&`q+xnqsA65Uun0hHAOSUUotxtJw?GC@#@<0Pa+r^A zAM%D@Uwi}|1}RRTK20y|vNOl{%TLlI7&Wso^VPx-K0<6#TU2S!rcHk9^Y`=BDK?+1 z{#J0Nw<=f~=yr0rnGNWWDWs+kGNl}9+C{ZYDzk7nlR$=v@S_yofClfXsy3nI^a1rT ziWA(&t-rlohYVBW)ip|1l@xEW)rC7XA77YmKS)m>fFhQ#+uU~KK_5SUL`FQYbmj4) zj#A~)O&Xr#rcEik=y=WEuXF-H&5X9~L08io=#V~mT&R_F!d@Qsqmrsj859%*2XhqJ z&Py=A#Ik}`xs#lH<6*FFE1!Sk<-c;|P_Ew_6n=>L7dLu_ZXpG%`1EPZwO6z)EiEr! zy%L9+fWm1S9-y{4!^h`aS}Kx%>Q;HV7;1yJ;78xKx6|nsIf&cX*d)kRnEo6bOxfpR zWNf_g`0?W;E{YQBT7Op^xU+4L#ND-TpD#!(GaXj(D70iC2yP6y$ow)l_ikX|j+Siw zx{f;Jj)(VdRm#-j%^VZQB+kKi*C}<)g?$jxFm+~@bHoqVnf0v zjv}1&jE(JJVqzj52)M=d-si~|uxcgLk*814IG3G4lBSZSa{xHtPGaIw5SVH9AyRl? z6!EBIm>H5m5%?W!6}vh0PXMQU6rVz77h0w$_F7UYDtcjUubP{u=fyQOHO5y$N45F9|y<@ z3}aJYUoY&7an6U~E{R?D6Hf#leG|IQp0!-o?YA!qnw@4dx%BKleg)9`Hg>W&N5p5ZJjf-*6MH4CE+5)?71?-!!_e;4RkAg`i0fVn zKdKL}uh-b1SaF1Mt4Z-uZS9*~)RD08zhvkI?EXP8?I|;%^v3lAejPe;WIfFB3@>k=h!x@m#>q46XPWh!jy*Ta=#s^Co$uYGu6(p4hhET3l1#lb;^0gyIM zPQHpKPAQ9(mX_MikL!Lf_hLdGB#9=pLt(N+oO##X9XG#lbGqLENVLFtf)Tg zdT;ewA}T0O0I)`m;NM@Y#MZsH}V|^AH*x9c{`R z85)`#2Ko{=uS{L$SKND?_F{tKo0gXFZ8mkMz0^8?e&%*y+2`NH8reJ5T8r?LF7fZ$CFTrxh1m zQWdRkV87ckIyyQeCWdInBHg@X;1FXdifAAmME@3$#AWsrJA1=(nLW!0E;>))k+JiV z_T783_RYVspIqznUps#%y-wqk^YQc-NAvUGKj(7+na)xmexjJr=Xy~ z#u2W9f&v6X$>$63GRK*BZwX=)sV1KjIeYd=KCl=yKo+sQWo2b_$e4xYzfc#8~7Kv4zanGJR2>o3GZ1OHHXDNQSH@tZHS&bE;kZ4D2 z8B4SG8f)k6@|#BY$$1r(y+l5Jl?=@Bt>k8oR(&nD15OnTJ=T|%-HKvwB1sP}`=9me ztcSvXDpDToo4DcR6UH)5#PUmC&Fa_lUOX<8h|z@ zavFTYNOa*;dMqt2_P{R@Xk%hq((T$6G$c*_`m_ga$=ZfdxXZJS!+TLRzp4LNr_B9n zN0#7=&`{lXypY>ghPXQcnpHHY?SR%cAc@D03g+)!ZKOC9?~#*u?b#Pu%fh*Noht|=F%1F*eITqf7Y2sv}) zTH*F>Arf(Z1R@KYfpnXTO0jJb{@)Ayx_XC8>zg+e2)BK!YS%Zk^l5$h`0)qBWu<<5;<>;D?%hgxT4Mq|MrXkG zY@_&k{nE29AeRq4y!asOsamUmvAq0t3X{*TSsr}~dGx4aWo%@`AJp*=wM1NLQ^&+lH=R4v5aW1sB|kCrkY=7O7XvN1m>bw3`g}X z-oy+Cjdz074($xw+}}CKJ2SZ=5lnxt){QKM~jwNG;lP@6Shrk6~PY z%R4^+N%w9>QTLDJH|1b&cKUxnkm?r+*3Pq7M}alp=si_a{P^)+(n{S^?o9!lgp#{u zl>D)ZEZyRIxP|ec$)D)>6^MvAG(pOB98p8!lNI-YhK_D4kfFm!i-M&#;Or~s2|W@M z098}!l}$txfPob(2|16yNB8UwH>JSzQ^MS zN=SO;>Ey(Rh9(~nn!>I#n}G);2yayEkJAml*wG2_3E+v(!KI>)c{^5vRNPhb&X#i1 zre18%Z$*x5^b8E^PL#VGICGVPfb!S#ZJnK^!BE;RFW7Ep5Pa&xu zOrrF-BFS>km8%8@w{T&HMMO&LS!7kvwtf$+Ln2anM2a&=`9i|OePPf9jJtR5UcG6X zm;wZK?h~;PA8}D${w@-kES@sXtuewT0h3B^El^H6H*rT{KBR7-x{16W|^1C5h#<9cf{==qfpYvT@(| zC^%YP94zqxm220w6EX4uuw(*$bg(hWU#pyW0fa@MW|B&*m{-tPNB#zv`M$32h4$-C z)X1KiheU28yna>SxbQ^ z9F?&>z(8CqWNLomT_i7EqJn6)Eg}_*h!8na4!$uFC6p&z z*SB6XH0&7~x{rH1eB{XO{pZ5?M;<>YEEK@8?9QSRLsnU_JGXED`0>LVA8}Yf-~gyC zHtYjmkS0^%9D;6hrwG~sFhfIAv!^jh4$e;sV2%@PYG9QV@*ejSe>}xI?COUhA>IgT z?;09*)y0WbA@%w(GEx&L;^E&a9W@cxJ)D|SE0lNB2D4sm4Z*8pt19ZmduJ}U zi3e00E3)m}fx$=N;gx~2QM~59u!(gPSU4Z>2B77(qp$Zp%Coz6@4oFv&2$aGuY~h| zQ1{;PSibS!@QFw$BZX3E*kzSUg``CTSy_pclvzSiWF;9Dp+c0Ats+8Q_H0;DBxOc+ z85uqAqi^5wyPx}c{=HxKe}(J1&g(pn<1^mlbNnn1SGtb27HOmqysLM4kU;VK_k2*4 zltVf&0y=2y^*)r~Z{cm(ymc#}Sbn^PZ(Q73SU_mWJ-8ICx5B0-o~28d0&6b@q(dLE z-v^-BXkVW~bpQJ&A}~?7<9gc>x-zn}%OGY(Se5}!m}a8cy#}TOA8qkn=$T2`K0PsH zj$KG_{__{E>Sc9aKRxVC6Uv3mJXZZdKJo_q6z{1oQVvC70LqCdJn=7o`o-1 zS>R;eEzi*Pf)fgYK@2L&7%VfAxKVifqQ177s`#JHU+n7L%v0a;-KK9Zh*dFDsn}D0E9LuBM?O1OP@5pFQ>Kp^n}K#)@<{Bsv(B%MFJBt6F)c|Rj|^d?3@bb0)~&@j zIE$sarlzy8e%uHzL5)M+3kylC&fZNFQP2Vv-hRoYa;RL#VN|g1*|p2@)%^MM$EudF zFhZiakhHZw{=XFG1KLac43F_~}#*3q!3s{+% z$z5%ouEA+&`oMBxX4jxXZR2^x(`Nf3E) za}`-{Ed>`h>FxQk&A8x#PIbh(R@7JF(a{2A6##XZnw-plm^Tw)+1~N#c6P>q7+&); zh}o^Km34JDVaAGv7j>i$Ov+Wk<)DM920VRJq~SXWO~5-^{m@tQ;H zbOy@h8hk9d#V;?p1(^3Ly8V;}NO;23l*Z4`-;56a2qY^81)#z+utTI-Sy`bqE64Bj zVF7GLgxDB$5=hW>8Q3F;eXT4dB_%v2MhM$LFK^smR^&*Q)e=0@l~0~NJr4A$rmZb% zA+NMMh@?jYdH2tcDNQ`Dk>NZ1y0i(nx2v05L}sRpoV@%AsN_u1rD?akG+KWWvGC;j z_3LYBGyZd~cK-GT%NZyO3b-gxbFbj3c-3ker=j7xhX_C*2Qd44J z(6tU)NWW5lo(`<$V70iok1PIqS=;hgJZhg_-QA>_ciwsi5u~;5_CKABkXOh?Zuecx zViSn}UO+HN&#V%Y@icF2-_6S7D7|Q%mA7)&8vbc>sI@0uC$~@2!XV!2_TaeZRheK@p91-|GSa5;;^Ve0Pm` z-xLX}=H%hgGhKmz$h&-bm`2c_FHEj;DqoXYD%4r9(YB5MNK$i#UIO?NN_f*O*S|TWPOerP36zVrXa%)Z=&l=c~JR|8>1- zM_&d$v;AcCaeb&7>07zJ)h4V4;6hNQj6f`GNl8hy#65q#(p7)MQBfCoCN{&N?BR%g z^m%a5L}mM`f8V%sY&YPK|J;|qpPv_p*8ZZpLF#Wf@ZX=4f4L@+%lV%_`}5yxe)Jj4 zwWcVKIhg0=AljdDiqnSFnb*X`1ejsm$IwH%s;ctjoDEB_~TDFc^I+hZcCG_`Ik<wBcK^td%cI{ zASca0JP9NmUfYQ*EU?|QZ|5|&d?o}0&Mqz^RnVCOaaJ&efFiC=3T-vke(|eU3%UH} z5n6&2I}hap1(X6womNxBCM+yGJT_L080z9Udg*J}#7QVS^Dp2^oAd#>Djz)>tw;P* zyl5oEb&}?JC~NeFnF7KT0D{V2@Kd!aydX{# zU>^>7D7!;Tq}S1b{tb0gyi7ByMc?oZr?{~1kC~a#qYpg?2^~%9o6}&cAEHT7MFlfb zo+Z-g!KiJO)_QKo5(h-qtnq4U!;AnE!%g)Zmo+m&bYPq<~0@MjB&@T9>uJQoIflrBd{Dc*$cGSLy4y|Z8_JWIt z)WgX;^48Z7;LH&ucU@>jMJ0`_wMJO@(!Ib?_d_EFRxR1<(7FYpv>B;F$2S70NkgF-m*59asU4Pf*i~Qf)5y=tD3k;3Tn`T zfZZm$@7jVYNYa&(kYEL(#(?M!$X62?fq(1y{i#tvF;b2^X&)S1l&Q~#z*-ZzRj(t< zdG@CxX&d9? z{ar1O!7KRj*FXKtPt+kFjHe_aOX6T)ViO(h0L?FVPHV@M; z{IP3Uky<^K1(lJ=SlnFg?4-%vmAC$2ioyr$*7jM)z%EFCjh#ih;V`MA4vr|+eXxF$2TnshljGRG6ktMW zD13p02H&fuRs`Q9Gn%p#{Y?6~xw#ydF<~U{h7X#e+`L=QOJaTkTJ`u5a4jcM*ue~a z1se(i>qTVEKxWCo&FzI+9lNaxic2hq0A_PSN}Bb@Yp$dVv1)W*~A+7Zsefuy4M z%|xrOB9Pucvszr71^PA5hzLGR6bWi*&?ZnnqD>*_E>l!JjkC~3nw~uAi<|Ws<&XFH zF+5(7tle{9yz>YCB83V8X~_Ix_{asJr?UIrt4Ve@LMe4lU?)%90psZ-A(?Yf41Pvm zO~=4QLt{ri2{*;Q_pJ~qHxQS=Fh+Oa0UyJ}kwooBT&}LJq_s`$nE~W)iLn<+x~WwG zpW%GC1}z%DqHDOG6Y^Cv%1qK;K?!gS3jr!hLO6J1SKIwyV&ioueJ?_3;^Blv>y4j# zovM!)l9lBGvihYD(c!XX-NOZ-Go;PS*nnLl4J{%o0I)+6Nb1f@eIL4k0ZX6%rcb)N zPi_+{0QA`78#9H>mdLk>&%Y<WJ|03`CgWDxP%)B~%7n9CjA$ zE4P`hx^We!Pwg@{M00-1Hu6IA0xQRdMMLYZgbXXH}{wQH3{KhgtoW^@SmP4fGTBF z25{lg4?5d7!O_J=-G%nEZ1(ilu&G(lWo(ooP@eP|qyY=6nZU2I#^rB!okD)IinUHj z|N7xmw)Jub8tKg>ntp6Kc<|r}j6u4dS#;DK{JJ?D+MlNJ`y0Tmypf_m7bKY zlB2cU`t^Yy3ohynxT1(f}3{%bcJx}a(xp&8qT{*g8d0K4yfjq3e% zOkcl#<=tq-jeu%uWpxc?{1=4cd<9^TJ55amQ&LlfLe)NZck6cM8GtGcL|xYbz!j_8 z7tPbQ?b|caqf#`utTd2@_r_@v?FhgjsZo2GvbV9jSeu)h1?A;$OS}Qm6BNXbZ<%vl z6!cw=+jO=86Az{T{G1p7^?A4=yn1qK%6_)S7Ptg7)hp5CydQ*&&`34l({tHym`wOKy}6S^^5(Nt^+OB-UlzDUG-IX;JH?=TnPxY zb#y7c2SqUaztG>pkBByTmuK@BcZfslvfeVT?%li0*5JW3cRsCOpV>{2yY=OF^Z_zMxC_4o?+7Z6Wp)~fo zwnU-`6-;GiCD9*27!P2M0lAjcgIM+?V*eq8d42;(2{p$FI>5e7v-xQHGEsoSzs#ck;eAR2=Jc=zi*P0D+a6_92J!| zK8XgD_T~+{)+25Z&j2lh%GfkM^!E2ZKw6uGDYUJB^R>S8mvdK8Izj!IgU#Vi#8xN) z7~6nhEtfw7{ZKh%YjmPRb0@AZnG8pWNsYMqbiu-f-TmrL zi8frNmu9p8LL8F5uge6en^_X6`D&=!Q={{ohIT^$;qpEY#4)C&{}xSI4XjzSrX6E1 zig1xxCyL)@MWg=rM8OP-yfSowx5_+5#?RoFHUo~M+JQ^}xmO)(D{x7l#)dCyZsr9~ zo%gy2G!kGJhPKNqhq2X*-@FN0{%m@3(iEU96{3C`=>j7Mu%K;f!kk=^i+$N2AXiDt z%3cAT2kDnP9@V3P9`p&lfHF~b3EkMM0Uqfa%4@wnSs_i>B1CHgUI~D+X3tofhG+)* zEa!_Ccdoi|ANU8hVaSKGDc0AIzSZZ~2u#rFIB@#(X*OUGVF$Q00&nRYQ3Tw|zIgHC z)Q+3^U@RGIZEbA=b?_lJb7YbNgu`DC)qqO4z?*@GhJW*(=zkO!~C-wZz z7*Psgu$W0i-_KCBIEZvgKooHD^VhUEnV=`x1L6vtDvId9UzpR;DsP+?7fT31+o{uy zV-wH=nxYB7%e+)q?ZD)iVer>k)L2Y)5|NX}o_QA#wWS^Nr$qX({sZ>#TG!&JTom z)@x(!^gNa&;=@$~0|RvKVe8bIWX@@RXvm7bW4XNlv_YD2R=!1B?rzN}bKD=`6H7lN z0L?~Qz=i_d{m~;aJw?c)fJ=Y#zGE<2b)`LJ2 zdCf`ns|VNa76_H@gw-}dn}X6~vt2v2X^)s1!frjpYsm0cJ*xG&B7Y+V8)7I)tu#VB z@vJu@6?+DTP7yH{^q9)fZf#_;a>alw5Q=nAO#30;u3EEZ9-=^(qK1D!z%JD3VEf3B zB6KoLxLf6M>S5Pfp8?v41vN#Kj5v~)4FY!{V5V51lqn;sP&;MQB_k@yAi04 z=TF)dFpIl`R=(PP9^D<$!l3v$cKrA}<=iujR70AvVQMrUq6*4kX;9Q)Nd^>7p-{B~I@2c(FSKv+& z0Ty7#t4Q<@5I+gI183;gte*hK3E>3gg&&BO5k>cJ_&8wKWLn&H=r1X0*k}kBhTgaP zwlHyPmUXp(gYp7s9t(esK9D*z;;i4MQTL)^hM2IH0kvf@LMx(mF8dE69zA;WsJ@}0 zIf^HOM*vr=JZ%pD!e-}TLE-)3?#PG55FCJrF2>uw%{1QwAv8a#mlB8?+J}aM5N4M& zClGcA3QTeXfY81LugJDso(=kdCVeFo^cdS$2pP|BMXIXmeZ+v^%HxzfK=K$|C`DW0 z8E?U(=mlmJz?o^`6-H(jmLh_8;ZB-FA_yM?aZIXd3-LJ|QovD@JVX~SAsIXVBv zcwrbi>>M0aplAK9<6s1pR$LV-;mgRM-f}Vt70xU(Q8@}#wZAjD%-)z4M)^lv9fF~uA?f0vp%KmagvVJ%v=VrV$AFQA zZ#=yei`sr_)PkzA2-8vDlct|}<>E@Pj5+eal>CrFmx2Q;10a=S%4^)?GF9L@#Rc@4 zhM!7XRB^jPt&fYURXFboX5qs4H$Q?AfW6DWi4`a!a!vD#(&E@p0bFQCayqnx`{bDY4J$?rBIjI}qb{4JM>nTRr&Ny7=$*Z&|2o-8vPu zp!lv;>rL`2s0@a2peBV0qYA;&A+iZ2OLwG(D$MX*SxXMfw(7MH|=Tf&cNh$SnPF4agx zZ*!4d?58RzD|=IB+@^9Hq!UY*FRxBcHjup!S~!0ci%6C_L-Yirkk3m~I8g1DQ3L=u zv={taijocAa(Uq~K+_S8@~sYbyDO6#;Ab~e2>`9`t2^tbM&H} z+b4iVouHg&HMYO2s=9_#_UyXA9r7^Hh>|t!+fJz+S6!>M6Qf?DJss@>dlP^b&;Bxu zHqtltmH-VXPX-3N0{lyY?(6XGwak3xk{dRJ(3xU|tk3wB)Uz)vy6E=4uWw@*&N?~i zNgPsFH>a9$<*csx2t*gZdn!(HpDxG*o2;jAR9rK6&zl z(9Fpu1q!x-XWMCXxOLHrkrK->w(yn)-Z9@(Pk zAot~Cj=iUZe^Ag#^buCG8j)`RyEs^2Vh4!ZC!|xAn0~9y@pF25tSl<2C!M6GwO=s> zq?F3QEtD<`X)=jZ3)M%!v<vR0 z5E@Y@N!#yPC%<`BQ#f$lp_zG1Orvep*A#r-#l4Chmy@zKceBRxEQ1z*=tRf000|IuHLxYePbipQ46u=7B#4)^-hYl(St) zpQ5*4)J^GF2B87e?=o2Mq+lbQA1w4Pj&PC0U>|1Z>(03qxJ@sG+Q$-@ldTf!B2SeV z8m8Ga-sV4Saf>LIK=+f%6TN4Er#{*@(Oc{3G~e08 zMUI|okLsC;c>3bk+(k+wZ+R=I8&J>+6CYb!`N?kIAfdB^Ox`;$lAtfy{Tic5_duct zZyD(T1DbNHz_{8WR;;&pc@1hR+|Lb)@z|Y6S?zN+xKL{D#}TbjrOSv0yYR}eI4e|a zV9QWPeKD2*z)OlJqF^3-p?hsBzf4a<=rgxOU(>Cr%n=>?)8 zT1GW(h6XBp`$c);L;*NV2m%zsUo7gIA&0ol zB1(mx%wR$%6 zFfw$S$GXs_Uoq6YdId+U54QM{ssCY`VnWg(t;QxMh}el^DmNuQ=>k?OGaH+#zJB-z z*-J#=w0DiT)@5*2j1UE)xbkTdXdEq?D)(Xx7#RyHO*hW-fzt-{gwLjO6712nZ#Z#_ zOu%*=%)=ta&}3)zOFW@?@PuX4O{?B^=oU7?eQ3qe|wrwf-l0S4}2PxPFLf{%*o-F8{@%;1sc@XQSR za8xO=fd?EnLJju2y@HSsvxrC=ex@axU`@oJke&wc08hZ1l;@Zo7QW@IFbWV~NRx&G z6GRDb^e2WK00KpLk9GhCdl25vDaL=fHvz#=|He8@E`i3~6xxvHCnwp7E)T>B1IQL{ zD2CHtq5Ew|z0WIuhLE@|#cJ5EHRl zOb?41a~|mDK|u)(c`Mf{3c9C`1E zT{ojRhtDDaJV;`r3*=R(6t4my`&pnEuDfE-+@|IhvZBr95{pC8uXk0~ZA*}0FOm@q=L}zh79C|q* z^yLzIS&yoJWWa821Uvg%i;dUn-XPNpqT?iF9=v08qMvvGmH7dzyXiE8>w!UviInsx z11So`3I+QF%DO$~_objpVB5g1AwIax6f+nrGJ#yB#VdPno5^@OSkd4oS@~QYR-hn{XNHwaz zN3S99grQ32?2)@l)KJ<-NNi78uLe@?wDX!g*~G4Irx@Ye9%4_O(EJ$@ot=4!6iCGo zSfeGoiakD(T`+VuWgpO_AIom+T|)o@D8h5b#9;WxM7El{n}Rlp@PeoX$?5@>peb$_ z5JAaSBZ?XfZeDvkYLhQ4ALSZ4=74PJ$FqEI~eKrOK3tG|V{lg(*~H`85ennC?Y*sZ?W zpyxEFX{}XNEMSiI?%PM&ZoNwYtBBedykRjqa#LGdcCe<15uhHmd(3BpK{%oLDz4sq zOOI47mwCR^J*vZ4Ir-^L012|c$d{pK)}Bq@)q6+wO5mBY5? zu=e+$&As;VO%d@e5vZNa`OCJ36cHAZ-N18mrJ8m4Ubek(^M_M%^XARNvTM-@K0ql8 zszDxPOVUzptA9OKJ)4GPx_;3Ez~#bnI9yGOwK^=h^z0iqlc{uH93v15{0GLF_CPTi z8BS^#;!C_+abaOh#Vod!2r=ZLCW4Fb0TSS5x1SrRx#={(pAgwdVJ`y2qX%teXK%lQ zC|1F=Sp*At1qTIm)2Wq4&Ibzo1;q*pHbh{J-V(#Lc~Rzc%>9D~5G$8#;{bRV8>mpYO$J-H)ua{uw%o_yP~#MT^L2;t6_+3h5}G zp^JpVkj%9480c5{Rgo7xgGrjXnf<|RIKBJx8ydhte^b1t8H^lueKy~!UtNNgN6UM>Q6pQVAzBsu_qEgksI ziAeSjwZvXvJR_){v6V{T6848n)1kg1OgPHJVMH%_=S@wb1c8-H2MGBE+9MkF%m}2T zkF5U}AQsj8a-6471m9)OcNgVnt=sLlwEKR5(Zo!H1fPQAOogMnZ{fRT2hyaP=U zM6@?}D!)X_ZyePOgkN$Qsw9HWqWjB{+6<*{jskRBlsh_T6Q6KUF^i#D0%g?Y=Dv)8 z>At?c^ReHM!P9?uS|J!yH1Ks}iHQ;8XhC+}s9LtycBZQd)c5n5~-E|~T(*pN{NM%SPY~ljW#Y12+Ij{$HnpMk& z(633G%ZFv0ot@ofm|$`a5Xe}%3p!mdm18jjNGBc>E4B3RrlqABJe&Uc(+m&~0i&hz zT2V;k4ls_4jdk1}th{S+AZuQHwxol2Qk?$NMoa?t#up;pnCVt;{7o?;+VE(Xy2&^* zpYnjv`Aawyyj*x9s z+LwTWkhF`lZpa7JohS0ppr0)?#CRhjcyXH83RTCvJM;5DZKE_^3_0~REC90ymXL<~ zOQb3=HZMe$GAMUVvVWPHYVBcuzHw6Z=+R#ft`Cfj_W;nbY|R;&UtRSeRv`>KO{;p6 z46k69y^H{&g6LD5=VZH{!xhhn0Nrc2_GOl}J%2s6!QNhDcTg#XDLDI7cWB#BrS!17 z%c{3bo7@5iO407>Sv_Ep6x$C`4-xA+=2_KTfIrbhkQfm;AWlIOzqI)U>Q+J`mX+=9 zX#Nh|%lq}=Ygc4^5a=3`bo?d!{ru?6uZKj-iTcN?G^ z{mX0k_Yf55LxB$xGexNLCWQ! zk)*Ak$1Y2Yarq(FI1lVrRW(JGo__%(inoSn38Hi3V7}gfh@c?RxDfMCSd`-B6~=@I z{8H+Vn49<^yQHK;F(5x<^(C+QbY`IfHx2TfjN%X2J7uyMI@?oS^bc_IwPE51G`{yK+?wp?u#yw`>MRR?BMcg#X$wTOmXK zZNvO_?vD-g?!~1Ra}bHK^KZ7J5WU)e6DHtX#>(P%#eAJ1FM!k}zv~cmA8cj37!k&9 z@)5UVA?3V71M*4#y7)9~qFQpwKs<39u?y5GVR3GYt*gTb!+eC&qxm`$kjf z!hlOuZ9N1g&#3<3P@H}UHfEScZ}g7# zdoRTp=DPNhV{c#h^x zNK}-WR3xZFiK}$|zzm>>3|I}}AYBMO25QzqgqvelR!QfbT#sx{gKV9Qvp`Md4MPsq z#j^p#Ee#kKk*`rzd2euyfvBI&u}NDywt{d+zIp&?wznx=08Qrz)OSSv0cfYY&*j1e zGYoGCmpi$L2n)zolw8^Y?Ft5s(7@vnsS8%4DS&grJ>XO3gH39E?#K!`jQ4trSXuio zs$lK~pr0tgviaQ8WDaA2dlSPYC%;5{{u6`YASHG5SJUs5`rWkP&96N zazhwT1azD#+C5GDE!gJ{WRjc5?5P1{?HBqMTR5CEm93p64A4mhgNtFojSQ_(&NN=tJ962izI zFXgEffjapbWT30y==iJLkMNm&E1Hz13}U{@iU z*}cA{5UO+;%W*+ zg*IjaycA-zmE-eMvCc7Ih#vZ6CJf}`!7_Qh0w zOxyrqWiWjNjtLOmclF{8vfs3{EGJw$QJMJRuEzjrf)=?1f!H|+Fx~QruFoJNGvF3; z#r!PinMoNS4MeRD+=3sP@Mi`}E-Kd4lD+Nyo7|PADD}A6^knto0Q~bfD^+= zqo#lX^S>SO;uy`W-PS(aO^2d%4;TuFTNdCUk;}q7Rgd&^sj%8|=zsC(L3OGi_`vT( z{s^2S$*>r%$_OoQ0D4YZSs4?o9Hh@BbS4S_dg>CqwBSYODJm)w<`O^*CeL}|jDc0q zp@P-8Fm$#XoH%%GLT(ZTE>1VNk1;JkT}VO!bSkdV-yBC8V$fZmp8QYcO{ zFnti+_zS0Dd(_VW*U18gfSis{uUNq3{I~UIgRH)7$NEQmJ0FRV*qJx2uT^bwi4umF zxCjr3jAFvD=cRCjH$S#u#dCpwQzPY!E~Byf+I^zjq>{D7eMWvIdxyXqm?csI$_u+a z$zC#{5+y77=+vPtE^ZZUc39jy(7qs~l1`i`gNTO{18-kfmt`Sq5iwnuPO|7&5UN#9 z*z;6yXQcrhqIfrh5Rp`;#J}sN6(Ch#Ur#66vmi-k1_PK2Ev}tK--n#}8A2~V)hpPz z9q8k{S6_4(HRy&ZrDCB5P(q`?2v?epdUiWENg6ZWHSztcN|E#w%&Xe zq4NuN2QeVLj#di7+nsG8L!ZF!a!+kxqDA(g%e8;woivbN{S7b#I|dM40jf$iIA-Ta z8fLQr>B+zU7=iA8YqV7v@VNtx0=nk=kQ47cc(4qJ*EMX)&j^0`Yi$w0{BZ%RQBpzl zNru`$MnY;z$g~2Rke`5o0PA~zP-8Uw0bA2~I$869kHPu9e^akszMNWt|2Ntu50bd^ zf7&+rXdGj`Y9!uNRhdDdavTxvI7-`^ii)csJ8q!~4%Cy{xG@wYVNk@~yK+=bX{k4e z>ECp3Hh7#YH+1-q2~GFDrA6+Mb`_ER5(*qSE8^wL%K%^@wkCej#r~x!2vBE!&CRBu zo2{v?Rv*Z`^IC+GhXQ+W2tzRlr%IH=^XNUwPVc%4tj@kXCDqOPO?00lKeW;kzmSQK zVAB$Rs+_E>8QNr`cQzw!Q_IWvrf$??d=zM<_%VA|QJ}jRjvSqvlOxT*z|cJ~@QNH! zplb`gFHU@fR2ds25JF-Z^4ktLBqq`LWumsrL?n*SnFIHkHJ!QGgQ5bxop zxBbwaOQVX>aQsC^zJl1Q5=}cXK#qO?ejKNXXq-O$ga7o;%IT=II!xJ(PfveyQ9$Z? z_Gx3sz^vI$rHTKy?-15b&VcEAAmtfoHlJP?n|=Z$SO}#>B~<6c4+vl7gM&>LJBD1I zk3Rw1TvJ);$H&VnjfMe4ljTy(M%Nvpc`&4y6kH%KOVHGh0fSo>+(za5hm^s*omU91 z;oxhDPxkfe*JmI;kyKE))6|BFDFUu?ursh1!{qvG0D@^rY3X3#F*1ItMNro^W5+hW zevh8-Jw7NRGI9k>u_saN97kbs90{hoFEJ_s#gx^SC*CdS!N$hM%(WhcK=Cb&DPi)M zyD^S=bZLRvJu&w)H=AF_DId4)&Oc&c@EEE53BrjeZ_Qg5F#vrm%~bhyueVDkWCIb_z4=rskVphe|pOC#p(A8gRnK<~4wx zHy7u0unDpPW5yKUAh(`GJ!_7=)q1ZTxRNQlU@Pn0yLM$l>L3d+h4@W@UcSG|xq3sO zljDk={RCC647V|#z0%D$byVW|*KvNHcQyoKHb)dDrr-C?&BVg3)*)kY{CEbDX+Yl! z)x{B%RU2Om5LE-1v2fK@$FL_-5JJB}P-68XYMVB#)(=L<7`z>V1i2W!a{Lqd47I?1voWY#M@@fPpW32k37~(0`AB zKiV5tr!^?{w?ZB22YpMSiz-)lBTA7Z2Q;1DTSfE3$Ei*Xj9)4*FW>5L$|4k%D8P;M zZ>SN7W*Y7p6NN}|MpD{l?Vez+b7hAL>q|cp|$=>I%NuIo=h!*pToHe>^z)%M8BlJ#kOz1R}e`jsvh8Bx=Q}iA^M$LL^1TrV*I{yihn6L&_PZ z0V36dNX{+T4G(7(ju@gT;NHe99VW8{FuLXHbPK9$lwWamJpUwa*hpb%4Gu~KRRS{n z`nv((+8Br;n!CtNCEMoXHSnU``aK9lUE&gl_YuDqNVO4M(kcvWL$yY{K`3sS+1Z2G zvjr|#6C$(o>~8bOn+XO#^928O^>$Uj=yetN5ivi36hUPQa!d|)te-tQ2n`D1>>1xJ zU}yJDPVS%IBJ%G7656$c3@cNGFtZ%Rd6rF>S{x8NdtzJWT(Kem^${Knl$wLsYmO&cg;<%KFOC z|L6bzE{@VQk^_s#+y48bzyDQ{pqBo0>#&%XC^vZ$f0-QB^0xl<`w-?bBEEphh>8gw z?3xU=4BYYiU8+{!G5_<1iagxzI&45yuH3qH_>|M{%l8V_!WLr%<#zl0CPj%2<$}N8 zuZ!=M%%6*hR$!rtGeHwgRqcy;^yrk>gwOBy3%+^d-aR(ZuQuEEEAs#Okl@j)-MoKY zQSci^M$;vpR{J=hIs57G=Q6iGRc-U#bC&J*SJaBC<^Ss{I7S~m*wy&Y;JE*B10II| z{~MzJH}?vrpzz<0%Rk?o1=ez*Ta{{g%e_Jrz-V1njjbDG`tJ+v{{4)q90Kd_+T|gG zs3!EV0S+469?1N2p630J3#0z?nhlV)AhW?742+eD-sAq$Jk`CAj$IeR3WgPeXiO}M z{;`AN)`l$jcM({G?-yn;XTwhVPLg9;QG){y#4B@4sdi6DE%9Kd=4sbpQHquvzTCFIsB_))Ug+(|<3Kzh5yW_|L^? zr4iRFoaEln@S_JMutlol(8oMqsH|!5w_x)jT5BiE!BqfUzbz;%tZC0SdM$3*2;>yy z|9*O>92pZxK4h(s$ns!|+vlY)h~RHzgKTcJ&AtGVRsooRUTj%ER1E&6Kqp3>zx^A$xRgxx@Ih1B8=V+c+#BBy$rfpjH?l^pjhlr{_$;bPITU|wr+ zT^$#hAq(q#`YR|b?*p5}VA$c&Q35{YSVMdVZi2v>$n!8|aBy*HUD>mrxpr?1)yd7a z@82(@c=STtM>>^?lcMWZj+XywZyYOkj*M4M(OlA-yJ<&p)wpzMZ`k=EEYHr5Y>Zns z&^a8D&*o)Q-W@5!+myuRrLyDH#Pwi@lK=on6Aj-dJq2?C15xxq&9Q`x%TGQE-z;(Q zP#bLYYU}GIq?P-3nq3##DJ*rvtxKelXNTb1fdaxeK@(AmbXkk@RiGVj2P8ry5;%(w z8<&i!q}(AEfQ=U7Br<=LfHOeIiH{V=dJ=?!$lC$ege$r!;D{W5;uA$-L9PrsC~4Rf zZ9d_O%0P_~*E7Ogki&XrA%&_+`njehS6?uGpA%?*|NQC2zlJ>gzD*VL$-@qI;&u@1 zSl7uU>|Q~|#xgNIEM+K9*l9oJbX9-RJ!*58&9&TPfe~jo_?JzTH|s`m^!q8E8(JXr z@XQ7KCEwE1g-jiK>3AcTTo+16$=v;Rd53|X_&^({RvHoRqD3VPiXN17?a21H^&>Q!i*U{RfN%S+Mp*&k?CA9N`soAvDF^MY&(&)waN1vz(_kjK(2C0IgQ0kE( z8Yomd8BK96UR3fh957p=^c+W1{qg)Q@EpxXwDc_`VGkE=K-&3G*PQjRUd;jLx*xaX2 zFYeu&I|AGdL;8TIc<7nH4!X^CGNX9_W7GryrjpsJ97uq~$_&sK^E1~Y_iRuUhJ_v# zd+R4uxTS5EkLUoOBoG*0YK4!AGRN#djrr|y@l3Xezz z_lyS`-aGvmw^)kgTtB}cY@{cup!c%FJmGV;J{N3m_XV9~%gJE+Hp#{uPS3vN;H20| z(K}DSU9Fv4StXc!PcoyPRcP}|{!d?r$`Vf=3_nZb7<)by(i_92ve(c5#lme{7jE&= z7wz|tI*{b~vEaH|gp{U8&!X(3-)WuaP2xVPt5jSBB(`GWA_{flUW8t&9Tf--?8FAe z6TrEk$=A&s$EN%|_l;(@ecWxIKZmjum!BO*FoH>?!*M0-q^?Gv{RL)ngtqwjA`}_e zbyh7X3qcOCP#7#K_gmkco{xQZZcs$1bF~>8vr@Ix#Y>!twaMpx?)=YM+M|LE7UI+s z#&B%UjY78J$ZzTy;sY`TFDT(>m%K+jBYTAug5)ckGS8`V%q7b3-uj^9nfgd|s`=Z7 zuEz!wc#8>-7_|+|Hm;;m&$mTJM+M5WWua(?9>+L;<#2DD?Jq1$R@{HV*2{EqL8o@&g2OwQPW0OrzrE-= zGFBHo+;6*eWcaPY!&ED(uwZ+z4Cker3kxsxR8F3DWxX`4W3n!R;r3t#=bB?Vy&Ovg zT$s!B7p#;iSm;bzKJ;1(t~n zc>HaYAr7GCjL-914p~`=L(<6twM42Tz5p-=7p3UC=t|5%gkgZpG9-gc4Ap?2hj@XI z&r5-YkM!2A#*_{wG%&D_`J#O!6R*)$5-lA;&I#*>VuzwZ0!c)K03()RaBLZTPaGH? z4_YN`w3bU{!-X;Zsr0zzrh1F1U~U(l!xL?VH}cZeGtK`~gt+QQyHdIa2Fu7~L};Xs zB>V)q0E&hIM|pYx7$>w6P88S-{msuC7uELiopaePs9t=)d;XmEhSJuw#$)%xdaMg; z*)KdeNVnp)P&tje(d&(jdJf-CfdH?j&_~j0{;F(p<;qhVHb0$O*5bR#J=ISYB1AU# zrHARLqrEGNBP%xL%*_n!Q3Tj1wl;IZqh#;#9oOrx-LX8JdgXCz=1NmbM)Tt|z2SKx z0%hE-i-bBof8y}i441JJgsUMaG){o?1HVIXYf74oQO97oWWr?O8xVm3Bt~Vp??eM> zay}U?d^;LU^guMY?%pCnUsYX&!v>y}1f@&LY}`ngj9TbF$yjxz+3$;qk_)T+7>=Ap zf5rl0iUDd?qGKZ51OE8)w{O=0KR>`jBn&sv_ET9v$;<(1V}K#?O`~?f>eYp8IP~|! z(PA_`qDOZow0gbB_Ll*{)i)+(I~Afz;%}Sv{2NV}r|c9193@zY+z+zhgFQcqpBG>N zu84_B#JpqzCj%P-X*6u^cq{m^h=^hC41@cREswpy-y;l>*h4+k(M(dPX?KxHU z9^tfKN!cCIWQ^c=uxp8-MXm;O&J@GM_!K!OLYH(InRWd8bcS<-5WA&sjaK?R(*31W|uOI3Xs!08GPr}OZB6o z9I^JLWf`}vj$9a%3%e6}tzI)h=vFmFIf^%U+ZX6g9Snh824`F^yBDqGzp))>OK;gy|X92xWnv!7))fOmhL73QH44 z7!~jR-Elzgc4${FEA0ZtmpVD+sd=+3A^tMpByjp?l^@6GU-<1w!kBt6aVwbJqBeBb z{r=!?1c=Dnc@}j~_%g>}x4|lTXNl#Rz(I>ylP7SagV0rDOTv47aa)!Oz zI4Z&Z?#l;C@3IXHi?)j|f7hz-`PMh4^;24W+GO6{+Y|TRG{5%Un%Vh*>&HTQT`G#+ z`Px^W4c51ITvw9$)fa8h($;3P)z#Wf$>`+o9#&1QPQB}8e4x9syXA?6Csob$9kV-0tR&A*2MVD#{zuJu&%X2=oUQDlXl-^46-yXk8>9i_7_x#*p=)0BjC z``1&-QQpg0*n96b$6na=gzMW9hN3t0kJ(yvb9TIGSlP(GztJkLO3QwGw?eGe1GNlW zFUzHo@iiPhmfx7!&sqrQgnZ+k;h7eQ5>{OIDlIgrN35#iz$Up(ULqLf`zYTfB5B5< zwzPo}-`HJp1+x+>0TMqER7oUGC$ zT^$#1e#XE@zra;)x4F$5gU^s9S_@%1%Ey_#@H=b$jkRyC z7zz3A6&3G_3Qf_D7}&N=RxGv>Z=kl4}N1RQ|^!J-D_04hT<1FkBcvqig0*ubLyu= zj$z)H&;8t9rSTen-NnCx#8l@3H2P~(K`(E%|1vKf>I`!v^_X|%m`V&K%jhNMDedDG zauj8DW6~IECOV3zOXmh7!v?!&;!}Y-RtqUhQCD}br)RuMlja|Z;0>p!y0dkNDPpyQ zoHvi2I4DfbovzeB8j&e#cw=FNimv#qxOL_GDhro^>)&!7?{_(I$}yoKk$#s>(>#-p z^QhLFdCEyrDxoaGee4b?3{;|!v(I#GU-k0kePS=KY8zktoztU3I`yh9FWgW0@kN!t zWTmNSaf^2a25or7_#bR%s=;-XP9H!oVSypSSwI2VD+lYy$;Y=qIikP{J_e&%C|){{ z*$A4uQqlD)qU2{%TH|m)!(|^uIv*Uipxx~2svI8w!a}v*$(Q9{_t5UKq<3DxiheqJ zPH~nmra{g|3xf2L%^up8%tl4sGPzl>S~WmCac`{1=c>`Uv-T+d5I-Ye>0YtXZh@ZU23dI_b{GV|0}Bg4LX1H@%y=FWnFA`&m^{ zIk~rh90tKWb@ir0*v(Cj6y^1D-yZ&&P>V;Ic9oI7FI?5l|BPQGPj&R`bSFawxJ@5) z(qwuz@<1x1wufj(5n4q^6sy-`Dr5NpkI^y6Pgj zWcnA=*!Lf1yl}hRU8wPg(2{+0WjR#JR+df9?@v|Wy_O^~P)W>Kuk`G(hn?^047G&N z{hmb_y+(&g^2s&Iy=UaqRr6eR*@QCM>-}5O0uPE`HsAAab2d6vD>1MrKOGg1Cq^?& zL;tl=u^XU)K&GA-E~uS3)5M0-ty34ATFcGxCA(1SUDxa)1wI5f$TT(p?R zi&16m@~rdd_o{L|?0I;Yq8D?tN?+S)^56p3@y_FdJ8#qN&D#EREOe9ffh3V#cO+Ad zm`p7yLwCe-ZC?;P&b0S31LHjBl6!9t7*e;rCGLxOuMuHbe}%X8awyxcD*4tEI!q~} z%Ubu~nFJp)QhPdjbn!(>S=CkHdqnPI$#ocZpF~M6>;G>O`XnMi#$)nINw8A+`AihE zr(B)T4#)ZRb$!d)TdADya#pO-g6r3^rr(s+ti2~txT^LruBoE>sPcRmV3r?+Iy3e*>uHo?d)rVIyWH`TP`m~LS%3s>Nij^r*Ylk{@TVr1H z1-f*b``6kT2lt4K$tTNR)1<_I2ihfHAD>If&1ABbZKGkz~_aV zu<*4MYKQ#IRoy$k3^Pf6_X>ADq15E#=dqw{GSDNd;W>BEL(@I00^3W*77sP4s<@pJtPcct%MYrq zeZ*+0iRUA+Vcm}KiJ?*FfbQ+My^_jPrG_rIoWyqL=Q2>v;SXxYHFg;?Nm7aJ3-h0Q zBo*!D_dC#K{UvQ3xDaL`fkraW00a<54&FYm$2`>;8KB_5g8h8HgtR=p>`{77DIsYl z2a4b0hJ#_vzTUfZY_uE9m$n892O=h0F8J}hx7+xRZ%InYgjL7h63%nyhL~CXN`1d_ z{{yiwi|GJwtvIid4JI*((VFGHZUu*7e@G8L?V0%gbapeG;=t`(U+| zrQydwy|``jp9Mem<}tms$7K;$XF+*y0V_>Bh%Y0D?bNCTVRZdsXWg?h=~Awjeh{$i zUq~gcxmxr*M_ZJeO(n)bOcw{@IXGK$swiFtr?eaTE-35tJ{S{O2a5Y?u1~f=9ARU% zgSHuyFK$oHEtul1I~(FL8Py%t8*z`VWc$3NiK69Wcl0lcvvF1U)Onmb@S;5b z$%5d@CBO`2C9i+CUo|=}?Zu004c{76##>4&W@uP$NR@aQe?i-X-))q{!~ zoAjz@nhnx|8K~!aeSs{ymxOqqvUNA^puG1_IXQ?2hf^D-bO%O~=M2e_NEH$J51;S< zw-8s9J$A~;onv$)@yhD&-ak25yxb)j_Bu0B&M9^(T~}_Gii?eJq@x-cKj)0eF1Rk! z);-GKs#3MIv45ZBmy>c|(llMB@^e6v!vCf@VjpF0XyIZdDS17l@P=)Dh=*Zx)xynN zB!Q%Ibytecc6!N9CS75FyLQ6u>*#Lf^@lI!@4fGOPdxZPqi}-DEw~hBUDB0tYWcN=eXT-T6>A* z+9hHP-c|j%6}rbgcT9Qb>C*|0FjDP&Pkdj79xG&*cVhDTDXme_?(V!TKz-+!c-4WV zGpD)T)tEJlc?Bin&UpUxsgjIWfTwadupmN-6YVKzZsLR`lW8!Zbd87zG2T$*@Fh&6 zM;}LsZIJh#aA|hGj`SzeD{Opngbq}g#83lPG8Wk%u0bYp6by6_WCnK2#GfG|5ahFR z`KcQ6WL*G8ikJGr)zc1efJ}ZV@@AERr6uh(-c}lC8XM(0Fk;eLF$hzF0RTx?PJbwF@CA~PbqnJgQOWE>)F-$Lmv_BR*|lXC)SZwDx^CuJq2q&QftO(-zYJQH&eD&<=sSYc_OBS z>-zCa_2R~s@kK-xA9O&{^0-0$a2WBC?}Cj)NS*B|g!oR?5T7QW2fK<#lZbpo?;-qA zw1?PHPzL+}v|$gUR;ZN&>Olg)%Amyo+&NE}3WeqYSYcAb6gvd7BPUKA0+y3H;D6}s zIaE7$$H3PV<@-XPAb!{c8Umk7mSNWD$_g_AE{go11ZY|S^r0(RYzVs3VB|Ww+fhsE z(*3(|F6V6!<6F6;I=j*W7j=)~Td&j}*F#Kvok>OgvR$;AxztB`sgK58cWtDSc1imD z?jqS&*U1oJA?$@M`(YBKnq{K3TFH)nzWg9~T3zMO8xS6;xBT~>`ilP*kkGWqlam$+ z#W8=ewj=j5U=M9#`XLfX_mw9rcI7Bf`ZP~9*J~MN7vJ#!*zHxH5BtO#pSa75zz~-CvY>QxT3bRc3zGRPr^N14YQAI$?$B^BUtJ( zi1(6h^t%Jpz09ZXFt%BlJ-mMUY7x=9hxJVob1jZ=68-O?8{J3$S9s{|>Z~EQYCeGw zTs4x_$(0#_6eCH-wiLQ~Q|`nng5#&mi} zt0tnvR27^TgV8R7Rb7`s%L3 zny5aH5lDkjkybr_t_+rRH437l)IWYKSE_Na31RhwY*@CR)OF(%IL&Mwz%90erlL}s z1#4c6lnR)A;#_%IBCUGdY~*UHgy8g5LLIMQP3B#?go9BNEHP1?b`PQIw;R{{@+gMW z$oK&jf0|fpZH4UbwML=SMtuqwEdrwdS&QGQ3`jpr0_MVEtVF(b^ga|-#3hJFn)G^J zdIT$y75n9Av-Ksf6e6Q0u^F*kS|~!A!bw%IKb_r~#dXq3cS&$}l{0GR@ILj4HHhe- zOZgFsl}$P13rW?(xQ9kHq%PPBdG#)dAN+^nE#J-czSJ;BU=8N{-{>9uURBr7_zGU- zEik3B0?Ln8K;&nWb>^z6hhi9|SfevaK;pDQrQ3Tf{#HFl{ZD}_4%9QFukA`5A^8?( z^yAN749Y%=_t2rX;P@d@WsT`VL|ewG&3<$(d8^F$1-Ph>(CEg`Q4mz@f4-9SpeEPx zKnM|Ql=){2fz2`nA|ee(Z!0&9N}hT4pp7_1efqB9U%p>xEM zwlD9z6je(OP z1djVGkVQtNkD*z(0*onCCKTTM5WF8>dn`x7jFL4F2tcR(o3u3z%+>)z9K3QRAvmK7 zb-?>=24jTQsM`R!fYYxMNH?y446zjupV&YTrp6D%zfk!$)Da6bN6<;y;Na!9FTfK( z1@O_SFJPv+!3=e4)Prcc3(TkU+M%zYe9V;hs3H4ZTSo!Xr?Xv7DO!>V!q{g{5q z-1ho=#-Jcy^rl~mVfrfwvzi^jGM=`G2ii*-0E$QpWEDm|G*|TP@Y#zJPfr#Fu;(4w zz^DGI)6Ey|*Jc*#w8M&AFE<@r1wVSg3z&#*k%$4Eg(4y}<2(mTi2HSTBDLGwWn9VG?he2;|cpADAOTZL?$k=xCbf zcYPO#or%2qH1Wzkkq3xm+%JfKi8p77DuTL@(#j_ootQmw$!jr*#k)sk$q(DVL-6ON zjw8tJ^R7zt$oM!$UNP+1i+o&5N`YpdHGNq3=B3B~cHEvi{BKqrWTrm^M9f# zY4GcwXcT_0fKAjVPZnt`b!BXw@{&J?PWz zHWHmIQe$_l$*7o`p#3fygRB#K*WK&N;Tm~UTO=yMKFQ;F-v})iv zl9HoMa!B%+{!8QF6Mp~6HgizIlcLRdr5S{Ax(?dFSVaDz1Y~eC zGFgG~V#U?%RGr}IRRp{c);-K^5a+&IjZlxb~^ic zo4;bix^Clj_w(4hZ=R|seKL+H)c&GsFXVDX)M*GVBw0Q9jjvAL&ZOiRkKTm#1*jwy z8^S|96i6l$4Pk6A?vVgUb*+5rp95i zzmx7HjEFfqek0X9$C{m%;KJO>JMVO+(l!3@xFKvOmOJc`CqYkJIuIu z>WhCee%9kl-y(|35)4Y1*U`9|Tq2Eot9244OmvdK;ybsMS%MbxFnA zeSRJzOl4xvsC%?4k0S1b-8f@VrY>n|^+{eClkJcgX{sA)b-#j-n2O|j&=qqP?#li; z5)IXc>dfzL3$@+$WuO@RZ%T2T;qNC=bIalq6Y|A4r58U#irhKWrqqOIy`6CQldDc@ zLKU9&(o6KW7gIKiOzQkb6y<4%aSWhL>S(<X!Fg!r)wY2ysngbt}H3b9ZAzh6Uz8BOgE#Jq}s7-XoT!qV@yK7XM5eD2cPha+N@Ht2MV53Ci`jW zl!ispSQG7hYHt-g$;2DSTPig(;`}L^WxLLWmtv6Ton2BcBp-ddlS(Ra3TLSKu`^QL zDO?BR{(E=N{s)NCCjJ|Q3(#;mw|g;!>9}N2t`~a`-fotfe1lh+vqaV`2*o(BI$>^3)70S%b#y1EMJ!DA-b2Z?wgsAie+>~ z@VUIS5POCXkpQ^~*wcp1Bse}p zhId}oejVW0fZrA7jz3UTB#N1zKK+1*%=x_kz&`pxf8YJ+*#F6ey7M1Z8A2zcf+%Y$ z@JprAQ?g_^4044;Dm2uTRJt(Wvb3vox3LEIrI$?c7#;VBSs|A$<9>$d>lDr7gzCDv z0(p`PE*S5W;~sOf+3^IeeBm?gu_ z*b}<6r=)R5uXpe=hIuZ|O%3$`}I|9fU)XTwKH@iO-Fpp>566Zb*FagFQ9%2<0FB)OcF)k8zqij6q%t z39L|*{Gi&%7VMvP5}`BFkv|7mY9_pr_G4kfvE_|IYu=N1gb0~g<}glAs(avgW$3j_wJlE)=CM>qR!EKH z1E;&vG^uBZ5H4bhD@dY|(f&I@zNfzEj6Y0uSd2~xRRMRO($#ehsMLDqi-(T;7(Fml zX+u;+B->ssUIbv|xiBJ^<{5?8;=HQx3GLw*#(l~H_%7lol=LBb+B0L2 z%>d6j?XDn|rdMlP%l^Qw_LVl@wm5QHqK(bP#Rb^nPq_?8F8;va2N)ekT*P^`))<3| zBok&~xkW1r=#%1RDk^;@Dt9qvk5;=ZsmmDRa=2J6*ydGB1uywm+&rOli!@u;ygaoY zMAe%=%7*Io{_#xzt7G{0zB$bO_r+CKK5ZmH>Vipbg&ktjza)AEK`sW!Mt8DrP01u- z^0`RdqAS&zako8691&sFlZ zIMsS&M&>+RRJ7h85QES$(!Wg`K#QCM)u@K-bp?cK0muca+ZX6RB6zUh;Dw=kkeh^& zVl`mMz`%FYO;>0>qC_7+lVQjR9l&?K41EhQ83T$o1t`RU*ke#o5Ywmg#`dVxBwCOF zD+wK0kIBf0gdy)H;Df`|1Zuv-o7C9dH9bEc2A&D1{w%6}0^?oi=>6L0MO|Ig(Ow@I zsQ+VL0LpPf73WaO8R|!X`f_GMR!xMUvdl2+PJl^tAQ1e|{JvKdGdVG;)&*QR&}+O4 za%n(&&hkIlM>Y0A#nYtJ>;W_;ZGccVZc|lRiH=*NL%uL!f=U%`)iDhSs{FbnX;+az zk5HFIM;G_pKl+}vxnF7dsycRq+N?80`sZw#bUH>v&=N7Z5%!C2PV57-w+? zMqiG;xL?$;h+L7mHw#B#_&)=5ON4 z--V1Ct~YA;2qo#9VN{`PXA^mG;QG}25;^f}JHv?oKLFQSQ_9al0s*ZK?;q@Wpicmh z*zYhI4_c9^8IZisCN=0+D}e+ZDtYtsE~*oTj_m;V1+^hU3w;pp4~NlYrEL8yn8ZYt z9sut`RWv~5NmbxOG_zn7j6we;dJWuk7&!pa-6<2&k`7yGR9OsQSY;5LL&f5$!Q}!b z>%YE`0$EaYVj4t%P&I3hNxu*nD`15WY(E%zvv#_M()-|`+_kb#pz2=YPs7ASW$oXWs1JBG%_sJ-s*xpN1dciXwI zTh7jxl+OmzDSoMG+!F&C&o3$0Gps;nyKd{V5B6Cc{f|q%#B0=Vg`9y~hIlPu3UWG-h7QUa5XSWZIPV?y{w&o^*;W z*h1;1-w39JNm~kh-yA>7V}q+#oiYzh8~-rBepUtgsb{~v0B9ZD3D9oW^$f3Lzy>)B z@yP~$6afXM2s*{zc)<+MBm8*x3HRZVIreb1BTY6@3T>bzNK1eZGQPjvZTaETr_jme zx$n7Av#yytToMhxtu+uZFZ3FB`*;BX@7Z=wsh!0=F-g(Px`f2j;y-!y1zdHDzcz%6E9M}}DG_cip;McJ7 zPy*>69DEB{%i)Dyw%Dyx9}+gHpX8nW>Ne1rR-PFrc6jxzO=Fwi!46;f?VH&}B8d}aga4#&^f{K& z0s5g_2@H`HL}tAjcMo#uD<6~-*S$q_jZ(Lt_TIYJ(H>)eu=_trnAfCB1Vx(AP* z;hA8&-kl1%=9sdZ%E}M88;A;vi*xexkMR!}85<`^{iOR6Z+P*?20WlN%qN&ghS~AT z7E{%!vYO9dC-;{oQA!z%p+fbJwZ{uz{j-F+EP<>-t?S%qqlmb;JxmF1_AS?M@ucQU zf$&MV(@vECZtn0)W@}z8g)&UHsm5bwg75+}p_1qFb6!l;_6PxY(lLrRXwj)jno&W6 z{+N;e)i1)|X`j$A5nNu~i626;Wa_%VRT9}>h?NTZ_fFfSpTtqb639UL5S7BBVi84u9;9~zAT~b-`uEpW&o(c*^-Z!sWiDE>+w~hJ z0obFSh>W4dyyYo#3 z_lXxL0za?wwYK=Kep;CvuAj&bPX9+i%V<|CFJ&5K^qp zy1Dwa8Zi-&7#j?t-zgC4%4$aH$T~Ie~Z)m1k+=f8r;SU zKgHb@RSOG?S3vhlmLK7osD~!Rp7=sV3vJ7c%PQnW(jY{GoH=s_encd5yXQJ`8pH_R zpNxPJuDhd-1vK92LEn!LTFgkIN5H*}Lxf*XNh(T7OP@I~hKzC(wCAG3}D zW_e2Pyq8+V+2ThhdCG&Wp32~URC7E~rFzYxM~tic(EK@4^Rts4pPKUsOtEc^yP~?c zwh-;)Ats!ZkukV@S?9t98n`Xu08D4s)}}zXh8x-gz46m?Ph35>XOc!>z8Zverc-Y| zn~Kv@#NYsI9`{+UM&7x}2^w-d6yjlyfk+G$VL!o1$@NV)@nP z=uJ%WIe$g;&i?K)ZD@v$89KIou+w7&*lioOz_-J)SF_7xq4}@5N( z?R06?yRXG1&#WP0LaG%K7Dfqhww|&wMxuV5(J)^ZHFq2s8ma`cM9%xdiBRwwHm!uC z8vdZ@$lH*XB<===wtGQfps+cKk@ll%U)*gR~ARF zV0RL?-Q}=!TOf1nhG$ra(7IdAHT6RpTb1jJ)VTMiNcUxGTokY95BAdwd@?r-&OeB{ zhJTsvYxi>d%nIGXc;GWm?A0s(?kZcpzjjq6rw`MK>mzCu&LP^J_ci#!Uo*Ns>9WmZ zzaU$<96D?FO5HZeta7=+AdEY{>RVVT?W*YIPTQ4UUg%DmqBL1;J^Tm zjf~~WtHsK0^d)`Yqn+F14!mr4onZp2Ui`9=QLF#KmjBk9#mY+Q`}=E|hx`9Lm4{G< zzStYzz=zku>%{$}`#$G(M*23rcCZf+J%x?Of z@kn}p+LS;QrX+l*{~pri6Ty4(9Iu*usG;#nEteW2$JDFHfPe?eA3CVd*gZDFCeG^L zaUk{1fvXnAznEkQ8Y+Bi+iB}?GbG}iP1E(;f?w`d7AQ0?j9osxv2wTN9_PR4Uu%CH zsVJXI`~?1?oXOKpq3k1Hp0|hFij`n)R_3zf^+u0)v3{o?c?yffGCMSAf{d!pmLKvCc$$$;#s~Y(wh{8pw8`CB z*@3~q)jt3IxW^I=Ye1%eB?)d@Y@*4=@io?i-J{nSeI190k^2XU;e1U0WD9IJ(WE?5 z8(kMV#n46)dB1@~7-=!(xm`Y=5X=@B4vzqU#Eu_^Q5Y>C3YpDO+i(^4%bIrJh2kE2x%r5)gaFSrmYt+wN-J#?WQehAVvD+7`>_jBiV6 zT`1tUmQmU8l_(bavZ-1}^;P)|Mubf#OL+D=NmUJ|n-XVUqotQhV^(JJsb@xC$n7lY zl^|HOw1QVC{Tr!1UwOCqmQ~W}3g1|oYUy@XjB8Zp>2TTqj8Ib_r9e~2OH*X!_V;hR ze8gDXu7ctwA`839l|nkii?U)2-M<>`?B70-$ywnYY1dN|ll_Cn zOiY8JnCPwIaFay8>5Wq=0?py377mMHQ?7qP1^B(HE<9v&27RAd7~Pp$Z9hEsH16V8 zD4@`RR^<#EdR^^HFraV&&i>paTICo8Kl!pwwUY2`kKG-gYV(`3x*>~|RMAv(jj&AgSb z^(&oeLQZ4mp1LwoWhK*xFQ>sS_-CI>1$U6Ez&7WO)J)B6c9IS|&Pjz4#m9Cca1Ecv z7<%8J7rsXl@nL4#Z-CZo^CLb%f?pNB2?FS#P);==qL|i~;G`60U4x4-wQyXFpHt!s z9#y4NXf-yy`WC!X-odHg3$@8bIMvP_Z1?TRA3PGw=)ls+6NVc$W#ls&IDgW*rKpg{ zlw7jG8e0}kkQ*<$PPwf=-|1YEZESmuHG^Zl>LsR|I{0WQl9;GZxU75mQ(b)?$&UY| zQxu5sub4Iu81^1|Dc`sIgBhu-enD|n_Rr;iE|M>(L;9~wcVxP05i#lfM1dQb3S^ld zlt03n+$X>DOVv*fuTD+l4=ZavchY8*3-HJ5uExeA{BdWxk-L)h7ow?!dI*p;ZV zonV*2|Kwegv47=V^$B^ZVogfiaWrO4W{j$`9=JK3ELAwgKTv;qYVqt(Y!rt5ja}dS zE%IigJ7U8l7=@OsL2~_{hr4ZOFjAfMBy&nnkT)WK_N+qT)t&^i?rg{ znNfuNd~bm;#o^HRlF6i{zFf)EORV2YgPqUGS^JaK>W(_gdgOd^Tf0JXAg%NRlmNa!Yw{W&Y{i-2FTMuF~|C0KtDVBu*d!zj9HLK0|OUS9E8|Q~3 zvMt>Ia}nWxU&M<|Pny7E6I@IE%WxHOHwZZ-lHbFG@IiE~-!&(e1@H;S-7ot^_SjeK zaziVSpM0k=liC6&54WE4HHLE5)uSP3G>Gk@b4}Wzi>Ds|EqAo>qkB61?E+b&ZLjo0 zdTY@xYFtF_48l>dyGh<0G(np%5Z6*u8Nw?QK+kNHG!mTm_6IGFCLfLKKY~B+b*Jj3 zS$aI1E1XA2oXM^}7dX5`MLW^;m;BOSDPgD;Kj!Z=#g1*Uipb0ce)NX_Dr0UaJ-5{f z{Lv|_6vrh@8sl`IJj$noXw0UKt4QcuI9i0o@G8`g zfU=!|*6`pe_#7sZ8@79IGg3Z$1(HpeSKnfFUTx2&Ev>ar-vvOm6*SXA+owSsHU#XD zRw1_2d8g#mbc??UckNT~s5Vt4mkRnY_Qc3i&Ix`QW0U^A1^%dQ#RN}Q%xz&HDbScX z*gI$&E4f?Hn7x0h5Kys#0QM149X&GOH9K6NcITLCPpT0S;he_{n)hMLc)7~bfKyCvZoQPa83Te|=#*O%32Xnr zKr0;P4h{}qUQI_%gO@=;aWN%o5T0E;k!d&r%C+D^Ter6ch-(M>0)csR&?wDHJg#AS zB!)2KLi0mf^dlNNH%nbuB6DR1i2Dx~a@QGx0E2a4 ztl9V@Wg~CNVgTVjhoewj1kXT0^ajht(dyg9ZL5Q?|mS?Ha65u=5sdW zH_N{@Lg*B)k0<0ma5k4|;6JFyhUJ9+vf##ByHZ=d_@JVbRBL#-nauj+C;r(dpYQj@ z-SE@q&|>tqRvWrmy-{=Zga5^J!6fxud;SL>^&fp@Pel?NDfRE<7+hr4>Xi=_?0cX> zoeqFdDi9nQAHPKbNcW>XpWFjnDy;G5J+)_X=uYsmsHHn*`ZvgJ$rAl!)z9WEQ-p? z-Y#so3>chW{g}Bwpy&iilTcVQX!M~4;I;B3DCBN5E^K#+l-~h-V`^<1Tr#DHuej1= z>vt&D=jR8XU9OAM5w8u($vM)nzfoQV4omRoH+)(v9M2K$(^dc@RKIv}xASO{zJ-N0 zoYmLU-B}L%t;f`t?u!eyniZTMU0NP&)=mvH!6y2zK+v()GI~31obaADK|TH{bLu5G zAL48tN}fLu^0fq0Ef*%U@A)zyX$wdHn{TjaB08a5%sLiRtZx<1(*1WDUp6& zb*yGG+3GJVA4)#bc1h~>JDx`S?7>psH%iOP=b(W57AEoxg_=u2lM@VS?t-HbdY7xf z9(R6Wp$OhIV5oOAMiUiY05AgVd!%97y?uELeaF|kCpuQ)|DW4-GX8AXaYlXQ6}HA( zoN6Xe+fV6dJNaqOUq^42+rc-80-Q(KC@m?mflh<(jELpbgvX>ExUkm!>Jqu)w=u{* z=kq@W0a%Bgs+qXQiA>!|KD_&d44iJC0L+rv)uk=|W>Fe=fE}6p>w?#OmSm_~zARSt z9gF!+>$v4E$Jh4S_EqQp=PB{0GPVtZ+@_!O;!4|Z5W>h-eco_ZJkh=fwZqrOH;#lPaJ3EO z6y??nw+QE$+k6BJgTw|RS6OvMgDQ3*+2|yD9>G{LOyttMs>?YCGCkj>{`0(M4FRgf>YX zVR+f2Xl3-wr|sON%5k>wo6rCJ@s8~j0AXM2d84%#TYzz3RoKKi1e-Mj*nsLw~1psb=yWOdFV0J1`(Xu$)HwKagmC`Jf~5BI)n`#YiTK z9YK|uyzuM|EuKG0KK4A1R}cW%YoBbQrZ!R!hW(&apBtOpf9Y3?)@uNu>G}ULgzAQb zaQ?7gEBaUfq3Hw2mNGf}IXHZ*!Q*lH>@|m3fBl5MR*6mqn`L31J=DL?Q307NCQ9zu zNdRi61bRE(A&CkB^xWs6o=YCW%Y-rn?FIJ~_s(f@e4eQYQyHgCz=?KdY?8-yfAg#O zrC2Z+GpVfQQ$7;@x2sL!O z-w+0A~ zIf;8z_rW$o%^~dM(%cgpOJS}lfa@qE{YqtU%z8vwsVvr7D*Gmty}X{{I7+u z?r&4A*JOUJuRQVSu)mz(Q2fXo^ag_Brs~)a$@V*Flz*gpzDusFamWf`430WdekjQ% zv~o$^9x2gwJj#?#y}$b@0~Wf0ucH0#TA9I{pG_{Oxln&pQ%k=D)@z;*U{S?icCLL$ z!+C1mYab`sK_U2rV5p}sxKIsXU_cWu0!jeJxH=%04`a<8~G z?o3hTW~mdQGPT|)ws44CrL5#Ju9*_&MQcUOM|j2Gi&P`*FJVL{veKKS*a)fQO3Y&T2Uyp=wW-^Jl{)i^b48bvR(B5iwtaqX zciZp8{ZuR%A&-T-g@L}61F==HlVma7>RRapeo#Z+@sz-~mQ5y=Z;7yE?(`{ap>{c- zX7d*8mM$0?9s>AsU|?Vc1a%-7vOrmbE|3LqJ5$(7m8_XZGBhgic|-U%7nFqjBfzHNOqxXAOUDpjj^(2M-_oJ`ew% z$6gzXInUE6H}|9kE%!yr>zX0eXgSzEcYvC9xxAB`<61vMDaGQz;M!WKYOq9FTG@;t zn*WL4ma&f4B4<~!ODq3fmuwig>0U?Qk2c$!8+!G(V9qQ@g4=@|=aFxPV+5H`eI?OK?7H^mZN}(SzUZ=g=-zLHa!oNV4UD-C+e5mSivL zphgEi*eR zhE$XvI<2~HDg2kxiv!wg53V}V=4CPj;ZET&)xJH|cV|z+7%39%e`^)rWfRJJMv}FtbibzJ-l2} zQeqCu5BTo-?>UcO!RwEFS$_U(mZHPmua5*bYZZ?}GW~ty4O*MQt8{o-M@MJ-t;GHJ z%awoLJOQkRabl>lpbGG2$ZL@dsOb3K zoR{`Lsc{g!_2P$|C8V&p3X*hx{P6i_%|Dl?`QSV?r!mvwzkHrPpQGX{8sEfhUwC?v zZpocDW=BI0rX=$2LvhM+T59b4S%Gkge-6}`UVsgLh4D~gzi7{HK3ELOP--7%7|%;N z3ra#ri4Zg4#?c}zY>&gIn%i&o{3>!CnTBoGTR(7AeEv{yVmb7#&_`B$&adO{f`=UJ zmuCIEn9peYb9q0hhhOETx}y9w{^T;Ubd62|4INq6Wg?R}vmz_!c3(J7$)&j7ommjw zz3-oSfHFJYUsK?73Fi5M^xP{Lir#)ufU!I*_hfT{+xjYTDMQffjCvZg;AgoOM}00T z*vsPB$=C=k!X}?e%K-|sUAuWCoYB!v-`DQj-)#Hs(`8**P-#*e=+8d9Rb;7MmO5JSM4Kb0g zRyI|Cpd?f6bo~hfpQf{{EG1v-9g7BExfspK1HpuZgou?<@|ZWV&+las8@s>%kiwz- z>1=6c(^c|L@>W&iy4eM7F=oQN$di*@;kF(kN!G3U=_VWt2-b{tkn8BD>m5BmF#a;c zoLPRXhqQft>m)jO00IB!vTbE3AWyOm>fuiO$#omBN`9l3taJnubtvkiRM$;+`mke& zq_QI)i-hv(xAU)#ra4@_y15l|XHMu@=l4f#y-xb&riWU3pC8icIh6k{aDp>A_tsRy zYnFHEiRa4nig@)cmrN1G>ls1sn|sxm*AT0Y6*|90Ta zTH^c-rK(hA<3aVCLWB4hnOiyNc{pSjl5|q+F|2i zi#ybBhuE4oCv=5Qog1$xxNwc?Un+;~3G}JusJ(8NopDLio9C?`mUK8Oxn3s9e-v`P zmp0#LojNv@&cBojn8+?MdwLV^I{Pft`F@vQjp76L!3RH2)pojK9&+S8xa-#MYe+twinb4w$G3A>2iI|AjY(M2d*(zyLn^?0!Z4owc zB_cEaXC*)$4P z?`#8v2gL%fXrbX2hnN*bMjlZv)TddM)p z;{H9pueUnqTqdiDsen5-Gxxw3?g9B`-8?WC{-rkGkT{lg!e8Z9AAcI?S zjKZ;LOwRQkY1$}{+!X%jVX1^uq6_hBm|K){*UYKIKJv*{{ihPo(|hlJIZn!pOFoi5+ArGYe&S?x~p4?VX@vdyhtZ@CcD-zWO?6%OHZ2h&ehr;*`)O)1_u*M9mByK?dk zLf0x{B04~gH#7~I^E$;$xO8@rh2Z-*AIj+ZjF>m}ETjU*ZX`#zyOUMK z!eOScLu4k<>qnW2z4Tr>WU`Kiq?2twn?sqc@KhryXQA+BmJq$(e09)Qzsz%w9eR6n z>nZ=q;OTQ!(30o0%@0iJxYOFBx4mPtQf;1CmQOb1k7-=byFMd3QyIZOP+uSSegzGF zp)x5L(YMH*Of zf0qt6Cg*Ei(Pw&iJ=2c`54Ip#LX_ZPcINvG&0FbKwt>}06ZpIzv(NIw2>09QRP3>d zvOt|njEjJc#ZOLy9lt-IQi2g-IC_U3Q2ARgDmg1SR!$oU@6Ns)AIlgkFaNjM(kA`a z3?LUjW> zuov3@;8o={2^^EG!#$*>_uJPZa*Pli!zK!Q_y%-ky7kkTU3{_Q>qpuPNL8nh+S%l2 z4%JVI|F4$}G&dKIc017zl=zlAI7!{y=Ne&yc;iH<3x4C&1H)m%59^Bkb*#OCQY}|9RH`@_EIWp$VlURN8kkiy6 zUy`QBjL7+dRgc7cI!Gbq`cpsJg4MkWFpv$_r!2b5&e;^-Tke`>oAx5+gGuxyIXEL{KTuNU{13aH<>|)eVdluNZ1y7#_0U-u03&B<>=6MgO+Zv)IqJ^2l+{mv5=k|*HEN<*h z{2$PE@#F>&(72&;mE-2--h4d{ByR+Y+&jR51=3LxbjMnU8~5FzbPdT7s;;RS>qcp- zVL7&?b7)2CSdbpvH-{R;U2*M|2~r94If!}v8RbGXH>(`G_@qPc{;#<3H9*u+ZgV5> z*bL3gIsm<;A)s|G;0zJ)`vJYs2530~aT8)HfQvJr^tTo7dM>~9_Wz(9yhBKmwFzG2EY=K)IVow*3dTT4 z&mwq(FsThh6E@@}k9&tFXwsiI^rew-+1YJwd9#q2{JZmm9}`!oeU>~)b9)qyafhEg zt&!?uy|+taj9XZ!*(lJHjJ{(p#(tzVwEga}*Q$@bMLiCm*n4zu5Nl7ccQIF z3llT*$ilDmW#4wiy(Y55wm{^q13%;Odt*+4uP1;9jedVQVD)uCa|7AsRMTr-523N+ z-9Ps80U1w4xvcwT@8CRmezXm{GZJf`eU|S6H+=={TU=q?-GMLt1)sapdPuJVIx1(M z5=(>67UX@h~DUbi|-3A~`(!S#H*<74Dk-1IH6BW{Uu(yn|T&}<;3B+kN08M>; z+hg%2I|TnzDA^u`O`{Yx*-%#4D}Yp`-_?L&A7Fofkv@Tp3D&J!J`?sac@{O8Eav3i z^wmIaSK@3)_n?*|D!jiI$N|UQ1Lae=B@bdg{3IoggmcL$Wst_qgq}v} zrZdl5nSbZL*|?<-DSeBu6-r)p6(_5>R3@70Oj_RNhD~H9aNLgYpqf#BqyMr$K!NAP zHVZ*pEmZyT18v6O5UspD;)*tI4B?~&ew>aQ(;7P~xNLaARAJ^Vd9!WLpUbSV{q-%M z@iQmfMmwS)^*G`&FgzTmd(0egdc%T?Bsd5j2t*I-=WOW8-}c`qvCLjL1IifZpKGL) z{eQ*yt6DUGJz7*>3b*NNR6Hs{4E1_kXt>{`FA8w@I;2 zo%L!fP+6Q0eBtrmf%P^rHU;ru8c3|)+Bk221CQ*v+x|P8;AX_<54^n;$tK?jKLF?M z44Gfwc*ApUyHig{TznRtM-flzzLpu^upg;_d2bPjXiDIHmMrMAxg^R%h+646TL# z1E;Aq0E*ke`95+eJkzzdSCB_G@I>m*wjyCB8W+JkCU8z2N)YE&GJ}*`W0`>4lN!^ z=59GZQbAJDgB>L?IiaFB-U#^e&0eyII+Nk%;~`0F4|7X`H(vjzAz==vTU5W}Rx|gn8d2$zqC1$BRolYmu)UCZc zi|%yxTsoQ-rD1oNd%Ni5v~)iSrM0gA*#=S;&z%YA<#0ob=eF!Mj6_?3e*(2TjKS)@;kKo+X95b0wx#K9;Yd1+z-^s?SNU4RKP-AcBCkK=x#6x zD0U543sJ*RaGo_ zw0=dI*5Fj?m*D|)RQ60p(iKm6HP=@(TFE)-OYG<7phi5&K-BZxEbrmZ=iK+nlgUDh z-Qair7;(m2V`0AQ_ekhl4aW-_T4S`KP{0eizw}D&0 z-T?&gODhtU8PpCPv>c|_WHo6Q44AmWu)Y1HZ1CUR?lStuw<35KJ3eo<1SgLC7j?MZ z=8N2fPVg1~y$yL7MR?-&K?^;f(9;eaa`b@-IcEn9aqv-nytkH2TM(-J*!_jw?kzP} zSzSh;wNOmR`r16#&{k$YE$>;jqO8(4(Rlgg`#1j&WoH>yRl9}jwP?I;1eazLi*+Jko?Fka(N7hlh`N8PuIuHI(wzdV3^B6Ox;zunf=a(3p0%$+gl zFo^CT`ys}!_-+6P2M5Zv-n8JeEoif}3n~94%}AH_f$3&)Y2jGFvKx{i@QrNwG=Pq= zJlXIPs)P1e=Bb74Ew|z ziYv8AIjcnDyB{q-$)3-~lPt)tY=K((F?32FNPm*Kx%X>iDDVwi*U-aM8v$c4tk&^) z+lfG?jx19D)A)istFZQ)_t#Wbxz_yfSV@`4a2}m~V&6V9CQYex`uXLa{zO(^&X<^M z%s@}Locy!69sM$&4j(&5vGoNEp%L!$r&q}4Z2r?xi%RBY#&|Dgg;)PBC|uSmgg$;6 zWf4mFl_uiwB(eta#N{B;jET z-XY{(GcQ^?_u+B%AXxg@av(e{83F_HkRib$n_YaMygh^weg96L@YBte1{`xD$&>o} zv>!iAxgiM10E0EKp?2j zv*4AL%-b%?&%a1R{0{Q*uouXICj}SRFPt_;_y+;3#$Ak$#+#u??}oDf!3Vns?OsT+ zeA@o zdlHguLv|Te%>?k`h9jH#xciVn8dyD%B;(!d4KEPK^VhFR4mER$=p--rTbmGl{8L%# z7yZ()F$F%jVZgCFuqr!YR$g9y{;%yv%fIxd4yef_k9bbkPLCxKAq|;$gg6#}66z=v z`Gl9dA1830dwNQcMt|Kx{QNs&xf++#q)G*Hk8RQXDT_SS*AEUU_``!D(W@xcs`L2M zL!`?sGTZ}lGRjWJwdhxMS2WPkWjlm~HeE)3W-GI_mLhMDX#6+dOfmGjlZ6`>J@4=R z+~jzGEm`QjlbN_VcKtX}IU&I2)8O5I&XA_Bqkc7{Z+NCbI^`)?T3b%i3kr}=UJsF< zV?%Bl;u`?QL%w=M?*oswLmp(sQu~He zZ*691ieGJ}$H2ff{2tBOgQc@lw;Xss%T{vs(Vg6E6zRm#W$&+HG1u}{GYxZ-zMgtf z2TqSx-kS7(`N8Pqy97y>U|AZa!-q9yj@4!XF$Q9A%W4Q!nfYj7>BvL`??ScU`6pgP zU$E3-xPvTcMC=GGAI>`?mVAB(ZVr&2gXtRW4=mH$5QP%12{MJAii!%RaK8!)!ZP&! z#R~DHkJ)lh^NNejVSL}M9Mw9CCGb)`gu!8eq6~tN{EdJUU#$}T&lT2vq~78X)6i(# zh<0=WcbtlN;&7mxgLnHABwr?{l)1UNqvN#zHn>>uo|S}Wa9;WTxm`z6SlVQ! z45)&i*8}#69P2mmkTQXOY7Y_-p0EYn0?0cJC;t|!w?zm8TJwt|3#4?l_!={ z=w~JaHA#5_GMA@Elu?Bb375S|lCm;QCKX&Ca2U@|9FjWhJiFl9nrT8~Aj@*c{TS(a|?wO#br-#JgrWUN>E~|&bZ-c*)fk8JI z#_;r4k&^_x`WLJP1O#Z>(RfmUpz}r{TJP*5M5ElShn;p7S=aUqdX~gCTF)KU`vpTB z>0fywAMb!FXGjiU<5dE4@hcpZAw_pE>W};aWU)HbHw*~qc-4sn^x!JXH!W21&Ti@w)e5pD<#~rOl_jXx0XiOiLdU_OA}1*ob&Kr$Hskv?K5#$ zJloh-6?3R{Y8m12(Qi<=@$Tf$A4c^Z2liaPOGgi`rHVf>NUz)b!Dn=<%8)Haw82Mw zzBbqOBq?BGcVG9n@f1G!O5npT;z?`X#*@#k^=}8B`#uslS}M(KGue5=GxwUJ7X4or z-{KyA8EN~~+_aDIGClQ$BR}#@LTs%W(#=pHIW+FiM>$i&jKX^`i+6ZPleqYnwt_s0 zGpXgWsyMp(46Xl{FxzW`iiA-L=(JiHH31i)-Z=A$lCBSu0&#V*DH84j=Uh{>QZG49 znMK&KTD%X@7K(^JL>Flgr9Yazv-SGHTM>T;`fbM-SiO^@p*_}NgDyK8bPiWcLrVz9 z56>(z5{926_(JQjO6>J#m8f zw)zRY<o^1=-OWCe*u=&wNo>6h_O*0*95<@WWplm63rrhHdlJFc^a%g@^X~43 zp58r)qkZq;WABWlM;e+^kI7bY&R?)<+!;9C#uv=k_K`8q$R1w!5phS7)IAxVg@5z} z=ZJPUlW-5&5CKQ==UZ$k%keO$qiQ3ln@ zSMgnal$(JifbJ0EXRvPATWcgtk>HbI zUDPxk#S^7Xl%kKxBb2Qo8T-Tc#w;|V6ib=%PaGv#t{3B7Yl_3s@ThXf^qUxVs6LFn z&`%er-bqWsdqXXZn*qaR1-x{Dx7f4$Wi4(6z$~i1Dm9U`CUF9*}xT zE<>CHeb;kOwvJC#;p`Dn(g}_|Xqol}F8p%b$|8Sowf~|2wst&!yl`a&^=rRFJZ21` zpas7%E5kGXcWdHxOv)$=)LmRB{6&o}vSkrB5*BLN5u>G{#{^N(BQzk9)t zb6>#N{H}U(yr6e~#I0W0i~S#EB5+N%PkCFk1#+9S*`6G5)XWPxZhq{TV9wj3K0bSX zZ8OdP?316Li(F3V1JoQX;@`zCMGiVUF33!d^)baBCpk^hDE0 zyb3mc^RH3;;cbPZer^d2;OVD^_no=yUIBXLWm89YGFMo$O4XWr4mi>9%RIXj$HE}tW# zkGxyBOZJcAUd(@NB>hVcM*jKv0uDa4kS(^du`vY-06#y!6ZGykKnGCQG+%uU$B6R< zql{%p!4Dzm?5wQE-@mINB@1FVi;*~3gz~^Nga)z`R3x741mVuC7vHw6i-gzIJbWEm z*I`QQ9fMPbWik52?!1fo)QG_Pe%rI&+O8Fbt(%W8mt4MeHtvYP*!>Nbj)PS0$2I1? zqsM15h1q$!f^QwV`1-2wn@D7=^0uqL;E#Qm-#4FKOBM0)nms-9t)eT9`Xt1mFQ0gI zEew61AvMNrpM6g%btUQ|lRXQv*gCVTu@De(_PUW+>Qb|h@DHOBMRxQYmzeaDoE|Ed zv8TV{p)Vu88Ax@3X6^FwmddlJtZ*3~hw)y6tftYU(E+LLTM#=QP7w(r{}f4ZJT2O&j%z^+jzKX7 zY4iIL%J82}m+ zg<{tF^a!9Vy%LVlGlD}91Ds2b*o!J@oG-o)WmSEM2jwmU30{calLEk|SUTX89cgCf z?G-uQRab-tpfm*U;{v^yU2Mq*T-JH}&O=px*BPy1SeAiGY&p~Rd|mfq%DmI+qykCH zg@TtEN2iv)coN-5hTDg#gxxzqBL`Z##rK~*?|H9#_L9BFnDOTmy6>c#nRKNB-`g%o z+pY(_5;>>I-lk64Cf;03-fX6B(j);?3$xk!|BeBm(gLi5{pa*?Embtaa=B!0$E#) z*-bbDHSGiws-Md{;9-B{ngE~C)9*nH1jZt1)1@D6{jxtifNx5sij?U!mQKk-(%9!q zpP>s+^`8Cv0z)fJ-1mGB#kT_Sbzs2~zx}&JgIq!3I{apdcqwh;={(HaXhiaRkKie%e8n#mGCU>sI<>o)% z%SF;eL}OB6nMW@@EFaPMp(Jywvzh0%E~;~FYsO>#Q%k*-%%f^nvDTZFa#KMTL08ls zhQS_A-TWb#`Z%7P;{wRL?Jy8i)RH?w7T~d>0*CF%sEYwsQY{ z)eI-A1)KDIvrc^3_G1!p{?;{3Fr&(+ktR6%Z~EOfQ-IZ-ljx%jd}-~~YN+`8hsI-~ zo2@M8QS0GV66oo8_1v9N?Kr|0tlLc8mf?PbN2BXZ>f#r#B<=UQ1>dh53qKP4=h2g4 zh-A2JK~NqLQ$~yV9@+giULPbHVu84d4pXYAKcmE16?n-zc_7DzOwd`zthg;Kn!Qyv zu=vDo!PvhpiuWy0Q;asly*G<530tSm5W7pcy5sr0pX~O&iUw6>_4tuUzPd&7Zbn*t zPY5`WZN_cQGp#&Juk%cj?q0nUg!eB)*CjpZ{u8&&;*SKHLu2xHMZjF|0l|-lXcmDW zl{UjQ<7>Bv69|n-oXip9d=M~BF^VSS46Jk|x^)wyM|{q*ub*l* zn$hCLW$AZ?GYD1|6Nfg^izIo?b(zyWGZ;*=L8jqoY7k|FxOl_&%&B zfAm#nm+gDH53TK{EKrmapH*4srOyfgONocReCzc`$}a3nBDAAKRnKtv`2ytLNb=MV z<+6Jc6>soGD*1Jg3vt31LZkX<+!-HO6=}zt=1B(a;GpzT>|}^EXNZ`oCNU+xK}_%f zeJucY=2rI25Ns<(Mh~<8Kv++$*QC>QneQt;z$hj!JqbkUVUsm<5%o8{&MU6k$4 zi?a|(b?6y=rtaH8Dsj+dY32Xt^EX4PzxObis0+xAWNbxOQe7jf!o`KgqzC3D`k2J) zv=(h?yCuB)C>z;;%^MO`N3aG`fm%rNPr8B@=vH`v!8=j1(x-24|8D|8>R=}z_ zv@SVxptgc9<)@1*by1pUhkxzlFds*Nm4)lk8|Fhb5znZV>2Tys6V@DNKYtkfJU3yxCJH1W3CE|5 z81I)XoJZA+90uPmXH=Lkgo|HVYX~3gzqfFDvSw8p`A?}V55c)xhP^G;H(ffr(;t`U z+hZa>yquy@`a(F7Q_C$|U=<`jd0+cS1&&!xy-W?4`}BonbncMlsYD_fx~QZ9RiQ>4 z=@rnaUt-SV(K%@_b%IWwO2q z-c51hi>p8lW@34VfBID_U%6@&osQ%sBCz9V?qT_;ezf?&(NK42 zD5c|&t-0Sua66jW4IeYdlB)P)F)sb~hYza(B9K6F+C6kl!qYXnub6W!2iRdWG5+%G`*K##<(M4r3CaBrix#u4UNYYi) z3O;VA-#OI31r(tS5}ky~Owo&jk8h4+C=x98>|Om9dM9Hpn(BIt!7~k zetIjo(U8hSe}E>`K>bSOjLdB!Gm`VHTp^9kZRNbw?qJ479c~Aa)1X3WO;IgESS|ZzNqe0wt9TlBhW`qLC1i%iXcg z56c6_7aues>kY3%$Fx6isrp~BQ%~qci2!eE!@B`dz##ZKws1RoTn{|XAP%)G3CNPK ztgPsJ%_V^DhnRZ+?C1ruY8Y50}Baczk!7;ju#DHNtR zJdqAQ;uAqafY{T}?@&;slt2hOHBq21fYCLJa&^9xKVvZ|DWB?ibb zn4O({8X})C8iNblq43pMjwGbqAUccFG}QxR2S90{%{X4RL~tg{oBwM<+Lkt``gAGF zZ(h4eM2$Q3-j)M~P6O3xhxyKu!u;;r`!aN=q9cgB5YXQxf?N0^Gj!dcl!j`R8iEHP z{>VcGm*sBMBDTGX1J& z>_0k|FF*49DeRNG5pO@r*FLpLs_}!gqs6(z8G`Be?ay##MQD%)$5?Y#RPUx;=BPiZ z-P5oqYzn&aWPaSW zXAXH8ogQen@5Ak?=;zmPye0&_cE$0uA}u4Mp3w7#pQyC;kq99K&l$mj^8;~Yz&W#L z*aB%31Dp_-h?<-L2SK1c01?Q)DFa4@kFF@fjY$cini*)GTR`I#{*X9g4=Msg?`*AO z?XN2(4LiC>?iYT+PF)EEc43mrOQWM7=Mnv2XUC&)r?S*MZ2?;P^U#{dR+c=j5XV{v ztAQB|IXhZAJ-H4DKkE0EJ@YVWBzJ%?{b)DfR0!FE{|2~$O@Q`sdE>b6X7@PUxX7RP zg`n`!!BErN0stnw{umShT&+CFDnmYV)s+??XePC;CDpdm_%{D@$I@9%Mg;nk{f z7b1k<2{>5cbfuE&ACbonh0Ta14<6!^X2i~B=sAOnWM&Z-i{bwrNgjKqUqvH*5zcaD zX9IO^JQ+1pI|7f1oOeYg>-+103A$|11A%kxu1-#MI12zbqnDD|9=@vWF7K6eFL0Mz_OO>k{MTaY zTA?i!5%+BL44u2Iv^3_#Pb}WdULuRSE?r(|yaxO%utKKZbQZTs#Tjb$%o!t~6(Wmc% z6&%9PD}O)w>Br#-pCFGD*F%RrEjY&zcKosCH^irV(kQHRUDQ(enXMy3ROV{d&HmS~ zge&AZZHW?{Qc;QRA>)Awf_0$~zFv ze`jBei3}W0EUql1ZQ%ir8L!KBTRZiSw0LW7Z*PMWjG9ZgwLgDedJkbTPjBwSWMbN} z<^RxH>kOQLvi9P|3j`YdRc!N~L({PbB5i?kg?dl%`~Q)5{)^WN=uIv?%RWB!I-b5yWdkRapnI?PT2)~AEX{y?z#&*9YRD^PWp{&FjT zv!?Cod2FX4gGU=6S`}*(Y2DG*J}-IjEf&#N?WSI}kV&Q?>ndu;Jt-+^*C&7|R0i=^ z73tT+zyB&q^cNjdz;IyL{La;9YmjLn(0+g75$`7LqTqAvqgh?FfRke-X? zV!qZiTEdP;a@uuk4~?Z02_c&6_XJlJhq3q_=N4(_H+?<`8ov<=VwKp(SyNSr{xSN` zdB^lMG@w5b>FQ!94gnp9a6t#fS)717A!p4EP?^$FVpI}c0!2v6Ju(RBdodciCDrhW zy&{7qg%;}RSrjFuenDZ+dwD_o>{XD}ja+V`Ci|NySmRy-T*}?!6W{bsR(O}xD^mgE ztNEzJnR0BMGvf06aenwcq_?Y6^4!Zh-^4)rnXc5`_`d2nKwYSnqc9f1a3_h#q34e)?@>BxS>K z*l+Lr-b!fM%$d!l@PLt1bJAwGr~em0dmPS-*rp^-_RIjH;NQgDG^Gqy*8j_wH7qf) zw(AOa4-jdS%8S64#n4+Tny#cIwsGrl0jV6Iu7I`H?$qITf4&Ebqp}g)JAeNCiP{Ei zWnF^=SU*3=8h||Ha;Iqtp|hBlCo}4c(tzy?cF$_==kjbk8s9`bU<2`B9NAAMruUp`KGs&wW!GiBe42CK{P3DXUU z!BW;0j!GN|9LP+*x!s_2Ju;j8aLgWnC;Ak+7=46jc`XG(l(u%*@aXuMk zpILZ&$6fxmji{0Wsd>8I?+Be)_NNWFi_sRJx|pOF`I>&Gw%FNXsmvk~aL+RHd*9p% zs>nA}drE^DmAyV;&911>+sM4a4i#1ewx?C9MXc-H{DOiX@aQjZ-XI|%@q5*jmDPOW z1qEzv|9=@wc-_Dw~%u?_<0r@_y8gE(*y6^y4f9~ z?)J4ol{EYN7h_U%#Q23CM$lOIk`&O*C@|5=T<;F{{6-sIY-`s-z3`F|XC|5#yB@RX2wrWQ(31-Nu zH*;3@g0;=fS4&4xwJZ3N2+Mc8Fs0T}Qtaql1~t&^wDP)hLJ(F|;{NDR<6k~`J{Wvq8R; zd+#9dez*WGvEIo^ICa=JB_VDyxbuY5zZx#_Ii!ii7sC)c?dfGO*Q`BC0mR2;iHukP zQSEruj@dUhuGOr3XY}8jsh)5^jGm|5af<8k=3U^g@A}kax$Mn^&jPa9;gOymyPa!gp0jW0vdX}>Q3qQ%W0 ztNen3#vXdl(}-H|N&w7DH&kR??tF>@C*nYe7da~x=Elc~stLu*5d#BRkKBfv z`dUot+tg7JoOs4%009k&kF$SABUn6!veNFts6LREeuV0Dz}#>wq==q{gXt|wf##0G z+Q1E#`j0KGbd`N2$yJpY0hs_JM+(CwlwSF$bTDw~gxR6=Y?*QD9Ue~JIBaj12V>h| z{XGDgq0^bCkqiZ>)4oR=9mg^8o1S8xVl4da{BwElXKb5zUzXZPh!;W6g1xR$jGf1g&?qXUA!L-cMow7bc!A#?E^0}1zRn=GGgHJ{&VnT9l_@KBlDf``K@t_~Hu>#Gk8ghh~##p?>bJ4<-97}toc<9#`(s-nF<%~WNm zUn09uwCLk}Ub+@%gw`Tc7F30nq3B~9wrEC?6CFy^WVkG_p@c+vTr?O$fYnHGk&%R$ zy1gqYiXXgxJGF`J3#P(~iV7ZoU+OUBSW$ZFNxtP7&Om@^A?~rS5{GukjRAQ4FTmUo z2HyhW^n@}4&vm{l3m643|3Fr`&AR%Zv1SxHFI65?3aWMV$o~pVQr3*py{Y+cZoi_Kjc0hre76)yLs>3>^3y>WO_M7Bu7)E0)EZIwVAHvD{>&0_DY2-CshjSjM~bqY;QLf~6Qx=rmQvL&56 zUT=wd`n&l;W9sTNtv92suXY%`W2}p@)tW1~@A!t&cwi^e)~gk%hQJM&yR1XdfR-}2 zJNBt`&8eKOEOi5Y=4ds}R(KPRLFAz}=cCg__$SpOC_G>tas@Q_4a=_#h-(xIse9~{ z|2kvF-{m#|^&bJWqx5}ND&ee@0iCH009V8zm(gy#I_~tK^c3p?*ks*)sWtvdC{-~q zxDRY5q)7na8ypxgKvOxELh}Cs%^-8T4uu=g(zd-u5tA*vzAf#7!5V>O!Rz(ZoIm(< zW__j(4cpiJ*Mpgdr%Lr}Zp`v)YJw?NuNqzl`jZLThM(b;vQhV{6IM6uk|9gTG#QTl zf;b%g)`z7Uac{#W7#xz+bi~>O@v4<6aN@esE{v3$b!3*@eOL}d1zcqrSRn#2_ZYW~ zIEh)7&q(h#DSpA*nO=M=SvoFp`Z6_i(Ir=3k+8=Uq!5@G-*J=DpgKyJ_en6uPS6^* zHSz{$n;eNw)|E6vSHJk~?qy*NUJ=PQeR7kxzog~wpsVLh`ur|4;8HTBOjo}Ccr-A< zWgS`~vwE^M!C>Tdlr>opJV>=v(KOUz(pde6FN9Eohd9DLC=r#5FZLLnw3)!t^ikk_ zDedY2)!$yWR`NJV(GWdRvBAl*iMd`j=Ig@FfTo3592H%D)0~#*E5F36O*(QjC>D)& zEXR$9nLhP;ehT1bZMiHU3ff#Rsd1Z&*p^8&vt1@Jr7K?KkVzP=`s@zsqhoUOrQHha z#d7w~4cm)Z!5e(Q4 zHK4nIJ|}YDz(geq()<7y$-!nxx#dh+e|WotEcw1;Y7;?a4oPkzZqBwh@Y=6oi}?qs z@&(QjQKm{?HBcZ5QwhHjh&x>h$!SF1_aiKWq#IcI=N4^Re}O+W^(A0k@g}c?Co#mx zIzQ`wULlW9uqwik*&!91B`S@t+h<5uC9k)CSke@0gR)ib;QsR6-$UTTH&Ka|hG(+4 zENJWrrRiU>ufUD>cVmh-43LFCLthWfKi^7e<{YrCl%3N}zT9tzUq+}uZ@=uh^8jPF zOuLCLI{V&0QJqrkmepc}+Ra9*7egFE*4F52u`R(ZqJeg;KXPhxTY3nMR|f8=>O;Ah zLW}vs;7(c2rKj>VGI>4tFt2G_Fup%0v`g8;N0q=-C0}p>e#{2*TcxWvr(>pE5636w z0!}Xx+pGX_P^1hy1x%iiH~;o2dWl{TLROWGzF#Sz1|^kxcP5tZZTWq0r7}b!oJx4r z_Vhv1Z)oWeGB*ZZh8YXH`@TmoL5K0nz&Y7vWDo&(rB*j9kjn~_iA_R=*bn`Ft7n+P z?&0@p2QrRM8*S%f*Xf=Vog;f}(U8H-o+~np2aL_RxlDFr8Y_Eyj|+v8qFOlxoo5WM zy9LV9BN=1JSii{wT5R_&3SCMhKrXemD7E%Gq~J?d!w)Heer%-i-Hm5#r2V2#$i2Kq zN8}kat;S!bdS&i9VPg;}Or=VFl z4RQ@Q;P@8O{yeG6?s8T?hi%@7@*vj%M>NOSX zVB!;Z2h@%{tznfH`9%<@s4xZ9tGd2?mf6&lnFqc*xntWPK)RphKl`GPt3Dlhn!)y@ z(Un9hk=rwQC6cOMElr8Cik^k3gFQJydFV_5M|0~7Ky^`s7)0)$K6!+Ltz+oO z8`4}XPtYb%n|%h$aOmVZRApWcU}e8`Kr3#jr6muInIr>`kxwNWiHD#C$y|zC+^i@F zX0V^su2zjQp(w2Bm_ci!yPIj)fw9sy+pMYT5ffWX_NA>D(u%KN(bP`Qjs|DBhZW~MH@7W6E1W{?vSMBCf@k+4p8GQ1 zHC%>fc?O3G(rH%RF^pd83rLWn+V|UezY3L{@>vmHKHK~5+@08;>p%SJt8#;Hy^dtL zTbR$zvu1gwVQrx_&U7*5akcXb-Q3He+|fL)p_09v~sc=wUurh?4*hzS%t4yIF6BvReNRg zxUkPVTH<%JI2Rvz(s1QDecNv4m^$)61yiG+dhO2{avf$rZbTP3x=asUzys@Ss_`3C$u5 zm=YD&!d#KqSyjM){hkTbbu0-!vHthyyIkyD)rviM*E0Hi{jX|`ooN#g%@JA8H!nOc z2tCW+W`pOt0~DJ~ovEcWjHT|VhxMbF4{v)FOE%WexZ{5_4xumewOH>l!7r1S4BY+OInKd;rzgTG?>&L`q zql!ZLCDWIEArj9cq?8NZ`CKajqnpb%LFZPoeAOil}^K7B-pK>80d323&MUz$)`pv4wt6Q#nP-!s`KG(U4VF44(rPAxO z&#SyUc$RUPEWVKmj!ost(|Hy%7QC^cCrQtlGPc;_OEtg7cZs5muJ0ogpUTe)dGdlM z4+j}>Xw}kvP*yy5uCDJ80NJQ;tBfL0SLc~?ZIAhh{xZL;m(QrYB)jJ)NVluxYG>um z`%UJ0b{!I0ENR~P?IX_6Y#I8TgYmwdEouC@qAO()HjN>7CM4y9N_!ddP1(<2GA|P8 zq7d#uT<%AE=e0w+P#jZIdt! z6j3fVWt#(r&@){)G7{YzHrwzBI{LDjGz+^bXV?7w#NjHWZa=;bPeaR*%3Yh~ht?HO zzhKB4Ex2!X9gWsTThDe0{#fCf_u;)6C;&)zHIkp{vt7GkPn0EimGe^YBR?_=t+1B- zvb%Pey?+=W-aY5~h1O`<+)?30fF19Y>(4D8$G`i+m+)_+ID1+jEu$`!mpZ#?KMc8Q zvU#CW)ff*OYFV~qI%Q)WmUr!9g$b;$lW!K@^~0sT>Hoa=kooYL`*(@9mj{&P+5(P7 zRYtL_E}0;jMLq!WFYl(1DNcWt4?}ZlDR{6xOc%? z4D;|9z`rs0%dl$y^P>zKyt17Su_wn{&)}rZ=q*4R?#0uR#r+UBm>{Db`K>MfXX=6pUEkBz+8JfS0`tVGQ1`RY7JPXP!(Te zvYLLt$2-x=-X(% zsh4jiZ6Dr+Sy4vv+M&Rw`}L70@G~2Fz3KGE)T6<#2B(V^B zwK}DVZV<0%Frm=Os3CR7@)a7h#M|PhDwlP~I+vFSdi#GpJs^#BOK*x-7QBVIKGXLE zj4R2q(VQl@Woba50-x8nW$z{j{Ic=+!_|_!k)xlxqRx~rOZ~zvaZGe!`ba*pC;O8( z0>;)kV_j)X7&Y`bIxS&dG)cZLZ=DQI`EUX9bJ}f^ZOGWHh}xVvMkp|M1Uw%l02R>q zGD$@qp}NvVn!A5?N<2^!MtZm%z615Whk#m6`z)*xdcUsQPXzG~{rmLaPK{iehr!!d zYfDPftd~ZZW&2c$Rf8j`h=JW$bB_G}{3rA>6j;tE6+;!|!jOf3V=?0-h_|vTgK<0R zTcW@^GFo}fnR=O$zJak&{zi((e7Ws%wAb=ehtP?SOz)3xt5QJ;bYbE;HV*ttY*{8i@3XhLpdi6-{PW>((Bb+#8l zP#W?WI-Wtb#VEO9dsIblJj>n|E6j=4=nCdwT3E*|`vGt=DO+3ot_~I{4b40)UF)tO z-Xi3)ep06>G#SyBSJ!3+q#Cxu6Bv5I&;@^Te9h^KYMMnvdzP#=H5`^(qz1aSHT1cO zTR_3Wf<46sXU55Qy4&asdnVh(aT)Wt@E>pyy-ID@WakwI@#pBDcgWjJ+qB^Zr5?W$2KPh^r8xDYf0l(*Uj#k7QC@7x(l{e zpRRR^K=5Xce`X-$+Ud8RoZ3+hdmPzk0%>URiCKIi!W$pudynh0!BwL>cCCONW^ax> zCt@Lh6QWAj&xD%}0zv!UINyt$6TF3kdMugj*j4IOdPgSt+dIg0a}003KsqqeH|>*rmW~>xE$Uxv)~Mz?Zq$5J5&e5J140h*{~)b+mu+lpJV8AO_pN~nn-+|f zt7roVcfW$%&qbs2yg>(67?;ePw-O6;Za>%=j{s0+(eOdzTnf5K$Jc7;P{nG({#In) zeg3Q*y{e%#_aE#xBqOp&6tELpaB=5tZG%WO@NOuO+dTP3QegcVE?*crG(orn7Gu9Iy?l^vXQ=EmcvSqsqp4gsaZ;$CpZ!a5T+ZJY1W)>RF1KEX}#1UXtoE ze30lF;p;G?iELoEZvM}+MEcjW|>}LV7K~)B}Iv3%u-Qqi=!)y>bYo+nv$x5Gbf%tBj`_dpq)8s$UHM)%@ z>L1VE;FbX%u;MLK+YCn40=G?H`jj``)K0iPxIb2a zC6R=!5GN2+)`6cDb`Jv(vH`_6Q*zE?E0yjpZnC0bR7!oCDySnW;V(ecGSI-QKQ`Kv zO1Ot^Lw_c48{o4~+xNfr63ToyQWgB*xUu`~GC!Zw_9WZ<@$BB``B`ka$D;v4O;dl) ze-*3!!t{n9^Vff`egNH@qiEq#&Q7 zP$Y}@M5-$*v4;(LCLLDmVddc-3O;j2KyT^VU; z*eNupN8NvMw*CHh9y0zK)A`4!0lJmc?~EA2S=W?YIjT^)%E$I*5`pG;1~2&~BW)bQ z`^_$!guXfJBS9Nqct=pc>~hyq8Ft>_sR_k^9cFZhN_J?|EDg~343Qz*zN5?;JqqUL za|FfFS(KCpy;KsKy+LcTT?eQsATx{x0&^qAiVhg16i zPaoM`Z&^I7DTzWQcFOYDoaiq)XS3gdlbgxt(2vp^2p&-I27T$)PfU+%%l)CQr6DRO z)Lvn&0=ax$7!0GD3HqKtzgz5n586&21j3#2NL|Hg=F0uFtiGsd>Kkrii#&-qZy>Zc z#N;a3&3o=?U5}*Sa}wg^Seb&PF*jzRBrFd zPfRW6rt*0DI+R+Sg}}gUn)m(M3BKa;c-yO`lAC2j;CuDXN&9k%jCVpTZ^qekc_RoL zuS^D(pNIlry1p&vydx$O_9(Rq`W^P(RO}P@>1kSbAFK7|pbLA&P^KX)w2!k|UU+{H zirq*QUh?`7n!Sojbf;HmF?!xDd(Q3t@`}Izx8jAw{_2+gO(QiSE7IuIYRF{_XCUGn z$Ytl?nt6GNAQSPBnV&FN@dx;mSR%6lc?fbnw(;)j1Of&Fo0E!`Ry)EOfLY}?5^G@Q zC3LXCG0NcHuX+SJL#6WF$~(ot?1JeHv)kTY(3!;3?|8*Rum-fQn47D@$Y^Rcb#+-# z2@z>z@s7{w)<}wh+8JC^DV2NifO{VSC|Vp%Lva z;CLv&Jgu>5rPP{k$S6RZm6a8-*TMvBi*buZpZ*zO*?|{-{M*_JUDuSs!;~%P-6Q$Us%x!Ps>2moi)ZiX!`A`Z68k@{Zul5a%lw%xbpO>TzIkJP=X2Rx3siPF3~v~t3LOMBVc!*?G>s~ zEy4rC=IC;uI$L+16$TCdyHgs$D~qM$b-Ce~Fl<9T<-rxIGy)$eh+s)G%j&l5m6<19 ze{H(DxG5~w0DxS*b~O~|dxL@@0&Y#HJI#C8V;D|ZY zEXV22&4Te(4YCU}&-_lGa1aXIkyU~q3@GA^7#k*7V;qO?GPW);N$2sjnMf?GExmxY z?%YZ<%yoqkC=!cHAS(-@_F!Cz zJb*O8db$<3pnT;yGJO?Mioi^o1XJmv5d$B4OjH?xp`!D)M7+P`y3N?KI zET+99VHU?cAx)IaT{{k^yg;J&SA{0W&8v(CVy=IjQygP06rEo0c{vqOAJ%if^qsOz zY}Cwd{NE>qTd$mBb_gTlp4%;su)m-;i95a>jr+8=Pk}u3rq09}mT)YcLsYM(Yi`xh zFIJ1t<+Oo;%k*@;?Y#sa4R?o(*H9ll-z3z2xMqb>qvRp3DB+!4HT!lzH}*>j2(J$x zp@^0){6sI^coZc>W3EBvHIfTmUnR0yDyL;Am)3LT$y3L;#NGHG2($?MjIu!eyy!l{ zo7Dzb0RDm${Z-TR(^?ZW`N0nx;qVvEs7PcfW|(_*o8P0Ipe>%#yM3{fj5Bb+lyb!0 zxPiVbOd>GBhVPz1QVF{T`}{V)+bzD1B!J2K*HTI^f*R(UqW~cv4-K&z7Al^^4e+PpBy*`D12vSzHgNtM zyw?oVU7!j+OMrvgi#^>VL#*^bu&~dtMCf+w;gYvhDUlH`AY*nQ{F0K|-v!bJ3NSGp z1-KI0u`Ee|I=H#H{WZ*>g-oagAGGP6UxJ-$|u5O_zJI65uv($95jp~rtjP|00gVvIjx4lv{gzvfrw)}bnmFOS6Qu_gDMliH1US3v>l)YkHc?noxQuM#p zB=Cu2q64?^uAvAytx4OhH*xYJE3&HiTYlb_eH1zeaA=beNqRDX5r=Lw@cY+oE_ zU65@tFrExQ7aiR%kh(_uHn+;?4Z{ZR-VpON3`+Ao5j-3!9TMR6@@Ok7egC&gb&)ik z-*_(W70bk*H)zg*JLfz&A>BDn2cv3K^{OsXjfdmWz~HX28TlptN2@it1E^;Vvgo4L zNvO?N@UGn)&sHn0*tkuNQzoXsi0c-6n_&qe&Mi!D>d>7N;ve`5%)P8OE^KPMr3UnP z=S2O!RO)wAoRrM_lkY25aY4gp=q;<|FMm36$S)NlcXo-_2Aw}lPpO`7v-NZydfMXchtO=mV2_|^ks+#x zB@jG5+dd}<#VJ1~grDwBNlAvzG6Y z5{iX*~op*MdErs3ZYa@Zr)ho0uec)cz*?Ckh zSj)SvR9v~<#KnJBlVentFVQ|8N;7w@D9vrlIuS}t|lKLSoLk3>crU@-_g ztZM`gQzr|CzCO6c*V@RvmTwGks?D#k)RSeu_&hs9lQ-n-mdLz9WdMRFe@ifE^NFtb ziTI?Qf4quqp?A|NB_57gJ8|4to>6%pzP}MT{FV0tN@I3fdbMy2#CUI24`@@9|%pIj;E4QTJU;4p{3PPi)-Rm{U91;Qx< z)jf@xkT5qXb;bs`|ts`zb{ z*<;^DPLGF3J?mt)FbRO%9=sWN!p<&1$*IYzscn#2EHW{hfPM3pfLU#jj@bRXKD|SD zxU$DDyS4PM^C9ccCEzu7#278hgO*=dAZCaQBh3KBwyooTfYgjh$OOWa(ix0L5Kj5b z>3>q5@VPK4PnUn>FBKXBL}q|NWR}=dR{;vuZAvT+HnO+1PeEz^4uYS4fDlG|U?{j4 zuv?B186@h-(OAAS?QbLUZa%BO!h2{kh26BI?9*z6QxMBIN$fz}4P{WRzdmq$r>^eE z9Vr_)IzNy1#AfGJ^VfnrF1v`aPs$QO4)0R0y~`hADLRtE)d*IJQrHm@(0-E?4JLmqu+CeF9k< z1+h#nrSD*8aA;ZKC&$PyNjm=vp(rYBiC-#*tupR?FPx&K8)jJYb^03c)T9P(R8H_!KnSb-e_!XJ-*m^p==2^~6iofA zDWVPY%)BS|h8!ji8d$KWs1ne16)4kJfNw94?Sp|QS@^v6D@3D?=wHd2%X>n`7lnFw zO^;IzW3^$Qb?jT-1iCq~d(c%@~0QuPXC?>>lGnYMu2w z_1^38=eM^AyeZBMlzcqEmS92{0raDPo3hQ6KOMy9Of1@wJKDMTQoqU~s8_0GKr*ON zCaG@hpGdWCJv$cTmL)kW6i3XxGn;x%9;>NEzL4JY9NTo%kE*HgB`dT z(MJh}_T2*(MQGtyWos%0sj~Zzu3u0n*(8Cheg9XIokIrPXBA~xl*@&2AO%*Jzk&2= z&9@nFC+(j%FSVxSVsf%TW|In#y#YdyN>4kOe1NqUSn*@BvUYtgfbmQCRo%&?u*MlM zQSk!Cxbx3Yz>YE|yc8VVi0AV+RBoT2ohZ=N#K~X305(i^|MBOL+@KBuj#Jon%~Qb1 zdUyFPa0_#}v{v$Qe7(x7^P-?r>l%96A3LX z;c1VuhfD6ASqG!JS1Fn?RS;9}_+2N!0y5FkSj}(x_E38lz%Ds6s+6kR_mruD&w*-& z-PbOh0)Jz5+k5Y)T_JmUF3Mi*rXHzJ8I<4UP~B} z?Nt3jb@XlX9?kR_uK>2z|CXP+`&B0HlIo zKDmuC*Lwjt+Kqs5yFY=EuN?zJ^%Ts^5=$rkJJ$UrYu@Y9|031uSzEI*IJ!o?!hB2d zm6yUm_Ckx{1_QO=cM$xRTUU1%3A~jvSN?5?V+_eLGaBaGV-h*vw8_4iy9UD(|M`+1 zBW5haSUay=OxHUc9^HJ$2$3-O!f&7i!x&3@0RG;Y6PNTTrqARDvN(CT;T8%T4i;9r z((#iwe+*>l1udPSrAByPiO40rBiO=&aGw3lzUhik^DvJ2Dtx5@Sriq8u=(!o1-}IR z0i~(!ya6Bpzb7I5xH7!pl@utr-5O$(_8B%r6I&A<{nUzEXK$L3g%#BNPrVpbb9*oD z3B8>ldIqhXG_b}+8SlDp9@1uQ)OJ+M`7NzY41^my5KmHbM9K5FVBF)rp~M6m2e5sxg1 zUQdMPNG&Y{D6cxiv0_6L`{tzTBW(mMVzmLFs z0X}6;6iCtBp`jydCxXveBl9c47tKaVHeacGeE6s`6&MjmxB89_u2DBYd9Tg`xNO{O ziccfgBejla85A928OtUH-^dn(f%|{=SMFotdrper%jLU{Yt(tBw>w1&vRti!-NZiX zPEIY?#)`ygaMbb|^6#fxD8Nn$ylmpo6$zdJn|_m&e32Uavhd4L(!32XBe~vK&Si=J zA6dQrq&NSctX@eTV)(}=o&*URp9Sj^n*Fl2pI$+f`y}AJWVN7%{Chm>O!W)LM z6X4Rg44&Bb2Jgo^jL|$Wjl=$ox-sw_kU{nWV{Kgkt^tR8-(gRT6|5J~W_g07 zVh@0zcmj)bL12)-fAO^MzM3h{v-5aT4HK%rLL~42Q=Cu2@NQ}yfQV-08S9JaldjS% zh5R9Tj*e>kM+oUwr{C^w`b$TrXi{Y*7*p}jifZ9o91{__W>k}{G@>y?IL{BSLGLnz zl%nFfn!Wlk-@v>oJ<3?+!@W__5BaQoIF4VJEI31XHe1GH*2pwEwk?I$xzfU zb(4+Ux$aSe>{z`TEaOp{Ar$EqyT^j#QgyE-4`gO55~A3E6){T!Xw1N0bNr*d_uprO z0U+=3RVpUYbAEo_^-8PH7qK9=?fU~snIir16KB?+JDzAyR{W$ge5JA1t&bc2#=MPq zj^05d2D-d*Vi!7g>OqM*ViGU3p~=7e603Or z#P5(bHMR@d!dyuPWz(N;n4Lse{aNsD(+ig;m|iz-WWNj;(K8~inERVF^d_la#nAky z+zajWMHNp`H6g+dtBUwmy%Lggd;t2~R!|9)*n?}djpk3E)rW;~9E#5XMt zCQFR`fvUu-kk~K!VwI}>8x;_@dQ8=TIS&}s22TnxUTvx0miz1uQp>hz zjvn^FoG75l$NxUzdQ-4JMA|B`$R2g(ZVf!Z*7yDiTNdd)?421^2spMIPZ#?!FyU)! zFNtt$6Bx^X@sz927wwt#Mg8&0es04(X))vv75YLG+-%!JaN_H*C?Z{FBtI}w-VLdp zOiqrx8Sj6z8hj{~mKHTyqvCL7yRf(@DJX%(*X{3nHk5H&M#rM;ck~BUYzXCGnQ(Yt5$*{`-`I!$SpaTOd?(hFKz{phgcl)s7|=>8}s zZ(I(iGr`0`dSSncmc+*^jY)wk?S7kPwGdyH)YAZ72GpKbY4p{sjoLiksW#3hQw^la zUXz@vFcytUUf`Q?9U0egs`N$b7}wlhO2m|KO=(0vbDgWg9Yk*i2(=Y}nkHkLDo}1N z;^Zd!6pjxgI%j3;!&uQf`ShwDp$_Ij&}2zPEWVY=lH!8Zf2-hklS)0U_62VsyzcrA zG9Lb)x4Q2@`5sbwu%a(b-_$XGXP6Xi-R~1 zFGD7~15!;AZ&Jsthu=a*wW|(iK3;01i$%}uBjFGK$1j__-j_8m?~g0H;- z+q9}P8$2A%bwmSnM3I|?M~c0!gRz%2U2M7;v#s^QL``N*LM)!FGqGc`qUK<`%sOBZ7OLzDsa;572^w|eGSmO{`C1TctDYrO zM%tVi44`inI?Kj~PhU$Usb0H2D(K4-XGJ@e-e+-)x{@o#ty;|`*Wvz-409#-zIeS_ z_d?Lj`K^e{R@_0*f|Uk7N@`H(8LoOV_OyUFd0yb9lzKHTJW4NP_sLl8Wu}LTEu#s3 ztJryW%2UeW8aB*_1`V z$Phl>(U%+jR+**`LIfVi|5O=`Wzi5)$47M?N7yNjYv>gRI(Z*ipoM4!fiHh+RTGxHDFB{e)K_hdj#=Q;CSmZmC(mp1z7Mv%wtA`7t0AuAcL zpv94Q1X}q7`te@RaYEt%14rV88cliTug*)0j0V4@xUw(*bz6Zt@P6MW9T$%2Y?E}A z=U-qNYexr%+3Cte7tSoW&5m&`S+C9-Hq%|2J6YJt@(;D&v!na(ChpZqkic6b;{N8` z?V_dVq&7pYe=cF~(;9Dnjcqy~$@xoMjL_q4#hYgc5@OrMFypZ;8J%q#)f+Z^R11FR zE#vc)sBV?7UeghWOT;s_cxuviLRg&QanH@7e$&(L^(1M=K1Qyqkk-v5O@6$knHD#Z zcvr#TgCH(^4w%bw;oZhgQM!Ye7-zH(Ql1klpU6injMm&k68p*)nNq^U={Z&Tk(6F6 z_+J}48QCew5{l|{n7F0nh!)t0C&zS<6m(5_^fGx?o8<#4@$1O-iO`%uFZ2%8=3{p1 zE?u@d`4AL4E4n&yb@n$s>Ldo+^vlxQ?34U1lolIV-$57H6{@wMWjm&2ChU%ZRfwy4 zETOOrnE>5i8U8ujUpVljTH>g{q%<=5v^@VlAG9aKr;FS7hdnbwE$mIY$<9}saK-M9 zeb79@QLR+9^v6Z!vc97i)T{iAhjuvpcKJy9{z0!crSZ_AB*J!vpS-alj~=xnxZ1g- z`MJE?4dzo_-UnP*aNs=pPt@5Q<24@V6mJ<7B3$N_nhI>KaN!l$rYpBld}ji}u21IK zZja00@gb|#V7wLEf3)9h_fWf?B-P}+l;W|vkwTc$+yuOe*qrg+M-zhZjQ=hhsrYq` zxVy8~@0Ln`t26ja)&(WmV10`fCJUkWa&S;me}7Q=f&>oj-sLkBA$~lgPn39qr--D4 z<(3Aiioo$|k(vpVEv{tDG%~NJqciG4l;5+nq_kJkw) zyZRc*L^PPDYSkUJPld3xs9Ca2je`u3f7%IR>Zd5MH+%wNCyTW4v+^UmKLk8Gsy{O& z#OMsdsKR(0y>5Lq{`jW_U+KgJpkYYSD5gGo&&BkIU9w-Sq_OzO_4&fdwh3T}xjLN_ zTXm#Q7mRh|awn`=zo}LB28(R<-t;I_@iq~=1s-3vSr>@#89H)q<^tCP?(QyXz6%+t z;_1oS#y_FJPOdmB$`_#Z=liHcy^&=*#(Es+wZO-$*MIYwtWI2BEe>}_}Gawr=7nwrV`bM;gu zTT-OQVcLRT{F;@9^dp{GEj~i}K76ji5Y(W?U3}Ebl9;XDsMxhXb*_5Ibty#S?wSj?INByR`mgYu^)2QJL-%`z0dpnba^FTZxD_itI z6UP22ZqA&1L1qHGG|a6gKt9rVOu3Vc&m^zRW^-mjrZGK8qM zD({d_xp%uT4OwO&v6gsxpkK|ahb##$!gaEJ30h=*_d{gva?orpr;c;i-if&UxNat-->Z;G7lvB9S`S+cCX+-2DZkSI7F;* z=d3m2wf}1K?f`4-|N4#FnAtUllNL@m-f#cs2^P?DJiNSrF=}TF>fs&){P#g_SGNe~ z457vQ?ZK%cT?W{;sfPY9#SSm@Z~NSI2>u`Dof4^{ z8@h53!P`%P#V5R(Vh|EU%{Buaps2LqEbHs3<9qoiFSC~&rA?$@UgpWR)dX!*h{Gm<{bQ(1@c{hmiDGDM=O%Isk=p8On#VycD7Dx5#EA74Qp2I35R7Xxt z)L1`Bd$^-14GV3XHy`c#?H3AGG?7BTM&H24xY#)}6cA^7A-4Q_NL-4U@hM&$_!K+z zU$+&)WZpk6OP|MHdBl9nLQhjqO`<3*aUaRvW@&<~-Uj7+0_MvyyRgvnRAEBU!OE|j z-f1nx-^<@s`N4y-?bXGv_6PA&|Knnr3#xmFJO$1_F&MSyOJHeL*xsIvNmRj*6fgv# zr!)Wl@6)=ky^cvIhE$}FykPD3HPKd934f~`rd&iCutyj2|8X&8%}$nX`@~oJ%(tiewse$&`Tp;5+unoXf)bMak`sH z)J8MW>S(UXZD)3VaEPR&>`ckG6!~e-C|of>6`3#YY8K5@o7lH_K78Z~hIgIxUpm=w zxg^5D-fF+@aIv!;2^a8v@CX>khCkAMZB2;E1y@Re(d&XieW@4K_TuD-Q$pypT60!E zi@Ys!Hq{XIcs1xqe!v)giXM$|DO%v8R&8_F3N#(p&a$|YZSzW-4RG94yt{l1b-57A zPWjl$?mHA8^zo(d^=@r-VltMIRq!$HO4g+}!wC z^V<3mFweullU&152mGO~3mCcvr{rGCb#_$6Zs^x%O-)U|{=O{!T4@W89%-`e*wmD& z1iji!y?nB6by8V?%D-$6Hj8bhLfgF0gtp8}(M-m*gNM1rJm&tAcJ2@CEG?fxlQ)qj zrce&9=aYGwTV-&G;vcWXOYbx5DkVKmrlbb$<8s zIE`USgloS9;_qj>NT~`-`AMw9JRu6bhJ zHp$shM0Yto>aRME`~LA=gG2JhH(C`LB#{q#X#7K;( zp^>g+*zNlbNcpR6JqWq{yk51A&21E9(vTTFzqAz4(@Cj}e2(s?OpKVZ^PC}#a}fsQ z)E*_~LWe)FTnGqA@lk^{6EAI7Sb!Gx;IorNjOkO7@7;E3%5Nxaufhp}VI4N1w+hl@ zr3J_NmKKSS!52jCY33|aiGJtS{XPLvmzfQ3%J$1|g}{+X?C9St_p(` z;QEQb(U$uD%Z-z-ZY~=cJ#pasbq=JJ4{oF89_i}ewi{+m3n%+_SY3Gc4mm=yGvh@G zwW_?uc21*sowZuWAr}}qK$k3B8k*A|ZD;&4YgVU^6YYuXSe3$=ru~7i>X7eCrb>VA zD}j#5-%H=RyI}~Qx%J7v&CKjL0r4<|d(YNRr~Ipcj&90MX}shQIZ4R@ zSjJ|H+pZ%y5}Sj@^V`(g?={kKUXA0bRPTat%a?EGWik){{sBtU);G>Imw@PJRH*$7 zc&kCwY65OXCIV>6a`Ia}XYkCVruqV=Prt5{&;`}?f)*?XZ4GvX#1 zv@~z?Sc2_dnY1&OmlD<#;pMfyTE&I4r{XKM=HiH`Ba^bIKMH)TSXtKaT-U0t7MfhO z8t3Qt1{(w7nJ0<$Etz*mZq*S|OpQ~*Mh3sIL$P$V{hXGXB7^UhQmj^-gipl}lkMo7 z!Sy*q^gUSc>s?~}vC6z3?s72>=3GQG%Ob~`Vp`wv6g181`LT7=r3Xk_`JTp=HvZ3P z4AG1O=jZ1Kysec$d0+(qxZ{!-L=}^sRlz+fz&h8Ml7OGQIs8MdDJdYqjnU?bpo%#* zKk1<3mJv48MTkVQncsl9m^KIJF=gEiONjpLymLV(dv`38NOK^H7~7VLfj`U5V-=5% zu65-hzYjg?*4t4NhU^_y*8C6&2raJV1b$BHJqd=kwqrM{!}rYtsU9j6xQ zch4X?iqQ8iksq4yZ>RkL?{gS}Ml&Ls?XofYncJw9N3ub`td)G$y9!kkKmtC*m`%X6{O zt945>@~1pa`^tmN?;O#^5y+y3@H41~JKXYaS9N&{EEHm{DhaW3cVAWwAc0d(DIslp zkdO-;5Z;*lpf|32w6qj|Fx?E5@zh9}hpc1kfQF{=qc=TDV5|XFf`AFOt>f(A z@O{ocdmY%NVr(;4hIceMu>8C;%}v8M8fqOXa%{z^qGQ4+BO#qv{gr>cHcC23ITSp_ z54&ic@N$MKAgUrww`w69IcwimRY;wZl5!joY1Fc^;FrWv)Mg#;xmfTrHg;LWY|%!w z>za1*O}>%isx9$o)q6)R&WFvuxsZYXfNUo!R>}#PrtcVD?;`+A z3BvvU$sAIpV6wsV2d>KRBJk%BGhS+6;O+U`Qif4apvk#EeQ*cv=7*Jf)~hBhslz;` z{nRC`hTX#SFUculmA#LFP*yKad3)%j>*5jK z-EC$uM6%DVrwUs4%!XB`07Gb!(!PV}(o&o^%^g1AU4Qx90~f9;T6-29c*t$5NVM=x z0l<{TS(b26oNOTi7r%LP=RxF$(0iHY3KNrjF&FgS z_C3K7UmSRN8Vq6EdnaI^xbp4!^4Begm4kqH#mZ8#sT8L(Z*G-xqSGYs%C4JlUT12M z&IUe+ij%wrSvlFxPfw3*`At~BnJH5Jw6ARQe$E6Xf)Y>vrQAPZyLj{ZxSvg@Z501 zOu6KdDIn#yM6KlavsC_b;xwgrnYB&d5@yoZ;zWo8W;Mbx?5af z6UO+_x?fVk58`X(vgNzhb>~c<1muoRH;N_w4vhw_RU3B&(=mrra*0@%@r`{JMh8(Dfh3>=XuR6qUUf-O)7x@x{2ArQ>k$L|D7AjpUg zU!&bn=;TD63oRE`^3+EyG~hPRs+_Qr`Kb+3J!Ly#+-Y7uJM zoW6!WEcnoqCUY=hkC(fKo-O$aIZ1Q;#Q`|kU<7`JVU^y9!Q+Sm?WXYelLrVt=9>1E z=#vwBNv~q|MwY52N;3sEdQ@%3S`Rs*AZ*QKmZ}G(YX7Z*Oi`i}$}2}=5XEbi|NcVA ze#J9PEdcS71m11s{Tm;eyn$y4bCS}^8&^Hnjp<*!pYf-Iq*MdI4@rOaEk0R{3X&Li z{$<6Pdaf3~;d+}DYU0H-J;Ybw`VofcUU_wgS4d^-*;~r{KlfP6O(h|vJZG2j_kIuK zaS=Lc5(H$DB523~bh-DKNd?Zl1j|X&WI0_l){3_pmJu{`kEmGK?2(*zGR=1WCDQ&lsNdBBZPNP+LP*)?5CA z4(mEmXp~+mVdg&9Gh8L9ywzD)n{POErIN2 zecG8l6bN>rIjkiD$oA5|nU2`Jpr`-G?D#oOU)6Cs z2I%x4A0D55u+Q3+5EkDUs`V{LUB@sfQ^SE-fCYmS7pvTu7Cm$ruM5iigUt~P4aS^K z_rKE%&-LnbYV3*NRgY00fZl{aS_uz7~;x(7fx`{w5}w!rwHXl^>%F3X81gr$06;! z9uXwEUA6;@582OQ_-55l-!4MYaEBy#Co$O4te zI>nA0kdo8go_}&Wu=a8Slq~_c*3p#^rd=NzTf5__1Y zI}8?D@#hv;+-~44LU~!yhH4Us66hG|)`BW7JaWp};qRH>tak_Q$ek2RN3A9N|( z_pY8W^3-ZK9A>0D6%}GGT(Pu!&a#F9rFB~ZK^fiCE7hDX5Sht}o@c{>Uzhz+{6;29 z63hDAjjBi1jtt5S@4tJWhxuq8G)!>}BCh0L=dT^&_ibO;BWdW~VJFXS&hKgM40QQ- zTGS)ObiujJqMA{}=)R+p7i)ndxI7~i3qJ;^jJNU^e ziC>r})9;Jsx$|spIt3Q0cBlawwY25$%rnr32HmZNZY=bu_Y3D4uvdR=4b}x0D)QNxf~w-M{Fuj zI{qF*HQeWf>RveVRz0+fkBi(VO_L=@j=d7A&+=C1q?13=6wA0W5DVIwD3d*tV0qA@ zk7}_3NTRLFHu(q=OpBd?`?v~Lw$~!BUH&D9Sk1xNeGoLLBX+skkEEn>t<{Ner{CG_ zV3Y9Qx+M340vTE%~;uMNXoeA9t5D59NE%_%0j0d zl-_8vEsbM^gO4F+X3BqJ%1T_w=wBA|kjLbhH-7Z3-;cC*b;%F}Z||?ffF>Dq8x4Wc zwBV4wEFFoKMaDRcxzDo2bVaOjxaqdVdo*AtbAIFbiA;)8Qo?tb-v?%D0>}7o$ zB|x-i%)?41LY{>^O;nIL)Eo^N@IcQaW+sd?JsLgpXkL{JN^&rQ%jWKJo$6wYasesP zkm-UTf8cn%`q{PBJC0ib;d6x+T7 z7ZwMt)HAv;R(xK1vy!$1EWYzphK#Lsg;c-Yibkxm{r{AYt$|92zV~E;b@GS=B9=m} z@xET+t%_-GOPo)1{PwkV>ps!6z?Qho)@|u3eT+K@Th^viUpk5>Yer<@Ea;tU!KUwz zAQRt>)GX)J=v*!wizEH4-P%mww#O4&^c0n!qp%%H{|J70Pxh~-yVcocdwjoi^SPlN z`z&FUWr1gS!&_5+4Q+kCJl99HLA#IHmi_VANfn6SR!un02mP}yv$=MyNKsNL4()f? zCcjj$R*gVs1w!KCvQ3bIt({d~Grslan_2{sYSf9g{jjw~^Mr-J_*{!^3ou`Qeso|KzdgEQ0v44Gee$oGX5xuh z8BkaO$qx-;9ncwhwZDTlE=6D<)QEPK|JN`_ z85;9dTB59r+Q*arrv6N5q?+AY{qnob7}fkT`U<<)VhR2*4O3l0_uV=#jPGx z#mD>b_e&A2XYb*DeAMbO>?sN{_&ZM$F~{w3$Dx?i zkN#QoF+Qp`iqLp-dGuA!klj`vr|^JCy)K)L4Nxjep*`q~_@m=GT!ZgD6cs1;zo3Ee zj7W>Sr+!}!#I`0tc{j1F`sjGL(P;zr3O4Dh?RD1*dpSeFqm~~JjJWylR#Gn5JzVLk zJw93T;H(l~Rv>um81Ox4qwOCV=zP?i>6Af~^|^2qog(%9ZxE(@epHIO)lj8z=$Lj2i@cgc7$IR@Ojvp@n4L1qANtX-&_2U(CW>+knVB!eaQz+mbfeBA~?Q8iD+D{K2js)Neh3k z?oA=S3hE!9j(4(l-R?wkbi3})lA`U4rNiG;DAz66<=n+ssE3f{ne=ne4L*o<}pc{gA|N(2SJ+@tk@FKmh^VEl7D8Jw(;y zXe!Df-aGIToYAQk8putpBiEw}SEp%F>0XO+Q|}O+JYsprX}#(k9hNy-5MzJ$UhqE; zS~@yOz{tZqjxH`gG3ge-S2%TVM-%iuY>Z$`ZJ3T`EaN54Eg>wl%_Yzoj{pGbcqG%_ zVQ<}jhX28F;-!pg4#iC9445NG{H4W8%Djs#*oy3cE=RGZjJ^Jvf_4Irfk z6j*V$lckZp-CNttbw5wb2p-qFfyKV^{&%7$hE=kgC9a~+9~69W9mPb>-ELYv zN*hy$ohxy3&K6c!MkhmQ2@S3Z5^zR?SFTv)Z62+r66z~ag4x|#6(7T2Gl2O@>3Ghz zCFuNY+-#Y#n|d<(Z?yT|{K}7*t1!s!Ur~z_wF2yl|Guoj>rA%5hnCtY&g0_YSp}B3 z=uNu0?`(6T8ltz)d0X4=iN-trGn5sNU3$zXba%tSiY$Bf>W$;&H@xv`MIXtGRYjIBGG%aPlKQ%R z(A6xkK??z%5wPppxWC?WIoHQF{p&?NA6{AV^&j7EqnI$)w0s%pbXkT!fJ~PzQ@}>y zxS@wzw=hDUc;oiX!;|Z1&y7PuUC)vfQVWvCSG)v8&ylFF z!4Q#u0cb+j*L6VSQA|n#kM+h9OAqiRPKX(MgwAwCQH~pE8v_&sT*|HsS>JTMp0rHr zzs6VET(s@AYP1p=!V|T^InV01Gp*A(@c*V|BUMu7@Zn1@gPzks^0P3$5$5bTe@!N0u)v}7AIJxq=H8zGfo50JOh=*v$RLLTl`^Mw&ap)#;g z-3$w<{iVmvDZ@;3BdwBfo=IV(Th$UQbj%FQ?5uIrX8uC}6tNaOoYT-oRWT$aq^={A z9)ysh<;{p@HOtI1gTz*MrIg$6B?r)9y7H8H zKsuFKcpk(m3)r*=NJ_aA{SOLAZ)e^}zm=uJrVZ99_AKbt4~f!a`l5N1hxF1j*MZ#q z>VYunznx*mFL#WVTYlFJV=K&YoN0uM99Yx{wh4 zBuc9RJW%OJE&jXrH>Q(N?#eWd6B`vX>GjSG|D(y&<^!kJ9Hb=yVWZHG=hwq#eHDsL z{x<)ZY@`wU0W2AjT~QIY>fs7~l!>!q{qt|3%pBapkN;%H9X>x_xf%STS2kQPm(uDm6@;5tI-Af(xh#kV=0FM*Z5XYgmNJ6f3WIX!B=OzUNu zl1~CF+B5eIEWKwrz)!ZFI9yGownEJAO1i*I5D=hdc67 zNO2cc@TJrQzrf<-w7Z2iGs9D8^4V2swYIGB8VMGAaUXvCVW`Y$p>;(5{f!KeSN(@g zkFfy2JV2D9F-E;)h<3~WN=S@uXT4qj7f#v2v8X-wp2zK@{7Wi zxZ=_eeo-q8M5fLx+P49CV(QkE5VaQd!p{_&qKU4jfy97a*2{@DjPB$D!7ubwWyUys z26)OQ5geKLoeDuvQwPf<8OGqt@{Db45Uu6LP;Y=-=k?5X?@}{!4NPan$72klc79H} zQtL>;;A7n3d7!{uQ~5xAScayvjXyvIE+gYqzhdfw)&;-q`jN8JJQ~K zAgFJ>1mO~M*@<J`W*}Nb;xHl=^3UgpgJ@ztYwE*)kK>UlLa$wF zAiE%C2@g{RfaGjfWm;XR5|*?v|{(4s0`o&!XB(997D~ zdE=j3H2Inl-V~35%}0l6vU$Hm7i4ed zX7kHFaH8jxmxQ+CtjPN6P*&Z9_X76>LCO7;A^)EvOxp!)BfhH3tAW+vvtOsgCl&V# zuddHq@jG3h$vgNT!sU6P4!T62=4L($FSUL&8~_+fRGMSnsLSoI)!^rPYC{Gt#4-np z^4yT`fF80d3_N1YOd^|n{Os-6ZlU;($`DSZnoT6|zYIT=FKFV0&9O9Q<>wW70iI)|BlSo%jLdg~D};dyr{{rAZZzH=)` z$TiA8G6g1S(7OtMgI^ILU*j>-Zqt8>eW5$ge#^<2C||#PKbndDp6nK*802=&w^-ws z+~=tw*E$kwruruQoFSx4FSnQ>T~C8EUlPe)hn|~%0UNmta^@$v2_*1i>Y{z|uu>Lz zS8RfNSvH)0|Hr(q!A1j`UmuW)c>L?@o#Um$ppVj-J+yrlZ|M}b(&hN=n|SYbh*Vi8 zK1iE2fWw%*BLMc@*t@#&$thQLFgtuT?*Xz$ncHOb$!>EbVqd1Xp77 z1>S~xvNmWHDHW43B>MMbI$;T@(kB2#QEtMUJ!*@<8jf`ax;s^7-Gh?!u2eI`3ywo3 ziomoxt_H*pe$K~rJ>OyU@K!7Z)%P9Ums*N($AIfU>IP`gFQRx;&68o|{;<&bIs#Nn ziuTNDi4=KKW1aI1DS|u9iY9Oxit5PfoUA5Q%-*8+oKZC~elYK$jaLSD`B_&?iB;D6 zWhfn|Iv|z#f-&A;c~!nhfx2UX%}AQeo$!GfH(cojvl3C{w+FeD2~ayvay6e zy}nd;Sv1i6+PO|tBE^gUAvHlUWo9HO%HAaG+mSAhPhwQ6YcTBu5RAwlZ;ot&7|3;u zFE-}E_)dT)>wopbI0CFN^EQ71Q$DpVBzCdPlZKaSGqn>7%!{82CC*1df85AI|0*By z@BtMTpLGg$GVix>-mccWuMH^xzj)l0S)W$R?G@3pll6~KE~$UN48l~udK~V0KFK1( zZs5=>BpeGZHv5F%iO!I8u(bt5t*V)@34=pRH@uubDb}OT&QMhB(QQ=BeL?Dn1UUM< zsy{{R*0h}$yh&VJu}xRY>oqFi;0`r98>^~pe@gVM4#GPgCSIXuqE3kjqq@&ldvgs~ zZkg>DQ@(fbLAMg)`-AAo0%})?ws<)}INP|HtAq{rAtfKjNb!1_e z`=b530=xS?U?+86Ckj2HR^*#B16$yix#+WU#Zyr2ETQBVKuVlKvMRHwbZ}T zyFS|mVwEY--m@GVRCu{7t;Rtn%!~t9t^g^}U`x7JTRiiDH<$sDt`4gdh9_4*1q=00mJ@UoPGwx#+AZB*ej{bXv&*)1%D|U59hKYluN%u_>7ojob zZl{0LGZOeZ4IW=RYmS!qJ4>W(y4^;atW5Zn>HDcZq7`6H2Ug15!h+GzGQ^t>>N|sJn0-fs{BYN zUpzCN`#}ne@1e}5L!D~x_vzb5m)F;R5H0!N2`wW(z8;NGoR^fu0x(u$;g(Lp01c`B zV>0?{53tre3%dlg(}aFlI#8CtGT(xLks+pjC)+l z-xUkt`zPcOH2aT7q`hbJol|a;gaW|R+uNE5{zu_Y9PuSUK}h8OATS=0{{egBf8)R# z-Dsn7f8v|V6=SIO?Bqpt7lJ6Fd66*)y#SM4S57s-dcz^~m;A+2OPdqxyY`tXqn$ag z1;&nQE~&GWkTHBvcdN+(esr~Z?ppP^^o zHa6RG;0XB)(EU8!gaOtMPket z>k4XHPSY~-Q9~w?4{Q;l2mv)#=T4EQH3N6aTYX%fyIvpen(iyiG%4jvOKmrv*0mh> z56h4vKNV%)C8tk#ieUt6l77(Ue58NdisS_QD+@kmpO?(PcAzgLCDnDfcKqXWUxJ2jGf}iB1Fp0%=~V z5aE3OvuEFPN^>YDF6|^ezO8x?yN<*qmD^HqYCq+NG`Y7VoH9x#on=2&9bvrb8WkRK zOJV{CgcWjKBFaTrtlVj!^@Yii*4xdN&l*hZf_Zor{|{B?6rESNhTA`AY__q@#&#Op zMq|6Nt)@X^+iq+$w$s?QaaQ&jXY740(yMl~Bk8}^_kQp5%vrxh0`9aA9%e52`)!PB zoaTnI|NM9Wxg`OR?Sg=D;t$7|RKY>#F$0K(pI+yW3N9V6UQ$AS_Eu{1Ir@h2$i~1Y ziE#6{yIrR7Cz6x?e{;fDS);B%>=NLjaiB)V$uRA0WG^Hirm=hXd5xjhpJW=vT^bD3 z;#IG5Hrx|JZ?K8Mkbsxa#r5T23(e`2CW3Y3tPje+w+H;Nd_l}z5pJm%bJ8m5ILHmy z6$c8iA0Gz9AC+`cfMX70AKf7Qp>2l&2txMB%0cYe^LB4cX77)(>i9KOHOA%ScR!tl z+x@7Qjo(RS%Z<6d`>Q{=^-p{DAi|O^E2M-vrMQkQ7VHAf6I{6dGshO$C?r@BAz5;W zcf%a-&HRqIwiaxSylCJC`%2oY_nH?QUg1G?uV~6|y@28akYych$}eD%4_Dnd3|6)n zPK1Yp(;UkU92Hq>yeU{*?Np-3ZX%~m0PboE@W38R}IDt!s6S5`UmlUvs67K=Yf430;c|*hTi}SK^z+4wGObYmMz!O zU6|^lW5ESrZ%~zIO{Wy2oz$5FCN|-s^cN_mc4DW$vg*L@_JkXBv=}Ni7KzrlPzI!sjM+9&n zK1%C5qknAD2;VM3Wm3KdD^T@?Q)d2sj%o7xlh^rWtsPs97qT7KK;6{_nCgsY))Ay_ zgFQQ8kbU9jdHMGoY|JtMD}$(E1b%H-^XqRs8%SDK-w%CwH7zZlGrdO z;B_igysvoz-@Jh9ee`9wbqDVO4i`A0WoF)7AW2;aNrio^y#_oBFWhFO{{2A;mG8$v&Zj)! zwR6h2OtNKX0$-iVhiK@lbJB^p3k1yxxjs2(^zoddc;Bjmp3d6hfeRB48~TExjJ-s* z(Q@zirt?5Xgt5rYQ{RgckwS;rbW5OYQ}wULdK$mve{X;u<%{g4r(BshIsXC{#$I54 z>(=|U>P5ywz%eabRrQUQfErH$|6BAwRl2VP{Cnh(K@#KcfIvF3Fvsrg8z!W`w+aM^NqrU7ek>7}TU zp{p^7(GvXTvlS7`ZSfOPaB{o>0pt8^RA6qLpFHEbn#IIP5h64IM(C9!h>OOrk=`1y z0`#j$_w472ISs9uV4+6S4#3A!Kq564zdG3 zdt6DP+0h46|LpljNY0vIhF5(hhGJ<9ELqU@({a8GH`O;+$^%hQRf~IN@t}qb)R;_d z79lG>pIY5e!#8u%r9c7s=@7Ihs-k!zSI_?FW-`|kAu5U|ez&+2!9Q&nm ztJ;K9wpkY~)n_zNukH{#k3#D=`{~XBy3Q*Y$;~X7#tXD4{?MEmd zDg3zMSZ-gp6$dHgO%^Y^d^eo_b$bZ`Z783`_st8qGNA|jiW&g5azV!l5$J^rylf(m zrm|Uu`T+Ek^|6BAdc*X8R(pDa;XkzZAO5;B^{T>oRG9DA0OR7~P~P`LF_a1<>7#*d zYdm0jjsz@a%)T8c33^UrY#%=C55UStz~qCeX+A}wR<0q$#Q8PA;&)%;<{|B7!SP>> z6wvOB;kYEzJ()Q-)JvW|GI_6rc(z?$*g?ddU^z4zgh64K44h(QB9z!CRczlgt1(LM z_*XplU_Y`ijk$0s==jO zAd{S^c;)pBU&_n7m0~e55(XrLQ)Pofn7K%^%w`B}sw=C6(Efdy6+AYes^A2v(c5=; z*4~2ci;Z&6*Jzoi0p}AWXkmq4om<6u8TidQ;~CRWO^xA*{pUK^h{`2~QGXsxHOR8# z5|L(t51TecxT@rC>*OnHkTzr26_EJ>mK-fkYiD>eF-OC@Ml0+P?`_zA5%S)St1cI^ z8E}FvY*rhxNf1e!60ySk(IoE@#Cq(QSr3o}Md`u-yavcF2%QtYlO;|4V>{Zfm8`%% z)$@1v6d^30Ldr(!hr)=I0K+vj6T5`zNE-uXL+ti{t-0-SWi19^$|EQSx^)590L# zBp?}H0yAKO0JL?eD~-)S7UTgSi?E~WlP*aq#em8bbe5t2fsL@sS`VI*Z(=Jd-q;1? zup>CHDT-la31rNLBQo8KCO;eA+-Ge#z9My836m1?G{t>UMPFY^08$_CS?`e9Pi6Y} z4drM+z-22Yn-nupg9D^}VtF*IBJXE{%oW2ILqvw#o(o=)3tm?h3-oCq0p<^hnn~*= z3Cy5lR|Ep;Z2y7Ugkn)H>KWkr$}G8HcS7 zPB4xDCKKgcL?#i7eU7TNZfS4djh5}I?Y|+Uf6C;vBY_N*5;s{0Y<0*i8FGbZ81gA; zqq5hoWimLv3OJnd@K+-eb!!Yk%1pFzM`NIr#)%rF$(*v*Os)W45S<*Tot#%MlL?^) zEE3C(7Z#LU-X5v=i{b~u33be5!7%pbu{=%MHN@$80;(_Afq*{K^V0=S4er_{oG=q4 zUUr2UlVNoY<#2iGmRDqog7r$_HTHs^jWQ5z_;^cBf4m``FDOYA1Aqz27YrY#~XF&x`OnHhTmv^ z<`mQ&l+8eeGO`%%F?MVFh-x7FTtMW;blp-4Ji>k;Z~$ryI8QLy{ z8Jaf0LH}7>`aBo{Q6hoM_H%DL(Z}Pe&P)I)m2&R2&jb2EMDGq!X6<}9Fo8v8ccV>Z z>lycltkAv?-S`QR4hFZha1;ChobPN%(9ya9Ccgf^eMt4>`N9$mvt23#kL^M@-eBxr z;#j%QpZ4lTJN-Cb;mzlY!eJ!EgcON(78d{HM2VQH)f$+7GJGG$HpcFeDyYs?JkdY^ z>RNI|{rWWIZ!3)l*6Jz>7#ONxs%_$mLB?a|*I=@dd4p@A^mc;JKzSXBFcA3Hn6WrTkUFoM_VA};ednX zpwDK$Of@!4Xu{^d9p6?LhKS9yW>eV7^wL(26^sLI!p|Ek$_4J*VQuVSHwpc6jo2A> zUULH%SEqXv17lIvuE2-iGlq+l1hRiCd8PJz`o?~FihSRCJBCvb2 zG2Z(4zSpu!Y3w;cy$P9)!%fE5Bkbz7kAN9K#`P+=T>D{ zjxTX%SXG$QEK1+{x6U5|(0k^!p(b_dR(QfKBC~QdWTGQiG@xU z{0TACF}XVYA8RANpD{U$MubN|v@zrx3izzfmF(8Y@Ax0*d`6M|g5AI3I zz%}-&PaSrAd!OaI_tZD-2=m@vzC9dcBkjg_>W`+4y{5md{BF7$eN1msKW*{})P-9K z(O^Vq0GiU>YGJOC*X1e0FU`<-o|xD3%0q3gVq=xrnz#O?ChhY=Gj)2;UD)7!R6*k% zL)5V^p`u*>`#gnXBBtN^z)1qAX)e(Hy01W^&CL4x#Oa^)aaDC)@=qG^qK*}$ zU8(W};8C5;m)G|M>87G!|K7Jtt^fw#8D%p#6v%NRh9S8DS49T! zAVpyWB~hDj^R78e{1wzW3-U)?z1KQZRQ;BOoe;#27JeVf3N z@zt)hLdRL=Wsy+DqNDJE-Gr zbV1W~yw;|2f;|ocABB1l3|`cjTTm%BrN&` z7G1rTH3>vZNil=@_cQENP8rpzhAQwuHW0eDoOdPY_*d3KuW=cNj{*$q9xe?(W=Mm6 z9-n$dylBa(h{w=s=)lB^J54(6KccIR?}N$vHN@7U5<=P89IjJ?m;arSN7t@}BuB{x zGAiH-?%j`6EoWlL!UJQ&C+E+i*I9|dWo?#t zD_fcutlv-K#s$u9m;X}}*sk8QRW|b^D6a~wA4^Mn=CqBCW8g;{s_X-T&ut5UeAsZV zRQ2ZWPDxR*MuZ1mxdcP{H^c7p`g;e5tg5OU@1-afqh9(w3&6nLo0euAOKAj-W(4*m z`5ZuF3Q%}bX8y?K=qxXf3Wmq7{c*YVPuOp6p&|I}*;k00E&9#f?815~^oP9|WkiYr zp$YnP*|A1;`t zwb-C{5eZ7YP+J7#!~Du$T@a^c29FS0E$)(fAVP)S5>#XT%r533eu2hDb68t;P)}oC z6yVzW3#l~#sr8rZ@Zl(qxx)8SNX*0|G=TBr-{dVhF#XC`#yU)(8U75*6i-zN z(?nKTrZP3I+JXD9ezOqv z8Sec@No>PN($(DWvu`z#3dsD)9oxvH+*D^Kqid#UtbzvI?a`j7M@Qc~|9Ys|pxiUz za;H)|v7#2{vP=RLsFWLZGG8Ddxk<&-pI~v*^gGImI-F zA_=%spEZ)k6y!H0Z1e>wb&e?KR%I-u;V*xAL=}2}oBbqsZ-tR)q7zU%(&vTQ7cj?U zps5z{15lWKiO+}mu zn2K!w0mg)%hb*FqDO-}Fd;nT~c7!~2(W;91%GW*vchmyal;;NteejuT$D{>^i9FzM zO33`7H0~sq&ls+$fKjNRrA*pqe8?JjtesPi=7I3bgRLez#xOz2mPY1&KSCuJLNZFl zutw8D6~=3ei-Vxhuf-{;TcJu>AA_^MrMK+{=QIY7*4h2&vLo?XcX^#g>?yPm+%j;jWZR zP0i$gz`wl(bmi%Haa0r7@?>5izo)Ke^2J&aXo`&pGOj<4z>k(AIrR{*;i0gnBprxb z*>#_tQ?j9uqt%eyAXp7_6Cw-LgRJmk{Je64y!BpK<8wGwX*n7bzBk=gIzgp`QI@li(M8^rz2# zPDp(VlFb3}k9A_Q=As36Yq<@r=vdE$OzJPP{9Dg+(h!t5t%#6<2f!trgw;10u(2=| zh!s)=BZ7=ByI^!+NXHgb63Wy-R7fx|EArW&DIqcL4%7dr7mw9}G5KBV=^Hz6w-%Zz zS!#6rNbjh(64BIWJ;AE&@6o%(0$~vo+b^-Xt@ui&mwac!@BY_WZn?E`!xe}e{l7T( z(1A=C$jZRLZ&=Fk@D+gST-L;TN7-|Z0&a+-XpG+{UaJxu@1KGGz=q)3BM-z%;~|j8 zYq4wj!b6Yq=cUec>LSew_N>Oc#uwNoO=2ME5@$pANf>O%I$?3f`G7%el^8~Q&N(R} zy`r^wpbOl*M#rn4_Ri4qJWT4LFTliU)P;1ko`GlY;p!9C)j0$~%=_6(FBvU>;8Y88 zjY+bhnMj2}2@}BE5y8;wP)TXrd}@f|a?KO;P$+wSH?sKyi7758?u-${5)*Vg;ZWQX z(Yg#3UL+%IEJ|RlimzS?B4Uy%KZ*g`9`xD+dyKxHJ|ZJghblg2c=cC~A(=j@IfDdw z*Xo_(u%RU{qh^g3k7vyBNMWZ~lMp>@NapI65}Y+=EuX@_M+GtZuUm8?6%ywZ3;Q)> z95?F%oV%HG(nE9-n!G>iqmGq7v>cc_LZEQtDtGs_6XxV2a#KqH5LFUk8GWi+W}Mnsj_iqk*kz`b1Z->Ia!TV3Og^V=Kg9)}ng zC^_p~OACfou1-CduFKD1^Jgim(KNu(P20tiL<)!+C62U}Sb zc-zxs+ZYD!m5HQc#aa&H>84^NT;Kwrqk9Okyy3IFOuZzwdugzw@4qQBh$z<&C5+I=j)>cMLb!&*iFtBzpX>c4!m9W()-5^;54v?bWeN_;)IEl#2+=>6Jf6P(mCHR2M}r*z=rKllB7$!s zr~R!uz$Dh=(f6XL|9bSOIV-zhb1}dK+4mMs7}mi?kLTDrwJ1xY`XooXGMAI0&*Iq3 zCn%alo?gSXds<(Cn=JDWyDU$fOWg#6#$DI$g5ngT=!teAL2s&i@b>DR=QBmA=X$SF zcEuT!+PS-2cde89y12=C+9I5@I{x3M=3rl=h3|(W-8lOV`V+s{M)(Gf;83%)ap{M-OS&NiY*`spsaQ ze%OBSJ#MS!fw@<%c$lx=<?i!sYmmV{rCXrI(vM?B_nYU;!Vsd_?{&@ zIut?VwXtCLbvEs@CRTB>QlIdCYVN|q^~SpKjmtU$W|yG?qz)(KsqcChM50albLW@+ zs&97gq2sc>&};Zeq4;t{1wT)PUU#zA@@`+>+FT}IX|Vs<<8`!fPghj%-pAfrTj)V} z!4^Wy5KjU*hH|N0ue<)%g=$;PP4jL>UEgwS-DYbSKg0>_w+w;zkvy2h2j=A!O?5Y3 zdc?u2BO9A8@?1YBkLGGZy_3K7w{)IuDZBFQ*cw2?9LFOeMW6}1|9t;+Z~^#_hYLTy z+1c^OuO+3xoSfYG!~xFAlE1HPq3w9I{Y(0#=eNe5z1)1tF0E@V9>&!MiV3txe~cn_ zBqk?)RMjO_ClKvDZ)jKN#-?ut!DTq*-s#xWp%Kr7#})&B+a5T-FshLq=*hnUbqy>^ z^`5yv*Lvn`*!zcPXAjcJ_57-=@i9E;CUIhS41$4L!}YG^Ii=>28U!U>82KCqKDzqA zRL9N_CP>B`Odk3MV*PA^3_X*UWi;-Aic5&BR{Kz$C5(2-5w(1`pHg#4s6mr|W3TVdue_esrk1W{jjHM#b z>1~@^FdHVga60GTs?P+JQcf>N<>k@8+P$yX9Bj7h`E|D=vSWXK5rj6)*WZb1{N4O) zm*qd9OD3lA|K6A3qP5WUA(5xtk3X9VrL>TsM>DeP0D{;cszWAz^nSt&X0 zxZGYiH^HXjZXiVQnyc(vry86q=&r#E1&t{%|1*q&ZpRNZo#!_gQH|+$(zWj>Zjc(? z-gnd*;qw%J{s&TOLa&VDC z8sr`PT9S6t;N2GGFuZ+VaS!)Q>r*XD8QbhqmSubNWer!sh@36(+-T8XJiaMh^GWAvM%i?}npufk zckADWJL=>k)*@a^ghcrV!Fy~tv6vLfdrZ_hOdCfGsQ4_GZe7?@Nq4>=#CEKXv1Rkz z=Rs_;Mrbx!YZr)hHMf63NXY{}Q*~c%XpNIp{W6WxnzoV}6s{9o5Nj~Z7*%X0t)2Rq zf6Fr2DDJE#4aCnEn~WGyxV&yP$TwKfD$J`G+Cn2>LQ9rW%qc>MNM>th^9ZyTaNdta z1XNlDxj0xuT1VEWf-szC#5uYryC(Zv%2K7`&>**{S|S*ku9}x3#QM8aG47cT?_8^e zSkRlN=1X9bh~=>0wxDCk5H@q;&6*if`^3Nke<;byM#O5t)0Pa#@-7ad=5OoPb}nqMKjSguIn+ z;h5k|;>)wiSFjMtshm&+=S5-AEckP^dT=>>P*ow^m_#<@3snT7DI6_59GNp=5_mM` zIGgy0KD1qP%rjwX$W}Tj+FRTLr{bcxstRSy1X%%v0w~Mh4awz@p4}p|Xi^_Cyjm7D zc!IL(%n}g>^Tlky5MqlpQg&NS*(MetnwM_dkRfn5@J3=68z~jAmm@p`U z&OLxtR90be!c#F!Yt?rJV=9bk|FU~=QQ)<5FHdmJ7o@GPF|i;}f7_F^i2#HVf%0tb zgV(Ijee3p96dKUlCkLoZu58Luff_KIlHrH*GeY!c zA1oT1x1DiMb)|~|*V4j3Y%`qqoflu={nLzXt4rCx#8qR8!wEEc*KpL+F*QUrwf*3@ zusA04X4D{mG_M;Elg8zLL$wCIP6)P|Lp(>B39R^|KGD0{4KU=?G#CiK<8EMEp%x0L z5?%VQCoD;xrls?tT(nMU3KLBFdX}CO39v_$Bd;UB)Ln`Oh=@F}61Lr z(LpgORR5@QF(`tm9+gPABh>5OAdTJ2Aas9oU#@EVMJ@0~>z>-L{X0}qM&K*eQ7Wcg5WkRwAa+IWVMX5#%=O-UNl*pqO@|3u&+``RxvrP%KmpHkPBJ1}~8# zZh-O=6Ab#clOZ4;bwOz{{&#=4bi8A;Y`9bFEjDLdNAD6OC;~uxtuBw`NPI-EIQXFZ0=i%l~{%Rs6mjbXevJG@U3EJBDk*{K4bQvI@5MJBj}3{H6ZR!lX2tCYwzs+r%Jgtc(1t>WxKj zz}%r7C~qe=Hb|8Q#ZvJr>XXF0cS_JHWk^=jDW&PN$q$lP$?rDV16 zOQ#_s)_N&m>WTd@Neu|$j!HmUnZxiT9%JM!+aF9@4YXq-Y5DwX8X>qCm)&M)eP0&X zrd7TSjeiJK^b(`+hzn<=dz+12((F8(%VV^*yi2qCHrj}ZsEr)a=?-SC52Fnq@CMh| zfuIfV$4Itk1!m0$=>gIffYnA0xCUmdMGw%;&wE0?uv13x^{hT$UsUrqJpYVVf;ABM zZhrcqQKq)qm%F!KO_PN5iAOffIaHO!!te}EEZVp(cG*=8s?h4d)g$GKjSp=m%)O0Ve>3bp_pSSc<_r=}xZjOD>{gOLYcTM?sxYLv zb2Hk;FqLtSlCHm)n1ZIO_JmH0HgmBb$C2Oq_x0a!4+D`*I(h8e_`Tt@86=r+#*Gsa z7rhRj;>Jy^u<1$KOHvN?Uj#q^AVzpdPtNiYzmCwIQ~849`D$%FzBmwPAzd9B;+Z8u z0-fe=U)Pqs(GbP+mW`FRzgfS8ly#iFtPlS+PL`-D+ur^y8>)Za zj~ls-(T=-y*h|yg@%D9`+kj@l`=~2@!j#9+eZBoVEZh1E)SUjK)Og!Wr%zY$F~mk1 zcOs`Wm)DVaDI*WGkJ=zDGhww`(31G-VT@Pw)BZ~XQ53qZ|weXBHsLxSTO-^ zo6#$PcahS1#*bu;W3YV7(KEdw`M!-d&#w_%&}Bi`ipQhbZ9pPxF*#^xHojNQ;)K7o z4Om77Vtv6`qcxHF4rKN1hh?zRzdDU_gHGCur2f&b=K_)jv*AsLlZCgg($;>-a~3mw zKR{vRhIi`Z4DpQjkLj*a0pqAONooC(+ez;Sf&Qt4+sgYMX$nUMZTQ+HeB;ZbYI(xn z6j}=zg?Ws;V)o$WWKwUaOq_+5Zmf+*Md{BGSwWovO;uU>=N?;caA+NHzup{yU$^{e zjJmmv{3m|Fc;RErNivV7Gh*IOXsP@I@zJ~X{P0sNT21r==^00tW`-HEC2&9V(8Be! zfGz17$1P3_w5cOQ*-<{KoKmCu?{!}*DLP5l(~)}Ta84+}FpyyUu>2`x$PEDQN{2aB zb=f|3i7V9OU}#2)_DvJLYy6)0y0=g}y5(3Pl~Qs`q9s>VGPJ^s5WnwdQZ!TV^Zpe` zaM&rR7QVe$4v%v}fZB5dEI8Kto@V4In@th<-racS^l|=`SIgLY(Mg_|1{{~tG^=n4Nv&4 zMV8>ev$3v%Njrx%EY7j2g|x>!T-9@yV`d?<{an9Vjhuc>P z^>qgJyJ*%_Tg~u5sL+cz*_F!LBV~Jbx9#EWK-NMV*gcwng6`Jkn;p}J&Qg9QZ&JsvGGy^QyFm$Z>)WhmVUCcw@c|4N&U+3@Q*S(IWAm#BI|-yzL82B z_S&2K14R#=uN|Xo?+xo=sI!k@44T5l>Uj6vTVH>*aNdn|@Ym>d$RMX4SN_JCwrBvx zq9oLMV3Go(|B2b~#|24)h~$XmP@+;9H`{<2c&YzO5|YalFzIuoK%-5}eT2`VyqsUj zF3kPg% z{crXCl{t-Mf|Et=E5s{c(zLXMm+c)EGYT(0C!zs2N%Rjz@{AgT3Fu!=A{wu9k`e^X zia4Q<+{gW82Ya?~xy1FmO52z{a9~Ncp{gP(5EaU@Rn|MA= z_UqP`mbo1rnZO@eM%O_^Lb?LHMwf|(_$y0*3>*B@*&GGBm?9O|CS*hmcf{Z833Sg_ zmvVohDdy7BY#OQvxKx_Hf(W?Mh+G<~ZWLgKrf56QJaCP*pN_f@-%oNz7-iK6xfVby z1Z$)&boVt?ODVta-N*K@DO1WivwIyw!cJ5)4<~7#qzkEgQ|0g^0Yft01BAdyfcW z@-mq{4mw_a2Q2lbs0Gx@;}jPega|OAaQ{(#8o2MU0YLcC+`s%CZ1QD`(KD3*Xa~q?Gtm53`vi|4k9os~cm^ z^H#a>9m>b^&XBIVddOFj0ETo<+WhPhIrbUAt8JZ zx)~C(w=Iy}U&`mK#+S7m{|eC5#C!j#X^DyLadqY+iT$H0wnLCMnTQ%;_eUSy14vWx}`FQM7YGB6Ejp~3nbu~7Zt7>De$7P^)bfNn~ zP)%6*nc+3z?|>YXRVQ|32F^@_DHMeIFmDcKs>;}<;#5k#+wl>ucZdzf5J6Z-DdLR| z2C&X+0fneDc;#}cD8BC&Mw7$ClUMKQt!#vRhdLe4gEK#7)&xzK$#z-&AO5qw*{*Gl zo|zUDW!$JPpu$U)VcO0XGg zs$4@<8d$5hn&v*A2<=slB)O9Yx&G{WuD;Ka0uq={OqK|m17KGBu+>1rJxRJ#Z0B)b zXu;xPmko%rNXdO^FO67!e`K&(f9B@{WD@;F{NZX{Ll))d;9<>1XdJb%)PN|%%o|pU z38sWqE!PhuJ-1PwR%6E%vHb%GIZoIg3eYrNN5T)1!wh{}xLq)IcHT&1k3OpMa$n85 z#;Zn?3$(04S^AJ3sG(Arz!fD;*Q0#HaO?!1jEKA(OP2FcW*JJPor?V{K;vd+aC7TE zrJcw2)2aZtgi=z28)*zWEQ^x9t~4hSBRvT{rK$pGQW}@)D=eb`1k@7wUn03TPLt z6B;DC3CFIlEa15Jyk9e8YOSH^RvP)h)QmJ#{J}@n*{}4hOj$c@R>;&VdLqPO&*~;% zLhEb_t^r^+@H7WLGcwP;=SvSm^1GwR^qk2XZF~o<*K#d(uPkEE-85D>>@=PT=myO_ z^(4I(<*FDCNc4WRp88&2pvEfur zuzu0;I4t;ZA=7D8`-vd)C48W_%vpy&Ve5dpn)frMMMNOf_30reKm3PWcZ!Uy8Y|_aLogueQ3cjU54fzG{D$Rvp1e0t*nf$uH*0t5CCM%-mdDYbY@M*%jMqW z$2U5_&KMre|BICQ+=wWS7S)7e-0Uk(a_oW^m2jYdloUR``-_@tQ;Jn=DST7FNV_h& zvXdv;fEsepwL0#k1=4h)@a~s%u}fcmqm3D)YX5taTsVoIm62c?&{q% z)Hrvwf4dYK$)1d&d+WrvZyKD~sWvuTa#@wh64aB;=UM!LRE!>H9^$R`r}IU?kLiK zOugg*mh|koH1ObaJj*>rvDMt6&bs@3mMsDL;7gD!;1(EaunOnBWu<~s#rAP1J3iiW z3(_7!#I1gw#RE$!F$aJQO00-H86nJ&763bL@oLO2z)+#q996mMQLMZB$1mM9tB#BF zj4Qqgc7YLZt8-)TcaJADZ-c@V!|vZVS}_9K*wy>r2K2)Id*32)RjUhL4$s*36PnQL zCoM3!4-ANpb8aJie8q5Xg;m66{<6kDUxOd3LLvRjIGwfgt)ugT`IP)^xiM-*-(sWw zUUYWNJVrQm->>1-!2$@e{a1n%CIdS;TD0MBz-;6WFTNlTR~3Z}M-%JFD6!Ei7S1r*%aICo&H z1z}LyB}|-&4?iP!&J1A3;Pk)zljwdj`=arPP?7PkesRt^)e#OJnS0VI zyTK;y0aqFf2A{PBBuzgKW8Vl3;G2P4dtvJ#GzARHP8aG#{fC~W@v_AI%-$~Vd*+87 zt*gyaV_F- z1f2+aotT(EhIxPLhjw&hX7NI)=^|FG56IsN)EzvwKm2{6K3UQDq1$5H#=P&X=nzcV z^z{kAt|mDo`$nJ?=I7zyn{p|S09a&%DGSuu08Q}n8r^dpe}uwt{8)G}+$j4l@Z>7n z4f%?#)ihf>vk{I?YMoM)o`PXUAO9nG#?fO}c0DKppX3gncciXaeLWHL_t#5C&aheB zFX~^|Q1Xv*8K>Ot|MjU^lW{2T=z%ka^Ez2>(oxk5^IHmw(;lu`VJ~f~ zt&|`hq^r~keA+1v4&Hw6$t&r$U!w0i!f47iO!d5?V-M`7;}n4C^pY3Va<4-hN&-1@ zEs6pak#mV+t~Yvll*Zd>%Dz5^#;|+{Ftr6_ZyFYWpz{>XFzi`72l*g=s2&TmLj~H< z{6!w&tNC=tb9~kdnXazx%SEU_etUZca24b?NZ=U-goHt$udl#INf1ySe(tVlT8Nh+iU9A(et?&) zoGBBnE&Js}sNRZ==S|J)#>V^1BKNe6hIOhuxP9(&5eU7uo5>Ox+^N`<>ZTQXfRt!R zO=C$DJT(_xCD)hdZj>twq-}}#8YF>?I6Xb+;V87Z2TD3P7&UuI8z>P2j6_gG%<7$) z4jYQ#7M-|@X6@-X3s;D9&E}VL`uZ!-8L)teNOBLc zpt`+g2jb$X`!kcCtzi>%z{qRk+6lgS5|V3xh-Bm{`cD@d1Rot@gK1Dg!=A?z03iD- z)?XQ1>BJu{dd-285mjqTw))pYJb~9AF$Xyeh4(35#Wfj7NEWJFl!a}1@?)bWw| z!xh`@K&cK|G{WJnIi`?fuRkp zqIUIiy%;Utz;(05UP8Y&q`!J`v6S|BJx%t+Q1sRy1~wAD!C0qF&&U@&{3ZQk>AfmJ zN1KAd%n`<7ajbufP5?6rtM~g3(1Et*t}p31 zV`(QAp`Es&fK>*SkHBUiP2C#SLG9Zvo{8uQIvgeX{F>o`}S(sPw)Xc z$Zw8gI6#yqFgNh3a;PV;at8bDAco;LK2;d-KNyEe%2l zZ{#hbNPh`>b!T9+u`_%-R;pLKeAYMfN-$yR>|5t|K~e1oGk;+&_XzqTQlXR0KY&b7 zyxCDj5MCI=E52>lDQkUM#x)})RVvB(N^Ghx02(TPL*@G^s%T>^O^hKA)Q5p@{u6*g zq0adk7S1F)ngc_uKfpXx%VJb-nibnPtm^DSVQzaq_;95zQK=P-hL8)~8aum8dH33d z1NPYHg;&$GKIWlYT=UMYP>>3s+wC93gAjZ$`+dDo#y?J}k8yh_cf-_P8IzkAL-zCn zk6?{Z=TUWdvZBDg<#k~D+g>Z(IDuKzf(!U}NHC{Xn%+fzdg6IGA261{q3HM?5R>(u z{`PzZJtKPgObsw{K61=nh=|*3P~!T8^y_a(8dxS~8DhX}6ibE9!E#$uS7~?_=DB8QS-$^PVP$mtpi5hkBLprtIBoC7cE^jEitQB97}VM5lRVbW zT&Nl%S*|BL;;Vnuk8U;s*-;q=nwVb>2SUT>a6#OC8Z8?{kIja}}Q@qk;)c zOW*e$ANs3zkb5j1D>|?9W(39~&)w>rl?fRc?DjPLwz$_UzH}+EDJ9N9dU8wtvA%@V zh}!jIbAkc^LF^G1rmG2@yHPBvem1Uoyvw0UPQ2=Jji?8na}bG#gD2qdV19lA5F{6} zDd0mw)~zs~m?*ly;3=1V04GBTfD|x;uZ}owKh5VBF8BYDD!NQ|fcuCG^uOD{6v!hR z`HW<$FkP6qxrx5&_>mvg&?9L8EqY@+bbyct=s*1YTHlLlROBG~SXL911b!AaQ?g%O z$H71#3xJ0S$*ct8AZ!7YqIMJbk~7Zk;ZdiAf?`&+D86J$#h{6Rlp`9 zdsDsh*B0&nM)WCCY(^At#feZhNC_WdI)O!kg^kTFa2seeoItGuwBJ-zRUH8F@ntOw zoWr+^*7esIKplsM0Hq1E@1&FHzBIh>-LLinEm}#Y&)?U*?|0+A5iA+HtPt1Jht6|I zZf+x8i+0$npf7LggKhLKD{Xo6kBFfu8cl?O=vN7{ zidUT|$007X{{;S4pK(m~6;CxVb`5UMQ=#g{L4HH(?8gSN&;5xO!VH=me}&!Ghc)za zohLjynsGV4R8vtUe9pQ7z}M6KYkl$4MrXTba+Ql&WMfOzmG!`U5d3#f-D| z2bBFTh(kfbAQNq4PRvt5BfBU7G;UfYPq)p$D(q*!VFt$e%`@UpBf^ELll~cCWr@{= za`VNi@FmrCrFKiDwAVk}H)r7b>Gx|7XT9R4^9{N3$AvC{;-xxr`%7%xa$#Ksp|;bH zz4TBbAHUZ2Mc-%$_KJDT8*IwK0+1o!^(mz6yiIh!_y4!#pFEK~WODvbTm0^A);YvrH zZSe_4SWJ<3pUcYp=TC~e-#@s|@Us~1)yZKoDt2B4-hzSY&pa`4^y$7c`MT#?=5?15 zD0PH0>JAUc`$X(KA&y5ZR_{5Wxp`-@ad-#tyn8{oF)m4vWULU`iRIOMU8iZ(eBKm6 zF4#N%;xAOoJL>)IJ2#}-edR#C%&?pQgkKK5&{~~owOvOTk{Q0R#ijfGi)I+$4B{QM zYNWF9eW&>qGW6@7XX$0GYRY#)Aozg>qergbv)6;+e1;E{$OJDbKgwZ`&&gM)D!w2# zb;2RSs&`ZlzPjb(WPsq^IKnV^aL^^-L~*PBLS%=pyGau!p^PnmVHw74+h~=nshUuS z1V+zf2}vwyu*Q4IN2`vtDkm80?DWKHWn1}h&hrg=Nxv=7$cenTg5LqUN7AKCVH zhzZ9fZ9CgC{YDPI7) zD7#pA$n`neo)9i6my=z%l=R?BEQH$07za>vD3a@5U*t4>oVvhECRMDKkq`s$NUW+g zJ}UrT$(qy(s4W3;g(@F_ALL|JrN!=}%X*3F*p1_{H6-(5;F_?hwgq=K`sP#qrUt?& za-ULB!T3}f@kb9P|6mKu7T_D&rv0`%noT!jD=;d&_mC=i@V??QKzw^P1UhQ(<(ffA z{6ET$x$%7C(H#WxjiFgYR_SI>BZwg3xC6elx8JN$Y|S1sbmFy34aEL0q2cS2^=}9@ zVk`!ozd$AUacRP503h7~we?W*5zB-$iL;JpTZZ-tUUmVyH`IWw>{2tz5_s(jFxImxR^;=S!oHtHzcnGr~Re)I}C6h%!I|z zyE_om@!e7TnI?xvF4<)0o06@e%N74+T}^t=$U48PiTWgFc(b$VcYa=1xzuem{0R_a zc8=z96-SvSkBbx>UmUb|^>Rac6MS|^fld)20{`8E+TaebN@rG|n4;yr08U<`K-X7` zN(KiepExPTJ!9D&HmQf}-f-OqD!Tpn$K*Z4n#bKlxzCy@!`OqQGF$>UpDS!<%>;$_ zWbn&=*zQ_V%=cnwmRsiZ4!rYJAp%G37FmL9$m03H+OR4u>$8t$K{-PR`0CjR; zMvc}|31VXsbet8WFO{7Kx9ZE4p)uzfX92y za%TcDSZe36&C>94=|#+LT#Wymd99d=4PhVYfODVd6{GL7XMdNa#sJ9>>rJTFnv(VS z_BUMmZcF)GAcT;L`>B|DVGx~7oMbVnLABB*4nX=`FEE5SrvlI5N&DX01I!hy6y>WN z^uvzLKYdAUF&R?Po*3l-eAxxR`j@c8ygW4&H{!10>`ziH);@>$Xnc8tb0>EDM2^#> z{e>FyEDsf0#H#;8)mcVG8TMPBPU%uo1f@$Fq`SKtB$Ni}n4wERKsp8KZpopM2I(&8 z7<%Y=Z=bcEbI$t#KCl*xn0v14AAA4yYVi3n$0UxcgQy*Kw^njLRlPvnh1Z~9WY_-s=s6Ah6Z9OUsnEn%(aA9-|g~usOHyAtI-L7 zXqx=*Sbp+3T29-F_BLdKxy=(-|!v4WESKWTJNVu6a3m)-D^Lg#UHbu;5ACyI;3$(oP zqW6r}+g}Gy4i360ZC@n(8$!JUOLZbtuc3q(ZCo3*Z2YcvU9TgJJ2pTfUzs;m*;7ya zrdHtKi#+9(Y9%n`&FP8q!+DA4`~`U|VSqK)To*#gVPu*e0Ch*x1{{aLt1ic=`}YOk z67`Iw7pDYD;&>kKo@=i%vE!5XL}iq^osBw#BzA&0|FzwZ?L(HtpY#DKth*LoV^+|M9-xWSRw+!{bd;H4ei z^;QCREwH}&aWxbFmyPa!*Tetn=Jx=ATAn^Qc^1=DORE9kiF`CgbXoEOOG#Z| zfG08U?$)^fcP==emi62CbV7D~o$Pmx4?$1+UQ=rwsUhDR*D3E?-h`h7-sVpP#bExW+5 zi>BsV-$T*IIDz~xlms|A`(sVD`BPjbzl}AGnkL;2n)^h72`mnz-KH%c8R>F2Uq{E{ z<_aHl#5Qr_zzUFg`WVRDLojK(J~xNm=6CW$o*YL6A|r(ZKm_T;tD5l?`4OyB_``D6 zpJ%@wDT=9}=E`@0rN&(r3|YhLai51N;t?@4W{328b4kw?o&?wAPrK)z$#?f?#J;8L zSkySSR<+^c=NJCIC}9Vx8MV}M+S>6i3>CuS^+=r9mx2GIzotEi0LK4d#Q|B<0z3rJPj%aPh9FhM!eapEV_FectT zzUrkM@;grb6$*Xad1ETL!6W(rrBGls2qwhhIw@L@jpP{h$~jWH(%@$$S-zQ0s;f6CRyk^5TKRN^&k=fn*wF$ZbQjwD zbr~KHOg|!n9!?9cL7AQaQ)YWFmc4-~CkM^Gnjev%YJDe@Z-* z2(RIf1l;elx%k;2QPVcr0}Y9vN)TNi7gKr+?XeJ4dMRsy4b{JpCq~Ir#hGe_hB4t-x;c2i~g8O_9E&xJ%weCSSrAG>wcBKW3P0ywNjg`H-k&uAq%zVw*|N6Q_LjG-j z-!|q}6n#+wl7qU3gAB5c+^h$&jMVHGZ51L=badJ0lCt13X1lWJva*us=%Uh+=-~X4 zE&s2H4;E)-PqpUUOt4LLDn&SHp2td)%J zX7Svd0AT!m79!4?`(M61feDoyJI5Cn!sfHKPW-HyOF$&*Avw8Eyj{O#j(FwmFRSL3 zwbxmoYruRlHumzw@fHzPgFs2Ai7gOcoCbtqVVN9xhI?8o=d@a8>r;Ic-4C7S`}TX$ z3z$ODuLV*NhXH-)a#JgA?>c=azhH?~Di07j8Wp6xEGheq&y9u)9sQu~!3kih+{I!N zB>W@N|IdbFG4P!<7@*mqv3K5D0)4X}VU)5|{83p$foxT=CQ}N#$uJB84{**XE6eiU ziUM2(0#IAP_B;wuZ8EqWr}AY!oOL0iLKxDO6P0aPSJ0bj>zwoV4KA^aoZ`+d65!@J zSi1#Azn-Vq##ai!1sG_$>Vq`51yJ7Sr}>b(V|%^)^z?8E)Jbg|l_{oG_z~spoO5kB z8W2W$3xRehze!v_?XdC1r0MtqS_*VQUEotv{S|(jNT`3Y5?M#0)#HD0p)7Z~DrO{U zw)|To0^zNWgs9(+#oB{kwSl5uJ;kPt6^%O;f*NSsNAfM=IQ%ZbbTOg|lr#r(x0*E8 zwxX4DC#wYqn_Zvlufr#^K74aOOX&0?YJMzuwG3wx*d;pVMJX0@5h}CF1RWnva26ET z&@E+S>zR+{;579o*o$=^S3Ra&W1Y3&=$SiH=NC(Frd)is3Am059_fJP*+-&1APRVI zGaXO+ei^UxKW(}#9%f*sShSnxZYxUTr(P8QyNT9m_Y^H^wAo_ius^5H9*7H$58QkG z*%l+H>!LWr=NggV+Ppk>1HLE>7SNwASZks%iC3V+R* zABptFvpXD1|67qZ6Ci03m&c$L$#kgpa?ZYZa<$oAYXd^pcbpUiAbX3pUbf@ef?Ci~ zL8y-zt_fOo38Qm#U9o9rWR!d8hRx2U$0O9){-FYjX{O)RaMv?tKgP1`b2DLo&+0d7 z3;Q@{+OuP~Y83n7x=m*x95-SO*RZt;LC)XO%X8f)#fR=h_N-XZftrm?hSV01R(ox()Zcm}shw=V7~>YWqiE`eULe8lTWm6SCL+WAA+jrs({O ziT1KuSx8P#Vgy17JMLNP#-Kd4FZ-o17}xuB^2*I?xrtY4<8t`Vkw8af*8Scl>;|t^ zXUf(B*}W(B(dlUM@l;gfreOyzr@#||O*%<+%M0UZP5AR0BJc!>KU;~>!^e)fC6p1y zeweK16p}FWrhnEB4KeLZ`Nk1Sa&~^x6SL2ljU!%)lb;|2E;ciyB;dO`Us7lK zIwSgG#e}Bru0vOOd2p}7NFDGrvu;cl));OleiahATZZYwJ+-P^mvmCQevr~QALS1d zh>2Vl>o|O3-f&+@)X{D3dyaWmwU_hIC*lIRF0S(nxDPDR4!}L(B-pcCt|>Z_%`s^} z%PqUO8kpd!mY@WSAU=szexUw<_b_?MspEaNQ$5|8PXLxNinE+bDL}ZTZ1x@;)7(fX zpTB_KdATi|BBt;zv(7C4f@g9>#*yg2PGjmTlhQxsMsgWN63)8(TK5Zeywg|jWFRWg z_}tURRs4zOFwnS9&AW#ssYT83s~90ql0%8kFPkSZ!Q(_~Dp$(rz=a{L5S6Fcp42n)cXy~?EjIcgYq0rcBWJ#MOq*2P*6w%hd} z$jYeC;Yivl;JtTQaX)&(jRHqNUXVc}XtC*i;P^eEKxUB^X@T6SB^>smh4PSl-J<6_3_hegpcQCz5hd)b97IOP`9y0 zile*jCroTYqeu~t3Atg^5%S*OR{t)V7vE&|dRQQ#;mK#qRwb%fu%$6A)yO(;%%GvJDx*yAc_;;w2lmLN)oU)iFoUzV{XQK*RDhFGumVQ zuU%P-#FTFG)p!5rmQ9c!2ye%z5j~GmGhgO|0K3kT($ZIr33_8=V*nl!h}N3B%E%yJ z^CGwM)ig89t@jTIcMMc>YCU+@350;Zfb{ruv1i7uqZnQPKxkcUQZC`8!)`4*$c$36TONJSPFt7`5Vo4E5@|tNLG#{UO@M(yxT)8HfCOoIw>!T?s9cwMu`6V|RlYy`uj4TRFMn=m3 z_c@xDj91g5CIK^ps>O8yw^Gahp!c;(Oqk36^A?MK4k*deHP;_BEv-Wz4umm^+;!Su5p*BcL7vc>cEtW!c-*$J)O& zH+EKk|2lPFp(A##5y=f4c=KKU0$TXFy6)5mck5-*eM{~~YW`I;9;k`xQA#UGRU zj7{rJSx_u-87UblH6eIJuW+Yap1FsdzK{hIbRqMhV|O>|yFT@zUUx%fAS``dyJZ)u z(0PqXB*pcxg4c?Z;&^gKy~(ylx@X-yy}6eI;DC?RBv$M_M)qV@%fiB*j?r<9rurED zYPEd7k9F$0uhFfHKc;Xw}6Wu zGnFx=;vk_BQ7As+^uGYSYZ3_zb^kw6Jn${DHMq+|2R-ksM(Xm9&0cvGE!t1RC0bUXXM2aG6DCD$e!YGBJt|u< zL7xRJ2xadE-`rXN$hsVA80KU-5?WkHr0w#(U_ywFc-5b#U|xi8Uf9Z8ktZOVg2ek4 z*+s)akp!diXTuL^s`FC@Ifl)e!)~a zUe%`~58B)@fy1%h^}T24@$`1Re&;b4(cB}7Alufgo<~VLDXOgJrasJGx_^)Tua)iT za(Tf5OSv^aLiP)L_T%@869OUX8m)A`uqXTU&Kg*x z`f?orXTu~dj$b|QC{O>;T%l)>YHs1%GEJ&obL<^*e*}8VoCH7KidrPeOgKX9ruF$-$YB!Z{x)Ts|)%s|WO=o!e?!22^aY8h6n8Tm8&0#>^ zV71uyftIY*Z0sJsom=|xXiqF&S9|m-f_n7x_t}6&>k0Vy^8%m4^6Ll0lVh^$hc1 zz4M^o7ezY=qb1EPyLYM%R5|n28*LHLiLH2HuE-(A8?E^~2O|lJFk_kro(Gf+rmBeC zRXs3#guyavQsr?1)cd$0HR)IpLS+2v`3+fa4Zm1M>H{_6*-0v74Be5&8@}Fr%z+}M zcL{@?7IIz)Kw%ZHV22vTZKT;|(_KikROP=4=oe~5gFC95N+|Qp)!{MgbW4kPb8D+H=M<>*Xu?+85!O^t;z89c>ej3%C5nz4wi8+l%pyl7Tp zLCrLMcQYOmN}gK4#8kDynuE<}pyRLaN0!j@YCpN2u{1;8RfFkmnJQxfz1_sSzYknL zH5Zsddf%XxoV<}$_W&{%{VMWxh}!of(xQVa87c8mr{l0KsIXGre9uU6v?|}B?>w`T zlPIdOC3fg{nQ8YNa2Cf*`n4~&wmTZTw4jU9pRg8vD>>VOcQ0@9rCiSw_HseDJyl=% z1J)uv`>%fY`V5kYS2kG>rf^<4&+5G(A7%ob&GA2kc?B>e;;AgDHD`S%oN#n-28OdoFXv2aBh<$fGv^yHfxf@jIj zlY0_ac$`g5QJ4&W;2-I)#v$v<)=O!=TE&nokZ6}Gm65Rvdo?I=`Qui~(kEp{P>t8~ zhSXffjF9~t6@71zO~DI|kNjkn^DUcdJ+Vh09R|_Syj8Jg2`cLCJC)&#;_oWGk}t$- z^4XMGaz}?-Rrwkt?R*LV)L?lB-Ws zy>HoWZrl~#Q-S%b`6M^`uh6FCkJj=?kq zIeAIt7?qZmk&$r81wxQGSlm1kN8V>(@3Pi=s`HEK#jC?-C{_bVtnaFvUFtdpEhqdP z6&=YBM>m41Y28A;g(W7Zi3ue@wNGjRUJ>mQQY0zHV>c{LT#ldtW!Z-7h|fG*1@ z3^SfN>w+mr40Vl!$JEQPchlVzZ!e#mjhBbc2;lG6JG^_Yk|h+t)o)UfKl!POL&SQn zWx(dC=oO^MJf#};S`EAFxRH_M|{Q2tX?dBDRU5l{_1K?2USyyw-}AO%RcQ4 z_0O$!7Y?x|cn_B|+iqx>pIhI`iiW+xRY{294+7-|Wc9SAxP$2h^ZEDnW#7c*8K}Qb zQrQ)AlD|u{EB;jm`~^7#rW<$%w^9d6keeARyIIv;`qs(fIw!r%yqe=jEGfAOMx11~3<&IGk2EDKi)%LvNp>xx08HD&#SJ`dNVrcL|T^m+q!UU9Le#?mg^ zXp){hd(RW}cc;RP&`!nQP}||Rxw0HbZSDEY!p5fWlKsXC`ws`4oETm@4y?!9HB1^* zL#%{-^J8wl$$E+ZSXq&jKgwg$ImE2#u}J=yPc^2k!G`hfj|f5Qk3ZDTgUOqyiBz|? z;~#h9LEtTzmD!nsA>0jb404M)cSs^F3PJ^{O{r@=NH8Q<Tf^nJ48Azm28~jP}hc_|dZh%Q@8)E0q>*;+E{7SC>@q!0aRpJJoN~ zbDCh|>kd`0sFX2@i6^1h3`HG(^4*TnkI#z8*f;Mm8JQm)xf>Q7blVCxGz1Ap3>Z1n zUH5UH^>N=KfCQAU;U=n!5?Y&U?rDzg@?Le{oF5CqBOqTmQ4v?$a=)NUQw3vAO=*d9 zamU7*f2o(Lv~kzq)oLSO?CAX|JgMqcvnmX2eXRU~zJ&QRlr4cA>$+9$BjG-K(U2lw zY1}WX`x!i(*dTwfTSg&x+ZlqWfAJ&AW|3Ge$}Q}M#wpN&9A^3foNG;ZVJDs0%lycKYEwFbrjlQ`) zDo%seT#lOscDl9N;l+B zsXqhDG@$a1#^G+2>k=5&bQ$R$Ch%jtTVm301#e}ndE$N^@TgW}EaIJts}7)$*^!9G z&{R;kLC=!;(tgc1RONY9)7?)rcjkFS>EvfaC?@E|h1e|BfUsZ2aD5NuGJT->@hh^t zLEU?GDLeJbI+QeL_)mX~fUO%-2D98;+oOTcS7#>^ypjMiO=9-X(AU)Z1DL7Usqu#{ zywNyKL{hgwr&dl+pK}anySV)3{u(QDoF~UPUP8>j6(WC`O#FB7eVioL?g}J>2`=vm zn7KsoUrB-UKGD zfi3g1?m*DIFgGkw6=k!AvW90*@Qqx%v6^Pw?=ijQ2Oo)ZGIJs*fyB!RW-A{4q?HCt z;;^$dKb(&7SNpvAD!uz|C?CgdUdVxYCoy^!mPZgV*p0u<2GTN<;(v6~=L~Cu z4^LOqlrCL}f@1Dni0B`a(Y+5#i|<**OqqlZ8Lu+PM|W+i&-b6R`$c2b_ zJZ<>f!+5yv*`1;f0QBBB&#uGx8^{wCI8jSg0>Hcxe5$$qTy{Q@gW9A5E3d}Ab=OVB zPwq#;k{GNDNHXdDUU!8d%}f8>WL1mE(R|YRV0Zfr10sD5n!XBhJjbuD`-iNW`XwL0 zR!2fJoh-N5nmI3P<;N6O#Tr zU++~aOh#^;1Cz$c{8O~?T&>LdfQ{&BswtApkE?B4oPBPD&j|u%Cf(*{X(lF;=BV0% z2TBI9b)N-BLxEhrsOB|b)hK>k*{lyb{4}%ff(&TmgkzhZ(o}L=5QGzcnz!aAzT(22 z*F9Uw7|1$ezKRO>;rCT@CqG1YQ)yiFqe19r$O4Y>T~>q z>n_JpbqbG4i}gVlObx4k&Z;nx`ud~+qc9_t*+R2XC;Iih`UOL<%%Lx7TKOlA-!2-{ z!Hgm(K`CZ(TDFyY>SLB{2Jt$y(d~>;51P>$wZHc& zUzjU9RArx}-YXhhD=rYmbbiD=I-S-aqH6y%w#j`MyYgjoD67E*DLP;Myk&yx$r)7e zaq)f615~YFhK%cI3Z(U1s`g`4h;pYw48bMn8HLEubn_6@nb~NDm+SAXDFm&B5v@yC_k9T?l-eu0&}@6eaH3}5Z)16n$T;R7}M_loHn$)eAg zS^`+1mX_(KFgr6wQ5sbAV?1#nj-hT>CWj18b__9tjDW91R*w&X9I(l|eJh0Tr~Fiq z&leQyj+CvtvYmd*YTk!tAnOw;{^_%6D=z0%Fj*Tl|0huC*hcR%^tFXcvM!!c3= zE_FLy4mXc^8!?y%N;*OWvyP*x5mM&Z`;Xdmh@XvK4(K&x^bxI(w|p(n zX=84_9lm?)J{Ra-jKHb8`Og{g7abUz_U|Dt57>Q1dcTr&4}=Wi2U&6itJedYq@2qK zk1k)e_Dd8%xVqL#HS=b#gMAC5<~=ooiuEl)Xo%at;kCheh?7W2eonNtAJidMPy+LI{X6k2{d$yA{$@D~SBH5HdKT$KdZnmT z#vvTd>h;;emO=6!$8DO9C|Lc#e3%T{*Mn&P5~+d`DE~hFx$E0TAkKE_`IgG|f6Lg9 zAAiRnl$Vx9c^u8TcB7Kj{Htia&n;6}4Yr=B6{^}V6i?ePRiAGM#p-;oKmRiJW@ypHPVTqRra&-*m<=}g!>g}!*v+Z`PLJW97k zKzo}uM79|KLw$WSw~YM!bw^-Q8X2E6O!H&8N&nxvFUV24uC)2Ui*s5t4AnbKgxnc;Z)jZe-MJRcU*kYf z=%YoV>O++ybGx(3Krxdt6WQ{1G?G8pVD-mP<}7BVy#ZLr#||nx-=-N4=_cKGvuP=U1iljunB7i zU-s`q7ut~V&EFEP{a#8li;SO%#DB}XU=4uawlEL@ZZU8#|5P!mn0ZFZ(9R2z7pvGxrcs7xx005%WJMw}Rzsp#z zoBR|T4)Kd=eL8)aoJTE<39F%Z>$7TbL@>vmZHNdH7?c=cMOX|+!5@d!(sWyor`)1UXzN z`g~L}ELAlf7b=3#r8Q>?xHj;YJAa7Un~C337YHN$p~7_K-fP?HG}dlho@qdCRqeKQ z>beL^FPN(pH;K1qd0aLgo*xDcH|D~5$f!Tib@)SahbPQND?m>%i)!$Qf4|Q2P*UD! z{_k2&=o^|(7DY}zY0L2Xritr4!soDjwj2bdT5~5y!^y+bBru)lY66gNd&Wtdc;I`? z)56454oqmnPCfB_LTJalkbf@N@HJtW3 zW0r&$_}f{P{C5JK0%bgl&zz%U1Y5SLQ^Y*f=B`G6_2g*3M5D3iO*4L~%;pQ66QwCKjaEZTT3{0QH?W?E zW09FdU|0S6>nC;fFiSxs*6?jGZw*FI$u^k8FmZWoL`2(04|$ro&o7HYV&SRI``Hs+ z{%`D!%56-apQhz1S~WFM1Z|h(2^*kdJAY@R#r;_UGYp+t;L7^{>Z;$oBDf%wxCQjo zDL|N-3$z2KsihT?|JAg3b@ESr)~i!~z=!x6 zueot*s9H<@<<<5UnOux^DG1 zSLk0MssvNwn7$sJ27KsJEX+mwC3H+ervl$w`8ShkT){V@tF9qCMoR`l1t08RRh3MU zSbM*zm4|zLZ9fwORP{h{5lYH&+I*~zIhLy?j1PjXQl*R$|E7Ob|A`8ec5xIZnjGVA zPQa*`W=)*0zXiw1*TdjHY1ZG#_QNDxnpe{E>M~MCLKC1j8djGN($OF4LX(n2+ z!pnDVmsswAA*uVVHh*BKWW9k9KU9jjX5FBzFSx6Tis;dis^9(~J*$FVVP(gGb*BXD zyUS=dp=etRCaVW0UZJuQB59so9ZzbEqA zeaIN>szY$NmM1EA4I0KE-_TW!B1hQkZSU@ycw&_!5^P+ z+Fh{u?*j*2C&qTb1|*a`ZFPDYF_b;SRcLBwhTx&A=&N%Wk zqW%Nzc`}p$IGD!=sgbAY1)Qk?Ooi947kVpE)=^K35x<)rKpf@_NdWTvZOwym+5@-# z7u=zFxcvM8e-wk}3=?k!+d|Cvr@=bdR>$oe&w(2+@VNVi;#+ojpyPGI_^+hVxf7Xi zqr%f6`{)5!15dmF>*VBuj!fzxCfKaF66t#ayh3$jKpbqcY#IxVMT?j{#o@p+HV zvoMYt-|NHLs_1`;w(y|pqVSm%;6NTBiavfF>=J3zEykuKurDN4$3*LhXQaeZKZ4VZebGd$-EY+dIJ3ZPrx zov-TNmq9K_4k1sDOV3vf2>wJ2nyz2)o1WtD4$;_)y!0yW-oLbB~7r z44kqjR9EXcxzvpj&|6>{$KgCM4m`N1S|8yDq&BBplZ42z&#@!JiR$%|m*ZA~k5*p5}H1WF?bl`JVHmatFh$Z-l+ zmQ-C^|IyXrx$U-(UPjWce06UPTH8@hnq`&6t^1EQh(UcQ&lDuk}PqQte@fJW@x zV#sI&E^JK*t(4SnTCDmZ@Jq+RYvBBXGEN(whpKNXr-Fw#7utjQc>Nbrw-JwB*9`w| zWHDv%Q}mGo>UF=U?jex75WrughwBg^h)LY@3NrBAtB}=a&$A5Kivi)fK=<%Ix*5F8 z%^>wyJjq13E%xE`Q)Ra8ro}eEE{Uxq?&H~#c|{OfHDdH33X@To(3}a&Py*3LF2aSr zVu&VxJlJ_wj zx3G@0P0CKw0@{eO%=c$^#o3nlq3(40^llUCxn+v}y6aDL43p5koe)jH_ms9%%dPl8 z`6Ix>Ek1NmjA!RQBaYAy9aMc+DXCmRXvTqyS=Jw#uLWxmQEMDeS=lTkEU^=4vWHK&*;3^A3j6iOp`V6`^%@(A zScM~y*&zX;O*UT)TE8%jq;l8-Y-}qNlK%*k2m*RgUQ;FP4IJ!{M{+YhhW*;!|3ZY7 zW&1d;?}T3Q7mcgy4X6Fw*<5CjA!E*9WfexBu!zxHEo6t}p02YdS5AV^p~@=cxjxg& znY@=Xh5CFXVTjtOtQ3Z=L_k_ittHo1+=gJg-ZSN4z^o3!LP~I{UdY?Hpu#e3l9O8z zPBP?0h6LNbu3ljN1rx;Y(Ix2`i00AMBBswPr+*RSSdGC@1K0{e$ZPmsFY)`~>Q_;; z;V84d8t}{BjlSx0b6h43p(B{M|L;WW-ybDEKm+XcseJw>ROr`Qjsl6N*2Ck16w91; zPt&Wn@05Suv>r{)t)VVI59SQNJFS=?MMP=%GUz@UX)S{+3sGBG|6sbr@2$5&o#VCknn;}+~iR63`uxhFICfIPl8 zi5I~w8~$nJwD{vvNwsIkWz=h9lf%6b8W>k1{H@I_r_YxAP2)Y?&j@*eR?KB$0I$MO zM1ezOgEZElk?qY{>EePD&>2OPe!daX@O0pmUkyRbkhL4KR7_lfCSSzCFjXzP!3qs7X$m!k$PiiIyu2%aJ8n&mU!yg%zJAH5x zY;$NYa*O+~I$%WrqvIZaMzG#z>LVth`7yAvbo1E0E0(g*kq#mA`18#Rp*WMN2J9Rb zn->PH41X!BkVzxAJ7G&#`_|6sTChQW4-hE=wr{}aNaa<$ov&uyPh=OLo|txJ_+6Jz z7`V5=+yd@!!2_ZGWrZan2(RkKQm;)u8QFHGK*CIuqq1Xgid!v*@U5AGCuXRphiD+v}`?0T^;5)(+~ipxl)D zGHA}lz6SnvDP{TheR(Wn!NGazRvtHdVANY%+~ZZ>*FWhn=)Uducv5fUkcbyD3XJaZ z=xvB$pjQ|pr+xqCO{&8>sU3C^j4+mf5}PdvPS$TDRVJ#eBV6xWL#q0bfBR%7BQaVf z5Uz17gI`uAdyWr_B{Nx^5Iyj|wLrj%7pj|hp8~|jw`Hp9gq7}C%<;+E`PmDiin~~> zt+oF7ckic}I4gzKfcE#Iw#x9Sfb%6B=jY*}y1yva&BSF}(!V$Fe|L|G?cacFpQ$*j zheXe~yA9eo0zlNxuJ^x)0mzQaT5<)N@1QOJVKLW0U&#oUj`YeIjd`HkwNT$+e5)-3 z;MM$Ot@xQe5GN^Azf>}+vK zEyVtC)vLC(ZAwuIGtL~no*WC4OT~n0==#X(br<2_Z!9#h6H=sOMe_)t#XbZI9j^v% zUmwAtI9w#A$S;_PDF+m3^+xXuKQSeNp1CanK*rTI|CvgT^m*;zss3*rArkBL81p0K zwV!z8t!LNx<_Avn7U9TqJ(EJUt3y})+p;HNNe9~%;eLIuZX|TI74Qx_FLXMer47Nn zcY9(qlkX!&gX4p&EyW(KZ#I!{Hu)?$;9p^88CY?GV4M{vR;$xfcfn6VE}R(0od7M~pmS`X znG4D1+#G=BhogBq1?^+-WMFd z(7M48y=(~nue*2Go=!TwTLEJV4nJGvF={ee`!4=Q-XtSZptYyv~|bN?K!e zHNlItO9iZ`Jk~EQrJX^M?tLDuI2B{_juP9rf=UX7?;^W`8?rVu9-px{J3!T>~zSx0YO z)x$S}8{{g4a!Q$?sKQT!Z<@E459PqK_r(C+p&7TbJ*#Y_^Fw>Ax{km(>9KJ9hW3f| zsSnd{Ci;&SL#TF zlY96-S>`4fAj?p7-7P&GmLr5-^1k^}ra!)R81bb~v%)@_v-llVe+eTNt%&q!Bmw_6 zF|IiM+|$K~DiusE{xcQrBe!j0Svg&8pvY#x%|U(E5!gDcPyX^7OIMvDVhQu%CfIrb z<%NbU3r7SF1qMCs9Gj)u7;W5@4zRy7^&?ob|F)GNRn^l8rG>6TpY2I5cWw9;%YS^s z=WPJkh40$Xa_dEO-ybBqQ^f@{*%EsReAw9j8-?PI@o{BAAytE*fnA8g`o4RidR5`- z1fqdoX%%%r%Si&R^n5#dM=2&^8|4MUJMN?a7~~bLC3LPAY)htL7Nxt7>0+EGs<$R;A(?#afD*S;4%3&O8s17#N z-xryG2lSWV#Q5w*=*FAnSDe-cSPhQmhB7Z5GADtS4}(2T?61&`!h;RMW76kHkI2iZ znQ&NKlIOpL#RN9lNlz~>m8{JFVm<%KX6bzn?wVQ4Cuo>D$&t%Ek@GTiqa!aQq&(#+ zDbh*#w+?<)h_3LwUi~5b=9E63K*gqr#V_1)b2W0e|5H zPj5G>ILYy!K?8V_hOezWyo!bM?wKiG`tJ4RF{X#QjW#pg9{RZqDM_os3;4?|hpAWY z(w`WIf2E>$k-?TqWBC+VqCTbP>@((}*5m{Hn89(CGNQ0U8Dkssexi<|Sd0w3xDEm^ z_Vu7VpYz6PD*v@f=d%e?lgx0-x+;^h7_&js&Ixv*(J^|Z-NrgL(44vrGtHP@j!DE+ z_qDD>j;z4C_9>i^@J%y{A96qTxfEddMOAmXci#ISohm=wJhc71#WDw)qo?Qp2mu}o z{E%2T!C^;W-W3c<@$(oM?rNyI81PtId|RRK;|L;%eBH3^dTbZ52L|$MNO85mVfFFH zRMPnGnw?NXA9UEc;tgMi%17gPwkLhI-B7kF_O?-}0IU~X@&e{zednC{Z;%M`UhmUf zTu5S* z&xfLvCoioqrhBNroW_RY+W+Pa`&jKPREpISi1gB}K*)P-7AGl1FE9`2qfM5J-*&_t zH6?yQ(GOg#4372X zQpfCnb7+BQ%?))tV)Oq^$a}L5Mv;spG&(ibLO;&U6}kxl75&a|mkWc1v2?xvfSB@Y zfSj?Qh;f=%_3?y1bOTGAg(&v9o4BvQvQ5qej5=DPEIjm-8z=^Ucx}X59MLm*MvY)! zsqk{2m{^cqqV&qnSIyx&eg{Sffw?snP9;An|0C`&sdv62+jL~m&xqsBHVzk!#_{x%}nPTRV$Wt)CCLW>W}^|K=t7|NZ`c@ zaTBFgD(GrhWOF(X8_>jMhGc|5?y766wjwW!#h#)1))yJ5{})$+vz3d`U;mW?lgMM&^dL@snN8k50VglDl4vr0H^&d?3AL!6e|t&Q z_4P|I9p`)A3knIloBv1ETSrB?eqqBibO_Q&NjE4G(w)+s0z-#%3(`G=l9EyaN)FvH zG>CLch=53gC@si)bH4Zeedqk4E|xCWz;i$Q-uv2DtTrYs8e@jIdK_IyLj>sFHR(}R zR2`Ukz0zR{b&Zsmc|bVPRgWjKHgpc}a~X%Vv0aDZ;J%S)Vlyq*B$-mI zFY4;&m5$*OoHE`MTLXFTD#j6}t4||ul-IIFNN-PedOueFXF4FX9^!`jF1uqMOFR$v zI4(E8fma1lTQI#WQRct;tiN}Gh(^^{BCle0=Q|V@Ib|k`Ql=A#GtKX4G13S2aVbI})oQ7a02uuaVREt{9Q>-2Ld@H6PV z{lGe3FyyA-fr&TSGHLx*+cd|=(L+?`njK3h5It)nWK$z_oY3Y=Xn|n+{WQ+A4tOzh zT}x#_?D)>>8uRPXipy>oJ%0rntU)}X7BTLLWXL@H?B1{NmmUj2(zV)FeL_l%nU5}O zMY*#}^y}28=9gMFMwWsQwhdwXkTC&@SpWeFm+z|43Xo~UYLNhhjQWqM6N&n?nWf_^ zyrx?_=fm1;^8w8FIT8)JTnAs%c&5A?b2mgYuzJ=CU*ZRJbk&V2HEns38^75K$hYnj zvfL$H4w&j__v!X9yWCekyuA*1el<&O=yND_F}eB^dcP*2&iNm|BHxzvDiV40tPEY>pyT{-ZXuJd!I{d3 zD{B3GW4x*Dz0KNme_PEYp}aSS5@}S}O`u~muwmEN4g&)uiPya!06`Vnig7lU`+F`4!MQJN z{k&cAKlONc^or)_XpRbbZMUX98L2Dci0z{+b3|v32a&{lQ zVHOI0k7h_^)KFPB->@!Ekag@OXJ}qHK)RlV^Y~%zi%+ELC5^5}^TK1^0?IA(@r?Wq zh>_ZeIIzbvL$k;fA`fSOV#)=2xevrs>Q$d6>U@Vnt&K z!p(!dl`)+m^Q&Oh!VoQaE#9ZWk2qDSf5rLomVCT%VzBhPjGT7R;m*XYhK=Y zq~!X39Tu2>9-h9IT01WB=jUPDQKH4@-G$1lNh1GjkU&I+ZAb^rLQ3p~BN^HapmmEy zqs}!tLtc7!c|03*P;@tk;*lcsa8P@_v^;1KT;;2lfPw<~IsS>8T3fe!EuS~rn%&PL$k&!GG4y032$UiEuz&^2uGL(R`3efI7-RwyamEEcS8GR zOJuw+e4XUJF$i&=hN|F|Fkkut(JxuQO@tt4cqL|3JTfYA&2+r-GH5W23UsYNIvf3 ztRi&>aB_mz0A6FG&FZ*EEaibN4rg?)#^;ujFkA&z2G!~^nd3j*{Lg0R&yB|5A~m_t zNgi6|SZ621$Uo4B9(ZwUBZibY$z7a6Q!fZN2M}vF@#ej?qS$8_a9l^}g+}TSy)&<~ zEaNCL5*ktEL@XI|nV4D(PUIAhXI@bzTX)SthLF`5g_zqSs_LVx9M8_BZoZH5IrCL) zl@rRo{4FSRf8F}?t9p%DZm?$*;u))<+(_sm2mYF~i@%rm*|pl^Q0JO2RV+Kr*zebO zTJ1zaTNp-Yt9u zKXq!pAI7|@oA%TWoT>w(w;6?NwJ)~U%ub_y>+1c1FpL7sPs-9Tzc7~mmvh#bV5tEa zNx(jeEh|Phv^9`jgqCwkdu%9#B*j+jl_}nj^g zK{PPk%7`0NL-j9Jjp60(!&zyxm=!Z6YVV)AVwkeFd+oS6a{T|`9H7ZYPqEJ@xheXHZTNngOo)I=`Jj6Dk2$us*_Z)Y4KB+8U`0lfrx7FHDl&;v7l~1m z#!$s6M1-#?ONVG%sOrPK!9{Ql(y$*A7d;Dn%C9{)0#(5l#(&h9kP9;H!rxO;I<#)! zL&~a}dpyr62-D5b9{-J4A@ZiK?CgL1F8A}n*2!T!8rIYHEn%42Bh6!nohUH_9#FN& z4zlnKA&%~ZwkFxW@uu3@f>z!>0LKJT=fg+JFV4_l>9sU?DYHwWncDAsZih((%Fxjn z4nH@7Rg6~o6dt0{nK-}>9a11)1nRLaDOk=k2|Cd=c$aTE%@7-eWV$K5#Y|qmRcPZc zMNQA*XFDgiOqSzR!9|E+R@9I@_(;ihE!3@c3*AI_yRu)Wp_yn&BM}*?Gv(Wn|82?} ziQ@?UTxAQHS=aJHdW=^Bs$7ll;QV=mTrH#R=Zx-OnIbD!kV%n2oGMVIbk461cnXODX$+3~8E7^X&fCK9lY$D+jk4a;E}$X&ki z$lE3|rmbk86;SL9EOgR@AU|gckJz{RNf>Y=81R7f^E`f_3N04A>jG8-KXLAzQufD%X3jqU0j~zgi&&7!@w_&Lq0U5V_8Cr&!}LhrbvAgI@$>jEQ(<4e#6IqA zT(x&0O9+I^xQ&a6;@}ZBO-?pU9pToQV9^#z(3dG`g+wYlk7M=RONt?lE5HcnU%oJ{ zP>T506Pfz%wC0t5mtZ&1!nw@F>g&tGzdUwT3)!5nzvO--6))`2c9%IlN;-*6{JVqx z1#huRh#`kSnYh7i-V2Gc21zOOMJwPWy9b=V=`4o8T#Vz7l}Bh*HZ>HjMwmF7k<09; zt2fglQvu@Gs<8Z{AS2+1Soe{_EBD*GfFDhXH{Y_wG68DN)Z|nEyS?#Dcc%f79a{>> zT7;&3NkrEAiT8T{Sh4okCle!)N?J{Hsa~HFic!;L?Z5Imnf?5`dKT&?>OYc|K*nah z6YtT89syBNiycD+`4&kDWaLzQy!eJ2CLx=xS)_wQa5^sjT!7xi(4tK&tCv$-*3U^^ z)87}ML5Y5j?s^+5Tq7d!QM}(5q~3Nt7DXFX?%oZC{;Y2x54dcC)Hp%YJ*&B&pupf` zyp`{p=Q$K`09IIj-a=~LffF*(etaCrowOfwmnfj}xFgjMMCdHFgWG8tEI5|Erqz~# z>!X#a_&;mPH=q%J8B2E$zNNHMf4uj!jDcaZb^Rk3RNpb1fbCKNETCTAM`)J``i;yC zsi0Zdwm&y#n#Z+c2HT6udVaupx`$bDs8B|IzWyFWTLSulLJyQv`!yLNqB=+cZt1YL z(6!YJnx|b%r({lZc|JVLth~)wLO%^>HBp$eW5P?6im*P=&aKxSLi%JVB>$D!MKs)O z_rPo+*8ArFpN*7?hn7%5j#0@MKbk3Qwi1^CQ39T; zdS*1{0m!he;Dluq{%runSW;8PfMWL>>5AfbC8qeEN%tJX3?dQW9 z)kOOrZ0nK&#kCDQ>E5JKzD+X~nIa7#%x&=4i&2dy^}wu&?iUM0BU?qt!$kmU+DlHf zR7A;=?rdR*k&G~L*4;Bs(FwN9hDgN zGFShmITWheewtpO@BK4Ec`fDz5fzf0noI)C?`)EX67m-I-op|9ac? zomKJ@dkf(Ah6ev=AW-G1i9AwtWn~BYUda)_&m~4trk}Fki?Q(;s6$sVLtA@)tw`YS zQWX_e8M|dJs{={vu@Hf^tW%!na*!YE$-rorotrxMwiO7BVcr4+Ck`Z{-c&olgcsVu zW-_5mK=~(B2&^$fwIM`Do%qNfg_IKZ@jqVLJgo;pwavQP#jjBbSt}3q+`ffgnl%1* zww1;~_~_~4eJVlaQFDOlsI(@r^F6|o;`X5ts1^0v;9Nze<9EI8qu3D;U|ZwKU>S~& z34hm|d$R&M&?aU|*8mY1l#QOA#Nl$~=wsKh0;CMYSbnqjwj|f@P1b<8#h&rp`dM+} zx7%%nHAo82qG}pr$AZWj6B)7HM$D+S{dMe@c zi7dshP+?1`8HKtoT8W|4ScnIG>-C|)W}X=OP$K$HEHL`?^pb`y6@Gn$URzBiKi~0U zK%SGM$47(!PF)Enqr^nv5|62Te_LIU9YgaSx~KU_LbrM6GQ3cy-wunuDBvD+CWBz+ zBPt11iyun6($&S%M_ql2Y$xeCKUw!>Xds3WVFWt6;&%$bLmL6Ku(mo;hWI&sJ9(V8 zj$;gF*4)(Bj`wo{A4M1`5;67DzLK<_^$afFFkeOa_IN;xx_$|*{!Q}(UUb8%q1wLT zaPKZjMckvWQ#v87LE;Nfjg2V$<@-O(Jp(6cD=%2$#e5Y&fi=y|$LA_dT7LH64z?Qq zgQTHl{oc2jnHMGICz0RTB1V|jst(YHs*KLviMX@<6<*ABN&?g1DMR` z!_TQ?``wY0E@%Z{v2beC=lv4@k>P|Lg+|Dx5DW@30I(lCvnTm8AZc}VcQZb6Z$GWw z?=~-cDrSdh|CST1FLjUOS(OPYGQH4ochRce`&>N3bwbXBev-s@! zd@S9#IK>Vc>3^+LiH5%=p;VYsutvFMO$`lz7N82S_&(9R-CWGUJj)PW*P~$rYf(1^ zR}h$bRF|`ZMa%FGQXZ51<~5?rm+@oUjdSo7@q2Bc5yc@T4}3H(unNUA!+;MIEVk|2 z1`g$p+c{-BAphL5*e@~V?3%Nl6(-Gt8X~0C3(E5v~ht6WMGl zqqpU-F>1nPDzx|Q#ZRF)UJA+iWOC!%;}buB|ACh`ueCE~NIv5q_yZ&d64NXeOkxE| zVJKRP??vP=D^#KHa+R#fd28iUH}C{yv;{#lAnv{61)d2knFgeL#U4FUxq@`Q-1Spx zjk}?)p3sc}&=9dZ68m1d7Bd-*+m^!v>UCPq-ivEqThba*3_h}jdlm|<#h5A@h0MOS zvavkC!qsF>ChXz4_xE?+?aw>7?hWJeN~1GX5>4}ufBLHHd;?Gd5@fDZ1j!u$YG4Fg zz>rTY*D;7fO`lv~qkiut&Uqzn-aKAwtK9GN^->jYUkso&D_=BhSC7yS^P9h2cQTf& z+*B^Y6tkhnfAxt;Q6J6}GMv=bN=QmtGsuK&mJgXVa$-@bOyL`@8;Q5b3rVw<$vyu8 zuRORk$)u7r6vGDAzfB4+Jq8#cl%Jy5d`XXkMbmmRs7#!ik>@ll)x zk<-jSURnBDiLptxNwV!v4KjgV)oB47U`_^+KW$)k=;PQW1+~Hxtd+;JB3*w0{%(76 ztl%x(V@4lL`7iv2Kc7H43sy%~9=lr0)-f6y-Vk^R5;nlaFu52PWj}v|Gv0;BbyC~C4z8`K(tj8K_D~bP0gP208m?V96k0p$!OcaG{ zq-63@aUt@x`S{;5HVNSa{r49)0K7R6Vj&eKj4*cFM>nJw?;CJD_SJbpl6Rxn`RdEO zkVQ9Ib^H%GW`A{!vA`!EFgpTy4Wa4e#N<054fA|@lJ}uozhY4DmYWapnIQvF`5r zM$6u86@^Q%M7;qS-w>MgzEwy{tsV~ohL_%QJ995=U+xYOlZ%qgos0XJ1|c@WC>1k4 z^!WGG@-UEaZkkIIqc}z+M_#P+l9Nk<$I&~?i8rC`|8Faq~(_Hl}hCzt`t8AAGRr-(V7S#TdvdisD2nyDTh#K7;1t z2rDI@=)roVKtql$aaUxZgzL79*Q9w5_Y*c?w69Gy~&wFim?o$%j zCegQyqb`vFs0d`LrmTIj|mE||K)Bc=M>hck%2c2aE(W@~KuC){|#(|HPG4>)EG z^cBl1`qV0Zj&$I8=YAeH9ukv8RuY->w<;6|(Y}!W4yEG$V62sn7Wb#YplI3!)Mf#z z^gR??)@c;3d1nOMVKZKOd;%(2R47ectdbesAcF!v(WIREnn{GY zF9#^>+$QD86aFt4^`QRY@!%zq3_H35G~LF8B-%p=CV+cgLX<}j>tGF|qA$IX9?K(~wv!~!2-LFdgVMIh$|6oJ4sp4~3Ch0Z zqeeGz{lmrkf7_=b88d3cT^yoI=j9Kx>EMfAS`R?m-LxW2F8C${Q!}9A;m&S-S`hEH zG36gC&x^(lcrD$v6Ur*UmS3@MPP9+bN(3?t20zu(x~`SSzXnArk|k&m19+Q!TKI&C z_g8=4;NK3|y}U9o=sw#7(SN~D68q2Mw7P7?0Eo&%j|MJ0YXhdYsOeO8PYVwp+e}NJ z5;6_T85=IWF$-4mluM{8&oLQPOCTAQj z<7!d~6m<8yGUI$PVVCJ=T!LRLCbPf>J$I`d-q*sr9JmJm@@l%oKfLV!9fE%b^?27` z3`qaKms`TeeZ&E3l4}vfe&DO$H8{hXY!|YuwoVMNCaf!kSS1flj{M z8;7Mv@=~GR7=ZNKi{MnU+8fQ^Dkjj{gJ5tNz z*&O7w(wbIix-hH*`a2&15B$+3#uT6k;JMm;0U_CMs$cDAOI%QDK+1$xVU)$8>H@w7BRvw{5X%15^@M$AOG5=+ zZ&ZbE1L4MqRpX>xAPzwn*arAe3E_mEacfG&i`_$C3e*8_a98wSu^j&uEMBH~&;PlR zUx4eYB96^<{=a7$QM{K96ySh%C{&|fypj;%lOsyjD)HjTCty%#&UNxaV+TTgn;u8gcP(+``FeU^tCq*KyIcaen_Rs(zc-h7w0N}? z4%86A)Clm76l4RdUpCsjEbLb|%`uT)D*5_od?%#XI>wb`Fij2D2G?UC95PaRrI~gz z|9t3eFLWf&#~)7dM8lqBCi)Tb(+>n$sFuS~`L0pG}ZCUGKOHs?8X?w?> z-ED~4Zw8w|#?}q+zv2L3kZa3K^b=vko6fGbb8^8)hMb&K-oE0o) z{2!&6?tVfjTuZ#q%BCSd(=f3wz0WeuFpw&HS8E_|gU(w%AGN(^KI1LzE-bE_I7T zE1hLvYpp%aG`lSuQ{W{(W(A--uKZ`{o3g!w9~)p16_OY6Nd0(DB7$jyC>WY^<~j4C zQRio+$fK^a!RLWJ4=?yhN8PCkqca#SSlaD*loXlw;opgxm;{|s9=v=Ky~SZLK9GJ7 zlS^=JI*#u1W(YG7fvyZHh3M(vNtJaL%!_em`RMLVQA5+g-^_}}(0LV6)jtfQ9v8R2 zr$rJOlJ4^pJlNt^8Ae7Edyi>gd6{`FR~VaW$xH3 z1Wyq@B)z8^f=)qWF!tB2%lulW)L-3XgYcYMA6&)gg@r|`oR27O{9EqEt`{jFI$1*>%Jt039B2oqAS#L zGKTSR8+tHeot7mL!W_V^zW~O#YxRL(D15{~Bn;66a*B%IB6&dYRhTR0q$k*b;ysmm zpY*JlejKV&NdtwZ6H6*taCh!Hy4Knz2|#Qsz}xLS!eE2rp1(RwAnBGaWMF=Uu({xb zH%b-CUYkD6^-e^c`_6lu$OrsHK@U0e>a_gA(J`ul`oH(PqFMV|*J-6|jnfxiFe(p% z*ePt}w1(tp$NATh)!V=4uPS7Cb(KqH2FX}BM`s#DpLiR)U~=(+R(QNLnMXW2ACSz5g$Mv-zyu)+#gyWU zn|B|q4f=?igw|0-(-`!c@F2JKgk*GpF6jK?brO#%N^3fJZCgqhfUwDXPmX4g4J?p8 zq9g5xn2{cR)@91%mQ=5v)@!QXUFw_?8r#+FW7yTIZm+N&l1?Rj6=%ezm$m;6VClwf z2zD8iYmn4w0^cyQ1Kkg(QQw`P=e#wi^qs5{-`NS-6bZk~&Cp@ycMHuWdxU)dg&4*> zAFH*#A^u3?K2B0*va;{57MXgf&!n(~&XmmEAUoeykVz3D61ezbULHUWDXbc{{czH2 zkfdt^{*+@NeANC^W=!(-l}vc^;6Jpa{b4xdWRo?FV8wk=pj*|ulm_7e-fA`gfmR9X z;JEzG{3s)JbWYLTAJg5bEhD^d-#`wl7FSyNG#WSBCoe3 zZ`TmL_#=ZHOtPRPLWt9B&0Iioj=x6J!$Gy)ozD#^&w#oK=yud-M;GxQtfsQ}tp>cF znFF9j;(YbPL0rBY6`c=M?=}BC~{Sd zz@bNGeVnuUf@t6#s3?;;%7Rm@Q|jQFMpM!YJrNb*F)@K+spd)4dhesIcq2cNN@vjX z!$oDXn@wY4(?!F0>WGoyjhdaM1CLX^AEw zm01F?83x-faHhs!e;408G;>L&AvOeB-S_ZjXH81D1VcGqL6!| zDRxB|u@j@?eqYsv423Jt3z@ucEp~hTo7(SNXio6o%e!A+y?S}>IwWC0^BF|^v+ba` z=dX`u5hTY79|!zA7)u-bBap7c%ZQbobNc!XWW*DxT|?NzAR7*Qh-T=3Spgz%mUv>s z&Z!}hiVqt$Ho?1LghSwfba7GWWhr)aG6++p_HhoFXfVBgR8}mUyz(?j7-IX`O-?V} zA$jqUoc~`L)Ta{TVJ)RvlxLF<)sC+Q^w08)CRdZMO6Bj>7Fx1A>$TJ=_p5%V$?>(g z{+Lc7E5@sW&ikL`|jlr3P7a1F9bw@yfg^^82S2#i88~L z-Y_G8Y5JcI8D8Eezy1C!L}&h?UyV6*a-rBHpN(S^U9^i+_mLtQfo1C(V8Y|Gb|I~V z3oK)CIFp9ps~%K&iuXX~VcAqnSU(GE6yk09^Ve81^92gkRS)YkSj{gSO))D5%zmp1 zIzFamv4CTo_~^)$AMmu+fq&+m1Mu!-PW)a{*bZ5r&Xc1~!we6~5dr53OWp>=1eJI0 zPFMrqnoFIF)N;(rFjH~*Lvcqxpn*#C3;{w)97IWi>mZA{((`g-u(|O@`RyIIYDFl$ z4RGVaomAiZ)T@7V7;LGk=|BOB*+@B z2a}4l{nAt06tF7;SVwA@bKC*19@YTaC!q8%a3ls)(;&D|UsXL-$ zP6A%p9CbenFPtTWrHxy9z7Q<2(fKydh8=hMIy#X4KQFh}aGdcP*!*tI8kipl+<@OV z?}B9hd7X8^D5ss}kjNBUsw$J^rlqV%fFm6@I~(b2WR$zHG5fJ!&4v4yR`3`;!PS_DDQ{w}_uqfic6lb4VGI?Jlk;C+--RdhX8 zsbtELJ_esNc$!b-Ti@UIn=G@ zJ~W-^0WFxaC(9m_1RFn3i;-`)GPD<>p+H9u@4U}Zw(C8Yk(;|POt^jWzykF4I84M( zh@u#U;IYmW$*B78OHt=eu62DPeny)Dw`{Tj((N6>tv_|v_oxv#byndi*)-5O`(;$- zWHHMnpRqqLR8(-$t(f%x5e7_5aPp#QUJ|fEl?OaN`=u7VOZ?J9y_qo{w95=D`$T}dty2adKr@KWtQiKp(UEw-p)0DCB*q# zb9_G)8dHjH$noVw%_co05g=GL>`s;bLsBdoH#t?onQ6Ck=@(C8gqbn z{K~BGT*tK2C-tv6Yvo|X`ZwBl`621;T*%!nt~&7G#XcZk8BOo)?%wTEJmGarMG@c} z8aYGdtc{;ph=ffv9(YA0+gQjKz00=|YfHIcX+f#r?)YJ}B6DK-N4~Vhu{`w%8lL*H~%|LcTHl%@3H@NjT zQ(BCr{koaf8!r*wC^i(3#fxAdtWfIPgFrKm$NxlYEltV}$EfiWJy{pp@_CMhsF&U+ zubgnlkC8(VVY>#$Zyh}d0f7;@U_0>6t!2r(jViFad<(F10A%!pGO~QdZ#9o7b_AFq zLI?-1GRI#&W88z z4Ziz!4tWI%Fv<*B+Y|iSk`5_8O{C**Yu)zWWrqMJZJ_3ema`I6ZuiM<|8E}^M8wtE zHezov?jBTM)*uYqA41fVt2dfA`FFxy4)&K!@qOvu#izLZHo~VJechh;?~&Ct9gJg3 zCW~JJjK56GZO9XhS(mG(^ob;4^WYAs|{S7hs^6*|oWmEMmnUjXl350eHDfWp87hB3G*xyo804 zmsF+H-vBVurVBASd-Yf?Sj3>|RKZQ08}Nq}V`E;|bN0E_n{|+ks+qbPd4AhA5TD1F zt|zH6(>zHSn^1t7ZmjuD*pmVnO#TM_CiP^h!~GCV=Iz*bnU2sTmu;o@QXl2(}iB z$^dyf!Wls2^}l|J%?aJ2$*h}|Wj}3XmNUfW3w>-8@C4yFysb#!DDUFrR!aU6T7bg4COc!Huib z1Nc_)woiss#|?cuwGdj~$JF*dvA!%ik(v*w5gzgcJ`!gSd>BH5&$z;VZ{2qirbyIj zORPQ<>9t3<_s3?`{~%fgw4ejzuXkAkAMeLr6W&8%AjW4AT7dSW5i4l!$3 zA#Bhxqq5Q{p~~fRT0xvvbmKvhBRL@~62(HB@DQ_l546v4Onlpz6gXS~>|N7|>SXttxjN=yIR9e|uIi)U+W<(3M&6h~=PyzU!MnA88^qt{FQC4? zwd%Jb5ym$xu_0E=%5au>UX+G6*ciVYyjiATa)W_@J2O>1o zMmoUkC55#1`gj_EGu-){-_gcXh4AkIx-E!zUHzV6l{kENiTBe+xuMIM zWW47Gtyh2P)dVR`@6#A6cV!f2dwKbc(a|30i02+f7fmamW15*JOioBSE;Twq_1`Y> zP-2pBjdbmS%1Xe#LU`xObka;w%1>VrGxItOHJv!muCXbpf;eHMh~)tn>0ai0{+eR$ zC=26=lllub3#Ol!f%cJ+Kx!>BBZSX@1wGlNBzhs)XK(*G%LQz4^p(7r(44X{+Tx$} zqjtH>xHSSb*dY@T+Z{~P+gLKK_o*E>JODa{@YuzXK2IdvD`~M2Y(DyO6+_TN%%ee* z_>i?qw5%v&8%dFhnjX-hz_9be;@-+P3}w3K5mXZPtV9GjHZ6E%;Cf1z=SZWR^`~Gi zHY8?wb8@-uVvo$?fqH)xTR$dr6MXZE>G<-M{Y#I>JFoBVOQT06*-xFxu4b@IH*tuAQ2t%pnZv~J zK>~N3(l+{mu0-$mA4%H=4e;#Mc>hs!-9W^cY->ag*Wt+-CfmN9$zW#U(NjY zA_X&JR2PuUiZ6bm32ZqAl9^Q?hMlj31q1}{5(htlGt^sPt!x~!86R|ShrU(Yv@a)$ zZ`OSVxMuJ)x?&ClW42T`>SG}qU0Lg4p@J*%SWta!HHfsTC}Kp8AnJtR8BGs1f)`lF z5k}CGVsg(~^Xn+mBb)5|%Z&h!3RT zNti;8NZFvl8Gx=qVQRFKpu^L?04KlVpL{OlCZSqB*>9E^WA&C z1^cJ$5;eE{oxg`T4*e~}w+=KW+mV>`|t()FP-I&S7+o-7(0)}R!1(!Xe>lFpb)k$RI#y6jDjpoWrJ zD-sMO_@#4>R3+{`A~C;_fOI}f(VWq8+~y|Liq@I2g)}xQWa?5f)YN~NbZ3a` zYMLr9%6c7jWsyIxi~7cKsMGdy%!A4oXmY6TKr7<-man1R^=(nD=Xmi+MP2*$J%J1| zSSAPC#`mwmJL@W!m%s9U$BIi#+EFY$-gWHTU{a+Q!DY#@@BgU@7U~NfRqEQ_iI5kp za5^+ilprTM3i7S!Jsga1PoxLUUWF1`T`~HDTNHDG)f8?Kdv*lTdJyMf!_$F}rG?Z! z4`yd)BYM}g5_IZ`u#?N+g?ntF5Pe@ke{TVQhn)|z(zSaa{9@8RRbf!rswV=Qv9YS@ ztA8Br?ZqJE8hE|tH#Vk&E%wuK3+X^kpN|G z*@0N?i*y-|FCJ81^S(byMJF}lc~hn-#e5BS=Kvur!L~lzQ#@^2`VE@NlI4Ch!C-&9 z;Z>H0T*C3WK9nM%(<(+ZdC}fwEb98G$V^gwctK1*BPLmJ6onRq$cR@8K%zqSSu-=7kuwA2A>g&;|m{1PsyV>Ck` zW#PqoQqXq4^3WyO+a&au#(i)7t7|wrkEIq$O!GVuUrgYIg|0!WP7-0TsIg%g2U=-k zf~Cz?l_(lN#?TlUQV7WyJ^%3nQ80g9HV3542egiA$!DbZ%KaJ;3@1ek$zp z@~*6Wc{#z!p#*`aOG49&%R^$*NbVQPLum<$IN$ZSQ6uW7lDv?+B!m$Z8I&YwzkYV6 z9N$oa#O2R(`oLWt=f1d?X527!j5Wpx;vPEZBQz0@lPLAms@A$oBZ z#{7!QKG^iSROAOr#y&LHRm9%X==*`t_A8Z(qx;zAZfJSp_83hPr%=h@AF}GkJWw?n z*iCjWR!`Z=C6W*}TIEqV&wc!eo#yVi{%`$oxt-LN{scB#rswpvJ=2;uQ{ZMsM`Lu$ zktw`bj{hk@B|aX-r|@!XgrxcGx%V+pB+6{i1cnj7C{CB^O0ri9k2%*ItGH-qZ{$86 zs9FodfB`~e&Jh2+v#r4ZsbHp>j1qrYPdbbp4NgDFZYgeRAk1wtvn>qkIC`#=!ur~b z<`0q-*79ex-veNfaN>Epy^yJDU}rWHkJTgPcioJ*)TIrW-Jf-(=qHTNJZ|2?*`_K1 zC=rr(X_1FABIWZKne+#Yu#AxLdT3-%Dn>^5SJpC54P}9+ep_GF38g7wgp> zRFV_#s>m>&2bE$CJ6b2}WY@*BVzpJFO;oEGQU<>kzyDW!z)A=3<-Pgpt$4n%Z!5m5 z@>(QLq5 zc!P5qBd?UPzKm5$;!gX3Uh5P7FkILDUDLp`@1@rB7W~VcRc(hNAo*Sl2*_~mq&@gT z-yl-W7TiX))_wDLF%HSsg?d8ctuMWhwF1Y>R;2*g^82v^FXdTU?BD&QFa_ld`!RBN zU6Ek?dLWJUkE`Q4vHF8+4-#|}Xg>z0VH6?x$ZR=B=9&<1rR!J`q_w25s5M-e} z_U=)+RUyZ=Z&MIW{okv5_en!j-lo^w(Of9_Y=53iYw%eO+%pR}5HL12Zr&{`Z{AEd z`2`pPZfvCZhB`B3kX_M@jy?u(`Hc7x#O=q_LpYb9BMEfz!p^3YK{(eNFcRB`0As^} zS@r*kq2pROMK?4a|Lt90v_cJ?vo4N36}J?huJZWuNVAB8XfOOT7{eN;8I0xy@Q;@e zK=FfHfX^Rv2jg`2O($UL+M%_jslG?|axbu_t_8sC-c@Hz$powV5FGOhh1+@DDj|%N zqOkYHPkh5Ko4y$5oM2@YRfR$}Y~R<`7@oNF&5%YzUQ3f7Z;7ypv$blKUqg%^%06YT^Ie2L7Lw2r|(3SD}X%@NY28HwKSkO@_uz&9p}q+kB&QN zmi`ijZVO+3bJ6vJAK>kB1eBB!zt<$P*1T+3Q?`j&2tHj%P~S^0%>VLKKmP$E`@6N% zT1#8~*sY(ZYDsJJ^Tl_MK1<4~)II`4eIjCy8If7qB6#6?5V;p{VYl`5eG~sCPPhr>`I_MQxC`yD|M+ zLL9~9&dcb3_1s!41-So!^YEE(Tuj!+hPkY)u#5u~GakVeFXFeRJ`}E9H$D>jj1(Nq zI?xY@C9F5r0g6$O^63A2BCvq5866*Z%zkcuKE5!Cdb< z#<<*=fN5d{V5TV`*F7{AvAFk&#-HK0e%8xQZczZV4^R3xdtDC7qFF@7pw|#% zgO+TRFxH6BeYB5oz5hKaC3t&Jw(V;UI&l+aNfhm^S(A4HELG!cX~8k!MApeE_I-#$ z`yH|yzduhyJhD!YgYX|Hyeie8^;uECod$+3v4(G1$2fVYrH>5Z?{rDQJL=Vyyx%u7 zH>bVlwa~_8+Ug}Y{}Swf>Ht#n4q$}ZA4$lcyFu^JCt%pBk(bx94(Gf$@46iYn>Jr% zW#x;hx1D_eqx3uOC$IZ-0|eMxz_$AQ?_-*0S|Q-Ai|12T7mw5p6fd^RdDmpK=#o=_ z*C)yjSdK)8E5=3+U+3oItbrnq6pjLPw)<-(#;=y$Wyxlj){{s910|J%F41h;PNCS( zWp$a7*~a*yUQDb@ff}=-hZ1ymZLWGrd3YN`&~hG4)wbW~?U9P^pP#HAnQj;7^`y+p zG~t+cMk{_jS|2&@9KAZ==xV+uu+=~1LmYrPmg+X@BWA5l9~9 z|AwiP_UpeF+aUSX;5i^l>XUM#^AZNK-eKCX&Q|S?Xn?=wF%co>M z;ue6)HpMX^y!Ya5*A8u1iN5s_%jG^BovdatyvXxgw< z-Nt9(88lsv*G<3LY;@zbW;1~%sUU#6zCHFWh&OjO+L;=Y5)J=p>{OKAUYs0KVER@ade zz@S4Xq9H-=zfC%9KF8<#1wJDKmO!MN#JetkF%_~rp^FP?@+As4+iZ*|J(Q4#wV8%Q zg>3mLyv}oio9t1DaBKy@@9=eun*8>#(@`QI-*lO#&TmNS=^3;$*hwa%}$OH9z1xr}C z6960~z5Goc$}<;(C3D<#fF%c9-;|lflll~a;Ah%YdA{Q}Y-R|A1*&EbRQV-h^?1>w z!3aj(^C(}Od{TzQ|6p;=3Rvj_WagPi)b*(P=_5Hdr>1Vyg%~;bzpOtIPq0q{IKV&F z*f%V|QDd3ySso|SBSJBJg;kj?b+)_S6YOvB-|JRnXRuctXif>w4}x1(C8WVqK1i9# zY8X^BRUmBtvtRdG@L;>>wSu0W8Gzz)@?QQP6?|5#O&xeL`L({qbBot|SJy1)a6`+s+$*Cw#r1;EF|^sTtP&=B_Op;?D?RUUZgln%uStRz#z|yeLzuU znV6ven(GLk9xvMH2^8y%91*l}JmhVqRc}?hzFBnDZ0sC6S2vfMDE;;8itO+4kGamb zU8eQH+HG&no8peZHZ<<)(SHJ@zB9_2`QNYZI5Xxd?Y)Vja)ANCE49ZEz1Y=u(X#s> z&81d9HDB+Et?8AE_jwL8pB zCiz$uOlpJ?w$EdrM7AP91QL`e6`vJ+%+=JYFQNzs31Mn_k#RF~jfO{t z>|Z8r>4T#lqqTAUutkE;JeHs>{krf*p5^VHw)JfxYxh+7v5zs$kv z2}=b_FF@rh^c#Bt`MV?f8Z~{BSnxUH2y`T~g;)e8{`X>o`qj_w)bw<1Ev@ch*1XTH z-h1trCQUAzz?-(Xy*(!^4CM^CZ*ysVVtg&u13br7cpkj3txX19Iin;M6NuvkhTOX6 z1kQV{>MvgkgD(Pu29D0p;lvdmKMr4g#uHpduKqm}yes{81lmq;+y9!*`&++ybtjWc zO-=Qa)G0Yxo4VW5(rN)zn+u&NmjuA2X4f$HrHdB z94!0#BwMF&knf25+kOXlza+S1X{Fl~av+@pj<2hAcH=*8 z&R0u8TT@$G>&_^0F{JZd2*zI7K1XPmp3Y6C#fQ$F;`6YSEKr7Fi+kI@iVS5HgF2zfj27-|?GQ`nKmY7ZsX zsVYAKelnWj@O$#5F9%GD8R@}*vXi-RHU?;2m|;xN6~r^6#8wuLs%m;g0YT4G7(RctVOHa)=4C6g7l zPJ1EV1qcmyD#l3MJFva^uys#pBcAUL5e3joFTQB}vlN!&pS|}%P}+!zYsV(`{_V|C zu;(3zdsJW^7}fcvsIt5~nN(DCBxX*QK2C6b6%Hf;Evvlc2GtKIMPBWhtp56IR%?yD zva)i$tth!(JMw7nH=ludpa8JUC_WFivn%~4s_q#}>+g1(B*01Z#+r=N*MC~OHx9(F z{1Y?RG4b`uMDZmoa19}M!;zYHEE!@(hIcBb-^mcpXW&lwMTguaLS6kyE|dQTLor|1 zC@1KlURurTH67l>*TIUb<%3_bUgU-S5cs)D>#?>r|8q!m$gIE(Wq)?eOV-9)?Jv^d(?YuM{TO(uSW_|_& z$O_gj6=pyD=x_k}$N!{h?x~hmSFu)!=laJKYg^j|pprOwH*Y!oZae8}_N1jpWHqzX zqvi0f!xV`3LmHqYN`C0<=5zpzm2yY}E%%=Rzin=AJ^>^@)^>IuYik8pS8ZRuRANf3 zuB)?ZfD7>R|30H4s@Oui0zl(p(20|jW&ah2e(8jNI}b&>Do{s#mXo6 zuX7b&{}EUM%2q<4nkdrd;FRB-hyRFl6v=eOyWD=h*GiYW>jbOItOZ1QeINxJXCk{%;LI7B#yG+=>;$$z2z>`8ffQq@ea582(oR}gYq@Ic{ncK`t_N&`)u+;#~v@#PG z_fs3wmj+P?rZN_tvBKjpdK#{^q!>tv2xu^U!8QOh(Dc4__eJso*nlPTGDdh18mQ#G&lh z?jA1*%I}>uFTXnjM4H!SMI|CKGEKr)6p|t2V0m`1jBeqej&TJl=|wgQa}R)ZV%*i# z(&F*h`RV6>=_iRp;|KvfTQks7%vxmw=@WauS?kqtf5R4#M^a}G_W-5jwyHsuLG*c0h>2m7|K4`5+EWFd@7K1Y#lLJ`t_Q;%KWbsh-3e)l7Xh~k~VovIj;1H zh;QhQ4yVt%8;3)X=^&ie-k*K+DR)J15Sw&Sfh%=Wb#<`V27C*#2sDi#FyIQ{CVISoQIYt?=>ho<;uc$gA7j6eB|2yS z5HZ;u5n$9$)^~7$V3fDSHtiseA@$?O)}@yX)aDm;|7!mr@%_Fy6LaY+yGR~icXSbc zN|{n(PhLdB2pd?TLC%81j&jd3CyP$E=)-M86At^J4C)%4%mb{LI8OBs@^W(x$2Y?i zpDXUBAQmt42&Bd~K+XKvL@DWA|JSn{LU-y{Lz2QGUryKVciojszt4|<#;-l&XlN2i zNt`fUYg$`(`y1(ewcuklk!4aezlH7s^Ev!>1$!h2P=Tqwx!sobO5yN9Le?AcrU13SdVqtE~0tntM0hI$>wc~s+h4XTf&NE|U zH76$?lk0;NkzWX`N&i1r7@kY<3f9)vpsfGoAtn9+Kri=!pUD1O8P?DMENSK8;!PAn zwm?WxHoOrNN$mGsT~-6s`r5oNS={_FO9rHa+8!Mj-B=QzZhJ_{VEc`xhNgvRy3Tr}6W z-sx&(-<8AtfZrA+<2iq8U+vQzej4Pzgr2h81p4xfxdFGOgrAb#|4pLwl^&?z=(huw zGnx-^QQw?wK|hjk`rkiX#VR1ui>j&DV%^(2mg;%L1Xf)x&*I9GZzmAdKjWq&VC(`IA0v-xR%B-s-1Wr;7HJBAK|- zUC-!er7A$#fLLIBbq9D}8=$H0$7sTo0+mM?+Ad-cZztV63kM%+gl~Qd#$I>#&tWgD z?nwH~$DbBqTF+@dYk#}229=`$hsW5exqH6?ajtU$l!e!|_fPQZ7G4^D;jrT9C}1%r zW#HKSEHQGKnwWerNBCLn$h1i(x=s6kp)r6NprSJAJZ8MF5Kjcx8VLzeVrRI6KU2>S z`Z##GwjRL1>_c!uW!lN$A8B~P(-@e-Syx>o|Fi3}A}J2>bx_?^GLD$p&1 zRXkUG^+A@`>}^U4c#D(YBL3&U*C*ZGt$esCmw@V7MDowsu#4Xc0Ap59vj*nTeF)rP z=Zcl zj=Hpc1I)jG%vLY+pQVSB+ci2jISf;?`(jAYT4xdI+h@kH(J3pD!tuyG3Y-Ur@}7u1RrdIb%9p z9bS!KEBmD&c^)q`w|jE9l&Jp9$Y?P9;k#bYX&g*3_d~4U;u1<;I$i?=?GOa;RbXOV z%%cNEfJ+0?H{)N)PUNP1iSFa(#P{lQI%MkLfWE-au|W{aJeB%FbU?WXO8XqvNn0PP zy@B6kYc+?qL*Cx=&<6g>Te!NvS-EdO@XrVKK76mXc^6tRceR zjK}q}n}Q&_>r$x;-N4vudG5nNl+4*QwE>2(-997c`RR}U!y8Asww)Kgx7E>(x4)qoe{&wUmw~kr({W4XZwcKWLA7A;7ff6EOQ{y)z(&_-|EHvG}06O zlLK0rlahHykoZ*Dju#_s($pkJ^Hl*aeX5Y1Z30vffS{zVIRBSe@x?rde#qn2q@R*T z$VkARnTCV=S^oV)5Z?;(6l6E?-b4VJJBlEKdmWV4PoY*XEdkY1#M*Rhp>$Ch>J z(h}BTds89WYP#H})@*%5@NoygBtMXP_4#ngGmMT#FnHW?A@>s+&%5h8{wuBNzTNbAGwekhX(VL_05NLqd03t!YN{3* z;Z)J8dS(f4@7=+ev933Q3NT}1)PjA!5R{-6xT?^bW;wtD@I!rlNXAZmeOAoLOXaWp z3>}ytO+$v&Qx!JK$r9hanfL_MnN3kWy)=9A2}p$wmJlDw$cSe>=A4K-c}U*^SLyu- z`nr0DPk#h$eR0^G%4hUqi~iZ2UxtDfZlXvPaXkt?yjOcOFHaQn3z8RPZSWZHg~*)@ zusi#~m|L5qBX>Yu{!1mX@AUHj6&~L2=lmvmkBSJil86>8;Bab= zl)DjN%yI8_bbh`ocFu5zCI=+oybNUJP#U(YJR%v!0gxAT#Kv%&4FKt*6v^8WRiK@P zr!D?TcQ(h3PM$#j7SoC=qYCR;;Z0QKecVnKCw56?>0HA?4AA*9hFdlAX33}6Z+>3` z7yL>XpEC}~iUv47bo;mFa zHpe=<{kxbo)hj5qZXT-W?sB>V#!m)zv*V0mByJtcI+BjRkR#Ghw)Xj90a$v>hjTYt zFefj0A9-;o2wp)EIuS9Z*LfsEy1d~T$sCl65&zZok;);8YtHpc?=wbh-P>=q^&4N| zN)1FsJADj^1zO{=rEn#7lSU~g9bgKjf&Po(GZ9eSrJWFy$VZ8^&434oU z?kDH#{v+@)B_$CuFhP#oseWnr)9Hw1FSHxwo*TO%M-*`(FZ|%RQ$fl4ZDcj~pnS!v zu~;~E4lU_)G2`>kQM&qw2Y^NYGd!CWs-QKuP3ND@=aa0|i>Wl((Sj=#Cr1jEV>__M zJ0DZF;V5-mFP~u5Pnm*QJC&BkmOdG0oocMse(A)*sY~|shb&jq@gb(VQMdoAb1&4wT)e9y58qiWRPfQ@p9wX4^%M@0>?k z0@JQ_LL?AqYH>~l>^*k+RGTGbtNOBa{ndqv3qd&;m~s0i+%4<x*{UAjF4fo6$~J1EwPv zFHWx|rRLd)|G8|W#l&nGOZyCTFiHgBWRfMfCKd?K7e$K8Ir5>V!YU*;;Z&)UgF{+t zgF6)j*XcDAo0eK_mG2yMVDi;?v&N7mN*rMg%NnCKA`aZq(!lOFfnC`BY>*O6?KafA z!2a2W;%{ShhR@>j3HkTJhSls9&JXKb53J`-QS=o)l zMp_)h&2@M!pMf7?HT@uvkq`YORAXhSD|DWTxuaS52x8*fEAsGno8_I?wM}o!2{dV@ z1^YU3N|%se4@5CORBKXF9XUt+surO((Es=CJ{b`TGg5LEgv^LQavB3ew62Riqu1)g zZlGXzH?=h}QFAuIZw<3hN$I2JcV7s;EOi!dL6nz4O+V-p)v`D+BD4l(WhUw{-)Ov_ z(MgKbZWDDx{K^T0j0taCGr4{u51OD5J9Y%eb{Gc#(dY^3M}7}Lm4rOHYrp9qK1i1* zs=EejR0@4R7;leE|fSjZ`Z3eBygdrpc&d9aAw)E`&vX zp6pzYc~vLs5IMbROfUYW>+|)*7vb_!v2Ipfi{J@2XF;D%4CKz2iPi32C0|a1??rFf z(0>73--w{7#so)5zuc`NO}G#;(0u&*c#gM}<#@1&1-I@q zEChFa;@NWfv;JyNrJ|QoYb8Y#w)oY%8s^oQ+D<%gDxX1)8=pbAxgAqu>Z3Vm?{VN} z&Hv0CwR%v|cz#W4BVeu72GfB)Q4Cv+n=&+lBH=1fb{R4hdI9va)={$s8SxNpHAgB_|--;Ndns zL7FRy6w$utM0|wl{&R!(zKyR_e=hqxAA-FJH%xXSqMm54h@orSpmmw!mf5O#fc2}w zqlJ%qhSuS?`^ai1#a=uS0sKcoqdPorFqjQ~#2bl0oo{+K%3=3HQw552E~)8OYdZ2- zu54)3j1(y>`Au4cSVn3?@XP{jjA}5Gr|qt|DlTLyIB;)$^8LGg?c6Ysdsr>cn&(lm z!^<`^(cj0QDBH}5a3hS{Tb36k2(4CVj`)2(cl|k~xJ<0^Q23!iri-+8^{x5ZtDcb% z?x_Io4DkmOHx)iL>Xl2Www%^bB!`4lai&gam25STAR)<}bg(-5YSuU7<-GKR{ey$cV3>34 z2{%~8yufhH`iL8-;wMT3IH+QpQku31%{FJIMHk)d_)9_VX>+1hV@SWEdhV2ok;lym z4RNy@;~`Q%)OP!Wsw6jA!uwcancnpKUIJq$J#6|EHZ8MtlNcLWNLb)J(Gl&~Nk z{A*>6jKm(fsp}`zJtPIa&V_p$-(#s19@Oo++YIvHWBFJz)rh%6;G)tr+(>c^dxKTH zL{FNVW0P%E2n{!ZHxUPG)qkJC(yO+%H`%UzC@Qu0l{34~kNJU#E^OpvuAPpDk-Ba} zw1s=E%Zs7al4+cqt7e29H8N%Ny`4s7&>S)FY$l{_RExAQ`c(%~48Jvl!k>7`&?}pv zOc8)p?H%-U)t%MK$;vKmR*7VuVi4w)#_>936*!)3jdP%FMgd+FGeK_zORNEC$ z(;1)9)#E=ItrCYT@rO%btZ2dBfG|qxK*Q6L3qa&g?Q^L|N`=^)V5nsOQ?^Z#97rxhU<~OJm+d&&VsSy)uJE_U>DOW$Ew6ruv*NVM&;8VT!wFKco z{WFg7kBnpbJzRYT7gc_Fn8|G6l~ND)l7ylOLo>E3p{CB#b!*#!O8Z{fws3A9D>K7d zj(?wDV`jwoxTgzbO^T<+Z?nzRr+mVNe=E%mgFWNE?9GYx$sx}h`8_*1Os@xomP)#D z>*DYpxPJPj(nMr0lWI;wPr4l>rL+4 zW)n!gypJE_Q&W2-7;AerFpu{;coGOzt035Dh8*Oe5H=QmTgL>=M~$yIp=5c(pvtA>c-aBJgUy z{O#Y;&vtvjT@QmzykW<)*Uf6KJ7Tv?_<;A+SsO%@5fO~q1LvuS&)?;3MM707{}j!i zZJOju*l;w}WfHa=5|dF=XdHK88egsWeD%^EGX6rSaLFAb3H?`)6n_fhgOZy%ZGF51 zBw?CuuaCBCB^8J@1$(>c@VEflZ1dIwoQ9 zL_Ky^@Giq~=(M|gcd^qTPnKKKVx}KA8*o^8d7ih5jJUVlQ3n36FuS@Qf5-bcPMGsR zJMjK9-yA=@4h>ve)&-ZF!7=M+nwpy29y^9;?Z>x|Pk2-l0TV=me}jdK%j#h1%hv3t z3;+{Wxo_*+*U#SwklLgk1~_FjcoDDfxvRw4((PnUqrTJqMT5&KBNQBi!pN04+wYtO zGzPLd-ugir>OXuB3>hM0pHRb@16fZt9@xMAUbp0x)k|7uksA?Dt zCcOOix&9+#bin3QyBAJU3qqmHd5Ct=pd7d7tKHz3@ba-ncc$mY+c=%x>M!`FO&}$H z54M7k#*D%wG0mB$;v}y)Ng^f^HLBm}nd3kCqOiNmtSytMa;A0X~ z`+K~CL7CmR_Fugk&DebYy(pbEtyAmY8k@BtY(4IA8Y9IakDqjUu|p6codvV zK(k`m9svE?BOiTdd?9BzjW1NM$`Zp72=(^bun1Ak%gTUMAkVUzZT3R<^nyGB^Xz_a zj7Op?3DFBNSSHEBax=CkaCr4T8(T@&A}KL({AoBgYJ(M?v`|<(o0~E{^Y;7ce&gL} z_A3E710ts9J0;MLY~m?XDDoVG-REQ=#OlB`aGvki=&I@9J^9y%g!qHXE0G<%#zS+1 zglb>xUSnDKAUBs@xu@u6yZPjMa}UPok!k-sj;txf)YeIS<*SrwK@$|`7FTvZNG{!c zxHk-Jb}815A00!KOit6AtZ-;a2}^uYJwUoiFKJUR~vL+ZbCEOm1#&UfcfsS+?1jOHNLX z=TIe6n8#a;gCm+jCIkiAsxJ!OKyTr>d%JRW?L-WSjb~9XHZqfS$LHGH4xgegHuQ-m z$`KYq({o-?4F2@qO@3~B_cMQEZJt-9aNG7Zcp5rDuFv;%g3^nT`jw-N$1A9ZG;MuK z+pl~69dXOHlpT94DeCKhY*9#aaDDVG1QOt_BrByELbWAq8ox5hw~49C5E?#=O_9Z? zvQXjkfed9^!d9W9kHK#6q4?-?@OPNN3MCFM_A~Bv%8R$+pEzI4SBY_}Z1zWTPK$QT zLriYX_Br-4v9Q$kJ*BXyN4Dm?St!%Pz-x05YNw!oKr_Tgay$IYyDuKD^&tYMr{WVW zx@)QL#qn}Q5AFSj4@2SHyR}icEVfoW z2knFL1w)UF$7m4{_(>88a~7Ab9;XkDwqDe6;u1;OfYfL%IHl4qQ-4|+YU0l*JKux#id-Cc3)ud zF1dP4ZS_O?AS7S4SO+k@C1Ul)JA3f-iQT7G$U7eV1CAri-zxQ`F|!h$d-R~T&kW2rgS@b`e5R{QdAp-;csN#XcHNZ(7n=wi z&={6)0VCuH1cqh`340ZIbdv@kTxq?5DY5CE2hI7)gQ*K9Et*ksuaImWZ#>*<+!~;? z^L=;K-(w=sVz{rpDe4Omizuxk@pjwverSn~iO?6n0tT|IoBM+nDj{H^y)Q$Gj$PFD<`@I)xJAogC~jHRy@{i zRmkG0_T;}Om8+O^pHJ`NHe$ZgkCP$$2&$=rM36b^npA$2H6U^yAkwe1pHT$S0^l?( z00N6HZ3o@Tg+zTp#PGtxf(Hn*letWWQcV25L~^zCD$x02w>5hmdIDlRRmg#sTJRNo zrqS&u@bRUhD`;BljJ=7byU~WsawR zb!FvXy&${NX;J=ocdi_!2lma~D2~?&LE^X=_KG56S=K zZfsOxa5uRx+VIcRl?2-EK_CElW#eX=5b+)-gToM`R|>qqc3{!RN=iv0*~Ph+??)nGL-U`5@TcOT<#F1{-ZnjqvryGf?3U2*DC zu^*fWKEvo=d(Xf>%8yp_0;h26zI@a#Fpgt+)@L_b%|kQ`Ee~+roy}SwE#PxrQUppO z&R2q)XX>0z8oON}5%r^Kzf|-9xlWblCseMNM>_5r&871(;>Wkj?}k zv0KaurCk8x(HCQdPmzWV34mLausrJreV~DPbb#59;kq#8z%Al@ zpg~)PShnth>9%~^gFJ#)h1QMou)+n{7;ed5m%I6N-Nzr^=dE=Rx@;#JF8%4XbeYuk zOYFsr+GbDf)kMa^HS90Oh2FU|?Xr2&TI^M*1%J8PQ8TzAP6n#G0yj z9Yq38E2fUzX4y2Rf4|N@cv$>(4F7>kazhvdf4+9^DX{TJKd``6)tgpJ#Va zRjofoAvynJBo&@Pk!8$3VDOKo!Lp*#HSco29)4)Yf2Y@5mPadm7vue5h>|oX4y2`+ z_mOst+M9UKgKq7lP23C3E12%ZHjD7x2?|)20QzZ-6c)^#Cv@c}zk^Vgb+WwB{$9<+-a@tp%%pX8c|8UaU%GhZFto+<2HOcrOy*Qa(?7n?LzEY&GL_U?8in zUlHoG_9;5YFWLG_;`}?n^F*U^uu!>gGTI`seN!=W0Yq(uQ?Y|oW^_f9+gVLe(_Sh9 zxK^?P8~n!@FNa^pg{Cb|F$n33N>bfN6k~SyjB22!jEH4P4g5l=Y0x})T5+A{KGZf+ z)|&wg)%olOwNZI_dGcInr^8_pBzZE01uy{(B5AFO{Yd4|jBgXg2(8sAteaz)^ z0jRs$ZM@>N&7=9IPb5MT6}wIBjmo`9DEwOZ%7h^5e)Zz+Em#J~&EFVbj{~oGfBWhF zJ5*v2wJ2qS>9lRckhQTMX?45s_oz3x<*&48zyzmth}N3NU*E$(rWeB=NtCcg78SGa zFK$C0>lZF+Ch^%mSraVGEH-<%`y$#jZd)8;csxX<|4NO~nv^*P8&xeSg~fr}^lL7y zcWxT&`Z7xCmwg~t`!YN%S+<$UYoQ!y2Se}7mpoe&3~W9SOu>ikeT~C2(+)k1`v7ct~Qx+v9h6$At~BTq|M z9YfjRMP}+W!6!vgdlFj9yO0Y_JqEppNeRwsaU>}eoz+9My9Xe(qs11kt?Ciu8THb| z>%dmelqZo44IRPPYKxfP_oNhdgy&L#zZ;(nfS7<^9uIC8))1INY1A(BKapYS0_1f_ zRyv1hxdo&pqE8_GD+njaO8fH5+j=ba*AIt9^>&BpUX^4x?5<9@oy@;(nTEl$;u60l z-zWRm&8%~axr;PJSuGxUE2*k3qdPH!c=C%yzDinvDJ4$|NQEn-<$tO%T49Wc z>)vopAP>sX0AOE~8ZA?}=4MgZz4i_7?+@5UtEoX|bfSR+6G$e*)F4%^*$F*K8@i+a zDu(LjkJC~vrvX{$9SnS(nccwnIE1PDTHP%UXHRPRjO&RAU?r<>-v0@^)3&R~sQVH^ zgs;QM@v??I2>7aS%?WJWV90$)^)Pu5hoB|FWG2ez)|P(f$Ha4ty}l{&EsoL~CRA@< zLmwAjI7&>r;3A0s$N2IW%J?UW`W(NK_;cwp>%GYVMCMwv{(pQqTQ3hRQ<}Ca`YV<-gw|A>^O6{dt?LmkaLu35^A4 zfa8*XOtjM?#SoK>^=|5-ht{|euwDU$XyIu#nWFqM1?Nojn5_D@} zbh|XLy6TDjOpJ_iNl9d%KrSJ8$4$)CL)wgKM*|m;{urllVl>n7qMesyf1VMMr0hH` zW(8#*wG%JbaJzN$DH;A{c!E*rMnHvXge+LG;jwiGG z=xnd_-LWr!h8wRhvo$L3>q9rw$ixbNoSD4TpTM1XZBb)Om!1{XKO6oJo{lzUJx@b# z!9jt5LSBA8ulv^Inz>b$8+pD>rCC=5Q;IJL3wnEd;h)2Zf4)8()YNuI*b4L*I1BE? zx!tg`>!nz2r@@&&4wPeHQ&}L?H%%CtQX5>UmFBgqA+$QpGYQ6AU}nMNR)pzu$tSg9 zX(mNh)8|nuaf;Q%`{wrpGJyR>E`%In3799N-wsiOWYkLnw;NZ6rO=C8I$n+-t460c z_r`6Xl;{HxQW&wU{Na(IML!j-azQZy8kdE0#U#TFp_AYWvSIPRkdUE^4;w1 zQ|nC(2-C58?6d|jXn(J%CIadO-@bigW@mrp+OX?)(uD4hxD3=Z zghF$#`9PVR$th6ReqXA6EkXD3<42wpg5iunF*I2JOorL;R!L_BHY%V9GKO8Mkv2Uc z0{lt`8H%KDlR$WSEP&f@OHFaZSVxO<5(88B>xh{UZ$hT#S!uCRmRq(>jFV?lZr+k` zbe=B{4QQ7ESdWo8eYANJG)-lCv-h+FF&_>XOCN(KOzk|V>AmHaPE1|Phj?&|Oy?T6 ztGNQy83E5K;0}|U9B)C|-z|Fik4iw82s9v1{&lN)JlmWIw^3Cgkd!5+aJ8I%=-LFw zv>%9tT_{DI8PVE#5EHKe?bt(5S77IwCbrw02mso(j~=_T9J78+@tM&D#%p~PYrnKm z9UQnP@c})i8r0PUpWP>HCEV+@-gFt5ehR^8@{)zp*_h8}HWoX#6QCrM$RNOCJ-Gjc z?239sucTX`=g|jfjCODQh~rh4iY`&0?K1t z)<$yHELMlIIDDM9!-a5kK0&lC?6hcbTxfzy&bIJACd3<_yqwW1IhzE*$C%@ZN^1{s z&sSW??7OcT=JaD2#eG^^IB)OP#p?(eFULpo0zW!AOzw{b>`gAOtT+P! zW{(dg&(vZnSfM3F3%HRKer}FxNS0k*$U}zu``fqIf-w01?M)Z+X6}mg4Gb{y@m2jeV^Ygh z1ihtRP9Wz&i$u&{KyS)Gi7zjsrEp(Tk`A%8wI#pm)L>X|n8p4!E;ITrDzwevv8f)5 z%{%*jTCIK%f|3P4Q+mS7d{go#xOriMm(Z1y!gH;kUOw{E-ey6CHz%s+=2|rhIT67r zw-abIQ}pd_i@U2of8wqm!gpN5n+OtS!2ek4+=4f3VCqQK-R_*-nH6=T0v%n1wYHyv z^Zf+iPXU4t-{^0?U<>^oS@P}kD&aGIqbJH8P7(}7#*mUr4e%iFq;OSoXR>-cUq@XE zvVXdTjx+u&sdU;(o+kU_h4Qo zLkli-jNHi36^iH7GJSQ3a*ueC!F)3V)!8! z7uP%Wf^DzTwzU2Y(6=Pvn=rwOFdDaD5XdA(Ww^hxTzw=qx*k*7MxqH}yCx`M)fsR;hYiuYYQ>Ns2r=dgp=T&{_ZD3kj2I zx~#1&>-zdSdbSV`N2lgwB*;nmv5F7#;I7q91Z~aIN3c{9;q4@$bVvo<2=)3=J=yHpSiV9uK z3t=~IPL&G00p3akl$LmI6cupe2PPyWtX0yz-orr8-=mEUo&DtF0^a-i)2CmT&^tHp z>ZUwEpA@PwlQ~4fU(}H`vX+*KUsIQcSJSKHKYE72_S(AL-t`-I%M5gptIqz<1x0Gc z90cC+o6d3f&q~Eo`sf#>?evG6=yVQ!(Ubz4jOhvd45g?m^Ya2V3!raQN#_p-7y!TM zC(unKnp)_Yp3RYs3&>@!j;Dc|at;not)a(^o1y1?Fi5W0_Pt^IiLZjk9x<@J(bDi{ zewTZ84y^HUyt3^FH;vk=S~_gU2cG6TIJZT2UADQK#hoCvjyGQVpGIE07n#vPBs%5D z?4NB|D2pEYjlMm9!)9Ri0h7w~h%L}<9Htv{{^on$eJtG^jj+C{zIwx$nsFOBIVh0o zS{!YRgBm*0QT{X$7p8W2+`)k}llr@XotY-RW=|e4=VuvIr_obZ&pt#?AsfgPNd#&5 zA*kp=xvoF!j-{L15;XB%f8c$z(PdXRBQGU|0fj;#nmRfz-;^HigEW30fE-R|%PEII zwJmukJr=!8j-pxYCM}r?v|d4WKycpr=c08Wl_wBgNYF*5;iGBgCaZV(=jGPMNn`VWj}3E(pc?IyeZn=Lx;D zju^QhKm%cDTu4Aix8VXS$nw53M?0NCJ6m=p0uJ!sYf0C2?fD6Cq@JK4jXLXHMh5la z@{8TsPhOykbjr+n+XP@o(#()l(znT79*<0P0HVw4dm9lkWb~zHU4$Js{ypE*Mb3{8 zAv^FeSVsF$0?Cd1lc>Y@cbs0EFrjZ$mzn@`K0Y*D@jQ<8h`?7 z0_Vot`@s&=iJufy$`5pS=6~cm_`ZHrdb$H6p;7qLh~6MPC)u70H_^~UtDiWX-zft~ z)XhOl55QDma67_{GSWbil{31m8QvbSW}Yh_ZR?(4V`DS!8CF^k)(Lo15lHzer-qXZi>RTWp9CnP|KUXagr4YEjM&aEpm!E)^4QJK&%cp9tk7X9)taa# z%Cd3|uu>`^d&2?qP@M(+CU*`ruLR1SRDM@zFw1gNzL>7H!>1P9suw2&&dtW?D|yf) z0M?lv#M2VM$?B9LY~KR7<6+rHYN#igZJ52{WM!U`v$+5<{d=v)k%FWFAFKICz05>f z)7Q zdLj4~?Sp!xZ@2kwqf|>Oc@PXPm&RE`@A@6DS+to&LFHsp9C^AEQA_h|pfFnWi)mi-LCx4)!ZK^5Cxz?IFj498&=X^78ZqH zkqA^kTRp&}Q$wdNGIR$$1(i*}u|@W~W*0MWdMhZUpe<)@Xcg8M_E|tOFmUOY5#Mg3MmhGmbPMm9ZWfL7OE4g6F+w zf4E(AZpl}(xl=G&E)dj-<?cl=K0IzfIVE10{M0nBZK$5k(ASVQTghK(tU&4~bQZ ze>A1+8N0!4Oz;oXjlNZ3&{qs{3W^jyj2<2wcwX-JprLLQOxxI)_DKroa;W6xJdeZl zUo_i{)&Th5x$}uSbWn}+7%Vc7<>J#xG=Fis1y0L%6MylQ3c!1H{iNfw#0OniVr_Cf z`OSe^B>woJbzQM>u%j#+Jk1_wJ$zz&0cMihUmMm6LrKuhD;Iwc7!e&BS!eqXOsE){ zwoi-r{M6Z`q@KWRkj)HPJJ3;?38gp8+F_YD~JjEv(1Yw`ak4a69q- zDJMwD0R(a(V@#4Mh(CJ%EawRhiUy4JCF(4K=~`Y1MtxBL4=BQZrZN8AyP@1ziN0hG z1JBhgk5n-aKt}^_-P_k^)*VHKw$5CwmkA)&h>w*x$3=J@uIvL`n#W=Gk>IPzHc-u5 zf3edPYdhW0(9rzn`T`w{TwRpHUI*T|wNP3&yU2O;v}tf^tuG{c2qLDe0qbYKJB83roc%W%nc{vj;PT4#B8|$daG+}uL9VCfsAM|>n=}a-y|p6 zf$v0R2rbfTOkK55t*;;WLX}8>Xk?z2 zS2Q&G?URoOx;bWV{QU;dKn(Q*$wgJ5k_Lv;G`B5uMWP41po?Gh8l0D(+FgK_1?Iq> z<5O}Y1_o3hen%xHJeC8L=n@J5yO7-S7bq}k^+Pu%`}Hx!_#PKmY$%;ys)2n26ryul z)7Rg>2+pQC*o&F&Q#QbmrGsMHq|D4r;3JJ>Krt1_le#yL64KNAz^^NN@s-xo`Tl;2 zMs&V!c5&l_#uzdE-g2^eUh(8XZ^yIvEvJf=)GM!dcex~IfyQah-s)Z|)AIN{BpDdn zkN=UTgz-xQ7_M@O=FvPVj7vk+B03w}3g}f#F!wOHdQez0fMV^CB zY2e|>fgZNt;1f20ckn`o1V;IwF5PA{pT};BA3djOu@a#Dq3;Hsm2{v?L%6Rj z^6Ipq>?WTey2ZaR3(g+Mwvr%OVgSOP zj8nzA6q{7uN=thIsFEBxgIrBLV9&KmZU}$|MXtb z9DRU6cS_wFTQc*W80arT|5GeruvhC^uk2Kks?Wmt(YanuQ5c+UpG&^>BOMWBocgJn}&2>D@=h{Zps~7_J^fCIM$XDW-wBex9YiYp> z-m?14t!al&?x+>3ogjRLPseXzt9MO*R9Y}TcmP`Y{jCW#m^&x$3?*Cz%`sLRH_Obg zFV9LVIo1s&&e!e(eNQd}3yQTfE&odd8Qath*yh;MwTe)7HcAUoX$?IU{d!D*?%ly` z*U0UstFnf$g-<<>+tA-UGy>e2kQ;68KM_74990xz8Y{t*RRIuAsHQRYWGVC>28PYQU!@AE1{e&;Rz*2`xCu|+s6Tk;%b8e~9J{1>hG zdmsGLz%H`0;Cb|lMvhu&y8ndfT1-$FTu8IvKPkq8i`Wh2CvWUs9vvHdL}2P}OM}fU z&jAfBrW(61(qb-}Sx$0{*~`KRwq2IGjolsd^I1$mSV={neIu6*s;x z18^ir=pds&yOfdzM;BQSA3_T#X^~Sfc*7P`d)yK2h$ZWPgo5{Oq4|<3F()w+495(z zt?e)}lr#hL9NuH%8DWkua#|EN1=`Qcfu2tf1L+RXeUJL9;Ay0Fw$^gTHckmXp+x2j z#)iqAy5lrXBa9~)>^4EBl)ukLvo~k~29-C{0AQF@J}b4v!{57e*+?XNL_~xc?a9Rz zDFp>UWyTk_>s&vfaW;@dMWYwyFX}`a8m4GP3K$o*DokBLE282E48Z!3 zi|s!E@|^gHJ8X!gt=ikTIH;`}hNcHOY8_#jJN@h#1T9GK9|Cjj!!)D9V8^lO*nMyACPwZ2ir zuj_{iHVpP1H>hiEVZlvCVA~dBFQ?aUhW0dmNQLRb_#?txmBFSlpQ^SobpK(2W^9-H zQ(VTibeupWk(ii>)dmt(Dv)-w>6Arr>geh!f)L&SbX`W1?Mthx&kYS$CFnY ztlpX`K?-i<->19V+CG~P8+Xf=gW?D>Sv4HpJdQi?TynRsyJ_^@#=ccja*Yfe9;d{Cevq!3={w_&+{(S|bOfiPreeK*Y zf9R}q(&3ubxxF_uP6MnQZm3eDkI`3drBwh?N1PDlVc4sSzNLT*P1$HQ9Dp*AIEuPX z#xEA-C3mcLe_p6O$M1ZiI8Wt247ZOU*U_KU~xI8;d zlk~s-u3rvF9F;W`BzYZIKM55m)u;euT6c$Gx**C3e~aEgP1|q(w{6PBdSI6);F;hJ zA>zNnmO-^PGY#Drm0$M3n50l{=cgC1D9h5fDqndHbk)^#?>?(QRH{M(WVD=URk6@O zNusoT0$wM#CI;KUcsbopj?AJs{$Jl4j_P?QWbG0}uZySE1rjm2o~rb^zYuMQPC2GF zF!ap-ZB!y%91LErr9Z`< zX%8T7&xd`9{Aa^~)BktJ8M7g@Uh0=>AJYzFrP$@L11R~U!s(Vyw&YJWRSw(-1V5GZ zAlRy#kSnJv-d~=$b@V^!l!2`Ep4Q?cclDnk5AKl=<6`69h*hEbK30uXwtA9s8)P8v zzxE*7%IR*oNP2I4xI@uy*l`7iHrLFQrl^W*VPrKRyAw{EmNILf_P4)u(j8CBNtcBwT`# z`=!)o?V#p=mC>|fZ17S# z`x@iPB-&MA+B^V7c0l#(V?e+$Ia(}#Z@CwgCNiK5(H8&@#SWALQGMDYFJ6E=Sne-$A&r`nsqO0-^usr5z8jl^mw?esS)f;K z5YQ0u`dyv^L9&*PQ5V1)KOYWD4x`aBbS#HP&j8|)d#I_c?FY%f`aH3vu7cfZfU zRUrN6nQxceiE#f{5Tp7WisT$J73J=P^79T{ktWwx*@~;~e}AmSLu4=I=?O&wW}Rx{ zP}aWTP<%*ue@*|f(sbD6tX2k-9@vOeqY_&7HFU^!DJoj<{MXF{9cBkW7QZ&vDrsDv z^7E%*8%znU4fO`i7*97G0o0|EC3=)v*I+**iunc-h(ic8lq}w8q|fqfXsA>JV7KgjC;s>9~3=QTW zE|8snqdeKPJ|MQ2P|ARVC92OA)yr!($PS@`t-4Y1;` zDqG1H%5QF_$r$VgbO`E)Su09KSvf+l)s#|!Jv%jZ^22tms|eVqHYO^exjQkPZ{lZr z8jbWJkF)s!XSFFe1Te%BBEg56IMH3s#qx_rb9Ram-IR z8S)||%J?EOFAy1VcD`+I)R|MmR-ujhZg?z)NVx<1$Y^B(7UoX2sTWaQ-1 zMcWPlH~K?t)F4{uzG;g`O7AXJjVh_am0O&LE&Ti_b<*D3z)lSxk*RXD+UBs{W}3IP zpS9}o@lFWx)*vxW{pT1AxJ7uS#y~^ay8P$qR8yQ+Dx0ICaq(n;UEO zFmS%kRq_Zd0R5nRkOKv<`SN82w%lo&^*69#j z(l-%F?df=xdj+%hSdo_q=BSKj3KgYbZO!@M!k>leRc-@c?vkiR> z+mdIUX$6i)7EX%eKv>@X269rgSHldY;6?U)*CzBq{L`)HF7K6BL; zK9F?UHTnOZ?HJ#;hITCGFs%;`-P#Q=PD>&tDfBIhyBRIsupEG`m}*9#X#Q2CiZW zu-bd&$zLJ@5_$ytPJId zXr!lJi3(5{J}^}@e}Z9ywAfPSZp2mTeC#ey#ZNa1*MfnXAEpgrLE*fA2#Wj9KSKka zUqN0w@onSW#Y5O!#X}Dbeq`1TL)wVTp_Uy}GX+8%6P`;2!0E=Ds9O9$SOR}&26POX z&@FB-=pqEc-^&`F7)@Qa9WoM6>8w2;EVlJcAvN{u8YA6;$C^|rs#DX6kGi~jHEVnH zusRk;$5$7Bw7Svb_X_7qqkH3HOS{qQmh7Wc%|3v0Nk5rpASC0nSTK)YN8+^VaS6*Z zhm(%E>UfWOI&}IVHNsIlea;(KO7gitt#7S8e`)eTd?%~PH~XaE)S=1OX4(wj1N-&k zpLB1T=Z(%3p7zf_WzV9hqD|;Mz;E3fa36F1U%MwSf!-0zB!{CN#?<$y@P!o!KgeR9 z^Ors$Empx#&q)h?`!S^7M7fNBy1+T*-g=GW@#<8d*M`5jH^&$J^=<-r%F|CdsB?y# zoLqnoN(w4TI@FzPLpgu_h||=a*&1@hY$d8kR~622@4M1Ghnc{Zm1!nH$wV0`{qM^V zwqSFE?TW=m8uB}@{UcaQM zkDCqaQgA%`Yg}r*pX_yKQF=TQTFM1|l-RKv3WJo1kvw}#y}M2mi}Ix*Zl1u&*D&Li z!!)`rxyLJ!lo!YAD??=6f5HufS0K(#MF3FQk>~t%sw9Ev-@hq$JZ|x6tvEgzJKB3jLV@M05Ld?TEYSbj(bJmgqkPCGRxl`)$`GooL$MKu za$(hxu>`NhcqZp0hdwlK) z7x$rEYdu2AymHJeSIRTIB#n<0B-SP6udZqwEuB5|5VUyz3hC-0NphYIb~ItB@b~z3 z=pk9?=7?yj(W`m9m>2vQTSd5tZwm5#54K|K#bu7UHKi_X;xuz~e*T=X=7Yb4jWWX2&Ys>Bm8TrXS!{Zhu&$3J!TBR6k@xi0 zVMhjkJMwf0_v7>ks)IQX7qtFfl_CaxbPh#lI1gi$!ouCI#OTSszF@H%CCNFcc2K;u z4;{;dvw}})_ZnI~=s}%?c@2deWokUJE8988^o+|$^`Q3jxLww&@fSthvAj`bqm%9Rw}aWBZLuiYe4tyb(5M6=Y3tcS$OXOUS=G96&9DS> zoY*nZvm7Ry^)Sa>0Wu-MjIpTqwh zFSXW6F|U8yH=yB^J%LV0wUj=6<+&-tSp#F6h_qFH*6+}V`;~&@GuEx_z7#pPqXS7F zE~ksj+}@E481_hfY6;xoTUn+NuuGUQLow+)c)l&s%akp8?XP=5eP}ZI=KwHTeDy)? zG&te_?_+N-U<@25xIgMHdh3@uFAHV^tY+4~M?j+TE#KS#!Wme`Fx`GY=%bAFhfgN; zHU{(hTfue0X!X9P9txys1X38`6_a~O5Dt)=BpHFhgw^7Vq;gi)4}(`U;+dnj-l1Yni)u8DalLos-+9fX+`aS|3n5=NJ+kT=V4( z-@AdIug>1tm`=+o27(8OtZR8NYWeq%rKF@Fe$8<0lTq6eAXwvrI%W8+S*D+QgFh7? zf<{*=TPH>#tV)8sh>3;ey#9wn2O8EbDyhP4P)YNFDE7PMMd0g^h&avrx12Dc*??HK zBTHA}yXB0P3$VM88C>I+FCS-C59Aw;bA92fgAm97_~kP;c8{xKMKLuk%^;EChd2)< zkuBJVfu!(~78ixb)`~uKO~$Oubd!3w#a}g`#DnWIv8EG`4ob_ad<(GPsAJh1AihE@ z^i07E(qCR8ACxbH$m96&<4Dcf1FGKJyI)}RM;d=FEhbH|-1Is})iLT9+2dC3P_b-) zQJC%^_6FgWW?{~K1P{P2_fne#!2|!A_IJ>8&~Q`4QfyyLh9%C|}w z?#E!OTq4hA+Jox9Mr|i=9rk6Q^FZgxdQ0qT?2zxM61Mp1Plv9=kkHMD%flzKJX@R#5Tb?y&1gX zdqA*sn^RX^y%GHVT(+i?5ao=SnOO_!w!F*cy}6H3Js3G}_hB#g5AF$o!fb=5RCFAvqC-qJQfX!`}Ja}EH9EZx?;R`KgW z^kNvb5?f{r^ezwp@=*Co`*q^XQJ@_S0TwX^$>#{vin*blFb1qIzrb@NuQe@)!7r*^SzbVh;JX8ES`29NDA-8L(pPFU;M?X>DzN?&) zTrGJ-?p_i-70YedC6Z(@*`M?GKCWF@v(3(ZEg4#nz{I~;ciD_^BR1}^cigRuuHOjt zq}lbP_eh?~_Pdzv>WKHbdi&wD3%NN5sSN%AQWK@!KA5VV;^PYeQO+{3X>zRw#Z@vi zq@n18LB*4nGV9?hT$LMlPjaXo^)Ls;QnMu=Cnxc{W*J-C^XlsAydB_yiv~8(RP5M) z;2C2WTIjBKl*bVuWRPNlV1*27YBO?|J zBF+Jpo{*e;IIPJvXbJA}YtXd4@qz+0!q(9CtmQiO9{s@}kHBG|9g4>hs36-w*s=E; z(0h0;`Y>R4^r|r|^0}2a0?kFl#CD%XYfAy=44mV5o}c6#0WtyZ5Qs5H5m^AlT70No zN8B{Ss z_nT*#LoXz-2nKmd7APMTk0rc$@pD>+o>OkW!l~qc6|8TZ` zfjY|~KFjaLle@s|L^XR~Vw$+1)w%wQ)ZW-?Kr{lHO+r#qgSithjN0Zbd$LbcPd^J6 zw7DBU3Z!8i@#qD!T`kDBuK|3O6y<8V!uzDQ1~l*nQKUzg^IBS3@M4malk56H=x0I* z16p$nhrE=I{u8lkP2Vp8v2sg1$D52~4}%Kn1q+Fl>GCs)-*rCBE`?zOzU05^BPSrh zf-t>?8uKzGhQ`pmU$;G223`95tL$q3ThZ>QNhyJj zU5Dm}(Iq`fnJ)&3CdUaL-=$B>$O!ns#m(Jdl!xp_%?o?DFNeH*8Q9-*{Di?d@7G`n z78%(L8=~9CayZ{O`((^^ZoC_@{-&(wzw`YJCkupGeQC0tXT81-E)wCiKIF8j{aG~h zD%xh++rE%2G|zp;vxV-B#|jNl=S7hkL#b0EHjSw$(qsHz8B6mWT#gzGLi}uO@rOU6 zFk{qio3^?Upw?&A!ZK533z=`^`W{&76O;P$%-rRB(WwNT51SuHVub2FEB#e*(*ai? z0A4;X#Pu3venGHnfW-R}+sDS;4owF)M2>|6d}ms<>hAQn6omT#j3IE! zK27j-j{Q{oNs9yS68~3$WGwLSAR{A_TENG~I_kCATmbJW98olUW|@FxFOVF=r{t>6t*6i6o^8TnJ@1y1`*Q;WW!RPhw~`D&(YG7YoTgi90B+Hd%N;2Zcy#} zg-EdI4?KM_Bzor&VkoZwg3Jd>B(9RN<2t~fg?257Sa^=dhBQ?v#FLr?=i z^5bZLf8uBC%LWkp>brFbtBa?Y%kL^-;M&!rHNhPX0{Y#obvci=L=r!XI*^NJ+;4_=k7r1Q=cv13ljy2 zruLc&AV?zX9WxxVqOEhMprf1 zx;R|x0#GYf_<2JD?(#)!aI_VHpHcvP4rk(Sa-m1RMG;WfRMBzfEG9O2=OyXitN%O{8%<$ z`W%c8AUgB-{P{B_RN$=2m+%Hk>te?}BJTqbSX^-5nHWQgwHxH=-cQqs&?=B6Bo(X zj+z_eQ!UUPBA4C?vO0aIRq$QOAm#B$`}yY+xoPecH>0=tj$Yk`(EZ1J`c}GEb20*{?;9K$$sM;p&3VL57}?cMF#TD}DMRq=iZ@d03Qs z{e%VC7GAiuc71L5gMIADY}n}pY8BKbP%23clhsVqmH!;p6@5tWMG3yH{0p%ssgs?Y zu}hCNCDl)3q!V6_2kbJ6{gMXh(E&|F)@?Lj$YnD9iCUSJ#V8-H&*EOiP?m3q=O@ea zE=F}E-$_EEBZUr+-f!{h-4Spvpmn{e=ke=o`IZTmN5_ecmf|1Yot}&7mBw_@tbZ)G z7$aX|t6{4RKW~4lm7549J})GRq?Z!j+1k-(^R zW{@7K*6WAvvarN07!WdA{o~d}+dCxSSP0;XY!fGljX|_g)HVeXi-jPyAZ(ZFh34u$ z9Y{qEtn`k=Q51D&S!s0%)*A+xxh8U^=?x6V3P19izPZ^TVs%?%&RDDHj!=%1=`v04 z+F4rm$8Do(W8sb0@w@nnjRhp=g?<)`{*g}~o7#a`9&>zFyhXy|Ko3+F_@yo(R=OKq^71)N4$po8X|UtM)zMv(DMw9 zZ6qEoL_-{4-dhxv z$s}8+4UUp!7-yF}=Uy+e7=LC&*F#X>WTZ6UY(_Rb&ZK8jAx~eTe+X~*v9>xz zPk5->sHf_&oX-cW^ycl&-fx$ixpf`Bmaf^y-?I|*4h6X6&jr$o@%_Mgv39!MGrdoj zc;E>ZPft(X&x$!t?*d%!xmXU@BxXInfXM_|W`W*9O8BZe~u`;bfp^=VUH#e~sd&G#jxDHN%_W6=Kr`DBb))Kw!T#Kg{y_{$hzE4oQW@yC(y+b%^%$cBDDslFS_1nm+&92VEeYY29{+~-aEVqU{VvdR3-ttc`HmZ~ zbdu_&;KqK`1UK37tcPD}Fhu;0c{$nsdOY78agG!*d_VRH6XT?D#a=PNkTv-)mYlt{ zWTIv_&Axo}%Au`9)*({g4d`F|8Oh(L;&gsBID|Q4u6tXV zM(?VPVL$O$j53y)G24lx=7g(23+a3?J!yga`x7Tf(ug*f{#ZJu6l&dfYKG~R;k)$< zRpy2{4s&wvnG~`9RV_Fe8H}^}aJFm(rt6ZyMV89~WUuP&?mL*W$J$dIJ)*~4cOy`# zTJeQcpHKKL0~LAD%E@ELGv z5g^OgS4%jHUxal_h7n&*JPz2~Z*Pv3JpFj*2H^+)8a=0wqp5LOIbqxc{XE|gJ*z$K z9jlQdQ+_hcVDu1vycd!&W3j+zb4ggBW2gxN3-eS08^dDhSQC6F0{qVzt#VXyi0}5- zBWHB)^OQ;3&`8T~|{=BZr$a_tPuxBGdL>%*7` zJ@>jTv85w=t8yr)OgUIQ!Y68ZoI$&Ug+z6KL6EC-K@PNOqr0?lS*8A-!}j7qZY6oGF4npLhzmJnWWjhEpVwqSCG4+D2GsDDd17ns|K)w0~BX|)6><}a|Vw1azgvE&9c$b<^;Xjs*b zVaW1;W4{H;fVd^Lds_o1zDfhlktsp?oNM0P?tP5eX4meahXE04K#D4;`T`y!tU|o< z@xz;cfOjcs*bgyJ3a6{O6H?d&zf%@*)=NPxm%ff)t3eKCS<7x16z1L>N8zZ}=0>oQIb%A+U!b1Y}h_<+$JeW#<{Z~D`l z3uY%FTt|#4)DF~$9wsh$v26lEBM0y=Sg;)$f=&z+2KD|mbB-NVUS5DIc@HiGaTU2N z8!1Ta+5=LHh|~}+K2x`noZCho38;-O7>PADHX?BW$`=6DTShHdAnrV;Q8NimhAph= zfIUJ#+7JYUtYAp5p9GpqGh+ z9B6dO`JgQru#9dPCQ3g)2}AK2L=sfu?t)xl&%x!4c6Ci84P{w?W}#CTvB3cD-l%2R zt40;{C^0u`?RfyEhe5zL0__ScZFk{>Jc*lc_DQH+8VvL!g`WZgN)c1*XJ^n)UhKJSRs=i0=nriNN~(;X(4g_34k!% z$tAe=*?^%Sbai-ryJT-`rereidANXuM*hRLvq=%{L&8Yp0vI~Nr4X!#tolG?;dz2@ z5b#B5n0DyJqul0)LE|DaB2@ITB~qkh=pmsX*erry%LEt@@j~O;j$_Np|COQUww_fn z7dQ{uHsgg0p}_N#VGx-~&*PEjV=?bhLbbsq(J9;iOPz;X@r*}Ibt zXN7*zn+VZUbl!#muxA~Xh!C-a!cU<$XaOOSZoCZ@qnMIgU-zhgTIN?q- zbM81bJQWNiIp<{B@`TmJjWLd-O zD1H%6_PJM=bDI>NH5>ycF@Muv5 zUAjiWGoVCbP>DLy32GV$Z3l|OsjZ&m+wp;}{Rqb6XX1BW)I$bipc8Ow0R(4K6!kjW z947Umtk{od*nRrWveb`ZX9ypI`0D*uRgpj$e1K$IK!jOF&;#7z7l<(p?6w*(IO(4h zq<3Gu3^)%e1K0@Cwk=6Pr5wB>09p>nL{3?8V5ES!Gaq?~d`aj&!%9Q>D^gJM%Fpch z0vicfVffWCmwh%sp7aS!It`-iu8Zz0)*>|%aQ;cXk?Y`J@JRUPAGmtTVR{yPxq=SI z{q10}qcKytHJt`+u8H6_A{$BM)&cwVV%gwsW}6`pd|JXipa>fnB7UMKUz0U~%xX0M zGF5qjCpUxnkJg*5l+I(wIo^+oHaT14s1cKJzjgJWXrP@60zAx6jwZQvT&F8$OU*(> zLEz%zW|X8-H{J*@|MlYCA&MFu?>0Tmx#RY?p(seosQf+-i{t719fRh8^a1tut!<@Z z)9+z5v|C0@2yz_z)T4Akfr+HjnJy|C_uSq+ZLcNQG%MTXpUsHm3f>K1qSM&ijH`zj zhX0j4m?_X&Cl8)KY2f0LbGd(Z)*QqN8s!69{n0?~|6)KaW|h?8 z@{v+F4JOIiK7rhvCMe{zr5b?jj|<9Xr$JPPS~Vg?A5uPTxC7O{1aJ}|`^j4?xu9@R zp^JYi8#a9HVbt(CdH)ZC_DgAui*K_?6xBN}IehrfI;(~(dG?|EF&d<5|GeR`~LvkQG~DZ}5`e;m8tuTZu|6)aHXK}9KW7&m=pjv?QbJRJ^!Xv7u*;#_b@ zh$ILz!RzJQw{JsB`~%PO!P-&s?%lgzc0t$|?p5Q`4ShLEZ9GLD4ZoFnxS) zpt+!iYaDD3HPyCe|tJ!4<&yeS%!6$tSR1yZtN&CO5(SgD2kn=$y z@UyP+y57Q)p719l3E)<6^p{I0#N(`KV5M_ksi1o6aBuZoGGU0Ih43x*rEb0CoNi~H z8?K5{B-@+TO%J+gF0mcj7QkLKWP682d??%9^YKaP5tjA*(nV!9Oi74_gWdlGFSgnT zNLPGh4}jmdS_t?x|6UyY00*Dm2HbbSJT%8{LIL7R>H!7GRs#@XK{svzK~Oy&Kg_Qk zX$=Jkcd+4skap4lAX8Q$p*JA4yHGN_!~;$iDw$eT%W8J5WqD2D6$|zU@;Y$*{G&;c z3iE*Y=P;hnRVDK6Qm~!m1sBfOPap=B*^)2JEUE~?YGYSp;J4R`2k$$iP+-En_a{0V z>-n7&GO>7%-*^vOegap-ky`6@9M3CQv&2;UQWHM;}2!u(FoIVd6KYbnP?Z;uBQFp z)6TkXBU~AdM}0(71Q~KUFxYl>CM2wE-yjVqAb@Xi2~RFUY?}vuPKd#W#GzQ$UFycX za2lW@TQ;~Kqf;Kh!}c-ZtkP-rYuB%r0R3GZ1|IcHL><{^E^0jJ1TL`n?#dkj%kQ6H zZ=xYG-L2YR-|s20V@2^WJcE0qyK1ivD!^z{NbKFR%0SM4h)~S!xkQMb2gTYZXwa$Q zQ5IPPGXz2bYSeNb%7qB)*K+7oMn_kh%4-CF!wu#=UG(9@6}XcyQwT9&vHkoAhbK%B zR6|6Zb|f%1j&kuu`q>4K1vh*6mAUBTr%x|s*$l~gKl8YiA0_7#DBw+==^dJIqU<0O zguni}*|-tmrec^~1)L#%JG$t3_Sl5n#Ed6+%px(i5(PcIN2hC_Mg<%~&Oh1$z>3)u z6-Z0{er)?&j1`8bPOB-Y?3$obuQmDWEQ@^>%-W;#$@O*Kcn8e0KPO6=;&~P)x!4M3OmBST~2hZ$Dqye0lFcQzC`-K z;0E1SuKVV%GhJ=q{h;Hu>i{dT5kiV$up23X8hdUAW5vMisD}>t_`v`Pxb=RwW{Yd2njI1KgU}*fZ9tILV$J z(VII5wX*}%0sbPO>J^s{RTmQHTDRnwKKF=h_Myr)z^O{hhhQxyT_ogpx8DDeRX{-B=f2rY* zv2y)zEKh2k3dng=$6JJFI3Pl1fTLKz71;!%Dt3I6u5}GASYzUH_7!%|jHA#izGEgR zz7ou5k{V;WhH88erWrr;xw%>F?f@9RBV!HXOl~OZ!|cfGU6PLyEosE`9aJ0*V7}YN zFJCOE@Qtd4yVn4Jx+m8_KTwOy4Fs#)v>{rd}T`eA#9jf$P%7>m9)9+Id{{Rv0?3Vu@gAK+8 z890%XySbWm>9*hBY0Y`j6Dh?m)T`A>6HQULJLH&!rDu^XAy%F#L;6T2bu&5gZ9abR zHS?=V)t{+x<p1?7E(FoS3FyI#>mfK9>`?qF=daZP>@-* zb<{L1oS)}}U^=nB%f_v0##dkKo8p*gTsxuDNyCMaU{VKgxhx^Vpbrc$Z4+RdNo0Ioz{S9nru60K`tElK{vl`yE{NN-TN{f+Balg>CJ7F4la16u;d}myeNc%lm2@gbahDe z4%zb8A^s<|Z9}8YZ@?Tg-hvj+%u`MfyFq zezWFx5z;lM(>&Z?t40U?v+X)e5~x98!+pDd@Fy!2p>A`dhK|U;eeu(opzOPK1R(4} z{%pyamZzB79{0$L2-KS1c9ha%TDO;-lRO_9VU{`eCaB7^?7^HCR*eRMtg&&j2uJAAN!dEf$u$gPdpwxm(t)u)WC1ozV$>FY6VaaoR6U zU7lpqh^P6l8b_YCJTvwz+U;*npmK|7EHK*>)OZq1Ad>kG@yiFp)MDQdkVP&sh|BTl%6TWb!jmRu}^Fn)m_ zM~f^D)>iOZ+&&r4jh=N}+CK6Q-=p5S;1Zv5Rh#gG(oLLms2|P2!$ji=Xok|Elq{pK ze;R7UDl0j!UXdZd1WCgn2mC%{D;`Z6-AYlRtD(_1Z4iK8)GRM;flHd@5w4_aIxBUR z{NBAQix?d2o3?YB`})(_^BEG!SvrsNm0shXJ~v0~S+*4-V?5w^p9Vt}<=@2+Cd((f zR_e3nlvPgi#6?XrC5GX=+okG;#i8ipVF@d{y$7S;`s}vP%U&PPi+Oir{W$&BN*{YJw|!EaFUm_a<95yFBb)PnK>siQ4C>MV!z$r z6=ylC6GQ1-)VTWAS1#xyeL(A}-}Q=M;s{g7OgIcD{RUajG&b)2qTbt9K60XIU1OQa zI48dNxVO##P-OnBoj~m}LOnn_lhUzDd&k1R zFrV0dIcB=0y7tH)F?0HGYk4+ysj4PM#TYJ%-{HaRdr+s6=JI`uyeRa>Dyrw*mwT#B z7iY74gBb9xh>lAq1# zt)REJx2*x{;!VJO>zTCW3L^}gF+0R4{Pe_mg(0}~w^3(ZD9aad^e$9o%{BEG434x3 zotS*nS4|bSN1ZKH&7&a@W6br?=SgwV8m+>l3vZS1__x;?SD6$PTEyRk!AcEjk({>egIttv{A*V)Y9Lbg5lHabaLQT3;(>vtKny=_(W zh}PL#+Sq0LO$iUwcg}f{GFY*DD}o}dHA-4}PTV{(_8*~aJ0qA=hQ4_tXJllQmR<%1 zEr2&7%FX?u)cpKcp)f5rB8Zyk}0ka7~c^X!T<6`^wI3Ac)@V>LW;t2;_8<}f|Y!XX%5k0 zvgP+C^xY@8AMLGquq>Z##kU%I%bNK!&Z>DxWOR#md+Wn?Gya1UlOeBT7DJzY)CNQ! zS>_?{uJR}CrU3taywI&BDJR!xqrCtp#Z-3|Lo|>CLs$vFUG&;>N0A_e>_IcAkT1;f zjtan-0}wZ2=j}sHhaktDsIAzHWwE;{23}078fL9oElX{&A!)j@2P*Hc$`;a zxWzMjbsP6mHK}enLA7R0NVssi+c^>qsj*1}$$k9zQDAT$0yDO=XNSkbbS;-HK&mY( z!e^Zd)!p1z>1QwU<{A@B;cj;2Tb8)rRwJqQ{!$1nW&S)OC7+P!4YHt7^X6}(7(iH+=6P!gpqrH)mp&W0IV&Y20e-zZMwdFvjztYD76Ii z&m}^V_#G~>Z3^+Ufu{t_d7PsDW@v8W4CNPtE=WkM5c~q9GnBAHsgSpW0m>*qEcNZ5 zLutAwG-2oMP=(|W1f@1*1O9X(uR&bSWV8jzKBx);TxQYyFHN1iZ4PRMgpTWT#8f_~ z$sTbJj?%E+87`2i49{0RT?P4@P;?VOi|UquHuy-BAK$6f)YK%jP`*qFWio_K zfR=~1sYuDLAI{;a^Nh;bgX)fj1}$eU{%T-QFtU%vW7n*(6Om!7&aFP|D70m>RQ$t2!swU~ z%YN??gUZRwd+uG%Et7UKX;uqhhvr|h4-L^?ym`~OwK}s2t;BnatQbJA0d-GeZ-5`3s2 zKr#@gnx(U|9KAml_ngbraToNDf7dpyUPy$a33Y4(%i2d^`ZK4g`d}Go>_+3CL(PFv ztsztZZI*bOy1Tl5L0*H1e;9BbWw$JwD-55ogLYvyHMkU*uW)Gnsj49?ZV}!a+LLX< zyZZOf{d{ynK@S`+5P?!Cb?IVa$sCx=*i+#oeR%dnze$Ah!uSfICvLT!NP4U4ohNJ6 zGvd#>7XBO_jKshrGtuKPx0UD?Te;{cv3%mw{<)eLHN*vBc8yc4 zJc+R}ezK~(_QLh+I!t3XM#%bI=}Ep!q&5tW?8EnP~o3>&Sj2?+Z)6 zmJNS(sld-(jyq4%_U$gTdMweZ?oXKR<&8>YR5pYC9v_fjx43=oJ1e04a zOM}LyrsqEtZrlL%j-rwh8DA?DB;t!Y+S@75-#ZKqZv-t31i!-x`l+?m7&w^78WOQp z+f2ZQ09t#cH5PWluGj`AgQKJ4iVze>v%&KfX?|d{iVGVACS{wz3wWWYgDMm>igVfPTxq^)I|{=d@I zm-tJ}!A3K*_L!#j2Oj_XWwr4@QjNXE_A@8m;${yZJoVWY{Q`U71hx$II=eP$3LAiV zq4u^jnjGaN*?RVTJrpo7^lr1fkk1|E)7=&DZ5Ha9@F*_?leYG=f+u1Ir?SU6)of2- zOllLeUFu6r2Y-{RU{2}2W7m`0xlwYA%k}NsFToqc`0xDpzQ5%UIz6G=wC^z?WiE_i zzuQO^uoTbys9cOn@8n|Qu14!9h7XR3j&EX-wu&DqlGIIop6@i8 zSAVru^}#J~8?pL=>9xO%HUFcB6e+#GLTghKICg`5`3PPZd~Gn*{ysyvzSaW{#rgcoLf&E^emAzX{Des0G_)u4JHdJ$tTq!BB0qa$;S>Wr zzqGwu4mEhh-_8&?Xdtz+Vh^?+H30ozk&(dz+7AX{zz`1w9TX03*eFPV`(3;Z8t z!djuDYrw@HDD(unJE$UTr9xA;pliS&B5lCY4<#PdP6-$`;IV`3XAqu?=*9@DhW;a` zblsP5ef4=@uZ?#VhaGtc*fuQ8%#Xnuad>$Xf!pYA&VMg)hZh}3BCXseu2C?=Gy;Fi z9nhEss5d}23Rzj%A)w?iBYHLv1oR+8)HVBkFJkP{+12`gJQ<^TdBVD%=@a4>OSZ! zoktM#|Cvc=oW(R)V*WQ4orYeQ2~UnNPGz(4l9 z={GinuCI3MGUV+bzjiQUK>TV@U4ZpsdE*>2D=WgvP>U&G@H9Z;00iqzcUht7;MxmEahbVok%^+$_`}f11j^KbVE&Kd$ z?LTcOkSxID8}YUO^_Y6}yAR8snfCkt36FmZ1BGNV+8A#pRD4}1`unwk$A>sV@QY(? zLbN0pcJOi%Js#Y3Vskfer}B@T7y5PCj#)7AMPFRi&+COq`aP)Xyur~PcyP z6%7q(vUs4uzz0$T;|E#1~&}dZ8kFO7#Qi6GY3C55eZ(e3SO_Z-I?U`MPp(w zz2$%U;2uXl##ZCJrJ{m&39Qy(1kvvY7pg*43Dg4RPuf!cJj3wMGw33ZwWlyQa8MHE z0uBota$chN<|05cufZ$yLM2lttEjn%+v0kbQ+IrKxmnxH!0P0M1r6c;89IW;Z0F8F z<461srHjj>a?!jAoKvgwt}AbyI9)5sPFDQTzG>{%yh;U%7WBCZ!Q>39gMSK)xyqkB z=$@G)W5^w!oc!k*^c6p~uN%8oIH>i9^f^Knw~cG-0FyiTv|a< z@i;nAz}zOF*=ieJ@6xolvS~YikSd zf*=;7t+w*Qy1F`W5TeQIz7FjwkeC@M6gD`drYHGiCK6gHwBL#A+7oa2w>eBMOHU-V zQvMzSx@c@Qx=*MJ0m#FepiaI430@P_Q&ANcWOUEgzm5qy0~K;(>ZaFc5L|!x%S(80 zqy8djE}yp8L3sf-?kuPdb1y=3!yK5!$k;|OP$TdOIEODKN$mPTzpe0wRaYl^I7`PM z`>z|eUW7M#2O?pVd9;DHe-dfWNKu*@B>L+x9HFP6zXp^fpFp4^7^tN&4W`G)p8qFA zk7po!9zx$E8Xl4t*~2`cQw7Kg(Feg|%G?@_32LSTJQ~FQ96_aM=ukZY3Vy4!q*KS= zw^Bxi!H{Tgxwl<_G3t(MrHG9FYjQue$38s;kr4yK7JO{#3Wmdnu0V5=SU}_X0^?tH zp~L`t&&$n;LBrT%4Qt1(Z^h88{iBAcNt-=+SwUf>luw_q5`T!_iPRgnucbH~ZYdNv z>Dv-U5EscqSsDBO;hoE6@>(7^bnPc=+Dt40G<#nQvpN!Wj4%~Whi6WB?oqZ5H~!44 z%Wqs7a~HRkY+2ZgjF?#w9vi!!8CB*CGPP%MY|kD%cyRZ_qa$@tkiR{!3=vVKtRjf! zDpU+@!%65x)c_1gat3|gbFd&vQ_C}wzfHC!)`ctx>n>I<1?;c8zgIll*Wdq~VR!Os zX90RS0Ep^9TqhGR6_`!PRUCt=>i8MjK!B(N9^CV|ugf`1ayh`io1TkZS#zq|)(%bp z`N&m=Rv2g9SJ&Q;05zj2xsyctv;qI|%{bmq6akX;_c?w^8wB%WFqr9(o7Jf&5HjmH z|NYJU{QPtu1PSc}1Cew6McvuwWj>?!piFOokNNT*bpJs*e*6kNn49kc14*(T2p2*x zOjNt}*?K#~AO zb;&c!Q5gX z(yO8P3Y%UYY-7k}ynyTRv0o@W1Rw_WehmlxdUq+UjM{reIaO6vfC!?Qre zc;@5ER0kgzK0=Uh^>qtKZ|y&R=)|W|9s$tgGsKr+V23siJh+U^qN1V+r2nk0u8!H& z!C5tdDbfq9Z_tpA@n5*`J|*QWHzeAq(;fO&i)&_`@;s2kkt2*x7woTL6>jS+as^4A z^+9xCAhwQ(++z^WHvtxv2UZYBLW$U?;Zm&)xv?vS6%}I8QiH*M4>2du&bw=@)JTa& zkLZ{5XfQAJbN9BMdqfzF_m&$=y>%*-kw$ugSjD?kex(!RG4c^E^yF9bSWGcB=b)$7-6lm+vWS^!N%hCl^==PWOS=dJ? zq|mM$?W{&15xU?kaLT}6`4{f5x*k>oev-|*vmpmNxNZvD zv%CEGm9Tt&KkA>^6mb3d1{0%0RgL}UJ4zNDwLf2DYVTnP|9qntPNWB;_WMB;g2nOY zYj6GY-nf6h;kkjA{pV|pZzD7$j30S+F7p$}xn*{3pk>f7oH+2`%E}7Sl(?#vjr6Mc zO|jK)PrL9j7@{C_Uoh1a(swclF)@3g*WT|t??J@X4C!8E9Ggr^Tn(C%m6eqs7c!LH z21DI>RCIU)u+?EzJPgMDBw7a;Z`ZpRLhsr&h&NQK_Ig`AUpvfnz0buuj zpBk@Tk41Zxn^;*f{Mv)bpI=xQs3#3??Zs$-F8|g|t%pawYr9}q6VuStO!M;J7>q9| z*&O5|wS`U$#$fmYwExE2SLs4+OCpfa1@*E}Nmm1xqt}RNhFVDDi*>* z5xEgj---qtHDT`kg4k~i&SF}>q{A4DKjZIl)382r1>P3=+VXR>nF60ett>Z8Ttzevh=-0~o_@ZzVtA3BA zX$?%n3w-(?9$hZF{=Pk?Kr!VNQ;HJ1+)E@DfjmGTb`*R%)PZB7wEQY;aA5xw3V5C& zqz>rwLi_FnA|fK%y%1O?rZOmyz{H$HGo;i8P>~6+@BN}$`74zF0^JWyH8{6R%gQ<+ zKtdO2VPVl*>R<-;IU{G3I5C(-Y1V@oX3ey5hyyc?ycU*0D29UER>0$a!E7H#Ix#et zpm0mPxs8HsI33;E`}^NPLpxSzgL9uf^jhUwK~{j?Dq1c9zn4w09!&aDUQhrdPma%E z+;T8KK*<4fRZde=6V8||O_VIr4%!mKpjSlu1^vdw4=K23~GyDA>|DWEZV;^(GxUjp+ SP(TK~ik!59ROS`EhyM?-3MZBT literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png b/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png new file mode 100644 index 0000000000000000000000000000000000000000..481375fcf68b104b7f491de82918659302242f2d GIT binary patch literal 498530 zcmeFZc{rAB+c$b4WvD1blA%Fni6og)sZfSYMF|O&nao2)l&LZ`h)fwXMI~br(O`%) z7^6@!%gpyXs{4Mw?|s(0t@X$HXKmYRd%Eih*L7a!c^v!xoA%?1=HdM-7&sXy6v~Q& z2li@HDD)>O6xvq0rTCZoUkh0A$4;kx22Mw8PdmAoIG9ronK;>ueOqN;rok#&winzXD?;Kw~1@4xywuF@Oq{f}R?l}kka<0TTPO{v$c`tQHAs3fR@{`<=YruyFW-S;0a ztD~e|{vR*9L5P?CYLAd1_l_WhJY-(W3OIqy56%w1#)4 zuP;SLMuyeBXywY4baZqACWAo*gmNC^o zbv|ogV4$S-xcGF(sbrkPo)VbtNQK;_j1!A@%i|{??AQDM{ak>TN&aOd;SwyZR- zjkpjW&u4V}xP;e?Q&LLG+19sdM^ch{V;(#ZB`?>KZ7keu_{5H{Ds+9&t7vhv`g^-+ zuipB-X%|YavN=5)+Rk+3!_RF|Cad z#Pgfk^w4CWqpYm{bCOS4br_Es{@KpXPHEzMbC7I|c;nB{j}<=-2u(YWeA$=j%nv62ivB8eYVwlc>2)mSow9?CrT>5ya?**>bjs7E%vOoRyEzQ z;EZm6%I-@`pE!JFh`D>0F}vG1P`tl=i#faaiM?-bZE-1WGAa0diR4V)DRXnaEn9lS3&ed^&awA>|GvhV?#2$=_VTK#`>D_G)m6TK zzosSY_@1w|k;!@Y?(vQfd}N7_kH5Lqgt|6TIOV+0x^?Tu`x^G7dEyBO7?;YOX~`0e z3|YTx&Edm`W!y%SoQ57*f7VldIb&C~-OZD7?Zyr5P6h9p(j zgJ}+r9z9z8Xu+md7_ zhdTE6zP)Q=VnRhjL(`O@&*brIK+AG}soblokaZH+9}!~5IdQuzKjjM!wwDMukByF2 z#L9axuUjW9YPcyb{$P96%)}1~?>W~9Azg;0OP9J%d}pJae0TqloulKW(ozN02!RXS z^6tE1VuOiw7owxti;IgRYH6scBTk1MEAy6bZEeNoT+YJ6qLZdg8^kWIC(DG=rfb>J z+{||U`gP0JClc73n&~=%kq<@ih!c(%o!=@Yu*W>n9 zs${{zqAqq{&>GQ`XU;I-X1Kb$e?iStoj4pLbKz6L**zK>OmE-5)sC5FV`ipo+_+KB zb(muPDgVOt>#MLX{f&L**(i2DKW&$?YFu*p^5vYzkN5B0>!-c$cIz_Aa9_j5eA|u_ zU7XlpdgeyAV*{8rZ`soQ{(<3v!-wBK%$jo_>L}wuH4KQ21SzR3y7VFj>JF0I=nDP2)%Gh{% z%GtC%^~bk)R%iB)9@?l9?3tsiF^4i^~=WI)BA)xX2u0iZM)UzxN*yt6wSC5 z_V)IDA0KWxckbN1jEo@cweB#*h5G!@ZnbaUR%s~CFEKPUcPQQ)$&vSOHsm2HIHtw}gp+?jqivx)PQxhwq`K)W3UoDLkCzedf_bogHOE z_V?9qUDQriefHr4$6Z-xWe10C?WJBpCeJTF`}B!ZMMZ^f`Enii!Hl9wjaa!Wt2U~X z*VZy%P4(5s)5I$JWaSKnuHQvkZGXw_hYuxDzwb9RUU$1*w!hGQLP$fzo`jmiu={h}{tXvWi!Mc2%^m5>r`sQYT z?El-_&t68w5Neuj8VYlAa$>!a-6Q42UFtr;fUd3-#x0-JBTN|{8@q%}Ds9u6>QLtM z%13~Y;EjZe7i<5(Tq_MEh`x`LgWh{g7y*zMu?KL6H%j}POMll`?4Rrq%9T#JQA)<@Vwi#lqG z_rkQrCT#VF#Qg^Oma8b`05tI-R`2fb-oJlYqDn}`=f}1LSfPNCHhBK$r<>c)u8CFf zy80rBy&DziiBtb->=uRTX<55Y%2Vebmr1|IU zHkZD}WJYP*_TXHz>I9S~%a3`ReO(@klfpDIGQuJ2B!FFvHgRF&{?H!bw<;l=CNHn? zO?{0v9)72x7>|WX;hm>1He^UMd~Acdp&X~+r5UeGOHn#-fKEt1D;O6UZ;)&Hq2Mh0 z(&Ze!F)>`rxn#E1ne{r)Q*{n^Jtyyoy1vz_ag(K$)xj&q044izgDJ&oSI+>DWoBk> zbsIf}c5Bj@bdWYScMBGfsNti%xF1_x295jz0th5Rm9GT83mz(4J3V}XwbKzAtoLkp4Yb|m!+kp(b3aik5UTXqCbfGzkb(w zzn~z-({FD3M~fS))@++b1Ej(?7kkaF0lK~n{P^X|mmH5t8&X`GnxtChzs{=P+D2>f zHs;w?HsO<}PhUQgayb6n$Gn?69r+jL#x!2v*};^Rm4!_Z{%d}unkUzN;>_Ot`_C5l zq|ODo9V%OH^C5?Cjp#AIbvtaz(Q?a+mTVFg73EU&=0ZikUhC^p7eC4N?O|8{yOdP@ zY;GX=r7Jj>2n!1Xd$E_ePgDRXGMKx4UMqPTjKO5!L$2$ufwh3|T|a+@0NkoQq_z2! zPmj+^V26mP=m^2=H8(aB7$z)87x&3Chgoc8vNgbNp_(7!I=s|O@c)YJ^M zRj6_ndQ6JRI)C>Ax_s8r!Q(SGvWyg$Z{PSgCw!fhf17#q;l1qaF#GPRuEDk_KZWyl3DuP z2i|6SMn+O*RDwCEfDX76JULMOD{*tS+O`*mDd=Cha>er9{S}^GUJZqg7FZJHEiLT$ z1f;`bMF!yg&Dx9I`kK;MxD`C<%*@QNBGWmg&(UFP2d|Y}ih59OTQvpU}bHIl5ueH}^o!kSkSsEL#bLUPO`!7pA^Z%9%i);vH+Oar8bOJhoNov~@jg*>e#OzFM^kk(qLd3m zLszEjXNQ7Rq_qys_i}~j{)V)r8!rCgN@H_#bAC}#Q8F%rF^!Kbbl~yz~Xo2b*RX9K(>L~GeOyT7}93v2U=(g0sp2>|NDJdynu{uJNlau;^ zj;IJ|sC!Y?(yZ0m15jNB@|l!y%T$CsW`8}%DJWpW4v(l^BVxcy2?Q%sGY29e?MBu5 zn>ir!naSM8kJ%}ez>>-NKj+89db_(f#>B+1)+)$Z+&;0052#h@>DGmR4Uw3(M`zmi z@bsIcyk9>*Goo3p0w|B%r=r4OZT-{J*bF6(O6hgX&Lcu<>gudOz{>pLS0;Y6sC|8G z)3%yYnRGBbY1^TpOP!r3sg%yOKG8~_{Pt#@R+iCD{~y=m#+W%dg(!i2eU{02_4V~~ zvtniKhL6r&ue}i-?tl00-Bhi_%R1P;QYMy`0$47Iu}KSO+JJ3^OGIg9|1G`utqs{Iwa{tbxg|O?+kUZKz#JL562#zOS7B9-4K>n zY-*crZ*ONX^PU>+QU+q~x|MV$la`j29(3n=Y^+$M*Hq~~meEN8U<2)2bCdVT&T{+~ ztWydWmF$rYs-?Vt|Nhn@7Y!kgxvAW(($Z@}IJe)Z?dhEX0{U|$*f|wr!itlZ(kDG> z3wgFlN`gqlPIU$FNTtW!y(gTs4tpxjqj$(>BqkRpq?78g>Sc!2D$UZ7c)E`QqFn?3bL+~odrR}T+H z)Y$&pX&Zgw=Dj<5WL*YDP{MQvA6qtTpi=7cTun%IgAdQ*EbX7a867^n@{w&vDCoS< z{E&6$;zGc$IG=?p=r!ffpYQo}`qU``B{!f)poKHc(k@*p^jc?Q9BnT&6wYd3fb6Xs zE2hVKM+QDhF6Y=v0ms&M`|m5hsLZAlD404` z57OF8Jk)%4NJ{PjjW}s(83+<_;47Puj_<8ow<-!6#ucW<>J&{ZECRrI4o-ly*FUy3 z_Lq^8XZpTm$r2^H_>qB?o7JLpZr1E8J=c+}7M=8w8=KdUaM0FPqpQ8>aKpcTshmGA zy|6HA>o2|Q`~V$*Mo6eJGmpZu_7=RHRTMLY;0S=7%ZiJ0EagSFWNzHJQUAbjhkvQ% z*|UjQ_l=njz`0NGQRn98*-odPd7rr!oO+Zk+j9}0>8nS-Foo>uicx*%AMgE{sexi{ z)aDlyXl3Y$Cihwy7;yM8bH4G8#8QFAG&lZEgW?OAd4@F(1XoBeQy}CLbVw}Qb&31K zs<0ndv9Zy1wux-z=H^yab7On|a5vor;MsfN&dkaJM#g|}-~hs+=DN(@-rkMN6)E*; zN49+U`0=3Ga!t<@rI3E`D13{GcKI2H zXMijNgM%wk*0eGW7WgX_o%)!;7SgxQvJKnl6#%+&$vV*~E=+C2bGGZMpmpkR+;^;f z>bW`R1(&*>blr?E;3m~TGZ9f@uf)-btzxK#s_gJg8OF~=kByBTasBmj=p9g)P*aBC zV=;h{Kmc~R?t#ybvn%Esb4>P}var|)JS*hklbM{9)QQJt2@t7$1`pui<79IsAmes56riM+(ZFt&F7CbO1I_M=lSu6U%xrIToK=jW< zs85YQuzl}g0iB5p=m8W2T2x6Hcvg+4Dyi?@|Ps1gv& z^Uj@aTzlgWyrj&oUBb=6`dLO@PMz{R zv1Wx>yQbh>GF~(JjnT?AH8pNxiBT;R(OayhW@j_3H-f_2c9iZrc8s$&T0A?yMA@H# z!Fa|>RYOBV(BviB@z(;0?b~%Z9^P(WmYbU^pq~|^?ZFdz{7~KVS>t-|<+>7HV{dj) zd~e?50Ds>gB*cJ^s(VLg0=3S+<$IN;NzH?KrfPqnWk~bPEG#sgi*IeAO6v^TnwnB~ zF2;&}uR7|z+6|_J1oQoyZ#=-5l- z@WwoSv>VQ$&se7Y?Yq3^WX?3F`yVSf^Q@wR8Z0*fy@&l74#rXL`Oh$~Re9-`?I0 zLVKd2+}>duidAniJ^EEujp>#3ha4(2Y4TYCme}69czelw^L6RY;;lRHZ2j$g+_#<{ zUOXVQ&grX1nrH6=qo0H;A>%of6H&h@<)DMpiKcmOo#yOGGmnM2o!FGRrHUCkX{%A# zhljiN=wulk{aL6tIXmLm%CtD!vB=E9K}P|gzgN+iBpD#riAU0^~(TDsf z8kdQpcJ$$CPzpcgi;s;?w9MfaGAo}1n1cR&v9?>$1`mb!t8BNg(TVwp#}c;fayr>3j+-Axy^A!q z^b&E-WqW}}DCcJY!tf;yOS)R1b;` zy&6(iynQU^Bo&xxj#>3eSUEhP-p@cB?7qET3!zfB#cNDbLGkptnd#|g;OKmOd{fiC zanQ`twr)IRBPS=9B+2_yeq@|@*KRY`)<(z32 zdVN!Z28PcCY?#vNZ|j_f+SeaDcI*sG(Cm2sB@h4+2(@)fMv6VJTFj{^7d}MC0!7?}EuhL`IdeJB*xrv=+SQxF#=!g)sqzT@DPS!;36GbVpkErs%dE z=)^ByzpjL6k=)BSEGF>-#rTQyk2NT~3tDy0q12__ojBsn^mWo@G6gl0Jx11<0o_~$ zrkM%A8>m*kWrMOw@Oe~LXgig7j~t&xZz88agntIU*pO%bYJ;1PQ)fBV)bw;bpoBrG zXQ9e0+B%i%j__{*U%I==BZ!=BgSbKNQg>BILz#~c?p$K$1(x4PvTW&Jvwoo)P4=Xz z=|!lZy~pa>+qoaxcIXL3i@TZG+Qto;WvErY6kSSr;x+rIF_;ct6VqHiB)MaUe&OCP zv#%Ck_V@J>xMBJEktlXLG4bZ$&|zy&K5%cts6+2L^)iRUaL>!jN5#j*h6Rf|1o#RYD@ildquJO4+m; zxWk@1TUlML_HgQDU3Ni%bJqNI;XI6`IucUD{)(CC{kyd=&&yYj^=GzzG6k!w{KBHPe#Yi zfujIV{@POFqQJ$XOxIfCp|3iKO3Vquc?l}6@ax-&Hdl^eeFbyvT#cH(S4W4HXb!ZD zYfiR3b><9fsmQ~o93O03M>I(9`H2?lf?P=0U@QWnJd=E2ZGyXnAz;F_+J~Re<=2FG z^ri9&3yM>oiex?OWsMQ;l$`aj?Zu5tE6K`9)!LXQCoB7uF44Uj(mrgnGj;JO=~6*a zB_$;)b)SHJu#5--w`@qDJwMob1+K)I7++oR!@j=0PON4b^fr|+?iHPFV|FkkWt{r1 zjmwtxl(7KN$M)_N2<~We({gUZ=iFH0a{#O>eow$w^IBH)GKrRXUzc95a$hQrttTl& zZ-bI58f%M!BTq?H zch%aju<`kiga9k%Iy`|;yisJFWzHt9Tquq)>|rJ1NuYzshw0v2&10NSyz zFe9+ulHtJ<+u+dye6W45sj17pdv`rqsbm$$ynI_+ew(-OwqC#}PLd3tEoh^3o5SSNq!)mx-tWiOpFbiSmbar*| ziLU*St}9H^3yX7OVLC$~*mO)x`j%sk?Mx1!*pTzywv1`Q%0=(3T3nb^go~?WvNRKT zXKwVBILcqtY1LY$vuDpDQ_}@w@Q52zsn1G=ZWosmgzsZn^-q9zUV`ZIZANa1FT^wd z7DP%^hYaBh)AM~~g77nYoe&+F_HQB~x zDlo}(A01(>+xa^LBjg_QCll5uyw&lWI)MU!vwfc*i^E#X%hRM0_p_cta(cnkuuzXy>nRVS@+{|gFb_wL;WPn`sbU4^;>>24(uJPbgZYh_0t zVAZa)wzeiH8temR-adeTZ1x9$w{PyKNqRz*>Vi^fQ0TB3ceUA@KF%16*`VMI8}zIz z*v}hr=>VI`h&F_B?WBf!Lz)?d)VH~b7GnaRi8BRtT;yop5?pl^b_wHV?n74YJlKNE zpePg6Cua17vTN5a@+?q;X%(2#&wYNh;=+XsK!y91l$2see86O&6|kepEkmWBgM;Ea zGoGgG(AL+GNZLTY)w`v@N=Q3AN0lG}fOGA|Yb7Kk1hf+NW>wptKYtm|ida`r^od6e zerf0Av=`7b7rPB0gZlVWr)SuFtfv=i!hnT{5<~t8)hGAd$8D~zuJ>RyQrh3dtXjSL zB9HeJ)%LUR{jiq+7zjCm^tOyNOrRJl3iM!QkZ|1W3wVMX`1p2nTBMiG>Gr}CBUS~Z ztzeSj0>w5cI{zSI>$u?jRCidTYee0F8|>3J-wbJ+61W4!P%BxL4Lp*D0{w)3&z?QN z?aKfj>hwK^suTO=!FDr^g4iW5eSr=aJd__Es6W=I%D7wka$@jk5r z=h5yX#npo6pgSPS5Kva8NcJ1T3aBD$KCZ6fxvk(O3#E<%rbom))b8hSYAyq%nWFz{ zmmo=V5}E|*<(F5kXTZ%Q9S>CqM{F|<(Z(AuQ+n#2noWJ7x^VHunBdd zb#l&o>-Dx6`}iZJmada_kpzNjYUq*rc>#Dkf@q0Rp#!Z_*WBP+wL*ulsDl^Kl)JHf z=vJ=0jQ*QH5DyqlDlbSf2@Ay zJLT2Y%OJ*b$h%AZ8u*x)(}r$^jTwDHKV9cw|3{Lbds0-S7MBQC;Rncc&u#1*KBa$c z_nFa{jlX^NMee_}%!`)fWKcMX0FSaj+}86024u@ZNJ%|b zAOxpbxARsC*~^e^(6CwmLX#O4t1dEFEQ0A1 zRRRkHnVDrSE-p?3AGA~}8~xzJVn>I9IK@NSc!?0o^^N--4wa{C##0mL9puXlC?Af` zKImO0=H~v`jNVR*JqSP9k$Br3=@lqJFM#z;&YlfImE0g8a3EbDp*g5*OvuEPZ1zZ;ihy$sN725Xf(FPo0i z6=?M5z^D}z6c}=OcAZ~NL@R8OoYQYOvEw=kMUN0Xg2dD9UV9jy1WI&Q^Z4uqox2tp z>5qt`jI3-0)&Q17d4)ft#JLY!Nt~+4Wk_$=y2Cb6V#lwdn-h5i8Zc=j-qT;%{WraU zHjsF#=EhBV4{0KYU?U`8RgZS-V_FA`V4Og zm`}<($$mXJww;*Gpk}XJcodhxo=yIEYjlG~IhgLXS|SCbTy^8FG>UAcjqjH?F*Cd5 zgP;zq@D~6+q>36GJC=Y%%uPv)!xzF9OG%0jPwoXcHbQt8aV;c2)i_iIhDo3*NfW@s zp@pkPfbgZIE0h6-lg>k7x`YDWg}5Qgrzm-A{5AyxVYqVOc4$l3s`cwd-!Mqpbt)zQ zL{q!5I>+Im)jR%Er%!*oeQxs2jt*Y5O;{Lvpsoq&r1}EhCW3>VnLMbbMnfr(Os!$r zz_=~(nrz$``NJj;^YbHOBO!kcDv5imZ@$2P|^ z4Ii&WVT=3@K+*;H#3ARp^)zaVnwr}9j}|7h=)LIWte-%ep9cWrGLFkZ)s#lekga_g zOl)R6r-jtscw`XX#wmsg9=Xp8eh<<@!ge71@j0)JO;Bcn&^q(;^O?E0f>E;KA@`%# zr&W{?XBl|8n-nW%YJ$*!69^{qH&})pJU=^WhTinDre-(lR1ThszxjT}>e)mRc968I zjeh492X|1JI!Xu~?zg&%YCwWp2p5qij3<(OJ`PyTs%qzRf&s6Dn`hx@G~7S54i$FaZR^0)96~e6!ohylEcKi=VtIdMR2Ywx zB-9!bm%)laG}5q%kMN*X4HlI>X65p>wvyE6)2Hwa*YNA?dNi`WA3uEV2ObziuR$!2kCcDxK|GelwToX793O=m zfEcsttI!2~2xHxV>xJ(nwr#t3{d$AN)xNT!rnDp1YEGpZBLcXnAx3)+VuqZB`UB_(QFuUVKcU=g* z0Z-klSB#(%M~d2@ZveQ(iSyPzh7^=;^nTC_c~OMrr{t(sd6|0JT$jbyf!Pv`IF|`Fj%y>mzMUg?tQ`oU3Nq1JEUsjR{$|<8p4U1n^uaw|u&eI6uFN zxlfNGw599cOTFhgQKpqi?iV3wKssQ>WNAkS2j(?vE|Z)aUK}|zzl;pw`x6A%{Ks4oXijqQHo4BKotpIze_KE5D7R5=kGe?o?x#MNfz)C8M`gbA9Kx?VfgA2 z5bkqCvj`!1czOkibi%x(0SD7=LrBLAK}S+93Gl^bWefzsfmKAR@_LvA04_FoY_p!=YI%=e z_uvdrd=X6{sF9clBnU=$DexTj6Ujj3AbRINh5><%8zqdBdmUh9C) zbgt@$k8Fy@ED8GPa|E+ta%vfd{e8MkX8(?nH7rx!v!@~Jc#)h%h~OD~*M<0a6Rm)e znwz(7#RG)XF*42$&>J97sSFP)7s@rO@UOwRdc-e?uz<`cmW|$P=S9SHAXE?!HzzNz zcFdLJk*}=Y++?GnruLkqFHzlz(gptcAp+Nh6`o9iH8Qpw z=x2y|13?ni3&>E5?`RDaHi9C+1_?SwQOG#=4j)e5eOyzB3As7YlTVMVg(HDm_!Jbl zv0tDSlIe*Dd54g4iji|$4eq6Vl<>^XPTtKXZXO=JMH&vubj#OnTLMd+sGqeQ-g6`S zF(L2;APz-3qE=De^G93J4ovGj(3FNEjx%t0^Cir(7`%m3 z0K4ipw^9LF(NNG&bp>}?!)qscI>EF+?1u!O31yFrm*T#4VlJf*uS~SB28G}5)84&F zfojaZgCeU|d2Kc|Gb1*wPO2sq-29yU{Jo&H&0;~(02=V<0Y^#p8dpv_K&m5jRm3*# z?Y*)ZG3|iFM6*&Bb8N`Y@87S2B~`q8#{zwV7_AYf90oo}G(9k6$IGT_#$RmIHoZNr zMt1>w`Z=WJx>)(}TFGtOGy#8PcI{G=EJN6nSi#!L`)#Clo;NVK8IjqDAqlHn*^?|n zzy2>r0PM)H7{}VRUBm~2RvR1=GJ>cP4JDLEF%(ZP5$J)aHn+B!ljok4ocz^`N-D=| z_WYBlPnA*d5JCFz$ofvLJ8UqJP!-%%ObrkL1*t>9U<_t_0);*Jbpgd-KZIV^TC(qv zmjpVF*PKbXf}R3kkbs4zJ<2vLc3p*zFXT;YkIQ{Yz9n!=lk<~eT0yynN586pa4W@o zc9vftaT$=*jghp=mOaP*+!L@8C=?o--pA9pfXEw8D9{bi2j$$y=@1RnE<{%l5fK?} z-cpEGL9`4g{CAbL6SK0!5dRr#H3om;n^w)jD^Yx*?x>ni_lLK_gSMZaaYmEd^K~Q~ zfDf@?WPOk{T(x%XT36(KW9?t9<=`NpeUg+vitU7Cy2FofS!mn{kt3pax$#kPRk#rV zRaF>I7%ErA>(?T6W`CE@^)vrYd(Nm5Mvf%%MIb=35DAb62fT=i4sSQ|I}@iA9Y&NY zQE0m`*a0?122Ey^7vV0G;Wwb6tv0PPgj1uf%A=fy4}DmTusBdHSw?`H{`kCzrRJJE zUy9U5f^LQ$;cdvGUIMZg+@xjMD2~QRsxq27hP2}Hhe#boz!MQ_Rmp=W84MInqCD+P zK`*O7dX7R-oF8XFoesh_OCX8z_RT)|Hf?0MfnW!I^_#wU#?ZC|HdiC2M+hIhS)##1 zprNCD$hTs_$0KeTxpEL#lFdchbJR;zAs^KYOnenuFnLoXR98V@BJsH96$}g&0KpB2 zu!@{0<{(NQ%y(FXKsQtrV8MM(PEuIGDLJ-Ksc|!CjE#-`9d_*4LC2T$yN%hI*FnrxHc0cR^a&4{QQ!wSjtFTvl1!-pid$|ffL=gxB$_7~XC_0>xmUm=7+QA)fO+cY6a5JYw83(T=3Nv|CM z@jsxUu^$YHWQ4%+mHxoPa!^Ix!Ljen!o{v5)QE6a;0OGmAS9wB^E9V`7LhLipaKzZ zM|aRF^Y#J)7jAxYR<7m{N*l^5()_iO(tm+nt^Z$$myoS|=1jWwN61OElw61dX(Ccm zIuvGnybT*S?h%UH<&s6=1wBWE*7WluYieHvZd>=i_}bquNRS6z+5ox)wJ(Y8!OOT_ zJNfhT7D^yuqn?v$bbQ{kKX*_mft((OGOq$}o=mz3Hmz0kE~fAzLLc#omY4s~?T8^W z+fVriDI}$SA-3B2`FSMzu%466(yyAqksz5?NPubQ z5C+&#w#cP}rh^FD77($dJP=MsN=1A72_XbQo=|uzo%wTQewYc0ZYSoXg|lgcHK z#e`l6`!NH2ArFj;91UjkRZ$!YO^9n(LAwf{OuOiKR1u9HXPtU2e_VNof{|(d;Bg&sPa0okV;; zJhqKv{<0X$R2QdMxBc+n^`!mF$1(M{txdv`pJpE>;Z?qXEue96;aS=Nw$2SdXJVMZ zmJLFaR?7xn3L{z!)S4}*t6N0%3*dnfDKg&18`V_swWkiCFab5tk5UaEXX%J7&XVWa zl#QBe3ORv@90c~m!X;s6z9{hc1W0>Zw{5GH9Gr`N$3%kZD8xjb0#4+Mgu6pxf-(+0 zfsG1yt-9@@sGz)}qALJ05G8|gU7##60eNtHX?Bz>3tlQl%d`w{CgJKg==;jVvGB80oNyv+ScC2hH^9 zKB+#{I6cbSBhIs51(Bj;Yxq+bo{UtfZm2{#VLRc15=X#486^T(GyzH1R>x$h&}aB4 z;iggIJEqY7GL6f)e{)=dDWP~igT2xG_B;_ZQ0Mlbb^ytXMJ%*Iy=NCQDu)jcpRDT| zK2jI6lLhO#5-A3U3QmGt!Vvb^9WGNWYVTGVm-CyRe2_7B`r0;E5bc08}lk`scg@w}0_%gFYhnD@b*RE{Ktrq~s-3h&>%m^F~gJ?ZmpZYo8$v zer!!0kP))Ml~6Hrkky50M?7=r7#>+Q%hM5^Ii^~9U2^+&0#za~%c8bsO};UB*)I5$ z$maP2y`~wJsvVh@{}q6|B!vP;ORKOADgG{JxDT2bf=hM>q9t-HaeMq76Ro(u17lKa zax<0}Z7ReKQ_aSny%rO*9P2958dN}i#sd;!F5nOhZcePJCoV(Wu$qWjm^|OpJN|qm z{_5k$F0sy1d^{}aQ9|k(8jGnCiC3VSnqin-#&!5!#MVU2rN9k}oahKUxL^ThO+@;% z(5R?2h%a2l07@4qg6b6;VCLb8iG8O|Z6aU}L%wTNjZx^R?rBEzwC0%55P$*5l%{?l z;#GzQ0YybcMfnjavZIc`+=l*@uVLFESE2QF^d|Od^g=t5#!Z<=S-{uGd|Ry<$-E#x zSP84E9`GsB8Obyh8K%zT+w|aylQ|zSwO(0%-H;S`N1ae@o_No@XL)V;TNvJK{pX;I zK4A&h;gf(3rWk1_bRK(%FTAGn$B!U{JUkz739lg@G;wgD|5jj&*FUt-5HZN1pszGo zE(IvZY(r#OTwg?oHxd;(s+oldb9`^f&dzB=_W_GMaPZ)T++6!Cd!K=wku67|(gMpx zKJt-a3`N0j6j8ita z@+%;`BWUM`fG#Kw9Rz3$8y~e&bW$TX7Y(yswL-uh-2b96UT> zh?H77#e|U&)J>Z<2~9K^6$_Y z&JVSR0MHfCUm&sb3-E)Gn0ui4X%_|ofrZEf=!yAd+5| z(G~2Lb--VR@8|90h+YX2d>La4O^dKiDCMw85OCMBJm~tD1sT))dnSq3X0W~G7(>DH zQzA)>=u)ReP2_7ZxFk{n7QGz_smRk7X&5UbJRK8c03_4|rXnmDhE42q!`o9pasDdO z08sbI*#ii_oP@IiTl)IxNGe~5@6?op#6&G9UdlTkJ^gqG8=Iia(Ww})Ps|u5V&KyM zJsBMRf?9A>*7;0)K?_bcAf5}>pH88AoY4s{_u)<|N@vkf>5)%s*x8qXq=+2Lr^B^| z->62djQFmA{_cLdhaV+WnU3U?T4DYSC_(5MAqQKaiobbym+AA8(b%ttn_b-@&0?cM z$Bfr0gT$VSL1r=I(wJ=5zp_K=>Hm$60KN&o=AxzG5Rl#H&p)c2!Mv{$gcdS4N5M4X zZauvUk;MAMw9RS z{woM$h9=p#`Wl)3J#{Kc`OC3rvE#&OAch-}S1h+6O9M&>PyUw9`+~Fj#P!Y4dr$#j zL%uIk!sv+|6_iM;``dJ-4#{Rf_>cXJj~EEn&kK)Ewi+QbXwnR7vryGH0v})zHBQ$s z>9)u~7y};K4=ph%4|uj5iDP^-1HA$M3-wtEU?n*ZlFb(c9|%UD8Ske-@aCkes|>~y zSXZ|Zs|>59J0;G$0uW$qy^l>#jXXT}#lA;2NV@}MlY|D`x3}ACG{P0OWA+Yk{D{yH z0wO5NBXBDcp|WGl^zl(*ntjNnK?djAX|vB|K8hsBkJYX=>m##g?eJh}N1iz&{H(;B zpZ{kzC;8*go+kNa-iz}tNI|0$NVYspuL@5u#eL((t|$jr*Aa78{k!46|9gs2pD-bn zBus&%3$k3#z$fhCtOM<)XU1K>PTZ>m*q+ERN~8BLg^59|dkWd0B)hp@*2x!<05Ad) zXN5s2@aD$E=5b-TzDU{cCenowktm^{(cqSn>>7nQ;VA29nY<8jjtW#~!PS7ZC1LTF z3xTXXIPd~3{Q~?eBocr<74Kn%qhI<%M&y=r^(D$3PALIZv&xbny#Prtj_qeyv5!a? z6S1qFLXq3|@k9RP?mvG{gP%aUfjUa$=tXi60Tc{vd8pP9HcY@rNV=Frx`A#tBKVGa zQh~p+t&Ro^qD2A(r_eB9>EkGc#M*8i08|9xGtLj;uuG z)O>XAs9-G6rC_DP>DL?);>O&NdSl{jjIAe`!3$ONp4v-dxOcI5XoIIBI@F8I| z2$5;r?mrX>8cl}lZr{aK9VgN%Aebjcur`46qNzaqssx+<4Hu?UJcMU>0Eiah(2Od$BqQ)s@A)h)XqONui5UnG1Th4LMv#g@ zmHvWHhu65IBaT5eGAOlr2EtR4T`}_Ps`U3HProil-zMZM0@L0kAA%hL&>VnWl8BAp z=zTjhg=uz~((RFS0B}yx>4SgQ{Lreue;L=sM_`4_kO1kf0*VGyyg(Fjdd!j{j88+AkPft%jyau=g3)Vd8XkA7#v$Ko{r$qMRDz(X297rl+ zO!N&Y8a(!J?x>WA;xmEbwuxc1ZZ}BMDlCZAn1-)-@nYY(wx_z7AYmkPv`?AvW1z3O)jEKY^$iXuB zIPseMy~~PyV*OorWKpHgxh;MI&oV@ygN#XQ6}#G#sZ|M}xe>@CkrEFKa+RUH?gm(( z11-!2Ge8H%@fIjZ6&)SMfJAiU4Pcp%pcx7_T@PD!=nJcI&#}opKJydN6kZ59(ME5F zi)M|E-$9^GnT`)2!%_a%?Bp@;*(4!u-MaOBelm8QzJ%40TZrBBC4k498CeYmXT&0e z5PQOs*t{1k!VfT#JgO;#HQ2td-|4WaMW(~&Ey8`qfYd4xB1g3`dTm5*6NaN9n`kDV zjq4a0SC}ru2!~s&^B)U2@W6HTK&Eds|DfubT6Cc2sDH#UhOd8BHYQuo&TcCiEy00R zU!V5;ISUBTQA?{)=zsT!P@g#@PcJ9^2CzF}Wp75rty@R^gd67|x*uzf>F_eO_1#NQ~HLITx3d{15N< z&&A_UA>RMnqx+`e^DTwCi5c1N(7J9xFJeX!`z*dP+)^ z-$t6KF0>bTmq~FDeth!GzDCPELYRPhXqV5zTm{pBe0o-0FGm?dSkYOxGBPrBxYw?| z0&S=ZG&*j4>YtB1ZuKuU3LO248}ip!WfXl7wwU7o$66(6LLQ!0{rk{oNa_S5MB&-< z_!3ObA(ad!5!Qro73i(tdc)Y@%)u>kaz@s1csKG)(bom7u|lgbZ;Y^p8^qA( zu=vTD6*y{w^?MsUH&oI9usXaD9;VL1N~CNov+UnO+qaJS`;ex!GE-^(QA&NHi4G2$ z2{p+uKA#;=6)_n^5r2fg<(x3qf#ymKzK&UF8l8C72y7U{SD(WC1@u|$^5Xi>-W_C+ z2s8c#^*3@5x6sV|kTRdL4b`4fj?NUZ`WP`(^&T7}_6wp>3rY5#eHf0cLeP^G;wBue zL*P70;2-LI=SL}mJ5?afiPQ(!rq>&RD8-36W zjTjR@m7v5XR#s_EHW;zS>2%A{k1#&3@^hMjo*sv7T^~P&ad8t5?-_1*=2SFG??L{? z+&CX0U~n)e1l^#UUzEyaq3ZX=#Hdler(sDJgry9$!=1ssH&21Owl3yqGOD1N8{l z1#u$IPGZ((8KFEMPqB~sF0A5+Ov{~j|1eMc)I5A*5?WO z*V6538{mhJuY@^ioEXD|NF9-Ye&)FXL;c6uYW}hi28iuMglQZwh!iC`#%lWNE3`t; zl_&pCj_G!7Gh)^IT?8_Co z7%@DFa4Xa?&p%QPTP01m_>M`@9BVe&!V7gzAx-htx`oKZ91ULV%d` z9PklTJv>O&*=$58iK_<}9;zH%(GdiULc)xJF(EFSAScGt95(j}*%dg7#Nkg<=MRs^ z{s6hr%91=r<@?7}mXg&&4tM+QwLdYcMb1iz@T8@nb&}MR*oopm48&1}R_C;9l->y6 z(vQ)mBk_lD)PW!sJq5|idJH5I-w<#2YCD2nbXY*?a@@mW(+8UK0vu3LRKRE0R(q2P zRZu$OHK$gU@g)KAEnCRBWZH%EC`zzx50%tmdV_*RFCKZ+z~I0`ldmmgd!s<4 zhlKx;h*Ej~2^+3jWdqHn3- zP%)$>l9xo0EGhf|u2rVc1>?7!g z=${E#3y6DEl3Rq}S|<*1fSG-yG`o8C*HA|oa#Em5v>?wF2(%O58VvupZ>@}DClHR7 zIQ5blTiXn`j-334%-9t)N5bmSJ)h(Gu&&;Y+hvc*VCeGVbvFrEK!+sP(-4h-1O%aolCwa&UOcEl#0Y~T5Z*3AnL+Q`*nCUEY$-_vU`XyB4p?-> z>^hNH5RU7@9dhHZe+lwT_8&Q56xE>V{VTY`4i0%L*2fGCdSpF5qFtiT3bZ*o;Mrb( z6D36Q-2y_ibXi`)lfepyVyO?>CrQjKBGPK6oJ9g~?A5$?)xB}%DX$)?p=QR(QHs%ijz|&G9ohK$H>~S0yFi7fp4Kf$i(o*fx z;gypA6Ag-FFBYb{nIeDED3KXR9JGS5Ya%A%sFiY5EeS|5z<`E{mBxp#1!y$o@2ve3 z&eXa<{|Ah0AO~2fn&Uab&juP!!VylIR7&tE|NCi6%7I|q^pr2?mOO0HIM0egkZw{Q z(J&~==yJre7wUlDOW_4t9BUKj^CKszE};OIC2nJlpHq&D08D08%Uf&2YDfF09BRRm(2EkSj;Y4&=$}*e0U9H2vgW+3=?3$ z8O*j$PWg=mQ8545fF)jU9|T|*uH53%^KuoH5|UtocON5;ef{p;2byaT+DA6%1*#TX ztwQhvJaD2WF?4@}IHlTqurwP}G#HV;Rtry-j}iz)?4UV$(aDJ$V>tTj`(i-1z5+J{ z$TZDtIBXTjgt)I~Vc7^F@&!W3tl#kyhggO6)YFUtT_&AL8mSi3F-s@}r5SZc8*e$} zO#}w(40P%WB%{*iunx}*2|72mz4{)Sab`IK-(D!a{*bMSN386I%8eidxTeu(#MsyH z^Yd?zkkArZC+C_&QW)rv49)-^_#Vr8-h!VYTsyTX%s|hopON<8XJ?l~&f0=pzY1uC z+84O@mQF9EXKLRHuMLy%kr*f>)~)^V|1|uozJMpQ{aUedh><$z>6h5**#4)UU^mDb1Qo zbA89ob=}YVyx+6d_pNumt@~crGX011cb@0o``E{EY!X)j)l_ci$*9e^l(BuR6@WSb zvNdQ{jsi7C6_z(CyCu^kWUvSQ*6#87AE*Um=#Kmk)B<8xBG0})hZQ$W!FoC@y!Yq9)MN@Z%FwcJT<8l~ z;fKdE9zfLiUY#8uA6I_)8EKF5`dWB8)T4?5h6m>sUaL2cNso+R1`*Sd}qf9a4_YP28P|o&N?Vksgojam$5E5NL?aN>qGU7KcXf+(pEp&lg@l|0qyk2$P@-72Sm+jC*D7}3~0xg93nvw zM%eDH(w;}sEY!FM+xK3>^N9%?Y z`L2SZBIR7BzV4+8PTpfrD81ZHjymQO7B`ZBJ4GBB?xf(d*-{v80udJG8@zS~AOU9z zj9Hw~aY0uWS`Z^>aN}c;hwZu4iEvMfXMCZY>S_Ui4LQIEHz?~flq6DKL^k&*MX9j? zS61Apr>dk-+=j*D(GmF$Ph%(8cIXI%nSowpT6rh%8Ccb;%)ljhRPZx~YhKaM8+(NG zGm4ic>mZ`ffr-}As};+;YYu#V?=dPk)a5jBD<#G5iA4TWB%cy81L?T1PmMHvK_Nh_ zKqS3)?{Ad=xrm+z(B<%bO!a>;9#$f_4n4+!+eeKuEDUW0Q)&xmyaO6Cgn4 zBIm#|CMK719!bhRJXz6XhdsO5ww33(LB{ivZrRUoE}kcc2x812TrodmJBj*^UBAZk zvj`O`3^}xca!V2?)8d0@>VaEIHH&Kxt}x;$%Z+wj$&QbVB%>CH67mq3Nn+1rBG;NZ zefo5mq#5EwD7QCh<6k3ol;F^Mn}VuOKg~P;1F5poz4U*RL^1c({}+iOrr?kR?!8eH zuK|;jcM3mzP(lg|osTn_3}b&mBcT8k5A`L7joD19AwcJ(_?%LWaR9>?5xmHh8ecmb zyNS3IAhJM=99^-EOCkap?TC{TzuU!A}9HkyLL%5JgncRP)TO2v=PaJt52(aDYCI1}U zSp=I_Y`T1Y##W%=fCl~Z;tKB?H~Gbc87mRuW_h7z9<3`UB0q9XQ0ea$c3bzr~P@lXL^vi2k32 zQc!MVY6qw*{HU@}9Pfl;2a1F~HV)-IlQ4jck(Keijw!vV_Onuzm1mNhEbrUBn znP%f+i5LZoa;j;kV^6PeU__fEN=B^h8!8F7fl@?BoInQXKar~ zG44Fvtt7r6hz|}1#A-s<@75i@9zUZ!K1i_$gH)gEc?37$^BFsPdTjz)lM=bKWubGgPqy%t=H!lF1nRH(R z4OUkgClxF5Tq=9zhwgE@Hs5xoFNVOa07t7Im) z(Yy`o3^Gf6!lQ6$^j31vVBavTw((-sNc!0C!(^+BM|;riBDjkpnvpy-)}sfCgGuj` zvB3!9&!gU=9v;t!V(dz4_Cl0H?jb|E>(+utfVbHNE`i31H)AmVLNTQ7|01My;XP=V zfwtchQDX&YrEZ6|4ma4CJp{bGBU?UknlU zV0d~)Ckejsz$=a~KuJO^e`4jE_4fB`ep|_q{DYVW$c_Qq&GVhZN<5^K^_M0_gkYy5 zT8Q$W9VGQ2ls!UaoPQFZ+oJ!tnBdPQr*NPt1(1z^4-#SF3L}I+-bqPm8jW?K^bffX zf$!*=hKAk2$@jt@M!v^M(r};)0DxyeOci!0KK-hbE9iqbXmrIPEdtx?ek&OH;CGPg z72}LS3wVM=Jb}RNrRq&RP{NUyladVWhHDTz_-#1Fii{Q>+~3i&B@pOGTiZ;)Z`*J> zh-!l3<^>ACBgWJV#MQJGG5&3CZWhQ$D|$jsPwB_P2P{{x+Sf(yw}g(yrYQ`M`{UNXcZrO_y4R6<=UaOy!y z$%48*%pQkKTl%I$UKHpjqVG4Epv#B#rPRyfQ~Rtz8v)B~?0 znhNf~Yg9r^jE_B#b$p%u>yQ=keGpElA?x$96o#K_ep|YCB2I9O&1PpOl#zB7YUd|N zqhDR<7DjsOioTZEU;DuXAm0ZNzxJ^+_!|HU7J_lV2F1UtF~*coUWr1;IQ{zH9KvB&BV>j62{gpm3ez6uEAAyj8To;rZ@M6J$Hk2Efw}|GwWwGSM4TU%@ ze%No=b}WIemzus|@d#O@jlk%QNSj|kfg0MrTA^a#fvY_kMNi5@ZYP07p#ZK8J6;3I zvXyw|@au8TPU!=ngy<_;j87Tb1!M$*BjV-+qaR&|wE}1~d$vz2`bK+reg-O|v=c^* z{R`-itA~fj*VndDU3dk2TxDDBXq}~~!6}5(E<_`O8$w@h6w_LfBap*ET2fhg_|#$G zOzNZZ?A^c;*P?q&L76PD@P!o72O)kvPb=82x-dP|gOFhcqaHo!Lr+c|_ijFf@izKu ztDyC!cRKko=rS3zq7%x4)w9b>!WJT1MvN;G!?i|ceTqOq6@fzd{0@*h`?$1QZm|Ix z(nqm#vyp4RI~MPtw^g&eDd%@XJu&Zrz!W<}=IPo4HXBlMF0vD+PluPt#nZ^eHuSj} z+nQdJdOns}0vh~=j$KB7fA}yTZ8RP%1@UvpHk1@R5s%@}P>?=Fb)*;cl!N`f&||$2}{Fr~IsE8`2}q=D|KW_AX-EJg(2sP+EJACVo^TRwo6 zeF=!>0KY|$or6#s(ERC{w|cF0>hH+MZxDTfQex$Mc~|}u;hr9ocUU7O{pVNQYLY0P zNj;C!m_RQ@fe+fNzyZeDCEXgJCZnTAgV$7k$WR2HNq#Uu4|!}w0u>S4ATRbn$8|nd z0<`(p2{BMG06Z)0`42Isuk$~KdQjG6ctk|3f`I-C8Xg!|_6)8Ik+TK2EdVxA8gFh8 z`TqT0j38Kb5A=8*xc)->tzE*V$>ucpV>+~H1QT#HkYW)1?zK3o!tS2`6aj9s)BZ#E z5oHA*4zdo_R6WoI@X~>6h3yTjtk$98wTdx5eR||!u-bhX|3S35I~G7b$LZ5;!X7JE z1Ioa$o7Av_bbu6RCRXn{J~0YuP8F3x`7IxOoeb!*M+l!nD$^$@Boyb*{AVe-dH?kb z!X(Q{E&tYYd)v*EyzrP1o70aoANA>*!M*jKFgjTM*wDYA9;2_le_(QBw6qrnoN=%ksrFIEM z)y$BP7&o|?{kC`k{jv%PVOt?|LviQLYV4b*d7^1ZI z$xTdJ!LNOO3xGyT|Cn)xq!jI`r!QngMA-4r%0*5%rBjdyj@46h$TMWsVnHu?%7yb; z0BhVg^G|-D;(8n-5fra|P7gS^lXvQp{_TTGf%hDc5ID#|?N zeq7viU~s66F^)jAa@+Zi#RL_VBMR=q74Q*5Qe5p}(vXF(5mt_pmOsC!m~V2a5=9G& z7wpXxWrps(0rEZCB~QO?ARuX^HaNI&a_n9D34>M>PdsM2_>uguF=Std+%5~5$YoT0 ztIALoZ-T^pHY1um#TgX6?6yDKhFkzR8t{fdizHO5MjduczItl#pl7$HWMl^nWnd`W z2ali3U{0@p&kp|Uu7iY@kV%jzBKBg=U`)T?=5H^bmGUV7GY8#)4Oe+L zvJGK0LCm(IEtHGoh{tL2#hQDEMNKkGZQKoLh5z{(9wu=oq$@~1)I^ezfq>k_(XfEJ zc5ssf?!r@m`;HUm1enHL+(Eer_cVNnSeeJSVnwrY0dp*0G5La`4`SEBQEHXbKh(m> zH zfK421PGH|oHkcd=^5LdY&Zf5B<(KjXTj#y_ysvvic7Lr3j+ia{XE%Z;#I{sH?Yey5 zH`FbeKnRfPDGG4Vxo$X!CkSvJ$%pReCv*0U#{{lLJixr5Yp6v?TE@_{E8O-V zjRqeuQ!lhinhp&h*JofSnCdMnNvGh_)Qp@Vd&h{twduob;d$5q+rJ*8s!M5fGS-6{Ba1k2|_}r($bH z*Fs}F1>`Fvp;v`7EEFX52$z%Foh*q#1tWJT=kt4RA+am1t*@&i3KQMAD2UZl(W@c* zYxvm_wCC4|K#Gm99k)5nIKz%Sila#ud68N%!w>DrX1nir{rSxX&sLAE&(jWY4r}4b zc$Dso3#;ueGMlAr(7A#rVDS0J9LM=EC_oI~j7tV@&LSi8CYW<_w{5rwR1T|%?TAA* zjV?y#OA{uZq>RA#Cy4qnX7r)aQIFQ13oN4L&|^a1EJo5TnQxN!2{)Lw976nbh_T#KYT~d*r9BO&d|d; ze0I0={i6o+`Vxokj3=|xf;R}&7Q^PIR(1uL3Zduz&KkHI$Oc`|4h{`VihLDP9Jto$e6ulcm_)$O2z)7VYW6e+u~ z-95pNUn1WT!{MNx@iO>7tbu!5Fy~GQ0*9wh=euwTe;wHxpYAr-{w-GnP3SK+M{TrQ zx5mt`)$G&LH2rhVL9c#xXMU z8ZA2RVAn5#8O+c&iUR;1w!^{!*?KNG3?WG!$fru+rjI6i4(Ok_)0F#N=g?C^%1Try z+;(U`IJTP8-S6mw2f~4m2}VgUXV^QQpVn@Xf5m5yZv%3rp|L_J!1GkT#!B_QTQ|+V z>%D(GjfI!x@swbP(l66i?AO?z?YF62FD2=>3D+vHcJNgve&rX%x;U-yxN&2s_yB8H z*&l|m<81g$^+a3aN&*~|1xOjHDoLVF||)eGh8s3gAQ@)vCrLe7M{nm}UW{?Qi2f!cNC$RiCCP=jek-V28z zE4Zf3N0ot6X@|Z2a8v7~(N@E!jG^^=jT||L)a8n?77e~hdl${~-mjs&-S6BP{uP1& z>}KDZ4ulR?UEp-1atPn^KK*@-=WVE$pQZj4%mHU)cN z4FNphnjk%tCPE#`Be;JNc0toyn6wcgUTpY0{2vqybgCEzE(7ErkGW;+=mJAeJsX^% z`!|iJdfbd!n&odv+3OscnzAgX(?m^SgaI7vcVSo--Py+ztBm4j# zArpDPlXxdITF6`ymrV$|7-S!Y%a$yHn9lT9GdVf)Ks1=dP_RVgPb4VkbR@j+y@RPd zJNxash2HOWRXu9fJ$Zut63Ill#J!@(1 zQv?_A)>}yz!RA6FM(fO1_B3;=!p;CBF4W+J^FyUdHk%xkP>&Np0R=hvR-z%DkBbJm zl*YXk7xrgr#71z;*xmCsBtrk-+N|D;fZZ%zi|6pZ8`-1t`gNehkSW>*lRBpUet?BD zaLEt_7BLAF&#j>Yzj``lG#s6PdaIqZ2IdOi;kh7j6T=l!vb_~60_{xE!J`oZa1nzZ z+S+R^J~1FOh;X)``Xyz}D6mv|g`tPDE+kjDU%x&bm-zI2Uwhw86A=57na?$;ge&A8kl+$nIQ*&`8hw!Y3 zmmr!yF5u?aL?dxEf=Uu2>RdpF${QI2^PlL#xb!~88pr|goQJn%V*q?k$EnRE`WI+m zOF*o>G(Pk!p%WL%9MsNW1(QD~wSsgLPF}`ld_u&iVh=!wXqK5z`uA zE*c40xHG<^af6oy9^1rkfJzQ%1I>d4?cWdqmC$A|&PdV2Y=_|j*aBC;Gsps?g}Ti& zLKoUMQ0k^!7|77YQ>7{5NAf>j()^QoJL6ERiGC_AbxBT^+8-zzqqYb{D5RWZJ;f}M zmgYx!bU8UWStB1-E)?QGV+Zyd6(4{GOdaCQWKPQ)s^Yq0c?184fX<+EsUbOYHgB0d zl>wv9_2oo@#^K~M-)ck*I;ywqKj57c@#(Q?+kMfpDZFBPS(sxdR(v14A#K`L@y%&E zpRXOIiyIcpXepZMosPO6u6{hCZ@7!Qzj&I8%4&_+->H4W&2f?M{@!!&Q2G04$tqK& z-Lc+*;U4ebv-#M1c|`^7Z*MPcJNWF)t;d4T;-5b;vilr0;@da;OD?9X(W~{icz>Vr zlglHurES(t89S8=Hu~6l@Fi~#xz-d~&bPXMyL#y%AKS!)zLKwPult4z%4DHBgS>Asi%$qRbsH^)D5!0qW zv7oOX9;F>M{s=T$5vV^t=r364IE8V$IX<;yZAN&^;nXji9z4*P%7BG5_k3rO+Tr9A zUKS7h%cn5g+z(&hdVWPz%;A_;(R(7@9YW!CfoHOc{Ef@L*xKr`E^5W2HX zOxv^~H%wpNF3rN|r*Cr?)4muLGg2gVSM6yZ7vmfn`tsFF;e9y5$JeY?MSM6507?h+ZBeS)+IqjnN zU7!AG5fN)m+ge*IwreM|F}P%BpRE~{``xiMEkb^5%HY7UXBT~wY}V@j78G9cU6gaq zTUU`!S(+N+;TAsXxh1RozqTlt?AoiIN6v7dzWjDkMny?6_F^C z-}Cpzd-v~y%*EYaxeHEaa^1z3B=hbbki80aDx)Sg~%c^(xt^*ipPqaj*$VmuudmN#y7G&Kt3HkWV# z6XvT-8WZa2>FF*IYaGbGb0;Bwf-8*rkAboR-8oznF7i(@E6-kXdGMgJd!*Cgi9yEp z3-+(;qhiyk1Z5aIyZkudq3<8|vf{n&zcF}lEASG}x`+JIdfXjv2J}fRFfB(jT5p6G z$mnIciK?p~KQ4*Zml3)$P3G#JyMkH0#S;e$v||rUSJmH;0{KZ=U#W^ty2F-^wBG%M zB!Yc77Zx}Y0moRJfs*}*Nv_F;s>ll@OFn>qIY<-2ir*naziGH?je8~c^`VTS>owu$ zUuQ4tm=ate=3utzXYbsgFKtUBHRkZY8WaVIkSv-GpMB$s+h>`aoPl&K83(7OZG&== zgZYk;oC0#BNFY`S569HT;y`cUm6H{Wau^MPn1jK>12q@9{?Q?HgSv!7oELe}t;ZLk z944R;48j>+N(apztfI4srbkc7ZsekX9-^x;-9vNgrCazVUG(3N0|)!zB@8@_pwgk8;0r1 z^J%h3Zqh$l&LN&HY?@b*e0DYOS12Qd=)Y9F~8<>bjf z6T9l~KQrx3(bVJPEOGVyot2oB$75{Y6NlMhlz z#R!W-LoJ5m1xD(+fkwp2%$Ec`w#IHcJt1frPbX%ezHP1aWO>P*EW=_SA}E?tuxh6F zD=s(FU2zsH8cI`?e{zKP+xITWo+h5Hyl-17t~u`~jVwlXe9$QAsyR70AlG~LY#9u?CwYel zKty6{vA1}D^6}Iw65rfUfKWbN|vGX_3PJ*%qRy%)rS1> za>DzQ8-icGS^ygulKSE9)N61`Zh&}HRfGrgHZv05!;k>A2?;V2_J*k+YS+$mIQr8| zswNY>EQ>;kWJ7c|F8sW`3!+ief!>2D;2IdAlt#Y0%S)TR>=>BNZeCtK9Zd}lOE+xj zJ8>|2y;Sne1>2gr{JjesbX$@9@uTreoO<+;4%V>J z>87>}sYgH>p@#+-b(eRV59*c*LvzFPBNshPt7< zOna+E=bM2iwx@fgP5Wh;b*qE|_Fu=xK2wwSt#xB)SWDP~9jfwSJumI|hm{I#ADRfH z29kh-1PLDDv7#dpb)o79bjRpZVtWJ2e^)ZUU6)~>wq0ZU+0V-?O@cr1F0mAvQzm~@ zSfjTt?%2o8XI=}oOJBbH4DDCw46%Zui3Qyj9qswU$^(A(Md%jB^C&~ zPfLfcFA9J;6;zruOaw%TFk>R#p_~pYur9d_nOB?I2Aw*zT0)|z^{l9b#BBKZ zzDSWt)YWV0%)WhWUDyVz@J1ci>NuArv5L{r^W$8q;~0K%t%&GhkK2*PZ%nyQPx#JM z4r>qoxJXl+&EiP(SZ7%y>y!}=r3Nd$sJh@*<3z2gJNx;f;zT7QWwmCfRHYA~=Q7); zphibiV*LK;-t)x+Zm-|=$OKEqIe4$h|I#j#eN6P)l4Cnp9NfNQ{iXJ{;JKFDmgYS- zE0c;**Kg^KSi=SHn}x zp!P^}=%<#CaBKnk_Ox^uwESCt;{u(SpI}xwAC%S{x$$l;hp~PsqOT=L6w1D+3fy9S z!YB4g!e>LDLa(U->mJ&cJbfc7So|8_t>?axk(=|Wb9I`bbpZD=r6us&1{XsC9BPD85O;+I4u7+E{M}f)_yyzP_U^`U{%w}}LaZz+ z_V!P3SjX~J9mz5-1OqfmsA*ZRMP;Uy?z@aN{x|=QlG8zp7(rJ0uua9 zg#0uN#V(Bps-l&;A6z;MDE#0r^t>QH6*h!GR8;DP+W(G49=~S6ES%oh4K8b-;iIYt z|2K6II3Ux{19Zs)-JB2rMVN_d=+%~>futF8frtS`RBxs+I|F~HxmCZBstQVB(GJsk ztt?2FtTJ~FkgMxDQqjN(otUmTVP2N?KKJ=s4*UXaj^kWH(`qYSt!Mm<2+ob;QR zP7t1y+5t{F(SgZg7is@MwMps~KbhF9$Hq?pmqC>C&Gh{)h~@P11!zOv!-lflTDQi; zVq5y)-=oz<(K}*yuJYZok7e!vi<-njukG@zvto;;)roqVCG+TgvlDzG$+jaCWRbO) zYyu`68Ly+U9Nn}2;=X(?G)$50<{_+j0iY^7{TMO_n3suSawoOojX|Nh@WYiaa@&fR zk6uEi9%j>V0)9YRl~JZ|fDKM7tmXDAE|KEqE=zrx+qioDPR&!zZT9ceqW|IvX0Nii zEy`V{`F)Lblb8y(*7uJ}j>B+65X3%wi{zraH7b@S)F3$J;+pGfc^0T;H}x_K6eS1UCHBC&1I8yS(h7QdT_&g_Ad;0U>zk73Sg? z!5ksaG+79>AIx8b(Bh#;1eBgeQZGic0bQ(o_$6CZnk5?{t0cubE|}}UuuVGMvN4LL5NQ%}UZ8FT#fV zD43H}&A6vgzv-PUzJ+Rp#s$>bWbIGi0u`3lT6DJYPl+H)Mf}Oc3V-SOr!ZK6=-9YB zw$EV$AMx3T>PHkz(J?ZDYVrcAxZA$ICbm1K8%jpo<5%68Q@G#)&O+WLDAS2WfZI0; z6ud+pKKLnum;U|9b-~D_i;*(1=x(u+v|I4vueIT2)p2-!EQ*qN3<_A z@G{$tcChRnK8l5TeKdmA%}encYwD(kx;piUkyr^l_*@)z3#`L3G^_ASFi57szS^y> z4tY_%H_1mp{lS>tQ{~+`5GHlid8{Tcci`r`_UxGf+m-{+4=nrAqicE!x&5oA#}`qR zx?&InY5@U(t$z9b+O~Te+uLVD?d;I=_eypS4tYc?2o8=X7Qv(aWTGw&vcX!RoWA_* znaP!(ooj^4bj{75vv0@96k8in1qG>wiJFCy*D`(wY_=Rf64zWSy0$0r?AxyL^m(7O zF5al)AD_45Lri%1ZnRfl>1b%!^e#&6^AZ^!iXY0DedgV*rFAN+-yBQ)h0>ooK8l#H zp%zuq@p)L>Kos=7?}+mJD8^nW_$V*OjN=OkvBh1RSkpm}|O|>PzXF`dmC}RNggt^guQ%uyA zsKJd?7jf{Jsn0=`Z^^i-e{Sx#pY`dTs9-)>nSiM^r_3~QGkDIHU}Ok0a5}r9?jSGk zLUS+G0F1mmtmkcn;Z3VKLGr=(J9_eD_+ZV&PEG0O@wREIKH$&YAnB&2sLuibAm$kF z$+pBCtT^{Q@YjZxa5b&JDfZQ;r(T1=sI-U0X??hz2Z8MCNMv;PX2`@E0jxPntWSJo z-TgB)Y!`QDO&4+_;-`;t7`?C)vS%&t+Cg0fH6C;kbAjM|t6KTN!n5SFMaJCQFGWRG z@#Ywe?4Nb1eQR7$=;xA_&1?fKTRaxY8MoTJ7R|^v^F-xfa=wP-jmAfhD!@im4QZE} znpz#|b}{Uwr_Y{woUgX^ZEkE_!Ahg6B;A7@^SLnb?e>QVn3s7ZSD*8Lh5JK|rzn4> zl;FX#V*q4HW<)Cut1}NEq@ieSt&-6%Tl)==n>cU{HI1k;`f6`sE36^yM9~V?Mxq7B z)>+~xoNF-fd1~*u)Gb)#i?NLF!FPp)q>{I?wvIBJw@=}7sAG%A)tOv%FW;+OC^);U zhJBpx+T&3+zP>D-%ErJ~W$mlKTheihLamLRzYA2_4g6jqpPsB}MHZn1hBllxe>H1F zZiK)9gbo>g%1B3!7+$O9dVLCK6XaV{MTs zkG10u*(D~H^(OC8*Z_Fh@)uvg{^?+RU*DGe(lj!EfkXasVJofSw$0i{%}>{AnMp2Y z*EYzV>bOR-Ws1PVh1_Z{Euh&XF%OhVFGCK-t&)=B16?%>QK?<@Kh9u;V!^fPNYJO2 z#lNc*n3*r!+#dObeH1+sz`?L?=*#-^G{4 z=S_?@$+fkoko_m*2+(1^u1PvnD|q2M%P$N}!7k0!J73+tnc4U0%LmO zkmoJN2=LqM@e%OD%wfB%7jF7wZE@J0eM{V@m}Rq zp!5Ng#qkqv&fj~)eZA2na9XfFCHQ0LR3<_F1l~vUK5H~{y+KjIW<4|rivw7RL&BY? z3egrszvpfEag6aJ<=UjqKW%cM?uCu`_-^CUJv76)hx@9w#4`5((6IcF{m!M#5rSz2 zBcr9GV`D^2MHH5n-bkNM*feVrS_)NHab&r7K7-YHPQ;Y^LJHh-*sg~v{dp?|+rQj{ zLk=#9FV)GoO9&4J9g-3SjRgunx-s*KWQPcZ^KixFvE4MR_wki~Ry6Ybx?L-`BS*B{ zcecZsH}w6z`$J;Sr!alN9Ck|D*MI)&)t&fELzIO9Uc~v~>N~%N^QApoE9L;Mzp+cm zkq6&@5Q*5Wz(8+k9}x}~60l_5IE%1aQXJtJ(**lP;(U|e$!h;Eg3COe_}xC2vNPMG zIHv0GA6iv)eCj)?6yZliVi-LE^$xlybQ&L2lgpC^$v#f|3BP`tXcCui@Lo5%zzFwC?Nq?;+!238kL$R-t<8)DCiIEEBZaadXSgMh$y$OA}$wVD9dn^^4@SVZ%eLg%o?F_OGgxd7vLUFJZ^m zL+rk`gq>zCQ0b0L@)xEF11-%#g6&MSk(3k~dPMSovft2_o0gd-g@#TV6NC5wE+-8t zLH|0(Gyu{S8mWTu zdZCH!V8SyrmmN9AB60@e;bCLYWa$LD9x6 zLtn`*8r()r!foAe=K;#1QZlr?Jb%lRR#-Qu^?uk&26t4KqqN|RO&=Deeijq{+ku;* zvAI-3L!Ux2Ay^mH{rtO8=HZ_^L?pkNGcI~YuB4zNa#3D?g+4PuZN}3$OceAT9-9=e#({m(NKY2 zmYSzfE;5;@3FD3z&ZjOa?0G0HcSYH{Tj&K#5PCDE?Tf6ZIHMe304ZDmvb=Iehj|1CM}!7qp4B)bL|r@R_oKXU;+?koueN&pp2JlAWDh zX*-p_v>?=T0tr$+LPIy#{=$U~=j`b$eO4%1ux62E<-8!N)+cwO_+th+7+i_s)#ivI zHFiw`#AuTa;6%9$5+DnMD;ptUrn8;$-#F=UXt&Z>D&6xyIR;S)qRD0c`;qEC(ftPy z=}E~&m2=Ces%?`;Pj4?gVmZ>V?H;T#Vr2-Az@%=~nBJ4hlacVM@KkZc6S48Ef z@iwlGw({)odd$bYF&Yb{Qw>bt4gUDR8o*lSxRT`@94rj-rAEp)NQ{OX_%Y_J8SyJLai$Q>=P*!OMUo&bUjb#ICwzDmFNSsKtO=WH~TxF zl!&t4KjU50dK()Wj@#~C}CH~$KEpu z!qMcE1T{EBUrOiBZQ8q{cS|LK=8!EG*#6V!ipmycKDPA(Yk5`{?=Q1b<1VUNct_75 zv`k-LaMrXb?j9a$aPH;f^EEBzLov&`eED)8*_Tr1C&R6L`RqoqvFJRm``!2aO?u-Q zk9U4rtMa?AF1Rjp-VqGK#Mg3|eD^=XxakG`w$cKCyU}FfN~w}wsgl1+WoFei3*&Ky zEY;q_x&!R`JOUcQUYaGi?Nyf5lF48n{L}=S@8*7J;E||4d>e3M_o#&6J53^u$WVzVh8%Tyd! zErB@3dU`ZkqZ`keP97?@f8zA}g^RscJFPqK?zgeoR-_?bX;rqgUC&>bS@8n$6hszQ zhOm*S1wP7C8LcJ_%+O#<)b+xai7L+g9o~-X4d%&00QP`RU*5Z73Ip!TM522{hl3g( z#*;GBI2s!dFx$4^$tqJp6Yd*s;rhoHN(j6-!)Mr{xZGWFV}ksikVYj1snvjx2+4s| z1T_B@i7{{JCH@t!xGXUQ__fKHWeG&s#2f(=gGO%?(GK1%#GeD`cn!ch7lt+{;kb8K zSr;2&W8+r*n(nw&&}qHIG_FnngN}ILZ1xNFiu8Us4A-W^T7i@ z@VF6-?wxS`bI@*EyL);nfC&eINA!L2@Iz=`Jn1U)ne|V~n_BOo?B11^Db*!k+@dp9 zt;IAx*NAgG`eb!kNO&kaw%s|i!ra_2_3lgizyS|ZkLW_2I*N}7(+ZKf^XA1I1(9wk zJ1b>aRS2wz{HR;MmI zi?)7T>;VL^;XTmIJRSG!PY4eWi}}17J$$VK}o&2KX(NXaVq8!$_c;=`E=?x;IO8q@7Ho1QK%>= zdk&zGD0=qE9I(!;p9zq{)qaX}?if3>`SF}7 zd_KLiuhdOK8v|dlrNM^UYdqtBg*KYj4&GEjrrG1!$i*UfynY(@@U61?$5sN*7s-5M z@pyN`=ia^VP;GC9p@Y6dx8km62bbUd`zpkeWF>@pWx*D!(2#?Zce=3f^er%{qT360 z`P;+P_jrSPL>z6fux&K{WC+gxJN%*k`0pb+4U%G~Z)_R7q~(2>U6MScL4hV&%z7(ITf?hf3DAWLj?RXYe1Vta_SNgNE`5x+Y(Zuk9=C@L(C8kVS_g8Vl;LyT$-OIt=q=CUELJBzqC&L+mb zzW(EoPvKf96*uqm|FfkG6NGuSjCewhey2qAAJ8#=`G44P@^e6eKsH?N$2l=XBVS+Zo18g?u`B z?%2)!&cNIa5(QoeirwLO(c}5&{-O<`Pz3mOI!#Snj8PaaOVA@&3@J~>XwOWgrOn5 zbk6Bgf{lQcMbhM3e^!5i0qM8za_9DZ&`RQXkygO*!pifE#J@8h6pHdQ#`{`5Il@fet-0&fC|`=4KQyVGT%*&=X~2PHq5ppjw|qONI)9yxz$e1u!l7uL86d zt%qGSjc1{Y2a6S-QVrl7K#1mWO5D71V7s2wC!y0B2=XVVYS7w=lnCi3EJYJsJetA#jNxOfa4tI4lpmUl- zorPlK1?*<2yoM!84p?=RUNM>YEG6JQ@h2zRw5V?bMT;1mhyYi;Wrx{uNf6g6(v!yA z)HscpZTtPz7)A7^1?UtD~^UK}^t#Bg~AoIBL3FmtjQ1A0k-fbvHGWV48d zn#t`RoL6TvRRw@l zFCTyvJMo1yZyr23%Vo)TSR|f%XDyZB9!sS?AOw)GtWJ_b4nIY?R8&Fvnb!a1@T>Nu zN^0*-l2B=#adWdW9qA+HXcIoKXa}}K$qe{e&l2Dz{NuycPLgJy70t(Gvt;vTDtoig z-bKYEERzJP2T(j+nX`C5j4n9$sd(~cy}8k*SruEgy5!VX4gX%*e%qVj5uJA{R5wds z&imcye^wYnbdayzxsM)|^qOVD!Fk79oR2SDufvPNE_iqaJ1Yj8xxu5UtnfGL*|tPz zr+QNt_K#Kk*>#U@9Ffe&m%a(t3;`5S3)Qc7gFK|oFu9Nqfj(&ZcfmK zt;M9{9;`ROorRVo2b~H_92wFW0ZT@D1PCv(FAXVEl$AeHMv+ykI&IF{Rnr1$Bo1EK zE{XBr5u-Xsg$+0O881EsAs@{27XVHXbKG=>gDg@(jg^-6T9Ml#ZHPshL1JN4DxPSJ zQGSNv*2YFxLBZ>38lz&eK2OhFGP5*p%6v7CXXR}I0WP7NQUK^hR#? zS$<*zKlqQWW)~&0(61$L8=Nc>b08;tx$q)PPl$YreK3dZNr9L>q@t*M$`0UR@OSb4 zIlnTpT~|^9h8>SGk@Zi##-eoG7qxh#?OVuhb9bz`!X934jDB!rW^xm;hs9Rp>rO&t*<@G2681BL*$i| zY7Lz|!;nPBWy$UVjFkXQn#*Ch?j}{t;y>3(_&smVqdt`v;s%H*tt1lfE_juJU2(OCjhWbW5zE z8_*qjzmial8rRSDwgNHwD%ycBi^Bkh3PY9x zV8*W|haSMWF1j&E{3bts{h!>Y-!N8e=Nq=kOd=A~QTQJ_^y~o=weyMUc1hpEV_yr4 zi@B^)7Q>3oC&{2XZigAp(^64UWoi90(7*KAzp?Q&DegsGya*bf(qgPmtAre0F8Kb* z4~v&9&3esVsP5o%OV!pSdiZzerHMt@_(XU>On1drI5PZr7~85h=wn;Mmz)a6*mAEU9_7W24D2Oim{fLsz|e25A&nbwt|rn7Oz>w@s>nWfoBeJ zC?4B2E~LACusOv0%=4V6U2fsIgY8B?7gjT$*SNfho^oGbBlzu4n@^@U{NA7)w;13Y z&Rq_ya_CN{-BenSq*)1JjqIH$M<$RKRAJH}jrNxtkOLij-u+Yd(a#^N~%D`!8 zIU!&EQ^ll)ktQ&N3=x^eMu;K&0ksMTQ3Qa=GYl2#US1U2ZUBnevEr@~tc5nEZuWsJ z1D+npD98Yr27Uro0!8D&kAAu^F_Ex^KT&8c|vK&Ev3ef)C zm&LLkFtstl_tGkcAA&c|Nj=ii2kVY=0AM<^v7;isz0y2&pZ$l|;8)ERbm-ba+6?0O z5-I~vDNT1Vaq+j9w{QcD5FT8M7+jgTPv)#j{QuwBS$1y4K@lE^t$h0Go0`g1S5JZ$ zZjmJWqC^Z0=`6rKH!#doXY8v=nEDeqa--JuPk4`N5a zg2vDRh#m7ja4L);2oGZ#hkXcv6>{w328HPwF?kMb>t=&{>8ZpqEQ1jQbzmd2q5htR z!h;ZD!Y!Z_UyGUaShL_7$?pj6*9lb>avEg$XQ&MoEHs%#eXnNIRZ(5gUx@RC2BTrs zE6e^n+QwF|U$)}9X@=o&Sv=laIU`Mz=G{Wb9yWrb3W-E;V@s*_J1N;&jKy8vidoiT zZO&7fsVn%xkN+Co_4yH5bAk_ni-#D~;ADevaE;0x#^N8uOj7erx?#~J4ysBP z;M*?TWHcR(iU$1lb(}q*A^owJo&bwE*HDjRm+7F{>80J)+HdcGF1z|H1~Dm5v=LkD z3Z(or&H)g)M#cC)WPUW_z$IcDT~^|LL)kC|0t_i43t`^o_b^}mJ6~R=%|ARO0fe1+ zXV%3s(-}Gd;B{lb;?b6Zc?|Uo0Q3CSGLA#V4KfqhO_23CiAYG~BAAQW=0?s`+4US= zfQ)nB!~p8j1a~p~*>oWXXXG-qebz~Tfh>t9kPjhJ*l|$QkngO-d{f7Rm9l6zq1=8_ za+3VpP{=M77k_`k0qsdJ_d`c+cEq24C#f|4p>UH>xlPyQq$^xZ<^ye)G=nn+YO$x9 zrke3tv-rgY@z}{3BrJ@&*>_dtd~a<~#9QYoA%I(&uCH?v&o5!NZ+LL4x4JgT_)7Kn zirCT4EhDEZtDEj!mb6$jN4&at==WlU5S`=E*#~A0>{!|mC->;O&e7;~S{-56@;~;} z=T!wtW@_lzMx9MbklX> z5A>ebyS(&ec&knd6U%KDHuAb!Tg~spNN?~!c#lh|i(`3EhUvw$#PTt-B_i+3FY*35 zaAjOQy-26{qVSS~{uz-X+a6uM)0?u%Sf+#HdX*;p>ZSc|)VUb(7at30*12D#lYBW#b=W^O@BV1OmF$dlX8AR9*^Y}@OI6&t zw~a^eh2Fbg70J9BOB-jd?9;Xp8Lam!((%=2QN8}~K>U4uF=z7wk?mj2om7*%*X5t! zk@s~dI}x4qa`lGxH!NK;E}h&C-r;VY+$X@iJw2n7+eLlaz~!Zyc~aVxEuf0HhPG5y zUlPvCTBB?>v~#9|r^A9>RU*bQj9aW7C=8;P~t$cpNV0BtJAtzNx*&BJf-2O!6azrXuG42o{0R0ULk8x?^q$MX-^r zvMtvub;P9|Wlfr*uejPF6h3CV!%2?{8eHkHTzze`v=_3LZUm!xWc&A?#%b8@e^&?0 zX)=Ar@_cEv-LP`Mw(~|%DIZDO7MOlR_m*2w(A-)86zcY}4l0Y;1NO`eN-N|YHILz0 z&bRj?N3O`+jUN{#cB!E}Y<_yCg6&K#=d4B3JQsiae&9Uh7rR||Gjx6k%}@#%DjcKc zK&}vI`Xru3ASiQ*F!WL#og3w~(YF7kw56_I^ookg z*0-m!(ofG(iRyUu%)KuGzdhKr@c~Dq?83-1?I&#O61uj(E)r%}boMB_@hLlJ;hIow zy{}6K)DH)2mcWrLE!5=O^zI0+RxYn%etb}}TJ#c;7H%Gi)WjdMP6&bF3{-4D<3 z2*l}We78IMm-vLJ&!fVKr0~r84{L&cb*27vFi)K5tU7yo_B~$hd!auy7qx9#vRm}| zM}vacO)0~N6ch^71AJg^wf~L&>=QNjb6HzJj#y6_v~0k#%6F>2^&EUmWMq~qe>{AFk~v@ zDX?`uT%a2| z?0NoW7>Fjf{;f7T-Fe3Ly&+ACpR2@mMHry|cbN8t?LMkJtXP#4C0 zaIN~P@vaUbMnqgZK{T56z3V<+x$CSx#d^&)(!gMhQHWwRCS+pU!9aOqlPQgV3DG1f zl9>B^yu3ef*OZP$ewe|MN%;@##xX-yg|Ap@7tU)x^5uFo8FP_bccWY}1cp5L^X`GJ zzgGrs2015KNljJDxj|HH)9P1SQwlaq*)4US#oxRa;DKMYg4$cY)YV5jhs5{tFSwD; zEqinSjdw}={GF!@GC!>hhpfK)pXCo@kCKLmqSgSKQI8#eAEJ8B=V(rLHoQn$lnSRh z+br+GO-WW-$gC0Mch|F>{i8SN6m7aZGBR@5abeAzNc-7DWv8+OUI??OO%viR%faWH zcTo=PK`q4#pI;CitK}ScZXYu)UBc%`I*fpZTRc=o{Wt2G71E&SHihn-WNM&|`^x(iO@}{cSeYIKfMjPqb}7 zuDs^5*2HSDxj(;jE|ipE4LYM|%ksl3L2oRG{l%Ez%6A3HG3~!*4$U4Z5!G7mYkpdK zaC>89!otIr1}7`*cB&Sb2%3tdvQG5zlez^Zk8(&+~eo-|O{w z^+)5T`?~J)I?v;HAMb$=)Bu(M7&dS~YhF9#zn?){S@hWU!F`#g_Il6$!?=$X5v#vh z*|V>bQx*6skbE2!=_4pt=s|n#Qp)hOQ2P7Chm^ zpf4|v1CeV%E02htQ?wY2h}$8fuw3Geo^qppwCPNrgxYfJxvUn)KxsqY`cWx>9B0 z7W=2iXch$fBFd2&9UB8xVbz7XKi-2jDlidLypDv{ZU-aR$D zT9J&gN|YQbU!V_JNtwMif55R3^_d7NB2-?Rfz9;H5?>2i1ONrzQb^1GtV|DmH&W$_ z0H_H9VnmHVjhQDP3K-%>A@oREik6G(4v$D8ljVmz7gg6$zBA0%ezc4&eU?iZDrLEn z^C^^R`0pO#)}(*h#mIfKH<+j`oS*E_#~nB%@$u_Mi%zJx*R@-+c5t{sp}GY4@)*cl zkf;I8cT<*%YSvhwraXvXGPIil$qPk8}p@1J-6w>ztDYX%>6Us1!n^46m=JgDG zor)45*8+dfP~(EzuYG$?62WXAJVp@Pm<;+#WP}3LuiT+E0Cg9E5j%d9f?W<0#nCVb zPF8EMtwHP+WCD(kEadGB?!O34+}a9+^JqMb*}VAC@c%*P;22l~_!4U7;3xzU$0lDB zSuaXALYMaDR|`J^aEbv+M!Z||S93Hlr$vE`aNDiAv$c1jBKZB#%Dv49I2{3;zXJe% z>9<$^W+Q7xyPQQ%uJjX@z0dm6;#=uobJHycr|hfI9=47s65u;%Wn@17xPEDU?8SNU z{EOYc!jY(ArsIabuI}@9tge{w8{N>JyHh#xyI_l+T#-R~HYE>Fc2(KWD446^he~*1 zkPF4(LhYsy8s0#~2c8(8_)dWE2;eH9fWNKz{f!#TFMwkE@v-CqaK{h@O&SCRhkpHP z3bzTe+TYHE{9-K!6KjO+fF&W2hhSIaj*@v}gxXKkHvr;|fO!SL1R*&-0ya?_KzkD2 zAJsn&6MvwFH35Q{rp1#y`Tb8~pT)!Q@LT}SC-t2v1SG%OPVM8>p~(L@%zF0p=1=1< z`yTCaU2pMRRDQlOGFJVyp2uuFUc9mU$h{*D?9y?I6uR!e18!nhp0YSqGuy;hDGY{IZd-Hc~u*YQ(NU}&K1LJ=rbWaB)0pU%+r^$>q z1Oo~*qe29J#JJjhzTht5ms!Q}jA%{^Dx3`X2gGA40Sg40^0IK3mUvzu>%fraf!Wd; z(C!e=HVoYQSRkLQ31|SJ&`I?UuBFO@5($NOA~X*o;)w{QW@Kc%u=DhN3`Y!T!!9iW zE`Y!-fZm?<&7zQTu&!v%t?og@Ff@s(aKj-1BRI;^f}XL&#y|5Y8Z2qsq=;B4lmqi| z;v5KhXm{yG*%P@3^#bkO#~mL7vjm8u6ZAklhGB8p=1Ja*Q5(xWl#5FZnRfd|yGrlS zkBpN8g7@)hk&4cPfqCbiti@K8YlA$d09BR+deUCV%xgd<1=heD5OMu>4wV5g;^e3KJyO4Of!_&v7cavuDzp?%-fLsoe390~}Z zt}>5XT2TZZInQzG$#p_g-ul&%#aTam8I8%ZOMOGE?^4A=%+#b_qeST!*BZi(DM$2D z?XZ>0;>l^>Eo$4tHH!<)XGHq{YQ;6*H@^Mf!G7m8v1pAZ7dVQQL6Va^nSfj4$;mCjvT+_a6rfJj{l(l?+ZMQlz)mj(O`24lBj)9M>s7SlTi z7PkLH5|1|m-vb*=V4xg>Q;js8gq}vQkQ4&){)%?Yi0l6(c%M7EM~Kh-jfUXos9_ss zMn+;=Tdnr|>g5-o>w9`?KP?JggoHm}%q#&@NBocHnV#i;dJ54*hR_}#;!G_zFZ(br zB9qSWa=kI`x;F<7yIrwx$5h1XVH3x?=%&!I*{T#!0Awpe4lHc*tRMu0?S%rk2$?|p zhsDDQEIHI9-#TcaJp@Nj+f=jsCG7+t-IL*~?CqdcUQJ*Douq=X`Kk9or4(wFG&`G3 znBTQ{=qG@GhA75kPp;3`!&$ZjwT(4+tf12aj;f`i;J?(cx-v7a9D`oPlDGDk02_ty zTf=*Go0`BGCM6ua5}HtPx}?id9WmIbmTz!f1sVxSs>b)??>;BsK?05s%rla&n10n_ z-R0b&3oraNqe4&O@~e~~)Q;Tbvb;(T^LFp++t`6W6-Owr6;GLH;j)E>n+?%)?a|Ht z1x96ipvrVghzWzH1N57#Yo@TdAQW*4#+1k;e)ZMRpOvROTNE%bmWLI%*vM>QDAW58 zSvhBCnv{L#+HM!XFsE&PCY#ML$+Iwi$0JEx7?_80gRuy}6kWeyd9uMV{e<*1nsq+N zSl_ol*u!_a4pT^(Ou)D?Wg68hbLp9lM+O%`VLF4)vg- ztBzc`{>UK(5BwRQ1qT|Sk;K1$J#--_e^`SNO}=43Jma0R>I{<^AYNN1#E8GEWs&l_ z7R82m!^Y{u?e=P~gJn|d5rdutg9t@3kTMs%JO@fc2w2d|2X=vA%wEquO*U{vOO2Yc zYL^6+4OBi&XTO_?`d|7+=T(-gv;k}jTONA|AKX6x_ub%gs~k1IQ4*iiY4OgrapgAt+6M~5eF*IiQRl)wH-`v-%hAe^{)c@ZBZ z=J{bJ^+y{oHaeYP`eVD2rs>{cCI{h%Yv~OBJPDOJZOHXO^JnYTw=|uwUTR$~*s`!X0I)3pePA3nx;$Et= zdQOE|(S=&J$0?_x4YB7q#e1HKR$ z@paok4zImSyR&YXonLOqoSmXpU$0$?rmiM1?=ZQdKE=FAUtD`uaWOsiOqY-C@m=wM_lqQ>G9@7|e~SOD zAi1IP<>#cmU≥W9to`kjg3-`j09a5sh)$uq_-1(N*1f?A$jo{-<;0E8jn_&ll-p z#GbF#=Uz`?uhcncn3;Bd?7C4`J+RqM7kptZmzd$l2>b!T)0e5TZEvfz71Y}OP%Hk^cL3}5%Uh)q&}5B_ zpT!yOG#v+==EuJeF8s*6+N+I+S>>;(Nxphx1e)DjQ2-!xwGGhk1_+OKnf*2}?}7UM zZ1DCuNO+!}_R78w(;}3!9j%eEfA@PBQa_MmBYb6bSl&f1;vWZ2p+qGN`BM+ig_6=?Y5&^ z|CnG{TCQUP`#~~J^&7M=BDmeOhjYI$Ti!^Lro@PYWRkvE;9-wzD z{iKDPQ%Ls&EeK=4D+HCBY^f27ZK!O2vlue81S4uB(-6n&roM)aO^H^MQ8|ZHKm7H< zph7;3xJt5n_wrz!O8-;oc>o`4PgK_4$F0Xmi1H5sPaIpE?K&&ZEUiM1x0{M%zMM{a zkid9@6XVQ}AQ4#prR!;WQ7dDzn_j4ps^P=fg=VXFX6)B-n9DD&uT%E550>wIHMzM{ zB`vCq$HB&5-zlc*4GQ3g>RAC_62UGP5JI+E=s3A@Eh?2Wc{*9)(6IEsmVgnq#YDSC3Xf6k5kv2I~hUn**c; z6VC(PcyTaa(*pVkY?xf&6##f7h#_S`+htXb62Xz-6cDlyfgJeS`Rp+$V*UuS+v}tlvZ{kOulC#ZC5+P1NC-jp7QuhR!1)GZEOlC1$6!E(INt8yb&Sjy z0LZ`mYW5H`R-SQ*SI_J3T@m4UQQ^pl_2d2*@$iW1=rkD|gG-Eu+QDu-)%hFc&WV|L`2V2c1NJc`9%T)jBo-{zQregkd7PJ`6qrUPJ>yOkNBrkYH~< z3bXe5`g)9j3IwRkkPQ;j1c4IG65Q|q>4*UKTZai=L6!EZ~JmDB7hWR(O`^GzqkV>lT@e<>7@Q1}u{ z?{U!RWy;g%Qg+^cmLPfni^cO2@wbJN_Heb0P-kjI%nS7nd6CthOQgr>7=1<#HQ3vK z&bjR8-`d*mg^yEQ1{Yt=f-wMOk=q;^aYDNs7gW1GMhz^W_W3!(h}RfO3H#s8-@GSK zE-q+Bz`i&Ci7#|vUCU2Ekb}m08|TibX=`q!X)W*5h+%M z?*KSv(CtljREExTDY)(f?1sOwiI5|$zlEC4#N4=b{}VUcgGk6P?zsU6i#B6HqTUhO z?9Y#=|Nf6G=Pb--UHu)(jVYOO`TsYukf{sP?9`P0_wU!#0j92U_IExJm!s_oCoevy zYq^a%g3RxsY)pI%r!56k@_fF4A%gG+Dl8L04#}=lO%uCU+g)0+>z~AU7s@86p2XdF z`APUn87ckh%>I&$wsl~IG+Yzol96G98lq4%3$P^c zQgY4wUeX9I{IFP&CINPcfcn2EuL^?w(*5d1y)F@1){szEH zkO?@9H{rA$fhK$%4g(|+hC|@(rysjJjy84Uu6Wz}hwY@bCQg6)P(?hGr4iL@tm*N` z3;g^r;A`qa;O9}9(&^aIflsHb!7S7F|OE*a^zO{;xqkrTcypI-SaQlY>%LrZ!ZVf6^- zg;c{>DTg7be8AP?ID$5Tn>3D;LeQjX&q6CHOR)kCKioU?-ji(7?QV!ei%XMUr2;*;^FFeU2c_}v!b~V<_ z#TG6=vO&H0%2)ytANXv(L%=eaB7gas$VrKAolEZ9&oHv*i;~KJXrNaKrWY)pDd+q} z5goDI3FK8>bI@17dNh&QMq?7>!{KoqDjEc-=O+$T&;srZ&x17tWazm78l%ACYBf4J zspoJQstLvQzQScg0B!cXTy6Zykea6R^3CkLlD3jc?JA`Lw%Ez1rHfZGchAYt0i@;x z>@6rD8iU}7I{?IT0q+BRr9l21f2$0BH1soxxsx{zs46K*7*XZ?WR<6cK0*F8FY$pC zEY4zyS1z4zWy zX8}wiCfD%#xo#S%zUb!kh*V2Elib9=X~0AD&`T*g)t#`b6DgYoNS%%YD1WFNMp}26 zF>u2}56p9SH?SXuuWp_H?BYq@#8O86p67vNY2#GIRG0A+DPO@`!sj5o$5&cjnev`_ znpf2naM-70>Yn%I+7^4T$NUcG8|}J1E~iQ{fvQ+6i_( z)IfISfDG;{c={i9Lq%^)g0w16lm?exu z?SV3Pk32^EGpsV*f2%A)$rG2TUtC0*n0Y0UTb14zQsV8x+>)5T(CKavHSg16&0>Dy z3ihkl3JA-`KVz74PY-icIq&tYz>99TUMTCv!BiM#FJ&!FzsFXx|?J*rAc(AwO2=?Ud7WV2L4-|SOrg;g*y|dbi_Nl>Y#`tn4G>RKT%=h zLVYs}Rk1*f1uv~!$wl(~N#;8fX8{nt24lqpS@_K^^waF{Qz~vRHhp*|OpAm0-n_%M z(?;tD8r7^GPB^WbcyRN*O*}$)P<|=M?1D7aAL34e-}f;7QB2G}KpReh?uNqdp9_j0 z+pe9<1v6FpgUQ|EN)oZHDY5$cgdR2jn)hy(aQbDlgs@-H`uAt@rpRC4xMKIX=o~Y< z2b)r}n>I(c;qFGOePC_S$P?H5%qIvV)X)9JVb$%nL|eSk5YOpf&R#?vSk8k zC!)EdLlyL9D{+vw1EY>7L&^Vux_X{nI}Y*abSks_mp(p34`&i?$}*ZK7#6JT^JRZ! zo8dlxoUQ`zO8R~<2zjY59&?|cxuwctqs4P1hbQ|~ZPXtsI%efdW@Xt{&688Z;-G*o z(4QS~3TM#-pBzjs$LV}nJ^%qf@h+!IsaCX_$yO+rNid#C(G}P6NDGau@fhm9Pvzw= zY~u1&e@MVmVJnU}8xkAd>;Uf`d_`b5lbxNd7DF9^JmV!f|M}r~?Ab-S_a~AF;7(+R z=~VZYFyficzQkIov5~xHabdr&YkQgGu|Out3xcbvS@qRl7%l%6obfG<(6uPxuPx_e z!`zfR@+4RvD5Mc0BdNhj5D>MaaV73NV~ToC3r!4-Ri+n)&*qtrVR_yStV>?OS~c0cP=k%M!2+`oT1GHLCIR-{kCn9Ua+?yJV(l`}TvtEMd|_!o2uI5Gpv^jV^yP#(lrUPKqhz z77diEIqI=sBWk?V#VijvDUn$T)Gh8yW1yN;?7jxUR7iED`U0RDAE;5isn&{(zj1d{ zV{X$r8r)aAi+3L-Sc5Gp^aqQvRu|?ns*x;xVqcqk6YLPH4&bDP5y1M8TTCpTS!Z`s z($3fwvBwoNYFGA42GL_;qB7XCcQ?rmjdXDOpsNnD3p0LXms*y5E7C55jQghmkxCn| zDYI8zMB}{dSEmp4q^f12BRCDId#JQCwD=N!1}ZCce>|co9;`9XXlq93DRBBZ(wMJc z%RD_gmy2Kd$`X=Es!yo)PBM??%uiKJ@>uM=Q}?#-a@fu}^%xx_J(Avn z9CDK+0>aEp0OY!#FT?H#f498mwY>1e*c6V-l1k#tdpbj7CRO_0_fvI+4VL@wCmMvz zz34iXdo>)%SaZ*SJ{_s(5Cxu(;|$A&EBWq??vY&^0S~bK@T~)vt{gNGkeb5#Yv*65 z$iJuKx=iwS_4b7Vb2HvqTc&hAej>}3>|p%>Jy{YHp6M=&>6w83XcQovez46_Y}CVt z0psi%F7Fy2YOS(ltF;}z`Xj5o>#tftY`vn*jmv3yRr#d)yqdX#Ham?@Kh{d}1jm2h z3U9UsvVy49Ana|35CnYMiT{AE*tjf~PsZ=rn$z!oP@4^dvfQofyF(7sWbe1+!L#Za}QiqEc3MyHx7d?YtiEqr;8BxR+P zL?GB#oJ_trKs`^4*_J8Zjm+vY(D{CdrFsqPyi1>oWXMq>AfQLN7^ZW`;0iotLqYS{(<*T{ ze5SQ=mK-C9a4hb8J*;ct2urVkp zMS?BHKyVMDedM8U<_>L+YSzCEMexw>fmc6&mnZ)%rNSkryVKdQNU^mT4l>MDnH}S7 zn*K)5i%ti9&h3= z!CAcBKG(`hjDK+C6TMMS(N5KPMD0FIx@n)jC5&bsAq%&kS$(s}iyNGEOpH%}$1C)1 z)}U3oY@ZTs*~xl8xTb$AX657KObLcqO74^FU#c z?TSobc`SchiL#VTg!e0(p&Mda@l4B%vufJUKM&sXUj8KKa95B=S-W=5&_GyRmu0z6 z0Q3E9({vAz`lb{#|o-xqRpY)VMRvJqA zkcaL@JQ_6e3mS#)sS!h^5tsQYTAYK^j2A?MRkKFfv2r+LGn*+eTh^hY5d#)jT)195ZXD$m?WiXtphCvS2UivbDEI_=-qp)pbkwN{ykIscHjq zKzw}sj&urSIluT`By40ry*QaJ>wNy(?^?u*6`^!Uu9$9%AS4?nqa zHQOur`@oe7Ke4vUPQY4Cx|xjmI|jV`8QL=@qx>?~ExWF^#LYT#H$;k><75b(>}Kl#+dIGq;G8 zo~L$}hKsC!-}aQSQLXuU;OM7s7~ypA^U*%<7tZg${SG{%jK>y?43S- zHtQ^Wz2RxyvNXHyKKY4n{44HdUkk&$F5*_|TIeeaN7lUiWNefs$nIg4eVcm9xFjk(*tmNUFt1exs#)$m z8L+(oG6y34p>IMI1c3AktYL})teriup!Wkq7=_><&{|1V_0lPrXQQ0X9522E(cMFto_rqzbz-zlX~MkwJ7Q1f;XWe&u;aDl?gW3MV&|o1`-w zh-K+pN=(rd0>CmtN!&CvO9tO48lp8r$oy5}Sc6S^V{*x90^40lt4~`S@riUkPHeDu}FDd;{< z1qU^$Udi#y6O0Kgz<=a4&|Tlmx34B_lwXn*yZ@W=7734dgq!wdR_v@jIgC5_w1qMr{Up=Z*UG!Ai_&e}M z_3L_o2^S2#S3qhrMdZu3sAGquC#0W6w0)Fl4FM0x8;*p8&-b`6kb41!S_HeUaR@3c z^hlBRo!^zE0+`ldDKY}2nv=+Q0NEWB7EZE}fg7sBv17*!Yv}%cuvKKAdbQ1|nLw9{ z$b5hb=PpYCd=IG@cY#$2_Gq^l43v}{$&Y1fG&CKyS$sLX=MDST;l&Cz*BwW4CAKeE zO?E>eU0kPeg4J-qs#O7@g8#~ra_?Wiqn2#;FaO9^KQS@o=A4;UiH}e_=KC--_Wj4o zSG`nzzZS^0vS!0x8y69|&&v*O>?lVohRuo0{L~@iJzZQqer)+y)*q?6*^SrcpWa#x zkO7kDB3z?2V60ug_8vIFdGaI$nEYHWp9ORWO+)n!iu=4%^t_2ww6xBzz&V%YDNn@o zx!4(O;6D##>Yz5N$ z>?e|*Es!iX`h1U@59@qxGAh;UXt5o(8f>oc(@cB)&j{02su5we<7>#ab0AwP3xj0Z zAF20%4wg&%Kq`n&6L^YoAUAkWs8V1ekJN!A(g=wPXricB?V{JTPwxY$ZXgR0q^);B z`b$fwB-MwJDhisd_AJP*Xp+(GA(0W7ap`?@`SNa}3Ly3^$F+=(5*X)i%<_3?DN!=;E8G;>! zJoaW{qgiB~b8tGEzMtLu6Qe2bDuq@WX`&4Kne?9TQ;8ctGS7?LC9x%mEP`2Vx=s#4 zTEW8gGGC(TBXtD!gVwn>dk}1swenbZhV{AdlF)whbh93%l*^9kwKx4vuSrP~n{0AV z-E8mH*W`uknkuy$hVO@KemQpPPQSlmEh3-cw83UJ!*}KCx0oOoykB)L;UkGH^Ngcm zBx;ELfc7#4+A?svUfc2l532&t~;x+xZiqiSz@~ z6eqaf5jLK;g3DFrph2N&J#b`E6gddozm#9*O26%PDvutcpGdoDY*pRge7QjG`BVPw zb{^t={>noK&HPPuJS|1<>Wpd;sJlta*90s+2wEErf=`3fk zWv{9M+A4DAfbqs1u-Qa`h^#0h8MGF2-ykdY1kC$LNDHckAha8-BI8ycy#8R@fcSAB zWP|`5Wn=K@C?)X1MX0bu5IU|Vz$gUv+>6Li2oh~k!X6T1+kbpGO8l8Gv$M5~JlWv$wJYCxboI%7 z7vH%7Cg2nynI+=5LWs<(E+5e2IE&x@Bns;{`*`Fq1E`6b9v}7OlSu@c~49lQIlR<@Ru9b=lmNK48Td70$sj-0uMRuU~1hqOk-_tYPp!3Ih!Z8zk|84gSY> za9fLd2+Q*?kLV-n8+bj!ENkxBNdWJC;8=Zq7$EzIy#wBzI;~ zvPtXpmgThjJwX$y&$>)0lk{gyiopJ-+zYwf!EMzBJ_+be)8Vu3vO!E?IL|USp}3}3 zF6oNNTyJ^eyq`gw3@93I9DOV{)u9iiTiGig3_g<-f4)+>bnCnjAJ1e$UHg7A`I!Jc zQ#`)=YjR3{2$*LBEQdhYZ1NASt%@otDw&f2do*{v-jP0m1}&2w&oeWP1T`;RLQlVo zRENXotWhK$0KO9lEN1aGf=$e?+HHW3;^*gQ_?I5uGngBLXXAyhk3fg2y2LTT*C!`* z*3-cBut$Pp@wGmZyiB;A46nJ{Km4X;(0=RwheQArRnR>g<>6_zr`g>qvae9&SI4Ct zT+yFBlXc`4D@MGORu+6*o;OP1ixi-RmS~%P3w;R&<#NhHQV~YIWlnd{e)L!s zI)p?Sw&E&~wy-(l$PKsWU&UPNrdsYZZQNs%G0}bG2knU*xi-a&P*z}bX;X_q-Xlch z>_ziMm|wYr8WWi*Ac{Y-kEni~@!wtB*k1Gz3Nisxyl3qj;2;P$#0t1qDA^olf=1&~ zaOjf|@Erh=NTz_vGpE(H5Iu%o@brw$GbQcl0s`l>H^tTIv*x!;76sVuyc-_NykWyz zt9B?^%dSs^i>u0C<4g#QEFU3<801t2qkrT_1&S1y6?-F|A#Lsjz?Apn4elNDChli_ zjpg+}fAD_Uzc-7t*HGq7qB=?EJ5~DaKUf#dYf_BFQ8K8rp_Cml*MPhBG_tQ%%JPdg zp-1xF0l)*=1XU6X$!cAqg54Y2)Y^DSFfxC<(|e$2C8SrxlN-L${pmHCrA^cW-A3aL z6(zx4eFCsO#+I5mRDlr!98@h!5Hz4H6322x>jT9Y4rFlhP&uPR7z7KJUB{MvHDR8p z3VzQ}Gh-OY7LaJo#R8B8xMd;05d#i01@W8@M5&ao1DAPZem)v@92|zoEIoLnnuZLA zgD~M01~%Ce7%7dyO@HtFdgwOngFUV1p|a)`2vb7AJUg#9I$2lY{!$2&c5DV52D$Cv zpvfHTK?|sl1zyY&y#FJ)1y;sx=pN{cAY%fkM#G~dJ%(0YVY!Q@wDTNtGfpX7un4)(b7Ho$JcUqn?I=tz(; zGNgOFgV~e&-#^}g@ON(B1slU{5$rcsw2_rF1kXU02L(`HLIq7;ae~}?mygrkt;@R& zdjrxVLKf;>_%nJnT-iJD%Q)T`2v{b}85&{E4UWsl{-T1IP`TU-ZHPPYYBHc@LEIde zS>A#!=oR}K9UQc$ZHP|0;c<$`4NBH?Lzp*f?8{vZ5j0%$6grITCh9*bfo=UqKN4R%?s-i@ZEq(e_ z=CgMM_0$c|Dj9A{90XFLgJQx1VooWA)G-l8i#(iU@E;;A&Tv>xfItP@y-Lvh?S}p9(6zX8>=&$>zWU z!A^u(gPd+Iw=dE<_*i@WTu$BJrS*5!qnkDn`7tM2{5GPd{GVP7KDJ5Dj2x-iY; z6SAWaFo7~Bv4P*9+>Y!h!U2H^wsG<6qj1;)MvbKCMjI_`dJEi}^$O*q$7G{5+D1JX zck0uJ4?Mqd8iJ}^uAqxwUS+9<6~+{%arm_&x(2i=nl)TXBO##BiTtq)^Aj> zdVdF8&Z{+|dLfWO=4khB?>cWO4l~+Q6z~yL03dXz0)MtOZ%987g87ANiUUqR*N!ah zsyH_#Yz_&B`f;rX;fMG}Rk~?Hn|T$`P52TQ{}K^4;{&f z9ZrMFJ!LLYacd|LiyI<>BH=Pw=yyTS&`d&$j+ULUw^6;mwoNo=w?$IKi#HQhrD1Cw zM+FuLJ?E&3Nf^CZ*{1VEo}OzJ^-I4!zly;8?hsSHSpt)BBuRdIJv%+w2pUj%mCr`Z zUQ6d0i(uoX6#q%kl(aeAUzSpN%?h0klE4Gu(Db^ovRio$%4=^p#?Hfn-+PK12m3 zZc6En!V?3@kUoLMI(psGj+Yk_t2rQ&PWhY_=3z6&galGdMDFIf4E}RWG*NWdvR7uz^l!2U+}az0kp<|UMn+Eh?!1~O z`mJHFFelgv8IMycI9~nieQ4vGP(=>Y`o`qZMXwUq?vvn8iM%|$y}eOLMmKTn&U;df zDsOsf2E3E|D4N88EPp4->Tz4s6wRa0;Xt#NWcIP$cc})$Vc10_d0jLYCOOU&@d7U! z(rHTQ$%aAaw;DAT`Tn78pZdf?BQD#{!_F2*7cP8J*$09G;ibQ=DtmhqjqM55AGeH8 z(|lV^1jGSWhVvvhrK7J$rQ>Nf#fQl@?6QYO3U8}fZRQC;QL3#pog ze4a=3;Q`2Zk_u!B3*hcrzEnJCo1F3aXu2^K4b3|!jgg0z>I((*=__f3vY~Jkxw|=A z_@OEvBA>$qNxo@@9hp^7L7(0Snoi0_o`d4erz`6ZTrN5tZ@2X<<{UGh(U7LkIxmW$ zP)w{pFy~fT+r`b5>$?EaSp|KMV65|XC}r)e5f_*01zuM9L;8_)h6IS1Oi?s&fBpz~ zI`8-G@z)P_4^#O-XDI$bnE$0mwL4kbH_Et+q3ZTK)4vm)I);t9=B_xD%bqyS)$|7$ z$|HZ;*TX^5u%97&d_-A-N;tJbTdgV9~<^#rMCj+cv9CPvy5^xU}WBV=YU>CA;^SBYW?1E$YWZf;WK3x^yCq1&SXkmMl{TEOOXZ&=8J z@9xK#Hd)v51QTi~RunDEuB|R1GZNex}w2ey;Rfvo_w_^~V%4V~=*4UCHyV z4)s$w@laaLtW{8jzhj_afyV&UVLjjTgjh8Vzutpm<=zQ(i(tw}Rr>|}pQ}bG+n>2) zpii*leW_z`=!ang2%e`-MH!J#HnlUis08iTUIqgw=cdx2topBQ*euIhD3rQpZBWJmH^rxEXZh()XiSVI zDQHT%&zZe(*?!DAHLf%3?(Tvom!e3KJu@%!R8P_Cv-|naTgh+#=GIlDOZpH8+(xKs zH~E>aZ`Vd2mwkd?{N5@oL=Nh;k2W)QqPSdp!;0Qmp>JAl2|4`kS|^me%8>aysA$q4 zpyr{t<3aX->7yt<1`)ClUmWrnRbO1#{X7LJg&nzJH#pOSyTk*Q-*A4W%3lD!Ru$OxIf*_%oHhwRI_Od-M-QM3h zCQZ>n_s^g8IL^G;ZqY<4GvmV`XCs|tH6Jn9J6ubWKh`yM<-*GHU9lf)Q`|X*>y`#T zyv4}O?jl-KCyy=YgLqt2!W?ON1v>)Odj?D*TfZnbLxK0r@&Q#(c=nIMVk=VQPYSjY z3}89f03GoiKz2#Mi&*C)Xp$p<>n0_1@gFkhzTSodi}#93Izu`Z`D-G+7ngG3xTrH3 zJ$k07@0cn*Ni*N9;bdNO!KR7=M+gTZ2|%%&5I+m&W3Bh*<3ZW3uV!uw8!4<|LxvzA z`XT;$xu`bIdV{iIO8dgG2(Il4t?iw(ca{xLnM+w$B$pwTh@a6iC$phEt9tlgP%sJi z@L-sYf$P}%2aUvN1HjLo@yv=Q=@Es%RPw{~i*bKy@+Qu(S_M6oNhx$Zn9&1sz=mVV(h?ih z2Ep3l#&8mxld`m9n!bOEP|595nl9!1R?+_asRUR20DKg7Z22=SUGn^qa4KXU_J>eE z_qCr!fP9dHu9%*z{u3`ONY+FbEh}#U;x8Y)G(~>j$8Qp2WMK`;nBAH=T@&CdG$b0- zS@1qsSgb9dw0EP_y2?^h@K5OGNRy4j*?>$d>2s6J;4%BP8)p2*RDH=)L7S^ySzgi` zP6tcDLdM&%g03ymnqT&e_!~35ibR8ZKO4ICTtCm18w|=05tb-KnAdnL!t4St2m?4s zhbYuv;o5!5x<&k6qFr+)gH#`CppW9os*!#z-r2K~8(H6Qtz9K8nn9i?4YwGl7>*;7 zS=$Gw!*7Ey0mWoSYlMYo8v(0`xeN;GKivfwHTFmO&&Wi1;8u`O-UnvO)B-JnUfh(3 zS`k<4PU{6(124KI42IT3hU@7(3I^8mgh_2Hvb6W5!^zi12kI~N+8o}OH8Ikzag%l} z@R8KAds$tz@qnhkG7vNH8pt*f`G`S6F|3@kd;4VM)Imo(y3? zQqQupUD)Vg0T`(S?Tt{2irp*cxKPDxN$aw(4_jYVSGkedYuRoGbXoH5txEG5LXVQ_ zk0BnJxQNN{KkUhXoNy`D zoNp@sYW=QIHne|-yLGSH=u%$aTfO#&?QpnxF(=;~4;|2SRv5C3k* z-8~SUHqeE0B;uHI<-G;Uh~KL|ZuumIkZ2Q+(YwYtnl2FmjYkF`kneRTr- zBB}utu0R^A0A)J^Jw1Z*K<^L!Fs(Dk_A)RS#l7G6r?+O434>~Pn$0Ds?(eGC=edyM z5!U_``2&oW;&BY2hwZ}7Z@WynFC_M@`>MQUY@AH;cK7Jx;naP&TBvWRaz>)2p&Vw} z@rTsu$tEFL-RvWd)mN(fW zDMeG{=t`QgYsQCzmXKqperuz}S=L{p#;NPllNeC&RJhneA0@sI;G$bPIqv}OKxS>; z`#~G)ROXdO^}A-HqvEylhRwppY`?$M0ZqE_iXRZJ=jh)E)n67u3KtZUcbUUvTLZ3$;m*6ZQIMDMy^zE?7AiZ}dD3Ko(1 zLxzQK?jK!KeEeG6(-fBZ5hMV`Al%uzTe(Ab<8~v{I)+6B2srq z4wi?+_LNQ1?OAA>1U%}}+;VvTNqpA28Wb~>p50+_@IQVwrBJb`_|HPJ!(oc-c^b)~reayix%tZZ3-+*~_5@TYQYvO3+c zTSKD_tyfn$M&)zAnz_3~wHa|3kh%$<`d6rsmjLSScNOmkc!c;LcTsxJnr9~duoB_b zvd-P%znAyms#wgoSSib%o3JajPmsj%$ejpZePD8R2lCI*1bMI@< zABb9%>~r!(uA#~hx!*M)A-70z{!RTNLT)Gp4BOK)goMPaLOPCmuVMzsE5xti5;H$1 z+)>#pPd{R=PsrrYc}gNsQ-3V#Z(y+jrB7MH4_)RkH9o!=o9ZhH}ANAx1iz?C@7vCRMW=9j4ATZ*%(m>_z!8Gt7!c=8xafo zc#@8ke*GJ*VjxD^t)6{P4tKA;nV7Q9b5aB}H_b{Vk)EL^2_*<1z6sK9c+Cy0?tGD6 zSj=vD88v)0pvAW9zhc`=c;xZjU{{&D-kbdCR|v_ZFn6P>Y* zzxm%nI`f|wlIvHKvLyKS2?t->|4unQ`+|}e-RZ#$O+rs+L*HY@rWkE=wIdR2MG4!? z6DnR+YT=`=FI$Uk8I~JPGFZ-?GujuIpp1XBN3oQ~%?)!Slh*9LIexZ|EkEe2A@9&m zV4uT&ONOCj5IHJUk%e$l?*6KhJVxZA44K|z7~)0j;uXNCAF_?^w_G|Izak%=^^!{3 z>)v5|4GL~nW;+srZM8YZOd5vJTO7(j^0GQAX~{q)uOw+;?tdH`xy|Yl`^4suiqz7D z`Y;_8)fcr6T0Dnnn!6S2u~k6{-7`kV&WKrLpEk-2 zSHb#q45{zjx}_k0Diq%1e||CSP5*s?5&n3T)#I!s&iP2OT3?G!l5{c|PG5x1(0N#x zswzFq_!I8ZJx-e2qng~>_c&k9-dc#^q~xMuWM=lQVq#*t7`!)xGrT>XG9<3sPjKwz zFH_Ak60(Qymf*V|<*)x$su8%+a`y^ha&Ya9{@l5bc6J$>>fHx3j;&~43ORh+DpokK zHyyuW<{V{BW~GWtoH%mu2Fdho{UDBB&a*nJYEw-wo(t)cEx5ezPS?ms z6DJ6E)N?&cM?Hyu=1QOaiHkJ8&V_L*)4?%#S8ZF(!2{MiSF#bfQ9DVbbj;O3TIm31&lVi;frm&!FnU{tVHOMgF?R!-6S z5*a=36^iuABYPMZnETdG^6@)Pyp9Vv(P()gk(0>Bje~prKkHJ73Z7Roc`wos52Dod zsAFGC&jv~_F$knvs&U-I_)k=qVUcANCdmTbvFIZjik0-7dX|<}|9#EC%$unNrgR4M z^7Kl~7S$Qwfbc1^kLAw}z!=O@@|{%1idoY(!9 zf-csKP5UepT*Bi9!P74i3QlMqnsg&3Ux^6i-uG%&n5EcVO-yn2 z)tIJvVkmZ>!T&|pdq7hi|9`;u+B5_4+l8{YCuDuBvl`Sd6rAX$r zD-C2OTV-U+$a>!2e!t)UInQ~{aXLAN;`{xK_xtsJjdP?HysB9`paN&4`MP_QX2T9H zATZ*Z1mmSHnAQsz^8D{@-x8hu&pM`$F!`p!jmP0ZWW_Ct3HN7WZn5m;u9y_yc+9h& z^OP!*?1a#R5Mr_-CE;r+BquT+ea#PwhzBQ|F&ZHqj;UD>@O?V!j+Jv z=C_49Zex9SMkP%OnMp84Lgq7abO|r_*!RLuQvAo#Qn7NTd%Ga z_kd(!kXM5UL1Cc0tIhET?>^prYrNcPgp(nF?8wUKV*6y&GM<8eUr~2f8a3 zfSWV}1C>DT<34D1E5D(E`|Qn+1SD7TQikq-w?aDy$-kQhb^^4GXZBSchn{5|23~_=Wb7oD}#%ndqk}b`{@7$Fi{G-|i@0wW$Z^yD+%i zxjxl{H8@xG+T83a`@Kp{tJwYJ@}RSu>>0W7E*;)G*ijuNIZxd0?$wMLv=;pWNz3Ja zZTgxTw!hKsPFLUQ$G6N!nlcZZv-7g3a_(jppcs?KYCZu5OUG24u&4zynl4@T7_nV zX+(~Ww8+c59lalf;#aa6-LgsCg$zwh!a!HX3sBtc?R{|ca0dfOBsY9#(fTMBjDM&4 z^du7u)BbmEWZl-NCN}l(sIq3O8OYgDQ@meX{Y+@idkA7d6N57#x-rQ*MmmgWou+`a;Dp<%6)3khJ?FKz=XMSRen zPtp=X_CXVqsT6;;nd`|%TK&;R2uK|Yv&r;%10a&}L*5X+XxC0kRmT+eQY~W($C~#Q zxtZjs9ml;>nJ&pJk|P*$eX2z3pgv+aV9rPzX>*Q2t)OyOIufsI6=IaC$;?*G#&G*# z!#k00-1y6CjZ|dO19B0D1=LyW-KT_8^fINis7Q&k`3&z=lN|;deRWoSIeGb7k4?6z z2)n(|97=`J{BNkpv>x-|3F*jHiVk{4l8XnMCKf?|2C{RS7fMQ3!LgqRRo?X132dJP zzZby~@^8(#lQ9j@VQ6V-{dRw3*hsNA)cla6^Zo8lj*+RWaD)3Nn#A%wx?6+-&uAb0 zD~^pD|G1z7-EAJ_AE1oVZ+U1TcYq8^ANgoR;!Ye<)e(4 zc_=+LW-Y8S#m=(M(LvDB$apAJmzNY%7M4olT@YPi9eG^&cu8xrE}Y5XusY!P0PFdl z^sLVXF-6Ko#jWsONX zwx^^oO0jQJ9coQpe!GN9S zOB7T#qYQNDbln#OmtUJLDUwHoCtQg$A6|Jpm1}krP`Ll2s9iN5+wj^o$@HWK{kH4C!!-Yf{L7bl8O%RXQX{aeAW|btwf)5JDWlx&XPEIWTW~NJ7+2RWm_Fvor zu(maKJ`=TA?&n>q%V7(-$`KTo$`)aZdca44|C}20t3XF3LLupq5W2x1dJRZA|5>ij7zT*MquQE@m9Jd!!hxc{l?AR#H*)dApcB3X zg;nwR-(Ub1%Dw$;;Z~gcgZVN%%zBtD$#&6(Vyfu!`xr`y`R48b08J zFp?2V<9T^-T!jD&#G+hc;uT1UAlU5rm?yG+VI7YwzlHD;K5!`j5C93-M(A~L?!2kS zh_hnEKc|*y6*hd1J~aN0iN95IVP@-(-d~GQv!I)3l)h|kC)1N$H>ijkHl!*hlu#;H z?$ELx)eO6gdU||r*$>%3qqIsHw(r(XxQxb_F;!wIB(u(reyZIQ-e#MO|ID5+8aW|! zp=o#T$yg1~V+Cev?b8pBPgEaDU@$|%guRo0+QM#K5V>IW+J@nAS^2iQCzHq8&Q4cR zSJM6#h0~2YmNlPZzqF<@{)S54^UMHd>RE7{I(68Hgg(F)gm{_I??w3BrCPp3D8ti&`~#Z?H4B zs_i;Deqr5}Mh_CkhrRrn#uZm{Mr+>C)RW$Fpc0N3yWdq@B*`z-6(5#}`Mw{t7e`&r z8+bv;!GH+$yL3Ei$fx;d%|t1=MZ)dIXJ}MnKTiv_qLt%zUD(Wn;rioRPl)w`#oIjD zEU5YRJvGeK#cVw;_sn&ncbHHUzaZfbEhV#mFxR$I@V%PL=G;dHO*$SBG0Q%!@zhX{ zqm`CV7u*2Q%1UfX5ef&|B?BK_xpb1qPHBQXLw~AFZmO# zm?zCgBq(KV!H$Lep%QH30jcc$?YDXiT=c`-z4kTg4#P3Gwgb^)==&BQPyLDReTAvK zLrW7ifd0e~G4RQ-gO{N5hrD)o@3Yzm{>;3d?1T@`#!(Gl7+!ho9(}?jFb0(PPQMJg z+hSiWAXJRjZkhbKl0C}j@tMKpZP|o_oN`i<#j~a8@q48V$`w&x#hq;U z!stXUj(7Bkro)7y^pyD~$2Y0QHN_rt<2f3ZF!W(C&}fjUH0d9 zbf2dxUs`=V-0m^CQC$$kJhTHZlmiaCa3mT$QngocFG z_t^iw4rqAeBuT|ZjqIszr|q4j$I5PbTe$8Too`Qll8y}?Z%_QdBQe_f{2TS)u_2x< zIae2X*h_Xd$bU7|F8H;%C%KF!y1Uy|cGb8TxMi^GDb=`C%Qt`RduE*Eaz*A>1nS49 zAIC>IU+S;fJLna4)dX{Fvd!Q3zEj;*ldySC{g`{IDq;^OSYb9~nygREic)U)b_aoD`stXO>yf%6~%A z?3gKV?y@9G-?uo?GhFmI9zAR>F~ObB_%WmA8aMf5mO%Tkmg%+7mp?Qm_7eKJdwsZ3 z_v1MtRVyB1xNntKR&4pcIryunJ&YkYcM(6gpz!;}2;?ObKR-vv*Fq(Pd}0uGx2>?QOJ=@Jru@UtU=nJ*7-|9QTzP-_%q~qd{D?lQ2^UA~JuRh_a z<+VHv74AzP2L~Q02VaD2p_Q#anVEBMF@QzwlnjW>7;S+WssK)qk%E2E85s)oWM_?}2N52SAp#1?Dl>8y%Bz9>#$? zcYWX&uvr<-{@x0A?qX_;>#X%{pA!kKy)$d+__}tyyhmj8ZvEJq->ep{K0Lu?_TS=2*=Wpq zmY+5X|2&qJG~Z}ZvBmK6Q&H#zZmO<|f-mSKq!S0T0hgx>&QG?OpN-salh`0FN7gz)1`O67MBQvd30Yu}3B8uq~~;C;4P1~zP} zs{Gt;DsNtPYIYH;bBgI+?O&OE*s|p0J22Sd?zbCNDB^mlef=)o)Ih0rWKiPHo@9g^ zW;|RcwNvNIu7bAXHC>#^biv0xcb|!K87_r3iI}zXD;8{G?W5J%0&@3@W3CqjQUE5?#!Q+3}whMwG?V1^9t>aUdx3pXsbxMJjO4Rnad#{!9h z`lj)23eAZzo*Dor((!O5=#gD+?>{U*(mu!*Xx~u{_-a`8_=0+DbKp|3ot%|Jt2dLU zbjfvN6;BPFmy|vxXxHD{?0;`U0`kvoCU3u^Ovbb;H&NriC<62(aH&%5&!xq^AN2eD zIHJpM=ncJb)Xx=GwG*WN_7_ER&5X_{gMQt#Pq=Pxkv_vt#DJ6c+vZ;2g;QM9_*cpx z#mD80k$Qiylyw7HuUcU*AJE5X+AdW{)2I`P!y1>xaDOh94)Y}#2i)dRD!}M^5U4`^ zTF|BMd*!E3823}sVPZTKu;@#sF?1LN^Wy)D41Wuyp{wj@+7OP-?)^8!-*LE#22QBUbw9`v8MSk04phMw4j>~DXKwXyQ1-oh`4>xv2L z5w1+yjzq1~+D6C;A<3(s;X8Dkh3^(GOY-Bt6jhLe1{BysSCzy7` zm43VuC^nMrxlDb}t0i*(lO+l}Z~bbF=+f9$CK7^pU}5Fa+8cx5RT6(r%npjEeQk?8BT5 zwphYkgVNRAnx`1x% z&z;nID!kzdJn?1oPO`klC#KJ(sv0n&s$}SND>s7EO*?|SO6KR4fTyZ%gp~84^eP1@ zY}kSS0HrvvW19iP{5I>ub+(lR2aUpB#Fr8AjsogGEy_)f8~OWk-J(Rs$|EToBIHyB z!P0gAWpElKgi|g@h!+(VJ%9NU@dTe0&xIaZ*PXW6GV4*^hDcLNYW@Y<+5jiC)xo?R zYj7nm>HHddmc#0y7KfXhT$bykrImlt&We5MwT-TL@vXUwZ^vzaEXMWLCYCH^b0#V4 zbGbLvar}CZZ@Aeqrc<%lKnI%yg|(A+yxOuNH)2NqkV;4-**h+xLVmErKUcVnOL)+2T8*SuGgZE7Y-84?N=5grs8_4vt?HOL&AuIiRh2T2YfRBJuz$MW;?P|*3rzq=(! zG5t}E8T+F+a%kXB4#xq0#{Pl~+u-!KVArlF*(B|wkDq&QdzgH64oUcthsDt}9_fb^ zJW1_XUhO+m^%`@p(jaTF8dVzn?D#M>ce2i3Xqk%Nk1jjE zgI{*?A56MyoC;iP5Mjzjr0tpn8?hniCfAi##f~%@zJheix_}3nl$W_ z7ySV%{7?C+=2{p3c)pYCZu{f&cla&I07lMGhxyQ%kd9;PD+%Gmrk*`P9a5|!BtsQ9 z2aigBsfWzr(#jrQ$E7`=?kY_t!9eYbcCDKiLU`m1W?Nv=8H0@E^fDwmz{?7m4?`w1 z9h9^v93r{S$k1DY)PiWRu1x8bQg2q#@P<9wiN0 zjD0|zj98>E(Q6E8GGdD&U}$_*3UiRr%bt>rGf!plocJDIv6UVX_|_qzf!MIliaf3F zsLfRWO~D)s7T_mmaR^|%R^KG!fjy>r$wVUQffhhfzEeU)x6ghKiH+A7?@-hT&F}v5aDD>)1@?*J+A>}5*cXp}6){Va(9TRSU zp2yg3<}I|cw|vEw`;$iH=-R@~kRoyes}XM_@aP0IVm^{jZ;hKSo0qiJne- zDOI)RXls{TUVg0Z3)anzX2I-4sNu;KmiGn3rUG2!Or8K7gkWW!tiej30^`(nP$t`t z)@-NMFV}Uu%uWL1PvL?rlEUyr_KU+FSeXU_>E9z=8*0czepTFn;zu|&c<*klaCJ^4 z9`mu$GdjI|=qNkL^PFJvicH|-#dG{$Jx<)mYZoj&m$`e12ykWq+SkHxdlYI$mrO8Y zG;!H!S&c*;bMS-ZWAjYU;43W*ThAxXtS}Zg{4K!TB>ZVNc~~OP+|s#4kCG zeWvn@Y3X9+{3GTt_G-qLGOSR08$Qryo1-5~y_Fk;L^aVPak&}4z%ZA{^CygN|MOB- zH8R`@=9RXj2;Oql)YKM)i-=dQ7ZO~g5(Ey4D?5=5P?3fTF&XkydU zS=>p3hvDoF!@r{&fMv%;O};}s8{+{}iF>No1-Oopvtb7X;X5*i-`wTZif2ay!UArx z>gg^4FhV?=Htlr3emFHiUqmPN>*R!NV#nB5s=TXGJ2$Q6KL^cU4-C%Z7wl%@!B^4b zkcuqR&rBDLp!K|bj8Cz@aSy&gqaZkU6|X4AT|qU@Q#*n@HF_-i^IRvE8&8+cRr%&M z17{jhlC=`WQ2Y`p3iE2_s>;DV4}!4>`=;*C?X~vkW~?+-<$X#XZcuGFg~a^Tr;?6& z`#xt|C)IBEVCgR_tmx%Vt$b{cK{V9`jKs=CVO6h_Agv1lrZM6;12YJ1V`E0(1wDZL zS&+vz?*+^x$Uex(AP4;xlEn(nS)^ybzxroB`zTP5yH*xDBo z>z-4zeZUtM#t#3$b0pDAz>*05nt_{<%X*%0nZ)MCRbA3$+SgzC_ zgjw!vC)i0>8kCfE1B6D?B9DDkk0UlMh zRfH19osS-_^A27uXn1k(^#Nx^$9JO(YYPTll|^{gPptLbJL(3R8X3Z}GY_9|$IV>( zBxf`l`f88Nq9(i^qimGL>P%u&&c@*2!QI@vq(_qfzD?m=-F3#T94Ero^fz2q7sd2t zmCpwW00596*(#v*kp_3n25`{Hl=l=uoQyX&H}#ipn42RyW7z1&V2fK5g2q87iHNH3 z;LgELLx%X&W-9thfM1Z{=&k?l4mGQ~co^T8b^sgIesSfq;!3+Fn`Jn_gzpCbKhJ;c z)khn64cR63?u0%;0i=9lLAlUb2a7KN9hylF3 zhV^eS!{xY+Mq<`U=5uNNA7BGV_cPjBC}K$$=zIXDW%(%>U{!p;fUWkY$0n>~)1ZdU zne&6JL!*fx%5Qq@=P^i7=67w{y(x~tqu_W)o;L&Njv%Ci68nop1rAk_WJ2|!f7@B4<}yp9K+ zrwx=a7pvc3#DPY-VzdliyRNKSax z_WaET9Y&|**#mKYBexc(*IiLhgW{H)3^5svN`+M;k(I>%CbId(-5T_+U@5J9u*uYP`1cOYaV2&q?*Ik@ z7|BkVC`0l@E0Pq3OcNBc?~-pImp5d0^{qSx(nSFp&^)$q;`F&32TI@%Mtmhm?4RrC zX3iH@z{Y$wPu7U%d&rG97XI+9S#=~{H-L&0ql&v$$2upkH|PMJ@VgefqzjSA0s#lr zqFKUyR|(H z6k(1R56X}w0S-8wg*cOhImr;7U6M##+Q-fMlq8u=CZTKil!Ql+(G@%$<{w*V$NT(+ zmU|5@S1SYqYhRM=>2Vz_o9xq7yS7I)+OuJyvsM_Q!-Pct{SbcX(^E|K^{!X5a`z`1 z%RAW6>ELVDj-ico;KIWVvq*P!@*Cy7`=(mS%wWO&M5^YB~-wyPRX$| zV@0C5tbz}`VKgCBm!D7Y)8Nin4Jy}#TP0yJcDc7M|AF5akoSxd+C z_bJI(akh6}i4HxM^f!(r@S)XnhMAe^1`3bAw-)k^PGQfD8d=z>t-K}-5%)%%8jpk3 zMeF>%hGoOu*KQ+a^n&uaCv3?)B6q^uT6RzNzoM$H^$hN25};T#4`qFh##Ihf!^wTR zwuBU~52L+t;PLRur%(89pA0nwrasf!C(h)A#-aqwt3u{rj$E$I;jDS!S_CMMhqXE} zO;?Lzmgx4qYN_4?W4~`7=aiaGzXH zzyHi2HxV%{4{(K`B*garIN0UsPm7^?oT^^A?6xH#E=Mzj*p#@N8lQ6QL@kw3YCH*4juv$Ejl$V5%pdO`7_cGW(Ahb>@J}x+ zEbtpLAR7eA0L?;_m{wtXM_a&T;ZiXkGJ?!VFu)6w3#YzlJWb>|u|&lXKHh$oABrON zDn@+iQ*?kHS11#fa#??wpQ6Z}+OW1}g?Yv8yr^vD*apC7c_w1msw$E4^Z7}Yi-*Qax7$FO2eTz?CUvuZ-$VsI@4V(1Q_n#@EP?L3c;$UzNa(+wQ9*~j`{(4dYQ69)04bFfWIiCLk zafB{s(i>(sZOTI{`g~x)#|5dXpq+iw4dK5KqTuKY_0pXFIp^PTkyl8|tw*ooA`^nz zER1$;4-d16<+`7)yE}XpSDfLkXoiC2IvnFfUIwZ<8?bJN#O?JL2cU37xC3AiqS&5> z5S$o3{*Y26As08&NIN^a;`%y%gYRX;SCu4F`I5!(7#32@`X9;Iw~q_op~X%y!;7HN zWkUVqOC2a}fA_4ND~MYKltWjTzQ%bZ6v#JINZIV>4X?B}#Z=M&09F&ZvW8E~Be1>!sFEkng#F(2G&O9VDhd_*hCt zdBjE0+O00!+lxTOA8P1ESa>uWN6gy%-JFA;0zJ8Wo7Azo(l2;}vj5HSYVKHZuWj|r zN-)Qa-uzhPdZ+2W$7@cMRB*%B^YeWSBRfAF&o>Qwb8ZJVkWY+l3%A!ZNcmhltjVYU zQm#mYW4ry>Mcm72WyAROnSia|K1m#rw}t6k7m2#6n&Q0Jz}0cFyq?akGrk4f+SkBt zvd#XC4IEjJtWnX(Ix;eXftCHlQF$m&>irH@_0Rs>e z#IJ%2ISyzJTuAcc&f3fYFC=P4FQeM>-R*+Q{A(H~1Am;Q;gsEqvRO~2U}4o_r|ZtS zO2or>nNx-(557jESbIfN6kg6PDx=1sT0l*HkJYoif8WHT0*Q{t#98Aex<~LfVG}DS zV4;a(?D8zqGC&-RNj@`aaF3c9EA$m~7)YLS*bn*Vx^N%X4pVOJA z5uGI`XDw2r58sbo3wyD~DcBkLIYNfr_MC3~C%w+jne#hKm@BJ9WjC$-QWz^}Ym=~r zo2{yG89TK#(L`nH4qBMsW!lmyiZC9-kV~pX`+~5x)^oV!%pp-~=%!!BpFjF>;Hx*Z z^9y%!aQZWv8U=VVQCCPx-Q?B@`NUL<*6-T%WPJKeB$y^SEQjsR56(|HmLgUZy}fNi zd8`o$RGOBE{7C6w^J}t17|IQvBen9k1oR_+I9UMp=&aT(-AjA7Gv0u@^Xt98c;-Xi ztJc6`)&=ggC0{81T6EGz2fFmShj@zZ!1KG6Q-=3a1>dbl-BiUq#p2{-yJ(=uK^JghDi3btRsf|9s-D6{yyejC$;uUey|ZS{l2h-@UcTEUvp+G& zXd(BSTxd&&);FfAO+ilSZ|(ssiSNlHwFg;eSL}ZSf*%J+zTNul`#yx~q5*EONJueg zF5gugBIrHR7)w|$`nmgp3%9|qvr2y`Q3}~~h%5ZK-wbWD(@EHpp9S?55=XzxC!}@n z6}p3yccrfQu2@{~qa^LR*Z8$}h1@9C?wr{!?8(s}5=Z0|R=G-zkBy5vxNiW*in<}F zD>R0RQo%aek)yQ7I+_HN)%c1y{k}@iSZokd6Q#4OX0qFomyrc{0q&5pkOb}xP`AK?D?r4jNV{Neo0I-eMyw+uj-%%Q_`YP z^x|aCuoL*nJF#&0GsoZZ#V5l13xW4%JF~{AB$Y~nLG?IS+TCzJjlwSAyfR#bSf5Tm zc5hsrs$o>x-@O>G&7rn@MRDQ`TVh%UJO-hGJ2$j-h)_tF#s)-aw z8j`T{RWvn8`@VifS{x~wne`8Dkv4>?-bHf{A$|qdb2TZbIKG0Ia()75dMZUET3_~c z!3Rez|4`rj7)7TiyFuxB{1n8@-Qi5q$Bh=XuwRoI3Q&tz)m6Ih)T~bPH-0{7vVhGM z5sELdj=Y05&6&hqyHizAIUsbf>=)|omLiZQOkQTuf?l+Lz!0uAC2Lr*C~i!BZm{aJ zJ?Y{kL8|F(oit4t%!;89K3DVY!PL)Sop^lwKrLJUTU+P*XHb*aw=j@Hr}g=+4Ldf;}}K9o#)NSW#8Q2#Q8N7_o3oEkM;7ZMgn{+6i}!NSD>Llu;~q{{Fm9Y0kA8 zt}v*U1Y3bCPQe667s442)t2~2T*byDN9N}}TAIY2B=*mT*+amrx=5wMRmUGY#B(R0 zWboZ^5+#h-@o?*g?=%O>5~cgSqJC1*Ja08|kKW}G283bgfgwr*+4#5Jw%u;E_jJpm8OxSDZAE8mF+|6@`+QQkZ z1qmKe5HX^+kG7 zo)}Dqo_NGQqHKj_7SpM#9k(|3)f1HWuWQk~d^e0kA*A8xUiS(K-API`2_#Z-rWH-L+w zRdbUk0(s*09p58>5C}sKIe;?AzA0eeN|{q~X+>?=hg)fdnBB-C5?6SjPp`3={N#yP z_OQaeb-}7vui%r><#dQ7NEJ5Fs_k2jvMLQ#ll$c;$R-{dO;zRtjNgLva=sMyhiNF3 zoH2t%e@zxcxXNZ7c6SLkaFzjN1vQ!;lp9gcWEjGid&uT+*9Lp2#1?T-jG7kg#aW#p zl`US^n%MgDjjBb75^sB6^y&O=(0HnMNEdx9e>Dl4giQf)M#s-wxhwI!%!?bOMp-}S zw}+>TaRwTISYLNLMZFdL=dw)~r4{bHknG5vQRP2+ZP#wCspUjnoDim*s^iRE5hXC|j*%&ppJMVfVD9oeIwC<}n-QAjj29-w1rQnd zbt54m0SqaeNJJOLMVM(AMIs;Y6~v}i3*qVL*38ocEn;qx*?$mNaMPkElOQ;8U1uvp zExxp-mcF^0l=;U0><7+S7%Ez$6Hb_(rd%V6IpMrDxh%*Z6Ti>>YMRq(6X0j+qSgb- z>@tn}7bNaT?e$lPkeEoVE*wvL^06M9{hT&Xx$hNJ>vtWtJe^BO(Wd?=B5{M}u4&)d z3ecUCQ4p0CrU??ND(U8rZeO-aF<7~`Sr9S@2F>;^)K)u(mncf9X=MgOU{D7Z(p&>) zTL;3AN7}dnhgXNF3u1=cNB$S2h4(%j6a;NU` zx=Jz|WO;E%zSkyHjbUkE5%be%0_R&bYbujx|9xB@51x5HF|Ol8bmsjhpwxr?<18=QMYAg)Y(v})wqif zsmPp85_5I$@)QrHdj~(9d35&}G0N%j>Dr^OjXSG9-Kzq5ZvxLD_uWvke2kpcKs?;Z znHQznDt>T~`WE{gbCnH&mYhi3cP)(n0?mGhOp_uuhF@UC?%@;0C?4TOBV#Uea`C~I z5O25R5jR~ZHE=)T_`ZqDxsx(-eAkP1RytjnhcESb{yo~1D-I5R(%Vh)v_fr-&%+H3;IccgUvHB*_n* zqOWjNeI>y9$ywa^8UsD{z(<~Q#0I4Xo}bcmb1XvV+L96$k>Mjnl`oN>Zw&FW!Oi>S3mlh6`c3UM`8`wGFb z5wqB_;)Me%t5+SqM6FZ|BT!HqZXkX{fcIPG09TcT@s z47|}?8oz&wRxniRDjh~&_zWX={3&4q76tr!J;}z|8lE<(e^S4Hb4-3gAXyATY^GZq ztt=Lj(3W!8Dspa(5GtHN#~_!=z*G9VMGl)_NjsMOQZ0D;J$=A~H1B7Re!#ZiP^DOv z4lh87@w>^eYm$qnxm~LfI(PlOkjRtX*=Y4J%VXgZry;h4pO1!&7Q?%~PO<9=?bbtwAqKt=rx$}9&QRj_*?QuCrvZKx zP|_>OCWLZa2RM-V6Dg-^X702ZF72coHVtl+A3^aN+b;_i2$DVwFdRup7E(c*dV4zZ zQ-JnRB|NcjTZKrRTlAMChO@uzXxHhzX4vXzr4#c&=IZn@?X|fG;vW(QKJhoXKtoH3 z%2Ztc7|$y%A>niH|1=H!7Rd7j4D1+W`yy7(5W73a$hwcz@;GrAOWjiK-lxh-AU36t ziXcEIyGg|)`XE+FJDdcg@{6Li`;K~5mWBh9{^*&fKc-4U2q&Y|st}r6@I9Evp;2Id z;5QjUF5)T`dx=?pN2YfDg)jyGZy*pib=qojM%wf!n~F=r>pew z$suX$2kn~XD-c^jjc?GRU;nJflF$V9uteh3+ur$aCY!EZWx7mqLeiK?05w`*EQMvq z&7i2eiB_-hVH`jwMyZgyNH0Ji1jD{vDH)#ky37%7H|4mqtUnvv;)I6bUBAjtG4(Re zFCRH#xh5t;g7;0ssUz)eVGF(0dzc17X>6sU;e+EzCq@o~f0lOwhZSO=W-n#@Z!DuB zTiESKyE5{M9HC+VV>`D;Gq7I_^sDEBubJXR<}UHXtUW@ZQnjVM7kUNdu6A?-j$Z8S zGNjx@bu{pzfKODFp^ie0FpnR2MVvK0rtna1l$H#d>r zwg93@(i7nX(ypKzt(hs`G7@&;OnEY&FdZFdb=H%<9(I%{f>12Ug|Faz=~zgg|NV(i^{64NwlRg@&%^sP&uqr%QRdNc%9MX)vET8{$1(TOu4g)@0(p?vv zowpGDlqtl61Qa)zA0SOI&m&rLa;2S-CLC$*)bxgB5eoOVu&TZz;uClUso%eU5pjkD z_YyuBlfiF|eDq$K1Dswpj4c1zGoe0Y{NyDM^ID=jlU4FtpAvh1d;^l$8gMF4&E#Ew z{d!TEvEZpb9VVaem&c3X_h_hI_;q(7u+FW6qQs-)=VR$Kj%%nj@yEpM(|1SjTUjKrip6;~vWAh~;s&srK|W@G zQFtM=T+$Goz@8>Vr5&j0UME>MJ`@#9MbRCl%rdC z*VX5~Zg_UZ%sVn;iKGj$9%j&0M1(#oVe;ElBa@{#Ren8+}9q8-d8i z2fk|%G}s9kWiq7e78LMXxV4ZbOH|yjeZWtl1Gii9&ssjd_j(Dm3bB$|vy}XiOw}Rs z8Zn_vjnw4)!R`v!-IYrl-Mx_c{qX+nB@5fmpC^e?J~?H_>Mq_Q$q$}bAslabw`8b^ zg<8%|j4FHIot9~=0+h;r-u*EH&*@92GK{|d9=oT*%yB!=i*oUFyEiN8oZ(NGgRc}b zGo>moM{J|a=uyuWgOd0*HR(@l(vwXBUVO^EfxTQ2DP1}bIsWGT9D$KxPUd-tGynM| z!Z^_R_1eS*2NZ5?_mnZsk4O4I!bPwa=Wnl(mL5_;j*kZ)1%VNc4dgT@OZ>m2_lFXm zf_K4<6ety9$fyYnSs?lI1o(Qxv=FfL*neBxh_VaK`j!V@+arfHlRNLM){xK6AwqrO zmJU30=UHwNAjGSQo_GkF|G&cIa0(YZlAQ=-LKtaQ0ZZp$1faCpqYjidUL+OyoXlUg zQjK@&w&KBOYC^d26#UcN6~FzVqIi(odUqwgzXs>+mz22}ZS+geUzTVp(hB7_)fmuPf%~Te7QkW0HID8P@-QSrl zs(<1xvs%L}jzu1w4n;3stSYDj3hVt4d!*GzjHv;MAwt>O+V=Fff3XbS?Y5Qz`*p;& zELptbh8jaS3Bv{M^2uNAha8j)7=M*kM4 z%la9?A>jGV`nPcB5l@9vj-I%m^vUO_{WgzI;>?|rKP@r8FaOBnBQPFSgoW6!D|ydjolli@Y%zK7cy*n! zIA3$U=io!fc%K%t>65%`r`%c|e7uywN|nqECsZk&>*iPgP|k*VnWo#3K6VGVL|CN5Hj z@Dn}+#y#0@_33s%SQ?A_`0+B#Lr=)cvNihuX$8w(>A)Q~@Tu7QF{k=Y+qTTD6_jc@ z@h77lr!E!IC!~#3*Zcx%lShgj3}{+o9T&7>*VzXu}o<<@R zUw%WIeqC({eTD*$%DZJO4!kSg^k7elFM$CRU&)^Bv0UKLy|{b8jGAoCzo1k%nSC1> z=7YnZG+^v*%Wr>8Bf;=R8CJ2w!|yCJfw}na3AaBo$cO>M%g9JFB)3*}%!>)3sWxo( z!Qey<3JA23coB-4WxxJ!y?}X(YWHu7WR#v8A=cy_yRrx$GKcO#ceCF_vm%`(!>7wn zWN5*9niPfbexP9E{d{5D!s6bKw9K=&^kHU_BS@9V#jJXXJ~_hMO-@LIe(TF`b8rwn z8;P$S3}%S$jmlKAc8`tOXTmN4!AAR!E=ilzl9e4h*}<8686$SrLhgQj!?H>;jeRH_ zzedU1HQcGtBTC_;q(v_p7R`5g(+H?a$xe?0-3jZGHx1(Xl+5mgjvZr@#2q!?sfng@ zE(f+MkLlo>g9TB6m4)A>m-Gd#7A=}YvKFIHI+B+ypC&k+8Fe#vyUX?9RIcadAEphd zbEBxjk;LLA1(6%gEj=)613(?AB4;&fAFr;1>B2NPPq)K7VGYXO8OTHwT4VX&ZFi!$ zTMoN4TuF>z=9e$i0N6*3LO4!qn_mt7#iKqqD&+siUfDbmTLj|=g)HUOCvNiCd6v^v z+dM-F+<3-_LoTF2(_r2Jern6qq``5(0$b^PTcq9&6hUVW#2HY`FRlfNcqeaEhWK5ucrJN zRckJ%H8c;&$w_t(9il_@U*bl7s@x7LeJ$}5Gk8 z?Hxe2sAK!0CR5Y>v8WWec;%OGuA&45^Y``Eps7w~7n@k4O*0N*@r;`8la-lT4Em9& zSi<;~%>LbAFkfJOGtnnjMGq5O=_X$fjXRXGkUSIn?|AsPq`lPZ;!%r0Qf(_Ud$kIL zX!WA$?wZl1+WBWs+(1P$4XpbFw+Q&!-YAjuzB4Vn7?wSXG*q`B)N?<434Oqw`^4Zu zsPd$`J(ACgJ^9Z~#1a*uhK^{xr}n3$w7m7&bxW3(*k}?}+>c3|P@E;B{XZo2>S`J`p*eY_r$3|tpAw|ndIp@v?Bbyb-6O@S(1t%XnWBwdu)V?((3GEjOJ+pk4Q z&$%|SC45j0F;C+o=o+jVfRvnHDm5)lBZi0JPS38K4A1;B{O1w(WSAww)T?M~ZH$kP zAHHPQYf{3wZx`|DbG>a_$)#EgyB`03es;lEsLE%_9I2ZOO9xU$%N4=WmE~Cpz()T* z=Jb)q4&(seVk%H7MaEM|`39cn{1^_vD>nNE(PEhPi)xIjm^#)g(CG(KaO0;z#^=s4 z)j6z1lcoaqnW~ow!dgF}9*H>LBV@EuIxZRU%hwqA6{;Dfole34H2$RwGDZu35RT?p z@34(XwP>kcyxMp)x~X-7=)7tog_?55nZO&Y9ih)(G(W+dk^Wi!Tqv4Ct$xmmIn%Gx zI{As9^TwI-!%mrW=p_{793N8UTILu>_*8!y-!{mW4rr=Z`lA!~ixe{;beU^%V^lEt zvG7`MGxUmRF-zWPlwJgt0B_o_SS$}d1q_dZ^tPF?F>2T4XUIoACf**bE*(;3xjJ^} zDRXzsupOg%@6lj%bu4~KcmY%m-CBR*FVRlj1h0bU&!4OK`zwIRWeGtbutD)mFai57 zmpTe4jJlUDsp#lXlF>K@ll%btlb*%;pCLL(Z7}0S@Cce5Yk=(p&Yp~M3~K_ z;X6l%aR)z^xhfV{4e6^{1*D>#&84dcFuO97JN=RFyjSdGGccwpkUTb>YamKjgKc2aR0-s zOd%(*g&`+b1Vbym&53!k`@CX`r#gQPn;SviE6ItYvA3R2JtF4lOy`Q#ABh-moYN}6 ze!d=sFA*B&5w~3Nw_FbwAvyc_f+BWzfo_mt%~R&>{Ly9MezhS?0#)}fnwC)C;4Z}{ zvF`KH&NNH6Dc)BptsVYkLg9ceoP2vV_`>hlXog=rEC1zM0l*T6@I+w-?G9Y)=?FF} zLVFAodev+h8M=VS#RA23xCI%q<#_N7ypvmz`q6ynJP)l~7Fh;KQt5k(*?91q_bsY^ zlU9DYq)8u3RA$(9j0k5nLPSRAW=MF~saotvv3mw)1cCXrwd}yp?F-`ndnx`}VXLE- z`W-JtTRCoScCs;k-Ke?ya@l6HNu5;WW-$QybbKgi>WG|`n;7#{XH=bwA|6bZDWLJ) z(1SRFJ2k^L&ed)7i@`5jz&`dQEGoYfhF4yZ&bzkT@?S}*edqboB|_hnmjvSwiV_p+ z^|jH~RcgN2zXKy6P5Qsm`YGyW)xmp~`fIsRu^;hsc2Kmwh7u0->qtXe936kCHr!)SuevuLUS18OR8&-+fBU`G6tf=d=m8A+yOWi^BZTI6t8bf&^bioSqXQ29i zj5)NAoW*&+KQZ!`b?;mygB#(mOO7Bx*YL0JNgqBDb~=9t>Ud`*_~;v;Jz*^b-aV4D zKY!|OpM}KYubRuc`?BMH#7HYCDk>@kwOhm1w>#{LK4qg@cLvK^Qcmi*O}A5SE{(E* zMn+tsVO4G384y983Ux zGxy6-)1vm1ZLe0}krInYB+J=3R(^A@N^Ew^D+L)tzwXn;>gP^Xd9Rx~l+mW8z6|jd zml(opP$Zb+ofl0D)pWDSs)fXKxy-TAeN)im*W*=n+3o+W}|bL)EnAq$_0QsNaIde4yMGB+q5N%a*Ldu9=js!wvp=(aF5HbUjU_fnK+sK zg7gc%lg`}<=PH{1mV9wxldxcK)&1YOHCGOIK)P083u6AwB4(Ng5z?rhVgugxPOZ*Q z;jk>kpd`HQ01S6ci-PBRt{UWJFdf#@nm$Qh#x5sEM)k~d_S!qSKOFJDM^LRZxRVlH z?>hBbCE?U_6ae0<=g*HVkQH|ev1zB$+~G!F+?{0te+>$d#CC$!&MFX)>>%Mq&SRDW z#>tA+6AkyyB7QZ{HvB)Fy>(cXTlen27F`011}O>YRs^I|K}rQ_79gT@Dj+2#NQo$@ zG^n67(%p#CDIkr4A|);L8;|ezJ?H%OyUum?wf7}#5p_Lt%{k^6_x-tXK!_|Rf3%?j zDX3>_@2|EzJ*R>~^~voqTlnu7)B)%nAr`=55%u_Sjak-PG)q|`@G4E{wfU2mg2d6h1!b3ZPMa7!*ao8R*lVy(T)&U)gfU~x3Z+spPW zGG(!!t+N6qQMI0e51K*j8~)pN-P5zAhA6uHyXIW+aUzrvD7#^sR}>fb zfxldF-ZJZK9)J`R*{qeqtx~KlMcgVMMc)Y45vq2iH8@-g=B_F7aliT8Y{YNB{ykOO zy?dJzL2V*guGjMOIIlLO%#^&Ll70$mK2XH@Iv%#u zTZX>phc|Iy2$a-bXu|wEkJ+29e_juIYn!hZj8DpaEta88;5)sKPgVkIrB3^txdjh; z^cJpdj3-Q8h!SC7kL^v7zH4va0w%O@NKPX{B99{NxM<2o zZK8bye$l+RA|ilK&gOLLYj1f%fV#u!YMp)9@NDbR_M;k!WHHT2tgfVl$ zQnBtuvhOi>;OhVP!n(40G|MYr7T=uq$|!;m6THAhrMKk{ddXVXhkuI*V%(L`L^+Nr%{X__lE zqo+UkGloMlF4|B&ecm~9X#^*yqS_^SlBu*RT>EdT&rSob6c6+$Ul-ws!3Z%X+3(*T-N$nn&aoqGk17(*yC2w*x)Vv zOCESA#j_NPr&oQYl-wxqsA1-HpX1zPv0oO|;4(aoWqh*0Fk(W&EbKH>(aJ1l=tE;) zf&Oem*VI4P@`Bt$Rk???TQ8-f{|5p5Dg4h|@@T_;jRs3cW{LP=`%1 zFH^jwDK4|~R^WHr*q1p9(KbRocgHPBZ=0^Z;iT=!LT?kwa#v{H)Qsyr7YJ&&_vF+Azm z6i=6NzOVgP>^`|T<)yej2EQ-Acp%B~(lnEz(g1i4E zh-R6japl|S$o)`d{B5SC6N&pu2r>Y1CWDtDDQ#t@Q326yngtwuf2j}{fS31QgWUWz z?hp7z1R+W_*9Fg=%QQ7U4|Vz{C0^#@{1gIa!cTJCmq;<8Zs%N^tQjo6j(qwx(AL4B zvihUVCPMT+4K|DhpX&M1NXIi&-cMJCM8L1iDS&t%7-vneySM`Sx*HM=!P|HH6Q0q< zix;uRbl|04P3!yg36#5qOP>J`l(Z_q&;Mqued$}dTUfjGqxN~4E8ugPQMkgJE6_sQ z$<{*4gz5}6HGLk-Y~BoOr` zKW%wm0NDCitr$r~<*mhPr)24@qTYyy z7xRKRHY#JQUUE{Qk5uY<7ZxO){9kf%g?A` zJf^hha@ne=Mz@e3^DX=CCbx~sihWUyYba4AT$)R}gsva|^R{MpLb>MLAo7@dZ}75+ zZ+`4W3%S$fZp>1OAAaBf^L=xd$I{m4w#3vO$Wf;r`YQ05;R4~y+;L(@bl^%vvb42y zQ{SXQ<-HZ_*eX-U${SUY-mf@W>1HZfnnL;HdoZ`q`#f9BRMw$PX5E-ARQFI2TWgIN z>r#Y1<)|HJ(1((MJ`Ay#{k5B{O~E$;A5@<-pk~S2m6wN;{^;U~YRFP-ENrVht_bMH zysya1yx!d+H*|>O^|;B;@5~zYpLwnA9${3_p!ZgViTUInTYK_j~XlRI%TY7|Ni}Z z@#N*pbtQsPpEW76-2QuvN3ciOqenrBFEAAd2RX+rB52{zbJHNR-QR;^X`Gx#?Of`V z;h$3ZEe4*b8&V|9meK0SNMpmEHODpSeeUFE;DcFa1aGIKqzw`}2*J-K&QmhCZ{MDU zUTCzZu@z#+^ajifr+GNF7xRZRt*##$@WUCrmWT>NB{7oxEd5)8Rqg#9F=}sjzDbtE zT#i*9fA0ib)SO?YFd+~t#ujhktDh^E1Dmf*LYT{t3I%>EiVuG^Y2khNaKI{?T^zx0 zXXf*Re=7r1E)Lco-n4&QAs60EmmL1#JShx0T+1TQeK6Q-s>WyhB)$wDB`ax3qA(%i zyXB?DrMd4vgghWGA#bgm#ZVEN{J{cy8Tqv7dw)V3@s zGYW>(h61EfsbTGFsFm5`U)gfl7cy^tmcO*UfK{Bh0w7eqDynUP2~~UUAHFARsu+T% zq6a{7I`AVlPMiENS=GG!(AzoBiJG1v=|{EG zr~Qr5a%v<4^4P@K+WUfr$6F0Dy&jX29;zm#=vrp{{`W5!hFjITlcJ;%sibQd#{Mmi z%E!s*ge2)Kmact}sJ+kD(u!FKX~k~~#m?wl(YqLz7w0#o;@`Cqeh-58Xf(Nr|t zJbk%4HQgRzC+ZZW*_M6i0Q#IcZmj`r`0_0ldW;n6$3A0?(m;7twa+vyqyzOLd zP#$gZpU=M(yuYmzqhdX|x#JcK@K`llf2uoV-HJNyf_mS9RkkiXL>VGDa8*co65~|D z^JD(&`ccE5rr)Z4$Diw1=4Pds`CVF+94P!wrmSQo?08Ru(DA3#=@unkeh z+FXs(V`-e9A*niUc9dXw=|n=40*@BhVA4;6!Y=iuA^{zf(qsQ6QYwAA3Oe=)aWFRf z!Bqyd*p7R319#gX0(WyrS3&KaC=}1U>N#JC(18IuvGD|({AukXSf2pnkMe|=OHner<$&2?0spRul^Elb=q(wz6&4^d*6Sjw3^Z5c-n~ z%uw+CELn9Zsm#uu2#phAhyyL&w+aW~n)97q&-Gki7`7{6op=YeT)8V&60=(J}i?$yt>L-hK+?2J;^|P)*$G+HUMzq42F61JYOH zzI=_;)+d3nn9=u=9&H2uwpA;wQ&%J$O1@9u(`hcg^0I%zxP2S&8FSu zEYeLtHO$tm6t==7Bg1g(bn<>J3qo>LIGJlUPxx=QlY&Rk63Q8-Qfb1f1aDQHW z%+??x5fn$_0g;Z?$xcz=TnnklbDbxlOfl*qfMc@(zvD}}hmxqKIae%vTm=?9vj)4C zP~v~6Ea-~-tVVqH)aN&HdbYN<;$OXr1Q4NCut4@e1O#=@!PM)4X_R4Jm|>pRp)c1J znt4|y(-3;+FU_FtN5r&%{Y>(qJi}l;;_ch3_wA^N#d~E;*-Vs+y48cK^;RxD?8(S7 z4UjRzM=_+l2vS?xZ7oCpObg>fF@!6@=Dqf6fW9(y=q#I~P%{{FHT27gw@w=HD^K22 zuu2tKE+tH!>$qDnm+b$2zi(~mt6LU1dCn{Pnn1qZiHa$k^qH75L! zECha)XcnGdh}{=a__wZdSGl>%uf3Y4mno0qiRx1%f4(X9rvAo)%w-BMu~Mo7z^(`& zvy5l+7c8dHWnYa@ius0VUW%T#OTRK(nEXk}|Gr1-o>0FoaGNx}sP}f*c*o!R>DOVe zgN>Rxul{B4mb=9jXOIWxkzLnL7m%6v3>3OqsLN3nKmRh9jTI`UN`Aa`8vGAh$ z%=Rsp7`5Eyyjnv-UsCc|7^+%ys<-jR>PH{0V(z6{*B9Lw(XJc9)>tgPee0ll?&ZKY zpXlG@IQM1aK3Nfc&px6i zGPe{bK7G&rN@DZMx(hGE%w_y7^}V*&sc(&r+5`Oj_r`TF=1*@j_IMv?OdtQse07Xj z$lL!#b{=BJW&#d{5X2iaaL_0MGKQdl0ACLErdRklxGS$j1LOT5J|y9EqkzK*=gBv2Kfk35L@qvgnjk+z*=M}@tN^Et#a(G ziwo&zqc)(XekO%8t7a=fa0lzRP80p<>bCEEl9wx(I4@2gRZ~vt4$rxqCE47X%6*I70_rOXaie+wOaMX!XgILj^Es8m{eGQU{O$c59HRdRCmj|KjrW`wWt9>rAp z(74L*`_N(;)gHy4ZpGgCz2d`Wz|0f4^e5#FL+%T*Zb`z=F?X(tE)i$5%Sw8~Z|O&q zgZAs@qWrp#>Rs2Q=_`M`DzjR&Um&y@-2ZWW(1&rF62ETqQUAVO7>1WdGsfsSs9So4JH>cdi;%ttgG2DGogt1 zP;++%SM zi42YY162d6yw7sxW32cqSCI8Xa0nVKI~`zH%^1S};fLXCqwX7+4Qh8|ZkVzpM^#}X zR=hvO%8EIFthcBc%FeozEjK}#OYY=^AbOSEO+Vg0VP~_H&d))Mbf1k4U~DF(I3s3X zC+Z^g?#z|W5QklB2YnV{-azoC*-^kOE2&6ku*N(Qh-eN zX@&OLr)w2G+^s(7(HdM@?_Y!GF!XA;IyuefFf=vi+wX1ctKpU`57i?i0yEisLU(`4 z0N?q}kQc~-0@c}j;}Cy$|Nl0az{9JuxED~bXJ!@+3j_!qtCN-4RaHhcsq+3z>e-k} z-&|GRe1UFrg#4~NK~#vstUwZOBJUzqn7O-^TP}8CA9r&z6Z%g#pB3jBdp61JR3CkD z3mIr8&1_i>vgHCl3t%2Z8jpezzVBp(6XX(z^ndH_GlhW3c9V+?PGfcY@kkze-QIoe-{ zGZ&w3V^5)RDK8P7^rIFEeS&MN{(Q8OL%pC)`gkgR)=A4fg+SNhbJX7S{()40oC(Wk zs;NIC)8Z+6gChGUSngp>0*aI|3d?Wu`gEHHrozk!~p8hyH_^*p|WCr)iMff zJA0Q7KNUXnH9OulG}{?9gts_;_}o;7e7zS=L+ze!m6s-4WBV;9D+U4yLc4jeT6E0j z;|;&gui8y@f*JzoSIhj&QX!zTW|w$0L-F46!r^d(n(JKT3%&sToL%iJfNgB0g6V%Y zZZdB^Ci};cQi^3e6Rw(PecruYvk-~k{#tkd_e)FD0&zcZp%YJWI78U!95#LhwFf?U zMD(DIp(V?H9kY=i;t?CKK`1zbXGBiO|{^j7jOi7wYLiMD8eKLG7CAZe_eRYc4`THP?7ylki4yBWFUvfnyTXJWWIDo6RUCimNTc zU1-ujsVUo`AvXP7f)Zvp`FPxcS%_8^reCZ+ix@%624;n$4crS%OD>G zj@A!27*O_oXX5-F%q^plI;7C!kYa8s%rt=uwLkG_^IR{*gE?;l?|_HsjI4p^$x{~| zgg^Mp)RAGB6Ya46I=c4Vju+zq7a;_@7(E=j-OZGS55MfE3&q@M;5ykv`)@^KPG{dh z!XFLQjHXe)GW7XH1ITITCOCH~x zKe5VcBh!Jn6EccERPXOSZ>at-QfXxMz!l4Y$9(2&j=pANr*-I?i2W(Ng$x2IPNL)^ z8myC4OH^{_4<0T5D&_ZB*MWXkl(&`p8@_zWX6py+I@zigPh)R1w}_IZy^^5uEg)%3 z&+YVBAtxM;8(C{gW&5qH{gL)qV!P_J?nM07e-n6s%&Gw2hR+0rWA=xtDH&~U<@n|~=O3f`v z9+4Zx%N0Y^<{ZKUvVkdBYML$p1GTjm&8cbxNbotU165_h^*oDS|H?jmLDVV=B|9Y? z7@_AsvWzv>vgG_yo-G_F_!!d;eq*tPcFT=M1^$fdqE&XjmVQ1~YT>1?uux_ylN)t^Iy z!QZzyae zuK}NXOX;Q|W@3hY#*Yo=# z8od~7`n>gN=stMA)ikw8igtJ0%3;+8cE<(c3`!C0ujl**z zmcM96wr*{OTX>zWQ#ItVV@0($~?~*M9`6dk`Z` zI$eem$hSm;2l;LggT!>=sdo&`ogb8N!iqi0WVh(rbFvQcKyT3xgz<-qsbp`g&)(07 zz!6N~q?6PkzNpd|4-Rg6knZz}h-d@^1k^4)Sf7sh{rfkOff}k#;wpHp&tM?lwalob zs0@vAy|1v&<9#{HfUo3lU$)!$j3lxv7Wz5}oOmr5ZO0qS-nL`e_q)Ys@pq1aA5W|$ zB1IKxbrFP(w?|kp9NGE_hwojO1(NC9O>+TfZx_Pe&sr@p30q=biZ!N{&*}15&c@zc z$X?}!nmDGPP1M1gZY^z;9{=Z@$1vQSW(yjlJMzaaS$S9qot!wFTa(IRcl;7ZlO>A1 zvioWd2#2o-EHZA+eMF?he_A(tsptQ$&7x{ULQH;Ixav+!ykZkNmvI^Jo%ZW$w+)@m-B(-$tr4Gd*R_KoF#!Gg6LT zQh8(Y)&+wY_Jo2;?nPPTDBI*|Q$<8ZkefA=6su~K-TAnFmwkXT|?j8 zZ1G}a;A{d*PLpU;-mSQ&azCo_5b{L&KY?TD3*;U)Hy_D^dP`MxI@eot(UHH&qc3-( zjT)7qnEe+w|Jzr3UG2lX;XC6ZUy40jugiMrjA4ZM7`YRjjYv>N;)xcmoE*@liF8U1I^Um=A8^B$PS@@p+|LN`-#L=KiEtW(fn_C_#?Ef zZqu{f87lxonqkRp+nQlf&vbQH_>$4;5A6ioY+vuNohrz=Sj37FzuB~;`8^aZa0rEKvX z5sQ;ehCAfF&&_4&otPoOk-(0T!z|J-V!)GDUY)YS$Xh?sk=)2WN2=ZWfj14?KSU;3 zL#;Ht4-GmL@r?ecQod{3yg2;w+xkl6Jc}im9PGN&ZYA+38PQ+C%T$6_4k^iuk_zSS z6A}(o2|mr06SFSNFQGN8ZCx;mimwf4*xL+IJo`XY1Sj8q9M8xeRq!lAN41dXi?`6J zPxA3US8e9#?J)JXO~q-`O9D{OLr-Pj(T)%7l#Gzp%HVO&R%W-3tGseUDI}S+wb6(i!N;Fj^JL_%e!F<1vJzJKZd@pZ&CUhE}o! z?prFO8k*vg)um&AN8J7PmF=^KBZ`4*qKE(`c(_UojTgaJrEgOAKNLLWo4`0Y3AC70 zZ{9=yJc~=v9Z{ZQQ?lR7fTPK^-bb{QSS8JyLT1AyYe3> zsfl3ljTf=;SA)2>k;TTK#85XxVi1rM~Gfo>>vx1YUOFv_8@ngA|m-fzBuJ2{Izc%#zB?`U@1e<=7D&rn7yPvx~H z7PjAQK;Uru()hr-_miWndvj2bDz5gOv!iQ5t+mNIv);6)wP_4_9p*PkH&~R0Mk>RIH%+0Pc*af8(H$=nG0o}B`}9XJ+_^DT~hxvfqB}A`<9s`|5?jb zp;i%%yv?tHy9?RLoe$;WCte&ZY`Luq$UjmpTKji~M}t7wR87eY9!bb1(Z*V~y*;bh;Vsd)oOTVoM<7-%i&So+C2C4-;zoMOO9I?w(ah7 zNY+sE_E0$ojlHn2p+oDxiU5qYi8_OHPR0UcVqf1Oh2K6c{SsMHEc?>e3UJA2?IC9k zA*(kE5zYeR4TbtzYD;QZU=jupR^jX1$dE()qiVmlkokvDD|a*%4@;+jNG`&A03^Ze z$zzXmX(YO3mN8*Nf31Ipzco6UbT=|~NTRlkETgrGOmD{~ixBsq*xd%*P)#3bkKdLU z|HC=`na|@kU$+6FfG08ZUsuNM(vkYR5N`RXraGUk4L}kDo{JU9+5<<=2GK3ZEXDYH z(gLwbRF(1BcXYrUQ_0* zo5kK_e>dK4ve^>oEkznW@p|l=AuLw`mej1hu=%Z~b${ud^^x7)J-?5Q%t)OCQw!|f zispr`SvV3Q6k_xHnz-MC3}u;3)*^$szmYywwwf+QJgb~)P&p$EE{fjYah$Z;U)@T{ z-|iF)Moxw@T>SeEu=Y9}@Po#Srbu{Ha&|=T3jX3l8NM+z$A68@`;Lqsq%+bOZcRqo zJ;OD8$KHMKZb`M5w0#u3({kdML|-U3U%_E^34V1&8jCN`1pTAEE_*qMl64NxT6un{ z?X@5)bFsa)Auuq=aNl$sHd=lXB_k6JfgrDMGkNm9cTn=lwnJQN zdaNMePkq{nCKZLi$1BG8V`&w_E{`aSzMt}_ZDxx&iWCx}qPw*I9LU-2X@?oU1@DId z`K=39*tiYSjM!V3vH_w8e(DCR=#d@Tu;Au-QUdEMiD<3ULqhm6gq5z8cb)wbH{Jb2 z6>y&YCZDD&d|=NEiZ-tBzq87tQ=fWzUaa*2jT!W){QsoA)u7=!$HPMiO~PiVvpDqt z$c2X?Nfbmo3P#!L?rJO~;^bSu05k>%(Np)ya&xI&E5XAT^n&-EzZT|epsEgRu@*c& z;QRTJtHNUHy*A*(s($|V%QtC`>k&7+iYON&C=qotqB$jG^FyH!gCl|ow4SQ*+6Uhb zlASjX5tMQNV=QlqSNnwvAb*U7&d9Tfx3hy(t3{`mk+w(?{ zW)+ywo_I2pz-UX^bzM>nP2I3Yz4HYrn=XptO63PJ%+j;0B(XGITG==$qO}$i!|vq! z>JS%e-o3z_C>WU*RRs6EURBtP@&ITjEiH`-LJ$YH%-rx{jwFltaKBZ#$?t7dHXfe| zJe-_Cbm^!jAS0G|{=AM@YchG0q4Svqs&ARF(_43Hm3gGFuOP^l*`5yUGAhep%)g6C zqy^{mjr8pJR8rIxy|6K~fKnG}L-fDw9!)?g#`if{!Wfy-P}!Sf5W1x--xmn`KI`IxQcY-B?Jk2$ECy1n`b^xHHcgmBak3?XS0@@#xOec(T47v zNM-sEVfv9pFfi5k*VDw!Bx~&6Xgy2Cb+Rt$ed85ng+zzCW>w(R#!TZILAZh$CKRS~5Bn*QefFt;c6_zutC@_d*DT*1i?8){v@UsL-AjS~HkwBAy3 z1={b;$4fh%SssU(#S@{L*^FdCM`cpmqM>6wwRsY*vx1>evmLvi^=X6aip61 z`O!?y|FWTTfTp+Co!SbQy4?7V4toRZad9MFJD7+YEblL#KMw`KD6(@Qc@~gci{8M{ z3a%VrO-y}ve@DI$xP>&(XQjy38&BmCE9~#-`m;!5+u#6>E=)6Msr#x9=tTHJd<9B%pp zA5jFZ9T{DGbPxei1JUMr1JFl#$(JT^+T`$dV-cpm7*P!H2wOQyA(>xNo8bu)) z{PfgP^uA{k6q}#hbYwswMm6wJS%Qlo^q-({@%Fel z_PcvI&1LWRHZm6e4S}_iXFkOB=boVAu9-cF8;!$9$%-F{<-U0G-$gQ2OrzBsfOGmc zfD9!cyW!GElcj%*Hgx_S6=uUmfC64tQ{Gvx!LMco@)TN0eflOZ@2L?f*W7yc@0GJ>C!4uB0h;xm& zbTe^k%k+&sqzyx-+s{??-7?{I;vh0*7Q=PS))azYd8N_evpD1cUF_S zr|civC~a1B3@_3TUSuD|=wDmunY!ARBu0(z@Dtq9-;PH=%>{9j{HoKSgdjbe?YHElzY38{8|1u=HS2X&| zBm_i@ly`mk0)t_QwmB|L1p?Z&JFv`tUZ0Kcbb7Whk{SiP0r}vLm}4J1K~xYf!KB|e z1uM7OJ&{+Xc)F=uG)BD-vg59_x(lYsEb+neE4kmtGf@=YENS^y@JupEKa}Hi@^=$E zew;iumIcG!oiB-D^~fS|R)S;~Uod(=AjxBdfn2?mrs5|Xs9X*4W5Ot;tDbcURR_e6f~z;W&rjOGC;B2IIc(wzZ!v0 zWBwt7jnc1?CE}LURQWY>7AocCiV?bjN05^ohTris$d(>tyUDFpe$a92LyYJU@hkW2 zS&9xGr05zo_(>zjE5a7RB z?l}9CB4IDZcsU2TyTZGyJ0U+DW%o{0kqUb-5BE1k>+(Npl$!BwtQpO@27TEbvhDyIU34H&j|gbds6U1po7Ui!n;$Wr_*?iFv-=l;ifaP5-C zKPUcK2ciXKivs5ve5l`-({=;PDhU$=nI&A|T6;J8$1orb9R?TFJ0dMq#MlR*cxs&n zrtL43K^F$EEdL(vV9C~PIRHq8HAeTH$&FJ4h!YysFCcCBgq*vE!p+UC>U*MT@Y+&> zu6%QrT2!&`jy;T)$YB;Gey2Ajl2aoVG6U*w974!6Vn6SIv&;h?dj5+sG?;d zm%8s}D=nV|aWhk`ZcWw~S=~UVS-fi+`cf0S_2Lutk}MhpZn=SC=t;Q_Iz;ZmrFmQe zpwz8?;`kF57ppwt2~PdT4*~`bKF7K8!6R;=K;lwN3OaBpWP@&5_~64|;dxpk^aYASd!TalR=yEBq?vun-Q6AMgc<&{b1f~>6zpH- zgD&2`=n1WLZW(Oz;Ug1EN=_oRBz`mZD~SPE~`<7hopR&P^G+n z8;w}N2kxqZ+a+fyFE4Lkc$ntV6Cw=Xpk_n?2~TqD*4iy<-<%XTF%MPOZ&G}0OmA_( zAaAqORdXeY^X#GK*}2*M+_Gr+<78pPvI+;IP*DphTjDq_9?f)-1S;Q};qwv_ zAE#E~8;iWtNqsU6c~C1_MPro?^z`&gOT5taOc|Hm3_awPGj|q}Jbu^q*=~Z(k}@^( zxn}Rq*;*>HvF4vqb|W7(jdb2BkL8VipG*{->jdj)@Y8f~@8Sf(C>P2926Ywz5~u{k z$*kPmPwN4H_txX&9`0gc4vR=F-KM<8=Ag`Wo)iJ<1rQ(ySHV%;>_-OMTQL^MEKhCS zntn->ngA?m{^{OleX-!;0xbjH2a0hDgV&!Y zCeFk5+zAx$2(UY;*VH*{b8!+~q8&w{fWaH;Kd$PTke1P!k1<9CQB)+VRxurX<&^pe zx{>I+ESZpr=M%+VR!aUAn2QwBEX972L;td>PS)ApkdSL!ggJ*M#=SYv@alz?JH5_# zzwgaZ9Y?c!@`&P0NMXaogZo+Qv|jF~j#hqs6QOkr%3be19Ko>QMZb zCQsLH1xW-KXJ63YW#R4A5V9)%D4+54H1b#tI6VIC|gX$xPxy5Kiw*NKx8O%m~ z2mKu+@`|(R?^^9TvQQmo8q7a~Nyq6d!5OAd(8M(tHC$ji1I3XjWDp=Ve(Ph3PH?Nv zSJWHksVOTfBUm)mG8>H92O4bVokh0~kWnQy!y)L`&LxFy7m%||WfrtP)wY7%y9iWX z&!2zbjSHo)*lhnWDKV&aTPR19 z$SA$JIkFhQLbH@`o6VZ3eZ4z155N!|S`-{<`l`&?v1>Q!7{4{E0;aZaWh3*?c_}Fi zBf8v;SSyBWt9=^f$9`}4Gvtqe$}(8d{)%Bs)B6Y5x?7QEStsj5GX57s@y@UYzBUFn z_8kuo4+q&A-@aWIr`Y@H6R@4bzU)B&&Hl*A@!rg1i=uVUbDvwnNH@WCxv-QT*n!BS z0S`|A;c`zWP59bDBa|hvr_gQPWoeA`m=i=&0@XZNytgmGxmOP5*YuAVt z_XN<1O2RB$tBC+8_S@3)8wp`N6_%S<8-?Q3+TDh)XG3;6@RsVEnnq34KCszao6610 zYlTzsY6%lYU3P8-7#||B4DNppBYnRbk;BaMlQ!|p`h@{6hUuZ8W@F;w31pZC`CRc~ z^*Q@jiX;q>bI9PLu`G#@N0dxGek{O;9zAofGIU>^!7>SdS8!6>eK=kj$Cs`%2FP#Lh z1z$FNmIUO!gVbt|CMr&%psN;hIQ^%gH-(MZ90kywUaM6RPt+y&qwnz2l7;V*=?qgAM2I=wCw%Nn z!ND!YszYsuj#$dawhE8;V=4t&+J_g7i6rL<=Pgd0SY|@NM z(hVAMEUBaxm6>Y34Nmzat6jk=d9wjLlv32o^R#c2-(vM3(8x`D8DA7y%4n3`ckV9! zHLe;0XlZ?gu*ICEu>#Y_k8lb9e$xdY97KUay!oV@rLl1&kgk%}ySlr#tB-+v5DsP4 z?7L*=KPF$mJCCiLbc1$OQqhekgg{tuFqF%~Gvdy;ZB;IQ{pQT8HfY&T`ga)geXezZ z^b4hZouu)@Yg$?!)k9?vwDBe<=kS}ZfdMTH0!_BpXV?(i19U24p=cwAIY43b2=d%m z2i|H%pLvd3z@WtY5n@rlauE5T4XZeal3B!DgJ#AtEbm+J|3Qc;AI%F5^3yo-FX9^| zknjdPb?t)_6zXI6%eN%9z_5{;#`*}`NG4}}aXO6690P`(+sy{KHRH!>=dy6)zb#M- z5EWlz#WVVT<`Dq&(tFaYOAA~zVu@O~-iP-d`dOPZy;Wu+bpauWdE6@+h1@aaOd>PE z6@aS<9hH2h`N-43RYQ#(k=$BHq{-R5dX%?GHNdORLO|We%kgAbs`n=qq0|CJ2yG6! zL4%SNNvQId2%fAQUKy4W5Me|WpCc0sg&sW$weT<})X!LTyX5Ww$2TA|?L$s(lN)n| z%SJ>DZ3dSG!4Od0RwUw^{V?T=+yvvgDgWVYRNqCBX^4Ga3Oq;Dc8YPFfay1zQS z=?Yboq(47^ZEYdZ)LBViA9G$O1@N$C_o&nScZ~t5@M$UF1nTPW532ChxyqjJ2gU!S z%APU6%e)HjHps++(E>o`^^e|I<(HDo`6+?CKzhE}orIThjE5MJMP+eDme}89=n>{D zP*zfjq9yzsjq(OcpsNPZF~`VU1}8)OS-pVYt({y{^HsQM!zcCP+W=lr79T=Fxr;LO6=29 z@#{f0q5N)}eV(xWHEJ3iwNRzA1FBJ_j^E`m&7NWVQ*ZYv6+VqE`1rLEwRrlwF5qs& zK8NDna1@rTTNATP5TY@D!k>_}K9>BD z)?I6hTrHgZwJz;TQ=uSUl|9*CxO?wj^Tjc<5QqRlWT;iYKI9$!asUl<6`&bK?{qUn zvs|V_?q=7{Q_~3=p-@$zc#Q`HJODFLC}`raA{`ZE6Gb8-VG0H9g5OQ1F7+dYmZ0B< zdp36DgF$Lywe1%=$H|H_a3c@1DC$fUGIgEt-<#_TJduDTQ598292`s~T3sThRlbbhuolHE~N)gpWSKO^8hk&1Zx!5&BDU=IiK)#)xwwc(Rh8BP_OfF3Fwqk8z}EiRe5;>x~g?=#@++2Bdg01x5-lV zc10L_aR2-?cVW#qLQa7ov&%yJRm<<;o(|&^Nc^EIFsvAQAVUB6b4;D9c3#V@;1jEr zLd1a#*l7&_Wk6Oo?)_MVJ@o&Ze{+I*Z`a;M+ZZcYgY>NfE`# zXJiN_L95S2yGm}9bx4b969Bw8B$d8qnZqEyw0O{$)7)LVnzV@13_5CKL(pT#< zFQ89pnRga#=#$NReh`0Ao%>0;R4ly}_u*{TZCf?FoY{7XAPMn`fp$Nkj+KL7Yr_@7 zd*nt(doM9>j3jlkL;q1zL|;3ls!AEw$}TJlA@O|&f2PnuIuXYbli$=R|12b&Pe2Kr zQx_sCP9ZnQ%FrX9dj^MiC;ncZMOR7x`w+`JGuz&`89hPhX5*kQ^p2cJ`}xEu2beAL zk8bDQjyUA1Vbzt}p*gRc7JYB%-8o4~x{{J3H+D!9GINrOV&M90TIsx#2Rk)UmK@;X=T06!tPXG*bd#-kLlIP1pZZkl z;H7Jk-O?CdCgW_!lb7&jA|i${0{3+TgD^PPQU6>X081gdrHW9jjF^vz(FHILkO@~% z6zVwp`4IylL+eWw)&zPH@a@6?g+U2Thhn(dbGQ5_*EuB9m&>^JenFp;9bn!7@#7Ma z6%5!xC*eiiXV;I|=Rhvl(|mGzVSZso%XMh{K)y3ijT8uU{noabWAFQUR=cNlsKaC|1x1dG+{u)UfqVooqX$tUhTSWnY4w6z8o4kS>fxR!~e3*+rL_2d39mDWm*eQ$Dz%>8< zW3J_Ah+`m|NzEkGwzF%NAt#Bs7?Q78^8ghou~}ag#zy>S2 z@)N2`u6IPpsYIJlVZBrfbJanIYjvUaNY*RZRjA93P;f7+!Gu~tk{^G;<4xuz)kil? z3G)r-PPq*UpeSe?al9{r5F2wSx3!aW1$}i+FIWV5m6=q?Pg+-$Jga)B+1O817g5;U zc(Nmc)I@M`R5*cVlS+2{x)Dg}|MQxM3e-eb&Lf8_Vq1eNmy(JKF7UcGfTRh2B9^M1 zQBzKHR#>dV=Q{B0X~jv3p}8!I2e9o}wosX?Ch8yA|0)m7Jrx!o#1V9>UPLgN7iL|h z{A%L&`TuZ{@Wh@qllt%}W?4_H%r1-Th=a&w*~=cW6QGdzOAfP`)1v@oO01XIoDusK zawAqwq5~gGa;2-LAmqNZCJ)mjwBj>DG)%!$2DWd2x#v8e1gYf zc`IRDTK$<#3NrwFrLkR=y3+62X+ckj0AmZqx<-pWK`~1NMsm_r6muiw`{DsHrd`kNGbL&9`MM?OJB9KDKgC1TGOD*!W%;IOvoqKk zBx(QPh~^N-3|cXD@muD_qKcPOACa(^-($>H9`!ru8~+TngcV0SN9^6&G> zw|B4n@s($l{j?Tv|Hnu8XUt*71$BC|#>M}8?q1S+{HxD44*Gz-`u{QY)nQR}U$|%J z?(UWjkq`uF3F(wZM5IHyr5iy)1Zkv8DajEK6h!HiZje$!`tIZRyZ5>Cmye(@XZBuu z?RUKqci|Zd8HCb}*}X^4*FmU-rQ08W799;eNELgSIvpvPOk#9Ai82IYNpiHaPIXj^ z*_$57*@O`#fbT7nqliD}ySZ#&9xF#@hS+>_9WJGUK!!S%izw4D@4jKlRXsCrnf)Vl zUXhSBM>->kLOo2ik#|>2S~ciaS2#whxN^^D83nM{*HMiyQz3&$Q9i7+WAjz~Jc_+h zX(HXfg>Bzr*hQBxD+_oPBv#JVGyNJVj$057 z`}*}OfXrf$@zK!*Svm+Fr2!nH^A^IYT?W!+bpNc3N5uw695>vqoKfPM9~qNek<1~- zU&T}7C?P0?Wju5U2~iL$)@*OvJI=RJ15#AP=+=d)i0$`mtijljg9fHlHtbo#FMOfB zHpLMhW@Cr(n{Pv3P-9O4BaarRyeV3K zdu{Yezd!EH_hj1DS6t)li)*TB!sAok_*83`yEKS|pnrK$+W)~hyR4SALY7vl__m4C zW7i8AT|TTIdNb_T zFFuiw?McQxS~<6CG*wBdwafiE<2qv5$oT8qwjugMRn;y~$io4RM{u)oQ{msMYS6qg)zK&mA%9O19#l?_@I+L86Gf}#<#UuR#i+f5MZu-BqAqS# zq4+2PH*lMrR8P*u4*L^ksD}jo@;muBaWg}^I@{ZuB6ifXdQ*mFA;q7)w%?G2 zh1piPwY)#{pB!CNRjgTT)CM1b$>{I8yQ+EB1qSm`ib+KV9HYyJ1$x8fUa>?{B;goU zq`?w=ow>i#NJ>-&y3aZAza!r#1@$C`v6s3xkK3C%d6qWQJWzA6BsroQ*nabN23RET z{jqj#H&22i1pgi^!6YhHabb89uxx*sQOE6qvmfDI0vx}R)6ycq-Rfv>j&`=mr4K~7 zgcGwWmEJ^0D-$RqW*V8scGzBf{Ki~WMOIXmw^?x(OIdPq={K@Wgw{^hbiX%8M>SF) zt6Km5HV$;oG&VLiz_0G}_qUR6t6zxY>F$!iHbF%tlUt7-uWkI*YGV2sB;$Nvyj)YY z1gqfXNj2>-DTi#5)GhAX4F%t#64KNkgae4mI0@McS*W&$#_AwaLbd$L@RJU=OCE}Lu|YUP9Mc%%&ORBOx2=WrFAFR?{^S8s(o&u2*2jG@`6srGJ6V%^)o!aQ?mXT;O$QH|Uqmk1K%jJy2QhK$1M575t$Dk_^}%s9O#eZaQ}WRyHup2 zpX%WGH(F#%v&#mS<<_x85&LUxJ*&QH)u@G9-2^ec0>!+dj&mz&m6QNEd3Jq*=63Sn z8J#-L&nAe9`eHsTk;;(baAf~>1hU`3%r(aSqKf~JuQd?+De89v39a1&d}=PlyKhY0 zs)Ke$b7j)SDCyIs>bP=w{4(#fxbxWG;LBoqK5oA#U7!djSCy3KGa=$e@cPn@`^dXV z&=VDYY80Y962y^cR=^%7Xwt-0gQkL&g6?OI>t8_WAYiEe&+WsKuCTv9yh{YHLigVA zo-QoBMS&hl3h2IC)4qV`20uY$S9DCwCqOGfO&s0w_}k5RP1Ku748OE(;aUVT0deeq z!caS?8a;h|Q9eov3d4iMp*ThmQK5Ii2qpiy-jJ+Oy7H%#O?Djf2`30c;Jl-72SJu$z1+hmg_as$M zFmUY6Sm>O!M^*W7k{)z@?{$47bE+u0!%5gg=6l4RzaxbF16-lMV} z1K!X>I})Js%Tyza&}uKW<=79OR+$j>Gx~m%BFQf3+c5I#r|tNvd`HZ_b%KQJkgtMj z^T5FCb`(>H{(Uq9Q+Ah~RU_-TZu9=Dp;{K5WMhO{7G$7BUVEoBacbNodHW%FC$_1x zqoEY3b-f(MLQxkZX}Wi66{;FS;wxR(pqRHsDg)SSQRSDMP*nwOTv_QTcsyt0Wi9uY`$6Ny7j# zC$T7wQTuO0aO%ydLp(;X3|%RSApwk^ANX-AC=lD68X#kb+fdR+ZO@$acdJ6uh2iaw?_valTkAu81-%XVy_xafkx_cjAVRauwpvm?c7 zaH`A2UMnHsWPJun9CS<5$>uc`6%R?C=x3zsgmO|It4C;Wy1J-w#UJ_6J9m_dL5nWA zj0p#hZyI+kg+jhhdI?MAZ$SnLO(QyOz2gJ%p+C*l&7)i_-<6tPTPZb(V$|}^$G+gh zx3qf%x(%wgWt4(C7^ZNSbxX(j?n5n(|Q6 zy&0?QwCKOBB)j&u20JtahP1evWj3{Bo*NC<8fUu)8%_th=ss%D#XrVZCLFv_d8-js z(UxD~-Fa_*eeG&z_7xOT5otI2{pEkP+7{X zR!Iz2nPX4~)nr$qyz0fL@8k;kLw}FIb2Jf;qCt-E%e>0` zDQ@X8!f`Vv^>M99z#My3oF;stZI)NQ5XVTR?zdm+iQn;EIUU5n(sRbQ&Wis|JBHjp zYUOW1YvIw-g3PB#h0?1g(1%&a^^qf%t(+v*mzaAexycJ^C$&B07Ydv|1i zcO~P5$xjUSEf#Wl`%Z81Sdw|X_F|YN^fCakZn%EG0Jnv_E0gHII{O*)$J&_shKPY1 zO8P4D6|)@qI2@x{XT`MFfMkm&50|xieHLS_HEbtH4O@!ZlfTD4fDug%+fqOJ@IYB& z)3cI9MIrf?3JDC2f;p!(u$oQIAwVbU$1y5+&}BOhO|V~4BMTaLKwI@y{`NsKj*`8pqnu~*6zu~E3Iv%ZHU(`zuVA& zl1_qj_h-|S_-Q}TER$Vu!iUw$(cdKdQ5|w^dl=+0&RV>Ns6^YpA_8YCXceZ-eqWJW zJ6?G89~dCrTckK^JU=bB|InB+Hb<|jM$f--dX;V&DcfD1$Tg4Skius8r~;SA-U3l! zg)3KlwU|fLz^M1chRyOxF4-?>ok*}MUtDkyJR5hvJ~n(6Ljx8{;Vt0a zbP|?)?x=}v>B|&;c|t;r4p<`a0|Y_f*cUBoYHC8(y?7v@=+oo6MF5`3>FbZ`HBA*1QO2RT4MD()To#XAOtu*K~@<6657(NMt)B@6pX;$b4xIhvbZzYPa zTLD2r&V#3`d-Tf5`sGpMxZt)>w}#! z&RyK1`y(~Ib3?mJ>X^qeZL(!dOD|H1xvYNq#tSYhexbPta*vU;r!|&$>mhhlN(r|7-n`<~ zTdI^KCx3ik!AnFOF+=bD^TnGtG%)K#F!Nz_!m$)bMtZt^$M<&s(`8WBdjYW`QM*tH z0pS8aMc-2L!k172hY<8)_(i7Ce~S@3ZmjaFtPN zhtka|L$mTGnTH)^in|kHjVVV+RR7xI@-+^4a zC{1YR`eMHiaJ5X}`FrQZ+`b^l{>gnQD-Wj01P|si-jb7(JGI9+J-#`7K-ao|y1nJF z%m1*UmAF#{dA-I_^t}z$Y_E+JS`-hUdJz2F5NT8V(}Q&+=u{Gz^Nn#`2JFPQ;IdH4=o1<3?b#m^v z&u>-&kB<&9HwsR&TrLyGvj(XS4ui)=Z+)OFIREhDG7&xGMb`GrX?FjB{P?;iY9jr? zaA*E02A`&YfXwGxxoC8=`|aLV$|@ii+;^Qi_2y4li1kIaFK(~1`%w8`5X&^sG`U=W zgLz=F*e5nfbmYmLF<;Y;^Sm<%3Q6g_L@#z}qjvq+ZvL0_aU>oBO06=BTh1^i5O3_$ ztsoK$5QmT_*Y{n$j<=Ppvz>{9E8UmV>VyR=`_iD0Sg>ce$TiVSou4`rkla#7f%Keb z!V3Z%kacF1_d<*8Mj>ci(raV}PGHcLO`*hQ4O?TR$>j0{fl#(8!!TrTZe^ z7ETK-uc=C!7KG1Kas1j($G!-WWZLxHbdGU46ncDAJ?B$65%D?!<)oAIX0vyfcbT5|st4`tk4ju3rw^F%nL92^p_0UiS*^9)jc3Vy~43fcp}7^aNM1y|xI zyZWnp+S=Ws#+&VlB_ZUNnMS~CZcBC_9!suIHCo!-8j2Dj#g(0*2ws+07T{EfcOelM z8~ZXjdFgr1CrcT?2a1i2MKSMtavQW#f3p`F91L@JRyQ`R!8s5e2dJO90ig?k^$Q}W zyRz>-NBM3G^b1C9K5jcMFMHWCaQAde#zyPrgG_>3M(q zW?*;OWN9F9{UOqKb0yFsqdD#e2HmXS)CNBnwz$Fj*+7jr_4sj-QiTnE9w+zKGv20e z6GukHeRQiALQ{1)v9TO|ss$y^AIZ~RYUD=#=FG51z(ossv3r)))hMm zo+84HnbzU%ozV>)ebL5Iq|^^WL_TZKO68a>dFjDrb{9YZB;Zzca(C5DRL^ z@QPBg8G)s5c?GeBd8kj`a1aKXcf6KB&1th?BC!gT(l&q*BEG+1OwanTw26;p{C%$R5zSD#f29vzJC7> zYZ~6reE>&cqehboP+o2?0D{y5PfrnpYSZZ_kOSbUfH>3~zZM|O1Oi)}t$SII83dug z$tqpV8<%~%%K2JGR=*M^m-CN;W4JZc{>Q(mXJ0Z`?cvJHE4BQX0=J$-vBsPD;Va$4 zsk9B`%ko|fCN>VykEYC@3$Ck#v$7bnvR9wCe65S=_>mlVy9RCw>|15ymBKP~R*_n@hx|*`?e}nN$gwHxocg<_*a*SJV>hNd0ZTQW9 z{fYRvA0F8Ga?rGyX!+Ouzl^goy_de5zh@UP+DvV${pVhbUIZ0=!!jLIP=2U)v*$i( zrrdGT5@L-{?depmLyglde7nydt%ze;tQ^o@joOS>W=Q6caF<1 zQlzg_)ZWlJ{Cae{Qr}F>`i5b)eNS!U_46N2evVHKkM|?{q9fl(D*ZgY@mdM5q8O;A zkF3PqZgf!(MV}^Rka_BkXWkJ=Mq|Gtw0yIBFVwq3JhI~Zex$zuE$|NTY(}f8xuKrh zj)<9YkN5HF)|{$6#dBsH#S}9W?Xh+2wpN(OTv!<>wDGarmbqLwke0Tdb&uC_-XPzw zDX=vrIZ)@rc={!&IGur2`euoWBKR-rdGY6!>8!PWbudBUyl&Z{;xC_ktQlwBW4#|7 zwXczC-Du=}DRjBc@U83@VPRfh>uG|M$J+@yRt#H?<+JOI#|w804>x87y8dLHtaL8q z_JVG4`9$p;1?!s1?V=)gDViCb+>5e>mE!AY$;xmy2c3jT!q1AR$9jwlLk|V}usj`e z=eHO7g_Z~D@2~8)Caq*_cy~{8V@gZv#V%;lgve%?79~0j2rX;5ku#WHi14~`w4G(e zS^b*FzaZ@2XO3W&A3kkbx~l}a^YmRz2E+(Q`W(&sW9a_an%M-~7aoF|&-v1n9di5( zd=!i&C!A!{k@&Lj+?O8Fe!^$Tx(jwu^ENPS%KZ974r~iB`hh1Pz>My}I3e@DQ>b+1 znHYi>f_)Q#dxD_L{5_az^l$5d)Gk(LW<=AR7i|zw2>l0bZ~(;4Rrxojt35hz0_VU7 zwRcaIL~CYPqw*emdSOXu3KupIGrq$y8XgIK2_HvFSz<1|0zrqkus8`Efn4eQX0h?{ zcmaTg=mSP$ho_x4Qkyn|fG6ecXEK8}(it55~FX>4Q(7BL`Sy87ZTttTxI@tiwHi-HarP z$9>)ifQI^d?nnqMx~p^K*5wA6hh1^8I8%EQJdQg4LtPn`dKfLIlNA zOWgTe7lw&>-)kr@ukX!=_o0llofdz>+8zd8VBBx?-e1S$vi3hgqtSz~d!`C8<7Evx zM7?$}tec!)3+nZRO7Z`yakI+!$iqRnHRIzriAUA?^zS28>&PPys*%wwMl9q|F)kiH zcRC$U)hDGbtfMkB!RxLLPitMBF;V+LVqS_K(b67DS4SP4p^Mg+M2wf#A3q5de60&g zBo?{isk?FIifuX8omE1SX<)MqRu#a?j2Yzb6zRh%Vz`W?OvfvVV_aAbx$&V+LT2mWH+Ss`a{b_qEojJ%edXA>o6J0=iI8_ z4xvOVOT)9{V6`M-m3L&n7Qjgt-g4o#5JX5|%w}pPQ2*|;P{Fzb=E)>ke%B*P1Gjg! zkHIg()=TxK-6B*<3GeGeIk#+d6GSs6L2vq?=r2v7{Ju@%X!?m}5)IwH=w$}mCC)P0 zVzX*b8)ePDz1Pm18g5LUJrU8nIloT*LT;=TkahFc;g)gT*YXl{%Daie7?LL?J>7yw zrdY>`*iLtqiVSD!ZaUeAcA(LZ8*)QC2i*oA-F0r}siWz=G_(esc7#x%b3}9HZG?cc zbhIL4KvLX!G0WYFRqtPi?`e3Az3Il?%4#*}ql>8S>h(+#&(|^g(GTYo6&2;Z*Qs8I zef)q>4iiw&!v>$qtE;QSBVhPNpC&y*`YZt!y#ga<*nSyJ773DcWB$>e0VzHw=zL3A zGbx&LSwW?y@g#1z86{mudtlGbAF9wvmDj?S`zw8^GoequjAI1GwvawYSNOlpGCe(Q z1UQ!fWg&c3ws-af^k-8apWDWzr{&}%f@|NMvmZci2_zS_(~eU>SLHXCKr7a@a%g$< z>}K2vPzkUBSrngEv~&X)T@r$c|7ReQLixT0hOJ7fs;YYEmB#%fw>lF!Ylinc!_|%! z<8s$Tr815P_i&#Tq~E4RGZm8~@M&+~F$%Xub)30{dH=zQ$_w`D-J0Clig<-HAD?$4 zO@sOgy49B?E(C-7sA*bCzD{Q2uM6DIFsT9J(xB*G>E3o^k@-%##N>K7X5?IpCro&) zTx%h>6uHOhF8LvUF6B*&stnisRegQS-rwL#z4@o@I`vn?YC4qxorYtr!F2q-w4bRO zD!#m;agp2C^WDq6){Adfbmv_8xyQGl6f+-KKEnTFn%z%Jhi`w<>{b1A$+p_5w3mkA zl=gDFrp`)(WV%O;nEcSrVsglb`M!-DQum6EKYnNguOj+?eSNg~mL`g{(fCQ{1>e0O zZk1^>mg|EP!&0x<=290NXZpFmA1S3DT7SJCs13UEgOK=QKSN-n8}EfcF_@_bh`Q`u zAO1(yD4#>CHRY$A4?H!y{GHLMkSiSs+soejyBG$m>E?Y_@Gtj+Z@OXW#O39svSu1s z6sZT~&}(@;#6Z3ZuH0QT^6HbYEizaLSlA|G1OJg&{fobn+7 z#mJpJUtIUuj0IQU`*TFDuBdPBmxmMUnA9r$62D~8YI}yzY9pU;uzY9B8(HerELoep zp*&S{8h@|Tw!{D~oyIOQdp?<$tm!#iGuP3d7oI1~%_a_39*WXrq+vilzh4Eqwn%N} z(1l5x8DHlJ3MmmJaFN%>R?xjDHfz0>k9G2 zzzh-`Ags=o@Wi<~KWnrHaC^-V>lZKUszVU_Yz4sC*SBqO07tvJ^V$z6G>zMTuDM$Q zZvts26;OrjJS)4GkmQD@FYaG$X>P9p%Ud`x6Ep$1Dk(1kr=lds4+ku4?=Q{|#ErHC zx%Li~ha3*p*1yZMLm|UgEzjQHE0DqPQt$a9%{3KRga_ci$h*22N>3QlyeJzPQ%^6r zf{dBHIH+UXZSsWEI$nsg_oNV&;}`{XX+Kb1vks^MzHbVA*p=MlZ|eyt0g%{hTfFp& zQ3Dm?-?Wi6mfHcgNE`?ySFZ5cF z6W?WDBDVXpd&KgMWC@Q)OZt6EE(9<8n0JdD0r^w5H}b!KP7Kic>F%NWn#~x@Y-dp< z6&8#9{n$)nhy8S{MWKfV{YWkDoBtQ$cHM(9bxOcMv#{FT=sP$Tq79OIe~ZqUaDLvC z42&_YZf_or?6MA*;08ZaxGsJ-5utVLCk5N0i_`u`P~io$;T?E#43~%3uaS(mjd&^O zqyxm`Kd`XGYN$d3kQg4^4w=Zw#Lq98MV+EvnRPk@LIWmXT9-{;n@SNr@40f7gKX$) zFpK$6?}pB+yA$+c-auuZA{x(!9goF>YW;KvUq&|AIPnfykNh37@oU7Yd)iZ z@$gJDR~1UbyLw%|s%lCkck%+^k;*tn^Kc534#;ym5C!z}ZgmX}vc(~w^QjUhJdOvT zFFgmCm^sJ->1GS^rS=W(Gx4_vdjzY`>q*_Javi_9ZOuk8gjDXh$({BwSb>`M3>&)C0e`V21V7!%pI zCd7v_1h?-zuAKA4BgH6T1xL(Ypm$HuzR22DHw8S4BOtB0zTCLa3iuU36GLBK zUJl0s>CcaPMFRCs_vP#(>Vo2>#jZ*U5 zv=Y`hOT{}xonkp)m5=Oot>>;X@|$`FHPu#$8Kaj2Vo`d^oznLkni)RAM-m_3Sg16R zvg`jQ)YDmxf1`JT8uG+Nq~P4?2t}L6(#~{FMX1vDJ;#7HcU0PVv(|EQ(<9Be6TY8U z=(YCQ?wl;&ivpFaY*pzPS{}P*rRO&?9qqODjismOJGd>hs%6t4`&B2e?|QgCWq}rF zSJv#uD~7d+fCN6(hjj0)Ak)Zbp4X;W=NUe%bOvV;xmjyt^&01YYgmWC_uy-or5}b?`0)^if3XlSti^&WFmePavK~%oGP&J>>6abp5O> z_7Rtt0r!rEOl*`t#P6-KZQuUxEnv|L1;%zqmw=D-2@&LyDGKNfZ(@fwH2q@ z`$TB*mklnJUSD?Nl16YI*kS*^SbXgA`oJes3@|ZTPBSP^-sidI(rwaZXM*W()T!zV z*_v)H7s=05g$$I(35gJewgbI{2NvkI_`&?1MT-2t+OAM=LCVO&Vowg37EH61p6I+| z4I+AS=1%#51P6SBdB-B!vr~u(G@nV28Fp!)^c?7){@$2bk>7UI~1DDoW&1>~WgV$%J#tbRo~=F&VbDblKdZT}~`3W1f#=cSXzNnCAo-YO5x z^rmSrU;~d24Z{0X9=OKN9-^;(KcrX>dE3DPp@zE^(|^s@IVo+x-MN5kgI=kI`K~ND zX|E9Cj$INK42ewcmr;+Zvho8h20!X*){-a3T>h>N57oL|SiLt{C?T;1Z zRZZmCSH~$-$;%Z2|8iT76DsKYFI!F+KIqUye><&=3AgJ?Rr~jA9Nruh#w9;7aU*fuU58jC_7NWVN$mt<)ODj4&Te@Cc z*{)9ZUX35X zu_AnO+mNv0Fmj5d;0~0UtT(Blo5Dt?%VQZ){rT#PbeYfcX>(7`4R{l}{;WsUo;DI6VLs-Aih@)W=_ zSZP`r6y&w#Fzm@3pkILY7PC%5(!Q8VFQ!geTV*17@J^Jo@Nvmu&7$DdqmJ*#ID+F$lvL(08O#D?v{*i6>d99yjv{8vCFIcK(yM#)Uid^ zy33rWmRQDi+&_c?nM7VKQMjOgsVamVurbqQ7N%7(Rm>B*0=u+TU$0S?}SB1&-5^V zMO3~f(vt+omqZ(LO`{f=g@l8p#?-`I>DiYzLi$FOSQTK(=Xz{g9x^Ff2|7a5YmZS{ z^4UgoSqe0MfobatHkH4FEO{$wGbx zy{wwzBni4NgbP#RuRoMvVSd+(C`!=`-0@<>gaGl#R(W!Cp7T?hurz`fFyc0)bG9>C zI@j-;nkHP$d-;V4zq(@Ic4V;w>JSLd2eJa$+6l%lv^?s1zWz9FeAC#TGv%vA0OD_vCt+mNVZx+` z!5bc*&lxpVK;b%E#itB+H1h{w>V6r{YdpV)ogurJJG!Afw%pr*R0tS_FJ?~cWU+r% z-7MV!v--#Jen%SPCxJ48de8N--Fin=;g|KNR(}3CVRd&fJ5LZD+t~=r}4wrg0lD))4N`< zRmElD=F1{k+%Dsi=$gbd#7iDaV#WTeSMMQcKiE^wsf+?;6^b+C!g3hSBfP#4CEp{f_3DGlvR#4pyLULH7@c%oR zo)rAqc%q;%#zByDxu(Pk$mW|nL3MjC|hN}T2;6$&&}O}pr*vVs zf}@;^!-KpQK<})q!%k6xGl4|I@ z@Mk`A@A9Aa%+ktD&_-OS#jeUf8x zi_#VUCo@E3*B%r%=O<)AV)=9%$I25PXAWNUidAYoL(VFdf7c&)$6d}`=zY92ZfjNz zVoauS2{m7d)jQtukhuJPx##0FYxNr6@27Zq#`+Ex&QM0P2j<8wmxck z<3aUlFLD5`yFfguCPXO6m(?+U#Wc!FqK?N-jN}xYPWyRkm;fvfE@5VtltAEV3!9z@xh*Svdn1AiX#8BDFB&S*WNZVPI{+mr6_qGs@oNob1L84` zZ3dntRRoL6vnIC7?a;lyeUrE9mRA@L*IoE0c&Ro?q!zg3}^G#kML${}T?7gs`issSSgf10(~qSm4hH z2xQFn!43^y%e1A^jm~^K8u+j(=$!-n+vp%8{OE$-wi{Z!!o2SEtIvN|qekEGo#tBP zDggBk02xdJWyJ>5XOoWr>GD13_t#ttn{}{38_|-&(#yG6eR$=ny)d?p*%V5`QeNMR zng}il)DbVg<+tn1Xo@<@QrX7N?|Nu2=ww-=7$K#G_wxXjBQyNE&o$Dmh2R-WCDML{;Pt)${Tcy& z1>b~tVJ85>YPx6q`9IyPn?(Wzm!hA9!dM9KIsh(X+Tb(VD*In&I=Ur&Jl*Ci46{Lh z{rpG@tTUnp*1BM-#rF2*-<0fVWn2Q#V?B?C%jBv>MH4_BbOO0GEO2EvhM$;!Qav*G zSx%scUP&0G`kabV#-ow0eavTS z0tTH0&z|2D@q%aZ`K!C6fy>W@^|kgtpM}6+N6|QxTDb4X=>knsuo!0oj2y^#_^?PN zWgs2{0$lw&K%YnZM1)py?tz>7_HtE-f$?tmX0q09s=VXj`X<5c-b}nN{aAr*!i%- z+XL69db#E`^6vl0;{D}jUzFqRhL61&jxcI51Va>u*(ca6509R^P10H{j`Kww4p_|z zeVf&&EOr#ps61Dw4)VMyLPRGlH`)#7X=aFDx|X9v#Z~N}7+F1&rLvC!Edu!o62WVL z{H<9Q;?+3v0xA^r|V(}ONlhfcYK51v(6hS%PVsugdk#zYWJW+M+)9(mnE6<(bz z1P$X-k@~f^!c%tuDMUUJ(I=4Z@OW(7G693%Piu{Vf`8x&Pku+4$W7NareG%L}BsoB$jh8?7<`!5Rps~?hXxnvrHxw3DMt@d6aNzY8_*J%)?@z1vGE= zjg_5OyDoqa!eAb7s0h31{J8fAuex~|=NFijfkPyr7g#OR!-foS>ZHZ>?+l|4Pw}fi zuG7FHap?uwhgqWdu)(3Z^HIP(n zR!mwD(f~V8?7?fcygx;7Ag2eZjw8!+$74?m>ifE@-bpX~)aW2**Zp~pQ~mxoEgN7S~W zSs{?AlMO$FD)ms3rVz6%xm6YF|-Xz8(K=B~}SDMd&sbCU7`|n)myeF|+BK^Vk zM=$Ii04LA@t4Bxo%4tU>9i5aP_gM;_Jtg#n)Fw|T!iTjG75$Q!Z3{<#WYqM0P>odN zM2;j>KCCs))ToU?uvBhuDFZZ)WNl+;XCFJ7%Oen#^6pSvK3S}nHD(brAOu0HUZF05 zUPaS8dXhhzcM=3#0lt9PIyAa-m93@up?fozf$)_qVFqWXhK8CT>)qJ4ygLRTNN|5yC8s z?^36xboZzN7H76R9s|d@*AkxPemUUi1GbewrAN>?ISnYkKYXC(rETsp43k--GPxYGz|0I8M=McnWpi2e+cR{MrphTvyVZ)CQ&M5$sW7r-# zIfsNexlx+B1c=(Ofxg}Mqm!L%sa`IQe_H7jLjsTGc+QaHA$*xUBEu&+Y8aBgPAefH z0`pHCr8hu%^mmf1k>*yAxIO}+>V_y9P@619Fug6fgGCRfF8mL^-2{bh9x@gQRCzs~ z*vVblu@*I2j`uliOpX?&zDz9c{e}UO;~tHT073-^=C=2`1j%^^z?bnc80Z_-Jw_LGnUA-)T&A>-s4gfdP};@E$3WH5 z)kUqI1ftb~g02llxIhv|7?xb59>ALz%vuhB(Gn?O!)?>1udY7n>FrhW@lsHr;hcYA z{KEwrs|c|fJBh>p(1dQ~L<@G7VmZo0LtpZN(i?9Ax0h@(C8N%V!&JzT9X2)`5l%`{ zZGH}>ZX=2n28%Q%dXWwJ|#6Tm};3NYBK*TJvH9^UdAwae}oDkBds? z_ds9j9pKeW1_`>k`i0vTzU`qxwa;eZ{>9&!@d4e+QcCCX;d2#y>6=IM0=Hio-$=iT z#)9An^j6ZFMMOkjszxn?A6$))z%q_STzGm=Y@za6%5h3CJNWvHO3)I*!NnD_=}$G_ zd;TADw9Y`64PJEx2Adv;N?6DZe)O_J?jMWbD^J+^V=0%2IC-6IirocQ?yXpe$hyFr zYS~BCW2Fb_AH3z)H5&;mFO%l$KlXD$h86IEU+-imJXcRxC8(oD@B{Pm(c1;1&u@1OOu5*}{uA&@b`;qu?=v#S_I zuVwohOp5@{5IuWU4}s&u_Fc2lwZ5%gD8yKEr@~mzf0b~Y^vLSpLz4`KO37A;3is&% zsSBPWDzpQI6cAcAXc_ZxTkeW;V%Gi}{@DjRQ;p+VV|aXmwGZGzuVt_zmnlY;lJl&$ z3aEYCNzXs*TGCRXOHr8Ly)!a8WU5n1Ec1sC>k*=&F37H9U%Q3YH1ZlxzZ zEcBv-=~ZaiDdF~m>1F6J{#7ah77}EjqVHP6rCLrmZ%fqQCk|gokyRAn{GlhV8JmB{*WM*cH`y4RA zfuT=qY?fkqsv!vP|09i10+Uq!3|zSUgY6p+9;rh^=D(v=+4>)1D9Ha6B1VCjI6#WW z$51_WS`?%4d5Z8u;!;2^Z|WzF;ufkt`^2Y3iH!XYn)b&5;kMv9x~ozS#OMFSnX*GW zZ|FKf*@7&UpBDI;6`b@x8Cto_Nmtekn~5o+0u#O)D1C0tN%k38muSh!W34c+9Ql^I z_FKda37;Q-f?W>blonud#tPjXOHE4~U$&X^7*!YdKjC$M{#;v6FB~vch!}$}g<8CJ zaUgNOBhI7q7S~-Mg{gZwNb`Rk(}X~l2cT@+AVHzQgow}(a1uJq#hG#x_1K@M2Penf zN`neb^a?PY{r5ytxpea;ciaHu*cyCjPSd>Ljmeo?F`&H-$;Q5$!2iLyQ7%d82v@EpC88(?5PSO8*N?KdfzGt=6_2IBDM`}9{eF+lC5bXKbJQ8SC_Cu9}$YTieKMr$TF!bGY27QZl1~ z$VsTJ3H>RmyuCtE0`T^H3~&G^^Y4JQgW5>P%ggKNF%Q!ZXq}rs?f;#c0>)>ZH%?w} z!DR?^uIh2?Dhgx7SQ3bj5g(yNQmpsRjVw)qlxL)WSVbBL;%31GS@ORR-phrv9}0?{TL#; zAiDE%O<=0l3Ki5s)TF+Z=VxGhv)&N~qqjs7sGJc?Csc;?;$i&ax0z1;S;NO?YY7#m z2xLzO>6P=J%b2qu9&7jp^WS?=)i0-N7glf}8k>j&KbtYf@e#ChL0(E?fkN~NN^kmY zPzpdK69_2lFyP;ixWP2ThZIPa$qerbQoWd!15-u#ZnEitWWS<9vJ`x0*LISf@_>PX zOWKso@Dk@X!I4p>0)piim<&j8J)ku89M>1$Z~K!sDl(^(1w4Axu81a5_|z83-rAFM z1gE_*aI(O*RG8YBp0AwhAah$s>R10CzTPq{t2OExT@M|S0@7WIq)JJPh=2%43DRO9 zC80DAND7FcfQYn6he)fWk_t!*NJvOXcYkx?e!ugcALp!VUzZ!%Y@W5&eb0N&F~=B_ zcPnxDUcxyqSUY0>J~$8nJ4@J<3m;G!`_Ld-=^%tRV%((Go{bW?e7cVPZA9-q|GKN4 zp16ia`n4W4e63#t5hP42`V7=X?h+S+FVj?gw(aSv_?tGus ziPYKRmn}ZKL6eS>5^r6=juqRpi4fG!)Z)A~MaTC>Y$Aj^k7p4Dyqvz%#KLshN<;&y`pM?kcY+!}VaIKNxgYX;b>tZjaNDMDu!z+3@X8;|~T)PTb8YfHfEwHdP zGH~dODXFOf-@qXRpbHb){ni!;i4K7v^Gf~>$H@L<&D@R}a&Mx8NqgIwBiiJg`NL8F zi$X^@>T)JeN8BWIZrDq}ZV&ZmahDqsf+!1d%ho9&ESf(1^hv7H|KcnpwmetwJq%I1 z|0HgPO!2b+pubiFiJ`bdMGL2{%2~tdeyA4qf$Nddc#<@ZyEbbgftPdc*5=}`Fw_zj zH4#yXi1z&s558j@`T$=*TNVlj`QGOdNT7%i{2H{I(6+EF47};a8#7K{HIC&6>bLL9ISY(*Ys<3hA32`b}h=CL^1b+R#C8xfB(_ne{$Ei|6A^AbU?bJ zB`7hR)2jCVaT{+qm+XmT~7#Fi0rM9`rV`)i1d0vM@PZ zt&@uD^~Uae-#x0mIWO%Qf)CkF%$YLZ00Hjeur?FD-52E$CLLH+5+ zd3Cqzm+u?oX8I17F~snE^=X>J$5k=i5ZGA1o@{q%XO^?Z3Nw~A+n?*pw(Z5&s+mY6 z`RGebHwXRXoI-H*E;CQlGXiGMaax1Ad$E^%<$d>P+Yi0?#|G9iHJ?anl5eu@9U9ZH z46`}@tvs2@DRi0vas1uH=D3>q8Pi1m*@c=~XHx%lCi&ln6}C-0=8JBBGgQ^u5af-V z7v+_jJ?XIlzf+NcJRg{ll+4?Be`Cs5f zARrxh@Ue`LdB}4haAwc}K~mDTPi)$aQajpqIJaLa&#OaT%c&p=TZ)%{ST(~qyw^{i zlC6|4#p4n@YPJH_xw&~S@!#w8AvT#IcpvKi(2LG|lY{b=`KNB^sw7t=)y6VC$AqX- zpLQgb!g}>H%5aqvtj^h^D{xZDO-*6^k;(0rcEfxuf2-ACfl82a1 zXOD!~o4l=h@6HCzkeU-qQ&4a8X03loAO4Q!GIB7!2?S`%QXS?Z>=!Q3UcT&Cqd?y4 z#6nKU{H*FvH;60sI}}Ovc)o70=hw#Ico?gU>uN~Q7+g#dF2BHd@!Q_f%F*H%ju*xU zzk5vedMBNPEB13d%-%@9X7*eRI6ZeNleK(cazHV?X~*l~V9$V0!xi|KstpH+`i12q z>6|}Of6%WdmK@T{x{kd2OOF(ig*6`^IJ2B-Pg=QHrrt3kXZB|CuwP!wY1kLxI4#@o zC#+leXpKXYZI$gz$Tf{sVgs+Wnj^duB=q0zBs+dhx;FoCJ69OA(OwO-p5?anuo6in zH|yI9bsA{p7Y3d#Ne~{I?+=IG=ym++*YWsw!gU64U(NPdQ_e(YOIDUm?cE0lHHaUG(kbvf4NqNhA6OT>(2HMNP0 zwt-o{MI_aqCYPqe06!?hIO=SdrBrVHWm#L;yNFq)*Jg{P5@Y4M&9XyJm0!s9?cqZf zPV5Chz+nR8ILt)5?{v%Bn&)smQ=S9br(2`GzOU|prJpG*r|DMTeu{U7`Kw^29~Ez4 ze8GSv?6tV>-v*x!10}G(FUn8br{ybL9+|K6NXa>OvB|p;m9& zyn)BiArDDZE;c4bx0d=dZBf|>(J*sGsg8)P8X`aU3M2aMSOvVO+9gdK#9|9dTY{3zBpB>^eqaio`2&RuqZ(jRsAv&y&m> zt)F!D3fp69=}&e~I(@Vz(>bC$(a78Mh)qWKz?hHd+OzM>BAtI+Zdi5it*=SRx(wrm z*dMV;pD}wRKoI$vrhU+;#_Gkns@*rNZYu*=vtr)2k5;5)&3o>-EF@1owzY-dK6}We zlB(We>eKYv(p$iLQ`R?t5$~R=$hMD6=iVn$#(aV2Nq^oDKKaSK?3Bo!<@=aTh9;UD zpE)-`1aUud{CVJDrZ7@NW3oqfZ`DU%i5}~fEO9~n-N?dXSMK8%Ruj=TdTMTb+^}`B zJ=pu%b>TzH`>V6Fa=suL?z+%@m*rZ-wFUihiYA`S^HOE%g`lGQ&cZb(|Lohtm21xy znwvrjw_29?0KRg$lIIb=tV%s{q*j1j0JAj_5)W3cxp7gYMyr54E;g>T4cCA=n(dXJ zNyEUSLhWLr-nw9p0(_uIE)a<(tN)`%k*1i7lLs0*o0 zoWI`V-(NpSj1`plvS;oItj3qycx9QTH|&fSUJiVPC3~{?75nO>piz^0$F0bz%Qbbb zu@P=LTQ^eUt!|7gg*vEPiXPOSo4F$s#&YTIeX(G9Iq#E6GTwyt8asH`*NyU9#4dbL z2^R46ppzdU91}ip5*1x(n~7(lDrNeyExiq8A~@;XchWdIJXkq896f5--&xbv*Y6K% zS$M?7%S!;gqX%Vr<`xzlyw_d_9A|}e8~dO;$=7S!Fu(u|WvX3jH~(>Gie&(}P}fIY zFa<1&dsE{}qk|EV)dKbVM@#|o8VvO2#Ly-fealDsu%d!-Y4{=m+Nkd+Ec)o^Gs1^p z+48$7t!Qur!2zZF$Es`)ND{y-W*MD_3WnF0-79Y$7-x2m17W%jl`4E(tRlS>Om27Q z>Vnz%>c?DZ%QyV_c~6eHlocwdMRZ3vJ5A}k%TJp5NxtA1v%a7yp&}TSo8_}QmQk_K zP#Lj$D)Kr8*(er_)cBHdoo3hMj^_5qVkZgU328S)fkbQFLysMY;oO}Qw&F~v=q8Hm3JxM}KTH(a^aKn<$~_M9 zO$vV6233aIu>W}H5a;$+M)zrQnD-E&rwld7DR3RFK6G)4Uf@j2ilX82{ic6^%kIab zqdS5~vjCm3K~5Oz(t2C*iLxR42D|cK1PH&d@D)2d!77(oob(?9-%25}B<+w6H=E== z={{Y1JNo&H^sx1pAxi$}x+V3QyM$sEIZ$$zvg2VT9cpv+ZFb_CV$z03IMM`(Hk{&* z&RjoRl7oNq9dMCH>Dar#%oZQAMM$_^X0*@_7|2B=(3y{5&W!3$DnO+G1~ZS5+R&4H zBDb3Kmku=88l1ds08i){rjD53q&4|qj1}6M<~Ii7 zeZZVr*Le1&2Wn^)%kcdvpUY1GDB{6+-e4fjQbWWJn+foC(1nUY;hd;nC&t1~f@QCt z?WwbgSPu_TdUAYsXf-xx{!&3VT&M(-M-Mmm?g9uckl5;X@lmNS*qi5LQ?5kt5v(W; z2?YHdc4ANulbE5ggQ5^BQf)q;(JL#IG3B#Et2(v>As0~w2^M* z`S+V{xpL0E`j>*&n_}9!R{@TTvR5Rk3`}F?l%dpG2<_#?PLYXc(5HRC(T{%YiS|ws z^`NWWmv{5z@+wRQRkG2d6BQPwaR2Vr+B58Q(SIa+)p;w5dUSa`bFTvjCLlv+ku!}O zP^}coz|M)XZc>zl#KZ5He1EqF$j7%=PS7H1y} z;f!8Yj<29rFv-ZiXCJfhXUoLZZ3|FB9WXw`_XUP4BXk!JGz4=+kc-AKYh6R zJe;WGc?kb%v?W+{9SWF#rN0T-D_ly~X{I{A?c-CAe9OORMw}L6d3&1ng!Qw^N}TAX zyLDoV2ubX$xyjklcW;3=_6J&ZtEDQ!`;`-vD!10*URi;ocd zGuP&<>QCC7d`#Q=%c3Xcy@39lM zKg~{n-}KSC+xoSz$aR{~5Kf^Vc_r*8wEm$oupUmlR2n(-SNp;IPJ40^5z-EDT`_;T z)ay6% zSvlHFB0w}OpkvO70Ds~PC;^H;P9~cq{Pc$>Yzr|B)eN467IsF4Q*R&Id*jo56SDjb zK0LiMs}shbC9ju&zD;+^Ws(4dQkB^Ys}HJCB6dXxXYY*X_?Q>vV2^Nq1dS{vE0&vr#ha`3mjYkbW52*)&Ky5}01gW0m5Sfdo6Mgvze=rj+C#vc7+UfMOT8}kb>LI2 zw-_5omHUB9Wy$7_3*MVOejR+^B8i@^e}O*qd-W+UNbR#rJci|al4n@#!S%*cH~A$| zM|cRoH1}(OD#(l}rH79pFikKnYybzU(1X1#F5Y*G&bctUjvA!&_koxN$PavQ?IMjo zTgCTIu;0vAsH5hJZd$sO94x1@IUzJTO+e0iL7gwvYu;RD@9p~^9!}1fRF(rxCCW)D ziBIx&L&aLvt|EAfHoZ<4MyENtZXw^xT+I#tz>A}l-{Clpr!PU-WK{4)T5B@x94WwU(F<%Xl|c}x^m z&gA!)i|6yTNLd7Hd}S-hbm{2QEjY|nfRpnh3uQvaMithDhSZOvV--JdjSS7~gA-0l zRu(@F0K!j267l9OQ?(s=7;#lw-xRYwMmI2GeuzW0vvbdty&1lO+iu92;w_~{&j%-G zzkRQgTzyX|sns|6VfY(maQjqK#)Mq%`*PpR*vs7FQwOF~)9^YO+q2E%$>BS=RekuK zz?LWdvG_Zia~$=! z80$sl+w^v5Go7lG3)Fg#pDl!aWjjQ`S>e3Z^gwk~A`O)`jW#re#cdR4^0C%qOYCsB zb++Q^(0%@~BY&`dva7qBON5Ivt+^P^1F0Lu&l3dr@|~RKlq7!8DNtW_*WCI}yRsQw zwH71wRIuX|=6QLYgYZJIUK?S$*A=?FG)mWUSwkr)tU8Sagtb_`H0_pft*SI*3%VXS!9w!{tRtpO*vDK~u3#23uM?Zs}5K*PH zNeOeTI{|W%)XPX4%K_%B;vc`uSxVWj!gU^tp~zj2B~aV~8y4!S)6|9~9wOA=ywtBM zzf}!~JFVgXylF&2<`KB&86G30VYA(tT=Md4fSHpcJHdFUKpm!wI>IS>1#P59MIB_} zrI&kjM)P318N9~@QVLisAL>oCy{zn$G%o+^IX&=xju^J>D-CKVr$L9yOHve-<|a4_ zH0I~8+Dzs25#33+@?w|cthHG?dOUf~mt&}+^tZb&a;A~L^`Td@Q>5pF$o6So=1@_q zKNkRir!ISn3PU7@*06a`{}}Y|6zJ6=NBC)9aLJs67#j)3u|5(ONK*Bz(uujjO}c8x zbg$}!Gpo5iWtALe-PmUgX0CmDEX|-HhxtulQb{WYnr%=@p7Rx0Gehz69(t~}zp7}_4jHPL z1CEYHqV$EX8$hDV^0%(?z;I*qAGqjCk_3HU7Dp(s0{%=jf~2|Sjahbc_M)cGhHq8+ z+j$NV=nH5SeaRY$HFJMwzR_AIXaxT~9Z8vw-+oKjzG=0SCr1BPQf8g)rS$RYTSa*X z`scXPo&_fFQ&PFILj{c}+zJ_@;IupYyOpVgo#sjIy^Ioe4VttfoW6^pwGsKGTBX5s z0m$<+x(K573k{5Lz2*6A8Vt!J?IVdZHb6{#Ihx#CHObcW<@gXVj9`;z1vYQw`gzDJ zl^`hOh2dW)alZ2HJXHLJ*DtXsw6@{m)g5`{=_}C8503480F3%<&8NjyeB-#Z;cYs= zdHs!Q?2PGJ%gGzx1TSo7n%dux@bwFkd_h%Nx%z68y1v+Gs?YOhC&E<6On{tW0@ASi!m5t0% zkP25Dc&hUYsU|B_RSp0c?j8vHNr~7fZXMRSi ziIBkL>HBLxBKW<$ozge>Ez&|ih~vCsUfx9k-!}}Rhw$?(HBJLUd98VQ|WI6DW%*P72x+W3R8Ou-2=EWX%t52llA+E$}hscEi;b1fQ$4 zw>W(fF{(cKrw}qDN*^(Dp2hpn`YNy2E%}$ogrdAZk#8@xb5g;xa64DN_}3BtId8{s zP<^rlheUr)fdO%sxehsR$NALk&UWa4aR8|A9)_WK)9fxo;ou|IdN&*v2Ky|QkjZRR z%%^6n&^|)wfpAPAjhbt=rF;!fIRx=5tP2xc9&kdxw+S3`_WaN!PXJ3{(UNb~JkaH* z&U)j=YXvp=Th_*>F(o^sURzUtuke5=)%6iV(B!DH%@PAi=8+9#NlG)ghASh_4N3=! z5&b}r4Wv=RssP6?NYlPbx(%+@e{#F1_RA^d^miu5r~0QsK!Ac(aFyH%J%>SBZQjhe zU(f`y%{eGmsRCQa8-ja%fzORjuYB=ZjG~w~Ygz9vKC(T3o)O780-BijFCW zWc;Jj^qo635qJuGspg?n_-$S_gb(dJXa;Tv5^BD}yYV6H{=D~3eRp@iOU|(m3FiVA z;Fg~puL5P_OM##8Ip&m1^#sAmUpGN#@aS^17$LET?$d{MM*7+Oho5aVkTB!=%*(C1Lk!N*4k>`Z0?ih>81&$}&~%N(qC zyX~(uB~ zC>fvR!JtUS5Ab^bHkm|}CAz*xG+Hr20@xca;vZ;k8ZW8?SLfOBop65=B${%S55;ADu2S#LV#Ly#T;ee4J4BO`` zYTI)X+oJxy_LJN6W&iUK7j6SmoQdWa-B9wd?>#)#V4(P_MnSoq^T*vG3mx+4CRP<_ zR*D=&2Pz8ZmTp;R{VXH5)tyqeC=IF}WTMiZOtuRRQ9TEAYDW;-oLbExF9T9L#T~sEO~*QhygDx|Y2G{D&)UV(1=KX1V@U0&5K;334_;)pfi> zi%|25#m`%&D8Y8l9aV{=1LwdHQNnWE@Ym<>9 zN8x=!BV1^eYqSqYRh zs2%)*TDYA3Y;M5=MMDEjSn}pcsz8(&8w3`+=$!OB9~j^tpyZ%LmZvc7o~Nsui<2bu z4Kus^s6>EXkw)-p{u5YhY{hI5!@+fG+xRC><;LU`pPKW#Dy4}3c#iN1tnlLAId#oU z$UBx@9~J56Q!?rntd73!$303dD;tSRy~FSrfsmhE$?x3W5y!>{kMzsnA9xk2;B(zs z&aT^MbuyyPpf>te)-pljSpo+jrSFctpgS9+R{Nt2(SJXL!`_-}<_`4kVG$VmQK%0c zT)5Iu#a2u&EYEbjqVRvY1SGF3Kd!Ki16jQunw3Ndj4LDpSvt))OtlD%r50-Wjvsp# z^F|ZXGO^|UL=2ZxyfA`L0{6vX@L$`LBP0CD5&*b|7?)62HrF*ixe@h*SWz$+GIM?TtR7h}@|05?pH2YVpza*UmbUG~a$2QXdR7T*#;#K@K_RZ>m>EP=xh>K?j&T zCa$5UB3Ho!K5e+YP!_Mqa$Sgf<^fVf#(}=osJ=NP%2wJU8CK#_AqV7`O;K;tnWFd# z{K(#2Pi|kPrE+D26z_9PD)Qp0jVu3E^^=Rk0sEJEzp?EVb?iu;bb4OX96Yq*4PK7l43T%O!@KHxKzAWv0}i192{) zJGaNe@HYf9$Q!}As1^-KGZ(Owxzax;&4>DSTeXa|bFR=D zTsR!Bs5x^Tb5(lsEVbw#j^hNu6Dl@g8de-`licadZ*Zs@$mRzmuJTQn+dg9?x+8a3 zX8nSj1?oGf`Uf;Q@60A`_mHW zlvPey7RZLs&1(jh+F7e#@Gn%io+PDOjU%VyD28*{2(L(O_$q?!d8CCQMY6x1*{4K)&ULTgqXt>Lb(zi2jZ4?n%g*}Ua8cp*qRrVcY+P#E$Nzj_ z_RjtzYrfH=lGBFo*4&wgsm_r>Cg~{}1j57~X=`Nu6xcWVtb~~cQ7aei3% zKy*uKoC6|mxW6@LFD7M`_|waF7@26I8A??9-QuG9VoM|tI}I`XTB|e zrjEZkk^;*CFGtY(Eng?={}SU!kIKB$Pa^^2gp6K`B0(a%k>@u`bZc<1G)uQ^?TE}{ zLSTH_f9Zeh@whnl@=!7!?H+*>N!4dA6<#DWeh%l=$aK zZr*HUK|xf?%ZKzSQjodBxy{Z19IPVyGAFr(i1KUJ4NZ!g&-S+|zasryoL#D!dDvc^ z|EJx?nfC5r8P7(h10gcQ&yxgb#}Si<>$+MH^X5y3uk70=#QQNcC>!(+e0 zchY1~9ch~(Gp|HZSh%{PH8U^Sydl0!`)I)CR#sMwfH_a&GM6N0n(9R$We(dvew(SN zOhfJNzIx<0xF#FhK!UyY-oC89iie`5fT5_up^hca*Kb&<^0p55nd_H_yaq`#u4TyQ z0p2|hG%rQqv2cLWsn-{n? zi}7Hm>}Q9+fD*w5QSZFt!4Yj=gvm0%%qKK)N-&_GI*q*Xx7{T}qY33o3G7#tOg4TF zXsOA*&VSm!q9oA-`zm6IUoJPo;cvhQpw8*6kxVBCIrB(?Z|ql*nCJ@>&1qlgmIMdtFSlfYrwX_L7G{Q=pj&Wm5WIH zjmfMRWgF`AGc2t?+Mt=1CF?t9M)fjDmv@DPmY^Lz@KREjqz@@MC8}2g!jC?l?@Q z`GUqNfr1JgkSMHN^Z}V>#Z;^@D#aRyPGmhgI2x62dT##3AU!=jWAG!&nwsR*`>QZn zV8nBv+<^^_myvrnp+5~#{pIcwX#X#@iQ`eZdgPYvm6?$7W^ocJ*xOHtg!i6F77kb| zZ;~cP^Sz&Z-e&5BMjR=C|0(d{S6H_FV>LCiF6~{K0%~h>@+%5$5{J>MqHkCJCs8-P zF<54eB8Ei%;zQzwc0ZS5ZQqLzmNT@%a<({dhIOM9ja7?e4p8ec2)0gK8BsI7kn}30 z5uR%F32ka%sIz1T-9#oy3|X%ddJBw{oL(UPNVJfGpDOoG=pS_yj+NK*ueodFrEkn) z+xNT)j?0n`5WAl@?t>vMfghKunLgZUNoM;DvZ8Guwnji>k_-$IBO2ww5Ez`T7+HO` zEf8$4&DY(H`IRR5Ln?HR;(wS%@;oXv`hqg6Vb)a|7!S?u01^XJ{d)eEQELBL`%;Fp zUeAa)v0Jy$33yEW;w?-sx!(r(Sbl){>RQ8433Oi<}NZ3lztA8Fw*TapUwg&>f(MTT0x7 zi}ZWXEqefg^klEYJQj4qD5#D`=fN1F;jRpF>)}^gOcSnxySo(VEY8w}b?o5dJ{JR|eYm+96Fu zOT{ZmZwTfsF@U7>IMS7l?BjDnf-_fUQaY?FJV57@|7)pO*ktU3L-}npKF%(q%oFC` z(2Ao6!!`J||C8n6=$jQfC5;PSi{G9U=>FZ-kU@pWficZgf zrtOQ7eEkywc9)szsgEHwhO&hb{p=v8nK3^ijI|{QX8vV8sacpj@GZ%GgJ6Y-->GUs zOu2FT?Ad_sSzDLtU-szmb$?UMhYv-;f~CK}#JhcIuv7rJK>MbdSy@?^Cty+yjC#i! z+gIXWz3Q5*{yqL2Au4KvHSP$ENz0$b)~F!^PP;2;W?&MV{t-~m1qKqXDzgkMUHPtk zBu>nG+pLOxX1?8Qi~x^HlMgBzDq^$Ki}6;3cvQzI=(I4AgL>^V+xAOBu0xF1biO>X zgGV(To>X}Fs|z?Qs_Kcw_~TzfPjXxxUocSzLM>2H6tnb(ZUyMtQgFK&Q|gC}AhAtU zZu=KQ`A;noQktM{z@oY-T?~<8kEzY&ex}XSeH28n=bs4544L4nB!=jw;_#&5-!(Zs z)5Ut`F&Y}FN>4%@?WTRy<6%tkj_(zh6c6~UjKlCcy`w`A0D381Pvb}Dlc<2G0ovO& zV3}$EX+=dfIsl|Wb$^Oc>5DJW8+Tx;Nd-i__aJAu}?L(i=ra-u>34IBEPHTs=v? zt=t`#q0d8NSgJ&Hpms4-PXNz#sOk-l?ND(&bv;SRk$Cwie(^Cs73o=+FUyxeq>tRO zj*B(QJ(Vu4DBbjm?rbP7Qu_KvGq{mG6mAi|m-}hnKKf&hDQW!-iFpQN>%*R(*YfZ5 zQp0mWur8P4`?^W8U994nYn?L9iJrkwo8$e*qM{PL|8;wogb>UI5q7~Sv=UKTs3#Q$ z!R`~#><-z8zyNW8DsFYQ!33ly>_n2@yCoevU^uCA=gzy)d1!(YTredzW07*gW0J66 z&-R(>fCG8_(Z?0&oLDW7)kO$NBz*UIa#OkIA+i5(8rd>g7Cag>o^wZz24_B!^D{NX zMd(NO#LoV-yzKC4{sS`reacsrN4|WjTFb)%p5eS?Df#T3MZGeGlk>)0Ri3{4FTbiP z8wUILc5U@@`Jy%tJ{gC{r30?hGSP67X091(&rd@-BV{$K8g+9q5y@6Yx!KRhVg*64 zvpU*3)#^itv`lPTwZA+&IZYyGwMw$aK7;p-?SqzyKD<1`_uko64#M<%^l;E{Ufp`| zU+%fOHrJQ`w`OPO^)DdQ&>mBTl`~NEOY3BrD=&%DK(1Ogwl^Gxw|97-=U%hP)>SM( z^!h+Kdv`b+!Je?ne&B*K#$;6VM3hf#CzUxoYO>_EMnowUR&V({*<=w$K z$hs|@$IUg8&L*1~@)O?Wy&ikCWx$}G>lpU`f~v`lVP-68?7dSobK$VmwTgN}0I+f! z;&B+-`y;i|_>2n;yt(=nMZ<$-u6QKGM)|IL&z+>Sw#ti-?#N3cjRb9!E;ztlA9tEh z)pa&5{`z#~vv9+Y*FY(UkCL=h4km6hYd{WE9hX2n}umj-9a{m4r}H-A~tf znXAP^Y>@+Ez7}IUbz=PsnLUDpZ=wU$cEU+xgKnD&#{9Oc%luZz)1C!GNU=M6eI5`X~%hryUjYX`%{M}KS2b;vw%sNNw6CTFQP zcK95Kj?DrV&m}byU)3whu5d20Uq#Qwe*Darty<11@>$PJL^efj<%)00niN?FGFG?7 zYsD#3U3QQE8QGdYbasNA{cco91k;qlci3c8OyWKHLvv(v_gL+tTvSGgNIizm$Bq8MV9jTt_hf@X*+oA?@*N6sM3E zWm7Nf$!OqRkH_X;k>9xacr$~vXXwQT)phr95hzPizn}#Ji*ld@UQ8ARR8F^_>}R;f z@R6fAAJ%7(1m;nmy5!#cr;pkM&s{D<&`xo?jQH-aEu4G4v_)bOUlA;)ff1@9qmesz z=UXkHeyHJc#VsM!gaat<6vt#0X~6E$WDoYx^x9XoOOOIrfZVya8?w3A?TO$AMgdKr z!`YPqXQji`E8*IaC(u$-X$~0iwW#qteT0hFavkBdXW$y|(b@KS_FV!xt739`IxQ=U z2+ki4RDJHUFi49yuFq)CY`E4qvt4|27JmDaCN^JYsA~Ap(VeIXFsk-J5FkBh{dqhd zcxpHA0a!A>l6=Vd?asNr0+X;$pJbr!U7zo#Kr1LP)b~%4pmJpeNGR%~Az|hXYzsFB z@MRpPcNsEu@r{I&O<_;%U#*5trx4MN8^UYn|8ShjQ%AI4_D8+o3U;0|7&j`$bCfP6 zD+d5!>##R}#o9(Svs_$Y{`T34EvrMEqoH=lQ(4_hC`v-8&X-5>?-gD-@##o>I2qb5 zwNnK{aT07l!||=y8itq-Iuw8U#x#W#9|5wD^ItT*0s+*8heD9YL%{rMXL{Gk;7Q&b zho7>%J#Lfw%-Py>wK`zyU4oxFS$`AAKqoHkk(j%lOTL+*chx{<2`p?VdFk>G}N2wel7f+x(-C99It;=296+5tVe&-&Ua0c9Gt} z)zqc|DQLZ%J|*5p+mCznL&FpNx>m+}hSQ>HQy}8!GhZSGO1qg2v+|FK-GsoV5NR2e z^Q>)F%1!brB`&u7kyMCR`-4K%-~r}*b8vB8vO6^sshRn}iEaHZFxxQ3fu>$%^dS{6~t2*4SQ$ zl}p$!e>{A*X~xN!UwZUdUs)Ls)%9YKP$e*3jNh>TGV`}cT{MewBH@I2j9adHybB6c zHeC3c@)l%D){u=+1mhSik>&OK~XH%`*6mc1>97^`yWGMK&IVdhz0|Nl{b7`SB)R*CCi%bsX&fJp zL2#lf{dEFCn>Sh6D@TL5o?D9*u+nS2yNk{;Dn0)Z zr9UupVQ1V~EW{H;ou@TwCWc<@Vw&F7KZE!l3gcc+k)j6*bm<(ScfK@xHd);MDfCfr zs+hE))ouQYV%}Q+LV#Y)g(|CbI15~Li#7i2 zO9=|Us!QR2HBjchH5IDqKH3RH>g#!<;0^U0mqNO_EOkh8lK^o zoVp69tmXZ$Zoo`FCCjXR(V6+AhnYBtSU8Ml&G3`oe#VMZ#V|!-b^Sd)2bC*zYvK6( zIrcBU z5EdAfgpXE5uDWXGXW)#MSa34rfv}Gyn*UuF(O5WGO^x>0mmWH)W_)s_ays<~3CpX^ zl(N~*@!|gp{XCSW1TDIeN4@zCGh|+YJdx7%(IZ=&ef$AQq$ z&zY8+S+)HXg0ig<4yoqz3X|7OCoh)Q-BUa|(%|{=Fu`AI_l}s#KKs$C z`>1<=ZQkSZgvyiJlgbnGWB*HBvG^7BSdkcU!v)-Jt@11v7cN-xqK(G>Nio#70-_d3 z&0#Xyd8tj*atX+1VL3Txz~7<9YG1DwMzkAzDa&t~xL-{6jGf5la^ZC2+=fT#hHh4) zS~Ol}H$#shA~#gUk*JxeZyFl=UNiGUOW*m8t=xO`^G=no^Uhm{#rKGte~*9=W0RYw z72*2v*R?WMn-;?-btz>f@TWFSf~_xY&if6vHbDkBpypZImb_QaX~qpbYog(eYVeZWjGuZkKOVvyQOSzxq{<~)F?s*hag@y1d-gQdIS;FTc&~CO z@Qv5{?wa>Rlg&y0)*#S`*O6CPd++fxhnAqmLI~k6D7J#{*@zIlfQFW;ePC8VVNuJ| zeXp_V%15q=$ue%Ig?#UjB4c4qnF!Y7W<&S22s^i%MoQrw`!;V@%SsqVR4P{lVSyGV zBuIGm#;R#uyI(;*2B0Ghcy3k6zb*6BmEdx9dq1xIZfFjh;3X1z>ZJw*G7PsC!b z424z&5hSqahde(RtI+V=e8T(o>g}-K+_oD+I0-L`J>^lW^cxKRW#!*%rV z_sVJToOwO$i(5Lxo%W0asQ)NcIO|E47T7J^1b{_42Lo5d@HyPMdxCX%+aMFW|J5MHQJ;HeV>ji` zNir)}X_K%rGf$?WXko>43)=(X?4br&DV?{&IvvAl@f69FOM>73Sgvr0YzmoI*&u6i zN*{mNVWoVpNu^;T39_68JKHSQwjYboC?U6bqnSBR15n?b+soP*Y8xGYt_zx#UDprP zlwB8wJhJ`>Lec$CKlkzpe@*hda-EYb`)dyRU(GF1W|{ngf2JdE61BNyOu4YRN~z16 z1ZCWC=GZ**WpWhx8TqU!p>pnPa|?#VSLjR769sbK-OqyPF){k(5W19?g`A3R7c;a+ zL}rcW0?E1}Cx&S*@D%dK;IT(ZD2;NK8@SavU9={FS|eIgiCjIpX}vy<`AUJEwOFbNe-;baUO|VeDd%C9HF_| zMe*}NxjeS2FEaA18*^otEB0Pc3-?aR>AV^T0mj9ee`ML<{ZEbK3IxUA*}pp-4Ek43 zt!#oKoBAqK9&GO|()upw2B%-ED)%wtEBx3> z6d8LfAX^Wd6PwTL>neU5Oz*WTTp9okU{wyd2{AN``?wwQZEkDVsD2v zQsExsx?%nA0(^w9-=J!g!|*FqM?$f?-Z*v|PmFLY)^Ds1nJMQLHbpdS6*N;@B>O>eGu5HBoZpc@_oK61No(PpiGaRt)(O`OMP@P0xubxB8sL#9U^OWL9!?=px=jN~pFhf#u zXotba!1t`&ckQhWAj^dRL)ix$h#mkF&&T13^)Tj^xbuzlCasj%cyOVsI|ez&3Y0Rg zkSm;~%{ISR#gn2R?N4mZvWN1@5P@DwZ=mL}H?aFg73h|dG%^@G?Qk7Ru;+zpJImR9 zKEE6l|G;o0d^8nBP29j`<>vp4qXF?uF7M9oFk#E><#Dur#~^Vgj~LLF0T>S=*kSTJ z;7ajI!~zF3K|5D6~1Se^;v3)6+SYFcTLxEbxESfkFTAG0ejd@6(#iZNpC z6!n)(DTQ&)3)~gA!)U>Ug+t9UeIed^7AN^YlOgQ7GvmTMh0LT9w6g!_%THyRG!H-fwW$1!Y=24JE1m>++|1 zowP-LM3NJ+4MwvB#vylTjeeo7MAGp+J-PsE5yZsAfOxD4B_#y}RQ*XuMM2RpA5v0V zR#;g0`a!SPfiL*k^CAD$yL_PkuzB!c1!ldQgNg#&mn^DXj{_MVQdwE)Hs(j@2o_LQ zzp7jf%k5bTs&{Rm>N*AAib`Sy^2s-|vCT4bTn%30pOJlfI}Z#M?`_=e=rOr|Uy=Wq zSjy_wJoVugj||t-)mf?ZKe=(I?FeZ%hU$CS?k0UYGvlaU=M>5KZFa4*3Ai%&w#8*q z0oHD_Jfr7~2A*}?abuclEPpO5eu{1jx)l)0ID9RAnw1P&H@{V$@3@-?uPk+VTYrrs zkHGF!#C5sUq@K!KJ_Viim4c7Ns|!g^?c~c%33D6Pn51^Ki)!Vz?T(9D=kd3;<<%78 zI?V`!Y#=19{m(u?DG!SMjT@RM8w`MejABjFNM=)teyy5l0H0fiY8N4l$Z_VwAXP-b zDYqaA!53&?CoFoIqyK#^rJ3oLj?qr3gbmUbFOw=m^p)>_(2Zy8coBlmV!1A+WLf&X5dJX1U;HLtf|6^u1c4eP+t_oe>oe6)e{%*+bFfHK4Et!6rZ=a&8+i1dwSVbu z`F(q)QF=n#V)3d%VD8}CVg^LUbdMk853}4he?fsF%e^iYtF=`egDh0raD^3!GQjq_ zrtkP*o4z=xpooFWRVhgIIu_u(_GvQt*)hf9avt*vVDo@=#lGjMv3{P2#+VR@Lp#BH+RCF*?PT9Q+s~#ckBhUG1cbmi~dIh1&V{s#kjUW?R1q3(!P_; zQGhP_6exm?0JsOZzE3H0{>XLb^_EL4frqY5Vn`{|yM?))|8* zM!tcskN)KK=mrC_ridkPhCKD*jd~D#*;i`V8%TQUmVKf;23LW2_+?0at}i#hR{5bA z;+Z?WxO-q*>zVafemiA9xclQE`{2sW;d3~qvFA9>XGE{^PGb<8HxbF{FP|D-%RX3; ztz8@H?Jfvr)pq!>H{v-jWW3>0+iK>gF(b?HV$E-FdUwPC-k)3QG9`O2KC*V)NU0E) zo%=vRb9O7GS#scMG0FxxIZu%|wxrqIm8Snf`Z%gCfS4IFp?*#qt-J zhlJj|bc9f{*DA44yy3z%IH zWUj|PrGRDkJS4jWbIE_Gp}Z?lUIC2VmzeyIp@)gqv>Sh?`}Q?(Y~6g-N&6@4f*+4I z2d`|ZNYSs=FWyZJxT$myoFA_QkpBgLMra#oEy?=7X-Aaz5R6#d)S!r0JhqdA)hu`CF-*y z071hCRprg}>d4fp)(47({vrJA#{nHH2K28mj&GQ}r0yt7H%dfnF7b){S0PgF84D~^ zwvtPbml#YIwB7A}l;0FCrd=@CD}-x^Sgvc{W(?DwRBNERB0*4;WkM}Wt@*O|_gGb% zW9N^P!OXG`JNF6)9Mpf*g+w9ci*8~4uI%4C;%94v53u&M3LPX4?DGQVyEl-kG@+Nh z&++Xj?&tpyg>{5pJ+(kW6tN80w_dD!LWn^?O|7b~-T;5u^H4e#hcE4sa<;PWL}pfu zPUyWBI`cTh=w6^zSlCp5KA8Ur-twZHXvef@W z)LTbI8E);vLxY4M-5^SXgmf!{DBayKz|h@YN=bJp-8pm$(p^J$cXxab=bZQZ{V|IL ziv=^!zV98^zV@~Ghv!vCdB=RG+};4wF2PPeNN?R}^<&7aHK3nFfm8}W0LwQ?sea)j zEr|@I~mqP9{>XDIiHRX^Ge&7Y!M*wxpX5N zBnHrNE7m|@2w`R12}JO*5sOI=80h-X=ragV6uV(~55G$LzD8+F)?ad5tQBq&hFz5yDHchj4f&+E!LZaU(hge$tzIvW*IzA~Vy6{_HW=IbFC4tEm z^wwDv2bG2T26s}YsVPBaQb$JzUjgrvlyBf0Y&<8HrZV3n##$BF(pPFURDz1II6Qtu zMJkiI+ebU_QJnOrH*Y?zJPOKX7;j}X07&g|nuqC8>UEd;RRwH1`3=N{)oeMO(lf}c zL~ZYRt!V+L|0+e-vV6DiDka0Rcy|c+f;WB9Uc}tK;9DNXO_?KiBD?1Af=lig>i<_! zIF#|9^~_Ys)H3exM^Lj1t$QuA5Eawt{649mn5Lwk1y$E2?@!#=FW*tA1F=7$Qp>Uf zOsP^GBCqESw*hJcENW=`{4IdqqiAWiv1ux1BC^GC&b zZ;fF~^=za%V`I^+1u8EK{?Nbzv)&%rB5_T#^Gc?=#b`oM&<_d#3H{+0UAqZ+3U*Dl;Hr0lSnk{`1l-NYEAeEA9CGV2{^aD8=T6{sX@|RxnByo5 zh|E!3Vf`bnrC|3(z%(n!@io7w)>BBI`hYGsnNZXlNZoYVPu?jqnymiJDRa}hQgne* zomqp!ZdolgXZ7q^^N75zxzb2WRg$m{i8K?Q$4}0qbgpz>IwGeXO{hF7w{huYn4GZo z;=^`C$BHSv@=k)8H?svgaGupB4G2}k{Mb}Pkj!QD7O?px*60~Q5F!}uzXp1-5+y@+ z{#5e&UI9_0mA=aXU$HwQ7g1?)k!pMOidtp7SR74oWZ!1@s2sc;o#PC3){H$!EdGz23kc_9u_b7Mgp@ z^cl#0;9vFQM&NIb)439Q`MZqqxQ6Us%erfNcN*Jr*UO&wv_D83bT&z@1li9(BnOmL zuz2+)=?@AaKgC3}1Rx@p$VNzOlv$fsm?v$|T#khQxj2E?Yc&cwIzs>j@r$!F_X~St z_u{en24KV1C=LOK(9L9v<*kY1;qD~KTIC0V{fSqmzz=AaIZO3F*AKYKsnk0jW(zCz z688uObJ`H77NaTsN`JUP>r%d#{SYFST4w7=$+800T@oz8V#-FZ?t`p22B}=jjdKbY zW@RByJv-WMM7Fhyz!0+hnThfQQO_;F!Dj~Y8!d6-XXLXvn`S*-raagRCoCqn2yE|f zpCpU9omLRp$p2Yz`4viJ5>%I&BO%B*X%JpFa0>{0){Alh8GO#0#`_eC`vtxN_IT8CaR}1s~uGOsMhXLV3mr-wb zt*bYr%^|2tCJskV0XjIyY76+TcazB)oNkx*YV5>NuLXOv0e09ndAQSvEC_IYFJ`o}xCb_f4Fbau{Z25Q9zcJdy=HTA^AoBL`*;tx;7t*0*z_=XE;RWL&mL`lIk(*aJ{BQlXmICm6vU+69%T=(0HTz+ zdh9rRX|jy2Y7ERVXmNkB%x#uq!Aie^oMy2l>^UyPI(JLO7ncZ@by-uRcs}5ZL$sU& z3lV%4v=s&+r>dj|k6zZZD$vx~%PCTFY`=Gll+r~uDf6vonDESxO5<3=nJy*yT(+;i zj+$4KMG5@kG+(K{Q7&zsVKu4SF6UvT3uv|S2JA5~s3o2yt@#OcjO>4I@rVI6Tay}r zKvdF!`2F+|Sq(}?{ytBW9!Rw*gRaOTVw|%V-`C{OeXy!YM+y6?qMk#45s#O5-FO@8 zIH>1UYvhqB%O{6L16__4B@~TX<2)ih~Lz(|`fg`fgA;#}< zK0Oaz^AR<^fXmEaWI6Khl1jun0a!TXj=##bI>k}Q-_3c3mWj>Dm1jLVawl?+#AVQ( zJo1XT37^Lb-PSBEKCpi9Jcsv)I@+|IS~Ws8_L@a6YsR^YPvzUsif+SmS^KGDP_aqm zr~OS#QIYe&?rD?h z-j2|=(i98pvtQ^?%Q6wLm!nqG9E~zmYnPquEj^ey;d1+s>xQJ_CLXcS-*DQ*aC5EQ zo9fqzLk8&l`z8p>j>i0BlS1zCbHXCeF-KdF@qgZ%Izz0%u!@~8~r2QQo6@!k`mw~aNei0%SW4Gv`y*@b&US8 z5dY)uOoy~Jo7tlgtOJ*aZ~0TIGw);^Jm=0#`#nH!JM(bpUWg_Tdr0Qx!u~1sXd*;8 zoD&EMlDrm$dx1gaFG-a#Sb6q;2Js!)R7N|r zW#bC{v9?|vx+x(M7|{R{8e_f^zD&s49ry@>8ifmR8X}Z84NLkZr8v&D673$R9!c!( z$mdZQ0ff4~EpT^9){846J_!eE|GU08q9YkXXs=(}99p1Ki-$SLiR=u&`uO2PCmn){ zSH|NV+5()QYDj$eLijq?Uwg0sBg>AY#uMm`^{|1<2bR!p5gP3~OGY))YH%fCZLg$5 z+Hth69fSOs`@61Alq)P=7aun(W!jH4TM}RO#Uiv?0+&8#Ge^uCt8jSCIGigwnkVGz z{E+ypjpd+q9leVV$JrLPF-J_wAysEm&s(rqJJs9s@!Xkw=`l(Vl$=>QIoe+1z#=0X zm)$u@4O{_AX-TM&VJ+-c8p5GEcnjqgaga|E{KmW~xat9rAv8AXui3iIw>i$@Ebg3J zf!%^VQn~n5d`5uJ>Ja-9OU?F+oGX{7;e1)QIst=6mbI6EE-S=-JgkFU?vqUNUqT8p z$}Cln4pcn_aFK^!tJikLvolU}1?i<;+-Lsq{3lv-OLc#cKBGw98Fc7leyEx5j71Ku zvYr=fT~_J7Zu&M``%Hh&SfqgYQ*2LdpBO>*Z+N_T5+fQ9`Fr4CV{xi9`sZ1^n0)Py z+@gfGYvrk_d;8Y8n`EvbgNHaxW?sw)bz!t(aykF)v2RH*vJp$KRy$aT)o^-EL%2ix ze|DsfwAvld1w^AF0FFlF%*>2YnTR`W~eQq>M5;0#*3F8VDA{<8$8*o34=m zLT-;kF<7b`i2{;U&Y}~evxS~6>*;)a?Zztwp&2X_{fkmQVK|4_VBx`eF3pOB&apa% zChhMM*1>YlbyA-xw+@?wTc$GH#MtOx;v9E9l7kvBsGu`#I(kE1$-n2BnBn;ZTcQ>X@*CVec zM+F&e>0_?{Yr%P`27fb{WxDF9VI!)m-F^}i}qvz%SMRyeyrPJ20G=+VYA>L z3G07x7yKu^c2nSYY0lfyqd3HDk*VnfVSoCM zgNP*EDL||IU9_9EGMFO2|UxdwH2l(|FRU_F%x%> zu8#{2#^d0}_Lp$NWFj=mNwA8eox$ zAuv-VE-7imdrDarg#BkW8H0A*e!OBfqCP+phNhD2Ga789@rY(_Kfc5z4Tp#)Z?VK1{K;Z_2=b9{eVhij>THdX z{qbj2U2QdKzz2uBaT)|}3np_Lnx-ei(#W1~H{`L#W5*k||K?eB3e1z5O<=pXNiM+Y z?n>?U=%`T#{`!x{TVI$he=9AC%3eGCQ7=8$PImB z<@j?o{!NxT@;}=TehJ35)EXiqW&`X1|uedP9RVw5Yw@HpYP1hZe3`vhw*x7{ea8+pBpjO3~)II z0Et2(UR!;L+LusV!(lS3>B>ovR2T?5Otrh|@d>JPotKXS8Wg*U0@3MGn#q(K~B;fA&ZGiFH zAs$?lHU%FUb1{)EFi~>mDw;n6fTMf`$rfQX2)HXoDj#`&HCbXEDHhKoJOhn zli{l^EJeqc%u%9s`l;0ZDa@1(CO$Uzp9FHQ{?XaWy-gL}+5#49jgJDyGSlBvd^lq= zg}lBPfK~HQW7bosH7bU|Td2@MRv|g|4_|$&ydX~iRN3Jnr+=s^`;5&3`aa?dT^~{{ zks-yV8ttFQkrb$6WL?XyiZ+ga{aXTQf8Y-Jc*P|e=%!d;0@XCPO^Y>u!?NBV?+DDU zl$WF+79tnT_`gytzX@PX#{#l6(`CWfbm4u7=9=0eBbeLa7>BoxQhWA)p~@gp3qwZk zrszcBbHQz)OH#yP4kr!=IW^Qp$cKr1%7ba<`B!dFZY!Q3f~bm^eqPJbXb`o(nZC^WukK;d1xTX_lajF%I1_Mv=V_`)N} zOHoW3^t8;Ka<@6?Ikr+jC_u6whtwk7ANnyvrtJq1-rq&;_t=8pmN(RzRB#=OY)MAU z{f#sC0}q6fG{hHj8m2mVunY;{&d1?IVH=+{hiq+{{1UF+?NEDj;BXcV`D14F#`k?7 zw$*|SH_N`Vngf%}vCE}wBg-*TyYMrJ8O#M7ez+atnrCrX$r!VQfRH~{#lUp@TSyc? zLdCa|G7xhZ6GVaZwdXEj6@qU|?Qk659IiS4Tt62-8W~M*zg`1P+|=gh+X~Bf4fuq6 z6aMgBTF$3U1%j+mgGQoX?Ix=8pr_~3AEiGdR1$2k=&O$y#Gw5js`T)pz-ZEsw>6SE z0`y=df9aY20&rv1qGar$p8LGEd*tf-U`|n0f{hJeo#x`c+3*So?bFF7IcUY!b*@_k zl*M4h2|!W0chcw;RY}ZNtSd!a(EFZ=J7upZURMC7JNi4wQNsO+8n#|l#dlUp%OuW%d1h8uL<)Q@PsMQuyyXH#|ow{0OLq@J6L z%eN@^^~)1S+j2ennYeaB1vaEvI``w_H4uX;ro3@4!G&@@@^YEAuK)8_#1)Om(4`CS zMgJNMb^PHgW!^a)>$8W%Rn}qx->HGMSM61ff~%L1aN!PtS(E*51~PK27SBrU96?+{ zpipQUJaL7!qIj!emfEPU^IYSpk&2!~pciZo%5O(PY_?fipGV4v|GBq}=u=0u-%N8J zVR+qv;inBv)~NpVv|opquNz~im{#peM47WYzRD^@BI^Giw3G=bPl4F17kD$b;}wZ8 zkjbzlA$)a@xPjOh-^7n&tzE(9Br0DRrle#WVdJ%BqW@hA zsaUo4Zdl;55PxVO!5~wx;g;kOZ{wNb3@Zi_D*C9SnX)Z(X{CY3$!@FxhN_-9qK@0ohCgZom#OWhUbdWX3TMBoZ2E^cbq1)U_9GIt8Js$39(ed7tS5;2ErwZxV;MrVte}h64CWDxwV{5$+s?#h z&00$Zv!TWI50RXs{iWl?gD}Yv!_F}W4WA2bZWXNdz4*=k@O1R~=fRniaw5V?zo)W7 zGB~uVH$%e$*i8BKAvyK$`n&-L`k&_x_l}l!y5RtzY4iGV;ruaiTlUT1d0nCklQE4& zD4qhg=N*zx5qv+q{0JM`nY%1(8SY*G011jca<{u(P9n-HU7U0J0D z*ZvTwR_qUTR5fXs7FojqJ)W8y?5?wIb|h$AzKta)S#^IMPjFF;9~d8-)0Y3m!WWuHiAC$meig_K;DZcmmnH;&pkDMR0 zkd^jzz4>2kJ|Qu9;r2QR`QDTfA}sz}ZF*Pip8+8(S z3Eqmv!B5QRd4-KjODB+*0ImJar_fr<_@MOZ_r5SZpVAzyQ8@3?A0|#YS z^_9Qx5Fs5#^AL9=?bck)0q>V81t+f`SG7EWyJE2%H9OiiiiFd6|eDcz@0{I~R-j+xC`W4I<&ZB-wT8_l*86G+_;^>&^e=Rc!e9 z_$8XqpFWTKdN0f@4y50_x%CL107P@d&~J^IEUKAurEO7U!x#329g^_-i?xJYvMHTa zElx3)E%qnfj0Ey-oey=QJP%qN@ZWn_c!yxPrN+)wc>W~);%8?&Z|t?vm{Epf$D!SB~N5nTc64yL&N8_4){SN zft76KoCL^!_jdT2FLtp(iV{P{GE!ws#qpJ@s!VdV%vN(9T{D$Aruzw!&N3f6F z`w76#?mTp=1ji;juTs!Vu-Vtq zL?5csre)!bLPXNJo@p3xC^VOkC>@<=U9flx!tOj~dCOMsI0}_iM z&j>BgP^r)@+W$Zg!SQ@^N=K*&S@{B;$~VcSiit@pEg(FtCWxH!;hzFpf}m*Ib)3ee z?^?OK5mQ1tpu>oGGN)ig^@#}=O+I}GCo&Kikq{!M-4e@Pt|K?6cDUB;JbzQWhcQh- z-V04o9n|tl>rnmHK`n_WP&#%{jEEBf-Va9SJjRGfand#@b zy9CF_R+<+6noj*+&%ytLZ~+L&9~djDvfupnLU{sYO>TkJMWQk?m@mSh0P6sVlyX42 zf^~v+XexDeh(1@q-=`f$S12c%4U9RvW+bw_AeCw6sC2L z&lkk%k1kzdL*V`?e*bEV%XtSGD2E8``v!z*ybrnNUM8mA*wNYC2yCMO?)QxUUr)4F zW8%U)tE4&<`8hsLb+&>pEh$2RKS*PTg80)h)^DN+I+vAyKuY{|yifUC!5G)}^|6n2 zd?QeGAjqq)_n|_ExFYnHf2G&N6A@&K**Slu)>F;syjFP>gi|kO24YX4%$SSyPVID& z;dzrgU9+LS@eFNiDSv=J4MIb0C)%s_BD$HPIrHCxI1p+t zh{7GU2%1%q9JMH=@r^Newrr)OiDan;Xmp;{r1u3H^arqwaFH)7$#v*Fk3O~DkM5)L*TObI=17Uxj1z(6*=b*KUT)r|a|2fn8)9rPoHgF1yp3kLA}TJw34z z{UX`AI$jC)r&ppVkh_KF{wC7X^mFh=*+up%$ZQtzR=yG~%T z3u^@5Do>V``o?XkI zC;Epw<2Rn}NcmEIj1H#}$e{dt%=1fzYb8fGY4e;hVlCN3GXniwk28I^QX9kEQ*#rq z4Kb*NT?s)z!FQ2gH+6xWWmCcQeNx5`Wri-*Va{rOpx@!4N+1@S9!mY><PcV;jm1}slfS&SfIj`BD2@}IVA(*CAW3@j9F4;GB4)LLL~bjPL76CU1;X%D}y z6QZD7<_KMkK$FH+Gu++n!f3eC(&OIuDJ^YCc67{Yq&3Vy+5s)NhJz*!1uzrw1f!(bpby%X~|8HRV+k zPu9`j@KLm>_JBr3a&o5jK<$_+U5}Cjyvlo_D-}X%Ku@s6`_bQJ@_H|J*zLF0D%FGh z)X4TNW$~SUk2Lt)z#Zw(CU*{+22^z7p}$kSu4Et7r><|RJX30nQ_sQ0X+|FbN;K`DSOW zc37HhvUQ}edqlm>rN$wv-w4)8(ol{J*A6JpS>$z=al^*;xh!lrI&_m#39Pp+ncn` znQoj_Vw^F^AqI`SJ>><;k~lb8NL03j_2z@H2fzp%2N*h{>trpjzVaRM``P5tQo?k@ z8nQ%Rw^s=X#%H~cNR9jeKx|JO{27C81aBoTX@KttH1cD1({k$$ouYh3#vkz1um3o+ zhRYy93AVy%9m4(o+w_+1FG!A9s-wS;02yx#QTH0ZS9A9G#f^lk_)04+%ulD=rI zEqAaaKR(_aqZHSwS& z>0f;g4_kT37ME>D`fS&iV_qznj_Fo=cr_9Ky;QREpc0_UNs*-ViUX2c4qydwhWj2v zFc$gT+|-*-WOTWBK`4<`Td-yI>P^soEqPA=R-e5I2T45@?awaG#$O+^n7}SksJug2 zi>t=>e%TN8P2tDR38#mVirzCivKsLb%`7Or^Y)@2=BYo13hVscna>sSY7E3#ZV+0e z`Mg6w{Av5DgM}wzH8uSPdiMd8HZ}*RE-GMzDdc}uJwF||PyAzh(x{~_LnaRgppe#g}6+duA@vEtvK!nwP@c=n-~WV@AH zO0UCLJmkG$cBt8ot$JQx9A_^PvKN+Z^DU0d;}}L|$jdho0U&8?fCUnnXa5$sm><=E zi~0#@RA`_(I%uAPT7a)7*&~xBp5Yd^WpS8)t{~4J zCDU-&fZKAfi`?usIsK-sFD{Dy-&Ii97Xv5W%L8U#xeDL=U=N_9$4fQ6V>2MyH6u# zuSbfQXSMci??8{Rea_RUuv^tt2vCTm8hXdcXQzih%*K`OO9r3YD-NEkbJ??jTqFbs z#yg{Y1@zyUvzRl6xdm&NxM2a1)V`lGz*0)=8+`r=1U6``nuYGahvv&cvQj5Tg)7qJ zxP?rhb-G0?tsWl`$1Y}EX16n+_K`74Wm-(LeI~e0BPH`qMHwc3jWIh=4DDH&cpPF5 z@;r4^KP0#9CwE(z^qiSmblK_N)n|+i3i!$ixD1B3a)rbkNqXryz*n0*9*Qv~qelpP z_09-X^=d>PxXW2+Amf4sF3k7W$|8T8tz=dLjm_#GZf$M2HX32G##9iuH?vHV+3<+? zNR0%OiKip!ZbOU0#11m<713H*Ps1$>TPKG-j{ypg2u%+N_B|2j7mIRb)BSnIZe^UB z%hp9)NTmYpV**q#3oi3Z_TPHnOR(}s*iVl17H10=I=((BsY*mFywW|~B&YH$**DS= z)4S9OKrkP~`}>r_KmF@KovwU>1GEp!hp+z*p;&9!&M*QtS2JtXhM%tYRJ)y<0y@sX zMHk2mkhIvDS+ZA@37{2+FqYR=0;G%Shda`Swx{ml&Q?B!reKtPIJN9MC+pEkBh%Pu z&Oe<%j+R!8at+^Z;c~X$`ilFIesi8Y*R!cQj^#eewtl=D_Algij!7w@l_J}(Y_-D? z?KQ37yU-Kt>V3N2a{+aaGKe@T;5@R@bNvF;_Ni-?As;|F?OEv{o--ky38+_J zzrB~QOu>pL#$dOTg zngoUf9mKE)SLsm?L_lafo~lMabUc#cWw6oxJ~|^#R@Ff7XLsJ;9c*M z5U|%ju;4Cj3Qogs?a8VUMYnKuw4#j)H`DKCC>JHNdEo*^^#KT@5f-tVl(DH>ot#U{ z!^dqRg3An0UbZ^9sWfe>x3vuMX=p9E8r8SYwdLm-rlTJQRHpQfkzlZ{e&fGabELwv zl|Yq;GMu0i1>jr_;4Nhi0$2D93Zm)+6|-wl2A_SVO?&SG`>#gi;*Q9F#?(c7-5>~; zdzI#U_oavb_A$fz*n09Wa(++rs&mR|(a|P}^n+97Se4nnFnOrmw^dKBqM@dK9BMC; zKu({f$j~eKIcg`BF%bi`N1S|C)WYOen+Y z9_)aD7q~rKwb{DGwQ)y8?^@RivDG2r463-US|^5lbuNj8nG^e7&KO0#O!(Ua3#JfG zfa2*CP<*QZ>nSV4D)$5i8vc!LI|+D*ZnMEc4zv`Y-+-=Ctz z-UWKe<#HxnNk@)&C3ffo2j2$Qb&kYyW`7VZQ)v$0$HCrOr8CQ$>lB zb~17HH&+$gN7{)%9|Fwh#_4#szp-{*JfVH}5+%ZmX$WU$o;GiqV6m|X*^(aC!`!Z~ z7)=lZa6>wK>+LjESzMd}K&88oAGVG^xQaE`2QV7|LYC+X>1|)1LvR21URr!^>3~;t z6SEHp)FJd*2>?`F0i=u&EABaO7&ct5GyC^~9(o1x=X43lfKS zzvBl|^cYV`tRK}5Y$VXb9?T^yBVAgD4h*k5@g0z;gf+6phsbx}FI6LW1`zv*oZOBB zKCHM2al@F{KL-17NgvB7fe5uxGWrL#xmsy=e_@O2Y44Mw>B5@Bx-gdty03Z*rlQn% zCW2f-(Z&y?k_=8I5$AsMca=A|nN}cu`HeE^cejz2iny^~Wdg$&xN?Rn1DGoGUC*M7 zS>*oeQ-~EV{-F#2O7n){8y{w!0&*0iGae_3XUzwA1J8FRF~Y1;=peR1V5sEo!sRKi z0w=I)zE6XAGoi0UoB}d66b@MRT<#Tn=qsOtMJZ z@b0U`GA&eO0ea49E(YT{@U121gm73d{NX9?b}PJFMk6a!1m1JHz-ziX$gQxLco zh`mVsiF>b_QxpEgyQJfyK{E10MO>J}Ss!L%;RYZrOA`pgMvSWdUjF>RY)DxvvP1+{ z^P_tl!G)1|Yp$xk{O*SUc1xj<1djQ)#oDGAFcqs%fKg9`vomc8f=DN=wUPo{-Ym4z?K5F$Kyqt zS$0D)xRtZpJF3fjCk?CqmOJeHE5Y>bZ6sNYwM$Gw-esax9oVnqYxlxCHNAt?gY@s? zhggcH;bZwuLobIi+?-k0E=v`VXdWXGZBqBp`~DWUcJK1475P0KWTG+hzWTVPEZNOw z55|$Dno!zU7Ih9|ZjTeG9$r}-=qB|l>*z`GpMK;&8QK7*WXPpeU`bijMiF;aMpHb~ zg&z=LecZtU8Fyq%#k)To=aBR@N>yJZh4bXD2L~)Zk~9Ds${KanI!x0g2HtZzvSY2w z04l0|dd;N`GvJDH^!QOG2IV}iLHgDK=YgkXVfexvrS?En8P;c1L8VO#Bq|LgvOopc zq5aBYaT=*HjQu$>a`@)_{{OhR)Qwd50{HZ!)_jFx0G=GyEDc*$1PQfSKC=wgr!s4+@+FU&~-n(C&B7x_wFE@0v@HQy7)(p zW|y}}lE`rS-NU)jNDE81I;>`Ta*QiVHIM)6Rs&-TXMo1&%l6@ySE)`suEpvnRLoLx zb;O?5zD+Nh0g>u}d(#X7qkww}nwzB^foYlc;3c+;w!$qeXL|>^TNEg#O#Og6c+B=g z`G@mB53MIL>7z^cWlOH)n#QL5VTZa{kJQ=Oxt3pf(qi~^Pl{Dl;YmZ98YhTrU5Ds2 zM%I78Kk3RDDp*^XqPRXpP7QP)pwS)YvV#WE8xophxZ2;fUrTr&wMnj4{9blN_RL%T zmTa;T7Y5#`NSuqU%_cQ{r0CY zDWYpt_6nQd*lKJ#Bc}}x@vZs0Q`>XQdP$A)=aNw#5#OKCf7Kil&+xV|&$i z@S4ae);wh{NDlAzdfE-g;R^wV=w|39W>vz-Tbf}f*%GNBvXROm^j0+K5c#qdrkJfa zT$Z8JY1x$TIpiP$XNvmbLf5Iy0m^_!y*WR$T_OiDzYWnCKGna&F7EXIXN07hbgB#2Z#4li+(;u$CB5B0@~PeL0e=^dtWoktM7DbMfK z-rtkn^1#+i9j=rHTKq2|JF zxo2s65#UH$wbqUxJ<>ZPF$05W{liXr(bwaaa;i*imva$n0lPlxwR5MGWj8>CE zf{5=R5|)3r=`Y;!sSgffe=^c707d~nQ_l4z&{;6RiMC0S2x(3h&=w>=5mG#{f7`$W0ozH#eJe=!L-*{Felp@chG;4E zSU#CNCQk7LqsI}Kl~oo!v!75D!z-&!dk_7v2i!S1utqtgQ_Rt^X5@TqYz$~neSp(b zQd0UXBNOpd-`w2%WnVq>d|EtOC<{02T6W`b+<1xi!N*gc`)8YzTR@wmTL`uh&ACj5 zXvpE}gC==r`BdeD=K7rud8a|osmbXpF4bK)jU%ekuM;@oyms_7+=DY|ru}3FWX|HY zGZe$rlJDY&oiUdr;tJD-w-kl4x_(4=UfE&^yye})uu}HIdXE35dT!X#0P;mV2Y)7x~pOpAa*#O z*n`UUPj36hmRLHtFjvXbmpA_*w5_N1SG%sC{CoJlz773p4R9aETYT2m?GHtw{V}+$ zk8W^$4$qe7wwn>P{*P$~j3e1XV1HA%GDz)@!qJwLHXGcQH~M==t+5+z=5Cjj9Yr!@ z*OO^`y^Ka$EEnpHmJuCo*42419&M%@1{!T@+@23J&EGPiudNG}n@cA!J?qmylU5!v zgp*;#ddJRqO?;&3)B)3do66{>AI1A*blm&)CExrgYtstO{T}#_j;O!IQs%%FP_hpM z#)?39c_LInmTdp&2?UNg60M!4-NuS@R~WJ^=%~IN0HLzl z8Fw-MUrz4@aya)6oZ8E%@P`ipNznnI`YR}kAFu;x*6;u|hVE0hpj>T!^NiF+OtHOCBDADF84A3E}66kQ8OyA||Dg}OtoWsaoHXibkfcsI_nA(>FrgKiJ zMTadk!I2qVgwq){S1AFh7?qbLf8mcp;|)_Yr7+?es{Dbcl<(HsBz<1heVQ3v^>1PK zyI0H{_UILSrXbqG9{v3Jh`H<4hRVcG<6ryjO%e2Et`^!HA~PiI7w7@B>>_nfc-CuL zdcwN9DN;;ZIgNtwe1RK#L;meKmSW$?IZKmu3xzTl%d&W|Q6L?t-GFw2 zJzl-73h1)-*60oI2=B&)H_Oi_vWJD%=zRx(x&-ySQ`@CK?Gw|F*KL}QMX2;UWg?yJ zA_)5O{dAnMF8aSNFL|IQJ$3?<>9=P6j!ZWEQ0~l+i@rnFCcB?l0_K-LWo+Z-BAqZ( zn9xCu@xzQLM&Wa(2j41MWi#)Xa1f)Qo8C!>albde%d%ypDL3k~u5fOA)Qd+9^iDpYC>;8;O4jsi zOaOCZvx)yCtnFOmaGa~NWw=kD!vUz^Ing=`CZMoSy51{PE&l=P-7}rHl@V+2kf>x*Zy2t;hc&NRt4N!HRCduf5F3 zfKAH_9*k>*+s88e{?CdO(EkC3uDRkIVQ<88hB;z8v|FBAuAmUVwihDN!ULSJpLWLX z8zC{hBku(dlHQWP%vFgHg!slhGDkVw1360E`l~_)qX;7a7NtC|?=g6S(|TH`J7!Pw zup~0u6My!-%E_4nCZkLqd%Sx{IveIEd`jF)^gUhVQ$2JzO(*#==myOR0Vz{-LRMoy zrL0s3Q^#dMj3UY{TuY!$?(V2*M%|6}`_*E9(P!MRyRH7qU$&qYwxR&jn`MgKvMh2F zwx?b@Y34&&;ex8ZkF? zqzUJcBzi>y_x>Ki#u z9RJ%r?I<{xgyQTP9@Sf8CVP4s$@IeuW{p=g_lN1gAYvEoa0#?5L+t)SzvN~`rwip6 z;Ne;Wgk8DhtSEqB`v&qdbG!k(V{WyciU$73zbP5K@Y+d#BP97gI5KV5-N$$QP9>gu zlH^Zf()_)}QXaAi@;N$V#T959frJ24MMfCJ2ZZaegR~ zIg&F1LX)B5MKSY|2Wer`(eJQZHY1u=j3@S%!6aYpV5A@^5?l8U}}jayzgmyjA+rzKopBjZFK6BO3{+ zPv@u*{+qJGm9ul9`)1E|`?azMp1!_WcO7(eAt#=cn!?@j2`EDZhrP^96}Y}CkiJBf zCDh`!dlRq4D}>^t<~rVBWV^w1&AFmw;`U9;Bj-TOP<M%olh{i|ucFuU=Y2_6yOl=rYx2 zQtbS>)uqqi4F2G?g@F6@KXZGsI!r}Br_^0Q7^!vK{aBHNNR;^|+nZ;_I+l9@PmVsO zF`Gt{IXas#+~g{&^PPgds?TfLIU?9VmZ0~Jh+$8ny=|iaf>~}(PEE4P&1l1LMZ406 zaWzBjMk`7X+ScP0dKQb#Q7l}+VkGWvww*Y1tfeYk4tLC`pl0 z@Gy#wP~dm?m+Oj07v6sQ`e&FU(ypO3K%7iwFL(dib`pZ-G|Q;H_y znOFFAjW>R(GRFwR897|Gwb?|ksZ{05iPXO(Y7rX{U25W4J$?WM7JQGvZdQOrLQt}T8WnQQ}Ud2 z>OMTJV7uYC!&r8_u44xswn!BA=V{zF>5XlP=s)cRF#FOkIp+ck zjbnytJ|yWrWOUQua!XvLcb-T3h~Z#T zd^b_W%w&)cV1KC8_*N@&sr&;w9mtn&v)zap$1BDLwO%Fowqf>C=d5?tdwB2w)p z<)Y7Zr})Z@leql{EOYq=-5vQ>d=P?TkEV*=p{U++Qwu&5kycEc`R1w_yF2I=H_w1Y z>@djoR9E1QV1IjcJc(OVi&#Zr!0bs^TRDb}{h`e0m;=M-PC zL|qzo=H_pJ_)iCax`Kb6vQOXz3nrM)r7oRA0g=>5E(3@?6{*S-RWlUBed4dgq#c4> zv@1`(g~CkvBcKVPhXHebM&=GJbvva9RqDGgZ=8NI{I)A6RjcCRrgpdjona-S6HcVdr_aqB$C?$7+Pf$jDmx_ z+wQQ)z`-HFXz|}%bF!_rAtpZlvNdW0NUy!;MRqLV!&9^K3XHt`NB37b5*ncKW-n`u zzvU&~$tdirpe*mkub%MX49g5tS!oT6Yug3WA+guU z>W2K0ZGlT?QdN^rB`cBw?8jSs2H6|GTtMe@*lq0elxXX7M~()~_X@ZZ@O9mA9T7#f zZIHvf?ZUOL_a|cO?&tySi#KV2GF5WS@AMd_BnMg;K<=-T;QsegV`Jkon}pY{HIANM zMn(pw;Dw{+r>3TU^31ciGAc6C9!T{+#mCEQX;A^M>I)!!{Mwl@-opMbWKuy$QR4Uk zP8|c7R}oV`{Y7{BRf*|^OS?AhYBunJEFDx8dg}fBDA;v=A)@uuIW=Xt;d%*vCmu4g zveY1@gA~WI9b@-U?GJWKWPKtx<)F5sd+z0=gIz(K;+Va(Z0x0nY6W`5#aGH`bxbu2 z52pfx(e5`}TXV`{9fozd{6!wN7-bu;t{4G?!)P=xoRcBlYdfY$%N?PfPn*gd z!19v?Y*ec54f7C5GQr-Ax0^(scYWC-VdXnF3emx*3$5F{q|YYQ9u5Yj>;$txM-sn7 zIN(vNLWjQFT2}L2aoTX(WM*@I0G9=L5K^1+NXMtBPw+3Rw(0e04C7EBZ(;>ZoHMExmCr?Z5|N2=0g{DWM+957&tg*zM&>bJcIi2f$q5Ya zoZ3Xa)D;U<`qQAQ%}J`R{*z1YkkOhH91{FqlRNLtYf*GpHFlyi-l5HoP$0HxORSu5 zQ|>cUUJiTqlw27c`I*rte%pCUIpaA*oCBKgCse3nFHqGP=4JSY!szL763 z?MZ(o1wV9%e?Hvws&fzMIMV)!C-bVmsH*0{_QkY=<0|Vtd`ETR^y?BPuC8+pl%-3A zIa~RS$~6J-J1<_a{Jkp_C?~o=8g{*;a&OC%nca={iT3!Or`4q9mRz2OB7dgmB8Ki2 za5N;|$oZIYnnloXaDMGOz3dw6=}|_+1IlZc`JRu4#bQ$SfA0JUtRwz?vhGte?HQK2 zR_4?%CN`D&N$OzoPstgSP*%A61A!t9`m^z}??ems-lDF3o1L?wF4k+uab`@N6vAFd zbNnL%+YrS>9=kDTx-KKJ2pxH#2|L%(GjFdeEEd!ITH>YZ4tG++@i^7$ErBIwA8mt8 zB`*429zE*Z+hdjQl5>el%eTIXliS-6LEEFZ;e_<*nq1%Box2;CtUXFf#m9{hZ#28@ zd{F27f{1u_RzfC@E2BDloZ{t!M;5P2n>GBRMV*G-j4iW@aT^Kks85izwdUr|-;++W z!opIO7>c{iu_q1HchCYVQM^IRe-%Vk3qSM*nUkYz7@iv5MpGyJy*i%~`C)eU8fqUA z$^WczE5TLq7%j%!y?3Yexz0CbMytvaA^aA)8>acskxCj?xo14_3^xz_7HWT&NXObd z5ek7qv}5zFVnoj_GUnF-r{Lju2 zx+2Hj>~zOl--BP%)+f#?x%lhI@l$rKDM31yH;ZQ;>t>tomp#Mk8#ZUzJ|Ylgs{G3P zSVoZP33i+l5Q*u+jzRqXJxT8$Fy86)j-=Y9$6k;hdxmqXopW*IDvo1lUg|h!p6I?- zy{;zVQ7chFSyy?6xH0>6rZR(!EQ30oz-nuQo%*-u;M`{CsHhi^s(!{6l@*kzK$gf`)U>&J9nTi>bOI#Sq&c8~wwc5r36~a@h%PJjd zpRGo>PaX`(6K>tdPYBhQo=+G(KsK}wX{20WAc!H>^VWFa#N(OchK~QDk z1*O*M5~O&OS&0MS0GvR`b))V68I|yJAYpF?N-k{L#c$yC*uMZ}0IG7=wTVuk8ovb6 zIa5%&%>dD{T>a`OF|S>F;LW~r?b@%`7l;&QSO1eTej5f-=4MGUv0s4AZUK!sEtp1_ zX$dpmn(uVR=wPuMWmYIhP%107pMLDSS3LGW*r4kq3I9a53M?k~jKZPU=w;0(cMY?Wj3%%ApnZCs(7VLQ5lxNu9sJ~)bl#{~I&A%zQ;kwq-RdM_C zR|UMupBjpfEf!CVa#30RVQ)Jlm2Abx{=x=%q3@;5h_L1^wVOWg3D0BXLl|IO>RX^C zoLLR9X1}177d!K`^>&VRV%BC`M?rX*H~+?GQo{D|n;fyrWPailGdhb6sa zODdyu7=99xd;Vbv_4%sUhZd@z5Qvx?C%5j>WelXPpQVazqYw39JG~u|%vl;cAuiCv zl<_%MEqn4wq5wy<#T_55IpOQ_?sZyjR5yzre0+?F>`l*ex}cyP^3h6V=H|YkxIm4h zwZN4tPM`c+Blh{xBv1fSGV}eE>W?huen^qwQS@7Uv|`9#Q}dA~=2@MjM>-p?(2a#O za`7`#P(my%Z>^83oDNcALJlO{r%9@?fgGq#y6*iSu70j?rPg_1tgkKoqaZPVndHy$r>3eSBrDR~}Lhf_i%-wXbgs?o>TaTqfUgzPnM{B1X$rgRvyr znGh=!%Nz929LM6p0MFL&&v8AKlnX}GaY{Vv1y2~LNZXPSaWu0!%5u3BN`FZo0B#4E zT8P!~V+UArB0K4&vx!r`E=<#XA<$qqLR#Xh9*sZQrOHNtkfU&Xl-*zd*E=;1#uzz) z@;AmqQl13OL!v~{;;Yp@^=yzXkI_RxXlAzS$8{is^rNO%Y;OGUgyLmOyV-ViZ9?oh z$v`EW!_cwDs$cA~shQi>ba;E)OqC0?{kc`4uZ!+W|7n+OFP*Xa{;eTp)NbSai=G_y z(Vr3`8h^HsGo*z)f^_07Fe-M$dpg7TioY}I5i5-5wd*S=;zc!>A=*@sRjG+7lzIgh zzK67)38Z+1;0rMBID3nJ{2{e>SM;leaG*RXu+|P{nA=M5aBRAgXXkA0M!VR$YSx%U zP_?5Y5@)jTRhZWi(1`IOLELpeKK8Qf6h^v9*h=eVcBaSh(gv2eCYo?*@7P4e7~WyG z;pZZ3?qG5ViIcaOXn;n{LbUnhJ5jMs5zHrWM1+w~?O5^N(4In!GafU<|>^o&1~+{6G!;IxS1@!K*9qE;XDzoIFikJ>$VVJ(zlOL%gmAOk=! zd?IF7>;gyGOQdOa<#lxM?`wEVDo@M3HU0cz&mBuL8YO<93QH6wtW#5f? z;#d0vN`j&LO&`Zro+LWus7rGO!{Ya})JF|4 z+;jC3+W3|<-JaxH8Txn>KXC>SlxwMZUR;z6Bt-y5m`=th--Og~t_4)*|+iHrTMj z@f|Nsi}6RQ`b_~i%bu<;rL0?&OoZQF z8O;(aqL=(YNYZ%Yvj)kPv!Y9Czx+<_D1` ztc=Q);&!d#7neX?EOX}@xQ*!36I6su4M^5?BuXUW*yD#VuAoww=zGX2alCyM#CC@KH8+|6e%5OIil674FrVErsKW2Am%vVD$b8#Pk5#%u+x3 zz>;9p_~w%6<{u_J5II{PHc#9DjqZ4y>R;Nm_9%8!kWbX}nEQfPv)wBT#6_Uqu!fV; zd$3d@tKZ0Z7?r7v9o{gzyFztNu)#RBTkBG@BZfJ8XI-EsUmnKK=4z{q)g@f??B-|B2l86DjS&)kDE>N;wlrtdy& zcJ$FUZS%B~6q5h6#YKLJ_5)pAJUzPJKaN_*r#s!Fczfh2d{WU&r>j!r`!vm>lgdIa za>9(WQpUf|-s1RymvOz){>;$5?>9o?{$?pz-@awcL{4dw(UHl1pG~?+TBs}e`(bhN zj%w1&yHN(elZdrKBpxc?3Pc^r%&uc{TdN7xzGw&pcZ<*xwwy&=qab}XvBvAsZ7F`} zEdEqtA~4OI`zCjwps+i)0-6xx{X@xN@12~%^UAXb0V590NL%(_)M?{!rK53zUv~El zgFLtN3a)tSmbJ8{ZzCufKHld1d$~4m;I7wo$u9j4O-ha%jae5i&C|0cqn=76(S1=< z6VcinQ_epbCBswuaz75=M$9Z{ZP#k$V@K%dwhbv8zkO15j;)8PQQqFhVN~&vg_b8n zcew;l$i$$g((b+BOT1O6!Z(!Fe*VR@T3)G21&Ub4mcoUK?`4BmKd;{pohI712_QEo zu!+UbxrKCoKY^M%%f-R@ejq>(W2`w=+wg~g^7!Ger!N;2cZqw0$<8)#nWXzFJn>t{ z^Q!4WuA5IJH!9~bw%;7JS)pCASO85x?CD@a2ay=22wjB`T-z5x7;b-e_qyU1+q*xN z>@S#SL|5~wdXrAH!jz_=_MZ0Fy}MnHbfzNv@~Mii?&_z~2i)h^|Kq2Rmc#sbTklNo z-?vlgK74k?Z9Gk4V$Rt;s;bw&l5y?Sgubi9j@e{!k8b(k)@d%=_lhkJ%#pU$4X4cb z2?d*2Y_t{PO#bj-tiIQ#eL{vjW#wEt?T*XIMoP*`+ZNl_@JaCn@lnn!(Ko|O{fu4( z=H?C`6o8H60GcopQ#U0B(yS04Uep{xiFuRDiiOpxYcyPH9ah0{9H?V z0n>90L-#Jt{3ZYrKUGcB4Bi??VMthO+k zs(V$7VW@`=A5QkWH(4AeHr#+|AYOL#WRtQ3^2CKP&(%w{E4xJRj5dW?YEY_F<0L64 zo;^>dcfMplO9ni)RdlBM4N){&q7MQm^7kHnUWyY&-l-K|cv&$1VKXkU%F1X_>3AcL zw$%3~+#b;rbq=@F3}GDQVU2kJKIatDgEXN%@tvbuF*>7u5vx9tMSye} zd-kUG} zGQzJ_bBjy~-?Sw7&7}Ha>NNA-^7|2Lcd^e+6(}#U%%c0gqZ+w;1M@VPA6K}yz3yrM z3^!-HO*S~v&+*{>;aE=1B2c^~ZN!Augh(5`jE} zVrGO~@3yE}RPrvUU7#xAOV2&!|5#V4SP*vl^-9Kv+!YC*wu5hY^IX5l!WqJi)-PKM~0>Z`siuGrx7v1N=w!_tMrPYQ>nr9XZ6i~+X?1J)b=g*2y>g|I)~=>uK+|wM36f#MQxnj6KH43%!%Iy|+ko7;*rJcQR?gV? zrqAK_G^An1ppkwCNQeME6S7d>Io=mnp)pFKIk5i1VO$%*xkT5x-=*{8Sd332>e^~v ziM2_~#r#E@3qK#_#9tV7LutD{QKLe+_MPPHy&rE_$*W#w6S-Y1Cg6%vSw#uPckH{E z$0LwrWC#;QWdEY7ZkF9^ zHz}A~JknR=D{KS;ZFXNFQUU_L(oE|6)l}M(VJ)rCw7Xv9;ms*nNFOauu3gC_73Gxl ziuka7l3;N?fnylC+qV1)5fJ>02f3IAW1(G>`v=nFr@)gRl0+c^YN zC>x$J;pObo&E^!RxJ1Q|7O)tbVPs=YSH*sf^fJLudNK&&^%6xU#tmgwzi$e+i_=Yp ztTyO8oMjcHEQrc&z$TA8r*kqJqcsM<6sbNr`o&K73Xg!`?DE13^VxT61b-?b4=P7GDsXzZF? zX7h4!CV1v@k-*3b!H0}mDJWT4`|*UkJYtaXIpa;AH{0Y4y;3hz!@A=LeV)AU`7>^? zBiy4fkEGJb`O@93G~vA^@54{>>cdqQ6&;;69RG+;0mwu{qm99&7*(oJVvd}Tcbk}o z7!murxpH}A2A%YRxX0`9DNj*H(F`VjRzG7F89Y|9PM?hOPmit2307c>h;T#%jV%+kURLttCj7BW zLq$wpdxJh#yGQ-c5&Ze{XDYvXbyM5Uxzw)9dT-`%uo`mz`L6iU?&XR~Nqz#(wJhv2 zyNanB$ITWowI{{oW)Z$K+nFgR#gCq)_|BA$WG%B>smjzlSZeM>vzLf?+r|xQy6UxD zOr*^yzz982rx#GTnmmFX6ZCPKyh%EIc2ba@YNBhQc}WCIR#F1M<8I!^lJKs&`ubo) z^u^bU*RRYv&1|QfLwM_w3tmh%{bXnVdx4-`OOr;h@O!+W{nOnBLJic_+$nm!&u*2k z_xy51v~Je=De7rYYHNDFLG2CFzv8M@Bx}_3^V2raUMupt!T(JmzkrWFiZQQZCBC-0 zdtCj)+P!7NwM0*6=E0qw<&2bpov2#o9{~({8))t}g+;n70!{0J?5qmhAr-4kP94#) z8xFcPif*`G9jd$=SLo_#|GSPxw-$kY^KP->dasl;ZXX41lhZ6QJ;->>NN&tuW{Ef0 zy7JTioFHB3tC?d%--A0-R?COpQzzC_CqB76A;&9@#Xfcaa+mydb{@euisyjAj@Cwl zh41}Uhmo(VWpfIJU1m7=hxDa@d1z8rHjtga;6jN5( zUOe~YoBU3c80Xj)*?ElIJJ0rn>lDeS^e-~&t?PFi#KX|{X-B*E66F~}*WQg&3o1J! zFHaKxj4(~fay-v5$~Uw(vpebOme$Cy|IS(}XiaUyZFjZfyD-nSK&+2hb)LETF6w;O z`<|{@k-5FjagopcH`o1qVnXT=1#5%;-#=r{MeVr33GE^x%5(DggzBHEM_+k5>3Y*8 zYA1i|PW-J!+bj{ZW9o39Z7V&~dmhyBb*Y6LNY7_(7h6m+u_bnUMvBAJpD}1LKa&xU zt}>!9s4Am-7hM`mTu)rdSEz`X`pPJ; zr&{#=#Zcvlt;U>tmKM!zSV~om?bq88r@CR>D4&bnFd!D(w%KRH&LWWfS18c!o-X4* zyX?{}N8js8Hfkg3tE~&HE2sAoj(?tKq6}YOR-+SXFs}+sM6>O@E7ft%{Z4Lt7d3g8qY3~)Id9*2W zY_{eq*n)9@qH(P#9PfiIQssG{^#^91@QUXFp2`j8zh zC8lS&&N|YZcEZIa`oh;5Qv1qf%+6ln73rZlkCj>m*OgxugUg4rJ37Z>E{WS05_av` zW!-IP(5|V2!YuD10=~O3pie5Lt+qJLHV1|HT@8MGHDHuaGmnYc5qR0Re5XeEOOPu* zcg%rHId6V$;OdMHdcP8_dX}?()k1`hR9brKc^PTOCFbgpm}tXyv37%liJ$PA-Zc~> z^54Z0M=)FXNgSl^*6cY=M6sVs;a)FhNj#sS>Sd!^S%H}d`>|}#1EZN4b#yH==w@#3 z$}i_78FKGWIrO@78T0LlP_FkMK4D-XVRDW8`us+$OYoh$(#9ngGn(gIubDC2j>iVh zZALoahZWGa1f)tfN)KlBcyGLYs=M$sCw5{!FHIOx(catnSsONS9O)&d!0SCc zuHIF~;6}S|NLGWb-&yH5JhymUhy9jf7;uFCTS0Q_nqQ!}Gf{`tnXY4~I#}EKO4M8G z@E%R0j~>AYJd<&Exu+nC3T#Ci`H&&SiT!xrwhXY@uyI=#i8H@k5&VUXoW@{aLQXD;@@_Abr2>hMtg z-5E{M_VwWDD_tHsx{AhEel5H-ZOC*?bfEd2Vw_>6x6F`o7^3Utau6OrDK{{Bx{IDlICY+DKkeruLTV_sS<^z%B|)*(`rqa5gz4vh4KN|S$7+%Gkx^Wco8Y>D z^><|P{(iyryT6CD@A>YF@_Ci3w30nxZSGP@@@`8<$`3|$KDr}uIjwhrnLuy8o@5On zKKk`pzvnC#BX3&%qQg=w6JvR9MY*StmVs`EmE;Upv@EsvI`!^gI_ks}(vU8BeP!{p@TnNZ zP?hISf6wN#9GAQEiFlP~oH=K$I!Rf8I2m0p2;1|mYUg(rlVPnDKXK7qN+_3Qs8N$( zfQuuRDt=?>SoXN>*8;JX%z51-+7ir85ol}kwcSh?@0#UhKek$Q_TO5AtBY#@FOESgp9TM$~5)r1|`Qgr$DLws>bX*$;LD z5s8`vMTVNvjpKOqx8>EovG#3oXM|%d>YN)bot4-GD&ugZw;l#Xs~(Qp?`8RyPuDZ7 z`G`X_g8eo#?z)QkMV7eWWaDa>6Vbx42O=P!G1Ro~1LN2c7}5HkHFNotI~aSgJ^I&5 zzhIe`*CQ;ersc!QO!aJ0yZTt++r#4F67_)gK|TdJ--onoo?&}6dru3(tQcoz>Pag} zPPx;{69%!t#!50-gO`pis}<%wmVmV!V$+wbHXd|P3Y5Ub5L=M_IKZJeyAGnyJjRXZ zU027RhcSqqt;>f*5GK^G($RGQ4W{(VOgsEAz-+vqJYIDJzDnc&)(6B#cs20ye4$k(sNF}~RX?FzG>>&CpT z<}-=2%}TuyTX@o{+IY7aLvQ6svf?ehdtswJ_>xOlTKshFh0EQ6cHArIYV1!7%OOvi zqK;EH)4_-u`tab5)Zf>a5xqfwTUFlTz1Wjyk(^sZKj-{tejrex(%<^Xvv*_!4P;n< z3|mxPn^{s@>h!$C?weVnpC8I%5JF7vMP4QsIx$f1vS}DzZmqOyljdXL&DW&R_9^|5 zK@8R58{-S}Pol0DooB`KTO~$kR_{8#n(Fq!l02Xr|YeKESv+ z^1uht`OJJRNxm2!aZ`3ws<+STi`ZbXP(_RJh{lubD%as)WS>2iacI$*(e+b|x~qZ) z4KoYL$TOcE>T3B>v)xeq{<4Haca+b{V9)IKK-UK~$?!V18GcM0ZmH|Ss(Huj68LZ# z8*FQc1U^Y#j)B>Z<)1&@Q63Vmf<|3*c{QgqS3C9Vx1FWs#dfz?iiDg>-w0=Aosb#n zB|a`DoO!O;b(4=ZEO<@~l&^VPH%7MbmRf~AMW$k0#~c^?0!wpmhtCjc*XrM&@u|_l zcJqz2dgmU8Mk8k&W=i)Wt9@5nI*$`}bmk{1J@?#BeBNVqJ~Lo>vhEY@>{J#A!L50* z*KVceGcQ191+I>FCH5rw{X22(a2E3qz_KVGHk;-=Dg8du|1 z7zzJ#b}rfY(0MPVMHkxv-=f#55J=lrO!|sQz9XLgqG@o(2$ioNOe+u?ZQ%I<peyw?%35I^J7N6(vhHRK?GXgflUobj{+8ZQV5{qY6gTQV~*|YM{}Hh#=zH4 zlCP_4_aA5T?e7alf_mUM0fF7men&HmfRu_vv`1|mq6@Y_;Po;+eJ6M^84y0vu2hPh zumw3}V6P32iD?Bv%q|c>Zi622{(P*RAgIfo(JFmO9s__;nCtunG-%(xwYg3DwEWZG zeb28yUnE{l7gVh;HBRp@H1u${SOu?HA@uAGFYPSkb_#ba9oLIb6-$^I#uO<};^7y|5}d26j_2l(!iunDx!jwG8(A*O z=M+TWUd-@5On;{5G@^1kx;!e_>=};F4l-ZGo->kV`PVltZ7H`s>7itOks8)iXr zvEXM+C<8BcMe&2%#>U2Y0A(X*WK;x2FzA2G&dzcT9^V{Lgqo6rg9F|*N=h(zd!HgA zBq7j<5p=i(kLGLVJU%Kfuj0S#Xb(kmgWoB3(qp?vYPi~s6IX124*d&Y5y88C=MFg~ zWlP(a`#b+&=Ss{vlQT2lL(Eg+zG1>qy~5*DrSfsO#C!|scM<^#=FdWCegidr6SaBV z_h_L(^Jr5GBFw+6`A=kDb`}+$H{$d6b|?R52tR{~nxKNt;@^$vARO*s-~P$<`oAyb z4AK$NDlQKG8*2S)^8c^NeUJ(RHIo1Ppa1*cdY=5lQ~$sJ=-;U7&1L!9|G$0H{9yh= z-PFjlNib6P#p>2ScjecI8HUpzEltS>f6R&h`HpZ8kyPxG|0xl@?^Cz(ZT^Ip%bb~+ ziI?QIHj$@y_1}A;Q1kI4;VmX6-D;YQYX`yq`JwqHb&3bQsQcwl$bYGj{%*TKN%HCm zbyL!;p)5@&pnkmeY#W=JxT%O)ys`h{aAWC3TrZQ8J2Y1KWrw@kQ1|AuOO2Exq^rw` zEl^Q6F(W*w`snn?DLo(rme%z}cIz$z~D`Tua^elJOPd7XhZlKpRMbmSQxa;z;FxE%FX#bW^7!ghYnbrLp3_^eX<_8Z+=(aas=l?Wh0z^Z$i2GSDn~ zyxsTf_iu8jhy!Q{42z_d=2B{fStpGz7@ocqDKcXGb3m~higZl72I{fSYZLLnTI8_t zo3aGaPLaqHNJ{?~JPh-#Tdy-S@17hjNH~FL_SH&Cmgu)cl#V@5Dajca6u>!FEobKp z)p(RB#w;&euGa1u2)isl0hln(WP%CYVpUa9X#~He@bcwd{c6{_&r%ExwiSsmN0B9p zT`7t4J2?PBTi8919zQ7M1}E!&QKx{T->|Ni9UFAhtPfG0Nw6;tgT! zBUm|XcoNSLI^;VmYY}h&7mg+xjJVdDY3&y0&a(S~*1h5{j(D|ijtO_}+!?T}29(}t zMzFWrOwSO%xbx!Wy-7a_pgu{0>p;ZJWzl;Z+A-d3@%an(ru8BofZr0_>fpU}>C$w~ zR@Y1unZ&j>hv_}T5Q|Bu5hnDcNcF+_6n0+x2_P=LoFkixaSgO+JeTof*|p~9dE7QN zj&p4~7|JVG{;EFfGRD2{A&NJk;V0bp{OHe4Lo-^5nrB;ETc=+Waoi9T{OWsrScH2E zLT5$9;m$}fh&`)ovr&`*dCksDm_)V+sG>c6`ZUW2y9N&jq7#5}p`L<^a$WCNJu{xWxZvQbDtt_};7PMwI z&abt$njYr{&J_z%s--DnJUS z$@DC^J9-r3>atq3kR8NXr)4u%sqC{q9hmL3&}9itp1dMimbVc1X!@)-5G@;}II+Pwgdi2kQWS+ zdzYNEVQ?i2co)_D;AW~_ARx$5&(UB_i#&v6_*zok(WY!|2fUn0j2|!p$jM7N*jDS) zlVd`qs;Vj();yAc*RT6wpMH-%fZX+Z(qNu$Mr5zBY)a3fQ-d#L*XmE6yvfeW5-Jk0 zzk=@m9&m`NKe=NwLVWMuJvI280pKc3zjF2J4y|l&xx4_3IPlp|{e0D)3Knam)WWhq zQ`vOEWhh@P8hhjm#2QB-maWowDM~*H) zl(sMG*2#y;godRy>z#$hrH6GQHnDK;dXn(igc3+ldKj*k-AOvfmXfw~3CrI`>LyGF z9?n+NhRq8H8u}f(Ad0jiJI(qMMd*>!&Ax7%ff7fL^nDNJ#F20y@46OYktjU+kC!d>;PD@!J)@sU0S?IB~JEd?um+yEif|8(UIof zL?vaZW@I~c3AHR#Nt|qiS;7%NoWVV^^c&Vpxf=Ij6?~M2-bE*IJuhef2638=|8U9E zDk;w^Ec^r%nTMrTFJ9bkdPmYX>H@DkdHR(5#h=Ty9boQ)dtSacKHOoc>0)7WBOD2( z7dgAWgEBNN8TKC8>EJ~|X4IUaj}%!GO-@PK;Q?%H2Glti{f;)y51!1<+6%gabr$m6 zz6;j1H@$NTBKkQ1-tJjQe%jh`w;3*e3o%l6h9aYF-GLc|KzJ6Y8CR4J-}q_%sFC&eWAg43hr>sp@kjfqYG1DAn!;>B+7EuUi;)U?R+~?LXjPJwuMHf(FOHped+Q?2S~sCvK3ff8rU>k zN(kgwSh*cfVZnr5A7~IQ!H5=MsyO;G6f=s8d(CS%$3xPqCfX4Q1UOJ5{#c&`iTJMR zbZ@s}I0QP01pxCch>qs|BIV>Qpsua`0d_!rpM864>vtnI(32b)4vOq5gO~{6!XAwNF%RrOzwY$J>&lfYnfdw5Y;3_`kYjNGYWZ0H z=dlcd;HtjZ)g8QpOBE0D2pPuOLUfa>R~3Hd9DX5KaA<_KLlS;49mtppka4iu9&m1P zV{Bi!P4RIpy$ELcMw22ghrds%T=@dPW(GnUWm}Eme|UJt;Sl2av){xMC^O#8(6a=o zN;(Bg{LZ=wJ-f|K$1c$=IXUL5q=5kkTMJHGodV}bunh8XI+_Y;0^;kCul}^P1V?Y8$rW!g9>2C96%X`K&ggMnCbQ zI1RhN!YOKNQ_DuN8UK1uezZRmw!J(c+hxoN2i$I`&>x(>KZtiU{PWQB^TmN&BrZGq z9x0>vSn}it(B;1Tw{i?j@evgEW)~JJT-6mW;rQKPGe>^;vH{T}58Pu%Cnw!%9UI)i z#TmVQaF-V^U9!L|$El2+ULdiDbH!^t#ARY?>H#t^7O+`>naajVIG&iA=gkEo3Op|N zbtB*XX#!kv1`N_rTbT$S?k?+jE~SB{2uK7$a+asiyp_R8%|awV?MGMvM=n0v&^JcY zz~e0#r9jv^+#Z`RJhvBbF1)_XA}u3B7(~IIUC{w;gpL^V1drF2&XyK0u?z+9{R}+j zu0vR8#lGch3%M8$XbK)3LxYn-?c)MP`~qOh?OYAa1N^Mcc?K^b6@h zaR^tT0R&_xKq$SV;@cJqUwQ$(r3cs`2){NC^t=H0xagM%yABum;)2e&I6CMfplH-> zRAJLgOG|e%hEZ|9F6j~u!WD-AQdw%!sUXH#vwjxH1{nbVy5nKcHC--?Gp)jItHG@= zOu&4HQuH`=CFx&XMP%F$`u(`x_ZY{ItzBt<6WS)T5T<IRSXBvBsO!U=2XQEb|e&CHl_;8}>xeF09ey(9^rzjN}}xtDJ8 z6apu1*s+NxgSDaQ`CDoZq8P93MP&n@oq<<<*Rdk;;DWPr$U@)0$7KWTC-If%jmpR= zg5DBw)_fYs(L^J`Kxz~iV6OV#qhW!84KU^hrB)suLLkqC8s)or(;v(gj?t}FPD6u2 zAw!jMD$zDlWelR<8faa;Kp>zzwN`S}NW^&?udVK`@SW2C{ZI?Ob0z|JTEgw(P5pHDZ(ytg_JCwt2~XTVb9YzfT&whMXD zfz)>Ed?z>?EO_A$At4uLM_g(k7I_3Gw+h&Zb{1y6uV>sp2zEHM4E^s9wXIDi_}OGZ zkUaBMg^a8J+h zOP(OEDaR#Gu)8e5Sm6F6R0QBo+6?2hwCI`2YtuIFuIgSVrb! zTW6;_E;WJNRh5;Mwatht6N<=ctPtMDK}b7rj!ZO3BC6cx8>?!1CKxSsEv-yKLc)HC z(Q?5I1WoFYQ5`zuW@dJ`LwNJBc4tuc&=fY4TdwO+l~V={ zm(eSodf!?k8n-OS01g*Z!YuQ)aH$bEf||n*=d%z&tWFFY4c*i=QUezzVeXvwzhsKw)BG>W(FjQ%Ujw# zwiWl&6egYawI<_n-GF;{?mXo*R8mUnFe}k1e(~WDjMo6P-qe+pKH;vu!^4xl`O+F| zW@dIT=yx&>#Fn_#?{l1!nW;o3aa5>NVHRNu*@)&v=%8+mMEvdoO_dQ`@9b66uwk4}GRsfqj1Ccat3#-ACx_9f= z<8fasMx615qJaO%Ri*nHx!vt*>grkb#~8b8@N@SbJW$hzeT>`S;%L@;_f((@lVyp@ zj|aMfl5aeSkHy2*Ebev+3~pl%fgeLc)L~67OTABVZGW;l6`7Gzp@T`SaM-iBq$C@> zQJYCoW`dYk_CHAqdNA+M5vGkHhS}=}8ty{mPYOs79oib;V^_T3T-N zIC8{!&Q|x8TmAj@;Y^r5+#`c#zhD+{RG|Z;aN5d7bXn8V6%+G4_g3>joHNhG7n%Z= z-ARw&Im?yVO&XBU2`Y)<0_FCEWt!1Cs4rP|eC5tIZ3(?6D5$lAMk$KHe&o;e(+AN@ZSSzq4z|M*P~Dp0V8 zTAs*GR23AEDxpZKQ_28d0a8Y&yh6uEcy*@=1+Kwm4E>+46ZaK)!5=ai6~;-$1ktKT z1-N%^qv+6Eq5poTWE;yos34;RlAeERoOGtTTquelsUiFM(PFULA1 zIe7#84!}%bDjl#SxW9(qFSXD6_qM(?m^hW5IxcZR4-V#!JkJsmPl5Nb7=2RJ-;@28 zoOMd|*RMXcYWZ+b*RII8>D@Dw)Ww?${Lo8z1s9vng9=m&+f{06kF%D^OZ{0_eNS|9PhG%R5B0mVjHIiJd(JYz7($r-Yn>Vvt7tTq!LD$-&BB3TkTBM1p@7 z^d$BHARHk2nBLNh=FqqNQlgWm#TIo{JujlSReWAz!n9v+Pxi=VW$5$f=BAlp0o#4z3_;pvi*?|xEM~zNfJI0`S$vHeB zL7~8)_97{%8Jtht+|{9D&OjT~E2Uu07s?AaA(MmR_;P#g>DDcAafVk70R*O8RFH0* zwanPa%gVxKe$JSYFP}bL#

  • ykv1ATU()&TnIfBh(sPksTpdW>s9`JN~<=UT7|C` z7hghvAg!p_Vq3BGhbgSP$W+R6XIUM6F6%#=Vj9%R(@#Obboq?pYGPqwp-v)EczAf_ z=?OMQ)Psj!*!hOA@Hbo?IYlZA$5nn63ilA-?}PXAF5iJl94chP?MHmu>!>;Ex?$R3@;;=3zOvZ`<#cAu}Noky#}onJGg= z87k4BWGXTXQA(kdsnDcMsV<}p4U#D-87k6cE;JAokt7a*Y&-==XoB-e(d{x9N+HAa=y=B?DRFUwpNkAAdHmXJ=tAFNl9r~p5>-|rpc80G#kD0wKN&}Y&mhGu@4|^|?jd?Ifa$@aK4owJfQS0r)YbiKK)mR| z6P@JTvep*s%AQ5lgD{GLRv#e!PTStzaX?k?Bq^~b;Mmwr0}0HT=MJ6iX@JF4aDnhTNTgC}|3QOBP}l&0qW`S;mYfzorcux1w%@zS zp-WF&89zDqs?Dn#uZ&}tjdtq1Fs9owt(=u#_SwY#T6x#P=T>l-PxCfQ4I-}|%U5k& zcUxs^%1*VQU!R?~6+L?Vc!&MgJ|nKij}XG*qMO@xQmK9@N#Z!CVl?{BP426sqv+j1 zb!Ie8WP}~Q@ZUsckZm?AZtcNZkh~X_#SnA%#QjoRD|A;!W!+0%Bb%F ziMs$!O|P!czelsnSQ(&edvjaI!-o&^=ev}vCKs$mKD%gB7xBJX{1h$$+`~Rnme^p8ERvA@+|#Pt&?7X7XsvKi_QGvSm``b8-GhkNS}N zBW4`#EAhZhe%krR$D^ay_iEim!}HpvPfLLa6+eGAmt=*GY;)gF^*)A?3PL~;{x3C? z@Mf!?pKl&AOTI-5?^%A*qxW8AWN17so>){=ba`{BDf0-ra+;b;NFALF{CcIAJ&zu~ z>Y1AQw*-f$1;xe9CEdn5X@-to?|b*Iez$JjR$99kq-{=uacz;1kYIe?Og-!5#2zqE z-A1odkrWW+?vNzDqb3-B+DQ+RkB{yxxFtEt8%f1&r)yWPjI6CLZzDOXy*;t9!>tll%F(=oQ!Q+Y zS8He6$&|Hy!?T5h-!RjC^x9m-ysPV5NCMPMnxOm!B~l)*w@kdm@WcaD+RHe}GNVFJ z;MAP(X`2-1EneLFgX7o*7pw+6k}0ynZQ8UsK4xQ+gWX3qktnJeOYrsVNlYANZDW&j z(|ME1c&E1LW9fvq*tL11;E5F5b=Q$d#*80tbid-qkF>~{{u>HYo0~%VH@GkP6Y*TPmreS+H zdWQ`Q7U=99*>L2`4X5%{wqr*{#efLAw|jk(t zb5NS!t5+{W=lIpOgZlUHJ$9@zQcs|4$dDl>=gp#2(l_(b-rU&Q;mnychNVE@B=dR*WA%o?G5I#k;uKl`B`I!HFX@tdoX`O+9k;i!j4LjaRqb^+=;nlHKZ5 z(nFK|!hQPOSkXdi7?{d;0%UA7WkZdS#KY z=5;5WLZ<3Q-(`CS&YC@YV{t|ov3D8vHJba_%-!AHn())LYu9V%T8UrI3BL2{)tILP ze#tuAYZABKHvh)fxe?1y0Rt@qC-K~X zRZp?nvSrIj_kDYAsy{Mq-N~LMrKM5FH}&jUe82W@;ERY+(c7Vdi|!5;wVAxH+pHK# zMSabtZQHj;%sr)B^7h8nd&Aimv&TsG`;?6LKYsiGuF!DG8nyZ76{(?iBjBdKc(EX& zK~-ki;DVQu)S#Uc-Vje&6Ttk-K{808+pF7xG5doPH8NN@j=o| z&B-w-pStV#lboE%fOYU*(^)4cD0BaQ6GopTuFadUFGz&4lFT5Ry4>{i=GU)ZALHJ5 zGeLWrnVI6(cekReX5FEvBH+tDUA{aFYu@0VgN6-LNK8x|Hey8P{1_a6Ue-hJld_}( zT8`jEDjzs_FqZgBJ7c%Ab53MDkJa_^E6pq^D?2}7>$R=ldbzr~4qNvoX~MTOM6Ymm z`-UxB((7w}{76{SH(YD)f@({yXQB3v`fYUCBjY!wAbA+aEuSfP{r3&++O~ay@xz*9 z2Z`2g+-5bj+TItQPb9XBJh5}<&X(=kr4y1imgkOa+hbH)$uJxc0=aDc`sR*^a|9Pf z4YL{L3k$`^(9yYDnC8vnT-xw{(I1A78g-91^)ZQaP%iDTr_IFba1TKAj+xRcJ zF9!}B$le(ZeD;DrZvnvDb?TIALPCJ5<;!UE4ut4?9K4OCvH^kuau^r|kW0zU?S8@P z$`rD{IA#p6Tg(~TR$CP{J$BrMu4 z{ddRDO{f^|rfgtfAOe5(DLn($8DjBCoSl)`Ib%6A%CsM!vZbePK4H+^1n0_TA|djd z0|HMRKYn~rap#V1>i=wZ$D+Hfh?SBaqtq8szlmQkfV>1W;-+di2$~-6o1( z&Iz98U;PvL!}x~NS`n8>ij%ne1%-vD%^u%${vk3sz^4bN>>ku|U{K=-ZS7R_S+m}Zg+hqipXw-p9oK1DP z;wb~QhlUyH>j$(VP6Fdvz-4ECGuFL^A~0s`*g^uknr*V{$$)E4W(_ynl&&DemsZtG{JAb_#mwd z^9w)hpZoo0e?8yH`c+XI0liSOBG zbvszuq1!MC=it;BC^Wt@24h5JH>=k-G~|$+zByIQcX9rCvwsAXxnuR>zO@5OK5Uif z>sJ+T*t98)D)8C5g~_fpD|`pKcNt=(C`_#qH@61Ap>v0?KAM1(WNY9rV4oc;oQ7D;Vz~)+!@d%MUpEiPmt9OQ(XDC#-s|(Z7Fx ziR4Rp`H!2fU@|Wwg-#t0f56H#W9Ceg8y6Pe*##hP$ojkA{@Z`tUW+sGe}1V2CsdA? zi1+;8zQQkcX|edf{qnzmEbjFG%kR3`y|`%8h8jhbhg;QZRuRz15G0vD%kOX4yxH^A zsr*5MZ3p__$Y=h};HKkUxVQL0%~Q(GG@>dl_=|GB>= zz8fW7JGyOociY|1GTwd(CB_q3tyANH6Js~YH#RnI`}Ngkhxd{70=f~ymfbs`T;o_D z8QGr(DS2p-J*Q9iIlth-KK9?Lgm2=sByC)#IMliuP*u$;L5=LT;q!|jS89Hh=Xvkz zGB`CQMN(Z|jR#O0IX19Tt(W8ZI_JjvYXRS=ohj?vPnbAy$+Bflf$3(^3)+#sUf-LD zg8pE+cG8U-(QBgTo%PLKHX5^?x!t|{_umsZ^(hh;uUOH7qCv!LZqzg@M!dcg@B#`* zKo7tZ2Vy6+)?!Lbg(>G$MyRQ^gz)kLCkAXqP1LB-9)F5fU9*f&B_&54-gO#axZLU& zNXtCqSMAT$f#tAVffsKaJlIZ|!>f+Kab9V>e55aG9vJ=%x=;SQ^+H zp84|CtAdx}lYi%JBhyM-Cm5^gQvWL0Nax z$F^r?g*4IA)3dO!_+Y!ZCI&UE8-ruTcjwJ}n(eZNfBW((wkdu=gT0*wTqacOtbWm! z3d4Z(6Zhs9s->E7m_&%bt5>g{;NGaR`bErSfa8YhFP6f@VERrVa7fDO+?>lRbNY%3 zLC}PYl3n*oje^eyG*I8CK72S+eMrMZM}7-drWaS7=Gm%qSVV+aztop6mHPDQa};qR z_b6z2AGbG6AZ-^yt(n~RZ#FC&qq)eil0ija;0PU?)wJKJ*igw89D@Ok2mQq z91J6B+Q#}HbImR->WSR#xqEk0$zqtdlBZ|=WXXJ}ZfJjod1yn@B-a{k4fBf!__5`d zgJ#zmP{&TMsVpx1{J9Nb;Z3qzkHO{_@3LP73cljDoAT;FuZiO_lYNqtbs-0&0ruM2qTPA@dTibugV3rTj(NRQaei&yy!lW-K!9Ca!DE58o>zB~Ji7EL z#xj0GZIuIFs$RtzfdVkb($--XW6=={!MwUD?f;X)4)qSdWH@P(hotvVwCeoRACB=Z zdnu82RKADr@WC*m zu_u7t0;j$~V8}ekDkaHXAX-3?t%b{L zF8K~6`ypvoA5Un#qzqk7Q)kItHs&T1BO-2AtX5@BZC~5anB4l(yvl2V$+uvxt(UA> zqlsLldp_%UEid53Dce?6ayY;V`-a>k9!NbQuVLic_j<0sjk~cA!Q=Lp?_lzpONKjs zm?5pA9$_t5(rm{+e5#g`r8uDsOW~@5E(RYvcC4bZ()7lk`_+Cr$#rU%U}zHsvZDFJh|-@EsEW}XObu^r|8?;R@yO=-=7-^X{*APe>W_oxR(bKs zI?A_K@iCPe-g)vwVZnk0EAx{l64jr7^z-vGKv-U4XV-khh!GI+J+bE*I#Wn_!g8lk zOzqjTXM>~T6vPlmMRQ_h!Pl?8uy!e#nQb7L)E3P%<(g;vmJ{`I`qXwpzGwVK>yTA$l}+>_SDVLjHA-Pas&M%rvaCQ|#P1B5u~H zUH<<5Rn<3kk%QU#hXVpUxfAEUY$|)EE;6L3ND_MqeLjA2l)p{Lix)2_4Cc*T|MW~d zpnmf5`#Cus;csWmnG+-vaF5b(lC7<+;nSR)!;RHZ{)Y~E(8jRFFZdlfweZ6SPwK>T zYqr-_55WZPflF+Dd0Qt+^HgTw3c*S$og=7Ppu`%o)qT4r#y9THnDclL!7e5F!TqXf zo(kYo{pbZ3%!=mDn&o-z+E}C~t-!Hhw{6?DrM!8g0&qBIb7PdRs@}x}TNXVhaqU8B z0=4Osf&PUok*O8z?Q(5P-^No~!I`m(?=(recI^%j5(}Zeut{9BwO`x#CASh}FjsY0%toS^vay@=A>e2 z0$Vg}`NJcxxQd{yRw`1rB;lm0pM z0R|LRC2cl-FPcWwmrqVk7BmY5rbKWVTgskIc6GgJ*htQMPg1S;^-Bnvu{gmJ*1ff= zEvm+eyz<$(j-n0C>5GM?RYFTb${lnDN0o)JAY#9tpC7%HdV_G|ed&@`lcr6{r~A<^ zmY|^d?BBnepi(t0_RP;C50_iS+qa{*AI{r5r?ADp*L}Mk0e5J5(i=uE40cF% z1Z{lwR7N@R(?S|kw}sCTSBiZp1@OuMrq2)z`4k@2XZarN3D6~K>$yI zzM}+4!%bpVeQVqIzOZ`x*)aCXTV4Lt|L8#Z@twdVctNtjefGNXr9~61lQv8q;7%NZ z`0^9j8Vb_X1znfEC{LDaDF6^M;pV+h220TS#%!zTjiqicKRMV<`AcD8ADhoHNTr38 z)7=}Ee-hM#WnBNPtgHZ8v{_UWNfNj=(N3b;YZ&RTH9JZll*vqt?awaR+Ln%y7)O~7 zkT$eN;s~F%-!SiK^unt{`R&Eamp5C#e!ZucmxE#^IZDp8+wXuy+!9phT{xM-h{BdZ z8>!*C_2`lI?3p4IN-72pApsoG8f3Ss`=E-#odQ?FTKf{h`}FQD0XdkvY%qoBsHel} zDBZ3=O>gReWqh)v%?!Nq>vh5OBk+gZ)>fne^?CB}x{pWQ0~Zvr*Ge$*7SnB z71<(2SzUhH`RxVER<88nC#DPy{&X%YYxx%4y*@tAme}_H<<^nD2vHHphP%B+NO>_<Un2jSRGwpqA?ZfwEOgGMob zwZ*}!gd{VC62nZs5JVG>)QFCk4)>IE(Pq5E!Vqn{#Vc2yt32W}4k5k!&*pL4L!eKZ zXxS#4IYcy7t!-MCTT)sK+*MR;W^Qh-GH!EA0FoEwT}(`ju&GO{!}jlQv#;xreW-j( z2xfxp8A=_7D{DB z6Gv;UKAslIuGb{JN3DCKhGad6yPpmL3M+7?Bs)pPtLPQG&fIYQil)?8!AZxst@kn+Y!ZIko=+5?i6q#Lt7o*Q94|*wDQA4*{7_a z-mbsCo)`vO4~t=9s5)-*xnZM5J>Kj*cFX;tCgGl9Lzt?NAw?~yv*wkt;W0WDCA~S~ zk*2=8ckh<;#w8yUaIv&zEC5u}`}m0yBW&(1N7iWKv5hDkw8gYucV(r2&(Whtn-DYt zt8i<~l_+qfnTd23Lqr5@o<+VCSV20#Qt@RC%B@D-f{WIc0GrvhD&4xN!BF3Y8Mw=t zOQ!(!L~6L4n7H7EyUY4_H#>s&!y#%l@~F!+vmQN4M~(AR2+n=7Old zxMZtEd~7bsVS88yhnSd}9#NZj<^br<)av52C6E$^FJmd$G`9F1JlF*ilqDw`+cM>e#W>on#*c)t5?i zQFM{q^iP7}NGAiRKKo;bt{ZuA~ zHGuy?bYMle6lrrBVw`4PXD>uYu6Xe=J7&nKFzSqGIdy(K>IFEbrz zt5A^KMH3lu@Cpe(oUHQt#mtR<%YXU5l~s~#%(i12xr?c?nM7KAaYV+<9{E{Wvyh7? zm5>3MKe!L($A>)|J#mmIyoL@PYPjWlMTG*(W%*(S%5xKsF`G+_gKFZe;)b4Wh+tNy zbPRb-gCsh?T5m&v2O?BQ+{mXC`u>p0!)Fg>S^Dv>=}2plb!W)38V&NZGiPbt7|?Q4 z-gL>U^z=-5`?e=R#S@DGc`n>^dad-nj@`O- zzLf1tIBbG8Tdu7vlgSjibvqg{I`opwjXkJ!f*RovndB~jo>}wivK&RVL(Q(LcuC}^ z4<91qs!pHzWN?~NEoA5) zB#FS$pzz+LO$zfFMn?XRqr;D9`3CNAK8WKb4C+MoiRvJN{83R=br-J%Ha+bt!ygno zlAM|&Ii!)%0}^jJ|Bx3gOeAO6Pk%cbnguRYT?53F@WF`?dpq`xx7QHf>JVn;>cpH#RX2nR%MC zT2WDvlC<%C!KY7Wt4{`G7SrJ|ShzEs_K2}4;#hzXP0svGNKBj#yLXw6Be7O%a}y@( z>o?=(H^D~0&Qg1B~wGUC{vk^}lk8 zW4vFGa$HMLtpw%%$%_~A6{p?4e|%$q*)CL|MGRMQVbVuAgXMIgu zFkkdPNq!IeTt-?HSN{DP^v-yKVGa%P(&R(l-YwX#ViQSU>ps6y(?vV6Sc@`OSR3;5 zZCB|vodirQEGydw=dl!i)zD6~Nrl|AV$BcQ$DSCy{$xhw-ZEJ1F`4DBujF)bezx}I z@;_B;>!CNezO3V8JCj1>B=o4a2MDGk!il4EG&Hoy?+v|#Yyt=p^s7+e?6Z#Up1_T9(X2rd;eCY7!flMa+IMV>N7Z=^yhd2|JwIC4XoCQZLk|T1@3c7Fp z=5uQhzCevIH-1E)8SYAsruK6_oXM9gf7?rSgne7`Q4SQGrk@*tPt!U{VPWE$hgB!* zEQHVt2r$0ovW4EN_x>uo|B+%!wx`Ki=-c{udNzaiZz?QJK0b$nzDaa7qYs(f)2ie? zLaciunBfcwRucLmK)V1~XaGU*vpd*8O;FAZ97h!PKu|I88jNu_Nnj=xw9 zkwi3@OcnI__*nna;85k#k`mD&gKuU8K8&zSm;Cq}jd;@>9PV&L#Y#S%+!qv;Rn-l* zp{dJ*h_G&lzC&!n{tHW&NTRuS`d@o~Yx~w_^74JhjOhk<(z12yRI%}U?XjB{yT)dL z?ZxQ^21dJ2QCQeKGYKYTKfJg`B6B`K<@x#f!kFW55<0a2d?L(uqIXTY7PFHFMuc3sU7@07 ziSBztsQj5tk2x;bUWO^ zF;7WOH{m6r7~&9*3F{A!ozEO&0hX;`rK24M%SIqe+hpD#VhMn)tarA3cTHjL3W#q zOW$$hy5r}&M{=&f|7=u)sN)GnBL+_@@14jeDFCH*o3O3I;OERuxq7mvPp9HgkVwco zlhE@`;_YX@%FQ*@n%RKgWm`k-m5jv`W*_V}yoo4S=-JSbd|sCMEMQ>6o|xSCYz5eY z9vi;A8ZHe!`AnG_oqq4r2|6nlxir>~#ah&U)22=EFH^gBGyIo~Q}xCZl&pYFW-=*a zPX|?B>b*4R4(*V(>@Nt-u|ww$^j|{KAG7tV3N1E%f>-sC~!1?MfT71cc8 ziI-4U$t0TT9S1lXuUYfp4RSrq5%__!^tspY3T zI>uG)ajtEljDEE;H$hzp7au+>=L9)epFJRCFFa&{-peJ!FvbX`-o?d5HuV#I(Q=ZL z6P$PPv!(Bbj~*>1G=Km7eHnbA(e6yvTCPWr9uA3zjt4|-zIGaV+$;IIlmeewnYhze9VK{26-j6h*CIM6(L!4SdK z03C#YAuL^6w{ArWW12@dO4>bp_qHM(A4-2cZ(wjHNMyh8ZoNJEeL$Dl@+!qa$;mr{ zb{pd)*9m>}19cE;@A0TpFx)yb=ANipTXlfZL=dMT#RYecCwvzMNp85n)as{}EEO=S?EyzkK;}S+GYd zbDB`{{w}|oFLbS&?td1AcF`O)s_T@Nf@6K~KrK`GP&juuxL(ugW+rPg4-fK9RKX(Vx%i zI}dZNAduOlX;h|y3lz*{p8B^RhI7hzFs6uOVHll+1sP9-I4=&>JqptDo=Pez3a17P zHlO3*jzgIA(FY()Zb+pb+D#ERxR_XV2X@B+#DR+G5B#Y_oc!{JYlI-Zbg+96*Z9v7gtC}%?8Bh}a~ z{0Pi>cJdfk+8IH=o33k8!tt3du(Sjs;TPM}zUTS4w+|n-BG9E#_Qg#YRdKt;=4U3K zo{tYs*Lc%K1@3EQ6p|7T!-Wf4?qmiGEYkUdcI;3Pk%`rw@uMrl-2;vuRlAZG5gv|w zyPxrI%c#FKoN<;tIX{0eS!~eLO6Zvi{0F5f#nVE@9=5za*}wWX?skEQu8hcZCLEDi zL>a+1FK11-VPzzbJOKqfA^K8rcNo{@0P9^*Yi{L=N)=47~nY|tD;##9;W_#tA4_gfxfx0H0o!UqM-FjDOh_GXaq5IjCPad5lG3yd{~j9L9cQ$)+qTTvVz z(Kthx+XHR#vBY(A$rCx+Xzo0Vnm637cC&OX;hqU4f%YG=qEP1Upqo*{Peq1|9Q6U! z$qPWbj25fz!SrG70wM6u{qk;dkmgxAX^#las(cC~8?*3gd;04R=Qe_>()g5txvL1d z*u!u;UcEPXCEYkQRcIU#f~g=3T^kR{Nc7brFc7q-M)Q0;SW1o0d>f! zI{sfedu;OPXE_P(Oo42Hbq1YK+CW9M7X~#-Yx(Nc(TOMOP^Jayd=+Q6f3t3v_)`1h z4x-;jVM-W$6D9i~N7?!(2@{jqW5P2mZ2-B75ueO88T@m|=jYL96X$?UAsL&B@($eg zF=-A}yD&a;Tldp-zUo;%F;RSlA1@RqS06e_SWJ%|I~Fl3M0?EkYE91fVp_&WxjQ;) zm%Y5?2L;ia{s3UKuR9H_#%RNQk$EXu@G(y#*&%ybTm|7xH2lJz@bv7IsC&Uy%C_AGxrr zFft^CyePo7P|(NL2bq4SH-R;ZjiK;IM3ykZWW0UOU%R4iGvurJ3EamyaJ0HMcz% zJ@3k@`2sB7uCHt({6fM4N7QLa7y#1;R`TG_o}>yhmoW3hHI|4qs;FuPJDW6D=-PD; z`>Y>sbYUvXb*BKXsIH!lB3%H3$mv^x#rm(4W#Yn!>FtDZ4KvLyDrowfc8PWc0t>x1 z#{<4`2gGO+bOYfl3beBmsC31O6<~u1G#iaA=2?#q?Z^upZ2klb_U5u@t)TA>7`(^T z9R$w_(OK3I?60jl(M8BbrG1`3NCZ~Xv~s*^*d_>6EcZG%{F-dvzWt_KU02ApyS&73 zh9%JqrIO;^B7_3vF7e732qnA&f>65UGE!g+z_(%XAF5v_nRT#AT+@md0dFmZfZtaC zdpNRNm{Uk98*VaT%wf;@s%Ot_hL4|5VhIe&p-3JGNb^EyoMK?mf@Zlp`R;!X=I^L$ z$H#d*KZF_V6qX%^xm2wbO3!bo2kBa&{sLB>-@|AY(5tSm^HU{a5K* zv)iykoDR?djGH_tW8XCkwWdTY~sX;(vUe_b|>gC+0IKy zM)0x7a>6a$43-OxZ3+6HMbd`TvPq|pKY9K<9or8k_qn(RPBR4#1)#Z@V}kS>s5CFm z5q}A)zQZ$LlhGc!S1AO%LFhuF5jwB%My+_P!m(N4@ZznHPfKVuE4u|lX6OCppiUta z2pQ@oRxu1aO+f{_G5#q*_6N&fx`INwZr!@ybbbpIAP_CAdKz03JG3|DOZ2nJIUOFX zs=32e6%uAaS~~mo@AqF62L&lAKgpvy1F#Cy#pFa+1@aWCN+BfttE7$nRC@LlMjVL; zRCcb@R|2=_cap9Z=6D1mvBew~%itL{Fin?k4E?fspCV@!Om$z*l1O?#ayoPF25~IG zbNigycA<&)dyHHa+39Ri@nAeerQ3a~;)~CWcKy9Ulp)eNh}$$tDsy9}5)ZytmoJp= z=;WbtyWk(MvcCSRmVImcGC6E7*U=h-9}RnbA!9WmCHlds=!4KAT_LWZ+np;T;Yv>l z#|93|j)>VE0jh^9ZQxco6fc%-kKuJLdF8vC*9^x= zhI3z3o_|KePJQ!6=+UOqo79gj(fGd?+-a)5mWn!+JVYRm{t%p59L_;);vsVOvlr@P z$6C^LVFZiQiuW>sQ7lCL#m?B5L1uwvM;qU?>2ntz9{Zmk=6eOqE8%3lBAO&L?)&)p zDG`^HP_YPV=AtR%_wV06qEk_Sr5exa>=_<^ve{6}dVFJ=M?5})ui?ii$LO;QXUct>|9~F$lgxlqMN;5sk>@pW8HdE zRT~qWi>Hw?uz5@)_)Nomko$gpZo*9Z+@?`fw?wKoA)bq3Q96P1bd@H((`wY$9Of=G z0fkfg8UEVgLUoHxc@ky7sJz-U!LPq%lXdio&YnOOaUl?bo#9#P&S}SwJGE%hqOtpq z{lj#Bm~E@yvJVa{HHi;FCwh&4X0do$nOFyL7hz9)n7kx>el1(HXc1UXNKlgKFJ2rL z5QJKVjo1@1lj7I7$5ba8;QL?&_N1Oi^yvbG?*hK=ifh8Za=DXl{OZgW^78w5$(CYQ zJ2rQT z3d5%53zM9SSr;b`^|Wt@fX>=W{n?6*EIfF$YM}`X5PezCs|SrR-Kr-}HKPAM0#_TZ z=`=o&H*enDMLK$Za_;O5#lD{#XVfNcB8sR!?PXp+8?(mJ#4Q}A(>1w)r9&weozl;ff7T6I$fPS8pT!KQE9=vDw1G_VfGQLOcJ?>pza)6T z@|Q}=SUZJqfsz-k`EdGc%8l-#Wem&cjLZe7mH&LXwG&+o$%fP^Qy}&bL3I}8eqBAt zQ^;fz42%@z6K4p3czrgHVFg*PZw8o#TJ`swe8(d-zlu z2>%>H`K+ts$Bco2tN+nlKLkpz3nt38nDOxk%(1KJlJf5x`SC{G!Q-M43&c)4()|^- zgbT z$;vba;AT$)v|>qj9m!D7r0drSE$(s4#*7<>AN!kspqBr`0zSmUj6dCL>guKr^q)+d z#ofF8Z>O1r`;;%Mc7qV?WgyjjKT-O7I}V!0hrTsPSf!y4muqJ+wkLNK#ww)JpZ+}w z5OfcvCckNMDnjemEyvB919FQ2Hjlq;2ymVCCl@i8ZSf$_L)-Y}R))&9r+WA?)9(iL zu(UBCJo_j`#*PJY&y3i{}3H_;&Hs)(0~#Wl26!v19A%cBfEo!r%Evy zjZqY3D&?J3RXgCCq=&TVX|tapvrg&u1adw6HcZEU&6)#fQsQKozaB+?77c|YhD`4V z9>5b(v=Jd;r>5fPLy~BEu=)h;KEvmZp$1MK1x`mYc6dI4e__O!*iGT$No4~K2~ zm}MPU12IE|(;O~>54O_MjmAnPMY70LHnKm)8U0VmEIkI_05J3kV__&c%*n(bD(8 zYNy@3+f0B)Kdf zzZQ+xBChash&@bJ)68CB|Nq#0VijaZ)NmV;{5<(ha3m!#icV7o6&{XgNcL)6$@C3; zOnRkl)SNF+ABukzE{1@M7~~j1*NV%;LWCf@G)7w5S{51 zRyRzoxN>dLzQHW1zo;HzQ_#tzd!h9S%~=#=^b?uB!w`sHwB{gq56_5`Iu3twMf zRhxIzU=80V+ogevV7P>eO(}UH;R1I+Oo?Ec=>g8UTcw4pj@}ue1B>6K;z|Yed}l0f zA$J`_>5y2rI@f@PLp)ifz zBw~Ir#oZDJCv5b$WFxWcJgnYnf#HI*a4Dhf3b7u1%HMT$XeNP7?-0cdh2tHjL}(A; z0*-XoJCu1b3qzL}(t(jHNG9L5n+N+rP+EpfFN>adjGAiYSb`>v89!bOE|N)No;@?u zw7IURtE+3c`wTF+1Lgi2psbx_0b85aS$~I#G?qVq;mlt}RHk}*{&h4R3!)qZl4)dm zGj*jSNj(iqiI`wwxaDeM;ypH|7-R`KH`KtctA<%iyr!Z63V3nb-5pw|4Yd@O&v03a zHbCT3&Q)1(W>ie=tbNH(?zf$j;gJ7v8N?Z2{!_`g9T~w>bOW>B8a#TCnkoirh?W?= zI!O%0VK|ERZ?d>_$7PzKsZM-3Y*AT7#}>`0oxuQ>epJ^@K>%%gO*kqhDE$3OZgTwP z$>eR+bg3L((Lq5=MruYzYt}V;b6NfG-`lFb<*U-xAU-lh20%g@@QK0|@7{29$|WmT zwj4C*tctsXIU0m;3{ZE|p|R`m;g0(#_+hLhk~t?Q>?LodA~4fhZEERa=qIHJWJ*g~hhZjkg?J9v736NoB5Gf?LqW6~1YE^59 zCt!hs{1f8Ox_sjJNf&K>%6-4%YLKjRoO`<8T{zL2b?~T ziDInpHH~@SySmldSu(+TKXYh_&&G!S510SO{Pw-7bl#PCx*DW*&bPO3+or~h6#?o+ zS37BG!HsN^MxWr!z{VGL1F4Q9>}JIce){OqY=??26@_=Ks0u202`Z@NmdWh5HEY%c zJYK<2V#Wy=UtT;}dK0AuMJi)+*os-R4&2K;Et!PlQXqNY|9Q6!+y1MO!}x|fV+|zd zvNn7q-S%mQEpU_d8Cq3k1%sQXJL-hkY^Ouq{Yz$XveqC^M3R1FIB6$$$PwX#;wVRD z0W9vIN#Oy;g`)No6p=>cEj9&NVkc`*wW>Ac0f15pTq&4C zjnOYi8sWgFV9cz*R^21Ibd$B%*?7ejSKUm%*D z-14`o&3g|qxP@*EB_fuKm6MkMj+Kz)JOTr|(6S*IlDEs0vuEB*K3MclM@L7Wa$aN+ z+~|{}9U>0RSGDK*MJtm>2d&m>WfjAXp1q8kXW-yum;RGw?Llzg!v%=uVvz!Y2xiqU zBfp(E0rD*(nWd9FH`(|dXKdzVz!$sWY*i;2F{Y2F@piYTnKM^y!GEonorIVQ4TU1V8jd5wr_|&;FghWy{LVmm^^X0EW`4Je|`jrr>UqR89Bi@>;BRR z!w9T~8iR(&AidL}yOs-oK2YAXYSg#CJr=)BZ3M=`o_B{g5|hrPSIvGw9wKU$_PJ&~ z)cfky(TxqiZ0RuSK;?5!WNU)-d(6g^igV9=D&#Z~bL5NOzbBy@1JT5xq{IXcj*s;I zKxPr$GWG(-sQHB+iIpSl`;~ezd?mqQ9!)`usX&ElOL+~y?v2qqFvO1h=SMsCVsfRzlo_S) zAtg*1WMle?Mp4+E?x$3}7&S3v?%WQ9V||*;g4Qdo*s7QJ>eXU&OmVt%&dlyny3?pu zc_l)x5cZ#)pWg-;8MxytAlsMBB8Vt4-v~MGGF`&-+le_-*_E!fH8o54RN^y`Huf-V zA{=LH$j5K=3s9a9gQz9hH3x+5x^Q6#zTM^$f#^kMCv1g5zDvTYchp#ruV|R*Aaqjr zpT#UD^Q3kYV|66`nJWm7L=v3zhaNpfW>CS28C#PX6nQT}n??y&8|_MqWM4k*x~Vu@20wd;&xp^ISGW++X9f{Kdf z&yM&|aOy_Ld@~JMvskBctEw-rJEO6t3#kFFO5A7cn0r9b0p>QRW=^)Tonf+$p1{A< zKDHZt1b68W623O6o!p4edCTqjSCKN2kcUwPGZ3f<03)) zW27}m_&o9Nh(ydo31Trnh?s&A_(9xyMV{W(E})j_^@}O*k0m;){pYiLNfWNz4)Y9#O<}&;JiiB!YF8C=j0vOZP2fy=~QRv8_{I zzqYKsiEJt;bk;DilI5KxQDCKlWdBhVvRT6aqoo8Dvlaa+@%9HLy~Pl0Q~K+NHuUgd zl0{sVGdY4D5V%yCF7;k#a;I>s8J4mg#98BM5DSXOl;Ly`{z-LHcx+SB4^8qx*+c02(kq;Z{=?MzlbY9GSlAAPG$`om2#@`!&pvS@RsA9-_rvHrdH8jXu0 zZ=Y3s`HkAmG*>i|U?mhbR%rskv^8>vXdII+6K^8=JeavKSStFYB?_=ICVQiy%f(oq z*Y_?Z&3WBGrDSL6TeL{%Qu7lVc%3F5Nf^u$zoQ0f^t?*m=sRqfvHDy}u)xN9Y5=~d zH=Ahh>q5cQ5sF`=3{y9F3v~i`+<{^)OME6=1LxP^(dYD*Ru}Ljt-{YNx(jqTTXQz^!O~SdP)B6+k#nFj{rCtetO3~C=P|g zvcknZ2hPCi%i9~~EZS6(UaO`}n=))IQ1g8iJsk|jljTdR{~-fq|YK4CUi}BP$w} z%5LC_*~gDdC(w=^4hS(U|3aK~Jw3gCrJ)x{6$u!pAqO{6&9s zX?ZSB1M0|Z1KMm9Bs13E?=@zF1jmPJmtzbakZBuH+c9miIYxkkq-|n=yB=Mc=0EX8 zsG=Yq5MDp>im(bn2n1GA`OEWi8u97RXhNZn#V}Ks39*Iv_HkiE1SI}fqlz#MSIwiN zMPh83-1ioT{IsBT)~^aZdQ{|l0-FIaQ?i)NLCt@Ui6CYf50X4j3>4@bYZq;q(?Y#8 zNM`I)W_?_#n(pibWD{K~IO>&!Zduk#Ny!_e`kr&3VU*d9!DnkNDFro*R9Cs|P=rl9 z{XJ`(^A^2702d91(q%sT_ovaY!l{HdiF1uNkNq&c)~<`>+^w&zm9tlXpue*~Yl3aF zRx=4=GJlt5gUy7YUiR%PjsTI6MT=AERw*V3npx6_13J1V!w-BBL@mMPQS}N;$d*A7 z7P_Wy7rxzB{84-8@F-s*DPF35$eQnIm1d;QNc8RbzS7c-!s-e%6+?$$>(b!|#M5w? z`Y-32Dj8|q9}^DJT37J1C{ln27C=1`;5w{LCSWvyQu-L4%OU=&U%{wl%2KcE_^ zyPil%-roPrTZWU${!w6N@iw~cxk#a`O1CMNTTk0QlH!_OKOJ#hYUi1MYr8j_R{hG} z_;~iCu>NqH49l0LSLP_!9Vx4w)mpi3ikMD9JRc6FBrQHnYi@f)xGS0OqJbFqplTRD zlMc`y`EF1@M0qR`(+5m+n~0BC^i8uy(YJm*9S>j11e&3btmR!-y01t)9zM|RXttD! z-EhR1!9}Kbj~q+hYLD+*GAaJ`1)Wl(o)cYkp4OT6xzT9mhQm$PRZxAK?|zV zjb_Y9VP=#9(_hdNq{Z(58S^WH)l8<8#-mC>fGG6p)xIDtID(Ct#x+$?m_z`~#3&qr zeu~Y0lnF7}?!UE}xc-)ny!z9MRi|-YSZ;vLD<@3Cg3&^}3frAA3C)m4aTd2BI6%0O z95%3ZW~uJFjph33GDZ^4DDC65YpGQO8=UH-C&Z2cQ&TIemN*NFsarQ6$`H|bfP0jo zN0T7Ib%yrS)NGsLtyMQdJR-;KP8-*4E5m%RZ=Rh!*U2v0U+Gu8uWx&Ld(R(f#7i#r z5AQke`c}E0zs{wy*~6e2O#P^WR$TXkHj%AJzvjDd->#4l%fu}Y1}ncezI!CO5!8;G zeEP*5=GvX6tkn5^84YBWYT1W?qHlYah9p%f8mX+RygH4l=kJJGVa%rbHK4E%9)}@+ zI3B-E?hA2~hi>>_+md=mw1!s|6&&(H1=dN8iIOnS!x ze{;r`5K2Cd?lj_=XfdEE%3^JDRfkssREv3DfQ;@QL7}1h#P9@`3s>9WfUBH2F_jK` zPvn5{&(&!4PP40iXFB-pZMk&#RDeqc$FEgT(@o84DJ7y#?8Ibw4zW> zJVZl;3+d-bhY;mQJS|kr@F5)L!1t(>GurQzQk|pfheWLwt|i}K5=F-lkglny=wNpO z8y`cw4r78K_D%zb4OX?Iod4gousHk5FUCLKhgK6vn^jj=tWjO@JpW-*IjwDyu!LEs zci}S-g|svwt9Dcf4QXw$-U*Ydpa5Y)rw~nq_w8WjgBV@Wl_!)V>K^qg`{P&t(W4ax z=GlB^c8s2Mrs~H{56|1S_;3-Bo&N2_zy|ec`NhlZUY^SMy0vau-Hd<5zAC%-63yD8 zcF_EAv_fhV1EOd?!3;{UT2*hq+yy>|&V&@f`MdwwAtV66pBT`zfgYp4tG@B!U*((@ zl$PE;n(c6F&hasQ+)TFq_&7UIYx#wkm_sZg(=F&?(^&h1U=2zAop62{=|_0?@RWXM zto#gTrYS>??x)g@@YHB*l>4mS>`s| z<<;pc7r8D8_1CT}+VSG$OY@NOf$RoU$Ga5T!|6dsfyK7a4G=(Ooca9Qq6IoNCu&r5 z_A=*K#5s)-L)Dr1V*36)iTO@$?zlWx(R_ca-G#GfTNoK-&bqqL$_mqoD%K^9JVl3) zb_yAWtcK`e!+1D!q<`PE(4Jn#jRh%kf}9UE88)7-62X?xl|?s}go0P} zrw}nrYkJrK{YCdAmB!XPa<^Xv*A*=?u#N zjd}=)i^CzZF+!~;`szxvJ=c$7zbY&*Z%1XSX&KiH#EmBh2ag1)DQ2T<=x@_n(@E8_ zAI^v~5;k;p?L6#gFVD@|wCRWDx5>04NmOfflyCRjd*FaD>cnaO`5y9jJSs5{;+c+65gTKc6O49p%}3Lgm8Vu$W0C_%yQzMHx(|*BQ!I z4A%fZO#YW{V)qvo6!b1e)ow1C;QCvE!eL%+K9V3Gqh;H+`Z)S37*i-lml-;fs6-zT zR#CnCnR4UsTF@6YpaC2tb4nln_>`U>kxMF_7Uw^I0)bLcfee7$FJ?1RCL@BbKVw^e zo^i+j^oqofUiS29RlVzhn6IDSXnxzqX%++3xn`k{NUO*-_BSpO6FIfW80U2M-+>)< zR55V57Ipt@K~d2zM2`vA%>VwIg7yetMjAmg?$IaoN-)pz>o%yJc#qOqL$kyabh1Fg zYjkMPLGC)I^L{Er)?yJ|Y1~}sP<@fH6h?XRbl~iMdC4|UIWoA*gkZ0Bc>tr;5U5@UP27i{5lu6G3P=nzHD)Vz-{kOC)g0>U7NEMJU{K)!C-2eZ78 zj6}y$iuawv%F@WlbDHKyEl)7K?wRhhanK}UQi+&UWVew1WIi(PVlmR|{F<$fj^dfw z0YUZwsQa5X`Rg+Op(PFAwYMJ57P{{=C?z4m)Kj>=enIDQr7F24KR7-iL7$3M%*_#e z2#0rpWqW51gzy7^00VNfU<4QJJquyQ@NDq_y2C+1d!T+NapOp#N8}ej$FY9DA&Lx) z;blbjiVBmz%_o6(zQAQV%YwBb=y}B)hAKIP{h_=QZhZ8P-sTO5#PmUEZJsb`5_)0? zO^$hPJylem;l4Pd_jABcsmIOI?Ua8CDSzyP9`9RPVCF;*3~kZDrB2gSKO&78?!F+* z_gr{5rHN(GpIEp4|1k^1IW$`JHqp(YUUc5H3GQZ<>XfD_r1gLxYe94iybLibQGItL z%i?5_(apty840&9*6xN>DDw)uzY zz#IY8>+~qG>@F6*~S^n~qZ;Wh|u=BX6OWdg2X*EE&}R2IP^nhRWQ{+eC2Mnb#H14$5m{{AB6M`DsS@X!_marlJw`Z8_j1~X%lgJ&|2>sL%Z z?)XJqz8yF~PrI8rpP9f`Av&hKa^?PI6^JRvo*5c;9HuyFvR8l->9UyG(Yk9!78L^a z0PQ-InA3;PO#a6qqV>ASdv0vCZA)Gd>iq84HWW6$plWl-7RjNwb4kyskIBkO*I~Fs z&SAA8NjQT3-}Lv5cfcJcW;Augo1J+idCgKl#(8q(@QXn&w0 z18GUftw}07c`%au@l1g%YwhR|jNgq!c3e_*vB%Kl{Hth4VKXm?6+896b!W8V_@j+auH-u0pjNYULMbKT#uxuqs>p}SM;)DR|KDIjOK=f>-sPo47h@Y!{vGpGK+@r zqfjoX9XiB<#x~wD2iMXVPc<+~!e>7j4zoZhk_ufbsSZenDtZO7TS4$|i1j6lY@X`Y zE2AKLt^yT(0LLXkqfwwghlGS2ZTQApJhwoxasz1~QWHNsybtiG0({toUkgoA02cS- z%?60w!Fh+y;Zkz)7T5wddIjpo?4$=QWr9`+Fk%>L0sb5Au_2}6N0R)OL1`Q@2 zhb6d}q)-cwh#=8Oaw3v4-NG{4vZA3_A;=n>|FKY40GRSayi3`OGd*yXzr__J{13K% zT(O5cr0bB#q5?4|ag`Bxhmh}3C=ytc%JQD62R(}TLXw6G`7$H2RN`sGqCem%PlfJ^ zv{OjPMMQ=Q_9awkfdJqjjMR@iy%ohipI^yno@NSKGG3`eV!2QV8)FSaLN15kuYX_| zK;|1SPOx`4`Jdj(z}camW<@-yXpM-g2jw&n=u5bDM%aiz&L3T4aWviHFg$x)fLC{b zI3{W*tXM*?8? z6``I60dYi^6Eh_@mLC}d*Jg}D!lLfQdSu?Q!t@Gh6XACVXGP{I@Tr}~#G>dK z*USaU2yq2rq_W8JPa3?HIJiFn5#NR{5!Vs?R)?^vZtvIvSVWEJx={FI@7>#jeul^@ zsZKX43<(&7bR?BAifoddch=b%(>MH41)D%-q)w;hNX$q?AB;;(6klkF38f0x2tV;v z7{3e9zx{-4uh7*KE2=7Pn*+8WqBjB=d#8SL-I&@}VrBuy5R3wuNI2X;C6gRn(p#cI zDUo=DHk8b{0e8SpLRbLRKRxksDNMC!X3iu}YoTYkOpNB`cQ0Yo7?kI6kZXxdR40Vp z@fyUPjm1|Y<`wseiJ8B?50(v=uL^Gp+jl$a7c!#<>}A}j;s?}IRUn4rbzg4l7o_2> zFTivIjQ4pHk&ggnALg`&D4#c1_Wr9!bysEaYQy2IijPl{wTTY{0Q@SPhOA6XOk^g* zkvvGf5d6B`{RqjqBzPkt8Us*h2LR{YI|cWX02s)1Se%59fMp&j5$P;|w8{?agCm8F z>)`q(=;?9q^w)F$jguXNLe$9CmTWYSkDS8O;s=ViX_%Wqyo)9q5R@pc0 z?(R;~faB8v6%3(F4IuJ;oVnyT!I#EQ9E~6%Zx1W|7gMAT<7FHs4ulmsm+Xg0lNGYI zw}{gs_kGpo69E9dZ+lX=dgnoHketk<^$!a_~_qU0iBn1Ep)yBEz?(_riy`t*KWsc8*J!}<<_Z8p)U`$g(lN10g@fDOJkGVua zW)i<`EH;0r$PNL8#Xfg}WE+Zf!Ez9jcqIM`j;58Ui{DmMXh0~V-7mFjX8=~fGO8WZ zR6ZqEERC4+wg;b%`4`%dPX{24bqSE@+Z;|u9<|$z~*Tj;1WMPOc(JY@HwZr?D`95a$jQYgfo)iOxZ!t2D_jE}2=> zj|I5$YTTG3yr15`-+gV3l=|ZZQPuBrhn>&txCBh=Duf!uk3#MtjtBH9U*5Z*7$@8U zad-d|6#*&0KR?+4{t|KR`j!R^TZ!U@WEsXEyvy$Fm2j=g++}X1SIp>~+U~g* zKRrYfe@f0hfJ-DY1#;%M7CzMkKZ6XdCwnA+53s1p*qoi$ zh^QVi2$Fo(6ULF-FkT=4G~52P%Vts@U+-993JZjIa$rnuo2gG9gDwzk@hTWMih!PC zii4=-qc+qLhS1X!H#1Jq5xFD()|$+Y`2*~%UJl@u#9@)dez4dvi+E6M{8$JX0!%2c z^o>qW-M4QAZ{G0d7nU5`x$~lWJxt+%py@R=D?I~#j9k5b-9IQOsD8aTNruE>==h5$ zyI5&TUW*}UIRIODEU;TH&oNf`r#XX@tu( zThtp2h+vt7NMY|y#k5r-=)vDC*c2~RH#EpOAl=>akQT(&hcJcA^ZEvBe33+85%n*@ zBk<@K;g%sL==pY!nDw}UIDd4%umkVI$%5_4u(jX<@Tj}$Jf|vW9bhXZ3l!4`V4A;#h74$p zKenu0YHGro*JCp0b;*2C*b7EF-N>;#dU~d&eja`Y6$rUVgbes}V;DH1$0lv;x}!m< z5u*^v9)(hdhyzg|$Du}bcVT=lF`-M+yHUA}^o9R>#TXr@Zqjw2EX|^)vtcwz&j{5@15p>WEsK*??=CRpbg5;`=c|yHP63_k3KCYiLDjRkT?Ia z_Wbx+^uKcUz~$hR5(4WKuDT)Ar4a|hTH1bFfV>bygFc#6jGwC8v$@;@y%@>kGR^Zm z7#k{HElZgS$}XYNh=FtS?<|zVd1QtUcBi{7MxI*Viuv#_Vh1^AIDY?&(U%>Vn+O*k z{jV4;3nbE1R{i;1JkXV>VOcyJ-`d4JE>1q`507_Bf5xkLiON!39JJk<1V0%!!@IzEaoR`>_9ggu$Kl+FN2D0nG{euH?EY@bD-|f#1Ky$V$-L%nX1f*f*Z{fSh*z-G9awAWbnrC1r(t4Po6EL6n|f% z5%vsx)6Ku`|2DqF4$^oi{rjc={6Fj6|L2qFql!QWVe1^vkYPz=xDU5%XL6vZ9C^5EmvGd;%?5p3Hla;=#$ZnTm#OR_& z0t`X|Jg+7AyF!<7HkTb>eWpzfGF}lVt!6*>UZf!2ku6-WzSCqmrmqZ6b!_#EKF<6( zLHO|2Db}R{78V~C9r2TnJ^d)4NClm~|+>+6Q>H%I1I$*3>i@v?$#L}6X5ruvc#ez#^h?JW|YEXN~wCJ!>S@-T99T&n)4NvA2iEn9VSgwOis z!XxuM0p5$=MKj!|wKO-)e4CfMa(t=tVL=DyhZsdKFml7RQ!F1WW^+j=>Z{^Be z-LjSsip_L9-Q{|;cUbi7*r@VJd(|nv%~I^Eb(r?NT&+h@Lpymh%B}dm=B+w#_4S)? z)l5Z?=pR@cuImrI$q_tZ7cDqGru9yF*@c=9EGs>|>6nHSHbk6T?dG=HZBlst^9;>K z?enTxuel$@KZ`QZUMEm?bh3Z{r=}WC?f1)67-kc6Rz2Uc*+}<={HCS#yL2k4z<-_x zTs;>!=_+<(a-8!>T=b4rGqmUa5i<-QUGx31o#96BWpuhrKe8@%a_71+D*NHWiA6bK z5pUKEezgg#j7$HRp_j0mF2Vbql#eg0EkEu#b__Zvt_v<$8{YBQXyfb+dzxW3Ng8sD zx{}d%z>V;{Ul7=R#Sp+A5d~w!11!@x#EB6O@;L!)<#1CF%!N{c2Nf7AInmL^5gL$S zPoz3@>SiL|7PuZr3fsL6zb`giwfbB>W4EimelEWBLW}PR8~>3|pIhtrq*w(u|0Cfp z;upsBAby!ek4o4m&+b$7ap7+My}@DpXUG5fHs0b(EA29Ma(V3bkh?dpS$j{$p7Ie*3n};%CbgsKliYqHc}1_jqlW&sbgL>RPyYilOml3f%%zL7ZfMoAwlc z;x}_%CZamX%(|se%X=;M%okV4V^C* zx>#@QC`ni9)b7->xnnuEps&R_Tw+Sidp9iHiGI8(><}wwg6fxV3*-BPyq0r66kxAU z4ST%SXUu&G&AMiVf9x>_jn!)xqwN_6s?qt!q67x7kXK178bg!Yblo;ARdDn-o|fk9 zwG!;CEt+z%IY`20NH_;kIHQ4V!wyHBJv77-^bPBb8?;*p!P<6cpuKRlL?i95c^ZVBIYOlNIa&`wzj#{{j!#Aewixi$*%-W*) zD4yPF|5}_NRJ`Kw)@r-Ty4!_^pj@EXvxXvC!=y<9j4L&0oyGo9Hip)$R#51UQ zip;x3e4uFmPaFiO90*992phByv+oO_t>jzDrV^d@XKJXbs{59!J#;_x@JI)#H`B3n zc~D|T|ENu|ZP%?~dc3i;Zt%b;eKxLJQf?yym8pA%XS&M~*5@&PBOXu~e*)p9P24*}FnBepYwhy}Y|WYnBhoNNXUfY4J(jH9Xer zJ6O$SD3zxjmvt{(6Pz!v{1otG!5JDqBErI>T7}^Djkz#Se|u@Y8nC24fb}@yZ~f4v zJ`*OY!$iMyWdR6|+YE;Nm|=;bkcql!-@BhK{Zk?wzCR;>DkV1fd+Q0-i3Zz?r4=>y zny>xS^d7~YbIns!H%Q136Ff8Y8vg#YxXR*GU;3kJ+-Q{VaWYG z62bItISwwOS|gk{e_QZA5i=a*^GSEZeYa)%0*5}yY%R-}3|NAo54FGHZ3Jjij|SEb zYT^>;Q8K@kSS4pB%04*507iUP#6t_Vobu$jbsAZeWQ@_bZ<9{PevdK4sM$&fhNpu8 z`?J<$YM&RN3OeRjY=7;vK3Y(qENbSSe-<6bMd#55OE`VM`|%_owkxX1-P+?;yOm5qAPee|Td z(*|u;J42>jx)K8hiV+4etcT_C9Ykmkj46H_P$4WxWfaWCAo>s*!v|YEi84J@?+TQU zI0d0=qX-KOYr%WeFUscZf45|%e{cd;9JQ5NQoH<#ie}iA#N7N&S6Nj#mxUtEqu1xx zI`Z#2F+%^T>g&wYV%KMl)TKQJ1@2F3KHdE1sQ09BMGEJXt_ff4VC}P$PKH6QZUUm$ zu0#o8P$#K<-39o!FkFAkOha92vfkeV%fxnxDH`h6JkMeamaYWgWth>h7UxF+GNFeR zxc+WCVoZw-z06HdoY?TmjOoawRb|4FyGrWvhf(HnxqD9*R!8WR_r{v;PVo%f(NeHP z`|{JmtQE?1RFdM!ppk~|@B25Yj?M)Hp1)e%W=%thZQo=64-bCyw3%OvJRNrgSBlYv zi@PIlzgk~+i;nt{mlMGo!&)^qz$U)U8f!JI--_t(7M`6zx?`*vX5VyZxTyuuulUFU_7I19v=L+)mp z&!3smtdEg2(X#P!4O@sndRv&MukW58Pgv(FX{iG3k?B-1T_ppP!-+K}49RQ0`rO~d zEdE`eCPLsse%`aHHYRL-msOS<#fVL5V%W4Dj?7Pcn&(XQ8)X5XyEO&vP0 zeb<4}hRQWKcmBLW9?4Qa6|@tNJLt=#ET-JNZO$vH?Yfm)TN(X8f7F5Uac?r3;woP# zNl$P6B1#?J>Ki)Cy5-E==HI{eQ@Qu6f>m}ytIRgkeiQq1CCjvg#3yJddHVfNY(x!B zF0W3drBoZUMs+*>+;#j}y%P7mcvEjMMcwl7USVgjr_*Vhs_wEGYw=N2%OzhOb_XuK zKgE50#j>9}Gj+~0QV$yE*aOb7M^s`gaK@gAvNe>7MVmBv;=3)#`W_BDIV?!|T-v4k zvcaHNfuf8BY`tHF|6TfMNYDi4nY{N-49u2aA0xWIuqp1zhyqvafzr>_t)mvg2s4T_ zm}dwL#J=vJ*+5_PLbb8(y>4p2hC$Wsnad|0TI2T1O7qV%}e^Pp5h+Pl7d z50r6YpdRKj&e=Hpds$h#7U3gy$Ew5pyYh8D_s%Vqc&A^oo!abHz7>79WLKul51pxfTvY8Ox+e|&@ucDtMNnJ71*v`Zm@S!GBHM??yfhbe!@@Y)l1DG$1w|=LIiXhf zzWzTy;gS;rXDI5r*u_jnelLf4g)F-70fnL~ReE~MM-(D$Zl7snvorF)=;nKG!TyjS zt5@V5b7_j&c_8WS$G0NUapW;C^Ef9SOhd)0e3vw=`zFVy!J(oiR6KGyLs`c{b(DS> z6RV&u8c|?eZ(w|YyfrkUQy5npbD&>3fQ?~;Uu~vGm+JY;yB@9^%lD#uW?lt7cor9m zPg_~=i6h3PnO8}_a80Kt>+L^Fc9;c&hjGvBi=Q%3e7)7zu@ZiGAJMvbSYUb^Rq%A@ zJ)0zL zT0DH;Qa`*KSBJ!jx1Ku*w z==-DL?4-lsB#5*2SwaC^fPB6e*G$ktU{2{$Fg{F3tHjrVU(*&WJa_FLI{bBFzSzKA z$U|u6{*C2tSGcgKI?#x+zuet8)~;QZl>4&L>h`(*xySU+UXH*13K<-|6)*L@j)q zcvFbm}<2u zw{+1**@iw@#jp@X-?^H@lWUpA^Cm9VIjEZ65UCp$p*$`=Vp+v{#&HeV87i%<64zhZ zL$!Y{;+kk=YFIL{_~qps?)~pF^tb%5knV1C9NW--`p!xJ!Zy;Doh%j+5h3h0KxRca z3nIPervPExhpf$EAglWYBnC^DHR)Zeh>*OD*fvFT&j%^$(j6)QIZ13_AJ_sH?7CLX2o6fcBxc%fx;)dki`hbGx2h+frTq)|XkS z#Hmt|_=iz&blOxd4zRjByHA3epY2x09K0e(vc(yFH)_q# zooe@*Xexe^l2-;+T^AY#^tS8dct4Ne)&=d5dsIXO9JhwtQf=Fk7kcN;Dh&c5Ez?{eRBxHS1GL{s0JTwA)3 zD0&)ZIcobvqZ8P#*VZ2|^PVpOwU?NfNR(DSmwC>Su$N!MAHUIsA%;rV!&1qShlg~8o{%GG3Br^<3T1#J_F*BoC z4+Olw(Wft8$Y7+>iV7j{c=yWppi8V>dfea0{(FQuuF9^HC%Ln-vKl={%F{D4(m;kG zIjH~?5Rif%r##mduRCd#O7|cqh36r2y7$TBwjbl>)A8`pyK=z+3 ze(~Z30R7%+PtXC|q@-A(;Vd`%d9Jg&+X)1OQul90h&3ceP1JDTok!_uMlCKonR6F6 zo^j#g{LaMtZC}!pTTFL&P0Yl$DQKj;7fMJgw&OBUaCQ1sn9t@qRr&GyIsxC3yz&(B zLi?L``-CM;p5n{aYJ)lX2`LEf%o15p{4}N?C>?Pl;_lw0NHrjd?OUxaYis;dy zT@l>AJ?F_rYsgt}i4rOe_Uza})3Pu>F;x|O{vAkR&9i5>@t&XLSDt*s`~xqmzNHX2 zZ@qTvtF4ulz{ZV_t+U_RUAcCx&&ljhVZnLsi_iL#H_cB`GdyNC4Xd}w)Ud8uW$Chx zvq=3_-VTve84Cfn!Z;1Ld6lD~E=*jF2YI(k=A>&$vq@qbPQ3AIc5SH+#77GGRzn|Yy_$KzUiyD{29HDo(c z&^Z_*MOOc8)o!0`OXy1fUPAe`-`rdnTCk3Xp&GP?&|ZD1sd0&t1oK{2 zRz{vTLBY7arLs{V`B>!qwE-tVEM*(2;BlW$8_1MN~}>Vf#wS%MID_FSp5IT+ z%@vjjQ8jUl*c7maiCZcuDapdlPFPfQS$0#!;Q0v!0MjMW^P|G|&rkQT)xZ?U1*LDt zqkFc*iV9m-&^_DNj~mo=$=`m_((J;v+=;E|(Srv*!AjEs3lj_TywP6cb>fnLkj;`` zaSWS!jE`^Py6%u)SM}UAx75;9_Gh~5*4OT9spnc1QgR1d;)5c}`1gy<`}=zF<{7(i zv2w1v!uR~Td`f$R#n zTYW!$y8n#UrF8urdz@O1HM-`Qgj#GcKfD?lrEdj;xBotB5E-Nk_LzD5FO}e4lpt52 z^{m)Fa$w8r9|E>HLwm5HfGq7Tn=4vtM|LB}Cg)mWI!MkLR)<oTj6u#+ZUdwmX+aDlt)kE#$mHfta8`!NF=|8-hhrS`}%29 zQ*v}VD-0GZ&kwPh)IQby-0yVt{Z5?ODc_kH89QNzS8AWs^q$r_Km9q{MZsn4tB$J| zSX^U}GM?{90(`SuM^JJllwk*U@21z))je5^Pwa+_LwEe=ar<}HqN=L@9sUg3n#H`H z1)$S0djp$=;JneGV^(JOeGia8FzALODdIWAgiddnRN~AceLtVRF|a8%N!9h%6*;SX z&$T|juR>FgKNCvmiBA1zgr?+a%f+919|o@ma0M;!Ppo=67U-KzqivcxGdJk1xn~ap z+OtP8AcZOxDf zH#zCp8`zE#{Nnm}~C)Hk9U<-7&hb zfD~+RLD1QawE8kjAagOLToNM|ZKN9x^MaWlpY(Lej#`*&SvU? zard8`f{>UqC1-ZH;V5w+$H|!7oe%F#f)$HSx;DKBhd~1~96{h=Jo6V#$*I0`c=6Mu zOsx_T1)q^thV;{SCr>z;aO-k=6!@?TN7=bVo?phe)JUyl<)d`l7~`3>*CJ&<^z9Xp z@aYs zuZasO4L+UT-d@k}JdJwT)e}dAgu;oq)tA z?SV3yR+V3>vvjoO%LOG4IG;U>Q5-e43udXuH+{S(GnlzxmWiboi28N0^5g|E<0}D- z=MHLLqP`sOIJaGBoAh#@B_8oQ5`h6znAucXRwmyIm*vMkx4*4!@wTUHQt@_u1P8;^ z_wN01Zoq=at(68}eNDz*pDMR}by)Jdk*n@L7wtng^U(-MeB9RWB(ss5Dcaa^MdiM` z1E)%@4>V|;xVQG8hM)jlgm>vG>MomEc%-W7Bo2qSZT6$REsUfH@Sg49bsw)Y_t;)( zpIy33wX>l<=_-xI(jV@0$5eMRP!1JV`Wgu`#(x>DfPm4`RI7sCC(#SD-Ct^JT@|lf zx$^OPr*@1{2-gyhW!TNUBO>?s-}~h_QD%Mpi`GGnb~#IvM@KXmFZf4!MdzW2V&!~* zqw#T&0<~nV(`!_V4-?j`U7Llvjl2;gDfSO#wz-5}4k*dU>TOznyq`Z%k%#TxEhd!* zMhVF$8d&~~Ni8W5$AwzK)@0Xv`;M!3Xfi}VKeOWgVPsr~5~#r>@kx+VN=}=|?6=N! z5|L-qGsIsgGW)y>G>?cZa$>xC>1{v+wQaD;ket?uWmm>oHJ7{GxgDZau}$H6Nh&)g zm3+18AIj&1@Jt0Y6dB%BS;?%dtPJ5dad;1njC4Sat`=pU+0@A|FnlKL(Ge>0)qNR5 z`b7+fcdw(Q;-{Je{vF^WP%T`TL?em@5Mo4dDJ{-VV`467Doy!mX>!Xy>37@tEAcb6 z*XEm%;|fj>Ig@jJ(A%qDI2AMpY8p{TM{|8*Wsyo0pcyWn0~c>fv$Pfdk~qySueiY=a5@{ zkG4UC=GWD|179;wJn?w>rl@RZu=&4fCagW8%4u|NC$zNK!0ZoBZ&y~1hWr;U;DZ1S z(1wWS&vuD%qD+a1h-gG(gQz^Gwo9w;u0BVVMV?z_n1_dfp%ueVS1 z9-`+D4L9RFF&DE@tHPh#Rq}-i^Rx1xMVI{}xc8|ta1`@TB!x;aw#0`DG{tV&VflJ`mRmRl)h8B6hh~I70@xWtX%mHr+9Wy@U?4;WZN?X0%r9B za##8Il=z(rvR-=aa@btDj&+yHpHh~Ul~dMVpRUF{+N(&{e9q(Niw4{5L+ZnjwoRR%#wP-mx|PeXuPanJ z)U%4J55)j=wnj%BOktI~a{omWJYAG~;R z(__(;m;+BTOQ68T=rR$`Ytr761BylQ zd~%jiPC@GN4UEwmo`u=l2Bs*K^a3rP4(S~9?_lA$Aw8ymJ(`tFEQ2kvGqJL(vy;oU z4@it6?_O2YB@S{?s#(2nd{V>ToeFaHFWSX^Tu&tDmIn6H->-)gXB%E|g-XpGrDBtm zW#j@G7hfLt)L2xWo=IC8>6TRIkn=XAcmDO;56a?bs~NY^H#ntoY`GG&$e8W(N7O+A z0`1z%$D|f+*SoEhHgX3g3fRk1OXWxt53P{>lk=R z!QX5MB_)QV8m85SBPMDvZ^pLPU32@;BDC^-)1Gjdpb|yv-Q;Wo;bfz8?McP5k$USC zBIpIXM>2T!s>(3jrnOa7bZ_;%yXF*P$B5_fr!!)g(O0 zERCQ;sOL1GO4fO167(0lpOTg`EEQiLAN1&=1uf&^#jZBkx)>ey44G5giWr-|`=(cg zJ{G#jSD0LTE8r~Kk*?;8Un4wkVkzR4lk)fxqmTT4)s$lYqH7dirx z=^b##`rIaqeKK?*8xFr!sEw*IJu)?TT6q zRDnUBoU2csWrh8w6TfFM>C1A4%S3TXEf|6+#rB5L6PVWo%*3V@g+m+UlKKws*_*7q zJR-?04G1WynvCF9Vc1e=98)44G5LsV&A5$EUH3igLaCGfVl+$2Wa~QDHJhM&d2x{c zQ4d|Oi=B_|2%csEI-d_c>*AfoDAqW$yODcvk>1Umu-;E&F?@Ak>|21WE8Vg5CroPQ z!pD?zU#|Dnvo;q^I~94ltTB4iv>(gD4YvEMxwt+epbvUG`a36GI4SS>k?4K<_nQ!t zn*W9 zAx^l`%1U7fE9_IorBE#@&5dfoiQ@jn;cva67RR32nc25-z%2a6l`}%ZAu&&%=lO3_ zW2GL4R&J9Ea&=yp)snMp%R(cme-0fD;}Hmxmp{2mqUhep)!#va1}|ieQlENxzy5rF z*r8PRB*S_C(E6k!nrdtzCYeJ;Yu(Y2Z`|Ty$Nw6pNHibUj5vV2kUXOoX=$)BV}Xa< zxl{X+HVo|?pbQ|1hjet*;B$~^@svc31|shsZaGr25A58j(a87;qYVafCr;T&>(zFk zH+zVT=epeAJ*(5=?7atEI-}n{ z8!|t9`MupyUVKw;9b2WsXqS-Cnk{7kz}w3EWKXfnjc@xlv9)J&_UPRetdzQ=3>))G z-OnYA&;K^CKO+wgoGFpNXnanwrc&9*N-&b6_i@T5A!+fkcfP6&sfPK6O1h(gmQE92 zV0a~nH3Ib70qu~imZz8oMC$(G3WdR6pLQ{a+`hdVftYtro!bZ%<4H1=^MhpN_ClnW zMF1BQ{qy@je#-tuZ%$#W zFTSlbZz_LkM6k@_VJ2Vjtq?Y#RJ#s!%m>qKcpfBN)w!uTOm66C{X&oCt*U}H->hpT zcP(7jv5Mc22*FJrE^zmqSglT>G*j=l*vq{f$N~ z))ri7^XVBy?>$_)bm{A$C`idk4dJ~o(-NWJ zx~0{&?A%0?YhAh}TSm)yk6;NTwnxDdcH{Q#uY)PV3JUjPV+BxZzRn8+=8WcmL;1XC z{?FfUDWK$6Y`jiqCav#I)I{_uJ;}_ddUt6b%JR7S;rhECA>pCCf(I ziz!iIIWk61RlM6MBup;S(DH>>YbZv&mNlt&=bA*#Uw*Y*wv*KW!&6w1;`zPKJh}^; z(V)B%l;`t9!QN!}4q*B>c+lY#hTlFY$FP7a3L`E!7`iV>ik*_-ra5)?bO|7B!n#1<;oyUPFHZU9h=Tugmp zDRp+$c`MY0S5Q3*o^YfI;P6T+we*bJQr~3Swy7SKKdbn?|7-t}xhUVb{P_8{A+I$p zJe{_Uj@v*fyt{)Rp4oYGe`=kLzFXU+lf}Gf&fsSXSM-oZook4O_ds;>oRC7{R@shg zl3N*laj0?I%bZ4tyd=a7Ja!{8XkAZv&p9`rpE-l=q;z9K++{~XJOUX_CTM)-?Uee_^TWz+pt0geG$;f3T=f$$C%s2OLj@q(} zlg<1dcd;<7gyx0ed=|Zg+FK>|I=bfq+(1b|(36`OP_i zhgSGjq$8>S_B+iGV=8eOAo1u0bDKEhlur!S!t3Fv2%f`GYplYk zdNb7D3Wa=`{2!mD)9bg3Bx_1tjMJi) z3?3y|#{b>Gd*1vbTvvT4hR?59y+V08lh;Lq(qn0HB`npJgM4u&yc{>S4s1*7n7pOv zF4X59eB(-G`E>ySA$7|pI+f1Eh`&#CP*LxZ6+ZHUk+M%-YD&E|Mju&Kv4&ZQE#v~9 zqGD4Y@!gV_7nWhXnoXPr4d3IQ{h^^Hha4>?y8Sr%x4pi&k6ZFx>zB4@srUZ;m>Wuf;WZKmkyI3E3~1aiBTm) z>NcR_Klt(F9*^8?nkRM2uPdc?77AFp(9;~!I@KAX|L3FN&$$@DvLOM9$C-5ZP=_*| z;sDDg+K1UJejsjjF>A*G78VZG3k!QG^${frxuAgXn6VokdM#zCHh*u`^|KG%Kn zWDIG(oQS0?o>m_;{`ZF)E0NEj?RRj|1E~cza-~=gcb}RnwR^WMG&DR;+HnOHbtyUm zi|-?g{{L72hn(1{s5j5&L_W8!rc<#FT9Zl^D0#i}v?{pC<0PcHn6LAR0ms$R%W-L; zXJ=@r_M(q?gL0b$HE8)__oQqLY1 z;V%QW1xv5({h`Bc9)J(Nf4_FVLy0gqj>U0v;Z4HYgJ*D&fl$Jo@KKrj46jz|u0S)qx+7-4Wgl^DL zq>RMptP7R~*xMO#G#+jk)b~B8S5ZjW1a9ZezgP3Qcd6ll?o%#aqpwR#O%uWQlbPb+ z5?vL}1F~=gE)MFChIAGP|B=2Igsi>cf$Tw-sEK!Mnp+*(-z8T9UiUTP*giM<`D8IU zw}F>BH*&$wXA0>C+)#9dTX9MPM4&a~V9-FomrD1UZgrC9diZj1F`vuFO`)H|MYqnaql|l9 z$$sFuG3zv*T|sjKUg4p4U1KFWB*R6i7LBLSh;EQzrS6%yNg3Ym95l1~S&Z&sUrToA zx6ZS90gAjnHJS^i;GUBRr_RN+7{ZEv`D2F6FF^`R#xpOoy?&sAv_kO19w0V z9fF0q0ItFkOhme|&UuLA&|5jJk(hjqjMf77a%rv%U@Vp6h+w2oC3D?G`Div4Ay5I_UzT-;H-*ir!%p zK1lXpUiOo!erwEAu-DQ0RxZ=>G5GwbAe054JFNfEAQCGd)9gRD{#<&tuFx~Dl(1KK zlth&#*GtFUmcFC>IPUU9uUKh^CLLdHn$N2+A#xar9lgyZaDNTg7T@%L3bX&w#%=Y# z^E&AWwPp$b2HA9jmp0<1l&bvCnJDY68yiPgQ0^B(v*#7L&kqYwMK#`g)jaN5)|vhQ z@oWZW6VW=cKfeJ|HpisxaI^#9zuPV=&+-FRF~xkEMqFSxaFd=GS+~Cn#EA4XSTPH7 z9Y2GkY#y6}r~&&5n86u8IUDJ<$g)75^v&?_z4rF@wIhEUW0TI35G>-cAJ%&Rt&t{= zT6W9a7W5vxkbd%>^YkJM%{H@*0pf{5qSru{<7Cs|`P%+SV0E{zisgj^o5386$@gOC z-ykQh(Ydevs@V4gD#;BTmQ?tgmhC#w`8O2{oIYlFNC7|)4XWMRU4p|(GV;4b&<@*1fJ3N=v4D&iffoRFq+6- zKHlDHyi!}W-A;DHx3TBsq*?suq>;bKqUZNVz~PyYRn+98ZKpb(eN6RfHq8gKbfzcw zbOn|*(>}2LGIg@Js3KgAJ;d+x+xx*STSf1Nw?;KO4$PTv8SD)6@Je25mlJ|k?jB0< zf?V!ad~b7il=~K<%O-e|@Y#g3%W}ZYV@PI5Y9cc74BR_Xr&n0!qn^ zMsu+bdB*t?72)D>wI-zT0<(9OXf`}^)sJGPZm<=34%9s7``J_TBA#VsMZiP;%a?cd zK|>BfspafjDGJZv0rY9m4wzJooH0o8`O1sGigc;BY`PwWKl>Uom@gMrIolwa|0M5P z{~gFuU}tBayNiS^yi8L^Bo%xZx6IRA=o{iK{Z^rPtH17Jz|%l8wVOK<(=66f&a5~P z#iNa$+snFfJ%7flm9fAUE>{UQto`(}%dcn;afTiA&pJ$gm}k<BmQj(JclZ#TyWso9C_-*9O$aY6M5ve^OJ32BPAZMgPVf*N( zU8bi`vjU`wzjI0*%I?}pXeWlTv!{Y|gJEqC;!Sk4Y5+#T?X8h7>F@7ipj&DDywwr5 zqO^woCM7#7D`Om5`kq4}DfjH8mE9%uv_i8jN6{spu6a7}M1c244U|AoS?w^kgUo~iXeoth!FBZo1&=rNL(iPSF| zgw(Pj1L1q@)h))DRD_-5$e}}@&h-5`J-YA&E1+1SZ#<|Auy+ei)LwZP0pwCP9W$1{ zpP4BO>dMmAc0eAf$>X-&|A8%>-xV77)ai92ym^Q<+T5IX=20QU1&}kzA+Cef$;|Av zK|@_#9WaB{=`ZIz^s4MCN6sK&%?w9bv1gue?G~UOpnIJaUI9SCKJYo^`_?~?c$*3y zaqB&0XQ{W=`P%@t??DxmKJG=SnwM{rD=%QV+m^@lPf#|gk@9XdzF6!NaCn+$1L~#1 zt7(r{P#%XC)}~Txo`q29U&78kY*wj#HAqLP3nuUmH3mFxp*OtcCARtCm{R%r@3PKE z59o~CF6?T*6>{JGBzGk+4_PGURw~VGLTTVtI|K*NNU-;;FUX-ZpmNBEIQ!0OFFuHn zh{zRa9iQvb)gb%~f)r)rhHR74k`lf@RFamq_HGZ48S%;}DeG0RdCv|m%!>hHZ+*Yo zz!ZpZQ$-e#aKc9eGB*cU*4foH1kIB}?Mc_MzF3N2NAB}e-F4ZnV)@vOF_U~5?Cx>{ z;oy)*Kn?vuUUV9A(_ID{OOa^h2Dv6R@lu-6m+Vb|ksy9p4mnj!N6qY1rFRABo-%Se z;yu4X9E>}_`NX6o+Q!;}P)(&6@bh3!S0gxfVm6LSt-a%c`?XqojFZ|^ z6cQwY9V3x%jd$UWH+SxNaUVSJt7+(;?H=WftD?i&#`+iMLvsIS{T=;_Ml|nfdhSK+r{q?I1ls=}Jg1pm9r?na#20)NFX&Hj&Z>cVdfql=CX2 zykSH2miwLsHilfb??E!nhInwu-x>kIYN`PLu9T8LFOMWxX~YzF-qO-&t5V}#kC|rX ztLa@Oze3LO4k-Y-xU=3<9}EEH%{mkl6)e#zq87M_peHgk8WY>=014x*qcji(C18r- zfwTEgBf0&0vp87K3Fm3f+;{`3Z(rP^2rW&;+d#*cgP|?R)qeQZib!ywfH-{oxSMJa z22hLuR1X5SN}~21Ng+0vJMjX6>pTX`e;=$edki~B+r=miXDIIDAp-+VH@D0>2hWPC zx_vWVr2q!FUJrX!7jwIJ$Co_!oUc)TlvrC4n~gmABu0Zi*$cT(-9xK zc8QQ`Vs%5!`wvXDUgmo7@aFm8V>fTTG0$A!>O1)Qm4F17%}oBF__L{9N~QA#W+#V~ z=aMIS;&isA&2N@A-_rKQdT>JJ?S&`L;{W;SYYCmN`YJnqIg>utZkw5M_XE~b0l~$y z*R)oRd5-Z6MIi}kcx0sX^!J()}coalA@@yy&ez9^Rde)>Ls;kx6rwV_gU90_A$_Vsn)yP^yT8l2If`t zK}D%tbNxB3qoGuQbz^^;zJw=flm4Th2@y?oFN2yKFsParMkCZ)kMNWuvm`iz2xyeb zNsEaWU37FEjj8?cT5)cXd3DwPEr6r=z!-2=y;|*)_%uQ&f%CXcgk&qVPI^#W;Yxtp zVfCvscZ}Ku$9|)J{?SX!xj784?i=2#XdUjc{#n6zOpDL%h#9k}?};WdUJp&9Y1i_9 zJ*;Z&B={!AC{JCu5PE|Pn%~`_mPKW&=Cy^N|BWzbp358h)sU_{jZ^9#9Ax(S&^3H| z-S36V%2@!s%+MFeU;&6fepO@k_S!K@z*uYhk&&Ob({092 z1b!1Pp6L=-B(r;2uST8i9W9SXJ?kgn}bN9J7jTCaD(iZ&TVx2RgZ4EynI58d8w5qQJ>mgtl;772)WCDc))wtCApv5kJvrvO?SOv zR=Jq(d|#DL2hG+^tIB94s6?^qD_wtX9}dBXSX*pYzp5Lxa!^SVNxG`%9z8?J_O%Tq z8)tagu40-`M}I|NNxxfrg6RzXgKFsta9w!i)gC{&R3(b_g3-{&hQn>o(bZ)2I>>YJ zJeFg*%~QYYhEc*-b`|ySlO6XPRw^x})ZW_~sQzVVSwm8QwNF14KPNyX-z3D^8-dK; z{S?QUKGiv9!NR>>>%gIflo(%o}zj3W=+@gyCKi_QOB3B zcK&*r=ZV6nquqmx9()sHzxwsuY^X_-%m?~f-d`@Hhxq-PV!*)@J(WO_h3#-}wh1g0m&@xVM+BkERs_tKGX=g1i7sPn>KL^;nDK^8s zkJ-%Vup1`iJ*p-L+&=BoyVo5G!U3n$wlb}Q+||j*xT-n3$ngS>;F@O{s5R{r-D_0Ki4iKWM{w;m6!IWz8*lKAzM&Op^`x_xe+ zcTlu!#Zc*nzdO2S$s4Q84T_WT8F7J(?xa#A=jgO2aFxb$KcCGd^#rcTZ3{~I3tV6C zG0EINrzQ!kHYDW|@7Pq)=m*>=_^*T_QJ5TN7D{!4}`XNw-P-M2fw z>DF{SYjf7UySof-${B?*A7Nrd75Fx{A@IOn_(ao!&I=gKKpJ`>A5nr8<)D?Hrd7mZ zFei{G5CVP#KFHMH5?%gBPa&aiNx!M*&Z8eG&9kBnMz$=Rzb+;-zs7hQk? zDkz|$ASErK(xrfcl!Bm?ba!`yMJNpd(t^?&b{M|d(T~C ztUdh4_TR9+^~Rjfd_tgZiXJD9z0T8(}Tt_NLLKqolyZgM$mF^n*v5?*{%hBVa{_U;L zLcC*&~l(I6!l}|#nB=Z=2_1H8lEGO%(!{BF4!5p~mb}c-;Pzj>EgV_XU zDj-)Zx_Lp_4K577^1TmUE-hIAn1bp)z{QvnanjQe~1{C0bLMDK-BErIIfj!#e z7!26xM%P0Po7&@GvS$Yf*OrOZpCc)3TpYTUYXOt6k%trS1M&kyiR7$YHU{FY;V+q! zer=n0o?*PT2eIViEU8saCWqL!3`#R$1wA&4znZ$pa~17~p=Uyi82o@=7C2GU+3bV| zgIPD#oRdwi44x5{{ozj)vKDgbxKHl8FRZU|V~3NfzWq)+1Ea!Ck0Yfjf_NDq4lZ?{ zcJ1Y4Xp6{Ap!t>Y8ZneQkDa?wKHQii-c1!#$H9^eHbC@ zmkgrn81PguSqnqW9S^5xfp;@3$G5JTPo^8syT$y^l0CcL+VT-3h-QV2XAB;6WTer;xII{wCwY66(x zXQ@3_vA~=a;u}9o_AZLUT>hSd0x<++2w$t-=L9w)JzyS^@g-o>gE;W0b%OAgm9VnE zm$@$qkOIGqMa757LZsv+c8b1rfmFseUZ^xg{nmvUPcn0cO9usV2(|i<5=V#zgo%F0 zj!)5~Cbr!@ZX`((=Ec%_;IE1f>EEl&|J?wc<1}BD&ftpIzjOIm?ES3#4eQ&~##BeV zlah|Y7|Y_1R3QOUPT=!mer-)A?Qxpn)ACG1^Dfu;8frx`g0o^KH2^IoaF_ZE-8ZZB)YUHmbAy(l;oxA(xq6QhN%~wsRU&=Q z!5gu}r=eY?qoGM=&F`F_f>F!vCmP083LCfBq;=SkEZq!6sXd&vW7r5 z)9f9zDp~*Cd7sNHvb@#~*n30nE8vu-)r9)q5s!6Q(2;%q{(AX*91@d+CnR{*m;J{S z+KT^ou)c!1wigE*=?iRNNK{(CMElc>Wt+n1QW#2f7jj8bR<)*s|->xun3nl_Y-Ht=-79;eOwkL?sLJ%s3=N=G}Wh+(#k8IAT_WN~Es2HeSi7alLBTx<*~Z`Kb3BVu~Yb!HbtK zv9^j`;Noq(P5>Y|a%%_J1WqZv!u~JczAdU@eY;M8G#fzs&&bZE1M(SyM>jW}z`+}_ zst{4{^5vU@MqKRdx!F4>$3WrIFz@gIe9`jsA;^5etO^@NBmvEp333wRT6|lK=s=bS z-4tT}dV1c31Mqw7#>%U~gZ=#&2sPxew-~LW%xGbDjQxG^z296F8U;I=fKAC54P7fk7XA5829}|q1+9V(1EyhTBb`0 z6z_u#y54$QZw+5x!0t=9Yf!6RbM5=7Ioa}2pXfsz0#=WGdX1e67oDqm(*X4PKUbvv z92hvG1I5t|kXfKZ4y?6-yExJvSp;6BUOXI>vL+@bC2euBvHbIIBfz?GgLt;Fp<%-` zcx-G;IB4;dxA&1%(k0)=(B1U!+f4ENljAKTomO!3wE-5b&O&sjL| zX_rwfACY>@ZCtU2Apt-X2wIBavqsE(41}WuKzC{1e&+&*X$L*TL%`)b$Lj=at*M!r z|BY15k#aHM^XJ<#GKZB7Ga!l$Y|ztP>eJ7!fT(l_m?cYkc-#P4&M*~RrLb5+BO~i! zfY8B{R#+GTx;Co98Q>2A2MH#6;~8z}Bh}A!kgue1q6&?`szg+KD);=v7p&i*|?kCx(|7Q(KZ-{qj{B^YG`}_Y`UH1`(B?>X{Dz(!O^7Q*sTO{3Lk97Z-Wb% zl$Vzp#zL8BhqSNbe$*cTB|U^XEdm6qFmmpjH1ALW8qPEfcBj$M zE6L;62{gw8BHilzg4Vx7y5YTfjU7J)V%i%R8Ib^j5BBY)fJu8)8LZ2PhYKV!s$9S2 zoACMOfUo=~q4>qBr}_2%Otg%(Q`}F*3@m6FByM1ym;d2?{FYqHlf|4<>%>1z$OSwQ zcnJtro7I?|@?UeY1m5h3%~5=};=`G>U85{!hkQm&X~lf+s3rd|n3{~1Er%Q|{n4JS z_hh+UM6DUklDsR5jo*(Yua8M+ORfjm&X$)@#&2kAje4z`!?OMVt>TMo0L|__7Z-jm zqwjOwn@+I)Vc5`siWzi?q9G3KfnTNiw{PFx1|1aS_f5iu$_Q{d_5K(h2({qAIbDOK z)KEmV6!mI-%S=y{fwUoD7Ps3j3ZpvJZT=n76C;rXLW5_FoF@%rWKIIoJPWlN{pHJ# zA!C!Gs1Y_dI;Z}OX5qi`;@k8D0G|AMgSV`~X81U;bwOn7ho*ucp$ypGc1ilq{^uLx zj06^PO)r(l>a9e#g)3;r3uERQBs>7}A4ngMiNG5C9?Zx5C`bA9aU+g5`btTi8X_zGX9@Xl^;rJ?)K~&VC&bv)>BpZ}x)svsTvv|M4;(0W$^T zfa_X?bt<`?L^`K1IBLKyzl-m#Sb+Op4alRV1dFb@KmS0mLF&9~P58S5OZ$&rR|6z)%32_|m}wfY#qP@tyPDbMtUN1l0`C4L9iQ zyd$i%{vKTd1-hV1l%)2o2j$w%$X1mkY)QnOh0)h(;7)T04J1R<6EQ|*&B^}h7oSO$ zg0nuGr2&BXXbem;VU1}Y0(C+Bt;p@{p-~*o=FY#Q5R?ONW9ZkxyDEaV3@cU2;Ovdy)l`T!i$O&nMxGU9|nBkVNg;;cWYfpd-OAljYK< zAd{*G>gwM>?k^)J*QyYg{pY%e*+98&uMZE9aX_cjHd474FZ($n~ zXk-0cK5xawyJBJ5O+|EE)L8$W%0gU&nhHjA7PQBk5*}*2m=mosKn}bSW2R#xkYMn! zZ1m|1D)*_)rx;LTpHq8?#lJtzm}Gb<3+921Ft~LEw4F@IDW`YlHKf?_#{J9)f!5F6 za-?=iwfCD*VS()=(eRUpe?Ff9hTKV=2$Y2hAge?1TRFm=_!E@{XIu#}y3*L}iU*@?Z(97YRzq5r zHu?a^QPac%@>k@!pL9It;pvmF7gir9yzRIb_bn-KO;Q_n4JTV%;O=d;GnU5>>zuLt zlAk=mPWrwM+;XtA2-(#DVi2@#K&bf6^a%GQ47;e;%OWEqg}Z-uCzYTR)c=b-=MwpQ zXvL}#jS|SfchH81OT28OM_pP@ZU*?IHy2`%a&E|J&{8vrkDD8!=oYfSJiTq!Lm#Vo z>lwM_xuv5gffl(=^zt!#C;EL~o=ge2-({Z0N2`DK3PUhG%awr*jdm3{GeytwLW>TOKVa@fhYugzj!?8Odfl+@ zv%Ixkm~;>b%7O^chlazb#un&P>zzr5k$CXk#^{4M`NWwsE1RJI1=1K+DkfuS9Xufn zk~2iM$uJF!JfM%v}#zg4EFEctVIW+_}4vvM)dy)jpyf%Cl3

    J3{b8`X))e!W z%*QLa?y$18+Wt|EY3q97_JlULR&V~$P(4>U-tBDK=t3$ZW{i2n2q@LeIflzZ_XhQt zVxj0>@Q)+#(Jou=I!_izn^laX6Zm8EDV*t?9!1=IL>3MhBC_bIR|5NWlNkKsUe|Y3 zWGr`2z9+vbsNp5f6gc-Vs94^)E-rN@lqr=EKWw8MYxQn|*U)+gQ~Z-ULtu_VVC$?P zAa8|q{@am?!+5rts4Hz`E0k?@6KpVKdro$wu#$hzg2`8Dc>}y<6am_p+ zTP6EjI#gdKk9XSV6Q7>D%?T{YH&@yKvF=dc40hra+QcRjIVAYY8jVTM`*6{RRD}j4 znp&^vm}#+mezXe0)gY#s>E4}n@-77_qR46xn_{;4NL|@_MaLZYFX~>y&^UFijaoyA zkosex>NG=HTqWhtXJFNdwMCdhTi4v{JzMPsw!7#>aL3CCZ?$OjVA&ZJDClNYR8$0i zgeJ19y=jyb;SdJQ<~di7C%2N^@{gXu53=Laxl_7O z$^CStNRbpHe<4(Kw5J;TsE>dj|4lAK;tL*{$n(o|{U)h(h75*X0G?`}=Z*TlEB29U z1dHvLSIy*mwOr^Y0o=k81vJc8HzroPK2GE61$K6J_!vYG9a9uS`0j5Z_O$l>Vkn@L zlb~@xZ!V#)p%H>^EbMurw*#F{|2%r~+g5GEgkLDK{CRw|~}DTEa_^{yKP*7aRL&1#fhIU-ba* zd!EvjL0(^mU~HO3t(mZUICmNj+oW+%t3MXd7P*($-3;e-e)X=dyg)>Adv7rSkx{9Nv8|Q>R-daAIUk<^cfrkAzy^r z)(gmaM{CqawJ@1Jaq{FuEgtpMKamV5J!4kEQILRwa$_3v5!c1~&Zz&K3&mBO?D3SU zPl2UV1ofPDfGoNNfM=3EGDKth@O4I^WEcWwkBUVo5 zI9@A!qV$Q137Ekpn;Ot#6#XWt`VCxz?uffxE^9xCEiz01fd=vXOGzr%XQ-@P%qu_b z0~7UFfEm|-rf83lR$GYw$S(IhgnEAsczP%uFt2QeJjs9*WXK>UQt}eS*0138YcPA) zh))-bOYSR$qiplieNePIqf5BgKlpAMjGRCmJU#w2@C!Nlk?@fl1FQSeHdR7WC=Vg8 z=!;Yr(cDm@BDLh&dYakreT9Df590lDZ~jgd&VAEvc1H;1Aj0hr2PjDh|X#2g@QER*C>Q&WTKq`0KJ zbsK zjP#@&FW+~XXl^S~OlC0cz@XYakh$Mf_}zeuIsK>;|E2u;^DjEUFL_=!PILM4o53|; z-hiOqO>xp2ICJ1&vD{O?VfkOBh0d=-OC`+3H?~>{>HXJ8d^UY+M}4O41Ox0#RZhQ@ zT4-i;Z&JPxiZ5zDUDM~4UkyL;;<$}%O#)F=hNKZ9jy~ZfcT5lZh6()LV~pcuNtJ8F>h_QltHNJ*e7+5($Xm&^xgH$W+&?4vzNMOLoxFfZ{XK3 z>y)CzAD(;6cyIL~&$Y_mBuF4~>sHgq#N1;%DzNNNSqzIE*kVr;7svgOylIBnrz5Ep zyzef04wDe{N-Lr1!h$&qKF0u-|J`|Q9A$NrlbGOGv4d6~qR8plabtc{yWkw$Ne_5 zqgZJPF-MJW){eM}{I)RiGtooYTbDF!`!UD5m)B&j{(JJojuQS&-FM_L$%S+FFadg` z@oo^ytU8c_&SDF?ofZ;FXAAx77hu0k+`iys$r z*Stt&cI|oNFKmq2{=}Z1uPrW0vQalZqCfx|i6!Ww#{3*yf7qvr7E8 zWL(gaF_um|DXN+q8N6H9~@jlfesu8(P)X_KnFX5 znUys)GqXA8+AVPdQ4lTt9FVytSX-{1t7fr${{8--8GNW~A63drPFb8>I4Ta(4Oqs_ zx#<1~eHIBzEDR+vStWV&4YyBw)vb15H*qr_*=ziH5voocZ-2yvC1pP9*ExP&AZR*V?8$v056I&(Q8wo2e>VJm{@vVm(7m@q4Ac z{v$Om4Y%pN{HCa#bP~h1cf}?b?j`=5|DV4#%yifIk9oMSXsE4TPOcm{@6 zl={DIx^P3%?4K7t9PAZuc|RXWs5XrQDS}wr{(Sk-_e-gbaq$KwnIRYPM2%6q?*E13 z=g|@+_^`YK9~O?Dzk-~!!rt-{b4$X&ja?1hc36z~DrXZmPv^JI%C;w*$2?;&aC@ue zsY8OveT8@PK^xoj^SxEB_>Z5k{blbhZnzkKH^E>p;5yUA{`+kR?t$7r|9W^DHj(oB zyRuvLv$PApFsqk1TBhj5UWRcW#|*0Us)*wz77vwRm;;5o|I$Kmo@TdKhDY4wA6c}& z(@2le;n3((igx!Dwl+1lWQ-ET=slEhO*5Lq$58Mbr^+;ricJ~DL_Uhx{W#$ypR(7O z_9Y7Ye&c`oFf7>kS|m4j4KNP|x5oddm8vG@mgt9c<3Wf~m!Q&}OH zRciNO050H#i(5^)B_nrL{mItsuQM+i=UUefi1?gXHdmxeh%|<XoZ~g5gC*>fZrSWL z!#>^ps`C*$6>kcQ@qK!T+IVvBFqB`4nuzZP*62;;-d@_lVRdF-#^7c9paGq&AlViM zSE}a!a*coSz^~C;3aeKq`>>C;=JFWNIFcQw-4_0C}=y0t>4{(CArv4|))_kx_~tW&N3re|rq z9Kp-o17FVcx?65dUe{@?me_z7Bn?`i8Y(HP?n@1{+V=bueLtNZaxD%2CXe_We&zZD zDOt+9>gsWsuHw6OqodT>#l!&joyoXzjh1-MW`~%VawS3_p_T)qs+R4^nZ$RjBno?s zI$^mWR#`;kD?0~$IZMVB0Z|W`v?jAXnLBG(;em338pk6c10vDWmzgt*5zRbK}lCde*2tU>1hlybd`zA(TOHz3N+ z2OVzrMFslZIbSw9Zc@xqaqXbb`TlXO=_~YC>rx#T_s>c#XC!Cp*&J4=X_m&(Cx4HX ziq#$+Z6%-%BOJV3Rry1||L+AWE)F#Ci95Gy-%zaHHIAI5F)SBR#_1taDR4ezT66hG zArMgjTSL#0lS+p%1SqPUXmCw}!`HVcKQ13qBEjX0BUj;Vr&SY4$BPD^VE=p2HOe+$ zo;Yze`ejrUDfp6Mz}$^fAPfp*BX%AJOxNC>h`CgOgU=Hf{H2VI_Q1qx2Y!EN<;PeG z&2%@_${Co61)Vw`-Q>R%68mivNB$E3laF3q(iGEGx@?K$}P;|J%g!t^o_?G5b5J+(p*ML4HHj;#=N^?|)&O&#Kgo4|(F) zx1?`TUHSL}>L|-4P;wKP(tWu9cuVJ5c4Xr&`DfaX3&8|lP!*o`C)USZDOmtjyjr$C|a9l`?&5g$+M9>elwqBC>~>JD{<7=9QEpLG?5eeCwbG5zT9$a z(F_8#VCVVSg>>pnv}LNUWON@ChVyVX7~4yDbo)#j^Jiw~(sTAWw`eEo zG}gAPM&z?|bsrbOQ?Mj@1tSt0(H=xN-BDAOWWdyNWWtJ~x$cj98$bQ|ZdUlMULV7* z^H@4();&7a?tO4ytiq2qHOpuqrJ7z7sCf4&$6qy-((fD1<)R~2o#PC_k3EUn)utXh z{40EsESDrd`(ztqVV=+C=eEa3(8jvll5C&FbV(RM#pc3HNG5jsn-Tf15;#c>h|J6_ zjRupBsJTw((>B;x6LyL+AHOweQe-$r5Zs7Q;ApM6I9FrSXDcwkK|y&j*op1%%`w#{ zCOl7U)pEw3qvN738nO3hbNOgb zI2ZlUP+#tJy?HtL-8szNx3h6QpJ`J}X(DZ6Gp`E!v+vV~w2iZ$f9_h3Jssr|j`MU^ z^BQBz!N{El#vE7E&(^)np801#_hl8t_G^NYpA9nHBgPgIj3kM#6?A*dAJW*qD7)nw z&=V8z;{%y_{{{FL^F>)7Xw4GKV;%}^J;BmGmT)Y6KV~hRUFU;$O~5IPrKKe}x1Obl zmX`m~?u|8RS2ky2T{qJ6EIakJPpbrWpxo{FmLFY#m6^{reN3LDlDJi}D4UBBUd}U$ zzqNILFBMeI3Xh<9vpi@RAx~N`fNV9>?J;~;6O%eGZ5mbo*<@XXXzlQxhfUC zwlS36{Bax!?wNIs#Sf{Ce&_kkHgxY(FbkwVtp-L_q=hbOe0E4rjqBb+{Fg?$BHd0$~9P zEP$}}yjg-e9bi{s42(W`3kZUw4*oY#T0CG5w!OFaP+7SrcP6)FAV_}K#m2g7uSv`v7@49PbTA8Cnb5>Q>xq?%#c1I>M1o1^* zwr~ZRf}Ak&5eX*a%jk4i?7v4%o0jWS1hQWwO$KYv6K#%V8v7sv2TkNKUUPjXnk48a z+{#gqRBFDg7tsmMRaA<~A4BNL=WQNIU*dCFPNw`G-q`Xaga$+f?&^2*$wkG#1M~LI zxAhBQ^DOCoQZ=sKtoOdfP8ICJU9Vg|xy|(G>3i|CA2avf7FCfS6|-Q!*Dr`}AJVuL z=gnOkc0%Go+}5af5?FCx z@`;TlA8}h`M+z$-RD9v-)u@{c5ov`7Rtq6srSoZV7^I)I6|bC`F@gl}Hkhq{1)x+0 zJjVEjY;Zuwr3+kC4C0icVHx`PGeD0^t*S}{+9V~l)LEL1MCKL!CZDz zQis3OMb=<*@#e@w7f+!i=dof3riMCmToddP;8OOvlZdtsBZJ=stm$ z@3n^|H2eK+UJ?)p7t-npbim4Zi3$dO?m+BCe9rhg=T=5?aC0uFIc$-J``oT3_|Szv zb@l|Egu>m63KDdCzl8OFf8>HM&`tx$+fR&1IT~F3S!g-(4wy2@^lu7EW)IhHyB~J9 zu`tv`SMrZm+KDb#uAex;zZRkhZpiUq2vz~^Pnv|Ph`tFP{PB)Gj}S{@2qv%^?mvq# z$ae=pS3=9BlNs>WK%flA4Wy{QfIw$VqRYeyG<5>oePn%rsHSD0s4AO|QvcN05-+fx zu`@9-f$?2>0~%>6e&~VCfACz&e{t- z(N892V}F{Bm7T?(L@b)k>a)tcqQR%Kjh}&i)L5sLxxzlqzU*62Q>s9f-A|r)!ZK+h zXJDn^za79?@w)i9E(p1MukE_g0;BJ@1J5#nvJ&sswE^|hmRte>E^6Qsfie5s1T?vA zz$9Pb3|rsmrP}@uy$#c5v$l6jWY2w2KtFVDHw(Wx3wziCvCI5Xm)9yy|y!SprDd?M)VZ}Y28FZ z$>P4=koxxXkFOHOzJol~A$*J(i-x7!ensda$FlcBJl-kyoWE(ZP47kcrnO z8`t8J^QH8A0>iB9$M)2lE1kWn&0zSbwvb)$v72bhVmhw;q@X4)`(fCzI}GEqv)=VX zH;W+S0mfed`Xf?1V(|gT;+zjsZ(q}H1$iczM}v-9%ll?+ZEYo$J@?w$8k_2SACT3C zzJA>d^h+3b2TPg(tPI|brfkQPJENx7%MLyd@$DUVBFMwd>G^savw$<8(arIlmId>7X5#6B$0Z+mDRx zZ|p4?cJcrG*y*;*fF9xX zb3Z1ubel=SmiEf(Cb94fdUrgQ59f01`LK&{-SbV^SzPInQ7=V8g6aWo{os=(C9TlA z^zw29Coc1bbO*^&pAijDb@-w2Um7!6-@U;nt8reNg-Pu{eqd_AA`tC*fusF(unL?7 zFqumr!R536S|LU%C46_G);|3mg|^}RWxb5_PQ%Nd`^`p8WXcl~<(Ebt{M`8~Z?$s} z>Zz`e>|u8(%@No571LY%U=3Hq+xv-S*fWWG5{sAh3y){A^EF`?g6Ul_f}nvAlC`*f zb8Dy$kvv9|Nl9T_>0SEu-8%~ISYhd!B zNCiW5@#kLmcd?Wq5j+r--M5*k(KB_hE}VVu3XhhTBS9|uIOuB~cg9qAG7IWGJ5`i? zjPvh)_GcT=JOsbe$O}KWOf3I)w8UhIxb@bz*Vos{L`FPk`{9uJ3`1Q{uZ?W&wY|}! zM6fgLoN|~rL99@4?$R>ft(SHpyaGWkGSZ2AZ6CnrClqf*{MFe@VLY#4V1HRc$ZyMA z*NGyG4g`JvJ9EOA;xvsr12ItAl8gSSWxzKQ_?@aBO%!_9z{YGHGzRP79?1nhiE;wd z=cqh?x9eLCQjm~*2L9qTGcz+phDHo2;Gyw?Z>e~%0HQFWVJzbQgAdpk{F=fb1`#s5 z2|8M&96en16G5YV;8>L>7OJuVH|wHbT`k<{lW$m2!6~K`nR*hVt`Q4M=MED#(YRU7 zw8O5)Vbw`9TkAoS0E+PIS0u&iz>P$Me7jkT(;G{p44}!&?5-S8?S7+4 zmHU@D2dwf=A60E38X6x!AuuCAD9F=Zx+5v+oEymSRNHk<6$z(U`c4|N-B`nrts=@! zG7DSWy@)~rK7fE;>~oQ!XcEt)aAB)YFlYbNU%dRt=#xxFU1L3KR2-$TXaT6FA|oj_ z%HWxCc^~fU2SbT9ESv;kJ|GDmv7OxmSJE%QU8tk#MjNvf-ob8GwzeFwZiS_#M+Qkz zcmZxTjM`H)H*`c5C)zJHS6<=lIVhCz8BeaN@&yyFB;&c4@AFj%U#=}@=@uQHpzmij z&0}6&xRE%a9eu`!u48>gunYHHc>4n>^M0+6-oKPUk3ggRwG1ZFjRyJL!e;!17zvdCS@2?Jp3-**gKeuX3S(ivL) zw?gicLefH1cr?~i8&H|X#Y^p?3JR=XLQx9Q(c#L`UjZ(GO}C*R81fBc7kh>p$=OoZ?3hJ%gWIvh9i@L zFJW8&``jRtUT)-5&n>Z#66_8@1X%R_Ng~ES}DLo=y>l$+)dmAhQC}G`$t_-sGXQ2~nns(4r#TCDwOJFbO z_jLPO5|)m2&qlo7%j*JRzg6IZ>_?Pt10vHrAh2}rHH29_@MScocZlj#)7E|PWF(WV zm5I^>yoo{Z+FiyLmMM>o#g0=gkozVt)`T1*_2tW^i>LZ8{=O3&KcDLJ{Pl)_$#dVm z1Iq(Kz9CT!4GN_7fIOi~K|w)Ajl|bp%HDhT!~{C)lp%JbCZxte7ITizV(0IL^Dff^ z)EmaF;I-`olW0s|+4y;&GMYLZ=hCf(zy0Tgqb}?{hxLObQb)~K`H0y$%D1-Nr&}IX zHatCx_Qw%2G@>=LQMQ{sAy0+r7I!gJU*G<{hM^Z^g_d^R#q+;&QtO^&jiAdags}^t zs~d$80eQA+Z+PVwoZ-QrZx4I&o_lqyJUTF6Xd9F#Z>#^OF1JoaM;`x9k0M6K*&8AK ze2YxgcseQ_4O%-4f5sRD781xPua5WgM*_;n%SmE@Yo{5`1r_Hj6Pn|%dUdL~=rLjn zg6;C#y0teN_AnX0@2|-m080>thM={5cf7ok)9=3t5p|l?E&S`QzYKtu{2gq+?nq0Y zKw=!Q?;V2Rsz6Gis8d%(CG5la(!DK@lZXL&-^Ef|9mkw}q`XUuD;y>;^6k{)5WzKKwSD}0bQW4 zHd2{`2Vd+cl8c!`eiuBfa_rV40iZxs%B_(7`3bu?WGUZpc z_QBUBmkF#}nVlGa)9+Ap|5kbMO$+l`vXxt)d38oA=9sAb##LzjMO${8Fnz?r(e)qO zXM6#3F@^3Kc^W}*Vrmnx*-XsLIE9M+{XN87+^=A66_BMFUcWu8zOz%L6c_b|FDGaj zmrXLpS=ntj?Y+MVIsWnFPut18vx{fUbKT7wTm6CGqd*;wE2`d4mEVG{9Q3MtI?t*@ zc^6{U(S?TIKs1HMvyd(Tk3J~wIQ1^6yd>Xtlg(JH27$@Dd^V#1tsz8 zAKStbKWnTc{^`QQ9$VLN>v+NeUvYG}2Mn_@2f^~-OTNfW>Yj#1e87DDLx4(CqOPX| zN^Jfd`8t*tj$dx`Tf(uQCw-rGtrd=Ghf1AyR5BEAWQ+xW>&%0Ek$A<~ZnMhl>kfDMXgx5pe8hQ$Je_hIl| zpT4x5mYp(m9|$~kO5lIc&yZg#lDI|(BTq|T-S4EP}6 z;kO)aVes#N`Q7aC^G!2`fAIx;810X| zd?X?6Jp0ca;BY6}RI*pGXwv;(R#TmiD%K)$-G*qE8z4916?(BP`tbKL=3(D#2S3=z zAx~JGv44<>G*8ik0#4AESk{o6df+4*vRoGv8uf^ZFiokK()rqd1SQ-2bLb>fQifQ` zNY9-^O%Xf|5dCIJF64v%5ONax^hq$JYyH{d80o`Y@Cj_1_4V^}=YaF;_Z_jCccQVrEEB7Een@$3c)PIV(tU`tO!8%V&XbEav7e3T^8aDw94_v#cgkD6lu7O<4Th z^|YLkg#PLnZ%8!y1*Pi9(!~k7HT@x3q4~|HP$k1Us#H>cBt!cO^Hz?(VG72Z@xp{Y zrTOHO;vVzg&Kybm7KTD?-9LNOx5SS#0LEitc6OX{>4k%9NTUNjZ#n;ntw6E^urR@ol^owSyIa2b7dFaR_J_Q+7hl*_3jfFbAkf4~!7>LkGSnw4 zq)HS3&;XtEgw>h*tXHqjAniJQ-pddt1-$Y#AT+spPzihjw{q~hB{t~0GLUYGj~7>0 z7Ka5o;}ao)U^;<$Yf!%OL)P(JXNRJ-9XXj5MO@M`9pj;`0RI;}*ZjX7r)-(I0Z|5b zP?SMNUfv84tXBk;A3m&uP1pb_OAVj~E1QWmF9pmCna@Ghj{~-zQy{|^G5ZHk-iOGw zB(L2oe=Mf}aV+Oiy$Q%9GO(FJDQaM~h=Qh|^H1#=1kEr8d4<7L0>u`LAp>kMAKah6 z@4X<{W>r!Mx!`$e1^TbSYa2CQVCoLu^#D741q-QiGh}v%9F0I?BQGy+)0LaCQn4=Q z1@u|u8412gh((KB%b*6Ch6Ds%umSaeFKf6Fg$Y2+!a8_lfvK3bO}}CEpTtf`<(@PO zf2<2CM9mP023P|RC={InTKx;?jsA?x=h4AknEJy1i^4H(N+)lk{_3>X?C;b|my)8_ z2HU&`XUR8w-G|>c#)f+tt`!$A+{Tb&Pr`WBAiR7{xaU!jy-yyqY1a(S54aFE%E)hb zVwvRk&2E(aJ9-S}$cgq!|ETKVJD3Ga0$N7Kw5Gw}-*>06KldWPuMIR>T{mU1;bT?qYaBn=lYhqq86p|9;i{>@ z$cu*09>fs_G0X$i5zXvLK3L7`)*O6+|BtLruqFeobqH#L{@~To+Fq~0NU>FLk*!r= zmSP#6I1&qDB!VfLq5p(jn4#KhUTZJu7AgU51&LXKSvTyu;dK#cauD=|sC7Ux^#VUD zJ1_{d|HgiFxc*vTeeS6G(uG+q$II|h2Ya5O%te$9A+p!shS>%hq%^3?;fL?oR*yhf zB^+_r2`2q>PgnO>@Bo&L+HYik2q8SYak-0SAnuNaJil@bH!trm@F8(1_hMDfp%K^_ z^^?%@~*yviMwb08dRxZw#63{3i-ft z^*u8q9am`>Q`>l!YTDio%bLX}(gQeqnrW?KY0Nd2_w6s) zhFhrtmV1%APt|V$>4A>n$SqK@t|53V;x#A4y4vDCM^ZHe-~wMh9LSjnn|r0A6##r? zi1`FvZsy<%6{rsZvj%(@AA&=bSpjMSCr%{NMlO&LEdrjX;PDH{fCCTfMmH#*%HU+) z1{XPj>BxtwWp)hkO}Uo1x|;(siqI!ep31AM4;HcO11E8^DP%>^8a&f9si|+c5W(;P zym^Nl*=T8>fR%@nXBEt!z`z#F^XGZB-Q9&aIMj-4--D2U8WA`7s&`~dCc%@8A~Vwr z2QgwN1cwI?o-+k6*#}up4`!I`ICpk^db+sV<hHBkbS$BbWGE2_WeGjX5e zYZU;_1ZRt0y}OsS&2&*mU|Q0s3G0YxOGeSCWmpWwW=-1_SPcuJlmIwvU4OSrVnIiM zTqGrjy#ye)qPGC z0dPMZgi1Z|k>lKS_}#1HaA6wsux&Y&gC0vWbHQV_n&#X@3i-eXx`W3rp*{X2}A}tl*ACmZ2I-(kG#l5pHrO5C^pB%jZUsn7#JtvG0 zWD5L=`~xs6zs+%V?2jH)B7~|1L2_QdQ>oV?lJ=iL#?W|-{=nd%sfo$lX6Ru6<?d9Qm(yM4c-r92l*_l zXNbQVayl#vP*2xvbMC0eo{8yg$5m8CxF1c%2e5V~I(C%XE=Ep9ttn!Zsw zQ?mFIQd$-k%+OtB4{m};{>Q>1SHal;W7xH=tywsJz`R)-$sXOyg_FQm0Cpr)HgtL8 zz3Qi_*ukR;;cI|CPChwxH90NK7uq>Ao`S!R!0DD?AZ?94P#CMK&3YkaF|Od57oq+$ z&%Ta+%c-zIwxO$}ck5Fy9Wyy5wd_ONBah1|lShTlqvHzQk8ql*o!#74UdfB$&HK}2 z_)mNuP`-n8{u|5Ya`_YHo}%28zFOa9md!lolNrAmpApf7jx62_&)hoD{~{`dO?EE^ zGrNA{@zjX6z{Bu+u#hLcD5fsVdtyg*PEYk#XkYno&h=)m-V3Z6<*>z#px1_#ve5=Vq9J<^s27mfdTPo5B3N(VSN|+>v>yT6u%xtg zsLUSavZ3P}%A6sGPFcj*uCFiEmUo9KITGmy1P2>|FC;h(eSo{t>eGCh(ISAjlb{F& zU*NmouFDt^5E@E^VU&vpr{?P*2ATz>fZ4hs?B@mx-a@dT!6mrpQ(Y|rAjL%jTqL2+ zt3Gr)++V*><+VLdmvB*Zvf|Cs6Pf%9_L_ zBo_yZZ?M%)^*%a`hXgkEMh6pj$#z$u=kc0;yYh@EWj*Wamt)C_Nj2I#=C;~F<+Klv zz8u!$)j!m^qGLQQmp@39g{6Qoxx{jKo15~kW0}9htH;=v3p6VdkJ?*9VyfMQn{PFH ztZiNU!EEWRVRgnIhf6+UWuuBRmzFPrK3V?4{a*dm5(!ax=6BDC?=Ud9mz*VWQuAAZ zpZ#w|oV}m!(%=Bx6$C8(8R3G{)VF8KA zOUGBTUMaNdlFE0nKiyfROtr%PC$YrK*3T8rl$ZvrN)L(venkzLYi3F!1TUTrCB%79 z2J_b*?96u_)7MR640~*>HNI#QECe?g(~TSPU~i2)u-n$aCG!_7xnEGNaXHM%qrnsu zOLt{tWL_=;4`Ll+#$g6s`{RvR8Qkh<3J+)fY9Lw|=psY970=z@y0E6;m?6FWSy z+(vrA66m^-0|azgu^zAs=QNfW$}!jR=&3iz9XADK7KhJghd+&&CmzA^Nq8l6hA;Qd zCsAkenA!o?v+vDV?yfx?Vvk9ksJvgZ%d*Fcu`{#pQ?KkTZ@#?z^#Sh7kO3EJ3D1JP zHM643$!u*NmTsoft)V0-=KsE6{PA2lg+J+iO&0lJoE!1F|95jF*vuF2PB8kko79^` znsNTj<)o+l>a6!|5Th}_Xd`~<;$2=Gosi{~NvZlb+-mG)jaI*lE#Gm> zNmJ`y($XDF=-Z8?0|ZLrE#lV>n-11R|i*>y{zC zpw|}OMW&Si*>He=1!>a^B%nj}OLXCabKk+~A~3^1_7qcnU={rp-UDWA&}x{IUMkJj zfgy=|Vm>?RDe%CWgm!s@qH}QrWuLz9zN`L1+Cdmj1r68fS0DuCV^54$4!@1xUN)EY z0n5fWjdFuLs5}32pzgDaVslgj3DafY`ZbFN7mI$^wqv%1vVsK@gO!y-W%1>uuj?K@ z)@o5wdPR92PwmIiqeCWBEsZT-{H=8zEW!q@pYCkT=iM>yaZ3(0G~K!I=*7B|62)($ z!}ZSzi*N1t;-qR*hh@odBls}aLOjveJk4^DUYtOJDu|9v%@-5ess9w=g3VIA!%x(% z%t5*pQI3@<27AUtTGm7m)B2=EI9NRX3#V|ryJXZ)3hwL7N@E0hms1!n)8EW_S z7C-Bo!m~ke-hWAD(D(Z|<;SoH`XR6q{?Gi4|+IE>&sZ=*GTe+oY$~%{bhvc1)b82>L< zACHCm*CT9Y7={`e8d_2%!DO$>b3|m^DdUZp-!G_HSE2LmEV0&xGgddzeOaLGl*>fl ziABM4KJ~tAiqYSi+WqM=^OzZKIaYJ=mbKwiOVX*O1W{u|ZIpaN=!luJo>aajVA-d} z@T4D}%FTOtuHzh~1>`FuY6{xkDBw-DRW_D80IVfQMbM1$bigbSfb?p7uuzyclpcS5 zvkd%}7(5n%7BunNI8paY=w%ab@&^wdl&nXA3y2)FfcoWI2Z+GVL_(<~m`i(A%9@$>l6{NQfWYeyy z=(b0W${?9zPds(zjP;f(+-LP*RyXLW*)H&ijWi{7_-87#e$4Fb?<7O0elPZhfLGl% zzaad+c-fgOOcc&34=ticBr99roKOuqitdV*H_orqUKyP!x=jlt6_uPWb+ffo_<{?i zf-edOhNA`+W)DXD1bCLk-_Upx6>X}0$ofzbOHFk?M7CR3o&qVVg^SXAIUJ7p4NC-O zUp(i3@7LAWD`QcC>M|uZ5?{$I6EB62RqZQmMyWqP^*`1gMZo>LD&X5(7d?22nrr8H zXs&G9OY>{b$+8)+vLm>R^Kp`ylbP0pgYSG~%WV2r+3b4?Nl7hEE{4{hFgS?L=X|Tn z&Z{IjcDyasMDEko#+2hgWv@DYE4~H}d}$znLPtq(@w$(Smg{q1%^(mTx`w|i<>@&C zOZtn<41pPA?^CsAe;msp(#Ic9vtc3szqon}sHmd8Z*=G`K|oRz0YSP;Km79#yqaS1JkfDjAOeA5z*&@3?d05#DX+vaW-=~haKxHJg(59x%KZIF%WM_*P=PKcg zd{h6TEbp8z*+KtnL9}JPr)V!&=F^$^VW)Bj8+}VLCV6T!wlKAFf(1R=J;s&6e=kc) zis$7XKvPd|Uo#Fh(`tX*Rwdl@<~Hy;6sMGU74cE03JGGN1O-1=2fO^Qu|}N&x?#24Z^bzDFoJyTZHHsOUz$JQu*TnrVc?CJ!8*TGdQ%Ek+hNXr6P@=yv*Y`3Kc4@;?*H&issq+@UGIxW}Wcd}BFdl5#Qj zHB61|8?!TXO=}eDTe(ag&((8R&&ye7bU-v0*#L2YkFU2vEj~Z|9OIO`tW{55D8P;H z^UA7ZMmZHnxkerU@?HxCZ=2zFKA58#JIm`q;TXBL2-)d-tsxI<{_6glUS(q zexx#yzbK{uAg=!)F{Zl^K`NTqQBW3l<{0VNUN{}!Yd%Hb(KP$`#<5qIqt>E?Q+Z2m zr8Nw3Z(#Jwc);jv-pPx~-*gBZcMfmvL1H;LP+TwBxYzggx&h`aGy(~`Afu!Q5Im>e<#W=K_;IN{%z!`zRQ1aCRE9e zXYUCYw+IIO8=6wvu*Jy4rImSui<;rZ6e!)ERk14?+=*_*U&q^=IniYyO+C*wytiR$ z4Slco(y0{35uWR4#-#}TCdo7ee!Q|D^JT$4Y7@2qRt$7izE?w0S>`b`M$+Y9ZVK)z zVGEK~Tdp0j z_v_yq98cW1MdSzOaPc06^Lf$nbgC$huisp;EuT^Aq^7!aImf3O@eaBgUc3&ICX*_7 zJGn2ops)CgCQa+>73K)h8GHy9znID| z4^gq>5t;{=H$6oDyWpoLQ|qFoe?Al>o8d;U{QLq$YWqvjUh`3peOt7Gj-t>}hcpbR z=>)yTeog(4V8F*8`6$hmh}>qsJpISs_yG<&O-)7+oghGyB;G zka=eIYtkj3O&_&6mC&VtLI%!YjL4)K*j(n860RI*YFwhk96l48^9PIZ9&MW^oRJ8& zT2K24f~H(dQ@u#(Ivr(2TK7Ni@V8xrR`vxWdk(7{`cL`k3YqmB8Ys6lIQ;wF<1K$` zB!?t2%v^$-Ro>ECkD{T*JMC0cb)B^Xuf;vL67}`RudjtBW878cs&}s4 zYWr=JbZg5G|9*U3v(`!=j21uozI;%)+#L}@{^e8J=wD7UDyT!P&mw;UAzz4L3rVeb?=CiZJpe2Hjv;l~J0e~G818LD8yN#k;)43-Qc zE9gYR(3wfF26J2=~-J#F9S$VsWi+OTj!I#aHVJTBZcj$uo`#uQHI8q`t;%Xh_ww zxlCz79>>lo7kQ4wAsiur4oxZDXQb)d&8;g=pWvsfyawqCT~s&i>CsniQCJxT=8HK= z7FeCpcE4rOfwc#@WB7M!K~YE+ot1h&K_a4XRBgi)D|Wo!Lj20`NTU$K@$_ZA>-nSv zFZVyqa((OK(LhhgeO9v@Cv)|9s?QWd3(@Y{uIKN3OU8x0DU#cQvM2=KxRmY)he9TA zhU@TBBaIitoKZhcUboI~e_~@`pOdSC^Qo_IA9|hte!Oh|zh{Fig8_yYUE81GJ))H~ zeB6$Zd8D6J@V(YLA%s}UKX`#5_SsVh?xh+2C%dg5>6Pl>H+`MbnGFZx+)N2#IWxCM zpPFVQPcTfcya>Vr2WF{X8N}%RA?Qf`sa#=0i=+YVYdmt%r{|8|`%NXu__DAFQq&eW zgfh(n_ahBS&uery=ZlB0b*1D#igF&lkgQ{H6lQVSo0Mrx!~JIl>uLswF9^y_^M1I+ z!yP?0*#^SHgX{sYylrmU@~WjZr+|r(_sw5|z9uyBwD=<;8pBx zC))L*zs0baVovhz4HOSqI6qe0FGX6{UOZ0|MfwYG{KP?;JlHqeQ@O}}&_;tMWs;lL z3*JZ*r#15;lA`%qtjr-ZgSEc_5aQX9mwE=j#3^ncr~>=2-^{Nx z_f)=?*J9F75z7#ERbU3kUX_kLylKBq*2B17(opVoTi#K#`O9+?+Yhp8I6vy{Rr=LZ zRjluBxKuXFkIC+~eW3Q;9i%NGSGH~QXR+I7=?>m~e{1wcN#?D<#`>S_-VyUCZEY9U zIl2YX`SRM@mS-|iDJ#S-5IW@cmiX~|EAb76Ass?S6=06Ak|$ZUmX&L_$p&A1C57gK zyLXh1zW6n>?#|GW-k#59@iZL?)`^xo>!!_<;kC3)44(0>!WMqByrOWEwXVT|UI~=shPSWCQV>5K!L|nnef5fnW6^Xq7rZNdhbF1Epis z@873IMMcq2f;ln*D}HZ%Ur>krqPlRg?w*U#T6>`6$mFD}j|ft*pu^h8vr}H1yP(*L zlJWI4N;^AWwSoVIiN+0A`Sc`W6MhAziVNs4G24hsx5>=P{C23fI66TNi%5U}siv=nmyv zI-dkNCFqGQPKeyxD2e2~%MSJ=&FL~`QdZC5(sjb+E33z#1fowjBq8xfmPe>mc&wPjP_(f2 z9)~~H)e0tsZ&>JlQm0}|HuAZFB+pwue`Andjx0Lia?PJALm(!yv2`^%HjJOz4GN4r z$-5-8OWML>Zy3ht)g4Jvx1p)x68gHY%rec|u;o$L5Wsh>cqsdBw!sG+%OI$nfov@1 zF9*-!&i3L|cfsYX7?*}LtjqH5wI0Yc=a*_N=UQSc{H|jy9L(V=FUE0J zH9f6Xg=2Y&yg4YC6)9l-iL^n4YiQc2Kl8l-&rrpT-W$A@mFDRe%8#+js6u;OAW|=IwW=P1*Zg1fL2kvo|?5&>(im-LiNo;?Ibgpi*BkDVG5h^tS zd+(j|Xzs`{&9=_MEy;=@)K6xtQnw3UyeE9MbA`gtY+6Bk_8Q(s+P!#)wf=9vmym*4 zDfPTiQnkYH`cjz7jr~Y`m@LK73q=5QnJqJ6dc%FBbrQ<6ImP?${kG57TPzQQ9YGH( zOfV50{S0Q@aKAbn0=+8uP{hjv=~bt%D_u_XBpE;~^O% zgnN5P^gfG`-;3Ng&S^Rz?Kmus|-=2_i{D=Pa$+ z{sM9;M>hREakw}bP(k;0-F8YAohJb3Adb81Wf?4{qb~`>^cEZJ?t!p-=fWLuB}pZ2 z`=#}4Kpn!RbqMN4!Ow{A@9%+8dmY5m_UTu;4(I3Poq`m3c7TEcTCEWX=)VHD3eXtA zWCG`hOQhLjAOZdS6q4wB{~DwlRPrwgH6SfM8cAUMqD7p_pRzG4{&gs@%n)pV`HBaHQULqlz@~ zbdDeo%ARUvw5*(p_kpZkN!iHg@iWuIo`Utmjf%7KzgM3qdk%c7Z!W*txaoCad^r*% z_vxPzkon-(tZ(lcnGNk8UQTM|Q9|*(71l>cqWyjqY^&-ruU)xR>?BPk4?*N9{@Ud5 zHvQlhF+6K+Op)@tqs_=k=h$J$R56BX zc9D7Vv;qgo=h{QVg1xNPv<(1tu$WAdLGp5CH$s+GU5CTLuoCtDd(~~#Yn6ptt~(7H zC|hE)cWWr^%==$fgEj_TLHG&BYlvmnx9DXLkLttM$C$FG%Gpqfn+-?a1;-ZFz)eP-<2>b5PZg-xJ@E9z! z(bnpsLh)#G9NqMcE8aSNrxDtV7>19bq#eANz zK)W5)V)(A9AAjy_6f*tZ1+7@fGei(t*5{VcPRYjrkR32M?omM*{tF)V$H<(0E(SUVb9Mr) z112o88DP{%Fc0U@G;lD0a*iJ$V!z7ypE@8j5mG21p%)L2Fz>-)EWJths>>Ku*Kub z8rI+mb2h?MmwHHc&df@XkScL9E6u0jvN>+Z2O zPP6|*1yzC~zD)0~{kl>rk0v%*5km9CFqr);-^~pe>FD$swK8qwiEyu#UtKv3d?4c{ zb0#Hpz`}|%C;2m_wr^fJHM3g4y-`r!Ij1XLnx0vnIia=s06@l4L znr`JGW&faz2G4NPKP?Lt2|=2RoaK)S`enCg_GUdD+Gu_EZYI)A)D~Gn7<*glE;!>3 zHA6(5T%YYR|8shKh22afCO@hX!c)H7b+)Dl77t--X(q`|i88Td<-~yQt(TL;pEZS3 zwy#HLGj}-nPKRzbC;vu0OR?{%g%n|pjYdgn%>ma=ob^@{Wmz`ZL<_Fv7dbb}Xf`g? z1vjGmPI}Xruk}`NFe6?pt~WvB9)1Zj9Cqe5?NCgo{>&ga{o`h+VyK{?`ax1F*u>IP zSil9RnREds{kYSB{hxw9X$y-g)+S;aH4_CJ4 z_c58qv~|%4l8*omcUbv-2WiOJexo_L@oJSQ58R z5FMXzCKN}1&pY3J#61eJL`F>Yz?;@gR7nWntMl|6Y;mt%1?PsfgmIoz%v}BSyO!3Yv@8*3w$-noaZF5KG{Ek6Ir>;r*7b-{x{sK4+5F76Ltm6Ic&TD`h z!qm#V`z6&di)kWj_rnK8b#)S;+hhS6KbKH6HDGfF+p;gLC)Wq!vhV{`SKET@WS}XN z#l^?(294c~pxpXa_5L z&~zB$gwcJF7C_B-f;`}so4?7hDw3hTCm?cLJE$JH^h}2pi-Qjwm|hMjsT!9yENlRP zQ*|5`z?jBRM{xG%*5sP+&SH7UH6EO7uR%mCewvo=n+=Ju+B=r{;;{l5jv|AnCm8}I z0wv+z)X!^=>hd`6y+?U#cN@&L5T|^#?8Gm-geoa3mr(GZ$HRwwu+w7w8vFIQ35%KZ_5S_I#LZg%mBSNsAV_B7HoX&AbZ(o}N%qVur>FEw*$s-zd$nyk z&1zR`G~~V*#H`h9UyoNd+R$yDSx3i@6Wh(bsdan;*(G2!%x{azhoVAH{WgXMkr6z)y@#d|0G z@frm&lbcwhm4ciJ#VLYs@81Q$6$+|n^eQzfW*H}W7t?3v_A7Yar8$J_aC>VX6-Z>8 zvY3ab;rLDaNSd53PKVbQwl8}n-@z`%o!cQo+Fh53!8wUnaqwsC=5RhKMyxoJy`ibu zJ@bmGDSexQUU?nA;?A%^bMe}*awWBN&KM*Tcbt8*zkJQL;T_UT2%Q} zI=A^!z21-9?@qn@*I?qYWN=Y!W;YMl96x(jw&(JEE$^>T%)`Ya=uG&ay>iQ^gM^Hm z?QGPccZe@BKD%C_p;k{gk{^(RmxGfvtt}-kCZ4SE8!4z?A!o{7=gUj3`0&bLgGRj$ zEQu7NEh4dow<%zHaaKOeTG4x?c%-=_O(}|5tL%P3$c<@ByLE5T)81gRBUtiQT{O2g z+E*Sy67%!^$x)79rCW zY*3?Q{0fqL{Y*Hr*v5P2GpIo0rDTZ=Lw-+6SM^4k73*9nE8Ko$myo*F)r!SaxRjHf z@$ba@yBes+bmc6gp|Y{OijH_}Z3x)pcJSv=TE$12_5v2yiZ(k7PzfzHJHU40h-0xF zeJU3o+kh?8@fk}pS3(WPS>Z_^8l5vk3DoeZCijOATKDMJvrrqOf^DRE zF6FE#t-mV8$g}#2)S7>*&REFc{o)N(xs?}|EiGr#KV$9r^Jh9oH%YKru@Ei4s@0P} zveXS+8#M8oX3Aupscm`{qO!k1Av%rAt2r{eva`A6cq_R?fX1{F;R2jq;Yxj6#yFOv z*{ldyy@mFX2bLg>NxCKF{T|gem$!$`@J+mxA}!oegGst5i<29N&)I9v~PQ~Ku3(>WtmK6!@k)X zY|;3kjw>Lm0xrS8V+|9v%WO2;oFii_L%!zliSzL3dHD2_x98JSh`rhM; z%i$}#Lvsy2u^@Sao{XI_KIM@h^ZK=#uXem8JpWWQov)6d@e_gOHun!UXZPhiC9750 zJXUlvq$H{vLFD0sfzw73`&HSBR;J1*So4r~-Y2tu(W8O+a!C)gziLUp%hR*2dwW`R ze^1vJwPDdCe*?FVs7yJAvga+K(b5Zm6VZ=}E|Ass_R>_I_XM|BFYC&}k`69jqN(*yrWdzm zq&p#SDNEfWMc(j{js1c(pTg?IfKdu9du#x9ScMe>i)ZTr4F@a_0)!U#urKdAj*pHC zgH!3_qjXFQ8yg!ji>?pt4Z806&KSrIU}I;OCkO!9__9?qV@beF3<|8;fkIY@m{lJU z){Y38IIOE|EMRJ5AhK}N6oz9uIU26rTj;B7dM`Q&ShxA!1c#iIbX+CRF_0x3jLwrYCV3r$9e=B2&7*`}!$@ zF(c3YEe7FzML&lKYhtRy=(ww4g7h=bXT@DZN;=2E>EIz zF$Ni}72XOgUo^<}DTW{g=!&xF<*{UyAAZ=8b2(L(5_&ysKmV!RDWd=ca8q2ruLosJ zhvB8PU~ql#d{yRLuTw`v6ytC)m7>p-72hqAvl4m0Rdx}E#e1ds>S@>d#MyjQc-VE_ zgk-rfZ7FZmcpo`DUHJT8eIv7lm*5H`-AL)&Kgest}r1oxhlCy|ubq%WUB z5__hV@G-!74yClbUb%xV0hcpS2;=g{F|@og*(QlPn}dz|O-#-4n+`3cgF~Fu^P-jC zhff^gcY%TC!{fX+YpMio=>15^x zpH%Mi+BXEWE0XMBCMh9!-A@O&#$Nl>f-Wdu%TqRFTzS7w=^1tBitTW^ACfyW8_5a; z-(=92h};PY*m+)4UGJimjF|l4!(xszGnE_KY;~vlET zo3oYS!i3La-p{*fVb}nR>#c8G!##NG5L7?`pt-- zL>M}=N~5Wq=4L}yFb-PIV?96XiUYH+fy^74N(Q*O00L+eB5Kwr@{lQYiPl=e=4v>8 z?Dy}nyuT>=c#b=qCQSVvLG_80FuQIHNXJ8AM<86yr>ba;jKEdJ)e1r2z0>&jxDt<^ zMDqj!nJN7oJ~4;ou{d6k+^^i(LG6DMhO2~%XN!%Q+Rm0tUP{mso{B{54X2De128%M%nG&r))on*Bf7@j=^GEr9+3_RK)zL^_KOV$+b+l%hQHvn% z%c!n>VS*A7PD>%hwN^RBHF*Xk_k^h~tkytD`AgC7?~z|j$x$L595UBU;=gG?;2;pm zk0MH8wz`y7eFa66W*nyP8M<{BLJ$IqnCSO|ND>vjj%~{Mu9%gJkyHevmqLhG@JFdd zq{`u9w1d!+Jwlc@hglQ}D!9oW)i$=_@Nnnwk!6Flw`&|{{&$!gLr#4K$H2<^1IYF4 z0j|ml0xe{b0{t$IR@$dRu-30lK9e9e;%YZ{gKf|c$Y~_)|N6nBwMyLbk*x&;et$1_ zl}ycf>*L&bhZG+!ulOQuexklJ<>S4hcS)ON?Z~BdG4TK30DTK6L?`BRqyvtFRRG;0 zby#w-+bjzV1F5s|83}`!+w*vxg$=%xogGuq3nf6vsQxjYN$VOwtst<(E%|TKka1b_ zAs?*m(|8*skqM^P|NOJH?c!MaGr~D-hpei)x-~5(A;EQ1L>q){ckeoaiiL?ySCBx) z?_6`QR$EX|(0d{#CRTcQ2AkV#mRs5>Z29G_R4kjF>)qdXa`}1`Pkhx%{#A|*?V?{~ z_MKNJzH8GVOTR)DhwCa%`BV7T%4uoj%bI5zg>M!eqPo)KQB14!umxQE17!qqfIHTX zQfwI)zobzTp^9TMw!;rY7x{A2f*CsM*jn#7j1SMb?siSTNH%5t_WiYdI;+*G{@?1x9ybuILSy(z+V!Ke>ct#6~2GVk!4YnaLk%+nC3T{oKsOxYA_5=I@IbARV@ zf@*1P=ie&@l+&cpR-wwldi=XV3A!N##KpSwQj9eha+ceS*>}9A{E&wgjW~sb&RQai*s=OVGt;|jWw?( zzuXSazVC=FpC_Mn{zpS*o9`a0w;?PSF^(W46!;N`rtrWdgN$_O$Tp%4MY&KxSr!vz z&wbwZX9IL(wwbH6W=f$Y9BUy29V3aX{&3Du9lGlL{#Z*fM3Ad}w`p#Uhe6{pk3F!_ z=8nBdX1(;384cW0DoeK))21Fb&f?02h;hpL*}LfX}wdMro=#LCpTwIO@ z22}FC4DrCWhSy)qBTVS8TCJ)A~k5bH;w5t!U1S$0NS_~%=8$<2}Vl}ltqwZh0N zK*6+Rt#>ceUdF$EHLmSbsx75twqZj=dKsN(S5Ss<1&Yh%{jo0o>r2p#(BVM z3K8UVkCmdwCSP#X;JsN)90>}1b-uG}bhhogeoB*#{fJgiQ|e39Z7x5Cul)Q^=+Ly_ z%QEpd<7+bb*p??I^Kb#I^e4_J=(-hlvz2Z?bX5rs)C1HxdgA!iiMQJFO@hpBbdG)7 zXZpzg+V#}wlAk?;7u0Fjc38Fh=vC6?9D}UxRsva##CoE+s^Ghdb+Hvuv%tV0+fAq? zp}*`Hwpoq7dV?nQpUEIXA^%f{dY$D9;2GmRNLXFf^#+Kx0l^QR>2-Ikpp}<%Km2Ml zv9osvN>e`e4-Tn`Hf1S%;2Eowlt_EYhov|!JPn{#C#& zJxc&R*a70%ncxp1A|d@qO8O0eXdVD_MK+{$u6k1~?OHy<_m_OFZa5#85|lgxx_oQJ zFh3L=W8mtsYWortla?0Iy{3DyHAUDAgo!PdAMq-kShK)uWI6nTRpP z*aS%VS-rv7&H6ostfPV*kwNAk>~`;Mckc^Z3n=oJeYA@E0aiJ=Z?{v!<3w`rhtR;! zi5?`=Sr|ZmwYjE{s;0#SMtYU}=gAWxLuTEU-{9okEoDf7f~~&1K*VXbqM3{*1%{-H z$ph$#?(s1vC#51 z1(tD51Rv%w-+7t)7bX`CexcM@@8?W^K0^q5{kI69mSvEGTS&^Sa7v(X35`&RI09Ep zu!llS#S4NG_ktFhNF&bJ1S{ir&KNRNyVm_VMGXYR1mqDS799ng(O!kIACX*Z^q9I`?$;Ej=hSpRnv^lIiD%BT=3(NnUPLSbFQ)=m-lX76?@jjoks-7uHyE@ z5iU@Cv&OPQ+ITrq$V%t`qI<{t_uHR*_3RnW?0mU5M`oh7c^}OIkMN5tUh7}s zij7GAQYXtZYdEw8c@f)1vf81@Ter-C!c;EOX5`$JxrlGtfY`*g< zX5Iu5GJjk_n>zOV_u#5MEoSLEwO?66E7ZJn0gbP>v#_ky z7^$%?9`3L&iR( zHYR;4s>s_PUAiGby3|k8ytC2dNsRO6-H2JdVzFBF-HfeZDAP6jK*ewhHTrP+LUVe* zie~@zO}>N7FJ8~KI|uE(s$>bG)(9E1n?gCS5AeB8x$jDKdTp}((DshnTJmYa*48PA zxEtHS;&I|hAz=0_@4eTJ^AWda!B(mKzjV5BI@%UxsSZQ+Nv;%p6#@w69H~QB7XGna(?WP#e zKcKPje==XYG68bl9He|Zr>8N2IWNRVcPLqGtXlq|Q%lmq>On!mIVH&|y-~VZNfTr2nwWz-4YJ5-x?y@~(aQ+TzAU|M+nQgUh>F5T&`> zS+`^`V#y5rDS0c~XG9RNwn0;cbhPk4PYMyuPA}_Tl@%Gl(TNe@x~Ht?V=3G1~C`>Ivw`l`-oTpcbYvKgVzXgXk(x16Gj zh={=W5Nc{_7Ng$;<|qZgM<|jU}-{e z^imje^;<+r`3O^H{af}v6TXAiV$CkR`IC>Bk8(1o9znxvHZf)TA>w`$TRA{pMsM+4 zW-54Mt0$Aswt=jmXiw$ECc7(gfgKzmir*k3GFBVTT{EKM8 zt*_l3M6NKdHD=oN#uHax0r~A4hpnK3faJ0Hp@tgqlsr^|CzcvGydC)0EXWe;l+Pq} z)i^{le|${1H)};RRpjS>*I#w8f>~8!$O2uxe}tbdN&UD!i4rXPPqO3tnsnbCV{@$a z+QmIBSCo1`*Wn^mbK_{m($a#120uAQ%Tj8Lh0Yz4nJr`GWNH49`vAeCvece-C2*Uy zb>!UG;D8Ar+}>e0F5akbSp=M^Rm)an?3F0?H@<0v7w2xUz7elWT*(s1Fniwaqt`8v z4!t`=fxV`2MMBU)P?ngv+=O|qhy9_$C>>5)`gW9vo^XhXI%N=FpX?7v`w!Uh-hqSN6K zc?C^TZEFj*Md;b(o@;!)S^LXi=Ogg;q|^YH3!46ycIukW7i&Is`0 z2on(omW8jR&qqZOwsWh8Ci<3^=K^6!gnLnmvXVye($hjwVdb=IMB+bVeFXj87t=A1 z@(&uVn5FWVfm}}q@-_2Zkw~it+E$eO2Lqz&r*{_h&tjiA-^?yDA}bd-yg*ghL!GQq za;SM-5H){0qW8bj)u0)G(SwLzBFnnJ&`(?(92Fodh4LeH1gBUw)y!;d)-WG0EOr-&>R=k1bN7cI zv>0RJ$bP<%oA#Js21rfVtb zjd8vVWfm7LQp##X-q?c7&^X0c*fr{t<~2Z4fVZ{M640{4qpp>I&EBTw0!o1XnDD--%F)cddAIr<18i4l|)_oY|o|`T?LMXukFG-2k6=CW#S!R)VTHS zF3lt7x(?=d5@BsC3h*?-oQiMD9B8pzaQ25=5svg{lTG~KfxQVasE*NyS@0FPPuMA@ zlJZ53kG9s1HHNqOdf`s36*NpGHXTX0kSSvHp+D~`Z8$Gl`aa?8wadLd%2VpSPS+O{ z1zG6OUF>O~J&@>NhMVzvaB;niyUE^mSU6p{24tzqW@(11D>HB$EY53&yc0|NsOuv# z=Et)=!g$}U(DRqc%ElsF*tyL8xlS15*L0mQz$x+T`7K#n(O{*PG5+Yg)p!mXkONj;1@SsPw+&wd9}LImh$WZhblTcy1D@O|KE4r z{#pgS6(kQg95%(_Ghl1k0HI1Ljpx??<+Bi^Ej8EARVK2VusQtwW8B}} z)#VCeg*3E^Yu!G$?t}lQ33yO3U$FV>bqAh+mOQ;mwFZ!E0+#^7J%Afh;BwXgvS>fZ z2ur7g6_5fQSUgB;@PQSP0?70BRKF(iEnP}#6Gg-5xP)J~42lcDIKl-yi zb+r`FKiqSwhZ8cE)@un6HenHCA+#CvHyO=BT@$>g!!enk2=+m$vBUuq;(6Mq1ACX& z;?yx{zJ%IyetPGMT1$%<#CP#~`j@iRf|8#hLREo-*!TAW|pij zJTVhAXYfH7{5Ap0$Yr!sYpKaky{ACeD$#m(Pt?7{k^mE2wSjD3sHg)KH++fOQh zFWHYTd9e6_;H8o5&7)wze?WKF!F)6|1QhI#@&rJ1e1H8{w&n)J_kx(I>z8b67)?FC za_1D8$_v1w3EBHIMa_FA?Avp`k?rnh`kRawa>|`WV0r9BM=JniqgUTX;3{z1e)o@| zjQc}n`NWx9- zK?FL?rw^l-8^9B>yWGkTOJD;*-xpJ2$Dixr^1FO$VXn5ZU*{xjaDiWR7i@I0Z`|Gk zm@AC#5fUN<(JiM5Zi^R^Y`0==z_0jRZ*TnDx9M&A;qA{AbnosQPP?V77kja(se`H4yEUZeR|HZ-iJSdJL`eZV+p_|pWJ zk~nh7$V95}PTI*Y3#Inv79vM~1+RVF!P+Q>TyS|!*o^7;I ze$}cW0XmajLFV`Cx1t6?r&BjNm9>@(z@bFOgc2+goP(H;Yi&L+H$oVVZY)QC>FV?X zm;_9u<_N*J{r5a)Vos?F&4(3jS=DVs{RzLdATJPd8`j#ff3v=6`%rerYQOmL& zFQoX3rm&zV*M!`!Qi)f00_g9MJS*=oAT%zii+>5tH)8r7wxjsnj33x7>6bQn-vd9& zNSH_7R}H1!mDDd8Rt4v`Rr!edK=;nh%gH-5Z1l64LHr8+XzQX$-GK^H){z%0mJej= z*{PI2Y=*ZRu}18kju9er-~YNr^!Z`;dSP;SILCpuZAswT7)(L#()-V|%&}PI(xpY+ z&Ia9hz&+fEUqR275XI)J7290kGKp`9nq^_CT0VWsz73xd{>j3*3`mdCNbU&gA3RBg zwjO(UDbq!PM;-#Z)q65}j2+a$iVBV{wmpVIR)(qrD9~z`8Hx5!F6%4lMo^f%2zyE- z42mh)DXCqGAXj^$2ysS^)c>C8CZ#|%zg`wB*l3|YLOAkJ(cY@(tt{v(PQH}ocilfq zUFiMhKYKgWSC(B{bkXWzgx~Orf`Q;mhDGC?KN6+@O zkK}qKJ1Nn(5xy%gdlUT{^P)ReS%3n)OM$xup<_6~;f0>Sr6l|Z$DFul(j=|G^DsFx zQ}4FMiW0CQK5j7i*d2Zr zKzWKgBHb;!tS|K>m5IkM6(1Zg$pur(E)e^g?M^^kJbJ-qr0+0)tv^E4(sE-2$$H2V zG?+IB)H7xT#UB@scG2Q7HYPJNgly!xgq~ciFvJeiv-f}~9Zj88)U{rI?+$#ikn#l_ z_=LTsU!qM>*EIbPj@|++>u_aHC+^EDC-1#p-Lm8^5CB8rwduA5M02wH&TyssjSigJ zgFz;Rrm~xM=>lU7Da4~_DK-ncO@<>RZ_14kt-5J}?Y6%zrNK#k-K@p2PipaGkep!V zIReXDr)M)*rj1jVI(Wo02wbB6j4Q=%V9rOVsJ5p~mf}W0X%lM6Y|^AAWJVC4@Ti(O z3os3RtvvGVKh~W!!Spw}UVzvD>RGf_ZD@}(7xZpnB|=`QE53%0oHwxSyvin@!=jX0 z_a>ok;K5MO%dq`*7(uGCp(lFpN8Ie6)kh;MyX<>p;Enr0&pe!6e&Ztd()eHsj9A|d z=&7hWXQ;m8&jQ)4&;LU_z|1s2r^*Z)jX-c55Z3BGs70R$e}|&lTDQc;M=>oN<^VlN}NdV1YOaJnY+u-y_uXTU5hYS zh7E5~>+)-=fd@6(kwp$xNo8d=`o-rJBr(=4c!ms4{e;Uc_7gk)W1163B-+3bh4c9M z68LS?9iV-d+!MeMXb{uq-n#Om;TwJ?nIj{061fb(6(PXViP3-`*`ZbWn-r*3iB(zY za1$rp#VXhAx^Mp8+o&lv1Oh?#?ZJ^9%OUur87u5N$+r4eA8nL8MF<(JR=_5eL6!QU80$fQvslx_D z3CD$dQQC5K#hElX$jA@6u0@y10Hb=Vx49Z_F%oaOaBxh2la|vo>^IKW;f071oUgy%FKM zo*@EOW=@{xJ}F6LK<@G9_ZNtJVEy8031=?STo1jBWl>zgHB%5dsUfQVhtFqs${r!# zrB9VinFoGR7v8OD5OR&vk+=t3>5KkCc2+$?j$nc-ww<`5MraOe-Nh%^yYT#96yd|Q z_??i&ggEHj0(ydx?NYB#r&GVg@P%-FI*Kq?knN+3>nEcR{=mI_@8utvjRy^2G{%Jl zzLGRQpu?Lxbm3BUZXfOcflAdAyalY3TUCQhuc@efK?L6k@YC9ZV5}+-v-nv`%Ikkp zar`*y))wR|yA>byCjAxBSOc%w-a+8I78&b4Op<^gpW?<~kwbLlfVdASWe6j(oGPB5 zF+YDS7xV<{4CkZv9D>t2nWuiXY2k%FNg(4i(BV^3(+I_ z;CfW5o~wbfT7BPYzO)oxDfAV06$g|EK+UK1)HIPTuY z*WS2-Z#be934B@px0s2j(D;h9-~)(iHvj)zm|{i4`b7||1zWy`BA9`g9wba%%%V_x z(lpMzomFC_QltBGawy3(=3R7Eg79*sJm~-M_1^JR|L_0!p_CCyNHS8$h*GwU$~t5_ z_EyNu&Wd&sa?G+-~Dazn_18-EMBL<#o<;JRaBMy6)Hg zy5Cvr8K=~D0~=Dg8r5ZW>m`g|J2$lILQOKL1is_wbw~a?#Exb=z~lS?qKwSm%LE|o z_Kse_9~tRFX5K+I?H{$Oi`ADr3Gyne1Ux2h0h#8VBK_20!sglB3RC!2*HT^eWWMIStjyfjJwq+ASaJt&;9IYM;pD__}FrKkk}`tJ~kQ*veZRSu&13=0_hf z3o?>PfzzaZ8NHQ4H&S0Rq#wBQ_sO)zOCHM`?78r~YvTV6EXqI?;JSA03Tui7$u=+r zz>?VebjWh5e?lDUr<2gGFg8?M+U^9Zc>)13ie6()wkqxCwiMLOz1lhk?rBdk&Eq1N z#(CFVg~wPEIY^<_dYERY!tc7g0o{2cCqW6B z-?z5)Mg46%Tz6!>lJ?4ztd(M`Qf0hb4w?LAf&hskzB)KDD5ZSegF6!S{uxe3);IhlFEOo%nYtzS=g)5;x2y{L zuhWT6b+T6u2N~raw$E7=57c`5l(x{fgo5-*9Ec;w@sn7>bE%qR?21-NdonwBUGKiY zi>EXUav^@=fjsAZGdxMDmFs~7@aNFP6l)b8$n1y}S%P&!CN(>=(i! z)w{EqjV&!;_4<(^9{PmZhORWIc%RMlK$U5}eaP z9ha1p#BKwIoY|n3I++*g4$8~OxE4qlCUcMiYz4z|gztgN0|q2tVQ>~PPlJKk2k>hg z{&zrr(J~MwzaT1jZ7psv=z|b8Fp}y!JA=XQ0GN*!S83Z#%^&uZEx{z2f|L{r07%4@ zQmGk`Ja7%$85}*3g?}AX^`|pTBaYf2Gw8Y+YOc=L#Z&b zPC`m*1{!gQlp><5UOM6#&?&L^)p?i)r0|*qkUq>S@(YvYK0sR|4OJ0^~%;`V2;rZ!= zJ5>~WiZh$ZnX#G}PsOL&KmKkYvaiPyG+g2$0_`vb*N*w!xU)ieYQ@@KuG^}Z`r&Y? zn#Z>w^Ma`wN$o^6P5(ESZV1jq&Hqoxb@Ru=0`7yIPG4+fq#W3W2?z)vmIvTUyC-_} z_c4Ooi4zZpRYqv;%NKmf|3qz1SVuLovb0Fu@=7bsJUD)jXnu8}c3b%4*}L@)OULqt zeK}Zu$7Z^|nXclkn7-83-o67$s^TqNTwL3L1tW(x5LgidLIm@*9j%E)wC|b%&UsP! zQGnY=l(6F^m`_AJ3J})_XwT=PpW)%vl&>@cL1w@P!RO+A4@8D5iVea|I_TXA7lS1a zC=pgwlu zlnE$e-U4p{xf;T!!~B27K0!XVUd2+JK4*U`|D@t`f{gW z`+_6MBN(M|0u2M?JH2u$;W~@Uni1PD(5mgP^0-NMj&}k!xCxL1l$sGgNiZwQ199;< z?^QID=X9b)WO*SxMYXNR&h4Vo zZvc;T7dzZ?zjk1Fv1Od-=}gQ0{}Yb7p5>_lZQ;X*52*E7d;qldnB`c#Q~48Mu4qTc zNe~4BkujkPj|2CH)Bba?r&W}hzOSaeTf-`FfPpzI@0!Z}gz7$OILHP*Qw|2~__&K) zu9SUbu@prycm>=jVagpmkEz%};kpi7KBe#9XN7)&C}PC`ujCqZ7Eu>r&K)sYMD`a5 zEDP#8v|`!#`T3XOv79}98ddjl9nlK)kpL^5mZ^ zzdndGYzE2UnVnr&8=~`eYmmAWn72^W>@A9ojSpXAf>bdXu!ju1u#xwQ%$+-TklEo| zJQQB*!r$FmIy)&d@t!{;o+EO`aOlJEDoRFe8lQO%ghpWTi$i1eWXFL*#Qxsa*3fHY z-WDDQoT9p+?L+5zKr^a#f58F4FX20PHy7GL%Ulf;UjO`$qd&x^k{`#*^oeG(!;L!0 zZ-Uo5aZ<0AqMNIr7j6sno)+t-ng2p`7;QojGJ^4+wIb+RJf5ZM^|sIX$|vRfX0wgS z1ARt|%2qe`Tx*VJLGvbkkFnTniLbv?r-}rn|24t9ApXA<)qr+dI%54(HjB%A6A&<7 z^g|i>xeTWVD4BfxC&l-!V;ZJJna{*a1Wins*`;6Z&p+q)Gw!nYg?CokiPg=7@6Gz( zdCKqI{2g0;-UjXX#}u=%PVWwx%^BY=SYPFn3$9fggGMn?i zm~a_3lVdAeBv4L%!ZxH7Uq21D+i}6jTpFmC(lS#%xPSk;NgYaMm8L8-0Jc4>eeh!d zBa~n0O;Np@mf!C83(7E%^No;E)0g)M}zq)j5XhC)#h1nPKQH{59Cu+R`Fe5zI-tOlNO}`=0GNK z`ojKuMn-W{I?x!8{u%(n+bNBE=d^>1kBpR|!Je&O3OKM1*z1&+mm{!W0B^;YzTcpd zAsjSKIQ({!J$j2o$3N*k(_)T%m|EQL3_n*GPKT-5>%}MhzE6J(_oHE&s<{5S(+! za5!8#XwiZ&_c$;I9;%G?p{_@FfVfRCJV6f$a9&W*($b3N5@T%Z?94SZ3knKC%(~6Hl4OA11QO7r z4Eg&e`V1fI@H*K5hjsE*4v*Y_*Ka#nF_&ZG#Ar8C^&u*|kM2Hsy@Uak%c@!B_bRgjS)aEcXa6Tjl-`@8<{^gpk2Z*ujb)DGw^|Ul z7yx_AAl-ra`oyJYXC*>TK@3uFJy-1$={P%+Auh0cW*9b@1X#P-ja%?;1>X~8C|>vVbsxom+vr^(33NXW>J z4PlZf1VPZK#9?$~axR@MFuaQ5KvZ0OKhHVHWiTZzEi^h>5l(;b?BQ8-P6t2aHQ;-g zmJaG?J;O)L@rsMbrYc4z;c#iBy&$DROiFr*FW(u17p4d6W8jn285Y|BR}QkylYRvS zH;i9_`NEj++0&EuGZ!XAD~@N?g!m9_!`K&!^#nWibkwg6Q9N6@^s#US;x4@fwWe-0 z0EyWYgdM}wb)%H-neDNaGAq9+K8>nPPqvx)8FJ@r#j(>1SLc_jNpJL>Jr#CZ*+sgg zSmxY+-)YMX^?6!XSJ%cyeqSdRQBgg;({U+xE}L^U>{H-D0|KCdi9}la6LkzDEiEB$ zf>aq7>@!j){sK%8WL#N#Ae*EoUu}KSXTAx*sG{f4dR-n^XZgwy+h+6QHJr0SzWL?@ zMGyZ~MTnc#MnOyeHvo1PBUK)V+XBQSiS1v<4mNUqiz|X!@0&qu|1TVHh_ubW)(UYg z7--*LJgUsVZVYCGZGYxH1=EnkrVViSTUlEhhe9s3tSoAF_SiL5Wl*>Q6adkmfwQlF zvi;-7kN*9(7X1Ye!otHDHysU2?S~P~sQQ!4tdNf*yBm)EiqhaK zFT&ImbDRGKVa*&=dxoCuEyVeowG^JYESm?S>vj8+?+`E#MwVY7#y@8+r(g<@)0B+V zT~d%#&Bn2qPvo!3<#D+r4Hu;v3Hk^pceYe(!zu4j-Eawdlw#`$oQ$(hXBJ$veMnVq z?H=C?q6!^4>t`~Xp2M;5y&AVw9v{rf&lue(^uPMBR(YlEE8;l-3|Ej;jWY*5ZX^hX zTn=7D^Em$HUU!dN%WX9RbV-@X6hBCCot1pkku~Y^@lA%4QVJV-J>v-*nwFZouPgUW zWWN&=KD*-s$EuL!X3+1at<}NkRhl{|!AU?_2+VKVc`LsdpAj7q!hV6zE|S0|fxsAoT7fy)e+glT z2@X`BH-U=UDe_+zhPa4Fc8K`Lk;%qNuYvrAHtGZv}Um9*+3=3D{8XMCN(Q!3d4iuY+n5bLfm?S|u*<64A-hW}Jq|Yw? zv@Z^!0z_&rFts~H_sc$@7{pUx;s)khVuO><)^wllKj-x1u6`B1FENICUXYt}(^mE3 zrxt)00ZH6qvFy&fr&6R|Kk}74PRhAj;={&@rhau8c^ zq(VGU0DFN13sN`7XX$EpQ0bXhMQ}U7Cb3xm;MlWpl7K(L3}ryj@@W-U%Fpr^MK?zZ zw^%GwNs#{CEB>^5R@DAkR9^VPOrE%AWWaGRLDcVu&qZyS{~M27vH-6l8?tjjKt|)& zETSQ0>%a3zu`we2J^I&oh#>Jet0&WIT|o$vN$XuM{zLb=2xhU$&$C>&r`pH{MsNmu z#;B5$@on$@E+Rl@J`xWQ{Ujj9cY@wq$Ey;0R~ zD`AoUW)l%fJ8v0tTS0*oPzN@s7%w6{S5qV#R@N&v< zymx07H`|`}jzJWzw!Ma;tt}}HmFQ)t=TtrRan^^iM9y)<-YnyDjx~B-BH{Dq|70Fp zz`LRsuz-=te56Y(dY!6ESEj{15o^*AM!$JKE4k%YJ|Y)4$@TNNlwFi&tXN1Bg~Yjn zxJ0>q3;NlwQGbv5Fm^lEo0fJJ{~Tt&H>ff|=^v`7$TRF2ug0C zP9=^MyGUpeCPT~8G|1eUkrOY1`uRLGsP&25-LoO29={yEE#!&&7xbPbn|OG3rW>u# zNBZwe9{b`Q;U@qp#DakuFsJsTKfnHsGP=v^%T2e-Un`!r4bLGwL`^Ha8_MOa`r?6f zM7Q&Gwijo!HS=5-w$?9jw@TaP+x@XTm4H=vHhoiTfReN;{U+w}>e^Z|Xi@@ys;Cew zc94Ps`GH|FlEL{o1Kd z_^E3zM(@WeH{iKY&yqzg3AL=GPm$v)8}94gc57L(tXTWRD8ssey4Z~I|M7eJ zy|_zwB|+Y6MfLK3>o5?#0t*!zdU|?q#%I&gr`{ez5oeAp!nto-t{c6gVXLEg_O0O_ zqPtRmZ~qhF_hN4mUbK^V((J0)Zf_3ZMeDE7a*`!xQDy=-4f5j~0DOY8$u?YmIjk*C z4vt^o-#7+gY62Afn4wU9pL>@ELdmV=V3gFL>hI8n%(j5<+>5of4as7bgb_(ys<^j= z3AjfNuNPA*45Y;Z2#6J@t1$PH$JFyPMA!X8v44jd3*_EEU`D;N0)v2mUqO&1Oxm~4 zxFCw5q3_>InV4Mk+AQNqQwRdXxyHzpr zYKn}K*)^U^hG>SAFUlFe{xS2w`|!kxrh0q3a}}G+f94)RLZ5Qx+_@HkK7+duB#;w( zxWW}Vv5%iT>D3$qjznNlyUQyNtG48MAeHy*kAhWvHn^Lpnhutco_Hjl)+d)s<<^o+0KNJ7o7I7Ak)%yWGEtAy%#v9V%zaV+XO zozna%w^Ej@k>&j05@E4-0=cZ;*LoiIWA?Q{>x zLsWS4W7MqwKrNw`s|@Gw9@OcQVgo!SN_ud6_30o8uemwlwE_==!r`~=j}!_P$@LN!9RX4+g*?S*=sDx zj^;_w+DPsc>Dv=!fKZ)b01j?Z_hR>mbdmQ!sqv<=*eIcJ;L4tmCM`~y?|d29M%$O}UA)xwLG$(2vAXcmk(Q8{s2GZqoPt}G!pUBzwjBA#bY^@8 zb~LG^`Dy;{WNOx12Nvu;K$SEphg|tAla}yri?Xwi$$Pn;JsgY7G=P}pVfV*{{8vJv zV>ggojF7Ow3`OjQ-@fl_sl7wi9`sr@r??`PXE4+YP`3S)(em+EJA zg71A3MSBAR9_LYEbX0>rcK^oVI}G};O)}k=M!;h=sec7r`QF@qeqsl?g=s9HEm_u? z!Iwq&{wxeUt2Iki7Qp`W@dHe(0uy9MflAoL`0ux*Yc7EB%!XCSHn zk?19Pusse99f(TqrSl_CJPTbB*erfKtjHM z|Nb(Rw2vk~Si1eJu>osksGAd^zF{nRy*)Rk@gw8X>E~l6qnpqHoO&_-Wt3RTRlWjf zPc3?p5}*5XmI7`&7EA^B?uo`Ivzc$WpR&>kxQjn6nQDIaX;bSsuyxpANGh@&Kd}v8 zjzF*|q^_m|{03|gi;DOsJEC8I{%z&j0odY=Cx0IUsPyK|n_tj|1206O^J}0u(w(Nl z46P18T43sM(0TC}?F++-veACY|6iHt%SMyX2s%qo-v$M~0zfS=(TE7(0+`ns)g0l4 zD9;*JxYXajL7{UN<@cW|rR zfEVePz>a7ggWjS z*g7W5241>(bL~xEUwxmP%~e`5FeSYL#^z;Z!iZ%fSjF~DbQ}ll3K5P(q^beY09WP# z!3AWHBjyXRiMZJ4{098ZH)Gl$y!2>3R{kNcBK{5PJ`p#~T(g@&y*9Af!bZcnSy2D}7!Mk-p`X7KLafunl| zmU1+!4iD%TBQD5LH%GuiS_Ks82mF<`PrtA^cH%FzKGY%HKw9zjVOp##h>xJi{|WJ`2O1MC7!W5wW{N1^oz+f0+^anthjzRLeA2W_g`lyqoKv5n`wAG8B1-Ek zU`<)*z2gLV>v!8BP(p6W9o|Mu(h@r+5Xx%a+P_XJsZY&+H(zj=fQHbYcQ?Nwjl~vQV@H?SODCm9MEPG{ z@L_BtX_|TT-nyNTD9I}j3de?%yTO%F^Wni=O~sLt2SSl&`j{m=5|hhfl>OJ-)Cw%g zHi!nh!WLM+RK0$@Cvhq7`_Ffo?^HKW#6IhuWAKdel(^0Edx5FFf^za^cX1@7_l`56 z3pF*84$kU)!C9H3C%}GD`vI5b76<{aw0o1Bz(*k%`JhYrf}0rFgqmzG|3)EY6d=d|0MSD~ z|3sPo1d`sw(P`xvw0;z@flatlB<~HhMnr~oXF55!3|iG5i{(>gkO7s$4?&cquLOiA z^Fl72Kx-QtfLjheL;LMkpCh!1L_lbp(rbs(B40-bv~Qs|gc#DIs^CMAIswUU;*B1&2Z;I$s@?ryYLxZ zmqe5HdOhd)QE#d-93c_mXEArOJAO`f)VFgOto^s{(R||ld~u09$@*X&_>f^Su@`2Nbn?^L zu@#g@%MQZkM~y?uC)Ka&UoyY1oQr35o$E8*!)Ql@R4xd8E%&{Hmv~oP{(^tv?A%pW z<^1k$uX;n=GorHu{HHTC&*)a3>gD}hGHEY(;*{LNA?5D7O1k9M!)q<2<{gx$`u8t! zychVz^h(Bc(LF7|EpOar`O(1)_Co-@3(nW)Kx7#Xc+h2r8tWE`Dk@sYq1jgO z?3puN_p^6*J>8Z@$jh!B0_-t5@fQHzXiYjX9a-5ETA3Ty44Hxd)@)yT6IlJ7d;o;P zQ-@}u)s4+xw0(|_i}7smhxN*p!_<8{!RRX=$S(r3IZoUQR?7V^?~_O5kX53lOP*+Q zOl~1xsm?mR^mIzkvC~xeTaFcl8GMaWcPYsKl*=)BQ@5?UQIUjkooS>GmJr$3!EGp_ z)_AiX^e>cHpf?3CJvCF}Us+h*%KEnoW%160iogd7Tum*lRXDW@V9z4hr{~6O695-w z^9AklN=kO6)lSaN2)P0|*#-=r{z8B-=shgZK3_I6i|@)K#Kw9cmV~DwN3&Lh^@PB*hFY?c?~BuBUS}ePB460=ldMvvjHoMa_F^<04xTk8#mgu8fqiH_ zbFJE1%f79@@bd(g$ZngTx>iMcx#k_i#o=FaEfck4vMA|0zjF#5{As@ybj(Y;EHqa$ zZSSy}Ta2Gz4se*e7);IXEH^^n2UPMgJO~1J*JQ|99ATV5DB7JL6AEe6fm0Q#tE&r% zUWhRWuVKY9bR_eg9Ig#q*P?`OZ_a}kW2fnx4Zu%IcE;&j&YPuiZ;Dxp~64ekAPAf1@;6R&# ztGf>=sW3y3+n^=z384Xg{qgcss#)cCnxu=C`;L@5K8sJ$RY9NrnkHkODd*@PAB#+^cGBx zPtm#kUXY9H@%IrER4rRIG$X6If)7_*XPF`kqx0XdFeO)zB~fXj4wuz2qa0KJffk@c z+dVL>^}Fa9EPO#WhFofMvzR*jadgg0V=5)0&+U@Wmn4$cE3doB#ok`#JlE~BJTpz+ ze7U*GW=-Ll#0ONzIQJLl29csDaN-j1OguwXRQs5Q%wveBra}bHUx@8h0{w7U_gGKUS=+x!Z!QB59Oh)F%x1_MbU&=#*pRn7*=Qk zW2YN((D0a;`M!f-u|?r*qw0#T5@=H0gBAJ%)?khHN;qr(f?NN>-r+F`J#Bkw-&9Q+ zoKyRqw}e+~-*B(-%viP4mB&X+PgiU(etP*qL%?F~2YuNt-vS-K(eN%~$>FiB>s3bC zAGh-FJb9wGZ)k(J>vRh??WWcL9f2enj=Rlu>legOjC)6Wle{P5rq~1OSnXb!y|(t8~i-&Rx>01<>p- zRTlX}4HT8>80T*fbs`>tD~Ko9-AB()fgDU1$SEg54xtTLWCbKXE8WphE zv^hCB(O2RgCvkCe3qbZ{2oBs{8|zF9tpcZk~dc}Xs;nJ z{|2hAw1$Q|*@l%`8lUdngfD$}{7&)i)?u#R-ZleymT_wL)-~1s;x+2fyd@%*DyCqq zgRN12gTGm?JWJ%U2CrmnKFhWZAKrVw=|8q)W{W4pkiw1Ig{!M3BrXAVb_arC>^Z{nEmd7sOHk6CN~p*_;*So7{CL_ zyK`M&G0wpFk%p;hBIHyq>s@j})RFtpH0}Y_Z+44nf>0w{wIyD3zyLfD-*5Dp8Geg>DJxnnE9_B^k_~!M(ogzGApS-5}QBi8Q%>G!M$xgpi`ekN~+Ly&tg`98d z=Pvu^xnqN3mNye=tAi^=_*^`*jN~N^f-5Bi?FxsJ#e3WGKF5)Ne6mxZG<aWe4xtj&FnNVg*|1gOx4m-Ncv)pM!WJo2mU{VZVn{163IkV*?CE19cQ7%0P9buFU^@7=nEF@^c zs>}g6fY9mSlZBAf-VeLwGpkQ*)crG5Wjw^f-($~A%iqqnUAu%`mEEH<-qBKdV(+0;I##;XQnR&_Z3vuT3xBPf;NS6-jI*2ZBU-k^2 z;Cz2i-9Yct=&qez$>~bBXsR&W9hwK0j7|hvPrlKnelWlZWhq$PBSlu9)a&oOq=O(k1Z#(x>Cb;)Ro&_Kg{do9~iHP<3>eP zW@K}yv`4wKYqYV{`;~4F{J-z6uL=D6D#l+D9(jH}a=J`fCOD3Inodd;@uMjQikKlB zNFRkA&60hP6X^*Y8|=Y*?ZyX5MMXs=Z|F2nP%xx3in;NZF9G0(2VeU^;WH>ytekXA zE{eOEV{7n+)5!+CxxHn7&Py3e-`vw1E}Ls6K9b4MV=Ev0tLKL?c%OVcRFUa(N+YlM z-(ClO4idD6wND~$wUoihxJj&+OG!P44Ktj*FxFRiwEKRY=4+5s<$QAW5J^^D7g!<6MhNB8xeN!9OVf>|5g<#6we zs4-(gMz(ZJ7!CJuq2dkn%=2a`DLOik?l;D?fmB}*zY@=2PdhOSNh zPZml=N42XotrfMFZ_!J{McJ!=xXN>r3#kyV)oD>q^G+ zW^iKbbc?}Jgc7up z9SBgO1zd_ntQjR&bCteLIabn`YszDj&OT3@{&Hca-8!Rf!=`p}H5SXNeP6qFbCC9u zx+fYtHb=S7_tt%v>GhkUC;$6qooAs0&g5`{HnAc=X(;%EYnvaD0b_gs>ETXmuh$F{=2;XK7yXz>yA4 zc+<#KQeVp$qR!CKU#1p%-E0XDaE=UKSdnvS?qTC1tQ?+3woe(&dE8$oG;eRRr&?0j zsYzCrI;aYTCR%?^+zxY*Ognz``kvk)pnax%uQoZQLnYIz!}`2Y?!CW`%Lx1Acy`**WgcxtY1 z9ZqC8ITx7?PP{uf6FU~2$Tc!v`=J5u8O=2MRfR7@d>^6---nL2(v;bMM~Ar|#dE@|$7AE3w`43TMw=;x59B`#hpK}X4iPr@ja#lEMFJ_o zyDwjzL@qC?^**-4BDBMT%!L~6?07)laWpnHr%Xv%TYHkb4p-7#+`99ZjV1dvD`$gd zrhkE%Oj9GXQ~Vz`B7Z&+HuPIVFJ>p-r>c|Fm+L$6}7&pI^y?00k`T%idBYf(SK34z!a9 z)xd=Jfu^l;7%OJNZcEV@vs2TMY-Uqnyi4{*XEY1L5-z4cBqNP?Lt_Ove=xs2`X(u{ z+prGQrEAAo(dYjtK6qSBpnUcgSDQb+V|*{nqWSyEQ}UzyUFw3f^q#+egZLjiCkaKR z5Y|>=${NBfh00u=>>Sp?Yx^Pr-nGH$q)KawzE6M2&$6NYa|ZEa5>#`}tY|gEy}kc) zYi$gUF|*{ESWH$7Pv$YkD^~M5A}SW4i3}S4RO;Qw7*8S>=O;+R6nzQpFF5cC)xLN& zf>rm@bBErviabp;HtlMQBxA&mMIbJCdMy5c@S1U5xpBb!TsjBXJ}ow=*wo5TmhnQ^5qvRJW2=&naT73}uOgNscbf?i!b%8q;T3 z7S~!GHr8Y++F8+weDy-dA_P8VvT_y)c3#_;5%Jj`$wyA@|GPqF)R_irFJr7iDQEYYc>591Gn{hDp`Ian>wR6C2S*lrjr)$(vl@Y!M6EX@ypI&G5BwvsT7D_%P2N$;v6nmyPMf(;VwusCj(-9fVK96-51eq(cYIz-zpVXx zrS9QCEpEe^4K0>L5!w2+R06rk1ZP~yHfdhWADL{=xPk`5nzi#3FJH-(%$Dojz4OuG z6YhGb2F)L~*FD;5-z*>txJ1Kr-Z{OCu#NE#_r05uc9PTP$<}W2SO!j?{qz64xuRp5 zrWe!ku3J2J>B4Uc)u9J!r~kghvO1JrKH8-T`&^uyU66l4XDu}9~_H2EJ zUHdYC#6n6=j)8g{VeBGBk*PJRu0EaYErbH@{lX$6XPiIW!~-vjAyUD_-yvKYFIY2J zw|+$q?p6EW8nsnxib%QpjmBznn+cneHyiU@^cy6uvuzQqO%|uty?Bpa&C$Y7PYo7P z#P+n5YyD~3AyEGD1h1uy)80RUR*(GMa#9#l6RAA}F+pGh&_+T)`3-0%O}BC9+Lrj( z+vh;Rw=of_VvQgsPz?fY_bS{>D!Iln6veCdMee#)t#hTb9RJ+n1aiA(~r3OAdz?tW4}kFd1ksjf@R)536X3*EaLbI6tKk24>B2Lh}s z(1d28W!eV?N!rlRr^7Fz&|3F_^jH*HNdO66WAvKOhxx$Q>mZlew%}H}B91~a5Ia~^ zv9=ogs8BrJ8@VUJp;c+woNc0c9(xsy;}$IZsX=mDySlmxSapw8G~OCx zU=RcUNRb|#lypfPxMX_mX zwO9FS2(QX5Jf*oLbftblOoA(QipA2JQlX(j5o_(-$GFTF;U70WydOMBRTlnzTt-%Q7C`Ut4vRs{J;3%fV0uF1^8y$m z`{$t&0$((5lO|oN$`;!*vGU1hZKW?>if38SwMud*ud>pvf1)RtTT-F!xGLUDVkjoN zqULk&ljg?ruQC@Xx1+WzVzDX9MNhJ6{sWSnCeoQcog`;?(Ptz7MA&{p#YZkU6A2kJ zhKWZHjNvS3W+p`Pi;LGmJ3Blos%+HFyd?+_@DG3seS(l+fL(_kbL-rOH5kfuFlhsl z0%&Keed!zw^8s}6bE$mZt#aON@98KB%5PMZNwPOdsV*2PP`E)&kegQqh%+Su!*GAo@+>2ZT^Tm z?LWJ$j_Sqq>D?e<<;w8%M;fucPYz8J#)~ebzO2O8+P`GYXpeFxyl?_`TkPCuZ7uSY z4S^n~2lNY=smTSghglfT(bm)Z$oddE&9i;E@j%wP+N$mC3eh67qCyYQGD!^FTvgRA zaJgt5UpcaC!+k6dF~@qmb)zL_2+T0N>Y!@ppRc0(<$ zQWvXfg|;s?D=nc7<&(#TjSYB6Ex0=vazjjmM7*)bKKnexUHEfczGXZ6q^Njkf7XJb zas=zktiRfRKZ=+y)W);GFLy*3DJ*qdxeBXl69#Wa)M}sXyTE|%OiHM7H#EO9`i#7? zO>5i#zzj}=wY4=Xx;^q*AJBk{U?O^BaabQ1ION9t{ryiXE};B;9=(uBZ(i=WqoY<; ziTS3ct)I=Y^F*tWHKn9YWZ>E5t9MfUv8*&x_I7H_#WI6z=s%mk4Ene9WwDw};r+BL|6C*r>M@GT*UvF0kWXBtMlkrpxg5r*}MqEf%1x1ka2 zAtsdJJFL*k>MCaKlo|U^%4(wVATVU;C64EsRrmpSfK<j2`Ojl#B5z>D_Tx@wOPl zm8U$VTeY^~B3RbT?4RTF33I-WC_Qu~!hO}{o@w+caSgLTW2@dC8@PD>=&Fg2ljeO- zjFK~C>CjKVyca6nNJ2y3*IP=wda(Fc=xc#Ze@p$L$iDHeig-)h zZe(yz;e;IM4pj)@zfbI?HRolvQRi4YhgoNZ;7Vm%&B;UiY(wu^d=Pgf&A5hf@u{is zbmQ#RO#F%S==S%(?fiMd6C`Q$@XByvPW8!R;k8_Y4dsot9ciql&^-3;BIQ3<()chq ze3sP#Ge>PA((Xf~BT({FYo?aRBe_Dp30r)lRHmh++&ft2zJiKxGpVrRtO@6#p-lKv zB`On_r1?;`hLtnB)70+Fe>N-R*VC$BX#?6?AclEoznZMdY#6!_9@V>_unXOZUjNQG zwaCE3-iza<#=O0BZg!;%ECjO z=>ty$``{m2gPbQ=f9m8HjXi=L#79eQfCBFB(JQ4gRo#Gi4P*C+f&-sGD*F$dq5V~( z<3l-~`>TK2+jKUvn!jw3{p7l=X)}I>%jL`YS+PlJ@<$9-Z}By7ob)*KNI&e6hM3>W zvn#vkq4H3Em@1HWS6ZgiH_bTcvHa)Y+UbP7&9Y$ygOz8j4>h&|_?s7(6)ldgL6r3J zS8cin89Wce50vmkSXLFQJDKaF5e-xoXawzm^5faOl7i5AfZF{P@2$BP`9Yk)iGKb> ztdU(%nyulvRIgORJz8Oa4V#-z{pI^l0q8e5U&}>Ae1pAEx8!DAWP6^~;|_10{rMfA z5}_)i{nZZrfsHSZ0u5YCp(ee>X4U0anG)S+v%cYA^JTm6!Is7fM#JOeJ8`wUi`%)q z_x_f;MOAX$en5Y)R;;(%qYJ`?lIaH#zAH%;9)+01N94EGBD7kMsw1iEg)jCLOz*^G zYxq6L=2_jpaw#9P>!8S&G0cW08M$=cXz4bi{>MTzHp~GnoW%VRXW-XUtTbjp)0eDD?1SLQmbLlgYQ2s9mVxzU zD{|vU)fFDjnmBo$uT^Ni(%kOpHG2(dP21>6CjLcDw$Tb5vTojx!Rt2Ce;7pKnUlkv zC2u8+E0VfpY~il3qUSt~Grmlh^}ajG9HdkWWZ2NyJBAOkyK9GMqICzULVDl~Pu&(L z(nd7xA(q~0K2nrI|!{;g_pOnYWIzM?>qGZ+tX|h#tmmT(>vg!B<#nVZj z>G#uK7tenP6s=knBafBD1QgU@8h=lHg#Q z)Np@u>rp9AOp(}C(~$m1MK^Pu`8OAIyUo@0QV&Zeh{?6zCQ+x6()_X4aPeLxV73Xf z4P_O%d{d9xNa{lc6EBVLr>LYqN{hKyuc^JdB6kCAc#^TddFG$Dp>KBLs*8?AfXv+- zFO`6?&iDQItz1^7=(iV$X4je?!d%js4MzvfSkoU36J(lR9ZrEeYojzYzs530=bV2& zW*hncn0xQ2sIs6B5VNCT8bC!5l?KTuQBi^-U=t-v28jXNs9p3#tJR%S$yu}W5 z{x*ykkU^M2oJj$CWH5!7LHF@el4+g%N!%sOb9U?g5srbRi#MYuu2JC!GR=k+n#{U9-#zm`fy|a@ z5f$AWo3D?e-(;lyv5&X5I`gY$RMQkVLlaV7_F-Tr$r&Sm?N>tCa}YduJxl$^H=csWqQfN;Or&nwa-BAZDmCB zlUvt4)ioY9e^OGpX&OOYYWvdrrw2|a3Nslbq`lEUCuA#&W)<2|r?~Ya;q#$G$kSaq zdan{yjrm~2=cJ+#L3oj4={{9djMBAc62npkHeau`oGe#NpsCS}vi)3jPKSW)cfz85 zCR&rJ+79{GSadd44@u!7;%n2KT6Zb+Dt0UiWE>0Fhq2PJw;Opw~8-4{p z`GTkik~>6-uP*toBeo4yoKTSUlw%hnlQW=P`ClrFfr;t6?Hf#Ch)7-(uuVXU#HnCq)Hh#?v`tEX?c=p9sP^(vr6=<5~DMH z3Gam}jMYWl6HYS`vSc4i&2HxXK}sby*nK&{ zMz~mvKTy(K%sWN1tb9M+FVBQ5XWy~Ry{k7*JQV}afM+)*ED{P&| zqC)grTK74o45qw(M)7NNkoEZTHSbL{nP;A{-#nGx%}MF)9;**^YMxYQBB$Yb8_suV zSwtBUpWN2X=0O=2^SZW9xpZxj^ANX0CNR`{4spFxL4 z&(V$Vc`ld8ASJXnnUQi2eXYE4_pL$)H+YM6Drib~t_-(A8q?)eRHqvD{rCEAt6rZ7 zdu+njx67)(gNV&K4?OqA=_z;hN+S#jqg)G>2CXLcDh0H^Vw9-{RC{D(VO#0u&u}P0v9RarvL){=f+>C4vlGpoNVEC)3Uq;_0!AF5Ajtq? zik+w8@2jT=g~wA_wx{BFR8vEnNk1))zogf^vTgLYy6l7o0Ykz1mWo8sNb8UBo zoV|}VyBoGEr1U^~k_&x|qqoZa>ppGAQdS~kg8q0)2udS<&-*QG77Ngta4)-q_6Q8sVkX9gCfQn_N4t+n^H zXPu9aXC}!-;(#;63~HpHI&n(4w`axyxP|#Pes7Q`OE*^7sU9j#hwNC`m&T!N?_qT} z%&i`sQG9Q{*q=Yc=3$W~tGs>~jb*gIA3nPGt)n?|P``D~8@V_X6e%O<1pov91sQvH zK1#+=pRXK~*eL>@9I4bjO@S_(Od4y$a2N`5^0tbJ!U4VMc4H6{cbz+p3ENwyOK%0W z_jTqHb@0&NI*1f>0Ua95MKZ)oAZveEkY?}VJ#QJm<}2&ncT3gXc=Kd)!}?poMq=4Y zb)>^56ieFokdl>|u1uMCNg65_P8coI4RrpI^CXb-5&)-Q<>Dd&s0LIU^~{q1t@Ox$ zSLWcpgQc8Yl;5YCqrimrc_j~trx^vUL2GP+Z;w6X5F|E_5#71aJ(K4y;W-l0fA5Wh zh#u<+(?17!>0d8ThfBOn>R8HI7Lk$CNi#fEBDkwEk3vAOOD2V%_)ZGv!=W=3GZm6j z^|^&&GwtSaMzl%|!vU&2HGb)mU_be9GvSHys$zm;N(mKI6R7KFpi&1inOT{3-fo%` z?oOXD@}dLD(%cX)cgV-<2(g7g{&vIfSOdmCx&t z-uZ3kwBj4PZ#Qr(qy|qF{ntVxS~J?K42{9WYpK!Zky!%ikTm4jeSpnjagIpKdn;PG z7icrJ{nxrGafddr@<8DLtMrL|5Jh#~N*y$0}Wr)tMD&N-0iw@XxU_ zEb8WovP*COtmgCm?0a)vrxl{*s||k={eFEdX6fVMKi^?>eRo}&}P$ZkjPq-!XljDPD?5sPFJYec|}EO zaoNGIWVuDOYHyrJZ~Q#C=ah;jkM?I9#uOxtzuoxDF-QtKeVyfH#NI)O?2Ffb6O)wr z6pd|Ax4FN4&joyeA?wHg>&H4%?xC?IrD+vzpR`Fn*I60S3V)^Uy!t&mmmsOX_XL6* zE{0eXOP_Y<58+y$B_saxi!@9X-?9&0{`K#oCg3dp{$%QYXTYmEA24hx9}gm^4~1^yq1TvCDfoO ztL7AmyR`>RgTCuIv-LaXNp|Odhy=vcjgpwricUir)TANKRVvGlo7k=3KL!D60rno$ z&TKUJ1_%$j&iFI83e*es4gI;Hoy4DaF-rKn^<$ZnwHm6PREkqSWK4 z{OcFBN36hnCuhZoSG^Q`gF;`v{^tt+^IEnq8KpKbEMNYin&E`VY=!-TCez--96b5& zw4{b!!J^QeJ#qgCcg{Ogjd8#nF&eG$?K!Aq&ky`}(=-JZth=Vvyq@xVsyclesBckh z-Ttjp$-X@MZ>0X`bfG$^Xe1_pqi&D|&8qf^Hg?Fp;rB9s7yWnfa_850(TcwL%P|4z z%=Pb3L1DvNVSmKye@q=vce?H3q%xexAlRS=Sq|mL((}J_gk%Sg{5Kf!D#jYjn!Bv3 z#s`-NRfTnqP{%;~+WohS3P1xs0YL$boqHSJ6MBx82?o3I@creLF zr9p11;@dZ*>KIV(1Y-;+%9~$bjbaY0NdUOVH2Z({Lk&*fnX70VOSjvDs&2DmD0EV_ zVVTJv>ld@99an%pG^;a18xOvZIrKJfKwFF*G*@11{@8ST$ybI+iS6n^vYcR=a1hVZ z>F>ufzeYl#!rLxR_olt=?D<`f!tU2Hnx2IIM*=W_J_bxon(L2VpeB$6BKm4%!qsS3 zMLzoKQuoq)}*>s;H#Y%gRmmIUvISV5;1r@(6vq^+!(K%~vBA(@*~v*gKx* zf4TLdtXhp4mz4%Bfo?nL?&jhfq(6GeUW1Oo&b@nWn+hXH@BIty(|8`n( z9O<3-ZhJFQ?q+18cP}Kzj?kYY`>ysgh4*m?rK0V39zCj=fmn$AI+w?N8p%li@as?x znbh-pmmhCNngT;*lHA-eU74}sZXQqrzX7a;%k?}>wC&c=S^5gl$}W_)wzX;6xs!SB zb`84{Do&FQ9dVVJm`%qfT(Ny#Pc4lf`MqSDReOd}Fb7;o^$=(p6YgD}?pA_gdRAuB zElJ1x-gNMhjYFun;4V1;Eeis|+v5(cKvOC4{;g2wJUC(voj=Kzg%e4?hD52qPt?=v z>W0osgFbP%t^F4VNY-3C5!=$v**=L*;{kZ#^3jR+g|43fz%!s0tU-6q|d8IZ5{)It{_1F1qJ^M zCnETlf^g4eg2%QrbWkfowS8c=0W>9~NCsTQxWV3ed5QD7EXiB^GE=~@#q1#LfJ<4` z2R7G34>PJc(|;cw$!0#>+&hiMlpt_y?F3yBIsjZ1gshMqk_HFY%)D#PrU2mL5&=Ap z44mJb!?0f;DMg@C*{wGB(HRiBXKwL(8yW6-3W7Ywzs_NvLg1D2LU)4kD!?UZd+SeU z2W-zAAm+N z>|uqPevLm0xJTrVq9H?P%qtIiusY1;W1P^jaVi{WsoL@0u#bD{wYl++#V5P3s2ql> zQ7zfspZ1(?iV-dDqwv&F#ysh_jNOv_qYE$9K$HS~j8NAL=es_rP`RS1fj9mmivN9# zg*6vyP6l#!&u40RX)>aN^e58)sLUC9P}bkCauTH1JJuJU3O)1x^?lQ43BIM+gnL1_ zj3l#YOoLG`3OzeMn@;z8&(F}p*Pgu6(h1SgSit%_&oRrcnLhX5o`2|;v%qlP`}DXe zGA_@5PEm!Y9P>hB7acA8OnT?TEYMhvSQGr%pQn_7!O-pxAjX$%t(`3?UNllE!ZD&5 z?HLQLzPLFXuk$>kc*$>Y&bzd4F|l!LOUBQ`qu6q1$Jj{C@Q9$QC{-urWSeZXS?7v6 z&YpM}%Hzn$o`}jAXCLEW!6sz&xt-NxY#)=tUTNjl{G+FP1k7U&T)GC&J}@|6`qQ{6 zsK&7Mh3{X2$xS!2!knaXBz4O1=ci1@%l+tCD=)^IduzwHq{bhhW4lCN4%zr)cI4<% z_5dy?t?axeY==e1wqzdx-G6mLcWNimBt!&HBo=4vTR6a*x|tvc1T#gnY>aHwIOWTVu7^R~j`FFRV8-V^D4E#kNVT+dc|Ltbhst6G*1Bf6&l zaE{8JhfS8Fq}*$FS1v$lS738DhuuTHJWssn?8N5u9I2i@>RtKdQLP)(jLF=R9^tzJ z91XfXnKQU%ZPtH^Nu! z?6964_EFy(H8I3M-}zbyYVo$6=A%`HaV^UoZKUsCkMLb_dhtVS_&{)nuFl%%p_0PM z4)0#EGv4FA^*lL-t7n|Z19rMr189N-Sv~(cFkE(Pr}u%Y{pedZ`+Gg7oy{hcG_-Rx z1nNuf&_^sjdqjKv8AZ3ZDrH(TMx>7^pO`NE(M@@l9nJ_D8S8U=Vb+V}j4!Vq5&R+S zL_r81<07th5356@#`HA!5laD)A)w>G3knU=h znq=TfFheKyhGPP=t-Utxv#RF&_!}(XpVJ*n66eH=i#p4h!J}MCFF5Yz`+gEf{>FAb zXlRNglr`?+$;*%0ePb#p=2Yoat2KYR-8xu2?Ibw%#+G*>{xvcl)^s+KblJ|MbKb%| zYwsF&eptY~;~to&SPE`2`OOLHSeB>X@+el~3}9=%4iW5Zt&sY{dvhiw1Sz#dv;N!- z=U$@VuE-c$KC6IUsAZ_*8y(%HLe#{{yLKNzy5&_PkCXRg%3#c! z-aqgl!&Jr;ZMZmHyohlq6PRx&#lWM=Iy+0iq+uu=SKlpsJ zXJ!glR#0LolsUf-{wG`gA?Bpqx@dI7&THqYWz{>FXUG$44Xmsej;<8)*-ptsuCIp{ zPKVbmcNXR^FV=?G4|#AZ>)7jjw%LBW^iRg_tTU|DWi-w~Why9$FrG(mxzyVv2K$`X z*k_6pou$TCmiDyUUj>^`{B{=eb}u|eHbbX$)s8#bV&fk2*Emq!gMQc1Pxb;En&y;< zsG7S=Vrln|-{Gs|os0*#{(7SL*nC~Jp@&~uWMnI*!6^K~F~%Qs3xZ7B=d{~*uNYMt z=cUZeWtS0i3fe}l-^L~g5KB`}3b?08AJM^yP^<-hwb0)wyug9gjU;SR_a)OiZZo3= z*(a_E-I%?TD496bCplD}3PTtTHjXtJZP~N-#)J#*|JH_=*389r(4#z!iYXg zD!ZQ_P^f)~?~t?6C|i$4smg)jBe=|@2f9|f8jicJ`GxoFTJ&pPu5WVET`Rw~+#L6E z*}ZcUoA9FfU}XC+3d7tTLv@Hvc`n_`)SOS<-jK*(Up{}K{Z`)Uo#?3&iaC}tCS8^x zmcpUT3p9C>UiT(m8$>ma5SXUQZtddb`Q75OHzVA}9Wx@svu*wPg8`KB{`=XBF8S=n zZ{qI8E%(t!wb7gGD6kz<8?RxMpY&I7%n47t*RPYmlT8wF#&nqXs23<0p(q?B|Dni;>-Jrub}`x&;x$cNGFK34qye15|zz zl+&2EryS4}#K*R|bfS~A{pd8?=whMW_WYE6#alL-ndp!1-WS!k zUa>R1Nun3gW>AvIbE>3K^FxGCxPL3von_4^8Y9a+v7(S~ZnIl+#2(pfa@*6&qbg$) zBT-kUx|R({0Uf)|8)pW&}COr4z=+h5kXBQ4MFcGvCE=6Jl4h?#&F`OZpBlDu70(`vO@-sIrbZB38> zDeNL{$qw0o`j}X`arfsJMK%^xJ;<}zvPs{tS9t|oAi|@mEFfezB1RK-!!Ei?C~N$5 zL)SGiYyTT=PbXh;uzCtUFtRt=;M~0BRy3^1QLBy0AF|9D1hK8J=drI!xpiW)V7o0N z+K%KwPz4p5-58Z<>awhZDfU*&uP+kMcC1&;5zv@oMr$D8E)iyY_xD>v- z=v|fSqKv2vJlL2M8=I3pR)prS{l|aVrvCXUni)iNlNutK(1s0UYD$HGO3x?{U4OrgBnYZEk)f`tt>`@U=l-#9nlwO@2oA=5k@n{+Y| zf)2K0oZWOT9^)pX@qhE?SiYvFSi?(1JDQUz?ia24yr~Del8jC~nf$w0SS8dwO9Z-e*Zpa_s1(eTFMMotwj8;OD?z?ydQh-2|3jVa);9pL?55? z-dSwZty`k-cqLCR+pZpJG7%v>#>{v-(SCMoE{*wNY;uTD`skrLM)W^Fj!ZnWKFNEN zO&)AzmD|&Zh>OVsw?<36za|{`nDI2Sv}YrzGbD}Zjitb)5tQL+gyLOrR$96wzZv|U zzy4`wOA1N*`B@g5AOGlOpmvx}^~FS^*{SeE=LNeWUHONUoHB z@#O82k3T68U$?_$%ILbf-JP=IcH8w|N zgbmlaF+_R_&Fi%r^6=Ijk_3~;kpt>wRTLYwHsgRCMr=fsm?49b`*xCH?FKY5%6rJ#^pN&b)!BBkIR(O_@f15g9{ z25SHILUa2CwX~9=ayNXVlvIv8V&|{MP*rmdupJ(M_WZPIoiH%#~gi=Z2q6$?z zHLnFdrO16KicZ&mT@LpV4dfxqy_bvEKpdHqS;Eb&TZvdyQALLNOKtp{BU;5x`%`*< z_9qeYJ<@BouTJ?ZYm{VG)?B>m5jNKxRAzpuJ5YJx$y=7MxLa@A zx#kb^#r7T~y_#(q|3Gi+-Yz>hm>?)0+1PknbM>P2oO{#o;wQWMBULF`rHTZ3XScEn zu^>{=#-*tP>7XA#C#g)bV{!)dty4T)JxKl&>C4r2_I}ei-)eG@fBI!b$Qm(*fetV2 z-$@T1;duO1M^jd{|K^5VByqL)z~ogp7A3nmgdqn-;ROtZG)>;10b(C(las3_tS8qE zqKV*qG~}h*6DKEkb<&O2>kL5^$VJ=QExigqnc_)Etc4At{z;MTn5yZ}td|D(*E;3B znS+)e@t}Vyx(p}{0u;dW0W-09?qWKZIsv3(Wch{>pC+m28}USn>2$$p)8mcF3BfBf zM@s}3I*fa_1=&8JNC8uXaEZPI1(x`*t&6K6usGW}Q&+bgt33Eb9No*Yc`YlZ+Whm} z+Rby%jiWuxeLBaV?`p-IvVB#0YwlKA$&NtPsQtvwq1CDEhG-UW7d+%POahx~G#t}8 zx0<|=Rql^3G>290O?Y_jXwvGJFW%63-4jA_(oaQ%D9Ay#@IoTO#wgxxG*R5gy;Fdb zz05K`ZaDD3>CH$eO9Txs^bNAGF-lPXN}KX_q_F?Vpw=1Nd?4I#oCR zi{44e%b%={$!ye4&L@_nU(PS%5c7r;x0=p*@5^G|GTf;*cogtV0m_MZ#WxOItvM5i zvI^X!E$scqd&UF${GS~Na^7{L$amCo2#qje>{0kA1_xiJP)d3l!c)oOubay%Jq7`M zISr8XDmZ>Ty#BGYyc*FYDwsHrc)o`O2AS04{K0rcSSFkGQbbW$j- zwL-*PdYw8{#u#i3Tix8nHy7zW+UIxs14J^m=uPlB8Oj|QlO;B{m&Wc@R3)(9WLKAL z>`Cq7&)p~x@SaaGP6f7sz{rb622U2I%O+eZn4nSyinyUT<5F=(dr zQj)T^;EqJ%i{z9M-Cf1?FBfaU)_S zMMK(jB|Z2hRdHtUoMKg9rZM6Byfy7DlOv)8-K-tXHvH9}MC0gJnXx*V<2A55(SX8t zU%}VlqMK%tH|~_YKNS|EV=nc6q2+EjhlAI{yM~Ix=WDQ*rRX6^S~#-ptea5XCap4M zJCg?t&}!qGlpI)Cc+pmg{g;Vt4QFlZZ!yWqi*vn2MOyi`-;6%X@~v-q(fQ+9-GmQ9 zgR70Q;qP6lBK=l~1yjlsIAyQwyF5pT=8aDVmkgd8z2)4EkvW|=&$Q_$yv!%aacrNijPe|S zMs70SQpFE1(P|~~mA3N%q*_@==?T1)(KDr+7dz6mdkqH$%Ov`imV|tqC&c_%eN~CZ zKEv+2Gz$}cCbcVdhrQIxS6J-=6D;SpG>u=1VU^dmj^jRTM%v(QF9fe=hhlv4B-yx8 zQvJFfVnYk1-EVx7Bw0)|u?#E5vN%2+sz&_>rQd~=j`6FEXo=+nuc zEFpo}!>zVYh4Qf129Vt7FRs2(yGqDo`AQu-|MrQOX8DC}_WLf&r@MK0AekHOmh{!5 zB()Ex1%VOPZ)f7b09+_dR+=r6kNw9rdsfADJJ)A-LH;~<&PTg=xIrsJ8x_@$&F&9d zA-AX;)`p+~Z|)~u$U0j@$&f6ajH=iAZCl^Q&ZJV8*xRJYFa^qRPXy=VDOFc{n{o$V z)=1|}%-B9M!lEGnqE@V(GF~erVjx2yc^@nF!@_wk4vI41p_XxBxosR zwa#{*i+MrTe0^T{92g5x$1M&RZewIw`%XC?R;8!a?G3ENlLmS zSO3lB)cclHEO_UT0o|3HjS7;I-Tj<6fwXrw2`M$?MLzixVNG&v8MWHD)y}C@KFh?j zXxWCv|d7%o9-aO$}i!U!2`SV(4W{oc6pjm)WTqH2D>S4*}#V@S6-AJd{ zNxd!{KN)1c>Rb?Z`^`vq5Zh)FEuTQheRa(1MWI9uwPLyLd?((gnr-&J-U&-(H{^r# zOGVDgtN&<8Xz-rKu0)AdG=GaFvKcm!Gi4NS8Pgv@(_9pK04Hl8?lX01>mh#b6+dyCrMkg=JDBf`9r^ON?Yqsl*-lU)lREeUT#5BLg67UVh+ zS+~y=N?`5kSqT~aBSDu_Qx&5&vJ|&9N=H&ty2jktru0>{Ru9TX^J=%0O)EDF_e44T z)Ezx9sKK?h_*`}7VM2DNOUH6_f8q~qO=Yb-aZ;4C%IH?yE2a&)vCA2+OA;NQp}WhM{7cW-veD(VLubem;u%dU&=I6~TO&Ni@ zj!iex%(Y%MD+yDHJ&Hc_)Va=#+pZmPH`HroJZlTx8eqeV7STlTkT)4pvp? zchXqtRx9y`We5=nMU1M>6({X)uT|9UPPv40@6G#pJkx!Z#@cv} zCpT|djB%P-DY7=K)WgM4%^2_6E8*7|m_XAp%G*-5n*UWC@>@9Fe4W3rXWV;PQ|~Lj zV{(6zW?{Wx^N?0>HCfS5v)ArfIJy;MYpJO3J7-;Lnkbo!u`Km23}=vyckyd~1svY0 zP=Bm$RkPZ!p0=^;r@7jj-K(UZmI)@3+F>J&J^9u~_e_{9eL^rK}63 zYPW;R`ayow#d=Sn`!6s)nTRK4FTW@aLiuT1jaTM2G_|kxIj)-Pydyj@TQeri)|+WD zo4qp(nR8MbB(jsP;T>hHA~7?`I!@7OT;O}W^C-VyqmowN`1N(ZIV+LBZB_Ee&N+Uu z%0|)1fp3^SE~I-|Tc$QWLjl6=Hg&4w-x@ADttPAqWuvSF zjOkyF*UOZwdst0+7YLYY4mfuUIE^UF1!CBK&}rn1N>g=Er^Y0SCiAV@s!o9c?96Pte-6%? zXJ~4Nx!1)$AJ<4{(P?|K`BmF8k#C*mvdRl72srTd3G)!sbCT$}JGxz^Z|qKf(+W_u zU7-w7L7Tq`-|dF<`19y@UGl8!cl}#Sj;G=BIkBi2|8p@pc_;QNOFbP@+ZsHB!o%?Z z#5fL29-Unu4KCyjI`m?~1gxT{IW%&J*JmCdW`|tF5o+O>Bp}>cJn5rR~WXOK6Je{lM%c{0N!Vrqz;YEcsIcv zF2mhTcZ_~XbDwm>;^?9(zmlh3HeY=l3Z2WQYN|FXA(S(J2eK`e=biA*I~uO~dCWgj z7(9xs*wn_kc#?78i>i?q+$|6E7MQ&Cs7_>uWR zpMB*Lepn}Yg;%z9)CD$S>-fxs=5opL8hfts!KvMJTd{z4*_ttd?u?uanX^VBF=xV+ zh$qW*LcT@CY@}<3&k(O0zDjdB)~{9MP*bp;FXHI}NBRPsvbt{U;>NMjWXY7zL(2NH zv1T@owMCD^7tN0;&vh3aWV_0Dujc%A`_+tq!lJmKJiOdc-q8Yz{9|Uva&S+A98{;@ zqB`v5TMn3%CO~Xtl#^4nKa9_Xw94i(H;`pN5l6vzVY&9Ce9DNU_<>z>wPN%k7vqD+ z@I37T$qRM5uPQQjthafYturNP-F<#+lCSj7;mkTXHG3?|@-noI=5mvB2zjb}Z_Wzz zc1B>+Zg$E#Kdz9jWvlD_KGRTkFyvlX4nubcahi|UIaxdOqgy*yMzlBM36-?r{O9+i z?>@hKnfiCo)nR8bwg>>_KM z#8)M=nuZBqPuxlyav*&b=Z=sKNe?amO3A;NZ#1(w)}-RTaDu9Ht(356wiu*VqUpuw zh0Ar$$qOfRL6&18p*D(!>gIj1zhANn^JXZN$(Bewtqo6|U+Xu2L7bngHQ9~X_z}mX zOP?^P!?3f_rkiWFV?y(Ht2~k3K|4_UWx$22fgNhYTKW3_^sTQ`Y{FSe^(>*K_BoY? zT9(e6qV`%0NqcPhuGn9ryPFZ$YV>pKEUit|jD0PJP9MwlW=(94UsGI-iax|I-t{$z zGB_b26O|~Q!18#S-thH&kWi=9V8#aBtuS|5l-CJ*&bp{*6H<3K7=S^GU5RL`9j)^U z=P9Hk`AIYjUwzKzW|*ckIYg)MxI}k16AYR!sSgjkVU`w0>T7$Z`oM@G0U7nn7jmm} z6(ASllgi!BK$w`Lz;`DVD;MDm+<4Z+JI+l;O}zum6?G;!$01L3DlFw&=E201=acsx z2vC4{;%uv8N4iFbVHuXPH9PrkYa8SGF>!N`b#bf}x~go;E`+=skF43qyrGxfRMOko zem9KAD$PPPMt4F)(^v}2ZLn#o6=E$l%l9zKGPO3fzNJvREXAhf?x?a+-RR@363Ry( z@w&SV_BE*tE6iTs7^~aLUSjVCA_uqkd`?;67B0q#oA$wiMUZ!qdH0U{gu!zPTk07&6G&TPz-;;SeRJuEH^k#Hd7b2u4~pj{RRO+=<9tNJga+A z1YK_a(_H_jEDg_k6dB_|Pyc7DU%+`J6ZC`j7;aZ5alPp0RO_>l$)BeM1iFno^VADTFQLYT zNKq!IMqV1%T@0hptj%MFV4i;7HPWle*pc}WvBFMRg|H&q4EG*VVBUKx1$FIE=HtMpf5SNdGG>F~ZfWIlnUiCJeU*TY26$^}K+8oZvVTJSI zI~E2$ZljT%3;EBpd73)S@j6NnpD><_NdLPqI#VqiQqPysf{9}+`@m;+<C9m98u}X6i6Pez)16e^I>u=K?KZ8^V)#gv_?TGOw3)Z9--O9e*cocS9&E?e8 zs}4l0dg%ry17)Mf8(SP_JASq`0O4CK#5qsEhp|?{iOnmkG;VhWkMnvET}z@#rJVG3 zPVwi*QK>0;_fK*_MaI=7iZmNc@=s>YgEYs=1+>?4&T7c%n#kHK0hBOZF*x zE@Ih#KyZOW$hEz^Fmu=IrIxGLfwNF3aA=$JEegp)ZO<9L63-RiU>UoLZk;F*l)Nr! zY>~84MGEPivSb$CEQzGLMIz-9U|WzEC8ZA^s)vLc8f$DB$uhRf&NaE%wM@hVj4(46=(`VVIas-Z_% zy0A z<(5bF?&heST`m%Z$jy`w@$r}0Lw+j_4@JbFg68sTv38y$l1a1~SL1}OKWbuzWK}n6 z&DXQK5k>@EC5Wq2pgAXU?bO2lM>3P=kg#c7>D@ug-Mp64?pwxeP`&^WbUNb9Co)Eh z3rvCNwiDq@XlIk{TN^i5$GqLF2rim~W3F7`-AP9(g)W76Q^&jqS(#6MTfYGP7;*H5 zPfM@~)k5^MI9UEq8MCT^z*oga?0UHrjef*V*$@XN!-K78-I^p&;kNu{Na6Pkr47_1LDYhR*mg z(d}kj-DyF#C3aBOm|0$=Zcpgb{2e4ek8bsQIoLIF<`c}uQMqmZ+tPgA+JGvMm$sws zRnXfpSRjRce|;8^!S?zEJXaFhsP$qE3K!-tK-v?s7o}0^E5498DcpY9i-_UdZ@qP)U%(AA;#zs*4T*Z#CBI zWNNEQDu^@brLV|A!AId)n$uz2raq{N2_t!PlM1;Gmq}7c^v)GHy)m@<|EhVTI8PS1 zDX$7qT`+z~eH%7GO|2BiF{%j>y2P3TOh<0$_ZFBhYa=2A(Y;AXn@wz|tumrRD2ipE z;)3}z(kcC29vX*xPEBln)~Q+LGG7XjuLgk10saS%`&o+jhW^<~#v9slPMo#?lp#tw zx^%#Ah4v@F*xaeQ8ZO)dg+Ohln&7a|M{GPR6t_SA0GGD_+nCh-v&j&PHZhEf1qFO+ z{QlAX*?A4E=^}lsXfR(X_38j5h4YBsnv=_IA0XV;3E1JClGjlABn2WZ-gO1?v>{h4 zPH(K`1O!pPqaJ^?Z()#bx5IC6kQqIBx?ilfHXn_>C^V@M*|#(zDq(I5E=H4pM+Uu( z``dmq;$tECw$s}FNA1{SWaouHk$#mU6_=>GT};h|AQIj%K`FL$kSHUuynD zJr9!j!-T6nrFHi{HdvB2eMrEKGcXiAy6-dnQ+lM)CMG_H41eex<>8mk@+DG}Qtv5) zQQ5C`efMt$szoM)b?p$zC_{=D>8^fRp)>xlV>v%l#8Xc)3){XfCZJNs0RUt@*< zgs924-;Yb?+4$pb_ZP(_L?@3pODx8y3o(x_FEE#R{I!= z`Y(<%n;y`bYkX-wQ1I_nB{RPl^!)eZ?_pg)uGhmAsDDl(2C1O@?gg|Hk0Ng+3@`z&b|CPyfAL%u^A4%p0V%+(qxA;&}w;-mz$cF z^PSWY*_!_cz|oa~61T>Xdjjrkp0g{Of%)Hhb#R;QKnIe#3<4&Aca6BzBr@3SZGN#B+*dxk@dqWagtD_DZ_RK0KR_bl zi^zEOd|RxqmyQ?1G@S6gE_k-`EFHZ8qD0BY$;c1-Da1>hhlRzIV*;uS5)u>7L+{Le zGNssD;5|Br^#zif^I+?YjEuY+jCq8C&&r#BibxPZodex1 z8sHlFf!u6SqPJ0Sirrvwq{dtSNyDu(=t>|G?0K>&nlS^DM~@9!t`Jm3MFkoQm~l+NnK*v48QN2z#buuM=p#hh<$yk3f~fMt*^yV*b-@de5Mynd zgw)VzG>x$9C*aH*$n@yV!$57Rxm`(od^{hJH)S}!75wpvffo*ln7&U6*c_WtDS$(l z7la~IM(c)KSqBR8{s*#Rv+=*kiVEQ-5@QwT;%)U2$t?xRHL&CKITQEc!v_frd<H zBwy4NT?Ep9q@t{xqFd&k^^kq>>1_m`k{1LI{Ugj#?}!aV=k`z;%YLCU(h})0KG!A2 zzQ9h@b8RVrou~zCWchn1-T)MX9I-!b>Img^vqG~}R(7_1IfZ~J(1Y6Cpnc~5kLpi2 zYCrmRR0sqQn=n-V(i{QygdRFOs6{z=gHEIT2)%0z^j%2;c7F5cX9sej2M%eihlV&U zTQbpbPy!1e{jPgc`Abon?mm2e?LG>Hs($p5Swy6)Wd-pk9+Nn{yF5pBD}q<1pG~olTaBKzl}sOEci7c z2@WWH4zqnVwwI0~4Oto`&bg{-4_oGu>6VSUT`;r@d)T1wlQp9Mb1;BaFxiI?g7V2W*bETVdP>ct} zYL-j&po|RcEI_hB8AYCi0eZmzD}VV2(1a>|>hQa8%R)3r-)m&Yfrgp@mUsnw`&`bV z=`2ynf9SPbW^#X#v+Qo!0xBicaLZ#6KOD@5xTK^xG;Tr{UN|N69YQN7!hl0_%OS1O z_x#`Amv1}-SAvGu^g%pkXlTeMAi%1tku-b5vUov)&idPFgqp;Dz-jF9!jB5)nOx#B zFma->ke~-+l?1Z(0LYwRB46&TW7s)Hzr#ay!)8>jb8pN*=wevU$1Wn5ew(ik~E zKYze%7w8!$p%_mEurt}NA`W#k<(_4LkuxC=eWDv+DlhEp0{p}jw5h7Xt2_@TTKwL< zgIB^(gY;H_=X&Cko1I+_bjNC5KMmLLbkq0Un^#Z0uV-G6d5Q&Nv90q|baegmRj+i* zu3WjYqH)m>XlaltTJZ9CD=I5lZ{Ab~5?w%YLAE3}Y(X6KU~X(o5iUd`8XB>6h?_Vv zVu*0FM8OzPXGy3GldngaFZM-@5fc{sm*8S_Bsrd2&&PJl25x!2T`}doF zRJ^eV0O|=~(&#K0i^4Pb-?)olhJr6d02J4Ue0+S+E11QNpd}*)Iha!$2QAVpA|kp7 z0O_4b$BEX&Lf~Jwhx&Pdwvh$~&{mkiei}z)=%N=M{TaHb-d}g&#^m4%dTdYWGNO@I zUW6?OVKnk#%Xo|G2NmkPJ{pp1*1_s`o=1YKc>cNfN%{;#pT-6dbv?A9(75N5b^ONi zgstdUe}QfC*Ya}vT9#yHAd3PbxVHJB@@rSmyg3#cl5Z{FLgIs$^!6+dygP-U7@guhaclY-f?JIoB+@#? zHcvylH=q93gWzu60izfIOgjh+??hU5EwWSR$l z9W&vbrw9U$bd(0Hf0&3z>FtXF{vtb1kt0Z3lB^P7S=awOu=|es@4w^ah1c%^(^cBW z>Ks8$$4ML+GqBNg`Aqy;Ab~wM1)@PGq1Ve-^d-a`a{mXn(TRzP_8li{9s;L}?aGzA`GfA8`*O>Gi<=UdKx(9y3Q0p!Rwzub0z~9f% zq7)p8`>U}2Fa16Fa)-meU$ywp|6N$vz51V(Ox^(h`Tv)W@P80)&yPJ=fm&ONA&D ztyqXIb;&@ugSfVoTr_wfD>D53gUn`Af+euE)8neK13OsAEyL_~P1*pcWV0t+KBpC@ zg)`8by?@tNtw!ib)1<_neJxsvE;~lkL}Ae@zc?+=#{f({*M! z?MZ;|JSY$VjpTsvsKwicHUsvDw>iHy8*2-c{B8Ky4&XR>&zXl$aCtkfJ+%GNa&aKq zCIF{9WvRx3F*<>=i)a;7a7j!uh_)D3%4?9LlRw~9Jq8TXaQ*%BJZ^1snjKBXWqqGo z3Z3UPT?vz86*ln0u>+(aM@A;&#^2=hbj!4CTw43}$UyYtrY1GK<`51lZ@?x#XFTV8 zAY6f(W*s`IKf@eoHoS)O_Hkt)*UXPrqR;qvd)GfZ|M=(ED;AXkey+3PR^2D?T;P(~ zrn%y5>ii$st>ldW(rib*p24ku^+3mS&3mC)i0^0TPq~tF7Uxx^Wm|mjaOx8CZnb!O zmE-1O1_~fc&~zG{8v>KC9}!%K@}FBd7k9=HmEE>pb}NstunNR}ay)bP%P&I>cz&rE zFweVp$@$+8C7fp^7x;O3Rg{$pn3McH`1s_)13vWxoUm=&S?obaPp=9DgBp4iq%EVe z2(G23+b?~D7!`4;FJR&~%!<}QE2#*pT94U0*M(Vw1svo)_poq$!RgO|)ASNQgU*Wo z5P?Nf4V3~<+AK5nE3^3Pld-|COuik!cI1cwI)C9p=vk?y8)n!L((Gu3YaQ?!tmXCI z-rf&|^nLK3hb}397jJQqIyFuxUNMB*g2P*Xd|kCwgJF>S*f=i3`vSZkkIS?Np%GYo zvAGGhCf4I8EP@-OC2)KLLGs&OCXQkE7{v7f9pjU{ms09*HdSMy!q#?|>5t^wVC2JM zV%ndzW0VWOWnkhoLRonMVWLR8RsDKQVn?C#c;hVp&0oGa14YET_rvY6X^ubhUduRw zVi-u|D*)wV=-!36=ZZ`u9K@E0o4-dJKVifbF95%fzwsBwImj%pP_bRl=VA+&gz3$5J5oPoS>gB0)YvPtR$KM7tP>)`XQVzQjd=UeXY3{=2F~`S2qgM&D+JWOS-a3xfSFCNQq(g z6R!LI-bN>!@j;H@cyZ=aOi0LM+^T*VO{;{Z;C_xoa`ej!)wHhwN?SH<%KX#={H{+Z zDmm8A%4$-w6(^Y_VzLJk;HGb2FpTRC8_1zCKorAR*``ww#Nz{yIx_|kRUv{KLt}6^ zIjfM~Jtzo2aWUgy`nwHZNVca`0p>V%TKU)p6BOZhIZpiM@Prn zvaROufb_y*Bj##c$XT)E`s@td3ehDkqwnM2cMp+o0sJZAGH?0!qQ>lnFsX{OFYB)Z ziY!lfNj+Qq)BI*Uojc&rhR*MgISPI6-7vkEaPMjf4b!NPT8X*ekLwMFo1Dj2>3Xw@ z_+)4)h%kxFYNjXLqvP_q^|Q9*<2b!FZ*_Y~4A--Q*nuwZL*fvL$1-i^#tM>?=ZBug z#-*kP;Bt+3@7_^kkUhP<*HHS(S=bJlzsDS?PrWLha``nK=BC;kyZt~`p3u3f*D>$> z&n?O_r`9lYKKYCKC47D0G zXXbvBl$1=t)xEI|{T0tto^AkwlicimLZkVU)SsG_E2x|o=dHX)m>3z;p>buR%ume9 zo`2^>e|?3Ad!f_J^Y>1If`W=W7}D?Wlykcfm1Ewn1DsjlH2(eVbpr!~6xfgjQ#fBp zn8L@&8Q)+=rS%>1X7Y@l9482MDwVO(vhoja$bD{0}A`AYikX%v$Hj#$^s|*s>4|**=|ct zn!m>1{;8#;-=?MC*FcM#se5e_CQB;Og1&aj!0JkPeCJe~Y_ztiN2-)7RI=wk04a=uuQ8d3PPlEifs~m@7HvC9SP&Nl8fz zbe`#1St?Esb}A_;HN3pCb#DB-mzNjqtJkl)1_wVR${)VDeDtA+(TezU_Z}WJ>HazN zMSgs%?mCF{9+8nO3yts_KxTJ&%iU!3UI!W8xo7ehlj$yNqp6>ssjXN^q&#gXm z=umR#hD~qmevlh|<6pj9zjNo#SLW@kPtV45Hy&|YJbd)%(YU8iX~ejF;+t;pk@fK5!_q1$AqpN`467No zZx5iNrYZjL;huA_n3NR9^uVWq;ntRxZb-l~7|k?#Os9#-$&$*Dy#N_IS9{8sb`(Tj z>4-m0tC4?W4HQ}VAFWSU)6>g2I2=Cd&${a1Yx>RNkf50S1oH;YbVJv3n4jP@`1EK! zh6E)W@S6M84=mVihb<}Fw{K6+%-okThBdIJoEb!5{=8X!Uf$%RM>Lepn>W8QZlnw3 zkb2O}q`MB>A~C6w+I@7?H1Uhv!>Fj^SFW((oG1--CnqsVoP5~6f_yA^&=60V)D$2c zC<+DvI1br7VZ)3&}+)?A}@1XVxI#l~BLR45-Sij@S)~6qq-ed}Y zat+8(QO{=Cv}uLCy?qCtE=a!&mVm>zgoGYHFM1BH-Md#o9=k2QqjUJz{5-x%&ikK% z|85kk@B6PvU;T@wy})s^YO00@E_4SH@DkK5@5Fso6F+~3Mn2MluZ8p3-lvi63-ZvvS2Eq@WL#l_e2^y1BMc3jCqoa&mLu zQ@Ci?SG9#Ajc`xm?>xI7mqiTgC|LFHaPC`NQqtWb*M)9uiUm$K1GQzHCAZ_Tb)wE{ zW0F48EEHQ_n!A=-i+kGZ0V#Lw-mML76$aQEjjLC!y5Fzy47_sb5)%qTI*{)=7NM0R zUtb=_&F%uIkBX0usy}x-caC8NHMO8|19yr>-lp>M^0rL8B^NL6TKrfk{6{Lv&Xaz{ z;5c>Ia1QvF0O52E4D4;RgOml%9=L&BOzTI>YfD?(z6W`Ec^-o0?5)8CH~(nHzwJJz zRR-chMZr9N&ztk=)t#`gEjb$7E9vcVz?fmfvyC`uHx88y+P^Y&C5Rx$lP6C?Sud=j zl$4a<>*cpGI&gg1Ln&}wU_z}G3U6+0eOFve!P&gbB8Ch=#(T3m@a5yNhEPnzY==Xc zw?za8-@0>WadT20Q)IcYZ-!7bI zVPS!G85l+VX|D@r~^4{`k`!+}x}27a=X0ii+#NZ*C`pb0+s3DvyB8Q3&U&39 zjXh3*{W|wfKE8DajT_vHii#TS+)G1;WPf~r%Yn6A0#Xs$vO#yGRyUEkU#4b2) zmiG1)(1KP{Q&SHP50`dyXvXglR_}=pG_t{hscUTXL{-ITCvGaJe&ev<+&M!JnmOy$l^zW>DvbliVV=d9+8jY<(=P)*YW z?f^3`2|KOqgW8&by*$+gyTdw)xOMMpUB8UuUK_%Y2%@K_r*Z$$Q5ePRJk`5~x)|r& zG`%+YmOBMRCq&`n<~}vFq~n(XFbi}7+kO<|t_U;^FWOsmApDw}HbpNfgS+S@-r!P> z`PHx4W>-@AgoJ{VpFK;5(l4L*El9B|HaNKS=g*&N@X*!l?6Pabd?KW7N`9%Y*T$C8 z7l!|dNq+u36W0osH+lVB|NHlEK1s<(s;a>>@i+f07fije9~YvSg6kAa@u(yLd;-Dt zRhgQaGE?kOOd^+Dru)}Z7h^_V9+sp!H<&hfa7Q(+cVVH7F*Ej!jnzV7zuf&B=t`Fo z0Z`9&*mB3(HEXmnDsqz%pl5yh#$go7{%b-&tHaUQM+y1Hiv=wk01TvG>7FY0oh!qG~tb&Jis4J zw!F&B)N!60>uVfpdCf~eBk)DR6xcL?HE^#+q#B1?-c?#i!{2oyEk!% zqLR|}yLay@54Cg@xmK@Rx6YvtFQ<_(E{ik0-BX|MVL z%>oQpXQ!6tFTC25sy_c!wT~pKDFV*U&K*ZSR9EZv_xF==D9EUT$q1@}Rh?S%{d+8x z7Hop>)^8}q>1Sia@cn~Fp1qQ~dGpVv);!1Qq#6@1!Ezkrd z+qN3kL*|54iMuW4w$1kX+k_fTgMZXiSNlTNxeuY_8hLazEiDhp6b3h%YPmSO9Fy@` zg~5&N`8hnzUiki}XZ}FZ*QYq}G;LwI4y#zeL%JAhf31nqRODLsLhLhRR=fY*@9({$ z&wIF<^SfVyl7P<%E`%sb>gzXRlyhwcHqg*-uX!Pbjqcft7dB~c7skXF5eArtXIBRu zgPE0e1qBb!2ZUvMc%Oo*YWN}Qv-pVGhKBcy8=sRq>ooFuzw>Jr%s*SgC^C`)H`!D1 z4q$4-h7D@33^%6nLp?eNC@nv7$>mCAWhFN^w=}@d1m45C4`}7C8echf(kGwgPd$3S ze*Jn`09Am@4g2@+kF;gX06-)777m`npJfSE%nN6NB(@&V==>Pb@W$REA~Lel^u=Jv zvUHc90_BOpXL68jI*j&h;&y~lbXENr9qs(_V}F(z$N{Bu=KOZqFJ6bm#lv%tii@*J zcdffrhFNXJ!`yrS=&!M{u>e@>RNP11fP4W=XlkR6?6eWZo$w;$1+lmEckG-(?WdMb z&brL=#lXeoD9t)%3N}o|C{h0$)9&})1>c}zp2X@CwCt2NZA$kzv{PnMeI+hiqyb|g zBfNU`>L4dBG343W|yGzjbRxhck%A>eSTK!PXpp6b~N&BW>&-sbjbw6wD;Z+~N-fz%58C`N4Vs?U@#*FIFlO_o0O-@0!7`n($s*z7MD|G~$- z58wetJ3ST&23r5*^yX*@XC_KeXy_eK{jI=s$MLu=lK3qwENUJ}u%RTK1f0#Cf}kLS zf04XAimi=?h6YX#b(&Q0&uWMeK+~|2`ipCL!KIjCk_Z@ zusLh5=36&^teE3hud;L9KV_V99DwKV#u^lSp2EcWJq}EcPqTm-`7ej1-v`54S8^*> zoQn<#**yLlia#l($*(JW+r^ym@paiztyjQbh>5k9N3haAR`fX53g zl#Z%#z*&1w< zaLQ6$Jy9(rT2(!n&c@nWUSd4B4_Iy>jGkG5f^bZ67_X|{>0WH)T&cTN)Y$r z)erVNR!1E)DPL;+^eIpwF$)!e;yGT1$)Syh1c{O(Hy^z1*3+kZvH0|s(`S1tH{(?0 z%^<~PU_^bhXRHsnxVY3odP9|3iJXz*=O#GA=PZoX#{|CyMi5ZSFc{Z@uOu6QDxlR zBpVv$uW>#Qsr}U?y4%m+pCD&az`->jYW#k-Fc*07lJ3(?W0gpg^O08NP@?an5CUsy zAt*y}M_dfNhl-Yd`-NfF|Eis{yu1BdkboS9vZ@5|7eN|zEuPR@ws&wYMqUl)AaVE4q4MfuF+Br#w3HPms zS5Wrs*@K59hsp%xm^+2%lYnJ!*q(n-)U?U{`NbD9Sglx)O@+=mr3;rIyw?#FyD_-q z;FtR+FrysO6n=9`cL>Q|@7Oh8TWytu&=NG!d6x{9v&;4|Q?&h<8~Q?fCEK*bbM01ay8cqj^EkR`V^e{n@VBHB z7*R|jke&@@W@e_}i`b7GIifsp*}4tiQISdwg-?==m7no<)8wtZydz^Bg}x}P-7ts9 zQXo%S?*ju4A%FaSDdeXvkXCwndeG$qYfjy7h=T6a#`4rhN_tYTL|P|<8Oyaz@nqSS zo0MMNau%P@4Gp0W)pMUgsZ7?AR>yGRTc{dK#Gm`HYN}HCM)Y|N4UKJ>pVfM^yp`Fg z%KL4^i@gM^0Zq=mynN8X$;o;yD%k3xjLZu170k>&iU)wE4K^fihHYRu*)5wK`L@^J z%e~a(>aI4MQf4w=dJG40s;VwT8sqLDY znss$`oo=~7HJa3nlD6w9$gCIawWEi)1@IMp)G>I@(+OIL1skv&v_0sTUN2s}sF4&u ze3(K3OW~fO_7(zz2)cj&yg}BIS~#fFRp*Uaq-{4wR!pTU)kn%A)D z%Sua2Crjl6cpcxtFrl3DA>mXM9y5;eDgj-A`X=e%;1JqmaNbYwgq+-Cl#Rr%VNa&+ zAL_Y$9!h%w%WeQ0S_;r-P>b8KV^mYq(~fLGjt9MwyG-DAiHWgx@v#WT-J85A(!+;0;(6+Om#>W#)uhl}PbQQq-|hz;Mhr%j4zLg@ z*pQ?9B-?hda708!g*yNiS}(neRIN_PRBfZ`|IBfKp7YU*a%>+B-s0_2 zxho4T1!mX@>?m^=^sKEjFE|JDAJjkN@h6Wv>l#)N1k-YWnh99O$IhHt50`4-CI6aQ z?&aM{&!6uD?MiDO95mb}=@Oxu2A${J`ST?Oj?+&bJqtIjKqZ8HrUw2R&Kl>yE<6AG zcQ?G;!;Vu=8gPVZs1n`Rphe4U_yU^0Q2r?tz`OIgFEO^5jHf)7zU;NTyc0#_td0G7G?B1qm+$f2ez*%AYs0Y15`BRifr?_aNzM8gEmd zLBmQ0K3v4Zhf|+(7?q@`8H@Naqi@4%u+k4^NkU@z-HQc~M%1N{x!cDL4EBiGkNFX` z4W7b%@yEyTC!n%Vs<8OoQ6oEM_4BOz=m?#I)oY{FtP~+Yg-PALWY$r@LSbNFaL4vw zWpqQ2eQ%tA*?maO%Iv>?{W|^Haj=dPI4g_%HIJHc!!xRKW<2H!6ByNhAkn!+keVjR zY87Pj0=1EEb=Z76|WfG9dX*Z_&H9wrxPP*g~>u z)Gd13W4WupecOtdGlZO?hD^kx^Nu>SbKF8u(sv>9rwpF1|VO+?{-3B3B zM5lm;I%)(qpgJ%Z^OH{ilTWpq$k(<5_gUf#kG1fE)q-hR&J14!V|n{t@G^ckfdz?O z(OMsVXayKe9TckM$Vx_*0q&Nh6q8?&_U4!7zMoIilo+F0uRr!ZZ1PC?+1SS)C0&1a z0tgj+dW?MJ;==gb0+UIV3Si3`Y0UrSxwn79)B^u2zkN2O;gcyk26Wt%XR{Zm;oQ@+ z>>7nmTSx&ziL3eT=;&zpEtTEH)fL6U1F?}fNc3%A%EawPi^;6Yx~>GnYlnmcJGO3^ zdPNN??Z;5HOEBVFY2}6Fv|3_!i7J^NxZws33&kKzUOubUKJk zH5F`)b>IbnGP(BS+c7WY&z$EHv>m>%2#EwB{Ft;frLCvEG9C(FLlid9LQs@Op zI5k0ZI>EIOx_W8j2=*3OV1kJM7r6Y|gr0*k6#I1e+!tP6-a=~QFgz@VL*{M8>Duom z<|lQrTq3R{y?EifUBZdN9c}v<9AofX8V6*aRk#8N#}u!{XTSCG<$k2aKD?Zp>Qg|K zB)AwLtQcAq1j{`QFI4HVU3L#2G;Io68yy_H?MLI?o-z3?cyzKp!Glpk1#|qAqS70&sj+^BFOdJb}K6GX$Yu8(>|e74L+j0hLLJBY->Au&(MUZq12JCxVyJ7n;p`&z=CPLpRI@Ob|#dp)cls&zLl% zUcF*`=_Q7<6RI$U?zR~`$qcQM6%=XMSoQg~CKPE%-E}BsH4%c;larHV1;S}&U}yiB z_?gBXUrT=GyijY{n>XU)Zqo<|7h|S*re1x+#lv&jcu@c=eC#`+N;dHH3)&;}^JDN}!K{*9qqpnB5aQy@h$Vf!wE&`Vj)gtGkg3+Xu| zPvF}S&ku992R6A{x|T+F@ubJ38c+v>{z1Ul?KMfRX1#HBXe>N5lbN}BSRY! zkw#%$+zuM|7^$0&z|MSNX$fLth(elsfbFO84P?*}EaR-~Yy(V@nzpuRn5OBNZaj_r z@F@D>%w9Ct)qRK0%5`yryDKt%@;|;|GDLWIP+_6HxZn)GR!>Y!Y!u#@Ml%3H1eBTT zs;chBcC1P09Xfd76etfcHST?UBoS5lyJ-=HUmb>X1gapM9vztcd?F&Dssm}b!~^T% zx=eh~(8x#@>Q|Q3pT(?R>Pw2CPf<`LZEoDqV`XKn0i_`lJ3`X85MUH6XZA%Fgwh1_ zA@OVYPbp5$W5$uEcIklI>VudoUcDM~F-pL`*CbF!?^(Mj5SrgvY2BNPJ!RE82(22(WxmK=E&m{7s_k3xcj)v%Hy zJv~=_sjJh%013@qWpW&kg{~q9Z{NVksIsB4G4j!)?I!gJtJWe|rIV4{VCQ@D!D)1= zWI{_2gyx$RA74T=xRU|fc%~)fiCek*AGdPXt~>ZDg3wyX&!oJ3*^GLo4w9KxhzuMt zCxA<<{w9m8tBGL&+!Kizh3te5_!i%e9n!-Q5;vEl(X)By%{43!*6GPfZAdK|?3IrB zuqUE-Udcyz+aC_IAb2daiU@=&U`wz%!;?~#>u@~mJj+L2j06*Z)(=S1);+tC^B^;y ziH)uLMbG&7CyYz)Y#MZY5)|Xevybfu-Xo5Lk%@`$@#DwI56?on&}6T4)vKSQ*X1bJ z%3MZJ<>QN}n3#`Aijk$*9myoNvA4gD)Iay@n^OUAy}abSd%U_IN!_eP!LEev5Q$in zS!=dFww$26GqM#&d|u@_&zYn1)C5VfawNGTl9PExurt1KU9d}D(EL1~^JIztx8~wD z-KU@G_vm`YUPDq*8!$l;J_K2!D7MK?J^{kOaaF`xAp?L^he^vT9w77Bww^Qp^5>x7 zHOwkpv`n0LTy)Vpplx9h2mmx`(9cJ=imI&6VZI;fNCuZ z(cB77&Vkpv|66ocb6#VmE9Sa$!3ilVSukW+#qkLV%JuEP_IaP+0+iAMcGRe1`iH<5 zt-@=mAq@e1--N;}Yw!7A>~@DCkDKDlFje`FBC*##4`c-!QdNfBwLnO}Pm+=zs8uvI z!HQw+YuNeE3swO=S6u^%1rd->dHmwV+N)RFt%o=MPap8RDEWXcLI_|*OWo8Qvu0ys z11}E0=2gUn!KuJyBMK=tv!m(+u_$@{^QC!oMKrl@5;Z3)i#MYdnH@nuY3b=*I4i;Rm)kutg?71!qSFbG zv-@jCPL5Y$q3e;Ed;en?f-Kk|>HYKd{(Wly`P&b2%E^Np{>P90&%gTc%?HxR|McyySoQ!eygZ>YASxguU7&T|6`b=lN0h2(^=;B z@Y4!1I$@+xQMm4}Mk=iWkX&+PcFljk)~R0!6h4`Iitvg^lEH0pQtsKaI=Ql^#Bw8v z2W%3&uREX|g9SeP^d;GP3S`S=);&3M_U)e~dU5-)6X2u{eJI1n!Vg>(F!`E7Hxv%S zjKF}__3N~ddkAzx7Wt{NS+t}pD^{u}Y7tgcXMg`)l#Z&Ge_#gyr&ca@{X$NNS=5x7 zkUQvjVD`H3$BCY4T!Bc)9Cc`K8o-pYEo$E+GTWt}KW~zWXMk^i3^ci>hj28&Rv9F$ zpm-ibR?iZuY@qpO3JBUQEJhgsWhN%32m$RCf8(k|^5nbxYBijpTgWOrzmR+jY-5M0 z=%pc1j@nm2|~yT#1j0@W&=-Nny>Oh=LB0 zOh82B4orDGOiLgVC1VvnCS3?5fRCQ%xXIrDR{8?#SEeW-5n4T+p?ez{5`2HJt@ARH znkdTYHUnqp7Zx!5urLJBRt;Ul&aqnS=4D=Q)l<8;cS$ptg zv|z&G!QI9P@^arvhvXlPE`0601pj@GHU+@gDC#t+ZkYj06Q*MJ-GH&<`gavjS z!7k9ecfFM%_ah^DawKu5=Q`O;CXuVOafSHtGe4%6$Ey*erli}BTuSCQ zuJB{Ijc?k6))q@k%lVWg?lEZIq+wscy7v@3m>z^Bm<6;bCiwc%K~r8LGVaN z4>1Bf=<8U4Y+vx3+CR&4QqPi;IdSTTadV*5@;#hG@$*OPRs=AJk4r`gWT+c!5xl6g zF()zMQW{Ra;oDF2{YxstF|Adp)y@Q@D*AfF2(WZ0a!Th#)_k=kqHEpS@zKoKM{ zK4_qK!5kou*Q|B8@aiMdC<(BqpIv<;iYn%bCYThpj1?e%5Xk4{W>j`PO2#tbyAm<0wIf zUsG5vT)ap)H;iMF+k#qr*rtCSvZ5aw*RNam9u8I=;&sHz!E`1P0lYHH&SENf6ADA3 zR9a2x+N(EgC`a!gvE}p(47d?<%Z`M*P<4bg3=Q8r6V)`xR(xg zT=+4EP&;Rv7nB>|se+!-V|(Kg5MV&Ox)_!%0|!SSO2dQvq6FPw3?7LJgWC{27lnp| z21r5<5XBu>kN1HU zn+(~YLWD?05UudW{tyXzz<{mihAKF2zDLO>dLqe@V*FO)QDDAVPW7IS9MRL$(`tET zR99brKTo56I=Mzo8zzZzYaUF0lDXyQ=TB9PG|@waV}`(sIZ)w0fWPns+3CW&)P4TE zf`T!*+&>Fl%pV0L9+S;FkpJJEh->T4JEtJv|9|K)P`hw}k-8YtndI{r6m0?E5YJ(Q z>({gJM}aK?nY$KVyZo9`9>L0=8`b?|4^Wymv3zp__)txAbEN8n@bC&hKffl_-0Ii- za19BEARO#(_6WP04*YFCgeBk4JWfa;;d>n3a?T+NP*e+;>2K8OSER%8qGPhj7&3b6 zC<~CG9Q!f@68W$&!t=9ntV87O+tk<-SycCI@+L0 zftN70G=RJm_E!1!r1z*h=!QTLMKdp9ZU)1cf-HIpzRhko8gAhv1cS5zAN>T&Aqn!# zIp4)zCxFHuQMlxqj#^qfsEg5v#UJVV3of}jAX7840+A3E8?0qNJr&YjrA`7+DB#Xe zV3Tcquk8dYB6RY#dHcgdNxz_>;_Z(=lsnp|o1`Pr%_^k7tW4eN%HY&(g{l2ovBO z3SWRZ(#HdB2kOfS#Plegn0khvpRBnf!-?1ShT6XX@Bss4d5&h)i$*V+MnC+p}on??xtpDT|GUwp>rmHpd-@&ao)yz=`6w- zPfmvbGq1&4!N7WqF(xrH_tFs(*mgid&i(t> zqg4Ve1auHL<3MYW3`E@G^uG4+-UvpeD?}T^7C?(g{j)1M2jH9Bad)TWDLwoHiN0;p z3f~#ZNuEBk6Z24tsV2Uxb)iExF6xYe^)f(MxkRG{>{hHzWVscLmr&eFK7L#eY>JFG zas#|pG|#$0`n!gPyrKKKe0Jj=0W@InK0)S$>K=yGBvr);4G`sVzts|C)%dtLl1!&Q zH-ASs3FER93~URuB?hxUr+p4h6Wpl}=+FJOa}7?sp9?5h|dk_6#t zPXdxhF|UV=Pr3&ngb1Z6=(pf;LNU#1_#OOHR5ox4E3iK97&U3-;r;UU>q$@|OAuSA zjMjZvwE~9@4HU}F%*@224v9aidX@LTG$R~1_ydF_bT2EL%kL)g;4E!yddB*$YG|Y* zpil7}iurFdhdqbdjjs>T?D`lL6Pu9-Ksgcm;JTeQ8vyDcJpcrAqCo@tOcxZd?#BC1 zLd5>t$zjuBDw4SIznvU;uXM1-JrJvy8e34vm!hQ`&)7W&Q7{RC_n-^LS(pUo52693 zj$`s8^T79doM^yMp3AR7^6M_YVAEeyf|)}_fzH$B7^FduNse9cIKmF3QzSVV$xb-7l$AVDQCKW;8g(&i{8*Yvqk(AR$Y z#IXzaO-`%Bs457(5j+h9AW5J;HYe<=q&;I|v{^WL1_8GKf~gUjL3L;|m8~MlHf)S{ zz#9TP==C8K?*z5Po#x#i_Z>y+l|XrKz>nRbEFq*72p$j2)BY*|ia?ORiLn=b82}XM zXF&bP6@t1mI5fobDh&|s&tPOT{Qvcc!Jv7`QopM08zN$C`0qO?$B-*-p=qvTZu6!p zKO@YPL<8mreegUHdmAIm(bX*;{R z;_C+NCrx@G8J#+P`WPH92VGWZXNZ|swaq0gFE3a;!D)Cu^GJ&SZ=wAl!?XHyqV;tD z8KlluK@!0T%YcN#%v=qr;*OUW`jw(oZz5<2YW5z-1~I^}0%Yq(VQvf00)B*He+x}w zBq9oZ3Yta_IzZ&-_5F}`a>+px8lV4>ym zZ{O0)kFi0Vn;qZq9qB=lgbc?9ieHNU)7<3#G>yC!6vL+U_zO}fxW3ptw9)N?K=C`& z5~8qglW<}rLBC-f$g~wx>=-Hmv0Mxd4M}ct9wEZKUoH*GQ6M`6KST=e3!6L>4 zf38r0Sw^}o;*eq|fi_F{?8HhV&0z97iPeYbr7rrPNbkY;S~+!ecHBnc@k6?YNC7%J zTx8}Ewuui&?7907ANmkdfe;}D<)zw07b!rbM2bUsRDz+z3TV~b_j(l8CwW0l z&Fw^yfWNB)gRnp(0V~h9d zUM0xW(vL81P;6`<>fz+Dk)dI6W8)UQj(iRanh!BJap>h`CTh=UQ^`_pAxbWw!^t7h zKGI1`nFw%&KaK7B$*}zLP5Xsev%^P@P;oDE3W05+6b`};BZV z_LQ&pLldIZ($CFkcmj>2f}~9-9V}q$IjEFX)c)%w%}g0sS$!~-9%I97Tl$L1PEurq zf#Bhkg9(xraT058lkn?(3$^La+qY7Xvq@hiX%xoOLVs*p8RemWY%@gITv5_WMm`?C!EMOX_M=(EG9hu z5}+^aA3Ryhz|(}7t>ci~2G@xg`x_Y;C-h8j5N$^E*)E&Ym6>o%U{{`o4N-ZO+kD zmUCHU3nFfc1Cx_%fUh? zD->24m<=R!7Fl9d6|JOS&QZ1mpB#I^eKyL)mV;at-*@X{76WZsSF|I>38bhoZ2Pau zd%|eTktHV1zB8AM@8KPUD5KC*I;(c^(Ba#vVOgmbp-|Acvmdd(BUs)9*jBZR-5b@C zx)>YV$1n-UsXJ6!IKGK=25I~Put-dLsCwfqvo7H!=)!nyvK1RItIEZT`uMN}W3VYG zDTN#7%x7b}RD;%~j!uodOc)7C2?<;_`L2~B6Tr)8LkT=+^!dcTGTHj%ZUteW-=xQn z-(h}K@j?s`BQJ=*cRKXpNo!M@(AQQS z*4)&D-l6y2n+x)HC+-jt5a>)a50cfSBN~PfrKY1pa~LjW?n%8*hshw-2D|oH?GE3Q4cH)?SI;nmNtFaQLVrh{^(IH+8dfd2^{;-3aJn2s9*}hk02cS z2O%Nv!o16LzJdw$_x8RIJ6)@SfQZ7Gj~dat+SLFw(-!ggmHU8U``Tj%VAw()Cssm7 z?f|yMbrgivnN<77$NA@q&SGK^5#V8e-jfSv!6W2wMCEEmmW9gURBNTcToHZlw5ni!9 z_n&;=U5q%`071Q_}3<5|^(XO9LgEI7@)-f3d=sk*^Y!n`ea zrGd<@khtRl4m%cJ=1#>rQ$$-4InqW$v*lng%wEucHndt>NL2ngPL+;;bhW9tpx}LM zr>Fdt{%fb`pQDpePG)qaI}55MD7XSFIy?6uI zM9NwFw|u_@*#PciJ$C;NyA2$Y>yZ4!fpDiK)VU*RB#{Nd*%_p*VD9JjNim*l%nDtJUBYl)~Z= zvm3pK=1(pOiI^7)#4`fJLU4dP<6}3{Bkq7=rGSOl5c~F%<~m|c01;{9pwh!=DkWk! zcCju@KaSV25O+wI5`l0iAUdc@B+ZY~<1lctUUc^#bV&|oZ!uE|HWx(V4Gt&Clfmn= z{Qc8Npd8>dGq7c@8`g>!yq=V6Zy$w=_M(lb=d&epuU$ZWL{9-5*xi@}yBXuR=H|_t zB=&=1ERHaM4?fwX@;EYndf!olt$IIfbirwLL{UK~lNx`-rl&+uKRkhUE;0(3CK`o!3V=2{aX8mL|L>?s z2s%B#a1&NPJ^Fla4Ayyk;{fyk6O(V>`{2g+Ym3W^Kq}}Yu7D8Z*z*X$pEOD->(a$d zv?zyymEaf_N2B7fJ_MT}XrBt>6`Bp{L&+ju08(jrgk9!kwSY!@vB^<9vuqlXjh89^ zn{I+!K9@f~-;bho&(H5Y7$=E#Ugbp|hy)Mu2zLlKM)Uau@KCsqCUKh`eO|MaS};@H zU6gOg?hR;3qEOhA`VHP6cqtY84zGiz{sRZEybzk3Ax-F2Ri#io2+kzL0UOIZ)Xa?Q zpSEkVNXrdBu5XBtQXJ?JZ#c30A>M`$hJf9BS;%@Za}O~_Fs3uBQ&5AIVpD@ zvIprDLl&0L-eCB1>P9RMq}p`AW7P7jcWV|nc#!4~oNL(j=WU;v6wov>9ieVP|4|J; z?2Tu<^F*0+xx?hy$jEpHz{|#{pYlO*^Cg$dH;^+Tc{_X>3f?^l;#U^{tlh% z1oC2_ls*Byb=26KA89i`v3`hwG}#t zM|H4w(w;#;WE&9BZa0rPSO*koV45u**?a(cxi|k5wZ%P04zt4qs6NkZ%e7gA_R!H) z41Yk?Tw9w8{26&U<*saf^=wlX=*NVrKw^xCJjX1gw|ex)k1giMzlxUW2oje7W+lPj zC>?DCTjZIYo_#vMEMKL!RHuV}2$-+f9f9S|lu7yaDDCCXF0E75w6p~+qc_WB6@R^gR z#bB~wOW6pMM0r(qbAs&Jj)6RM?~qOEe$$8N;!0+7xj%xthNPuM~o<}_hVSoAi@ zk73+rK*1(`o^!fRkQw3;O#6$#MsQv&PVxAg5(VOrf6X(L78AqHuSSj$0c$FQ%>#P( zX)O+H3YtPlK!!tHl!%J>cwT6*i$`H4!Ul*fDxunNesJgQZmQNz!8Zz^!%*w41M7Vc z45t6pKQM40vHH^NBaP3o;BpXItJ_bWufoFmpr`~xdOr@F@m9r#NrO4%`FlMhO)VfR zD zb?d1!XTl}j3VM8Qw z00Ozcjhw?j#xJ9r{A+GVLjU`&u{M4?z58>a*#%PxQct+wT!XvT zQ*;=R%A+B?=l`s0%pEC&N)64&C)an31Q+Fo@3E>;`c_fFQLJ5o3ybVxqqHk1Llia|sD;`cFTa zVd&@=s0~E5fX!hg#jWtDAi&r6I8H2WpjUw{ehWv!Aa*{1(8+}4A$hJ}T?vDN&o94z z-k`{oIXexx5iuD~>^5aD27nW=OZOn8D4(PL+W4ZT<7B>UU`B$O{PLB>Tx!n>Nj^Ts zAyMBJkbV+$A^n`>2)737I7_<}j7B$h3n)_VFJADX-Gip{-SuA7XriZ)pnid^zrTNd zroKYQB<%9fv;XvBg{_8|W^K^#Uj7i%)$=W*1t@8Kt!;F7+%$KFU7}QwJkfP|!p9;#?Fe{%+0N zvg7u?v^UDj%HnY`!|v>~!H6fX7L0Xudz7hF7SM`-xF=@!U zcv{`q7!m^tLs`CXKSn9Zy)m>2^>-4%JqST1rKKwnKWHm-g6x2E4Bbh%fb{(w5!<_cD=ZyRZ*2MH0lX3ggYojE*Lum=7r&*vD|(v}GEK1LV!U2j88- z!MF9Vj8urOhuyy%5)j$b6TjHI^6Ag=qBjy+6FG1Q5!GA{;ay4_S9mJvP)oy8hE!b< z#sNtjW)S*xc8yoR#+vRB#eTVi$#)~pPn=UQ0t%-TLxSv+T=Q}@eglI%w0U!hEZDd- z9}~dSCScC~s_zJQqg|jwa6t`Nw+sM@oOy<(aw3b8KDw>$iHc$;iD!d#aChOB3bGlA z@A>C;FQ|w#M%+mel69?-bU|u!gO*=OZSC2y@FH?r<}Du|`Q#r^x;^JulrKl&kTC1; zH~INGfG^~9B@4Ses82T43f=wv<%vT)V$~0KtxD?kDuZ`Q_T_%X)!5ESeHzc&4IY6A z#s^66Xm`uyAK1cqx=;D1+!@4fqR~X-Ps>6keA;&80$!KaXdxc9RqgS|3RJ7$V^ppD!gK9qJ(UjO-uS zucO$HNA@HeMqw(EzRNe`7Sm6m2?rHAjBmm&YYj?@d;ScLm=Q+QU#-Q7oS}a#`iWym6Z~8#dep{Dd37=e1(w zf)kK5`gn*oT+lr36IdwOzg>d`iJ!Jne^{kRzV)OAB7;uy7dYsq;HUQ{2-t(b1X!nw z=LfQ0WyqX|yG`P_;2EJ01v8(RyvH#g&X(K=`H*&XfCl~SX~dFl37#CH{g*QN=G*8u)U-g<1ZJOxrQ(13;U4Lo`MCW5)(`h9IAuQE z1XKZy(gk+76U1tMLR+&CJs(7wglZPzRHd28j-Uv9By#FRTj)&L2sdFJusq9%#P$G} zQMi2G`XHF&3*_#1yx~V@B7RYUFa<*8H%yX=W?Eg#rQfEr!v-&!WC ze))0&Xwy9C9Xdu!!eXUvZbvZZ+;e(a#0MzuZ5+bY3fNA_(P>0`XXhwqMucXI`3O)F z7~KKe{zsS$pb8h_rPQ;e7#jP!d3=Od}r=gBd$!L zbgt@$G6O}m1VLJyLPw#KnuB@#et`{aouY-bXF((<7j6Fb;@ol-Szv<;!tE2P>#irQ#!`Q`coXbBGH(}%mO@shoNT%{1 zL&?u=JLa}HH@0}7(5x6#HzE)OU~PlSg!}#iWa&{*9FJdLJt9Zjqp?JcKdmH!ixdx)$11ZCKq*VDENqWLZM}f!bYyLP6 zkHWp^vR`sc{Kg;ybT4Ws?Ayd{tcHcx*>diuOBI(z$_}zw0TSdA~3)8NR6g2b9XyGK=lT;M0)#aw$=RYfP=6(~qf zF@$(QwlIpP(!*~!e-kyf9B46j<_&CkY;o}jjS@KmpJ$SUXK{)J)UttL^k#IEXe7ca zM5Q8B8-il4x`5?mn?T!}pjI)3nT4ebY7_|izJq4o@1YJ%qR+IX zqJkDF3_NDiYYJV7fNFTPyrG|uJ-`}%htA};OS5d~4~LEHfyQ1faBfg~uTo*Q%HT(j zHh{gL-Ix|7*9(>SY^I*2r?o!8z#>5&&<|L~t{1Mvmg2w(T!K_g zY*?IJN2()&1!!W&;cyIa=sbZ5Lt6q)?J7m2G;dDfG@Q38(`>@H2&n+q^g6Zc76elQ z(*RD<5fFjnSYa3eTF_ctdWp$Fyfk8QcD%hAhyfv%>i@;spT|?Vwr{}rz08?HNQR7+ zF>}UbCK_a(EwgAqM8=g&ndc#8C^FAUhO&$ap)zD9L?j|g$nU)C*}MJy{qg?se%?QN z_I}!nwbpfC*Lj`iaUREUqFEc%M?I%6f1aN|Rs+@%7Qli-g{?*kAj5#3I3Yy3R!E7y zLcq9|4(kF^L`?P?X)xNH3*7&OvW=kAgA!xlL)Zejq*1sh17H!*a@oM!1N;*PRUkAG zZv**f@*o-vQT_q?7tl2IzIBTeaxSQwp-}@MSHjz?1b9d}-vFi!)FLeWKHx*PLsB<0 zKOX|y4m^J$dbB`Bf=XM@fkqfXAsVPiX7j;Hr~WngR-h8W@mM>cL@iu}_~bKwa2nig z(H1UTuOt){6yT;s27M%Dkc6Ua+iPrK^+L&ViV}WK4ca%TJl5YU!hT=8^nj)xr5H2o|w$ehGr4H`}evYK@LE75drs1K1W)!9N9z;-H5n5h= zJ1usuGrpp>_9etNRQ3y^pbxMyv;0uT8_E|$+mR5SLLhyGJc|~RU*MCXy@*CUy*+wu z!P_&*dho)_`@w<t@@O%L>N*C zOt=Vu9Z*gJdSajfz6K3HG?4`E*bgAfF*pkVA_wmtx09}?Z_jyq42(~ za2HjAnly?@G)RhN7|xXl=7;6p97n8f0g;0nD<7&K&CHmD;P5E*foT z1xEYN(x0IG6nJU`yywmc9JmIS=v>evpI%xbhn^^;(Kn{-H623U4h?_TkvYzA+LU0WY4f?o0(3H>z zfa5Cwv7$6k3>H=t*rmUn0V`n5w6BVTrQjaOO-mrnfKOZnDy9mw4UK9(XJ#%r|IX^* zzqLdE(*&-I5h#k3(209W%P7*zuB%4q;o zC?bJF8H=`64}>T?V6k}M^&1--zt^Y*8Z`8}>`-wklz#Aaqfj0;WCkmVqu@q+3hhv# z#+oR(77iuKk6|BtJhvyjTE4gglJC2otCJ7p7N9ix3`F*%x-(#%3VKp8h{ouy2Ku`R z+ylS+<;D5uGNMGc0MZ@;Qsd+D@;)HWx`2AS!EH9Qryere%s&||q!l0M=i5Qloesq( zs^J9)#sO-r#x1asX#oT~9cm{+Jo?;)gS4;bJrK&On9k(RCi>R_QQ`aY+?TFAlL zx*0+>z*2*0U}X$8oij_F4OW*rPy-U+B%suA_;Nk%?IA$@jE1^7w3vHUKFK4nm&q2s z@qC9m5J|59NlXyBvPLiA07GHZY2Nh1ldtmDhQn{Mqm4}qY$%j*j_zCS^XKOWGr*A) z)px=ahna~Jj7dudzKsb?=K&h$*u9GP88M3`bPkXk$54MLpv|glW zak-f5H2U9KxHy@{Cny*N8Cs;=7c_(n52r#_tnR#1)ggcq8{p`{a1VnVe_j_5x7dKo z;P^I-jk0=HSsgt0jA6=4?IjPa``U~Ox~jl0PKU-2YFWCvE8g)Q_)+M(R6luQ2Vz~6 zB~jz_CI|w<*=Poyg-1`mlG?Jz_+I|rjT#Qv1D^Domv5WD=U^OC zQ3|6riZaD)?24teyjAx{GKBbZ8leH-rI4e54#Mn)v$Yus=*K^&h;*<5@> z2<%Zs*7kw{)Yj4d1 zpAL3u3ozl7n~nbYpdi1exrd32>*EDa2S{4nQ;WeFx~Hdv)%V*bBy8%?{l4o7w8f?$ zBe`(DqE2&PJR#S^Ub|*_`!v4^5L8e$D`;SvK_`fMF9JOTi^bx={Gz3;E%)5hjl3o) zl&S@-ECdI4B1XYGu3)BZLi13f(l447z>1#?>v%?ZJ9v_@Fw8%pP)#L@te zU*MU>u^S-j1Ae~qa9K2@W!7-Lp*?TZCI`yE)K{mVJV%YJY#{%vCa3s;-jWcWpAAC} z4hBr+aWDRn3V^G9-)~2*C{QlBfwH8o8}3-B6f6SReny~zQ%H1#DtqC!6c{WyH_r)M z2f8CIkOjrZ#UYTC!OR_M?G!=a+^eKt4Vz>^7qjrn;;;POvu|&w+5wyZdeaNr9tCvU zU+GOEI00JU^{?Yg<)m18VFYBN3*w_0N(WfpD39c6q zKD!Gwas?qdAONx^Z{-D`v;b|};2&l0?_H35AV ze>PSUMF$fcKI_Yu4=^zJq&yOQ!*u8O`s=Gpba4E6jh_H7vdj(S1`>G6<%`$;JRe<7 zC^Coz1d1cRbV!ACF#UdQuGk|{l0Se-CbxFm8?)CN)!x-L3+ywsiDN7e_oA#o4H8E-xhx8_gp82>trd_l&~FoF4JHS!*%my_|St`h(A7w~C1Q$zosMc)5s3IADU zKOR)5{%4tW%K&!mhs@yrZ;fblkN;hzPAP33Is=cx|NMgAKk7I8zZc}nhqo(QI;edQ zf(p|BsBn;YanO^)Ad(&pZM1fdQ^uPC?~P_IUS7Q;DJLQ!u* zz(T>Vi~vEKjXZSdoEM0yt&owREpV{I$_7LU7ze;&lAvK_MQKgeKmmfGOc-GOqB2{M zk%D<)*4P%HI;h<~I?@5M$gFu|8fAKqZ-Mv+XK>UTIEN`CkL&+=0^5S<`s?0&JEgok ztXiO&iDN`E_J1uA;>V(Y%o>uGRNli45;8xEP}rkUCoAM}e~X*gOcrVi^N}NZhoRlKOulT^^gn-@H%tm8QY0i5QF~BJuU!*Fc=_F^rw~&$d<|L^mkCmM`JW8!R8Prqn#jPI7JDQ+!t^ z-e^&zWTk!ki0MP&N7z6_Uwk&cPv6yW91(3Xtq>m!wYVw$IYHPq+?4m6RsO@(4tBS- z9Yc}9JmJX$oXPl_XvLo_jdlhV3Qck;#rvVwMK3G&(xomaR4KizXUwaGz-E;Lm=g*? zxw^UC28@7~zh0OLx$ zSw2*y_Dw3mH1leiKi5{r^*KH=V^=S^?fox`{EiFaIpAJEw)TzQxKoF0T}+2qkpVeR zcW`z)($o0n6Vl*l5^Sy`Roe2aw3-OfX)TWTpJa6GiNk5ktc$Q>1U^2t1ul{W1-nw! z+HGzX&sF-5NV&?b(EO?e!ve}j=~j?|JlmC@9y*2KwJupT77ZOZ_XA-THF|S#lQp2} zvnm>t@(v6d&?@vbv^*{41)L9U<^YN%4em3*d;bcY4L2Adgqsr6RefNNF)w)7S#sh+xW2{W zgZO&a83F*Y$id(Tr7S4;Jsa?ZUP>7JdS!4M0Lb7yWcZG&CpfKg;XzM3k&&;{m`;as zriGO~`uOnEcQelWjMPKc3aZTN1%-5xSBog#eCy)vv8pF)px%pK)MJUOE)ylX7{irX zICJ=oj=8%f?)2UQ7hvBegYd&fhqsvKo+3?dJvg*3IMs6 zGehr9gGb!i52@vnYbzMqW_l967{<>k^QQuN(FO{Ww9~$)P^k(EY(r!OkrHerdwWzR zhGuyoA-hMG0g9nLeE8)aAb6i{th5-R8xGZ-LqjYC`n_m>2l^DKupcURxBXxKs^I4U zI0Y&`g!&8Mp*PU&GH>*zMR91aFRaJUrQskeL{KMq6q+wFtEGnSM?2t`pjQiqy3t^5 zl1@37J{*@@&=T12jTo7G{vzyFVA$;9o)p7-(f@>^u1O&psfKPGwIfe>zfX1Mz#4eVI!O*9(xsr`51%SK#f#~hznf_`5QGEGB1%4>2qCU*;o<*0?=Eu59YfOZ4eF?aL@PrFVp@ zE(e=s`$h|#IrOhIP_H1izKh47D;fe;cnhWOX04$@W93>3oq9!IgJ8*r%{0TB9_0dNsf8C%l(FTjUH`Dy7WY}L&4 zx|@O;)jQa8h0I^)j3NcY8GA zqJc^`$+HuJ32xlDFQlnR)qO^Ez9l|^VkX6o(wa2 zjZ!)nRh^jAqb_=)PR3_eSXXF#!;vcCM#8Om0@hT@!u&Bs`6mt#Y6QmpGflX6bgLm%%EXp(K_0em`j7mKPh&f#PT`h+RSr$B^LTIKBaEaqOquf8I#hk+V6@1|AZ8}-! zY;%)~7#mOS^>hAmusl_KogkOY!?z^Zz3sV+tp09EzWxeZ@;)+~K@ro%eeNYmw!$$p zYt^l9DLkHF=9JiCU1cr|i7CQA8-lNt95+4AWD)3L;+agdeuVx(d@USX^b&+D4>gMh zm6rKOS+tb&+emmsvF~!_AmS}>DoE7wQCK2L?`h=Wq@$tvRM*?(vEAXm3wr<7ML^m< zrVn3N0d~B&2y`L8c)~O-P}c*P!KEq+bFyCf5h6?$*Cl#tB6FK$Pap0)+g!H0g*8~R zaTU*4Ul|{1S9FlynybAXVL<=%ce7vga#M?RUSM6dN(vh_)8XvklN9 z(dRcX2%iZTkK@N?O${H${&Fp4qW#Tkam5A`hIfbmUNXAY{1!+GY8=gO4h6J*ZvZg@ z&E@`q0m0ZWw7QQ~ZD><{T*EhL7F`xW1>{Z6)5djhDJ}gSVbhaq$ke^3^J8_X2XO++ z*`{$($KGtd@luq7bip#&_rUiGalaF(qfv1YNr_p6h^v@;(Dn0HNXX>_gslYed|kns zfvcI&8|OPxzB&H5)Ocu|D z1^9P#Qi}c42Y~pY*)v?pDP~~+MZ{gV{2BNzaLJ&(J6Et#pr3RAp{ViDe>2?H@Wj0B zxMScR#`tU>#r_ypgy!j?@CFJP=}_;$Fe>z)WqiSJ6u^O?)fco~z3ov$Tj1dkZ-&S9 zoyebVjomUWGG%8}wL*|_Mmf&I%ue(A7%R##UjpP_k-UY#)2OHlqMswn|aEh{yT zthhdYsiw8=D-5^E106C8A`zSbv8T?2F&RrDd0OFPA6v!jAm^a(1re&|5q`o3Arv38 z5y5rhIHG2!qJXqgRRgtTUkj5vc04!6on{` zV2llx2$1^*HXJyn*s1k*rS4g`iN77u)HGQFDje`-ZbNC^4B}vbFx#OGqyyun5Jg~S zLiPUa=k>`(z)`8dBaE=Ey&auQi&o%}xHS*n1tTNqf?le2I1dU309J{hPkbl+$m;-r z9&_7lIA*WTG;IpfBqoJ?7vc4LuzmD#eaQFz1D~c85yR2I{XUTbL+M`PweOYO1(F-m z$5#%hSiX2hAgA%SSnujK$_iQoFcqEX`P~P$0fK-s1_eZ+A!9DWh(I2L8cL%SnJ{2p zwg6)Vy8I!vwO)1KAH?;Yr=!U(EZXLL&Tgyt?HGbLaAT8rDjBb}XLM3x6D))|z8qyP zRGq$X&VrKg%xR-Hh@j{p6}7d&mr)7jX(dN0c*<{3xC>m3qx>%O=&?!Ro#S}~-#)Zr zkc%ds#)~e^ie~CQT6!lG4G3k4M=I!erq7zo-jhpnk32SPYA>G|>~{@RfQcFIYj8a_ z4g*^g8V1ZcS41ZJ*$^ zhY&eo#kH$<>^lhO!hcS$O-L13P0*;Ay-yzh4>q^Gg&zH=&6-_r@}jid^)CovV*sM{v)G-we8_$G7J7}ND&=)Xih^&##V zQ0olj5%2msd2#>w1vTfqER44H`AFYb!wwwhSq|p!b(>R^#n&rxnQ&Axq>B`=8ZQUu*1YD{~R%`wx(rOPBr0j%+)0o{>Hvy|i$P)1G;9k`$4@ z!?2zm^K+0&Alq?&Tllof>Ewm*^Dq|D=HeNb!plmymXSJsTP^W*`*|_WiThF zC}`n8dbnSzrThP&=iit`F@VIueyw)BI0mnSh^z1vBXbddfqjk@t%ZPojRKPWR7+6* z5^krGud$t|na?P|?MTYuCP%{*4u(5hw`qD`@W3*Z382`~rfIDzUn6w1;c&xUyYB z_&Mjy7-22|u%+}pq!0w)zgDn0>h^B{`4iAhA--R$yPgr(cR@@%sf>8iagIyaD(Xse z;P*G%G9m+l_doprEFj_YLZG<+bMLIXt`2&}TU!`7packj8b+$Ce@$jqk$@4|zhsTx0@p0tGH}--LirbuZ zP%JvfqjVWL19pLw>a%$T=OPFY`93L9TmoUmISRsx&jynO*l?}RIYxu6kwI`8F9}yY zM(Pb74nTZN)w>QbqnHBG@#lNOc=G}mywE9KVLz(?IMV3{LiPtm2@%y}c3kGWoJjXX zFB9S_E_+w%9pB&Qvb}|(>{B8qITRDbgaq#HaP1zb4t;csm=ue_fv0zNOqaH5I6P!TwWnWwW)IR2rbxIbs~sBXu8TpZ7TKArFA2TDq{Ts4pnNw zxZr~CN5;8woaawxLc*c(|2b5hZf95sz()&Ixd1GI$KT1y*mgad-gI$N=qIDyLnz(= z9Ymn;&dm>eX0-Y3TN})kMQs3?n3(V|8xS%iB3pI>K|s8LBG)sP0$pZwS}M39R}&&A zGz=Y92#^tM`pPdz)Eq*6GEBXNZJo183+N{gA1Pv-)OhT_f-yF^3k%M7{}ca`|M8>R z4tSsMWW9`|G)2W+l4il3KPY9Q|GoZUDQ^Ek&bKx5&iPuUna)4JQ=0TENAuS+4AvYh z8Y0w@29IrBMzI?kIghqy9-XC=SI3a$K6JyJDykx^;J3Xe{Ys(uz(97{L(9TgV&Q2? z8D<1M*rj)=i3o1*G8ha}+^L|;YPLK^-Dlr}OFq%7a{C!l#9x$Eyb~N(PGzg8mgi_V zOrrJET!0I3XFzveqHcbW;{d^J78HbNdSqi`69P3N~8HhyyujDF^p>u)3V>t>= zG%BY9XFaX&iE+Y)@kogmU&!~f2H$FM=PWqnj{Mvw#`^DxW1kD}mOnj!OnYjbnylpK z)p-}{9KblB_i);R&toILD21%h8xUlTMr@GTo>37i0)qT8o7{_o)hXI-XM*JFQ zU?fRGgNgro#I^KVr_e_NS$=CDDY!0(-a8e2)uS=|Xp+UFl$l`LLVV7!B`K$FTaCan z@gZjSFwQ{tr_zB#`7MZ`66?cBZ8%^dFHOzV8qV#UBioL+TZL0gVW?ionnak%{hsE) zfr8=g=wyoM^D|K*Cr^fa4*+j4Fp@*9JeO8SYbapi5F{+~K}O(*j{2`cmj@lA1wGjg zz?0tqRS|@-njv9fwm?E{L`uM})Xh@?9dQXwqMUpq?ktDA5&5`Ia|its}ld>=NYQ-~-8 z-_EW>O4@rW*>y-z0^$26BuZ4I;vmLY`A|3od0bp3l_(N#a+U1EHA1)Vm&P74UQ>Pk z@{ttZ;>cR7gY}y1yIgKvC`;cwd50qQ61J&aWs8C>kqkK{zcf;gMO@}>T(#$|}#k@aJ z6--*dLp%n=Mra*{65xqt<`)(~orJ5s0H~cp;VR^5jRC027GT##SsI#vsVzAPIFoL0B{~u2RzVGW|E_!)5R0`m(&Q zzF!)%Des#U-kLmd>;&-(4S(9yBSywpM=I581YA-|#?=*_7P?1ILHqdE>P3RB{jWI> zg#FL_1@OY%p=A|!J?$H%F`NZaZE3?ddt#YS4Gt584k>nNOOsp9z8dqG{LsbRuk=EG zeCO;WrE#+B(20{PlYzGrk|l|Ac%%;^!M98lElJvFrWwS;YAOlN6dW1BAVm}(Xfy7I zjPDXS6%{J0WfKS)2+h&Y>31zdkBq=`r6s+9-+7E&*T6sxWB{m}G6*0!!T%I&ZN$s0 znod@u>U&@^L61(b209#+P!AzEP?lxGPSqXb*V53aG^wAvWMs7PoRN$Oj9av7z_1C= zG@E=^)#_Hgq_URV@`MmzRH>GgL~ky?2|ssN)xY|u{XlWmru3(;VbjGIX&x{}7Yy)9 zXUL{1mH$26nre@J-`VYVxOw=A@MDHF4b) zRx8mtZ_I=a8Hp#5je`fyBPN*DS#A(lDMI2*U{0zqwW+cpC=j) zLkpuHxKhsDz|04I6YAs(Buit<1`eaIid8_%ZHAe{6eMU5+k8BXBO3N87#q2jOG-$f zlf7uxB?Yh{!#5V9&h>N>i2S1Vx!M?YcvZaeRvgPcb9T};bHe(vkiN^dZIA7&U+Q=b z)bigya=qu1sCUv2veoJ-qiM^eb5*gDQO;PiITa4^qfG0EPdXa5e{WdDzcN3(BPWJk z<-m86+-m)$7J1B(gHC)`JcmJ$DtMgIG~ssw|EJ3B9KM+MP)?C-+s_-ry?sm3T>_b| zd#_t*V$v0PnF_%@nwHEwVYkNUCcZ?kUv|W^Gc|9KQo~$vHjv+?pLUJ2Q%_95*xtWM zE9OppgseUYZIMgF9}%2$sB+!1TSO1;7>=p$kU}nJNlA4Cbdae)?*8(jS|oa1piF6S zV$;;rRD^SF4L*8sLve#uE{M8;4&MSyUu$RQ2xumtH(hu{1nRPedNH9CTm;p{14e8M zJWKDN-}q3)0Nj8jpdlUqE(}#VG#FsAC*_yl#A_Jx5Dncqexdj+vSyz!l0u?HM zrigYCJKT#j(k^49$wzq^zc&xpo(11ctmjg%Gk0T+SsVZXc4(agZEd=sZpE2k_j=b8@ zb*JQCj`D1rU9&OFApk{7~&Ke?seXg(OnaZM|l!cB*48jf98q-r3v&k zB-gryo3Lo38b%eOMi~IdqpqDOtqT}QsPQ-4{&;YngPTto9-S!obb}RjeLI<_)6Xg^pK2*0YoRr26l|w^CR)vbmnLeZS-}IMtFFXoo^m-DM{aKrAByl8l=hvQ_aC#h3LY%$WMu7QY zql9!{2Lq;i_Dqv$?bXBX)lp#!D?U zOzoBV??OuisKJz=Igkaa^aAObADCOWR@j4FWgp0|cXG>rZ94?nOa%0K1N+PG(Cob? zrU_RGm(S!ov!)Cr+VQ(wrMAGlW)-++)bi`p ztfYzwp759Z8e>qIQfultL2>4S+94KpY4-wkJxks0@nychx2cZ?xT40l%SLfXs9+?M z2(&^au}3f^XJekn;jV6S#uV}sxl8qPibZbL&gnncy1=Pj_EbU1v^(<_%bYW|s@1ks zCdjqi@|+3&&e+JEl7?1dHQVgVa+bv<7T?}}_6NA5Gbfd?vYlvg&CA)f_m~p4S9C~+oj$V6i|{+)HIhm< zS5}0#ylaz!54QEoRD9yIC<~3rexCfwnYeq&sD*GOS*t`_oiAWUJvzvaRGJ6oMBUI_l5D&um0*V`%z zoP`gcWvW);)QyTn>as?gwP*xeQk8YpQ!GH+E`=~7^XD%$@k(TA zG`v1Y(BAsvHK0zk!L6KW0}4U?=C+x%cxUpL7~Wnlmas8QNuNyB0IQOdB)0JFe?Re6 zJE9yKlOAdf=}`@uFGJc#^zMf}+cYLdtcB_5HV`lc|Kp zq^Iu8J7eEEvwV|n?0-9nlPor(GM>dS<$rec(j&4MzC_>t;_8i+Qw+-CzhK6K7*~85 zy9QVY?RaFu*n_Z2F3ze{23}oHyjAauJww8jBX}(qrN!?|*U#ojVNJNn#AVX#YW*&g zl2p(k^z-SMl6VKCct-nplth`A3h#v*(lL5&H>LlzAy+07-93wFhYJo_3mTdtE?166 zvp<1N(P!WW`spREWvo^4Mwc>x`Iwn^V~6PH}YsUBBS3HEt~1*GQ8?ES*gsUMZwFOPKO+ z1**!JKpPBOT#j|-+(B%#-8prViWnm7{i@ijo}3;Qq;E$<+(pK@#5BT0W-;zHn+HZS zvPzoXeQPpWzAk;(xc1J=#xB~%Cka#ew8683d&p;Ju@0Ip+idg=LKBl5f(!N8cuST7 zh^(bxKR>*;kXYB8+lwh7;3&m(JD$QaL=&rpsFDTk$UGcyY97@+{N#?qkhIFbNARCT zbqM2jRbIA4wiffEj=qW1!DB_wu*qAN<_V?bo^*=&maug=9#gUw=^1z~wHs4H&3SQj z3@>59opUVoip8DRK7Q+;n2{QKLakK-W3|~R;V1DLNfyx##VPV61d)J~T~aI+_pkA?+WJjBOXk+zL#~uk)JXZ; zyY`>^n^S&^A*u-Ow7DtGHA=A9=Bjs5X;m3>r=1eZ_DN*a>gnJSTe4C`jgz5fsvj#_ zgopM-A57>Z^^^{sSoCW!Rub$iZ8F)ZJasv^_h!C2qBD{~8$3y{M$eqD$NYZ8Ndo)o ze~Wuah>-|CLycR?emak*4K^e+Bx)KaGpkXPi{&`yoIXZrA8YbtXi+Hpn2r2Fj{tkX}OFpblWKEGvqwd=>;@ZvFPgAm$V zUnU=1nsGvkl6-EOU<8XX+D8ddj*Tc~?gw?klqEin^tYcKY*Cny-?+A=r zInwMxS_hKqu3f~Ox1PO)jqeM2$h*Sgbr{b~q9p!zQ@oL*!_#p^n&i-4d`63#D74{N zdG|7%r<|!#eW%;l{!GI?yWNyd)}g(=*)Cp-3kA@{1XoxH4txx;?^le-g@7U^^L?m>j7)m(|=h-s;io4 zY{*;o@pXwkf*;L~RW!(!=$BCyo1LNJGYA7;cFJH@f^eIb4P~{fQTUV#hDh-;)JxEF|E+u>f=ZPhBHbsgb;v=VKdGbEB z^&~!)fL-wKGTTw0dm^u7jR7a+6va_87|HbM`?R~=V%Cf8kKd&8hK?#NdOnGr>Y5X! z=V}W-k`*Pj}Zj%=l?v<6Vs2e(>UzYCq(B|D%kf4Gs$5L=LI^nIyfgEzqsv)@b zp%4E>N0{3d9To>u*>Wt^NzCeG&ju07sYGX}(^oR0t9**+&!^q7>xTa#Z@ zPaY~E%r<0KvbQFQVSkc#{lZ0^El=hqVm1|fWy<5lpI*&=t{?0?+K_6?c|^`TX_m_P zCXLWhg6s>z4@HSDp%O$L$VO|ZI{JyF8_2sh*7fj>IP!wPRA0*ci~@ciG{ z`f-vr^4W?d#4XXRCLc*TScjuG68@WrlyG7MIjfQwnB4d;+;29;lVJ_)+!2>HZ$w?d zbKq%5_;Fot))mfBbBfyV9$IZ?C2j#HPmU}Zt@fV{-3(ic&!05CGrw}BN<&mVnk~lD zXU003gY^+}X^3wI_e!l}%tUQ4&B*M*z#oK=;I=MoT+-ETF>!p*eqLN|vTU)v8~ zq9<0nR8Uq%f`uNPxyKtddIkoVPu>Ft&3%9)$=zQ7*bueJw=7S66svI0YH!JC%MCRb zzC@qtzhwd}kC5SId*DWqT09#3{B7aPemYn;B*G|-+NQm$Ei)njj@W^W1eI?tmo>!b z7o8SF2XTIB+_-SEZjKI=lZ8b^AKqxNueeS^61Y3ow8sK72ECtK#>jkR`n9`ohTY>d zT(zJb7Q+2MHy{8wOaWgMlH?pMeVWu`jC+bjfn}4KLCET2F0qeS7xA%vW#k z<=%<3}Rzd*q%EyeoYEAI5wbZ z--RWe3qEvV8g{^kdoE?*_L2pa-uR2pX4ju5gCmD~%YhTqn@4|&%CJ&zbaKb8L9G-6 z?+U7NE~uMo?rE7M+0J8S^^eSnhyzKt?|u;EB85^0`}2F8i8 zv)?aDWEQ{~^s6BhuFIn17m~eoxtX+e7jIBS(gqKWvKngk=qc(wBgWBgf9XBJn~9V* zUO~NGY;Z~xXJ!rB2{eSQ@l))6{RD=h`Xf4mR(&e+S4X> z#xg(ETmAx1ve^t{yv%3X8!=^G(;sb?53%|YS)ZI>G<@Hazf6?uXY-72MVrttn~t6# zHPenqXyAz|lUcfNZ9dJ1ey&$!`MX<5oOPc)H-_U=8MCEfh&OY>D;~g)ZGl9BfY}@s zlGUdn$Oz+YS|)#`J7y}qlK|5@hp#ezX#BXP8>LX~2z`>HSX{rxw8@7KAH}y{a+N!0- zlmN5D9gZo12t0Oh{_E}w*b+w{|1WsW`j>{)DzMiF^AjRGtp=-GXU(&TYvdFZm+13a zR|s9_lZ{5F*xlM_(aQV2-})<}JI&O$3$k|SPTcq38bLs`hw}de-~+gSOm`fuT?VuC z&nqBheg!_`8*R!4)ez^a7{y_??HTj4$`Gl!^vN zzmm>LqgAbfTWZ}&0c!OLdAwd66aa(UMC}^*ElG7`IW3SRTj*gJ%Z$&QnURQUwT+|Ms^yYw`+}56MSZo0%ij(ZDqA-{4F`fB6c612AmLcE8yXvT!W_4iEHHrA z(=F7`uj#N6)dHu0t9xACgV&GSGtSA-lS-C$Y&3U$LsE*Eg^cgI`XU1K`9jV_6`=-% zjP-67tQX{Pl3eA*B!c4JBhQj6+iyYsmiu`6cy)RHzqL>BBHQl-=QD|5yEkFOSw5cI zi4j4R*YNK3IavB9U#y?#zARJc#?9aOIH@TfZz3zv<=G6`fr^k?eVNw;Zocz5K5npg zVNhc0vO1Dok{xS3-14TsKI4+sX}DLt9}sug&*@~JCv$UB$d84iL^WdnJ*jnO8WiaZ zE45P}Ylban4>$cFuAR8avOMJZdPMntpX6Yc5Go_7sjy zdPo>XO1)era;=knI>a0CcHY`>y6}YGi(meeY~YOn@fmtP4sgRJrKD8B2tatu=jD&C zR$RSa9w@@pHsiVmq0OUS$bKMuvGOUiL=;g38!}$4b%wTDSk%z+{}NPvd@X zVe&KHJyLj=8ZO+6=yv9FA+|k;;c2`qOCtpPJh}y8HFHb5BS1n(}+gVYZ%K1z5 z;NkTOwEzdgI&frWA^g5vxtXZtNojoF`@>!NozK-t$;p>=boxIvLL@i>g9^|#8C>yf zCB?2fK%ttF+mpBNqDNv*ZyBTJ?QjYCP6Q1Ou57^X0!wea|M!WPV9|hh!~J;hmL(hl_gz~KwAraJJzq?p^k)|9T_(2%h=Vstu3waXzt|!jaNNAKA7%e z^XZktqpHCuPFvb4GRl4)H5D3Gl-ifu8cmp`}3y{-Cd$oOCLUH z>&}7cha)imu8cj6URrW4Yxp9IPI$q?B*SO0QV`cQPz6#}z)wCL{p4O#{;9sJ&r{(`6^=Na!N=99Zd-h&AxG9N@!=J%j4C&V~M5ZDCNgrx#NyHI1JM_X^_ zKll$g`|C0=q>lc2W;4N9$E3coC<{sZj3m`POvxoJ!p&ys#TEO!I*)xiWxFtty-fOT zobQ!em52MUEjDo1Hsz#6SKUHpx8$%nIusMle_^yWn#n-eMqk_!!`2NVRWx5WvhZYh z<1}!stsd}H)N>aelOymAd+td_f)xhb+QFQ4F;bJ>+@N4kIC0;Vz-z+u@WIpHXdv1= zjoqJR-|vJV)pIP>yalf8y6uk{z5`sIqnGo)K40~ZjTC;7_V%qV`m_NNHmS5BhUu@X z>0mPe_S5VK6@Fl2hqn7w4!SKB=C8lL9*|hwD;o)Sy%?O##>uUPQ|PX#>OMK!!E)UW z=zAdhsa0_?G;*P9VJsr_&~+fZaifz=Cz^lh!*=!9l{IbEPA{)3cz0fP5xzutLY24q zWxWY_beZ1-S5D$;BOl)KQXt}wh74S+jtf^-%+~wwARroL%0RIoop3>WQUcu$min3~ ztZF8O!RxiJ1~&-}PhWk*bM+08LfA+_qRQ-qszYUq>VzbA-fppz{FbadTgL~J+Dj+* zo}1Q&Toh-n=pwIwk@Zb82k7!FNWpdO8T|)5H9YZl!O9nBtjmqaI7zx;eog&VUw$E> zdAJFdJ-or~4r(Cz#qHj#Gg;u`Y^3re5{vT|7NlylH&Y_p>PcsiY3GaDR2o9R9FTYd5`cyzi!-I(!CZ z-M|#Bodq4QV9C6OUZtQ?B);b{YOV}_fniL03_xhqfeN^M%R-Q$|Zoc zk7j)`XUdZH*k#K}F}6%kgVTPmA7@}sQnB?^)!n@Lt(~_D2#Ho=%*$4^f37%~jIBrjEdf3O)|vB6&GE9&UA>7a zB04Z45k88J7jN(^5U_D=7-IxuA1z~}{n=kP59JeHKO`WSBoJ8sY4}}n29@z14W9q4 z*;hI!%Op+^0@L+P7UYxWy8(fz`w)9G@0+~4b5NlZ66cptf~)b;+dy=U0_Qx%liG6} z)fj=xr;JT7B}ETU5*S-VaYXU-&;}RLp6i+;5kz}Kq!%%zZ-`vuwghnNfnqO)0wUh! z=q6lm3~(ZQwITO!Pzt}o38e)T6WF$K>#6L+I`M%_kZsz89$XLCQH^{4I{rTE<>O*u zWy=6xG+f4awWpl&?fHbk2rjQmCUixQwfK~TY#~FM`_}S9J`~MtIB%9mNhHp1RSMRb zc!O#DtNuXl`&RrXPk!0hzBcvZd0#$Tfu!dGS|7qUT>QSl(Bc4{0P6niH_mu|*&k%e zS!2$4F%262jxqhAw5D@OZ(k#f9!yG1Yg-(+npO7ftU_M9Hb*-iyY1 z^+et9(5}u_{}Q1BqHN{McGqv{cT}Ji1lLB$GDee+9En!qR+KF2hO9R!nJj+c(|eqx zpgPUbejG#8W;UjKJ|y8$)T+zAlG<%rWtY2J|Lp_(FL!g!|GFg0r*Hb|QQMhw0F~Qf zm`Vq#Px$YqK#z;2;)@q``)%!&pL#0_VU>sY5;`BmWiy7c1K5ENjkIcs@31e{cr*8Z>3bV($-(dFvZ1mg*RH$ z;rUsq`V|7Y<9%0@xo#L+cl>T`xf2fEwmot~NF@E2u~{)O!u#q>6m4*S4#vgGMdHNj z?_bK~psbD*pVrFNJ-RlnliWLIN@e_2M8OLh7U`^bv9Y@Q{cc1#3mn{JIj3<3J4c8u zmuu=eK8{Y~O7#As{*)*GfTf0vv1RX6G03r22cjHWe31_G`(e8F+0IhMuuj1V$KpcQzVx=HghSztDxdx2l5h-o=Z7-)@p;U*%gpNoQ83mfO;m%% zd8n_xtANXDc&xsJq@-d3#}LEbk4uK=l~_;9sOQPnNc?2ej)+rnTeM?%wD0rs-G`Nx zk3F+f`2Q&|;lhdk10T4+C(Pcy9l#VRX-ppV)ePqF+)cW`b-6KK2qP#;k75RQh$`Gg zc$`RMshvo=>qrDQe11wiP(O_imp^>rrM1HIs-uL1$7da156)Em{{3PRWnl7;Rp7~D48O!b5v<(vN~J5$>*kHj^AzP*YDqA zd-|GqLh{b`{SNAy;1rI+V{#8pj(LzZEQRcCNV}ZELa5Y-13TZp_xql2)qFzSv*3Rd z(Kh1S^xD`Rxhn58HKK7A6w?RYA%PaO6rg$lH0^<%yNA^k=vwBrz&-lHk$27_R@X zKF{yFckwmud})}twlm_G<NgT4Z$F926XZlIe+`5S5V9=Vai zy=`-2jhx&DY<)L0vQ*~kpe>t5i+AVm*f?5j&wuEco*TlN#!dFVKyc~mIE5+6ld9&+z2@;E7UJrflj(b< zo;MXQO0|@6@7NBwOls;_6f7paIVW%ZIjtvTOfS57?Q?aXdn=Wc>q|DTHTa_LfM1~V z=%K=zn%|mnP2-M{4uVCA1;{W!=A!5`y1T#jn`Dm0ddUhVYvo*ielYsmriZc}r2sD3 zN?BJbqu8Tn2V2j8*9u-i40+) z%C6H+pVIbwqd)D^b`a~s5#IQzN4f(ht86~~4DzStS1aCt#EJgd>Bk&;gXJ(7!RsN1 zj2U8`{>JNTR|O!d1*t7N!l|xuaB?;FVOQrOA$Or?FyH&wn7_D+-gNBw2vbZIn zlUQ{at(<&%6}YfRpoaxW#; zMWuf)vDr2JaYI|(I{KyN*A95#0qjSPt5;1Cto-!k=or2{o8mqxH|z?HXC3KXeS;L$ zP?M{m8rf3H71nt-Are^AiSm<-XnmK-wJ_Qov*)}VoBD-B_ZJrT(jlR|f5G|4{_C_E z9g>xf^D?6o-={h#|J`GOg#;UWnRqD2$sO zh>YLP1ghjbt9&7~M+gt!15Ix6A%6FQW1T9hv6KMLmrdn5yM zt&!B4oBZ-f_HJH&ekhs524NPiBG8kN9jf{joJVeF~XTOGWWJ+?EA&-bo} zIBk61clwnR{}DiP)JySY4kpi^6bLo~VyNI@+vA44NPF)IQtkW0 zTv46!xnyOGF}Jd4ocyR!NAkY#P)hPQEN*C(tgm~Pe~n1T67l{73?dt1xX0H(|Jf67Z|?cHxpkDj*w*{Xzgfx%F6_`Kg3+oy8)eLJ z&3`^p5Qx3iObSgtcURFdd#7+J?88dUMC`0Ej&743uE`fGG@TqF*7me6SMdEeAw^#@ z^CH{(V!kCmZvNO95n_XG&*`OL$i%uD(r6W(PXTo`8No!~$V1ST@t8PJ&9|&^Hp|jO zOa*C3AWVHG4H+I9a62Snhqi@vor=NDsgfA%!*k2lcYY6@K-&PdA8 zl8@%+)XCaZ)q2f}IHL%7aRXEHdKN#8*F4QC&O3jR?JbG!yW?|5Eb&cYQ~h1G1eJrC zc{c=9>RZn|;cvuH`Z{<1qNo)Vi7<;)a;Z8FnpH0RRw!kI#?BX~Xq_xa<%f6Y%kz3Y z%q*N5?6f|wMB4oNU-GP(rR}rSuZww9g;Oo4!AB8A8#wL>;lBHTR}c<%xwV$GZ?fAHp8qO1NJ`CFYibo1*CR-dKcK z&kf+FT1`VS@h9r^Le$OQ1s;#7Dm9VN!3Ly zphtk48Ucb7uuAKO49K8(<%ClS{H~VJoLX5S;Ujla#CJ=2j6x&K z@Job@N`2IoQ!9^NWn5juTt&1Y$OpR(D(Mc(5KR?9rrP9n@3G95mCNxrzRazfd^^rR zUwSbsv54Qto8M2bA%4F?1Y~aiRKSmDVkm+x=26-ed`St|;-wFH%8A4E`SQ)y+r;jt zE;P?nqSc|G= z&!VnD(cyd0#5^|MI_D@20g}jT76St=R%c+m!vgSIs~FFP0*EVh?2+2vJUQC<1f>Xw z8O0#}6M;e@#e6YFP1*!Lv;nvgfGFPiew!Bd2m}U81MiLGGivJSI8V3^mx6N;703Oc z5xFFQb4GGC4`JHy0}u&A<))rC?AgInxe3#MoIwP;1;yL;*9%6QKxXf8%DN9|C^?=S zE;@G!4{rkHjHFhd^qd~bfWQFx`o3qRyqOSy^Ey_{nz8P$78MF`3duw+eaF_dW;@8d z#yC+B*UsmL6W2Ora%>#+aIHYK(ZsM)ldJpNoDypDFC(HSjV6znzo!5-m^PfHTJ&Q*iC(q`ul_@gA^87xAoSh3RNG|tz)8775Arbqd zz{s)NmQfQO&w44cg#*PTrmlf-h2X@HEsPxHI1y4H8{IP~W2tY9TheZY-Q`geM+78t z;0(Oe+@hkF2=fln76@aGkf*>BVj*t4g0T~^H(=O9^Z+9=G6&OvlJG(xXLuA$DV9ZC z930bKB2z!1^3N?Ve*<~j$lzuKD1!mbs;;iWVESUGA>INCGg7cyG*D#9JLaKX^>ZMa z`-X-TVMHO^4Y?DcuDgReh{gnmOcD)h76nKpg{Nx@*Q}4>VreT=2VA0Go>We>0BiHI zXa(V+^`R8?5pMt;x-+N@wh>I)L$VuTB@BHJ&Gn0Xf6K^+-Z^iL&ocjn%$VvoDduJFzRct!{r;Tz+QS}JYg>M3h)@@RA@<4Hqjfo5-+dR z>nl}@+zE~m{M&A!HlCD=wHkv=*Fmc?>OX&3vEFVqq7&I+fiq*a#cLH4ZD+L}K!EgA z7Ij=8JdQ-z9mRE9D)Fsv;^Ma8TU^EKGBX1p4S{LL8-}CxKs-XNWKmv2F-{85La^K#=IE+XHm2UP8F}IgcLec$rfk|9mCOa(dL9AyQC{3=& zbb7gXeL@$r*KsX$M_xRwIJ!(<&oqcJPd+8w|8&85dqQTun#_HC{6R*RgTRmZL$jp7 zNQ<&@v=a*-rLcWS{z6{1OcK6<^d{|`RlCcaG?ntVxiq985{M|u6E?VlzxJcCmw}c@T^`#!agewY%7OVE={adWg^C(ZL ziso;X2mivTc`R%wVFE{E#vi6RO-m>Cp1agl>R|v>%y)Q`akx}tW!PNDe;CkQ`9Xiu zH00>h5(&P(=GR}JT$?^GAF5yZH!}SY7sTKMp2G5Gv;dh5-fTCKx^RzklX3PioOVb6 zfSiZ-G3s71g>2>#ES(BN1<8~0W6P1lx3SbVCJpZswI(d)G)h=MJTsANs3P|)y)1vL>G z&&#H>-CqjBed%#D5~W*3bxK}jnXmhdtEb)%RdP`{iId9HJLkl+{#|`jAamz*@F(_p z&84=d5m=j|;!*LX@(-%{1cVgNs$2D+JmFKXlY`IC^e6i+)k6O%(I23%c=dc@<25cq^rib3Fm`K+FB(=fNxVK$O;~ zvSFzN+oIm1M;>Uu6Czimu~%P|hxch^Eg_3~G-E9C&_d+u1F{J6r&PXu|HfE@PBiajnFlPqlGY$`opVpev9L?B_llkUFq~ubI}TWQw_)} zB zg2qDS9MtjJ_MbnM#{Vo9q&h=M8RM)nb0N67bM?Na`{s@sW=L`dm z``H1EIJy|Cm-r=x4eWOp*P6|e3mUUydhn+Ru~mXh-+ZX6&$wPmS5jCSLCPDR=^{SK z)S3WoPGMxe=bxldqPvS5kvX>0liZz_}rjO#U8iY2I!m zHom!gd}2>uCZBI}{uZGYQX;UJHMo8<(4Y2bt$$w@e4_@xOoIYhdgV-MemwS zcd344a-Sl|0c5cdXMsn0(g59p4P6|X)uhLYhC^Stxemn79Uj7U60YjjkIA(bzI7egpL3mBZs_2AS&g#0c7T4XS8i3+p zaYa7^vGEwr{m)kD@Q^ll`r_T4TSv}HmR#^gu4HwIc9~me@O`nGQY0@3$G9b1;FliE zx}Np9R`2LSi{kaI%k!h={?AbeKzt;CQQe`H!sAo)ScR)3_zLG+ma0r-0(y<`!*K}c zq`RzmJN9IiuKc1zhX>V+3eJW9^29m&-ZaMgU~*j)7%l{`HXkef3y{Ae}o+jIX; z5Y!Z2FL_Lsbu-{-%&#})&#A6$u=)#YxoE(W;WwLQmf;tA01m#Jjny$&jdeS$qG8C{ z>eY7vUjLk%Nsb9I6y?URD)KQid6UFLus!I8~>_N z9e5l&o~4zZA&~Q(*!YbqzK-;vf|&ehNB7fh=|mi?Lf!9=@gx**v@52l`33#wzoRr2 z_x7uX>&`h;b#?H$bt@yQO2O|wZsP8Z*H&%1&glMHR2&$s?7;Ab!E4e`aS+TpsB&o8-DtUpD$a=`AZ_-&-r`CVO@;Lq=$xzqS z6dLGgBZPoMBY8V$$+Zty?*|_T-g5*lD=@7a!A=$0z_&7>d$i4< z6pUYTuT-1Cy5sxUn14MuMSgLL?p>TiH^>AJ&l`91Q=yIzV-nX@ul>7P1z!EVS}R-* z#HdN#KFx1lctJa?)gL*nRq7{7P!h5Eg>b?{(6EspPzlZsVcP+HFF$s39qq@`Jr?X%4(WP&&84ACWC=T&@s_&wW+j zMO_<5Tk^4pu^9A8s&{+ZD1zQuy^snZm$et1)LGgkl+W?;T8s4)tUo;N=`9QNlOFOo z*^l=dcy-6xAVvS*W5$dHIc6w`uDc(IF@1xl{^Nks?w(+P&gCXopxET7P?u{cezrY# z%ea%l2pG1R z`;AYs@X0#h2j(E_2BAD)#e-|V;b&COhF^t1@6zFqkkX1mCdB}j`wev8iV#mQ^=IAv zT~U#u24!MW(%SX`3`azCwBl1wS9nxq{uLf)y%L4#@F+eMT&|&~3E+l*enF&~@ts{7)t#}*i9-9@L0S_pjiMlHR!lcus^@{BAC8v3(tz^-9DnPYrIYf<-Hq{yT(UW|sss@HAMLXU=pz!X&d2C`3?b4f9X4P%S`?^o zXBWS2e0kSQCy(LYJ6-zjGW`U0iwNueeF6WRf;Icr97WXtwtCVUd}i*&GPc_s?ams^ z5!;h{xxNo7ks|-^4MO7qP9!n5zA?w2#@7i-G9679RWF+3Vuy#gqB;(C?BChdmGZ3d z!p>kMM~BZ(KC%D9|{ zI{Xsb(!x^RW6H<`iDsciG@e0Mt87Cxj==cCuVB~6`Tv1E82^989!wNr08pMoTJrRC zv|$ILh(0EEH__6?tvhP_}Q0|+xih^|%n15p(O;=4E?B3{@Qf39e) zoPbu`*r>?WfRy+)k6~Scz0b-+L^H1s5HN);0+2_~iR}x-5wZ z<5Yn!gE*QVz|UKX{r=bj0$D^l{z1R`_3^Pcpk=Lp_NRK(e79m$haZ@w!(DmZ88;(~ z9RvzU&%@ed`gr4RMP;YheKROj3aKphIJFFcQ1hRf*vBu7O$~@CzV3UlX|4Y>pjho1 z&h!V~6;iLRe^v?kBZsy-sA$1+U$nnZ;j1b%-l&LsMtwU0i+ke5c*g8L@tlmSptpLk zV~V^Z+?a8(qyB>n&t)lHoU?CT3oBp8MrW<8=Ds?^wk=`D_efII$Ky4HVxPRA*g3?r zIQ@r>Jvph>G{Xi_zo5jSdT0K?J#52}8N z$1Y&n7+?Hb(;w(qI{`}ZOb(Tha@~4Nq`d>|)iD`}s#$rp==pzSHoTTjFMx;Q+lR`@ zv*>K)7~NVo9+{)j9#IhUu027_J5)OQCa2z@=SRE%W0g%H_Wyz$U4RvJGP?ixVs!dj zNBZ>G+0bWKOEFR))pQCptO&n2Q8Wiiu^bo@j2v%O`q#Xq;);Bu2!0P1`+fz2e1|D3m9vWa8D%V%yq)bUT%P@BTeg+E~CF?W8C$GBmTOa9zasEeR(-Pt>e;Bm-`DBWkRT}0B#2eTH-2qMM3Z&zoZch# zVX+a=suuU(-i#DMS$WRjU0fON-y5^7y1%Bz`%#RKGLp6{T)FFp@(C)Eg_{psmkmVQ z&e@i8?}NxQC5r9y=h;s`JsTDoAU!aLkJ&NVbKxzxKq85F>s|rM|2j8!z18}IQ9~*W z;&}~O?Nb}A8~gY5_3sGL!2;p|h!&ZA1qxhq=8gTMYT%0@jq`TMcA~V;(+2&J`s5yP z27oy9W{5CM#iGC4KLWEGqq^q??yIfsYy&7xR#O3aoZB&J$JtHuh5(!bFG@}tf-s(N z7nL^Y7#MUvLjYgof&$0E1z>A_BL8|b(F~&GaRcQ*mHdR+4Q?ejQ3G@H%SU8Zqm;CY z!(>)yfm9q&;h@2^5v+l*U|G&M+W7b-uQAsd;3*%5aXd48$sF{O$AnV~kCgq+QH3Kq zH~w(B85}Dg^Pb1ua%-sguct@dR7IUPfv7hS%n?H3MS<}<_{!`11(@=hA8rtU$tZo9 zcpBpos`$yBpp-A0lqN4O!onVk7whXeAdNBUdWFp-^32-u3rLI-)0=9o9s2cJLw~(~Bfryyf1AH$ZgYB*K%B9-`B9aY zh$D|(NcqQ?Mdx1-JiGWh(H%u!648o|eoE=^J>lz&35d$Qpj{k3UhrWEZ@h0?iTP>X zFXm-)=x>nvzcnj-SaCY~U)>75-ga9*W7H6W%;hi2$KW_^f`A}3YH%o4`jJTV63t6O z{J_6#dte?j$lIouaC_WP`2Kx4UZ5O6>EF$_b=34KYi73(f4kJwi}L-<;W(R^>-wp@ zjWCSRswKe;QE8Gr-r@E)pR7FBva%&vdEWlxXGf9yAdo7(p8ShMH;m(?9=GJX9ovzw z^e=snqYIl~Z8bYx1#?GQi&_XzNBSG@2)_C^DuGpCxP;7D3Qm_F;PjF_IhaGVHj-dp z>4YhIklUo8tvxhv4N``YGV7Q>+a-1c=cFvk4|VTFuaayj+~-$k$vh;uM#-mpOyw_+ z_BNGC8g~(h1QFLa9TcNeDb{<}Voc<^nP$d?wAvRb%I5cBYQnnwuomS_w$~Bl4(_B^ z%wO!_b9Z@jf6)CHG*-Kz7}eU>Xi}$&NC|EU+-A1T;!)spi~H)zd>MzzO_;t!ahWy! zRb0Lh7QMGw|a@(2KkT?t-au{4UoZ zzrN#a82c9R`1iE6q0W=b+veitHiH4GFpu*M$Y#r?hDHYUYVN}bb(%RUr3e}<8Xk>b zs*)H5#I^-vGmq+W5%G44Zz`y><#)qEU+&c-p@C(ts(LSPgK3lcL@*Q_KNvxtE z)F6^VdK4sV|5KWQIC#c*B#Om*DI=t6Ah=S%s5{ya{sZis>@aa{* z`FWh$emOIIsUM{nE~<`67PU?WKkA`B5pDDfSloH^TemT9d2k$gy!`CnUNOfj*@{Se zN8$=-i{@gP9j>kOVHs-AeJeCXMMG45l?E)v+JzQ>7u)B=Onz}e0QyPQuyX?I0@ru zs}@te5CaOh(AWW-WpH(My#paDn7P(%Ai_$(*0{W~qI~HbVrc-G@M~ZX(-4iwlkw|F zp%0bLs)j2FyJsf7Hs+(1m`tFMLh3DUqx$3!rlKjzj1R4uR%D3VY=Lz3OryKi3KV)K4&1 zkjZC9!xua@2#3PFBZLg}7HK#nLH-aB6Pbcz=NQyMbFd`%QI;vL)DVI{3la!R2v0() zz;V0Uwe&?KKn6P1cK7;iM#Pg+e=tjw>igUJ2JL-D;sxx@C@CHv!{UFBcN)p2-xJ-y2SM4327R_Ub8Z0_ z^7n)7M71)H2tN?nb1~@(*gc zy6rS%bFNSOnp#}7wztG_OT1N0^Yn&ZvJeka2tSl`nYbA?CCC>)w4cZH!*?6LSzkK*GP7s^n@AFVa%rot%z9@DyDebqUvCc zbRL;W0uI|{Orl*KMiE&Es-iQvu(Gc)JzZi2o10H>KXPEpoF4Yn!Ae9Np5F6UjbI?R3BZ>Y&}$$@#m5_IQZ z14X~by@_9ah(ql{fySnhnmDLAGRW1U#VSyBg}{v- zf|;sTvI{Ibo?wR&1!F8sgP1`K$w=b``)0-M_{)D}Nj`rby?QPYj4FHl1k@dwHTd~u z*3X{NzYtD1Td=wQ(EcPnruSSG;{%7!0?E_@iYes@)oj8Sfbid))(KrPyb`f`#UF%F zd1RIX0XOdVwaxZMf3qpy5|y;FxE;E@ow1OFRj5u_++>ArALG-@pCmQTsHPEnHD`#E zwOQ_SMppD8J@lc03#;$uahU2pB8SrdRr1q;^z&Wje;g`Lz!=c+1S$HVj{H7Tg2THF zMa25n?_EuRB2NEIoldM_CJb63e34lwUl=j}7Cz`-^K^ARLhhJ4FfAFR8o4*L;`AWN zTz~0gi{8V`#eNgsx=s1Y@fXAUcX2DbHrr>v*X;Pl+qr1Pi(U)`85$%tl316-_72vdD_bzr(99|Jl-DL zh$4BPC031bnd;xj4B~u~3ID+hh)q7;z>O9r%1R>Z3S1poWo5DKsUDf*{l}XjGTAvf zUr#FG7L?O3UE&Rg=%K{@r&81sZ9`4EWzQ4do&gqzlc^12Za8V4i#%ah9l{qE2raT+ zvan4S4p6^qHp$*gpvfgCG(;?`*eNOh7AHMulY3JQEay22j_Oz#pn82cu4 z+C4z;Rq`m2f1-7XqJF&+&RS|n` zq91+L(GTxlwr6`NZT*h#n4( zdzRy_#47dVlidtyUawo;7&=_rNVl@+7?$sZyc41W@BdX<)2KH+#myLBTYxj@5%ieI zbSu=|eq^W)BF&8IW_zQ80SwFu^rR%yDmSkkvK|ODx?$ye_dcni_u)`zQ6@6Je2)&Jd5%{K zRDRQ2a)o&3SkICY8ov|2be?uEQHu6*&Sl5!`J63MOWX|Tb~1k5*2-`>H&7T-(?e@? z?<;%l!;wk8PHf%rDS>(>_cM1I&M}>GJ$@P{qTSFriRRa&e0n&hks~^QV)<=(LXwnQ@6X`?_gr`+2_Ill{yQYAjM<{N##_p z5t-+}WXl2G3R1|DLvQITFuVxl|CxRxkgcW1b_VTHKl{rX)$zm^&C1kb55lj(XEyk+ z%gloDN-lO?qQbKr>$vE5Q64?s)KZKiswoJ;VSF~FJ4;~cYEwo%X0{{Il^CKkYE8kP zzaPfzOtG$ZO7!8kv~L0=ReZ{e+deoIQaw~owsocpccYb&=3*zX?aQEj_u-1tfy){PNsOPbtQ{$#1<`N3pK0t7 z%HOS}{|2Qf^2DiLuOG6vXuLI7K2ic2+lU)$_;W}6f+&wMR|-ypnU$Bj z`r@n+9T}UygZ1J*jEV;lQT>AwE*UjR`{Ox4$@|f?l@y9bNJW^7y{}pt^}eXc0$_u^ z9s~p$pk zUf2J*_`?$potX1w4mAFu^jljm#>k>9NAh|J?rp2q&gA!cy}|_cGNHdm7Z0uwMI!OTfy1 zMuOzA6?fIr2sU~!eylX7@yXAymRRC+ILb&5H&dC@S-D?VbeCXyy`Zw%cAXz3`SCZ= zUZwf36}*4?yq^qjjo4sO*qoN->q%mxlq3fy7Mk>g^a=b6nnER+ZLSX-)^4Lku+wN| zN0>X;fwwWnE6KdJxfq3V!y+fDe7(rY*!YGdvkWy93igk!@GlRoDk%rey-*Ovx1=n~ za7%Q;quxn)Ic*4w-0sY|FxoHQ9+Mh>JsWYP6m6dl-cn3XdC!`i9bP;Bp1@xP9_eMf zmlHsFg9R$95;2r{a?Y*2%kOwmL}Qs_X^f+N&VgZ5TRuIi$Nd9ph-~rzOWIN|U4|mK z;HMH*()Im6XF<^}>@XeLkzKk$EQ4lUG{a8jXV{+#p;(T$a-OsY8q@|93>zk`zL7 z!6z}Rx``W(a=0Y?TJKz5qJbZNsRItGpy*yQ3B*?7X?eJ2O}y`Bh+@ZoNqt?~gwgft z!S;(@KCbg@8QNQlKUGk+1R7DLfmxzcew$CI@KmnMzIcq4&YC>2-fbd z1q+=YQ9~ScA6n?UBcpp+uTzKICZex&93b&5@;;}!d5QI0cl2JV8H3*bxvL`B*K@!C zhZT|FFJiW8Z1vJ&!$-4U_|ZaWLS(7qom|pN8RlfBSdIJBfgj+b8tr?9%d7CZ$x2^E z?PikP?Q>cY%H3>UPN$*_;Q@5{%~_X2-*Fx3Ise@FD^T<;kA*ZlhO(FLj{o;@R2*_> zwIm6to_DS4O$P8`XzHr8WS@l)+EW(Q5x?{hwX!&MAa+Pi@igJ+FN9B`;O43Uxp)2{}o7i*)1b3R- zVmqwWh4_W!so8ydv~E>>3@yKQ%|6QLcpYT&T%vNw701t&?5mgB-xu>q)^~IoRuac1 zFTgRnY`TrTT5OxC{6d4 zY-;Ae^95(t%+)IyFUl23tm)ew|9NV7gl>A9M}M~?EcS0D%3te}UvhWTfS)y31T^T) zIM>oBs+=zG7CyEJQ;h7>tXXLPh+oL%ornpxvt^!|rk1iKDETq%`c%0lLc_cC7Q|B~ zx?}g+yll(oUQ$NcN=iHD-4LR^%+OQ9sQBj+wLNojm6Y8o>fUw)>b3ZSE^6yOg??hG zDc4mc^57M$P_CA#n-A2mpN3pj4;y~0lu!1T96b0FBxO4vV_L^$ctP_CG1^Q+o_npH zJ1w&M1pLHbI~SiX5H?N%o58y0L0CEJMx{Mrr7GzECX9_x!y#LosgSh!z|rqHMz|_X znW(Rg;3xcd^yz5yRn%fd`lHS& zj?M%cU%aEzPv(g2D7sUIiff%={UvZx8%omL{rt{A8IJ#}N0c|?elEt?SZC}_9))`E zz5V=_I`Si=hgtoe*hsfxFx>Wimw(0$<_xOy)$FsOl513Nelo6NJ*1yDYtZqIID?y5R<^f_4mAwKnbacoDLtGnK}{FVA>W1EJoJ zyqW&YAnDOC!jh@1<2)@y7eFb};!G7Xc7%!pe`oo-Yc8L#Zg(`J;;>1ek=c%+m+_;kJ4hj@MR6v54hMQ-ah~0Z>eiP@#=;2>ECST9eLDt_9-c*H% zt@m$hJ);w%BWhlLko)gz42Vk5ecY}HU-!L$%FCU-ODCZO#=b)>wE~8WBp!{?Jy9a^ z0(PwIh+`_MX93R|I%SVcjc;?`xtK$8Y<`wiA?_BjY$zMkMnkj_%=LqiLXtzzo#3gB zyzK03qn=MP_V@X3krEsCwc-~l&{%eQbkp3^UsB!Pc}s(q|6(moV!KPTG8}-@tGdi9 zQjfo{p#}4uHX!yu$3U>*#54T1VS9v|Cg9T>nB_vxS^6af zsXr%g0=da1LGIn8;GV^-?Cc;Uc_qoNCJa>FTY&3ka-0p%R5vgnK^Ga+B926`ab|+5 z0s)vodgU(K1JoXZ1J)VxDlz*AH2{^mI#(E+kMR945pHJp>4S2cLAl{7pzx7kKd_*Q zF6U=~i4+0rV9@vIxGvj1h&oz=&Ya(T8Y!#b>?{Z&-@=epLrF=wiFn+A^m7+IMSQ+n zTTU>Q5svo^SuYN0ZfYP6Hew|JXDt#I2$T=wPKEg9-jXT@e@pyLLR&`+c*TN*m@Vw#7@3saiQ&D z3=2Vo()2*+U3|N|5Okv%l4%kP~ckAj*5VE{fQm}*L@ zl68N-ceK=|#GJu?PC@!`K$@HC>|B>%B8$FFY)a&)=fj(H*KuBb|8ZxNUSgQ?(_#DX zg3DAdHTJN3>AD)nS@rEhwtK05EVD=sQESeWyA^Vtu}MUN&Z7@uKv31s*SD*-+OHyf zEm)8{lSHB<)~f;$7qXc1g8KdYH((HQUWyxCm_h&`edh^rbw62<06+$Ts+CzvQC`Du?3jS$!{^JqK1;rKaX-Gy+%XmD@Fw6rLqPL3K*laOoe zf80W_5Jp+~hTb4n#20W{q;axa?1yM`fVL^>*scP| z{1Ayqf*939NX2_A>Ua^!O&T_@UaJ__t#RQ*Qk7KmV!#Bv^{P@!?T1VM-8xJQeci$A z3k1ssztJ`*ZrsM!5f~U8o^wDg&w{ULBff(=@KW4R%}{B5odH{-nL*e(-q4Y0WFu?z>zz266qfH@RL*WARWnUdYF_Q6EhBW4%#$j*P-~g5=Qrk`VJ7 zra9w5%d!jk7HF;8T(PzvWTi6{s3%D?o@N$cbl*?QE88~F@jYuNl zfKuWsyztNl?h{`@(=x2eqZm*iP$e+BZf`n-y_RvuL2gW2msR95xrwFr`s~;BNf+zi|Y|q9zrxh?~^*y zDcFM>G48yx)R$86r$wax3&`w77CX+};INY>bF2FDD?|7-%AQ$?yrs$52h|)s>HlW6 zhl;u0ibxrc;qM3yVQ|fl(?bAOL~HzS;|MdAChJM*r`dmYm9GdHKVap%Ih@gZ;5B9H zYn5)JVAvYTcun+|lgC`%=4A0Z$p!3}MKoXHF4a|jCN&r)SQPtLTA?5VnaI)Sp%%|q z`Z{lGk8WR}2wJ+P@{!XY&*QVAM|W1xJL|5GQwG5h=kWtl#@G29?Z4?;0n3;E0Uu=` z?DiYhUYUB^WcIw@Nk}kzysPM2>a#NtRU@l$esmNGcj4b=z4FeB)AcP6fu}aA z@=0U9TguAHA-j-c*JaoPTA4NV_<2P7;>HLfm`l_zM!)3LBg1duYz3F;SV*=0HHg~m zoB56U%hQqBRPy7=DUkHqJ_zcb%$j5ccd*XHEb&j^#2EB!gf^%f9TBQd^ z7XqQy$oxg6tVp+a!a9kJtvN)y3h%!d^dA%_2fz64%L<>^pI+)zy{=Y-IpqO4KC+i` z%ps?g0zEciR(E9?Oi>QA^Xa0-t$HK-oJJDuRo$*%$U!CV&KLKuO1`f+8|(JZAhU<> zF@q}#!ZKZJDsn=p<`N}0NZhWzD5|E3b_LK)mhqY}7o07HO@#6x7k;$(a8h-AY2WhY&;);jaIZ{UGi_;PGpINYfBILEdz!&0v8l;-fn! zlmuIJ>ziuEm5?mcX*NjrOe?y%zer1r|E{nw8{x1jK;!FEL!4Ip;#DKcsak(;Uwb?v zm&7opTlP4$ndNV2J;UQ{)c0|GZYcdP4xIdM`gO%zSTaX|!#`&Qb^$vtcrbKN(XjUb z3!PJ^Qo&)ed1yLNp~%V0mwJBLx>&8u3>)Gb`ld_iN;Lfgxa3POLHzzrIV~Nm!bYxy zr_$bg40XN)Y^nzrwh2?ljgAS}Bk8{+%+_`1{oBsBsXr*w(G6YC>0C&R9gbYKo_fIa zf*4JobAuCp|A(4SR}ZibwiL0a)lEUwWV}YAdzLAL;HxQqNv0S%+GY|9t?iTT^Qv{G z)IR38*q5p^rOsSrGIVh%3(FaICiD#Il4fLV?){i2tZ#kN$nQtCQbjF)r4?z^(%w{Y z6xZl1NtG}O8dkp-H2Z+M@oagNm+Sk$3og6W5h(+nHtNXq0UyDWoxROBsR0-x#?2R+ zl+O{%wb{3GNZ18LSR(|nU1gGHfvIT+$Pwj@#kA9_QEWlhK2gf@rtpwD<0$TGsl*DPSr(VhwHQm9X(Knv~WRdeD5`I)m$ z)#Caaxw%&$E>m(ko(ErJ;NaEyRDXV7aufjfdwl-$%Rl_79IN^U5KV)E?Cn?BwTKH~ z^ZQu9L|RcXfYX@kp&_fiT2E|`wwE%gEcx zz~um*_Zlmat)UdY>=1c)TEBclFYAWi=YNP5)~70T5TI;$ZPK318!aHd!~1u4O?z--2Xl% zK2Rrl43vl>+}DMl4_eNk3LFV(?+| zUTlb1cn{CM7ozdN1CChnkvxv}_IBM$JI4Q!)mRC&zb~$DhqIf5lQRPzI{@vm1WX=C zqF@@57ahSQmB=XJwh58rj@w-#NWd{-1BWOHB@+`?h-6`%BGxbR{66S90-81=TzvRZX(5r-iTqP+h-!{~i$v%t3B* zW?><5T2CufmW@k&S)jZBE5A7k6wmdb;&KLS0TSR3v#$|N#+i^NMBLz0ANjO>W8ZmD zO9$~Dz#ss5*aS#IaY3R1GwC}$ByQJehDv#_n1>w*=>P>8(ReM`M#zJ9{O24#Df3Rp=(%Ka- zAU)_<#RO`xk#0TBKOj74-=AJHnm*VeQ=gvCc6?qqx`y}xI}b;b?$8_DsvrN>8OHY3 z{n49=A%w#I8|#U-{tM}`6E;4S=KailnujTz~Rah4$o*bJ$?h@9u$lieJ1@0 zin$@w6Oq~=I>fSy3IUi=`=3Bp$leBLh6OAIP_#nZ(SXb-*aW+S6Qm9B!SMi59-v#9 zg)$C&6DWUJ%ZU*AibO@()%>~wUW~U8R0FfsBn!(I=I0%ef8}@L4bebNh`|D+@hgFd zC=PMDg97V16087@d=P~H<c{Ho0HTAF{e~X+O=D|^lh6{0 zrl?Z$=rzNrJGjMudQBZMp`gEk)gOfHAEbxtSCjeNK@o~*a1wJdey1C!NP7RT{=997 z_7`~699lnh>+>c={*x2qAIAF~UVz3Q3800*>`8L!es*a#uG^J0)i zy+xF$6x=G`h>4BGq}*_{UsRuHI-sOSayZC2LUPy0f2cip=J)_g)FNxf0Hb%Bb*IC< zxAPi4hV-8%X8u~a)<*v=HKoP&d7lBW<@>wLO?#E<T9=E(r+ci40h_Cq zM(h#si_&9FEs5H`$6e3txBk5YmtbN_*bj06dGeYb;^?ZB{Ak=Thd8{FMiMuPyY=HC zMb<(^`e$T!V$?Pn{f^16t#5kbXrZzPC^6ZJ_eJF#Po^VJ+o@`DGm=cQ62`6kJ}S8{ z$fG(QqsOvnBsip0=W6l@O1?jkvCSY~m%SWbly&v&8yg-8`i~s`TBmr~v$%sO6x;S6 zt7t{k!13OAbB&aX4!@xRdm+c;!Y4GxyQHz|QYfBq%&Bty3b{n=@93U~xF!x<8q0zF zv&tlu&K?A|&&fxhfS9umdUXRP$RKYA)5g%RO>oj^C-xZC3c_Lm8UEC~BV=V%wi@pa zAt}Nl_J;ATh?fJJWp{B&a>7kyv;(|cyy|6s_eCA_MfncQl%$>PPg> z(?vG=%)^MOK4I(Pfz*TDhsZb@K(CN-JM=w)^uce`f{m)2U!NDyuh?J?uzCaJT<)%% zl1UzZKxy;LW3joEO+5}!WhA#6xOanD`)Yy6(1M+d?8z+~JvS`Af=zN}T?fyZSuN2t zF?#=j`1fzO_GJWa5WHu`Y}X@UlJ$V{C5mv6LU5{WyVl3bI<5Kc^I*S`&I^2W zF0aEe(Q`iEQGzVsGPU}YPXzEEX)&fUt2N{#W)P>F*m&)$)!3#eNGRrE+}B6Cl15fa zt*PXs){IIMZeL& z;%0NmP2$N%@h}O>=34LBKKGsH6|Aoqyk}@!ccnD-G-r85;{W06t)rrBzc$bra_AN$ zBqaotR8m4hkj@bihHe4r9_dCAQ0b5m5QY#%YG|dA?vj!gB_ure^M2nizO~Lde~hk| z#d;N=``P#2*S^BJ)JE|Uvgag7(o)N9eS}iXOga%5wFOPL-59M5T#(6N;8N5%(q25$ zpFgMim~=t7Ak}&zKW;Vlh`{y&*I`d}|3m|MdTYPce2-VzOhl)mF#w}fRwkxCPo&DQ}m!#Tx{?cf={qHXvT|OkKvuX>O`jK?wQ0ilqlY`zrJUZ*893Q|X zi*AUgaw1PUeYc9-#lsx&sf@gwu(-Vrob6XJs+5fEsyX%TC8qCtD_}+!wlGKGyPI+% zgGpCF>JUKF%2k9Gcmva`Xr4ITy8_;7TNueoFqPXni}P0SYCk`|ylz5P<{7w!lyYSM zY!t+^%3Z6R=mlvpZ2+_i7}|j>=RJV4-pX%(s0srl>S@#pNI*pA^Ris_gKm_qGIS&2 z|1gnCUcGv8xtVkMZf3?A0ATl;WL^;EgDUqPP!?8luiZhtyYcDgu-=Y~yl!#E+cBR;bwm36_Z{?GmE1;PNn`1{|8U=*Ft)GuEQpJ90PD&AUGLUDxc+x^;HJTymTl7Yt= zGSvEFpBbJu`H{j-jVQJ^;tr}2&Z2MFlcM7I7Vac(4qF@3%M-vJR5%JkI{U;O#gb)QZ z05lU5c>46rE~(f~I(#KX@qTb1nTelY7-I8Mue{6TH^|Hj#Wgt_9cW=&mnN z2=>37o^~@dI@+^IAG`qV6(d+&0!VERPKLZniPh7yh4DL{U;Y5Dmee7GX1K`XjFb>A z4Ve*%{f^$HkiEzzR*|uZ4iFk+zDx1*WvAQ{1Z40+vU|4HyK(#eaPjSZx0 zccp5#{>@cWYIzBq1pGG(V6-h)srMONVUAS-#QRF=@)O$xwzz%JSH$~m8~bMMC`3IiG*Y1?r`&Sob`1VBv-NBFCvdgz7;34K%Qf-FrEF8Z z@0A=ij4te6LG6ai06*}F%?RIcYE@j9Jg)vFJkDx%UjsWalsI2k@t!Ps5(`%E5ad@r zO$0A+KKG>QOqX#Y@6`@`is#R%Y+b~=2fx=7+(NGcwaM@0SS`2(h#wnP{cm$k7^Db* z8g6ab-?Tud=v2HD0$?@>c7}Q;7!*JSWf26Q_L~0$H`2_EAJClMxIwV49&Prnl#yF{ zQ}hb}V

    i+pHOaXP0O- zK|QEIoGBJzOf-Z^+YU!~?@Rh1vt5^8hwbO_q+=4D53E~}rFb~8r^C`T^*ZU9qff&Y zWf6D>$dZ3@_&j(>3dv(n!%lz4;tQ@A5!+I<0V*RRp%;AlL_T@yU0sJW7^Fb2f4MZ_6q6B~b`X!$JSw&r40?an9 z0wV8k?z;$-F>tsbZ-nT?-u$w)YCweL4HBh=W2~H!oazh0K#d98KNz*C?Z7MdQh5+g zQ-nxA&dG8CDu4qV%S2H;&IqW7I_b|I*j<1x24z2bo2QZbMx#>5r-SH}q;l%%_`?B? zj*gdBt9z|qBH#(w#ev`k)1BJ68Y51XM5qaVGPo2Frz**;niWd~a|mwMNfx5U+V*g~ zqIoQ%Z`g-q-Eaff$u$1$oF|t|hR++Fs>UvT;V?o_G`7&+SZ~4)Cw&w8$rs;=87WIK zvB*VVw=|D+Hg%P`PbH>$9Ywdedo9lS_s^KY@a%c^(2UTaMtP~85bu!4wxczYa?0_KOP`by>}jcl1SYX@j@o{*@4Mx+x5lI%Z?e+ zQ9u59zzq#TJEn)Lw6-|~6s>M}VgcGMFq=~P{iDtqU%mqN_VmxU=>)3QF4!PTY5UjaPsdQ>B`#oPui6#U&hy2hPm?@?Ch!W52$8{`LXBY ztj0wd_Yd|au^Luf?E(oyXD*%jxwmtosw^vN>66e#_Xc+k&!>WJF@cas!-1rGgUzcJ z#U+JNT3mO%Ii3Z4&7S$E?)l5?Qs`B*^O(+)Z`9S;5>gEv{I>YL+my)8lZ}$J>soSk2@|OBW^3<%41)FVB zZ&UH%cK&0s2fA*&*2}0J=n|8^{nqs3=M32eg@?gA=8x?ByZ?Z4oZa%?7srHUe*b33 zDGU5$_s8_O)Ph6e#b#G##k-MN+#}h#`$><9bJsE1YpAJRgIbMnLI)Ha?r-X<0e!13 zA~ETxBK^^*5QhdV&7+GhGE#eXKI9LJZZyHDYZ?_adD9x=Y1!omU!#pityH=*QOFwlZ^3fn1gZF02M$S2F@Ay z{%ya#W}GN*syKDOC0Wy~@n*WOk}iC=sfelY&S`6FE1G&)w51{bm298*_0{WbOIVQc zjNPhXE1G#Xt7I4q6|}syg+<7bWgLc$r9Xh$Vy=L}ftY6jiMsqA+>SwsaBCpon3;-T zy4oiQu@1rGR#(TL*!=ASU`gL|#S|~B2vF#F0Q#GW?W6&HMzk0o^%4ufHct+u2f5pPtxf5ddnYY<)+kJrf3e`8V zJE792Q!Ql5Oa%28DrWL#1H+%jmvD&~@HcjKwWQx$U{Q;!%S;5vbJ4FYM17V(Uz)LO)T_u%fkt7bAl6s?OQ9C zxAxeF9)Tb6%4whXwQoGuu(*#kT;Aj(GGB3zm=tSsa&i(%PHf%)Fg%yC4d$T?m?-)U zTy_~;AolK&#g!QJ{DF}#icij|`Z66kS7_K#`Y3T*FX!xm#iX|}^Uk7kVv$#O;HE&) zHvo>CF#B6>lHI>R9|Sacv0KwXMjjq-KLE@`IN@_Nf}e$}ba3!RMA7bVFEmKWC}=<7 zaCVsxdK^e=gZL-Rad!cTLnvxtX&Lsf%dEK3>4Ja&Y9p?mIXntyyYuzK(#kW*P2sc- z&cZ8G8p$+v0&#?Omv;977FRuO#JRy2**F zr_w3IrkXS=y;ZLGl$E&h4W@b1*S^fUS%W!`_$)4G4=FN!!3SmGV)r!-GEEY#TLxG8 zoXZv0dG`IKr|Ko;R=hgeQCbl!r2U!q^VqkB=P#*@n2t4!=Zq zQR}TJt!R{vm1m9p)P=3AukV?B55R6%w6NZ6y$ZN2;^(3n{-8@@K)xGLOLV92MyC2Z7l?EkYxDR&&L7$4)_~7n*itoaxdd zC#My5+cCv4QG_I?`;0Hi2tSD+oz`3Xt1@gkl$RSf+VMqN=!UkU3Hz;IC(FWFk7=dB z^;7=XMX0ZjT(oNk#qYAhQS+LC=Hahlq|>IwrV*`CD(QD+3*PXLq?9E`X~|eC74VFn z)-kI-{624%ZlXWX#^`LnR=*C{Z$aMk5wzELcasc>3qMHjdcV-OU|bedQSvlK^vRcT zQ^m_t#&V|~JQLflWzega)Y~V2@@U8ejm;T`R@G-kn)7Tnr5#2#*O$E*&hY-ViZ_gs zmvdu{rs$WfP0hAF6Du#-C*VJdJi3&`H`|R3RKsM756I1*eBD~r_RgXwurlds(ZEI8 z@Pv&+f|Nt%?60nx-(#~{rKl3|_%`GE;7?Mt)-C$fp6<6Bs%-mq1@l!Fv9g>oqTa~G z0fYEu5xT}?tyX0Fq?!pFZClf43zyL*S9vrkVHCsuIlk45@KTEpy>#XGomqCv;+SUTApsXxnr^=!i$?9Rf4S{(tMZS zEQ@^iSk{9f-B0}Ls-#tlf8YGU;|HDUM+K%tH1sNg=%+eqok^Pd%KVY+bTK`p4sMJ6#M5r4e@0s^)A8Wq%1SOet*nT~xpq1`tdfQv9(tRe7mtn;)g+0Ys~lLzZ-QSU z{N@YvAfsTPk8ZAqGo3q}|MTQIWLS({-bml71JCn*4{z05x4CL5I34i~5Mltyb^OCE zoZW}c{&1N%M#O3W9}VFZU!2?8sF^@gRMqC{Gy<(-!Sc(o4w&#`T&?fyq(XeC`OTZ# z!KT5nj@gXr71mnFOfEW3MRa}hxyp#FXL-q4Sdh@(Oh~eb=J8kkNNhmfuL`QH!E{04 z3bhe|F(bZS0;RIw$Bgdu4-B-veY*|ofy9r42anMslP)VumUUOaCJU8ReX-wv-5}eD z(h-?UDl|}5`r*L?(g=dF9{qZl%Yk&8h~EFn1xgMPs90fm-~3}b;k91KeVm!;^zbu$ z$CJN)jUprm;(TQ+AlODwaYIz0LF^gCaDhm2!s0+TJ2tV1=(ecf-kxqu=z zU@KpsUjUI-EDx4RFmkByC?>>ZiaN|dx-N0CYIm_`2cHBP@2h^j18vH&ce*{U zHJ_O!vwY;FuON1C{~YA~2w_S)sV!Z_Y&mH<<1e!}B&(;rr{le%Pb>4HA!iyesW^+f#*`^9uhf z$pS)p2hjkyxKHGfEcQvE)*W*=BB;xfa*Dz_i}=S`+5B$XG`35``3p{D1UzSxI4JB- zyC!3}A!FzTr3vyHc`t7&^PKw5vAqv=D~QR!v;h=qKtf?bWo2_)8zq1y!!zu9j@x2= zS5rrom*P8Ty>wI<)$?BlF=fo9R($>JZF*=l+vPCRRLWE<1Y~Xa!7$%op`}iCFGXmc zRgguBMzdx`DS55B@Z`3_!sesjv_JgoRWh-k{G;(~*XC)}oo8z(Z~XqU#K$1pII4Qv zA&S=c=@s*RR~|kNO_9pDbn#v36pushu9yH*yO~SUWrb?qj`vdH${(*Ze0QsCmHbE- zrFiCevCmsAWpBr88ILS10yYkj>zikgcwoDyN+k?wsd^z5PQLT zGF;Az%aZ)a)nC~I4V~kiHCjq}-Y&VkRTn*ZFR!HE`oXxrr?|}e0kwR8p$2O!H74&| z?XXChXL<@$Iaa1hoLY0-tsx2J4{I+-jIEz``oI(R+ABOv{#m2l^R8JQgUDBBs#6*) zN>!8OI<=lf7<#-NU_K?$ zz)`rHc2)b(Zh!JMpaN*p(DhU@y+_8tbNDqr!=01o@Q8&;7~Hr)6u616!jOWBr*~k+ zbKY=Jog*8hrK-S(e)8Psjt<6Nn}eCu);H18>9CD@%~9wW4zJ7zYFM;!Xn`(ZHS{kd zQ7w9LtXREMZlF%&diaF8V4_`xYKnidLf@hmH!VI^)-@SToSti4nQFRFSYn1XGdDM_ z*Z3HH{lw9u5%sshhCiRiegkM?eI;>A5EF5dLwfn0ktaFZC_YNmfoCVqP+MEYXGEk~ zxMDiFNXhe!_#Z3Bu-<-XYkPX`J=Sv*{v(iItqkq=Viy^`BqWr2ZtO9g{@~@!hOLi; zMRIfe_U03q67?)!Uj8?@1LP6#OHe5AIWmRYzIycvvkNfKM9e|(vP(ma03kNq-LaQg z@85$WhY$<^SHWJ3+_#_9n4U!?8JRVrJeJ#8Fq55LQG*!Y#^rliYaX&(GknyG~wvUpMuq(lqo~n?U zA{UwC?B6PzvLvJ6Q|5F^lESjoJJ7C^vmLG*T zmqaZiRFJN4aiejhnhagy)jZYQyAc}5HSwjb}Vf2(YM_JjSY&pl3@ zA4H?6g9pq`eWyMd`jn3O7KM#--GO(ymaIS9FTLCSmS+Q|$%rBDgLyRZ9P~j8NO(ni?IO!f1y+YlnjxQn6Weu8ODowNgDep@U%~+SxALM(^-(T_ZEDhKD{4MMMwE*Gaq$Cf# z#jlsv7505F3OF?{T+&i$=RKdg( z>f{D|)_OL&D@tLCYWnE3#algX$(#=oZgbnH}2__m;FrIg;ci8!GyN+G0n_EUO z5{s#z(NVQi5BuCwpWg0U(XKQ+$X&yERy{4V*IFZC8ub~!W@lv&u!bq9pX3oZc!ciY zE){9X19u3ji4YLUB2)*g3ij=yiV9A--hdgO%j=B5m#hTD4uxpSWSP}--j=6O>DIwX;KMz z8*-Kq6I3%+18mYC@m!cbK>@}3TmZz6mx6zdvF8>G1X?S-?VcYHRJH+n@`sQz+72LrO z(GPOVfMdKG?=^z>A^lH5L}>znTCUoZu>Jr_Jx*o2j{7Y8H+O(S5@0pR|=y){!~ zdhcE|4m9A`&Pc)}L=6`mejdQEd_@?2;xh6SmCcCD#GDV!0U^SGdLPxTub~Mzr)mM~ zm7CiQqg4DRaYVwU(=NKkZQ!{AanqyLRt1g|cP}n%{)O7p{>o{SS0Du;N+VzJ@$umh zyfa*9@Z|l?SW=GXypIxIRaVC7^00+-b=!pst@zUkhc|vyWYVZIx~eIc>OX>X;x0pS z<-C2dD0PyqWL0UE=VC;d%apO0R`T0fA_oo`L+8rUylx1h0)1FRL2f}Sc5t9({^F* zt(-5@ELwEhGbDqV%VHiEx~{10E#Z8ajCtkPwbmP-D95+F9=Py1?}_rbdp8^x94=@U zE1uNdxZy2-jLf^se2pcn1B!oG6>d8$e)m|->k}`pMVr{15;JH0So@1rYSmS1;PgZ}dXvjmb_X15=q(W# zv9-LJTcoeSBl5LVT3h>wpZL+@M&>J(zS7zbwAR{Oar;TSCZ9vF`Dj{ZMU^Utmn_O6 z>$a=B)kbPvlaAc!><;1k@%vjx@|-TaCdvk0kJh|g$e&5!5K!1x8l^LtpAg6_BN;|! zC{i4L^UG_lcDi$9w|-g-zM0=NRy^~rtS}})H*(Hm=18~O3vU-j@=nPk{)fCeWgnB? z*l(D1PDaBc+bAGI#Cux#Soq6El7hS)e`Gwa@OYP<3Cq@PAAfglS60wJN!~+0yC2pb z=%rw|K�Y5q+0WuQtNUOQk^co4(SA@6s-67tYVD#m)-pZR^pKQab2wJJL>X!Tm)< zfHE>FN_Jeg zfrJ`lJ`1`tWGPYr>4IWTTT3gXlg#H-qOc$ojg>c~m++sdVXI${? zZKiF4PnZy&IfABWXr4WgGS(1?i_Aly_ull+91kMtb7_sAWk_cR3Dd?Y)xGXUpCpQA zy27s=|3c)szUqgrga@S#{3>dWWr84A;^X6qe^HE4OldFtCWNWc+V}HgG4dWwn&-i;wKuY5@yG6~O-~&vUQW8Gt&NYLU zaLezg$2LLeI<%iKi(f(8Fup5yn6t6F{#Tp|#cOAOzZ^SFSUD|fs)>UP+ITd-nK$oNB?zwsCZ}n1l(Cu?A}WL?o1|%d-AS^Y=&B%Cz)ZFD-9GOj?1wM_ zXBwti;ynd)iPG8nx#bCuj}j|iun62LO>v@mvCU-noi}z$2L*gc?EER2ckaJK@D~O2 z8rqe>^%_ag3`ARyVPp#7{%J3@YS!8oDCRNKD1Y?>?PmL(TVAJY(m@!>C7A6MNURIn zvCfy2JbFJA5*b%_{#{DQGoAA57C*?|XR#LeZkKpO;vsq>>LFV%$NA6!zk_iV3Yt=E z`(LIPxMc4>yysd;hY53gl(}ZXmtN_dv{BLRA1a@(X;Jcqt+3vHtmXPg!l}sBD9%$g z{0ruo(l)_*F($EpL&Ne8gd&4Fc%u1ew#{v%DgmMf|9$4%Ip(qBmTSwhIW+Byw z>t+A^q!aX4Kc{qcR+#*!|2?T~OY*GO{tK+*gZC;o`{e$v$2A@p{*j*yCqhAS@in1% zxUdfW$u@Gm>u9IS7GlJxKl9F*SLTy`PFYhVin)HIOJVz9VMv<|mQ3N#IZf+k z`C3OlF!=;hZW=fJB=T0DgAM=lyzC!q;XhWsZ=26I7U^QwClZb1p2WP~RM@Vy)esR! z*FU}DYE5q*`=F~L*qoC;=Ch3JfTGbM0iiWY`{Ii5eRCX9O~)d71e7~Eq%!r}b##KW zb(I{fTqKzB}l|GgUHyRbic#P=VUNGvH z`>~ZOn}-v1{YZ^T_o=75GyfjjyC%CkYG>wLegoYNkG(m2dc#+%wg=9isSFtDBsb$N z(7#n`FRJpixbT5iX5q>5KX&fVk{*a^I4L;0t+L;mGE16}z~XzLI^8FxUeUB&NYG4?5C%=!*Zuea|&PeUOpbIPI`o{W1`>{{DWVavCYz&0|C!>qMd# z0eBOe9Gs0^Wr;8rYjLw~eL5y5oOl}{uze0&ZOFI*vdY}Sl@5|N=5{hxLr7ej{QjUp5kt|)Fw#teMS*B3J zrw0-m1&_?}cH&pqYM&DIY=S$zP@+^%x>{>>5u!p6}>eB*JY?X0M_R9p_D_ zp~&E5mZ^V(6N1S1K6{AY z>|w2#a6)@75K`k{Ns>vh#VoQd@zwDxq)f0YGphQUIZf6 z4!R$_I#f^WMcPH0J}|nrn^=F5@7vMcT@Sr1;M~ibBbTF`(wTg0@D=}OqrwA>^Vu(U zTkM)T`hqtX3PV*U*|R8hs$Gy{MoY#Y*Sf$$`|!y&5+?2>GWle7Wk7nQMan-vyJL27 zsoJ(S#mw_nDm0BpqsK@sR;rdXt49Xd36X7t0f$D|UCgY1bz?L6P#o!{OW1{Dy|&9s zm}~4JtEI@^(IzLg8hb`iyZ7tc_@JVyBJawMRvj}k>t1hjM(%w!iVP2wx9P2i>b(dl zYaugRD2i-cFC3q}GF-v=!F*iM^0W)5Rdw{S7Z%yHEhxl-Yb#JTA~I5@*Jo-wdd2-4 zMuyNsh>#(S7bJhv3;UGpa}O^6lktnREV)WnqSLe5e`XQ66quf4?O<7BK6U=W1t=%E zAj|;*L*Tp)wl+4njUU53j#L*)+G_TT?+=-Rs&< z{rdZ9vveCW@#6I>5=Q_2{3+>bzIxmaED};(rD^SMeYBVHm%yci=8r5KBc8KJ z$tFhEe$5pa?ya&J3FpkC4oa=LB_{H6R6Z-f&kxKp+ao7nF0vI#G8cndk;@O7qnE6yah8hA#lTAy_ zO?f|`A^OlaWY4jJpI@fd4^vL;$;-%N=*vhJqV)5vGOSluKFw*DHK@Dx>hR@mK8+Ca z;mUWO$~0wyaL5vg6h=lQ5LLoFJnHi3x`nH&P8LOi%lHvkj+Jm`053zS7uwk51>(lO z)NG#L`S1$ueK*vF|4RhBjrM_jLYaN?ay#;JWo2an<55|;&)3s|r?gB3zy$1`AL(Mq z|9*>fOVB+pQ4@S03=iZ#M3p;47C4E9m)9Uz!^sy9L8Q~Ydqk}#C{k4}-t`W(Od4#} z*jN7-#*IMY0|E7^djhqTF&;uka`@;`=D1eT92dm58W#C`@r_}dMO7z$KF0j9 z&O?vsP~$iPIz6lfVBt^P47~$J+(TQ9tR)%V9@JZx(E)|M!yPvSBx?u4;1f?EY`PS1;U< zeAnT>_I1(v5$X=s-P^@AmMZ@C@g^iXt`pn&~qE{r3@G7bI z?u5NRy{bx=^=2EoI*WUeguZE;T4M-F4_{Y2h?HDy3%GYxNSt0{jkU% z0+;}a*nHu}F#U5y^D9FvcUp%l>cmA*QKdXznD;VF`|hdPgon-{==|4~Y0>gVvwU*0@y*~N6! z!iI@XYx~K#wqaS)TOS|wW=#+4uuJJ>CNxi4jt4ola8YZyub8Xd7NCl)c*u5)z3;Yv z(B1mgyGly?(bM!-1%?9z4gR3+lq=EED_TB#|ayLfRr5Oy z+~>&G;v`sh+J z&$?#Kz)ZJJR(;kx&;M-!I&2hhtJWvzkK2J-rvrZV;r-HfU=MGU-g$%B2N7eLd%UHR zxQDu!&JAXnh?gMANK)TtcOrR@n1h+)*zCM>Dy{6k8Gv3ypZesk>^JAUx6|xRq3=O} zyu3>N{-+LS%TiJ-Ziw<37Z!W#H@>72&I2J!T(~< zk*~JL1~XE;6DR-PT>r%;5lhpduU_$DKv=djsfm9FN-|+kB7FQvlppyJ%Bd3c5Ha&NUcY|jv{TU3qjhH9 zrQ6e`d6M3Bo}rEjis>gBW6y;#CV9|xJT?kr3~qRj!cF6Zx~UDSUut}s^r1eCqgI^8 z?5kEn@h?kC&hcK0i+_93YnQo+U)QMP)5#sAKelcpM|-~i^^R)Kyq+!hKkdS~k>aJj zGc#*36s8<<>35>1ZaPM3%ASg8mOpGYeW%Q^=(}i(q%rU5hiox{rgvs8ebg}(dGY@6 zez}dJZ6jGv%d7K(a3sXuC=Op7{BD_k|mZ{O8ww>gfN5=GhPC-+Eb5oY)&# z+VE#eM?*Kz$NRJ>#u7l_NPszuc^AbYkR;es(irCgkl?oCi4K2kB<|RZl?TH{28;?4 zE7*O~OpTGB=Q#{K3JaRd*`0@seJz7S*lY-At|h+b#;}kt2M=6_kSJ~wr zoPe7vY-EBMh4XIY_K=934l|Sx*JJ*R4!ZD06Zi^<_2bHQk`L2MMMw!e+b;Yb{mSsv z5s5VD909LKh#ZoXrFHhc!LbKrFeLyvU{{!3P*uHv;KLBqFc}tVy>?$I3N!dc1YW=YkFy+|Hoz&_A8P65HkHFJBtc6Fr;$7Zzcj;IeZ7-nx6; zkxlx);wrKZWnbB@PiFPktKyJxd0oKlk}J+@vc$RiJaSsSr4X9L8@U=tr^Slx9w_pq zsBbEZ;drh__gY$BMi*LRy4Es1^*5UOt8~K$Yu}j9Z{*jwI#A~vaoXPyz&{#u_g7i! zCxr+?-}W%5@!f{l%)b2(3=h07)D+aF8f&N!ZQ2^z;&Bc3-)>jvSNl_@p=xz1o9cSv zWv|V`yB6B2OV6iVmW|>|8?veBKJxB<^yUWho`7Z5wN2k2p7h}x=XUB<-ipmM3Y@Ju zC&bux^UPr)BG}VYzlba(pZn+Xn(0vL?Pl4zQiJ{v)vMk5Htu~QoKD}3yt03Fzj9$4 zR5`KrqdJOBgckq`SE0M8WW&%wp6My)+Gi}K&&|!A_fS}tX-=LVxG8j_$v^4YPM^rQ zej)cK^nXns<|sWyY_|;aaK!DFkv2&{Kf*ByVTO99`a=hcdF*8uPV)MFPm(goPU+HZ zGO`bCn{7+ZapGgu-dMY})?GtZyum#1$}V07C+_Vo9n0RY10gzp0LC*|7qpiK&;NA( z-pTh@`pLvMN2aenwc2F)pj6)p zeeQQ*b|syv6N8(1WK!y60j88;Z5lfR@9e$dnKN!LaEedY@8qrO2S*lq?kgN(<*92r zVcc`+=y{;;a%LL_eGR*I?nJZ{kKv(Ze^&|tBAuM5RtDw=m(ZjGeRv~ttumf2o@lwg zE*@@fnr#w{n%z%#a2oS^-iS|66v*H6m!2Z_w~;aVNfsBScY;jbJWmnGzLzLbbr}h| z;5-q3@3*rsu5sM+(&!|`(hd#KWAJsq0}R%$>QEx28o&O_(=$)>kVI=8LQX?krh4A% z(lPGI%*skmPWFa4tq^kpV0>ueuqmNu3KB&albM}>=u^yEVO&F|3T;HC^Ssdm`xl@# zVa+{Kdcb-Cx++MJ7d)K*_L`U54UvQxd?GScd(9K)Q%-F7f>YFT9qylTLOd34KkMul zB)2Z^U)&&lshapcJmTn7v8d}G_N@`G_5H%K*I$0USHC25)TOrxhPrEa?-u_FrE9wa zjS%o;B24x7?*i`irT>cg27YW1#aDww8_5dq)>zFT=8zOfm&+X{!-NwXP2P>n|0W)F zBKw9wo;n+6@R$jxrcu_#7hS|9*~foM+G( zziw)+?qqZGX3~9${M_8g#(3a5u2y^Wvj63MYNGg?L+lvAS-;8+VH@@t?tAp@B~%bA zK7Mf^PAtFI$)y%KF}Z7UYu_n<8A;b?y?)m)8aGmyHeV@&v?l8bmOGr*?Y54zP4?%; z`eOF92$v-)ll#ST17#g)^HkJcaI6uu z*lOIr6X`kpdhXDIk&b4`i{<>q1)Hi%@{yEaY@`p_EOnpg@(q|(pkEVd~)QpxY z%k~W0;Y*w$-D!@Uaw11$I6i4fFFsj* zF1(TEqh6OpEZ=d~vch){EKhA-iZ->MZ2KzVU3(y)@Z6Ae%&~`|g;Wd`<2*-ccl2JT ziRSqb`-^*56ICa;eTNtsyooLeR=RnYo?ohH`ZdLzI9YGBhF9)mqc zz#D$d;297)fRe|i19j&qsL32{sXcD!R`$KZ49gtH^MU+eZ`bfazF;I@s_N_O+ZjBH zl@Lz2XT-(JOXQXh44m#Y`q(ar%?msAe+hk&cz6k|1YQ#n2LM+QGVN5gwPoI0e#kf6j$6ne`GhPBy+JJGr%#`DN9Q?#*@B#khIyaBZD(imxRuXC zU*P3+8Nv);gBgv(slqd>j=i(yx|DxSWJkf*< z{pcm9Kwu(xox~7!p=M>Do}Qlj#?lwKitNUk4rSKUwyyyETKH~O-0Ll_Ytz;bOTLN8 z)z^EGRR0_C2#d(B+KF5~q4*D|%djs`RbUs+q9>B}3Dqg2WtkZngV4wiVhkcI2~d_| zK*BdfWWQ=ydtiAafOLdRBPj;kBwjzvj#xkeiKpkBA4L1`njX}puoZ)TB)Un*q796I z%0a9OM;Ydky8yTda!xi-a>Rh*J2AH|iL=u&>v*o*zp!)-LnD z0VzSw?Oa-#ef+n3l;eww-V`d1#hxfAe)DeBl}5_BP%Jr_#MDu(R-VsrXYeQkgu_5= zp2I?&F(~Le(xsgIeh9&7!yYQTJcovp$o!Oytkpx($)*jwHqIli2B`}-OLdUAi;)$} z>tT9&57b2hX2oj%fIyH69?8-|J!6f)lr7*k4n4zMUxszY?y@ULZK8WQi=YgM#Zm8#eYDl zVbXRoY9Y|*DG#ASm21*RFJI&T(R9{PS*=?a2L%-==?(!wI+TzW0coT=q?85;NfAV8 zB%}qA?tVd}6zLG98>CaZq`tN9ckdYI4F5RRfpSuo6j|^jA0@4;4KC-fol5u zb?k5d^qp|w*5SXc-5OtIZ&zU3Tr>Y;siSUSv~WZH+TQ&p4^#wOhjy$gijQ(fjHE}R zm?s9x=nB~x^-`IpqL_yoA8GmBS--P>--}YO^Z2gq-8-@JnW{^Sm}Y9jL%%zBA8`sS zeE-@h@m_@Lj({5#tf6-ckC>1(^qe-KuO+|9R$`vrQB41G-f%0NfSr>JSH-3_2ESwx z^|+2$yC325PPhiT#=YrE%d}&8DObu(N)rY~-$3})h;!NPapy~M`WzWq#1aC7u_8#IXV1J7;Ib8g4ytp=~`fAjg^PWNhPlq3Y| zMqXYXJvq+Y-U&Ro$RPsM4=@`20NEbFyW5~%KrnT6EoWpMD`<~)22dvdpOtJ|>`p)c zeqcs`4Yo6v-fQPI2F4h|MFUq4&h`?84J56M50;(!T@sPM}xh#S>@Obj4P1I5>4}o*#g=AILPn#I-uf? zbuQOTc0laAg(p$5Pi$^4dhz8%225IT{DWA-mlUp4{q~Gu1!{%Z$YaIQd=5roi?({U zw08o_>;*`(f(ff1JQEDj=@k_*pyLBz4hb%Sc|A^iyZPO3`2UCIQjj+0)gfH?%LP|zGA2e#LylU_$OkG)>OlkFe)C$SPIL~!84xCv`_IH;hsq6XPg zlLK1@W2>hJ2YH3S-6nehB=~=dYUuKqQq8}mQEG(xtI+&nZa#1RljO=T8;X090oEks z1|0EMUJ{`Q6HLEJU-7U0N+D|Y0G~#<1+cVdjmK$_pYme*{u3Pk0qTu&-VE#pALh0E z6c5z2{S$OGiLYwUc{h6>@Xii--tdmo)2CIyovU2Bf^~DjNb@WB2G|Xn9h{}I*xE9C$aH-9ah4|(a?o$1k~gxPQWo{1%eT_V&uc4G_W5GnLk? zm;&g8X$MOI7Is@M?~%8RLW{Rr_|u>UGM!e2+iZKrb`Ke*Ygwk=u!!NiHU0bhe1;V@ zr5eic{Kxs65mCrv>?7G#CWY<85nZ3y#P+5ICySWt(4YLJNXzE|s#%+(^I-9o$&w*c z3f>bV8#4!Y|7Vo;A9^O|aJ?fpbqQa(U|ZYL9G<_KbUCb;@C>X?7KpJVVM;BQuBoP< zYqwxy0W-6!5D$4ch_bMDz`}U566>|*s-oU_|6LTiPJipaA>8qo<6|EWGZj~|iExC$ zaTOzZV6DGy#>J{y@S@<#Lax@0p#Zn_k^|leS)Jxq{k!XOqW0bjJk`Zq|Fg61G4Lvb>>}jr!6`@S@o3Mt7d}C_E}SzP z9|o4J8B#*ccvqcQ&8X?Wv1hO2?7I?i)VwgARC1v-SmE_YCFVPfoEg)2L7DX2O5xaRb0(=ZEmDsL&0k9$kp?l+ zwUWIZ4xE&oOo7{;-oW>*qdh3m1r`4dP;?O$4X$L!eu&I(hs)K%HNNKQp(Yg0ONde8}bwxCb6QU@g8DA)DD^4SsQTtUvB`JEwb*oUm6% zjOUOe_;fz@X$Ki=r-}YlGcvHQiE>g`4SEYhv1=xFVNeQPy+~pnYd)~nz39pa;740tgf{|k$zA~VnI|DEuDQSjqCDM4=Cw4@Q z{0n)jR!9|rOnRYyU)!=1Do!w_=3L5?iHT~_*x7FBun3^fYJDql*K{^cM>`JNoisza z0s`AJT&M}H?=_BZUiwdvxz}-%? zyQHrWh?9vA>Cck*{Z(e`j*bs9b22K_ldQv1eDw11)!&`O6ttdE&t6!w8s*~(M%`F! zkXje^9*wlrYjRKXUlLB*ESY}%XOHcg6z6kRZA)deEVw_z7GS}JSn1uwX8cz*GtZ$4ErQy%tbt|h(&S0|m25|$eWUn4cWA9HeISr&v$3o%q@0o)qRAkgfWj~k z?r}CxB-_w~y065(IK{GQuYdf1h5p^qbrkXlH|1cpr;?cgBo2M53XD2T4`C=;_?S;~ zq{X1v^CQD1Kk+e$Aq3&a=#qaKW%5R?U=E__a@g>0p5UO0O-lDPA6vOj+Qr{ zZn}#^(Ot?g*ulaUW?gt#?}51#i~`5_mwzO--(McT_gNO1`2#}|yaA!-0gfC?aArXo z9kFY}-fH{A2QWPtH50uv=TkGC?$0Xq;ByZ4%w5mmwQ}%R^6?HlzYnk;JwW6!EdmOP zN!f4v4c#_msLLxWe*oea>1dRE$Ykl^p-XB+xEJCct`#Dl{!J*estRF%V7-Ht64*BZ zPukVhl~+`h1?OE5qsgNj;5b0ijTgyDLJ%+xtJ5r!Kv!EX6mpL+n{1uJ1bcjO)T9cm zMX-+Yog;%X+#-<`J7|++sas8#;&5PtogStcIIrRaq99EK)@s0?0;wbimU{3O1+9ON z@&zwzD4BW+arT;LOD`df3?}hf7@M(*)&vE-RCtC}+~<}GKbN}-bLym;@zVdC0eCaq z=ghfS&G?98vsMOez9^@zKz!;s*m(ffgBDnr+CRV3Q5O1j`_?yu`oxUaY7n^mUH0Xs zKK0c3mybizZ6#573lq1TkH5#q!SC@~i8+BeIoz~nu;K^T5Cyxz>f=5sCcm$?$$CwR zHA~|a0%}8pZ5}^m`}V=+rDO89N?Pz*KY|hX!*U*tf?Eo~ksNl^>FFu(0pf?+ zq!-!L#*{1u--m}sDKXQs8h(X(~tt|DM}QsGUf-~)Cd)mhNl8;;Q#SIw z%9;|^_RM54+2!?{H;-$H6x63Any-)s5{0AL`HD3t^(hSu{g$UEXNs0fS6y?C7YgBS zgJVj%y@r@2(H?7fepTpD-`ii>lDn*=%P7>kJgj_pyF>BZx~Ji$tD7|qWVl0JF~9fH zi&=^tFQ0uOurK^0|^z@3EaB|KMtJ_IRgiz{YRrx*|Z|yke=ekte)BBW2t<^W3 zi6BUz!d@AIh#>PI5;u7Kz{n2z8CL=}MCG6+C0F$mU{|2#7Kr2kT7kVN_|TA34FF_U zE^Set3g=@L+9Y3zR*u=7ti;W2+-~FVFlSYBTm&OIG$fM8c1lAH8K7mo=0FFBbt-H* zmSO3nq^deFI@;0A-PA*7;`1GH&2ZlVVNlJ$pc@Hf!_kBg;9;eO)X`iX&RkG2GBSd@ z3W<_KI`P4ag&Rn(0%WKWPTVQy4fUoORoLu<8w!|X@X&W!Rl-yWXR+l}v;|)XG~~X) z7e}yWa9-*E{0v+pq>mN`x8^@(OsuWsT(2IVZVZ7cSZvCH8w7D-L*S6m-}+{QLKF zHg@p!1YkO#e_}_Xt`bItDWqf+l@=_M;w$p3KwU2&M8M3>ME~oZ`%olvB+=7r=*Fm? z>@PcWpYw#dNvg0%u*$LG4Rq;j9)@*wgaxH@akRLFUEyNr)_qNg9vmpE6F4zAqweQe zn!vvC{MkyHuzlPPYdM{9e7 zTtb81jN|FzR0Jg?m=W+AhWs_M7&XM&tOZUms6Z=BtR)X8N(ZY&?Vb1GDpfpqWUptt ziLznw*%Z>^P}8bXI~CPbmlRU>NqMOdu9MLipvx3?$|5ys#zFGnF8`QNj5jmWO( z8<(avBru{H8Tr?DTtDXg%gKm;HB`H`ttoQ&+M`8xMhb(p=4?^uBdxBvN?k>X(V_@n{47>N~n-sPbGopm!S@icA<3qxCyEyl#LfC2fKB!C&KiVNa!XAkp|rj zR>jT-Yg&3@gz3e_5ipm)h#~~$L{P@QL7c9<+`oGfu*`A5fF4U|WjKY{AYU^6$qv-k zD=kf8;oRvEN8kMfeo9c+=r;)=JAt&O)_can#s*kBFxWx$A@I2n_yPE%fgyo3)PxiQ zLJW+);PQs`8rbI$4<@)MgXms$eEW9!cp~Mxp!?KG16>T792ygP6xx?Jvnm4K&kE~? zZ0w7x?c}XR1_m5Ohr>-83c_OtyOop;RhaL^4l3nzY0WEWvGMbJE*6B$Wu-kMX75wq zh_+LV=Rn094^G(}v=!I-v&&s!l6*ZH{B{d}|ADWQ=fkqa&U|%#H}1a;&m?B{#F}P~ zUIv1Fl2wDF=Q*w4nKN>3k_{fgL5qZDj4zjZQ#?dzK`hAXM>bF(8j2naY9OdL;8{S@ z7YPEs4svmWffpXoeu1gwJ(8k7?!D0RQbXxH*-We*lCM$(&ENV3h}hHUf97(aFgLkc4B1t0y)g z6pj3aXfELuRO2v}0T)H^#?5TOUZexJ3%36diiG?R0zOhzRW&|*QuoUi{Ue+-vD3}k zcI6r~*|>ZRl=P%wBtDAWUqWXJ4rLgykSwOmaef4JMW<6;9BMsQ%RB{2VU7r)=T@xZ{sVubijD(>1X2sK z?7kAdPQGW7dnaLG(=O$MD95ls**&!IX-BObUhs1C-0PEDrgo;gd-Du+j(E(>p>zcF z74W&-T+n)C?C}Q^DRVPY^F1(Xz4BuPHQ?|~u{3;qJ$vCIbc#%Vvyy>4W?~c8gzvyR z0vb8ojWMCxP40war{r#@a1a*7tWmlu)>56my`d2dK^!;%`eX_B!q>ZtYO;7O0759Phz7Q8X{w0P~UKX3g~ zqc$K|6M)MA->ecwnM}gnqrb~-`XAk&ahAKrdmF@YP;6)x|1`zxaVn^ZP5D%>>T5)^ zv(vZWlg%IU>w?{a%D_NBDdMz4Xji5E0OYL-1;xi%NrLL80qGfPXYIc|( z%}(s9ZRN2UvI z!7xMo8Z>?2(tx#1{reBAN_p=C7*Rqn?Pni}H7mCA<*KC4fqSsss*)E5Ek*8zmew#b zu-ZNY%veF<*>AdY0;JQyxo+x31hEye9ZE3v3W1T$TJ{vgybeb^TwHn7N4OTi)*jja zzy|sQGevh?<5$y>>j5ow?IZMc80!asa^55Nk0dA!}00<-{CeD63i}hL?NZ*S(%H=F4)>|GWTUo$6?9 z>%}Ss{qEGmvK{eiw*2>~(lSP-`g+C(AH~I8NB7q^(67}H{8l?o?8x!P_bfKx@Ck+N z0kIScMcR{XV_Ph|0c1z;n`aS~m~vGyUuDxMjLS_)O8N{H65tL2#RKW>0SYIak_2G> zMA?p5h+(6Z91_i3%_ege{+vt*UPrg(;zo_Clxn=em&E4st*4sIx*|Jaj7o6_q_H`$ z69WSV1P8@|jsd$PxTL~n^PZ4U2Ly1ylJ4s64oSuZfD`zWh>U9`VGda+O^#HehLg|W zq*dTgfR884bO4<|gCwe^wze5+>CrieBHeH0>vI$3qi98nUp5gJ8Wo5sl#jRe*tPhI z`C+3RH1AP~(P0*MMj2D=Q>zW}1-~{MKb4BhAy0%BPN*{Db6NK?MqfI-Q=RK*PInnt zJ+_`DevbKWgLGv1ik;;jhpy)LI$injAQA`?7~#J7Wx4F+5s*+oBxHxT)W0}7QO6^k zasyXf@!twI$56GJno$_)=*Be-lBHth2k-T0(JJ4z%3v*Z#V(RdUBkJ3)j-iYAHyZx zN8&>567LTA?TNf)-Td)#Tl;cUWNd};Td}X56>pNbNi^lqrrd2s*!@Ycsxd1Yn|ve& z3I~J=Q(G#XUkp=I=*S8u9HRDlQxfA8c%UV#v#8KYw3Ufj>zZ*NlN^y!bRHV^mk zTwO)mvE7RLdWvQFftT=xd0xSs!t=0@f@^uj*+t`_oMfLzVloAt5@zzS=53sw+S#=) zZL)ZriTans+8uqGb(j+GM{%)EBpQ!dCl^GT@XBiC+Pf)392lXKUZWv2=cnyUX;}IX z^B6`20Q<9ACnzzO>vF)hFj^rSTxW3XJ3&qkiyENPXuqFVnHDMdRa|$Oo~nE4xs>$m zc#+!=X>>tCwC;5@kP*pNOh9VGLlb4xT{wtv9Ebp|7SnU^)z*k5xmLV#prO`!7uYSP+yW)2dG>1FaV2wKpmkJ6 z?F^il^Hlz3(9&EhRaB#?7mx~_6Qp1RPg3ct0Gnv_b97lCg1sQAR;gk3t3sVm za07&GoYd#2`Yk6RT_dA7{ne(wU-}ClHTV>|nQYW}+rNJ-hUKZb)Tm2CY`#R7-FVpC z14M-n%$M0r4`WTLK%1T5Zii{*VjE8}^k$Z<_CC*@FbalYfZ zU;XDji?eRQml`ekHw3aeQi)gZeX%JFQJMZhoj4Y)n$9#oJ~8!UW&G};c94Z@rJH9u zdynA$6-E;C7)+P?5lP9lnd|@#5^o(_MRu3Z4?44!i#$2qbh6p|iUz*>n9}ABb$Xem z?t0WZP|zL_Kiql{_duuDPqX-7YVDD?3D5dz(JA>SD5W%Kzffzk7?x4LYPdN(ja*Q) zhof!(GRIA|ISBCTtY#FVC={8vYwe~L)T^tNT$q&xr@Ib3NFo)8KH2N-P^_=wsaEht zOW50$johMXeCK9u*Z$>h^+n-#v%#I0z-&kA$Nv6}_nMu{p zYb^-$>EM*Rat_~&47+l7JfaiQ?-tViX`}0yqiXBvH8na4Qf+4C8GBd@=w-m89~nAp z*zZ?F)+B&^1ItTftgU@5##MZ|HmaK=nrfdil*Uh#&ixKFAL+{a%u~(GcEzz1289Zc zS$b@gw?m-`wD1~;uj*kS(W`gjguyIuE=!*?$&`T2xUtynP9weIzPH(>VO{DZQoFP47_#p}dT*CT# zRGSP{BR7JPc86ZU8ICWxOOIUfc4}5e3u?pvi8Orw%=M8?!@wq**pk$8%6<G5*?j&fMq+iqtHAwA0(`ulX}61zKu)AK^a zHOIW(<%GFp{nA!7J&X94*7X74w!nDywcRrBjC18u@%{=h~$> zuz3Q~jDmrh+tUQ9_EN*yIsN$Me`068EmD<3a&2p~&hyt4%kQ&@x&@w9ijJB7S@Mec zn2GKu+L`hF+Bfl_x3$p*7!00umISq$X}8#37wZx$#zkxOnpU`ZlB&NxP?xMuJdtI6 zUHsAnKfO@0hCH#@*=gD2hTsgJ9UmChTFtLXz_Qx87* zd4$h>)^NNDvPmK=x4)VAzAP6l^c=CpZ7$jH;qC;w z2QLo~K*;HdZ~pOiVt~}45MYMFsY8R~d_h5{FOy}D|clMob8~IiLag`vlDeOhxx9>IK zM{Q|ao7H4<1-7yoPO$Emgr%laHV%V2x%XOqRs$ud6Z`dE|B_ycBY{5oev-D^4u1Wa zQDpLPV$z;`Y+PFIM6KgjgKu6sYL5z0ZzkiT-BsBuHNrS}jnO*Z(s)jEi03~}5xt}d z_viQ7YUFx!C*cZVc1ivSlqvQeAA9`n)hK@%cjZp@wKPfvJ^RZB@zPg?gRHMf^Fkd% zmIrZXjn#R#FY`W(AAs#tth}?jukj;mrwDHb9Gmi3nEw)OhWY zd}mwNzK)-IqtN|6eC0;{InFrH!@04cef|BFUqgPy!}XD+Wg$cH%H5%mEjTE0JrEvubWRcK77`tK;`176cU-LvfNxlg+9R~S@(3BR$H~S z9^@8$%D^vhpKvOC&b>Bir*~uJDqEsSUKz>jgRHtYM8n~Lczs1T<{Ix>>(9FDKZ~KO zIz~B`_~nh8b@(-JT=qYA<6G5g-KADf(g#H|j8rjxaNS@)$1yKYygv^Iy_LH=X>4cU z@8?XZDwU|XmqMgVU$SGSN4ZhPYkFiGhYmYi2)!Ra$t#yjGiOxrlbwZA&xTCSNs!nsjB#f{m)mr&gT$`^ z*%P@@kR*TwAs$wq(|(t}@IuIXv^hEXanSha#OH(9`ToF!SM08XNIZA4^pCs<*0F@^ zsgi-;BU;V+omG|DPH*5}4@e`*{YSGoOOX1RxK10VDD2vZK>eX-gJ?_B!6%QlRI9Uw zrgrMYIUlP*^MAWC?_?GIx6%l zbTKQc{ZtY!`*&`($DelEu<+ZkOH@~cWoOZ4CMi+QHld|*suBmslY#M{E&7^dMWxdX z*Pfsa)3vTTRkEpCjW)OkP}z!n`$zV)5zj(Yy8;A;;>}b-isBe5xca9HjDwj(!`~ zZ9Xo8)khV{qcNuE!Mu^TDIupvFD~&myQ|rY<2$i?#VQAwpe7Zy)`SzT;3UVqm|S^K zo{*fozhu8TE(F*iKpG;+%^h)`ng*BUNKr8~A($*7j0)^9tYLcrs#i^ZIy^?hV zW|?JV*Qj>QC~FPz-hBVY^2w*-2d$B#!;|&TgQ9nwzCj$c6I{KxxVY-9EaW)5s8Zhu z9b-?KEAF4ohDJw&znhxEqz_X=86YhH6b3gTh-|=#jVMpBS1~g;e*=q>e2GRdgTa4? z-8_ghk+fo6z!6aajaa9|5NcLP;6~D`CS8lsc-EiL$mDj&!ouPSxr?#s=_S~LoE?~4 z^20Xv6ZAV`p652(pf0@av-9wrGy1F4UG&?_8koM*dpF>x#8dS5goZqvFqJkrB`26R8ltPjA0NF!TZs!Y455YX+va*FwGh|rq(mP54^PR6+0gd zJy3OvBn{|fT)j_by1u6 z;eeV6wOLwSJdS5`skK!ozpskwv+gcS!N{%_+fN&@WwG~Oc|crfIo3;|Bbu9V{nyK3 zPUgP6pSaD|D3IlVln25;IK@qEZ50pwHcy8t@^~5h*Fd0!be#RZYQ*n9dCa0050+lP zr<_?9dM82ec0@FZ;y2tqk+*s=i4~Ysao@~Us6&r)u)LE9H_k(6Yun&ZdF`WHf9;^t zMt2ViSIzsc!K8oyL1_hnW9J(Yjr+Q;hBw9@5l|RTa#st)$Hjr70^Sc-SJx*NY7w=2Tuz;`EAed1ED%#%+3me zj>~D@kzl$3F%>b{Awn_2gUm{oH!w(XO{SruniqUEF9XW#97@7 z=T~TU`2^YLJ>U5> z@CD1ik9R8zDhn}f=Dywy%QKH|Z@9MhTjQ46x};XX{})pdgth7#7%-;vB3T%anjpFd zgISlU9GIWK7@lP6+B@B~_lC>}(Bar9UO=Dge+pjz>#PPZf(&Eu+Cl!*2RCVoA>NYI zXM-2%sZ>?+n0sEnvZ?F`Rl`GvY}${#u)lU%jF;CEV#t(7q*dF)0`$bo%*;%uOya=< zur}OIRe?|nF1@n;Va5#ik`AvxAgz;^W#j;^6~iZA$>X1K^$dd@mi=^1{xyy9(Q=XR z+pP5N)g9N>-Y0!bREb?U%El(wO8C(#?sKuF@VLk~L*=83M}Z${0XGc0?8ea(xfkEI$ z{)G1;+w?D1Wo_O_i+-kx)}rclEj2YZkZp(vD#$Jw((iM4mS0-RVn~uxTbX34^;+)y znt>5(bMMm%w`>r?g4TAF;Grf zcyKCY^n6bVCW19a(Z6W;c~8?Bq-n$H5tm5=zRZ~-nf53qfK1_mN5tX39K z@FS!Vpx7Nr2l&7_6)WgbSv$y%4|H4~ikRyW=fLz6X% zfYw0>gPqGM@y5p8t^zZTa%Nk3!4Ag_U@cfw^|I@fY$Meq%cv1!b3k*J`kk-C2hIij z2$29+hb}9`qySrc@R^~dz4~V@e!6k*VpZZim#~zRi|Yk!GvN?|#tRE@#=;>t0M*e@ zrtszE7Ol3exYJNg)44r#cOXnc$W9}0#p(J^aKIpsGh8W1GW$OupL*z;09sf}s!=2aAi#*|9S+1Arn8B^?l)qNfLsa1unxJXSHh&lg? z#OLo%8PD0iRfO%7H(Wa|ZWdl(S9Cn>K)?#!C2(_lp`Hc?XFEHkf(;}y$Ii~m&7DvY z0j6*8>taw3q=i3B6NAqw@)3m1Jmd+X77<2f`o6Shd`SV|=({>uj5E$#g1OG-p}GEK zzZ8I8?5lb=Z-j}ipg-Nbre+{}(CAf=S6wsRCe7ZLXH2%|uTM5tv-ahdbT|}PM9Xyq z*EO#yalY{?s5J0?u1YR5^%HNVImMV!>_yyYL*Zz<#M8a5zTlaQM84U-3V|n1G2JA^ zXJ))I*}c7!&3sArj5KkU)c5ROjNi)XoRYSGbZ^u5l-xmB$!eB(LhQZTvV+;UX>QIb zn#+ZyF!d1r^4xWKT#2m;A*?0i?N{5Cm0 zso_X~r&w8I!reTVKM$@^U+v-eDOcujgOUdW_lpwOS;{NJIIc5Z2|e$4SC?c|GAhH= z=urMnb6$10KG^64pgfw`)Pzc?)BLEctX%S$FH7ZTy=0q|VEfil=B+C_TSd=4`}n6_ z(E2=}Q$9_;QB_m{l8iyZ=aR;>xKOQeeSIwE0QG9Mk2zJ!nz7Xq}# zj)x(k2oxfj0?!l@QwWO{vN2A=sc<$Tkx%f`x*<^-VFUC3$+jx#s_U?t!LwzG>v$IJNt4F*T&_grJLW(;0T9`5-w(V#6dQgbf~fTc0g|8Mga9cF|CKnZ{*LfptcQa-x6xP(Ys5EjvjN?Kz}CY1XS& zt#(^k(`q<}NdxbRz{l%ca0~nQ`C0H|hL!+yvzMhEFAENufREZf-)d1|c3=A`YFK>K zr-*dwL&)Io-{|z;tMjh%6MrEuvZ4EJ*T5wViVXm#R54cHA0lKkGJNE)`FSK)!5%^xvO<6JOb^z)?{mF3{dy9K zu^zu`FP>y%&ib{reL~qszw*7DU6>M+0vq+`rr~f~^R&oh1xgNP{e~$akyCPOp>LD^ zWb$8xJ9PIX8*3@GE^gvYlLCgrV(}P%DoqAo_gr ze_jBm=-0={_c=J&HolK@0n5bYy z$xMy|x9Uzfxj?eyQ?>b^Q8?5E4}L8WqNlIt4#No1)3^M_3TwjMf1nD@Fm?Ib_3O3J zY6;9Oq^arteQAhas*0a5K_(Ky#?GgQ_Q>84QDnhOo0ydJCqFk0!Akg?bek-J{)DvI zLhh6;E@lgWr4V9+euv}tmpc+jDj6|7!4%^O8A-(W0!q;WT-3l+Y$uQ+TI&QfDHZnJ4w-8VX2k4KVeMKg7$;T zZa)|rImvsbs88HuMRCT@2kDB&uv+}RbZ8!S^ZhiftS>oN9;-v`ZY`W_{W6LF(;KGa zWOQlr)p8e#=t@fWMmxFDqg1j-VOGAYxU(Af-rb%%tW^qv9uQ4<^;?+854(MA>Ysl# zt&Dd*mGn@jZlPysO?vzM&XsnP1Htj-Q1k#Z-`r7hf|CKhNt;Wqr6OIWaTTqq(O!Zl z=VZGA0cJ#XBNwHd3ED9QgXCNS*EbI9yBA~Dq+tyVZyit7b;C7ZQ>km7?Z3cH2eK@T z&zMyCQ*E#E1vs^3NtiB#h3A1O+TAp+dPrG*5H@|85m^Lq*W{~t>w(|}*`GVuJ(k&8 z&+l(ZKHW=sUKjLe+KS6@sNZ+{?r_J=94A`p!v~ypjzz!zRJkxFXa0W5{v^Qp-BKQY zZ@K+_f?zw+4tUwa)Wxnoa3M=dN|r?!p4s~|boKV5(g^wjW$%b_y)NF$L6q4M`iuDb zT}5wYk;>nCYwK%z`5g%lVGPWpGWB^%{W7U8i%mJ7@A)2yysVRcDu+yb=#qC0-}5Fd zB`m8?zOVCB21Lfyc-8=3(R!)#l7{})*yJBW;pYlZLpbIIsI13Tn)~k?;HLTzvbC#O zGki%h9bVvwvM2tx7ICPb!8o!|qY#1Zw)rM#J=#5W4BME9IVVcc1hU0IAMV!B1g;oF zTdG{}F?QA1x27BF7zH9iDXP|?T`(IUPOieeh_4gb!^6-IGkQG~FCg3qxEX*8NC;>& zNEqeuds@Ux0|4Z{WteFZcR1v6WPs6m2`^{Wi%o7W-!I zqG^vmj|6uu&^uo2E%nlbmwxppaG#kI%=l3t;$nJP39jkc4b&H4K|@R@+gyZgcNF^ zaknueUS{*OfV28A#i7RF+Uh^}e(#+4>^1@HW0m@RP(xJ>wi>_#W{#B~mx8kpK-5am zFh@m21sm4rP74c>;Kn@5PpBoD=1FPWrqbac)7gX9MTrRtNzVYM7WP29pwF9xh=lXk z5Y_zn>6~LRMMSlDAVtLC2T2&_V+nVrfs+lRgg;|t-ka9e)`0rvN3rz3X(1PeEHe^pD=uNvx&odxqi=;?U|6WKPUGHS0!U0 zH&03IH~84g^+(RJU+tOsfaZ^ZQ*ZePlzJPYo$xBxD|PtLN)>_sq#tJ2!Y#VSc(si~I(bem{xBhwY*1L57HfhEX-2h!rocFyyq`d@$p%}Xw;}?UD#*P@C+TwYuj9WwKqZGj)gW%6-yo{0bE>-K(1f{I}JyUxq;zU%OL_imnisY?16 zg?B3*KMb^}g)aS`3NYz@*=6tXr|68@V)hiGOU>pS$oFmn^wnG2Ld=+;5p#Er%f*Sh z;picoY;V)x#*0_l+9TV_5w{G}*eR&tjDB(c@8Ak)mG1eCPPypo4bQFCwovpM6VEg& zS;Yj5l-Kwh8nr_o4jwx0Y&P%(8#_LIouxi6%k*7)LtC~%z?WDSZqNj89cr9)IIP#T zv($4P=90{Euhzvuflp^_A=FTSfe&ISNLm^;SHRYRT`;saY(^_>?*C2b(qYv;9XW|N zZW`(SVSJT^q%G2P( zR1}zrvq?9bd0?L=VK5)5=M0IkLsG>qkAUF zI;KV}mQU;__VZZdB6XL&Z5_ooema^;ZHxI|E8Bc9(~ z21}}uB8R_!((hI4())4*+zuHK@CY_&$Hwz&t4vrr@t-oiO>R$D;S6_z(J!@>s>!Vu8+b_~^Z z9rN!cenKA~!ycYz#5NSF|2gnNP(nw3mq$ot3K~RdpWJQvbg}wr_k7Fm6Ii$qwh&|{ zfj)#-A0dc^i>en3s>eTHHeUU9vbPMqFW;bDSXfvA z+Eq+0*Zq2tKe?BWC?wD|N12K6EzX0DpMk-r<5S^sX8kn47C}JNBqV(yn5U4702Xq7 zbw+{GiaccjPE@=+!4XQ{QUSb_OzT{_Qcq2aD&og0R?4Re0?hz3*%8gyFRsnAvbM)I zkXYi}KQ+?llN~XfRM@XlY@g@@ny=d+)2Bt5c<#%_xb3u=V*(y%t7 zME9R@k~=msPRMsRKAh${oQ-Cb&XA{^JTSc2PQ5~EZQ#y;#PZ^pz?_|NM&wUx1&Y7^n2of>U#sjQOq`>g46x0{M zM2%R2z=eSrVIi#p-$t&HM|TpZbnV69eZ(!9(baF$9ubcsZ6dKG_BGiuvibDerEO?> zWIfg^GH(3U69tqk=MM+G*>S#`pJD*80@o+#t+h$Ejn!{6b4wR=0PW%MuGLJb7^~WZ z;(~z~76EGmU;E*{{WWEIEAB@5zJEg9ju)@rggih}*Jh&aqY4-rwse=4!ZMFj5D2ihE%m`=RP~lrHE(V72R5E}>99|6Vhl7FE@9vStqZBsAW+1~=?(X4zw%?sV}|mI>XhA{Kp`*56B} z4K}GDD4?#}CRQ#d9gP2@%!t4H^Q%{Zot5^o4tCX`RvF$cleEnC54WARD2vB#y!+iv zE?atwy73`}L=k)fME$9UWiTdfmaQ>+JKP;r*`MF!h!;*`!)p?5FUH@b}0h#0;+U@yaDA$pL`D~ z0Q`!4k|0?Q#h9{8gweJ=HH`U&E??? zkdnaM?R>ob6vPbqY;|?=IfRk%`a>WM9o;ji{XxjnXTy%?q(JE4g6tG@P$Fev;FE(t z7oq~l!~sRc?LbrO05*{V5BY}|A3%4VN62=&(ZX8VkNO(7=mK#2`Dj{om*7ndHNRkd zQGaF6-Dg`$X0BglS3T-$y@gFgiNf*f$q?{4b7-GfH2EjtT;sjt?!A59`>EUi%XxMX zUh4KQ+4|`z*1CL+K;`4Y{FZ1Z+%jLHe{q_OyQO+rkv{2F-C!`W zDEjj7j`-JO+8sG39e3sW$AReD-y3PYSw@|<-Z1j;XT+}srDGDb{_Ay+pIFi#)}k`Z z8x^c_%i;_Z=*u1z96B^I91*$m#Bcq;E4wLhMHK<0^K-`L(U6T-gz&BMhSx>>fxAUU z_2Hc30S1Qq`!9v(CHn8j>l2bi_Pf-JL~SH9K#}!?Mm6A-LprekuiB(W_vtzxc-!hw zLHcAiCYqPpr#7tKyWGuOmybS_>wbbzA<_jPkn++JMVF0}y{pdFWt}gcJ*{(|SVeD= z>WGNbEbLfwoL42MU(w9c(QTMIJH&%4v9pNEh2raYaxJkEc-NdF#bMrIe78RvJGkLApf+N$CbrX^>Vrq#Hp%y1OI=>6R`@;qLR_ zxp(G_;~Wv?yie@C_6i4j_*LO`VBrgL*D!j&j^;dp!mX)$78M)S8mbdo#Dy75voa1A zPZjQeNJaiM{-$$pV|T0($$i@<{P}pav)f1t_E^j>aHAJcXXtLI7;t?f%~<@hC->XW z=W~^!DsJvLeiBb#Jz?pelHv%~$06+gAX=xrfkQ4H!q4>XAfMo(a}sB_5iCal=RusD z2zv(*@h*X@7JxP86;vPsiV0wViwcIda6N(dLY?a_4I*aS13Zi2BL`X!--8G32rp(Z z3IW+u{8nM&4kk3d@5Z(|%qx1TuYsH| z03jOJ^?qmj=doak1?)FKra&CkbQE8P_y@p>%;e@M5hlq9&r!zP^X>+qO!M&a!r%<+ z!(*+T*_!=@A_0Bog8zbD1Acy+n5=a3w27=O?Uum)ehH&=AlQMX0oTU3ecLnY< zRt&xAJ&M(I>s!k?b_9vb*Rs^*URX zcK2DK04^rIBa{;ZZZ54uulK z4@2<@y0#_0c~@S8hp4of@(F@T!=68FQIwEljK=zqaU33k574hVcnErK<|9x=7rb40 zyJm?aKZlQp2hKyTJp~~*&j*^c|3jLIB}aDX=-_+!uyHs39XH*kL$k|dmc9@ zjW<0jZgNAt`r~stmzA2Bknq~diV1wfZ=}KZi<9QXNE|B+($Y>H{}Wj-yT}#+5xvFU zaS>0K(|gU?@aJxa`akgNM|)=8`hR?TP#n(xq9|j*F0<8~S#KrFa^aCe3My5a=y2R9 z=NA_a7ER+$({C_ow>AA5KS6$JaP_%fTut^%@_<&t$$uaFwp3{Pe#><+!)#3R=HBv_ z=w=(T~Joq9hLs$Qf&E4ZJh1zBI^iYC7_p6pdN1-{#bN=Ea@{XY)@J(XSHQxHWOE) zLs(TzBBZD+l82oq(j!*sPBW{UN~qMyI6C?GUmkEUJC5k!ew}s7{<_|EpzyNb$DtEm zwhr_J!~-pIqFq1Euoy9yMSrXQ!ROTfPx;d6k?&aJ(~|0#Sjk;9{O1Jp54(0tUwsk1 z5C?P+a=aecy>-f{2@9c3#9eN~qRW#!!~wF9n;XIu)05e|qH0AmoTX+qV$SXr7^lOv z1>za-5P=)70+0`|G7g{C15*V^lLUqyfMDKD-q+#wpkBD{G`U8H678q=SBQfLp*Ent z9gszXI8YE|TQH&mEiBlTuJ*=)vocYL9B6@7MEs6L^b8FVS2y592;X#NX=;C1ln56> zgipinuH~CIVbI0C1?mpuP4|F23gO@aZ^HErwJXB?1_VS<8#G-`ltB}F%+B3OVRNr# zLUn#dUK2M#OFi3oib0mrX;K5(L*izH^AWf0>uUX+ozzXbKPXv}-^Upq1hrpe$o?<0 z8=EAy5$WTfRr_jvwj%b{lFEbp1)|{}h914`-v(A{yn^T4MbeQKF_MlW3g0rB`EfzQy@5UB7Wx5hWDhxXEmkyy*lZv{dtA9ss zS@==(;$6_QK-c}!);0oc&+01F=?CAFW$N(rkD?$m#pWkGI#H}Rq=hg?gprt!;_g}2 z-pXOE#GYH7A$qJfIEA({hgQUUdQLB=ePY~&iQkW9>)Ehv^OZ~m<7czaY@Dld+04Ij z4NQd&5_iVT_;vyXD0v=3qXe}gv*wo#g0jR%1rshnIv{Ws%z$3l*o5oybivpWPL8G> zFpCL?X9>oN;b60shXN`ZvBbh;BNvPO1bJNNu(<{N9ZJ;1!mTjZouc9GFLYL|4Qbe+ z3`mnKQsW*9HvehG3Jam+2lM5-+?k5~%p)ANHAi_t$^LQX^l^l(da+4pb=mm3@^2lX zoztFhcL`Nb4`IeZ{ziqJJ@TZ4J=1>&`$|5SPACCLv7>@#s2T}b2G4zzig-r zs$G(}xL@m1t#AD%Nqrje!rI6g56|5CgzuMg@akb1zX|vZl%%dDv1f#zB$)_oc&Y~V zs&nzqx=VAkdagNJBJ1wE{rx7m)UB85=FIcjp6y*eMOD~WOy{Lci=58at-5A$`y&sS zMk{|7PI@w@wHU3xw9FZ)tKv~t(8~?4VtSff5^?cc;@&za>c z^uqmYjMwURcqZ&b(gFg}B7`y0eWK57F)PwNqivn;aqk&>cX>vNbGe4oW+pP=VOZj! zFby%qe13qY!9Ga~1E~LH?|J^=MC@>Aj}cGZIXopT4U!MQW$FS3OZg=wIl#IAyG;lW zg)lp)F%TOX_O3hl@PX>1;dn?Kk%kFOI9NnIF9ZymyuSeE8VTzg0$Da8We+-hcA5xH zZS79Lu0Z4P^KfE&usa8`tzH5q02n+H*zo~DAC!Thbt1t+gKVZ0X}`4SXkvKw%~$o! z{eS)xRy~XAH1~)lcM%8*QvKXE=~`p)G@kR^KJ41?nS>uhRzg6fy(%U)42p@W1o5`WgJ z3kwk>M1TXKS<;+QdFq+_cv&0?&_DF!Mr4A0n?KA^Xz-FDYNd+x)TjLqbCo;rBoX8heIyydW4CN z))9M54G`@^Uu-IRXQBwCgHSLck_j$4d3}*(z)%8+EKnLpHQ#JEgX^o(gI?gcyj^NT zzr(8`!O!1HswRO5EI#JqF0VH#c6~%Cqk^tCqw?(bCMZQB%;!y+vP8Dg$tkOv1wRpHOmI`9Y~H`~$4Q^wF?!sU;vW{nU;e`~8{9jc&}RE=ZfeAOFPPM{v7{pYV(o*80d{U&i7Tg<+o2mPb!I^>v7fUZ zSH|qxxO+Iyn)kJYd+2pxuDUCqOgcKm&0$ zM=&+x2fu!ZPz8T@L`az>7-0Hc@ZPdPc$gn%%b1!pVix;ZL~m4lQY-3LhhvVYFNHPp zGL;GK^O?s z{>T+2Jd^yPeVo-a1w#Su=dBh0P_?LPLZbX4`5AJXN+Z_>NE-i14!k}wNB*n%Y{)w6;j`#qwXY>wEQ0FQz|9!y%9lo`MNG&@1Ng2nbj2fD^8z>0tl{l z@A<0t-?tNH7c)qD#=+R+lPZF(aWsu{BwXy{;{$R=2w7!g(Jb68C{)k46?phi&%s1U zh=iRT{uD?Oc^S6aPd%y$s{Wx(XL6T4{o~l|*}*H!w5%(Us(K9PcYh^50Rb4|1GS@c zU>m}XApQr8asYl>qdJ!2+tN5@FAWQMQq;gqVNMou^q^&%}h(m>CO)gTAL1vOg@u23|+&l0*6T?+Rc! z2|<%H(fbrkTFKoq8S2>V3{m}q#YpLoRr?`WZfZ&q7;4Gr(U`jud8tJc7a9Ww%e2<@ zVV+|%5k*e^o6Y*9q>X=P2EApIwLa+$bg&X(A&hF5m$UHBS$76Ioy-k)+4>5M(@8CF zvvAA{sUyEjR#}pr)=*Fc=hj;~n=jNozz?^i5A97(XR9bhaJg z)KJL&P9+prr&@gaO!{u}AEn|F3x2H%a{Ubl%TSB=j>3X5)su%E5cy%Z&E|3a292I! z(rJx#?m|ZRP%fsc@NGd^ni6ZU91HsQ?MVUd*#KMfV@K%oisy{-0BK!!AT@Ym5XaW% zm{_Mr!24{!n73SmQn|YNKE{1*c}hKL!uia+lbE@o%IM!2Sq&)mM&g-r`S}kc`d69j zqFL*rzcP)rEDtcJei@=?m)>4?*`aq`A3UxSs;Y?7_rzKUsiW{@(Jr=fOUba&$9xQ5=k?U?klry!gc&B=T*}KLZuu2;RMK8-{f1j+RSa)f3N*D}vXAO; z)^j<=^>$pwcxSVIe_;^K_9f;&6;}CB=3h3Ilv(woNI#GTzjvXI=z88D4ey49ogoS4 z4E*ML9_a4AKj#H!!u1e>&DiZJ6q@u6;53&!1a{{cfBn#Bh+g-@ku7 z8^`VdtR4cX?orW%IlKvzf&j?J@w@K!%P1=&1O{P_4XZb8R5xS*1utARF32)Rn_A&v zVqzkK388NRXki5rx^uW3#=8vu8ln(h4>c?rIIp~|8#s#VHs^;(k7cLyE4scl0jNt4 zfU6;!J=(J6{CMNkvw83V^1l3?56n2&VxPg>l1f)6)C)ZcnTJy*twjYTqD6v`V}dL= zX(Od8<9T?X=F%ZfYFc-<&s~xb_BB=C)L?WNU})XCpC*D|j@;Ya_( z;l6Aa`Sqp!lM7n3?$_#fd8?1Cg#wk&1ow*Hn?1bd!&AV0;*p=r3f~=TM=r@yAR;cv zzVY<=n66bgK@e)Z%7=hQNt7u3zRir_1aL1@iXmzRkUjU?e`mkGanQ5RZ8(UM#or-( zzG=#4BGa>f1}^ME^d~F0hR6};rayv~=j2;P3OK3Ry`{P15nO#L`vXCG28J%EQBd~< zjrCc;xWvj=uKoQU=_6c1k_$4|(br^Z5{GC&Ci};3rpQ@%UM(#l5pE+qi^lG*{&@c@ zm1}j}M+v1|exfoC>fluWcq|nq)x+aH#!_J_JV5sD1@T~uhMoO91_4o({=NU$Ni_?| zfHwx8I#E>jlCxOy`ezdzW+Dn?ihr@J*idF!ni|EhK4&dzZe|25vlWms1RU_zBW!

    b`&M(yGzX|8Nx8%YAZC|jcP>=thKD2K%0Cs#3d+%ANn>rA~V_j zE%89?h7r#)S`~!?^X0+R)+f#YkDBfXm*Q{krvvIV;%=m>Ur((lvhNGm^nd8N^c+(S zVI%$suf54Dto2C;DQ$((KQc2mvRPAML7`7{Cq)ml{*mFm#h|=Rzr_WfQnfxlZ0ZoDW01K7{h%rr^3LA`ch!8e9T=6&n2_pje zR-gp$0{09=Q2gq#$GEi+;8;rt(l*2*3)0|&7b>i@itpb)B1{EH!pPbdK)^)$gA+>e$_Il0rtDJL-rv2UTr?a+iLfgLRFLzKn z9vnO}b;dbQzI`gR#`Gaq7w>sbAoXh!PqaPHo=#!1FLJ9d@sRzHrs!69)|Nt?{Ki~o zW0Um%D~Nfg%=%Z8!8Hk!&67)rLBdrfy(bSB4icYK09A znlvgo`#(G=Z)ukqX)MGU)(rTlj4JHj#|&puiY&6Lrn>sxhV|r`b@$UIeMU`#2H-@r}ckn?NxV;HPt;?34cZlIvaSNSb6vGSpJgWB(EfqHsGOD8OZC>tY)M{NGW{NQWprw7#^)K$$EOa5J ziMhBCPy?$PwGWZ?!Qg%H2+05N0xE1m+<>>|ue)jPDBvP%8G^*I`fK}i83LU~tgAWV zRbawc3mjgc@_rfH1WxXGw)7>7_gVb{h&2_3ljSqj{l~W6_pd#M=cm(rslADZ(Oy#^ zK<$AkuZFwObM;?(d}-|3{e&xa?)2fp$IUC>iVxo+(uV+4@FX@?WFEcts}r>`a3Idud752{C>$FKxrXxnYB0k5Y>#Cg=@ ze-aG#%gTM{k9}5TpF#2bB~g$fta`_pBR)DW^-dZFoH_9-=s>&wfD5ss39gV!k)_Vj z@>)=M(2s-cU8lL(uUB$uE0WAms_yuesJYzAOLxv!A_ho=W_vtb7NO zdWbOuCuFLKuH4j2J6ZLP?FMfx+HB3&lnaVNWkPo*;2fmn&A#Aw zO(OK2J9v{rViG`>8pKBZk?ETFa>eP>&<)G7{Vi6#zND`(W9zOQL-K{de4%IbrZ|@E z)4)fz^d$b+HY@z;=m{#+*_d6KTeR{fa|RN zubG@Pu_&tQYRbc}Hk`FacI$d)N(^Lc%n~t}NV?Bya!$g$P2x+(s3tVkkJ3ESFybi2 zr2lj$S>iVa*?e+)A*^Q3#LX{h;b$Vv^@Nd0z2B_DykpH7JBR?yRJpW;9&7PmtcmS` z4O{1=Hs5rQIdi`N9BqLPqT%oYBLlcX5PsN*?F=Ogc=$PjEC--X@J&ULhGy9e#dZUIRMdHs2r{MLxl2R>9cK~B z(UC3ZT1cJ*p&>GeWWkS`nIvQpOq9=mZ%73p?5|rNz4)dFQa2kL8&fwo%9r1$6|#xf z-clp5&M@$4$RVzLJbR(C_?S#$`IT|)k-@IF66P)4Wm?oQ8yhvA@UkVgDRRkSugn{p zvV0k;<9rUHKVbU((YP!KUeAj@!0+Luniu%XrfcD5cL71blH;KOZbb(!ZvzsnS}-hW zfjk$4Nn1rz69H7tS9|q@6V~J~0Om^`1ceh&2H{tDjig+n5U6OQc|Gl!s|!KR)UcU| zV@o0#7)4At zkDmj)Xn>`8gcu2nCnPk{x;RyzY86+#bkFG5@mWhBE+f2*)TD5o4aR`jZ0sshj=N

    afam5WGT7^3OlodKsVkyp{~3A$Df#wX0`sm(s1AYRN5plAv?3$e)KS7&Fv zar3tGI`qBd$$hDfgPXzs^9%8fo--q3q`dJT>*`Q%DMIBKz#5=;O2+dw{^%N7y+@Xt zjaK}^gST@N&~E?+K^GbXM+q!YvM_l#&_V5v2OP~$tk_V3O<2cwmWBz=5{}s34Vx&9 zU1Ay{9eyTpTU=b6p~VG}IkH6)Z4kU%epl%3Q*qCqDO|l3s)9tRvJz@=j+C|gH;#}v zhO3ySnTS}YIr`$MFv(hX`G3|)YaZISKCs{^z9+0wrnpg2?@fM|$ii`ZZa-S@P0VQ6 z9AZ-tIvXN!qxkdvyAnnbZsFp1yaR2V%~2$uI+v6!k<8}>t&7zD7BBF&ehuGYlz5jG z!t!}|m*bram$&mPw%=rBrT45x^A4Fj#6M&R^(;?3?PuSyiA!#|EO(-!#(#yjfIbE_ z@tQR?P%JuCqC3rxjm;|htm;p~tz{CCDzTh}$nl@dioQvbcjgQo{ljr&;L$VDcxFc> z%qJxj$#zWAw=Up{Uq3BuQ{(RmlO!J@?|a)#Q9g=xwH zHdA(3%VljvXx~r8=^wtxv=o#WjjGq4e^LI+4myneVq&*h^nsA-HcXX0dlXAK=78|_ zfDqweJ@2`F4=nEyC>Y$^Eilq_1PPGg4`*zIDhE*&fCvP5hk%^vUy`mFv5YuY^U5DkS4I&MHpMf?t~cYw~7`Q%C<&%?7a%j$xjD0jcW)S&X0ZNRTi}Cyp{D=^Y02|9Z?O)}cF#<6NF+Tn`lB8RZWdJ2 zvNRumts-Tnsb6*x;u{X6NJ~>Wma`y}^>k-(YnFI5a96{mE?{o0$ljTsdT<}{7+J9vzx*>*AH2O|O3^hnKDy=d+z#Jvr#VT{mD%0sNi=brKW=DIi z%i@Dg`Y#$n%8w~EbG%6= zNc>BArNJZE@Mru;lf~F)@P}J%T+0t_d-)1o8|WtvSM!m6g&t9L@P}S3BDXwTl^ZAR zRQE$#`iW!1Mhjar`L6HX)uF!m9~G=^9P>ZInfQ4>j@Wog5J>uu#iZ^$BL}oH{Hn?p| zhLowxlH@)!1N03<__tR3gY~p)lLI|_Y|64ZQ%*voZnm!}6}hO%aX~3+9!d+yUi|C2 z0*}7gpo}OtD6FT(sWCRcfX%O4-P7`ATUsORIH^ExVu? zI8XXF4>boKxgU$8TtApOl#~qnxik8}YEB(T)-g@WF8fULO%29`xwD78P(}()>@B@e zmRrp$s<_Mf`wA&i$CZU+_TonNlz9XFicK26PH-orss_E8DrF+V;)qnX4VSQ;*!)=# z)xfjIUUSybfp+34S+7dI4zx&z-5DVyFHYKv4ersBsAdmDt?vaww~tJd~#LRheY;il8c^3it;?PSWj_}OySJ=5CZpusnkNJs(t z-)%iSnhs5+D54&1PndUWbPcJZ3+a$QLw#1O@gpjL zy?1NNH`qq<|1sWkE?`dI8rtyglkofM2q9NSWM9uc*~qbxSO4jDNMz~mQ>m4ne7O|f zp;EXGR7h!HS$~c5N~7O{0O@NUtPwVTjoMmVs*-tb5?58%mSxr_%!DX;|VIZ~0IZYRbbt?y|+qAci(V z-viXwO%PYV|6M$zVDfdv@#8QwRwV6_A=Gct(a{Pn_tK+?k&xh9>v41fYzk~&P>W5! zzx0*@O!+&KjdfNF$p?(n)XOqJ(+eup9%LRv%* zZ!vg6#2xAlmBh?Hi;}nP4qhbiaFsG)YId@IEX?LvWAdB(u`cJ>gaNQzXF$6spYX?? zQp#V=*OJ20);M2Dku+&!`KUU8M=`^7N66x-_x(epfArMUj~b0%{o=_VZ6HyDv|E@e zm$y@UGh(%b9&>WBRrCM6c8PtEK1^5|H!3GVMbbcPEibtL^^-?a&Xru++BT9i3iXw( ziudqY1Y;P9(K+ha9Ewr2+qg^+O|VYANd(~@dR)<|ye;1KJ{WyYn|+0vRI^~5RdzOj zruwF8n`M~S+SGVegU!c#do7NgFei;QXxviGKIo+@IPA0_a1 zT`sW;DF0d8$?uH2E^Sr5uuC;gQ0e*r<517qV)KOrv2I>_juze4Xc~#D$a6mW1Jk>e z`JT0LnA`L746Br7sOlKo=6kk*tw>0l)xVNjB-V5>{gaAt{CbAlMAk(%3|^1i)1_<` z3DD0m+?Khb+p%tT@i0=Nh;a~~Q;H)EHEnd82tfUTz53Rp=hU{?l={;_$f_ozl8Ecw zo@b@b=dpCpBuXDPl6Lo_6RxkXQ*mruoF)2hB|3nkDw3Dp7a+U@LM{^V^CEIU7S$wA z$zJGn0U-`CeaJE{lP#NC0iohk2_CViU`Ec?Hm6}pOuYms^eZ5ZsO1vA5_~Ek7W32K zOAtVOmP+~jSw<}NBlKdImtwxhB7USB!|94p;cSbHe3E|3@YeWXWWzN~r-XPUDJA7a z&Lht9RFZ1@xm2X1n4^rOIBgN*%76On*G>U1+nJ(YzkdVk(v|JKze1X=Ucwg9%o=A9^EOLrWTD!%Cp+xMMzJ8^}zs7`Q+WTI4*Qd6z7HQU^86~wh zG|}xY-|^IKPBw{+Tc2@68iGZ92%4K_ZuHEr5*{sG3%D7*xPu~)j|o5qV6afq!kva; zO+Y8=4-sKVo)x<9XLk|T0|xCOaYV#pTz8qL$3r4V?x?1RzW}Nsk(HMIe_Q}<4AKBf zwLow+Dkvz(wc!{ach~D(8KxA}Od_2ZFX>1|3zsWvDSupHGQvzlY+X-e?N2%VAO^-$hkNz=!sIm1miGe+^Q} zXB56%^dT|cR;|>vG6Z3;iqAAJ(akW`N;mqkHOBI0_NxQm)@hVUHR`u~FU>y_xU0|B z2C_)H7!FTR!y(}So2*ie^&#=@P1td$V6k$-1`Xn!coj2GPa3${ z;e4fu_?UVj24r&3!+q*sgE8I##H1|p-X8HH@=_M}Z}#@}-6MFdu>=o#!Ep(`3}L*B z>35mu7m5%hDxUAz`P?Bw9Ji3-75pUee(MVXC~GR0WnoBwh!zFb3PS4zRXX2)tu>Hg zBeKD?q1Jwv1e+o%*ID!d6<$_e9wsy!`4iSa9t|AcuvmM9kAaHw0R_sKC-`vScFBC~ zUU|ey(h64rzynWivqoRfblqx5JnUrWvaH9#I5U^Lc+()Gud8e7Sn2)W3m%Gga8lxz zmX1Qeu|P8`{9+9I6oexE=Q0(3nd*R$F7(cGigWL$0-_t$qj@xs&vUc859=>T-cyc=Y zb_q>+&EWOF$4>TY(P% zAP0;)fOro-7nBRLj|!%?f%_&3=6LW9OfvxbfZqW0@c`o~J881pGK+G|2)NWaWY*Z;4)g4bQ%w#sK1s&o$mo*VO-40|j85p?jZ*?nSL3pS5>oY?4X%hs61u&|G}4UAF2uio zQtb&frSDsaTr5wNh7FTj_{q~VMFwnejvlP;8>C+med{9mUV4K91H(vz{WhptG<`LRtHCr510N!dZJbmgG|F?(Y){rzfHhR(~)z|AkB z?+hYQHwhV9a>t`QOK=)f9+em?R_j|{Ci8}`R(q=J#%8LC{6v19XwB2@Y5oxTsYY0n zCu3g)y$tG(zH2gpN9a=?n(=~s^?Hdl6_1`RuS8LWrt~0&}vK{j+bYq>%X32DYl8&qE|NfKf38Vju_Q zfcpJJz3;go`~V>YbTdm}@wP*>3BnO5*5FKlTMVwy#kX|_;0m%5fXUDT0fK>;4DLt( za>8DK!x(A>7>yvz)Qmm1*g&5G@D;S=|FctEjaGD6>mx_Vt)X{;uLOEBB(1}^q#Fi# z5sd#f6-NdK2E3C$r~D*5GJR)w1#x>%A4h7k$M;)m6={Rb3A9eG`Ho&*v;b!q7#Mtp z8+2=1&a$7^@bIe`;Y;^NoLt0GrV0_3uw)4^kfClony_mAKT0uVXw{RrG4v2)SwGrjGY@ zrjfB%Lh=@ij&waaY?*`MyPc0r zKekW=@LnqVfaf#h0o=PL#X{4?!licW@Dj0~f05C(^#enC(Gz@@*CCp{Yp z^b&pr$S-sDUCS~&LHXVxUCHy{lafs62K66a?Qj1H$d!_p8b znPWSmIa&WSo%0uh!F~4Ndu4kX_OV2NMkPn#8kjXnT$M*ii6YMf*89@0TUFQ&l&q*H zWU#4wCCW+2rFc=n7r!LG~ZJ}j4V7>)eL z9tfg(0eV2tfP%FII~^KIc=VkRD}V?RghC_NY5cNJWPaOwb0jlYE93f~ik_w%QEwS1 z8*1g)lKPLbxl>p99rv`Ai@4_Wt_#f$%EOk9!G2RhPx6>?Hwgx7^ysU6>CkvK-;5}`1NRjPQ zP^_q}>iEe@;F&6F)w8r7vfwZE!=G3BFJ}U~2dLG{8jf&)(h9g3!jDYi@3ciNL?8fe z05MlD>WCkxMt%gZRstaY{m1KfGOGCBkgA$mHtfu3B?Q(7S`YV?2$6#bdv8?U=4%1m zIt(Oegcr^u7FtX|F~U~|(aQ&2wDvMFH0X%l;qsIn2j$4LjsR-#!Eeh)*$XWU?{>H54oG~$cc>|txd7X-_(`fWmDbw z{F9{G)AJ)e)ee3lTlXb>u6TV3Uf?@CU5rdO5z0W?2_PZXjm^?YCS+?zMtX3^LyaHV z%^16D#Svo~yGo}>o8sG^Ydw=P3G|>axM!jZ>wE`TKlMz`{p%`;)L z(G`Vj=Dp{fLPE0f^PKOzk`}UI?chr8;`@4{TCINQUqQZ62ndqi%?H$^oB z^ycZ1?Qh_dMt=mf6M!8AQ45M9MDaKHlBr+d&#C8_r>4Mv7uMh6vXi^+zEcuF<1~mA z-C(74r}=4rzO7=RCD0=u801fB#F7Se@?+889Cm^LM*|p)hmUUtII66yEENrnxoN7z zwrU<}fmR`UF{v#a8PKYSK)f2oeYx$&oW}&xld50b;$*Utkn_nqV7{qGMuscc7z zl+Jim$A@zZwMS#N&G~!WNC`>K;SV1~3PfY5SUo8qgsDX-=}^W#_aQlK)t+Iamh;Jb zRJ_d?uwygy8p2`nea#$WY5Ff^8!ME&MSWVqr`})j9vc;|6&<5PyZSvQDlw#|3q(J^ zrMLcR%}W+&bzCl&cLFn_>zVV7|G~#=E*ccQ_U(j=}Ej!>Clsd`F*n-^de z&&z4q2UYtK4YLnhyuOyYj?%@~Jx2m>-#5R$fP0{*-;Kn;OQ&b_q%jj(@yD~!RvpHA_!nbh&egoJy|8`sOaR>kA!$Esr()#*(h@^rJt*zi$ zUdDtqzqoi90D#|FAY?mGzXSv11u4Er4q)<3p_z^F9;|$_wa-D3IP5-ZyF!V!Z=|Vj zIwvUgQuW??L{bt7c{AVzyPow|;y&wF%znGKEgBX$ZqM6AiRx$ab%k;QCF1P1p0x0X zw+#_s(96~mH%_1Uuzm~0ULdnu(Dz^eX-sFo^~4X&FXw%FdVMfy2zTgW{AD&PQ73<} zV+4%8%0Z^oAXy#6;E4sF!>P#x_fOg`xzOqQ6eW)Zca(c~V|@H*FzR!p#3R zZ`xTe0orV`DP_KC(I8+284!dZ;m^otk5Y(@`jA;nZe{TJ=QRetx`uDce_gDy1h!KXOw|5_s9aZ z<KNf<*m$6g#Cu6>b`MLfQ|=S0+68nwdr5x~#2w z*6=VrRlcN;Go3AGcKWn14>_%9o~uj6Lbv(bJb#*@_f5G4Rc|^QFw~}}3nFomKJUFO zdOPjqIQ9V7{(b=WcWSxYwdO~mL)=GNckBK^Xel!tfrwcUjKwqbOAu2ri_So#MF6Hj z)$c#G-MQAENK6oP*bU52#0U(+2;STK9w(nq)-<6jTaSCxf-jBl?U^5=-_c#acL+0J z#H9rd3gmarXs*p{9JkulaOX+lVFd0tiCfk#bn)`!Z0zT0L~f||JvI!tZqruwKRAPY zQjwe-(z39yRLa+JM+Y;sWx|%at-4?6r>m%n%V|oK$YVr>4m{p}3k&WYOryOl5&9!@ zsK8R9F-qIk+C98Dc`0ne&1inHQC1kaWK4K00W-KAFAa~dlXY5;U~%jza3s)F<;r1L zrB1xe_$%p0rD>IR?t6e#9Xpbz(3zcoC^KhWUFrVfsDoQ5)MWnGFRLtMpY?BX!Oq!N z0Uz_C2-1&EmaXK{10)w!{W`DW*2|Oen0Le1)Upn7Vi{@EM+<0?#v@E# z9lh%GdZG7m!rD@Bc;omp#0DN6A*$BoaMMGhD|BNO!6r)e?D6sWlE0;PYg&0%1p~q( z-nHXf&WK0>DmuCjxB}oCbeh-QmEBoEnNa&_s`00WW_tgm*se>d?TC(UVyYWfI|CSy8$Z7Iq!J%Gi$l8p@;&E`lf8 zzkgMmYR{rZ89mm&Z)Rj~--kx({EIlfIn>c2$JSFps9eg?luqQC2(>!q4{^g8Z2y}6 zO=e%$aM4dZtV@iC7Cx5rmtUK<^im13R4;PNy>AHMKn^Zeaj%YWBu$Q7$W+9{=ps3Ef<03JX<1gHZB>2qCI~UdDR~*97tPh^ZmmZ2(IR`|LTngF)gUrr!Z3VzdEFX5e|W31lNi zu!yJ*13q<8y63~P^Q9X4f>Meec?0BEwkLG_sPBI6$5AxLeA-&Ie0^5}_rp7L98uz) z(02kh4l7P37c@WD=$?3BA=P)|V!gk<$BCax^?q!I5UI!dc{CSma%nvqp(f*6rk-%c zxJ>5Ko$p`GY@}|b_i^bCN>W?0?x`KtS#Rxb-lA1bkma4%8M#s|KTNti$}$tVFULUq z!A+d45JRqWk{~}(#cN64S|)YFO<%{`V zdKLdKm$h|u*m+|ivo-c2|5OLFeRxY!E08ko)owp$@-sBeaW&#h6koWTrV5um^ePVZ zbKqKKW{^48$Db2teC;#$a*C*%qM=^A^Q_vSQ)wmFs~$ZdbzOG15utH)1|91=*zr)! z1MmTm{Ida-kDB7CxnI@(q87%NE^w>O;c{ruviRg-IG>3tu+7&|wr7*->clKv8LgzY zTtiSh{4JpBkb4XXJCXFqFk&_k@URPT;HkE59Gkt!%j{QdY#ezt377kUsgX{}o#JX%p%aF7jz^V-OmP{j9xnwKC#SBX*3||@?3W1gm?hR0W zI|+g=&ora+fvBplp=b>Ue1n^h-9~1$S zw-?5Egw`rn!WTE+kFB2tgd5b@xs(`mc&I=4FMhQ&iOzbX!lix=j7|}VAb@0W^IjQM z=*mf@zcNj|WRmie9{Qx3z8{|_*1N1~Y%3(S^>yPf>Ut-?>rD0Y>p9(1Y_z|^~UU$Lej76`Yf{04Zle~J9nTLWqRK5>xnID*X~>1>})=*`WvDr}xm+-K^0F@~gwJb8kZA^*3)*8zh&r$SBkDSp%NiXT%_p zG|D-(j-CGj`pbR+4Tj&1&)?a(yG}g!Q*OlgvF>7+F(!O6x+k+T-KCjZ{rb}@GpYgy z3{uRl!zNDuyRw1j_S|Al%u)=tQ`UZ$5hZG%a}IUFY_T4s`;<Qm*qCD=~-weg+UF*YIo!Pz7*FtU&m_2 zJNNgeWEvC?Y4QMhgEQjL3VtkAeQF(%c- z-74xDBly!vw+rsQ{v8-RcUl;B_$TDIaDRnriP4%S!$E=~ZA;48*RYaV!>wmcoQ7p4 ziW3GOq%sx#Dw=zbhZgofP<~6Yve{!-|9y|?;#-_GfjbNkgNFzP+fCZq#T^^Uv)U1y z^vMy;l{yG)Vz@m~yG09X4-lDmM>V-#rbJ9gmbpzXa9~gx*3IZg2jhL7uORPUMz|3A z?oRpQgSy6Vf~@PwAn=(H?k`~Ud-H+%X0=vR%*k1eiCg8V*2(odBq?7k+~MCL?|-<_ zO-nCoc?QLN+Cg)Ur!YOoy(M3$DqFmrj9OZ4^DCz+U#;kJVX$HRM38CBhceH#Q%Sqj z_Vjg5YC@Jw(v%lDDB#cWe8_n%?9~J*dk(o0KqFu^WQo;jctF%|*y>y3-so~A8#wuBi zhs~_Yz@GY?lw|HPcyUa%{4a|?_oeR9$#a2s7cNY`>j8X7oi6BAM>HmJ*|Df!jkeJm zW(H;XYIO|r=UNqh1Qnj2o}FbImjNv;ws&0fyoesZL&|k~V!ioU{rr|u>ZIx2m4euz zIbQsZjpKCj!4jHADZA;|pI$Cv^q`q4FE958s;GSX=}Ke(=63dtui>mq3w+|aHYow8 zv67ZA`oyV@A38D_$fi$Buj<_`m-@ZYzFv(B6X#F%yS-S%#m6$!u3s^GZE(ab)^gi3 zQ_cH>=-YKCdB2s%7v_Z))`X&dK@IL;{(SV*%*BbGZ=9$&ye02&xohv~j!ON`&FXN> zNKW#~=>MVVETgL2-mXuhNQZ>5K|(@O8aAP%bcb|_G}4<6>28oNDJcPw*mMZe-Q66z z`(6Cs@r>aI#yNNfhkf5`T`}ix?jTsVQnqsU@G-|raU^QB`wX2?Umf}^#^Q+czxfzR z_8gFJeQEdAAHcfpDYQ)A^SJAWy-haWZ`yzFp0ywFt((_oPTDKVd{hnyRpDK6@0>-cS%^bF_s2tC^cKgmsub5l@FgMBCqBsq<<#$o zvRI;?eTS7*g2%U#@kX@7o617BLnUh}xjMX=xFCDD1AF9rI^QH|Pxx)bf;p(UZhXb5m;Hs?qFUjeJ+Qjyp1?D=73a2;t>N)g8 z;9DV{9YRRcgzaL&rr7fo*HYfjJ=2IrT~>{*1ngua(b`Wo0tPvfirf$TD3gb%+b(1# zh5d?`)Pe`7hT&6<+P5-8v(as%&-<5vz%V5(&FUnoUH@$|#hzIiv=I*z^BH zTm!$l31<(}#Bl-%2v{U{1Fl-glcah=)4(Pb$YzHKV(;N0c;Dt)+SK>?AQ$FN*RV{d`Q1 zk4L?-2VeQBis0D27UI;TT|6rP32aaL!@LWqtg0VyKc0( z^PWF!0z+Fmt}|>l#6NWC7K{|xd3b_A-qbJiuv57q`tPdes+lgULU*1co-UR%*1vZi zjSoC-{%IxL*uowp$zX3TD$Yuo~0)$qkuu)GH z=P`S}`A#;^OtY%i7w`b$Ok+fvW;SZOJYW`QOM(EqrJ)Cs0|Ms)JoT38b% zvDm^B96bM>=&LK2c>Wt=>}85wv#u(XYVZo-M76Pq9<{VOSPiG@VaX( z0ihsePG8>O=tlCRPu;&-)?L#~^DB-bBBESxD=xAL4yQh1#VH`qcQv8PclZk~<0JFupN&NmWDWU$`MrurjE2d?9XLYU`VrQR z@whdy65R_JQ38j=SS@Ii9--RO)J3EL^t-{u0QcR&ij*k)_wQO%O}n=gtj`aPeaO9f zyYwL{Hs(%WNWWLnUq>Kb_r?axtw}^lxi5CLmwY~ zxVY_<3ilQuA-TtOr$?TnMy!@=`Q9OWALD3Iz$$>7Hi(iTQa*Gm0cvk)^=E^j z9p&&~xkiUL!(q)Qz1xEqvGVG}vEE(7&KrtsK1m>I0gxL&TnFCbYUs^^JJvN!Jw0bz+thrk^ z^5xsoVGmFQfjyf*A6qR)m{*e~SrI(>UE4I~C+4L`RH(|IKyN!XY+L=nvAxbAD+s0r zX9~M|)$f;W8tyMH^aT&TbyUv1@+nS~`ZrDbwpuLHcuh=eU5-c}ljp|vEXNmr6O*!5 zen|RKQSuEQoYblw0uJv=6W`4hHX|N_Zjm>%6K*F8(Aq3c3=p#gJj2EW_vYs2AlU9n zW#_UO++wf~Z%9o|wF_6DKj^xZ&v+yI?Xo#kU;LM3vFD%dVrs>*Pazztr7x;}EH6{vs!{tcE=Gj2ewDcCJ`xokiCk4I2u5KsK!*k_5CWUHrW zlQA_V#h3Y?e3AzgV$PLw{f;d1KiF9YEqBRl1qFq65D0P@!rRGIL>Tv4<2v3f6&}7B zx@w--ge6lpx3phZygv&}vkTCBiNoi^|KV-IGrDHu6`J`*rqz$pe=c0o@` zr-I?+d$*Bm;S-2a^Ad<{j|_+Ifmg=S(NW$6#P~$;K8@i@3Xk7OTNKKcVNmrla~Fu6 z6)uo^dlxOqOpx`y^#Y8IuD#A`%AVz%=Fjg)fy`eL2c)=~E&(-1?7xkt3j)wrn3zJq zX$x)lJePN$1cL=2V#EvO`ke)mV1Z7iWTGUOd~N5W{^`t&B%SGQ^55#Fx=(Smfa+WK zA2sTn8_ACLK9k0Y7opIhv4l)6-u}hWqTVj&kjdSj;$y)`+9@zg0TYSo73~6!Bf$ty z)!FAOx1x*p1qF03Kkxt<4PXfV7}f*o$GSR@T^|in>w&f5m+qdv9Zi-45Q>xIj(z#Q zE!wh^|7yqMWU(0LB&hz3$Rc~Q_NA*w=iY+aGots$-c7TX`c?=mg0JsLU|zJlKFR+A zfl&&SwS?haKNdbTM|ZmB>Jo1izX}i!ExcMF|7wnb;DW!G!ktv;$s$D3)QaMB zbbWCNgYTyOOEIjOo0o6cgJjBrepwM4?Y(=$j9!`W$+CnB!jt= zn@WhD)Zdwa^LFe}KMTwW*_2W(DhZ%56m!tAs0*HSuY=Y$HO=FfJ&F66JXN{vy@kgo zBNgKE?M_8B@PFSKv@8vIdsIZCq+ba`#>1(ENicueI9lF4cCmlUt{iytPC(Hub421b z1$Hn856>hDoBa^g63VY z37Q#`f}6BrW8a$j)j%#j(XbVAIg{tj;y=_2_@^E0gF|Mf$%#aV~ae%34ktR_)PA*Ys=CSO1gg=RT_?RPT#Me z&n73X)GY*M%Z`0*MJ_|<@-5}p&G5LC{yxK*zFLYcWPBO^GJ=a1`H9eVwU0#;zBms3%jrZ(I(DYx z?WJ^udE7F}XQ89o>mhlG9?91iXDrI*#^9tiN@- z(w8VHu?b!Vo=m_YkKhFY{oBJ9N-(zyYy*BE@J-yL%H!s_RSZ*!lSGll1j8FJv2-cC z1cov}j&$FHtu3jhEMAPc9Ur<(e4Rp$-<)4Sh+5ztXo(`CqKtu11uU-uC3A(>54U={ zU-jmGrQ3BKG2C($7@wpVnbT%#$9;IV82%V0PK_8p7Mz^F#%En*$oG|CrU7xQ8zRLF z5j&nF`oi_e)9suI$i`HF5W|wYGSS^|>Ax=K&-R{2BucYgMq5THvY$<5`L*cY{wiSZ z=0Gc}2|t%Xawgr5zd82X^Fon-->G{1*?kGiBy_{%NE%|j&0`osX2c_#k|_}JNiX~s zhoZ~H2z^XL=(jUZ`Y@e+=_8450T&Okt&^E9Bk4NzP_f^&qJN>2e#PY+i|c}o41yo= zw5PdrFF$$I51;*nVQ(_UXVekThOdReGVYC^{3Tvh!ZYUXp3y%g6P9DE#KcG}gbi7X z&J+qzP9a}c-jm9}OaJQ)WF2`%9Nv?3e2Smh4U5l=lpD&md2&)%X_j%QnylJJ5ZPFN z(i%10%`TqScd=qHt9+Nq#HW*_>l(A2Q~ua?lqAH05{q+nd!=O)TmSs;$ck8I?6n@z z_h66$kOZUGU+Iz7Z*h@V`#l~~*MPcttBveQ30s!;e9Oe{F1$|-XtXKgIpY(q>qER+qgmvtI;^syIG@Cg}(j&K>&WGowN||g7G90I=n1pA}LtlwIqxD z@w}g@%!`{};_&5rayCVA?*bcBjwo%EQxv4@+v4amS7T!&U^npt^#(AW1HBfg&f__$ zeTl9!yG0M*R4!s`jU0wnBu);25DQw13Z`X{S)tQ<15z?UA)qa63M%-Bv)bC)->0v4 z`)z&8;|K~V7+$-FA3qvXCSa0{w$M&Zv^HG9pZ!emW%be9VfN=!ydwdk#hkI7CuU5= zR8?c+oW|BkrfaSrSrT3kbvflO+ejXP;_=x<8n?88a5z{5yYXsE@ECNKcwnq0q5y{; zE#%Iu^Y{Ya4-MWpfDjBX79tVqf5e}{U0T_$aP2TV7#l$b<9A10_2zC@Xf z^80no<9o&tz=>Y{t~-_PeNKCWKiu~zLYn4p5}A1?FdL^erUC9o%-eS^ER9Fg3o$gP zT4gS0*G*c{T_ank)U}CdztaA2I*DN0Ew!bMaviWq5yGOrjP68y;GKe5|J;PxZIPo6 zLt2>|MG^m ztT19%vM4bE5qwF_0bvFa5&y#(dBHvuSQI{5FSz$!j$K`bW{Z^_cT){SgKy8}$6*2r zTwqqM0xm%<<{;p32m3IP3!3+-j3=;ODFh!uU0}a1lq##c9?UT?VT*e*r?O#6y@HZM zc!@+_LlrhB7%(X0bL;UX<8y5!KN*aS!&i^+FU%o(k`|FJxmEZn%ND5vpHn&B-^rf+ zIOhR_4$Im;-)pcQ0`(T~F)1-60z)Lx6rZB1!!Uy%{>QlQtpb$TVv=MnYXvAxYVk39jTM-KMAD_oZUBU05Tht4$jjknLw%ZOECqN>4JR%c>TH{?lFu`5QbIrP4 z{{Vm6O(w}~@)B5}vy~XYrbgIs2qW+V!^`liyDbr%NXapzNsE3knk zl(~MR_o6^~M#s+9Hx%Vi@;|W|32RG`StNl*+ABpny>C_*46FsNz;mF(n$^+i_w}c~ zPJoa}&j*+1Up2`!w3K6+uIlD-RxV(;y+8A$ei;_3bb3u_r^^UGs~8EeYz`x6CSWJT zoaP}^io3*4#ug018<8B=JVcfeNN{DUyu6_P1$j?hg)Qd%%1V$7Gb+MZb*pvrPW@_t ztSg2}pQq-9)vlA?^U}CQ<#)JUN;VZ!a|r7-)7Q-S(AN8W_=1doXtN?vCeHn6)hD(7 zs*`Z35UZr|tA8RT+J_fsv@>*#C?u{O1T(R8i(ZW^wW$e(Zu})<4rNDrK;U88vyYy; z{GfL5+Y*jcH-$=yN=UHrrcz-C4@~O1uE~Jbd!Che^M~*YodW;bFX@O55bGk2(72WN zku6JLUtS5phXQ{I%Uouzt9Z?`>ucOCXOOQ$H&-YLX;oqvuR-k}qC1amf9{rI@by}^F+~WBY zp%GZ=K$z?gX=@&xu`7R9p#aYaH+nG%6hqo+Of<27JgfusORlSU50A7h37F!GFFGmv za{B3eP4QFZ&;We11DJ$vg?w66`Wd*9_B>rkA)<_o?%ap3_Gd$U;~(|vE50D%d|5x=51(OWsxXc?(V*u}A$a>Z(Tw!zKRZ#XNt8$h zmu1mN`%;J^bJcv3X~AtsN2V$BYy9xi1jw#bRaKeCutjX~D#HXmV%;6ztBAmz zYR_K}DhYntUDpCVvt1R{Y%C{i-O4O(6#xKq7d`_j3D z4F3G5YuKTt19O;_Zl`RUA#P&*W#t-4tE^w4(M*J)z;JYR&JfpCPLfI0LINt?GLE5% zBQlUks+K<=XK~go*KGr$64_!pP?)^L2$!Y`W!I==q_a11#coT*749?WNUWp4vmR}Kap9wDXUxC60+z!W?W++)BoyVDLxZ%{e zSmJauRK_H^X+?9h{2C$pKwQ>Pe(DZidb5cKFW7HdxcjhDH}?gJn@nEyduQ|urDyr! zncQ@Ug{G^dx1GARz%4+`%K4^=GR10mFGM2~#2e))C>(5%M?6 zWtzD5m^9^)hJU#ubdA&eoNr1KPVA5V7RJc_c;&UO0ts6V=%!|MiT!wW%*xDc=-_}4 z_+IkuRccJ!6syP=FRTBU{T-7`G6NMQSo0+@;e5%bS$~gdR~yt}1jLa%SzMPW)NXz> zOir029V_hNcm;dw@Vq}}%80}1W6qh9cLz~%N{57RAF>v%&M~=y;RuH4Oub)nu2-;Z z!BQVoEvlKqpPmBI# z@#^?w>lxUzuA!djpBk~9$vre7!UVf28I)t+!j{0HH+NCkd@LFCy?ql$?>Liic4DQY zY+LBA>A1$WE&H-j@Etc=-fR91P7pI!Mc5R z<*c8pPTV!(Ck{&g)KpTypLp`jgPsQthr7dD(`6c(G%T{e?+oVgX|%5daPbPGEi~ks zpIkE$mb|*z$=?L2<_HKtoToO^U6|>P0sb1sPshb!KkVLsdAGPJ{-JHRu&sx_J(os3 zQYnFZ)(vU{6NiHW;gz#Zw3Pg}ErYkS)6*f~GE3Aff0d_8{5dE%DpM-QRcP%a@$(gE z;@vXERfRWk_yxAsg7BU3fxv$qip$<@{%aR{rjFVhe6&N?SKACtE^KjvjI?R-e-qvX z39OYwZy;UR+-kA1cT$2tMD!p+okL|Z!e`xkLRj~lcH#CW%d5s0gc{CkgPHPdT zrA*!aG!##MdSAsE5do(V+zYSVS`Bih-_jl&TRTa}-%)OZ4)pYBTpTe(a=vAh^q%KM zADRz0p42T5c&8ifp;nHvcmC6Ofn&enwm#ROvX`6Y>d&^`dp-;KU9~x|@(XrRGZnOq>t@J*}Qbp}Tg+!BYM-VEod6S@deNXgT z3)dbD0Oc%zE`V~@`#RZ&6r@_X?G_gvjmomED1rs(aWIHIL!${5(e$TU6j@-5^lo`L zA`li4aF=!;3Dv0)`~Ik(l>N?Qu*HmXZAr02xmY4=sIZSYNrnz27aN%smk9~yN zJZk#9j&e$rMYI)B-ju)9AVOOpFY!sXH8>b`!L{9S6+$iA(2<3mW|BLwmS9_2c)LrQ zE$|R6P7Pk4ppF;;LBXfQSGoY_o6Vwzz4$-g)1KqEx0SA`Wy&CW{>P6ue{?6}T|{>9 zKJU_@*JX;#{0Tb3=2tM5dxufs~dKf-x zbFk)YKd(W(PO}5~+lIEbgT7N&S_5CGrUsO^W~_ysm%P@=PkJmyZxxanS))^f3;&=e z=umkgV=d&JYV4*&GfT*Lv70DluKmp#IK&Y-c@~psTBQ|ZXWKPhOkX)a9tL-P)F!I1 z6WMq_sZ#sbw6|kp0rjjlsItnazl$m91qpV9;mv_{EjbwI%Rstyy`+7%9tBh|`jk%} zuY{_!`f(rDa%@{u-l34}-Jig2HhEh@!Q1P3=&{tH=zT(Px3F}dkxNAJ1{pBuPh-l` z6@?XcX<);Q3H_*euqH$jl~>Oal-0~vlu=ASf9^gKl=+waxo!?C2R4``uE$&bW~Er#&`C;@w{Ilq&cV3~n7fHnO~u8}yNs(WS9D77BH?f$@FpN!bWgG{`N z^o3C>`#F%xRecfR7O5G6%Erc0l@#!?AOMF*Nf-;4@a#9)nw6bs!kpE$q|<7!I|h6Y zpfoN0fuo|(E8mmADs8fs;{_C7V)98}3cf-W6pGKvW9RQc0X#fC{j6@TY_Y2?f>qB~ zMC4`o#QMVt{PnvqsfqBbhqvD~A3P68x&GB|n*20J_-@0b3uNFxUk4=pF+*El4;O_{ zxda6TM}~)i57ZwF_rNsc?){Rn@yTUJYQ8fkv8D5G_#%BT1ev2x_*Gn((1 zC9qwGi6s5od@_18a|IQDPtFNt;%AK3#%kIoBL!iGLOp!(vvF4c+dLbRuBT8Nb{w$3`gHjMqVu9{h}mP|%8?@Q3+o z>z=*)C94Ih(8z$?AEcW~`pDBRVuMZ{JGfcVdpU$}0cSvWk9>NfYvaBM78uR<`*v?< z8+9js*?^)Ic&30GQS}zZ3EGvIntDw89t(XfKg4N+6t2(aDV)VbAl-ya@*api)jg#| zGon+I71qu+o2q~RMoSwA0($WYbb*3+Z(acbjJi3SPZH8o5cCMy97XxUR@fT7(#fSt z{4tD-?b8}!Jg0?2(&UXFT2ubnRO{cP1q*~^$p>uCG#Ti<$sDBhP zUGWyG8wL1RIMal;-1nAHmldcZINo-YQ& zgVSqFH1>i#`y)Yic3)57Xz)Moyi2Efb*DA}G-MOQ%ayf5d%cdsiZ#_*%=Y!VAoR0@ z3`0>h-Z1k5S$gROi{Szww<$LKoL>w+*FzoD(t z*w^B&se^A|)0in=hmE=&#gTWmsh?y*2_w#6q<{V@tQ-yk3BmHd#FR!t@QQ5pPP?K) zfPLuJk&wNjF{?RwC-t0MFa6*Q+V_?%Q3i;hm4ZcjImjhi_R1;g%62O6yjRWmCHZj# zRS)wBNm_||IPNNTWTn&Z`8$~+-5SOs7Z%>xE;ba9$0H0YS^9!!Jwhbl_XW>Su5v?r zSKK{DlU^~|86<<@;E4kD2oy<6Y%He3L=Grl#5oSn@Z#i;%9l##{pOmRO8m#<3T9hJ zpG-(LWS5?D8Nj|4^svC-2OI<|ph*BB;Q)vREGf%?c@1RvfCGkBIr#5t@*n-wz7hKx z~QAqRsKh5;C(1(MUuB)9)LWIswuMAkBevhd|*;|p1 zKbn^wQ~!I9A!CR#mZrMdhPs@6v%2XJMMVR}BjC@zP*epD?6_sf1NR~8 zvCxGXTF?_Qs4{%&0PW=;opg<+)j1sgbpsQ=T-b@R+#S!F> zJScql+x)MY`~q4H%fEHoPAXIm>_E?Pr}(>mpTq7zgP?PyJ( zH%l$Pn1wa@1yDmV?Z2OLG8sGWF|xXkw@$eDa3@+gbwa)ef*)w{LmPlU;4kwxHjA8F z{mZ%p__?XC_NPqpw}wzya^bJ>v?2G%?jcpKbvHjId#FrGii$Dz~g*GY+N568;PY8`1`x({dcnAopUt2H5f)^7a_wz$gv&UO1`Gzpb%G#Y|`@xHmvf z>oSOe*=_!iWBBK=@&Pe8tJ6!(-Di5w0rH=V;7^TGBRes;_s-~VQ$Z$0p#$hdW9A|0 z`xD~F7vB6ns7a!{QFN3=YDAW8i-yjMdUm+sfvBbi{kf&n1t+~`w$}=e*bNwZ(%smZ z?;}U`GUcG5GkcC`!#L1c-P!4|7x7u$kAKmYTW<8A8#YQ)j2R`x#UCj$y8(N&6Xa1S zfFDwqwGgut42uA59$a#a`cOG3N*+o|*}gE$4SPkBN1dSG>+o@-lm1hCrn)!%?LX&{ zUI$Giz9=zgafGFYc>kXkpj5;5bHSl=5_C}6#r=vMX;Tc4{Y(zxC? zoA=vw=g+FatGu}2SM}VO=#uPNDcmfu>D!qKs*FA=%4j2>1F8+NPqlG_4w&-}Yg3?Q znzyYx(E@|#?*o`XHSrX3gC+Ol#R}-J{wJz5xSuc}-Ik{pnB8{?I9m5j_BfO_8oupS zWrSmomRcrB;(D)#7F>Q+#Iw(K`%{-@_bXQo9fMT0;N>b^Gh+hO1j>a?o)ApaoKTDo zTsA@S_Ghf+cLVLwk9ePo)l?S0mQIv(9|MIi$m+0lUqKeR2B1D}N6UVQ zrVf7HJV?D)HZ*Bhht z)7_1%-~j<0eQv}vrPo+nZ;kyhP3>${)f%l|T7d;BgPwnEpZZn^4keR;wr>zWW~|#a zXpY8@`Q9iFH9BlyfT^DMNqkn36=79Ydb+rQ0p-&(qsCO=+Y~{Kr-$fnXTUCsJ88kbhr8C?xO2XMPLayI_GD&_9U_`Tcq{vP$Luja!_HYQe<>7c1Vj6%zZcC_yZ{&-+EU!G6OkpdO25)qzpRSFY~ zFGIRCE?CTGg}=cH@L!BhD5U_uu+u zj#mL{P3fU#$F``lqciFT;$$V#j8zsLqi16Acb@p zGf^hKc!@s?P4s`ED2xL=8}zHPR@s(S>b7Vjf}hKW7}SyY{!k%j{CmG!sMdbx9oGd)v)xL@8y5ALigOGA2ccaNe5Gw3bS(bfI= zq6uMqz3^1n0WQ`p0eH$lSI$7#-rp~WHKf||C6jh~YNB)NmwcZWHUvC+0pf*o4Cn93 ztegBpxDc*y>)YO+X3N4?of4_yw|l2hSNyb?e;^PcGCQOIJ2UF!P^M66(->juO3hfo zj6GSevk{t8!Pl;HLXp?HCvpJ0W?+y7B&DRd<5_vulN0=qfz~E2D(4g5=(c{t*h4{e z{eZ%1oGDiwyq!}Mp-eUYjd`)=s(Qa56=Wux#%b68-d4)PHmvHo|4S-K6TGy!EwWZ0 zzeJhcsid-+50hzD>C&lZj>4hnsLFX?!=+|lJsJjB+IN==ug_Qwc(-40O0i6B3AiiB z%NrRQimFpKd|eAd+5@9JP%A!xw7a{55Pu40D1ekm@IEra4Oo+Lc4PiYh_cbz;WJ{h zZeM?N&r-{~Onok%p)UI&qPsO!>Qh-mm-n>u!Uw=W-u>d%vV`;RNL&4cU8~m^%>UXr zGycx1PA`{U_apegE0l2&FhzC!@vxolA9fiF6X+kF49ffa`=AK>Vr~5mI8K0s zUI$sF-gtDPdK2T@w?ZhE%1IOvis196L4eKiGAG>I<@R1PKzm6VbR#^C49_Vd^ zCY(wv#}YQ9yik+P@a}j`mPc#By+5TwSqh*7TLIMOGZWuG~9kmlMid z#b(REj4@mU18y)Qt+-q8>B(q5b!&r17PJ*EFU@z`i5Qptt9fu*Qcuq{udZ92XaAT*=X!rLI2(Uot*c0Ws_1PpS8^9v$Np=db%^(yB8~pYt zeX#5A^f%*APqgkDK{duu-IJz}eSGPFs>(LBQ+d0gB`vC&Qmx-iTK5Uo+mV>{KoT_# z^@qP_<{bb(x0KH4QDt1PSE`9t{jcJa9MfL089PQ@O8TXKu*9vecRw#_P`F+NGK%S$ znfD$Zf*{yf!!^_CIt)}Tz_<$zF)^mZclky3hZ+4iyswb63hl3`=%=jHDT5^EZ(C3M zHm02qxzb)O(rRr%a5?GzX0-$w1YjVXfeA20)*vU$3uw`sV{QpzO#+@1Kb_dSsNBZ4@4yBeO0}?xKEV@mCd*wv4JO&Tf z_%|WZThhN$DmE0unpf<#?%|b{*(VRz=k89N|Jo*DtkKlwK&u4i%;eZoST_CJU1kO4 z74sHtx8jG*ZpYN#XL*zqH=Z*FH*<34eSf+1e8{g~_gomAw;XsZEHw>16>1kQwe9F^ zbKA#m?1F-&rUC2W9qb|6#ZXv_HDLODQfw?NWW^F5^gO}QNlGwq705tPl7GQ3?AIRn z7_qc1z4o{;EjIM(5eux#5qx>FaJp2UgDQaQbh#N&} z<5i;I4)s_$41j;K-AK{ddraVVx?cz2qL_@#4@)-{_5+^21xUE}JtCY1BT_5_GJ6e~ z%_9Q~J(*&xEnAD?zyAC&4{TlwmOEPlAc1b0cO>-u*GQPk_4*u+yetF_{`zOX$k?8=xm+QjBiGS*QE=xjIBLuP=`YZs(clq_G7YMSz^gloW8EF4dqeu{rgUV%a*B)fjTp>7hQ zai_$ppAqn?O-&okck=cPQN6AQ*U%IA0jLwP&p)4R?J;p4fhWkU9{z=^U$tO^9b^TrBV<3E z_}z&m(*MX6DC!-sjRe_^uP3%{3q&f9M(({7@D2SZ!m3)Y0LD#s!eROLhkt;sG6TH4 zWmMf$sNCAk%DV)5wE0Tx5CO@h=%^^*^|MqBSuad|NES^QO17m8ia?9i%?2)oy|5&3 zz?E39fougNKVKO}QgU)}KJsqh&;oG);16}|GyKqR8qMTHfBQIqlJ5zJ0E5jeGbVHK zm3VJKX|_6;on=o5cU~<#Kv#>C4ZKM!;1{3HjUBLlmwR_!kn>F~MEqgG+W^o%>OiX+3fV?}h3xbt~3YK3;Rk@ZTPMHmKgrb7q*Na#VlQ$~9F6RyzmWg|)x zIoFAU-}z?fP%O%6!!VnWER*%(-9rF@$%b==f41zX81 z1}&T}5>kj)lsEqJ8 zG4NU2MTd!6@)-U5wC9QGgwJmGE1EoEn4a=&*4qU%P1YZ_t zh|^PNH*sc$$HbSH!^vC z;m1$gtpY6u{>~Z5lAFdo#uK{d;?y}#j1n;~0+Gnb$N*wVt=#@9*0E>9;i*Hiu^C|J zsaNdnR|WwqPuyb=N%+0y4d?wJz!Q>k21t-~czWS3Tx;>A_-v+{1CO(L{!WLLbhJqH zV*8ul?$IXBHxTQIS^(7PfB_wG7LPQq5Jn97)&fd&SObO+;FKF9~0$>k^#= zDajFY>OUIqc`ZfibUkQMIDd@|15COAtGWOa!w-|$iigiyLER@k;9|ba zrbdLx(*Of=`FawqiD;n1`#w0BiL<=(isX-BT-g7*5Q3q%Vn?3uGm;T~Cuu%>koI@M zcDm9%?NadKTEo%*r^Q62LiPEzYI#V9k;w*8gTj5m*W;?=CMyf7lltt-qc1Ti*Y8R? zcGk|_fpf6nh8_#DOIhGM0{!ZK!a#IC;3Jh~YIrQ4kHYM1WQfG5^4fL!mok zjqY*$f+96K(;rZjCL1P=*a}t^PfS{|!7?u6f)&w2P`QzilD5G;E&(umWOf!K`{IiW zXJMeWZBsfdI<%^;l zWY~fc*-8-1f7d$!${@h5f-saoP^W-+OYramfT}{4a3qK&0Ru%Mqon)QtntE)4Kpw$ zDlYn!U#ETZZ3YsQH`t?mk@xZ1`QZ+x-j^a$aeR>`4Sk&B%kc1R+|S#d_4GAm3Isx* zGnY%MOu5#%-LAU;SfVVp+G#JNK~u+s-<>xEjQAr{C7u2VEdPUX%)lUzxQ~xYt$70( z#gbeJWNI!*HjoA9>q?h9=zqPt9|zzANo4e|M-oqwk6#)D2rRge!21USUdzpVsh(+; zFu)c28q-R|_t=u|mR#!2j)8zIx)LtUN-nJQAjkOZ+I6%f@nw)U-+K({g+|(x!d;SI zY_0F3XgCA_(Eq;OE+?-N+oMBx^m4Icad{5ay$_tEO??=NP+IoPzdcy$8qBT~_QHKV z*7yBGCW2W~VsAqCgL&0koYG+Vtt%!R1ajU!+|lux#LIXH5SjJ4BHKr$ThuaRq|J4!qUqN z7;-8&>?cdKT94dr{_{uc)ML=`^W6{@nL;>DV{DCnc+VPO(6o<^szefWfO80N9dmMW zKCf|KUPzOQ724n%IO;DgEId66AYTRO=`SuW0LTo8A~CIE$7BQ)ilUp|5nNh-%%ssz zaF^^c7ZB#}XUMHhQz%sDruk0qEx;~ zXh;}A%oypK;+Z^TfDMIvF7EM{ zY{Ne5tGS~u)HOBzv{wh*NKi9@DitKu384hMSEushNk&6LOozho!Pdgkk#WG8HCeTr zlI{MZ7tN==vqps|Y4!@vs9o4%K|dQI24J44-cR)2)P`Xp3-itf1yw;$5x`f!>X~^= zIJmT!L&_zp>T1yqro%lu+VsD<373y*AhZ&n8JT;buQ-Twd#wR+sz_1TTLi=KSuodE zQs2?g&@6$RbdvE1N*#B4V`$E1eY?NGiMFPaVg6Jxink@m*yAM0S{5G75}b}8gwD`( zN**CQtQelU71tZs6WFE9f~yeYp44b6jD2$D45K90^89d^e(T({F0-k@;#G%@wNqK zKFQs~ZqOjuIRC7uD7{|R7u>-s-$LC8SAG~kEbS*v7S)zC!w9sbI0LUZ(9Q<5iC!v; ze1SNd{k}qahwS$&+A|%>o3Pb<%ESaDFlabJEDG*uEs99!WR3sjk<(BTKd#Ft6ry|# zWo0H;b67DOyuw@6T{%6Mbrh3{mEk(!I7!#7CYPkJllGkiwgjL>lCc|g&YZ-@L<4Dq zYEhnG+DhLKne30C;G}u)|COv%d+|5Q+ArYVTVfnD@MXH%=!x`6FH>S*$Y#AI!PXp0 z{g4yWc64-Gs_yj#6Pnu&djsNH9`0|qx3@(>X3B(R;Dn_*)tsEdh@&Z_UiTj~IBn9; zNo#u&U-Jj6<~f&9ZiNCiMPN{VT|W8l{=RyT3l0_*W8SyL_wJ>&wM0N44@$|P?eBx7 z=4htQtr3~ZIL~C2+OvAMLT{Khgm;Jr1qFuNr%>Tz%!=B^$hnN@x1L_d+s#~5uysB3 zzWRe?bJ3Ju1MH^VNWTkJAmRZTRmH*v^$w_D@(2QGK*o0a6J!`W82kZN4II$tnrFh$ zfHodb`F3Z-krx_P-l-8YjvS90NtSo&q#N|7=ap|0IuLs!_rzbuPznc+Z%nBrCK^{g zE3JKA#sbNoRN02?X>fNJFY+N=?R#5uRjgeHy*MIVxJq6v-L`i&to?-{JL8Y7iT?Yi z&Nh=X=%`Dai2CS<0u@d2Ene~dE`hDj`#K6_fYlK&w1VvscuhJ$6)rcG$ShLI>EO)x ze$*|O|5~f$r)Ro6tITq%NvSMyOxkHbbBz1t(d9{3zmKY2vJ)RUn!VDF@v+D~C7+3+ zp|=I1kmI3xSyAG%J^<(} z$T!ElRBbUm`!KcL{8Y9t-7a3%92WOTr9*<@d70|{u!FCPgjm5i3j9AWA;OUAr4+BB zYyH8xe;e zJyc5f(Jz>PdITP#Q1K5G+H5`TTf)izio=*GC@8?FhF=A~;r^~mE*Ru$J3AF(s5+## z`lY+4%TRx=iND|9-ewm^0)Zavpb#n18cyjyn^AUJGlH7@xLt>)48+ekI-mY^?lCf1 zzLCt7W^s-o&$EStsid{7EyVJVY=+n+2+QPVJGbvO`csezDYynCTCgDnz}hc%c2dkQ z#lR?(HCaqY=M@C%roc#{>u%Rhd^Vw`JTt%4SxqsN%V^Z0b1fTWJ|;O7!~1PqWU}wZ z&<+>J)!OZ1r|>vKg);qd=rIV4tigJDm|))zf$Tr926O}HAC+Vu5oRIhy-kt%9|{)r zae-|@Rik0?nfTc}6n@QPEGV`)DS>BvMgCZevbEP z`Z$?7Sh7*W--o?w&GQ2MT-kUTKVZkJ61pwkdT>QaVQKcA?`Mk+6+DM|5#M6W!>|0A zjKFmwHi0I?kt-jWpddOV4A4VhFgUT342VKLPnv3n`k!tQ(AV#fI;`Fhl>K!a%zNRq zU|cnxpLw*$rH~nH@q-x_hU)_v@Vm=w2|wU1g*r|*tSn}OxzjYzA-Tr~TMrAwztYZc zejFT<`PGRS7;5&~Xs?JCPukrXkHDC8kIO!+$STtO(XNrem z_8#u!D}8!9uPVa9Vf1%{M>c@pa;YO)1>p~G$f6J@r)u?Y06#~L?#VkSEW)%|+&?(b zkeuo33llgCz6@V1nB$~|MUAPrhiy2M;asxgQ-plhojkc&tJ3=UhDF|e9mnb&k`@CA zP7+h{Kfnyy-rEy1G0Dpv02~iXl?^_djZ`QGw6-Jch9YH(nV*>)~i}NtSf<4Wqbv}F#Tcf=FsnMVTEBS63aW@#hTJn z0EBMr<6~fxK0iO-xj$D|Rb8#B`g{{K9V+M}0P0b|IdCSztJQymXb|nW0B$EBBIvlL zYp8icJ9T8cHFia$NG4*j{ehu6Y^|qTX=bixcGk1D=5&|o?gC*_$m+{!U5*xm@lbuR zaZZT0rU+6Rg%*kKhc}rV<*zkbn#S-&8Eb9+WDb~pwZ41asncNOT4&<;@H*^mHK?`0 zJo=|3Rbzu;)y(khsQ}`C%40CoONUC4JhZqcz|;E`Z4EAC`V7h7KI@N(G7n7$*J#G&_8?6A z{V^gt`GFDxdH#=dA&-|p67@tHL_}!0pKFN(s>f_y){eDfsI&@di(I24 zB3jpupRQO-tf$B|5N88?+?JUz0f30&CLfcRQA%#lzU3L`MU3jt^V zUWRwEZzZ5Pf_CJ;{r#0ExgN*>+}{2oFA!D!F;6~9Z}WIk3{rl!x@Ra;DW*!5 zEBO@%)Kh)Wa)kjt2C&Eg>xVn~E@M4$61Ly(Py%z3*_C6wbcQmTA&*G-!-N$DOnk`{ zhhl!I?Gov=Yzv^DLVvwE7tx#AQHX<&E-&x-yY>8x79jgeIIi_y_9#fyY6Dvd;NE`9 z7y}|1P??=afE_0IFsMK&L9>eN_cWyd)2ydX6O<94lyYgD@WvAmAH-CgaNK;7wYY60 zYSv5@R1YSF=jC{yEa($Q-F}Ll)s?DV@YnKGC2C_Rkp05H@t#_*i_E)`GSC4LUI5|K zRcNyFp-lRPn)FKo91y6hqY6^?o#gHQLyyktILqlLPF*< z#=WjStPK4BRL3}w4qs`yp>&%q6(6&w=`!esNFTkQ!l8j0{0A;orf3Hm_K5OKRqc<* zUrrfWNEUA@zeFjd^Z9vP9u!xBIU` zb{=8?gn*D)Ajc{mWsL&oOj=wNjKG%B8=I-vOiK2A;@Hn?rL)ax#$?Smi_I) zZu5DLqAfdMwE$BD5IT#IiZ&-X%fv{jY{UK^O;;IJ<<_k!>6QlR20=ne2}waxkdSUf zkrXzKQqqldiG-9O64EH$5{h&qNK40^`+Vb$!SKh?1DiM2n(IjnK{v^+z$CuHv1c_F zkSKin_U)gr%p%tc`1e0Z!$V(uNEAM)qoMXEJsG*1)&f5}CpWiE^Fh=bZWEl4l0c_7 zFm;1eln{6*@JpkVbe11(r%}^~-YtG_C9foY7dN;>Nj&vY`?DHkhbjohWnEo`#KpzO zb`bA_R#V=H@~thOvsEqzIGCHudQ-@XXFef$V4Se|#((G^0al^-<@?R*=fZ`KwZC`$ z^VE1L9&ZL6qZWNQx2`t$jwe`UZR1Hyux!H9P|mZQ^YnKpf{Ja1HH7iZi6bW3&&DkK zto?rTsFU!I>(P@%b>__N1e8bntUW^1DzB!##_e@q~l>DS48u ziRbcGf1=<|*R5hn7l?BL6&&ch-R_E*N!R_gS@XrS*i(u{)v3rR`!T7iKJ__GmVR5!AbMi&G!Qe<2zv{KfAjHG>`vSg)~ zM>2Ll7yW5b6?#EFz`d5wo`HQ!_LlKe=s$p}C}bM&;LZi131Wpj>CFYQy8_+`c$y$N zF1gAv+y4pyNnK!p>9F`TKUVx0h-5usWR~unsoD;c2FqS!bm9AeWG1=o7fbVL-ao~L z;;WVw3HEpgZVeEbK5pC?Mfc3VtNeL_I^gi3Pxs{J;$mJKXKebI+Xy-$(^DR+G)(cZ zN90?t6dxa7J8X0y+`7v~mJOlU--$r{AD%7xq90|hYb1@U)^7Ez-MvE`MS6p>KJ5G;I~LB11@sDAz4R`SP1P6;^RZMSYwOUy3dp z1*k#3e7OhL;_+ELevUH99vT)N86rK=XINK}$^XyhGrEWX-;NyE{n5XW|GXlq1r z*{`kXx!piLJdRiu8&Wo6>S~=NVZbZAHRA!p@SElwjdGEGI*5;u0`eW&D&#FKS-6u_ zqB=(UKi-#;iUvt0YLO!!TV*pSl%XR8wmVSzfV>Uqi2-5`vy%R;JSeK6;R2fc5=Bhz zZAcOXV^*&G?fR6AssB{s&hZtklUVvQ!u_7lw!@P%p})TIKA0trwhnP37jeQbB>ohc zZ$J6w@qle*YD8|w=3`oERK{T{nOEGQaK`Ad8m&aQRl7oVn4;0_@sej1O_>J-%}Y6> zee$FuOeZ*&K0%29-O5wmyOM=V#rgXgZds&MruzCP$3sk$T(mS~w`BsAKag8QKY zQO0XSxo)KA*(kbv(Ax2SCncKRbClr|p_ag5M>?smH%8KTo}}i86>^tq7I!SPVz1t; zj=^kicLW;&#b5v|y-4jjj5p+Jkk}rlUby#b$d3XVIapX&REo9iD?x(|T?lf7 zUm!*aaNpsnsqn{z>I>U5Uwgf`okTT@b&!Jq%m9+-Th%|OrnKun@;9F_!^Twp?7_jO zA!t|sFZFGK;RZ%RUbMvm*=XA)r_Qu0eRb(jd>e||Zi!PCu zzLC*481EC~s{U)0y#db{a)S(3%tG4k*eY2E3ee`iUW?s{M{JB?M?Nkx!J4RlJsHSw z>hE}XcIkKHRijCTV9v??>8CySl^SC%JVs^43ce3>jAsyremwmnerM1+U~Wf`%P<4; zbJl4fGt6qxKmb##zP`Q;E2%7qmV4PV)oDi!tr#Aj`ektWi0>9Th@T>U9t6Bmekf{G zhNa${rNmYzl1ST=sPc`#!ciZ!D77X3=*O1G{@4&Gh+$nNf0*y`Mo=w)W{(wX#7a`N zQeADWX=VQBbB1^$%4x0d_nUq0?|Ssy9h~IF3Y7m1dTzMl5Q=_CL3+xkKz->qx7@p&%!YjoAfpp8m+(dJN*RS{QQH4!Z|-ZJAo-Ot^bOb zWtpHY^A%GFRi1t@9=#6t`TEwbr7H`eXN0~AKbM9W$};W2`a=)eKe3Pd0N82CC6PFf z`q_NJ-Kmk;-aHWU%lkMsy6e;7E>rLC-D;kGZaef50Op@f5xNg8QKQ)zxI=274^l={2M+t8ULAp$sI>con=?;K)65Z9%UcGoh@JatsQmfB) z{TgwU;>gGdDvIaz<*^ng+3t9SA9+Rd88>7e!8I3vHwB;spX>8EC2`|2B|wEE{4Xc{ zzeBrH!5d2-h8hsNYxtl2K#s^xunJDM_%lG)2{OIx&@) zQBiELlL3rs)a+xh^4IsTgK5X_mn~6{cg6?`Q5|lOVxc6de9y^2mMI`J2ArL>R+9mUznb6u#4JBV}@UzN~+8kp~}d?{UeE07X*JhhyTs#Qe zdjp?IA-tHPG`+ETKJswCxKV_*KO~OpdE2I~u#{`M$rUTrlWyhji^SSma)P?qBFay9 zI}(jBo#?m`A+zJ6_wF6tR^dR2Jmr0V0-wJodAVz(A0@!3Us4GxKz2S>v-df-;GxwE=;=!4GP_978Wf zpdU;cP-F#pn9t-munt^e0>Ey^o)GxmLMtcByU7U!#wSo)) zSW7a^t8I^#2srI9(?nT7TnvjI-+*gOBLaPIxpgXAmR*e z3Z(qk&27G{cD7xWzbOdhb#NSk)^y3s!yhMoEf=a6S3B2ISMXAiK=jPXB4tb1`SA{j ztD)6ASG#!rAp2VKYHR2UAK9(P`=pEw+#x6}Ee)tg$lTMs5l$GSoS|x{1_dW*HE*XJ+GtE(*-)%BD@sFsiy+u{Cw@uFKwW$oEZhYp)H?1ooW`Y&-A|D9bI#R*Nf z3JGOJzvg;~seG2cP^p;G_wP1o|MZWJrf;Ko{SpIh;@LXdIv`_Cf2wS~9L7~Z-bKlN zKcz*^kbb&4PgP5-_rW~9BBF(Q0p$GxLPBql=yJcv;?`R&eVXIgx>LgE!NN$HUkU{Y z-IhX?lcq+(eoyhTc_>?eMSTt-L7vZkb0(9O-p3l{h$~djDT#RxQRjn9k+E$vDF&Oa zOO>6Vex-b|Ts0<_NH7-zm=?l(dPvJXB)`K}c~4Lf4IBh0xGM=?XB?5-Bn&+ol6x37 zwzlL$&h+7m`TxBGkerzV%4=_LZ&Bw(48Pqs4D$e8!GIP*iqsUI?8W$(uBM>S=`u0W zN60e+ru7EyjC;*(iikypkK^IU(EF1GBLA@HXu`&;vrS~wO}){{@0QD_kufor2n02Z zGN(TDu$i9Jn4aIgxSYFg`qMQwMg~I3-L2}O{}P0Ok8px_7(F{ZkmA|5zR!s2;^LlI zzg(dP!s>o8sx^8~WBLz95%DR?3+pJfYYJXia0Z@Px{Rl%lcH}fPVkJV&@#S(@vE?= z=B~oac=AI>G^1(8HQYXsg#vs4!U9hScbxy{1zH!Kx6Kn1PhMPAISReJukr9iEBwYt z#E)RVE}|EsfgAasy<9&)L%d?k0w!=t_m+RTzIjVa@fnf+MroEI&GbyE@u4EokS+tz z8BUZd{Rc&t>r&Q^SVA{KF;J<2_i-Ego*VQ_wngcyC zoE#Hyd^HS}^kRA3=q9#zaY+|5A^{3jP~?&QJ)uIe6ov$oVhciK6K?q^iuatr^s`$s zVxOW>EAZ;e=$JbIiZELLyCK_BO|-P_T)Hj4;EoW;PVdq*BmRDIuXNxZYp(-HvYWFT zmstWyz8yI0C+DbdVK~hPX4j#Z3IwZi;YD*WjER=i@ecPqi+_AEFWKW7vxM^D2ni?X zr{v0}31@}|@5kD^An5Pe8rHYgkr!IJHE6uPRZqMwwH?PC+vXAaI6Rzs0rCeRZNvSO z-8hxQ_1o|=c?jmeCR+Q)lsCmweR=J)SKXXtNeK1t-F3 zgk!S_?JqlZse{y^`OD)u5u*s{DRU!U3WpLR;(_FhLF6nqLR|5+S*W<#-^KnY5(iLA;TTtB5$H(t3Z>#B3-gZW{29PSc7ik= zx16T8v>`iT!J`J053);dvceRZ00OOcP}|YI@Q1xl!ehG?`nDY$RD)@Kr5K=w5$-m= ziLSZ^8jBI9s>WLkgpq#yVl1NNkk)T8LtS?LL32j-^3F=y;$|YP63W;IqxvT+Q zE6mIiH}kEWuyv0qQ1=u5iSq@7p!cb|i=iGt`yzj76kQ=a|O00G;N^@1wEek&~28j#{+$-n_@k~ zHa&2>U{6LC%o*{8f_V?X4#?L4Arh3#jj!KYWP2#W<YA3UePHI_a~K7!abt z`Rk6PWa+&`7k)vmD8LLLeGR$ay_IjD|Hs~uD47rFDjZQ%0!JG6xY;BNHLtQU8g!oQ zx56{^K1F5!rc-PU|pLX3)d#(>f z5J#eQNxJ4m!5!u>T*4s$tY-93^b9`$r38y;gk1}n_jkNA`QB>e9L17e$TuDy;ARGm+>d2xXkjN6TMc+4{wGZ(|3sX-!jz; z^L9o@M=hzTZI;BhYQM>`h60CX-r)sLHPA26mlhHdLPnJYLG)935$i4rjvvnJauwB_TxV{W|4~STI!`@@q(07$f)Ji`0Dt>>^^b#zs!s1 z?X|OltVu&OetSuhcOoC-Enf968j{QHM~OZBv&3n2 zAi8}Y(?d?Tll?K5`+Dr!&xa?so=pF&>NuZ|HOVif9@Af*eb-ceHAJ*$)LPhacTT}om0O|wW zeEy$zH#PrmZa%h`7v!M5<5+nJGA0($b(RKYqOUrNMmh5NS{K_pSLJy;*{<9}-}8wt zL~QPcpEekIewI~yZCRi7mc#m&PMR%YuX?7qwJ1t(%-ijyCHC1wOe|B8;0L*i0(%-N z^*~=k9VcXwfSd3!2NAA8hNl~AAkODli*Eq^*-%?lhsfQp0l1eDbT^f5}PBHTlrr)&8~Bc*$HX=1v_ zhaOYwFUo~u#_!dDpQLl3$yGaU(~TkJ)}e8Mc3{^MnDIMc;DSJ0@G$95Y84z{t2Uvw zR!XhUBsN%MPDtYq?bWEPX~x=S!V%5spW9q+E|ad#d?lSpwHvxguv)LcTRb~S7a@M% ziVn`hrgEagr&)X~=bTNYjWLPL4ULWXz^-T)zb{GAvVSE0`wbmBKt&@I0Sgx-Qi@!1 zot>S;5#RraOS?la;hZCFN5o~Br^FM@I-H`{d%!4u{`}dj+>$<38*`;esaR|Ut@me} zz}y{2k-4DXi*1kWDTrRto1sQ{)*TQFd|Tj^04@2*_^;q*Gvclg%n{11jw8n#m);1S zBidoQr+3WS^UV~i-JKJCTxQ%C-}vhhiMdC5?=N?%(1;Svbq|nT)PfTA3D2?AI}#Ja zpN)GRkLxB0ijpO_xL)McYd`qY7L^tsN|^q5C5&U=d22hVO_g5!ulkJ%uI$DotzYyg zl~U&lKe@^K2m0H{GX<##B_;iTQuV(Z+Nt>9<3xnJg3&uIx{~SEV!OI@s^S<|XR%WKIB@qT1WF)k{!6JfC0wC@q zk+V|@pK;0FC~?dyH@DWcgW~-d6hIlqI)@=o6$Bj_Qoc0OSI+KOV*e0;@Bz{gD1!n{ zMu6i&5_sw<*A~A={QUV-(|VdyEkH&J@vvn#m>*6|3c7u9t)GqfEUm0CfQtuoT@c$U zhh}OefTCzMO8dR6E#tnVs_|f>QHS=t>i5APnClYs+$rae>(-ufKl$a>dHXVJg20qv z9|1oP4o9FJ)byoeU{C_xYq5?XwkiFuSj$zFSad4EAmu0fH@U<(m+Wt4l+($ia>d4s zvJRhBZU`wMusp(0YD^9QfYx<~c`6^Q2MWC1^NS%ud)S3tOP&ESQ>+Y77=;u8g7kMQ z6Ds|# zTK0UP)TP!Nl}CRJ zXkayaA3GAv7tW>KGU-5sw7i++uTY)uoFvE5i|Kj;^%H;x0Lk)EE$6eI>}uSBkwfOz zl5pZYfoQC&yniY)V_@8LYj4-3dC5yU#UYJ`jkAa2`e$cnC@27Z_c)+s!({ts{?2Iz z__OnzjWoLN?rEis6&UeT;GRXrVc^110l+H(Vd3|Y&l@OtZVR6*mMNvri@pp0UwS?17Y5?PUWtkhVNzW2ij3}_p8C243k@-JK7!W4 zoBp%X>gbu~FEP~v(Ji&te1=EDmZ^K#2|F!6Q9(o$ax`|BET`U;g(zN#a{|o>$UL-# zOoc=AOAT)Xzj28sz`N1zXSju9dtFdU^8N;z>ZeV19v7 z>A*ekwWXGdpm^S9VK1{f=&j3M`5f&9xm=GN+D!Bjdt$AJIhQbs=jXRVO>Rzhn#Hn7 zk{AJxHSR~Gj$4gONO?Gg(-g+>X>3%c)eC3Kv!J`r|um-1t&5D+2q=E;5FvwI^?qZXmBb@%~p)tTAl2^>`!5pV)63Oqop<3s<7QLUx zL5ky^XAg!7q}5tT2pw2fc+nyD0jaNZSMMa}DmOg|Hbn+>;d4}xUTdyr@Ng9C+esD8 z8ELv!5TW|qvg0t3ENy=I@@0j+oqjLt;-*)CDo0@*NxwDI97Y2KS-{3pBbFGT4TNfT z!=0MQGw0w({;G_OUEM?;@h*vp5s{244a&P_6a6S-T^ld%Iqcs8ojYu<0ic)%lb~FO z>`E}(t4H_l3bMmYFdpJE`1Kntyn$1a|1`WJYWTy|t+R5wK^Uc;aM2b84U@A))jmvJh#BIAtmszQ3E${IU+Z zRIfLU1Jk>)TB3YAR%2-u9Jk(ah&>^y+t^Pmet4wp2D!})VW!N7nF(=-~XRLnw*EaMcy6Og7Q0C=NBjHh@qr;TF z=N%L#*@kU(O+nCZ1CcEF`1tei-qpSOO9TEW$C-v;Ad5X_5lRXhZ>3=pzft(ZzUY&> zdVfd=W^gDQ{YTqnzxRpcgkzSU-X*_Pwo9-Le@Ynt&|M|*jk{N}(e5{1aclX>dgjU7 zWH_s*2Ll0oEmy?1@3MgxfO-C7PSa4Kwk}H1e(1{TGgL2wea%}mpDXbon+K*<{Rfsm zU)3_L|682Um{WXN{auEi#=A)kNANmEg!H+*LmtsMW6FWWDp&4dB5YzvX8~m2f;$hi z29Vm;0TbL_O@%K3>|6eUc$9p=T^8$vBQI!g5)W(!bv~zpd`5KvmzTcqj?BZ31|Sgf zj-h>q92}rgR>E)cyWIE<;c=h`f#kTl8AreqtQljKifU^q0qo`W->&uBtQ`is2c!&< zVFnUQU1uCkFUd8k6>|WQ@h|S+8KlucM+PKE<0rj9Chvtp5N^R2IMc&o2~IPxCN1u- z^kHM5!O$too}k5HsO|X$p1dK+1N>RP^A{*GdU}*TQVdhSe}ktF3DlWh|1(u$PiTXZ zVkF!T890A_gMk6KV&}6%d-vz3ef%wvKms6zL>q1vFJBU&qoaE+MTzV#Cul4}T>7)C zo+XKU_iRMpMtcV53F_b|?I-F$8({ZcpTte^f`Q3}ybiL;H!9+5fTUq@{UJ&v0|qvnH*!%9Tj5CH>= zhHgUCx?-GeX2(jxGn*X%?SZEQ`58*TDrN302Rb>8X^pJqq^!oKOHCsm#oqFRUWzYQ$pI8&^UmSV07zY`%E-{2r5>)sWN7uI7 zYT3UVhR#Qbu+cCOb!HO8Tmg)A*sKZ<$>d)obM;l}cSSF;J70XfS=;m8zA#nY+*dKbNk5g-EmxUDCA%^yeP8?OYjwmjho19l zKeg6nR5pWw*r>2tzXxRcqwIp+49BaC6St(KB&hNVQc80*IkC+%0}?GyeJ%zqyR8YH zei`eQpHe3NFxNfh$;NDEwYNwk-ck|&qz@-N4llesj(pgC!#`Kw@+KP*j^PkpYwtu= zWjG~02U{JPh_E+J*%z7OnvXLvZhQr*e|W#W8Zp#sXr7oxe;Gm9VqD9(`|G+`xl)Q> z-CnxvU;SFv&D@)U+AbDt*$+2cj~{BO-0c<-5kZb8Sy}YJmgA{;KYxxtBz-Lj4c&7{ zt{jdz;(^IovYs;S0tUfiS`)%*`q|b#fERYJxM(J7-?ywH<4Abec=qR`zOiv|*HYWJ zZy50F0?3EFBCsJg{+oCzE;8naVQll|!ensRz6{$RwhCm_X$LOV@{ETuQ~L(U!ldT?Kg;Ls&~YPCM^pz!}2i`#w5KE>WcIC|FV4;QhjqRee;gt9A?*vH;T$b9G(GllJNGAMVdVwfF@wvYAPTm#|+MtoOb4aLOCJd z)1kh+o1Vs)czmr}8Yij5viZ8?k3?9{K#zhk58QWfd;&FV zLy;iTj}OwhA*pkGxJy>Opf}MXj67=l`>F%JtORi=51;`P>;nK&JBcOyOBG>9Wt{#D z@k_|<37DXu@8JzLE{iGzrlfDbrC7u#l@eWgFG^bNA}WlGR0sfV+Z7l20y>YV?l7e9&?2alQMR7BNv%3CRzbs!C36u zMoORZL?=lB0VXmU$M1_11i$`#cR1?BPsiKJcsT0aQ`MHlCNngT6BSW|0LUeN9`DZ0<9HO+r9~VwvT`9YF#|<^PP*_PD-~#UX6oj=Nf@pMR7v(&*YrQD zD_xD|>l7U9$eKY?sz6ng!Lh50UU(O7&%b~F+J%&HF%TMnI>8wiRY6PB)YQ~wW998^ zm7d}U2MyQE(6rtMjn982bqHBsX&moK5@fOH;nbc;9HFOT?s@>=WS7QHqdHQbWRK49 zk*?YDTT8KdG9Br+?5<$M)deVP;0xA*M<9;z^=*2Dh?mnm`3F)#ZotrRo6$wf5zPReGeF+3pY%SLdNFGtZ-|+O)FJyS$?r ze40*aP+FnZ1r|q=D8)TcswCoUwoG#KfSj6};|Zx{ass;5!VhK54|CMUg|<}nzt+Wv z+V8p4Ixlj)YpSJ0FH^%VyldPeH~9%O?tRZ@b3BF+I;3=#kx^4pez%Lj!KbBoC?D z>5kn@l*$IlV~D6jp6#43&)n%molpQ637KF&Bj9?HaRTc%m^Wy^u28Il3-SqYMSAXi zr$qL$!smhW0v6OTfUB(oRA$0ui9ud#gSX%WW(F>d@$qp8aN?5CgF#r)*!Y&?bX}k_ zYu?RH#6FAetA)+3q2}k~`J0l8Px<~9a2C8;s9+Q9g z#f{w)gz#)wO(7YBTI7!jpR95=M#=M#Lu zXMmmP&*2?Zk7lPsnT}U8jn_v`9DObK!8DJHgI5hBSl5+a+Za@cNVXeV(5cE*q=Y4I&Bn817Owi zh>@=$z?*`oghL7gWo%+1?^ABBPSq!_=*W7jv0N2ywHmeIeHyykgv;7u??py6H}7{p zL;T!Kt9+Ll`lTARujYpfY+p6bWyE-2^zAc4pOGYr|MQG{c+QU&e&hbX@Py z@NnG$mxOTKf_DSZ;ZswFz`If#3fil2$p5C;%Q!cuYgO`Zrsyphg99R9SuSuN(!Qhq;`%?c3`Y%S=9S+oVNn4lrL%+>| z$tW`4wCc&tacYcWx7%~7V*O863ziLd$#AVj6@0?HXCN35q}`~XzydLoj-KA;1T`nW z9zmjA4;(q&j(eV*a0sl{n4VGmae->;sbOOJ8z{o}gmVh&ZxGSnfAAxhohdeAZtX63 z^?B1MA;Td(>Z2a&`9>At@_2PLm=9S?aHDGgh+% zp6DQ^Sy_!NY!3aTX%9h?LNO=IPuUW(6ns4o_?}L#8@v4kXV8kOf1uwvA3Fub$ea~C z`|%Lkll+pj(f5_~s4kAyer$OH`Ak7wobm4muNtsZe!M;G#QYLtA`?}HL&RR_&PLR- zB|9IESE0Hi-09Lks`xb<4&h%OkrY&&M z@$#oUd-vFgcf93;vqRd4kI&n?IClVLAO_4#K~n4`^9XQOX=yYwCQ`SlaQ>xzSu1yR zaF7G0$iOqKq(l^GR-GEMP!SL#sM45qcOMktfP25aG=wNcuvb7B zll-))ySsbp>r(qPa~I+=2S#FIhY1jh1CRi`7`XP3ogttcyp#F}u#e8kmMixQ5J|{` zu^zStre1!jgMK0K)5%L^D}B=E-JDmIu}!O}F8${E0qi~IHHPjdJsZdqj*0I--Ny6n zuMh0={;@;|4W-Plg)f=1;WfrZWM-?ugVj5|Ha-=$isQ>G%Qi46j3_)9_2|I9uf6oJDaak%}ITLhUeNpFH{*@t`BoG zx-0XpaRmHT55C>tfsM0-k{tJjxj;oZU(NLFuU`VOjMuj-ffnYq!oDyz!4i0yM zQ_=E0_oX^^p4UN-HR!4yq#Hf#E4;BfC6=S~zyL4V80|B*>YJBg3JLztC~`H ztDYR@6c&=TTl`~`cuK77cGfQ@pJy-3=NnSf)8rJaf}tukeR#i?*SY-x8aBtH>1REY z4lS=*U{_C6Q7KS)NSWA*2P6sR+|^MnQhp8EYct?6#?bs>G};@K*jbMsx09}ONXa3+ zxnzxekdaF>)O4G>xqXiOsl-fz3~SC*-;D3iBGb_&uPJzo>U_aKM>odi=#pEIpO4Pq zcftg<;ZQfKsn{RT^g$vh`&y6uvmf9r9Au5HX)qFMjg7qDPU|i+wk& zewEzDO92oYIRX9t3xA5b{~-gpT)$0qrP-)!j|8-nPSW{wlqfh7OY*?8weo(QJG9;a_B z-%?Ya#@Dc&Ni$W&1=APNb;x0;M5nK)5n7cc2QZLrH_V5JXt`iFDe3A4-R9HUcXHns z68>ER=lmE|dTngnB;mtfm-@d9&`_9S`zG}`7VogBP^2|%qgs(+5ekdlIl8`>v&MQi z)W#W|aPz@0UFFH1rlI2)3y+m!=f&{{erwUM&b|MIy*__q}xVBN-$;17Lj5 z3=YL$WWhU0Kv@9Z;X9nU0Dg74IN1|)K+{xd6?0j}29Y%W+E)hREMnJ-k1c0B7vNza zp7fQ|(kFq8Q*3D21#qVbzEaQfwcIi2ior1j+SvPR@Z!_`8inS z>J-Ulb210%!G{CJ(l&}cgRvs2|J;ggDvZA;`6-`SU$Po~p2D&74o!BxPfOfF?2<_E zA(g??`pAySh?5U_Te=I2io7&(095?h+;mmQ^?K4WZ9Lqqs??)_rm>E)=i}}Q#W0b)(aA;HRu_eoPOiIa{7aq@|~zXOiUSF{Ub#K#@gqwLl|vj%4wyHk=pqKT$zs**B3i zkv>RDZNWJg=JFnyxVr#;WC$bq28EuVnwz76jk@?dcU4wo-~9C}UdtSRBsLvZ6j>8@ zN5URkps;aCDKX)WyVQXOmBTMIS6}(7TWI__?%MJoj^5v7xOwiQ&*6b?Q7PI_~fUujUj|S0uf!53#^$n-3NfsYza}_Wk z9W#nC4ptqH(u9kJs0j-U3=|9w8fsJC%h~j4TG>n-*0PTRrSnN6oVh{j0$+zmN8xw# z);^Ym0|Y=P=}Bxml=U6_Ms6*pkhux<%>12y4o<)AL@^R$n>jgYMvmC2A5!B6-;tK) zf94zdfJwF$m?9Jzk*vZR$EN*W9vG8O-bkOIBS$i_CG-Fy>5Iy(D@d=Vl|nXkHJobM zy(uXH``}3C+o3lQOqBCk!wS_$8%b}0`PE0t^j8h+E}$BN;`VkBsFv&AONZF7?+jN9 z3`m^K`q=5>y#o@1Kmq|sKDwl25#BHu(U7h|l*A)Xc#cuN8G#H6WPUg~tdS5Yfoo30 znUn<&QAa3)Ul@oVrklL=JUT%=pXI$R7RbWixQjNJb)UyiW5@S+#v|A|Ye&}DICIpM4GuyESs3>tIF|M|-Aqn6vV|_QIR1{-olM)` zKQYld_yDXX#G`^NDS3oF4fBxUUFGT4G zowxt|`P2N`z()#hD7+M4FWFqTfcSn+GSUa)nGDS_7rec${Z@k31YOHQ{bf@Z;tMDX z<@o!T7q=A6SXoGh^&_1kmL!gyb~Qj80;3;%AD@$jP-_>8;AqkTxTVnB1mRB21VpG$uzy|Gn4&1`KhA*4H2U4aL|HyYKK~xu!m;@#4ijg6>0RB29-O+; zz3yc9(|V)xjednW;`b19#0wkGDLrNxYYh9hGzxt+Xt%aXA z{v`akzgRld#^Y@9s4R!o&-6aghyG#@)n#@AJ0~C6L)B3eedP6+hyIFWXSX5}W)n23zu$OWR&n6|28#Q{8 zKwGpdm@z>n%t2L6N57{KFuiy$oq)mjkOaloC92V;YCPHu+^PDcQQT|9gU+#K?pBET zw`tk7S}9EF0}p-(kF+HOtjZ;mi%}=emf6!F*e06{$>x;Sg5zVdeUA(zJ$F&SrU@~S$Wkt(!Q4XUpU}!GRh2pa0^gCw z+Brus(2ase_iya&L?ba~JSMg)7eCOW!dw~%Z|cdVACzB>jg4VvES^8IUf+7a{GP_l@4w;TN;Ejr|i`FIjmy~596IfR=;od)9yu8pslBp9kn}0b^h7& zG`p7$!jrfmB#$MZ=`I$iLC^B{Hk&_)?b{#sd?BC#b!y>g(54 zlWAGTJ=yjaQsEr z{`vKdlpi>S9f1X14zr%6<{InjgLrsiC}d-3Y1IQ^&*kweCi}-)SKKVzUyuXVOJy$+ zv-Fm$w7e8oy!|*%k7992Z@kG#=j#mLG7+vrt~W$H?tvB4i1lM12}Y1ND8brU9<8nN zPY1ZuW78Z*={xWba(yav z!s|eagM%_pD;n_Y#Lb{b4rQ3m{rQ|xh2Iz(&SIqD4v_!Hoz$KxWD60*3RyQ~ zVTH~$vHJc3OuoSALJm5BGw@dG4595XvBxBcdMt(*Gt*SJ}4F->R zjaFODs=WT=$5d4H;Gwx^t4R!6>NWrE+Zz+fb`*sK7m+~S34>J#NH@3(pgrM8WB_0% z?ZZZUx7EC^gJ9}yyD6JrG_VKM8A@pW{VP9Z_{Qh?jZ;sI**93Q;#AuImQhj59n|J% z*X@3={bX8Mq~KFi+&ph59Wr4b2fX$0f&NPF;EWcE+k@7>;Lr@Hf>9O6nbs(#IO zN479*QQDX-&%yyf#>Vio{-Hl#7)|g?&TwX!iEb{9tP)^_G6n9YV}>N9#Q z>!%1si0(R*$@@Cv%Kmy9cB}5$Sns5kONC@wS`dt;mQRUEB5qxtk}o`nn+!v*_lxS} zu3-9mzecj~oRbdY&a0Lm*VZYFWghUb>^#vWhX9}dqv<=qvFzXX?d+Ys_g={g*~#A7 zQWPm$$jZvzTegg3L}iccnOUTS$Chk`kpFeR-~aD8I*#{Ed3rqeXI$5Lodd=Rh!FK8 zuLb{gGVT?5HCn_MdN=6u452|0Gs?Uoh^d=>Typ*B6imqW|8CXXhnnc-+3c8}v2i#M z2LkrLMZPt{khz)mk>^)2Ief<8>G$K?;dQr`A7}q0NO4(c2-A((@gg*>GyqF5{nG-y zJ~|KTqRC@jL|&d45W|kMmJWUb50tHW8h`}UNZq(_d9i?SAlZ@*e|Rrozoq`!bDZuf z1Ij*1d=z!Z2{r?91Zg7ZwX1&)4h%#(*nV1g!&7n)bwq4zJUs0VN*U({iyY>PmR(n= z#lus$xk86CguxCOactlimS!ME_F$ak{73liuZMts1KF2o!r}EbM?lYo1NRAlK|~;V z2K^fi1&KB*wXEncn5>jnL_?hkl0&2w_w=L$TPM&;L_DO7?@p6^R{uW|Hsa|9K`**b>E zZZ*%aNRQzugTszLlV#%SVUf39Cf)k2^QQBZWwM(tVwV|2S?9UuDSfI=Fwn(|=q~ir z1tfYufSnGW-DtFekJn7&Y9MD84w?@EXZNcqltMs&+|t&T!xLwCXdy~njSD;d-*)I^ z6O@DQXJz6#p=)%>ps~hIJyaSl$`megc2pXXCdG}couo@VHyuEMu(;yRpI3fO zAHHwUe$10l77a=pj-#ERo=Ol3w^y2xo z0(puoCT-D=^{3KgUnQoSYck^RGd`9b!IRXSnt1nhzN(WuUv4r@w(?b$2hLp%OLyTA zGKybYTNFxHyqSlsab{aOXR_$#U5S#XV~4UPyx}ssLd>8b@$#yDbENBV?JI@bUtOG> zx;xH?I~M;7J>Igpqyy$_my&9&B?wXxoflAK*eqLM{S5(8Q`Ok`3w3?h_*|3IcU<`~ zHtoa0vlTU|^ME>R>lZ+{hSMeY3j@!#CV&`VtK!^_P{L)IsI88{j|LRa;fZvFI8akT zJPHz%BOoliOCO^2$<^e}op9Il#ZF8z`JV6m!+73yZbe=&8$#&&kUa$~=kS6a3X{_X zV4U?sBbxN-!G4uX00Fmdp30Lag1}to>YD*J^7jUp7?ZL8Y0iP42EW!va}mRCXnSIi zTX6vhzI!g0e_Zs8ufj0a=X5ng6nF>%IZ$dqcVGVcb@1$CD$!qc*xFO#iZ_7J4V@n( z$?&^wbcGWj5zH_VfLuHv2!Y51zBL$bV`3;<%4=%+0on&fKmyPb87WdJ!XwpgK0Cq% z@*@m)rJfz}05S-dAFvI*2w&veVz8rUS2}uHm3}$*`&((JxUyT)M3d_^+ckQs$@#ah zTV=qH?~v0vAT;&HY?{uIZavE+B&ycy@ld{PYQh7xH{dQ4JXd%)32{Od$<*$DFee(u zISjLJPe%*$d$~5`*n7$R{NxF6*S-j3oH}!mleHSkALd+o$ig57FE@=muj5g{!<6IT z%JuBhsGV%4ge%D60C|D0!A6Q7UE^_bK0&jNQ)kt5TI(c-OA=xCmkB$|S~=#g zhS@7vv*0X-ny59eVso>RUlwPAf#ilEk0+h6v4l#oW^-+#?AoL4j|OM7K2_4Ms2{pj z3?~d|U^!>dPfa+AGd?26kVdm5+I8MkYb1RkZ7(EuxG!hNx%=)n>u(-GzRJoO$?kQz zNaB^fpa;vi%|E@wI43A7KB~;)u%EAVu;&zDnKC7Rnt3^;WzPL*z@g!LzJOggX`~Aq z_tLq&T12=DO+MuXSN_;mVnq9uqsSr29H)}^wJ6udN_I|fs~zePww3~i`*t(Dcv~y! zSkFUm=@xx!Cb-@dIdFs(VioZ=@g)%D&M*`h7UU8p(owZ7d{QGK1cRq2C$`cFy3L^n+#=t!JIB${lctCg@v z1auhTE#uA&#kIA_`T0Ng8+bD!t^i-ZW;#eHucqU!H~M8+Oo4&`oGzK+s?eGeSDq0yJLb`PRbNj9bF8kaKcKuqcIcg zy3Pmh@Tf02+=R` z=nbb6;uz|}?^T@g@!=srJq8m1c!i2LZ^A|3j!)F$>U9CX3?YW(4rSvnbwjL2k9Rcg zP^$85*>Nme1=uUoPCPYxTY*LCe()ak?4xzW*x$d;lCbzOtFWuccva_;hYxKdpOOg| zT&&4fwzXNwrc8rrr1qV^NkQ_01NJOU7#g)(M-3GfMaeX1xq3Jo!`Fr}-V0dld+(pA z6E7bm=ajJwiyU0Di>XNx+1>Z?)c&}^1cMD&B-A$k`eo%bv|A^$-ZGkb_cDg#O&^by zYaR=&eG%^txD9pL|ppt!CQ-#(9~w?NljLMn0Fb{8@e{K!-A7di|Q1w=(;KS)$hKtrEyGF>&Z$eG^o05ZW>*) zgpb)EF=)b}D6$>+^#%$1?Bd7iv&))DL#1^py%zqRGMQyH*tEE|aaiJa<-h`KD-E;2Mh=D{B|`Sg&&f!4~6XAjE~nvL0TD$c%vW51lMn8;^X)Ven>j6O^Ke%6LeBCL8NHxBka)Yg7KgH;*>MqQVb zU!;?72h{OI0KNqR3!sxDAe_H0hL6NcL4Iv@7JhMAs{PxY4vctq1nlU!;UGK#x?-n; zZ^T=`-0Ns20k#B$2y6#{jh-uVpCbq6kVta{gd!yPwUG(jaCYXTk)iHc-*=Dk_sN`J zAG~8tQpfe?rWW!s;CZ_~RD3$fdF6W5=k%tMl9CZ+mW5mRjAUKNhJ@V>_g)b@uT={q zssVAT{p`o?5<*_b_F!gY?1cm(L{kJeUY_#pVmP5-0*&~#0^%S3+;el16Ew^}X|}-B z+oz@?T_%4X+%|vw_yMXjgmwfJEckAqCIrJt1sEIjKBy_(n+Tb=_*Me!T9Ay#L4~TQ zPYGw&$fr-XwzlXG-ZgzTmtmsz%p4W{lorPD$Y~y^`@kRkiv?P=+FPt*A~8aaRIT{9Ps&xaZFue|@$qq!;# z3O2-e?eSx+5t|*tp)}Edet|n$Tq#0KmL>;Mmy&esW7uK`>TZRWCgni7gp&@+7}b4j zj9Jr$GD6=%o;X*jUp^gf8o}@|HZVACT`!L)w@X zI_W|CtzvyE?g#PfmcB&{Dmr8B$***ZKb29_H$8Mnu0tD53U#ViLy6?d>3gBgrTxvp9Ca)gJjW753OzEv!f{cmGQquBH4H_kF=d zw}-rF>gxu6R7bg(<=>q@{#}-+3C8^71L-s|URiZJ=I>4XiT<=WbByFmd#HV0UePk8 zif<(6*!2VC7^2g1bjkqwx3;EYq`#dBjYMO>nFPeC;aW*U4TVTwQn+=CYHCQ}UU{Js z{^uG*{xT&jgXF3?dm$}y9L7)Z3VVHfrvqVzIDgyWZ$kamHS||}I=zf+K3ER>>hrro z;-kP)GUo+|U}7`A&ya^QEK#UqCh|4tNq{#9Oxuj`AsE9Tc9qRE!xsw1#`=sA+(%wd zpW=^2B!%3%Y`l?B{kkH0e%?A)wT+xq^wkG^oX``Ha(HT>g$wCte!jx&{~XQ$xbI@T zIL>3#ios>M>ydibbzW~u>)&fHUGBls2dW^9~oHs5(8e;&)+_>U4L`cIS?&1;*-Gh4{oBM2* z9122&jSq?wz!rf(i;VYBuCE{5Xuur~A-j{U2HlRX#Dr;7ovI)8!%f>QhC zjFIo^ip4m_Y9CsH+w>%uoO^>~Z+iB{H4A|Z0EiiMFUUhc`c%{3LWR2LjfM=l}Q!as!6Bb4U%JnNy zJ0>QV`g(eNXi0v5)5>(b8F6^U$!+&f*~Vc7?oEl0l#HrU=8QlFJb&8pHn7Z{_wn@O zu2jjwpS5l&6>s#W3cfycGvcm5xy!(wEj-HUQIKQp~h-8@t>te!G7 z@tOVUk0CnIsfj+mbFCSl-+ZRIyjscFh{xLU@YUUD)1G6F_l6}`?FWOugkL{tm9Lz& z#LcX)b$rsbBK+^Rh_!D@)74;h^iOdOchbYXH0oDvWdKk&+skny9e*~JH#B4jAQ{qO z5mbVM0#F3NBo0oO|8L+L4@(%RkxQW@@?U4@6h+s8McI3D()jjZ`wA$OfYHtNLI$i4 zfz5|ZYL}LlC`6g+TF0MV3Kb?(Yv@w~_hYdyj=soferRZ@eRVZ&#fp-O_1bOiDd0H) z=Z3%U!|?I&r7l;Bl45}?mq8!Wi@`r)?9YT^y)J?pQEkuf!mvY6)|kZ(RqR=I17s5* z5SRn#|4Y92-F`{)lDl^TDrS&>0q6kD9jqpJTPMIIWQGGbYVRss)VqPlEhk{a84mUF zGE6KXvVC^_;N;ZT?6i=j@d#-aeV`6-sJL)Z>;JwP43;R(?j1# zxo9GN_-bJIc+btF&*6yhUtres&{6ye{q-U^;3=YIf85GrFcT^6SmiMEmD`jby>%K0 z!y2nW?PoY;tMD)&^;(9%tRh`D(@wwCHL>giA5_UOn=-93(Z6T(qO8{BaE~yV#6fuF zcZMUbue?1fC0~+hee9}g#iuHslAS)a{WBx|%GR32V?aUh4Z>? z`$tB^WtlQiw8z8&SH9CbIehz}79h&6!9>NV`uMX;LH|_f=E?g=<}1&0n;Fp*K%~K> zn^0~DjE;iU>zNc^%5{v`UkZMa%pb8>6uYBnk==c8q3b2peRI&2ox6ML+khDB!r6sV z$ca3yFL%4=eHNi#boSemC<*fDRUC#12O}d~(MO+^FS(T*JaZ|;PGy)00>-j{8J&9~ z7ep1r^)^G0kvPI_@5IdX&cmVUaPJ@D6-8Y&{UvP2`>y1n>v_FPlWcU~o88_f_I$oU zn~w2+T!1oWC1Yc<2a5L>@1w9(^Vpjlq}?aH+?^)hZRG7O3!Fgp^`m)DuDDz4tf<28 zsvk%rTz~&G_Ftx7fUzbWcvpykx(^l^*pd{1stFQ5VK067@WBTrs>AcF9b+h076xKu z3F=yU0aS(s`gf}PMwHmde?z{mcc#o88i!O=yx4`WA?9m5l#^9yWQ76bEVeIZ{z_mx z%I4UOOG(Z3ND)t2`}L+H&7LA zSn3P?aHWV>FIUy3cFg5CX6sOE-d!?H)&$07KH}G-MvF0}Ox4*QyG8lgWhI}yu;h${ zu!?6V3@6X%_c{LN4LA5}cO-`ASnxKMI&u6?F&V9Lsr#NnfN5ErQZ;`>yhHx_RUwTa z&O`Az8KuiI!h6N0kLT}sgKXT?yKnR#+Sq4jw$|3LZw`$sbhS?u3=REQ`C57Peh}aN zp(@eL8RpgGI9~e=edNVMlzX#l%@&(XQg?0%mWXuG)To`H)>F3$h5@Bc!Lzxv+fNc5 z+g_Vg!$j-vgVY}0mh!HI8Kq_>^?UI*;uBw7SFf-FdoDM|aF+3$SacW*vk5u*fBxJ?1v;e=@*xpu! zbO}I1F#uoz5)8nNoG6$mM+ zuAmu#WN?I`53YX>PEHg=IqFd?PV{NnuR6fzRP?SLa|OA3*HkHA;pY zMC0_Q#I3|`gy$w6r?+1-2#gK$a+cl&Y6)bB49iaCYu` zyB;W`KO0kC^NR%Ihu%v~XkiUfl=xt6NPtLTgfhTzR8hQ{n(o)}8N9Qe)8dCt*)QO| zb`>^q+Q?JGkV9PaWmXoHntS&GWe5M7GlF+QIc~-=*#z+;wxr z1G>b04f^H&mU7H7{=xg`zx_MhJ>=K?;5S zO7Q%B{JgM|3P>*H)nNLo!=Ugjn^Z|c_(}PfCuq}FpB;%zXYRT3I@_{(^E%tj)azOD zNDGtEm--m^ z6Zmit3WDqiMo|#>2VNeq61!pb(@=z4?vcBxDO5XaPa%uRvgIk!(-tdSd|iy}(!w`y zGOAcNU&SWwxCx#UM;52|>?H6(Ub5`F#%s6CQGm+qlUd zgt!7!1jxV-4h*OU*_aXtx@6_#h_t8n`ax8J+)(@7%>PJ%1=1J<_JA*5AQI^)5t0f8 z%v4FeVig1S)fe}k0VMi}3)pM4B` z!d{rykqY49_VYLnF|}uiOaOZc=lE z1?7pD4hDE(}Iv=VMOXBkwzvb#x|GlqQgFQwP6byEEtVMTSaO(s z@T{GP|Cv*Wz2Rh6^ABJY>^D!G(`LJDeCeB8LY$rx5_pDYP)g+am@$O+PMm3=@d!d# zv~VjvDTuVZr}>#RAuo`qpTZDE+39JC>1pidHu&#e$#Q+mcWwL}mKf$Wzn8d7nnAnj zl^*V^ACV(&O`C+5&a4`3FO%n= z4$LXaREm`~qk|(Q-!*~~XuQB^OM_|jvDT&r69(!2N|m5I$ia9Xr&p)E6>9bsvPiNT zg?f+eO+7M^_^m=kgu0%fI;b5KZHKqD5PiYEm@`A>myQ4+_}$rKLDP7Gcv#vq;%IHp)8$;u`2G zs5#}G9zAje31e+F@IJc0_Xk%LCH@!sL{;!H2Y*T0s#2A&h(Z7oJ%N6u1{R5MoDZ*d z0mw7*;2O*$o`caIgz({8o+7q8kN^itVqC?X{^+S^6K6gFHqKQbMiU=JB$H5k1E9d# ziq5f-bu219rbC7cx{mV9$M1~CNCncpRSNLeNcFz~nv7qzJXSC~7y zZ9e^t6SL*975wX$a=F)?WmCd$S=UB6T%YigKDE+OS_u)vyH=On(`^g10YsG#S5LIh z{p=}fZI+877Wx}}=vE0TY|U~-7)U?9N>h4Bp)C-z{X!c0>u z1tCtaw|`BnLz;dgldfG_zxv>gg73Lpn{w&8cm~wt9OO}AmY(uDIj@AOEqOA6>5ajZ zS?r46T{!z^vXxnBRRdUKn!>T6(bsC`_A+rHulJUyaC@P>ttZsgJ zN;UkBUutqL!9gH8WJ%$^(-jk^wt@4%yO7fZk^$_NAJy-Ej(;O1ORt*7imtm;o^PQe z?`LTpxki)FuPSKFviEmoQunOq1BNw0`zIdOrr< zGH?umo)98k%6S~xz=s^vsKCiWGC2@0CFtfmKQHe~K|@|x!3XGId?FlLo5b;CvQbwy zhtc{ywE3G9rZ(U2dCmr6UNAw3PIVE74o+S){QvjTuT!&?oX2}ZVq3;M)o zz!5Fmo?QiXf2_JzNg}02G*N`+r-$mer+;TU;=z*{%Fxc;<6@wwfJ*&jqc~x4-)DSw zHVX7==YJYHdS~A~M0zo#Gz18RI06$I)}>Y$9NRK-(%G-X6(-X1-H^C>(}rqZJ<11} znM0Z96`LrlCU$cXha>9&o!NApER`kN@)$}=vGJZKlN=KXa9qkQfCL_so6Cqy1^PZ( zq0k8VWyXJN;KXXYpk4B^!%BMTIU&Ov&1PQb(Ye5rmAW)}dXZz3cn{D?^wh2u7>3)v zoAqQO))@=DbC=_xERj#!eBE2cZ2naV)na|y>)0Am)pP8e1f9S}u%9o0nbpT-ks?r9NPK~Eo_Uxd1S0F6u>#cr_aER4t(dll%(^yGY(Jw zO3RRBtgSjfFXl_AO{k9Pi;U~1Q}NazA2~c_!_eTK{)Cq)Iik)+OhmuLRAJce?t*RH z)MhlOv@2~|@z}>_JBajvS)@`~$Myl_Tm6b)m{)TGVf?TUPA?raL)274*<-Z!)NgRi zs2*;{lslH+(s`mfRs7P_M)*t1=a3Rz>w`oMy83$GS~@d?1+w+hg5LGc_2mhOCMryh z$nbEMt&y8FW40r>t>7Nz`i5GRL7D@X=Q6m|Au1S0uquH8%M%D4Vkj6DZqV`kT6Zrc^lb`bx?;_j z?0|(=XvvefeoCVo(}A{ap>CY#CT<1 zW0bsVK*&~isx8TsaH^IU7YjD*zCl-!d3~F@_v;j03foxK21lblxtLy^o?B-E--c^R zx&wV~kaO;}gQtmIJ>lNY+9Lbqdq>CC^i-NDa-5bi6Q4# zWg554t$W{nCYs{+$B_$t+b=rx>Fx&V<4^gWS89nYs>yB)5$AASVOrhAv$Yy_V#}MO z-;Z9`>roVMi<|!WME37Wsi|ap&3kJ#R^=R=#1XUGT%4HVs{(G>3f6jNwSM=4bNcTe zqSN3loCR=O#M`|=D@cg=R`ZIUjEZl@aFEWJ*FTg(fbU3%LROmUB`&mfK6X!+TKZd0 zJb9zPz1IE1G}mNof^3Y^&!)Y}5pnfgc3kyI+Ub?+(z-V=N}oL5&8|Hd?TC_g)g*aH zqc))IA!4A87Wu4}jVsTwy`lnNjVpq7BF`N?ZYgLm;2f-AC|ufpr=M(tx$@hSWTij8 z1r;TuPKa#~cfNlJ<`rVx2e-}rfkCUz6ad0AMDhl*1VCvKQwKN;?r5edgAx}UprN*b z<6D3#Mu&ylHh=BdKJsJ=<6)v2K89!wH!tgh6)zAQN%adl%mrvunH779(XltwlNo|l z(b_-$npQShe%M;Tf=%)S3zHMcjxVH%l z2owO;2Xxf&1b~SV=S>hG1o!*$GTea@;qFEq`7QDOjmOEW2?;kzaW^anYTEwLm6n#e zLN)?;;At+>ZKH?xCl;w~>Fh3AQ<57s?FkVa%C;)k4^6eio)EQ#^24I1YqBJU(Hq>F z0LAdX`$neY8vG`?Bxx)(;`^RcD|VZJ%FqjHF{6puSG6>&yks4y^GN#Ujg-_15IQ2P z*(Xo5*U=ZpicfroZn3qdRrRFFQg;xDm^=AiI9xW(WKXBb>K{p3WrQosc)Zu;DDViy zpRmZI5lApDeOc$;tI5>2>}HF#;Cr-Xz=k7+FBfWJJ+ zt##X#Ir$Sg;?G)hcAO*x1I!~^mGen)xZt9~8M?p!5jm0^C~ximWs9SU_k9j=t-A?Z1KyRdv+%RhQT#VQJJ z>d)O~d73jw)43WK+FChc$rMrf?x$Sx5`X2$sQy{2>K9a0M5?}WS3ExkVxT;5hil(n zNyt~Vv&a4?$Ym;nU-Zg$e2TrI+%-{?shP6jM2JbJYhCa|mfW}p!)e7MfrX}$`&g9S zYEEP81O2)qnt7Nunv?Z-x5ctzoyP{QI=hCIVr^0W5aB1K_Mm z@dWqIzZ1k+?DcCrP|BXX>^P;@UmIE82ek%SbkQPYtTy@`3k9ApGcR{so^>F`ci?P} z1D{Q90viTx@JAYHyd~k6#&VCSy3vEpbc~UHF}<6czZsfVdL`LO=f~%WvgNTDNg(T z*GEN|oVFPXeL>_;`9JkPco(okgHDr&$>-6?Jl=Z30D>o|<5f0Q`7F32!buIWHJtt; z!MgtbmZ{&b6@B7Rne@5&@8mvUar*l9_V%itBpf6-D2*pis?>!r|Lk3(#E*J-2cx-f z(*?rd$JQy7ek0RdWU>Svg~$&PE~1|187UMW8ymSW{!Nbrrzog3hvPV8Z-1am8cmTq zDxD5>qk(kjoG*i)))u(tzYi3_cwEoESM^sjvfn94>)n`UiqY|p9(dXTg=UvKbmVvpw$Lv8>PO*=$Hx9 zE-Gqs2JOt-4^^?nG06K~k2XT*U0s15=cV&`ogU>W0ajZZ)gC-vx;A0!8;(5&v?FFe znrnwVNbgq|<<*904LV}<8@A7TI@{%N_}n9qZZJRms#RSzSZgoN!tO+FCKW5Nm{v*P zNzx!TU~;vZahQ&EhH`a}$eFQl0cLm}+WX7J3!Tg|Vl-y4(a90n>~W7TUf}AJ4Q8Y1 zHDKNerQhPm!;+ILsm@7wQ>o`(c4O9{;`7pP+gIDNd9T0q3@8z1GLUW25=W>KN;HT- zBqt~JRaR=&o414lcMlHgge>wff6)8hY_Bq*Og?gjbROQyKD;J>3Mk+&($f~oj2U=lrZ;aCYp5b!FbFAX-@gx&ocB?F7{v-@#zZ)lzdj-@hb&s1 zuP1dTJY`e7m3VeU{8TaaQ4-GsnagF+BQE|3QR2hM;AfWum=5*G*$sk_UVSYSrKbD(o zbW=9orFksSz@^Q z@n(N=`^oUkjSl?mtBQphWJar8k7r{#q)!>IFNev{Kaex0c%Kec`Rg}oT6fk@!6QYP zdUf4BMzq1)gMh7yzW1G>j;@o_8=eot$_x(MjrP{@hwD^9K*R^Y-FCa=EkPIiqw_=K zaqo8Puyt@FFg;$?Yq+Q=AF!8*YrU02GI@6Tu2G9~nJ=N zl4p#JdxwVbAs-q{o%m99+HJaCzIwmtYK4CN`h!d==DTu9&xbcvhLZZ!0$#sj#rs~X zMF@KIBdLUYEqn>Nm3VU1-MBSl=xb~S3B_b1c-OK$K1J5luz&T!&0ignTCME1H$?l% z-9dSu1^rov*tfdmPh(a3S&z+wc2LWw0q!c87nf1k?xTrPtcfWEv6gJ-^4TIa_Iw26 z?gErH9H--hEHk|8Z*5L+$h7fSGQxdzj2uvD%VUMjkLb6eu>5<)fxYhPCBbUZ!rP_q z!+7wclnt82Ij)4aiBnz~OKLK8QNKLN;9`o=jFF;wM)l5($mxw!(Sy>`w0os+-YwUu zFw^?laiE;Xz-CzAI<}wYU^2rqvm5o+_9}@E$Ew_ckL-UlboN{Ekv(GaI*+oISXsq7 zH@CNYZ|t^)-W9=pH!JYX===6lXup@i)~6`-o_s#_b`rC^fBAi;)VpA62z*CXulU`7 zT|e+dV8e2Rl$=Jdsr$pH5W}C z(+iwaq0AJ9ZkwoJ`d)VO^PsslM^}q=FZq9HEa=HBs%TgWNob0$WYkIK>W@kshm$jV z-R*AF8F=S3R!t2GZ+_kOAf@T)0BQqJ=Yw z@^;j#9&D`J&p8^=SbWjRSxzs}a__9SHx}>+Z|)x7yhf+j*a#b`ZP$I&BhMp#S}A{1 z1}MOL!`JZc47^Uj<$=zu7pxsso|g;E{m|Yni7xmbt_%Y5xVShV()}&%8wAI8@V9bz zcfSiX9+>7s^#|_goN;w54eW+CiA4%y!@OumJ10!wJ{|@^RKQz;k(KePp3+ZGnOxHa z0M<DtSs_EbJmXzqKY#?8NjM(QV5VxdA;KOV0Mq{gx78P6ZRc5#daRsvjz zU?xQHwrBe(L2vw8K4Cm1CFQFUmDIS|xOtdk=nfCQOLZ$rY%nuv{Lr{_bORD&^7xNr z)6&wQ0thiADxW&v_wxu#DQ97@;Rb(K}t1>4kbG#r?*giE@^cQR(4JR6%UNDS|j zo3VYLDk+xkxHJ5MtLQLt168m6n$2ncIZ;F1HpGjF^pZK_3jU=aGuHda$wkx-PJ5#3 zn-l`x74!bh%N~?Fgt?m;R6BZ9Gp#KKs9+SAzn*^~YEP+ZZ$dV5JK0jRV8B*0fcdsr zbPxa7wKdl7iE%59#NkdRTH3m-Yvl?_Q&9}LWQ7T1osD~m5#nG`1XGlx=~xve*}8)s z0(##z>)^G0@9$r~mh%ZH#ZYQ12rfq*Q?IVRaxyY9x@&98`bqs|PL7JNuQW_uGbJK{ zOb(f~!7f2(-=zZnzUTW5LV_;D!5_&UgBc@rXAv-8H8nMh9Pm0G@T6*#d9MtR`7k%e zf)>`8U>hzr)t_ua=f1B=+Rs;o@7vpRvSXb3#^hj!3;)WRWPZfDLyyfg)D>rVDwCj; zDe>myp}{z%sv?}`d_lEEJTQ=@!ubi)(CcZzT3vDDTIHx zBkxu9Z+S>CPCNbqWTD@iskW+UYDnUV4uMeK<>iE%YJq|B&CSg!&-un24$J>>c1v<| z-+J5*+Dj?_6A}26FfoNK{JpnqP9ijvW|lnc*fxF)@kS=}O4DtznmYZU6b^HrhHz`J zkiq8+`NoJJ9=5Nv{?OjO5a{^G56?`(AcYiqZ)EEpcvQs7+$p&InpaquI=o+syiflL z?Fwp$^jPFds3LH7H-0|@l8&}ssMJ=^r*$*0=bofmIL#}^!u$i~L$WrKCvL=H`};~` zT$r{wPP#Lkt|isg!~hj`l`m;@RK{XHB9WvWm%V#c-S;haB4fZp0IxLw`mml2H4n*!5`EVcjHLIl&0z=$8p-GL>JW)E zwvY+uY$R1tb>mdpH#2=Fm}!yMsU@2hk>j&w%x`R(ZK~wSsv1N0`f<2LzJh?riw_ew zmIB;=7(KAwljhqpJhO6S^wcPnO;Ovhi(}%mm1i@5dRrX}VR6o?z)k}}G z4;Gh>mtF_HpTqWNUEQAec5-URWxoK0SNZFs0?z z^;fHUjHVsSHFQZmRES3h`_@_k$$#+_VlskJQYf8*$VZ^ zp@J#>7SfT9tc@< zm95-6hVG)ctc?2;r|wKb@4fP>s$PV7@a2KV*#5*VW)vuDPgaG4cvCseImE8wXT!z> zWHMHb9b^Hxza0P1<;P#y`?VUK1y#KykQKSHHyUpLp3@}LtP#O{D zQ(nD_0&2k5`X}`8W>iF3i)vFdGT4ECNWXA`gCv?ms%*+z*8nDXb=S>-IA zc`)c58HwE>5X4WSGN}HN7Z z>7Sp{NOt6tthmKWRM%b%l5k4OP+ZBfsH$UA*tDZl;n23!+xo#5l+!?YcqW$lyi5=kyoo1R_ZI}FKRObOkO zJ|F~uR9I(d>P?gYVes+ssnn;yb;2$zOac^Ykg~(sAr*Mu$X9j@{Tq_ioFnCiar5$Y zOts?Lqx&#f0YU-50uT!zd{8$jSNHB+t<#JULf`>nDGYtC4mCqo80>4HLab%3D$Q9h z@unmi6r|C1gP5VI7c=}WV ztz1^R^#Uk%FoVi=Lr>_=%HWp_{C3R4Kay~G)-O$>M{nw{jU}HO%;O@Iuc9u>O{WId zKU`c~JP!PKl*-dOG*{5ry{`Nbdlp|LZkwIg+vL6;Bz&h!9F==+rO) zD+I2j-nO;x>Qxvm;jPA}y2i&(b%6Au6>|9g8|xzRTZm}|SVVo5gol6x!~Ev z2=eTOQQ%7RUv4S5-^6$&|4Bp+59p069)+g1PeL83o0`7F&%f1bs$a@t&|c%Q%fy^< zAO*V)POgveqZ+?18i z*Nw%?vmHG9xcp{j3!5=jjCHX5I$oKqzPxYsGO1LWI!Bnk>iwiUmfTixhA(hEKZ~{6 zg=D&w7t)Enkz&|d4JgNi185cNA|22RLTvk94MF_M_lk&^Q-x+*s7JyeR~krHOwPI zClat7%T@6Mme-`ja8})WPYq(MVYIh|<#q;Zr;QR)4DpgHb>HXAS8+KT99BDcvFU>b z-IX1lyE;<`k@}L3FOGz5_%geC@RV`8<&|rB!Il71xB)_kIW`G5ns7pI;PY z{FRjgN!()KGjZ=82C~+gEWsv{N~jYwY^)4A*uUqleSKR~LBrT7UFn&l3Ypn(i)zfu z9>n@)T4j^vA00~^xJn`1b zDiL5J12H{NV*#>wZu4eMfy)s{eGKjz-_>v*I6Dg=TMg6~;3cV#sxK2frY@+ck%O`}{o*wLvZ>(bk2XK*prczsVK7O%3#$UkSEepto$UR5Q?mrx<*pX+ z4@k<-Pk^NZ@5z6a-=-5t6^Ip`|N4!E&NTiziRv7P^*rdS*(vey_KJYmh}baJKl%Ow z2vW$Xh!VfBx!K%qBP%Ofjtb*$O-9 zmMTk0?^9o(T5%tXa#Q|bNDT{V{Ur-KBeIA6?aOV`#x}G7%LKNUL>{LWsHbW7c-vp> z$LtoB^4O$=V908{ydfjQ_xELM=ciAfDkxiF{u3x{$UOL%q`jWD-euw6i*&zG691~+ zTwQs=2G%{=OM*W=e2=j7<6{vvZkV_7_88Yx6dhL!j_}}qV00p ztL>YxwTA#0tXCj}zCP1)jxDw6>l|C1>>1xL&6EMNxcjsD2KQ{WF-q|CHzL+q6F4b9 zCaDO##Xw^l)~IK-SYe&{F{p}47lgZcK<0$uaTMoVyC3s>&tr2I{tw}0-zMtJuVFJv zF}&7D^LO1>orZB>b+yhBQQ9}IHH?w#eU>6E&BVfKJhgrOkJ9HEb~}PRgS82YQh-_dVMUbRX5I*D+llN`Zmo0R)L-i z;LDI9cvPpimMsXb`y1U%-WP!y1o4pq4i<2F5Dk`zNxGgI+!mnk4@=S>B3*b12QFBG zBDQzn$`AD%!slN&Uz0>C2L!hQHK;g59#-3Q2vMfPhXnS|2vGwF7J%shQrhUf%LGLa zLVW(uEc;^NG7gF0LnbBh%r}L^Vh}PgV(|0tXU#u+F=vinKw zi;4-c^jHq1xr~}(K;5KJ!Yvsc^lUrI!vIyaohD+H?UIMn7`&UOqmw&&mbhht1g1T%PYhQb1Ysb&abnsSSSyc3ag>+1*i^{M&q$Jq3c1nyxXNFp3h z_db=#b3BhZuA13Wg@Bcxv{DpGF`Eid>2t2guEv+ecb96h@>BJV4@62y&XeA{C&;Sj z5}&$N|I^lLHl%id=Vy)=t`L@SZ*U#vtn13G=nct;t~x%u@0ud{hOr;6U1s4>4F`Gr zm`17hmO@L1%brf%0j9uR5Ca8|*llaNN_;OhLGFOfL0=1sW5TmP+kT>B<@J)=0VV+eh)(i`H>$R57+~;^<#ZRG(foXhui#b$af`*c_?2!cg<{ zGfQ4%)S~VWSA0hAmbs1B{`j0+6fgV(lMWI|7#>jz8w*^q*0=Z|An|UN5ZJRCPSVvC?vte0z!}2TJXFZl5W&AH`9Ry7-%o+U41>?zrg9(Rm_&zkwg2u z`opnEUoi{#LHEHF6XeCn&ErWGxpvewetdfG@&qWSV+xU;-QHh2If zA3BEnt*o4$G|uQ#+E3Xxp0@c=#p$x=ulPIrB#J7&l&LY|Ux=9M2)y$oz!J5anCklG zOU2)tccLZu=dZL{e{;e`qJr4`v{Y5G0nkv0z#~fc-9S^phw&q#M!_x9&F@1Nl>gDh zt&`KSpm-=~AtZSj+DSH=v_ASO-IXZlI(Y;I!C%!fy6)>j0uoM!IFz`#i6SXQi~KgH z_=wsPVX*wq73IT>^?zoHMMZ3|{aNVZ;0i>wEL;e|F=OEO>8}i+V*srtfcJ?WPna;o z*24A-42E5iH0d#%E;ukc3YXOt>t~ysm6er?@Ls^e5hE)I6;3@4jNRq_gl<69zhPpd zCavfH$3yvp8Q*i@-I=DLV}^Rq_fvQ@e-&S1yZ;r|3nf-)V!;6zDgq5l3(W~mIi=CB zD#wd6B~s{tHfSNGuUB)6AHI4NXFjHubq`!7v+H)ipBFBtSoFNdih)A$=N>ih7j}_u z4Cz?bRQI`|+yFV<$?uvVB9Ihpf4dGy%rfle6QGU3SHOSyc?`Ai63M?s5;!n9{wTE9 zKsg#MUvQk3kx};3!`djaX0}d8-6QmP7o@k)#J#PrfAQU~BmU+9ZD`OvLJyKh^k^S7 zzSQaU@tUS^tXV4c+$4dexOH(6i!`M=t^A1Sy7(Jt{SvK06DCsgR zHPH@nHZasEXCG%~=P7*xxqZ$JZ(=Bupf-o1gKs{wa=^|YaWL)V_A1!olh$HdHlhn&sc>&7 z?Y(zG1WC7+P8yn>(^3d;G{=0y%30o35KwHZMy;gkEZVq#BzWCe<(ZIBYV$8l9iRc_evC^tO_Z6la;-)vbV?zWn{0+ zL`L?CY_j=X_xb)l=dW`P>G3@GeZQ~kH3<;97}kkUc%N6pV4rHAeAyKK(sTXcQNH&H zJ0g~8^tkch!Gpm+PUw{PAod?nsrHk!?$$0Mo$&%p?Nw2Oc}p9{Kln8GE2I%%2ZB>u zZE-4b=ALW#lHHB{7uEbtJLlmBT8o@MuGC7Mzc|R~B>S%zS$i`*@yY%^m9g+Au}-PD3|)vpK$d^APs{J;zv$@Ygo(*T8T=Zqx zf+;FtH%fwYDN}tYyUR}DGb44spSdcpm}UmL{OWQgRQ^OguDzk%W{}IWZysoC+JppHotC#;)e}ul97?!FB@9` zbqw51FccHYGxBm@FSzm!#z@Uak4lZ+2loSN6PQJJJqV-Igk0L0Q#gUUGhN>daNzHX z;~DM*`1m0hNh*AlBeI&3;rzFLa8_-qG%=5D%Ll&j3D?^0%=C^L+~Ty=1Z!HsW>Fx2 zZ^Z+d`Af{>8N2oT1|iPnIA64HZ{=S2bm9pw;nLpls5ix;&8HcGb<;qL0!Rl9LOR8iQy=m?6twuj?ZnoNx%j zqqG&IZE#1zg9v^Q_hh@#^lGqm|oUc?0lFJTYBFJAk}SJX&rr?E<3> zBM?x^Z2v%k_wVjB0gY~&OGs~rypS%xPH{|+64)iGrAyl}*cn4ZK(uXD)4L=M ziLL-Kf+Gp(@>XQ=gF(jE1`{1EIw68B`7c)#C&ljhalmYB0;Y&U_3_Lu!`utT<3}Sq zMmW>7*RkMd&xS402){*7!QXQwUz~P3WGwov@4NG>K&oA7ikyJ$RflH6f}B9TkD+vP zLaMZH)K?xlS$~yJl8Qrj^d?XSA$at1uS_qt^NacvKCjj`w_shtzg0(IwGCBRQgQPb zbZ+91oMaDDbG0%oh0@ySD!7E^hBMpi0AmHc##JLwb?eO~&dr%YS=IumCm}bD0xbo) zA%9idQb2V)K2K6=Y8z~j0mK>{OlldXe8GSynnI!>tSN@jp902ea1faCC)w|>YRwfw z@*gzLkvxYb^8**bZjW;4md1x0#5|TXKHJNhqjV99vC>~2ENUbuaMF3)A0?LFmf&WI zFO}H~7vnTaF@ct~BD-UD>(+d0h@O;IQo@k{p@hKJBeuD)>e1vDqS)}G<@7*1`ML8M z?G9_5OSsU)x_v0`ioo@j)M=qy}gY}lz>pg zwHn$U4Qw?7qL7q=qIG4DF-bKG;oa~kb)Qj zXoPhDxh1l6!ki6GaM-%x#AaGrLcRj<_8Hthj7UH`PL%Ix4-CNw0Nno%+&MdEdjktd zkOdQzjS3~sS{9$5y!n&K z#CEheO?7m}%)u`zOZY5$JVNXVT^_k#fys>T&fJLSLOwO~X$Z z#&5kSmIh{5hh=GMNgm@fp}5B<4x5)sWRD$hycngN4^2pL;2x0Sv7E1rxlD zhe+fP_JD-4j~_EDDu_d5nRux2C_XymvU>|eSPp^9Xc@{@aDZK9&hqct8u9%A#F7b27! zDjWDo;QWy*ng$L8c3Tpl)`_YlZOVSX09O?BYl^}d222+f=pg`5blC)G72IAO8r~;5 z$Z7>@>5TlVnrNKUjzE}X-x$6C0>`lXIM81Mgyedsh^|3ag<;1luJI_}BVs=IQt0!M?Li~Z2B z!%_9>2OuMLs^dF_fz;1uopV7f;_z8kNkoYs?lwx%{8c@b`&^7W{;;>)R)zRnXD?VS zyxFGwTMa+1ZIWKb49gvrJFretCg1SWS<$6sZ#;gp{^s3p8inY-git*@3BN$$sPtS4 zP6EqpYpBFn)!D!4_|VeiZme0$fl;G(*Oq^o5I|LL8{7{YA(0aqlwptrLmpF-DxefN z2AE{i8NS5VFn@5N@A@bt{a}AcUVlQ>V8@ed)GIwlaBDAR5hv%hvHr59Qy^~}K!+ab znGKKI>7Sc4f2P(kDAn?PIVq(i?Ek{{;Y3LX}NC-pSgPe9iH&`1ZQ8S)7H75)O!qM zgrJG%(YB(63PxmdQM~^oif7Lwk?3$*{QLU=h>LH4-PhI{ zR*&l$7$9AZU>~nFrH#=2)B(`dC+|xy1l0?T!F~G`Qm3FzQq$P@9k{Om;tF+2w1^sJ z170GK_THP>;anB#=X-8C&6cF!TK!!))cppoFa&OjzaX4kz^$7G@Jhz$3~(=+5wSyCm! zCkg*>wd!hVV`Lc_86g5{JwJ3}BVHKgFr=^N6gY#4s;j4mxIF*_b-LK4;H(Fs5R@n) z8>JoS)2i4qV8{TZNn#?^9ApT=O}(4OCR{VBp2TmXYcO>Kl9XPD-CS&!Rlf4SSEv zrTuGbB&E8x8~1X4Y4=P5NC`t>E~iJu^taRZO}rNp7M71}?V{{kjq&7iKMx;8H9XHD zAR26c&0Z!HZ&`v!Tx4S7714)*&T)`Xe>sG{&ab7Z)Wqy$Tq+`?OY8bFVJ5bow~MT0 zN#a`E-G#zDH`#)M%he-CT~+D>(Eko>`p6@ zw&4+)D5j;CybOF{hOYae`uNxEimhdC=J~j$k8d=ye<~T!)>-$(s5gIFiAV-6**ybZj^)aYsK^-m#cCwxbr*;1&MQ62i~*$ zNp8#$fA7!5G#G7OiE8-5HO1|i!F7O@KW>FjJa5xo5D6|$>raau)^268KL&SiZO?$V zFWy#7ixiL%Y7jjE`9@ayNSQ*{&=4EIJVYb~vJEgkBDLEHjs+tm;LAmR){9E_&s3oH z0_H9-{rr4;HD@@#?)Qu6@SqPNes{YFGbOS@79H!htIIs`5z5DdprT^C-2;~Gf|8Op zWHTPo(O~4}R%x&9?dgI31ELgCMn>J?iFGwgqiBD9lz>cvBPhq z*F(7-MW8N^DSn5yR+jTR=ck1J-m4(9M#8L_g@g<=->fx3AGxC{(Wr6p8gUH!lx)>6S)d5-yBX( zmxVYvIVBFm-iQ7%ni&TB^X?yZ2l>(iQ`>2PH(31n`Pk~`z z#R)a?f*%%d-|uk&@#cw-yU}7T-hcWM`L9bI+w#52)n~K@;8W|xWuzzNFOprcawu8E z$+Fz(PPLh4o0d<;1}~JXz}`v>nTbSqD}GS<Oqs;qT8W{5rzWH}!a&uUy!h_+#$246e&NZ2;#5O|U|}Jz3u)D;)XG3t zNeU=dOVn)2wFc%o>D8x%nh%l& zMQ_nBjE$^~Dd31t%5N?2k$*`qx#`wWIQw;=g2!k*_`hmGgP{hWpu#RvIU?%$mE1UQ zBN?kZEjnM$Uj}DE$hU?-0=)kF)WEeW-|Jjg)04}2ry(0ZZ;BfNFAkIw;GHa(NIVkN z$iP1om;kcvbu{`^)t~`%GDRe*=Dl;kBz?TFcYKw{m)j&XCac|ET{K)N`3m6t0A0c6 z?+cN`&@={c22z_G*{P+giv-9+0L0u+G#^mSf$9XYIm{;^W*LOhffSk}#BrQ{w#aT? z#;9%wi8!FT93DjkVF(TfZ)cX^)h&8$`Km$f2+c3Xx1dv6Qf++cy!pxf;CUV3exUFk z^gD5~rK^t2Z~wh+jOdb&Cx5RXiplxZX!dG#G=;%p&ux>SD`82Rw$qPMvRd43%nLc+zA6;1QZWbj`8Vb0k4k5OZ{ruuXp462U>h1PA0i!M}tx44V0 z$g@WzJmgC<#5nT|zIBr!NmY7fG_zzRJf!O?utk)~w8YBJ!_fhZ=02^fQud7R^WvzN zD?ia01x+q>m_Fj9>NOUo?+ZL`O%HYNb-(SMn3~YuaFyROF}?TnRrZlMj|O)5UH{fO z7nw%iQFLa!bX6l?nf9I~LEe0?kT_eV!jM$}RcwOVItx&lQ_`=!I(Vo&2TsDHWo4D-WC?_aP}^zhw2q9- z6~AVN@5{P$>foUOz!))rL)7bKAT$QRb1JMaOjFC~6Zl%9RoS4?`ar;6CQp9*wgDhT z(CcpM;Xwl=5P;WUf>NOlLfYk_Is>Vsf;mwyfeccFRT6KR4SWzs?4=(c*0kN`Swqus zknJ*LiuQr=0x1$b#?BPApG83hN;!}T@CW0Cd=GO|BQ#YC<2vsckXFm;?}`*L4~XzY zll8!34uIO?tY;I2Pb;&lyZb-@t0Kdzp>BUDX|Rr;R*pW5I5EiHlg=eXI_uW zgf=9u2g$HJ7+gOG?t=#2kH;7($ulwj$FG1 zNSY}Kr~VU%dY?W-_&6|OA}9bDnN9g9HR0yqdH6Y)D{DkP24IiRp9MY6b~?@f+ACw^ zms)Lb=di>uatv@@NB`p_ipcaMQA6m5f5(|^6kxN9M}H}pqPNa>!(_klIJNKU^3aDK zElnPbcmAon)fTjJ7t?m?x#DNY-AgU>q99H>i(l)DniOqU4?Y^dV%?**a1>kk!}-Ddm7(99yHPGnTcvOWkxQ_htu@eqao(JHeEUY)mrOcS3x(iDoskJh811>J^Pu8xMNv;uA98;Bdtr# z$Ggws&@9nk6>8M(v7zaI# z(ewFDAJrF(5u-mu1O``yoyQ07AenaSyz!%qeAI962vOfL;iPkb1?WUz5>0B6o}M88 z>tfjVH&c`iZ)tPC4w0-Xdx|7tpx&pY_*Xj6le2Yd8d)^&?^mr&<>s;?MTSVciH(gk z2dOsaLWN4e;hn8)h}tjD7~UK1=uA%|V46;>Z-O=L3M5#3(SRWV`{HQUpJ3LV(CO#s zC?><*Jg}9cq{xh~=8#r_S6=BX;&I}{E*wz7r-RkOE8hcgM>U5Sl9(Kz*}kf}dTzNd z1&m@^;d0YhQp(n|({JHQhu4CHa>8pVa(E$#l#*^=oNg_^)&WX}_YikAZYK|SH-K%k zP$L2(P5PkcqTse|&(?jF)dmo z#c+E)DRcA~xhsBmZ!d}Wv$fMp$q?{CzDiZO zNq#!gRaft&6J-y%B7e?N84$1wqAlx{pjIjaH3*Jm?_!! zrib13Yr{st%MIuS;{P1)bL{~VgKR%QRuhm6P}P7$*T6OxA~ql=CpS+A4?6TS@aB-kXN&Me z?UwBwN}a22DSJH=z$!4|-%jklm)33d^NZxA~?$sk>Cy08VR5((KL`^m6$ zx})*&{IS;uX!HVQd2Ts#?XCOn8728z-h1LPo6wR>6!y_<@^g`b+a{W6Vb%2|?mM*~ zbM_f(dc()-L|kstwZ+^nVKFcjpbV^dE;L!5Q1kXoR^snd_hkMT-Wfq?oWDz6niD7R zkjrj5=N|}puXsoZ-MtHO#kLa6-k7eE@hgJf1Wuk3^sD#Q*#A44KJV7av0?ptzVFPY z>z+MhKN9iPdDYB9x_+5-US3AmK52jZsP-~GroW~%=h9qlIqHF@f!zFY#d-UC z1V8YqKCJ#g2o(4)9;#M6sfzEg=eexdkd;I71ByUmDYSgOm;~ zzuMR932YN`&5@+RJ#`z92m`}D;8@z6`H<7tZJ})(xgvnUpy`C-;O3Tr6wyyb@C|V2 z{UFqjV6Y8$SW5v646>T@Gv`K{0{9&c#hQW=wjFya>;i0FvRM4u@q&2g2sqml%Ygg=(PuZ2J#&W8m@vkk-`GlNOv&&|GLfjf`qY@{)l81)Sy(d4?mW z6%`*J2r{9wzt1FFky#cvX1HZq{y3QfQsVcvYr&C&HtVMi**?)kBIv1yan}fwxerw! zya{x%bI>}Rk`e~of6Mv-h_AzniebzxQVvZO1gMBGL^goJl9`ugL&b604m}N)H<%s+ z;P@&qx3So)IYgs)II2}oAVw?Z?2`97bo3C=ILd377SEn7KxA+dhp(VnMbo@J%U2)r;OC>}hIS7RKvp5o>@Ks^O-cW=cQgkHcu@`}@%}BL zSp`4nV(ckD%mjb6uNLIMRn5e7qzWEAK;@{R9yBN1sn}jfoyl1upFix8_0G_!ORE=$ za2=+eByGCu9P1q0uS4U4p8Pwte<)UTldFxw*&xxJOBlbVjt206@&G>@1^nf>2W`Z- zJ#jXw;enbKm1d=;+(m?)m+x(^&V+o`#$IBfV{pcC^q23ol#Zk3>vaRVzd z&}$CH@*h2=KW3S7>flQ`huMP0prVDL1u3L~4iBxzj|t?oG&MDSkmVL0iKq-NZ5gyA z;N6%8bwAM56M)a~-`{b6B&e%J{G1~<%DBa7fuJk(Ys!b?U*%7jcwIpr10Xs=If42Y z@Pp{=M<7jI-`n>&qaAF^IjsKt850%<*ceuwL;*fTt}oF0s;JD#6cP&%nn#3F|s8hr~vmOkn#65GzRh}?^9a| z)2KhBL3{4MpoM#Qx!xn3k%wo0`)w!(%ITdbk6@kma& z)rQX5xu<>yNuS2Y&pi(^_(QUCl#_K_Phg^gyC@5!jXtDCBiddXxcZA7__-7Z5*eIu z?}Mie^8FsxE<@TGP)txNHU!!UxYs}~HVa4PlQZ+dryr^a76y)2<)Yl4Bi8it^@&K9!C|@XwKvSy1#?KMCdT zA9?zKGyhzsw{_{j4I%@1;vDPHUEngh^|&!rYlf*^EHE#T`9H(Ox2;3QXhZ#K|3icr zn_azZHt1t?>Mt|>J%a_u)!ZPV^5?|hwUq8^mUo!U^WDNlJw<$!)TDC0wX*X>BO>d3 z2Ri~&w}i6rw4!%4YiL@v2lUjK{SM98d<^kWdF4gb1iPMcw+!Vxr7rXL?vgq7e_aUg zYAamK;vjfc+0#sFg#E?NtSjw)cz@ecPn>el!+;9&%!+=)P=@0qKy0N32M42$o?C4h zIEdW~e$jxB(HNJKs!bOWbl%n1FXPDbledkXe&EJiaic8l(UrKkisjEPd^>a3;5C6| zlyAoVss@XHExGbHetV@?QJOQc)y46nTBUF0SAeertB}lMX>McIN^bB*2+r#kPa_MC zS`IMLQeuvfbM+d-4b|P*AC&`1V%ssW}_#?)jkg&3o@(W2?XO_Y-c={AOeZl ze=NAr%W2Y$8AZXA^@)WY>Zf%XDU#wRZ{*I9WN@#d^3MWcgr>JGMP5_3n zF#Gk6>7tftz_XEKw=en<$|=(!ZG#NWe98x|D#)zs`1`knt5*Yh+lwC49b6-ol4p_> zdR${QZOKo5T84Tzpn~A#_<5Sj_HN_8oXLn4x$ZlsBM;gTK^{s*KLZkQc%S zw?QjM1n|9{I3h`d$rJ*5=M>4lKnkrt=s>}tfoN;a)>c=gK=p_G`@M94>HwYvm>SWU z0U|T^CqKQzeX9X0|3{(nVS*xy?z$jntiYS2uQ{Y49$rF#+}mWs-X()L*`U_-OAmsR zLbW+k$pyeSw~Y!E8#=zeQYdu+B41rSJu@(u$NvDa5#C_Hri%PKAm2M6APadcf#QAp z2pGA{U$H@n|E`EE;QkIP1-Y+W#Z@C6MMmbO@Qz3^EZ-4h*R{g@ZD`a)X|AhOHIZmG zzrIZsX|(ftL|(f`MDhOf!jh5z_54Y`#xgJysi@$*?|X=fqOirhWzhZB`0v_iHedV7 z+~Z(op+y-d#?Y4Mfs_NvLp`z#D@Meu50&}IsbvbYNq>;oDDy^1cX|3t06ThHB3d+E zo9?88?bCqGV2SzWft%b@mfcxI?CPn2X}cuuSEdE4YkcCP{2w@;q0GBRAFiogcV&wf zN>jjjU~B9;yYiy#cJ`Jf1uYIIZBA7$m??fRMgF0h3ZM1-Mmta9`%s{*ocPMPUZhk4 z#zAo*X`q}Sb!a_#GobHeD9Xn>nO46;#&d7%&|cCIoPsI>UXt?URaCb8z3;wW@%;U+ zs%;^AE@D|tRiu0;A5LOF1QN=gH0I^WQ?kMf+fUK=-m?W*8a{(&JHds;?pP!v_V1go zvwO=+ONGvCk0RhN`%w}{TUN@0D3nFpG9(&UQ%mwQN zf{;ya$iq+o7oNlAg(ti$G{qsz;GpYL@2J=4Z=f+g65RQDeAMLhC&uRb4r-$_X(8qO zL%^%8E{^CWxWfFjWt%ehfNun`Xqz$X+-vjUv;5+w0w;IS0h{G!@C?F)mzf;W#JJNN> zJX;B6!8>eVv&?t(h7%biZMPpmxQ`+Aw8x$rig3RT=ol2C{2dejQfQ)rUc?BbqDZ$o zWVr)+ex_as`2_h)!j38T@Rg$@D(B=RH}R1)q=N+OWSt|5!mY;BQWTTbCTO(7?nVS` z8SLLX@y3-?JNKOZhE^_w80^5o39J*$2|>RUB#vgUfass-9?}zp;Dz9-3!L2O0AOek zvKc`eWc4XSTEzcOYVCcpiKe$$rjNkc*kpUjrA=wziTIl5beW$zE+H0{*+8E*vI)>A*Wjk~{c7K|yz8=WzdMe{&hBn@( zAloA|)xo51%%_D0%T;zH=^_oSLT|R2RYn5QG3%P)O-x z)CT|wVWUTV%ajR{oy*|${G$Rjj68ZF_PqTShiMijsW%AYh`!Gj_g!Z8ZKp}mC6 zN_+7CzI*phN{bXMzpW7Fn4gaY5;g@sN>%P&V|aDWGoBQ136QOZ{FkU)Q@bS4RwZtl z+IW*)QgRLC1TKw7sjo%T{IcS^7gCfgs$Nz;XJ)+m9E$x)tU*&M1r`XYOKW=YH|ysT zU5)yD$k`(k%8~!YLFgC^3rHk2xYXe>h;SIN$$~Zrv{Cm#{0a?|{ppgCh{;6Q`$DXK zTK6eA7aGXG39n%y9l40t0_B6aSrQZRoRW6$y?T-~Q45ZZom-@=@yc(&_5e{H^Ea;e z`tX@soxwdB=CR7Ip85@BrWj>o+_mdKJZ2GqA{X*x|C8(eo;jxl7aIinzXd)E=I8|g zG@(G+1yYDGD5Z(7=MURn$H&K^%KecPy5%+>!Vdb3@-JUP!CSw$yd2u%3_S{~#M4*~ z>M$b6fL9Sbu#}I%*-(PEA5pDMW!tU;4U^hLe{8CPhP^&;vPE?~@b>1F&V);V1Zv{JO7*r^ufk09+r((Ap%PaYemIlp z2csbUkHw!79uOI0=jDoBdlnR(5|2l1hs_f>tW8&XmAET;Ksx#(wr>{K2> zWtR`C631#Y?}q;6yPe5rodL73*h5Soq|&N0{SJ!mI16`;bn``+s@@F^g>MYwiB zmM>;(bGS5@Y2;jeJg8f{FaIP@8AX58;i>X{=yvAbs5o@#`moMYeS?v^WBnlXU({09 zvBgx3G1o_#FbACIcrv?Qb?iiJ3h4&h)YpY^L9VvnhGi7mB8Gos%cI*%emZ*US=cQl z=lh{*l_)9F6l+=T;c+ElOo=7VtIRD<8&Brq1m=>doxQwG z*JjPgW8lOAyu9bz{Nd@)!~`zG-KTKDfC%)5ro^Akb#^ zzzw5@&Lub*0v6^#SxRz)VznL+Pgu?n&<{FR1lD6N|Hc`;3Mmy0UceZgtf2TVLO75PR=Ab4GH0Q3u%vbPVA^Unan)x8F#d zZOiOj189?JFgEf^k40tD8_y3}@jF2lmC6n8OszlGP$N>k3DNgTf;|bXl_YTlr2ZZG%w{+Ss1wLL2>mAAvv~hWO5~qDrnr&D@CnxJb|WU{C@JN_#l48K6p%JO zZ;Bgxom_KvZ}%V3gxZZz$fOr{D1%=QoYQ~^LP#&7U>AP97PtK^CjS*MCoN%$XeUxd zlFyz#g{+^sz2i17Z5S2@FLb{wl zy95yswXasLBgXc@L7&IxYX&I991NK$EiKX@a0jP1A|8L)bpClw98zNtgd1#p$WocH z4nG5W182d1)@Zo!7y_2cC1Ryj#{k%bfbY(fmyMiU{ciuY#^C<;m!$BH6nKMJTF?4s z&hQaSnoQ7jGq^3`fg$WLA0VuO_c3pz!6{w!^b$~BUD4|lM$Su4qZM>)>rZyi?xv_| z##tpx@5L2T5Od5b0yz*hZ=`?IW(xz@3z4oJ2FZ*wkPVhgU$Sr?%V}iM|bR_Uu(KP&s-mJ-K}SB-2-qO)VrJk#>?B* zJLwSk?r&+4`l7?1O?WTL|Lqo)m_WLmJTB z+^qXmjE9fH$jp)a$%XfYO57KPpZrlN(xIGTxVaL#6%=SFQMpK_N?N>LEeq<3_MKlN zxK4Y8PLi(GJci#ZGY0E1WL};Z}LiV&-zVHvq1l7z zH$4l9%vBJcwmiAdA*rAShYrSAy5?&hr%3+pLE{DN;Ci;fOZq?$;$3A$bRJcKQI5xM zU|QADiOtX%693~qzdKYL7kKG)XTvQ{?3Q^?Cq|#p$CGPDSqJyVnU89vySAS8_w7@= z@~}<+U77RzrRuKu$m`e=+|tc^OOI$DfR_j|d>J`zVEUthM+qVxioP>MPBw<0_z<>s z_WhG_;4(^e>%YH}^s&~yjOce$WhDtB*H0YIFyx5sr1!pwZbHUN_N@{8;P8A5 zxqvs_e`ZTV#<1_{9Rz8D=iw}>l`<7Y*v z2P=JV5C43KuyReDxz#_jxtl%rH(`y-;{KKx_G)LjLBtSqG z@-137SM2+pWgOAo5oyBr1H`z;`=g@KyPup&WcJ$c!gCFz;an#e2O>8Bu-}%*UqJGE z0Rq*F4Ko%Fkwpg&?A4Azk&&RPPs8TlDC8V!LzTEI<|5 zY)ZI=1ge8vg2_I}0s#NY9@?_E92(?MDGGM@=oTfF9hSL;G`8z%Ov*cLa{8)I%HM}h z$e@+Ox(OLu0!RqlTq}X3tQcJoxYWly0D?g>xFCKxtFltZa0JS>Ae7r&=ObL25L@|6 z%-a8@wKYPTpUVxf7<^#fPyeuk_xK2X->t#raXoKUT(Sa&yyKb%8*AWln%&Kq7=;zh za{7mE38#eJDw-|^!d z+MZzoJ4xbNip*Zr08z1JDoZSy{CXegL11)-h!|w)0@+0m|88x^*wbqtHDcUi%j%M@ ziS~>(kG(G2u?{fkYFrArZkex0(6keX5ES` z>q1YDax~p2JOp8MyJmsVJ@Ci*Bt8^GOs0Ieb(O{gH`xC+n;P@lu3 zTj4Aqya8GVc1>$r696nB#<9(7;lS-S1Qx*As#U%}Qm6y?ZyNwf$QgyWqu~32vyj$e z!v#SDHT-QzsSRS8MwFr|ybS@B&jxTqnfn~FY9V*X3_=qi0u3VZ%<+XNuOWq1h_M~n z0l?SKiUBH!Mi$N<&a~+10W($7nVW&S0Jq03?=|2)JvLhm5rF-HPK7O`9UkA}+ zu_>{^=++IpUytJgH(Qhqw^At{te+)l0m+A?4UD`^z{Mj?_j_F;Q}%;7A(*i)f%Nd# z7hOLW;RqniI~pE$gl1Xgi7kGi_lzl5+Vc(N>(O(<`Tnt>K$EpF>JFavy?1$ z!>rA;Ro}dGsdbpw{QS|_`8ELy8u3+%D28wNU=3lq>SrWnb4MmAwCz{S6025Rp2M1e zQl)C1Qc9Bgz4MXoPIb{AURL?fMPn}))lTxPZSoJ+MJw!-LT=iYv&0ayIuKF#&Z?tW z$ca(qQCnE6#vfL8(OAcKB{!0Gf;+B=4R~%kZi+O$+T42I2WI)$d+%p7>qlg{ab0 zc&J)!zv3a~YH7u{*jybfbh>NtA*jpBIM}>*$q@NAY4cPxj4Ko_R<&1E>FrFpy~xd5?{a8OWl-k-DN2?`O2p0 zv_|6CGcrm_K)t)ZXs@+Y1Mm#=JkQw+3J7p8k<^#f5YshuRrgyPyH3;fG4|_cFIN@g zJa3E3)=2F`4MHBg6oU`225_$wtljx)(#`Zu(%{bD#RAAF*`hhm+S-F`^P&ma0gfig zF@MxHSg#ahrBHT`J@hrt>mbyzSf6p}5ULu;&*oCsHWzwgDGxQ)uc6vtetEprw~FE+%D+yvY}9Oz*&dgs%P=h!AVI6bY4rMF~BzO|hB3CFSwP|BbmSM>5uxbCWBmSL0wxK}qe4yAynu_Ph2yt#{1C-?h@)N$>xmwc;l{;dZaKp-I`lUdKVe zDU_C<7!{?^r4y}0Zi(-+OP>^@i={Z3Rdl*Eel0$_pZTU zS*D^6l9$wdiMm{Y;82MkQ?si4Ue+h42Fvo>0qd~#io(Gl5TmdVYf)~xHP9g+v}hVR zmOTW*T&I_SAq))|79IFkZv`M^+&v`;Dq}buqt6GRoFl630_Il5o7&RTcf|YUY^~%Y{;$jZRA~13R zE@BtD_UzbQtnm87P+?9X`Ny>V)xT)__ge*QpYn`+X3%_ zCl88+2=XvMzTNP z;n=dUlaZ5i6(H>Tm+%Ar8;qd6Hy!Cq1l|lZgw21PaA{euNO)Z8XA9`3&_BGfJ~Cj# z$>t>aBB(nq$jQ{;BaelD!8jL6wgGh^GB$pkek`L)!4jxO2Ex_GY#IUq0?iU0d7I}l z6yxs%U1A^o;(Gr6L+Z4m8Qh1Gy!8KiFkKSst&E?O-sIN$ij};ItN)@Q@`NdzDY=he zLi_7tL)f9v0g(ywSAD^4-x3qq__uXh>gTd6hl|)3Yzbr$tJ_UK#cn;Q%~ZwDaPLwM zEBz7R5kpG4Td|lWeI~l)a<|PHW<*u7@r77+ir)(p)4cOhPsu~}sYahxOs5p)5x>Hm z$;*;L5suw@l74{NjF<}iX(i*vlgrn|9K!dxynA8tHG1C9VC=F*<@=0JaUN|beGs$R z0;2dP7tQbrOeR1PJ6PT4!BCPf|3jr`=?;an4r?Qv_0aJJ>A3pBN+Y)-+#rG8(k`X% zDba`DT(YWf8Bxv0t}vis_?-aPrlqy*Q?srV;Mh^C1=_^?E}`PmQgQ(Y$Oq;79F-{y z41bEy%a*5=W?(sl*a9S?4Zs3OG{4&LD6%(^ccCqW1hK~gM1%esG2Xq;oc7eJ%yW{P3g`wp{<=l*)Hi3;hr{}_Ok^=K5d!XYu z!9k<;WCHYdvE5bOpIFi`EwrBVJ6Xu2_seN26X(7vyd5MKGWZgtP>>FWRC>YMCTHQh zyM3IjEpyQAF!IN#$SwBdR^s+CNm#q=1Xg~v`|!bj)soT&jj5%ld-ATw?8gn`scQG& zR+)@>mKu;x)^%PVU(Slx_j33djFw>iqNJqsX*T@^Stw+uZ=og!;%Nn_@Zl9+JsN@= z4}_N3vmw(V)V+v9+T)lX9+P~aTtd-8^C`eHzM_YRhhaM_T87ElZ8kD>D=^G~8XaN` zzCj2C^WdxMM%O>NiEUrC*G6D4hmjYF=YpZ3JVA-TUR*;i0zL<%6w~Yn(#Zo*1|oqg zcmvwoA*(j9@F^C?1^&BVVRFm3mcdZv#dJL)qJ8@o6H2yeB)w>mbcFvXSfu=fK?anm za_}3#vLSp$_9njv&Ek1_jjtWcb>$%m9)-6eHXlE$7ozi$>CW#tfM_p^BdY!~wmgkH z{{2e1&O>X6nZ2U_Pa=r6dg*;~deB`G;D;5eSVC1TF_%sp+q7?+xdf4zktX93y~B*A z=mqm!Psy_=MOMv9{VSIr?V{TY&m0Zc*FVJ=$_&j5B(Mp-KX8fj`In=~!E()N;%k@E z{7r6t)6SKv&VD#%Sb}zcpaB-`LymT#ngz}=ta``3?{cEIedqi$5`=EKtENiu0!el? z&7FPfTig&@_5FlaAsdo-f<_O&q#5U8lHmi#3i_cN1^(QupTsyL8V3dlF5O*z3ZU!$yj`lw%aTLQ4CoD_&XZEd}jc=vO3@ z=jE)@2U6siea*Bh{!BF7qBY5yOWg~vY_df{^1Ntrpr zgtG#UG}s@zEclUI5`b4w=-`3L=k#z3HZP4uf&RX}5PQl*4l#_P^jOCW@Vf^Zxi9@e+qD``Ngi zAf!XWejMtmiunc_3Z?5}npMtOsVh;MhK3xgQ?-K~it@hTQ5Q|qPi=RhdRvs1t9|St z0W=B{fKkm~SbyURbcyLD#?Lx3-=f!jI zXaxTgS3asAz+e*ZrYVP@(mG>+C9wnJ;+}(NFDFqm!dWz}W3Dx5rx}YrSVS%Q`XK`s%-u+T_b$bS7!o{=(pU4hhEkOQmTV&43Kde zEOP`{E-b$wMLpV0Y`TeizAf&|t@}{DHTN~X-KyLTROaoupUO&)5yT#jT+$)SlQe)R zY^6W)vpS=XT%YV6vwYInc)BMg7R=vAmGHKblY1!3(t_(waIU%EaMW(ML6|;-O_kq# zMeF&Qp;tTx2$~&%PbS zko>0HM1SLkmT65rM*YR8SS`B4yvzq&QY=*Wr~ZB`rJcOpKqyyuNFH)xVztr>CTxQ$qkgzyYKrq4?v_GKJ|3cz&=*7YwXl9HhS8w6PSIH5hXeg zpOo8KMFrVGsupY=a$WC7JAp!%fG6nu`Qc0_P^7R6LhBwM{*%X2~2>wus%#zNo1wFmr@5K?>&c%8;n?A($P!u>e9rB5uZyKijj-S3Hh;A9o-H6u=S1 z#mD0ehE6ZRAVPWL#(hv{ARA%&Kz?vnO2vpH|V1?#-sn!0+hM+rK{YP z>$)EEL)1lpKk?Dx=M<*j_FI*M32{%x1W7hcj`4d&4TwVIqwS2_zj&E^DkdZlL6wk| zp>{LB_}z{5vl%CFciyR9&s^ zPRL4#Xwm6gS7ct!Dof>j?urXqnxu-pCB&@Xh_7;aFpzQ*JOQ=?3<|C-gJaqw>5O#` z^qoWf-s--1V%c^RScm4`e1)V}@Kc%zP~C=vF-_sHcBX<17e>nTff~+0K*x}z(7F1Z zc}kC=D9smdz$ymvDI^j|K9}DK1bD*%wf8*so zwWzBG^{IYGamh$w-y$H$5m3#`#4zBn`M2l>VLg5u2b037OUmjrP>~2f1^@%}yqRi6 zXM58-Z|)pYLKg1t7Zk@EZKiWhqM&bp5XY-aG%J&dav#+k+d}Iv)6)NeW)Ump*kc3eOcTx8AKpZu6G0nXg-oVSpFu>g$`s zM*jB?ESk|l#Y0v|bP7@U{1#gnq|wItIsFnKpA=4)4fHHHcj`I^4>9uV&Ch3<#*09{ z72*yDrf;sM>6{1NJp|jLk?=5-9qU4U1s(!s65uglq6b5jFT}8zL;v8+$!LxJ^7k95 zqOWlab(QOd;_VW%Cq@zl8f_S!-nyFh&%t$Tv7?sCrjN)(B*?3nlyqD_x>@hRWuKj` zjLs{Pw=q{(jL3t&V)7$45j@ zdga@xOm+N^Q8C+0*Q(HlUtdsHU*-=KTsdkuVpuW1pV@M|LbFb%+K+iez0Ro^-l|x= zjXJ0BMsQjU1rtgbb9O-{_f1@j3Vjp`2F7Md08$8zaZDc`2wIuDVwYYGxZPit(j(L( zs6i3eY^;sGHQdA2=@%#B`J&p0Y>V@d_JBxoapmw7E*H5qbWb+Ppy}U`H7P%wLA?la&)Vt z>kwg~vYhxsAZi(&gs^;ZgrZ52V$HGIN|tKgaF;On`_Ild+juo`+>U(iKG%rMMqZ#s zQ+8u!7J&epfI5<;0U1ynWomK(;0xVGYMv0^=caR0802;$)^pT0q&RV%j6AJ`ZfN;> zyz0O>484Cjt}=2iphZIrZw%Be`C_s?nTH_uJ9m;qbOKrl)F@zmQ5**$lN|$ zp-tN5cq#EV1Tg?rptj*|JZGy%?#5f>cm$*1e;JNGc1nMMqVYH=e%!vcR&*3D_D?s* z*4|$8w){gf{gWm}i>o3u*Q4cka-_e!A26x*+*Rt7-4Mxn^8aW$3!p6bZi^!!DV<7# zln98lbc=MCl&F-n2ueyfNQrbek|IiXh?Gc3cc`>9-2I$;@64Gq^PTZieBUSbf9eu=a=~&+M6pZ{3T0%mWkV=7QhR~aTrHUtL&L3I7sFiQ+x_gdZKChkxC|Fd9-ba9J zKwa%EnETcSGrIQ&C89wfLjvir#zMWwy$7*Nc{m9oD5R#}8yl@7nxA@1VPf%yx1j|X z2i&*H>HutECXn*q2wZiPYxKj8{_^A0oBsXqf0*^I4hwgeV%nyD9omvGZ|A_AETuev*f8=>%~=A0bSx^?@Gx zk75o4&*U1)dyYFqrG2_H#t|5@_ChOh6hCYUGn7L~$rf1)+B1SSa5`iRNLkFC%zhbC zKe0wjoIMkiyVY|m|Doi`@VQ8aaXr4S-CWaS_n8B#Jkp*g?P3<2+GEmoGzk zHv?F>xw#!g_JNm=>~uj>xJSTd#|PPPea;|ghgO+hQ{xDrcVzY*p;)+}!<1vGs2V5MCx6SSC@nJu99PD$9d49QlB@U)7Q>6X^}2QPhgpz6x@56TO{HwEEu#_ZM{J5c+UeMY_lx0kI(t; zmJ{d9N{!E#SEZWShszi$5I!Ss?xXs_1y+d@YHBodO| zmdPT7Xf!wlA%>VY(Og7hRAy~(WyneH)D@D=d;SHo@gUXmNzXUcsqD1#E4DMbf zGd0sxcRx2}7WVaaS{6z>jzvG~ zS4G!DozSThJWB~qPc<=$$P`2$m7!g)y3Wcc*BOFutap$cq3c|ejC>x_jfn8xA7}82g6P)s&X+ExW`u-?~zc`q^U}8$-Iu z)Kmm@b?2LU%`jrap@DS=Opw6boiD4K)f5F=8WJIuIA0);tN#smONe*_XesF)t5om= zp+VdvPzk)41|IZ6RCoyw&&?4)NCQL#><&znS@)$IP-p{&mGhlo3DPC$_%uWon6U?s zYy#tfib!zIQh>UaXQk*VhS?oz#9aHfOA!EpY3+iYhk`XIz@gYSe8O`3$jO3mOtX6@{mG2_yfCr zu8w@d&-y|t`d5fwEaiq~LvP}F>S;f-wd0nuUX@^uED zN+e5if3m8nkcZco#P4m08Umj%630cDxA3m1oAbT}e{T>n;Uy2-211W>?aTp?qv1Pp zXxP0DMXDfw>HNYe1dGexoXe#UE{e@NwVc4NFyiYa;{saS?Oh4^={RRK9==j;L*r<{Nmbx#0}<0*aK`>$?NQ4w{~ zGsreH%F-!*BSF3~tMJLx+s6>#MS_J;*&C&%xqK+OpXj{olJ#Kk^%JwU`ln5%F^7o{Zt z%oNgY0unV~sP9mh11cyJ0y3kcqikGUUEJQgxSpF@8PX6@1wlgyrE|Cr-h3L#2{=^X zxmg&~Gwp=>ddI!xhhX6hZ&3R>!=>+Ds0Is%0H^OSF-;}*KC935eTi6WK%0!G=J?B` zux{yvWmkG%gz(q&^ttw^PS1Rf6%+O#$y%@qP|}ft4d{oo`y%P8dq#U^5onYql z+<0W#221py;9#=UX+8mPtRZH6Fe*VZ5K@I9?&PGTEenodMZ;!cOkPn=1VOiky?JA37jGx(4e59|-DC^8Nk7e6KH2_{}C6x&v~sbKH0k$xd+Q=(KcZz{R6 zCpxmhM~+LOQCTKUJ(4@Uqt6kf^ys$dBk_rsZcdLyxyk&Q=KOlMv?_iYEj;E9s%^rL z)xW;GfvL!?jJ!qLVpd=K9o;=7iZ0*rkU6`SK{q|TP{gt4q3F+GM2GG>VRY+k-`;X;oKmV+KGrFiJ_4K0EAddDY^p{Ip`q*f+#8C|_6{MOd_ z(VjVa`|NY`yAai0>W?5($ok0DVZqs-DqX|@vgJX(bgu5`guPXl{=7H&z2_dP`Ih|T z!P!>!Q+}8vCh>K&(n6I{fhQP5CK@@W%uHylg;Oonzu>H!&XR@AW2xM5 zyxG{;NR?mwzrY+4euC2j=Wl}1>sZ&OAWsf!8O4XlGw~ZIw1uEP9k!`0jv(E;|8Rj0 z7P~Edi})Pc|VnMxM{cQNvVWrv*fB2_QoOmmLy^LRu>jrz1tv4hHD|knaWej1}Ka zKMXeXWHAOHbPkq8_*GzdM0{9~5rWu>5H_e4V0nYz&UYp~ z@3dN<69fwx0E7YI8{UrKIAg`v)PXS;xWC`lAfkXlLw|@t)8iT6-hPAK*&75wQhc6` z2kGSn*X@SBXu7yb6vs#<-WgL(gnqXL`j6%190#`G_l%->5CknaY?SxGsQ?5&&g0mv z%}v>RBpemazbEb~D=WiG>4uDqjF8*!_l%74x2M&BF9XL*n3Wf`GEPZneXhJZy`?cZ z>XbsyANT2Y23Rt5$I$Je3TRfq77iVEI0xJ`OrV|Kr{ePgd#Pm6L+A}bEYS!)jBs%N z`x7vsBP>0DOduZtWIqD{pz-?w+%n)OL_G0Jl3rJZ2RApPVRXEt>xsHsCVbimJ_t}? z9nmcv-%<=@|0Ai8AtE0MR^#Os>Vf$D@YvXGLPuwOzsSbe(MmWVOO}jf=jO`BU=Gy+ zl+X&z4_;-yE>0Ou0Hl+IFAh z?H-TeJF)49zu7J0xhc4E`qTqYPELMr(|L16{2LZ3<|qHg{p}7L!OJ!8x3H>1XdN&e zrJ$H?a!)-N)AX)yyuID{;}!L~PIY$=Im?^KTT8Cd=W8H$VA|jj8ig8iW&i#IhJWZH z3iYwpSmixF#x2a6n(irRwszhjS*_Vv>66Rt9fc${AgkmqxgN8U`o-iYd`W}GsiBqU zX76c;;#hTSB3wPl?=mc>4DG$QrwUa>we79t>|}6?zTelrD9gS|u}UQPprYHn(^H6@ zjo>L-_$}4xUpn_WH(Z(s3!9JIma%Z@-gs0>6yp@j=d^+b_ToSL`?qKJkv9QQl0s~f z>m25ENe$qr0qzH67Y8MF7$WnoB4lAsckV$+7A0j1Xf(*`H|8a8evcHh>vy~FylFce zPE`x1PAfS#Z#ef|!>)y{WL+ZjzCi6FhCLK?5q3R1Ef-I#azYzWDj|c25XToG-iQP# z5O@mwtq}p#&5az|-2t}`sRB~i#KQ`UM^KP;;t7y43jb0>cOxzf*nH5(^&%K$z^4+Y zr1V<0`CP8~;E;|%Y0rl1B6#N+E!{8AJ^Vgs$aaDmLt!3{ki{ZFcO?7f;?8FO3oa=O zdE`2{H#_?aj8A6`T5}P%b)B8$e19;RJf&1fx9)k3Y6MEXkX$X&-MAhP)!8hug!@?I zRNBwd{>4BTqr+k{WEzf&a4i1Mn00=#4`;;e7F@x$&-V*|{wrAN5WVq`nHV-U^3W4@ z>_d#o2gyQ~F_%3tRv<9q-X zf&bEvlRXb1KMc9{2=IHs#mCXb0+uweh|A|_q+<5o208w%cvWVmBoB4(b#Pgvvbk{k zlh`ocO3fvx+Z3#KKuWgm*vP?cr|~J(CpxuIo8$HYuEtnwyC&cT!Obd5SM?Uep#=z5 z2T!Jo)d3`w<$cupjCI4&pI@MY1;aCFe#`Vq#QV6NZV{rD#DTHyM&NFkxFVntVaAs* z;!IRwXKNr>7mdVITt(d~&@_GC;I{&Z?sVi(Q%$H_apF1U~utf8fcrai{!w);|}r@Q7W z>F#;txv5CS!}#EQUJ}0D29>TaU~;i^!?5;A?b}+m!CK!^$FJF zNXQZL>YY73SV)orh8_}yXxdK52X+dhJO4~a3bzk`8XaFAHAe$9YC(A~9-0mx>2zw? zIlF=&5)9dk@Cpg`7DpjG2py|4*xY$Re@;mAYI;naSo-g=aY6#WhRv?Gw`Ocka=pj9} z>TXfuQKO8HxD@_9d=DaDD0z!iNk`j1KVFb$&1gQ#Ay?5Ml)wwX#4Y8rmNA-rPR{$v+el5~&z7pL0j8 zk%<8C&X5j-Z-ZnTaVEj4Ts)ECQfN;Iqi|h}?E_0egHw0RRt?ZV(EX)4KY(GdXK)a( z%#u*oOcuF4*GvF`6~+J?{AVyj18T<~bYmnjf!vD7gxzp;d6q)$3d0hzj{uMzubxX{Ff9YBTg3n=j53UB-HCcH6gYS92(1 zM=HRt^@gPsfipwKxdYX0jLfj1Wlc_JCE4<==%p;j1^JTcN+T6UVNn^S=ol$p>T8mt z4Fu^U{Knj~LHU!v44yPp5x2e=4f{k$aN_Ao&SHx}zLr!`mMcYymYppHw$4JFF@~o2 zJoHEU)D?Q;^AdW>6WiNbcYS4*l7tLac4Js$?Y_NobHgExh#;iZOkgD@h;xG6BI*WX z%{#iA)YR0nU|4{o#XVl$Z1slab@c;37FMUv&RLFI0Ew`OW4ZkWI?&*G7LvLFgIN|H zY{S1l1+QTnmPTAbVAK_ttgg2a_HMCrELpH8fxV(jXM6b2&YAk0mVwz{N%h!h@aQAW zXmGT*U;?6LTgJs?#sboS19723`p#X!!TaIU-v5#-V08&zJJ@tg|gg@ur~%_Aw31rO}W=pGvn~S11Jm3 zGhy1?f0Z>vU{&{_ErtP__`1ODwTtw`0G0z@_fTKsH@-!7#1No%gK*)>A!)={Pc%G;BNQSn5YjZhv326TsBMQO$@ld0-L4i<__v68VckQbqu z5pE5@!XSTlSo5_5chIcf=EVy+VD2^#_V+_RR%<$Ckl&kD`tAqTW(UB6fHy^UiZQRE z=bI>y6ROLMdMR4l+1=wysR%V zic(oPsqx(9zw%{lc)xz?QCy1;o}wz_>A_9+pgMVkD=8WjXuF1Dd6bSgnP6&xC%*+< zPeM=*xm?VjN@D@mSMTcYsYTuNk|!dtK-D6>uG#OCo3ihzH0jla`N)KYE?Wl;CfMNWr64nnBk3-D@LF&r7fil=$+(q&E%AXDY4R#Gekrnr- zups|nP}XxRy1)V_eea~UDQ^4!y#Q~dd_7#;RET>IJwbBz8fDJHkY4FpQPKa4#vdK6 zMcZX@uabRFyh;Mk&pBE(9m-{{LF*ARjc&NYaLCvlAJ6Sn9VBfaBBE(0`#^3b1@_QF zEixgw5z?qi-fA2?amp-N;C0lJlSj`}6vOFcIGMAFKvU-rv5bwy<3DXS#-b6{vcVTL z4W9m0@Fq5Up|c%U(AmuQ%4{R${SjCfoL~@vo)&sGU{?SP%qLb>SP(aphDYpvz!1|{ zF(Z0wu<9a0B`62r#sv)==@muX+(>6c(_xtda`Ay;Q&?Eof;f1A-Q@{BrEb6+0cucP zOUvI?q)f=MXN|EDN=b-IB`vL1M;w-YLA?ndnLbDsr6pa+5^r!`3A0c>eu?tdFtWUe z>eO>z;ASL((gdjoP%pB_ra8mNE(6Yx(DoH3txIYH?@G#>H<6~|&#EH+U0Lu}1D)gT z0&A=y*4i9YL6hP`1>CdNvye z-QHQZGJ%<7<1R=Xu&ik79mumymxYNR!Gw-V#r{&m&*IFjE>sKckt*X}zTk}OEfm?P zw}eR?08Fqz?S@;4qa_=5Lhzny1&tXpzwj4p1I*;aINQt~tjWO2n#(pJ>l#y^{xv~N z&Zpmuy6kBc28i{7hqo{lT++7tU%JOb??v=EZB(h+g1jqD-mExy%Q?w7vp(hN#tMFC zzrlJKR~S0Z7V%O^FEr1B?Mp#$Q5CO|f$Ly+;i#pfiy8VqZS{s%;2a0^0x;p&!)A&m z=v{t+g<5PanCx_GL z>FVZhewz&Kn{|!NuX)q-xt?3kMOSVLc=TmlP}|gOefC@;pZ?O3ANoy89W)LeOQz6S z4T05-D;S-F;X3B%@>S#dK)CmQueUwYU0N(OFAxs{-utkDMpW=3Z5&`Qf>j-S9H5B9 z0yP*=EgT7LknmL3_G|*-Ay7(E8YiU9N;_>B_S7($KyfKB5++?+j^l{!=SQl=H=c_Z z_25^2crtM1Jssj_9IHKRwPA36vbS*egHh@VX3uv9cqoH=9vZL_TlDsz=I#q<;Don= zMf*EJl&>>UFv<8W=WDVfuQo7I({IBM24ZP@w9omIhV#9C_lv`ECy*lnYcUVD3U~;t zLt#bd3ozvR>X~|xK{T8ik485>%fzJm)vCPbr&GSR@r84!7(g)ke7v-rolh@$FlW}tTWcCn%rrC|~ zS>YUx$Ud-XjV)&k zCRBhbl6kB&45%^k4w2#%(V->=`V_#P8|>1kPxBiSe`<26hpf7R!xLqT?REjE7bwy; zi@WX}2FZxz^EGKQHO~&v7)V7bVz0A+Mh>Bm9Rxm5>x@|4!7KMRNH>ah_oQbn?`BHy z)XQQ#m2F$SUdH+P!gJ;HPrGcqQ4bRCPMB&%V2)}Hoi)N1uyE$FKc;&{(GUR&=gQrz z;u@SsE|0QpSgE!S9F}ZydQ5x=0#`bN*E;22ckDOL+EwO^jA#P7nhqxKlz-y1axsxF zn+D-qv_pMjrP_;9@$GvX4f(8TSevBhVsVzmd9|_di%zs#<8EY`);FOBOR6*tc_#ST>OoU^kWRr!xD;2O3!XTEHR|L_Y z=SR^;a1`AG4i12!VJQVXL+O$+WDmwK^;?+a2~Fb;gs zW^_|W?Kq*gVcV}Ffx&cgUUrGNwfw!gzSr4>g;;Rg!8d7P zGPKaD&uJu@3nCy~^I$%D8^}P~x7z3Y+?V>bcSZ7uBnV<)f$eD3v+zc8nHiTG8H)~A z{~UIcd`^;(8w27y2=-W0lM(M})Af4V>PfqaCa(uDOe0Ms5OsqA4dI)>?~fpcKm&!n z0a+|t7z&|H_YEB-J*KCs_zNJ(gP|&PYrL8tPbgd)-W_f0nLhR9F)zg$NxZm;LnRAF z;StOcX4PqNFZPp6eFJqzmUu>TGEoHik1K7;V!#1PopcS0ctjP4+D*84XxnrukeO(A z*?rHKMI61bBY}I%%E}5U9SkBlJj~GyU;hf99+*o3wgbM`15-yHRPJ&JagtR~{SxmW&Nua;LGo>w< z&KrrCI|=c{_0CskTyP?ZLrp1bFVwzsC*h>j?d>WrN$K(WCn{Aiero7RmRV(b^1Pe6 zT_-j0eq8L#gR&o|a^93sfJ}q-x-KesK$vPj4JVQDlVQpGTd`Yf+`YNn^UAE;fp$RU z0nfW1t%jz-2^}{fL__eHj~>rbNiIs35l(a6fTsb+!{&qH$%ra{c~v~jx9k{l&o;Bq z>=X8K3@Ljqc|JOpG<&FiZ|w+9oS>fV{*XkG#r5YGqUcLN!nL`qz4XRB=w&&8n)1&V74+0rH( zG>F9sv9M-sU#CMmDu8YN!ci1pH!;#*1QWIrW2FG~%*NNbt&ri;9(47nSumx#p)aF@ z<-#d2dVDm7wK2&v27iLhF6UF%%A9C9EH>3LL+S%o-;ZzU@Z26YHZ(9Gk}Cj79TM7D zb-(VeW`Oq!Xujq11AZDl!~gVw-T32 z61tS2qWx?64Lb%hzA9};1iwnSR9jI&KN~yepOl-lmLl2(p8QI`eaAZw!8!mEU@(%F z1QNmh+pbrD;0d*W6IW_$Qq#e0Cy9^axM`|&?6-qWle!;XUKw9M0+ka;Uzede=efeD zC~%Y`Ut>batgO_iAkes%WxTJda(-zS3xX0YyrN)V_Qc#=>fYRE5Lz^>Hh@WiQsuJX z^EN7OO&dTG90}6a)*CE+U1b4b#$x3?0{$N^v%PR892M(lP*LFcg>Xvj?XOp8{0Q_` zd$9$(5xHT@2b%~~76vdJ6daKu_>+K56~3s5;<&qrXnE8R-0@D|~*xaz>}Hnh^#!GU6<3PpA~zr5W3QOdh!(3<(*guC({62y$fO$#jiBlUV# z_uQHYL;8DruPB^oV(vG8SBoxY*qHvzjFrJOZPO#1$vMN7GiB2@`rwDU0}iXYNzP3U z)!920QXW=AYgvr75iK2T@Tbe-BocCmhP8iaxt?e4r9zWkLL^I(F#d3HmamwPTv(m}=7peVB%Oug_unr^? z9f##D5%pJyr$KK_7Mm=BOoe91*hdraMsdE@`{v-pGt3d6Zd{+UKkpHnQ0>6>pe{XJ z@p7=VL_Nuo7CpGso>=k8-f_|n*Y*7IMyzPZd*y2ISI3n=N_Cbo)h=V2q{qvH3x(Rq zk1m&w)7#{O3)!Mm1#X=>fYB79iVGE*DL|EdOYuJDBfPc2A^F72Op?B#!x|vc5cx$a zoPd`pdUd{!^t^zpXJP{L`t|?1ZjkC%Ha1^yhD3WGFnON+n(G2`4T`1U7;K*Bq5IEm_~64*^b&ICOM%fmx@nqZ2qe zY2a6-r=!C_jUO(aUAY)5AUqQ`^c76(aQesfQhF}F{s4|Q?rUkU;HHU!r80(6T|+~J zqY&q84n$O^gPqG=26mx-3TmIhd?I(^QJylUd2=Ho9EM$U^DMJIk0~Oy4_nUo0(m?| zWF)Vr*Idxwbs4_+^L}9RfPTap+6q|P`?sZkbP1%XLR8cYia$484S6a=2cGY(P3eqq zS9cC!g4F|CTWSZE;F_8LX8Lxr;txyYg!Ll62uulSpVL-aa*`GSHKgr3- zi0}nFh}+*|V^l{sT;TwRbkKv%AeKo1DOm==wq?aRR9ZH-`EM(Is85@k>vEqMW$ko`HWfuNtAZO@x=ziq#ipn5XGRpjnL>4!!+5s1AO z>uqY|K0vu8hq^rQUd`r|%S)l0xtr`$YPWJ58F7K3w*T=-wbi{{YMOMkjvJ3pX(_&Z zS9|Ny*S=HlLlWp2vKO--j;V)Qar4Fd5i#GQmI!y|%21za@J)G&haSr`eLE2m+_c>q z&fxT4SiJhme)RaRvI1+B7;UtW*!MXp`9_cC;cNbI0o^0t+df&=bSV!Zj%>T{Dv9i@ zN4#-@M=V~|8zb$lLn|69!ot)kwsD}QrnJS@FaX4_*!lgaWx>BoHOVNb5o`3X({oc= zsr}~^321eaSE&yz?j54J)cmy)FTtKedAh*x)TCQd1#{@A7Yk4%L@Nz&ED42nQBb;` z02BkRQB?MrF}h;}3S#NL2eaf6jicSU7OSQj9~^6i4!fkU#eGgL z&e#vggF8Qu*5lZ-ei(R$D7F6;FFc&!_O$zis!$~1K`PzEMYp$n_DK{!OeT$adVK*m zRX{)aYh1JM%_=2=0u08S+4EObXf5p+MroTX>DYoh*vU&lTrX;z|3<48_|IjO<;u%m zRKBJVvB7b=llu0~O1D2YH@vsLjk%Nkq3>%iiXj;I_e@z$1&x4}pjn(QZAR9^y+V}E zq5N0n++2Z`R=F|f6d}9vH?h~7YO~y6W?BBGDM37ESAO|zWe5}jux2hHz_|rJO@T^% zyaKfhd5F7$u@(cgGkD$sFAm-x@FkCVNMCS2cw=luWKgE-_g=$@E|7Dy+C6>y>iUAq zwH_7jK9@YYS2CA{C$(z*^J^|IOa6_#q@8^e?w9vmC zK+-Yzbm$x}P#PpPm}}agQ4PW&@K5Hj6%V+FB~IcbT7lVk$8+h{T#K6b9toH&qyiO{ z(jIifEd+-Nco@R;Aq54s2;LD6M?foTWvKyGe$aFEK9T`-TzEV56z(5H$Wkl?2Py=| z;ABY2l+9ZE>kpt*oBUv74400ES;vMeJZagfEiAfX1qp3j=n3H!D2o^^?N2Xm1($yP z@^i0a+RZ?O|@Chvgm&{`lwO@#4}hvhX$#(7Y5n%C-<*&fT$)uG%?# z14nc~h?$c-y&Kt$yd#nQ7;N5v;v3dhc*-1bYN&d6%qEQ`EIbhHtevji6BK(C-;Kc? zvhWOsUvRA;C_AWphxY`atq}i-8Bd`Q?$WNiYhaaDF)-tCVaaxK0eJTb5_l{b9FT};2o2K<*Gbd%0Lio-bxso;?rA?d{DL5PZ30Y2Q)feme}fMr;t*ol@DX*sgi8W02DrrL2b;Ui2Q6D#@k&1BBN zgZ6AmW^KQ?FjNcct!k3_A}0&uB>S* zDucL4#afx*A6E5D$7?pJF`}ZakD5mVR)ZOO4N&OuFOmnIxf`XoZ@iN`C`&TG_$~*x z^}S{u0={w%d>c)huraH4|3wC?XM%e;*RY<<*wmO``bUnmz>S@MF3NeAm9X*PnJRa9 zK_)!;z6}gue~f#;$vd?I9Z5b{-V3GhUjy%{9xdVH9??F{dkXc_RCdrL1xOC?OZqjz zjuiTd=K(3oh$kQJhp!F8BKKfv&^N8G@W>qk)|D0CmtLtjrn?8psn7PCAAS}b0NkTX zldyQ-=as#$f5R1O?NZ-D?++J+CM`OtkP00nL$f+3oNCF#E zt|B+!Foz#04kI9(_*%dp1ozz#)W41>BL)F@9T_)yQo-2?-bJu%(8?uy>FR0*ZhDAU zA5V=pUH>>r`w)qFt;(~r19zUm4h|_ zHhch|WJicP_#0;lCy72xSw3l#lkZPTN+KH{%Wk$5x=oBN7fV?!Y!t9LRci~nIGLAn zFo6X7kY7QSSmbl{r)nb0SA3DqeTp&)U~uC6Bs@a-RZLPE~C-WdasIH-uD3CX2E76dF{$jFJ%b~`L?u_sag zpawTm@GyIt{OUyFA5`JIBn4c+%|Xl+fy*Hh-?E%7-%UI`Jj9C$PA=$qlC{C5S`v*6 zYLe-C4Y@jtP|ET=CH2ieGLZStXN;UmG?aR-Si}|(Uoc<|4h4yVMM=4%gGCRLHzpnT zJ^GIi(=aOv-r~p@LKGdA4e&GJ1V8l>OW}}FC7Cn=Dbr`XMBzK#P z#CXLZph4gb9m=D>ITHrDA-C%OV)x1L7t_?XDb`$zt-C{~l-cyM-WZHN`4+>mjtZgi z;i3Z6W8h~4TNlC$=Q3$1T>l93ywt}r;9l>2Uk{K7tb^4yQnlpN6WA56iRr$HO(g+l zW4!CJj7+$-36yllsq~~7gt{lPC!^&2x38Q6g1;P3WyXkQG}{d4v&ORClTOd?d2M+o zCk0Pesr7Zdlj>>P+I}lc_1m+JLpHV0=d1wP`&@xo^$eHXiSPJJD3kmX00ngvihx*N z+a-^kGN#0n%1BafUSsPgsW79!fC7BHYnG#YY>RT+pW&82|J8i)E8l53ssnU2Xaah+YjI}5Q2fmrlDg_=LC(?U4XTx5JtLze52n4n-VY;O@` zJrpbHcqYYYo!I$*5VfI!I#Whq8<4hV*SC6%)e{>2b^EFT2R!f=4d)vJuwL#OC;cxq zSnQC?jV-@An`7y<+=ED^&FSXDQ>hz0nYE8HfOlsBiyf9y`A#hnBj}Xc&SIT-A*udXmUW!Ke z-(3W8yBJ<0j1>ly_^*9D34*ur?CuE^QT_}YM_4h=Kw@x&=~>>vgcEdrxp6{HJx=q)ML?2lWPR@BC8! zC&6%;w0h|l8^wB2suf#i>Vce~7~<9XFkU4tnbU*E!q_GQY-`+oV$%Fi(nd!M8A{^0 zWT3=m^uEPj>3AL?y9sH0kTx}2df2t8m+Oa}`l&`!g;TvAJxP0hR5W1bRZd9Q`6B|5 zw&lW_-(!90R8+kkTaR#q3f{+5N^dL0#W6ja&Wi0$HYEsdM_l3bgoHs?kf4W_8u|v0 z;>3q?7=?znYJ0Z_t27$U{(enay%~t^aVz9V7`~#8DAC6rZ@0k}0+u(6xJ9K8qd$g^ zy@^wjB7VF$Y>a+#P%Ny=T>o=rDZ5W?s=OeuulLAZ+vp^9@lR$A$p@yYC(B1?NHz*C zFrfa0HuM|w*@<@C)%$m!5)aS~WP^*svoJ;tS@FTlm4Y7=%L_jy0#+GZ4YGw?jm<>z zRL7YeEc*Z~Zjm0RAqG);FsgVSF9gFOIJ@`{4E>$S(OLzn3jiLI0kb+nK7TnaNsp2- zhzXucu!e!deSr@e-r(2(9?r!;3KK~m9|>5+LULc$9OBsuB0?`mB zswft7nfTPZ{Js>pB81ms?K;rZ#FM~MA*Z8N9=`m8$a@Zs@NjAb;KmL3B_PKRo+$H6 z{(eO>bIL3mS&|w+x2!|r(R|KkA#jHv--weOb~u*2RKrKn{di1z7GoQ(2+9AwZK?;R zuVnQ{<9bwh%YiW#YiYugcL5SrPzMZiCAq5U^XIIKyPp-CGc8P9)lW5iZ!2^OuP~IU z^o6scyj2+Ti{w|9q~3sIjNQ~9c*X#1RRdazGX_~BUP}Lbvww#OCpbWb>~2)H_nSsV zsnC02R;nI_ZjB-ak@IPswlk8-{*NDgVxm-O^I4%;&-PQHBIip_tqnTmxETo)-Au@x zs>`|XM9e*kqKCD+TycyYTF<9)&dQ1Qc(N$+Jr$#TmgS-w=lA&+Ox}NBrN0$${>p|n zZOUs*Q~Sr>z*vlobjObv&C~Qbt9Fo4D}r>^FGv(I=r{ty@JfGe?a~XexcB(k87h5t zM8efNH*o<`@jFUA`v1KEZB`V#IWkktTzmPOq8V+Q7W%CfZD(@c3f^MiSLJzHPD)ZO z+;97+M%j|oaV>;JuRJnCUlWeN#G&YbUx4`o{Gm?!t11wsrUc5p9`(dBjzU?L4d*9~ ze<=|u#v3f2QtBx}sFLe5ki?eku6t*UySRiEEiU@K@yda5s3yw#MIqU`#(iTtJ<9;v z{zr20vxc3wm>V` zE}@Z+3yfKVtsdf#q!h5Id_RAb?;n%P6k_xlJR%S^Iv)4A(4z*6IoxgtmlF&rSdGB$ zx)Mg>PY6yLE{itd*~%xF5bt#a))X=^1gw@67t0po4WpSfzSi->au!p@$W%0id6N44 zYVytK{HO2xcE_laj%XAp9oHy)>DiQwW&4QbG;jyB6Tkfk&lb{6%Uvq^#e6^Q+3L$@ zA{V0@AD^Ap-A}W=dO0F6$ERXg;C=Qp^pEyz@mQ>-6Va=%+|S(fD8wkCfvA$+5}9WU zUbNJ{@tl)NDQ|*gh%whvpZk=rnUtS(U=uZby48b&j_Uqz@;SoJP?_(l)vCeQcvqmD z!k9GEb+4{;r~TL@{Q=lH-@av^;Eof;UTGa=>CjQlOf4;4=0dTgBgiO-RK!)5w$I}G z_|z7s?$jzF^7sUM2r?M-0Mt&ZBmKtV?v0xxQO&>-!2M7kXR)r@0^>A*VdOW`*gIc6WUtTvta zWIM(Uwc5@=_ABOp_5aN8R)tydu#{6!;>wY$m9Aud8M-kThROe@pfW8b_-(2vXVgEY zS2G1RXpK48`=`}alP9gY-8BkGfVx(rxZz_vhLHSHH9_;sgD@EF6~fLQGIGT z;>#i;F!GxK4=?1%#;?^5m-8cmHB&UL7{|LDPolQ&iKK%%0!PO@0wDAH$?bK zpSc%DQJJd@IECKlD}Qt)z$QQ$IG`5!J>;iwJ=1r}xu?2s3+VNJpUtIPVmW zZvp4`8d&RbaF%a{L6Z^mF5$63`~g-@ut=0-BW;88C(@VzcOI;nO?mD^9^G@Vm-X0R z;u!7xxLcx2u=zv7A-lkxM*RRC@(JG-PP40egg%pv>--+ zyw;BVeCJ@n>vkCw3x?pH5p|TqYy*2sGa#TK<`sGfwbtcq&bQP((bakscNyyI>lwXO zKQWJd1+o6UZ417`8E}=Rzpdz9-{<3Y%Xz%d#H&&uSM!)=OHNWLO19*tuZkXjUJS&4@gr&)&3{|MFzgl}w%}7d$W)!JFfM5k#Pe9l z)_N=I!FC+?psIgxP12X6|Cao}CqHq_;xYY78CbLAbDul^yy2{Yecj)}@%5H!c6KqU zZQ!%zi1VAO!6fNq1jTCcOf@uw*V3Tb@3MkmAYstV?hVRVp`7P^zajrt9YgivY*Aw$ z9`~UAI}3%b^Ih`Sl#_fo`W_yRSrBEm%51Eiyp=SRoW0&rLvKWM+_K;wFw1&`dGcvr zJjYKT>J>q2HJ4x7ScXK2`u#P5~@|JH*Wa$Y>3s8YZ{|N00LpN$R2zz?qOKk7V`7&qQM6hlK2I51KskiXJ+J(k) ze}%djzO{`_8?du?!e^(ZUNhE&R3Vz}${kZFHd2JCqr`d2Kpqb(6o~N=B1I`F13d!+ zW7>`=?0q9}pf|6K1Pd_-N87)D0+8B3!iQi!O#%3GF-QMhgG|JPjJzG;Yy*W(kYOE- z_?1%&m6*kp?;1=#ve58jCV?((hW@UOBZqq6#1u>RFq_3cL%w8{ z^>owr*Z~g>1v!n8Qv0v$%uBmMFh?STl$KUbm^rhktWX&KwsQpCJ+<8v#VJRN{{F#1 z3a9I@Es4@KxPOJFQDUxJ%5kB`vqy@r4K55W(e!`Z)uOy=D&@~V8h*82BO|>^@z?63 z4yYTrN&R`Ry=hSOA3v5!9t%4O^!TwY;ak6~ZFoy)fQvJjT;mygyQibBFSz+Krs@7= ziE!&ETy1ioWQtb!T0coHd~g>fw{_LucM}%UvcHJkGykm~v4_1)O--$FTV$24r@{U` z>M*Ms|MDY{&(GCN7b2q4PX@LZ<_fM( zZnkU>YU7)bdw4BnjDC=6hVyZXfWz?xx+qY~UEZfx*VZB=S{Ql4IAa?kK&xT&J%bV4 z7am<;mV@g6X+1&85PZ1}GkVK{-W5ZT8KJE{s}ALLVYpE+P1`VVOe-^96=~`*nDZKT z1_;p|-Fx@w=^NUz1QfIC$&qsIyLT607wtP~_x(6xkm>8dSody&f(Pb|3pm20+(7r` zu6n&E_S-4U_$OlB1e+Qd9wm#fAd?pY>le^@kn0W!j!ZtaR(|>pNDf{18t<^OVuEK9 zsQ`e0*$#L;@WS5p{pjf)f&PF9L=^?E2qd@ly=!*}%@aY;Trh1)x=1V6^0J;2gT&iJ z%0^lXzI?Xx$bHL*w#qQP)oYpTf~Ze8Bfdh_hDa(Zu9H*pW6H-=f&IVVcF+5XSE1=J z?S`Oi3B=vF9HWs>D%1>5utE)9>i_WmolyhUo!;?!SWkjhigUztTArQz-pc(}&k-#Q zwve&=KqaXlFOU9`fA|HOBIdGTOG>k%?Y(75{YUO={kMWd6_?kXRqj!2TH#OC_APt2 zyrvfvr4g{q?7!e?*NL?1edP4yR8LRN<|nV#sRa%SoEdf;UTfr6mx!~DC%k^cw5s5C zo|CO~S1HH)H-U1909J6j#gp%RMC&586k~y!-urF~FLSTpS;eOoaDb26Lrr)`iDPCP zR*$k({_tP`OHL-FI^fNWqDl4dcu_j85ugqzj`JJmwXgaxWkf=H=6YQnpi*yM`A9%8^lztr26JhXANu#N~L7V#w;OxMl{Yb%CN#5iR=+udTZ+OJu>SFFnj4@Vw zhIEpS)-MzeSAAJVv*aFG4IlyUTHA5i`eQG{ zGbRedwVdI?VjrxUSn@Ieo`3{zkdb#A{V!ZE+JobU+jKh17w8ijBSW+MJW50mb4OyH z@ZjF*K|_ib!N-eeDqwD`4Bl}bdOuO3{$Ssq>H@lC%wR$^)+5D8;x?6k@+1dk0a03B zuDr;)&8NrKOA+}ML~|&0Lg=r9@V9exS2(RNYxPW-O*k$Q-Hw1KVZc&rH+t~;v#jN! zUlY%&uq*!Jo|)Q-P8mdyaD&Lqqzz zqanuE#j$G6Q`g0*e)l)TXj3F>TAiI=`BjOtvJuE^F~rvo>`)X)@((s8PlP?O^CEn@ zqFegCNJal3?WCnNY|n9K1}C_lG~@8b!skwU5qs_?{d18R)Fn{FtXYadJj3=aULlqp zyr2A|;Ww{sB#q~k{3Wfy`}L($9k2cCwL{0}ju%V}ub56mOl1HB9hef; z;D%CEFDxt^y6w640I6k!_CW8wxC}V%WJ1&!1bX(l5xm|-p;28^Q@a0hM5Hcq06{_M zVPK#IS0ZE^8V*Jt0o( zj!Cn>D_JfCz8e@$P&7XrynFXfEc#`(v5}#nX6K=(>d_ZPS(S(2B@Y8e#h6L+FZ1|r zO%M%XqY4g-l7B6b=pe=-N+G&eG2{io1&_k2{U!+@n*A^N#g|lP6+wi;Lts}7&Qb76 zXxM4P1#1v_d8{_U-A`Pbw%JWTwhr6U{90%$qiKX3C7Js-H#Ugo9)NHOv5Shv#z@#i z0fV4*mC66@n8j`y%!Z4l)I!QXj_)ZXYi^N&iW3S4q}mAkQ0UbYxE9 z5YG>SAC%5U#f|Eqx5e%T%dJ`WN~$n9R& zCB?W^TPCD#5LP)UEHy|{dHtHLruxm1?Y3!YQgYIk=9NG$D?;s%Tor=Ow``9RpS*N` zTobyxZg4DfL^O-Vv@_ZL0ZsUqZ01&n9tWmBzn~zjQDn%B=|}yC!CZTgiT0ZAE+hK! zLnCMshp1{W5W-PWkPQWRcW@=tUvoDuAq+a`DfnRxe*xIYAP`4n#j_Ah7dEhCE-Q}L zNB!5(`*U*wE9)eRO}_YiO3k^KIJXB+PWErH*8VlJrf0q0tD=hM8Uc$Ag)c%p6m>m& zUbOnDv6yn9Q30a6!of^R9sEu8ZL z;iQJhG>~gWvVstiQrvl$lvHO+e*k{JdlC`^X2D#?fPg~wVgQnGc5xwsY%sXAHan9W z*tpt&9RZFVa8_pbf70QpG1 z3=iy9MMXIe$~#f5nlD;MPBm}lnOE_Jc07|-r+qi)etzv?*J>Y2M0h>SCGTgsv^8i& z_OvdtMmMzku5#noLweBmwec|7Wu*uZMm@=(w~HuJ7~gX^$0cw51~V6 z;e`}kt3OdTIj+qfDUv=nXt=-OB5a{!kN0<}UC=_jrzZW;(Y_XsU!}4XW>p5sj6!_y z5lJjxUwf5JcqU)!o?7-dOBugP!u}u+`f`%^VDz7%=C?%>eC_XI!uc=jkZ>xBrhCzb z)NfE+HAi$A_me2mF$%qjX7yyMn<496Walq?3jhi=H8q8N5|eDP;1aUsgOV#~W`vLN zKhPdv91x5p5F=0ks|bk`;4K2Y35)_TQFc760NIn%41CAn6XiI~55^Em7GN-VvXjCb z{l(mSa*yrlD&|4s>>z)M5GoM>rttig_N1eZ$($?JqiSGO%nW>~``;Wt!D)m6T7#qI zL=CwYE~-*;Z32 zit6gF!vt>m6=@}&N=~}2qiE@{NakzIz}}Dx`zQH3n!tzXW$w)s=lllyRy2zLlDJI+ zrBIzXu}sC)SIB>fVTLtWL>DyKxnwNd_Qou<$g9*uZI!oiOMCsWaq1}We}FX=6IIVP zF{y1uoyE)0Sl+#pLSED_Np795nxR8cE;XSlN6|=>nKSdWCQ@*Ivv)cJCub}$t4q($ z?%jOdCw(p;EZRWGdR(PE7%Qzv`uNzj4dmD)*_ymHF0}dwBA+ zVrLSQ_G}m?RBr+CZL5wq(hAOWrQF+C`Ej(JgW)OVrB5#PjpXIn#)H7!;}$N>*L%s) z*pHmkO@c_ZFg@R|6ttXR^vUK_UdIyg!u8v8)6#94w6)#xy6H&=(;$8=X7e1eyq2bk zNenz#l{eTUp>nybFNFOxWB-CF5r2EA`C`4f%m1v~AMp_TA3X7YDS5dsNqOT`X@4Bl zh$ACf-@boe072%Wj#H&R32uSs;0teW%qPNM-hluF z|7?@PN={cxI0N;n%6fUQeRy03UzN#u>NCVCUR2Cvt+@2O(T}zf|0YVma|y8pw}pg0 zvDT6_jVE{+s@OETbrR~;qNG4?1FYPrzwi$sWl<_I(u;0Dm<%Z9f}pNmBx8c=lG%(f2o|16~2Uk+(O zG73lW-C551o>LMN)(>E`<+;Fqa7+$enMkNADv0`cU;pA6bq0;5a~=lS?N!YO+?Kd~ ze|aE)5LQH_G!uRtWF$lAWzgT@fC!C=i3!OoIy-BOGzsqtfcA2L?mId#A*o#88m`O2 zhGo(X2tUhz|DFiW5}A*@bkB}|-alnFKzTNd96b}J0iuU&Kp1)pVD_@D$EpMPF%SB= zV9s-Hn1vBe0py%O4kJyp_@PMDD+CQ8x#-Z;gTj0wnZpS>0UFSp(6r2z7sf4b3G?^g z_^`y&Q}fd}{Ij7-TDQrp@PW}CiZ>@ccmu1jf}Q#%8I*%T3RieS^D$>IZ>Fm>!ynnS zy*Pp8%;H8Lc%@3{Gl^JVE_$uG>+h=1psjqoWc{-Q5xdh7T*lG^75%!{rR|W%4pTp< z?EojaOU&#}tS8(v!OF@C{Y1z;g=zr<)XtxG6{WsC^(>hh?%7%D*e~6Q4|kJlL}||Y z{Iv_M)%cv~4N-W}cJl8ZqgNSDpuJU(chB;v0k|hu?8>j}@pty@;(NM}%WmfBYp%Sq z6u537aQ*7-uv`MFfI4;KL&^C;=DzkdOB%Qp&atVfjCqXlR@#5KY278MI=0-!E3yt+ zWM9&NtQcsoFHx^Kb5~;VFK;J*Vv&0a!mFKeBPSsB5t97B(odvEdwP1>Hp#LeFCP;R z_9(7b9cF$|dW@8=9d*T@0(GuMxY*6Ek+7tvHR|gv!bk6=A20>4jS_Qm{jQ6xd9%_n zqe*DbzehqsV&y~2|JbOdQj^jCX848gag4oa#*Hs0GJG@#$%%FM8f*+69?#9xguma7 z;Wi@8R3(j&%bi#covX_)ILZdOCCIZt3XDk-DaVL-+0qVS1}YwvdLZdwZy)X&uR^Qw zw}9=Q&n{V%Z2AG1l>i%A1Yc>5CSzO|eJq=*a2mQyFXP!naP0@knts5U3A-Pu4>okruY-b&!icOkkit|6l}l(ts`x z)`@tV!tXrns17A~cGz*QLQCe2B_()pdvFwj85~J^KuU-}1BW6pa4Ig=zEPpvu0FFY zaNw0m-K|z_*6-pRP`j7(=jZr%Q6IMIeo~TWNPG1T8P58dD9#e*R3O<(-uK7yjFNO) z!!%-?w8A&l%j$GPx-$H(?K~6B`my7P+b8>`HC#!I(O55`U70OZ&{J28t;AN!^i1NV z*t+ls(ITohhWMsi4)GBRMw|-qHtaz8Li}x^S4&Ya;UPA|ry`(}D;1!jcCnMvtOGQ! zAkD^tnfZc&7xR2j$ZxWvOOk0*1nufcW04V(XE!vQCsmgpXK*Kd%71^> z?ORr2mUnR9|26pS@)e7_&awqp72$Im?2GR@PsdAwv|KbS92w3m=%TTi;O~7;2gAQ^ zs#=XkC$2{hZc7P}$l8d9y#7M*-AK#$@K)#i0uP&^2Wr%pu)c@+@c(*%Cw}V;V93_l zMl`2-hSc|3!&m0ibj)(GFL`+lnja8|IW8nMG{^wXl}?sAD3pPT^Xk#grgm-TeM$v9)d7ip8A9d4YBMIfBltliN;PQ>NOVO9i|- zP1}Aplt^~*Q}zAJN#{SeEb7R-r_{p&R7OF9yxZLWMv?xGJJDZzhASsmLL)6@B? zfe*}g@ycUV}z5bZ3WZ2YNh?4uku+2^8o+-xdX3%MMki@kGklMK%;#Jkc z7KgMg0lp62Y`BdONE#3fi169jXBqZ9`D+X6RY2tNp(hmRBLt=d6La3gx|XJ99CqIw z_Ns#im+(N7QBV|>ZyUpGru1-VJ2^)!M++rdZypmH`vy=g2~l8FJpb{kox2jaC(kg*&FgLyA*oaPZ!wHHy3GN zmek_#6z_Z+5V)Vsu6rCatt!Y>&f9AJ%%aMMw5#yuubb#g1>AERP0g~&2L4p)zBDKE z9J<@alq(4?Too7#fvO(N18lJ+(20RqERo)>*NF{RaM026lJYPjhEiQsUMakR2p|N* zxmeb?z(hi|!a@36n5P5O3(rsb{d7|xSPUDErGtRx2Kyuls@oShoN?hlsD zv$vKmmZ6Hnb|wG0ml*8`_Rj;o5nYnbs)^vu$*b@Rs)n*?KFiffCb7wJko+quet%D; z(wHyoPlrT239gcDSMQw9MXBCv+wt_F#mNp*7B@2cpJ(JVTQ^Nr9WN5szph6oIlKOU zEdU#aY&KZ{3qB$C(>q=}yLL1i8W2Ains#=HXm#l>kGhYho6n6vizi=~zay~;3m8a5 zw2X}2@!Nt1V|isIA_O1vm$gE~v2Tn_C$dM!9E_+I6)_CniyoAt(wQ z`s#U%5)50AhXn9azV2VQ5zJG|8aEfY!;niTw_Nk^!jI+BH(kTHA^SHy((nLYlX%Vc z)%`-W=ib?wF= z0p5$t$w5-hP;|%UV;9or*%=v8Gc(2r1p^DtgBW&sE$9Em!+@vpCinwd!8L+7W*}b% zuQncN@>cT)#>Q8`eGS`l^uKRY`$~w|0PI_UZNsAawra0WD)Hb^)05tzUjeW5o$A^Y zw8%iWixjUh;*Cx;9oz-eS{~rK|8>S81A3-A0x?)2J5p9VX#$i6ny514f5a@~DJfd2vGbMdwY zQw10CH0N~bdXj+6sANRr3$I1D?Og&JWo#E~AGB`nmnL_jN6|7Tw3@Q<%Cu>rpMv$Z z-m;4#j@Jz#=w$;b<$u9Y63|TUv;AVO9g%*+E>qJVsmt1P^DC!9)_{qQ(i;Z5VYC7V zt244roEvn*Gsd|di~Y-XYAhW{w~%Ox-DFJ=sc_4b#HIgmg1!`2C6-ye^7${l40tr_t(f1tqFvY7&4?Xs=MpH)i8TlFnuXxqO`9j zlYZ5(aiv~4gL=qmhgsm4VPAr3)x=>RN>3#|UinS>@0(}N`)n(&4YNVNAt&9aF{7Kv zIf~~=GK1zFaq$>Lpl5Hd>T`%7HHi5YMqx0Nyn%rhIBFP}!1E0HElBA6`m_*c6*y2y zb0vX!gtRV2q@sF&DNk_uwiy2hhFgT+IZ2g|GhqaPIur(0Rz;fx5rY2qXsoBH5Z;pf zOJ|)#zU=N_e>ima_V?v;mjH@_Q0R`&W`L3dikk;VX^Z;FF$lcCM+BC`|3bUr6-O(m z8#woqgiNYz{|hglomL!R|633s;KUOGXpk_d6VL%8(Mce->F@7vD^xTcsy=~%h7ge+ z!c7kDr;ZDa7m2zw*Cwh)^AhNItO?3COj=G)pw|NO45R^R^4pCvo5ztnLX$X}$7sDG z_kzvf?;R~F*Bl3;5bGGeo25$1-M7g%Ps50AA_vdiz%q*R5+9Q;KAM5Kr+!$h_m^Jp zgki2&3{%OCrjrGxlMUa9#?sP#@Dhd2he=o}^;PB(L&|unW;U0i&(l>t!(nH#cMF)2 zu76)QpERv8O*-&U$73C4rFIi_t1r`*js5-rXaF1o)xo!F63Z}wFmGF$KlIx^+(A_@5l<#p;nAqTx^>Zkgv|3;v z!6P^L9+^L*o&Lzg{y3gg(p)W{?~^8KPm?R$Ml5J^lv!qh#9p+4LxuH&te5cI=G7c> z0h&(lE5i;7mE&$A4kU3qLwD*wIL~>NzWM%?+|N-!tFBi|;@<AVbLH-LWW)&W#v72Vpr(i@yWPJWr7_2pdn7!kvd!Y}$fHBcZDwBXqHdl!o&uOS zJj3&#{pK*60m;uI;+%rsoLwZSkXQju1bz^(gf31js6`P z3MqaA+d9}DNe{Jz_yv)SNxmu`Tka#7P7#6}R$ zsc*AZ5Bbb+l!CetH&lk>&sY1?UPz}0I0%3&C`j*o{(By&NI>k$P`jmD?>CxV5^7ub zP*w#(W|;VTVgCZhKjI*OjTnrgAV6G*1V}6dE{K7Ff$$$flWL&Tm<-_4`!ymRTfHrS zV>37RC~2I&9;lgJu6d zV>~Zveg3P*JGQG4fww54TkBp&@xLQ~Cr>W?xfwfq-gm&vm+qBM7RQH#M}w+7&EK;5 z_p^-^@#kaZ7~#+WHzR1FCB$fBTMYJEqbu%0R1!oHbpvOJ^qxZWAL4-W@u4|U#n4@M z>+4cVOb|6zIeNZkKw~qe%rw1<`PZtYyJAed%F0gvv%0jX@f~8+SQmdLhq}2pH?ATh zCaO&X4+T@S=z6v+Ox2l>Q~%VHbr?7~VWO@c{m%LMI}=FOYekp|yUgQZjuFyr{r8I; zO%+d~KVe{f?z8gq&*8(k0}W#UM3in}P{L44PDjVP@15`Ga>+_UR(r>Xq1_p;RCaf_8W!F7DjadZiH z01gVK3D}q*FbT2($pPpi|nQPEGKFTjWdT(VTjk)SD zFrUrR2gG`LU`!f#bYc95?$bT-{`&laCk4!*Hy7CJFB?sHBZ+CdYoB1>ttBnfxDsin zY=_?Tftcqb!5hvujE`6&%ITA9K92lk)7MwJ@=hekzTIz4SU2BgMo6!%S~&eB?@F`v zK=&@iL{cJ<@@$cexbmJifuI0JArRiT1rBDA6m4U)ATtuYa7f$8j<TmWvz`=4+E;-9t%T^rprS z^lEF-qNDx@1_n8RT;vMR>{a(LYZhw8E;7Y3o_tCJ5%$;DP#;n-W`oHp#uItz8_Q)2 zs;PD_Ph1Q$c7ySl_QnmQRS@z3_|rnb zs12tLbdAchRKm`?G1qMNS^(sGk-*_CtoGg_RhH+_P*dB)KdQ3zrq$&zId)*Qp!3bKvJ4fKNaD}c@^|CLiN1}JLuaFVcDKx& zs>ZF*(_Lq+IIn*CYc-`;7xyymPUNs#Pi%TOfo6sxV@XRF46F=7LX?0gw{cs82M1|# zfg5%g8a={}*51U1NV+2p3>+N8;KP9He(8Tg@8&*yX;lUto@`?f@LBl!{#P^re=tBb zNFze}9D>;%2WI)o)tc_hqMTGtW*|}>a$lh|gA}PT1AQ$9oXSXq3J@XA;L$l_GRMvTY;$6Vpr*C4IY*GS7uFq96emnh_E6 z7bv+pA#nmiUBOv}4Jl1v7Xg|GS)&UIFafMUu6)LL&CPu{V&L}#3{-}_ySpl->p5go zMlV_Mr=x~20x?(pAze@cO@PRzb9KT6Uu@b&l%@C^>^Lo2X`qW0e$dq5dG`xm)pZ&^U;C>|#4k}8tOta%YJ?G7-yKqk;ge254A<=A*qYIU* zjX!nBge$3fimbh8HspH>*rW2T)NfuGdF{1bqw_JCf5y9ASTFM^aqdtcDN721e;?Rp z)&#As@u}qWhnaBe@o~4*PaLyi=qGf4cf@>r?EQ5*bbND`^o2Di@tjr7lr}bTTGD-E z5k{Pv-E)Ef+<{afD}L3w}^VH~fmtp&{^4F8Z^r1NNSbw8q=L()0nfx52i=#xMx zsQ|C3%X*c_4VCgjvDrb&i~vag>&h=7WhG}iQ8~1@9L*vNt!|IN>PBbW4L8?Cqc_$b zsCjIEB6QV|xTHncWT+t($5%CW*c+ETM$vpG+M?$p(Y}5ky25RphI;WQZWaq3^oMe< z=zdFB5*R{2_xGm{Z@#vj&3#q^#$s@Nn`cEq#@Oa&X#Yx3wrO@RS()|t;(W|pYH!kj zTACGhF45AVwX5{PV{8efx}BHb(`UroQd4xhp$&O}Y=wHi$4ohE%XUX@>8gO91cv_) zR%30iH4#tHP!z?^!tZ~o))U+pyq4sX#d5V-y_K7pB~jUf zba|7b;fl)`^>zb@JwZ~AiL}8XhB3PHHN~LVYf^^!akCT#_#KQ?6{>A_0~)z)f{)65 zL}cb=1z$XNGjUcaI$`BbBid%x7_)d4`{e%TJ?4;%yyuCk4u`^1F((j+(rZ0TW#*%i z|72hE@${Rzl;~9MF@4?F1O(@5kDro?>etlPMv4yaSC}*)#G^$i;7Leb79T%9qj0_1 zi_N=#4-PCL32AoTZ8bWP28Nc1Th_V#@Rwo>EyB9GO~&;!n_D z>3F>P@^aZ|?u6pvpV=k3_m_Zch!776{U8e4jdAk9km}SXip)nA z1HjjVpvBF?f&m085UsWg)Ida~oP&DPE_hNv4L)cnw?#sO5!!B{WqR@+Xn!G8!#l+;p36Pnzb#{J8 zaWy~-xEf6E;!AXZ!}8F&urh^EW5mhpY+tl*Q*8pz35}hjBQuj`L~&*%bxv_h3C?jK znHUuy^-y=SD!m?@W4wwzz|P_rFIX}bL*|&dRfE1tPzF1`iXd`4!r>&4$&c^4 zs!B1mMnR`IvnoyH6Ej&A$Lsy3#Q2S4Y#$95B6xGpb*N8%jcLoLrrGaMauf8mcLe8R zkP{ylqXBLgGA^rcClS@&DN?sLdGj@e;=_M;(^P}V6$BUhHhVEFMEsB8)9%sfI*tF~ z%%A2Y?9c8msdfa_2%(UNxOVAVlt!~vsoIovXdC&5D@S3W|sPtRQl!c~Rr)-cEU zob7hQ*#g6G8-z+A3m=@w3t!u={TQB_8y=>A{eD?6*L8Jy86lDoTRrM+&>0vyLD2lB zPXtMnLc>MaCPY38`oPi_<)7JxOUb{G-U9f|u`-Bnd5icQ@j)38g6$Z41K9^j8X)XK zT#8D}nudmv@Hn(SRL3jn@sQ$_e#nw~6GT*Cgo97G@b;pn$y*cl4+o%{hHeOHnAAa4 z_|Q=YkQrDUA^j2wO_s~(Jx931viI*Tp$iS!v0w^7 znaGw*xsUbalu2P886G=j1>yXS-MqOHi=E}i4+U1cKGfB*b*ZwvW7{^8*ZMdbXY@Ln zeReC$-0i88s3+V+(9#Vprc|&8!zEzLzo`#M@Js$qCoZ$P?{m66v!5)B$m^p zFnn1QUHZ*s1+jKtCF1ZAx?eP^(rYz+tywWFQYattnmnFg^vRRmtavkZU7G&7RN!+e z&@Fs5#8If-#-$|V(OSa(vl;U`J5ATNGw>$u9=0z*(c_}d`O4GB&Jztp&u1zO%brIi zq?oAHnK7g(8yOjmRkQysvnNZyJb-@)?Z=A~6@eNI{KQ9kda2=}tj|foYX~Rcu5nm9 z8aN(6&9Ixbu&_|}cs?u{yd$FSJ&W$5q1$v$V?#`PZL*shL#%i1`G)Q5k3HwFpSQu= zW=;Ee?jJO)uxA})AyMHux2N+v*05>FZTk(%&Fg%SC1+wbe2z2Y_s7|fsTjW;aYkm7 z6#w4zvftg__$QUnTO)m8_P8|PH~vrS;Y~xK<@Q`CtAg(s2nzFpgnn^;{vZe$MykF5 zwF9dQFce4)Jp_6KQw;$E43>l-dIxn0bX6o4iNT{&TB+gi0N6W_1VBvk0)&PgO%C}L zl?vHn0XsSivHP@bPD-&6oe>s8I_!_Q-08wQnCn{2$}> zE6C^sN^S`9E4>)_mCe9PxEyw$;}puzLPpgb3BE3~a4K6DmPWUu=C?ljhpZ;lv^e1A6_tq<(P1YL2B*(`n{c0nRxP;YpbDr%aObX*mzP0+FXRzwvW0+*2gzCI zOH;iUkjbll*1_TQfaY7@O?nKs6EzGYY_o5us)K->pLMm;j{4kTz7pX_ZYx!NH{0)S z7cn&lzvO2Eyfd?xtUt2Z{Kmf+9Jx3aoS#_MUiw5l?L{96C@B&EuzM=YUF0~peUvXm z)2U!gJo}hzA<%4Fos!vPb@L0nl_&wM-v}?V-ndoe5hz&!fGCs%fBWc;1y>|W7sVI{fz7~Hw?bACtWMyT4{Tphx>F2kD~Nmo>DqzReLymhLM{v4 zV%Kd zejqTl|6kXO|GtnvQ(sRdQeFjXARkygbAh_J`1i%guhd^_&qP6ucINax- z6(>;jR;q(U>VrO4o4+K9k~I^U0XbAY4y|e%Ccl=nh9=K5PIgdl|1WdMxOyN zBpgi(Z79}%eFcle+Xn>2Z}6!Xn159?#hz3#E(9^AhQ@N&6S<2|i+0_;+`G`2AONLZ zj6!97J^S0@V{dr}Qy`pxcX@}@XaOrGMmt1AKQXF_@znXN1|FzaUSldPDF%maE&L8! zk?DP`LOXIF+8O2>gX?WI?ebE$=eXGdiBJor3N&`MGK@EZNneLKJ!T}oZmFD~D@F|3 zkPpQGhJ;v3ckBzHp+?L(L@<2SbHxR&ss;Z0{!lL2ur;;bb%{xM&%+=X|Jm46fb^j1 zCJ*9BF-;$I)%W)H3TP+#lonpltKAA*1JJSZ2MIUiBDO%3z}hx^g`O@rI5_Za<3UyF zr|I(1l#zSTl_xCnm|!%4skVlhA_|WiV}fR1VkoJ4S!=}>yQX8CKq~o)lKS)W3^tAS zK*o$9nTxN9T(T_Y7hY50nM@0o#!u;Z4A;FK!2X7~C=n^*(NknF3aJl~3neD5Z z5d1Zu=SpWQuGh~fm12ZWTur%i9^VkK8!X{e4BK4mvbK>?)Tf``1fYWjLO-Ci=O!R1S0SaC1j2OCqIn zGlT9nX$U&400S=)Jc-2gwcbM5bm!Jrii4{?nMFl^~h>tT{fw z7r}>%{NhNZeb)1z(vY{e)(pQB02>RBxKuy`2{QmfT0(^D!pHa442zM9_sNu&?z4Q& z^-Jk4-DqOK2~D)l8uD=bU18%-RM}{`@lN2;$vF9SrV`hm71MG*NGQ;<{_}%9sIvg& zcP%=#uJ5}b-%zO+%(Pdpa7snie2vQpt2uME_x(GBZst0{kshX_Ti)`FsIMmJO^638 z3yaPKh;?(veq$D4(kDb{E#|`d01)I`;~=JZTpp9pA@CD}X0c`c-&4DuD0;|;@`ss7@bOo{YTbY7AZpdvF?G~Om^L^FGpjq3qu|nYr`eEG?r0z4};X3QA4R7CWPmnF}ayxKZK!LaY&p!vv1d)%_CnJwwJ+d6gH6Q8+PbL|uV5xf3Cy z0}e8GQ4@u^kxTYAA*HDTx-Rl%Thy1dWv%KwjVi9ag@b;!;41@?+j&t&n5erylJ7dT zY%R%~P8@jiIRbe0=vDk-1S_}WC$KO|3+4?P*|o1W*Y}_mR^{I}eJ3(|>v?SaT<2wR ziyZhej*ox5&~5quS^zKUh4F9SLLi+>dh*%9hCy^}EaDnl7HHg79xJ~~yykSHB~6tD zu(fb+_*{^HsSh7WAdU={skYH|XJI}G2_Av@j@eDW`DT@rX_$%MKuicE`+$3Kkwosc z7^WCrBKX2!S9}D~D^|CBe|TL3SyNJKrlq^5=XE5l;Ne4HKOuBEWbm;pfiz+s2%k1rvD>%dy(sS0MAVhA9WCuFv?FgSxF*{dG_4y`h}(T=6XHDN)TxwC zCAxL@>I#q8ZbU({j0OR4oD6Ol2NT=fR&4=6TZi&D79YAKP4kcA0*8`J%X#_59FJP#CExwtr9{aZ6R1A{7`h zFsnht(p4#HBB&P9X6l003uJYGTWNT5vL2)77(IWbVvseR$<&)+LsmW;eI z#@d;KSn^+W`{{E12b$F;J#1Dx$nQMmx8|jq;=P}p@~pS$_C!MWWbq5HuWx7y ztoSb84vi#y85Q3<4{p}`x$XI4^rLOe&rNaT->n}P`*<+Y0?3_MiI{C-2QdX6RbB_E z3<+O_BplG4B6eKBUJ-#QaxY(;Zo~6}2<~WhBCht^2;k?ww!LD*K55g8_|YMH1khiI zEgc>k3x**V{*(ZafTi&olq*5sXBfmrdDua9!}vJG73^S5>~YA3gJ%t70`YQAd2i_SPdQ42TaAT@d3uUGU+P>QO2#3se*(478HH$7E!-yh^<}eSvC#!Dr`+j{ z=V!|Qr2=qF^@S4PqjsksS6S5C+#nypUl1aa!hAlZDro=Dq1X}~>iTphBN0SvWQ=%h z@$DMxA4+a4KHsnjdG(^M{^_Ok~8 z=)c*ezE0k*+vyCwC{p;_0T<44<{>)8GGmV(-GcA5ZVVD&2ZC))XiX`_oRM;`JtE<=G|c+tZb zDnlyFq)QiK`cU@v@&53&j|1yU&X04^}^JfmSN6U$J{AnNHe{z-0 zq^1Qi{k}sR(tjwpH^h>g1p1zAH_%-^9ES9Pknd0BwX{ZL%drX^a-j4V5DZYLJ{;g| z`Ffpxo#%FLmiPc{EZ}*y>GMka&8Hxh)?fwWflJJt1uNIol|JqA7G-bBh04x9Z{Bi_T1;jz z_9C~~b9cI~zmIIMaDpY9bDGoHz(n6bU%5g3Vi|BQF!8J19;ayzP;$oL%qFi}@&hQV z&X~uAZ>$vKe9+|Gk;jd){%kULajKY7zFXo^LfqNxOEmI(gPx z5?_rzW1|Is#+Sf<49YfxUpA|kgo1)nOVgo4XU~zUkReyi>n-}a1zjoKj&+Jb`D^jN z3D?CA<}*2bD}73nDUJNhk)R?dW*im;`W~qIeBj=X3SA`Gw=}ZxHuf*#e3gbEp#J%s zFC}v9f&c(GJSLytO8au=M*UWObN!Uh@D*mFcyn|yg;U{9Lw*fNFogaVc%6j-+=MIh z&f_b-G&0lx3zhS&?={m|%U-CV)XgXqPuc@qx2ho4%HP02)lhsi#bv&3+848mAJ0sY zO(f<@Tz1ID_nWX+Y4r_G|Bc$PyWqL_I(u?#L7WcC151-c;)k3>pcRd{weph-8q&VTR!UpJVA1sV{#rN=^d?qJYoL52j3wuPPKy;B1)Gykv` zM05(9&p^jn5~Lm$_CKBhA;{n|1)CDmmH}E?Sg^MZwAH23`|2S?e5_c5;1=_$O7U@O zMh53~11JWCGF-VWBxXEQ)B_(>7Or>h2xL_wJFmEZ@s|tw_Rtc4lX2Vi)DIWE!(y~{3o@oSmQzYDROSu#a%^%D zKSd`>xiSC64a4P<6kH|0wlv<9O(iJU;uh4sFZM}%`_+S>To_M__UmC$OP#;R!z<+p84oS8oP$dEZs7SaWTuu+$)^p0QRY@oVTt@8wb(c1~--9De7WGrPUKrn((J?b4hWtA2_+)vhr$ZB> zG=0|tTXum%c?n^9mBcnR46}*l6-R-Y2RzWVmaQ^nHq{O0CM{rlH6)HPA#s^Pc@q*& z;I{UWn3Juq=y_2LCo6F9;CYuL6&@9&1Ns(56m)-7006kH!N>~E^}_-}(+;-hVj)pn zktP$aY$OFmPcO{uVlR~==KU2$j6gE1-L^J#Fs19#Sz#7muwId-GHW8>tvWA$kpyNz0l%{Q~0}HjTJLg;Wva65cwP`;O@C^J+ z3vNJCrxZ15DVCQlPWmb!gE4bGc!D8Oh41hv?)EJ-CqH_uZ@Vw}7s4A&Ss~6GByX@= zLHhWAS<4_LT7ac0|NYB@g9Exg9_GE=CBs$KmP`yuh?CEbxF2=r{mzSORVHIAx1cNI zcx;+e+8mT~Bp~T+dl)0^R)EJDPpH30{i9f)@3shvoZINC=iF1m786)&V+^M^PavwH5XSx6Dm1rwkCEWVlK){8w*R}?js$b}a>9U5X3{_OPU68cj^ zM&6CdlXx?x6E5`eSPsLMGi8Ijw5!6tq>oHhWY5@0Bdmxr3q0I;x94-&rdyNjn0{|V zYqdET#-q6nw0kl3tGQ(Mnr=jOeyFd<1DqfxhVY^9vTN@aq3a80`2=I)>>f4UXtaBg zG-<3x6t1ZY`zcb_%^t0h$SMcJmIB^d`C|YM-~syUef~bz_}zP}tR{r!zjyDpsA%aF zEAr%_zX3Qci2cdq$4IXg(%=KSbWo{qP-=X=qKJRXi;%&&_qHmGnxJHZ2O64-IwU$> z$SMPz8|AGBzd0GNmlp~Tyk_{@vrVsK)!lUe4h7E_rs^rQ394Fx+Pmz8pYT7C%v_P7 z8!0v+?h5*_zOfT?j8>q(?&=o3R&R!XxPy~!=)>`dWk4xG8SRRczSy$hym{tUA~D7{ z$svhTE)ZOU*#mS32=%6^8SuXZX7EI|f=S80hk%<{f+tfY6QApO?MwuX{gX%1@g^*5 zR;dw{^4RN**Hl>&h1p%*&`nlvBHB2&;25*Oyl;$b#43?dm7i;|zd4{|O#?BkO{Flv zAlI(7#^{aG4D^7ws+^ec)@yTuEq0~4TC|TpqB|$z;at}_fQt)(nJ9$rdrEDVlRI6gf=s;chv*#tWKCN{6@=6eMuIJBR7wzSM%_DIBKCZ1XZ=9TGq>S!K& zS#np0V9;J%E+r|7h>dzC*K}5~q?WO}a*eh3Er~|k7=#6U`Si}X+y1bA)-kzj7V11d zebU>feM)zHym!ya%$Xjm&&}0U2c8Fw-vQl+Z3qM@H#DRq&k}vwcIw5sv3d?ORIXZHeY4WdK@T`eHAwEp3`Ieaonm( zGY-0grOu;E*ZFa?e2tiOo@g*a=dkkE>qvj&A~69>!W-Wwa*HyA9LxS&N^I?ntD1ZtCW<7)a z{QT%&##@#M*ZoMYDDxKKyDemO`1hxKa8&z9`lcopjp1dQ6<1k#OH6E`D`70TXW@MA zv9{%nUPug}g}ufuu;yD>3Ns3q4_XMd>Tb0NqrOd3cOHVG)!hyoy9K zlZ#4rsAwa1I1>tVF8@&l+9g=zVLEwud{0!gV-9{K&{%6)U~#+yn#FeEIJT=U=MlkGu&YVo0uBT-385d~~oGu3gUnx~rSoe3LhyZRR_ zm8{AR6ON-pHUX$j>BvQt!$rgy2HJ_N78!0N1{toma~z9V;!>S*X6LDASGxQiLj}%T z@l#6o$=G=o8MEkw58s^n9yO7b#ET_nZ)0OBZ=cw2@6YuAGd_e`06=^YNB!$8?#Bfi z+uM4LsfT9ZbpYW(XF`o5;5;xaLXN^qPvY{4Z>F%e18s^V=p+q+>(bU1kCN9^XHA?r zGhG-;w6L<~G#uF0&G)?gjK^VRhSe!n}Jo9{eRvj(4&GK-dlQ-S)YOeRZ90bH!-RSenL2+P&4oKDYReTwR-_9AfHgx8X-mY>mzoC!F3IpYOl%0)7j%pNe9%l%|(D z9EB}5{VDT6(8&LV2NUJO2bMl#UJpe7C(PC&H(~y+xJA6>^>FNt(i%<7BgnFwWw1_oOQ>B!2GWg@ z(a|78Me{F&z^nE+U6GHNbT8?eZ*ID#k@m5~`CskI@g@*wBPy$%#GEtCx#O?T5#}BG zQ%Q;MRPZ_+xHrs#upWSESiV5YnlOJmw$rlCWeFR+7l=_3fXiJ~5jW?Z4rU%#h7yb3E9fEY*^5To>Wv-9s}3rKz1D>By`LoAO*zp;qE4@lN-S$TAJ zGh}yh=gOpT+yeF9{Mdu>k_C|iMIu@4*8r9hR_<5ix4-Ueo1)rykrD3bgfZwPe3DM4 zN!AuFBvPi7cFnoSNad&(Z#>_q?3(qYJ+;hpZ48N{#iraV-MzBw zDoRSXaqbhod%`|*-FG~a!dHmDV;wpX_%r_q18B{?$OkoAa<8+dj)kp1lg6*^d<^Q{ zk%(jO$xdw=NpN-0W_ZFh9wiZ1&F3*cPJTvME?}nPyL&hE{M>h>2!&K8AVnlFk-(eB_TWPK z#mQQ|fFlel&}n}KG)r=f4CAT>bBnJy4N6i@_4>W~PIKJJ&U4PWHzMxRY;5L=d<-5e zS93SpY%_LLPuv@}^{|xuT=8Q-c~!ffZ0eB%ywu^Wi_WoMLOY!wB=2bwI?##CqrHb~ABQ=L4M{>;4$d zC3oW@q2+AHi`HSUHuJqljnX|b&8dYku@UVRG2*=c@c%A_#GW+k#B*M)#sXR?7BRkG3 z!FpGr3`pqP8$LH`NHSkrTa%K=37fQ6fbR-c7Nl0tUJxmK-GxsM1NOPHF<|oHpHZE1 znDC(^tAqS%zr#bGNGS&-;-x#5E=sx2M!@p;ScBhJqhevmrn^D8u$S5QCoH16Cy|#MfpN718ke&oVytu+p zl$f3MnOD+Mmr9{l0<_pbr~nc%S0DTlcPG?TFo-j`;;C^ztvgTSm(n~Val4VH)HjUG z)Hyo8+hrXdzp5)KQB%5IV_05V9sYD^{^hyLc8be}p+ZEXZm+4ksG|TCR?Tg8W9T`b z-?lwV80`>x>3R;`*>33uI~JwU=fz?7E@4nweaSe~;G`#`iia`b_G4FVTS zLZ0cpA|;W4pxYZr;xN=)L!LX*F9M4>EW8w7R_L$KbFH+Y_9T(C1-0Y(^yKkUN5yi0P~~% z&Hh{LQj7S`ldO`r{()em*8xttj%zL(|C)3P#4=CFdTSP6fFnr7T|F%%(X!NxrzTBvO;7m9)S%kRW2YNGGE+l^jnxslOT4R6qB#Y7I#8(q( zKSPXl{PatD+(MRQL)Qmb>@P+io z=4Rg3naW#9l)HA$oB9J3gxmd?n^S~BA3m-CR=yi3fVtuBfJ+44H>3ztEfW3>WCkFO zSMboniw^@NywgbC9|FM&3AHcnn!CG`0cN%%-YO@OrM~+}FaznO0Ow0C*nR*wc?;`@ zh6b^z*9tj;a}5g3bs%9hix4*ea6cOv{trO!s9$g_Xkq96@a2lVZP4fS3O37*d-ZwX zh;Rn!7;pr>){%vVWWSmFJPNblKVj#WoA;uO>V))ss2*bRw74YeGg1HcYpR&M&qpcG zEq!jK^VlmASBJAomM!^ygwKtk;M-*^-v_Xg6$HM$A6fh~w7L&<%d+r;L7cWH z)9r-V-(@4Ov+y9ER?!r(%bhMU`+s!1*ovO>TY zdE{@fe6aUPJ+d`7M}gW9m}GdQ0ajwx_ zePXXUxHAG(0nh;IBR%5kwTO^__dw5f&I~erOdjTa$NstMLUA*}UNW|V&`j!cob;bv z@#^vQ%K92;s2#-q*wchZCO)4ROd^^g3j3ddYtz_x#J>{4E23xmhD5l1?N+}~MsA5v znefF~$v-kor}J_C&`L_WdfHStx*mA|C%;O8-E!vqj3b;~PNH0rnFd zi~*1(tyhnAC^ZT~3|@i!q_bNFBkO%}gwfCQugNa;AJ?2{rxKDqn(%ZeMBjHt^;SxU z%Amo~1ywolGD2b)lA5!3EQY+Kps9sZC4W14V!_tsP5VedQ905VDj+oNGXJw%#+AaO z=AZtgLDw^mNULYWDkE52R&?!}Mp3+UbJFEM1H$YME3cY$D~$eC==%R!0BG)&A==kg z8SZ|1`|h0>lf;`fYR^I#U*MkaT?VNaw?qClR6IDZe!U6MpuN34WGNzXicL+lV9#EeP{?w}ghp z9DmHA%yUX*ZG~!9^4)hiDWlrI-Fj?T%Zf8=PYkFfSRG;$Yb|bVs}w$nEMPHvm?J@u zx2!7V#UXoF#P*AZtJ&Sdo{8Sx@S~}|Rn8g@GPX9<*lz*!KosPlX_=XsS@`GVCe^4JB1jxPekjt(CG) zzkmv*Aj{?)Fjc@Vr#b5C9`LkJqT6y`;_&qR_45;p4}y8`ASI93A3JO|(36pejhOH* z_A-$xz72k{m_7ephGdn9eL1hX3mXighMPv^t0PtpZC5gHC52VBhp$Kb*zeqKvk*Nq zg~LMl@OML=MB&}IE>4Y1<;~7(m{azGNOXk#mTF-nNe1AG7LYe}7rrma<*c3sMyttP zv_kU73DP@HHLsl*aaZ5sTwf7eCiBaadk{V$2L~KvMbXy2Gjd-#$gzBr7vi_8u7rS&_Z6 zQ+CKYWRr}nvS(IS_9hhBJ9}khuaZqR&wakv@9FA~{)=-ypZEK|UlVj+049UDnA!8$ zv(!JGeH#O$OsCB2(vhSNdbQ-2R$`gXTtSw**viVw*tHtwDRWLUqG{FH8ghg23gxHg z(@X=0PhuCBX78(hwAQc+zT%hlp-bPd!s{GiH_cJUr+j1mByhCEoA!P32$7!p7;*ob zXT^Tr#O;mxx*xW&&p~q+_e0Ff_CAZwbLe|2=`-V%VyS_-Lj^%xZK`j3e_*YOc26*# zk2!w-b8n=U9y&h8HB{L6UD5fJE5y{3Z5S5d(t|OKETm6;_S$nn__2uh!HiC!SDtYIo1t-m>8h>S1aK6$5YOXRxjUa(X(2+ zZet%~T6h`rw-~1o?yaA*dfy#bt2m}H6D}n^GkZYj`<`}JhWd^x`S)>?c6;rZ^=Y3X zihI_Ee?~j>Bk8IMfucjHKJJG`P&U@h%p#o^?JrmDQA!&aI+~Vt=OJ3Q38+-~14l93 z#Ex!m!SHOuPqql<4?ia-n`dWf!D<1=wTz!1oWA#n+uIbNBm!RAGX3If3R%EAFRHk? zqrvHp`uexFN-~T1qh7k3*CGZKHm$G@`8Zm}%&vQrNzJhx@u!Z77SwIABO0tT-1XKG z&DLfq|E#{KS065g3Ljl|?afKvVam_u^ePv(3dkDHdnPcjwoyjr6%ZSz(D`j|;!spJ3cnu4m3j=r#e&-!|vulVx5JD^}DARvd^ z6l5>p>x9vQGodhGGiMlU7L}?CzYt0!pvDZFrv(iSEp3PWn=^x2!xCbn4XuJ;dAP4` zyGtFrX*i9myOWWV4}n7#mz)#Tx>efnj}rP)IQn~aZ6@(c}<;GowOlRaXk@_+$Sxw88q<}OJ1t? ze{1STW&kriS%d@}GR{Nb$Ib;xE%6_bPf^ZjE+SRr4O>q0zQgs!%kxhltbiAx$? z!p*m@7LYb^TUNHVr~`>Jp%nxw1Ox=AQ4uWJ8J{L!38I3JKvYHNeQ*oF6-cLRQ`rHZ z21xWWAbkvuIh+BSxCF#ez|Cu)bkXPzf3+QbJW_kP-M)D93ca+`;9j|9Y*1U3l)}k7 zE7Gq_2Z-$VN8biaS-yUPM&!H9ghwf2!9K^0{G`SNAJjxk|IrV+o5W;9`0Y5<+dt7; zOD3q5O;pI?27N0WBZiGWG>s>H_Fz&*gT*2+5EJx;VHmhF`SME(D1UEK(k(g*kb6TM zmG3l^wS%4j{sKgjQDtvuhch7F9f(T~ncj}jv5xi#(p8vEfltpYmIwQV!ppPESm{4; zSadh5h;$Yu$9n>f<{BER0=VR9BjlO{3!Vzr9c6!X$^ITA<}u)(t18CY88nm9cd z9`c)ja0a&V4p0-q@drxrO=oEkr$7ad z#dmbc@l{}rgX1Tva4FhTU7X;YLG86R6$i}C8%zYQnhs=pdD8`fx#J-XFEMN%Gi6S1 zI82B}^?ZJj!lFSd^4H~upv!`ZC$9MMU&ZD!hAc5Gm8|i{)~_S8@B-v=&$<~^B3U@r zSX5uE?4Lx!cLtW3tJBge(9<L3bLi#(Xcf1_G^NVuT0uIp2&L z=YIrWUIB{p&Jp#2Zt8d7F?`^ENBQ#unV6_d4I?b{4(WB5 zuvtTmasP7Cr#)aucoU9mF+Y+1p*0~aURT}h7o;}Cd&whdPQ(uAVZerk0v;rFxlBZ? zYnD?FW8>WOy&*wZ-GEGjhz;NG6tE)Q=g&JAjE8C=z(26h;x?5Y{LU!3BVZa( zGCNf=@C{MSt7%JP#jt>jePnljrPt-eB}&p$&2vX+^z(D`=RF$v*EBXi8*Xvv_?JiO zY*}>@evlQGW<+}%Bo>mPRlM^)VZfRo|G;xu{Wns>N{qEGJa!M{*U+!_)Z-EBv?G!9 zmg6!`**L{Y88NS!c_O;x>*cc*o}Q!RT^`x1+sjekcLCaf(HjCOo)(#oQO@0?)~~D8 zov9Io>S%~K&(>gB$Yv$M3GKSm%qG-MOIN5Lh@bjnj^Vp z$2W8=uyL06Pj=eduR?6TzAn1QyF<1J%d=ba$|D~a^eqpj15uWBQ*sQBvbe**^IYF18oL%M?#%NK0uG^(NBZK>ENsk?TFNGbk~H2x$>SB zygiRrn;z;=yz@^%*JpN%SLp#P3cHF)YR^g*)4oA$J>O5* z!Z269aCOyrYrj06oKhd+R_VC+yT4@k09e`SpiZ9-YrfL_2| z0&h3Oj08qmR_n_;V?Ju9QcjOU^aiF!1g#CZE%Z!Q65EySIM3c=dKNh#)m6ro+a>lv zCxUI2_kE5Ao}k(+*2-i2BR5Cs-$m|c5t4N$ZI8ZKpbF6qyTfATHTJwp0K`Ig0l7p5!$7q2+}9oZPGp!fZj zcAgN(Dx(bS-D)*zT7%&9ku6BIg1`N{h`4Oy*c6yrfKF+LMY)G zvEhgagr$ST8+INXUNoPy8gx1dP#nJ9z8PAF^7R3sxC=ow3#gRL)z!~UsWDrOBuIf$ zp)0I9fk(9VV3MqyWRKlyZIy;o67Dd35Q)O}^q<9BM+eRmSga%aEHGmwwZ+G7MCl8? z?P(t<)C)M*tKd})iyl~Oy)eTsAv~lny!oX=LdqkH!WwY?9T(5=yUg#~XjiYdX*xPn zc$ZQxnF`I zTop^){tqF9YryB)3T2~!GNLF(5}f19qsE9JLORrG2@nB{jtti+=AHm$0z>ES@vbSF zY~gDQi^uhR=>uWyhX1bZihS0{kER(y5c7(OK>@^DKu!RF097tFh0?QUJR-aNp(1p0 z=LQs%lz!8j+7uGbVmdzylJdq#ve)i=U9qoNiS_5|g^%p`rhk6PA`*w3qRU0lx|UMD z4_xIhxflIbrBl8;@1M6}nw&1>^StWiY*V>SaRNRqr(p+mO+*1p^7!hpmv{uMp=OnO z_hP!EX9)F+$ePp}cfTX-u5g3C5UCjU2ertCFXsIw@|wec_)0!0I$iRx1gxPT6@cPN zwZ!yz>jb{ML0y1M+k1LKn~F3i%}4$84fgk`AET2z%(URW1H%^Z^2**}?~MsI7dH6s z$c&+SF#Vz0kf8jd{;N?+$H7Vef!1#? zMIQz?&G6#k7t6O*aOa|Xo)U4!+OM(X7CK zpWNAru<}a!X0R3so^0Lyyi{k1N?C?2?!Phezx48p?KfNpoY3M08408hUq?%o2neAy zSyzJw54Ai1`Y41z$as2wyW7_I=1Lp{nUFDnBGh0*26*!pP88ppVL$coqY6Wzw?S0L zV%GSjf^N$@;aOQ!)xXHgjSL94hdHuGtl&f7H!AA1a8Z7wrgVdEuPw|<{E?g{li!Bq zTe`Jqqk+uUzqkFFCT2p<>MV4{&qH1s6!@RhcjfCX!KnmSsd{QZ$NtmF&iF^dYR z!p^%m(J(LLy7KsgBJv+N<01n0FdyoMJE85LxnVpWe_F>2@#ttIEJQ3vyHz&i5gVv+e`g7Ke1lmTOY4KBN}r~2wZ3BQ%ayg= zSE+_ixN`Giq6y};?s9c<5LftlMys9Z(0lEbb__<2@3SeHU>gBJQ=1|6m zFHIR}D;zgC6ZrlyRGx_HJlDHpGqc;Yo8lWCvR)W!2WyeCed%~jmIcLAsc8?xRI^h9 zWU%8GK4Hc}!&!y*jj(tGY8cs#)D|7&7w^}f&-g|zB=`=$806)DiND8lUQPK!J}u1L zOH?9#0A&LPsTsIdt3?+mqB7iJ(?*R^fCHiOuSG>Mr*Uj?452m+vA=i9S>wb`c6);_ z6)eKKdU|hR$UQr7lcFif>+kD}qX=^LfxJwi{eY3arOxEFqGMBAD$b78va;H{vGxjH z@}a`!zp}ltc4Z7xn7ZsmQak=#ic`CY3f2flIl3-*RNiVdm=4<9WpbzsP11)nv(a>| zAZwbY3fjkW%sL&|J&LDV(8IAzhKAwz7-$Q)X2pi=0EL|>d3HNF2&y4NK5lJo(S50^ z!iq3{5F-iP8F*-5f(Y5hL1lXS#*N zw+t%_vT_`D+kZ`~TnL-h@`U6K7Z|a6ZgbThUj*z$_B)x2r7F_%Jylbq4HxeF7#n1L zJ#|XD_fMR(7FWXoF(h9wruB|s?f+Zw|FL}pr8yylA1m%aRUt@8U=Rw42r5ZWOhn1I zQ29R9`Y6B#mDzPT@w{_%G*;>)y7z}z5ie)hg!-2+V~F2|>hlAr2=v$St-00=Y=7D= zrFw+C$!Ee;-mO~&>;GcCb!Ql+?*RJUr_3^AZWr#)cQGg|*Z1;2^o; zYmYZ&h|CMYGHYwpm57I5Fbr&EGX@Z4#9ett|E9ucd?yhv2t45EkH^OJ;<&V4OUyRqn=17i) z(7BV9q`JfH?6Vqc2o-zLGn``_%)Om#DrJ(GdRhrf{{ys4i zd+)RF)3bsMmB;D)?Uc*>TN5}tzo+Jq9)yy^+%bX}7HgO)Pg_5Jq=ZYIor424xI&lC zwT-@;x#KeQPOBPum}>80tK3T6bH>uR5+pfz{6D^ZG|^3KkWkpQ`6RKloqV<#V3bH9 zwDC>}zlkMTZc?}K+x!v8npwa2Vs~5goNtMBq$&fLI9$S zMnX1UbaIv;c z2>As+>4Ac*5qsWN=a?QX?(^#5w%=L(3amN!u^$dcNURO+6v)ylOeW`AINw(OWfi+! zwb4bxw&$u6He0zDuftFgrMu}?bTGZ3ZfvK!d)9lXeBZpVirv~Y^{O;*lk4bJwG-lP zWXhQ4rpFym@0o`zH8l2&r?aDYYSpGQ!fmMmz`%xjt81xTsu+>?tS9wZ2;8w`B@Nvf zp_JQ@aJR6cyP;0#WGM7$^VX_U&)^^t(61!?qh_xLEu;ln14TuitZi&>cQ$w)wTWuv zli⪙ym4#n3(Qg^NC+WzWkp@J@A0k>Pm_eKwV=nZYXWG7itO$OQztp z&`K4r@GH)--~HMp68IOfV)M=`opN|#I7bomds1*rfus=-G-H0sC~S28Sjcn9s_kxLsHb;ah1p-FPXYxpJBE;+bNGQfT32aZDP3qdre5=nLK z_LHBXWmxDhs%HZ^Y;KNg3Xeq!cXD-`uaKpC&8{Hnla#=zOrNR})`%XAA9t>QdUkra zaXjx&2%SD{j@E1*a}f6Gi*n#XNrC|A*P%5JhANP0?{0nDHUSd=1p9qqW;~=@D0HWp z^FI0&{e6tsh&F2o>(kFGa6u5S+;2}Q$))4Ge*HRWLuoV;jc9fsZ0(S#Vj!b~HV-r& zu$-atnP%1c0_pojfk(JkWa%|XA5uVb+TC*9{d~~05Ef64FGjz3rQ~5Zq<>fUxw7)y zUvWRX&wy1bsY2jPtr+eWFy^9V)J!xDI#j8%$HiX=fFz1Cg z7}>qiE2nSpld%(pMe6dwl8$nEWIEe`rQH@t>;&qWecO&LN zui%)LmR`ee`d!ViF>8AIK8^rd#;cpslI@PCq7*nS8@sGqIcv|Vmv>K$IKGM%oZ> zcC@{BbS(-n5dL-J{8U+fBdU#-fzY0G&UOy-FQyQ?N*mv|YafXR{%UEHTm=UShhXE;jsx*CaHU|%lEB(~l_ zbKoy2=%e+Fclf*{Q^@&7}b<0&0OL&1F(XTeDlV7~1iec80jBDxG6H%hUM9Wg;mr187GY&)#6JWEjfn zO@0>1%OG49`Qt3Ies~(~*l~Z?-s%6f0MqgREV}qp0>)rE14IFsb%yQ*_?S`go#(K@ z%YpnEObV#BM9_d{DWw`lEov#;OUcs5PiW=gCVCNud}SYrAVdz4y*nuhsveMVAb*bcqo8T#}gjo|*7>{XEO_9_boQ zwqstdf3KIgOFRE=`=F~flwfE}(wC_*Yq>R$CzhyaVX)bbOZE;fohX7No9yfA>$?gvf9yf+0`Z~%B|vOqvyIAja(cRs zl3;xrT+z8-BMX~tg#P-rc=KCaSFMO1e#iMy3u`qqP&z^S=Rh)|u%bKcS0ypdnuZCb z@cT3N_7#z-hwAxA=ItRj{R~%t#&DKW0#bN8jeGM^b#%bcxXD^=eX3h7nog10v8Fm0 zowenrfaQ`+!)0u|bg4%pB!vu7sQ*$yIHSDlHkNGGP$>8K-nV7PXC?S2)#oDBN}sGf zu%CdoC~~{m(^N0UAgd6lsCfV$GmR?tO4@%uc6z8zJA4%=C0W$B zcPaMmS2!TGpfAb-8XKPf0%u<@@3mx!Vt<_%Uqp?0e%~VGY>o`Y#_Bn5K^RfG-{Py3 z9&(!DmDDY6>RNs#pwijv|FF0o1*JwbWO)eEdFR$1)KR-_xLG@z!SLDsm zlof@JutJuE3SQ12CHa%(f#U49=&`!h%c&X7(gT^8EO83WhkvGnX~tW&tmGD3uY@Qu zTD4zUObl*|!xLgB?%TTDwmSY9ayIxwB`7F{Wt<_oROWdm1WQc<{@rTC(so3`n-|9Vo zUfMr79`#cFNOz33*Hd(Jce_S^+L)5(9>&H|s4Yr8A+CRm);+aE zt3bWy_ap?tg&wA-prOg!up>yF|B4~J(R06U;WTkz%^!l#+S+8En5B`pK=%LUrY)*d zngl2AE+tSG0mD6F`;}X`FKz8XSOEY4EWOjJv40%06VIcj0uggEpFviI9n+mHG_bp@ zD8lx!Ncq@s4t*ju{krexaK@vok68&*{zrV?T%-MM7Scl+$h18(Wwf&TdiE6m1H03U z)nt39msy~iJH8=)d29;k#KQbM8myE4Ao;vU{5Fj|#k5+;LZL%lz3aoyYQVRsT|sLK zS|1}^#Xi@no+GCSuA_Ag;bV6rZQ8GyfA!J0>B2KQ)chw~86M1R>|R656i9Z^O-cOq zQGMsVD7#7%(sxq^!^nWiqQ+vr`Za4$-gN#gvR^%`WF9sZSQOzqp1fp=xN9=>w`RqW zRA`TEZ5^Fh++VK?b;GE}pw%Rqo9n9(nbPcDzyp{ zNk_ng05zLX{`YEqej70P4wyF~jI+F~%onl-yr86VQ9pbjW?M{1h{(vj_yPx#@}Lf(tw5yokz)3jnu>lrBn0;d5BCVgOc!-Q6BpYH|R(p zxgK;7Elz~Yhdh&do%e~bpdq6u8>V3&yt&(mx~cklzz@^X(uhN?Jy0?qki8W(sg4M6 zCGjQx7|&>|QEd(<#=|t`O)?ftLZe>jfPtzVLsm7`Zi_zmtV`35XY`Xm1HRKs{aAAw z8%0UizQ7Fw>!p;90&9`qF#ZD(DND86;NeBHYWi;V!N)U5ghs{q{V)0z72GbEEDI)c z2wC|02wE3U=*1#Esm*cy=wgaxPm_bl&DksQOe4h_c=6sx2xX!x2#?IHzRgK2&hm|*DWkU!6ClCu-8lEw0XZBbB?8B~S zeZGMbnm*0~TKIUZ)F%*lMnIe(dpQ{WN3jYH?pH(3g_9eh2mavwg|grdIIS4o$E)N9 z3MgFddybX)**6@LK@nhH*1($dgBW$?MM$0`j=;$^#0!*a@if8?!wtImwCAPdETMH) zDRHQj>1NUCJGlvF*3UN{UQ_A!_n|b89qH3y)ml~PefH#PxW16ICwF~vYU-n3Nak?G z{u;7Wi#3ioWcB#0fK)tf#ZuiMU7(ttydVqlz2NQCU_%O@p)zx3M`sl(&BDN1qXbX? zqM+kMxux?aIfpb``T#C7hU(pWZ?g7|GRA}SzXpH&o_XJyBj|6>KunV0=xI$#WbQef z4iJH5UMfI=XR=KbcLniU5Qy6jp;|zhGj&nAS-a3aiC%Myb`~iX5{DrYIEaG9z9+!N zqP}#HkIUc7{3$9gf|4TZ=`w6E^f-Uq^47cvu&TKO*dL{Qz*>Oz>=V=t4lQJ z3jw(zsqg;Nezk$15~Pvfb1#Ft2c_0%JZ|Sgac}U@GnfV9FgrPFyj?ccH-2f2^~Y_o z`Lh#pJ&KT4Ktbk&F=Od~y?78q$9cuI&X6<8mKStt=fkc$_~dHx_lc6~KU~g=V`%m| z90<@zYN2Jgq2v~0wOE#4pT1hfP?K_(_qVZJ7jQci=5af2DfmZEq;goRe6v2BdOS)Y zM`m2Ft?FJqNcu5xDBuTZ%QQ?|g&D2w17Ewf&C@ z!eg>_-yjVT6<-UQi_o^m*8K>(loIzg>c$z+suPKG{n*t$N_EN;a;@Oz2LP zXR90c@MO3~GLpK0Z{S_ebn-?Qn!;Xtmq0pXQcpVdY2vcL_1z9pL=aBluw5B26KVVxqf0jMJdt+Iu(_2IL3BkaiJ3-^!ZJttc zj%zJ$JICeU(%XCbIqPY;EY{ZMH*Ls?NTXlwVau4?hv6NKROW6bobi&;vqubA-}Wa!Et^?D^<$)pz$tCBQ3r-1+8Q z&TG@=xioJQJ9dzUgl1C6jo|EthG!`foLU>mI#enxO3#CaLHhx>IkJ}MdKh&yqHm{q zMzCIdRGaspAX=m_#8Bc>tVL8d<;$>mE!;c8eJ)}u5TBzpExk$6{iJM=|I5nJuxC$$ zs`4?SZH?ih&8Sp{GyX5G2tJXkD&1{ptI>XzjwE)Ia$+4BN|nj8vwRXEzddh+a90rv zbEUoM1cGssncZ?-e6MW76RW@Qd1fGnW~qEo3fht1qh2Zk4)~Ov)8R10%h;OhHJAXoe-1LJ@c!&>>UM(don{F=$RJ7jq~5@EcZp zm*>zUEs*Buci!JWz;eKXR%_k8^v?x7!F%(*2(kV3w1v2YC@S{)aOX>SCPK?)Pvi0E zzUZ>!n5TT_0rMerL4rgYifg=1RuUG)VHp4o33%TKQE@k@X%@xwzaIsu8(mLo&%^7tc=nIf(p**cknCpXSGid&z!*BKa?~|=au#L<5({_TE!mA=n3#8=fCDIXi#qe zCi-`f5&>S;vcUcQV$;5Lg%z0&VU*x8X@#cdjl)IQgRT*0ucF6_$pIgZs-ZwF)Kyj4 zA3y4Z&vY&5&#LT+sz~Sk8buf(YY*;i=LmAv=xt^X#*Yvci=?`UUeCe1<~5U+Gw6Bp zU}33#qDfswu~+)Ja;T?!N@~2?>E;O8N6++slexb+N>@`4z731034I&huxc3EqZmOH z3rNJ@rnMDU>8eDP#KR5dom=NbV{o6ytb>?T5lUG`N!|Y3W$H0M{tWX2qsc z0xkiNw4w9~a1F{ulDZG}X1EFb#6sJR8fv<0o<`^_93V$`?aEi)YHcO56?+dYvs(){ zl8fyOEKYA(6n@s%@-NGMjeN&a|K8BKA#X-J1CcEwF`bXKcT=_JAYgAW-w9VXWk1qh zNj76TpVWVC>IEHAm6`C22EQOf-fqm=xNa1W3=Q1wzK|QsPf5yRXdW1q#>VzApcy3b zpy`$dNedjYKKsdYFJ8QOl)aYImkAeLtHiXX%T_^N0`sD? zNGj{{<9MKw0pe%*qbOAPl3$-|Yg_;mm-i+?jk=7sfysG}a z)1v#GaWSnI1spN@$yRrSkoV$B#DH^0wY;4mz-<_U)FQY|$SmAFM)49YM>;Y=aVr@~ zBy-96HDX+-WGT`~vAA#l1aaWeP@u7etdnV>8@7beC|i0zb&41d?S?oN)r6LH1Gsqta? zqx{p+?^ERMC}~~b;V=n>Ep->xloOr@Hot7)=+N(62&(v=rG0Zacl4lGtDq}yZ@&3@ z`_K6|fS6)FtvvUFJrj^%Fb{yjhZgJ(Ai}4B1qoG`*9aj$ouIpi9|uE>cVPh2O!h;c zw5>xg(Jep4!RiBvn*L+=NgT$AYBGd00n?!49!NcwoQv!I6N8cuzS9@Un&ws3FdVuW z&aCZB#_B!fU{A4R(f>MRhHMHjhNyWYPa|kiXC9qYGX^Nq_ zT4`I`XE}X$x^d5R!K&R=isBZzU(~L9`NzNEmh=ay-4ZMJs0rBaI_2KaCP_J{!x+o3 zq@kw9dcY*&6Hf$nVC=eJ5Q3(9UWM{YLC*?6zLhCwTIJM6jiQTN)(1@(8w zjd2cOyP5HnE{lR*KGt-)EjS|U?_ZfG^!Fdby<_Yc8tjGcupW;xjLeowmv>8^6nR{E z731nOX3Wusas($i`=hJi;|J*)pJ-80tLIwE41oJ_D&vvrPE5 zhKc1`eK>D;F=$g^r8oN=EB#KtM;u#qMDcd`cdUc#@gV_q#M>SI z6Z{=luXAA|M!#|7>+2K{>nV%KY<=Q~SqX5!S&t2l^MhQ8r_67yMZ(F9W;PDvDHhMa zFRfqeZkD>S0eDHpWKq*qZ)n-oUBAsunuSE?pPSq~!8i*&-@KpU_&92e3#U>0HpKu} zQcFqo0-KACnGjt|>!y#9_NOOwjFw@qyug6>o#`y_SO`R7sDm4x&&!LsD;iK^peAJ$ zAA(9b>Xf+TF?w@x811=EgM(K`tH$ta{g0aacgu31ExSDFEH z0B){jP^+B99?Ytyfk!ka`5lvS9_ zkDvNh27XD=QW<_j-C5jG+Z=crrJ3seR0_u&f>Or5gy0pb$H?Eima4*(hc5gjzC+L! zEgQ^+pNOLt(9Z2oTJbWna7a(%pI%MRWdFxNPxsq>GGGcyy~3Qm`k3|qfm7Rl0&*F5p@c|Yar%;Yzz$4-WT zfCEmQTgZdmPCAH6Zhj?b>g04ARc8h*<~caUfD_5#2w!!rd`OD3bGfU;TS|eiBEm#S zcKTeKw)!q}ipAsN1>y0JT=o355IRrsGvel4(+k^cH$6pv8n|gytrOJD)4Y;KR2F^` zQ(DtlcTMkne8D-uWeMkNGNr@D76!WwU+7ml9l2uVn_8~C z2;gLa7_MD~wgFuuBW*XAuAUePi%hRY|D8W$g`l))-r3;>GYEKsAuxh#p771_b?~Y{ zx-BFRpaUlYd>N2S^HBZP)EYzxH1$J?`s2kgRL_NtP2tbTJ^oNuH7#1T)1;Cc`*{8T?R5R5*4%@kFs!6_fSpHlG-w8Sk-yTQsCx%r9dRh;~CTFJ5%`qU2} zA`8`_RjiKYrB6&g;mU>R3>tz(JNc&R(`WdAZ+(8t^n}i42 z%S8`?6&>wY%SSOz!3WpvoQFMRmlS&)yC&2x#j8EE`N+*H^)P7|gq!8fvf`a7^sgXp zOo3W{?^I=Ny&fPjIk_MQ{lVI?sc&Rq?NCRcMvVU?C-e*xyy~bN5J&sBC~7B;20rN^hU`HwIVBi#oKHc;Z$u|!5hW@d;zuBc z)DSbcAb9wZ`J|HUl4L>cAuj}d2|Sq=7sL*;CD{zt2VXO$1&1|PR+e_2>PK;Ds{ATg zsn(wEVrAP0X97&`U}%S@ij0a1W=>S$s7$o^k2uGYzfhsPknd1un3%*uNdWc*u(_j! z#(RLf5kwZyTN7L}=R*ZE(sQp}OqBk_>tIL@%@-A~4^u&wcO<;P(JV+p`7}|!wguMX6hsN^BT?ljrxok zJlk24(*6o%3kQqVs_;Iv621dtxL!E&KW>o_Rx>z4!*UXvA~qE3@s|&uU0OhGh69kd zAa?jBQySfPo52gT+9j(ehMY`2b~V!(8*gsmzq?LBu#ctc#fexpWM&yOLK1?*4)Qwg zubp|GX~mt?Ux^@xXq z{R(=1m;4!27=4Zxfu@&7Zmr-f)vnPYi48)-n5}PgCwj{jq0zW{G2uuQ)=F6$QCz37 zWj||VO+<<#yf4{OtnYVMZ5k3QK@VVTVj?xeNW~A6HNbHU?nHsdzfXaNfM22h^bg7_ z3BkE2wL6Mlgj|?KIQdbf#Hip7&=r8D<3R`*Q9u*{d1~a~%F%w>k#3PDP}**)v`pOH8E_3n_3iPsE&S+=2YF#F+XoJGW|N)NKS=H(gK+Vnfra)yYlB^6-S*bjEzl2i2~H|XcoQLEhG%<6q?Z}ptTxu1= z5uleS^+$aPcI&0jC1*cngx}c3(>c^xE)gJ=gY*hhFK~d?di%1$BLm-YbavE-pKkX+ie^FR6o$;$_$>sY@^?~5z4jvDT+f@M4Jle&~L=ohl?$$F2T z*;psQn9C8@%J=QtH-KsGr?~^}dGWnaek^Hdcrs-0OhQ;>vXU^7Kz3YNfgo0*3%vxv zyWo8{_jac+p|Fc}6d@h-0YA2H(Y0y9OL2H}(x^o*I=baWlrQN~JJ!1)1UQz&`2t~R zAEy2$i$TEo6g0GyB|)$g>ZP3Z+E)gRCy;Is0uO-{a60k0!;2gB(l=pZ!2!$T0d4s_ zB14rCsr9a&H5c9f?hp3P(E@j)TBd`-S&FXSUH&8Ln#3-*eV`O7BI8F`*PbBa5qRB4 zGF?Wsxx4EHlB?gX7iPsLO_`o&Js9&iWR1!V^h2HPr6dciY`Z?`qXs31MN3nG_5EYa zP&9*T*L4Yr?wJlNwTu)07A+1oeUlH%6C)2LXCI*zMCCz>Uj~0yCTZR9pD?H%LB3~d z94Z(A6xz2GWt0XJSv8)%ZSLoh9oJo9!|=>O{U43O9;WKnhwlp8Fwqc>2`=9Mc4zyySDBaY=p;-E zxi4?u@so;jsur>CGe91^WyEJzn0F9T;9ddN1-0|rdI6zu>jPNmLA3<>U}&rI?KYEw z6cN-M0+^{T`;BkE2=4z|3{hK)zOUpT<SrlY>rA?^Y4o^-_vRJ83hV}2BRAkZ;kpCWl6u^#-j!4K) z2Ydu&MHx|*fYYlDz-`EYg^w9^w*DzBU4-zh+eWG?sV?Azkc?qAD9v3_&Jvlach{^k z76_ZXivM$;ER5wPNwtCD%NvK!lhLv4Q82fZJn^jQ;TwHC~PXm217ZiPHad*(th4PPt%#a?W>ov zk}GTb!4wW(z1!EaAWHz{d6<}hTyXG9E}~3rs&7s;A(wUj;%H8%__}+sId)JO%hrnU zTWKxxP^;7Al-F%lZ4I5sy5Gk}7IfuW#QmwH3oC+v*w8vA4Li8_5DabREh3IS##oAd zZTJws&-ICi3=P|6k9=L#hn{Y;%H7g z-}U@yUMfVhHv7aQfs!nFi-|}aEgRueKbt7^^F@2JS(J7#Ga<{ys)fljx0W!>uGTyD zY>VBtsk)(@%(~jnF%OIv1fIXSy~f~_$oHC+neZeC8ch_Y^uvj}UeDVufj#}|(mNxz z*Xa7*wXVkmZxSGa$MyR@4WtS+Ho*?ZX;_N}vRcrUfD<3m)KQVKW?0at>-WwIbdG@M znn>S@kWqV{XG^wftKL8Isrr@$0KMQZ23o|#bzjeoPlXwoP0iHs9ZHmOO?i*Crm2Wt2#Ah|ZT5#Z*yK7cwjs@)d?AQ+i zr$u?vEt+G36+INe6PT8lD~^HM&#YEd?4-3^4rUa&8Up@TR0$GENF0HBM3kO(%(@-u zdif)#0kI&IR|G%;*s_FP|ItdK*D0@@F^llK97w3Ib&UAHmz9#S+R>O>)pc`bXXEiH zXMdBEOFYgc6kOf>;k8CIzG2uk(}?-0KAU)Yu0ZH@3Fa z)zThD4q?}!gyP3&aG|>aZTWiT1Twyw793CpYxoz2!zcWz=}pq#gn?253uPY&hq(iT(H%Zr%AzSSW-vNdNs51EKf*jlPowX~Gym zlfMN#znILyxbgH$a#mUUUc)FE3n9ECq->!nNe4j5($bC>i$7)vqFdDnlV!M-r}sgx^l-D-XuDME|ON%sRIyJ{pT|)c@0y_u;95Rpi>r zk}fkzK@vUFH`wP}7Irc|BD1_kXoa6nI-VnSC({D>s%qUFbR+&uuBMN49zTzTvk`liQJ_`_TQkEF${ zbOzC^_tCTZBcmkWLyv~9Jm6;sR!FIA9o5MM8X2%7`2z%LSnpQ;Bhraby?v@nNoatb zi)2dx?I!!Rqeo_spIsV_ukLxe%QMtDtUntKHnR^xXoODMdj2+W5JU?xyVh)ilWdSI zbWvwi6i@cL=;6-Y9tBPYDcV2IOL=(ii3+(d#EvkFnEsVj*9EGHe;(!84R7iVUu$NL z@T%c25Alk7^z`veA!z0v^Ha8iz8Cnnv^SUTP*r&yf;CYU3!tchV-fYqVS(-zbWv_= zsjdMvFDob8jM-sih86IJL)o+hfxT=CqljmB!En@!% zAF!DMl{!cRZTH3?+0(o6zlDmh?Fl=}mk_Ro?{cU33W!2OWET0{chopK?mP;WV5^)( zRFH5bXT=wPw(9wg)c8_gUu1ZJ2=6YmPyezj#sX?}2J2X;dxP9AAzkRgX0`F%8Z|4eH@{U8oTH#qEZ zKc}quPt>qVQNQ8xMoz|1S1+k2{o&4naSVbWmw;b_bpYyTf$}6OB!yrJxDIN)PLQ(c zt8Cj|?TK=6UlF}d|jihu*iiDJ;w1|XscZwh(A|NT<3?LvOA=2F?{hhz(UEeJJaLt;Ly6@{c zWA9_HeCr*WmoH{}CnvWqGn#;j`ZyKIPyb1G^0Q+yb$iZ5)t&u+*S*`MBlPtj%6-Nf zs zMWJ3sEc}411^P9>{E@v@L}yG3&EKy>uLzDAo!%Sh()Fk67)Jg7e z=9S~Sw~^Si{PP2r&~olveY7uEq#0vaNR}wtB??)Q)9&g+qQjr|hg)t-NU{B_d}dT# zi{)e^UT=fctUMx|AN*-O9sLo}R4j(#7oe{IvI`3Zp`3T@-3=pu6;-rhV~{Tai88#R zqTxPgyZ=+6f}V3^WF!c($Us2>TQjhNgXjj3EKKAd@){dy;D>4PGlh+~*~f%l-#+aZ zNc#AIg8{loj*0~H7a`LZNyb0G!V%6_v3a%vSWi*qkGX+K12s_yfn}ZbS zOQUg^Y?ttB&@awxQM9DKA2d-@snW8cKRr*qG~g4(uLr*XMAR%UTAqsbxu#v4 zlgd%2En7UI%lukmo6d;6o&_e}MOh11LY)(5O2$XKCHb000vD3al~GU8yI0Prlgt;| zFr?{;HM{A@S1FUq5}w|e(p##Hu4lnhl8>nG!LJD`5_hODNkG>OzZ}GKbe0gzJs?=B zq=6Kc;2GYl73T*7!G^QGlQzD)Y~&>2XdYsr`&YfTiCofdhx`)BOrvSIzVtjo3}tGB zylk;Q>TAN~8|k7v8j)5=H)DJ5#&j*Qi_E^<-3%W76V`Zp6M)_G9U^n%L_4gaJ(ZJ{s_l!UtOIu~k5PA$ zaM`bbWw~pgr_S*q0pCbj(}RJ z{d=O9w#WWd5_Gz3zRyz`KQ&(Fp zH=Ibh6%_>Vm^1{E!MoGo-0S-0{LJ-sc79$su^-q8z%Mm(cGfWH;iqRVXqn0JL(iy> z$MUB9&=dFcUfkSF@VH(1)Ym@d^8Ni#((sktS;;xppJk8S2oGcXtgVaf{ER@*!m(s;3AoyVQYq>+iRpq8am3{t#sw zeS3&Kb!J{G#FV5OftS_jjTf~e)G7Qus7XmtcY8vfRQcTX-;)G}gUc0FoU}iDza9#j zOWDh<^*_wAQh30yJKk@~>0Kj#m*COW{*!;cE6mI1$coz0%axjb2m5NBFJl#iA3cfz zjy=?bO*a=?|N7MZQNS#Y$S4{Q2flOi_Dc1r&)!@k+f=q8zK3Qd0W5xD-lJ>~A4eB@ z5GTxjc6u7oG+~!R{_KL+d^K82P5VKQ3;oMTUW-BN?yEX$gRR$BQc~+un_`K2hjumK zVYoXIf6wcii^s$|A)_~LfPMjqYm6&91z%$|F=tWBG{?4P6y*y;GM&o2l3*9@7FEvJ z8pX%3z{#~ukG@{+{=HN1PD`*vSlJ%*Go^)xQ=C;9;}>o!sXnNjpG>jXtvb*=b}!@X(GZN*y||{(}NTUSK`F`Nt zriQmc&x$JhQ4Em0kUCYx!m&kN&SgZKTzLsQb%Qa7tA!RRwi;Vk4zq$Ys*u2a4F-MKzJu(Wm@C$;md zqv5S;?W+VD>$go_XOS8+Ui_t|R~y!if^=|c{V7Z6zDDnp3lnALS52`7_J+!f z@($mz9VW)dH?k8Xc}zW)i4J*_X9wuPQ~;87#LyB399J_f*BR@r;I9ujRtR_pw-I#F zNFuO+j(k`gQh0FALE!ZHG;_p>KIPTwN~az^dw@jFEOW)Z+wpCd-(3Y$n!-3*^|a&5 z$OIy0gZCQ<=g}_eqVTWc==}b!mlANWV*Ct!h|clkb06l+&-v;*VT*c`)899m;S-r0 z)BFy*hl1bjl)YBq;P@%&&JfzcdGO6}&kHH?z74&~sblZi8`fchlC5!FFXS*XMN^M& zeS0ll2NrS}FxnZboQaW{e<0wJ*~R?xTTP9%KK(f5rb3))Oi#gO%dE#rE>Yrp2O%7I z8=|A5BMwrFo{jq#Uw^(3%R&7YAdh=@q|#wkr=O* zMb5qB&xSg2Yht2VZhpYj63=?VTRvn_TufjOu9ix&@V~POmUZHu>J+1~Go42~SRR>? z_;(CVjO1>Ay9l!B%DIvK4QxvuN9VW4qx~hIN3_4!w>+5Vi_7*RyFZD>Toat1?Y_kR zK1)%;gde(O8}pw~>9DrbL-*P2L~!sw%@4%;x>m$5P@U>@+1*12FzIR3H{g~$Fr~sbBB?c*G6H= z*RQ#c%2lju)~i=8qqghH(l@C%0_w}DY`3HB4)aiArq#5b7=O?y9RnG?WG_@nAgNT-F z+*+=(%1|MwwBdH(VDQ{WrH~j}Z-@kq85|6@oTxwOXkQl8Haf@^B@M*a`}OV6$9PN- z53!^8VqBlE;shMT|5N!zbmc43@HLktok3ay4$dqhQ4Z6GBMh0IfuRR-Fus%@{dn`P zQTvT+bPw?pp2ZCzamWAWLM2_l#wB3&!;oVvAz^2Cx81J1BdgIf#6L5#cNC7HgVNLC zh3b2uTcs|@{m^rRMa0z3;Lk_AA|1Yqtc{J0^cj_| zHffIUp<86gCwC>TNQ$lQt=~eFKo76;X;`qU4)rqQ>8uC|mya9Nd71R}uuN48C2Qo~ zVOq{Bsv&cxFsn`eZI3eJ+WUmxV#rcl^8nWXj=!El@@>q}uW5>UU-6c$U3elRbt$Z3 zVgg3bUQ{)2vX_yR^Y1I^yjWn03;P)~CIHA_6u3%(ae)xoBCVLrd+yE>EhMb}sR+2< zLij&f7OIA&I4K#B{!LFdzXzAe6V?rusLeMP7K@cAL-T?@sl0DuzR|~&2w)z+u^U<} zmWs*nu(1C;>-A_AcUh^XUSY%|N~UzeqJ-?JwBPdilHic3RyvXwt}rLRLnn6(WacB=~&)HkNTQesqd%s}{vxGFYl@hv-6Y(&Wy zyjIP(n$z(J2rOM)wS>FlAafLqYI*uxo4Vb$T^Vb^qrG~6>xsGbrak#}cDojU7`RS^EnlOC6$kB*FF*THb5 zw{DUPcpZu%lB%#W9^8c)x3&BxxAN13%h=-4`5%_On5wa5)m~hpv)p>UdsWL4W0~kh zL24_K2^4Jx*k7EqHoE$jx4ymj0h2o8dD;t!vemc$D}sn5Cf}!8tH6R5rydpSF;%w+lT_6mRg7NX{- zG`IM@tb>s@SjfNFvnWQ3zrDT9nD&$jh(A!Dfm53BY^)7{gyJytSqz(O^xU(sut0$$ z0AR@-N;CWHSP-Bti;Q_WEyN6gmgZsht$J397=nKFo zIq(8Tkj+qLTcJvdn=`^np$xfO5dI7t4jb1tgT^&+IpC!FNc@5d{4KOY#x&T_CdyE2|p=NJ}lP5k0?8v9zk_&X?gyY z48#F-0JH|5HzF0cOWz2xTQzGk)kuDDDQVOkEKPL;7W7cr?bg{! z46(@hWiE4BjR&4 zJAaYU0+liA4O>c+yX{<7KrmeS;|Csyh*wuvBlxwH>XxIre$g*8-jNu*5|?_P`R*YA zeu1(K&kVq?dRfA9Ig^yZ`T?>P@bD#dx}#B1sPs$Ax+7Dp23@?A=9Nq1)(3&gX=#x{v;>UzzxW#}EJ zQK!!P=5+~^Lq%DPC!S8l4-ktg^$nC26rgrlRLaN<_6^$PVoz3o zg=N}g%bDad+$o}I3yHyBw2)fpeBo~*t9JKDq$$iC$Ao)MAFo1}mYUSf-SXr{3_}v! zXoj+%JaOUOPkm6+elT!ruu!*Om(oP!LXesv;cT1!9;m9&wuK?Tqd?hz^8d8}J`v** zGWh-Hm2L14Ji7cnyzkR;_P-bJd+w52040qw!m}2sjCDekr+c8$Ih>)8u&xwkryOEjwnB` z=6=<#=ggvZ8;Fp37yewOoX$<5$NXcDV0)Tp(QT; zRia8_uB?GlB*i~ze42ipJ|g-VH=cYMe-h5{qdApVLDK0Xf6xouTqpFc$B%!>pF?5s z_TKU*L*!T`;c*|GQ565IwZ|S;1taW$k({0xC>?h_CNm%yib5hyYPq5*5lxDmTq_2P4cygFTiz&2Dk4;BtH_+O?+v=m)@j#vp z4$3tf+Gu>bM`@VJ{m;9SZdmpUP9*d2rM9~KCd$zJ*A~Qq`r(Tw>Vd-P56;x7^_PRjvPvyk7m#RbNW9Dl>fbPEj{^j)itJkS~#gctg4`#`XP7MyM@TmPcKMwWc)HIiVZET z9iU^`!O!pd{Z?i5L8d`du|1l6S&eT)atV>kPk#uf1|>YFq@1bxFRy>B!#`2WNeS4} zhSw0YeuzrNoWEKXcG;PJ2;PEBNgr~+MK&x|DJUqwj`EJ`7$WNO>SD4*9u}m~_5+IO z6VAB2x27t6sH&m7hZZiwZ3bmkTwI(2HilYzbi?PJu@^is7V>7%s7J6~c#LZo`btWC zce(eH_|g413?1rc|CR?Idp@*Dbb<}7^En!(Nl$rWhjhJzti{W8R@Rq8EOe(vEE!Ah zkl3`aWIrEv55!QKCoLVa)2ci;gV}PqzV7N$iNsx+By?xz^shu=52^Q}HjPiRu&e2H z<;UAkbu4#atPX*>-&#IPOVA0iW!OE;PnVE$&$@lp`4KFTh&;?4j}FILy;*FW$$J;Yx7Ba!oQU_#CgBsADl`|CXlrLnVAXh zvy%U;EdzH$nQm$HUAEQC>=^Nx1FL6rtdk_IE48wIy(b){NZKVho1P`#)vOEJ6SYl! zePO#u_Ks8IMc=tTK5aE~{C_U)m_Iu9&KNrHu0=&)7-TzBRnr71?DqBH617yMCmT8z z&#vE&H{G=WqtH^qllI9NC;W3~7lGgfUs{2o@6^snqeEE>lbaI z^;bQ+$7l~OS-EMt&b67$x^JW*JJXG1QL;lH;wo}}<-z7t|=F;b)?Dp|eJ@ALArH2jY zJcBeo+gYlQmC91lw(4~`yiv2S(XnnG(B4)K)6(7vl?WnOLiAu9-{F$6Aip(0k z3>`V69q2t@v1IO1cQq_AU?**-Xx>LpRK7?0L2jg5m6ash|H2kr6vrng3ka5zZ?miK zAtEwQ;(dqt@#(3>t5>SD#EKgQW8d#{!!@y}?ZiYa(z;4aM%7FI-W&yw^|-bscj2Z7 zhAtX^yr^)|;^!^WbWyQURe0~$x$yIiT_-& zizd43dtWaveYE_w6Z4O31%0ff*Z|FBrp5oje{^{*LkxOWEXZNIx$y_7Po8j55MqxC zve@qDS6$CrA!uR#W@oF0}55a?6yH60CwqvB@|FHz$?9cQJ%Z!eKEEgp}?VJ$Xc z=!ssc*3Njx5JGp)kHsduXNjHs!^4gL&M6PrJCY^s3XT(=nQ-&4^&q64>zwp`B>YsYKsPN;$SUazyfxadQ{hnJ`EbE9vKVs(TJi|IK# zRvL~oVW{unFN*z4(ctHEMq^!f*Yvf!6Md~!yA%0eKz1#u8i(!XL)9@lv+g@)&2M^E zcwpEJTdi-zF`7S$r!hQrIaxTpIlqN~4ifkKPv0{$wJZ0TNFQyGo46&7ck(wF&rPv^LH_QS8c$B-nHhXC z*Mu?VD;emzltJZ1#xwK!-}#*TyTi%|9kd6UaYsx%;l+n9YYc%b8v|{z^^<~&f#B6RFh1G*nQgeX@n8@(Vjf+Fg%&W2Sd6%KePS`iWKE?0&Tg z`}mKG5T5|&PfR=pGiL7^XHGnK%QLbw6Z!$2bg!Emy9*a7h0#5*=0UhZ0ffk@OP-Lz z`oewM#9*GYYW~pfEmuLj(g(vHa36tgSP%%Th-7Y)ciBMX*XFnsZ-!e~MU zRLEj%DQE+a#RXMKMxPb9rkvsRpLFW2(&1xr;pwu(-$8D=lSoqhX-|uw+j=y?KK;E= z3j>bIhp&cPKVR1B@h+ndH@_2)!+q-0xM)nV%d$WCS%N@fkK+#Z0_e~xBL*{&5U?JQ z^u9~|^$w}|lWl&MMi!{qd57-(lDB-nl4g_boj^@zV`=@fz|NuC?d$jNth;OBpWbQY z*Y~itsf*WCzS7=`g-?^OnybB}z67RZ{$P*~2#7I?F3B z$Ab|*D7l$-suN5esMouE?l*&pGhAF#fBul4j|r;sj(=0=b^qQ(U#?qPY~LIK@a}ye z$h5AwE`UIaA`*b|&*WwRO#pcUoht(=M7YUIQGXzrL)yD%zs7#@o!dH#YWBMrJNXq3 zf*WoBk9Vc+XxJ}DN-1AfOOF+NwF?YJeU0)g^wmuw6%R^7wS`2(C=Jh>Bhfd9RG`@Fi78ug$%|w>IdB4gp+A_N!xh*-~?W$woDxVR|=Fh`@edPI~ z$^enGqRo*9|Gd>t+)C|#{O9lez1!HavUrp}d9{#^1&Es!LL>)Gv%X@bWne%Uc3)Le z8%#o`E2zl83j|W{&Hlc%qqYsVi2A8DPAC13=f=CiousAv)KPbh-YjUFOR#mO>>W_^F~; zi8xP8<(JBYa#)t5BswojlFhuSVSl4n>5~+S+Ei)THdfH_RsSq+t{%TMSsLbZ79Mwk znvvSMmh(;-T1M*prbLSTFCnYfafRMtefw?Co&v)+rV2P` zA@}1k2-eaBYyi7(Fsj0nr@@{JF}yJU0evp9cNzIT(B{L$fdVdVnSq_7a~M;<(;EIADmL2=I5nVfj zbb0U2dM0Uy@9d%1ti$rsiv#;>$@+N$(A8_Oud~o1{AQ8fo}OoMn;K(+Kpt%i(+pUU zrjqVrRPo#V+E9X#8k8V9I8r=FsT5ZdbYf?_(o*QEtv#YGQu+~PiC@5bv^!-XYBM7F zGn@z@F69vFqxz9zZxmyhXhYp`Cz3&zyk?dpQ&?XK)eVV+eG*~F1I2_${oa_P} zO;#o?EsYN?C2<1cusfGrKxjReU5;?oef;p1j7LG#v;}unhsI1)9(K=D+}q~D8Dzv{ zqRV&FI3kokYrlnM{G4NGmjii*^s^08>=2acP1V%P^>}m1USiT{D(j@cE83)@r@TL3 zAF{f0kUU7pvx%aew3AQep^k#Ih(uxc{_w(F&|KK@h=m2+U=@3YD^x0bvGRHFhG0@Kr`b9m_=jvIe>V^0J@p$>uU(_ zlZ65iuu=#L8l2xSgW!uBVF6NUD44xXZaz2Ri;ILiDaT?WmySokUjeQP6Yo-tRM0^m zy1;b?+?U1EotcKVQu5y;F54`vpRuKV$rta_{O;h5>+wEy5!dQDmqZy9#P3U2A4>I+ zphsF!L{<1~lU~j4$L8|!x`R4LqGX&$bX~zkR@*GAH{Q;jrOJI)b74}u!MMP!SpR3j zZb4|$-9ZyrEJA)TZ_@avbmWqYuKvrF_|fjDlt**JEv34{$3CHbm66h~Yn%gSwK)Uj z@guOYAcEr*1(E*H7Gdvc$ZGqj`-Qlgm?y2G}RtK--rORV%1QHuyO{^cv?lrn^k%KOoP4}BOy;ak_ zA|(&mx~2JTJNc?cbeKITYI`M;(z}N!XfC{Q1&X8)Q&XiTQD_si$l_yFVo68@4<6f= zyr(*M7v=GdxywcX`^MNCBtpORgbbDiFm;n2b-*GL-U!)Sy&9bQ%swvs(4|4U@Fe60 z-0yY5!>Xs!k#5Q*s_3D8!pnCy{!0@;(e5`J1J$|eu#6e*PS#HEMT1%6xxfe`6P?le z<~lL1DCVD_KS<=s6hD{NNBGvI)8q)oLkYA0u>1J4vdPo2PI(HTL;}PR5tjw=UJwQV zAA$5`M?(n%D1pg@BDdXTOH|_I&vK-h2j5jE%G+IKQjAKgrHIqKK2^x z?f145X4NNuY$o1Z^od^gZ@5cgHcWe!rzef2ew04(sr^ASJ@0Ng7Ip7W1|i3W;gFb z)Ml@DLWFczP89S}vQc&V<$>fg(tG%ucqB6J2b>D~FUKe$-W-d$edX zNQBrPmb<%|>$kA{C$kmB73fFfyUms%boEuajytP@;|q#V>V&@Yf-RVSsDLY$l>fZ>`g6xXw;0+pt(weS3nNjSEy&vGV7MU+IJF6Q ze|t52io|D_vj z-xTiAlt=ZZ98P7-23L%HfY52H>mQUSf=dB0mzDbg*9;&#t%EoSFq6Q24)lX}3Q6z` z9eBZ&gr>g+?;*N=%Hzx9V?n|4GCm`H{bKe2J6_V3#4iIE{-(81FhNxI6QX`h?IUHeb%|A)Jw9!S^&I-NrTbjqRG2z37tVnM*O6{y|7Ll8r)IaX`k7c_Gr_ zs=DeJ6p4ASH$}FdMTst%Wsi2!vEes|jpy5kit77%R~Hpw!l44Q@%KY)^Em~h60da+ z%%=sS?#E~;YuSroMItV`@^V$*VK(6*smXL*6bbow9BMXuQSX@Sg@B_wHy@wgONh^6 zqh@}R7mF3D$6Y=fO&q5fg3ccGjZWA9u*uBLEc;4$FPQ%ZLV7{O1ev#0jQz!2BK!IL z1=57Z+-8E4qXMCWoNx~>3V(LkU>IBhEyDk~b-#us%ftozYkc`2#RWVX4?vMUGBNQU zRNv6Mo4dQ~IB0yl>Q}~O+R`3zw%S%8#}3ihdnx@|MSwh+ob!-dMZZ@GDR(R*CMK)n zu%90Y;7#T94)WhSk5o_P9o`FfMcj*d%~Q$|sf}{gFe?N^0!GRWu@oti)S_Sl+sr(n zyTRV|JcqYX#zV`pIjTAd%07Ig`Vtf?^=A`z57fGTK$-WjUUOhi$dI4U?(eTK|NUTw zzdW~xJO^2OzL;=|f;!F%A{-D=4u~TIOh|$sy9A!Mr!@%93Xx1WT^S0#pAC);H4UX$ zaHD*3bC-)Pd1Pl(zWO1y{S-FR%W5H}G}ZR4{fOZ!E&AU(hezBz*HW9KGfc~O-E%*G zKAeXxYwz}IEj2ss@sk3a)dq}ecQ-T6cxj36_glq~?%uikQ;j@a_FVzLfBf zdr1lf2L`kh_;fPFHrQ!es;0|yL!bU3dHlB>fIh9Ic9w_A5gZ&Jn$8m_`5>^XV->fBC)FQ7=JW%!XndJC+V~DVe8C=W*{en4ShG32t9f8NH3Vf zzu^B{W=$#jPnK?yIQ$*b%JG*_gK{6z?#E0>bXC5;oRh{gwU}9_!g3SFURrTT-y3H8 z#_|MXopy~|b7iDhVjj6w_`bD%xU@1%C!gI7Es^}o*5{BU z4KU@J{3{VtExJfhi9?|f1rHbCO%dc0NnwusgwfVZ9L#f$Ig#?FmVf;p>aGsPvAwa) zXhUg5khY+-UOGJ{g=+fL)u*_$is^Z8$Bye=@|cdj)5W1}x;b%gzy31!8dNSFJ3M;U z3`(~Ls?1G%@Qe5|_7G+1aPuvZfvWqLcsiJ3FvuFj#YqL()wemD4F-v0E|sjHflzV9 z`t$Li>*{hfr1@P<23%A49~Ur~18p4P$^u2*KIAt*!lk*74-Kf$;P8fa`^i|yE&A=& z2Kle?nUOu$zZc7RZXRw-t300Z@R{Zx5i(U7lIhT0T6}=Mi8ip6x8AhE`9gjUd ze8nB>iR=CbP8OR6p^Co!lq4)jhw!zWjhVB`Gp_E8{C|d*_dkW!;Oquo z`mTgIlhU>=IR6FWK))y9*JpC&%()W4-v!J!;`ImL4Ji%g%6U#?%ad*oiSo=lr{})B z;~9t>qVuC6t*ay2gl$669qAV~nCCL|QE*JL5qn+CiX`vxY>X=8xHWu_+fG{|I&X-) zx8XDN<{6byxh_mpK#i-LDXmhc-PJ@B^?ZD~1ktD6FYq_rPc*n78Z|!jSt%r-lI{yn zzQ^IZ#6Mc_nui-^Sp&~+_>~KZ9U=4s$m8SzN5TOR%*Tlh+!V|8{|IFy?;^6<lPTtjrT41?OGTEUPp zTdUYc-xfnBF)8mE`8p4 zae<*F&d1fc`uD^~Q?Dc#T4I=9BQUEVxI{!9()wg5Clw07!3xXF^DMmW&NaS^<*KQX zQ+%=TK9>BCv>r0Ww8BDhie{j-gUc;l_YbK`?((?ab426=+{cJ-7V3BiIh_GOOZHH~ zrzjS4LVKQ`cv2eAVeGFt@mQFIjO0tQjtqotI>b0cOhiW5xMUq zrr~Xxc~^M)@qZnIpc9R?VSt2HAhIusKe44{b&%Ri&KK$^@6dT>@(jfXCyzA(7B$29h-B0R&5c`w+I}rkwQ2mW-xCCeQWhMR@of zP-fga+J>(J9FG=n-cS!qp3y>r>lD)6+Kd8TlcurH7)Dg<`}#YFKU%7K?0q$!RbmIy zW5pf!VqyL4?En24>?trCf>+hj%1ZXme>yFyJ0XG39`=z;9+vFlNKQ4~k;ZJ+Hj}}? zgrOT0?#dcRU!MvfTgC57480Vf-9}|&lU&#<{N7<%@XU&e?4WZ#FP?Vf21Rs{0yC*; zP=j63yJ?w|3hlxg$R|(5P4ITRls=g!Bf-5&orLaPwzW@D)b4_ zHed?7k4;S1)LAiBCq10>za63ZL7Q#1m9`K9DwWI0<~^$$HBTB8a%QbMW`?}~NwbY+ z}CVBqv-y> z79dW@C>W1>m%LiA_V4bjNp%iH_PnLK&Xy-tfmmJsq|W{!>MsgkmcoasU`Wp_u@pcZ z?1L(jv?JR%5$SXqK$C&9^)I+>zUQPyN%qJ(cgNj}D5h(~ezRkBg4J+1fQol~p};|a zw&f~^i7qh|$|$frBNh*cw3OAgJ?3AYM;yd5T> z)?xcX7TgJ*Zup+zw*u;CP`MiusVDy-!NoX0c-3)XOmBjOM0Vs#`7^hApoe7uwHeo~ z*g^5bnL*~&jd+?wo#r)M`;`mfU;18^>PGD$5?>}JWHT4_Ouf-hPEJ63)o`HFmHyd^ z@mrrJ)AB(grS(wVgdM1D`aMT|`sjtkMqr^>gpF}tC(n=SYPx=_fWH0Bp_@Isx<82R zd)7dnVEN${N;8qFqkw`^sc$PO!=#i7u2`+zz^N5K<6553%4zrBO3ttE8~c(CDXT&# zjxfG}2NI=o#z6?aHaK)Yj%}3Sb2$an7?z*e8;Y_l{{5T#Q;B3i?OY(@ZF}Fd=nO+6 zBSd9VUd|0K6Kf0|JyBw=Kyvo4eM(LDP)jK@y@_}=^^qv7aC6e z;Z0>_wjlw=GDu7@t8!`g8{9I2C3SBBe?~;^Leh zX(UJxhDVqc{KyDri%q~-+avRFlHTioRUk!eL0!tp*GVuTL=wY&SB&(s=CMGQ8l;N@ zNEi}hDPU;}GY_^0*50H$%5s^`&!SE`*$*vO?e7$L(tg)X4kSExrj6wh=aJxI`B6dc zJ?#?dA6(Iofr9+Rro>ROWhuR>ze7*f%jD4YUzy>18H*2pWXe%U$!?Eta z2ncutE_wh>!48QJ+_127uRJ(p=lohTZNBppxIPw@x%ylYNhB!kERS`Fo(ZatVL!Zv z|Cjd;Y@@Gqg%1{gH;m#e+G`TZn&87@*Sm;z=3#hVoT+_6 ziyiW=YItv{jRl;7TdJm&he+LzKXB13{2^t)QfgrGanKfVO{E+^6v%2&irPc)PIv;& zRpR7PY7Mx&ndG6*9*(u~{w{8TDVL829IPuEcv0LBW>^@YZxA8&!nuhJ%IBRj= znz;&jFh6hncf_9tLSuXixB*VL%Kr^_<(Oaf+3fFjdHx)uZg*^cr~OId{`2XE$SZl| z>o$L@GY`J0Rr#eq_@+;XTKCRiB7ui6=};6;>mRmZw!8ytUDj^{U{D|;doP%kL-TT%p0>7=|&rr8=Hw-3T`^v?~}I{R41} z=(A!1W#PR{o<C@vwCPy#{BOB;Sv(+6g9ge+HvmrNOturwEy7YL~j+v z<}Iq+t^4m@iV*FYwrs&^sl~ZyZlQ~%nOQ4gFA-%58%wq>RrPC3DiQsLl_g4>00tq9 zM-0PWemSx^tFP&kOxQ_BuWyRXT}@EN3GgqtQfHIT=Uok`c#SKzZdRHrhh*2OC( zaInMRDF`MBAf(eyG^&x%xPC2JFLC?&t6FNJZX*o#)o53Y?wueXhYBBv<)5(IoYf8WKjyL4G9BtDUy`7bNK>gNlXE;1Sd}G>~a>q`92% z+g|k;Sz9MF^BYd?uzL`Bvcvmk=5oa0tku@({mhEI2w8Xb!%$g?p#63XDEFY1mDL@{ z*JfV`R$<81=Rg3YKt>AH6tvsH08(HlB{uVee>q9Np6bPRc7LhL;06s6n~{9`ubFgS*M zkA{ZDn;|ArC-V)AGJuZ2rqB0l??$Z(s*Q* zVk>foCCf>^;K97+#@|w^0D>P|=53+@!Zs=d3E%hU%exatedU+dT*j3D``)oY$WM83 zS(`;#{E1IbsZl%NHL=nQ@y|~CXZw<<>7Njp;t+kab)vg1AZ8mX|3y9C$ZyMNUPgpg z{`qqTn6~WBw^SsgYI!@i_GFpd+=4@DtVsPsAQ16zq0B(on^^M7x;~wi`m3P3<#dO_+*9k?>)0Hs z* zA5uRIwKdtl7qypH*As?Bv`i1SYC61nUwoPj8hu04xAS|UzpXGdl0BO)|1`2EN5FWf zm*Vi>52q`7u)2a30OZl|s>;5L2mFVoBXrB)d46xO!zAHLP9;1gIDKcIM z7t6O{_gI#O=FH`Xd3boXriWKoS>Y?t(9>gEzC(JaShv8Fgfd2!siCPC)tg)1lJ!xq zj2g+_%&fPl^0e)&|15sNcH(~DejTTNNw|(F*-}e}B8!`4o`dgO_j+RhdW6!4$+xI{ zqqD0z&bZnusGgt4SUQ)8aCk>zg!Jy&&TQwE40shGNfQ=60C0h#Vf_#HK)Kpz zaTGvRWX1$xRLFPBme7ao+)GFB;0d!w^6D9s>xiGx;&1q$5Ofm2lEPW9lSFvsQ@Ubv(aeXz=Dp-rDz&5HR!S7aC@L~wRfMq~aO z<^~ghcS0c6Mn&CPZz1`zQtv?bY)9_aw<7rg^yR#LHTkG822N-^A+Gu(+R-<6H#f%Y zNSyG9@1=RLR|m-kN^TML50P>0w=jqCu%Lmd3&ZnUw0kyp-~^rG#@jb+f2MJJiQ@^`CtH?y=xjb_D^YB-EjR7ohfQ@*R~ z@{=Iwz0)JLu4Dvw6=+u_W&puc=7ueTNMaUDX@nZMePuK zU)UE}PzZCkA#BJxVop}1I)SY9a68WZt#4{_pd4T0ea2n*x;sQh#YLn2_am~If8st( z;PoPi?%|U{9zZ?OoHrR*kg1t+q5RdsRR7Zlq4?4iUvI!ww3VQzq6+$C+o0i{9ZC$Ovh*so9p>AA=i9-)UaO@a8B?F3ZemBI!^bd@et$2ZttUS z|7E>@hN@1_c;x((BTT1K{<@EcMM6~#4H4hJ3vKW1eZc#Jlz7ysM1`zqX9RC6^tg*3 zUwMDgl`CAzJ^J&*hY~E4kf?-y7c#Fyyd`kL)Xz)A|u~1s~<` zZF>i_3RiReSuB<7_r@-5Gvlmh`5*u1!r@Hlk!;0rWgKGnY6|!-e~vG&nV#`m_Wt1U zev%nSAs3Ytd=64Ra59H4&8}Fpp==>6Y6!5o;!>2lyYy2Z1##jHw1&n8qCX;(Q&_19 z{=N<`3Cq97NB8NQnmoRA7T0RLe_VUqW@`%pMF_o&gB!UxK3;M)x??F$)+s*ngeu;P zGMo0VAG!AhYw|g#Lcl7y+Wo@U^_oQR;luFi%uR9hmiZXic_2?1&6SIN&F=rm>+M4f zGhIZGiK`$od+-TFKMRUx#6G>}a=L9WwfU;<%}EJ+0qFY?O?D6LH1}Z;KlxKoRm6Zp zJ#I5SlT)fMA+(18{o>zJjNCN=K7NE{n5d5x=(Uev0*%NfDs*s@m*1;!=P!TZikZOn z#K7{7bZx*Qi%hAcT0z}TOF65+M_R=rLf2o(-ZROn<3e60N8y^u?aqwV-@d&CFfDYh zzAK#1gT^*U2TBs?INtz3cT_UcDgjg!wZ1e0|H zvIz=q%3XDrD^Ua03|UaCpkqNOm-6x+2fA)%G)4ZOhF{I98GZzlHgGf0;)jO4?N$;P zS|8mT)qmmz!0#y_ zHCLMIKPSgmU@LsWMc)I9J`_6Ss|!7b2nmqv0v>G3ir)J7w*n>twC~m^X%}cciHB2+ z!R|WR)XY&LCMj#BMcHqZJGItc$zg2#-@uVNWb`gUF!i0HWowN1Y(B$_TzO3{@}$TW z@NOX}tcV5I_>Y0&gSe!p_x}0$=h4&}mcJ!Cd-Frz)Zl&550d)#FL2$f!`f9p#Y0W1 z-y`-moALBa*?DFbsUP*)?G1)w3yx2?WF}5zn_+cCv?y7Q{P#pTqoEit3mTjE@8ib5 zDYA{is4X=;4Fw58bC1tXnNtSZmJZC!U67N-KH!(l?0C3bQ?y)#ICEi@J$q6+UFLO} zRoit*(uWoi!qh}xu}@n2{X3XTf`Hw<(XY00UyJG)UF@f%&FJLD;${TK5NRd+&(gtP zI0(fI`hgDd*G&w%?2(xnBbWT7I4V8~0`a=f(<|mGbH>8|GSGVcfMzq_5>RIIs8qU{ zIxs#+5VORXt>2)iAdvXCZPM+C6RNcbqCbvP48y{Zc*=Tm-xW!T;%PK$7bPpBa#`dy z7j+VHi+asLwlVPByLoy(a?4nI^=10~ zBWe{jF~d;JH@z>Lbw$-$xOKTNh;vyztT287hW}dC_!A{|2m-1H2BwAvF&Fm8?RDUe zAIvHJM+Mq03$CK(R#bjUzJ}^=a%xnPV}JfchlGS+OVl(q0q7JL5iiG~<6=UVrr1r) z({zloJIL^#xGSyeZ#&VNgy8cc`Rvw0f&lJO>4-q^cp>KQ7JPK?7rg(L3AL#4^WsnF zSfSPsBvHRpd8-}I;O+i+OmMEvj`p@6zW}{8LqfnR{ZlwY5*s^kZ&Xyf4GQgOke6i> za1r+p)3Z=+wwLJ`P8k$X;LA4-l;m%u6c2H^2Wen~k(Z8!Mir1}`>K z%5eDBoXMP`&8VUy8+xFJSQY}j@BWm>uY{J`G#ijp`Ay(3F&D~+8+-vO{DZ|0Jc|V} zQtj*O>_E|;a#M*qixU3Ry1mT>0tWXXJ??G;Mew3P0SEzW>#YAR$xdjjBzV%2>9bJ{ zY>XB0J$e-IasE8ZMNz*dcF!D$tZSNIuQUZB`mF zS-x`atKet>8tRxFBNY|ZW0=c{EEpBmcr?y|lm${-+BY}ty4<~^mvKdrny&f>>I6J% zW%6YjT!x}au!>Z(58dOx5T>40e{bJASezI%V!{Kd477hhNtJ1^=!A8_^r5^i)qk(g zzi)~y=oOI2=$K_iR?HUvqDShdcBQIG=tGq-DSGS+TL5SoEeP}XN`s{FCnzW=x@=>v z=pUH#9ge=8d%V59%a}8ab0-Y!9|}I9`tR$-Jt?NYy#IeRodrxn#ON$S<`I~iy^c87Zcq|UzC^wup8 zcT-8w<~?dWprkdnH-UTo1m~p6CEIJCz(%Kk*Ib2_u#{pxWFS}cQ-u7xs{4svoc-(hErV$0zqJop6n6-` zhikjdy2Gp(gk2XdeHz_DA?XQKFi>U33F;cK-=NPaVm@z-k?QhTk)1?+we(@w%CGP~ z6Q^p76XQn<{V(|!_7z+Yt%xYr-l{W&Z;_+OovNgA&&@OGuYB2;-0i|(CA(z?))^QE z-SGS!eF7L}1%-rI{Rl1Q%+a42%w4DEE7%@2HAncfK1Rhwuw|edn1SWg($-dnCwa_9 zXXP*F(QOOc{00U3xLv|$BHxdMR6N004Uk&!Fw?$rhf^%*w(rSTR}#Ozh6M7n+z|;S z_DZ&wO2uT@(^n90kA?l3)(&tH4!8Ac9P#gzl84rH?>1e|)G?+bRh9n!OgN##JjNTM zj@okR!Jc&Av<9p1sQ=*5xqyUpez*W@mV@OUqww2w*0?2`PUJWif8T~MR8ORz0MYmA z$K*4!VYAD0-#oEX^FPsFyT9+a|g3>H`%V5sS-^c5pfxzNtED}U`bsWYeO8b z=F|=kY&fd)Z3}}ZN+DusVoi`g8y}YSVPHMB?28H~2|jz!;t#hWRr?m((*Hf&ES)Q8 zc}P0*8`Kzyu{ntp7+0{Xxb^>TAZNUAnfxmm>CcToh+scpux10qMP#7V>iTR1ci`7y%V1i$U9>~}OX7$x`9C)#aH zF2ILV_jk(rEZ6sf!E4WRz7@bk?XeBFnFta+cRe>hZi<4|s!F-|haW+q{N+N8LOgs_3@c?BZ}Ydp zlWO~3^d#r5{2?~A9!2K5D~(T)Nmn?Dtm*bQ^9%($NHfj@c!6ZTia%^qaES}R)Q2kC?Q+BtRYK-f-7bVzC7!%~+k_|PHajY>@ z@Gde++Yc17jdfBO&hq}ELc0MuC4fw)w8c31VZY7GIqMY zhfVyDZ_rA2iwzE)lZtOp5f!w$j1`HJ8_I-4mAz3plU(CZjN{24uT-3Jg51=`F!1t7 zTaLq&w=%NkkAU{})`Hb*{~z7q@IbuR9rSEsZ~?!M{>d92-Is~?3|ehnNDQJY$+f)f zpT!fQufWUGGS5!T!h!*SwmqsTX7{k=u_1pTCF_YkK0eVC`;wR>rkC>eMG{%&Omkiu zNFQh{im1cYPU`@^+@G@kzPK(5>3S%eK>j(^%>mWW{5)P6USYm9?D=$*?oBb$X7p>E{a2^rUYe1Crb*Yd8(f8=pzR_?{>YX84`i;o|b zC@w01gl=VQqB4lr(L2ntM1)W%!sp9o*4hy>7VJ!19;5ko&gg{7ilg6 zj;AyvM*bU2N=yXd1OM)wq1o9e*npUNd+Tq^0n75@-@k*!n}NCHJDu+O7J*9HrB7>y z#Oyd+oY0|){3iMq^zpvi=EWY zuFiO-d;W6z<$dEl6neV@Q_4XJ3$4xTLz9L`eiR;}2(tjZRSb$LO(1T!2|jD=Wm|!Z z28!o2#!lyxK}e%|_zpEV!?<>~IJxuFmw4xt5rv;Y1Ee~ih|Oy5%)dFfFV2q>oD_*l zC0vg$WPoU*1j`h|azX7mYrB$vba7j9Qdt2(tgH({Nz);DvR)H46)1xP!i zPed*8jh6A3C18_(QmN{w6tnXQC|gJqgp$(0Ba8mb>b_;B6;cLC#*;^|sy5YPk;J%? z9Zdj@=D!I|lY{Eyd1m(=3IdVN27ZlP)3 ziq2oTX#LN>PGwC7W%>MQ-S9CB4N(NIkjg_oyAZ>53R$_9VCLNukHwQ>qqV=nbgJ$< zy9H`9n@s7G#&7JhvVTY->=7t4_a2CHyJJ!Op@4_K{Uk+RK|#x8*8|X~t*oq+t&7o= zA84NvuN!OagpIW=a0+IORv{3$xu{72S}{G3jq~z5#JK_uAEa z!yaaG!lLD42%gzBVMx~Q+gipAKs?=vok zLTce%i3BK43EEiZ53zh1IMVC1j~dI8Vs^Pdy?{aR0hA72UyHyZjk%v*CHLoDO7av( z{ZW)ok7Czq@3W4N^87vcl|8R*yjF1h$6u|L_;($+`7eRMuAWTUAkN<>DjqHtfy_iz~i&jl%c#Ke%FKv zwUn5*p`yZ%z&txOF*G>Zu@2v;(Od(5 zSm1MO;1!aKG*ZQ?-}Vml=A{2N_#Tye$jMB6zeT3r#uh z2efX9y%G$J%`^tN4kho`n32mGbKfhc#j3NvEtrXjlG5s1*4Y|^ufZISSb#GXzMalXh|BT%b;^(>J>Sou+H4`^mX zAY4os`sxq9L@H2lB_mDj5H;z1Ptn?+%!{mUDF>5N2OP^`Qixvej5c+5M=Bt0+eMW? zNQYEp8!tHdN=r%*(kjU3l-$H=RdZEh7XnMUmY&Jzqy*t^WmOQ9_5r8374a-%Fa**X zH($Bx)M=kq^ONIda(LKeuUf_L) z1Fu@OJJShab;|KQ{d!D~Lz4oh!qDRn|E>6B`C7kRKYu0jtq8MA%W)qUFJOdhB;iZe za*awi{a3<`^^*_0EJD^;(WNxsQsz$cy$e*YUqYf z6l#a=Z{o{`r!j<}_W7_DBs}Bo~Tq1vNGB8zU=lPA|45 z-Od_fge9Pht1En>#nnR$)Vl1enFfhOJ(7wNr-N6Dp{R9fMo`PwWMQ6P?v7(HWHTQdUp7}Y zwRDJN)RoQuvJGpi$;nClNDM zr?jwccSWw0?)lKV8Dj^B8-c~&#aqDx4@PZ;;+Ez83;}(%IWjRsLlsr)-~ZIx3kFTJ z+Ds}4bwe_z{48lBO#5Y3^!0I|V?v!P_&1|b1e)|#`;*)O>QqH|dYM?bqE}kjVOxv5 z9PkfN4QZhPCsNDosth#P=Lo%%$u1Gx`FQSjM>0^dMN*9PRYgT5?B_xRspeJ6d85U~ zw>j96c!+;{jo-^udAPZOn1`%#1Ai(UC+(|Y;851kcx*`td|9Mq1Xi5=#ZYJoL4x$a zs}yDj^RS7hXKmhqD2{Sly-3;EEyfpokXS)ldXQ*^gw=0)P#j?&Yo0*gqbe5GI1T>v z*RS)lg7Z^|j$EJTy@SF?a=lCjFUMh2i&2Z)Usf7Zl#0-F&I0Il>+=6#&ZzNM5hb8w zIhII!_xm?cqJKW>J+WjpD_J1JyU_ox2;8eD!qglj!lGcThEgPT4UGh}Pd^uYKM3Tm z-pV7??v+?gWIKu$Xx!(I6!O#gLo>iK(@KNNtb@u@^vE|_DCtU^~q0y%dg1cM#k z_w1c;puEb;%VWcp2qKz>M>|ewU~Ayy-#-N?+~EOPvMMws>_`3QCnr%ja3;&{oMls` z)L|tCEj^59@ec~2P&B;dmfjlIu#>svzfVb^k%zU5N$E$9gS8C(C0`+K+qlWbpG|Ra6p18tmWSOc^$boeuI-JYx4sWfLEz@O zxVYlaU`Ghpmo(J>h&pd~S0M?V^|y899p3y|#ek1NouFv!Y@>nJ!(`gKG;Bhnk1vRo zRQc#6@XhNLVse=51L(n<1MfAYT69YpZf`yIq=o0utcGm1(w)B`_PJc9LSCV;!-LA= zK+r2JM2<)S*A?!kbn)xrqJ|M&v^oLrva`A>CNf!1dxn-?SAO|`52Q=!DM_8Vvf_+IqZ;#=aj54-+t> zPmq2d-4w{>+23=-?+ErR1cUO{*47||L(RBe@(rE(c!x1}@RCCvI&My8e6Y?--7~0* z6T6*wh!c}`q9MPI8%MKgjJVJ7#O5jdh_TP;nD3N$jYvBw=l|DIlX=R`t|0Z z`X^O$ua7vfN?K_hoFD$PW(a^|vo zApD`OFn;sRL(fIwF<~7VvOMNN$+~YWlXJ7; z4fN5<&KR?=@E*PhZl{fXPWvH(Hny+H_6H4x0?ErR3QhEYA?gm@=v(J?B{B1}=!e^` z(!>dIY7C{dwJc)1<|+>S`u6;KD1~-!Z1S2e;?mvAGBy+$z>2fmH!BVqMcY~Sod^A| zo^buXJEb#?|30X_gAR;CalZ%^JaTaFW;P(t!kiC~p0cwuJ~+O^Y}(c~G&&jt2?ULd zXOI>KXpA#ZuBhS41~>|E?tncfeSTN>x? z?pz7t22A+v^O@XCz7LH;beo>>f^aO&llX#OjcX$goA;xAM!rU)qxn)(f~anfyb9)n ziEV}=7Y+?g6b^vfNt=dP*fDEpHGD!Dt&yR`DYF{B65D*ktg~>)DKTF${Rc)-fBj&$ z0<3tjo|1wf8Ghf({g=Hv#Zt)Ao_!c*vUOS&(}cp2%^=I}F^{DUv^FVpj6~rbX8F{_ z$Or+aRkpJDO6PLZ?(MO@4=4!5P&LF`(w`*7BsYpi4RdA^%!zHCm6T>IiO$&g=t|8M$UY_Z7(*hQl4GU#@D-+Ha6a@>T20pjNh$@BCywSRWeufR_jXC z2^Rb{g0vEA4OiZ;iKpbLk|eTr2}NQdV#~iw>v!e;hM^2kc`+u{?)g!g({iS%qAK~J0#cK|lG^tvWhQAfxe4%n* zU}~BmvR&D{utkqA^evyCdRO%Q`!E#bpsfZu#-O5+$TOA9P0cW?QVu%@Hv2^t;SAl0 zcS@}k*U%uU5x~l|ef`JE-E#y*B3HF~))vZK!!iAcA8#oEb02D86HI^!j7-%c8RpuY zmMYe7-UPLq5D*t>vwkhx50=>S!&u5UsInK=&MjZzjANl-=sQtz!TjLUyT{-mmb1Cf z!^;b)hERy|A(g}Yd`uuJnERg~dlB_&-abDeGf!uF3@$X^09b#I-B#se3_?eY{PgH5&GKIK(jvXX?c)^9qr;MO}#_r`gu&SF4oCbR^_cjHzBYs z01X|@FN^CSinPBOe7V}%+G5~9;v*+EXpoy;R#}ZhEbFaY?&H;F#*R#OFDINvCh~5o zJWgh7OC8Ej(px%k8#-H3=X&_Pyu2Jayg+XOjZn4J=GgFKMdL*o)&{2B_|O@~&gr0Q zedcp0I7J8DY7nN#8lR;$%r8f;AKbljt7EmP@7dEVlx-dVWJgLzl%q$jtzut|-01q6 z4svH2)jI*U0uRw!V?-hIrE4Ik9t|>;x#xtj9*;w@#Ew$q(Hs5B=sdKQdG}luX z6chxt--O30ff-s$&rn;(uXVSnV>~1y4}U(T(!Y1JPP*sS<98HYkv!Z$CIgsJJg7Kc%7bdt;EilWKM9rxbdo%%UtphAc&u!7J& zSeKyLqJ^uMZF04z2u*}<^?;P;0X?4l&2v>QsuNCU2^W=g>9$;)F8kD;ue3!jb#nv9(?@=Krl z?Tnphi0g0u*$l3pdk2*t0KH(DC`KUeT%a3O{*G15HFhFoT>)d!KH6p1#LCc$rIe>P zvTs=Dvo2?&NVG>B+Tx1`cT9<Oaa?WxVmG7@-1J_U&8SK2(&)IgE|zpv+>7oc zzzx+H9|tW6j@!+9r`RQ3=h_L5+2;B2*EEsiAwgStvKpCOT0PD_>eaw}MViKkhE!lB zitNH!q8n9}cwJVdJ}d(T>1g|AEG3CT1-+Fi`=#I8s}rR;++->Wt^KVod_PS!izlaG zO3tx%iG3^vD_t1*+Ob#8rOUOTvR58{yIa>l?}CIaHnSoB>>!GahuBBEyFUx#bP~Oa z+|$>sIn4c&NK8G_(zA4#*kr$_=f88rlCH0KWNTfm@Tc`XnN_4C8HPtAJo3eDq7P@4 zua2N!%L-{}RY`qmuw??~VuEJ@D>F1TZ@$p^VzI)62L)$yjb{zd+$YD! z@8q^Jm9-<9R;`n;uN>!>ltOXPP6I5h-k{ivCaqqHO{^upDs+ovz;8GQU{1jMW(GXU z+ruLxfykjzGX%ggU_F7|M?!Gd@o7-J8z`teZXbvaI~g?2-WTT=~l8j zWyqrB^jLLsGsUZc$<+vZAJON)Yx8*5i>;)HyW26NTU@x2-qWM2<}tc~s>{9PeoZrt zuhj{DLbILQ_o8G7prdSX&<{4~Lup)oW8d%+@RW5|SB|ZRz1FTZrzunr6?d?`b9)pqfZ}vYvZf7jEezpf> z6q0;|fca!&)YRwJoS0ZB`Mo&(*Yu4SA^N|UGVV5YH{Fnwo)8Ar1ltuC8?IZ=*paF+01{l?a@z6)cbaBtg&G6co(mZUb z*dnpgOFkzjV>6LT1~aY!3<=^e3s5ut@$+X1k#t#Ve0(`djN6<-Lhm4cs*#8SKCH&G z$i^llMFL*ziY+UV&zSO$>BQNeD!cg+kHsCem__#N)qG1@fjO4XG#p)1L_311ieAVuJGM_vs)`pxahAEgct^7$-8`1nXW9GM=wOs z4?Ucp=Z-*k7BsFyPu(2^!C; ziM+OZaDt8Q9e-Yiu_#kY8EnX0NVpiH*EJ>$k~ zcc#xy0{RC;5RILtV)?r;s1=O7yiN5dw)%^fgjO@hGbNnIxT|W(P~t z8GT#w6e+24HXa#!>LQbSqs^m#je;#lhf1p zcPSb?4WSQIun);Fnk+SSJL>1nWW+)iL)_{(Z?WTi03IV+$7rBk(f}C|8X-+SjG!## z(3{kceDA@W(D?l3xD0XNDHbwC zrCBj2Fni*?46r;b`0|HnRlJF6)4DoXtwK*3zqIdk?eu6gOegNiP5r1dO5m#Fuyw*G zbYs;E<+2PU9a$D^0+AWkVt+h1#K zET}TE-+Gd3zwJVU8bK^AeP{M|hdjl@Hawz-8=IXGuF`!k!Bdh|zoJ0=J@C!g9Eh%T z_mD2W2fPq)Ab4qNrmVC#e0Xo)j(|OJ0vqM1Y*A->9&x*3$*IuT%#2QnV{}RB^%XIU zf|2cVH6lNU`vz|+%PVQfaZK%v@bje#7{A>aP%AzWx+%_LL~iAfSA6kN$`?auoIL>d z2F|LGE>3Pu4 z5HFi9!xkDA4Ps9zTmPK%2klNAom-^KCS=Mbq&_CZZKm2^9$jHdIJxXOVd*k^vQ(1! z=t>rxdZi>&l4_>+KO6+)=)M0yue@u|hg|=Uj@|~X0cKyMB{Y2iK)$W3%-WNl9v=H6 z>DTHzmw8c4Sf5WvfZq;W16ZdaJKP}n3`a3CpTm-?fo-O+h2W_I_>Tu8+Z)Q?dilo`CO zc-IGqw&6bO#EKb{RtmJWU!K7xy=F!~Y)5us^KTP~WS-W#CvW&U*=z3`cx*ndJLn)Q z*oG|_pX16in&ju+!tj;7R}l6u@kCL2`+Mk3zU+_opyKz6L0hLWRxesJ`5c5@?%#64 zcgp8yl}%KhRgU`9#WwT1F0g)(atD*F?0|LY_id1cjPlEy)=zVFtt63Pag?~$S43LV-M}U ze`M^OoS+F{uQH@p3!`Qag@Ka?XiPxGrX|D$2_hLKNU?uwmx&{L2a( zhOSaM2G0A|@ zGVI^uUQ}LKuaju+Q==|BxoaF6eIA#Kj*B{0yk*=$O~&8GcSIS;Vi$ z&SEagJoY|Xt*ZUQ(O&On%FgD(mBfGOhgUkj)q|HB5uO~nF00#cUBVA0El{u;OruZp zi^Z|SZN|RL`R|4 z<#SW|g+Ka5tU8yhBdD7)oDT>Y+*O;t7KXz11ZE{b#> z%6tH;ni4B(^DY`D^D%mnvxDVMWLz59DE&O}DAg!`(pjGpKwFvlE{T6Nw0Pu<`@!7; zF%$N>KR7V&_4elL%dur~U2s&gfMEv&DS;Y+5)xIa!;$%EycIw2E`2M!t0PEQWLJN- z6p3;?^d(g>7b(UAYVr8=^bsKzX0hg;;njSXEDwIe5y6rxHbLJ({)3%VmornJDjVCv z5Y5H1s)gwDSZAV{prUY1*N| zEb59h_3Hl%G-Hl(6ADVR#nXu=Hoi4K9c}d58ywCk8`o1>jUi&x2*~n6MDX$6yWp~rK&YPx~xbq8@-f4}aq0-DZp=hUK5L09xzeqX_HIE~&&kJ|q zPxrR>;mUKQ8+h44BX#8@y-^L%?zO(}-)f7+$lEbBz8zTp4z?$2gbAM5N9Nz1HutuJ zU0q1wE=K&EFfDRd9$=x2Y{$n9{SS=WAE@m!E0QL@Iyx2W5ew_-SrvBAs}kmjy&O_~ zR^$&v#;5vBHQ4Rm_;Vv8kGS3q#_l2PuXo%pS8o1=+h!6;69`J6%!2I|PD}Q+vryID z0u{`#QG(|$#NwDak<=age5j$=6*?7N)WsF`d2508ce?Qwf_(Bvm{NOW6CYxwkKZhT z)k@21v7&kizbxbT+`GzCEWPgpcOSVte!nnBDIh4|u-SFQ=Y-!z`$n0)G34Oje%C9t zu-(o$cc}jldf3 zjJETA_jvC^fiUJfJRIC`iepGUEvaztHL80iIXWQw!hjORojD|y+jv;}n&kD5-?yDR zUi|<)Qaa@sFW~8BS|BF*zmglgn|-{qPTxye7+s<77jwdtDc>w>y$4T-lK040uJm$t z{)*y%&?aE=gD(sudq#PxytY~Pc`eM3cSaY|IXcShOBj_Z%s%D1$GlCQ>t7w2G_$Ap zDk%-xd)uo@ReM!T^YxL394WMioX6O>qyEEWZ_W+aP}^Grrj>Ng)*@7G9GkQX(toA! zXJf7jr%8M*^gPA7LoIB_-FRdC50mjuc+NWy#}`uUNi10+B8Bg*#-hoteE$AOr`Yn= zgOx3qMaq7^q0u|RDbJ_d0_)bjZ!x++-eZH6}&6VemCq)IHe zYGga3mwpZF|Ew%WPEBS7BVY3Dd#hnQ-Mcu*UOqc-Y@lI$;rLQsMcs{po`E59SOx_T zm#n}nP`g;Tr<}o%ikX56xdq6{$l&nalt*R=`PNcuErF9s-<=x3)>UU$$dmQ8;?ApY zq~NzsvyJ9!3rR1=L`b5dE$~6=_mS*-q#N!32l3$*2$vrG0f`m(m6l>Q_K_@5t1eNJ zI1EF&&04^}4`J?iGNuH+VYP>cl1fIj4MEo925z)0&*<)TO{~Yf9-vOSi_K|U{NJOv zUTVWQSX-CzzyZCobB~ZVzuhg@df> zW_(FXoU+d$6p4+Fjy6&4XBQO6nd#A--eoFF+)mI_zd6ypL4$;;$S={WcORwPdRk07 z-y8e-8dkmD7!|FZHQ-wbtG*AmX)qcfx2sseV14!jSq(j9DviSWBk>6;F#nLq$&Pg{p{q^L0-J4XGg6c|?jJeM0 zf&<2in|S4_W!;|?_%s5BW5C@3No`hk_JWP49)Gf>e-C*mMkX#EMs^% z6IHB2_8+zb*G0TDXU-AFLD{vG5OENnvl{|!9GFf|=MUg7zRwA*v3JYWE1}9z4 zRP=o7f2b$_4avZoM+)X30)eMtmQU1?9|Pnh;CBjh!%V%Wmb4+P-{9aOz5OwC=*iCw zG5|3y>E|#qdk_-yyQzP*^SVA2i57IVAefELs`v^hGxBP$;;<|U@ig*6r#Z95H} z7zGO?+48LvZbuGJOmELNAFz3*!ltHScDAqp6sqKtCatt@uVIaKJ4!{sDC|N;L_0jl zFlk-%T=%%n!OU!B48qDtR@DEnyuC@-{NHbmm2L>XH(u8~u&*;cGZT-~ek&T`Aus&? zF1a}CbyE*=fA6q|xQ!s=##M-1S3)Gb0cs*AgW<=0!Dje9w{$BUmTJ* z$P1(&%5%(0fQ|QLKnPY5?BUzuaoK|(Z7Au!*98M4e`jwu``{zd!3*+(7n$!BP87l{ zmXxiCq(0L=v-|4M<9LrO7H5SG|5W&;=N&;(DwheD#kYJ5x<^?RcI2MiEee`TY4|;rH*zpanGjA|DtKtcT)D zBo7fb%pkR7!8;jXFbD+PZ76E6=(iHtk2UUW&TPQBbqFMK7{uW%@1T=9Z@C?!ZTOuv$(Bx2EYIJ`loYM?Fn30 z$`pW8X{-LPZrAJA=+ugR#y9ThAtw!Pnb4^S9%x{R5^#c;4v&;1~@z8>itNDJbA**g)WseZZ0b=XL#HPfP1M z{lieN)?Wu9Z;lD>{Mqwb7yN#Go_@m*Pve;0)%|6vn+NLy>77VM*5we@6@kdb#-slC znKI9F)bc7vvx^(-KgWqKkWj}qRhBnnRZg?9HeGpN!5G>;zDA6kKH=a6HhWmg!S*Gh zZa#%h6vD^g$V3viB&w@w#daS^t4Ia0&r7fVQ=~R6kgPpG=tlkk^{q|DhvNL=GBBi{ zkdak)h>edz@t97ytBtEF@a3(JSsvbkWf{nLG?|o8-;1KPE^U44b#KiQ5x&6gLSh>c z?&<4G1q?d4H57-WUX^M~S<#_v5eC^?uMx|H$d>%90u_VW&%>T03`}LXW$5;<)k9-L z!Qls(Rf4nH^Lnzd86=}oszh%VQzqa3RxUOYP|S#RaS;vW>{Qldwa+Zd3Z9Fp5Q0ku z6B~s|2WD=_xZ0oF+1MDvMr^O~rUAk6Mew#goQ8unqFAoBwwU2xIO~8YLJ7>?$-H*7 zpI)?>F_WW=O-)5WWx~7YXynxQ1@YzBzA3OtbQrJTQDp>D@!xO3rgf%P2r1j2Ecsb)X{E!*;F8z|sa| zwdpyo+?g9KcoUhgL<*5N@SH!ZM~%$YMV?WL8KBj``vDdx+k`PM6V_^4LWQ8`;zDRd#N}VK4JK&(qy+aKFfcCk&aT_u6$zZ~foB z16VNO>ovP;nG^hZ|DT`}K8(&PZot*h&_G~arW}|qBNq-2$t8Xa-&IRR5_72n z0M3ckZ%IRNMjSMFrrmGJOEZGAbifC>LOc+kksW{1auTOKf^W;Dkne)5%W@Ub%Upxz z`)jw??B=DS>u+t7ZCeTq2Yo#7*GNBGu}vo19@{>vZzI{)ywF;z>0OfG`7HgTo>V@> z{DCG;uuN2F$qsqbxeTho_pOeD(V7x3C^Z4KrLeFtkNy_iGS>=mDCOwYc$kIvl~2#T zHnw&G>?T5CpStsA580ejt!L~9SexvI21*#Cz!3D&@S`ly(_1o2UitQ%SMl=l63i-5 zIhyAN1S#AU72dz7Ck!CW@T>`XZg}xVwC3U)<&9&SIV46+89v`@XNd zU-{XA{nAzGYyIPQH%fz-#FXmxeR6g{Wxb|!f*)U_hpRi!pF{%gLKo!G8Vj4Q$~ zmL2P^~Ww7&ij>i^T=*J(4UZ&ZF|0Vz-59< zn&c(^>!P)*PGJq5D;+hpM~XId`J+!{S_TAT<`t|tIR;womwKObz3i$RhxaK+BVZpx z7TFf=l`#aHpdQyvK`KO=15nd^?uT@{Gu3KR;zQYaU1CYgjPF~+aJA;uqZj7V5aVE* z;(TxyBeb<-+D4j?P~fShdpnC*jzF%x!K0vd z__~m9uKwt>YKKPz>BH4M1Yp3@zO^6@owtlhCHuznhdtFK7%MuDgBdohWE<;<2aEMFMO z;X`7V|FEv9$1KRiz%;S?{ilO-i}>Q?)3J} z*;~>3t1589IG>?cLr850Z%|I=F>F8Wuv-|y!`P$C$!=`kCo``7s!a@{?4Reg*!`j# z_Z;pN9`31?6wX~1GpK)+3&eK+WnFZUI8y3(A?}}FXXw5lnB@59*}zE0kI_2Nkl>Dd zUpeO?e_CT8vffE^c=6&y*maj2E~h}zvp~@%Bps&}3W%JYiI4>2hMTLs$cilfi;`uf zT@H`NM7Q0e57lX1)LU_%QT-%{3C+MhOxaB-o?hTbPj)@7!iEo6L_GmIgNb*99!UNvWj2nwDtE0DH-M9oRIkHC&^ z^*VGuclCke3k6TILNLzr(`Rl?4nmX@FSKc}(;u08Gmp((inMlhJ-bGt&wZfvfLOuu z?Z{BJY-xRM6r4P1VqakF>uYI+o(H>wYtDG05*xvMU6!H|e8cmfh`;NckL(XF;LL%R ziu@K4UpxTO`2hY35OUH36PMkhMqKp~c<*q3HeTHz7|nDX^zDhvU-Fx5%F5PJh*Djk z31|tn@3BW>_y30mzwWio1)oQdcGROJ&}AMs9sK^j_*e7ZTICHH=Z%pvf2tzPESoNO z*$5$k0wF=TJDJg9ro(v1=@Kep=j?QD*2Ex0oB_?5yWoTkzA}5F( zNUVF~g+}wV82ZEg(<607F=HA*hb1ZL1&v}VLuyNLIzQVVzad%#?utN|^}zQ8$5%>^ zdubm(GA5%ae-pJtp{7=4>N@{I9HFG<=DA-;pZ-%FOJvhPEVU*&&`>OuHqwI350PmAK*H zHyC1wFM6&*h_q-;!afiTBJdR+%cj<+NRy2+$!K#ia;T)cc(FUhmNWfRe}$W|{hIHgXilqPh( z1++TFbdjh?5)KqUjFh8eH%(-uSaE-8c4r>$ikA(GP5v_e9NP4DLMtp3ZgMkn6MQPtHxtROXN^npNTNW1_Kq z(r6=)wa{f)k`JaZHSr|+_TI;9h_Fr98MS2ATPc2E?^IHS(tf_$6Hey00f{QrpDyBE zvw=W$%p4dPz$W=m+V)6b3+1PnG1n(#X87L$q#Hd^caEU;>8=RaB6Qj-`+YkV(333tQ zhti+$JNKZ%#{*~rSfnpp zkXBmgmO-w8A$y1Xu2xsg9nvSZr40=Y3D#3D0>AguMPy}s{dx!31m>HoP7kOoMnlON ztsF}E=N^jw_r5kVxcuEwgFgxjQZzc(ql5|bvk^I?St{v;s z-O~?(_NEu(;wOtoukvdKg(Qz?qYR^S@loRk)}=c#p&83<5B=AOAjWhTdUp3!vv~Q7 z^H>MU+-6I6zM$aCq{hpf$xpZZzEvYKv?essPNaI5a1aoJ`&j$WZ+Q%+^6NPtI3W}k z7DH_gCIs~m!A5OhypCIr16c;C)wmyinarFAfPhn|YEM+p&7Z$+3wU=Nw%RbqYBy?} zR|s9wE+v2RuEzSF%5Df@0B^SCB;bB8dT)z_NC3*7MYin16%ysX_#^Z#Rj9o)rjbSl~85YWjfMQu!e1qHS%-KarT$#XhUl zgY}Q|kkJOA{wmy4`&;%K?vXOLq#ssJEa7^uM0P13b2vSgSRKrwj4%7!?bHg$T9Z<3 zg5cmewXHlWl$ce=M$tl{LZ4pZbJbG^rBKau6+@9XSCCX~Uwn0}@Y_Rno?V0FrE7W5 zQ9FkZ0i2_dE6Bm$zcFDy3@SH>@RV>^ta9E?V zPx|+s%IApBIYbS6WB&LWh9xlIM`~vQKmx2TR973aZkstt`+ukHw$u3cpLc_Q+y*w% zm;0fjQg(J6pwELe8CX!jJVfPT9@EQMxeCJHBSj)MX%(hZAGQ);q3kF5o+O-smH z0@B^xb!ZTz1f&!Ykdl&+ZX`vdK?FpkK~fPxy1PR}K&4B%Q5xQL|KIV9amM*{#!+$a zeO+tKIe(MsPVWu5@1D2Yt6QxJzr!Bi&3D-SKQF*APrGKo+_w%oJ+0<*s_f^x^^f4< zh>wZZbP}}(&Z>Q^%Xf{^5%4DZ=7nqm0^o~lFNxc`VO!Dv#Bj_cW~bnZ1vL+1!iiri zKsd+LKm#BCH;_f)rv`6g0Nf8%0ErF<4bWYTs}zC1;=Y;~Mw}c^0A8jsxDYHd5P8W z>rC!z5dJ9}IU&uXGsF*jV!htGKc(C;t0!!qjSO3K%;rVEc`JQ5azztnFbke8BqB?kca&`M?Af3G)(0BImR$KYGq1=C&-=O zvw4Cae%E&~oMOLuFHk!mp>pVTbu0oUFqL;}MIDt3LYN*1(qdL zaltlbX;^%|3zqqgl;G!bva`GAn}AqAwoyY{@+AJ;9N0m+^!oBrhI5JW>Zf;l+S@}1 z4$XJdI{WgQK7L>8t5mz{n*F${RAa60K(|&>=F2Ft!CC9sXFyOXdPv)Q_=gv?W$nnB z@=AVp4VfwZgx-9b%f4~`H)KhVoi`%AoF_O2rHq_xc)S^j8-j8uqcad*Z%OI*9+nD3RPGd6H%gpzUS}CKtHy@?e8==W0XS?ef$O z`QHNGJL!xV%%|J#lfv_x@wbs#xtO;s_R)z#q-C=ZIq+}d|drH9gWH8jNY-SE!>gySr z-qfVUQy*2s>QJoEwCfNCIwvGf0$Y_Cfe^_r{$}nGC<}Sg=+hOM)h7@xl$w$!j78Hi z>XfA?>{$HbuLp~e?a7pU0-80%Y3`as%C3v+eHS4u)Ep?J z8}BiVO-CKI6a~%A&LaK$pziB8NjLkf8)Xj~p{%qTUv=Mn7jI~6ybawQ@Drd%?!(x{ zza-1>55`VDm$Uyk3a^3j0C(BL`U~v!{uA250DmW~<;ocuZ^OhgzDu7pEHy8bACm?_ zfq*R^v(tMPuVK`8R?EO~lHG!n{4c~_7AwbYXlwTI$YY~uAG6&vJPLkfO#@l+$0@l> zYK&0SZ`;}GFDG%9QapI*g0rW0_z|3RjIszKcuspd+X)4`rD+R9*!7nt=SS@xccOH4qKbJbagER^Z&#kNsmm< zlN&uCRc`;cWGW;1UudH~dDZreGIOH5ekJZk3u%_KM1sae>Y_8hwGq>=@@ZB5CS3Kh z7XfmFj%8#tX`0qa7zKE%ip7shNu(8?Kj!#7H1V##(PEHoA-%B#YMZ2hzKV|-7I|7Q zOSYDDB*vJV(c`l_qX35<6sis^X$}0`o5?|fAj$2X>ODaFOHmky;8kfj6^ zFOCLU0f7`Wi6CVvXwC&)KnwT7VQgGnyL0Vw6h{_OhQqHHJvZ48l!*;14SA8gkb`9e z>4BTtow|{IQ-O&H-}NS^)6WJ1ft1Z*O=_O^bOQrr;mUY0BE3giaPejp&-@e>?)^aM z>&m6Fp5?On4+zz?u;hwvd%KPDdKIvNr1aF1)ssbh?sxQ!F?YvuhjrKt{K}r!rTm5< zh!I-9zkQ$R8)uo>q!BXK^XN}C!NB5Wz^}(0(-9B!H;uZh&yD#T0~kz; zVs+dD5GQi$ff3~b0LbJXRp5$|YE|J9^t<7VX4cx@hDKAE!}=@k?x;j;9<)%=(t?Lk z9vUs*odEvJYrf#Gng7)Cdyy5dvnMN023ejzs8SkjJo{q#^%rs$M}Aamoo9jO34(%U zKmaYW@WA$~W%H7iF%JPU3J#MN#A3;uz_&#pu&gj>U|io~d_rdKm0-$2$ zlm;El<*wK-hPXKy59kN{`p%A|8>L}W-#w?LgHdTe`^W1w;pD;0N#&ti0cZHbZW}`3 z>atNpS%d_zh;;)A{!1 z4z0+#d21^1^x>s2f=0zAppMYlCK>%@lDeK{*tc@GBwlo-oPIprK&8aJsEraby{w?9 zfro&+_7efp7ur%}4+hmsIdKhwZi3szsl^T^u_$!+c=o3`vhT#tHW6Obyz5hJp*B{Y z)JM!pY7kWORF@`4SSw&LR+fE>*Ew5mjj&l{zn1)gJ=%KBpzOuuf^MUpE1U(eD`16} zR>`>2t$0hr#hLxaY*0!Z2BoYP`lh2fY1q$qRP#WrLVCdXeSN?po_QO90KJ-N4*#gP zs0NikbNh2QKrrhwK4*O1+iBJ7W@5+lPTYyF@W+E4XlZxzj}DRl{tE}^EYi?d-u#am z3H=eXS?Wx_#hJ=GL8fXuArYmOHzhf6xLZbT-s_Sm3_+zkF)J|14!{i z%9Frw6vS+Uj#4$w`CUO7(naFVGv8L{#tkuWuda*F2QFUD8EuHH$ntbguT6HT&zJut zXntBEOaD}=&)tUWso%IiCTAAfX&vW;%H?DK$=+VBRoAvww#2dqunQvH`Jm&DWXZ;e z&-tQ_%3bh+n#)y8B46QU__6iOaE*(Q=K#~*G&Q)Wm4$`H)tmF3xd{TH=`3+m)?9sS z@g91G?YMW?LfLV^`oHF!~B0Ko@ozvi8#-OQ(sAmlZoji1Ol$11`W}Gh@0_dj%Op)CK z2vQW&>$&5b{nn*cJ%NQ*{gcJ@p@b*3(>fEDUHTeKY)PFP@`5=Ab)G)d%^PN-&PKW} z;>(+J`V(HuS-R*xQgj3}QvWWP>&7o6RY5O$@}Iz}@LMeI;98jwn{K!t zR9NG~l^<^AsL2f0gnFYJnwMD@yBSD+x{C`1hEEFWY*X;xnOuK$Sy)5C?Hsw1X=q^9 zsPF#xhSWDD+Qj)fb--}L_Myi0X~GR97#E~MzT*}02IReMEjjs=!94Ix3|6Eu$u`Fs z21e>Qff_L#dYe=Pw6F;79yO5Sa%irdv1H%+g#VgQnrX`kb!E7W9Q$pnvM4q>95eiiZWyhjT29K4WzMmmq~t^29_U?Wsj zdt8_E9UIbLyVF#;PuW;yJu`u+8f+!ZNAG1+{!Ts)YJR|*r!PlrB}f_I1^hy&nYc}; z%T#9YG3Ol^8x>xN8&F}SzWe-$s?_4MIP%2)AV*72O)lN(%F2s+SJR7qI5|Qo>GkZc z^)5%Pbh+MTkblE9EY9oPF=~2LD(u{tTLUhi34cL*K9B7%8))}$RMCyA?ragCI>G4n zXjgb1I6u2Y+~D7=mN@9tXzQc@tk^11zjnv^{t0SxjH80S%~Og1n0e4&DE$0>`_pkC zrn>OU%pE#>37VHQFV`toqVuHuo6V4W$5YU-@_*$TC*wMF!azz(ON*V_NFQhgf3P|I zaw$V`qdIZwsM6n>*W@~`qfi1XE}72K4jpbdT%P&9%R0lR3=03CBlulLMi)S! z^t~2rj_;9@Uy~_UZ*m7Qd}UE9WRGgOMH%;y*gZ;ww^Hx@Oqx43`5(ks9WrG4|Ei<%qAn=hCAcYh@F7E9Bf$Qx+FD^Z+bEFFTkf z{>lqRhF-I9Z)!aE;IaKYPkJ;DMLadNwO(6oQ$o$vNi^4XBub$Tda7@rqsD|E3t$e= z?cO15>_{uCeMD3A(+enRP%!5h_3JtFAB%)Q^GUq7TVCh%mJYS zT=Z_upwbdFqRs9)GZJQGNa29?OtMU3_eB(#(fP1nH({Fxfr+Q~-O(%IKB}-YZ8LM9wFR+emocUTtVG!bg0BKv8%iJ zgm+JJ%`f{X4qB*w&VQ<=LZ_|uLA&5| z4cw3jSFmvB-b{(!It#cq-1|{AAk+#K9mq0C$Wl7`|A9UTi13z6HBf|basKg_RS#g4 z)T;M;L-%_5h1)`Z;=DGGz!FJPVpu;19~I>w0W(&r{NDxcshD5r9SV%W@!J_=Co4ko z-j#mY_z|5DSs<>F1(yyOxH>ucgyjp@F0O*W9?nD^mj@Yca7F?OL0|rRF}@xH%=1Vl zB`fi5Csm6#YvG6e*&MYIzq(Wq1}!T7!E)vM|8it7QBe+fe|`2NrQEgd^X}dX3D#PE z`^yif>9b?^gCZH74}=5(!)=nS2|>Q5d;$XbfZlITnu-eGgN;l_I3CzNN*x%Cb#t%z zrq*tz)OHgtMXqmjt^0ym!|yU(E@0h(X1dPyb`%%}kUJP>-xSS$>+#llt9fC59J#=@WV>n%t|wBMAU6~}T>MGWs!H(wQZ+0VXbIj|GdlM7c|W7_m~dcn5m#S>ZW*)~2I zx6>_2TKiTADw!}<>sjpHvr{K&-)o9hL8F&l{$1@@=X<~msTt>e=u(5<;5vb~RZwmo z77N!{-#+%_Bu^swy_Sx>HH%ksY7y!OUleE&V^_zLlBzOe3wLc6?lXxS%Ke1a%G`-U zpKs{x*`rRc?mYV3S%mTK@F<)804Gb-5iXii3C-jZYulJk&Yx4(+lbgoSV+f)5ckT1N)Ws>?y*Ol&>A&WP-n8z^_9+YR>wde(P1n48XLZ z^!PH&0kdyNCc9XIWGM4lkk0Gv*L{A4!3Y@YMco&)7gpeyAYnyHEH+7 zv#%PB$36-<^&O#d%HNxil86fPxSoN}HwlMUn?v>ce@+1W{;M#Wv=#qbQI{0SHU?6j z{z_yMs=U*+D1rFIl`iA8QIDO-Q|0Sy%3t#;>g-9#qG@c+891O#_>pz4V5EU!yvRci zVjN_^2^Ei((hTyFxy)@C9JyYN?+ zKVNjH>@HbD%1TRJU-{lZ`vKg}meBX|{}?ow_qZL`HwoWbr!(_2skqw6zTS9#`GZGU z_uJ2z$nxEQ@Uk7gPfnkncsr9H;T>_3;u)G4D+Mab!X~DB#7P)`B+sKB^sAcBL_ZE( z=9+L2r^n;k-PYxtxWEzx1!B>=@c?R=fL@6Eg+RXcho!X)l*yjR%Ju1(379s#to|(G zYR4t&9ZqyH92_yar5xnLfHn8VqW|GpGGdnXF;x|QuCIl1*n^1SZA_I*mPl4+*I%Zb zZ)0At5n{ghneiO4)hJ-f!B~jKyq@iOJ z|C@mj;*7ITib+V=-8Y?mJA;FLd$}j>IwM=t&mPEV`5Q25J82IIq}I5)I*Y1}Eo2Pa zX5;2OpwoRqt2 z$liUZ{szk(dqpTzq)YgegJ@KN2Su-boAyHz8dsPu_Z^}AW2#nuG|l{CF;ViPOW4&= z3dv=Kvrf+P(oMbExN6c`r@LgeII9Pw09@N%?QkbiA*q+s(;^sU$FcC0zBt+2VxIH# z^wbmD(W@N=4*kfx!%tSnZr@$-V$q03cnZM3jr@wkSpY{qd};Drox$amYflZ2L55b5 z^X`gPX_J&Y?9adr*D6HY+t(t=#AaTO;fZ3wDif`m@bo?#H~N^V{~_py(*ARH*#yy`mCfccEPo{e= z8S93%uB%3r)AU0z_n9K;jwH(D!!z|_R`ZX9;bno_PJ8WZe=YeMLViT0j%EBR`O)8z z&rQ@H7f&4>yTU1N@qvR7zIrg2dZ}V6?!oy~QC}Uk``P*Dj`!`JH$fE97(ae(z5ZR6 z+<#wNYc3~`Q=jI61mz+Roy@NtZwQ#-s@+aW$Mk6-zFX5p#hbryVZ8#PNm1YmiFCn@ z9cTH|=G5&pmk}0wJeNJ_S41l&NU$z+lIC{n{a^sKGcO8d$2x#YmIv5w_)GA0;83zf zi+^7J3{Cq;OLB!Hm>sJ_MgEal14ikuXAXDj&HJ<}jRHM#YH|+SYD8zQ zBbHgV@R6pU=$o9r9j(^0tI8x65?orl1D}VceYyHLIuDz?sGrvj|9DgJO}dz`ICI0y zh)27>4@ZMN2`LhZ-Tg>=NRM?U=_x?xHabs;fD1HaNE!ktWw#{Mb~T!Y<9foLvZ)58 zN1=&OKSFBiFu@_4{e1sUJOceg$sEXA5UyF@-d18yQUE0CqM;^_pdz9vOa%!YbLozSN+}$GLO!y zSb@lkeC?{lAF%d)yu7Uc|A}Q-t#GCeT7DAI_Ec3`iB>Li_K}F26Ofi=T?uf{C zyzJ3O-N{%lP-cRC8A?kn{cMaR%#Ir&7X`7Y+$^F>WAasZs)$uZ(~KvZ3qQm>e>*~$ zN9*WbYn+sHHOiBn35HSpK!k&oB)FM@_^x{!g=b#Z9Ld>f9>Oc zDp8oYMjn7c2ff^dGU=>XNq*7j_zkG$fW<82SffuFqFgtQ5~-kH&MxT zCiT?4f6}_meued@e*|0p_3Zc!?Yo0OfkSSz(U15&5JoSS7C|VUBz_3LlV1MPRi_#n z-9R@31SEhgSg7N`E2F%kY#Zcz-yJom+fvs@oog7avLnd#gwNz{~+R z2}rUz_V2On)kasmHFw&k)2F0;YF1cV=PfH3$zwKJ=Eug|K9LBVMYGE$ov`h4-bM&- zQrrZq0Yt6@eWG`NUl8f=1K}0|2lMR$K?itn0<PDgD7Og4MgP{i1an}8vQt08_jPY3khvO!9Tv$wsp_}#Ji$KRs3UNO044u zOuq8<&}aPF02}O%do1p{xx!WVm>Uu1Vp95_8nvl7_xktm#9&2UI;g`wQqlMTkaXYc zvo)~faEFMbbijoFKKi+xt7sefx`Ov}y6!H_7om&>HIH=W4H7Jk%ELWYO?3iydQVus z|DPAYa7=8$-nH|skGvwLGU>}Io31-A&YJyx?EJPEe#}E=?$RE$7$hTM7h3QfztKmI zVswQrSBDd6>Z8Ow!5%ejK>yeoswYFBT=J4V>DHS8T3mfGKjMcYY}AQ%=rG_db?N7) zyiQ!atwhee|1pS^Fj|6><Lt71#6I3V8eWXFNuklKLYf5dq&tjB#=+6XN5k&5Br@ zhbiy|4@a)Y7S-WhF_G4S#n+_F!$3JF zN)ZC7>=Yw$ht_3Q7A&G-Z=%&p>YdaaR_Ty{wzcm`#z}N>YL^Z7)!#{eHMtns$!d$m zH(P%mP;iew-{j6ETr?2aP6e~hs!(wb&e>AW5mMX)R$I|pSMt{bD){wdnD_E=Vu>Xm zH)Rfau60S!ga&OsK4#G_ZlaU4Sp6t|nFcpvmR6i?EL4;yG|3d_i;U*p@`ylE0MqMs z*PX!T38qpZch<+b1%4w79_fR&UqKyF2Au8G)`U>tOyYtS|D6wNHFOOl*`2Fc0cNjB zR+DNgJ}pAQ_TLz=>;-)+atM0d-?srp&M;X(Tu?zc4NwTZko$$i6u7jy+D+h7mGwTis{Y5sktG&%OSXe{Z3@Za*m-2%Fy4_qI3ibms(SLkbL3_jih znD3HwR3;t%zgr8}%@ zHGjnL{jI28RleqiQl4SSkVclqspb;AOsaFOYCy8VSDlg9^t@D#`)3y;9LnzHP69!~Lkcoih6S4zB?PA-J< z)ma(T>6n91Edy&+Xg)C$%m8Sc&r<2&s((jAz_{%o&tO9e(eps%)NHkz%)f} zMIgxw*hH4)`9v%mef@AVGhJ?>SbLxUD!2poIXXFHON@%ZQn@}HCuUn*8jZa9m6vaQ zHgEE+`16XB8%@$nJ1Ms5a=Fk|0v}d+;6p_ky8Eq_U4mfk1GfVRp1%9@tM7^5d!?Pf zRrun6HPSYuoSD;o-(L)|Gp02QQq!LKI0~&J(7!C9$xVo0eUUi`Vwqw?;bZ9yUz1L| zkIVi}x+x=k`9904GA342ETZ%S0eJU0Y!?4Q2nY{;QRt}!>nQHqjI2Srd-+m10d9e8 zKEmr#WxnoD!v`3{99g`hKMw}RiyUW=ap2%)YZuGfNMb+DuV*(M7tK|DyA`??9%OCs zzE*r9qDd_&HBLhn${y@|P)n*aEJ|T591rQx2PH5y^nG-dX%&vqykbgGk4otW@Mp)6 z?z)QeSERce2^5f9)fX%k&wuEE(}YTfFo+2i{}^U`TeM~8_)oe^v>!VWHgtxffRYLt zKwk6uOAX73(1F5WNOg2}Du#Nk)8{;3fQAC7MYG&qaDVjGtq*_w!E<-nv$lOi4N1!7 z2ayeK9j&Nd4sp~Spb>s^m-MXhVazPK_Xwba{PND-6HX)Ua>X!*2r^A8@uRSqQ0%+NNc);;;AWeC6bU3X?)#nZ2_> zxv`KBF47VbL`;OxlIdQb(WeI;JW#|5l{s!YQf&)uj7`o05YiX=CLWTtOP`FAAt4ms zaPAM?RXKJj1Z4)ESPiZ>?P!oyh{gvFfr5TEdUdKaJ6v=%ZLDR`n;-{NE{(km%qTFc zARz)^>LVbvH@2bJE~;0FJ@#Clr}4jC{~Yh%Gvb;&GVb3(laj9rWARdD1@i4%Z>!IR z+ZIrzeR!2wi2g6r{?iKiOY3m4(4Mbux7}pI->(Ll_iKJhZ)y~}oxJn_t77jZt0(e-{`wUP-YWB}3G>BS zpZRX{o4@8;u@7}gA+WO%{~@I_>Fnyd6k8}@`Q7&Fp|JZxw-Nf+f)9H^CyfoAs0cl$ z$TuWH{PpBZ%2MiD-fJ&tADJ0BxMo-%%Tg!X zqy8CPK}-!5#{Pa}`ys?Z?6J4ZDknnt=)s`dqILMT$!#k&t2*A3CBH=;@?))C(IfxG z%DZPRfY5^%7JP$So~!Twv08Tj`ucS7ufKBkqC3|w-6G-dKijJJgo)U6m>oN9XmX?q z_h>@>Mxs4r>+YlWpRLxgifloE=cUg|VB)k;TsV5$(6)5ir@0UPTPboJl7v^bm;Y_q+o=YHA$RR)U`J+-iqN4U@j8Db8>SPhG!hJg3sQ7axytEnA}UOqmZwqG|o zmUWqny6z2*J}SAMzX#-SavW+^HnOTlkiL)7K3z zrPLlZITOOIx!?f~>_|`luCfN^8C9r>xp=6V1X&->p54GbQ6@=(j$Bx!MH61O$!@XG7!SCy2V*4~_JbCUmi z;$o))355cU)csC|YogN9CFF|)nYdT27mckXeu-9Uq5MT=ML8b+P{X#(#<9E1klnJ>~IeOI{QRZbyb2E>bxIJ7s&tYSvhndk=4f1sML z@a#i>((#{51T%uUaC4k}j1*aq*BKHHwilNtI|o^0t~S-bN6= z_`=?wcp|K@45qcP+O(GJ@_&?NjE7`G^tj3FoCK34goj;JR$tYOG1o-t8E9$SY`-o7 z3KHyh$o>mEZDPJ|j|Co)+@{Me#zX%PIB(YyS@8}r@1rJnO&&(Q2_C)Y-X5IZ|G4g9 zCtHZhQ2nR=KVoPyRCqS&D2%k!BABUDJmuQ;_?1Z=q12-+3>+o9zG<;NbpC{K!?f7C z(cP8}t}kW^eMM=^I8@n;K5iZOLhR7uovP(rzmXr9N54QX{5cOIljLw(3wBqW{8n6I($zw{;!%v)8zPH8YUqGyc3FFe2&>Z;H)QF&4v>3Fc!2dTeqTGG0lws5>S zif>699lp~zFj!F1QihEG3OO9${rr*S)SOoL(sb`8r2nTWonz|Ys^_!J($YvLXG<$D zGP!KRv3uz19wIMhXYX}cy8f8JdDUs>7m*qWVQUyy5R8@`;@oi(l0n2`A8(Cn%MohF zsCIE+aYtY#W(5Eh;XsM@B0O+tSasoFjg^z^tDZtzF#Q^YT*fT%t#hwKL|#Qf!&0bp!cC9eR6SvOw3HdHFy*x2q$73` z{zFWIUD1QMPwvvUbvR1WhZ>INg^N?xsD9}tDm30+C>r&fv82}wpT_pYt2 zE#&o=KE~*Cnn0D1ceU9@qU8RsU=Jjg9{xX?As9r97W=a@k{4)v{nBFZEKL2;@)>$akXRM<2uj~E zXH#&4L+q*WD`GNwH|6U9D-RO61d6m~Sunguzm9lsAn9ZhztY`n{FO}QOsX~enFqjm zrU*~zU+WaRpL3Zr<>~RK=5j`JY4BSKR0e;hDe6*axGnVLVe+dJ&T;UPv=5g%nBbY^qRT;6f-QCZWCUKOrfS8-Ebpd!KD$Mx$ zIZX!LAPm6rAcn42W}!tUl6dQ0I@{YdTOztZG6B&&MIJ-J;u=eU6-4b&x|?$G+OFv+ zVYv3{JV7z>rXb!xM{P!VR_>%2_KI>Tk}1A7yqEGH{$ki^gx$7d*FXn1X&n@_yY)M^ z=N827P1gwe{EYQLGX-Ukg4&@JtHq5g?LKo$H3nZ&=-d0S8_f4{CE@{T=_9r~%Q!1Q zAtM3WGDcsu3HgYZGB_awuhHaXZc{Y4tHZfVs=?+fD@W(?7l0Q}0Jp*rczj#5EU((k z*jPB$`)=&e`FX?c2gvWQR6l4uiZbSBVenlE4gc!uIoit*{OKZo>`JuX73=W&>H?m1 z{NEqTTS~1w?#{1!4$E_-oPjSeU{h10)Of591p8dz%+{NX=zX_*n?)9jHWBt?oONze zJ86j4drknm%?&Yxl8E1i{pHY2y=64A`j4MrsiNF9l``g{uDWklkVHLWlv)}R#cO@DO!;lcs}f)YU8lET5gvmd*r%b!nWm`dfe zDQ=rCY2z0=L_5&-&avIkT0n%+@mQvk=1e*uCFFXIal+0%-Le|s$DAV)8#}9#iCe$8 z?#$?}j$l>H>M;OA9X{Zwu}4x6ghbcVS1!>b_WC|O&9m|rIoYTe5F-Fmue04HUvGd9PePl7)*Wd67fSfF_3=OYTb~XM^{`|?gVjAH5 zLC=x*b9fPA;qvULZ$-rJZ?!?iT)_jiFLRYj;SAJDx`y|}2@vqoKwL0`_D-l1`JrIq zJxXFuVLuDe8;__`nWBLe;=d>hIFye_yInuYNl1i@Z-~w;a3vTWKXZ6q&v!aASfJ{e zpb4#-#TLL{05PvOx~09mNW>oQSSXWwnzNnD^}U7(E><>vIQ0P-@AlYz#%6xRf(Ipc zO6W0jbMQ^eXI;+mrYEO4(vVX3SQ}Z~oyA?|?UgKA`-c9ImwfTSSBa9#>Ax3Y2O8_c zE;&x?q?Uxv%;b+1g~>a$tY|Tw(if#X?4vl6&_k3J=Nj^NJgBnhtqxPXV7er~Q8&*(JK8EUhR8TLW<4%{E1QWiQW zqS;y@7?UZk55I+zGr^-cj{dlW78U`Q@s%JQIeC6_quB)l60c;-lF07$yw8DWYFP(e zNo;D+ad6ckH^b*lhfpsX2g?DuMac7N;dIuola&=m!))$UaI}9s^56I++}M`7bM`gp zFe!Th<{elmslXB|=qP<2;k$&rpWjnId-v% z?AvGt%!!ogl^gM`-S>q!-pPhX-^2&2ZQC-WnMU9Ajrkf2YVZALnUej7>hP5eLBMGa zzjSc2PyWTJ*T|5@q zX12RTgI=0Rl%c0E&x45-%xRI>m>|Wy>cZuqTUmRUz3TsL*Cb6XXb9oV`CWsl4ztpy^`Ct+2S*TbOfnzxbnTS6(R?u1uiT9yQU36X*5dfNry2#BC0ssNIcc1A zmVxaPpg1j$q((;%4=Y^}aT!r(XMPYFLh1)07BK7IV`UZ_0bntb;Q(lk0~h89u4v0r zw$!cE=@-0Xxo5D2#)&wFx!Cvew8D23Xda*MT!|6KJw?(GkTmh^o6EItqPLJqL?rNr zibFf=N54pHA6sSfgA(*~xKlMqRn^uaTW(*TmQ-W{`D{Fu#x1v^%J^5R;5C zDA0elQbo$=deTsl^iv_>JDPUSt=grY%q7zUI?xag^iZAN;u6W3Wc7IOv0~y*pZ3-~ zT4=r&0T<#-gBKpKr#kah6Cj8S-B~ekw$RekGt&|v`6*x(0s)F-FtL)!^`EBqy&B8M z@SUjhUZ%$FMx`H>Q-SUI)Uxu~m)P|Oq_9~5mG)CIk)Th#$-RPy4cJm=S2F6W!~tdu z29LP2E*#67Uj@jOC!rBdv(pq&$uG63Pcn@wiQKtUZnbx+LR87%Up|utf)A2;fK-kF z^(oMm*oC~&!X!Cy`_IfD;14SsYRakgJISMQ{W5_&jiFh}&Uem|(r5s^W_sYtEAbbn zM5ZKX4~I(bTeEO782SdvI>FMKe7M16RQtm0?Aq8WB(cU6vrpwyZ6e>G6Ti0iWsp(J zlVnv?yOj?E7GZ1QswPa|{_Za-3SqkHVCu0)f!GU5O=pm5FiGT_)MG!Yx=dGcKTzEv zugLt8@(!K?zw~ONY9u3SsC*MIUZNUSDPDcN^=$o&s-%&EP0pxarW=;&bw(}4(;pkP zV{lhw%}-QAe?vkPl2e~BO-}dbX_cg&H|MH9EghZm)2NM$GKu^K(i3!Bf^w+??gpTwAv0U4Si9c_R}eZ;*5m{c6?Juy z;P!@d076}}xTQn>gKC%!?m=e~VuCUuSRx7dY@G7SHI+x2GHxPK(YhJ#*;6rw%<=6l zC^M&rm>>#!YAxyx$!5>{eL-tbS?1VV_Vh;mg`djh{=FTWGbt#;GXBWtAjnqfu&+*@ zoxl$+p@;NTa^W%%wgY(+MvRwV+oM3pD3&90_!zy$k=^^`j0jp+1DgYZesFJ_^*-UP z!!xPZ>N}QT4)}~op+NG+atKa>Hi=?#813<-z1)2dEN?W)|`orf(MQ<<#eH-4A;-Rk1D~i@+59JQ~yHJDg3r63RL>Cz$t?E{Z+|P&_>=mKU~WjR z2dl-yci6ORw$Vq~3<=Qzi#+^j;kpSA)Z<#`CxG8nV%gZ-ybCiZP}q8UdWf*m;co@n z6nNv8S4k)d{py-3@na@lfbj-wDoBeb1pX49GT^O6bD%DxPj2XG^A+Xll=fLPWeq?H z#b7MEfCHg>*U;N{oLZc8;e$?!S>J4;(4JBag-{4ZUe;Sb7G}WV71$>V{z|d#HS?;$$Q$B9$})PqocF*>cFNwBEwj~ z5frB>PDpaNb==!LA2}?^-TzUcT3+_X#5Sys<*9X&Z4&EhCc?dJOBj)Qfq`Y09J}3l z?_z|GY2ah;@@lU)tfdE*5 znR%{%u!Ar_DE_-89EBOJ zuJkd38Vz9~oK;VxlE~kf8|7J|4{QXT&wx_dKY`7c)D5{zc(&uMKM23O&0}j}`u5$x z-;z>pNV$D3_aM^Z@u)O~2mbcQY(&EtJ&|PpOKb)n>x&xG2G5OV;K_gz8cEkAue_HD z8o$L#Z^Q#-0s{OFR6MQtY^59)M76%Mwhtk#cLZV!3oByZH$dVg*@h=E^wytle;oxv zYWE5dt(nA*CoHS_e1Y>M2#E)9!GS-(q}gBJZVlGi=43ru|4!>Dw0bni^6ja&(5+qUWx4{>5+Z}XM8K&L$83#ziY#1_Te_dCZ6q;E;AcxEj| zM7gQ76x5wm<)~);>6UAakHyf`i?FlCLMe7X)LgB1$Z2N<3{<2^0*$%?H0}49$#t z;7i)|l3yU=$j0H<$7BuyYLmg$O6Lw8Qsw)^Ds54ig~q&G*3gogzSj zJB7rno3C#qSh$cAuw_)1$dR=Nppfoc>lu74P#PhA&3;lBE7ZJKkZK0n_xLTtDwn(e zmLwgofwNBvi9El;BzZ}Tz~7_<5#a#~5@Y1PrDV$Tm?qVTI;wG$cP_-MHmOI<=4gHH(hf+OXb~LAgTS7Ul645Phc9?JdhDFsI9p&bTKnSiv*%VZ7Kj! zp$u|DD|zK0ZY^f8=#LA9)iPG_0vYzEQYXJY9i z>jo!C%b+Ca6(Lff+;>T{z#q@>)95EZXnXv;-@taZ8jWR)L zWyVKB2n6b^!n2;Nkd3Ypf>)TBj_P_t$15rpW`EBGyL z7z1e*xl*$CD}LhJr>Jhd4hC4}4(#l2D{)Ej_h}tXp9Xv}`~81jfc=dB!vEGNy!_6C zd}ucv!t=-DH#$iA6)H?fdHsrihM8$#-%Ot4Ri*rXsTcm)QTY~sBVNS={4zc{QZb&t z8?nl_HzaPAvn3cL5bkk2YdBr8X0;s@pE;HI7T0YFBz^K5^VXpMVLLKzY1L)$qf4PN zJ72E%aSmYFFligl8%B(8y!>q(mEZs?QBI}Q!2+uuKZn0HmQY207GUPP--JKoAueo^ zU%*PObgxk1Q%w_9gtp~j8|!p(lT!D*GXA5ok&#d`FVQ!7eOc0`qt?Qw?Sw%gQ1pou zw|r0cnLr%Gc+Of*sndFTebSl$FHz0_y)~j^5JQjsfn-9!c=lK`3?p^HH*(O~0w@5C zqVY4mF{7ck_Y%~tNme-T>@?f%bhoqYEeGhV5#)`1bu3Hn6YEyU3CP3@{5rvyrTP`; zRca{lFZ`6yDF&fBcPihT*MuvH?aXvf=1p0l_nkyBhv=+9ZpsJhr&BRN6?-yXEvm&ETm4 z1#*ms^Mg|Qtgii$x;00_Iceyo5_2eM%HWe~7aLy#D}bjbDU9hE&+b*Gh|dR*06rVJ z+m8V)73{vSyj+55VaapSQ_879H8k~6))A*3<7#5B#o7+2ugKO75SwLu_j5L-ty}x8 z*>Lf8HqL6=P7{JJt&kcsXa+0&Nl2LD>R>9e#}g8?>xYWZ^L&l`P7R$|9zTAJ>~Mu? z6TIDv1FYE>u~k10XYMIc1kw{kgi7JPDH*uw@-F{eHW91n4A+MS{6CK$H$@Jqc10C{ zkk^1#X8k=hwH;ezARfzf&5HQ1lOHd7DIKxo80M&ZeJqfn6!BR&B!-rR|zIjvez z=TaxriA8L70Imu62Q*!HT5=8Z&={?GNW+pk{&TZX-h*+ng9a3z8JDV0_M=_5VfS|D z*-ZOWDjKb7J?^pPeG8jlvWO8y(m`b=Q^_q!yuB8hR+&@uh<}Q8(fo$d)YT@Bcl)&lBtQfXG)c~zg7IP)zAZrT?!jB z+8Q_1`Y4^EZ+m$kd!ESuE!p>P>Zpge0~cWis+);i(e!@Fs;H-rSHASmIJn9!uBMvz z2n3&LjAiLzwq&UM)!gZlekbFK(0(f$SJfPH{XtPOO?E2siRk9`;RlN@)&n0Z6duiS z*PH7=p!6+<5z2-1E{B2@>GZVDS<=LtNX@D*Tc95hLkM@#=S^EC%m4$L*Hc zeBQ*-%AYkDiDHTDbABzb{YYqiGGn_wXUNMgCPWoSH?x?tRr#_M{6-<<1pn0H+qd}1 zWAsrB)M1kkvL$l23PWlsf_#E5&dObS{H4R6<9>hlxgK|;GquR3&yrM(Xcnc?X03-^ zn)l^0iTl_jR6a>O{Ued{#|j^7{_xa3S@kz9bxb$9qLvj0hX5qwfo@bhz24s*yIuEy znu==d*ULithT+UEOl=61fx}iFum(tX*vYObxNpG_3Y=;Rup`5E1{y88V5gBXn-(|0 zY7aUJazza*-HlU)z(yU;1t5V*sfNv|ih=VD^2%5DKR&lr)7Q_G3xdsUbRKfG#w;eb z8vak|K+ZwQ@X(JfdldQQLbjIbKXeRCCQr{A?B!}8r^d!XXz4zPW#xnk1m5m0rd07@ zDaf6Oif^?wO)V=pYj^&e6az0MT;K&EE^Hxackj~=sZ$+x1MA83@(;R(_oe#B?e>(* zl%5bpeOmGwcqD3F`RX&xZK-6e^gPZzl(rO}M}ib-<4!C2ecbf{1VB>iVh;wh=I))Q z1k9&syK{{(CUOynPpHlU=;3!EAAb9T!n+5#h%QU%{fof=elc2h_Cht!>46oLB`^)X z=D7yGGi)ZY!?}M~!s>;Rd@hYlSwWBzT0AH$?&*?3JP&}Hvxs%BH6kbJPgb(kX3icC+#l?^fgLXcE~ zD@*CW;;Q~6#Vl(-;wvEUxEjilKF7g4$Lxyw1lA}CX*Y6>K@Gd3S^(Qc-eb-nTO*M= z8HzJxWKm@Q!nk$cW?Ja`{lT{TyRPWyr(S8wWvlW77MW|hEhC|iz_S5CZH_|)6710} zswnf8`1v$sa5|qu_v|< z^)N@|Xe1*|{O|g~Duvuh;fb=%tEkQUS?jCr5M8V|Cy(j&eD2Gs_pVUiV5GRkkA6cA zlyx{GuC4;1T@QOr6EoADf$eqLu&r0aldKi628m2LcrXr5M^6(?+}7L-(2hz|99593 z7;ECU+XfngW%xS{chu03*B*V99R5Yyb>Et4kB{n+BySMfq^KBIW3PywEuC zf{*Q0FsLNpbUR%n430#yY@s6_ywCd26*%4gJqEeEstPzxb3{Y^_ql4zp0eSKmbv2x zuqTCr5>;W?_46m?HKa;#09(}>0q}lgW)pJIzB@nOs=SQf{!%nOrrT_F@FDU zy}iAiqsu3!LFd--$nF$+;lWx7JOQc~?j=IkL7yQ}^O2Z{2unsE9Yz_%PHgY(!C8d~ z_EMB9b8_+llv2V6FZmcFEJ!NGS>W>3Q=22Nb^7-Aa;*j)#MSjTX)SRYb(k^0S9;g< zYTjBXW*q`cU2^`75f@Ce;ajvUM}-vS-`L5m1J(xADL zh$Tzh2Yv+(&&1FV@B`HHK#lxYhKqA^;8*fFC7qcE^b8 za#3Y9`>@3c);m=G78Dl@^^-BI0RI%E4531nTz*0>`1^5x#iPD$k8Uj$^ z5d=r~^fza@lxO};5Wv6G8RP!1cpRO^ZSIq1fqdo*CCFb4Rp2d{she?liEu57$-X)+ zI9tz;!LlvkR!VYvpbFH9o!wJvt_$%eI5UT97X6e}K^o$+{#n0=2!CcwCThIuVIeK7 z4$~9mlwvykH=WFFh!t!`f~(c(pFAnXzW=}|`nXv5@e-X2kz44UHJ5alY>@gG z?wV;dy%!aYckJ>|G+*55ZBitZ4sszqqzg|BDi9L>A{Yo!_3j9# zC=up_jaZq+H>E{IyI%`mH`}OU<;=xz6r4rO-E8qK@b*(vb8SUT- zD{&tOkK#sml&JUc$$tlElcP)!l&--?g&IU*L4-vQJSQ`$7R#}zQSDfD-mebF?lv0V zWr~Ry09u05Ur-qo`cR+)nGldnRah5Nxog2Phxc_#OZ%1Dh=_ip8!bS23W^Ht9Z!cT zj<|U&U=7>E`KP+g5!<^KJ2zk|BOIg2rM3X}_JLgPo1yJI%32_cB-8^@Ich2bpp7(2 z;a!}I1ZJ6+cf4z@K86)p1_yCJ=prC+BLJkkFu-8l?Qi9C&dK;%JGf;nUtL9>?8XrF zfgxE(XV7*-uD>L=X*A?Th#_lm>aTBUJq09AI-)`=v2yh^iuJmm%2>_u!c3qxmKP0A z+S^6wUEq~J-^?`utt}=|Ly1?FP|S6)10lTK#W*u?Z=ob^p!1_)W=1Jwm}LAyp{WaH zt7v-Nv>6KufygOO$5tK7)-i#yJas-JXKPYO5{Dd@r2fO3x?BOOjG?kpIhK9rCvZIg zo&yifB`TO40{%z|-j#!0765zDs6s$A!1*A91q>8UO_-H*+PQI%<+7Q^iL~Z#lCdx?q!R>!PMF1QU>%TZ;Ut>vn)=A(c25v*v9SC{=czY_wrzyoC z=9Zz+v=EJpZfKI<{SnN(s=MYK`0@6^Q%wJewHT=VX&8mdV9$VbUTyn!M!KF#28Sg7 zBbmqMxn8s2KUCE3&e7D)mJb)=!JO&5Adg9Y7~R&>LjeDBP{LpOzt*0`3=HU+`|HDL zg&F8vbgK7=TBEtzUt_}sR z4`W3wox0!f8KR+mZ$&jf=5o$W&iv@#jmFCr6GpsA>-1s#1WXT1<8K%r05M=^FKzuT zgqV3VvNKc#!^kJ=*9~p$+#()S7mcVWPSczKQYDGy`ej7gB7Mxq*N2At3776?FES3= z2d>lzZxZJDc?FajQO|l_W_-)eD~&u;jGgNLflW;`jhkAUq42Vvh<%q-H=gS2_bKQ5 z-ptMjS`o%LpG&oYe?nJ#ug|H$_Wk)Zt5f#%{fF&*SEt%i5AR>kLC;rv^B%CyBDCxt zFj)CtpT1_kzB*{a46rKDJ6Nu%sTmrX33_@9v#j$5{6Z1;xUtJ`rn)8!Uq=D4{j%}r zCi2P=-0`*g!9_Z%uh?~J8X8_^hI&s6gCpc3^Y=LlMTXyPZ^NuGkgK}lQd=aeS5hC} zaJc4_A;nYXQk0~4{uj(LK!WT;<8ONPO|(`S<3IX6>}Z$W*_ZgxC~}p1i`~J^5$@Ac z!=_T+y8-Ok?Du2V<_e|H+$;Ys@^V($b$&KjuE-yMHBA-yduW^S@a{?-7!cUpinh%T zFQR*jpBtd!zx^%`I`Ljr#;?27x($eJZ7GOS6TE{6zqo-lp?mi}@G6#gNEQ()8xGg=|yWz7Pnp(kXCvx zczxTxO!A?k5KlI>QH7P?UR{XxXGw)X;8l2i`c9VMme`OL1uFQ(QVV4xT5(||3rqd| zPvht&XWjMv>*f1PYu8tEZELCpnq8`1Kb_AVE4L8m^#*S4SO;S#Q`+tze&sq|?o6AC zvGADv$DokA`0?B7AgG#!Sq^yhEN9_e$UnGbYu#> zI--==>zM?gS7eZJn~IhAPC3gUt*jRxVfI9btR)(N$uI(2IoNcpWxtLFv>VkKVxh@2 z_%oF^pJ2IQ5@p;EaMCmRX;E2cniG{uvHR$@(#rZ6iRnju+Zgq2>7clO+8lMNKawWp zpOxRp_P>%Ks^?^oB<3C9wORM@WRDNcQLzrHvU>EBPOj)K_H{0E*bJ8Hg_`NTitqq3 zS;smAAtDwg%q&SKo+_1EW~M!maiNlFWUPqs{`zw6`h zwXOaHS2F-d2iv9<-Jbr&OfhRrty@Qny<3KPpy~dw z5D?hiJp6;!v0Y;x}!B)&Lv5g&%)){DR)cvRsDRIH2Oh$pgfOHjNo45smh8EmaIYS5;K4B-uWJMec_IrU;|CwC zo92jf$hsrHwkrI6#e*3o*VZ`f8oIDl;CD!Qvz9RP-|}Cl^M6{Rjej3x)NM#9=uJAZ z4{b6ydaC%6-3%UvigAz>xn;0L{h=QE_1OK$o-_Y|u5h#$t~nqD!NV*B9%s}7oBjGq z0+op`a_=513En&ii6+Lx4Dm%xs=!^SdysbupoFm+Y-a$5Kxu0mC@~hq%9QC`DAgORiu9A6i(A1o0SjcyI&I=7qV1hWie;{G5`wG>9y$_Az;asiPGB zr(T&XOsiWgk}g>--p@6rS~$k+Ot?c?NPN1_N`h~GGsRG6*R$xc?=V}q5>NKSn(y=( zX)50qI+UETb^5};az&9RlmB|Moij5N?e(!miB~=6;UiOx2dK@zHGPU1<22>vZnD#xe8s1+)rlZ{53%g zwpqgL>;F^_;Dic%U!?j^Q0-cY6%0J z%A3knY}H+&>;iJV?yXI|Wf|ztA8DW=Bt&>J`cTlpftUWotqR?z;*|>9nWP8tPj6LJ zR|kU!+!Uqv6p|=k^F|aI?yvnf8)X-^7Fd%sq-!Ihu-`=iNHTx|G<0-ibFie0WHJ0C z$L*_U{A36J10t4MsJ_)lu1aE@Yw38K5MyD~`Ty8b>L)M5oR#srTy+1rcURJB{eHX` zlXsdoGx#~dO`11-8L~ElH~pHvn-K3%KAw~96;yWxKy)x3#2&z|0%SJman#4cIbuyI zD#wtZK6=@7Go%$9He?gPy`#df0jZb64=0@!&JcqxNXhS*zs&xlAh6a|&TBbYM0~hw z?JP}$msi>!+@`|-VTO4z!(l~0O&xeK0FDnf2~_d9X~mGg@ZXFMeD6$jq_~B=S+|ER zRdOsB|Es>WBXI;mzE&TVG2DN?dSZjsvT_P;uwUCA7rvn6|8_c$MAHRiLCj$$U}CKu zBKsiXw!Bt*@*8WAdwz7+Qlh0WE&6cSqkMb?r0iL98`mviw!6Uv3yVLufVf*-_Yr|(L!K5OO_F5n*z*9PGcbxyT-ZS@{X(B1Dn(&fK zDxX9q4&r!j#zd0OH%ufdBiX{O+{8>+n*v^4$ke+Vh>J+|A7`N-hJcl#{jvpPe0)ME zE7QctC7D2yIA*j^O7K{_jLvErf z$Dd73M&+F#z(^&Z{av5`3?YMxj|a_#HY@QbmGifJT(pT@g!ngG(AtRp!8-H5wZ*7% zCeW(FZ$o{6kfRJx#d-$kG-yy}qW$RjqGa*Wvhq8~Z{{sKk=#vwddnGd9-!T59+Iag ztZBT{&YPQ0!ZU~Bw;u0O3wtGUu>rm7Q3K(CxHm+9CM&xa&Y?ho01YPvk4*)coI1WZ_LIU0#kmRm<+VS>7D25@2! zMgY)BR%3^i(|nj(-qe&7-aCa{?vpNyrIteLH>~zkD1{)@BRsR-jJ`nz$py}t#q3IwdA%UyuK!)nFIuBl**%;)^t7$O6881X z^vHy&6BxT+zkWT|7zz|P`^l!_ScOKdS%dhUYqDRkRtB336|?Ip-7j^}QT1zjRPsk~ zSTy6`%i=lEQKIzM*{}Yj?fPO7F$1)4|Dy7K>)h4OTzYlEr9r-M*Iv@r@i%+Rk9%Ug z?4BOB8`m*C#g~5hmrOM~KM%b|zyCZ`x=wJY*P%rl{p_nUQuMV$!MxsWBVK$Vp}=zN zwD;t8&4k8|UE;H=r^7{bE06sB`E=qm0WpB}%ULy`Xmg-F_Q+2wt?z3Y!~`(jm8K3b ze$jP`9rS>e>+Y93`Sqj2IrnXg#tLG5_bTg`zIEGO&QE}ZuL6QXODF#F55zzk$wi_U zh*ka@lR?BM1EB~SCuaJkt_cBy`p_(WGX9h|V^!Md?{5RqR2h|FLFXFN8I@J_mc`oJ zaM9e}#^xb}u0!=9(z=XN!n0~~zRJ=ll27}nk9sJf0s&4%X(0uC7-Jfn(4NZ7d3*? z(otX#z$_GGgEPv+QZTDly^Aw|&IjeMEbwSaa}-`JW*B`^Nv%0<0@i&WyLPBkVR?onA6+WwAR^ z|0yT+erv=MdgeE+rKTE!`}`iSk_~=IR7v?QI;ZZ}q{u{ihxRCWV_c!O++4Cx=9Si% z4JWMI4%=`8EIOT&vV{7YcDa}Zl9M&UbpM0CgZ9;x?#~2`6)>t4;{(trv$|MIxSAc+lT?(#1hyyJ7 z9Urud-*A_LK>Lnw4Cbaei4Gd(`N{zqIpODFJ&PXS0R@8!iLk6JM!+8H&sQ^m^g=Os?`r1!=>Z6p z9DkfFPxD0GOL*8OW0GR>_E^ER!Qo*8DKDc*F0zUWEg z&+iVMARj2!V2pLpw+Q#9J$oSZMWv*y?3qw#J(0u`Wt76u^mJsU<-q14ubNA}ikWPC znKM=9Z{>cuk_t@OK7Tp)6!@Uwo0XD{Kohj?`1B8YB>Ss3()_BTYJ{q82#sgn!_K+k z+TCeL_l!H8=0xN9RW1lUiyrQMSm)?8PYKIH^vAz0k#COdkh5|0-p$!N6dn}kR#vsaF0+`E*3Aq*l!f4sv!aQdC+SO0?)^m!`itwZ^yj_xhzoLqpi2$K!J=7 zBUfAU(}F!yH!}*c(z!u&?nfGKaq1{c31YKBGl?pzL3oqFx4$^ZY+`(iYXDLM^NWk& zA);hgPXvF@BR9g(X(xcM!N~)NiHUWaT|DSvPz45%g?@EncufhK-Cwh_!At$ua#P=N zYLZ^Ay!bJw7Rp z`~G+1_afzOSEv3--<_)QtMT8qCI6J$8ZTZi%(UU2HM=s!O@B0!59jjKWh@je>PoKM z=k@0}6xcBD)+4bdT)Mf!gZv;`zBk*NaLH!zbfiT})yRLQIy%&p1~)_HuN$XnA=BnUb568*(B{d5pQmYSeZ3jdQS|w#9cJp@B_xpF)P*uX@q3C7 z%8-0}0{1aqXi%6{PA12Py5%vcnJg-$_C(U!SJV_&sS+3nynWaEPGg!ikgjpCSE+Ny zV+kMy$YX-RNETKf5Iu*U&b?+vLqXp_*vPY?!!x~jymIz@R*`+h4(q-7{%uU$^M*s6 zTI7R=ORJ|VBv}0kZ4rJl#{s3J>#Oy4iGE6c&7DqqyF`ZN17Ct3qlKQ$a{tNdEuTH| zIfB_FuFnFSJ7rDI5$V-*QoV>CdKjRe(sg-9j4r?4sMp9J+!b1(@f$z0?jNge-o0NQ z5-H%o?NUc#mDpgXF90W0U!XD8rTOfV3kjacQl_;G_bp_jt4=^xw;4&4Lc4gQDtmgj zBnMeosHWwK$>PREn`ix7t`bGHY#GXs)Hu`F^`4sz&%(mESPBc+0VGC|1}iHo$sBrl z_i3H|2=z>JGFLL3M*^@r;@L?6UnhyW9Nk{6^@G9c^&ozLyj2 zXUq=wu1_!1d>QweP8(yfCFb6EjjSEz>J;Z{@xXsKhSPfU`YcA)adeD% z$k4dBZdFt@U^flKWStS|OgvjS@jB?A+RFh<+e~=FhxWMM5mH;kjnTaJ=h5T4If}H& zi^e4XUSR&3i)mfjfS7MV1|r^V4{W&AArJz%Dz@2FVk$If1qFJ$)G}PQ8&%E<(gnc! zYPu26O6O7PVGgnfi^VZV?pss<3$D0Psv8ds5T`fK({Gcz7rMT#tN+p`byozv3y=_;La`%fv-o`xJT#YfhPsBCZ>N*eh2E5o4JTBPUtdb<(Lf`m>L^X(O(iHG z5U*hL@=t0Pl9FBE4FFL|B;oCBGUvb7bks@0bmmI!c z>^%Woxn=tmrsYqcZpUq#R_VP!XnpL6pXv8IhD7zyL<`aj&@_YC zjA(uZT~5SfQ&Ti!%xhiz+vwd!vw>V_aetQdafasG;i`z8C5wws?|etsQg2{U+(BF5 z*Er3EuNOYwali1d9bh%a;v6?5HUc#PI*9W{I6{y<`)Z@N71y)#s-+sJdl zS>QppbReELRER^oFS!G#0BF{sTp{l|Q&IKktoO9A2}GKm|1M7NRSj-riA(@`P^G6L zMi5YDpLr#s2GR$xA2}<>vkXCoR{oF`5@}F8)+S|E8|#ktvdLwK$7Cuaori}a@8Q8R z+%e)l3#$z(xb#jA}&*6qRJRuu)3fikMH%7;q?~dQG{t!SS*@| zISF)l^?ZQwGT2x&4O^X=o;GO4q0_dqY+-+&gncM(mG!Pb^Iwg>c*?xW-+az_fUX0L zdg$27+k3x*lch73@n8S3!#+48f|rhpY8Pd8J>7f#4q}2pgRyvaMg!sFs3!~l9K2}d zPi?B`ptE#0EE;T*uMenS2clxB(?>8ZEiL1o-hz@Kph50?i zT!oj;+tSs*N994q4tclzq6R76skhKxuOhDk2tgjXxt^ z{@7QifE94vqgI0tT>Zb)%f!?_CCBxdY1odI?;D}B$B|zC8JRP2e??imRb1{lSy5Su zS=`5?q=fV8f!8)u+qenT5u8Du-94qp13`}sZt$qQ$Nh}&^LhyW|Za)mt^#8q*+BQS3Q56c}sj4@s-OPA!pj-Irqd4K(F1q6!-S?C26 zB9aNmR|vQ`FonH1BnO4&rXz}|kwg8qD)rnW84sVM^n7lfp0)uZQScW092j6vQmXPQ zSw0{B&hHyUv10yQa}u+I+J_x8KFC8FX{(62_+<9k#Pgj;jhQEVy1Rhk$y-V*++%*Y|6JbG_ z;?C6U-#+7(XQ{P9C6ZPz`7jU^7X8LptI4hH9t zpcTAV!B}#!mXp9w^zBw;hj^0fv#M0r=QT$sS^cFb%M1j@TSP)i${R~|fjsUrpH}Z% zhbAfS%(7Q$tdd!zix-|W!NYQlRLDnvqygUBw}=|4s)TD;fQ&bOuI;7nWU0r*Xz--8 z8DppY?2Qjbl+pxzl&NjELst!eKj@|_NkWIWu(?u3w@O>A{CDb}TBNx2-$a+q0(G-5R+3Q`1C=`Qblri%MEhs6aFruxvm+16~q7 zjM%)$zCO>shapQ~ZEd~r;V`mnzI)zX{~_IEF6}p7Y_p||eeZ@YJBx*KiTO?Eh42mc z_dJTfJh=||jtCQeJo)@#+^8sh{l3BdJ9`7FAnFDTh=E5!V`1fx* z6M@CiJ&+$Ymq9E61H;=%J5>D`Y}pXafz3SZyNo4}FK#xugz@!_yH9j=B{4BEN^_*) zuRI|2crT%b%$tz+l%?mz#uw^D*>{(WMFEN3X8YqW92d^cbX&;*D`w+(>>wPQw5G9o zyWz{nugwQ!iHC30oRK~Y7?}mf#}tNGQ65UiEq2F*ZIwP%QO$^`mue1XbsOC`PuJt)H5 z(U-l(`bXx-tY0iLZ^Up#21CHx60|yC$bijS9Eh8v-+++~Q8NuDA~=ksWju)JGfG4R2{abm zyS%$wgU)1B>A3QU;r^o@3x6DQAmf8TT7+σMkc&4KR%2iGVGkpgbIl*1z#L`6> zYlgY~`I2YLgx?UBJBa84bwPT$rc6xc?Bx`sm?vK^HC?7iHJveEGlu(-7Y~ z9f>(OBfeIf?n3;qSSBk9@h$vF1}{BIQa`D$ zqotLr|3;x9I5(Gt?u2f4&JfbRD4-+iMfG{4EN;_4$*f1tJ4{~b@_`0jVKrL&s$PV9 zdZ5+v*f?*JVicM@2=<;CzQTT_u|NL?{7oBrdG);c()#qg$^&6e@!daJ z@Gd)@lX}b21rRf=E&%SpZr$47ADt>7Q6EIVEfS+JD<+MUj9^+6VOt9D^?(si53x8( zEiE&6SNEGUC;iXEKb|aueBR$6lFdwt1kY+yM{J^JRTsuKfT^KUR9QlfNBRlQda+OK zd8)y^?u1BeB9G-k{#i35n5+?cdd9iDeZEU zmp*fT7j(Yy={Ca-a~Stqn4{tI{<`d(-gAQBV>{xL|O+%MT3I+|2`R6TYqXd;Y(6Fn>}p|Sz0m`5>lX@S0L!M(H4~c zM+eYMx}VxiDAYP;!zUHR3n<2klOx`Q?qrmo5#;T`xY|uYDc5an8&j@_ctl?^pA%N{L|G; zQ6ZWBYB|$)*B{KL1>JKXKP~=*#qUnBKN%SA8Yeg_eMxgZFD_~iE7k4MEqCX29Ade= za|k=4VWhS0rUwKuH9JEwSH1Z>?FbyZzozC!80f&$8PnQ|kr#(jz(G6oqT2Pb+QCLd zP=a_qvYI6uM=3IZvaga*FESvBiF={`&v%+o2Coh8IXt}eKq_Ge>x&%#16o>%(BN_f zrv_9-dx6(^;pn_gthQ#C&vg0tJ&hzC{ovDbj`IGcC3u`538|u?;m)SSRv;Bxo<&uC z36}tiiy?k0Tq~wFHk*eV>eff(q~M1iEW zxFEX*p)M&_h2VOGjzi+`;(#?qJ>S6N`S_z1YgK&de~+7T$C#zvp>-57zjK(PGglU z%d-&=O|H>C<%>`hkQdt)m%F7pALq#;I2AE|(`7LG?FW8Sz!Fv>Nx0LUn~R4)qW{`q z6u|L{G;<-&Rd3qGczA~d4_x1n3t|jDePE$eGcsC#|JJ+lqZT)oC?~gZZ+qKFcrfa? zRZWO~xApS|o_`bZ7X219#y$Mt5?N@CRlHfm9r8G8Ggj@prL#W&qVWzoPb+01C8fn! zBpCY@%o)EqZ5gfdaR@NC|Bp5pC!0_5>fsG1@ zc+h!cQ2s-DB$Z2p6FRMIcNAtO82pL7oQ=%Q2>o6XvtLIOxE?fhQ?s*3 zJm2?M=!1i49c|t%HdW#Jn39ny;}=%M%%p=h&=Nehi>;BGF01&h=S-D z&_R^T9Ta4dPXsNS_gdL8C2^O$Onp6EpGWHto@;HMBf8aX@5czvktE~`1A~s` zWeyN^+zX5IyE>!kA3!P|=u#T&WzEbalTa9FX0{lkTRqfTck2fSSQytDC$YEq{PW{c zFlp=ar_h9e=qw|H9Kr5;Az_iYqBs7;a)nmrS~NrDNX3Wx-~rE=TlisP_rK-2s_A;~ zqv+m^A63N@v3(YgD3eAtMobkK@Q)ou$R2%gAykXORooC!Q0#~upq@YRQs<@u(Dq@2 zb7a;GW1%@EJ%hV9y6&YH$+R4ux0D)5s{lij-Kx{!I1ESf{V>`_{hH zzh7#*5r0?ewdu9dS1$@K;_g^F$0JDJ7-`>4?L%}vERC*pZCxL5Fz)wzJEz-ncK8FM zn#rHYH-!k-?LO3!lB8Ye#@UfLD_Q*S>o` zb|kn|^J&#A&D2imMj%zXvcw-T5j**WNTF1)L|R zA@?sqY1x)mpY{Hl;?V;rbq4!5U_Agb7v_>*GYx47#Duwp)XzGp-5Df&DdaNkg!!Li zN&q2K*+c|ov0l1z(6baW;>xLU!O0PAc{PXdSTOA}*lf!QdX}lXwl<0a2 zTzZU8TB2AFK z8!#~Kn%cNvY&@k33NnU~D^Up>ek*7lynGOB$qG7N`rW+YZy?k=JV7doinl*=Y*PrB z=>5xc9&qi&J!UYn;(oib(w-c44jX)wLVloLNid{$sUOX*4P-}{YFTH*A)%9UQ1A|} zfn(D@(cujdkW@st2ogk$1f5$6jN4?1d+px_zz-?o8(p9{5G#`ssCS1|vybIHAxlR0 zV%?GCcDpK;3Octo_Nz%5x5*tRUWc}5lNLGEC`fNe)(f&6#H`8-|K>vW*0q{$T;_^X zwf>d(gnb8hIJc*_2Evn)eoCsGI;Om~A*?Fu-sjS?#e+pth7U1LCX%GuTB@q5gN0&f zUvn12pp?Dd7escVlqm|i>aqaxw*8|Gtgp2DP;@1aR79pby6~^A-g6TB(($Q^S!P=3)ffS|zjr=SOgRySBMDhWr ztP(NH!#P>kf}Ex%!%TCQASQ1+I35U-Kt1M+^VVRgzHKSqx-nGLub(~6V!M&lDd8qz z!_2+&E68};-(P4=W?(Aw$FxRQxK!R@M2U? z-C=vlca)jOlj%wNe_8-;U_HQ72g(oF=*gt)5c2V}y%VR9Mp&aons?f$MD_)#I(GLK zs5R^A>Yx|neRs|1RCkWW`5)%j7pkIJlm~MzTbrA2Ce5gf8p>+a0^Bpkg7@cHlsY>@ z6+$Y$S4RBz367rHS8=KZ&O1H#Q2N2T8-xQ7wJET({r}#!u&_X_5BjyA8I}X*ARj8* z@9+g^Dc-iq0WyyMFxNjfrxX;xFsS&R?mp1go{k0MM;j6SI z-?OKuWPTmIq&)Y4rSis$IkZJaY4J%LrayO=>01_T$fQT4A19LkD&3uzN2dzEftQXU zzIi)OLzJ~BGVksP_Orey+fv?8ieM5EY{4ADW^MNeCCN_xcZ1tU^Y(Kl8r(-4?xiYQ zB#v~_J>dQ<9oS9Y_E0zq3g1%g8CcyMaF}zw-@Djfn}6baq(L%eht#hHXt<&zwToU{ ziTQ__sIjjleN+MtELD6K$_bV(5~vzi`1t7pW8b}W*!eu{k@J=p@jSKm;nI!2)(9Jrh;QX`InlM+`FQb=rCXx0rHx37~^X)A~9ndZz*bE38eyqbtH;C zWF%nZ9$6R*+)a^=@y^=X?feJDA`XMS6QO%_Q8=*hlvj@Uc##cmvV5KXJ6xInKKrZ_mZMNU^WD@^w{8o|2Hx!vSsby$BJ8SQw{R~QilA6?v5-jX^=k` zuRPIb@dY*2bXNLB{=Q*ByU<)(9Cq`5{4~P@j*x;6rqQdyz`0W@PJpLwe0eUf&B1 zJ(4Fu{O8)>+HR+ZKk*|5xf13j<281_g-gQnwDRoxvX5y4KG-PaPdB@-xf8D8V(WV9 zQRuRZnr%LZ=6DjUvd$n|>i#8;R{{0fKPqMdTPnhtZ`PK-urtc9sf{x2Wqx?)6RI)$ z_ut+go>53{`$PPPlo01&y_=okS@eO`0co;Ma{7UhK)|$T)5S{^6hocpl*22qK3$Y3 zr+!T3R*EG-vU;NdDd>t!NRqJ^>NPSTUf=XqnDVBHsz*~`iQ`SI?CP^NGT4(b+^u{^LTvaj#7^dmyxp2M|e#@ z4X_Rs?2u&2@3mZiYary(x0K#&NlBFC#4DOU^zz@d?VY1U#N3zZ{fpzwS)E#@RL4$N zpM!W|5{J&a3K85*juc4NQ|(4I)Az9q2DER^64q4)Ku^b-U_E}PK#83KSEZ?dktU<> zW7xB`@3{(SX}zLl3=a{vvyrw{dZ<`SW^eA0Z3&n%h1Hy8RuQKVzlP4ueI7q9*{`{L z2aqw~1SSIBdqYu^`k2KzBtC%ww?wD4t?lh`uVz-A z#LFux;6h6{Ar@m*|9V_lr2-3|vUbvEHkr*dFSUmehcW#i#QAzydQ@h+D=5O>N!5od9SY*dOa!eJ4;WWHcXo4wy0m+M(LT%_bg{|r zT_JO4+d7d1pbGLxei^Jz;eT0N2+F|@>g?F?_AMIYQBYJofar|I)Iy@4KjGL(K*?90Gi zi2d}>sZr18yoD_}uSK?=PRh1TQNmvVty*`LvoKvTwi1pT(Vr-$jq zJMr#ejd9dd$ejSeJBxm{DZYWnvQMP;Aix@#@01)w-dGwEN6+Mz#eBpU6ZpE<>W64v z!4N-2%udqE8(xufG@4B*bo3%rtSY!|xtam^4dtHF{iG!*B*dC{-!Qaa7$==858Ye2 zrn)+Zn*bVXl>fP0)iVup4x|y1ZCqI+I0d%-9?0~4i_aicJ6JpM@KwD_5|v4`(}EOl zIH}e)kL5l}^vgbKK$7y!P0+J5#~^={7WI7zh2kstWvO|Pzg4CR`*+iy+epQ6J}(e}Hf0JHEB8)@NYubGYie{0q% zF=ETtYb>syCIm@!y88psFW;E*6o}|2of2EE)Dm7jcK`_}NG#<)kX@AkyqmbynSNIZ z&8p~q7b_2}iyw$292tH#$-KtD_ycz->6 z{FdLVo(Y)gKoCKg2(T(KVURF^WtY90gc;#Am`Aw0!(~vQMBO7Zv;CxBmkds)DK0rchyh2M3+Zrmn6> zTJ!D)Ubxqr{)~EcWQv)l0XZ^Z)Mae4a(*NBD(lDfiw^hgZ5jP2l+mVsEGU3Y_ZZG&e5Wat&CVYKBu4JAaDZ2=G8Y+7m>g4Xl zgb?GP(tm!OS!!50db~eSV@#k^^L{3LtJ*W~BPpTV@zUL1%Y7auzBOj{2rXqc%hFgm z!%xJ%(b8viuejF?RM%sD@oYccn+fN$(QY>%FsIPOhEF-V=7Tq1O7Hs3KZ}Cyc#kyH zCHa4>mj5uRYR(lms`>271g7S1x4drF+>wEsBwrq3ADZ}hSeMC?ug^+DwJPTYeV|4KSFGac11w+svTMQE2?e{)R^M9jcH;iphLjK2+n!^G8qHzVm?6LQsK8Qs#y$rQ zF$FmE{W8TioW!M@yDxq@5GG#81tj*ezY{uvb~L?`@c7Va_73W&7#j*5NaRqv`J6?i zb#;1eJ!n!Q z#%1Dg2>L}<27;x~BvB3${>~&#ae~0Z=?D&6iCI5OPwF*=j&jB+2cb7n$B9g{ zi*+zqGJsfkeQS%{l;ioz@vWDthx)~1dS~-rZ}oE1dS-^K1eFxt2T>SkyI>-MYUDe0 zseess|0&k&fktK2_JsPRlJ_y=2e+-*Vopk;ko*s--Z3NZMl}dBUStSn^qtu(@M;xN zj@r80eRd2bu6e-{DfyY4){K~Rlh6G-P{+n`=tbape)`LFapDObe1u}wN8qfD#pvyr8&()Su& z6ob~4`Gr(N^xKalk6e6v?1WlPs&YJYs3-lXt^%0T^l==@=z*>9$Y7M7k!I`mG+kCf z6p6>;N4D74EQ;4g@Ym2Ys&avrP>*O}{$SbXg_e)=YY{b{oDVZCN~Z$^ZY#HfSf$HL zYeHShs{I-mxg~C>b+aT`x%{R%Z}O8d`|VtJBt+AG+KtowJd#;eE#8^n2}-z+jRq!x zF^&|#mzMtQOaY^Y3eSL`=l$7(_C1IMYX)~czd=2ByqEYLV1%0wc#cwFmWUK0@VKY|VvGR?3vuBlJxd6?x=s)$|Z090K=AJPC|fNn^n|5+Wkf%sH$Y_U18AVO!>9pfG?ZUa)-X&U`pRB;75?{9yd z0TK{!m&{2u71RhS;%#PxfPTb`%v>RVE`y7jvHw5nRL>IkzQv`l9};AQWOz9jqRBrF zo3UIBIIoJjCyaKX?TVJ@cfit~&$pGGE%I&hh!46zrFwVdcJA6+e=%(QLt4#0{UBOz zm?Od`B2jZq@Q+*VhsC&g!J_-mFY^yGD|NZ~#?_Ud+}C=bJEJMlT2&h&=uVsYUVT~3 z+wXW?QjCfgl1V_o0UvyCM`nipdgSMknN=BTNxd&DtU(cqR7aUW=|Wu{)|~%VLf~#n zvAHmrhkI->y4*28gC`!0(chH`EuhL3f~UzdCS4s)iv{C<0 zF#GG5-RON((z>CdwUj<)@SoqF`+%{z?2x)dx&8Yf)|zz6Gr&gOBBGv(SAl}dgYdZh zKEPx_%De>+QcOWf-L+$4v^4&jI{aOtoe8mR>n7mpY#XRMk5ji$3w##c;_$08 za&o%={S%^!i} ztJ8x?ayXwHM8HJ`z@N7%;Lsv0c)bR3QB$w#-8aeLj{r6&1unMC(wy&7oG?HNT zO#EvPADOnO5`R7*yac7i%qrRz#&VsQeI`e`3ye261QAHk_?u4)KQ`h{sRPSJ?O3l{-o%y|$O ze)r}n@X=M!d(ZgjdtM${WvZ!Sownk;EQKlZ?f`&#no>;Lktx)?iYN;%FzzxJL+e`V z+)*5RapHDN`FQd+(F9fBQ!Kle{D7+R+VRujX)l>#I-b`_?cJ=JbTgi{+J-jitT*+=a7RDWxA0sJkPWIR=eXl^U@xQB_4+6Ptd`6b^(Nf9mQFHzru8 zLaOkPKHUuQE>uW9OwMr;gsX7l#8IQRSHz!?hjWY3pP;>iHm6+o7p@WC#PCvkO}P+DqWO-A?o|N?Y~_pzxbnk?%Wg6 z+}NKnz>^17S$Epj+w>lGYUTsR=bf%uLfg3Vg@kvo*?!(96xF;Pyj|aQl(>U{Hn;iLfkL{j zj&)LDfw*p_LVEKgdM;qR`?(7MrNLqaY7b-Mk`o#hD;LX{^}(L}uh)k*R!h-df7`=x z^i55BZbKE90L0b_3t|8N;iTJuK?i4H6tI|d-iO^<-aw@Y9>rUDH|_=3A*rDEONe6z z>=v+uY7Ox~FUvk2pVTMR(>*|g{P8ZwgNBBeDI&QaB^}?((c$4O#SFKIq|l{U&Y=XS zvvujb)y#+l+8C?{5O`30iu1c>pFy=n8&XsUDL}J#2wScvWu-6`9u(C58pJnR_pfH> zu4b|Js%2k|&RtSD!qY$k=Zusp{Q|o`^dDp7#m&7&hEGquYBbJjUw|?Q93G%5ybWS+ zxf|YFp{}WkVmqPL>~~hpE~Okgap4Ow6wplblZz)`ihYPhQnUrlB!J7n;&Ho^(y>4o zJ{K7g;RM)*Mo(0V^}3wh%Zf@g^!XiohH2W?%O5w9#c6liK7TSGU-bV-b`QyIeq})# z36*anH|RYo`zw+Y{AO8VmDmQ5*w%zRe`ucfE5WT+bOY}xO4SkT5MEZt;i;>au?fwJ zDK_@iOKNDTZPowN7PxNBf`!xDl?-jxx`+L$E|wIfA17%ZuBHTI9(9jV4jdX zcMI>C_w-n7TA}#lMVhr)ihVu(nd4R`bO*clr~3Net@aMtL#@JB4fMHs4GUAo-Qj=f z9;Z-(s0wV3($O!zdjF<1RQo7VQ@$rkZ2Xjo#vPV3Je+A$&D-w05&GtQqu9>G$To zohtdkSa|8Ed%zs#_w)g4Kgb7%FCii+NfyH(2shjCa5T`V8Y>DLGTee&5JA)S-50wp zb1u25;zaS%;H@+mfwNx08s}Xj(JlCa*dvyLr;F{&!R1r^FyP9`X`R)bN{kX0^Ze@(u{u`mz4i|C`71 zb!zm)wHb=R8pE~g5@&qZ_8P51pR2&)qXpa8<>UGvvGkfx?jxr{MAqDb(m6w%tDNPO z7e(mgcAGY9+_f3~w|7EtGD?5{)6|YVla{ZWUxS;;elmE?`aq!l2 zacj4h+4c#1uYJ~=$MLS${z$xMXC9v~jLAK{aa~L`sF!vJzA-xLL4drqsEYY54tRYX z6RJj_s^9L0ZEZ*ZoT~)#;Lwo9Ao5-VmF5BC*$3$<%%A<;j2IY-40{4Txk8FeIYrkL z`$iAyL~(|Rv_^g7uUWKA-s^_dEOVhVVwiP4u=$T~#d~Dn(WzM8TT`fmi4n1ZDYzM9 zM^gr|!8g;=Strr9=Nx&B*=>a%KIDa)+|TG3+u7eeXff6Mvf`P2eEr+8CGM7lnz0Eo ze;D_C3%C*k?<0U7A#xIxd$=IxftVN{Abh5-$sV$%pevJ93LW^2-MHd*P#d=h2uH@P zxD!3&8qQ8iQBI)qxm2-a$j%dvvP=FsiW(I|mf+pc@@u z+b}bx9F&aTBz{DBfmmU?V0@o)x9hXgc{GZKNIk^{Dd=+O(rIBlN~c)UI%SUZWm}1b zS}&F3MBp*5Phu|{U-3h8`8cy~(a>2{8a4fHAAi~a&-?lJEn*lb)fT4$Vz*j}RN0yQ z#G~4Fkd_ZbWu6u|rWfPPzIF(cFhAuE$U00g*QJyhp^=`VRV>yG?pY06!jrgTS zgdJI#Gb=spM3DTNc}7BF-N}PNPc=VFvYXzhC78FRJ|^dyj@ea3pr0)&f)SB{vjF!f zx~tU|LC!&DOQ$Zfd4o$t(}iZ$=VmM$PlD#Dhh}y5?HPpxf+aY3UBLq~)PKWC|LDa# z)m4UEYe|*+ca&bVYw`REJ50DH*%4DTYx!qf^l~q7^Vc*5#L*P=SsW;L?S)PrqfVHM!Qo*_^+6shnyh6<=d<#VX$BJ<~Y)5VbqRj7%63Y{j*UDOR8d1t=qegln)+1WTC9>5j0!wHSfju=xQ zA-_b?920hUX~ra5teV7&UhCw@XMN69Ga`;`PY$MT6K~=a1&fbt@Q|8PId)e~bI&>sLra1oed+@OF;={R7uV$N#d> z@+v9_=n_g;KFjK5V!gV~qo3WO>nviPgfXouIaTm}O=n7af*Lz{Klis+-R;Mj-%kWu z!rI_IzPfCjM`@w1v8ct%^x^%f8Sy2Cjwt zJ=*DIlWc9CCOs^HV zTv$`E;7pEqrG!rF@;wXJ5JWtDFdYaF4<}pcMGMxTDY_w!MwQJ^L{Ck`@PGbXg?(5y zKM1xw=#63xq$YD6b?1Hfpf&GSZ2;^(kS;!b!>OZg-u<{+O1GQHS>L?+srGS%mfy7& zpEHX|`0RA_S7c%HM<1s=nfIUX-!HXoj`>jLMBpR(RI$e#<5jlk_go`sLDT2&3y=}V zipKhdbYC%mM}DlB@*fu-j`){nS1!KABP%q@HP9#D1%g3Jfv2V${OU4n>f2BRs58XblIaSxg2rD5|PS_M`s1w|5++L6nw)ZtXK7-e;CI+yOpO5HiT4 zQA^~N3s0JUB~rew-(McJ{p>BI${2jhp1l>LIA8pG>31}$#26SfmcCi1%v|uk(RHaC zPu*JZ&$m#`93`sAoS9x1HcJ`_LzfcNVCS8geD6h#NI;$}we_Qj%-~z$-~Z-!#xHrf zhqCOVzV{XKgcY>qMJ@h50ZaZd^<>qN8ztc9xl0^=%!$i~FZTVWrRoH0p-93>z*){W zPqH5DSvHdvw+-Uz>GDzpa|K(RA_}Ca%R7(62YvVuf`OURgiTRWR~)eKUF1D_e@G;N z#h4~q-b^Ud9KvX6y)rZhj)g1c`c|tUGP(3|S?_Ab9pw+T96t5Fd9QVe$YB-%wteU0 z13hv7f20ZNbTK57C;v|7_kH%P_OZ%^IGujrp52b$`r_b_hBqAXhe0B!6QdhVRhty3 z-t+xwoDd84DMCxJRdtx!4X~9!L?C*i5mx7Y_)eJ=#iaX3veF;SRKV+kqYH8-#k~*Y zU9(Zj;3Zie-<-AV|6C64SP5--+V>c|P6z)f0Ix}0e2$EJdJ zhrHz7c7q^REn%C%Hyz6WL8&sQ^x9MkfAhqAhvw4pjGFm;X3!D z60?%-Uzqv(H$+bsr+9ZeDo*!5?mI4!zi5%ZagwTDnzZkek(g1aRuO`T2%=8?{b-4f3`BlHyp|+|Lq{T z{2yV{tb;HJ0#>E-J`oJ4W*?dB=2M^$25fq5+sbyh5o9eaA|8Kl1@3# zdmhbr`Ha^laRfozU;TS|)@5IuQImJUrtZ*xWHI@m4SZDp*x`~eZ%zq3ycBmTu=}55 znCR)rtPM+E;DYZQdUTAR1xT@@D_IsPf5{*-#PV<$vmf3(H^;ADP*b0o?Lno?xJJIj}8RjcHg+vW2#JD#>1n2Pf#wl>b{vr1HE2I2&yI+i6-*U#As zK&WCJo47K(j$mo&Aou3hUXl(rhiA_eX(n7(`tPXwI6C@_Sjy5z zIDxliZ~|MMZd{3V1kmDws?h;T7zPxFGrJw!_grbiEqsDqAni-uhwMm%WdY z)Lf+ttNNI4ha8Y5a!oH>x5Uo*#C`BJU&_cAYSa9DAdqJEZDq)N2vgb_$v@2rY3O9T zpOY%hQ~>$#^30>P9}}~;_0>r@=VV2p-?4Z*IN1|qhEqy~(KU7-vW}G>Sk{ zHm~`-qOQwQq+#!!zs-hK53C z{7*zA3W60Ns@MX|U5~cWM^^u3Jwx<2OnmsjNEP>G8INMWfvdqv95iVQ>)}lNDSfRj zX9p_}8upD({R8mWO9F2>D_@!?bbeF}&c96(KD*WF2}h!rgvlFoGHhpG zUupmp+Fx~B{I~2P3L}N~rG3~_3r#APK#K?`Vkgi6VQ+=_I8YKHHOzi`f29)J^L4A# zB`n7?UP=jd*_^{@fk-B_EwB5929EH!Bt`~Z2!td61e+Fyq%h3+t$Ogal;}{~G#V@I z6dT%eF3-^3HUC#`gFTgVBl)UUtUh^AC02xSN^+{ZuFsWGUg6^ht^9UuPDWMKw|?mU zJCe)yMYCvf=kt7m3RSV)e=cnOl@-hGcA6xt?h)196eO*Wnflwezq9xAR0JO*Hp-g0ALG>Rv;GE^Pp zv{EMA4MJ>aGvVo%%#9)IK%(pRFF|P5ngKsPPEpQl;<#Vv?+QBwpJJ;U+{lhK3YKMMshO1Ul+xen|B>v8+cX|O(I(I z?w$Pibx_6JCRRb11mx7r!-%Ke1?sNw8K>*w`ZXYhjM^UktbXV7;1S4cxt4tLxyuF+lzsFB!QkiO5hO>Sg?lu%&8ly{pB=7^+6uTG zGdRwuaSYt=ng=o&S;y;U6?4IWmKJOBkYy!Jg3+&aJgex!Efs6}xTwg0iVpkmq263m zpaou0ojrcB1s3>(UUEk$7LqVASx!law4QgPfBE+hmYyKRGGy5RADJ)nAw{&jc9|{_ zC6!`iU&unR3@!m~`}SYO!hn$dQP-(o)9t-Zs84l>*}w~Q#{e;3q|-C>Fa8sg+PmOJ z63CPSAq!zlm%MCEc??7#mbySKtg!QIVc{+`d3wL*oqV|;vckG~FYmaO%X_=Hs<%FI z2U1Lle}Kbtv65j7QVmpW`NE83sDBUqh5^Z!FJC)v=B`&?B0k=EvYZTFGOCbAts<_u z)m>|=s~}d+8iAyifG1_+@(~;bEzp#&E6b6Woyy=N$!x7tuLm1L*H|M;iY4 z9jZg}t+sVI*|djcBQ$sp&cvbpbK8c35tH_;^*tAqxy#VaH=;(Za=W7CpFXzLoFWCK zPxrfc%OB{Nx|w!5uTog{v)jF;`Y|qm&w;@=J=jZ*y?%^dmGVml=0h4ER3=F_vBXUX z@Dm&j2T03i5w zUXgOnC;vY;|DGQxYPO_ZcK37sh>FF$^hLNnzC(M){C8Z8b<3T-Pu>34rItj;l&DC1 zkVTix_$m!Dp*7We;#fN6WpS3TV><(R-Rs`cEw94=G-x#N2C8W~{EFM({1GHoGTAd{ zgQaT7@D1sYL#)kq8Scn28MX9NG=&OcWW;T50~B=>w6u4EqKLN+&%_%|9Mvd=uel3# zycPAdN(ToA?`CT-0n>S7tb}_htp(-tW7cHvwy2z+At`p*LSU0u$rfUUlXJelB@Uo}<;7(hA*CoDtKCW(^fNszNTul6~&uq{A5?MaTOz zIq2_9u4lJYbX$iAb39=e4!Gj-X9`%u>}=ItK!OoW(uMm!Ks0g9XGSwiGR{_W%Sk0+TPu4*l}O7wTOfF3+qvoAn-P!_7D%aqyVzTqT4$lJ|OkS{l$9JC*O3wa>R?Vbzp@U zQ~@hc@of3`8&?YpZ~l_ z>O$CyOlkz7I+;b{95`0LB>h#GM7~p?obqeWcH4QIn3%E07Omh{%CWT1n0j{;clHI^ z&Z4(b*(OL%UrGWtfMWMS6T*Xh;U-KDh{De|k+q0yIkQhuUd znw@ozV3M}dLi;#!m08E`a-KP0uHrQ5kBX(?+0Ap`nzb+07e+@N;`ZN}RB%z*f{IFm zlLg%}XJ1cmd;HMok=!42HoDg`^Feo|ufls5XmY1o^#^bpzb9tdowOz&dIFp9I^M!TH&K% zXpcpE=sUi=5)EdWIky95|Bb-3iTatvOLbxNKz1OPo39oB4wCV%5JqBgIflzSh@18y ztTM@cPdyf&OMhjoGA`A~AF0Bc+Omp5P@ixF1F`Kv4Z?Mr>9y0&Q1^f_C%6*Wz46|g z4@NER9Y@3Y)OS);L9}^4P-0G_Q?>hR%Z~<*xH2GngTGH8Q@u-FmifStE%Rfc@J67^ z@t*o&TDJ%eW^&(huUM)t>qSFNMzezGHXy}S|KIRBXw>DdOpVkjjrTy!R-6cp=%0FYyE)MLS%~bDLeO4^0 z$0G%{8rT>>5;x-2^d|u+Z*n_-Y{%@G2f9*^5)gMp#3T!J@5nxh9#Xvf1`V2+KvIGq zG5YfE3T}%S84E%BlAq!?%hks<(XHQcLl*eN47nk5C#R3*9+Y-K-H$4Wg1ux^BjX_} zWPd=AYBY3~Jm>t$K|BCODk#(Td@i&_APR~-TXDxW{rE51xf0QW6KaB0AmKJ>%8kf$pl^`B&GX5^bplv>F+gZ+3ghkY|USwv#Pk9#?8Kkbc1bbZ?7UEn96|h`K(6k|-a? zw;_uD!pCdCD2=`CsQDsYB*PmgGJn7+yu|r$j^Zz(2)&B7jR`7RdV34n&Sh5A*CC9; zJBp*i`jHaJ70YfSTkQU+oy-q-QrX#6rGwJmFi#G|Jz&9b7VRgH(j;0*2OR@QVt_F` zAVyn##3b1lEc@?z3z`2z?3Ob-{Yom$6$#~ZgXgXet%WwJIUfa(lx52PYJvt0pMrK#tGBs1QkR8u5VdB2X8d`yUi7vS z3`7ykN$!1@!yz;WZ{2mR*Zx77iN%1B7G25Kz<@Ry5P)DL3)BhX3|Sz3+|Ff}`$+nd zMC*h%Ts!5B^LfVD&Nzj+u_Xd1} zgb-bOl;enPc1;Lrv1Z`%E;!B5gdvu7wq)Tbd-e2|7T?g9j$7Z602Q7UKV@_%&w$j4 zPm@5W*xYXLXexu*2z%S=zAQrZ^E)>&Jjk4|tL4yEPtNR7bgoKktsmQ#uQTX6j1&Ax zjko;DyR_DB*~I{r6PK3E5n8o4syl}-)TT8Db-&G4HV!%Io&k46WTX)0D)qjqVa;8-_ z>E!q0>o@dJnO}U-^0L((OKh-l(axIJ$do_MpE#K-`D1st{&SeU5KfiRyENM>{X7_E zTuSOF7YIJD(szPpZ==_Kh)4U2$xl#@z=6GxaC4dfKCXMF$q!fI_W_;>JroHTxzB3w zNJz#i^=F(!8lj5r1Zk8-6{d%W$GIxQqer?gWu7x62D?DGJ+#0s2U;$1R@UwzbNbWf z=6uzH7`}K-_yaY+>^YwUos#hH;CCOo!(Jdief?5544dpIeJ}gH=fcNGb9=-8 zp1%!mSPA}cZkQQRQjHU5DtESO&p5H;J=YjkAd3(_lib2A)aO-2_?P`IFv}UXK@vyW zWX;5i{2(VHr;%l+F`8l925VfFJ)!!2EL@Vj?&H_=#lHJ;7iqKHI(yQP#q6rUIP&tz zO}O&C;E9f5cKzMy8Lw1v#k=34<|vp_D|Y13EI)7rY;CqV{G9JDBB#|P?AF44`yw#n z;!sN3-6AK%{l7{?nMtUh5q9@`u= zRhK~K+{Qv3%9Z}szvDZ*yCCJ7-(TwCqri=lKd1TSC&_DoJB=2Wn>Br=?hsoOQfJ2iHBPDH35yxP$B>-|dYP%IsXVqo2(?bF&}jAHB1;K!=TDE*`IF>&jd~uG zemYCoD%W3MS&4vUpwAUiSjZ$sUmYzn*R|vvEkHYhVGa_w5A295cCVu5-bM9a_uwW- z9IeG5tpoE#&?#$`jhC+EyyWC}05$;J8*Y8g!IC{?61~U1qV9N)yW@?ePMbSJ&%mJB zcVd47&R4Ia^`xx`KO391ht&VH*yV!<=&@s4?qMREpwRr`4c81ik%%Su?(mbF4Cl7n zn|ry;22z?7rz!*SyTS=cqV2W_ z2SlUQJAexsH<-fOpHGyL5@TW1_OPt3Ue}Pt0IT#=U zeh$JJvph!;lHcHnRHmn6Y$q?)%NEP9q6a_jweky4OM&BK;fm#8M9My!^?a`N7MEAZt9P{X|CR;!$&kL z2XDr{vXB|SGy!Q!M0I^|cBn`>9jC^Cf$lFx!=?y%g<@TvwhbrM5K5%HMh5dsc;)S2Tm5*f4_8l>@)Ufn-1SxYRK;5DJEPAR`%fwlRnCgK<$WkcU|4_r zqd!!gYq<)VuL*v3tfuVu^N?;mILNbllZ@ouV=kS}%anA%RAN)kl>zaR(BlJR=KkfG zYu}ZEHch4BfPwbeIqTejLFiOUqIo7~K^hMmh6uJ7(V7kdGIFZTnkF}82vM^hc*d); zYiMc~PHw7{&laAOw&Wuwx!#Wbe=UGCZDo{o&dZ9lv^#L_aB*{MR}Ovk6v`}~aN<8n zu1hT!9vB!{cN4R%H9UGS!KixunBxv4LT2UU=tK%1Xp&w8KLWcY%ri+ZNE?W(erL~# zSG^RmPkDGwOt3mV7AemtgOZ(Cn^c-sg`W&5p+~c)V<P*e+`T6WiIR&qGuO^E0m7B@K_}cXd1|fFOS0S-F%X$e!$Bw!*N|Ey79N zFGf?tmfDE&jYf!Zn<7pTbj%NXe)AQg`ku4e=r0IIg)m508aQQ1CMi>`;-GatThn5{ zqy0&D#8znD%{%XY27~^`Ub33g+1WXnvdP8ib5{y=)~q7Uix)+0$|x#!?uNFXskR(; ze;m{ra`#1q(F+$z_F^$+4qsajw14e^(!>nPBL26~0dn^7;n-m6Bs%BvH_}*4RJRJS z;9hrWd6aB`8!pS9raE#tN`Ey9Wr{>no-dsBSMq`8^wiX$`Xnr3EAp&FLGu1xOaIJn z%;=MxP{B*$76K?AR%4OWa+R%4tFQWbU-c1)4J%@wG*$lmq?Sg(D1i}hx`21ElSBQR z?N$iXH2;a#A+m>XTZ1gL<*VLA4zkW)UtPfbkw=#U)Oa!_W9@c=W&zDD%7eg$h34;q zlQbbJRZ!Hn5!c9dOv@?Ga~ zH$93}86!C8RHHjcDH~hpv_R*tH zOt-3jrsoJct}cF zNwLtekCWm;qMIm=+syvSM{-RjQmKW#PeZ39J9rpeq`fHEDW936qHj=db?alTCwp3V zB&7IdYeYh=3&kBYI;plcmzPnY)`e-;E%#+-u0<1xh`|_j4gz!`-AJ>#jWDduj7D`^ z<{(W-)6d|PKgarzSy(g47ql`UfQKyK=G5mv5E7>=5qL8;_Q(hl9O{hXIojZ>LuI8< zIdmYmVyk(SdX&aBeSIzICYFtgs6i)yrx-}*RV(^EHne-fe071L#rWcVFq zFK%MAkOC&iSgdmo=0d5e#lfDbzZsBqvKO_3Q%(m->LTU{tGAUu0lopQeyMkVkQ=mi zgm_oKW;giLcM>j(B$kbT>~lrE5u9>6?^Y>#6xp#KR~V3tHwri*=D(~es57vdjGFxn z7MXilbB8eyZX`7g4KWZ}ThVguBdwVDa{zc*wXwuvB);dvY&kpq6S-M;gJ~PKPOOF) zUeZU)?}0I1Y%aTt{jR44gYZA5B+R@=g<4$7RuQ4W4F6IvDt~X4zVhesB(Qs^Ihd!< zQ7}uIG-Q>?O9l&H>jMy-ZSwC^?fJRlJ>91z%=9M*CU5%3#Hj#pHe$HePHFB zEg;SA%JR>-G!H(S928Y=a&lfPGbYc=H0l=Ull&(k7&n&kNTs-V%pap$vGA_&Cto;Pn7CBwyCn+`cOGMA8xz-x{IkHl8p~YL{e-6)X=4$ zqPitx1%@v>ES%@3YuLVd?yA8+>J}1QjL+)RLX1s(BHKj!bXFFzfX2K(3TA=G%h{39pxAZYRQgt0znI zX7p(;Somdl7A9f!pCT&O6h4~B6;1_>TDE&Uqvj~2YABYV8Be&7ZmN&Gx|BrQgzs-= zTcZ(4!i&Q@>VCwYm|dyKz_zNjwW>8qu01f$w;T6^?~C`cw(XsfLC*!pizJOAqEQ8{ zp|sJlV+6uljq;@8OcIi6D75>~tsQc>-i;1^MME6nf^SR#GZ15zX z2e1tHKK;`tp+C?-Je8o{U1>c1t~!pzQ@i~Mfjn~W#sNDu=iZb=Fa7a`oFA#c<9?#` zM`k`3n|#GfS0stNQb|F_52>ekCzD92*TXEn;jpdt*slwyy{Y}MxBY|ax}gU9>m=UV zmT0WzP^9AL!50WSA^}uN^KdbVNqUGalWb&I1p6)J(82Xu9$ds>g!PFQe=` z-v_i;6ob8Uhn3pIHaj{(k8j&E0WG;9?m(+Esfg6)5}Ft8c%3xIP>qiLqd8nQ7~SEn z*(-e=cQM*p%)?{kMw37g{<*I*&p{+S#NEKsd>b(xaD7>4@nG*N_a_k&tsmv|MWr?K zRSwtB#^8qzOg$mQ?Qv`;Yr;`s&pL8V_Sha-m6L3)2&*6aWJ^XKoz1aL+Y9*+bC+l~ zL)s?{B^CJagMJi81qSsjZRDa~T!Hzngg>Ko)8oUqom&cW(2pEN?G3Lw`ReFY>W*b^ z`&^3+YM?P9NqkIv;GMqth)X1`48x-wD+Ez!CY!HMk!K^e^-mI`VN4NTmYWsT@iQEc z%%BT`9W`9dZI8^qsVRb=M(tZy+!%e6+cx^%Z>_#@91B|FU5dNgR(56z{P!& zFlhP07soLBae<~rs|bYD2;YxXt>bTf;CFUV+I{1e6 zsYq@7UAF~}qdI0>bQHv$pB#7Wj>V9dNJIvU7XGUrWfvF~bC5B9QfTr~4($%IB~lit z#>mcR?cE7yeKGlFy`a)h=G-^PaE8BE#cl|fu(dZVedHO(X;v;2;l>!JaLD*i$CtF+lZN(l(@T+1 z4Vr)W7tPpB$W-0e=oPI0*icy{MRzZ;q{+Ug$hV$rc-XY^53g|sACGt`FBF~3@(~w_A zT5g)1+cr^n0a}yx>+5FuuR$7&~WK)@ZQl`m{~*W~71N9O`$HN*+w) z=F0=PZVay-g8f+*F4T~T%*w{bf`1ai&{b#1$oMQvC5)D257~bG6^(f@LGm^!OmPXhg_%xAL;;9vVx4Kj) z)P@E#R1V;DgNh@#4gE;7a8vx19vZGqQa0UvFm$?9d8qsKcX3-t6n!G`(@;&9q0Fs_ z$YZ?)D9ul7Hgg7f(+5T{L-ziA%RCiXgA+EeAzN!$oJWH|TPbH8*gE1uCPDgO(auW< zb=objQ7rp47lSGZ@moKGNERsK!92OOy^Uuq4Psj8_>MSyy=4ka_obvd+t^U!;H)KS z*vuc-GrVHy>%M#Iva7`73IW>tZ6fmXD3dQV<;1wr?B|PJI1e8_RNiT$JIfe+2In;p zZS9O-b22?(5C4hY*@`SVt;!@$7seVG7B!718$@maa>Zm!*BP3d*vs#O-wPgBplG$( z@)a1olr?_Bv>MG=_gcP}PPR@f0-FOn;>93U$PR-BHrt+vgsou4`i74(lU(rnN~^WF zhQzyhH%a=?al2xMgZIT1=&gnyBazHmDosS#&DxrSvfJ?+(Rn-Lqv8uSneLkT|B*`g z*iB|+Lf-j0wLA=S|$R?$)Kg%`<<2k!$ufKXj|HSTyj86n_0EnwHF#X$bmH^qQR zb27$y!)Ep>2#ddu2uFbOH|oQr|D@x~;3=1OXX;!>Hjhz|jFct4=`B{$AAP(#oVIkG zTn)|N%Z=RYdk_oVNr_8=+8)B7#Yy=91AeDeu`K2^@e}cCKHa;w3vF2iNztdKE@nAg z;+OtsUGfe&i@{v`S4csCty7`dQK+In`}DZX927YGY{Z;id=y34cU=^5h?A0Q`I3e1 zY6M2hhd2=Sxq{OaLQ%F~fPD(UVIVQUz`!83@yhwd0Mp_-WT)q>B`Ad&s;NSn;(Hdt z@u*gGG&IUWZQ}ZH8oEfIoTz{@77Fms!E@xXC|4(cpmnE8WuJYut|ZkC)dPs+_@tyX zxf8|L{V%q^f?7{)Ktp$$PTVW#R=|sLezn{gp4~HblH@w^x=e1Ox7EhrZkwtn_BdfJ^nB9kpNKc$lll z|4{aCOO1a>#ol3>E>Q}6DE=z)u!VUC`gNtO5%OP^4l$(%g3SN?QwLe1>)H@BK0fF@uz#}YH01>R5}8W# zXRNWcwIyy!LiR*QFtwt<1(P!|cK=|e@O!!Rtd$&u83D)O!Zw9Viy&n@|xsaao(NWAN|P zTafJvdOB&_GA)wr?bsvKCq=rE@1{0ik)Qtb#mm8&)E4{&BdLhv8A1J6bY@fWZWw$5 zbV#JqfMsIqwtsUx{)BiZYPChm`yXzlbjgmOx_UNN>W@Ii$#{y`79-m0;WyL|bi z98Cwm7abYtw&eruUtPwySalCN%iQ7kS>Qg=(9tmxVk&cS6m41UuY7b}_MM>WL=GgA zC+<-yMzf`OW3xhjCYI>xVL4DbxyeGK`XzfxjNzqpYkQOLNhuP_`UCN}xHy$oA3h4W zT<2wS#O8+8M05GFpIk^QcOUlw|UII9q}`+Vu@v^d;b(aWZk}J zsfcG^0tq-ni9bdkEkFhi_P@SwjK_m&bjiLIpFS0sRGe69^*ViSQ4!;uqD(vWVbM10 zL#IRB_OSrF4~Ff6gFW*2JpC#Bt9wY*jimR8M_ugz;V6THzh9ABnk*beS+p z<}oOi&pt{aO69Z$(jpBl{oV9H^%iE*G$S5i#422nzblg1tpvJ#O2> zH%LRFUl}1%mlH>W-VVg`*$us;25=2$`o9Q71 zGR!&%pXP#9__MzCX(lFxDZnNGp}YPc`fn!}6dBTiJ)fS@P4^@XdV)O*73+hHVz^R5 zZW+`$R{XHDrWxvi?F_0CxFSIX1aoEQt8@2y!kB_6wRE0*$UA_!BMcK^PzL`H!VzH0 zby1+oK290gmFwI; z|Gp%R!xTb6n5fYi%00$v3Y{c<^5d=)CtCO=cbeMXdp{A;?NIl?-wDq?V7*ktsrVBk z&mF9?$-I~?5-Y^i`Cn4VaV2N0*MsIq*+m} z&=`1&JskciH}po%Of1Mt7=N}1e_R=D@GZL7Cn2=Ws`u>pp2bTM1kWFyBaL|S-T8W9 z)^xCU|Dlag;>G1$l89Ki23LVy<-&qC`lmXU%LX4B$H=Ua0{lm1L22hgA=~1tSbDQ3ykkuhqxB4Vq6Q(s_I9{yhi4%p@t&al zy_C2gZB;rK<}z)sU+-`i7vXAKqYh=H!D`w8R)PV3dCeq2p(FIS#Qo1nAwM0473gkE zR5M^GhJg|^o}N^gghMqQcr6Z-sG{B2YP%XTc^7^iSXb!0*Qy>#r2&Zwuf^pmCe^%( zizKEbzcw~L42F6TDYO2|({h3JO(_6Aob=Rwnt4eDvsC=020>9X;H zt2fI7any9{)w_(7C1CtqwQxOMyq*mX@+zm0Su~@^Z$Pn7FT&43EmyKxiwHRzPs@bN zoO3DCHH*4O)H;e2rYgmMEBa8s?pZUH6j@#FExkJ3T{-l=6}fn4Yi?x?eI@axH(3a; z%{XihvR~YktNHfr^uGsFkoqjbpxvvXKb$M2R5B}5c6fdl>J$t0u<>W%)3)zuBXg}V zBeR@7cx{q;(`m|>n|i@y9q?(icBA~6gRru1a~Q{eKO0~dCPcv6H?v+rZ$4dgJ?DW! z2fh+0_k}X?ATsDSpCKHF9D)NuBeH+B8%Pf`WU1@@gbmm4&+Zq0|2{aFKe>5JV}i6K zND>Bv4+IlIyf`!vdiwfa@I0=W?u5G(tn6D6^n2Yz)noTCV18r_vO-Ih00xz}BM5(} zuNg?O+km?Ed)oqb2Y3d$bPU5X43n5U4(ZfO*Uq+rhM;bSBOfv_nqO(u%vHe~|9dPp z!y|0G^?zu(%BZZea1BTbLkrSMN|$sAk762=y?w1Gmnn3*^>bek^Pgn~t*A8( zG_)|Z9}ZQ!pXhQ3X+wjwkVfLXF1=+-1?h_w8RE03EjBEgCS=$)kM9*2=M)d#Z7{pr zE%1n_A1Dobs2@myuDyE+oKh@$XT3>LIodROGUzMQNhPY#m4H=j6*g6xd9jg1 z>I7w>I8A-TmrJ}|Uq2F_;yw=k?ivghuvhk@Z$~RU;nHKs`fjC z&z5XG!~Y%WED=P1C}T5nSV69pQbF2_W)rV$(zP2)57090$g|b$zPbOBRULU)j%s9( z)gDqTYnFB*J@Z+j-51MpqH@3;77;DZbmx4S;XAC%Aha$xXj}E7K}R~^m=v{$&;kcr z-4ook;4 z=cHyM9N}1G*8-GJfp?ox|0d@ebb^C(*R55LW^q7kPP0;ODd3z{EC&O80D4pfE+|hi z_689a=E}bMD)MVrG|w}+@yw5O z)qJBXNu#v4yL%slyZyn&2*7ODFPSQ$F$+hS#w3Ev5a!e zuVaFjP~g7%R+p_*rqK3BM}QAzZ=9YE2)s5qol7}!hewrjBYOIS*%&HQH5wxkppg2= z@A)&(fbH{jybThPphU=V9;Sd9Sac6*_*Db(p6j{AQ^d}C02yeWEqPjl=6Vb3Cs(S@KTe-yO>8VVHd<|VcN`GW`|ShX8${?qAJ zBMjx-b%1o{fTW;KgO05&Qg8qR+8MlupkeEv2E4qlMS=YM3`oHqzl zhh!Hfjr)En=DX9iWg_gkIb#RGO8{7>?2ZGGk9J(T-~(OO#i?0W2jxM*a>jrOe?ryu zW6}fB!l6?(2u-wUm=0>wiqnGkxhHvn7Ob53dv!AQ(6?(jQB?c6c;3bvjlvr**$9V7 zeVsWjFQ;i$9 z30;IeF=%-=-+KJ{+wQ6D_84wPH;W@Nf*9Ip!^m%O@sjSA{vVeY&@%8?bcfzDwa5|& zd=mJN=(MCpUl|_N`D4`@(ymj$x889lL7*HX0ya1)&rQzG*Jakt-!_Hcame#dx4VC?C*_C_u_;uBmT`5H+X>e%961 z`LmtN{#&U$CXJal++S=WdkQXux%g@V%w%9&1=6nuo7Jw@n!eXV8T=OjkO0q|5~G0r z`QrKQwtD+Rf)QSuq?Vpu{`l4~0I$5&>a<>`T%g^=(&867Cx?!O>e#;c0BA_ir2}Hp z0Lk)yVHvePQ-^J=+~ZVK&fKMGV<}%OY+(G_fl#RD%k%aZQp`hX;_5rmL%p2zUjA*c z&;ynOxbF_kJQtSF+beX?dFL$ndH4d98YAQi=$pm9AkqEPOrdClR9k9eEfW zd3zG0k(E~|qrD1Nm6Ht;l{nR#X1Kht=>F|LfUALuz;2}C;bx~}$&jZzfUN}Cdlp6Y z8gw9u1}vMeZUS)C0ficvDnW1%aFzqcI1I#uJU*?z@Bwdq+rtqp_yvJKepP_T$$(h{ zBvKC;vjAQmfd8C)eBh_Y_~T4Vy9|dx=g%wL&|1DO0AuC0wz^&;9J2cTUq3{t?kWohVo!I|t0qR49 ziu`oggX?mX->VW?o!{iGhvktv`&AN@;ahOTjgYn`__J5^YIvjUiocV=?wgchQ>2~UJb$oP;RQlWF*9B#N`9{4-d{B> zZ#d(m!locr{PqlGiANLIY?be%M{mu3@u*=uliXc9QWe zdR$`nC+y3@-)aDyqh1Y4v@TT>1#6Kp<}#pwW*Sv$?%zF9rE)f1kxbNTFAS;w#3sKQan;KY*D;mR1JLGSl4%|%~_Zv*I`vf{WqLgB9AjregFLf zp!-Z!kn*+4fNKp`g~b-kUBJF`-u90H=&3fY?mvW)0uw42T|hKdA!YRnGuyvbFcI_e z#&c4}RmVEV)_&x9skv%Z@Y~Q1y3?)Y}^8F9;X_?a@<~i(QEJ}KS5bku#12F`t@!roYAZWTJhwc4SG8cmljsL z8~_mu_@oL%9n_9PLy_=dL$0Br-VBjBZ2$27MaXHqUj*tZZug;r1-Lfp>J+289Fn9q zAGf$psL(blmnnWZ;f!GIPb?tB)fyzyf)(?%Is5isQBdHn1vULa?ssqj zBW2oZ^7Hfma=WjQ#1?%e%UP&B-$1(s2to-QCCuP{`FY2**!?*yF)=Y_cz?s*^XI5Z z5$V`e<7>E&PP+%u)#R(3y>{50*ZUbeSUk9JuGq~!zTfn{aQU1ljk1`kNncG4|NPL@ zah3ud2qDffy4qYoDxo)%6ZO?O725pSvGf@<^L>~g04;Kk)Iy;owT2dN>YwO zH0n%<94(=Pw@T|u%~VK`Yk<%|DJh;akv;mK7evx=y(s=uXFRV(}XaCV8Ljn?ErsR2WI91_f1Q_6#PS4?SI+QVEzx_wb-w08}c9 zsPnx?%$~IYL{aytLspU$iXTMc5Q?Dv305r)Cpy|uBJ4ljTDh<7rXup_^(}BoEdM zU&zsADIf-P2umfQorC_b44qHdOk7-&WdX(kvMTx-=sh+PAQ2-Tv6^APetWPvgW@yK z=595_8;42$(p{6ajSmr>xZa%(4h0zyMd()D#9N9H71f zUE*a9U}zM&-5CC~AKU};-xN+@lwdr+Tcuo^xj^f(Se-;2uRX_&83bsEO2` z5g|(Y46@6O-~0gx_-oD}I39ozuT>9dsyESqn4g-ccmGOpQ4LIl;H7U~jS?Y+2JV1Y z$#sVJ4c@QB#8)wve9$go>@H!)qL+_OXE+fSM~Oa0(Y5PpZAQ`$Wh3!BtHBbLEt;JzgTg%IzJoO!(!40FOkn7VXWuVv`V#L zd^eL-28Hv860W2S!X=Lqyi!KX8F$H8?*q!u2Pw)p@B1BA1(_dQPSr2^8X7;Z-&Kc_ z!(%n}*t8%A!Kkc*5-5+-obFWO)7bUHNDrWuLj@&j3UA*^TKND(VCG%@Pp|!qjEsH| zkOge#Abg499xM6|paC1Nb<5B#zZywR-rt~HGJy1WC;_SsMQ0G@LGmG4W~#GK$$Y0A z;97xFdD-HH>(9@(F^t$7PMiuAYE{qI)Lsnp6A#2LPL}Mc_8>Atsvp`2$ADQakxZ?F~^8a7ZwnC1q$ZR&EiP`dQEzKa!f zlIZdWYs;r^FYJ8(fSBavo-w5gzFM1OFL1}bx7}lAWdkrh0$2}6%bwvY6-LNjEEFo` zf*p9SlZU6>8gDV9)N2!?N+P3bgs&0~2&87>4ezC};}o&6)huSr&dY7+wzR7G?93tskH!Tv8x_5~G zAglMr_bW=W1w02Ocu4CiHkI$mPX`)UGwxgvpw_3@tZp7^i&I?RIF2U*GE=k~& z{MDipus~y0Mv$k`>T$Ml(jqE+jQgX?yk&HZSk&)&_=HFyhJ<+K_y)~mfYZ2QyPvWV zjZ2R)K`IuC-q`2O4`qd&J)vhjscV!Ch)#1$O9aqCbFIPcaJ(_b;H8cHhAkSDft+wD zuK0bdiI{r#>iWOu29X7(L9`o_l}Za)k;IN)SB?uwOCy<1cre zXn%+GpE1FZ3)ZxPf`SRN&)}Av`5>MyU3v#P+jxl+!DlYX^@T^I3d#~c^ ziwl5b(W}T&E6G~5L0ge7Zxws`aen1+%1cuOK8NQHDR{%Z_`ldOdv+UQ%`M!$=RS=x zo)}PV`Q6k3puA6+5RcYt4Sx+sP?1WAiU9TkFe&_$p#%tR(bx{;cwUhq@dB`&i(#Q+ zIlwObe#59LV=zh)7>5|UhlbvQw+wE9{14QZ_ly2rzb=NfZL{W1jl8T-#QXaTe@Q8@ zrG~KT?RLZSqz=^hJZ_T+m#LxcG_TqKH8b!wc{#t(TAkZSUv_6Pfr=Sw&V4NCb=$h9p-g?UBrBsMEqlJQG3Wie0Jqc2jauh&aHRSf0yB1a zG@xpkWcH2;3Bx0e7$Fz|9FCu`!xyAaB-aeF8%CMG_Di0}e;0=Y_!huJdNCt5j#x@@`*fzHQ!zV&+3JeB^RCD@qRV`2V<^9e>by_PDt^ zAJ%PW@`09*PVXXf`zgOitq~oRz2M%&3NMXFxq}9?DS!rm=H-=>{4a{c`x*l<8aC@~ zviDD=jIgOb>nu?)8CI*+?|-bH3~r_zl??2E@BG`BIt%UxU`cCvI$Iu4mkPs9FtoIB z`i2_1!%z2}$v^+e5=}udpVDbc`sJp24()q!$r7Hf7qdC_W`Fdy|n<0GlRyl z@0rGxTpi9w+X7+@MGl`kjvJi?OnO1KmjRQ6%zbGOmM3|aG#Vf?bEhlZ<##@|Jfcv4 z;L4`?-wL&)&;15}9YA$KW)CdbF~Lm>l<{z2)GLC#2Dy%YQ_h~2#1XvI z*)l;DxVgjkBai*$>4mu&#TL3<@TqMM@AbGMqgV^)1`+f}vnAI=+7@hkUzrKX;|}I5 z7BsbmH{V5vH^}|`eDuj1%=rQ&e)AS=_|!FOC7l*^KvZJjd7DsvMazv$vJxs!+z|ZT z8LE)N)xQh@U5UU>T^@bR`s=@!`!7t1%RQj@O6flXTJ_#1A>5a&x1DUnf_tC-tCJI` zQ0mj+2`<^SuJsg9%nR;3?6a-g)|hUpI!_YPw(H`p3t6~ymJ!e2U^y~iNdY#Z4@sl3 zh(=b$`viYWygreKRnCS$0O|Gs_+!@fiLQHRI#qxu1mKbIl z+N!Resf{x#kkYo3^T+UMU+5k-?mnZz_Tkz*XsP6cv>4Chm z;Ec_U&*9VG(2fsb@U@7Do#+do@~5OI>+T%=_LsUg4L|$Nt`LohHC+2sF7`w*u4?#YYa zeeF{nf(rvf;;}dhs;o$`wDr3Qx_`tVQA;YDudixQc^y>K)t&E`ti=-Slh-rZrF6a z_ZT9DZ5DzC=bjE4XUf!aOh|d}fa|7ikTn?vTxVx1jl$;%uS#>SqQV3AVtH!+I>URb z3~pZD!1-hFcE%XI$BAgxVK_NIM;kEH`{VKMpEl@xq`apqH!RW(^bk8BBzYbT{__vg znuYz2iwPC#RF1$u6iQXoFwf~9YMNZqHKo`6J#O{3#mpbWci|z1YEg4C4@3m2$rZMw z6r)iWHVw!DoqjeAB?A;xO8LATzpaA-`)OrmC1Lj2Yim8(n&4M;HU{kG*UT@S6%`f0 zE2x+$jmfjH2;C)xcZrP1sNBmy2UrL&%D&#w;F8*Hu8H#MXGU6O1jIIW4A|yPB(gOI|}a09wF50vR!f#8lYkB0`V%~-^Vvbp2v00t$G#G*|uEG zYzJHNA9LA1h#^b@NJ1jZhm z9^ud2L?>)Bc9HTQ_}W53uhb3sT#4HLq6GdW#8+d?gn7hamD-*1lZlfn5N=-0U&pFU zUmNSFxKtbz+tSe*N_<6hni7BXPbH$0gI`@&9pzXOd89+>PT8CThLF3rBUh!|Z|UKC z7B3nSnt}xA$}?v72f-l9H=Il)3ZV1^@}PBm!+)zgCZt!2OKqxGgyPkv6tBGHCf(7Z zY5U8{$c>4SUGy_VHlBXhCvbf4O@!_R*`}0)F~M-(+XQQs>}CJPf z%SViIj#$n{$O};PlTol&sTLZwmUsCNhNrJabp)aWx^UZlGib!o!)Oi2pu`VdBaAA|f!W zrO3)H{d6uRzk09f6@n2kz*y}c24=&w+u)0&1kNj7CS{l_DFRH2oIqf*8|LuEsvO&| zF#)JHfaE`C7yOP1wnlT=?!@;DAp^?&j=ny4V4kV_&5M4x5jm+0Qv*ECp)lMt*5OdvT3E|MR<8u5(wngMV8q*@X=Bn zLOdws>IBv|#Im`>K&lgvOQenh$-%2R6D)%@H8nF+BT;ZLW13dN?0Kc*DM}e+e%49# zPnG=pcAQWx`9sy)lz?di-?^Wq_ikB(!m*RzH|42)37)F+A%}IOyBe)B044d9fA3bfVm52}jApKrDW@A0v{cp9kl}S(@$>YF zD#l+c*W037u(~6#dwgqHPS_x8Bo8Bn7#f^QAGrcxXhV1BjF~RxHVemLsu8q4fdwfN zI#O&(@@_Ek1Rdl-6u(Ek1LzmXyVlUu%z8@&zS!67H84B^RR9n;P0V-M)P4Fdi0Cu; z9ReA=8xZB@ZsFqMn(uFw@jdQH{kE4VwDp0mT0T{oRTB}hYcw>do>VMTGpt#z ztgC?oY@@h5ai>w$MsFW77)8H&x)Okx%RC39t15R32#zIbSl)b83~YpHH6C{-D07)9 zasEsoI~e$xheulY$FS!9f+&-LisEq7S8y_=x=!33saGDdxjpQjPXxj1Q(XaxZ}|8r z?&icHAOm3Hq#`4CkXj%p#mUMt&2;E3K6JW`(9=P#7#dIOc2+l?XE&tg$S?|7`3(j` z<}r~PgJS4BTzvlXC;pTbq7Z>Va9x|{@IuXz{Xle)cg3g@`Dt^z8~~Rg6_o&n4b(SH zup>3U?hP@77QJ8sH7VW$wSp7rf7W8s2?oH9!}}dUQWg`d1`E8_nY2!m_D&PikO?+d zjC#=ayVjS>R8+{FldDCBu(v21u0vF5LN^zl1R3edZrCu%Ki39kdV{%C!|G&(S(Qx` zF2(xzm^u>x-S)QSpv~#};12CMWTYG4N_23y`@sSrfMN@~6suoJnH#nHOjtw;f%Ey4 z5&pL{8r84N*&FnvzgcA8s5M^Fo2Ol|9c4R+lY@b5P?*#qfIBgt$S}k|=(*cb+(`$R zXTYlP`T^v*QJe&Y;$!x)aC%Y#x25>K4p9lb=#*nYJ46dm?;Qx<_@pbPgpb1n0yx&y z$z)&NMGoI2jR1b{-fWcaFHPd`EA9`prWc}`VeD0->^*>Seo%#jH@edt7P zu)2TMX~iyFFbxQ7;H}dx3x?puj&uK4Q?Lr0b#4#W)ZXewnMQRN>$wqD{Lt-EV@>2z zl$Lzot|VV{w6wCtc&hPC{PC(hY6KF>-Wb)AVQ9J+!=c>`wC>7bNbt}=s4E&OIL@x_ zUjvjRJ%9R~Iy8P#pfbN-Vw-{HBto^~^`;s8dK}e4tG^B!r~A`*TtRqW7Q0!DkzC*M zDSMquTwR<-+bMf0Y-Qq5o_flTs*|VgpbifYD`=~RjvEVHZm>Zc`PwomST1j4Wo2Mu z5>$^cUi-nsxRbj*i_|*+ZqrJkR8h^rhpgv~&Dy~SaZBh2Y*Q8&$@^VGDOCWCv`XyM zy+JD~e7&Y^Y*2Xx4zo_kCE>3?Mffh`F~kF8&I*D>ZujIsY#uSmcjZ=?$0mFEBbukh9n^vV+=FB`(rN?hnpl>4U$Z56}W%0}?kS0%7c* zy~Qu$0f#gP9L(L|`z06GhL3{|GJ;OF`tjW&+fxp+>PL;5{VyIl{$SxvAE+FyH)$^7 zH@a=Nt>>G*&*LxD?i@he3y?Rk>t0L5S`*|w5I1{Zjc@dn&ikJ_LC=P|hxo&_niekMGSZUF7F)(aJrUnIi3bcuBmvVS0ja5pk(!EJ+Fr-V{KWI;bEvK z*jz@$yWHrCH(3v3Dq+E!LMF#k9BO@}(-hDKDcM5V6r85BXGkj~Hgp*YSUPjmM38Fa zijlgT zm*NPi`_l0Mz>0y&RU^ERHm=4WuK7fH!q55JKNxB6N6P&jQX_zH=F7{~mwr&jr|0`3 zl{|WA_o1;pdgS?e;ytVvX`AhiPnGo5!rEfqy|JuHcJV-2B!2~vi4gTFg@#IA;OLdw z3QVg>euo*X3y$5cntD&f#u0JkNVf(z)<;3Y_M=sg(OGEk;wPp=qI61cZ*TOXF1Fw) zAhW^S8B0W;NmvK2w@pwW;1A*)@Yj2$388@76&Tr#xuP)kLc)Ae7yW@Kcqot5+{6S9 z2vaccspdRbLD(|zu!|&Ze`e<<7|tr0KR$4J=ujS8s;RCPs)(xz1T39}Kh>i^Jsn88 z?zp&Mh7}Yr8n_r`3Rf$c?Ru>cNMzK1B~LJEpMaXOCndzV_=^Oh_-_qI4NFeszCqj3 zZ>*pek!2C3?`eBMW7$uyKzuu48`0cxPOIl^O)~9eSN?^^$^`*z)_ew`r1LRE6zlsE z`lRg@xmzK%)dPI@ghCc?92;d38(uIXK|@x8R8W7gdo3-+<9CG4){HbCIFYF!Kuu-VZ{(! z$rG`qhtcYU))Y^i7RmqLw;^;v7y58XL(GJ3ngr{e#sxa@)H?1OHK%NOei>Ttq&aTn zIrm|&`lR0Pj?jZSdP>?bsb6Mv{lZZp9;KIq5M|O65+OcF6HEqLrmI=i%6M>{7kyO=W>T$^xEgXDflFV zJz-yGSevZSFuNJSsbCqRFh9$bEb}R07!m&aX8{z?E|za9+h(S393R-iV!SKDDHQbz!?gvY#>!JYTcA$g zSTS$dpz+f{nB_ofORS(2#TqmKem`!ETbq0#H& z)l%CL3fK^eHi`xgP&7HZpJ3`mgYXXQhm>Of8sxXUpvRKoE@z0Jp2 zfKf#WM7F!ui>wyP+?sn0_S&lE>t4&pRO}DsE%{HAgHS%FX+#J~Ll?+W)@gBzQ94YJ zzdK!SF!7;D=(1vVT;S~4w-)Wjeu0042J)H8MJrI0P}kTF8*pktzC{4bQ)aVX=pdlA z?E!SI08#~w$`;yn#U)B^b#Jj~#rX!ijj9%IWG&iURB3&v%EM>Z0cF9ESYmA{l^UTI zF=-|}WoKm-(f;zUeZG|uKaz!w&ABuz3@0Rk1+`qgRoNG{eT-1L)e-$|KDCsZp=b3zKqgBR4f!C~gpcWmQI<{9v5kcajLmAV_ zZr9AMs)?xR7qxOss4PfT;T|pTp3jHfE=mlg=QAzj=;_nbVL2ux!sXoL3_{O>WyOAP zOx76cI?-)?*7wtJ~WUq{c`)9!&8KVdW)iF$0YZaJ33TtE*M;Uu=WvTD45HybHcLemx> z4<)Gu-$qFI(dn6nz|&qwja72|r|}$FFxOEXHwlUx69>LA4I6(rkwQh?fWNc0A6rSr zagXMoWrsRi{zoA(W^XLYMKfNK{*erF1jGszCfGOB&-%9f&`}H9^D#*(aWV9B&t+8Z zZm~T(lEt4%8&_?{()px$iC^SKS|9W_H0HGa$>g}E^+w~d)u2(W=>DVUKh*MeX7P$3LAS-#Ta3y4FQwMcN|MYY=@SkE0NQfGvb zE`*q0mxKJq&XuJl{P}g?j0l($Ol@s)J&V(DZp<)d4`(NkvxC=xzR{X`9z$0fzg5dF z+bsMkc5;OSpUALXqi1?rI7hRfpgCBFzdtdZf;-5P}*f)^#IcxJ-ss|dWmO${*l9D=h z9bVCG{AySd-$&*ml`tntS?()~Ohj~kHm=^wp=#qH(MyjOD{CtZ)F4R;<;y1gk1EHk zxG3=VKt=cJ&<05jQ?|_9geKRn30>dLrV^R2L)lX3(RlfPzjI9ndYx6LbvzYR{q*UNbr}*u zm$G9uqtAPmQ4`tAWI@T{f{hL9dqU$JQ(qlLt;4SE)zy~ z{q5VX^+SZz-e`k7rWTAmJl9Y;F6!L)k<~3NbgPs=Dsy#p1s>5?n6O2!0$UY5Fs^@l zv-Nh3EO8h_?2th^AVY=q{#x)Cx}*a?53sffbQy5Lm6?~5Q|Fk+a@=Wf%v608UIs(h z83jW2z+bzPM(0t6$tUrOhss2;L^x;lf!`jwbtEYII`b=t*GAZgp zn2X2bU&CW`)2fh?=2RvA=wX{gNZRN(V6PJY+YQtwue4;YP?`jmDODjyYAgh2k`3B? zyazSwNWPqcVrZ8o+3HtvQB8}6*3QZ`ivD_2?|@x=@GbEWOR>+Y7_vx?J+uTt)?5Rk zQ+}PYMFwlKO#gTL3DZG{hIK-u`uK;Ak}I5o3#W;%V>OF(-=h1kl=1%Iov*sC zQ`EQiE!g>aboWe6y#+ySEA74{;k{i$L$ohsb?95$pns^!Ma#s87o*>(?(gyXbBb6^ z=Tq=4g@(SCrjdnF*z>cGAA2P~@8^j5<2=2J*QtAa-%^(N-@hHbA-G~~!wDs5{~QF` zK>RQ@da={et^*&y&;wXknWi=N6f;f4)>8e>3fYhTGH55Okjyz;>U=}=^U~WaPk`hC zi5^8wc|+Z?L*silybIQ3x!A#PJGVQRTt#FIKxmllqfxLtJ9@LnK5bfHa;MoEcYoBw z%gZ|g%JW|K)*oN3CK`HreWxyt$8+@ct}cf+Xcrq4?{U2)ZL{Hm2>6IqgdU zfFN1MZSjuj%kT&;6pL=HuYKDd+lR#pm+2#6jo03O@+VH`Ym%Rv>z*H1yU#$mth4>K z#(;aPBs;cvM7VP)!@=6}mDZ@r+34m69v4sd<%Y?l?W*zY7r~}Uf6vE9jLI`RPQ=?E z|54;}(-4WIDY6sWVmgaS^2w1vAAeL1Inj#xc#h7)CaSwlk@;>z2})~`%6g2wlHpmE zEJLW7CvwQ(xG~cV7al4P~Q2 zz(hguAn=HzCKe-T;>IFR!HGdR7mQM)1^;Lg+M&I#50Z?|DUhvKe6-$KE^mTG>V5yN z^t|b7L>p@tI3CstgT0kwni?27J-k>M-sxYjq^m6U?e(z|hO%Kw%S-azefOPH&GC9^ zAa`Y7{6xf(F;s)s*pc)2QLQ4;yaKN#uhU6A08JN;L1pg0PLB^O<5(?$6>Z~lXX&uV z{gFIuFS!A6T0aZr)Vk!5xWKwKG&Q9}fDTf)Sd>hd7Pto}NWWP0SFRZsG#JcNo^}b- zlMt%rPkeVz(BK+N6N4277-+1_)LcQ~dE7}n#-UxxRu1@V|=BtAN zbD-FO5Bn`MH}?>*lb2&g990+UYM9}P&}&4CkY4(wgRbghNIgXK0wr-cX!INCn#+l# zo`)$_D(VR)@fiS7_S!F8qkksGA}s(S3H?{}^X04f=JLLHxZ;joRZ>jklrC}D`kdz7 zTZJ+ux`Y7}7R-_mvz#S3pg_yhVQ9dJf?9v+ylwoqL2#IzEvuERStjs3C4+HCGGAGT z*EhZOj`&dK$6yRAulu9O)?4Q`wST|$yh~0KM!(?^5Nw0q1?y7`l=>Z%I&Y~K=|?e% zQT)b>kX)Mb5TD$qvZf9tG?bG2;{hsdlo8_S{Q`^bcW>d=K!nX$#uxckJu2ep zui0`=Zb=|SG;V0eIKXTX?wubJUfyPw;R$LpY`@UFhnZann=I8|cW)g|U%_;(m+pCA z1D^U(7b}8{`QZ8O-IK){ASJX2W&^7(2oxXDYw7`JqDZj-U=vrONqA38{3{q2EbQP= zPEY3tgF%%R&(e$n6#w(x*S6QuO3c;6BL$qPL?s`xt#?3v;RT2oXa6NI6YSQvghUkq zoVc5IN%~Jm>f&nCOLE5-Zk$$x)wR_1;4;AxPnby)3q)I6g+ zwdM0}1UZ@3{!;h194@9Vd#Y@)1;|wgrA)=dnQZA`9ssxj_->+YeS7_;Wo&)IT?5kG z_Fg(>cZ7dEAHVb(Hw1ZRyojkIQKm|;&Y4rDk6rkWkK}n^HkTmRaL5=xz*q)2s+2$D zHS0cMmf9|Q6&mQ0ck&~C(|z9&C56zMkKVY;t7sa(D(-o0`mgYdwZUK#a{^B;=18q; zO5T%8A_X*m5URVjL2jaf?r}K1U#Y>bI{posZH8QY)yxu$bYbLD*Ld#29UA(|wnkak z^3*-On*U1A7jKf@ry8uWN4s_m`|SG=XsnN(96h8WL+NswS#uSKF%-)^N_t#2O3D4w zY&K9lSAP2ETFf)!?R>AlmO;ilKiu*)eL&<3Pj3?JF{Ks{MSq&28~e-eqEN|C-ww-i zi|BpB?|ZFREYS{DJv(n!$C*jylE!~&jNmk$6YolnzegpoHt>#uoo_0+7JXQ7eZb@4 z81BoHFC6tAx!KURu8!2IWa!I0vMkfB3_td`jG#%v&6GepI6FC!Xdh`<^9To1CDP0+ zD~kuR4Vhml<*W~0m2Eakf7Oy$rY^FRa#6hT5~#ELNNuPBe~Ox2-xg6j195p@XM%p3 z3+FEuQ4vG0)~*`=)!SS5K?Ha~G2aG(9#ViZgKGe!@B|8d1dk>cCnpG%{sqzyy7{vZ ze$Q~tThtBl=Y99UNSoeuz=-azTC{RVT-|l3OCvxI5&{=uyR76M`K83UcAcb7JIKT4 z&xi&@C15!|xJJk|`~6N!+Xd;r*3JKpuE@N-t*>ek-+t0?V2%>eth1o+v_lLZEw&8a za3gY<@G+DZ{?WLjzCG<}w`%yjpMB=1kmMB$TZ07b07#BLtHb z{`I{zm6}?y@{C1v?jO)OS^8!?;X3Bynr9du>OjkaId1OXso<6KTUL<%4gv(!N?zN= z{n!%&qWK^AU%SNtS#VmcX50Jz40#*vAsV9Z!ku;<{11*H0UuzN>NN^7bBb7hc~%Cl&*jHn zXpnk1xU{5|I*Ge!5>z#rioJ1w1Odl_6m^%u-`PRePL_k&RIQ9ogW)gQe+molk6=k7 zY?&66G&Hp|Vw$gzC{PCe4%WALKIxA{qK=_>2P&NJki zn(N>G9_cDg5UW{JUADkt{S4ya@>aE5Vuu6kd(wIDU?n86VMOGgKCwo_u8~Vc556Vi zY?oB}CFRf)cJ=k>1m*An{(^JT#}Q5um5mM5>mTC{W?YNfwyBE7e#cj+_r+z`r0=j+ z&~!q9{a^$y{5R}ALo09%`-mL&OTZn}N-=Hk(KO1)(R7w-J^_Mi&YC{sUz9~qSIu1K zwO({;*EG)`m%Zh_j|OJvn>&sY1&fPP~z!@ngn3I6r<9ZA(9Io?I6jpQ;a5Y*X}1Xa8QPh&SUaoP|F6jh1N{9O^F3X~0|6 zKD>WLRPr~U0Ud%Zrt;!5I~IN~W->b4#94$|o2k1@dDIRhdN~T8KoQZ>82;}WISX%u zfKGP(tL-yf4bVb#0b)h#A4y*B`X5i%pRKj=Kz3r)EvM$H#xx)9n~J^E?U}wAiFBxQ z-S)A^F47B;-_f8$Fyjd_zUHPATIHLB*BphBk}&fb6><-r>`J_ z`k3H2(6ifNm-4LH`S=%a2PyX-s8f#s-HJ}2#Q?!HF>j!>0w@Skua?)J>&v39xo1G( z5ySiWRDqs$;Ex0GdunRhXTnDxX%L=Mxj%r11y6l zquLB{OCHQpaZBnSC6awYeCYZG%hTR;8W|^_hPw0oV2`P)a4mc!7cH(u_;MX2c@@zH zb;6p?e+szz@m;NjW@?>p?6}70^CBG_Nm9b=KyQuyF&?c0c?1x>#y`+WE^;-MRULJk zmUI+}f4RKr$Z=5GcV#Ik<(po}7sc6pdw9EUx=^=sa{g57^6L6XsrRn#<&<+s5>qW| zqDF0`q>v@Z5kVivbk8w#ymLjEh2W}qiZ6zl=33=&>TqkV_`uC!A!8RiyLVt;TQ9l7 zb%|ZY#EhIs)^F#YE4}c`!C&OE05>>j0$Bd&o5Rv}_Fc3h!o%cFA89W#BzF3jVColU zX2HEYk2E;E~)=GDDTtd`yl@^Sjjiz+1sK@hqD|=r$VYgA25B`gL}~+Nlc8JfCWk} zj-l@wDs(<3$iRW-BQ3z2f$RxRQ#|cPS^zwmh#u7b75(T zyQ$7;B-6Q32L%mHxfEN{bjl%S8{)ROwqi4luD+h<{p(Xs3S)WEVeL}p3oR8o8RZV} z3IpqPJ14~8OXw`dDdiF$ek5k7$ic};&!*ka(Ql#s+nB#IX5@-DUy%R+-+?2m)yhAe zbzk!`qQT$U@mshhKkaR-$=g*y8piY0`fIxb)L4D}4SMb5{pIE#22alZ+N;YfLNprZ zD9%#z(esKAdWTx3%-NGUshGI;a znfY$V8nldx-5lC@gEfaYJhYz?^6zvX|At^jOlXiq1}?TD0h7<)e^0=d(KZWf$Luk8ywi^4Sh1I3{Bmt|A?cW*h!=sQUQjm+gdf(J zEpOhu0mzy}q%(6vSgv>_&{D28ifZHJ|IRT%8Oo_K?cW1fA0=X?~}(O zmAA0<*C5D8qo+{OFU%g3_}qO2u7G4i??a3p8rHHhj+}>iO0ep8bogzyQbnq_S{8UW z9EyK=P`u(a$V&txQ!Z3fO2h)1ne#-<1%@A4rjFl0iKBYnXCv;ozU_;@hqnB?4?Oes z%`4WokC!$2L;v_6pT#v&D3e|H*NEQ!6J;209R+#B=Q@0E=PJf@O*qOZ--I2eF{hQhNB+5@Lt z{Q3&{uFo=(lRw7DRaP|$K2^#^HwQ0(##EviC(KX$=Fay`0=KzHLc>}F{_Z)m`{u(C zZWC~2*{u8#1cMIv2NaUL4HDAcD4EBrJ#q}_bXn|cwSvCAR>f!MfpV-TO%9;>YRqNI zvmx3WQD+;HW`wL^t?f~%7IuOtMS{?Z-0?+R!buR5};r`n^j?Lncrnhr&C3+RJT+51GG0O=c zR(P&cuBxwz{xx=V-Grjy?oOoAC*{HrHl^0;=1W}~_vzD-C%C#|Bm(d6@8@ACmQ3-z zyUqP8Cpp>}sdH#yb0D(1UE0aE+Z)A_|eFVMoo{Br6DF2pu0&4R7|xQFB+q2tZ*c}Wkt z#)noKMe9IM1bFzU)zL}m{KLb;{59lg0z|4thWG!uq^^n?XYK+mMjZBGzwgC1djqDQ z6@zrnq`}QrDIp?zYNY;Sv_2I5kJW87^iz_bM3)@CcSL-;Hd4DZi41z#%ez)r((4XchU=79qt^zp1f;L5N)7*9W@+2Czt1;B`*Sb z1{#|%`S2inq;o6Fk*=pMydLB{diSf&0nfO{w{3~lG|IO}H%Bf68tP<;NB#~>bGquC z9u(McnU*KK;FEuS^Tc^owm}QgN(;Z?-s|BGT0=VfhJU@pefPDjKz00rb9>RmC=VYu z=ZVe-LXcfIV;O^al zKRWOD!Zk=SaG))x4UeJU1GXC$7SaF?XD6r1=H_MiluWoiXt2mFE-%Mjd4dzen1zTS z^rAUd;E1ny_{7{*XlB0zgCCOq@+F=IYYCzdBj!fo3Jm`aVZDL7Lv z(?~O;08X9yZ~d?O%Vh-!vc)W=nwA8?z-J5`-mTs;ax&F5HNrWI8`JAvG{aeN$D|aP zNFd#5(@x_DiyDC#+RV{^`P%}y_4Ks})OGEAq5rY4ByBaNe`$J%;#j=lwPuQnyKF}$ zFs?m%cM_oJJvKTDT2mXro%32MFOVu7{x>ZnHFX-2^<~fil)hN1`4VWHb2<8ttuS=Y z=JM)ri~T}U_MdGM{tmI0Mr%bS7;m_>BUcN3@X(OnkMaZIL6>ZwVU9`DlJWMUCRfdMru|i1et-%ra=-yKKV05l2fbKd+FkTytI!rO;+JzKM2JWs;@8Pz;j%hVN+h?@>6 z&)uc4#{s&i{ESP09ksXlk|^_V{N4GKHZz9%*vbFc=DJj{_&8a-D zXD#dt97c+w+^7e|x9wwuMj}$bYdN_G-S&M-eB8WIpHdsw^GMX;XT0L$(_Qhk8@4+M zCttAllcA*Te@5VV4qShFaJ8OXlt=DUrORp(ErFChi>*-UXw0-7J8{dev@$)U1AZPP z`a5YlKwOvFA4OH% zk8Tf-)Bshp&G3>gXvHe%mP{-`1`p!$DP`)Y!vg0{Z&wL@g2W$^;O>vfkbooTJcm%F z#=!C8?tKW*2wePoTDji?!b#eu1A~`LFEIcmCd)Z|J3-O+g23gF<#3+LJ^FlEwE6`Y zJN87d^8pAwIW;ZrG6I~dR{dIWG94r!JcAjSufa=t>Qd9(FubqtEoa5pSJzOn>Cp7* zY6hRh&07ydRe=1Ug6Tm}S$W~6GuMotqDo%ZmNQuxzcE=K{BwH}YX-rXM>OZ*QkJH< zbQJev{%mLY>?bv0{F3uoDU!GDq?78`-|a(eXOA5%+GvDxhw={p6JvYfj5M-;85@i8 zs%LkT`n(j&6xM45@-Nz+A1uMw4uBjG<^Vl0J>8x2KQx_XP!?Rfh3PKo21!90L^_o2 zlJ4%3?ohf@UZe!1n}?L{P`bOjyU*s#e1DvgF+kjV-?7%UBx8{fbT|}#m5XV8pS}mW zxGK$3yJ4#jQIKkLz^G2f2AAr={&oEuE}sb^7FN|h%jUUQknDNUIY zXCkHnoA=ljwxN?LZ9T0nsb{m)3I30?doBnLc3Jtl;np<+6o*{`&XQ?JZpzFSVY7^n z4&^i^f0-Q6@6w2N%|_PE4;Pt6MjkowE1vLro*Ar{M6om9_EH(?o4%L3ZO+S3>G~&` zt4!1-B9&a!^zYSue{-@T%u%jTZQ|wjj!>ZZ2)#^?6I3xPCp*CO-ejVgtf4j`-84JT zb~$HTCm$i7yo+;JT*i$8MG!5q02NvnH4h&!t$rZg*%C9|bpO;I&#}8jLC?+$wg;=L zlz^lIl;Pkgf@}xiLPy?zin&&u%@X&&SFE|qnCLhP9Z^weCPJ*Ywiiv9flPB#z#nKME z&MgxOA1HiZ9(>NWQk@ThDE&~KBuxzgc>kuX0e_cl@4c6=3|X%6W08qgizGV62Tsn< zO!zikZ$2I0^Mp&c&}^GV_Iv_+`%HrQydKkei?F&7{IjC{t%Llsva(#hO|L+L%kmP6 zU+@?6fs{dbfH9vE;?d$pV@xB$m_bE|cD_0W3;e5F&S_HqLp|b1bq`N|`b>W;_oiC^ zygUwj4mcwQK_3e?&}Rt?@x}Z#Pc&@RE=d^L=_fcphq7wX?*qN3CD-c^zY!8XU`jPk z;hF!}YM(MwYSod)k{ggP1kckJs_gCr!L1X&iv&vZ^Yl8C1rD#@1E%Z4w?xR(FKekU zBDSn_9Zh{3@rJ&}&Ow0tGqFcQh{nOk2Xd>;Oijhy6mqH~U27lR6R+tETzd7 z6MnZiUb5#(yG5cpsoUBfo(%`emv%{oaufkirNd_wKQEy~s?z>nTG6pOttO@$0>hNf zNs;&dW$aCjv4If>#{dlKt)Sm^*@K8|iJpK)l6blp5g)UgE;l_HT@Bi~iwY6M>r9~} z(Uif{)QEE5wx6?m{26;$^yE!tE6%JH?7^A&CxTK`1U>izBX7ikD_WLoO=*F~&s=RW zPw6kBduuyo{rPSLE4DpVvqz6rYimUgKP_X?FN^{!i~6(p*B@){`8X{kcrGOi9}ssl zGR^!h1z%70@m`6k?Gjj$2->6us_vA6gY-&a0h*l!d~|GWF$o&%H4tuwZ5ZB&rhTmj z1;ac##WE?Ip8!WUU^>p$o<2QIJZJr($nB5^|I0{B(W;USznZzKVz3^3=Xx{z>3B^~ zMK0vIsZJAh_cDN`9RvtuWMlw20B|+rb2n(#iVn$df@oSf1%>Liwh=%hHQPK@DZ=}r zKHTO|?J=%1T6lwcN;fYe>r!-8mZBWsG-gm6Nq^Q1=otTz(Yd*q-1-VJO;6wbk)u;! zsvBH0l8;$)FV~|^{5!g|6x}oK?9LAcQYH^zRpu%5^5-u>%feBw-N|~#6XL534SX`( zZQd>LdAHokLT^qb9iSNo^Y@1$clM_W=G$UnyY~g50Ik@?&5eVLOHA8>UXzAemnlr# za*gAt`Rcxsmk{k)?a3072xzQz@2n*jK6$dj}Z(!S@uWrjX%@*Vt^;{5)5RsB@QuyD+c3&HB z-dt#w;@f7F1t2Pt3&%sdiy`8nk{=D~$a}?K)duUOUsAPNAvW`cTRjXrq4F|EW?wTT zPjPEg5?}FB=ax#`2*eyIXSx4$nmR__2eAHIxs!H-T1vp6YF8cb?^t=7OF@ue#C2fdQvUiPCM?igabB6pe>+;lxhm=}@Sw z>BGp`#Wvv(kvs z{+=JREyeI@^(>XSa`|ZIY#K=6Z++(!-i<4cnbTUb;Be#Jbz^U6n}yG%NjD)#%({m< zfjMA)IOZ(5Pvok1R;7j8#G4GGHfIs%HFm($fZ=2hFJ4u5wRp2JuyOWUi;a(CzfP;b zbMA1UI=}RhJp>e#;bK(4U`QISSpe?h}55(bs0HK>P+VeCDC_`R_52>RWNU z?32VBy@`H#b@+?Ex&4jyXH5TFAcoT@J^HxfGokK2e+?4W;x4S2@J)am6X2W%9cGTn zf4ZIJC9uuYY`?-Ib(#bs@`5~%Vvd2jUWzUeJdSl7mIR6*V6T2b{zXZ+YDw?V?PjRj zwx%sh&^QwH;Q`R=z(n#l1`bOBYE9$k;|O$gjMLk_8t!_G&@R!pODHI`Zo#GMHab~6 z|GtY2n*hN%&o2d<`v`8I7N97cxtfRN!6PJCq0dx(hr4@pBsl#9%8E^-qQdFMG5*>O zz);4%0E0tCh>nMKPuR;0G3*(ZYoro$*x;wal6f(zw_4{#0}Q}_rBIMKYcB_*+Tnxv z2#r7;JZ>kJ=aA(m+o+O4>E~trpH~YDrVRkns4WX~bA_A!6u1xYb?D!hlw5uf27((O@~l5MJ?p3;p`mlLiZhSC2aav`L2sm#63`aR)HSlaL%OsIcDXP)nNzg2Dy50 zc)P@bt}W7)x-7sM>3P113{Esy4q%~t2bd&hJil?8cdZ(mkpue7pIK5jz^wX*9NoVR z{ys3JjaO=ySjb%Wt@~7sURvP)V6f1B{|}mUUbipk%Kum}Tg{G*jZ1D~TDl%)`sUE@ zpPXFP=%Fzihe)w~ilN@*l!$4z>pR)BcR;>_U3&B1CsLM~qLG4L|Mu?=p^T*f5P_V(P@WfG`&vX76x8 zuvq7wX%d9il-2r=WQ50rKgm$g|3O1D^CjMe@AEm9dNus`m{zL-#pnzLok`v3jFwHH ztK#>_989-hE}9Ka#~&6R)MJQoogDA=f}sR40LGJz6^O~9Uc z-K|+mQ6a2OwW96CSNKf(E6VOC|bAj-E+;2n!LlUsM z4ySc@;>+OLql};3KCPtdOQ)0pN;}|5cGn>2QF+r`me{jJE6pWw{~%?-(Y;Z2jm6D} zy;qPs_I4=%pc4QVE`e6qenva#tT&njD8&IkIqt!$v4j{a_{*V?CtHlFACh}mwb#8T=7Y`5jpwF(ZDJ?CNGJjee<}FQ`#;;pA+J4UM zyS({6x2WB-bGCl$McZY$R|~#tCLsu+uW=am+@mnd5U*$;0Ju|#2i3Xlk?nv39x7V= zPlbX-ajD-44Tmg0G3Y@MF|cPhX7GVk9Ah${v5WY)iOgkG;Ozqq8!JN4vZ2NtrCpW^ zJ>i&zT4fnA7jy3WW!C$oH$#Tq_+aSgN{7|LQHYb8ax|8HczLd&p)p`y19F!5`1u>1 zw@{$c)6+wuQtrzn797E}0Tf>3f?nUItj+wMza)u|*@L?@8(6U`%kP`Rk!4)*##7jh zKX$AO7GJDjmF2&CTssL9dcd`RYJoc-I(!s3$=SuY$XhopFz?e|>{Bn{NY~lU^2Y2> zEtZoXi92%P6k;Ek-ps-}5tMz)7s-lcJhg5Wcs1ol!~(sj_G0F-1*5uDHg1EWtY5ks z?z!t>^qX*j-V!xouHX2dCXx&MyZ<6L8F}|wb2vI-Y_}PC%h3%s_Le97IkHRsYUs%i z=5r+bh~Jm=)o);zrVg3?H%-?V{1fhgWQoKDe(5sw-Xp=gQ)C6o2J#`hr?l(6fmf~` zOcj)t0y9N=MN`*qva)N<80}DYO13_^v?nB%fX|6U5kHe7eK$t$3YAs)ozBXA^@7t$rPMrO31<5mBzD7K$c4K7Y^2)yCyU)tyh0V&_ndlDv zLzYl#q3az1PHMlltjx?zoTmXrmnWa?gxkyfHPV`{dF?KTWfhg$FK)Cx1{ z3cY5!qaUD|!;c(T!f=(;;IFqDij%5^BYZ{mC@Nys)G$Y}^Yg#Y{Rzv{+R?x47Pt_{PFRFd?^#l zke9H4ZS?!K4ZE7TnBfy^A|MC`G6T&rbpi6&<6m;azQ&@og9S&b>rL%>4hidL9z)lc zm%G>E9*~D}eS((=_ek*;%ddi|EMIA`?}}2aXVe4cv-jK9je_v-SXG3z&1k1mK~oJe=UM(ENy78|WZJY9TP`AU;*^q#{Nxl8N!yRTQ|~p{(}(|m zJ+U{W$CyepTcKXURK_G-$+FB31`&O;vxxlycHx6PYj~UZAb%S|hmeg9$+QAojbNc5tq4#N|a`^@CDg8!EM`vSnd;Qrw z!k_2R!gZCA6gr zAbvku0}S)axwSORmok|M6qgKji*$$Pez0;;rxia4QejEXZ}U1aVoh5@+u{3H^`}y< zqAYb_6z<@GB#D10LF)#?WA0?JV3ujzk-PtkGgp~>P~GaAmD`Qlahqsjf_qldaOYz9 z3kfr>c|EKXc~UyULlT-JIaNn|8coGZx>E^3(*rG(Yv284J}{8U=A>NEt!?v?5Y@#o zT#DDsecZI^HHqzCdB#h2{=W3RfCj|BxQOua4QX79nm;rTY+=iJ{EZ?%bnN=i?AOT9 zq2rG{NN9b<%Ifo}_qn6hzeCf$DM_$+Iy6J|adbkdY0QT0*FZg{K33WE_?Yrlpq1F(^KBk$FqeEUAY))TA6&eR7q+BTciauf@Nu9Rm$k5<|0fbK+AcD*^foPz zm2`WqD|9pA=vuVm72wtW=Hq{$Po_rw?#MHoYT)OYCs=!&wx6?bu+sdmQ&yb!s9|n? z*?u9dTDyz`Nk3QL!p55fl-({3`3lMZOgBAn44)q-(cB$Yl2>@aN#Rc40u=-RW0D_C z=dA~+6m5l;xhs60Oph=E5Ax+ntb~r=ZlkWkb=QnEV~7|cUX zr|F_nYMqxZaj)M)`2gCIY=2Tnr1@U0!luaMNCayExi2sQaE$0OIsnv{xA2elz&jD$ z+r$z5pUD)gP^bUwOH8)Ud68qppIZ=bfPWJ15&FMqI*Z zr90=m_O0%!GUWKzH_~R+fScLW^s|AK1(dU3Aq0dm$15)qK^9-$02*m^bN%}z6{@E< zA)z7pZ4Whf7Kg`2GIa*7%AnE#_%ZOP6NaIk9(6gy-g+VimmR6#^%qB%!dK7tBwGp} z1!!QmA@Q~*rEAM_>4Gc(c?<{=& zU4klN#~*%@aq1r5_~Mz4E%&nRyB?`HP%f|o4)(HF(90a@rqc;2$sFvxoU0oLo-Kq? z!LWGSNOFCeCo^vVezr#wy~=Vy7tH}uaK3@Q_U;Y_4AO0V z8Utxfe*dhf4e(M7C^skY%W8vMBx|P#?Ls8bff`=)_r!kQbfL5cM%j4e?SrePjZ=j_ z?!?t5-|t|Ie@(wDx62Ogj-1LjNco5O(fC6LxV4XzZzj*cc|Mv?mSJ0Wv?@>NQsZ>8 zyCv3XEK|=@O0S_Mv-(;cr`c}hIzF>RkJ-j&r(pb@F!i4GjOy&u46PJ%a3KLCN`gi7 zmpu^Qib+uCWmo|d&e4bp8UO0=aKojBq7LVH8L~Fws9MO9H6(!*_w>Oh$?aohN;TT# z1=q(+Re!%oFi$r&cvh7Ap($rNuw8ANjL{$3*LXl|%(y7u7-za@XIzS(Xt=~L6g+Tj ze81o9v+Nr)^;Ouo2hZsA&{O@WGAZ)sXa1~75RN{k}a z{)EHsS&=vn(&l&lSvFmRUNC1AC2@sGX6@7?eH_5JQKHei;f6KEfpUWm?NTzu2xcw7 z{vQP(^fmSMGuv)O#)P?zsyY%K|Lt5buk76{dxi#EC#$glJ^30q-Zc7ND20YvX4_x* zS=>0IeaZlikBE?PwPr+!|GKh#ImX___S;f-W_e_USBM2Ahlo(t>yK4xwnc+?KHoku z|4A7z%_qs(H^)Cm^myE@@-YAzE;|>}0cDcYVE9v;x^G@`O_n-DyVN%+9_3NM7gOtd zm4_QHHa}lKW(gRfbJyrVAz{n?KCsSG*j2aaL@+!b6TyId9}OY+yblKl2WWZ_5D+$} z8=H)k5tGN>j!g7(!Uv0j73;Ku%}^*GR=YJsW?DC3A}4TKM($n84?a1&=P5=g7F-n5 zuUg25p`jsrY_9ze8Z+wo+*<(WOYqNtGFb+Kkw}As9S7R;KZ5!L!}V%f5u47)*Ectw zHrLF~b3Z4=2oge}geqb|T~7mSHhw*S3^JM-lZ`=lg*XMPvN!o&gG{v~22A0ABp!8# zwX*t8=Xj@zO^GxwVNPA>GB?Q|ZBjBs7>I}#iD%n3#z^q%QU~2E#S7lxCYK-h)hZ=$-x07Jm9^7MHxWC0FPEx zeZ8c+d;QvR@G^Jpe2lilkY%Sjfd*Ch4pOg=pWm}omU2haY$liSPVJG=dm38Jtg0`o z*TSP;AKHw-wrslIy}w+bV1i`5gdklq$q=rF#gybph~nQVo2w#L`D0jU*T?xJL$J;5 zu>Ux4l~3(AcsfWXfm!Ol(=;Ibel+p;?X_`e+CQT4Dzxi_j7>l6wiQef19yt5Pf=&> zJbNnlVZx12e_(WNI&R}EkV@tlv#S2HhcCnmFnH7#bYv{wVdSNQu|RSU<>e6o$Fn+Z zQQ#NcS8%vNwz=pGW%~CNACo23KF;+utv*gV>crC28KB^)^gg7Km6rREsB3yT>rGSX zHvh9UPeU8(c}pQ6lM$V?LOXX!TuHPEe;D@MaWAcilW7_snE3ERBg7;g<{0W9r#61` zgob_qV*|VMD6i^hh?-ne`|Dclah?0=eSQDZ6B-U(iV81K@FC*AkNqoD=S>xLf9M#u zRa(-~)A_aBWhQO!!f_Pm_xkbH_*RL}{(p3rJ1>YAOC}yvT{N&8QTI!Wb22y_6q$p* zpCKevFAZPW3*bAwuEpfFb!@w3vXUHXk66#YEaZM%v9hbWez=lC4s^=?4o@!Z7d5nH z{Pk-MI*l~}lQtNl@i{l@z9P6xY(0LgwF(U;ql}OXCEazdXhxQF*8m+=2jIn`4S4`d zDJ0P0!2S_)L^{OM8=&K=@G)XmpbX^Hc64mfn8OL(xbDTk<7)3ouEy<$h2>H;V?f zv|@d_N@Mr#sb%_R4%9i+%u1sIOL}fwTb73aOWMuZ*cmtT6|l+)JuF$+T~W7ta3pVz z_sA|b`i2^>eQ8IWqAcpwfKr8IOeQ}__bUI6<3?Gy@Lz$G=oqnv z;3?A4Se05_A;->qN4bJ=0rWv%m7o`5Lak8#K5$6|yV+>i@PI)#Xq15o*ua1S>?F^d zJhG;5trwJs+6z5@2~PUh8H|>|wg?pjx!UP9>aqY>d17MXYv8pz2dB2kJc=}x8&29o z*4HT;x~GMg!OQv7$>-CRyf&|zvCZj6zJ;8xk9s?34_kcG>q1kyOQ$J2O}>Cnf|rL3hJDTM6N*ll<_f1XGc zPlU{-*@q(Y;fIM(Ri9M3_|p@lpUn?Qkfk!}G&+L34h5rbC8Uy7c*+#Oj$5ZObw^*n zdcAAeX#X#tP(iG{_s8@``MU*`vhHk)IO`S};H6$z?wV*Ruq&;Z*f(WjlPJ>uwJ`p7 zd|Cz68m{$&wO0SRu>8F{@op$yD)}KiHyIUf7hsh(B!d`P{&(` zi!8bh_V>PmOlw@K3^t=CcojoxAaL6{{(T)Atn5a{Z}kjwm2$)o4K(z=Q9a!T>FfUH zP}WHv=;WZNmiBjui<biWHJ7LU&JmpNI}%9iltsh?Sj}#^TZ%pa zOE*o&y;Gg0?#$QFv#Yzg`FVR2$d?SKDR?t0Poj!GS-ORDZwd+$+QfmXy4K$ATO!b2 zFSt?q>a%9hk&I*srVjsk_c=$25{w2Zp1b_B)fmq%vR+6%KAhMLQQn_RcW3Y7X!|=? zAx%tlf0SAGbNZoX1|f+K>HanE0vbb=q9hhh46MkW`EtZyQF0-lS#EXE9&C4Yb!9#G z7(Bv*^rP3x9>kswG+1k?wEQdL$g<9vg7uR?qpqC<3v$$a=L1TxLpJp^(`vFsn)}qj zxIpHX+2#Qm=Mny@U;VGdrljF@sa0z_(kt2L#6!yQZuF=bm{3{N)Wo*7QFuKoL6d=f zSzl)c=HogGIM+j6m$vU}b}k#dU7~laFv#}H#%m4rZPa>PKNt+sPsT4`(bYqbb~W^djfC$cW|6&n=1$KD*3807L`s!aiH>30rQ@ zoeXyzZvJ&>`09t#lucAr^u!zT z&Sl|G=G(sdQEiI6Je}>UY|Y0)U<-1G!N0W>U01f`=G*m@` zy$|0VH5Lzr=5s4XCE4DXZVhncMl0_(A{;;2C*3q1u0wP8GxvwNcebmwJbU{`RNLWBgaW2i0v#8fUs+;w zP4^6??^{duKNP3OWJX4UouFoe92~u)CfN@;W(KJ@lgRpkzRDH~=@((LaUKR^x-=Zb zMpboTuCp=>xpINulo&e}|B+!wTu!*~HZGp@st%1O>TgNb35NXooFwps_HVe_>sXSew|wlUS31F( z>||5$rGXb>`cz1MQgSvmar7V|g4afGe++ohWlF<*TH2);_p)gz)E@G8f{ee>UWVZr zSwwB8Pgr`toQ4Vm%YzKTlXKhx)V>eZHi^+!2$Wog z12|C!va;t;g<*J9wmI=-EkLQ7<^Sxd^9+C{!1S|mF(OQli?Vl|MEEz2@y)gi-`=%b zq7+?h_ctu*_p(hmHdkq9RmxB)DXHkmaa8esD$PaQMN07)n3%7t-dO)fYT>&9#aoS+ zeS@=){uduDRg2V&?d{9u&y{pWs5~-vRg3K#Pid46q^}Bu<;N4gjlyh#LLK-aK%m?o zax{d6cAnaj6|14&*UDGkugS(%US3TMt*GOVgTlwnQOmC5^{vMrTNPTt=-b#h z===BY)FNL_PG-s+;uT0f-Dmy6nDnFT%!vFR$t`eukfglO2J$qLs4UE$yOR%m#KU-X z!pn#0%uCYPt8eu%&cDNyuQ^R~FuS=ejCaNK1Pitfo<4J*IVblUWsXOtjIABH2#2;fMe$BVe2HHMbGNXb(YWOYeed&{nL?1at-j1$6F;ZVcjJ@x*4 zTt#7{$V$EY*k^zKu(eX}tI>|vzH?cXyky+YDUz=q@0yp=0e&8*8F%HBa{{x{tG(L( z(~4}GtAH5|9$`*v@vSM!Ufmves${k}ww#OX3dAcExq?6cko;Fw*(iUxs3Wj4boz9G z!}Zk(YOn_-qsZUcD|vW@Djg?lCyq7n zTKNeLU=T$=O)UFsFSz`-5&`_}Wk?hISC(9ZAcm+&O;&(P)mDlBn=MO+D6cGSmW82V z0BhUh_-SK>P2c5nE7*R3#0L&z4$FkX0KS8@a3ubN;%eUi{QS+H&32prz~m zRoXv%KeQNA8(h|~xl81$7eAek0?KE}RKwk}JcH+t0W(cKgJkUB&M8o!RJYXp6}=K6 zFNMoP;B8-ea0i&s((*FwWAurm;}p*UmxP{t@!xa>v$Kmp{%^aGB2mzi2zKC8YLn;C zFT!>X#EY}8ndm~4ZULxusMx5|0sP@~&C=J)%n&BXFS~hZ)8>R~;RS=<4+iTL3R3$ufS5&rv0GMRL*fiQUhCy0dJxswWe)_kCApbwz_HtKtYAT21`2NA|w59>eRL zZ>qVve#CG*5!}h#;yrozGa{R1VeA8Ab71ohSBJ%R+(2wxiDmTr&xnDYMq6S=TBWiN z^QCppxVYz;-ARaNLEt+9&&c{MMJxf=Qy{Z0sovqw8G^i_*rKp;Jv~2p|A4;jUueFI z0cj(G5d~blA}@A=^eGXuGPLeumgzl$`as8qdKXPeCa-~ z;`Wp%Zx(NPD_ZicP1u~|v+|d3eOn!^ZWK$fOQW8yNZLV4(Iwfg)^T;e;~ntX_&9^a zSOV?EKX%3=L9%NQ*`_-+qa@iUzXX<~NZei+m?$TA4L%5qn^@rSuf5~05kJHq?3e%9 z9U9^HM@T4ujiOg77UsU2+niBZj%V0W$2*Qwll>^Yr}#wvkmd2sbpvuzZDbQP`ljL%mFFUi+$Y@l~MGtH?}iB(k|{WyeXZz$;} zmWtwhvovQ1zP?%fjH>~%Dj*2}uYWK2OK#d~Ic^7!AZ8;QEY42=sSzk_ik|?h)#~#4 z8Wh~1073~MMCH;aR8Gf26#aB9@Wo%~7~Dw7ZM{nOhpLPcQuWg$BYqH|M@UkQh0;Dcs$ z`xVK+xIV!0yRecn&KIFhKPL07K2%s#$}J@ge850W9Cz43_lQg{5;Bya>preZ5iTi4 zsOe@4>1^tPNFD}_tuMWwe*yY~C->`=zBuPuAU*q5us_i4?8lpCH(oPz&9=`SUYCgm z#&nKEd$InEPzP;x7*xd&ld?Qf)urGkOEf_}lwt05k1FCI?V0F~GluRYFUy$Lkc?+5 zY1$tdQ+;+|NS^(;fy#K9NfPl+;e5K%V+<>GGHp zd9YxR-Ik=g_(Qy{7}T`;L^B~I`j;ki(7|>bv&Eagbr`&%q@k55dR@1pJj5voFi7pZ zd)*24$jM_I_lv$tM3cK@dp&*xn9qtpeypj4gKvqJ9`Oh zl?lFNa)Vx5YqFuX2VPrkJo1(1&t@c?uqF*f4g=gN5mrBmIE;)>SoFVIR_z{1HabA@ znPA3{3dSJj8U(Iiz2J!s@xUK|s8t`m@5nawG-OKF%ayniyeJV#%Aag0jr>Q-{hg%` zF<>6n8-=;2&qERgeOdp6s&ND!+Y8FkVWi2CGk#I6bPK;pR3I1Om5I|O@yP7EzUBrP zSiPNo2avwzBSZnb`DZm*Pf;qj-4cjJu+sEcn(uHOA19p_eLdRB6lBiha8oCsRkM(1 z9F{F3ON=mofV0CR3g9)_~!R*cot|fb)GmdqXG5JYoz7!a%RBE zfLqigoT(zU?PjURud3iMxoh*>@a0y0Fo&~9sWgVZ2;He#Tfx#S(P|p(e1rkM9{{KU zQNf?$u_E%R@|&^n@KO%Yk-n$_NgVnxO=#fvyYDFS3E|l0~o71!-*2I<} zUEkiMf;0_HNs4Y_XA(_!V>ATLB#8U@drCBqo}=#BtBMUONKTO6)+jkb>eqh;V%bgBY3lM|tCpRX>#-Av^TW}E@ z)y!dqi@`;nfT-5aH8!$M5JCjBy^hUGN{q=aRMo4oweb+`#Fv_M7?L=#^3U@!RIU6@ zg!zAvm<$tZZmUNI^|MITdP3>X#Bf>5o$(FED~yM*QHNtmd0}EUfICf!L2}*Owffp; z%!?NYZ<;c=v5LI!p8T{~drnUBx|j;C+qI7e)|oBruo1sNkF@i}+o=gQAnp9qqY-*0 z^2n5wF6zp#Bd>3wKeJjfI!#NlHTkKiQt2m?7+O?-X+FZk*rM)|)f$iTw)lqiRGdj%M8d z&1anQ1FBTVyR6^JIm|qFl}nezfE3EE>m-pd+=C+Q69z+$3zF(J1LMOFmV7H=xw(SX zk-IfwC!@v&w2N#a;(7$x|7g*euBnZ}r~zkup+a0YqdmzTyW@(?^ea&VsRDq4TI;dm zM=F(k0on4iOParl501SMwjQ#KxgjyV_j;GsQ@1|8B)$4LLMte1ft_fX7we^c5o+8a z6){>yD~-`F#ueEki-=e4Y=^3nY;GQJZWas1yx07@U?H&ZdKCF?Uv7fz4oK1xo#&9} zKEw?RR~aeVW8ef_nawam0g(bdv z5k%A4*Cbj%MFN?(3k3=Yq;wk`1GRU<#|{z|g*;ip2NWa_&;H}zCHj=Kg5zNu_TlGN zV&Vw0!{c*TD6R{jd=o2nJpVg#?pmCgq4Vr7KNA=M*&0TG2fpV*oUbB1N>|N_^@pm? zE0MdJJl0vz&=6c0n%D%mKJ1FY z#89idoyuzOzwl%z0FY&_F2jU(M2A=Y5eL*e6VBmUPFifLkJ7cGQ3s%;B4CukKjs35Wg7{`pi*5GN@)zk!k4#iL| zDfAda5A6cUTG=CVmg*o<7c@`ZLm};;wH^C=O|Tm7>v}1@Ke$B$KegyF$LuskRrpS$sj7shL5p30UFD7D?mU zS%f5#hIZ*eSDVf#T@a&&ah7kH-`K_pJM=v$qBU`p0#ppU1CysDz9g_Jv_Fa(>M;Ud zK+KiemtLNzrQLFox_J15i4-fi8c|1WjJZsv@j5Q}gEePD`%n^TGwdk|yoll;Mo3&; ze4Ex?Pw*e8_0AwqCu7=mGQ$NaT&MB;6#A|Y>z(#9EIc1WxAr+C6rxtc&yfFHk|)+} zYOaseI$?6YBejMULn&!7tAqORmnKuTdWo^S9dhWyWMSx2;XOrXYkg49Bfh%-4JQvG z>FwzNLIet)P^_sE#ZNK)g1)4o5DCFp9By>oF~r+qA&l~@U@t>L-%JLyKd1O9AtUX6 z=U*1t<-54}V3#KoXv>e`7p8UH{y`y9%x<;+ndGBQ<_T}1@HV8^MDU>Vl!7tJM~l=h zOQHL*2X{U95Fr?b2nqbFi3~MhiVZG(a9lvxoWA4`|AIu3Z}1Xk_if%MVz*4Z#D(HhRU(fQ^Q_pY(?( z{STDh^hBzr6x80G=jYBO<;ZX_WMzBK-^u)Kdp)n0phrqyUz;m0J$wRThqt$yduJZY zKsPJGMrd0@husdu)bR=hR-qBh+J^%nONX<_AgAjrxxxn?sPH8LAsIy8vU6~J;-53G z5q%xkxy8U>fcT!sxgf8Wn9NLdI=OtAaF^f7zE-xTXoKbIap=m*Mzol7Xqj-OBxndA z!O~GZhOxdfA+(!A(WUz--7m0o?RJ+3*qOoRJ7>!3%yMte%CVatCRqg@*xWn>Vl=7f zpf0+rg+K6$>m@_Q$bw_iUVjjPi~1t)biN`nKqs6@Lm4`UeIsEMJX`puzbTt~e2+uPYHMQog$!GL&A^3fitcM{+^AznDB!@xE~Mh}K2d<_*AGhj^wRQO$$0ND;q zqu6+eLj0Y|G)9+qcQ!z%(0%icaO*UJb}P`7zF>UjF{+*^qk6QmG=a2oYAmOb7!f|bTgn|?S zRu1S>%@ovb4<>3Q9~NV~l|%^ayJb&F5DaT?OsWY+_mc>}q_TgfdG1aK)h-DEr~Y`( z1c}TKb+3p(TZV0pFG^BB&rmNh8ad$bqR?i{oe6fk&C;1m{k&4Y!aYf!R^lztm>l?0 z2PT4V*Sc@89qgPcZ%i=A?h?xCOQcs^J@a4#Qd)Ga&9wfjo&&3)V zuI#`gda}dQCjRaGD2NW86Gs}x?8?eN&M^DZDsLGu^{;fJf0()t}XmFQw!P+NfLB-6FV)_PUuVC3e853r7f>Lru;<)9*{nb&5W=*>|n zZqNRxG!+9nP!fx-`Fmo7rQk67bv5j&f&xU)?ZOOvj-30XI$L9yVLDv* z1!y#M3~)yT)i|rM{>-bVPq8iN3OB9_%giKas$fEGZ(7(3Svayct4)BqKnR8g_{F%} zLS3d@mEuvMqr9iT3U1EXuWV;{)+979b_*@WqBsw>$`$&nZ~h7xUw{?pM`mU(aP%@j zAq1TGzdSSmBp+yM3|_7bHUPfnjlxf!Kun?AfEbGUg=j#(-{_0opclSFUiN#i1KUAF z&}M)+8Ho4=u+PaS7eL}aJU&(#U z;J=UBfJ|L}a*_N1GE|m1wVOjKYWVY>8y=+o1dHSiHehoAQwq3D1ZxUD7bFqcK3##| zd8Ohih}gVC0?o+P;&OQR9MFb&%YZF7<``hXjzly1gOnqD=NmBc)zX~{RtMljM&BAb z#*GE~gxckj?i!W}+By~~s(!k@Fj&j)B4iX31(%%$m8Rdh9lcx|jwP%vmk2t?AKZ$%Bs zq2Le5qY=FyGoeb~7o(ufBdjUjvCj&JDRGK*G)){1ksX0flX-B%}9r!~T0i{kaI1|&bX^`6cNbp@J$t;R(ZWN2y z;D^U@bMeZeuGvBY1v~h@2MA#yJ-hza*>xo}pm}N+Am)Z{zY%bT#x#FH^4+M>{5#F= z`1oE^ReSfAzoAI`t8{U2ph9Q;41n+VEGXy-oNH)?aU+l z8 zqoLA|*a7XDeZ&*pPx6ki4=fn6w`C9i(*mqdQmFM`MBpsO|57gjK4mzQ9nT2081ixM zp5bA+uK>Clgi$pdxx+9O;2IrP=9W<^Z7Ud0eIM$7i`c#4^myAR{Cfue8}>)iJ|k08 zxK}I13OU)VoR=Q~fRQk_-tS^XQ z5MNo{M8)9Q0BoMXga%YP8@KCD+Vxe9fogo>R@`Feaiga8%Z<`mp~<{7=b^EKtKw!7VA!D!h7c%6Mu)AIm_P+prr+t*D^FQ`!K0f==P6ock({B zYoQ(wNA*sCgSYF#M=I!r`~Lm=2A4f-g-n6)<70c!d4p2p)t=8-2i*F%K0@Fl;1im# zfyq|!cnx0yHU*H33*5hNkl@%rdIx|V656QPy-kR=o#dk=^#@fFa2UO!Da;;DvY&+t z4YvGPKUCyx|8CIh4(_Sb5wHL;X7K~2yUoSwB?(`DEYW01jw_YNVi0?;cQsG8VKz+@ z=!N#X_BTli(O046Va{0?J$yN2OuetyeG+}5)qme(M}LxQvCYFB&7yrG;EatqiSfv~ z%~;)>u2%O3YBHL5^)hH=YxS6OT|)o6*e}R2=?S!R)jP&;L0t6{k&2o6qV}*CX4-fO znI+v|llj1mT^3sjlIvP!#s#Uti_^baMW3CXMB7qxr^9GT=DbwG1aiOEP^QEhRr+J; zL^FdL+$YUp%=}!B@R+Fg-!ewXeMlwAn``I=2?i9|0wKdKnjr{B3_5w2iVL!Lqu_ws z07SXGEumTZ9S);**1Wv&JfHj)0cL_lQgJ;6U(AspIc+l{6dQ*plDnGQ&wY5NIksXH zTBfvj9N!shTj=r2T1_n zx7HQ<1|!r6qW!81`D14v;jei8VfAjCpWlGrcV_1zr>%_w!~{4kJl@>-fGEyYPjZ0~ z6LWI}sND{cVobCUeOweG(UwK+r~C8@>W2DAF%IdS#z|6Pze~{J!`m-5(LVgkZ-1QK zMN&VhAZ>7%wdHnkbu|Lv2pFNTJ;w1t+6+(5bw35Y>vEau8!-JSME(iYOnwL}$RdUF zTX}#ANZ4p_k0Ip^0f31V;ZwXY}+~pG9V@L8`?yLNXA* z_I2};wHPm)*&i)(wJVqp{xv<4!5<1>%aDwJJ?b#mUmFjqW{%XrsGss7{Zmf%w7D^_ z??G8T$P;E45QsAAi&+C!Nsz1Lak=|O-}~sppNHdSB!plWCjjH>0P(e%0-iyjU4;$>K5$d032{6VF7Re4G#78D@YI}%OcPb&fcj`A#)_M z&hxQqil(UF%jJ;pct$5Weuiw_v4PjkonU&#Gr28FSv@Q#0z)w#+4NaX9p{CH7r9M+`M3Pr}9!%4WX9$f39H0~0;iLKe zUVws`;G>r$H^S>OO-CxJ37INBIh#Ye>z1}wDfZpo157ek(N69gs;`UJ-0_n<+W68i zZ`;dm=P7Uz)lklLFth31w=5PiDh*OC=i`3whS)%blla8WWSUPl!T6yt@~9P8Q|iyK z!7l^%5ctJP&2G9cnq#+tqGQzAjL^UF8CrHGD_6S~+a)gi%ye|`y$ zdfVwdzSS6s{Y$GJ5`F{bPnh#xY_U4g_HAZ`6^*6-mS)lNZ+RnY6eHUh8#HUu8|970 zS1$90OUW5O;5q=^(w~GM$5k_*c2;q=)A1C|ZL_`}v{7c3s8O3Q?WewUR`&R&b%cqG65NYU z6Wcn_?{E3{s;W=P*RF7U?RnI~7FAtw&HHBj%zvlTuL_KIVe!-dW{a^Cnvih)p-!(S zTQay3Vy=oFt6OvHQqP`-89u)&>*Pfd<1KB%J%L>G3K?trd32 zDF&_y5F3=M9eBz4e(M%Xa9eD;YRsP8##3QH5l?ADA8ZDGPlY^SI0 zVe=x4Uru68>+}HNt*omHG~hT7EM0e$c7PtKFS9ni5I|l>k}l-_(7Wx`Sjsv|zinrC z7{hDBxSEsetG3(cfW_a%6WmoVz&zY`{Ttd$1j9f`k8BmXf`9mr^KH7>Q>P=J@E)Xu zVhd6dQc`jL)IgxCoH)baG4OVPikvie>OF#6^(9J2It}?mE59nAxxTO>}!DS_7pqt0U>! z67gWQWQZGOyD=T3{i^dqn0~kH4l;nX23mLF5{(^T7&et*J42D96!wUR!Q{mY|4k$s zIUY%0LTgmUrOeFCzCV9BuG4g4d(0F@-gYj&+<9tqElza6`St;kKC0j_mgyvTQvfRy zVO#SB`(2A;~-*m0+gCOseGM%aEC%l^x&G(xIV zkED8sJ9SaVxhIX6v{^S_bKR*o_3ndq_k=@XtO7Q$bEB-$IyLjfP?0$hdDISijDl-Fa?N;n2VMW~D z&7qCxxbNEh*tXNm>}*z6b6nC%+wDQy+U@mh+YnW`k@q$uimSgIlScJKQ2OFAb+Z$d z=*{MB)9+T(+_DbitZQnRoS^0d`m^5(&|bYS_#pmIw?MM}I9}PhYQE_yStPXWj_sbp z7a0Apq&!-9$Kb*(J07J_@T2T|qKe9El*4eo2xPz4g5OPbpPap~+6dcpznev6TwR~u z98%vxaXbEg+pP$k40x0M`t=K9Ap-0^?CK-Dl}PV{#$%IfG9(+DIKV@ zxG&nM(y#%1HQc_Z9z(*Zz~pJNu#n*XK`AOVrPUX!8UNU~*0FSZy<}!#k^eie29dm? z`3Mu-n+G>n`^X4&+Tm!81i^df!c{R6<7euObA{>WyPX!^21}qlf=mK)c{_5BDDQm{|yNF!w+Im6h&;Q{0v-HpJo5IaD*3b@u+0*Q_88tEv9_KH$B5{6JIV?95O zZsc_e>W1r-@Qoh(w~uNRD1(iyc6_@3>Je6AyhX-_Y0W!){rR5J|3aE01eygFn2Icw$VEM9qS?}yCR{RZU6`Rzh0AMs0SDO4@+ABFDfwtDcA z1{#{kvKUG{(+*;tip|p0BqZ4(muO70)$kuEdT&*nTB*a{|0d&C=9oPar&xJfz@(LQ zzL9uwa_lLcoSNo3;CBDK)j4sd7!yy0PpJ&(Il9@ny9KCP-V3Ai=_fi**W+WnL%P?3 z$mC4D@g>~3Y@jLn;w4vkQTC1xx-hkv$}-jW7nxcAws;~ukZt$>mgkeD_8AN@)}!m(rRnm zXrv51Y)?vwT@GDbDFOl%$beniH^Fs$Y_s%mbChPZbfQSD>?LZj2@kbOx`3Y?ufM8* zgqCLa``WnA_%T8eLAmd&MVgdjTVgl$)dveyGJ7G~<=5us8;Nv@Y=pQ02GR(Y8&P+a z)$5=#A1Z8yx<_%HgIqPIFcL~iN`haw-?F9>ie8rRiHkOAM~l)@Qrsa}?5@W591+8x zt`=ofV5A3U#e&{Ky3ZQ5H=i10m6Y#bOET6!|(t2 z5ZmFnbf((1Vl*v8g@%S|e_ENRP-J?3q6bMP>~2CwZ*kXk2WZVm&>~ZR!6iKT6-= z)CfVbWQyxpUuOU@E^Gtf=Kw5Vvg(mE00>zWkutDD+?`-V>UpR(Hs_&DSH`->RdwUp z!v0^(xYbAXA}KpNPGH0H$12xyDk^Ycz%HD8i&T6Mq51l34n}&-6bmymC!Y;XQTc=l5UG3i&O${_Q(%s0v=kgpJaPUm` z9qdHnWm#r)S%_H*>Bx0EWK4YMz=QMbdQpnbPm?uJuPn&UYmGcaiVo;)O5Bds-9gmg zSURJ^e%Cw(+*#z{ncp*^99`v49EpgEURx|ZZ;Fy{L36-+PD8n+P{?U&E&Qzc6Y{+H zB65SrL=em(J2{NnEs9LY71NJN8TyK;K5Y)!R?rgZ^pQ5<7~XiQF1cqyX9Ak!*!pUH z4ZdXceD@jD%W~d@^XdjJ>9p=xXG5O-BZ}Y*uyl11JZ7}J&?}F z@axegkN64`E5s2|sig2#x1BEDEd=q|l6l-;9@Ac#h`0ZVQePwPWmkx`p-1YXMOpVY zJg2H;zmH%#+_DBEa}+JQkN(2!+uY%5IHyF(){(+ki^ocIlYwyMMt@-tsio?AE zcoszI+_^vA?$PgZWJ##tqSefzWJGsZ?V*m!s+A?a$*k5CjP64Q&>Nk>;!xZA=JDZ9 z$);Kvze$Zlh*XZfz`YEkSHYSJf>e>Ee3FZ_7vJdIv}q{HV3-7nFZ^ z{po`*NppYWu&HvDSRloMltF)8etWH(sObyV1c}^n-?`sJC?`W|TDXmEt8l!O;E>0} zJOGgQu9ywM7mUiwm#4c(NzYT?RmEXxHIr78_e1?ulk?T~>2H_kW#?`}7bibdP}`E8 zocjEJz9i0}ANbX%_x4|ATUO&dD8~SEdN)3Zz$GdgeYYf3|4HA!{dODVnZzM($Fs6p zH@fVYqFV8oo7({;^(s}sW1ShwzQ&d(q<9d+XOV#2f*?a1k#I;09@~9b=CJ7-cb2U; zE9J%MD-w>SFP=@@v33X#=&$UBs)P60|Ikk)iS5>oe7zlt|52cltHUNDydnCY5o)z@ zzS%9==H^tM;N_0XEu4Z*h+=wBN=AsskpR8OS{{+DXbFLR_Zpl#kOb~7_(eVi#s@Yc zZ-4_qc4S(~ZJ#Y9ob497i>H4AQGT?^&n=++SMF5hn&yv{7 zA`u$2CsWt#E^`WXRX?5_2;n9T1)B5BesvjY;RJAiUN#C$Kr8TSygN1BF8<1+mgH0Pk3R?+tHMS_*)uqE%4A4`4Ya#gBwmEYO zw=up+kIU(zATSU#w??%Tv9o7kQTNMo^h-cf6UWI(mYaNv9r?N=f1ZZ*l1JzsZh3bF zrvHm?HFNB2ug?Ok|mT6Kmxau#frKpZCt4sKq42f$#`bzMO z6Cum|yxnZOt9k+{-x~WvkAOiP@6Mzk&hC!t(OmyI4sDv;O4J*&hPTK7a~&++%J=cT zctZa^)O^gGJE9)c1e?)ju1`^-JY~#=H=n37hapMAK2`AkFh9vC=bnU^oV+!E!m(&;jls8TwEd^Fl`pQc=Xl4Gh|@v+3-$sG8Xidn#X7jWc2?EqJc@ z+Yeivj*7Dm!;vCblOyohuGR0YWI&Q~M(6Dz?(Oq01&{0xSEUikI>f}NujUy%QZ}rs zPT@L-_YLzG^^n&*Tm0u@`K%@`X9E0RU9z~XD{GrSy6-n57*jrX!3JC%^b#R``px3` z#rbhmp;GPp$Nu7$ykrh;wnQ&0>fDa=B4Nz!fkf6DXqHj>iaU!a$1l&%_4^!kC9fH} z{Qg&!FeS@&Em`n`_AjqvDrL8N+(!x$Ia;%VAHMs%w0T5wIWH6txEjz_%3}`22=s8M zMIxd_F6GWdP-=$|g&mcu1wtx7<>dz#Da-SW0xH^v>@c>Yen9gr?*FtKa|Jmj!1Ne2 zI?0dSz>={G2y`sl!3~d?tCtrApb$M!EL?=c*5p^YWN~|)dEaT{zp?F4wB8&I&Jo{J z1IkY=aETnrFOSLC5wce#nyUutk_aYb96m97R)Eg`bMDH`^%?IRT3w9S$k8OC>cNQr zsV+l@)+&05V#p3VN}YFUQdf)Px&B;ADbLf1=y_wJl_U(_JFI-D+gP(o zLY3boCi6Qh{$WHANc3|od;}G_*gNU%@6+72Pdh4Hvt70eNF46dTv3a@wGQCLa}mCt zgT&R3p6BHqw%_E+DTz4@+M6K4*I<_fYcaEr8EQF^!-o|7zRhg}{oqC@lL;TK5P3o& zQc)dM?``9R5~`Xef;$%^@`9Sz^8Oyvb0SNkgTI@Z$YOII8^?bE&wO+6>zGU%XQ$$} z)bY>!GkB#iU>rPjqkz#eU%hDUL;laDnf=GYRHM)D5@^1E#|HV}NZK>Wr%P76n5o0} zYG&tq$4v}bvsDWt!#5r@Oyu*1-4`TOY((NI`k?roLXtl<|Iae8LOBK;T~@rEHvIHd z(O9wG2SU+K^pS3ik)l_j+uIusD&fQu{{PKycCs*+`uSZuQ*tYgn zKi`taE;~Ta3EqFsuVNJPQ54upS#kCIozZ=SC~&B^)CHZk@C2gpw<3_rI)u5neB~JY zLG`2&MmYLSz=C0SFBJa~{Bo-*D}4c`1EVyAYtA>j<6~iA-CdY-y-a;|2Jt|v)_b0F zph~IF+f8r+!V3-Pki^!$Mqir@+xxoXvyWXSz~1C#Mk!_G3+DdV-V%Z=|6F;zFJHbu z1_k%CXBY@D`P1+|`PM`@^Zs;4OM&roW~MAJ8DRt|PbTrQB(w2j(awSk`B}N zz0iQs1>`(bN+Pk9R*<|B{=qKB? zY6~S9j?1TarD47X4rzPFq(}>eqW|#RHFKVrxg%Md)9nAG(qTrC52Md`+-j3LB6aS6 z)3h~rqTpT7?xqt0u=tm{wGK0i$^MFJMUF1K%m)!nG*F0MOY6MN6!q>Ss(mJO`h)VfOY^IbG zJ0)7pRLN0D#kP}ov+6jc#UCs^j*ZMxuP~nA4Yd*qE0-V^BEtoW-i^@c05N02`11}E z<|z_jdD@dDTusCMZ{8QC?!bO)MM74{U!2UZ^5Uy_DKTgH>nndP588J$|GWeK^A-6( z-4aC6mWjH1X(Y`08FMF5uzEpPz>?zN+{So4o)|bL&2%kZC#9dm&LC1D#~jx|CR%WW=;O%BP*L?WbOLOF}`@=^M zZUj4!OtI;W`l6^r!^Z81^>dnmTTpz)8ZVe~)2Dtn zef_#XNyXdEo`fS6>)duhvQ94$-c+?QLeRYuER&nL?bi*Gr5Xs2%TFJb|oy0@HO@^s(5VRxUI_QKfd?^0mf@27G0uWVc zfFJ{p4LdDS4Jz_iafT;^@nNK1-rJIS4_R!=O1p~3X;NNun#c!`d17E;h2Jf+%|@ILuP~g*o75n2l-BRv8Z5ai&f;ENECiUzfZT%g z3D_Oz$O?w4#DBv}|L()v#QQM()fkP$SJ9qCXYQxTzC=Zroci#Y?gUZ3FkJQm(X%Dv z12zpI?|(X4sxp7nVY}M{oBtgR%`7dUjUJz* zP>XsiF1107Da-@F3rtNS6dUy-O z23+Eh5doG9_;=RPzGI<{1;9oqUj_X#d4w z%J;-qhF7OC{>?&u?v9&h_gweyb9uSJGL3aoK}H6XZR*wgQq8SZ*D^b^(uQ8>rqk+& ze)>Ye^5pWqr1~?yo{qwaf<0ukdH;z`iSM|3c_iNtlmHPppewK_FT1xUv=3Vb^c*RY zB_cRGqQ9P_o6c-f`O~EliM;E|tOMdT)Y}ymF5^Ev&ORaMUq}DH764`2=0Tgfn?qZn zq)eZQ0dlGI1j(N%GXdhx@JT#H;SZ{F6a=Le&o)hxpM~lqQH5q8oRWKTM%n!_G2*fC}+ux8_wWHY;DH^1z_d;0PB>esxU`u_?=o-P^SpvSc< zBogBwv@{wK6r(E66+9UE$k^dkrJAR}ah3fc;-^eIni~nBjOOlWZ~UxD(9&|S^-Lh1 z1VJIp;Zwrjf5dZg$U4NtB{LX{XuD0_^DrJ4s`(z?AvCm~q>yG_ryKL~m)f_VcOTB$ z54dHyDrcf04fVV7lj=r_onL})>sW(IC1>WAtY4TSBkV|Ef?B)i(YKX>J>&esc1L-{ zz&WhouVGkK)?53(JMzV##+A(Q)T_SXg$IeMy;9e|olH8T;;sUgx=0@v??W#F znOq#mnzV1Ah^_7cmC$s>t0aR>ol+h?KIvyarJ}Tyk3Jd9{i&pX*`Eu>a~mfDa&J)y zl}zz83I!of9dDm9?Oa|SmqoW=;d<}CpWC_Q{!5nIGxqU8=13yO$JeO$I4xe+qYRa* ztgjCN9`)q>{2Ss+iBSe_W3eXlCmocIvE7c+gK{Y7?z^S|SqruWy}(kUfhtTU*H0#w z)|2{hk*4*Vqow7qbO2;DTm@$l5NQZ7VTLkucPC|-qnbn93srg>5cB?bY=`sprL*EN zg-lCP9u2OQ8rGMB0=V+6T-YBn-bWBj$5~rj+uHpT&^0Ko`&jZm>K<|zGvQ$6f4?iA zr*oa3uhrb;_M&_cp}wC%!x@E5H*pVX52^=?P-BI!L8ka`~ubb-|TCS6O5@P=~R6vx4h$cWB$L=h}KeuLWNnZg*5fz11Havs{ST#ls+Dj^ zrwj}g7Ah{Io~Gt~NTbIBJ~u*OOo0c(ic8a7A!|cJC=4-ot}hboiT!Zlhhjsf92R^+ zg&}37u=CzMNNQ%KiZpXR9Bz%%Th-}_e^FMKk(EVt!pqp)29cRKXk7sGRQ>#5`w?u) z>^m~KYE$aC==5{Pe}&+&ao>rN#`il`+mZ^gz{4>;W&$qgQ(agv>{tO3(L;ynTE6`R zgd@M>0Jcn54u-L(`Fzn6L_RZfbCL`X{l=}NKn+8Ig9a$z7BzGUG`a3~!m9$Q%`h9) zJLYe+{;LtadIAZOccUnP@CCIAqW`)?y8)z!;s|InvM8G}<)|Y;56A7u^T}Im5cok( zj(62;Y&7_Gc;s4nm!N3hyn#4C7V4p7F;pedEuN3ZR)+J{ii7X;_aW8B^zI_Q}Chh zfIv2_;)ms6@A~jt4RUnhQ;TSyS6w0=y{TXo&8U44?o5 z!(8g?kimOl8eL)Rdp6Xum#|>LZ4OdPdx}RFEz`S!$_2S^ zI&gDBzK@QYy?u)bbmyrDC2Y~ae04+nUu9(_4Z1%=dn|KwNZh!hiVF06*6L>Ava;bJ zA_R9K0*Vbw${MsH`B%wbLR6XL*ejz7VxiG*N=!U4x;wq=>v>`uL2MDF6zWwvHY^)b zbO3z3s^J#hxJ8y2%LJncc051n>g<4^hdxA=hfNLZu8xFajJS0X8PATb&wd?@oq z5`4)iDIFl>e*ACp)it5W#WFHX5C>i_yg4&R*P!$kUN;g7if#bs;4)V&(>CErvA?6& z=kIFcAhRX}U~#>&d+<>AXu*Ns!{e9b?dCkPug;P2-@L3oaRobS`5-UX?%^k6Oiq4@$AO`hH1RMzQtoP?c_x_t4;8AJi z{MAyO4+`Dg-QA0wmu+EaxKvpuPW0dyKS9lAis@p{uK&cXY^7y>6AGCJIBX}nFR9uK zSZEKIG4tCsMQ>60CDoEs84dKXvZuB>+lclEN=uHPX-<$L>g;d-2?FM=!=v8k;aS(~ zWlmn>G{G<_6;ae(8+#VDFUA|>e0=wJW`ht)Q|Xw@sn@d7iOk0AB5^q3!<&q)t49HCLQ9A^Vt%g)J5*Q&#`%@^^o2>=#9T9+>tqsw^72A1m;n8RV1hT1AHTtisk zyV=0mD|guzE|SQ4r@!wznm~8dEuQuqhH>AmXh()H#KYmuVegJIOeU;K+B zs+LU7J!)pL0dzIskliGnt&pEXw~+nbxa@9Z?B!{+M&E(Kpq8a$s$X1rkN&6?ZbWcA z;MT_0NdJo%Oi4*`osn4p)reioDG?}>O}@<)QRN9#^HJb@(=G2N$DW(r8^-XZO?>Ql zUtJVz4PY37vT^bh#obyNel@y!75^xmN*rH*XZQvnUPVuZ=oW&~cM@OEi4BSqv44$J zM~ekj7;S>WN^Z1>|M-l8H!ldqpe${SUs*|MC8_NnVAt7}4iLxi_j7URBbyTBNx;_vP42SVWs zw!~u;-N11HCXC@Ukoh|2u9f!mA;QliLyn~EajX9jh)4^}tMNH9G+{}(xSVc_0(F}S z5L0)TmizG+U(eyF_bzOBT*~#H@UlQ=GmwY`26)CQV)`vc!5zlFJ*IEg)QBQAln)YLP7A=ZS3sUc3<5Jf<6(*B$ROGm66cRg!taaO`*C7cu|M02J zOiaYN3cAq}m9ql686Q+Uu+|mzJY$3JgSjpo>Ke#r93(E~;=<`Se2`T57Vk~DXUOVV zbO$8dXBblYSNc=Mf*eD~NB*Ula6|MO2YEy!Pr^IJ%U1u%stRK#mj{nicp@}p^;2*n zEitE_%-W<*399Mi4e{f|-&1|{Hmg-Vn6(I{U_~`bb8Kl#HhVtyoluC%$kcPs^blgb zU~2750}cVr^49+f2ldL}$Sb6%zkpN--0M1T%}&DNDx>YUzuQnsQ=6H7+VC-G$?N>j z0b15Aud>bC{oex18tWVS65`P_zvLtOmz@JxH3Bqj&8M1`;$J0PM@!C@w{*V@HKpeWw5qn|xTl)QBOLtef<14I-oS z^FPrM2P2}lUB{k4J-%>Or#yW z4O2%)JS~Yj9N#o(cgK(Qre>W}7NSAGQL9&$mtgR=?V*Nef=uoqWoI-Cfu2(o;Cx+> zE_@`cTl>5rJD+X91}*G)Mx8+wXApJ{-28r7L8Q2#^lIg$1GXvNDqgSR1uamDtrOWC&{_W#PZHr%K+xb!yoy`TO~wek!@ zyoWd}H3#zzevBLn*y8lsW*k4&rQ7Vlv3-{jq6|a!e2eF|-^ZG)sBr^QWjE&Pc)R*Q zM?zx3qSvvKkjF{k?{frZIVkT8T-v|$ufq@pXVtWdq;B;A4nLMeKW(9^6{Gy;M5)5Hykm1%!FCC;v7V`Edb70O0&Z!v-?VomgBO|-JM76k_SJHZfO zsaZ~hUtb|CAFlNs{PhCfnpdqO;qgm|l?sIg460&Q!IY_^r}t2GtpB=yWf$r#;+yW0 z(%CpU>63=WyA^>OgsZ>}%za!UB2f@kO$vKjA9NRkKl|WdMY56Rp|SVbo-X2PP+dli zflYOCm|>G?MQFTd42n>7Dh(EgaD=>=Aw>N6-WW0ptc|hNQ(4FX7I}PUKBHMSX8JWOi`Ns&>7G)&J-5^yW=~yz?r}h{AA|Se+qEOXucBV zcI2a!)_9%T(9M0RD%aS~dbw-zlO%>C-vXar9#vZb(U8AV9otD46BEk`j{8Q*BU21A zga793B-FHMDy)Q$jc;irhVjzOl)IH2imNg-L|+6+`HPiAvZ8K)ANj@Km}5GpoPU*} zF*BEq`8Z(h7XQJ|g!TweH&lVCI_%GW_R?bX#wp*4o~Qoj^(~2&j!oblvZ@`)yK*%O z6G~<(BeFqw@0jGxkxabaKH~qnX+il-?Rt~C=Cjogjsg@Q+RCl%lgMVI7vkaZ&(CKB z2LTE8JqW+8+p(5r$Y9N`LX+c`mR1Nh2vf1G(=i^~t@_r621c#lr@qEFG5msP_qbLa zP28OcKTrhUVdnvaSmv|Ntne-bhq5_O-LQKVZFr$ll@UrT^KW;=hO`w6E31&5oT2M` z2n({IflF`e=xDS5G1Q%hPfKl_x1P7Sid>&)+<|{hO-&%Z{;Ah{EHr6jN&M=N#)MtP z5mCN0U#eNWD&{J$AC>Q+s+?PUx4Juk=CB7#(LKPN!Vg8MD~{XyeCm;|_hy~HL-{Rk zo{=rSkoytCpT(9JXaNJ}IROD{0$%%`O96nSae5zO!GA=7!wD#xEL}|2l&wn*zMZ3~ zy}0+9OVi5v6?i9%`BPaC7$)3THMTD=JyM&J*~R0PaoT2YJKU5e4o@qq{5kawJ46lO4S5F!RD359@<+ z0X}p!!GI>RbSpcTD*QCoU~`ok{S%5B0wNxpJ))dHx!flke(|$%s`K9Q6RV$JdCA;u zo|RVG&Txl)vbY+EI{5Jq5vT3%Cb8k%c~H6C4B3lBzLMV0A9gLDdTzD`posf-D-ekx zF!OG(vT z8xITz$a`VXl8gNaTh7Wx(yQL*`^^Epy)t(hT^A#+tpVQ_J;E6~F1W~1GUF2*>t-!$zD`mY}Dkil_>W^|M(7TVNH zu~Bjm81tk^K`8$V$FRI0> z7R~CdTllg6QIf4_ME24|boyKqD^qeyBn4U8eS1xTPfs>99oCw)3?s&;kQ;@PiQRj* z-&YN?7*4aMbqAad*D0O6JU4TQ7%J-vdP!geMeZsjOc>-(EVgP=UP*K(eU1wd!>E!Gp>KS2%Z*g-TWf@#qDH@=Sn@_r!3>g z)-?X#fBv1{2{LxAWH_3`zWn4NN}~*UIZ5YnIcHU^Y5LkUA{|u-J>G(pKeepex}eU^ zca>CXa_F!9cdJ@Ct-0}WM9^x(Pz^657RWSHI;nVO*THtKo%uR81`{+7w0q zZ)wOXA35I82nnEM96YzCr12o5wv)#Q{$E}LQ=A&&xMOF6s2F+{J16IpN~%biJ0Dw4 zVW&Fy#t=WVCPj}F1TPhqtF{res8qjWKH#^7oLp9$#dJv}|y2qL^6 z`4j0$D!-0-(FnRY5Err1oLwB6{ey_i?u8~-Xms_(75#_jb3N@72~@-Xk(JOP2G~T` zdH#!-_=DFO?m>aQpGwq5!=Ru@ABoO=w!Nk>L?H&fQl15Gg8)%FW?WiG=*?0HQX=t~ z-f@w|IAMkLfb30Uy{*(U8ROf+d8#sziQ~b6|A5yqXmAV+>G4T~-r@SIKvPG?s?JzRmc0Cq<=&nD z$l%X|sM6e$T=Ku2w5*DjydIzJe|@Ks7_zSX^V|4%oLDuUmp}zUDN*73^CtU=>4>q{ z`-yvx*jSCLlJ5l-yL7T+^>i5ajYMK7q+;*gSloRM~Z zrfOQSVA;2$F89RW)Y=+Lfhhn$b~(U&audDq`(hQD#;2x&KnDfCQmu%mqALHWh%9_F z_V7}-EGD0PQr(3tO>D$3mES>k9b1{;*elRVdb>Azvo{INf%vf}d9kS-#>W22B_~!5 z0!nHZVG_DdlE;*Z8>aG}B9*OalbkMFO^RlKYliBp;`DwN9nyZB_**e}qZ5%be43eL?F* z-B2M4%s+BwmFeQ2e7K9%z1HLMh`=rp#3-%tiM zuSjF<#g+crpzu+BOX}CX>%@7~38yn@KDfE{-Me=-zYo_o35kUFyH;DcwH#TvJ3d)l zYcmIRilZ70d6Me5Zn{2@Cmdtf>P*+`dRiRI%0yzZ%oCsS{_dQ_52#DbfqS^Jz8U3J z3GQ|}C4oBXy(ta+H@uHN<2B*Sc8McnhPxB$;BI!Zc}dzdPhP!g_wp7UwW5xjWvKbG zi)ezWk?nbC+#*rbzBolCh)JpQ`IZ0GSmcaLgx~3hK9Sf{dAI+BbOd$$YX(9M_o~;` z8x%x{dh!JBsjUoVAYvD-e!}Z;yI-{uorc>u2x%F@BUT z?!9W(Z`Rfxv?u$)>rv>Nc9QH?A9zN^dcaUcJ zb#JlRy+&&B;JAIL2;?Q;v6XQ_D2!u~9%CQWJS?5Ejt}S~pDP^o;PH(|zDYSTf~LRN z0rS~)Wp*=k1QI|~jZoXEAbcC=}eL`VyXM5X(@mKCR^UaCMEdkKDnO;X2KS=&^f9gqw z%HB=06_Wyruj_2)jwO>5LL`MB5@uMy z7GGWcHx2!P;Ot&LBzU|K>L~MqInK2E>7ihooz;H0rvXa!#ujNbQl}6XahbttTb((J z=)IN$9<`|LfudZYhz+*moXO7;o$w7oOIhfu1A(*tGnIa|EGcX3b&Qo3bG<|kQ^Qz> z&`F(T{0^3Q4CX(=Ig*SiJ)?dZNcGR2`#n*nm&m-%>@A%Dg6PQ%qzyWF%M-R=T3B4(ce!e*>C#1nt(ZwF~Ld)S~fU%t!*RdN@u=*Jv_wE+v=UchKFt}koquMWKB6@{*q zXqf{Z-811LF}|!G2?wj6C2#R1Wlz>|#Nz^$sO6F0&sm>+sq15jmVYrj84Eerm_Szo zVZ_eP{`ox(nabbMzs+@yk$ol}VWLaSH?OR*38ua6?R`IgCL3N?HdV|u;Jy(ix6t)Y zAm#@m5tR8bjTJ|@dC*`mc$=P(h}H56HY($TAuE{=ncF++@&DHXxFNAho!2H#3X(;> zrSjK9qh`O8KodT4Za|hAYV17^USf7yFy}D=+Bhs{dGh6}o;x&zE@_DS1=lcNra0RO zEiUiHjM=3=%3(bAmP?b?vS7M$jgLkI`z_n}+w-Myw}XP|kRvt<4sA9{FjLITBrBl5 zDI*ml-%=m(C3&G&J}xw7u*F@C(0<-_`vJU-uj&@JW<8XKYNUPxRYO8TB4%O1=)LLc zjRvj)-2qp(p?dA5xE29kT!m-F|7S~blCXswhrZi zsCICdAAr_u?CjtNS%IXVtv`P(DK_s)dTkd>2js$XD(Pg!s%{V+eg}1#d`X)~gLMj_ z2eX`zkdT!VMh--%#`wg5asU4PnS}*uef`w1U!T6wP%`!n_RvzJZN2S@3!kD{^dB01 z%E@`LbS#6B5qtLL$n;{@gO*K?R`i52b-1_GQFFLvo>q6HGAAKo=v%Hi_bpW&0Z|JV znVK$*3ik))2Bs4nJ$-#G8JZi)Lo?#C*9fW!i=DPsQQRF)eP3ulT==LyyHV!Wbb3wx zO@do_ZuVw@F)vbB^bOHFgv@x3>JMYF+fw}jtMqdLcb zhGCW<6aIdrX>5pMM{2%Y1pyQy$L=Z~)9pk@RHs0nw`szXOcK3nZ zo^;Zl*xpUS*47quu76ZG{B<5|6!HeFFdRnBAs~Z-09VtuZ;KgD>T+|DJ+Geq{LdQl zQNNJpNC>T418Vg1XQee{y%f4mmP}!1-ileXmYCbC3NTyOB{E>Z`5~dE7M-H{!VPM4 z&_)5YS7^?$AM<7ZI0#=DxlDV_fn>Nv?ls$4f)5d=M&XiXLyanPVd?ruyV0~~8m3Z8 z3=g@y0kZdY2F4M}<$w_saNZ%1$i{Ju4EgetdO<^G2Y6@-j%(BV|UH&_RP)!x+=6Vti=p@rS}nX8Yao; z*-2VojayZPQQ`i)2<+D1A&~B0)}q?$?5We>Uv6jwB(wi>{QDl0_w+9|kMHkjAcXdBG45G^;=@{MgsKuD+?bf6IB z$=4yE`dRbE@aAzs{Zyg55Y@jvpMPlg(9nR2)NC#$uml>ZPYB<%&G*sq6_6TA`FRIx z50+|(LULDud_ji}oSur;JfvF6NNs3uMp+bMF7FJ9#>Qejt>T`UVm@>+zAy-1XML!v zuI`*N;3czIVOYAoIX?sm?vqcWPdW}f#dt+Rczj=4p86iBIVudXjs%Eij=qddr6D78 z+fQ=)^h0nnv*%U8sirbc0`hT{4mN-4eb8ilYqW2`Bls+7L}VQ)K2%A^zv!Dy{M9K< zO1td5BNNNqCfi!fK@<>eAck^ta{MP1X;kxi>Nv>!j>sSP%O_^t2Xlfy{G)0sh^Dv*B|)kCC2BLPI;Ly zvR97uMQUuQ>-Pp32m}khq>T6XmwJy>E=b(zX_Bzkf8*U}ovF zioWnZ4SWHgL!pONDEv?P)e;u{%`WlRad1rbsk-xihT*8tEB}YhRuD0z`3zM((PF;d z0Xdpl)Y4tnDgAtrgOfA2sfpau`aYGikal2U$iA0@JBDSAE^7aKPtW2UanpSLmxh!_ ze<^G%ANTG@B=u;-GH?^|aN9Jb#VYc46R-e&r#Xlv94$h;@0`Yzf$BwFCo~OR?1V^V zn++%#-3c1>Yb=CO1U_a^09i3u{eAV>{(M6KtlxP*wquhG*!`p2IQ_Yx`ND zKk3e|qqO2_U>&{aEFTM5q#?jTP+s9}^cA7%5lVLe&q^{$bNK1@&hYMQIzjGEQCnSd z`YW!j?ZW5g(}tfr4W25ZZ0jKwl!K#WdS9~KJty3R%2{V`cz=UC!qh*nwKd}%_TaxS zD28P-Z{9*m3pBZpp@gjdy4Zi)occLqa&Zv{Ko>9o!>rdETFQ*MD_Zt)QIEya=XH(l zq@ep@53yDtCWE{ws%EPKe&GF6e7A?Lt&NR?f0h;(qYOBL;je~;VJ4j7GGpFMO=$zO z56Ev3GvVKB&z+wv+AU{=d@mw>(T7)7R%q`MXFwvgdMPB1Llpkwo3>&P(# zEtH|4w$sG-(F&>Fu9Q&ac1q4>(4PwD{x^YHA;#ANL4*i1^Yc=&vcbgyBui+*x@^@G zTLX?|?*qtgGyd-8pv9cAxTDuikwvP#P~$8xh>`dKKNhgHTo&Qy?>y21;UT`qQ| zB;WETEa7`4P-H;(bMjQ{qS$N3kiA!nTAPY)S{s|)>Wx)L?=Kno=7#)<99Dj*TO39S zt9Q22Gk7xIqPY4~K@!>R^(~K>9y|8WiB^0&LL84SiCb%+4C zOnXa~Gcn=UeFXg%dQ+StLJD>Zlm&Uv!7UrdFRby%2 zyObLQ)xh98km|=9klX@2nlSm9Or=e3-*44{C6A6M{4QJ$Fbw#BKdJm_DmiF~i%qcUm=1TY%;?glKYzm)9nljrZO137pe` z)#@Q`?a&X;SkDaYT2IT5&9ct3!8EQ}>}4<$=T;sPTK@CmoO#e-hu+UwVei+Hvw#6x zgp_gm6d9*%H}}D=@%uCG%aZDT6)(T}pYLjIld%T?1dBNdIxPNwb2|;CJY=f49ul$^tFjvZ$I~&l z-lOmq)$mbcWtx$t_IuOB@fS!+`}wplcuI#KcK+ca`+qcjWmr~e*EWcN0#cGnONTUy zq?B}bOP3&sbSu)*DbgSk5`u!#ozfvH-6364-`exM-yHL6<`8c0y{~Jnb*?jT94!{S z+39TBjlG@qz;h09Sv!Licly_3W`(n;b#umwtMd@*ES&rrNFZ-v(72K^9PKtBK z(zUAJawBtbLtg!fz&l*xW++R?7kKn(NI_)?Q+56sn*6|{(%*Np$i7G5R1J zM-EJQ{8NEGLsR!UuGVfo;V4&b$?$ss6cb(c0x!Y3YFUNZ-QC4`R5~gv z7>VK7;V7=^y*e-hD%)X%xw7Hgg`J*0)@Y3ha^Mb=QA9<^X| zQuMaV$YbK+pZZbrivoDbcSozPx=M$YjSV$GFN$I9CY}$BJaAQT^YOh#_V)|Bvw$8j zY`pS!M|>H;3eE3)fqDTp(WYUkarFOfhL8;xq_7}_bd+%MT4K_CW^nH{FS$HUvK*`P7N&BG&d#PyQUFu-+5OYOpFaWW4_sQZOk$Vcr^Lai0J9AE z>vHM$D>MA7I*yZu60EMa8sZ5s$QGWj@7)+w#xYrq~!+iSyQbBSkv5D~*%A zUxj!4G5Iqu-i4csG`NRG@7?!l@C~qOz1inzN%qX#-vu}K4RhMvG<;q;8@z*izeb~A zEOHRI9&?1Q7DG|^Y@^wWJ<#ogRy=F;itY?V#hCsfdO+K#+Y}a#TH;GMZV?nFZN6%| zF=Qb(lxt1D!ye>C&=+C20X*g%tPXW-8=ju7JYFg=aKjr8Xb|2ztbK26Pc18{Dy66b1Yp+MP`PlgZvKG$8)_-ywW=` z^RlK{sV{p(x{Rh3zZ^9aB7gPa=PShmT?*O7x(~}m#gc%S{PiLq;T=hvV0j%Z%%D}k zswkFW=6nBZXM4H0h@iB0B;pY=2yG6S$!fB;m*0wJIbGQ!{vK_YGk>d4WKX{)l<86S z>3FNWnahW9_tSyMO7_MclLY#k)z#G?ppGOC%oG>jA{16W&$MBgV|s;4mN^gtHTJis zk9GC$2jaF8anq=hA$s24LI^rGwk=(Z$5{g##cjKi(o%$w35^`EwUM|09OTY!yxeG9 z*O#yA5H}wUcV1jDXb*lYA2VKG#jb%OFF^p2eMK%LBKyPn3TawA?Vd{<0SErqNPS#b zoQ&3CGz5_eXk0YqKIA#?VQ#RM)wK{(OFhR9s9@N^S{Mo11JD9C@B)}ncaY#w`DHhM z|3;~kuup7u=ekw@TCu5KH8&aRE~Nprt94G?*H;9#Yzp$i%DMbf83Y7%DALm}(gtk! z!jF#JATvn-k&kp7-^$9nK`7F>vQJADy|6x3e6qyp|MA)d@Y7h(K>&adS0RQt0*;WP zl2WsSz{2Il+0JQ3IjB=b;hfRliOK<3=xFN~pcqZS?^@{E-rSS|$A-yCGEjw8G&JCX zxEUHqI81y30`riVX1&*A%7rYW>g(%~pAVom;yws>FBDF&XUY2b5kVq$yy}rq5cpcy zIv$&&hi61UKMF;ac!#d|R@6I8WoYt_h4-4|(GpzeEVZ!PGPwHH{Yu0)CHhn09G9lK<`K7uoH zDHuop)Wd@e>|{)dpSN>oi1}w|<&n(X<8F5F+s#~kt5n?N1qh}CPsqtMtzWEDN9k)+ z%r6*<1yQVT4@rwO3O{~&{Nt~TcNVpV5|i2uLsN>4#KV4Bp?cZ;VH9%A@$a#&a=oiXYw!N=mhEo4Q6!(+STeAGF3smc~ThtQc zx>3DUcR{QKi;7}1ley!lc6IEg>(X+`btZmF? zohN^s|KJlh6b`zvV`P3M#``<1^Yn44u<)$h-`~!4PUrO&dRB5*{QUf^eX@|=%HH_o z?MPQ82r2oGvnIPXdP8s`y5Eml=ykxuD=IE_e*PRKxi|kK^G+l8(cxje{Clsp{N(3X zm%cTB9MeI%51D#`epko-)DN7dN2An)KlR3t(hE;;I*nyZN?t#$+aWHUUTU#fCHD!s zJ~QEBK3J*0f1%76e=>dC5CT!^+9{wgXx%vEnd^#vFOWD*c7i5VCA+(?=2)@AnS6zd zmwxIe7uPobb*&x-=0Es1uGIr88n!#cXcx0)Pi(n; z-kTh~5jk>}{j&Yl<4Y%JWDBq@Rbu1tF@+)9#!#nt5HJjcQR zxomt8ORV&4|AQF|`IwP4 zsfQG>S!#oV$;!$K3c041p39TyD>C>h5g~@({=1o3m>FAuk6H2kdjxPTVD&XRF#-CK zoa}5=r-oC;U%B86Gxt1&VRvcY6C7E{sr^o9p;V_@zkclv7$lp+(({KYOEUJ+8^KPp zac#>g5uP6?YVtNLM)4=NhjW9s7c_hh98sSc@3d; zYZ!!2c)n7rwJ@B%k+%{n67DL_mK=UnpF|+*6q!RS9!IaKt<9tGo=kN4KhZMsQ9r+TQ5x{zPtQnd8}HiE6HoI z#WQ7|QS(hP?1jCn@nSIvx`-V&pDk*d)>B0EIM<9n5O^?{V%w&?giF}p?*9I5{?C`! zb`m?}H>o#U9lw|>u;@>}=TOcoWg%KV)(Y=z?d~L_!lfhU)hUl-v!~jmFSwe`gF=3+CvPMo=X{((y_4$Ws2)r2yg8auk;FgZpy!ICf z46nsD=|AdLEdm7)c*l(C%1j0p(4HbrK9dxnJLEyhd*WT-9HiU+bJHjY02Lug;zVJ)y(g@$oUx36We5NYv2P(?g~< zkVf;F=Y71Y6Iv^j?&r;<_^?}XEKJ7vfO_!%y7_#?Z&wo!L*-VmZIIOvO~ zjuSAXEV&56*6YvZh?57Y81eSdXQ{z@8{Cic_ZhUqqn7JSOK*W-0;&#ll8+4x?t&Np z5FnXg-~&o+S9kY?*;y0>PXE0I3<_{$Yp}}zI+?NO67e~(uVsLF0v#<3S?~l@Znr{&vGPdM{zeoan44(^KDkcKbGN2x4_qUCmEHMP=sXga^zWuq-R2S(c(@*HXTek%d9z?z zKiX&^{to)}j_4c{da6C`T)e#`QW<-OqC57p$zJ7Oh-KpIV~2Q`kN0DW=;=Sp67SY zq9`mXvbq45y&aD)2`wVZL+7{l41vSj z$NT7c@oV>@KGbO$6gRz_Zct5Ns+E=c(llbh7TzL3WGf~b^&y>$h=s52_eYp0b`v5d zbZt!+Rq^TlM8jlIm@{n^KoA>PaP| zuHViQm>7A{tH&wzOgeu1#61t32ohWeuCJCei~#GbFfd`7SG z_%u&aM38a$D1lc#^plC-R*d>5QhSabv5GRUH}Sx-fwT8tAF#Puf|amuFLk|zkBa*s zHo0A&CKgw-$hDBk{!l{GBdf%^dOXc(_n0naLfvomMJe}=sd4XyVo$7b)HROz*AS6Q z@=fB!lY^QBT@{zNI3jJ^oYN885f3|x4oKkO#k6R2DgEh~P;_><0xk?-<}j6TmpAyT zMorx25B>7K*_FNX;kc1E3l4c4nN6W&AN`zEF{a-4z9z4}sjm4kNh@*=D$ay1dAZoT zLoFFm+r-65%K2*bs!?9wvAs70^Ges4MuQ(kvI|dmF;@rmgxm2g))y)XsdAybGGfZ6 zKN@n0P5WW$`9av!`GW)B{P)&AVJ8{6=&iY?NY~!%TRqoZ2qv-!$!c zGsVgRTksYPFtE&GRS+n(uE6WGJ$LuiyKeLOJLSqb@wS3*-;xVMaFCQkr>-_ilMUbe zubE2$M8bm@I>Y=kM7w_T(B&^igZcbZaN^dY#i}%nk%TF87!QADAZ1>;4|=g+rc z8F3%=`VubLx(40U8dgI2dNahWM_jw%bAog_6}R5kTj%B-Nt}BDQmr zo|BMj3vRGwGG9kYzHbx+I3?)w1EAsn7Lg5~AMyPJYfW98U1w5;nJ4QbI$?(xRlFJ1 zq9gWj2w_MHmB~%}%bcal9f!rf8mQGUHa?!y*qGTKxR1%Jntld$R!XXV>1Q*rG}-k? zx81A57jj%^ROuN2hl7f5-@<)F%X;pR8qmdx3sXILNTD5E19KWMB`YRHj8!4kvUSO& zqNn8iZ1?PffnnlQw8M-Wi~?NU++fl`U=|xbo)}D&kdP1vSqBF-u&-_EfA>J^xboMQ zV)wz>Mfp#M!oot+@m(o8)bD?O)EOj<%6(D*N&)Nzfl3JX9jSP1!#dD$Y9L!1G1^AF zT);9Ekub52I)dH;xXl579H035a;x>3a?JvGPy>ZEDJe-+ORL??|3g8+WZJGTc~6sp zoV1|KoJ?Y3V#zm_D7iTLs_N=yyXs$580Y_=3&4|~iif?pMB#L6;&XX2Z$KyshqDsg znPwo`gcqvD|LRf$?Wu@fiF;Or^~gxjsSEeM@E`}NM%f3$-OPwErvOpzAP=iy-UA7* zs*aT2C7`fCu4XiFm)CxviX=-sl^USxR){mV2pu%L!3%WJO?i64LV2fVa{+PX67kwA z?r-KJT@Cwy=rc)krbvixpW*N7_J#JFQG9MgZOtMqzk&@ejePe|yN6pf_J(qo2iMM4B6f;Tn# zLPvg#gcjt4nqf!VQMJ~Yb{zDv8-DVFv|%$3`p}*pdEvS%d=%Bx>6W1FYcdwt9lsx^ zzn#_!RQ&oY7@Cw%_r-FCIHYnnx>k#tJVL&i6P&L%tdZ+G-XGj+7|mX8Itq5+Hd5T-&HZKM1{ zakn~c>vrRHs@gZsuTE9}ESR!q$tIZbr0VVpmCl^_m}sx(g)|%tEBvQHgJ;iurvNTd zL*Na90@re({jg-}z?8e8d&N7hP{Q;}em**w*D0FX>d7;A#FDb>OBhgW0;H2NrlGLE z!oiaBJdyt9%)jxkAdGnp_qvuY8b>5_V!)atKITE`m(Ka{duLzot^Ip{JXdP7;n~t` zi#btNy}&C6ppsDg?4UwB?)bYV5Jac5I*tE`--LwhjvF{7mePEj@OV&oQuo1Dzv&FX z%uf06>rFi4sL$MqO!x&rI}63>$+S?aVo^i9EWIX5@-&lW$i9*a%j_>8P8p~qh!-YO z7&$82nhgGfJyr)?8coal%y{S(`#Tbe3Aj`TvB4=4*;42hP!XZ0E%HQKgGia&o;!+l zrJ!Gedl9y0no*vnrYP{;z$J3>XXe7F!%ixF``iN-4rqEw2x-6KGJebp%yMBP4W|mp z;Q;c~`uh6d)Koa=gqk-FTWt6ceknj|AbQl*)iv!Q2yTu!cYR3Vv7Bm+(6!vYlmD@W zAr`q=N#0g~$f$898ax5$$Z#rkP1Dd=xjJ-mbB{OOz9VKwdPzU^^J~?Jf_D$p<5>Dx zDu8nno>P}4xPo`Lexr^-S3y}VMIZ2&ogFTXMO%uTdD?GNhd?#)R`Xlet8VAs!SvPA z(vs^F_7~&O>zmQhR6HqIS{uYNB5LKdRoZQOuk-dq)aJb}9rhGRr$CJeOhV1=$4(9H zFnEHz>Eol%r@USOPJu+L?+)wR*a6geF{a*coQ=2orXM@53kVmxXV;ziBj*<$MvJ#N z4_*m#6Q;NHRL93C%26${@_1RAl=RO0S6upO^|BKW2WQ59H2tHTaiYEV^`5~q>G3~r zHCdxBty1-TSg7i~vcHl2GyAQ{5Ge0?^GzKpA-${6chz{F+<~EppKaHtc#Nya-kIvo zgxn_lm+t$V6<5~k=Gn4uU!HY^74CxDxg{IT4qf2wL^*$JCtMgamvSjpT{iVAV$%%D?a?t_tYT3!OKB}MYi+|f+vc57 zR8AH-_(?{`1a()j%BlvBnf)>`w=^|F18RR7-ZF?nMx?Y34XmGIE#~J9diwgTg1=5h z`Z7r&HW94oEM4B>o#md1-ddt<)IJrp3ob`#_hR!gBJ`W?t)80F2M#$gdX7zsB0ZtB zxF68Ug!lV+|BFZX`m4X>F`P%>a9Hta>%U8M%(G@8D7|s+6u^`e1LQ(8bMst!Q7x6M zu=|oC&C;a>1#i@-L`!#&G+)1eBbhm1>IwOG@RCtGQq17gQ+psHt&pyP=%T2W{v;x_Zeh^IBt2F z+NK8>8f|aoy2w6OMGmtA=U)2uC|G`zJ@-9bN_GYplk*X=i`yD$q4y}6S#=U-r(jP2 zS{cOC8crdwxqt@H1f|^>u(dH>o8RF%rha}6DJMskMwn(jGyz(AdSL+N3QQx)8Nx8G zw;t*?Cs^-^azW=n&VO%-65464{6FByiGVKww^3v$zrcb75MvnRCF1C{?qm7O4!?Ac z+J?CvT}iV_S_M05cV`D5c3uoEdvA!1f9!5+CbZY#EH-=8?iU!=JwkoT5zvSBltWLE zidJ99Yg~|OHHnQi?gr?7)@^t416$d;XVYBP-WX4 zd6Z{x7$GYVc1&FsJPdtL^;d-YpJ;(5DB0`?mtrI{Yx%Rkxv8&`Ae_W=tCysio4qmX zY1~voQt?lz!=$i2BrtSbUwEO*9rUxVJNG-H_T{oFbW2|E#eDEs zx|M2XjKl9|V(VFZde~o93)U;eW8wd!?^~s3y*%Vg2syu_LnKY?R}}IBD_BA=x-O&B zIF23wbvSR#Ux}mxoh>XD$Ka13ZY@CdgB>&=gzN;0IT+at9tQ!RlE%_VJ>ca|RV;YD zr%Gg_f4loT(W&({J9~(IdYTZ@N!$QEs)UgdC9>%TF>PdYG^lP9o~yvGWBx4A6_BU&%%-tDPXukF#}NRIoMdk zHSAMF3+@fWw~>)t?cg*$Uv{}(rYm|g@Bnb{FDfU8umzL1U~SA;ZCb?Jaap<9=qBZs z>GD*7ZjgBCwXqSlR|eJKQf4tJRvxicZgSg4cdNaL=xh5q*%2l$&R@8@xgi)6j4SY} z^f&D7_ea0C9w*>9IQZ1gJ$#n0k3obX+xUSCRW6R~8Oxste~c@tlU*S7H?m^?_M!BC zFe9~eBBX1KZ4T$pXB*#%qb;^*yX7KWrftEt$rx{ciakz9?)Ah3_XDx${3Xl2eoj+2 zM_dd^bShz=(EL`*J|R;4c9NuhwnAs!9gj2ab;?6sMNWypYfCh@EXATM?yD_wa-4c?(|i6?ezJasM|YlwVBDt zTVFHV^jEBWxCIx)mar93OQ6d6ztTs*VY*t8w-Zs&MnGXjo@^#edF%C zyODb_X|m&w=M>Gj@9!z@KJ_|JBb*T_Yg^g(gzpFk7k3_T0mZpoZ=b~Hy4U7?+Mm^T zOqAo_-R2%Pvle{#(3B|Dg5iVAg#gB@W*rDN3WGt_;Qk}U5 zRD`LIA(H{JQ3N|wTdv;nwYZ3Dv!!CHY6KZI`cZ(|IFPOt~PVcIJv-y$1cw~qjIYQQEy|Xai%%zsGm!u*;OZ4aR+?fAeKYXu6{2c@D zR>`vmIE}vLg$t6dJR*t6E-1hl5ILqm(9CX&^7{Jz23{b5K_npxFkoOdFDx!L7k~dx zq3*c-m7?0kX)~T*lMR7f%)f>Mj~&ytEw@~drh%)CbMx1)Ul*49-vN44q5{hsP|w2z z3`_{<_E>e8qGD0HL9^xzg7V+r-SNQVo?Vk6R(2MaC`f`6gi3%Zh?C*k`M}MQYeph5%o$AcKMR3{ zv&FPtOocyw7Y(J~kd4(v8slAVQP!Tey&qL|N8u6!{($rDqY4@jH+?KR=&Ae`S6w)} z>zlBYlYGOYl92_+>UeJD;R2u8#UKCRxqnwpCxK|u`vN|WVu67LGNzW-C>xX~H>F#y zVU3^!0Nwd48c)^9o%Wd=uWEf9a}Q@Y?*R3(ZhCE5PsrhW@O{xV^S7o}&ehP042=^; zHEndHu7ByrF6>8`yOm^FbvniMK%?zWMjDpl1Kj5A!j9h!=zl6~$H*Dv2*)Qf>0QGg zKC^iknplmG{rKa@k53cc06OfbC&L&I&gp6uqUp9w{y=I6$?M;D~G>s$}qugmkU9`zr$=i6MaZ&i~lm{{!pN zxz;mTK@PZ^o3>v_^#TEY^jQ7(2YSp>gw8BAgpRibgNeUk=?}~_Zf7C?GfR@z_tBT zRSk_+vTWHTLfM?tx!&(1^@U{@7Z-}40*GMl1p6o?uK|*VD+X*XVxLM2Utbf|&r1JS z_>yWjOIopHl(%E&c+e$(UtE*Z=hapHBs3=vJ6zt}um2qTcOa9)t70pTzQX5@NNbzg z%6BSs2C*k*CTqv8R(r0EKGZkUW7YfaGOhagd?I0SrfbUHH%YRzm^n3RA85=Ys%tcf zD9W}^G5#f?K^G~WMcN^MkBw7h_JuE95NzUswb#bp{+lGWF`biDGh4ICb5*L1u=(cx z&9($Gv?aDMVqI2_E^4BgGuu`c#ZIg8&$Vd&IuERttzy|0pXd0aL|{h%^?GQ|w(V6< z0o}eld%J`VN@2jKac{@tui%Z$UF^nAq7j^B!9$)d`VtF|T1;C_PMwVii-9O!Gn+TQ zyGj3EqAJy%y^PPweA?^;(RS+m1QGYupgv=&wuZ(lz%wW)C<<}js=ROvHx_l~h&awE z7mCx#^9Vf=cQ_}PB?^TGX_wRd>{O5kS+(E64N2WFOtM@y8%Fz9w;?Ay*xp}48blX_ z3K?NQ+0}9hV@_$iIU3Hi!vEr5I=iILUi`R3!N85k#>;;jX>wWfWZkUo-w(U;+1~~Z z$WJ^nt>W2Vn??a1RT#wP4X+n+=H!23afGk~_=9E=WN69DfR>|3xgSyt|_c4E;9_{HyG`qITdBr&OF@9o_ANQe61grp{+ILOYl607dtt&0mXlzSHdUPsB?EkVw>rkC?=hGG9CI zIL`qkY;tO9Sdj-U;|49EYaD%|rql148S78I3(RH^ZUi?ti?zbA2y2Fqk1S3^<9Q@1qa<{}ym1#C=YYn70;H6HF+0mW%}Bw5MfRa4 z@L`)gfmA4<{+X|3qooiwdE|Dh(cr0upxM3GSu(2twi3CS&9l%6>Ef!4v44e=FGaF? z4XWE^8gF+N@;_PXfZ)id6}tG*onV-y&_UDDA;z(WvYkj$wr`!mOxkWeSTB{tAxQHdF%T8!cre|be z*`0|J^QGYBX)h{GuEpT5!HE1K2G=`66&0VG8zfEZjEh3}IccZgi;uYwf0pl@ch-F- za8maSxqSd<+5E%Ag)OxC=hZ`9ugIb*fz}&k;ysl((E|}{spN@T@0_6M00YIw&Y|VJ zMdBvgEfz))T)$NQzzEobRog)H-EsD1hTXHb!d?K8Du2)jCTDS4sZl!ETPu}p;GF-b zLQnX_j9?chC%i**HZ%jw(oG>9)xY}dS5j)<1A~Thc6QdPE@=Sut2Nqn=8^XVE^%RT&rz$cs($w9Z6wVBiA_=Qu zVCNty&VZQB&&~z}-s9L{aT@!#ZIdvVET3OqQPEs-Z|SeUAs4PN!Mgsj5LP5C*K&)C zBZk()juD_7A%LJT|LD!UI?Xf($1}jS7>pBh?}(Khgb0&^uj_=OZk_-SPs{X+TA690 zSvkUTEHwx90uqoSdF0Dcu5kiEianSd2$#6bO=2Qc5c*M6gC~);xpR z>E+9px`u`pFvHBKjslc z^mBMjC*;jzgJ0sSiH&xkjDg3?_J3Y#utf*x(0QqcxPWU1GvLPkdSlMZ)#%F`2v-Q+ zchSp}g}6(wb+9U>U6*@QwQ2;k7N8SBU1vpceUNENHLY_T6JckQ|90kV*h@#Mn!-F76lT1_rY5A`*`VAJTXdHo@Ve#3a z?c)vYfyL4(eQl?>YNX|Czs?->fE3S(AYkMr$0PCSIOc0lhjNP1F@TYKSTe5v0w58P zvqIKPZVrVgt3Za>m1i`k7{;y9TuG7 zR43;7$c{GeS|4-2Y0K4|jz6q~BckUyFMjsG8!!a;0P%-KX z{Z}}lBEoh5Kly;JrEI-SHlxZt@hZb*eI=g{K(Yp+h+iW$Sm3Fn8u$$qjI0rUiF4`S zJ}zzvA|Z{yoOW;6r-YdjHiaF+5@%Y)-7c}D)7!_NRdFf^%W691P${UX5r;2hpIvFh zSTM$t92VTLdxu17uoi&KLZk_+99>~!l$?e*cg}_rItAlg#vjk1w89C}N_0GJI6gQ4 z19{q5*`|#{kQs)vkj;AoncLD{QjO?~wlPrg2>nd4uxAth!HNfAe}QEem5hu`iWx~1 ziC#uw_-FVX-hqqSTx5tX$WMx4-`pX(kPE0(@GFqQmBgo9qUxFf?B@>g6**Xf#*ev{ z3sK;rNR!LS(>NK@4bm-34Nd~$3avSc@Z1$pL|?a?36cyhl|{^!r)$0I$U{H!Or@_J z4qb`O(9y>ki0oV_EGv5gIPLx=C28MA)Z-0@#YTk;TJ=w>=cE&jCk<5z<8aeFRwGLM z8iJ!&$E|W85N3Tp*q=EA#cdCB=LnBB?nhJIIhl;6>FS~!8Cw*4L%O)_{q&Ih0*t$f zcIC<(sY*E$ecGY4dA`Ub){LNNKuOXHS&h(t_Z~ybk=Op&b>sMZ zb0WOF8WICcc0&hdRdG*x)HdNt1S>^^>`T(HwYiB9Yr!xejB#=$xH##{%*+g)v>F(g zi8I{1b?ILBe5_Z0;&Y!prMBx8(%!&s7U{oiODhda9<3gF!Tj@suOD0w;AbK}k&tl; z6pDvDc|o|Avo^QXa0mo{$bf0@6F-#!p*^j;+az~E+02@#&Z4AmFXI61q279i+lb#- z(!feZb@j`|$-|b%HdNI$OTL|vowrd>BRCsE5sB8@zu*L$1q_&W{@dk#cQ_;1d(#e* zKp7dHlLcZw#B!3J@Tn(ZPH{$B4l{xzLJx#!&;Sw}YhcGr`WPFO$Bb3%A>YR$#nH7L z3zHHoo0FK?dU+rbFDv}Rhg0Qzbs+p8aR3U0uEf$$iA5RYTE>cXKqlb25avrRl$2xv696tJ*n%N4UpObA zXyfAMMg?12pe=*F72K6j3-0bQ%Mmu5_B+k5h+PT#Z6EvLL5O#S-Fr3S5oAyJe{wjz zL&Iy);ESRb2YPM5S^;(986a|QGWq5jR^b!V0z2n{<&zMxb6OynL4+of_zN%-^e?;& zfx-kn1WfwTRaOT-WQKT5eyo>jp(s~z*;NdOCRvE|3Y9Gmo*`!4Po7|+mFvG@_sWL?j|@4cZgKqFYE>3IW~ViTN+pAbN)*qFTJEvu^^xjOU1a%d1b6$g z;;j-T0nG_bbEb;c1`XJ985eafIyx&Yz1uG|F0>kbt-%Xf1KX`uH7SzwDVNuWMrJyc zFHz9yMJ6wIW_mx7CvUd=&B&>=(>S@+9)Ek=qrSI2P6+5UD1~v7@9w5?UwFt9&!|Mr zH}sCF&)tglnxl75kO}NE7t0;9^F2f?UuU+hM?>gn#$S9Ma(~Oa>(vr;J#Wm8164#gh4g_? z=E>tvY+j5r7PVwd@;8e{JH=^sEXnooiqoG=NSDeG37ZLl*Jv)rZF3r1+^RTFsi>WY zEs4}<^=$wCUS5j6(1?zVMBX82{NP-{c>OdHV;e}n@PdKWrdyehXmo9D?Y)S(Q2SRV zlX*nKO0r>-Z_%cru@|cZjA~^JX1+r_j_pm2u0iioq zyd4&ug|(Zf;To~ch@;F*dSf(-zIFkA>E4#R?CRaLc81= z4D{h^fMEynz&KMmvkLowi2`}E=s?Z)^P>V?b|pJ+SxCQ?`3tEmlQ?=UfoQo zHM|f0m^WZS(5EpEJmNzyXRxFMLf27kvuP7F)8C_Ed?KocpAOD>eUjpHoB;NntmZ}o z6I(Os3f368a7QBl4YC1|>@FE@TQ0Kyp$865PQmm4G?pgmqFo${)@ zBi{WoYcKk@`anAmz|6b%C zEB}E{QWY6Ja4)ZZ*RQ>}tK%kc8Gw%x)PL*x9Yd73TXA&K>O}4wMAdrXOO`~PR0Ahb zOuYOb<$5#{HJ2nWQMDLM_E=`r6N?m+FXqAPiRhbU?#Cjkzd^x&5t4zzqY;I+17R)cKX2RIkH?NNR()}WnoIpP2;QL zY*cpd={h z8j9(&MUH2qGE*LrO${e+y}~i^#@Fx}XQk4$z5asAAUr%=*YZnhD*2HRmT^wiGeEQv z=V~xRfb6e#w_|{ITq1r$PtNE*DbPla^B*tMsh~YN&gF<76cU3tnRqoRAYe^QZ0tF$ zJ*Y#E%B!n8x7X`^@sX&RUL}Dk-GZQSe0-b-F9Q0w+6EYHkYm<* zwqEM=&rmpEEfr8_Ylf+68g8r)VZW2zI3-oGPCm zP>cGI!5F}v0Xch-s68OUi{h_@-v{Hi+8e@d>bF%Hp;(eW8&FqCjXh9dn-4V~ehdQE zP*IKN*(}v2x7~uEFkqEM(h2bLwi02OKKQze=YJvzPZhL2p!tJp3C|Yno^vZJsNNs_cdV=Dm)=4n*rj_^E=`vC%X%GniM96&KDksWrS)!^K007bN^CtHtNaGrn($v zNFE2HGbUgTweg7VSo1a-OZV1M#SjE<<2n0AXshSWs^p^R?HZl%_w6Tuc)FFs%zw|i zh+aadIbfJp*PETr; zZ0%fGNsafFI?JIL$4)}J_#^r&kCN`m`I$Z5b*y|7Xw+z|82=L#whzp7T6D6Z1juGk z=C@|@*3tD=7Q9tR-ISs!R5FnzB9i|sOBm5Pmt>iclwfLOp_`mT7}3sWT0dwU5LR(> ze5LBXhtG!x)(1FmbM~Yga}Q+}RKkh-x1nVNORem@yz3AuC-9DAg*QeA|D^Gw$b7BR z8}t_Rx@$Ei*}Uy$6*K@JL$a>kaDQoOX|f9FByIS5)NOZ74Wn};;`I%g=`syBO^e5h zZi?p(Ks_m$NI z+Nqt+%{-2tc`|`drb860WwN=xZliia!7LUgv@{u>b4eO$Xpl8o+wkyK?%) z;=2B{j~n{V$;oNIio`9h!X+|1JglLlDUyv=TU|{I)mV_T<|0T#t*{2mQ#JDB2OpzX z6}|{phSE=h&dic-85hv({Lgn~7P95Y?;jclFKYs&1P57!s1SxB{@}eh#o_?*}w-sAes^ECR_ulBRDQb5xTGZpak?36mKak7pJGEs$;H0 zRlpGG|E~5p8cH;CcpR>AMCZ?kG1p(M?M*gb9+rW1N)|KLCzHk>D2R+603o<>!RrfF zYJQjdnYlneMb81Y3?lVIBoQDa+TFgo+(y8ty}i8{P&EJx1^C@2mwU+`pzz&!0LGao z8;zItU}brZ1|;F1pRLt&b#MF^2hd&e!Xnnh*w_kn7NAx1%pd*z6-~>$);~<)5}{m0 zQZ^t;BIW7Ym=N0O_Sy_x**na~GUCbqlCCbgx^BSG`R>Dk_dOc+AQmmHRI|8^(|-Sf zSJWa5;@gxbUqY=v7*h|u(0rNfe*g0A(dYMJ2cp~0wwg-zO{Z9eyfA^3aN`86e5wRe z&e`3+{&DP7evSzzP~|<-J(b!t)sed0eDcw5(MZR)v?~3QWgjsW)MEm7Q@d~sbIZH{zZYm-FPl%h1V((VLQ(he#h{tW08$$Yq+NRjn9I3Y$`=| z;hr6VMxwQ!OK=!dVty;z1qpd_Z6A8*jiDzA5_^(n@t`5BD&95Fy*4aEsqf+dwXMMZ+r z`77YF-g)XqA?ow+-coj9EqM25D8&5hW$w}#9lk*pZa4{Eh*r&|Wo4K#7<_PyM=geF z-e#=o6Fsohzj3}YIu3eoF9<03*X)P_NWV|$vi@3eZj3d~qvm7a21B**Q z*KYzb9nPBpYx0Vq|eE=-@Ccd5YEh02Yda45i8 z`sc0kr4@qAiT6Z`khlQ1Kk%^2{cwXN05EBuYYow}lo!>tE)!KtaP5)rDT$AOPJm~p zvyrV`5}#{^lX9ae5KY(ExC8cT8QJ)Nr$V0P=M{`=sNn4Y=}CV!NrCUUR)VE6&T$yg zZZi z7(J)Qbs#T5eDA(|!2q`w58)q2=#UBw!Us5$6{E@U_C54EU<2^)+<(%hGk@+sBYI zlLZ$%LL8l%GBaoOvXVRaL7OJ@^M{j&JqzAzX*4nxf0{W6ZjK!}q#o+^gi+m%3bTKJ#>x zxH3uO(;iR!ZF>fLX8yz+X6?}C(#|_v4HQaj(!VU_l3uoN?3&qo-=22C18$Bf7DqW& z#==duM*=H6(~slmyQs+b{lxCv#kF$@*&lalShr%PkdX8h>B#U{T73Zl*cLq9>__$+ z_RKFHn#xcuTdnXE8oa*OCX(6tknYV~a}9yjVrT3T86e~nyWc+k>-jqC3D{=hvVEL)c}cTlLo zyG;nV78r~?`KpC^j|>qCMU^JHR>;Ehp<<>tab?)?vf2Kf^LYs zDIW8i*M_#1I}0v-?eo3WuLwepT=2{8fU|r&ZR2|Z1sl9W#g(}4V*kmsqc2={d?bt2 zcAKpmv`R>72QclE5E7lp&YF4PU*3EUj!l11+G|`?NlCnjbtWL=sMRT&bx_Zi6NAx`eSY)vwNz z7K+hmm;hk`9T5=$sRW4F0J?JLv!iF}U>IZKcgg@g9Bd5$TmnM6QD|7510UW^V2o%Z z;zlUKS_uWBMV~%(bW;0A0u>HCjlf%Nwj=7Ujgu21y=bzN*m;B1^Q!?))r*xMh{Z|@ z1UbUGE<7Rvi75dn2hk@$Z-)dMAax8*7!fIHE-Z~e2V(V+6B(hwJp#f^;C{u-&(Dv1 zK^@T!0<^av-vyu--jb)Vi-0y*aVSeOu1ajs14$4EI*U`?F2;YBWetm#*LZr9Hv0J= zJ@EJkf%MHF?gd>5OwFA{^!HR%78Eg92%cM@ed7!9K!1(-<9x;<3$4n#fU4`kqjv{Q z)Q4f+7Ch{%g+;9TrOv`fm})LNH(HK(FnYkXar@I1ZgRsRhvE-K+9RpJ$ab^xlhWtR z`8!UhxAqgx!hJ$1LbK@Af=*v&4jHW8NnVr~rI4=ej`Hxhy^Ll>M4H@`VBK;e`z_~V z<2UT5-sE-~#k!40V&vP<6KuAlrx~uB{ga6eg2r+7W0Cx;Baigm{!?*nLeV8!OS$ao zcG3ZYMCPHLt^xA;+75FBO@wd6Hqy|w5r!c?K0Z@3vmo@MzYMS4rG?RHTAAgxMm}Hm zR`#VZ)JZtJR%$y$=xX3;1-Jxgm%63!nF!< zWN%=E13TXw=>Oo&S0zFR%<)a@9P+x&?VswR7{XQR=H@mC^jm;Q;Mz<`NXRNIya87) z99|n++hz#=fNuo&7OChRTW$-GmVx+H!EUgpw^vP770U3>Ot`oa*_yRACgclvTwNUh zJfVWfP2hcvznAq!<<(RE{sWKlQQl1nZ*7uiB2D{BLC!SqlQ?xQ-372~Z`5^(e90UQ z9mwGX9wOqF!u!bvFg;)rlDz~$brSA#=)SDmn}I|H!rrSxldHt1s6)A52CZdW@kJ%^ z14B%?x`qeC?lKH)e2B_apYMmY91J$V412n78sh;dG2V%mnRZ|OuqYcLsh%=yX zg3r!w2k>j4-UCVf37)H~>+CB$QB(6S9mC~YPtU)HYTM^f$3iiu5cc4D z7Io;wpYB10zmG-gR6UBeBtvDgi<7^}GioKe5J5)YH6SLE8#F0H5WkZNPQ)^q#4L~R zY`dDFM-*?UiuB78^@eIw1|9wlfi;hb;n}r|3#RN2EsP#i8mh3|%6!5Fwgqy}9_$kI z^6kkX`|alQ4q;P%+oo@CRH%+~>5K!_L+%;H5(?Xck4riThCFAT7S`V8L^ zHK~gY!5qX0Q$NQpw_hame*m~01bM7DY!V)uQ!Ru}22C}6pdNo`qPcjVH2awI{(WFs zk`xscaXos3wGUl9=g74zT;fvepUmt(t1M|WUNA+F-@@@#apcK3=WM8n9ZQ>1j7Y^4 zW>QWUhxHQ7-Yz}WtlzMJ8U}L({GjKXliXlP1lHRapX}}IRCRSj(J*n5qXxLZ=8g|M zaOjQ@^6bVq$I&*jn=2}s2e`HcLU7^#fYoEF<-2Q!PSbT^Aci}#wz0VZQy#L2-g5Gf zfOH?=Wg;v;c8si&5*&btRmb?E-C-vUM>&ojiTi@u6%0`zzyyY!J^(cEH|(8LG?zht z(p8ystEABGQ9WT`33v!uTptx-J7o-r2TNY-RlVl{n`?Mw$H3K-A`}2nTSCupw5>lVP!2z; z{g#S0gKGzE%V#$lTwlP`9~~hwfHTt$5}Ww_`#Vctgyk6kV(hxzj=Lvd$ob^I$boIY zV%qpWNsqd==v$Ib3E`2K}A{PlV0hV|#_*%-BI=(VQN9Y8;fnXDu_#uP*n}IumN|;{~iov7gKlppx zBuOk#*(v(8-!H&-WF$swD|-cSn=K+84qYmGR#l7z<)$=FR7SH$P&l$|#fl$EjUQ|z z?XHZ)9?19PLRi4Q5WWnM$-Y!XqcB}YxL%&QA@4w7Fd%qdP1fzp94r=q(;@4%ft>?2 zO$4xTz+-j5Z3t??aAsv>T12pCw|3^6Rk~F+iiO-|R(j*CO%LUyAMG7qj7p_Ti7;=e z!BGtr+)4o0fa?p{Y+Y8icQWgOh5&iZ^r@#S%2uc6+CQB~ zj|Mi;0oFB|jB7iCU?QZMzP~qivJSZB8oOkhH)B_8Dopv}Dl{bp?C|R$$H0*vKW>1x zRmKNiY>*bfsRKDqf@A;ooo8Q-Z!`zr8wctot$}_j#%K(=AF6&zEpaewZ?gAGMS*(&)5Z}FU8nthHT?NQ zb#x0qX z-%qbhyb^nml$(nTMiVjb{ik;74XN$OTxn{sh1l5GR2y;wXVdXkHGPlo`hX9@4|+6% z{_4V~xrC%GA=n4xagf^X2Ks5h0Vv_1gqfXN9%d!(sfK|yEAlqrt>6rKBj$z*jxp|3 zrnNwGV`HnF@Z0}3m7x5Y6C^yozP_#ym0C=%#CQ`qi23?b!!`ncx2qU!oH>t<7SOWO zpCNaDxF@?$_)O;VrP;Td?|4PVvx}DTqrr=L1C1&*O0g4y-52A_ASN$LP#1$yn z+#KgS*uh=+N4ldz_B4Ylfn8%)fU-H+fc?3ez4%Ymx^u+9TsFmUr|%N=v)}jd;z+z$ zs_A6R*Ob*N)E?LTB&?r~XD>*gZ@2nnVPtBX=H+pQ(AnPV5CFv)&(P54fR$&B?oV?D zXLRmfiU-eCcviKXa6bLn&^;fr5j#9IY_r#g!r$WCG8BR8ha$J6rD&u1*Hqb3z@W1{ z^R?LgzynHF8t3RhCY%X*qTN2MieE#J^brcX;Og314P!z>l>ONR+6a0rcCrl@U6*d7 z{O-#{*srs(7MV0~@cvNqTlLz=vNs*??{k z)6@&>9df+1wZ;7U@>VC@tuSl>C8lj^im#wex%W(r*6C13pA5OTkUQ6^p>5@fgA-R- zfptI-Vv$kW5?tP&5;Sq8<(e!+QbHP^>DcHHAj3v}hhR(VVPkQX zPnMFFzKvwFdk!>$=U@>0s}5r_Kz@c{0m!^k3W{8Z#`}`c)oJHU-)X-7#&xE}9JbbD;kbD3j;$nU$6|DH| zZjnA$0wMk_l784jUX8;@Sp*1$@*5hcfFWF4TfbsuG98+cms}e@6>zK z7iDFGM2YF?UrW8q$_hZb3J)lrzj9JoZLJ_49$p@ROrY3-?*nO?#Vug&o4kGW2L|-U z@WLZR;%B@4KaYOt>Z@b%LLsh@FK)u88CVk^CL5&6SAn8-ZWCZK&}IH*6PN_V{7ZM?iD~1ZVwC$3?|KujfEz& zX)Yu4w~^N)ES`FLdh|p$@<6!`)TQf}xy-W|I4_XG5H{EeLH02E^Jg5at?=E%3B1Y4 znS8_6Zjs<43dhSG1E;$KXdwt3TwJ5SYPC2?iIHDXB!UG5DffEV8Z`*t9A4l{vr0@7 zRqkA#Hs!189i7*##k;Lq<}K{3`Q$cV(Fpgxea&@TlMEIORS(zs;a6~lj1$G7Yi04Y}g6L zAZ(d=ORKX0K!7@Z>%4c=>%^~j%Q`5>LB~puPzG&RS#3ag2?ffR2<~PJQ)F))zUGeCvLqztD12yEV017lt<(AT=2rNSSDHgoa-r zlsup;Q52sPs_w44qSH-uvGvv+|&9jx2aQ9 zVc%q9badY-JFfUEZh8IjX)(|ldzk56EM;vwEM43TycIxFV26!1HYv2+8v|XX_Pknt zkhMS=l#IF%<$`D3!@XMedrvM8Nrk}${S`>fLIPkOY&oWMkJMSmbIh=rv?{Q)kO4`M zOybby1_nA@zNTPEAOn{hoc5Ww*i#x_Tn$l7Es_0p0x(P4z@S(=;ao(wBKSwWwLbYm z73|+IuqwH^3Dj9=+h{lb38yfFaKqjklWVCT;bZhaTZ%-Cnc)I0v=)tc1B%&k20Cg1;ep}*)9}leFKb)!>9tYm;9x;o zg@CRAI5q;J=KJ~xi>4BXH(r1b5V|k-fFrG4)`tU50OIfF9pJ3gPTOi|N|F!XDb@65 zQ1}BOZJQ8&2vUbSSAZ-?Wg62K%2icVkV_04b2Z#1e9cG1_ab|<7()q}^0&`EWEGTj z+qa5x`ZHs`h*=oF*reJ%+udqdtt4(|@*&;)Nf2<1G2mLe`4nAoH*eGk$^xFQ0Qh8R zVm5}DMza*+e8ee0k|C?^fM5Knxcc$5Y~&09>8&=6?{W9ZhCWM+CfvNlMreDGN@az< zon9oNZ$_WyVXCE7>@o>%_?v9c{gFZBiYU69YBK#!3-#dO+o?RW{`<`mD|&J4v;>7a zdzNY*^Wt=IaH-|%arPX2e?Jv-BJt{Lon1bsKq5w!-u_0xjUFExy`Q<>@LSOu%Xr)Q{S2Lo>NDQhX{BD3piIW%~k99M~D* z3$o^Y&Pm?&2p2@0P|94vvBfhVi&}!PW~cM?PKM@_>g%eisue&A+8~Duxj-t+?K~55 zygR4rAJnY=T12i{J@e|iBmzWKR_c*>F;mNt5r>5;Up6>CgPl0xr{JaFF`ni znX)}3z$7JpycLd1fo$3a(!umpEa=~V*eO6Ub+$PzV9&sdicRy@*GG!MPRQsMH;&swyr-TA&!EWuQd- zRY_t-7G-wATs<;2h6*PmAUbhvYZm;_tu%$SdKPXiSVBc|y)Er< zh!9}#Su87+V{gU#oOqI__EK{hdXJH0#-b?QynLwz20<0tmAW)sKOc|pd{!4sJCG~o zspwvvroaaP4sV)(=uI5*$_vE*v6LwE22x8V6Eily-b@J0hRW)CD3U@D+` z2D3s4d^!F{qe@708@YEQRa3z7z0-@)S6rFx)K!R^m)-S~B1$cLeBfMkx#DZ&D8C!> z`N#RLPyH*geC)k3`M3D#e|6sAHLc}h&BHB7R|9*Qw*eF=4{vzhN`~z}WYs2j94HzI#4NCidgyU z)reW|ZU$2A1`NT4GlVE{lXrrp2yUP0W_#Xbuk644kg7Y9e?Llo?7YvzbiCnPveS`3 zY;LTTrT(34-Xnk(+dz=I-;Q+~rZxIh6^HfD+yik3(6bx^#={km zuYX^qfOe7ASM>{lG+?Si1{UQ+An5Qa-@mWrtbyOT!a^@FPzo~oU@fd}Y{W?)=ysn> zW_!Wi1rsqlH+L5_F(ao)7?U%)sk9Zd;5S7&X2Hmm$+|7id+@=J-lck(rxcnZN9~1I zeCG|7gazi4hwZ$fiF-TXTkHM8@*9NNJbM$~HN*?H{s&K9QP9+|ztNzmlXr;_saZFC z!C~3)#Gg#inp7p6a)we)J(2KU+O3MG73~@35i;D(6#EL{Z+O|#zJ?~KZ3%AIc+*B^ zJ*uv035oWm%e>bpKs2m0@O{IH?~{s%!J?9y^MmDg2lT^EiYx7kVN8}l+H|e#vl$s4 zXd7vVY)wz&@tf})TSi`p*0~uB1sxj*u@Z#Vqie;jQj!>|qSE3xZW9hv#$h z%!6S6DxAfpkYty-v-gP)!t~|7u_|8tfSlSvQ2nK^?2F+_k&2on#lNtSdbhzLm$y&<%EDgUgz z;b2#`NzcrF2X*Ue{Lp{o@94^TG-IIVPQJwK|C;2Gq79yNrg<>3D|HsOI11Dd+% zULym2eYBqLJ8h>lxk=w1oT)K&sTN;w#S|^~qn|w#elgCC1zz&qhfdSN&_3P*73>+Ld zkiiUM)$&;dI0d!bbsk?p4VG=Xs$cNqE$lh4I)Nbk==gXEQvZa0KTK*4)_Bjzx#}4a zvq4K37d-cowYYypS0#oH6V%b?_(dDvFJH`Z_l{S5SZ@1GU$H&#`pxUE`oL?OpUt9e zpJ&`daJNsqe*bumKm@!bF*JH4n_qYXqnOdq74aA=g8!p1o<+LLw-@fQ3!yt~?b+XI z1$&=T9SR+?*S>Zen8QYt-gs%nCH9KxmJ$&j4-+YYqYg#Pv<@U!_{R{IJC>KSR|Rtn zcj+wO9eDHLDch2JqhMQ8ih1znuZX9MEUkZztd`H()Tjwn&Xrdfs6E*SXmanFqhI(t zp(bFi5kz*5sPKMEZvOUsUxF?CWmt(=?01^x^Ug<8TgJSfzt^fFO3C#5o^xD6@ zC9A(3cKG}uY-Ko{A*jwG*7m0=$OEpe060!izk{s>2&#y(;(#XV6k1u>E1PMPMw+Tcg=qD^afCp<&1_laU5RKYhJ`k3hbadMsVL+NK@$`1Tnri%$J&!qGKnj6fT@!3t zM++PFJXAFyi^KNi&D}!>`9a}=lJ?kZ@{NylUW%Gj%R%LA({0^>MF0mtFwsQOoL^c8 zn&>Fg{asdrfQc^=6e`D<*1JqOwuu8FnuqB+zxJ`@*-1Or*I7aEXT-^`?M>81q2X(w z$Kf_icAEV!PFnxvYPfrU@|`Sq?^r8zjqU)oG#h~Ki^G~P4+i3-x^JsNVaY%gALAB4 z01lKsBg%ecd?1N~2Xzq9&V_oR9q3L*?Fa)F>e+EmFI@jy0M#TRm;$=ka{W=0`?|g*0$c(eZ{TmMK~RM=~Ii^si)q!zd!3lXENzx^UKCwq-vonC=h(-@G@M8V$4v>D`-OP z+hJCTQLS$L6yqv3=slJ1dSgckngrYC;K<)STzZ}xlo3*Y7C6I2g(Xe5OvlhuO>`%G zSVbv!^bOHtY(Sl@#Z7}`hE;fTgbJ4FaeR6zIB`Z>layIwV=Ht!jQX1ux=zm&3Fs$qQceRSd>~c-3ul#F(b{WfGNWl$;I=& z%s4ZayTs=!GHYwn!#4;)ZIQB_uX?E76v%fMrk1rZ@E73Lk`O}7a2Wi%^7YkrsC%Ob zadh=>l7<*MeR)zQdZ(1);Ro=dLpXt#?#lz`Kfiu;Kzu6Tvz{B3_SnR;N@g1K9SV9( zjRr2+iO9g@aZPCj2pvE(IJzfEO^(6F858O)k)yr1m6c$^ZV3`$I8JmmV|aMr&O=hH zz{ue$X!AqN0x;u9Q9qtpihQun003=BfyJ{g*&Idia6@^jqA>MD*X1TQAu$K`3$fO| z5&4c`B^}o;aYchbs2e~ke6FCwOPAsJIwFBsxh;Af+6(aO{vJkfHVf$z#_q{29Bu_E z+|QUlzin>R^($Z3RbP+c&T$lm!KaV6dS-g=PEL-$aqVMfFeVAl)N=c<$1X)+9re&6ex z(?nDn>XkO+V{eyl;~@^o_+h}F{z zkWL_X4=5Ga>a1be+TQLwJM-?5A5N8OAEtV8pP5)zTRXA%NA#vIYb@Kp{Mt>>^j(Q3 zNEK~tY@A}ewC9c8t)04v;^^otn1T%vsEiUEPxQ8*Q`R+?cP%8Q+-^>NV)xwJGU7Zv zR8x`dezD&?1HLt2_Y-R(THcQc0YNwl2|4ZthjJKU@>)+*-ZDI7FqRR?zaJ^$W<2Yg zgTa(Pr~_%|-8obJwQ;bq73+bgUlwf{+{cB-T5GBn&uOQLq?m-Ns1K$_+EVne9$U>h}n}c>=3_F|MwaQeK7cwBc;p(Hv?*)uu)!*t4JT z$GgYHs{Ik=`}zhoBtO=Y+1N-*-6o4Tm^CPzp3x}Ye$`gn5;t+bq&o3|ta3$L%g30m zXI7&B3c6!r4pb__I!Y@~mfH)fv~*0uKqymCQ1C&(6Kjv}Z1jgKk%wj}WlmYyks0MH z$I$z_ea=6d10JHuaD0imxt9LbA*{q&Tu74P_!gY)VvTc8!NxOmtZ0Xek+;j@`Dr_Q zt?O>y29?hrACosbad)0n6%;w5ylytzT?1SXPM=QOx-CqDG1chHRVP+o)NKjxBEfy2 zv0=sl(I_PqRXY-7S9D&aAk$n}G`IHmmq4>P54ewXp0EUA_j`SYK>_f#3lF{}vn-DdYhn0YTR{qditwMNph4~s|#|2B&^nZn%> zU@S${KFahlGBf+ONJDe1Etv70bmnHrO%&I%8IA)tg`4f4M?KC1(!w_4e(hK`S+VOp zJX&>F4^O0=D+hEIR;X+rYkgg)WZS>Da83Z=P-1%|8^10E3#PVhaO~f!d;*KzMK9b&Ft;FOJTUta!e9hj z{qIZ2Vucthq{h&qsi}!}$(6G8)UP!XvhEFBqyD%6*bCrs#&a-+@x9pWD?$xuvZ`%t zEJGPn6h;V;+(_tSqiAOeQB2h2wROt(8;m2!zdQ>UX4kBszxldH<4L5AiIIu1{Nqm9 zLCqm1?bKkavTo9`?O~P%e!y2%eQ?ui;;bdGbvwG+?&h{iIN>mf(ArIF98{jOSI^W) z-HAi9Yl)4Q$H|%gV*j4AyVvk9tyfyAY<#!HNAkR%JdXnz5Lpvl74zu5Y^-dH$KH4R z-M&cPt}&zqu#;QN)61FclLS|BN%6EH!1PwGuKb<%JBRfJ=#zJ)wWF5>SU7wxFIhz} zUWp%{9D74T5b&H~Q;rJ|k*d?O;syIG5&m@RQI6w{!~R2Mul1HLj!}_v)e6s zx3c{hAC!E24&PZ%)*PUfMnjv%1vkM@46GiUa*rW=)~n^e~LNA zLj^M1dS~`q8g}=Vgx;%ZXv*@sGA!i0(hJ0qmB2nyFD>P$Y`3;2j#MGA{3eBUSVkp7 zUBOqux0rB2)bp^X=J7&^b4L&NLhV5KkiCQ?Cb=k#`UGjp)qMDjqy$1&z6w6#pNMCF z{8VYnacMu3zuPuzWDp@Q2(ou%MU)nMN@8wP#bAg}Yi`K#-CRP|!`MtOMP-)SiP+KD z=)#)3ePSv?8DpR2cYdDp+m=#HcgrY$Hl*7zWx09wQ~zR z$e`#&>Lh@21JTV&0I?xN7&JOyfi%-B=${veTm|;dE9B9=%}?j$ovCPPttAeDmPQ>p znCJ@61W$~iVXsPC(DtK+4)8p9UMvr02)QeRz6pZEeZ7%llRzjlDu7 zLk^I>83zZ4;on>Z3EiGnR*X!!r-9v3pVHJzuY0Ng2@eOQt*AOb|1t-VX$AWbWIO=c zh4eiNE~XB6#Fugn*ACTkLjf{0#f45Oc)}`7y(r&_7FPj4ING6E6e6hl#tvdgNm^P@?k@Q7 z^PbS;9*h7}gOPM?CcOTx3}@i4;QB93Ms4mwd`qXZlGmyJuA2gAjS4k#DYrZ=q!M$` zx+wT+(&>ZPZadnP|1eUqd(2QR)gt(f)1U4}RwBi)pVhg6+lLa0T$6w37<0o6Ddw0g zHK9#geo>OxwnZtCYfmYH(QaU(MSU%-kjyFLJfk2NCX+;|W|W6T)#8aSHMk61(^A{5 zKGJ_`$x2FH|2*$KBEhm|MkqA)reycr$@D`Ilu`rw9`!HhVd>_nVowLi8?8qSYK=ON zWh8GmRg@eZp3;Z&%$o5G)IQz2^YQB&HCDdE;LxcXK6%_@L}yuhFI>0ASU`IP?>q7j z!m!c#B`YXdhIco(7h zbhV{#LXfX-7uIMlR>)=ONpnPle*Fv7n3-bW~6b{(4ly&CK7F zpP=YeB&V@m6+m{VO0~?h6Y-gOjVgKbbj2j>@5|sWfX;z(==`(qHEAfq(9hJZxW`iM zAdM6r=Y3z<=cn@nH-i~Xvv~h*XM@(mxWKIPsHttqSZNZ9i*BFa|E~ogCkLGjRFDjW z5@0ifcB3|EcVfP|<#~e%-p{m@lxkmM7(~Qe7s1M9m5zJEv8*B7$K1d%~z zo@BEd0Q3-y5&|Z5vH%FYoEBH!P1ruyh>4y*Etr~F*|(-#J3CjiGBvj)llV$v@J512 zgNApT6g@Q7=~`@TGJ@<7=UI{P;`;eA2)G?G(DFYLS(jIw=Lo*nljpkms>mapf|RuF zjh&)9S9IGMzX4%(2M0&Y>L62(Y3`ex(5aQ~qd`(y0@02o7UpD!K%c*dTXC1GkU5jj zMoLyE{%Vc&Rksy82dAv7B{l#f6}v1Prc+^m6XQe_R~UT#yw&<>Y?Q^9B^knm&V}wg zLcFDO4i_cb)Xw%^N;NxhvYFM4lldgpdKBmRo$fy|Q}b`y;AaQF9Dbu0fubU6Bgc;b z#^V3n_aNw1f2TXP+}H6fsK-%Tc=WiyY2|hQf#7y`8bT zrbFidWXdVvkT!Vi&4qN=DfPbF_-S-Oxj|pyF$QPzs|Ls8ifC8@ii*PY2MhDi-5Aj_ zgppH2$v8IXaUf(%N|&Ar4-=9?Q&D=&k#!V&e2(PDb>8F{Sa2s7ynP$4ZS2h@c*_7F zwniBn(5wOU?ua0kj+Eaq)Z7|Pu0o^Ubn$%($|vxQx}g%sHBUC$AuruEdWal%L_7l2rp{%b9q@=zO+sV8~x6~E5$-QZ|$Zwa5*F6?dJB2Jz}|Y z0aZl0a*$H2h0Ar(&F$?MU^*A37^UH)-rl?w*EH$7aqn7G`g+r!Vi@<8Bw;7nEioPQ z*ipVfT+J42-V&182Q_WIw|?hUzawHwys4h!hG6gGla-s1+j@x>qD8-QkvT?vR=>U^ zG*Kfb2^%gY)qiS+gB6MqBC3uV1Jp-LEVdJ@E#CTXv2by>&bN=fA$qt3dzo38H5qU4 z_EYC>G+s=Z{mI2YJ71{d7%|(EItn5!y}3JSgx)PEix)0vw{vDj`d%J3FFVQ4;B?FG zZNJG~xorGk$X#(p`YJp=tR#5LG|PEt{EhH!u;RM|EseR5^0bUXk9`2_yzTW+G7L@v zctV$_TCeUDDvV$($!7nGDluF;ezFe&bAqgbF0 zYCfL+2g7f`ocro!bGM!=2>K#`j6L@s?mFOrtidAQw_v`u=Pt5pPx(iedHF;1&K(EN zn}1k_iS54)4oc|q6Cl7g*lyvvu=VDIsQ{H%YQsn>ec^s>yazjJD6F>?o9F5S<73%J zwI7IDjYwPga#%an`6&nUtgP!K0KIEl+25oliJOeg`5JcMf`y7Q=V{aMGm=85_*@EB z0?T*2-51-EuS9*JIA$4m1}gCs$o7ID5HFtZ%#1gfM{%Rr9?No*--qm|3u&V+EG#T! zf4Mp)om7?BZLM;>sYUTf=ZBngaA z(<7ogOWw2NUJwQADhy`Gj>Ph+mKfM6Uy<=H$2&LOc_h&qALk=sFe)^8^NMKrc_K@~ z4Yk73HTHqewShZ9NJf&g3M+Bq1}qX9wD%%jwf;rVx%-NBSPW6o^KevWCPv_pz5i3c zVH%l5y5{_{ef#enaodSch6ENY)o~yUh?ohy9b`b(_jNGcLW%w$BfCNj+jo8;sQ zuui&%f?=hUwNBxUf~bieb;#_p4!Q5&EzrVf#h5tq`Rcqc%UNzz{@AxUE-AU3J*ML< znDNJw?B|=C>$tBs`=&l7#H5g0P`p8F11}W6pkP7yv0XA~Qq@_}VL=7yadGtZwX8jw zGq|PTz(~1sf4Gi_+D_ZY&%nTahPy6RgYA3)bM1nx`Hs9_XyWP8w#xfc5b+!zAA<}; z+$K+;QAwCuft?iDt>+~22qJpD!g3$i7!LBkci<(~)2vVfR z6Ca=I&+}y}E8z`?s)KWX$lCc23Oc!kF_SInM-Hq!xCm^6=a*coy_1~$vbhJ4_P~qX z)>j~y!JG$iXjwj{P8wN(x`vwCBAnGdEpXsmXgvqP#@1 z+pgB6Lt4qH<)rAZqU%9<=0>Y&zTW)p!--G1H?JKk2enz%Ls7{Ol#knk2xLx0 zJp(Cy7USkeAK2q(!j!@X*3-@{&nNDFF@JKw&veIC)A`X`6M#;Yd# z&Uu|FsA?ekf-=UT_i!)kzbM521XmZVy%98OBJV&h3){enI&?iSLe9G!NR(D0#_DQO zbd5CZ!j|eLHUn~pCUVq|2qbU5xh?5S3L1Cl!Xn%6WtGRK&&1$6s&GM#lXjfx2@GpP zZy0RtJ0bE4-Mueq^LIO{+e#Lk+b{*5G@V>4Xgx(=KSA{#UZ&FIB99Gs6U=?a?NitR z6K@LbJFW(t1x>{O)30^xj*#Qwghy{3P9)Mw#W?47Q4=$^uBw{cIfld-BM}EFLZ)2qCO)mk_>Bwq! zclRU~Dp2uq$J0`!l@iLAi&f*c1%FWTg=ivhaX?T@S=q0#O+Eb~M6~Bi8Vs^^s|pe! zy8X`~-=2Ft!)u>^h=Q0{SC_x-AD#35soK!nhM5!pdy3?Wh7%fh@}HD)^bIk8Do=jE zvzymuoOd30rv;~EAbPK|x~ITYM=!2nTD*%eyNe+2hWW$tOIZ_yaDH7JOqc}UkNtgQS);{`_5Jl^8nl)5>E#-T0$JfHrXy>J=IJSmq# zYO}&_cp_k*NQ4te|Hf$YE~mT9zyu>cOg;sqbxUx0Ube@cNd-?jebeL6{Ic8Jq{V#= z2ehriRB`|*@|rb8eflH<06J1h#G0&JIIa8m%rjV+zF@-m`vX|WReee+4BKD$G>2QH zs6-lsGnxxW53+XeOIm6b8{pCo4Sv8!Uc|g);=*wFB zS~q;iTjD)ULhV#OWC_25KF)h6b$y`deR)5UU*RCV>4mGq%A?XxEU~6x_yb0s3D7u7ul@Y}E za5Spbe6t~3+^8Ns_MZ!@BKbYIaP5GLxt4^&G37-SE&n5DbaWJ1=J25Sgu0tFS`IS` zgm!7+VNw)T8^iE9+e$9i;Pgc}j&jiJ$(Eh1@J8KTNvNo=trs6IicBCNAko^>I%km z!$Bd?hAw|u&Mu`BwzgTzI(+s-B0F?KFDEi08&fTUb^27ozFz$YLINcNAInmaPGnM4 zYc7y$vNzcC+_b+txdBbY3`%|?+lQlVkIU1uh#_EHej-U4~eydA#f1X%tsq~pwQGLnY z_TAl``h^JYlEY_6EEOzJpwNbvcUb?BCAfRv?(HHF@CjJ=;uoOgzYwI3e_}$qdXmVD z4Z@WB@lyqx*O#b7A)NS94%)s8(x*Q?y!RGE7=CQDOYkW!9A2_4w`07JEp7&N5Qv|K z0ua{dk(>&8{H+j)_y0otZgCYMr+byHkjioueUi-jUKg zaueM8_^Rv4$7MK{Gxv-AkjD3J3UmJ_1B^a8;Gf(B=SZC&sFttPaf*I?y+CFrUTy?k zvBBAwSH{_Ln7z9QEA4MTw>W!~Tnw>dAB6pdzJHDxD`oSxd*apAl}T2~%|NqJ|DUR7 zAIgGHZXM5X{o$+Sw(I%~u*8F8DgCCZoG8C|c8H6stJAGBINR=f5(Ks}Ojd87i=Fy9 zscWMcvD-=zQ!qoJ;D5U%7hY^d#j%EH82AME`4Ip{z$(&dw}pLevhV9lXL{)MqW=7j zl7(Yc&9Fk3-{vt(-j1e%HrTG=@!Nwmucc&7sZkTv!>&!U0!Ya42a^*bFXPZRpeKkG z6+iGL*jcx~{rlIG38Bk*`T4SkkA4Z&VqPs%v?9%@ApV{AKOBnl*@u+a+H2J$bWlHB zUS3uVua!q#PniEBgL4JxYZIOKzVC4>`|VNvXFB$mQ7xi(ueUs|{7YJ~TSu;a7BLV> z(mQ=T;@;?>eSMvk(fRX|w!feDH#O>tP$Jcd=yu@{{c@TZ7j@Ue9rR#lr6g^wKhple zDw-@n%IkF2^9RwJa=$8jGPZC;#Rtlv6Bqb7$QTI416mtD;n*2b+1lC}8r(MX=6^qx z8-{(_A@hBz2`-OkL1v|`9`BA+iC=w%URA>{-lKjZ)%VQfPV|R9t0t{WDeef)U~S$4 zJkOkU=L8ZQ2Jw-3%lM1*@d+|{_NI$-_yzinV4Mbnj1ze^s$5OVL>Wr2Ygl#%@-hJDSD*9h8klpdj}Lkq3z-)l+z$C4o*FpP(1 zzUrpbD!(V!!7*52Nk2K9{8Pg7_?z^@iq|SRq@$TUpN>I*JeXDZe8I^|Z;zcg8ibdd zocqi`F+ip@I|s)oe(l8qk>v0jv64DdO}Ui@s6~bYzumSjU`OXzzJX*zpLe^RoQ&QwA-$G%Ff*$!pTl65~OY-kxj)rL|%N>kr zaq4-W-(#<&M#5#koOh>>o!#Tm_`acFhIQL4M6oyr4AB#wGyd|IN+C_RaPp_kQ6cP6 z>Jc_D%k)z`w(uTg57cZe+$U--6?QpZKHYSYayd5xy9bOqkYAq9v6#&BUSpS=tm^Fv z(F((?@$j=2;+I0Le}9#y^O<}`fUF!C-FT6 zYQq_QQh6%5&;W{9WSFDiJOd38YyPe>4SB;p(k}+N4pRS)bcg6i5r-D$P4$~Cqq+~+ zH^cv^CO-$=1GupOX|9NQO_`94Up@Mz^hu)(hQf?$QV~sCU;W&Zk5-V_0XI0j2gq=G z_z2;^6hvLwoU<0sKJT^`%x`JQX%IbSf~ry(Wo2yW4*m_|5y6ZD6ML1mrPjVaqI)&MLR_UjTCz)r#qVMMG!U(ObLfBA<%vq8N)s2V13^6@ zvuK+Rr5&ycGzg20_L8{Jj>B#g`?j;6mnN7B;Tu_m@py%A8>mQ@<<4@XRBwtvr;@X<35@k0gx!_fA;8v~iqPgQJ69tEw|r2Yw}iC5&QN|s1p`0*nO$*99I z+cAjt8pBj$n7-Hcw(m>aL+0=9x=F(uBpvj!;~zedl1ic}D2QYvV5>bv%fJxBO1st& zzR~zi-Q-gIZsMUrEFm4)Ttx1m%@7ug!Qyv}d8x79)8k|8NX)+m(>kP^7d{enumf7S zxoM{`j6eF8D^1wRk6sxPW&kKFJe0a68b)KzpN)LIy&-{sk4IDB7IJ_GUzorZsN5jY zc>lO6=vM3Dz1A1=^JYg!M~gw1udY$l$6X<5Z~RN?Q{WQ>w1x3HWx&t?LV*;yds<5r zt!Eg4XPviEA3OTjO5(m;Z_%h7i1%l`R-cd2118alb z3wE%)SlzYX^&B+$@(f?bJs^3iFk8;%8>{tS+lh$@hbpu$s-`s^P$-LFZoP&IxayXc zmwew#+NJY8*zH!%BD{_VuUn zI`2tk{g^wzmLm_d(IpO-NKvP$HOPoW)5ESUYqZaVcrr}**hjS>v^df(Mf0iqZPy{b z>YX1Y4w=fc>Osl_@5TlniKlDbTGJ)Xz;IyP+taG;8^nQ25OU0rA-{kX@a#@}fKMH8 zEr4W5*+gTa>VmEVkuWw#&LyXH;q)>R(t#yVJ@eL;D6loiM5nz)6l9TT2Xw)Mr!lmH z7DdaFX(BIz`wu-AHG9yEV^b9sNaeq)i24~R{ zL~bqGz3o;xZE;!=@&Lu-R~2>5$Muj|0vvJ2{zh`{B{N7Gb=mdrxpl3bYKzQ3m#$6a z&0_W7ihJ(p81#2Y$^SuId)LpOw9uA>tm%eu8t@KTD$o3oQY&3gEp~|dx&lBukz51W z9kxfMrE;%y4H|ySw2<002oyqZN!*at?jYmD7VV?fYol}wD zvW%Zzx;InN9IG3?&QfULdnc33!7i_zztG8L>6T4<&*#lS+Zb_<*w{-8{xHK=TVSIm5^Di=Q<8nW*NOtsJv zrTyqpEWB51Cc7qy8jm|SI3|qDlmt`1%szO?+sgVVytc9)r{T#^Eyjd{xA%`C$pOVL zS@^wU9Xxsd=4hWbgafw6OEkGYwm^n2{5a4-L;8VKW~WPBLLv@21Qvk{3`nyK z%YXr2C8Jj1nXRqj4cm;i+%GU^fYx7IM<+=zO(-eOWVl<&_kEVv|T zuex;GKuquhW=8+zRT=Uoyq00zxwNlIF=fqPb0RD$4UJ6OfBh;OQB<0$=io$yjj!w3 z<9v(M;9lor%#5;fSu;zS?hmV$sue?ho_$ZD{8qHQR&6~t$s0e9lIedJl?mr53 z-W=JQ!!}@B*-gJQUmLLs0*tgwnZ{RkvrV7~fYcLE&L}+V2Sp1b9kLeohBGc7A9Xy= zhVodGmUOZreHMxJr#$r)NLqq)w3~f&Vqo|DuaNSri%lv7?tWV7Kw8*_U;ZVas2@F&S^L8>WMRw5+kX!@DO(M;5#D&Fp-9 zN-!FNEioKVb_H351S<)ItT1xoKdfdU#=e=?vE^A%S*ecBvpD&bPDb`^N-~;0QN@W1 z;>N8j=3mq&R)VDMH6I;5&^~P+yyQ-!Guk;s{C1dSDyY!vy^n}mRj9UE2xS|7kugCf zJSF@%(8kQZpJJWDB8!K3#wlPS@VmjpvTQ>{QYL0{1nmzE9M7P!bYeS`miNoaQ{S22 zaVD>{r0n+I64E!Y`t~_*VO)F5+9$S$+94~NMTY93$23QhSI^^pKs{R(}!gJYYKER{QrfwiuJyA{A>9&`rxE7=em&%{b-CjCEb3R>ScKM{ zF(ItZoe6&bq-b*a45i(l4NPjXU|wjwzG!^~>Pj#))9*0fKu2X{#Is~eA(-cl(bv!; zS04|1m;RS~yhlPz?6tclsG@*;1RMx#yU5g|&Xs+7^4N?)iv}E>jA|OJ3ZPqn7G53_ zT@ao~Ue|vg@V>yVs1pb`c)dM#vT4)!8h0@BdCLcvR@QTYi3d^WkMf+$`eR?z%1|o2iPxgCMt>X zB-J%Kz269pEp|Y5^oY>{w~EZSg;M~c6N@Dl!E0gp^eF+HDiHBhoR^R=osFv}sPI2D zeRnw4{rk6!tg?k{A)AD(?47;$xI<>PC?k81?7jCYdn9|StPt5Vgvg%Hd3}G!bN_W8 z)uCKIpZEJbU-S6yGD7TF6w2ysQhLGlK@P*1+X3B#1aw_^5EuFHT&jz|ts$Ok5`t@C zA}Xv10TgC)B)dO~{23@^0zu=BALuuH|0uHpm5XLFJ8&4yaBq1>YH-lSBleZ7!PecR zg{wCi7d_0RFM{y~Y#){%P%pG}E=|zh% zk&6 zjTA|n*npuO){QZ2uiym>9aU+)&mx{|qT{LNVwU-pl1HwoSg<}*mS@e*P?pOpE=t zQfxg~A_!U$x*)!GnU|oRjj;2cp_xYMf^sfEMHDg1FlKrx6Ze+dX=)-}cKlg) zhY&%;g9-rf2b0gLSv$dr*ycX3s$!op!&V6|lo&ZygnJA&PFO;rDJZ4F5cra_UQQoBz_URkw*;4I(Q~cuIRmF} z67M}?rP5-%^V%BcfmV)~Lq8FP$2h6jb=KRt>@=xAW6NCrq4JW-x%XMIcfd;%5LYO{ zqxsBqfK=k8^ds#l?bx3R(fGgY@TXo8S_ybyoIdtOsI^{p8(*<#N8W$O`;c0udiJ(x zU`RgaxCB=Hz1f5m_OAT2dXS?`F z33zuX^;7glwR0(KlBAe4s(MppXn8Xa%Y4|&3zgd=75`dM9-crrF+n|nzoA|gGA9Z) zI^qv_za0d1oqB&8xZpWFc^DP0w2N(WCZQmel=1sZcw07HeMTH^0lv^|eaO|P&n#n-X&ad&eI^OW6HqI%GNONEzkT zpV^vRJ_Lb_nx-cG6u*&*%o*&hh&UVsD3FyupbcQo$~gj$-Z@U2)zZ_0_>K^G%t(X% zz(1wx+ z(-Qo55Xz*;kec&PM$AG!R*Y&ps(s;}3$=~k1WT<8s;<<-nVKLZNR#_^ZXw1N~ zDqKg4)I|82=s8>8(F)J@A2-r}G2*r9JL(1+0b>VGnjRXJl$OfK&+t8dOWX1~JdW?gri7Z>*{U1ky2dC=$CtQ|keb+4|j4lzj;1)$vKTs$g9E$4I0HN1)S`diAq z^TE^`cn}S}js_Yz(E1m3zL-TnRK5BBrtPI5sj9%7c+e=or0`VGCTz8EDDt#arK2t@ z`k#UTb;5Y_`VRf2tEs72Ye17fBocvm5fh!4B@~Ok-q6bzQ+5aUS?xE;RSL;q}?+^<>5!2SyK^kN{RWJ^L|D9 z?0LpeGTR+wyshG_8v`B&fW-kJ2v2|J@Sm&e5BdSfu|?z=$ckRzBZacHc|{}UM^jTI zX=!P?evEk+sBO+&K6?8FObWafV{41*H&c&QvI6^8@&EZ<89|Pr%QkwN!O<QZXkREckRC z*|}-)YIm8rQXSKMszbeX9%p%>N#r~?r?V#`PVp(9!u{uR%vroj~cSUTb9*@BD2=QLg_*8&2>FB%_cIqcBv7}xYKH|M^=WC z`M;>L`#(&yqsug9Z|-<5sy1l6Rv)XQPfit*P_tr!#T-$31L`A0F%1BsOkW>+dU`^r zrT?#88Tc5XVgpR^?92~fifqY>^pc!=K6BJ{sf5$w(D(}oQkv~-oEp#2Hp2Qb%UW6@ z1^747XCg} z+&9$Mmw>i#(!8*Oz2@J1U{#R((rA$xoUz?J$ zGFHD7P3kA8kC(4N%TV#z{=tlpYJsB+W)3)#U^rmn-~cyjmgDzL<-9r)P+ntHKD$=N zEDBBQy>xr~R=@Sv>VfJ1*e=6OjbB7!gD_VcOD>7cv6CY(v(9uD32MP8N=N=xqh#QWSPuSC^dIW>em7z%;Bd!BX-PsiWr4El7q4@kyEnWx4HEjf#L^1Ulz>kg8j1$Q*C zs1Ko>2BPBlynQ{d23!qA`YI$yk>wwjl=*nEmBxM)#8>Sf)VDTPV-3eLdMrMz@H93$ ztF!*D*mh~+^vvo(Xbb36HJT{ia%4^k5lRP{OxNw=S!+^>=DL`r%|f5pIw4tNI!8}I zMen8?Z=|_;LIepXmXZMO&OZdZj<}oJF6Z~LWaYOd;SB(7A0jIp1qCIE(Yq@3&im}! zt4%tuJS>*VRnq%srQL9OR;df9%hktp6{RQB40r0mQd`)hFqJ zcE9ql2-9)2lXAfwBR0XKp-w@@bL%o0cPnU0`b&Pc?PBs{_##G~PYI$C?srSHiq{I^ zD34O0`ti9JUGu|OqN4Tv9%gIAepO`MHPj)AJ3Q)URM81aRF8|TVl{Y*-6>-E()I`I zM%0l7FD&b_>l+%7-{%C_qy>Y65y%pR{6H7aI%Zj4TiNV`8t$(c*)!0}=)yr-YS+ypl zsOm5LL_(oyQupCT#^{ycZ#YdEts+e79xf@Z48}K>c9F)6lwHQe++t!;W46Y-X888b zUWwhtrYvYw*}hSo+fjg>JPD~?=K5QZJ5G)2&>}72+M06UuSSRbmX=v_w7A@szRmpb z7Nt)L1adsKI2@crzguotMAyfx#itY|u$x1kSevagG132yj*2P_6s`bo;J|>~tmFIC zx+%l-z0=FytvV3PK&Ujt!r(^-)@&F}eJ!5QANCgWl_!@h_S&OWqz*sz^BSkCMERoQ zenW4AdChPitSp4`{vN(+>O|oe)z#I0Ry?T`E1+kWfmV6I^A2jWufMJt%Ab~YT*_N) zsR}qF%kSF5K^)!?eqnNAT708gSiPQv=lrP!5P+190?G)Pd^#R&eu_RQ_AWK4oJFLl zt|I!W+YX`}mfCN2+7W^!C%Kt+#Ktd9HW0_dlc; zmzP1u($j8cLE}94Atj{`5`-0(OSoy{g9RQ&SyF}-LQR|Gn2+-&WmXAY`hY|rtTJ`W zc=x--UcD-2t}qb%6U<9PvUbs?csic(jql=qXZX0pvIO|wm23+m!6;{>vcGh$)@>s) zKKmf1U!%el(NijNwuF*{~GjuJ=ab| zJ^$2MuW6ZAnnYZDi0j3`_&CFFfN$A^9w% zr!jwDhW6R|bNwX3vo|``7$uzR^ij?*4_1BZFz~C}cBW4Nc1he|dDa8xVe#DT*Y^6> zk3$wE1hu99;(u>gfgAjYTuMYFK!Hc1V6FZ^K2#?GyJk*UCQWwb7M^0}N5lh1_w{ri zb6S_N#t1{z2z26d2%7M*mnhO1;uW0^+7}$I$A*Yxk0dlliJ@pER)<&p>+D5G?LGMe z7cls-{{|O-HLXJ$2ti5>MxkH*aCz;6C@&GcIfzkOl;nNCwjYb5Jq?*We;3~EV-m)1 z)AZz8r|G6NTZgGAE2kpBd7yZ?T+~HXsSmpuQlC|F@$-iwVqp=XP$#>;LZHOYa`I$e zjIncW+c8dFRf{sgc`SN(V+-&TL`JNbbJW1d2vl|BK~%t2XSzchv*PEOBcp~>i-1g- z!DZDbB{+})Z;ZEyU<-yP0p50X)iqoFBGPqd-DhOZkp^#N`9dlTS3JuX(kmaZ7{Emj z(o4XG9y2^Gz;gdQKYsKAncDla_vOhlEVo1F_%Z#EyFind^oP$`plM)LvhS71KQf44 zN)2>+YYCS(w+c!u1vMbOh=ei#0dOb<1L6A!#|wpVfDDbySkz{EZZ0E?MeNXTZW<&V z(A?VH)#Yyy?%3Q`_W+WnpQymr&Lt#dE1wt-9ll)8pR@N>Ky?bxtOsA8j?fTcr4k|V zBm@)z>N;!cB;p8g)0_WJ*u0bMq#54*>+vo5Ny5xh`$WjAQ!NB`Z_OMkjHI6#49_fJ zY;;gS+0Za0MNVs$SrtDDPw%HjXHKk_K_x67d&IAi9@^}DK&NS{iEQh-`{Rc|HSasz z!eAA7HQEa-KkU^WA)Q{@n93gYwYyqLE@V8~=47%(=!0Ft(i`#XPY5hs!uVwNRy(^-)LUSv?tfn--US831*`S9@nluBVR-$8(&l0anngE@$l0A?Q!(5=g1ZA$%k1d0P%J}5ee#B~}F zn!)vwR>XXb2{F|WD|4fZ%v9M3H^Jv3qoRVRsTDd%Qv9McTCs`G1^|pN$m|BV9-Lw~ zsvBw?w&q3qoy~J)uaN!TFX#uzmgPI%&eSmq_?mt45#@Ai^2Xu7g z228wrtEyvnAu>+20WBdpDYqgI8SG!6b7vIsWP9-RV9>LUxMjhuf>89Tkva{B&5JU5 zo#7_)DT9pStIVA0&f&*4#J3`;V*3oaX*b&~IPHs^HL@<9nZsUTQeE`1);ACe=MW4(*@+3#j~OwBvmaoyYwG@uG;w=xAhT{!r|El z;=QD#L{2_be4v1RB#6H-(@59Pb^an!8izEe={`TW*+ruOPVFjQh z9JHz)<++cDvVQTx`egzkaWqBE`dftb6y$$!%prUzKr2M(vRQ783O{-B!F_q;=!?~J z$nNyVdZpE;T*`CUB73V+$J%E3{Q78OsA0TGyLV(WghBzY&VWq#O}O2E%Y;n~niFvc z^+JMzj=Qt<6#)a!t;4qO`3$m(P?bfFL%U2k%sbyYN1nii@#5yzj`bw@{7?5 zTj%bQJv3+KGO3}`FeiMTe+`)wSohy*xe@P0$I$(}VMEH{6-B=2dElb@(ljqkLyCt!@avByx`)LU623+GDS8vEH@g zYLZ&qaxHIlw6yGn+?+)?-LP&mvA-R3<@?r`_uogD>@sv-`uc61`@tSI-d5mv`t(MF5<~Kr3?=XaktI3)=U%?jfR7-kXs!?h-km#IU{t z%lDY5vuJ%|WB1N6OQv*bE6~M&kcOYA^2=~PcQSWAdNJKMKc1(S!jV0aO#FD3MKQ0) zBH96~gD5<*F{aN8t^nBB6JGLA!r|Dn0t#BCm;0+ly9>-bO2aKCCEv8wY&`^ciXp%r zlEK+Cg{{4pa(RwrqX%1nv_^Pjfx6%K-hVgb#zM%$PBtz2>p;n^_?3XB@^tD{l;Y`M z+d~nta6B!_$_uDf9#~UU-l_ewBp-cFjmF*EwYhYyV#_SxV2SK)yG^~qOc)g_v8wNl zOI1__)?SF|Cu|?165k1@AoX8~`^PP!I7*RwT?nrz^ikX*!+-*9*>fYFU#u4Eodwsp zqqoI+Pmjm*v$>3femKjGN;JJ>0BO-`EN=3>mlduQ4*i^ubV<6_S6I(Jrag0fGs46{ zV$!+$SyE1Tt|O4M^gUK^gXECl3;Ps(-5w1Uksycbkz4FSeahFDd%2$mf=joUg-=UK zmQ3`!vak1V(f1VRJE^Z5MR_I@`)MEdD|i3IL3`2FMDaQO^zkuT?88XOh4_I3wT0T> zK6|8t{puW-wT7~9lZGPtSK%m-KcC0)VjEsHzG<{E8X`g!cO1Z+n^B!oj<4f1(QyiB z>Ps8~ewORrqh3s&bVt9d9}1`A)?q@(f0aS?Bc`L1%xsurc=sbK?vvgfk|-GnI!7s< zU@jptyzHpNW>MnF{^M+bl#(HNb_tiO(##P2qydO7UwaCk5yVLL^XE@4HC<5VasH+Q zT76)67@^02htCOI*I+ULMQj@uqOOzL}ADTGuOkY73eeTVjC(I za*gp)XF#-kKnkw9P5Jp5oUzocrZ7YsuF=C;FuWSF4fmrUBP2=O*@o|rHrVq;HpEY(xW%-C6`-64^7RRB> zro?bxZ2kT5Aj!I4yL4A{#SZZ8+)#qD|aZK_0NV&&wPIeyznInVEwsz-*?ft44QcIUyW zZl_pvcOMg^W3sVv}q;PI)8~-Ov91h*vRlT*LWqX9qNU;+a#SHwKa= zRb_qTB#RxLeE}XjyNyb%PFS8EzT=N^aK_d#9*{hcCI_QM(3~klzmuO{FWr(esrAs- zubEwU+KGeBFlY1Le+~X@-2_&DAZP?pzy+(TM3!bHS=nv!4vlDe*(7&^}iI9l*Imz3S&1;4=y)1HUjY&v)^w~&aj<*X4X`{ z=aQIzs7y1V3uVVJaVS|#$jFCq7)>WWsrMABal_xi3KwN?B&eLS#$EyF-8QgTUql`MFJB0VBV?GWJKbUe%%6s z#i@TPKFO0Z>Ff+FL`kO@Z2#p9U zMIPu7#_}sfvI`2bDskxe7Lxe$-Dtql?A@}D*P=-8Q)kGKei0El^gp4nvgw1WIVV-o z(4Zi5DdO~RjHu2l@e@zM)%-J*u}55Qg2#zVXOKnP7L}yWa|!PPnu;YT_+D9BCLr_N z-ZX#JV11=nMzWp=5C|N1s(tgx=l{4f(`aO!)xJEXw5WvOYqAs7EJf{NO8@Uo;$_i~ z&00%J2BeY}8y%=2+v!!RW~flep*W2SL`DU`o&>5Wc(T-Vusr2pQ2~LG|K`w+g1u_} z2V4%Sh|F}^U%!6ACr^v2z2NI5xniGy=2aHo$~EdX9_j`x@;wXsoM8zakY8Xl%H;&W zAlV73U@55-D;_MEqIpdC(v_@Ke_uoKnf0?SNZ|x!+bRer zsE3BaL*G>j@)WV2=5K@%wEH$Lvf2)7#S4($%Y%hy*-@9?4*qot-xgPGicaS57m#!c=S+=oce zcl%!+S3&C498j2Kl@ZiKNCl3-ItGAYlIR2}rRzC3;WUrXyxZHahTD5od=3f4ixK^_ zZAXQi%ZQ%v|B1hoIZYl|xI>002*#2g8nrzhKBhG@oI2ZXi5_P7CZ}n|-{wk=R-142 zgWT-w+F!EG9Q(goOG393K`BBtw*F+bS0B4Uh&W`Fj4FbTbO%D|nSRRubybVND-wX8QW|_qx$xo`-sP zNnc8=@pwVLAc%IYyg|-NnDpnjjT?7zeTVadMtIIWgsEVWdfY znFj#-`E_IjdoyZ&T=2HY-*(tym=LK`jZvu@o=|{l)N{P&d=g&Dy?W&MherbaqmXn! z4wD4DqJd-S85uoKM}!}-xzAvU$FQEw+VSDKW*I2`mxm?EVB^rfu(0^W24Y~OUVC1OnQW- zH@~%gB8Wb?2Mu0kcq+rQ z3Irx-HZXGMn>J<5KH-svp#sUL2F$q?Pw?rm!O}u4`pxAVwLNmY<2528t&9Wo3EU+c z*X6^>H+UFlPaOXRH=TsV7n`!yE&tF^0cL$U^;K5q*RPQnqz6N+A9HGI2tc{g3$-8e z8+rQ!>$2q~E{AS<-O59fo>#AgKAv4X@_ogU4?lEh{?j!wBIZ%`{IV>Pbd*s+^fSt> z8S*lBwUn`|2?DLvVo6x_dR0#QR-GpH>CF#uAHA^?tmHL);L5Db{2ZW%NN{u)1Pv4$ z&m48uj~}Avzky<+ct$0TXNx6u3tJ^j8Hf1<8_mb>Z{lRqCnOO{pOLupbpS09lqZ6U z2DOhVOay0e|L7pe7yAPS2=nI>Ao^@Rhw<4dJey@bc-nv8e(~7MM0Ae)M}{kyIrWo8 znOn3(Dqr4M2ij$#U$Wdbba35EfcOij3+jO5()!W5u)&2-&uPL3){lwMfhOH^-$!ml z8gHH%pb`i)22->jR5s^+U}a{;cYVt3_Ud1j;fkF>lm^tYOVOEayRgRMN!v<$dq0=R zjSW-D`sROQW;GJlSC<~<0%=!LUEEsc{)V188TutPRvTDY0amp$2?xsp16b*ppL5l8 z{3Q17LLDAp1m)#}c9E%l5ko6!$;rtD!oougH2X?$=mRKAqOVGDb)JT3ZU;|Vq`eXN ztwD1HahOxn(}@u1`R+4@S-ExEU|AL>AO+z9Eo! z3%WQ}-B7>Xp3oXL=HbY)otCPICmrls8SWXC7Lg~6EZHaMp7&?rDy9S08Lb!pM?BjRPl>G9DK(+=XKrV?gCMf1Foru&egUNcN}pgme=ex^pO>0R|U zYY*+K?fn19%=Z>+#N}^p7~fCb1wMN<`+^lVG%$C6En|Dj_zOjo4RtB7|B(f331xh=;n;Y6i)!g@A2Y?d~lO6>RxAI@y#7JCt%- zEUQlNv{KKZBK={mHFG?ongz6WYF8WvTpcIya@6qq3%<(?Z9qmcurScYV#5p%|2$;h zVob^=W@?Sej*h#0lYon!mj3Npbr}!eD3lIG4C7aoOmZp5kx+~%4*hB~N{7B3yG7Kq zdq6v*AbQ9eq1@aHY&?BOM|I4Cn9}>pi|TF4wtlUaP%}yUYxK<;w^_qdjTU1nIFV^U z{Q;ox&J%yI1*f*_*ve*Xc{q00YB$~ih z2{lwo*PkZ7$rhnnU~i*1<1tJWdX?R{EhXw0i^G54( z|7czMeVe6n`?cSc-rf>(K+K3@QlaajGT+#%7wcg%@vZZqVO;@z(T7nY0`6lKo`=Mm ze0eQnDf8{V?aozWE+BY;(Yk9KPKx(HO90vU=!2Z#B{30E!7;O*fdOO~a-X|fNN~6; ztqsN_@-a^u+oN=hJ<*`+@Yb@qJ)VuuWb+5{9RGWupEs$_Lu{ROyPI< zU4O@(wWT(#T~UdB;lr!sHn2)d`Vos_6UBMks8Fsry*`0QtURj(h6Qf!IOnb$Ow+>D z%@EWo-eN8v`U+5=g6unOTj3P>*F%No$}4Zfk|fbHSfwBXKvCb`M}^P+Qw{fDzVWb# zmHM3)j)l`dwIf}d|CT`w2Nx?uD}h}g1pF0{{RxL3z($Cc>Q$1ZSf8IR{xY z1%2(9T`|Oief}L`H!QEy4s^{DQ2q}Tf?|+`#uiF)E;f$HF{dCb_-viimw92wxjDf? z8m^sIoDQO=&wuGIH#bB~8J9bsz4`a{i$LPHPTtBxkpx5?SrbU|N;p4eYh7#Y7oRQH zQLk@q8dOP_?JF$ypE8{^608w|~Ir0_akPi1$N80TdAZ z3710eiOez#KAwr#S=4VhRb#e_zC7SRNwAmo(!;u|RQ=^y*)!=@CxSkC>^&P-+BO1N z9(-cuEF@L!ggVP{7rI_=;ozEa?w-t+k_cNDGB8}yZ8YE0$saxxv|cE^0%GbvA9o>& zA~RCh?ik5r7qI1m)%4IT&OhLUN_8h(re7phsp&QM95m{uuL}@GF%pJ=&m*^>K3P+Z&361^!X?N%I-?qML&6Z@OZ}DgZcm^U(p#Zm zuLt%^CF%?CdV$2SF030NID0Sz`U#+t_2~&$V$q-J-JwFCd7S}FBK#?kZxJ!FC4M^l z6>7IdFykM`t;S6&a+mpu42XJpln6KEBp~P{ykS5=b%0)Mlon5pnm9NBo9Ol|<`#pd zl=&8ZERdvDGILo;88Q$}Z&#qk7}N z&Na;O7s1$kAiPbo#mD@6^*8prRJO8eo|L%Iom~TPp~43YF9TA;mM>@98Qs0^j$aP# z_dm~bOi92FGB!rrSLD?Zck0W5>g+g#I!JA(`xJ9$-TkXHAyc~i5cx2xS*{xuCAFlH zMP-=3gn#4bq5F$zxZf++7KV8@Z$hau1qHPhVDE zuGDVv&NOi|*lPfZTh@Ebjq;p@gP4S)5-^djEkR7(*29Px3i37FN46VVZ}hA-ueb?L zN;zOaWsVj&5@-4lsi68@rhNCMu%ypQekb$vhpK;k1M!)SV<7InDT+}T$rf}^G4wo1vZq2(d+hn&G?h{&9t7@wm@UdQDoywY_ac5(=aYJ$Md zUH!6ue4&1$R&zx7U#M z@YzH;hci&IbUQlH?2Q{0ZGEeD(3owpGn6;W4OhFHpO#5SyHrkgze-7w)n3Ro(8(6xHM{W#tY<k1R@+L$_fY?LP zPz+$Ri*bN)VXuI7Cjb->Mb@D15FdI!0FMMtPkj+v8jI?g;P)rc{P`lxKK;JPp4YFK z7N0RI%|O|;^vLfXMX+~}{_AMq4c>6(z{ZRs!7`8$7S{`Ct*$l`XcIXuRWXACZ5Z~! z>J&1u6*&JI?ndq)rS;>ylQsQmX!L<-@o>jCLSgADW6=w5ci1(AJgGPR0l!;W`A<_z z%M99n%%gU8cfU1PWG*>vv|eRsMP4YHz3>#M3)VnI0oxy<+Yi>HHs*j&Rq2EQ2Zvio zvG$)=4)_7|VC$yYdtmiE$vZ;CZgfEaGBrTh56>;47>juyeD~({MX|MYBIesKzF#Jv zcXha9NR=OS?r$E9Nan^4h6JD{x3&rcC=L-}kbsM;Ts%RP7Pr4x=GJ9%yUC4#8Fu(n zeRrSe&`~Az{_=si>vS?*OV-+Q|9?*a0z<$Svn~4KFLHk~1Ge_nj-h#&D4_MbaY#)b zH*Ac#@PA9180!bl0ILgc*K$KB*~`Lnej8hxC)01pKmhY2UV>`e?0sITV~*1GOXB|JA2Vt8?V7#7>Lpo%{D81EvJvEFM| z{>{TYUjyq(VBZsq*~&x2+G%<`Ioh6>$`F6Z)o&?=;-^#`(9v;mc+GEZ~{OfFcF~| z0avPgSNrIGSpspk7Z@DizD_b8HymAOWZ)Jk4fOPM9BkL1^bEH!)|vE^cFXKgSttuY zpIpv-v(Q;-(D)bHC01{)FY`<^{omV7(aJJ)b8+$TAo9V0AB22SJwXj8u)&8pl%~;q zzT>Qb8mAm=E_3~9;q+IaqOd-V09YOwA=w-eT1XhgU?5IoFlsoXWQ#=U!D-xDLbOCB z8(Pp%UX$|u+qd0qaZVkL@{vtR8ay!v2M6t3yf+GAdB@Jrn4Z0#T@Ig)8nLbNRJS+1 zc$BsbGdrZBK;skac7I{RzxO_M2#NkO^2)+PKx{98J~7U`7=nR|xB@yFAoyxvYjkol z(arL^V$O4A-c!irRlh=#W1=P{9k|FDGHd*$bi)i#2n5+7G%uwjNC)@bjC6dSb<16_ z#NrYc$BniFkg95AlqtcSdrY6{DDT_MMzg=~YE*xFX(#XJ0cQ%Ui{;sb_adk5M{tLFhij$=q%)z%cCk}aQfnLz z0@BsfDLH9kn53ph+e9G4usV=naxuKG!|bg!U`e@#E@&)D)@eGrW|*xkkZMhxI34He zlC`a2+W5;vE7f65F;O!`i=QTIE%<@ag=+Ts*H?cb(XA+j|F`#CkJx_EX7l+=b91Tl z10w|6{V5Cw#V$lJk54!CQD!8_0>7Afh++n#$}CrWod9WXRj_~JLCD94aPLrRAipGFq1)Rc|;rT_@O>g$8z}bljxRXKS>p~{X(7X-{ zQVt!*;Z~M8j%3`5s(0;I?aRtO_6h@%d10EAB~nd-Y!Xz;K}G6u$hrQZcvO`k_=Zka-QQ<##eZ7j8+~}(g z99V(5fM@~sr&b#v9}Tq5J|&A{fHMl(3E|qU##LvjbmWI}|JrfPaQ+!RS>^ z{Su&y%(NEgY3+4&^cT=^fT+U+ID93?_436214A0OAZVnY=xm9ukP1;CoQ*(eRjcf@ zAaYC)T5`~*F|2V+8yDL?JFIEI^>*sJyNcJ;}JhFRf8JW`ie=YTKtDmv_h{`8Z}k zU097R?wX!p2e7^#D|wWa?~IxxBzf~qQG=z-briz%bqmfJP6SiT%FS97hY$!Hn4DDI z^ogkrt+%3BB-VSeX{k!^_e2w;KxuossPsY}G-gV4%Vm3}_OB-=X15w%L}&wwH4U5tLpK$X?#aFAfgsUJ< zFSCA4bXL_3k#X%Io_HuLDG-*#4|GT7Hu=|_`6As%qi<&Q@1Q8l1qtO5xA@*aQ1-l7 zU`l*JvmpA3a;y;e>HjeRzGor6a+eFxI{HD0J6!|{&;a+G<>m0KqIt^@`=@sCdVcZS z8C2-V=RUx5Q=8zqIw}^`66p`pe47=>Gdm5bY)U`w5QoahUh)@n4ARD|mL6R!&r3C=bmk$jY@1*zBns_xafzLoD!-Ny#K}ufkpI?o*!^`yRRn2***wv`u zrD0-cC+=!u30G)v8c26F3KTB5c}PX2Or97$k+t>AhdRoZgLBZ8Na@A6wg9`H@0x>| zw5W!(IBlgMXS&I1yUQpq)s1Qq_rJ|GUL`Hr$+Uc|FgYfK4PjigsVGI6i^V}*ul$>e ze2>!F!$U`Ywujv+tcEBmBjw7Kz}GQvFs9L{2p^yVJglM2s41&&Xz}mPw2grU#{D1( z5O0ERD)cw{-l%*UrA>gH5AA(SJ^Zu%)^>}2p_}J$Aboqbj3PU)^k7c3zghLB$f$V` zB?Hf0l5_UR=CC{p6QWHLl=c$w=T4KZuRz9IU9b)sb11J}hBkBom$2IU4u~)&%wBli zXrO*qlcrL)<#IxgrzC4mCu~aVHFLtR_~^2(MWN@W5EldE)Y9oCg2fvgl&^l%yXq9bE-p>J`i?V^c|ved-B?}yzr45u zZYW=*L9KAr?*wogLdIZ50}o7rlwjT~sJ1|KQ;N~#{22k=G!$uvD^7v51~yIz4&sKk zSFm~}wmL0X+LRNc1z~T4dEn1}8O9^H$@i`L)uum@9PG40Fbu#^vPgJ2h}YvCw>}DK>0+ z^LbGX{nM3JQ>*OWBE>{pT|*9Q8)U3e4uTvFAW?x7gh9VJp6U$p9ui}ljIX=P*mpPC z4loZPsEF`eKu0EyhXq za0GRsTCpkOqdCPWLs<17zk(C`Uh>O$ANt%x%pjm?o`iefKtXcDFv&<-V>BC@h6aImXf8gd6~*5igpUOi2QkN|ZqZTmHN zrvSbK)fn@;CjzhI;~2rh3%~ZW-B%P+Ub0(AR0-GTvAfJDQ;8lWUy|by zgh|cv`VsZaiH5TZTf7Yo|4(9Mq8=<{@DW2WZ^5WGg8shNtc$lhMJa!GC|{`Tt3}n* zdgsSMO$hh3FW8JM(Q#&2b#6XMEiPFq`bgw1-hU~i2hmy3p(KWt8T^1;@8SNvr`MpJ@vRx=GV>1WM9Os2?Np&XC?i%GAWg2X^4}X9Ger=R`j0}XMz&9hf65hd0xHofYrL{kt z8scz}lrXUvruGkKMlc4|2Iv!SJlObDoO{Pl)}I53jff%0K0HtTm5L?riR{&AIIrRe z!;WJ6#A4|v(NWDcBbI`=_?^2Uuk+!`3h=|2J62Yl%NEny;v@Fg(Bu!2Zu?&AKK}gD z==DJ*^C4C8%$l2e5w8m@?cY!D==Cj!t@2M6e)%%*{3XXzxrQ;jyw!MXs>k(Tgb>xg zCp3$!(<;10727!%Upg#nzp!L`H6gL4O{6n}_t^V$Z1Rh*UTY5!U`8s?oT4EnZlSxK@D*9Umuvz0UFca6Mx>4WPc_thZQ* zl!SD45(TQ_kCk7~v~QI|AVM9SX$)vGpiGj9Nv4dF(O^?76QT2a1Sumls4z*x*LtF- zyOq)@g7XKJwg!V0vMnS3tRnT9**K zjcdy_E@TY?>5glzI?d7&IaYMx#|!4SA55>!bx7{|V+#MgLA6RLt|WNHUlM06A5_-~(?N zsBOXQtsy^++^{JyXgycczu3FZmWRH5OYP}!GB=etA9aI4K>s8bH3TJ&4&x3zT6h3G zPMV@P`=EBc1?yfFzp~JL={DzH%uSLzQgn^yyv}YBI z)u+YMH{xQz5l1R3gnIs+VKG?9a>PusrZg<^&KkRu-_bq3mMjHc8k?$gmBgi(SCkIB zPW0BZ4Y)Z|gWTCYYPT{6=$zE<_PfYmFIVZiJv(;Ll_}_r^+r2XF4Go?q=lq&SaeWC z(Eet_R?t~+)U>6DxgtQh6h+?ELv-R!ijk2QocJ1PSut>a28?!TmpLmj{F-0H(kXJJErZ@ISA2&sG}(t|syG zOyV)~#_75Xv-U)5aVEFhpws0}a?E=S#yZAUG9fj{{b>Gu$4UOo4s8U(Fq(@qyX_FhK(PnSAH?pq$|C!8wn-H+wM zg>{vTQY;=APdyu5tKHtD`|V+EEnj0lF)_iGt%H%HfZ4Pi9FsF+VeG=9$*~%Y{L+6A z)<6M*+{AM0nYZ`-f>_?@5U7MFC1H|Pl4it&y+K(ND{Cj*@1SG>Ndn!Y@Ijume!Ju8 zzki>A?!XEpaWNqiYOB9*XX^ks4Y_2FDX#ziLPL|Fm9VtW0G`BP^Nio%?F!=_&*w0o zlMD#l%aV*6Koc_@U2xG&3&iT$?dSg~hvl%cTS-%t$qsYJf?RNaJr9{C(=Jgiw_Izdw=>-bZhNI>_(8Os207;pLOeFon++^ z5SXEG=6}dF{T*U6YBbzE$_^k(wZt#%d6JvfTW0$CbYG@-B>VINVBp{O^?v7TTPkMY zdGJr|DD9WR-$b`1Pu&Z`#>!uRsYN5i#KaoY`DO$z(%5OJcMxH762O-nm$m*YV|q&j zF?jC^$WMMJ+^}A3A(>B?NrHDG;NXWbP$Yj6YX>65`Dt_#LdR>ftW^EUpFDo}{9FtW zC%1z?MrUX)xho0C)`tN*I3OeW(AfA!IbUOTC0s3`6b?$dICD!Kv>!sI8;Sy%I#0Qd?g?u{{ZNJ*!{8M@K9>12N?N znCutB`vMO>Slc2#4S`7b4f4!N$@^%OP0uw{jr0^ZvXY znw%gJARt++iM$cttt^!Ps?M8eiRHaD9sR|tC84*iety*F9KT=fbGKAL_&ETpqDK>D zW8cCS$4|Cwx1@7l)=KQi-dIy%;Fmv2yV-cMYI;&3C-2|$9)I&A=lpmjV?|au=TjMw zmTLHB?6-USSw0E+y>;}+&u?m&HxL3#qyzumqv?j;!Fb@%BVC+nyHj+-hGD*406|xK zbiS75q=6{@>~M{5iafQ<4I<>xr|MjdLZ!nqh{Gtti?Q4f7Q~;-3>vefm0=lL2O~D; zv@Lq=Qg#W!L!Bfs-lH&7-`d>V3?+MmpTFD5+I$UHlpF-*F7|QIabqt<($JCQSj_mR zSba>vH&o7Cff)GDzbkg!fBp5gSf!+SPzehcT_w}?qqYlDC@WFcr<7TZX3UhYXecU; z=&!rBvDvC>dOam3>!qSXVyc5EPjnA0Ef>@e00-y0i;j|f7OB0idx6$fdiursBUMlN zU+@M8#w9Zn-qm&B1Ho=2`_cYBx;Z|fIN<41oexcrq$+d-wL~y-gNx^iEpt(dKhB0t z8!)Dvy91|w8$X30m(L37w7?sU&C0vt<;GI6<0=`8v1HT?$x;|86c-nR*CY7-dwy7i zAOIn>gZ4Gu-Lmo>FIIogrJAIbI=6g;oIaza6iNaYB8Lb&Ge)mEFHlV&) zz&AYy)$DW}Pzo9Owy!w_DXinb+DBokFYH@ubt}E_n`(jn00BFXy0ZS)WnmGKU!v8SEdQaqj?ij%r6?bx#Rh2Rih{yg0la!rVch{9uTJ-i;K z5K$W2&l(R6=i#-HyLYDIZ#=nw@+!`n98y8C(Lgxl zoXtVU7wg0et{}MiS2_b*(uNzXY9>PsYIAq`?6Z34i%UxpT$QDNT8_xxkciTp2gw2E zx;<|83=$o;p&J-Jd^7OaqVGIe3=1S(6%XY7wrFo^8_ceVy(*8z$d+x^PmwTyUCYEOM(ut(_t`^Vumy?r(FY$F{ zEu@Jmdt<_SLN*WP#-ye1lTfEogE7u+Y1eML#h-?v_~~N=NwJD6N|K|3%aB`=hanQ$ z$VHXIOYWtl*#{1ClNh&?#f8x0hlz$qk=aV5DJI>Kw+keE@!#YBus|i}-=5~cxGl!l zDrh?L+FCL|r&sSGN*a8a3eUf1{t~v0u1{Q#a35r`Six_I3hLoPSxN>oZdh*xs;f&#_^{!zUroH-m|p^Ip3mMb>UYeZ)TlQ`2_@`uVawEQm&(zy!y9L{)^~ z;}aa$Nc;nN!2m@Txr*{VSxA_Mx#`PaZ|4${ckMSnnEj3o(v|!PUJMXXl4+oiN0a*%UR$w!`C zKx1kb)bE8=RSAKbWBI^;s?s5D`Hiz`bGW;FKd7XFjy})ML;OW|7y*stx)j*64fziu zrs!W`GqU%?G5M3g(Q?N}>+}Nir$C+__RqK*2S-N)U9SVea#)Pzi-cZZZgKz>hg6LD zMDZ>1u~2Sc)S%!L?pi?W^UIcH*?Uy`a2msVV|wdqkof4N`fwF&kMhB4L#)w?1-DuQ zymy5*!Ttqzw(G=?A4UM44m?AW(Id0>%y}zf5?pVFciDX(!Nw}_N@1y{14Zza7Z!A1 zR&XA?W-XIa)Rm;qR`#+Jdu&`o#1T^ATiz{1GcD8laxWuP8zn7mt>aX2^#z^rh~9I; zL}On!V*UBE#r?GUkEn9)Z}r%?5{>8n=@;zD?%nluV6SAIXOFWPuF z{mHyf+St>v%DwQlT-sD^RTaxrPp;}EG=Nh-S)4dwPsAnbVTc539(zcs8rl^Isbz2y z7YBUJj=k7kDs8f*Ds$OorHMkezAqN7t{#xyP{ROCux0aZh05Q5{UU&g8cve(qwPnO zt+SQ$moi$DnmarKgY0A5QtiL2JRODu)1cm)`eeOFp7Japr_4TpLCpBXQXyhfzVmSn zMq!2wgmQ>S_Vz2PxpSHkdcf%Nq_#uladk`bR=Ss`=NWU<*fbv2t8vmiiw5KTB zsteJ!Fl&EdVN3{cPj>XYXIgcJe)XRqu`O!2NFiCT@UrF(1ahmSb;J zhr5=Gg-Mr?Qk>rt%qkA2obMLYuG(i?n7Y5Mef`Dab5rhXI1^jNv%cAn{5EQeU2 zYVjRvn6T{9ME=j}24Ov4Y=xuZ^o>NQ02ljg5n{7VD$M!15!fK|c_`nj3vZ>MY zjM^pbK`hpcn94so+*pcV^-()E{_nU~ z{sV+x0+Y-*U64gM6Oz4W3&znGVZ8}?0ehad;S9nI**aWFy>G3$7B@_BaBxsW40Yc! z8jel1$FfwiR!_2`s;~4+a50s&A08gYmx%aDYF8lWi2@*q=cT-aEV$4h=?wf}WQ6}I ztDdxZ@QHIoH~H=;@Cnde({M%OlOnaiVEmOJgwrPI|7!t8458tT@a7bB9}vE`q19FS zyXZZ+q9Zi)Jci)n}j9xFS;RIjrA^m+tggI>k4x%3KYt&m`!U z?@!*r%oiwY;SBJnVVEos*p~aJfr;&ZrdVLrZDrWfK)E6_M3UFtK2G#5aHhMVZw=IQ$}WyauW_Pm|_ z(b0YW3EQM#MfS2R)k)uxgnyJvzzQ1-j_?oso?97O5t|n0v&ytwlVw(_x!onoA)({OA;=?(}Q;AcW=_Ys;7K%o0-YU)7%Kv7a# zX2!<#D-69K>)2R_6w4mKT(n|%Tkaqu$x5OT>o#gQblimDG#Rp30N1fye>fM z52yya;4ybCPh4P2Gg#Rs-1HnZY_kKi-eyXkbnV&7WpK^PppBKU9-^`Lk^0-R@2pYD zc?hvOy04@i{R?RbbKWsM#_tF33;EMmVyarIUcIU#{uZ(9R(HzRLR_(6qDj9X$f-x| zn`a4?#%Igag6B6S%PqXrPD*mHM>V0x=iUA{F^+>05XxLJ@9UG86 zB=mjnlkkwo*(XI2QoOdm-Z5yKf||rTjcP+IjY=BR=&kXm_0E5KTm#j-=OCyDV<3b| z44B#hGi+?k-6;9)A?(KRd1H9#kqKB1W&5aFgbX}S+D5&eDuew2rkMrMa4%yDJd=B`L6;vW)6=y$fxorY?g1$)P+%AZi2u`J^FM$7gtBTx zIDy0ySSL%yrSr(95BJ29DaC|^Lol%fU<&>UK_svve_fs#9R=yE;M9FE3KudM%5x)K zo`}<9&h3y8Y@qm}^~%T|)-k;EJ>1AJq4C@@515669)z6E{QWbc&HkYs5fAUKGUL=K7Rvn)%Q0!N05%i{nWt6R{G&+g9p(V{GOY;~BHq7GrJ4M&T z;4cE$3mYXq#x?^7ZU=z0ph@tW^m_5l(jU6(l~@yHn$iB(kpy-HIhUsp4Gs1fUm$!) zluY3*u>YBMUYB}!1LC^jot@7(14WuEl%WEpW(9&_NmtPBfCwHo2zQk)FDzD5a?+;N zjsrL=?EyOj4b2rS5DJnGqQKi5)w=sHZ_m{GO%Ji4DK4s}d2AwX!3@lS{4i)Q#WHi%KQ_RI}o*D$<`yd(?kxh^D|nY*B_pFk+`G zOyZW5OmG_4Y@6>?NOjvIllCjxKL#4+7)r}ZF*RoJNqw6&o(SaU+794k{&)Au+u7{D zYn>bWu_`ps71O98#l(iZ=o>VwSakgnO49bD|tjfrF;@; zU+k_u6G0i z0b{(>)1LQP@KbZF=*RtKNlI0L?w?48!|2NEqeQFQ63=ERyFx7SQs{-p4ndr$|IP#C zp>P;Ny9>bT7)}o`?m~lhX81HwA=!x$sTTwh9T-Xo${aBvBjA<7u)Xl<+=Uq&;3YWF zzg~Nt&jD_~d&9{jtZd*^X=l@TLI?}2#*eO4tp*wBy!O33KiUz5Y$HHXx*z}%o+ZHd zp^_#7jz8-JppoL-zn#99kb{Q;aIiSc`3_}w7tAxgmW)D1MnohP=6#gNu1|<)lzPyA zR(QW8@e2c5A#LLp-ysisQss8@dN=z?T?GDrU@o|#ICq*EkPEtcXV#k&l@Et_?s0UQP4c}{bvQ?fsr4yMO{~M;8(m7_(mi%qQ{6$i>Fp19NP6y zrJTc?Kp@dwCnX}sCjLdq_WIvLZzcQjYueVh;x@BG&l9zNxIPNjSMV`9p|suSg}Kd+bh^3+15CDeO{msIHUbd$B!a4ST< zpROzpq#DaU+fN`2AaPdm7%U87~Sfsfvbq zu~sCa)bNcWczD{ujR@B?q{@jgmUVV&omhj*9)1>&{Qb>pBx7P?M!>U8m6~^Oc)auI z%HMx2q06$?e~*_F`PZhkETj}_U;zevmm)NIZ6+mj^(PZf?jRxN*fECOF&2v|ypt+q}WzWpPn zZVkBrHli@{>a;X-lG4}fzbV4Ar5zR*7qNEZO>X=??Tn#mzjDnXl}6yKUYd3jux2W% zs@b5^Cm@0S;+UhwnW#}%?eNDz=Y4tk9LTG0fR1|d5J(Fk^z6Re-~U%oOzDoJrcViY zVHS9z!0n5AGHup7WG+>#JsyajmY5Om9%$`y{T?#jSzI!it}6YJ13|*Z%UklSvisXO zp_7Z4sWe(p<6&OMbnsf|TKW3Z2zrr%8i&fKiae>no~UYih-^-Oj`{IQLf@IctNkmp z4rTGRYdA0T>Y!Zg1$LWLRlAD-d2e=%X3QH|QsaMn8CZi^x5LaHPWSy`Qzg40Mg7j^ zbI#s9eaigUJs*unxtbX(Immx96JJ*A-wt7Act|FyIUE9|XESiZbH`YQF}{a}R{+fU z+-!-Fktyrf*Yw92-Am}+i(K6C6F)cGPViXz?y&1tS=XfZIxS7CuL;7u;CU-U3Nc>g z6X(9RAF^ML-$=q=4$k^{h<0owrPNTFo3T4-%=ytzMA0aB-85RIPnwBM<{MRR=zcr; zRyg6%+Un|ENQZ=v7H&iMBtibxS)&F+AzVx!K7Qm7m;ED>xFN{L$DFF+$SEdof>-kn zH#ISgvt@McD`2?!2z-prf=nr}z#dX)F%BQVAK`U8jS3-vz3{vKOyFp+&3O2r=qa+98&@@ z6mar!NoiM31+TQ(DY;q(hQW!G#jNHmGfXt!2Z+b|Yg@6Y*&=%>Wp zmP4}mY%C8?CWnH;;rRiX^irt#60hg09hp$p3RnaO4gRe)uhd*1gi}dgn?DoiWAvE` zhggNG=Y9D0nwl|^j}E4g=l{Ikjyl3gv8v+V^N8#X5nWB*f-1=Fq-Kb z8*?2BG$R#{pb#(G%6UpNHtCL?{*T|-3Je8LYbKR)Mj*L0307BdrL^u#jJ zET13iH%w=E6Y|4G9;m)|gT&uxj8Jt2G>=9kpHlKaT3D-p^Hs|#ZED!GfVnxjtDQF@ zF>9Ke3pvi~<$HK9(_SUVwxX;jk?nhp?F#QiL`hJz^o+^~Zll1u;qK|29;KfIXR>-$ zF?^U%NO<)q<$z&I(BZG!OUxw#vRZ7_K?0uMCxzaw&98@O+2*5>7+At>DT%4Np=qi* zfh+C5Z4jHa6MRY4mEk3LA!)l5yz-j#xls43o1>w-`^*S*Hkz7>M88*q^k87?h~SLe z_^qS+vc~tt`I{$pz5hiu&Djwj!SsT8s$5-3;b4a?l;$@%Z-U_qAqL7#vruG)I^444F37q7o zxG~qX^qjceSeHx_LeS@Ck8M#eW9DGML0d5Prib)R|#wVv;WMMxMA3E_PcBk*P|^T^)g<3FEg3%hD3j zpt6Kt21a#^P!NWA8+f^#zkOQNJ4{;cXI2PTJD$#c{7+Oa+Q-aU=(d!A6$@-azXr_O z_p~>-(M0i*tR*oM*X^=oE31A$E`;*&xbTBFZ^!};X6P*9OsdBh9Ic6NmzLvQ3|$)D zz4s{+Kfgvq64@T{W3^Omlilw3ggds!m%Jj$gx@wDT~pydf1OCKE7RBp#&oHTyRBOK zHE2%nwM_WZuZ8z@u=Yvt5D(1_Elfz&;L#8l%v;w&dDTEn z;nt2UkV-kjo12^E>MG|8fq6s5_wUcSH&l0pw9yTLr1p$_&Pm|TIK2`NkVXbnP@;_wP7`jelaQudKc8{MKvy z8@;Zmb61tm<^pcHCVa0upL|mm7_?>|+k{MtsYA#ickGhLW#v?vWhwWTeRQU%*0QLp z@SnsAck#zkiT}o)y^)hs$@d8a-AuWd-wlP+x%Ft&D$RR3CZ>rc&P$!p{gaS;KW zs}`SuH*T3#XC`ffn6NaTJC>^Z+XH8`KAY2I&N1WJXY|ef!#+n3Vxp7Y`Dvfcf!}_k zx#25<%xF1oSs@GEFvUthrPT;4rHeSdlasLd3=E>C>v4nDlRJ1D<6I-7%AZ!U1|3%l zeZC$PnUJn$(pOUc*0Ql{bf3u7*x=#H=Bfhe$SW^g&L8a3D{y)CSK00ONYxPR7-o9eGTspdTK^t z^_9_RkK?uK+*gCFWMH$zY6DfYSe0gEX_)(*wOLr0O@A zf{s}rG{g1sA`mR9FvrKJU6Faoe8)e^G9|C5NX55r>4Lr&6doS{&u=k%@BrVc-f70# zpKb4;k@4#t=dZ^K3*Mgr!;gVWkL<@4X69SdcfMF(3CK?3n)gcal&PGP|2pp)S?AHk z&>XmSel**SF>E%aP&B-+Ojdh`pnaWy@yz<&b?4kRn3Q`wqWNz~b^j2F`huQ_UB0S6 zKLh0>;3qo`M*unk?p!-=3QywZiW>uVCk&_{07yH`3j^jP{nk_c2@j-K-80e8>7!5x z%r*mgB-EYDmLI5^{Xs5;X)(coQ9uTSJ__z|I5`>IVgu$E$+nKe@SXn70cU$9{@J~= zi_7*U=d_)<&(C})cpvIBVuNg;h}E#9>W5WFBMX8g$|CHz*V#o3p_#%WoG_CAZJD*a zva;j%YFFC>d=QTU$f4>Rkb&@n)p6(S#3MMHqbx-ijqz*1B{HB~6VIPACK*TRm5qKZ|CJ83;)6HZA| zq`UGSTY*s(DeynfJFNEngW0glLMqYyj@U1>hG?YDVwNT?uJGwHRE@d;XRW2HyWWof z$-1(X$J^T*l-t*$uAYZm@d6@<^hg4)6ewOEIXe?za{gf)0P~>Im2`7>d{*h?S@(B4 z)o|4%j!F5Pm70GL9({eXk^Z6`2pX(vJ=!`KrGs)@=htyeo6@NszN>*`go(?X6V7TAiO;)#Dc)w4ddjT|jaB*J@CSW9 z^6%%f4IXG706Q6Al$Oqcd)^?g2eU?^(gVCXHnw=ddLHyPk+ISe%_s;KVHUcSgPys0`Q+-+?zg?( z!U(Q3eq{sSp5y_Nn?ZOP1CQb5D<~_|^zDF6P+6FZ`z}+!_7x1xRum*_BPx&l&h;@W z#Z4w(sGw6Z^Pgp(oq$lai;+<$1aZwgzYGk3RQcl{l|f-(vV*M zYK^bVemGiWo)RGKfBqp%(&4&zAs3+6;C)g6-E+x!_pc5K!=w%dW5y^+Lj50v6Ykd5 z`D)@4!g;WXS5s0(_0)l|tu`;SeO-uVt z2%RlQ4?-89zAn~Jep@fnM<(70z3b6R;(9NBSAkKJ6#oYpTcAwDH6$@f!S~mBU7}|w z%qWmNVGW5>&Vs1sm|cfRf$uKjkTH&b^Q9&Lvp_}e-tW=oOxEiPCX7vX61^dR&*7Ud zi|k1Nmz{;KD$JnW$?pwny$)=i`ljtBY|jWUvmikyfaV8qX<{Eq37;{s?Oke*& zaCTu@&YaE>%zCV4h>%`E~52;#R#}&m1irq#JSPF6$7emx~u|H-uqhF`L z`={`+fXDCX+$d3EzmNA0ZQdtl7w>Li6lS%xDPFH!8=V+;uxekaY@VT?) zkBTyJ^Ybf%O*yiQY3$0^6$sdSvwT_O+ru5u!A~mFN&53QW#qFr6(C5`-?Y%p$j!)* zfA*}>YHhf~X~|%mmxrgisi*oQJMZ3@s!XNWRt#$6KKon$L~9lj9+HSP_z_gCbNief zRTrvdvLQK7AUm}aZn^D~m0SWHSDg{X^BateDloCr(a{mg1f1Ym{{pYI=uod$!iYlM zq;TpEJZ(5c8BOWCR4qUE*%{*(!MAq2^8CWSq%_)RHqe*?DMTJ`Uyr!{F|hLDX5nhw z0Lc$(;*9SU_|7`o+EH;*sTy{)nbJs(G=@~N+J`%S%^_)xusOhFC8UMU7dI4t4ys8Y zTtN6<6I}=ab5oo9Tb_Uf5%Cl~H>^o{E#af?=p7+) znel>iJZ?0EccQg+PLY;N8ygc>hZJ}GCSu3&hN^DEopEv8Er*ZLkYpH)o^u~MmY=C| z!Q0+TeO`p1#Y3z-g(!Wc5xd^BCpbUD@CLqpn_C{pRIo0XqIdU9-_lk(>F+kX&lop& z1lT?MKiM__Kyn7u?A@iZ)odE_T0;Q%iTpKeBN$NK3R6xS_PQ_B7yPZKZM1 z`JQu_@x$VEzdiZN5>oCxY5CV(nKS}5lP+{N#KeZ;C{y%MvFwe3XU%GqJ`B4~`5?~6 zG}B<}86ctda%OJ^m&}6Ey&%>&sK=cf#MUoYcWm(oNS9ay?<&T$LOftRqs({yTQ;^o zcGn?*p$%kjRf1)&&FuXTphG?TD`)9x&DW(@DjsN$E`^C%K@eg^KGIQr*a5OHVLkgCy9F;Z|>W(K1mA! z^Wf(Qd^Db4P>Xx^(+XprHQU5SqkenZN1d@BJS za`h~RMgt3@um_z{VJ8-N4DtrZ!HgW@4i@?9(RMrzth=kBS;3)QuOD?cu=IB4Od;r> zpUI3cT8G|T$=&f`is^(@z#WK}C@3kx1D(i12B`Dy{^$N__FO3U{I}9&LY0h)<$4=$ z<6Tq4sW>TK9uz1B=+IV3|H^1@O?j)H%NzZAEld%P__udTCDjEpE(iB`2;Nw7TKp=D z_r&NzA>eB7PL2}KtnuKs5v6i+7_Z#RpzdFJ6V#AI10e>sALG%$FazQ*u|42PZYzCxU@(=bvO>%bHdU+>DHjw8= z)FF8WcW~FR)5nGS)^mQH?AshajfvTM|CWUQE1ghj9>RDe1}-PY#+ae^2G*H1PdYf~ zMh4osI0>iZJ|&Q^xHo*2+_cxB>;3xmT7WDQsDzKse--2`o(MCI+{uf4|HBCDuXrX20h=*9HHqE9=yH`IiWlh|W!d-6UpkBWz*g99Gs{%@b(Zkd1`pz^prfOzHf z%)A;%Fc^A%JHz9aFq8b||7!ujaf#)fG3FwkX{AC>N2kC?t;m`;8;9lK_q}hyG&If=qsJk z9#gHTFDvLctv;J%I`>JIvr^lSWY^b2Ml&b5iO4g1)_9x((r1YdO#O2Gp5RAx9A~zk z&_ns__45#0I2)j16cp2-C0S@VDL)7}EchP>F;DLv#v&C^5YdTR2V~)XnNf|JUFAnc z#@{7;Jgtm`|IP26z)8c2nE3RgU&IaB^Kwd+53!40xSs^_l^deu8XAS_c{D97kZXVX{9(ELM$Oae*XiZHNdR<{u4i{Kny>>!c*y0O6ri$@_GB_YN`r6wb#LlbwU{+Gj zJradCSY? zo3!C0O(J}eHHklbfAL5El3og7fM@Fv(B3Ewu2veUT66$`k&(ylzgAFO&`A;`1iuF+ z-URH%}le0>v@90ewZ-ZAH-{TdEzp{0L#zT(^bG@sT!hC4eTnuPZcetGA8 z$=5vBW=@qn2o|nW?I{zpXIXxIsMS^@`|`&s50J|^W%wTm%6m6@QTP4EZROrFaGetPLBLVy_r}B<%9$NkoT+dLC3xxfeDJnwt=y#4_0ZXU+O62 zChPR7vrDpTjvw?i@Kg@K9Bjfzo#d z;Xylu00**1uu1AYWF(Y2QzXd`=BUG=BdsVmG~%DRg=D#5{n2r*zppQpCWLpL0mT}@ zf>B_Dk~x*3@APh~vy&4!AMNgqVfH-n91v`9CSS+2&g~6I=mYc%pIQM-01%b}MyU{p z6YH423lIy`>_G50R8NJ1gB|o)n2;Eda{-eIEK=L}I5j5R8S2a73SWS=9g?~`7ZzCI zcVTqO@L<7P04hk>BFNyd!&LLgosY_e0l5dH6=Y$AVLt?zKjjc={W`9*#1NjCK6vn* z;caQ7nafK`3fkl+HIts2-FqMM6Swi-{rK?%!ON=%-n7>tUuL;)euK%+coLd>O~8iC zn%EY>6ch=**l1}ynS8|o7jXiC9Y6~(Q8H<*XB@DP6P>!HYYeR0SlW$x1t<#hjyOAO>Rs$MXQiA0js}FTP!Xo8*<+ayW1E8R zMV*4&VRM$HD0j16YtsB7M`_J6C$jx4+=P5->5GG}@)c(QSd&VodL{Hwk?sxVzB>zHn+kI;)diy>ZblkD(9Mw8eLzA& zVy|CMi(H0{3EqbS+Ls`~hg_nCpH*N)lE%m+V5~^cD8wA%z#&RMzhHm|0;XY1J~rSw z5I7P6x=VJ%;X{XC1Go&P zffW-L4*v^WVsqfrz@T&6x|jR9;1anGI`o(D_`|!^2Emj;^|iGChQqE;0P~`PDemF@ zF(hRe!4p4><#KS47`~7gC_~tRWU2med=gn&3So_WkcS$k{6@1OS;($hSZC|Uyeo6I z&f;Rc95^LeN!syd2W7NdPX?Z02n>)id^vQzH=`sFaWh1s-Ji}a{+Elmd`u@1E9{4F zfIU!!SOgfJJI`c;&OU`B7fvZ3+);8wQjXv@yKQW2P=@Cxh8$+jp8W^p5eV@x`FHH( zWY=>exZ#;cM@5Fl$!T#MeOMNX-!R~qJFhNh2nS7T8z7`;on|qm|FTe+ED?;hQ;OKH zPh9z(-x(*ImEcAL=;@!-~5Y`I`s`6;hZc(`U-f?Cx3-nIan6dUTuqdO&v=V=hQR?vsPmwG4aXB zOR;rYQNKY$WYgO19|eis*@Kpq69mjPs$Re#IXbF0B|{tzDB;@SdspNC2pSh^7;eHn z5Cb3W=A6_z0muyrck+nb!gNQ~5;jcgXKe)pQZigCrl-K;O1(s~1B3^Qy< zgmu+HIUlWx;shq%0YkcyEg38~*ykwfp=DkFRbl32SQw$tPac}O@IGe_Jcc?V{Gr3N zhe1(EN#p_N2NNKp0OYar&mSK6;$0>QGTVOC`QRvTFh@;sf82UWB1;;T4Z@{P@TR}` zhGrMUK+}LR0mt2PwyWuD8Manw@i`o%zXXL@7nnv3NG#a~RWar(+5J}2AL5!%oC0di zw&&z#++&kRz>Is6Twz-SxEGWb`W6=aO$;ZYLGB+@rxY1=qVq7(y$Z-t0(pHV7{a50 z1O%ZDonOYMh{)&O>Dy7wN{60H&UhosUpl_2IL8t^?1qS7%q;=)t(C}gJpCV9J^yY| zehiTL02FLW)r5$`b4X!dfO=VZNd^^X=Q6brx#)(fhjdDRn7Cb3iKK2vZhN!??gs|q zD5VA5%ttBH>Zcs%OHs+T!?ziT-8OHKaU^UzLm#m(4p0T8QA(n%TaX{iPTu=#6_hBf zNWrv`!ig5R+JT(c_VkqVkjUM71~Y7!`IZkPeBMw5M-jwpVIXd<+yK@rzAsj{?D?q* zdZgv=*~JTd&_u5OSyk}e=e~Hm%<;XbHcuJ?hkibtQSj3C;#41XQ4T9qVE1|YM&y+s zO4=OQYm-i)ecV%^v#V%h^Bq2_Ne?})Y1h|}x>HB}^II6gJUyI);jXP6PWPX9a2}7{ z)%%o?)>KzVoLQxPFD2DE#T#g*>ta`&qm&JKU$WAT`GlN(Z#`gTXTWF8^{CcSukAT& zgdR2sNhh=(*!K@9{x&%17#kHOk- zXo6gE>8nt$;hexU9?bYI5`nh_6q=YB#Mk!*#tjO1I#lXzFLV;jA0($DWjYip zO~@<&IAy%Z$<2*`@3=rUei&w0I9?$#NY~{L*yg~?f^nf!e1|Lx6bcjA0e%RE?S@d^ zb-!r8{}~&eTjDnkJpNTvgq;9-rvcP< zp40XV1W$dtBzCOKfM0k8{9cNh7ABUfv0X3ww)7jd=px9pZ@?poX7fq z64S7IzCFSx0shnE{rHv<_r#*CaZ1NKyf>N|%!;u|y$*y+_SBS=k$Sw%G3PvDr(`I3 zb5qk^`bJidl1r1&WgE~zflDyIl=kUm$02%4bss@`g@5n5{eStTb)M9H36yN{0trIt zz`fTr)q#1--#uquQ^>9LgKz6`M$OC6Od6X@rtduuVa zeAdKBS42WuN;H0-2K$6^>L30T4ZT5Yid5B z=dDqjR0({xLrU^py6@=30zCK>z&IWv`)WoNRG6?v!t)D#Y)EP3?zOGfOIaAEcR*Wa zq3qhK5Ph3_Z8|wVX`SMpY`9O3U z@>FbAeA}%UnRjHStdDuez!nC_9ZaNotzfRsl{3_*q@<>P{C@QOp6l;Qy!iC~FcbB{UqO69wEWf*lWf8cW4xYYmhA_yN5anHtW(mwI+jg#zMD=$DS{r>E;Lvp!Ig3+_Q zpzmQcGnLC*Z`zJ6zlJ@TbF$XuvE68acX7nEJz=^X@KmL?3=AA1Mk11H(oyevC~e(* zZ<^$oQ>*9nX1^^NzK+$+N@POx9v>0Cr9_akk-}zxWWX90xzy{BYH6ve_!2X^0wW$( zWs)Qy9H6@gU91>B61?`M45>d&e)U9!4x3d%d=wWg?wVUupVWY1DgI!0CIhW|5KHr; z5SkqykQ2tjy$e!v2P+%*P9K^1C&Xb2zVPmC1NmrC95XGq;5&p{hvK3UwEPO=P4Yp* z97}Pq#O+&g(qBYB?AyS*EH-|JNWk<~?dr)^95pr*rNQ*|^k<%kT_tK|eLZNl2NM=p zFXk~C-m1n%d|+rG$r9rs!wv!WS}bsS5Q?UpT-DDnE)~kr>VS0FSNP#>*1)QG{??v7 zxmU|~qnAQx5|i>r-3}^ui2Sf@35Wtt6FfWl$2Yt3)!Sv((8^rXCon^Y;@<3;yVxg} zjI*s&;xjVB;H^{(*e@QQEztPxuZ}p=2!eoZEKqm)7d|7h7yNgstUi15;0FqA7iva-!Vj|YE z^#358{Nb@ZL%ctwLTVtu$p9GMw~R}4wI@uF+9*Mvz*4LH*)bmFHe`3qK%G(srO24E zz_=?oRv~B?tqzjzxU{U$8vPv+8#%jA2ZJ|*w5er{d*9uXlHwjrgHT9V_L_bHeu~4Z z*Ybp!MY$ZjcAUxFm4Tn%zP$!+gfCWl(~4UXwQ}S@c5Eq6>20eKqmZiS#oQ z1!)S#x2?gSu93<-zrS$&m^AbJVf&9c1(0JZo(q+iS2!^v-oDs#`1!BvcG5e_#@o7& zmOIP;dp0vC9q#Y5Mcbk)qZmKaX=%&gXEfMLnsl>Gbh$br$I57*F#0E?rvMKM=$5=b zB?g?knq1$Z=D-NX!?rcgXlz&Es$dktROMFH^%gj$9wODjhL4FsIXtYZ5YYcQGjl<9 zbWA6&9J_k48a5IGB-p^Nt+%HqL~IK8J9GJW*eRzm6@kje7ia0J@%?2VZ|`kTf1qGO z27CgPx(c^$eEs{Y9_&y%&>CAF%)Vs|G!iUX>0#C@`q!HO_%sRnS*x_9a|f(>-d0Xm zzQ0^BLfHBQd`XnbUqI1##r8u3W})h4dd_!44bqE5quFws*i};hBjGWZ=OTe|C!%{X z7-BoYPTKFGo%|cr=3wg&PsMRGhj$?ad^{lf20aQsR04Jt=LYe#sHQf%9~kMLj2q$| zUoweeV>!^0?6*HXQJ_L77+6>kmHmi@r$I|g3--H5Zf<0t_rOFU0`Rien0sdKM6u*> z<1dbRzKgRnX0Z{lXbi>JH8Foa5Y=?Khd)C#Cikk$mSih@k>>gPUlWI~)ZS!p@;h6>I#3vkXds+sAX{lkc4Wum!9$HPbYGKssz_1SoTKL>8y*pHqtsNB>#84WKd~QT zhdk@?Z)UuvOfs&uHCoaq73gDQgAFHYj@9J6bMU%h_0^6gcZ?V8_}_XZ#vT9!0)`Xs zu)bp4=VJj;Mbtwe#c&uC_s!tqF4^v(qZOiTz*)OzLjdO5tps+bF&%uy` zF@N0S2?KKoyh1Fnr-On53FEX|*~1Ycd@+g7@j1 zcms3A6(&g+jH)4rA22p0Zz29`8Xpom5uWRNC&X{DmOQMIanIpT1n&w}VFfthuH2>Z z4}y?)z)$d&!079%OQ!_>9*DnzOP&UBE%14K0=IY3d$9JwTpPh5V@_WB=ciPY zpSvkodI@l_Fx}UZ+8KWfU@?kDp_d8`jHm$Mz~G0FjPMGxeM2QBq$Yy%VSv5>gB^pX zszZ%}mZ*vI%FV~H7eiM;H`r;ca56x92_qCf0Rg7JeY|?+9E#bY_4V>WUlm_%FIh#3 zzo=!J!1u+Sw)KPP<}W?z(0p_kmbIdU(45tSlUvDwal~u@)q$f)KK`-N-$E`pVoc3P z+A8w*ZvT~28@oQtNw#IY8%K;Lml+B&HOc##E zEcpX4@r&ss1Q69WE9JcOJnTKWH+_nD)$jI0s>MZBAt>7NGcuDt)!$9 z(p>@~4V#v35J^etlv1Pwq@)Bz8U>`jXPx`~XU@!>IdhM~-fO+@^Zc^&%}?6(on+2~ zS_yL5YlFg5@%?EJkMhJ=`0s$d7?3MuL>-YhRe3t>WaP$k`&>syz)KADEHAlL+zT*B zPN=o73`0s&Z7q3rz{N?{h~}iqd=iK)#|`w6b2^@m;_+X@gBx1XrCPoZ!S!hdCdlV` zT8*jF#GV`duTK-ip3$mGFaF%xLO_Fy-y;`<5qUXKm5z|Wu=~R;h!@$*U~I>qHmoGI zL}3Kb5};osM9(>OHGJ0cFeW4%#IO0G=qQxc*o$}e!eOrxRAdLuW;XzF6s;EUn85KI zg3<33Bo~&yU=2hb5E;m+8QQQ4CbzC-m;0G7xfyPOjkyaz^sl+%Abf*A@EKPaK^n6Qy|!J7tTE|eu#n6y{06ZNbMEV4Cjc-c9NCj_W{{>n1) z6Er!;SuOO|*48l8*YK!a*WrMy#{U2c2DXzyh^Zk=(%zo@ZqIC4o12RcO(Q_kAmC%F z3&>HG~%gG+al)8*aJ_KkZ5-p zPbv#Z#=ouOEJ9F&ta&k=-5OhHUk%I{pr-7EOA^HUZkeRyMsZV%n{5Pd*1d^%KqfR? zSYYSqm=82rSdDp# z{4+Ghf)HP$SJ^LahJ6+>m?>`6bw|^hNMGMpcnZBUoI)EaCxX zha#6ll?j?ezr8;I#<&Eby)c}^?CiVOOX+!b%!e?*B{mk7ZZL^jJ1R*@aS~pK?L?%SHr>Fb(Amh$0@#7Ch`d3 zdG%MCoD-0uSpO{ExL+Cm)1WW+F|D)SP8qZRS8( z_X0w?5Tzj8!l1V1S88_?riCJ|p38qGmjqD%9T2^@xA#tr=wzWLI4V1H?)E@tAXs|^ zdhfn)bG?mHSlK!xG`%BbY9+^{>pUne^_ZNkF@cYxU%D-?;=Aj)Eg?5iClDP!z4X=T zboF%1*4K#KX;jTSzFjHqjam&>Gu0J%IywEl>j^L0asMBB4y^oKrZ0b@ucqQZQfR%e zXIFUdT?ix1%}@~ADdfi=Xtz}y#b5>nzPcLPPB2Ej)+F`$_8UDAwVH*WP zFu~kDUm?A;$%3{vV==Yu^#|Q&as)k_f6Of`uwYU^=qe{Q;jbLX5V29OU>o(f z@buL8blHew*pZ07mSm?#E*oMv`|TTq4di&W&DhC-Hv`h{1T_+aJ>B7u2h%;{*K#iM zTqa}V`)J3hyXFsksC(cRp&XSHU%FQO1f@o&43`pedY)qg2|eaYryZmD;0|EO!199Z z2Q)viv?~iR&zSPQ2D_2#eQsKgL{o?)!kXiWR{$f-LI1Sx-{u&0hT-S{()-e%tOQ_7 zhJ3G*yhl4DK%IkxRPuCY1ks;Et!g{$LHB@BVs#A%`70v>!LwMx2X5d`bg4IeI~=U6 z|8QUx^MRMbVAXlcO)vrk-C(srsOv=3!!37i82f;=jxg#3WUA4)(U6IJANpSxvgmy4 z{*it({KiW;`|4o!lEj|LQj}6Al#TeVj_A;k#?O)-O;5b_=8@&}=A)WJZfE>K4O#!p z&8U61Zvh*243>Vddu{r?U?4d0+jH62x!B&>h3+RhK+|Cl2f7#6@G(5q!v1HT6f%kV z;ueKoz?uS@&1*YjcMs{4g5And!dZ48jvqRgHntn?rQ1{12YN?(YwCPJ_7*I+ z2_)A1X;{hW1b;gFn}<#Ti%a+zA9nCl6s(}VIMT?P|=BLNyk;Re6IGbxUh=jD#jCVDG4IQaOJqknKl z1}y|+E<;x&PN4K2of0a<=V-gMt&WZa!Y%MLm6luK?fe4ODPwf3K5z#a)XUx~p5%~F z(;#O#VXye*0x;kPM?{|LaK5FWr&xF(7xzuag%#qS)*>vGI+hk~vEW+IDb3NDPpB;% zTQB1yEj90{FVhs^GWra7G-@`*`074PAN%?cb3ZUD%b@GzqVlPf>yVtOtNmUEMXCU4 zKDm?fHpYwR#G#r1-uz|^?$(;!bB@UzD3W-1>?=V*;yZ16rkI|`HmuxsD}225+wrk* zeqZ=OFA_>CEd09CZ|gZ?vjR`#?3RRj=Kf)S@MmfWBp$9VnC!E$OM?)5=wu{&c@f-6 zKa}VPKT8XA!2&nJRYIbWarx6x9G~O-aby-O`g~r?_`f&@d7W46#q`!>E_YSa_HPoY zTvy@4$1g33Ynan@=-%Jpf0kLdLEKZCc(#Yarex^6a^S9~r(-T?-k~3J15I6IK2u6# z&%1?+PD7OT;3knp`X?2qP~6RG8}cF*GUxK9*YaE#aOjBhUJ44x9X2KDFdEEK7dAcA`J*5&}o?>5=g% z^lpfQ+4)Dyeis4HZ!EWG_KRqyw_a6x(&(RjzpLqq3>KJ)XrzHc=w?|&jQ&XMf_1hZ z1?-9da+sHXhd>Nv)@=OLDU2?`2N4OuF!;hBTqaDvJvuq4FMCVD(dX6T*K4@c&k`Y1 zQ-uK~^ns@;!T%JhA%T|#o}=UEcrko<1~*~uM6L^{zLAfiMeII#I#oP2uI`+8tzXTUC_YtCQE7P=Oyt_O?pv>aHUwc%WwvjiSev>|Y`U@zi*2>zJFO zuReeN9P<3{GV@|3GiUL_!?eJ$gaUqXTSh#Y{L$BQb8{oI155$}WWd^kFzxNl2J0*@ zoXhjY%TN4X@SkosXJ6C7Quq|a`0~kum)wCqfBu1mfgHGW!9PUCmIzZLeCF!p*lB5L zZT+_QU6{dC2NR_@#M>eY2- zVz2wk4i0zroey|_-H>(jVs`NLlujs$k9ZpY(do?XPDN*F;9|#OWFgkEbe4Cv$;C};#oT%vN(vC(b3$wIj2Cf)*jPNMu92K+^ux2YK%Gp;!-6NvP3~a>Q%JEYn*m&m0 zNke?{ba@)@H=O_y>v(v0*kL1>2e2;yC;fwi=KH8xQ5|*lKqRLf@Rf1bui>aLZ>q2m z>f_DQxqWK}V&bw{)4N4x`ImHW1-_=PnzeNYS)Srkyr-nb4xPF^Qe%0WN0itl!G*1g zoSrn&RHWv;^i{O$o7YoQGfYuo(95*p=1KB?I{uy~@%E?dNmJ?TQ3s|Ou6+YCnfuFm zd5sds(*=Xqx}E~kpGe}7zdlJZ+W@yZwmE9_h=QHNx0&fLx*62HJp%R>IQ)mnmgLv3 zBjGY{1J_z()KCSg9E~ZNR^F;0O@yYbaF8TGcqP+!^78sm?{A@%Pz2O)?O?f)_ABAI z*42BITp5kf_>{Quc%>+0sg>+k312gy8dl$d2vO#0=z0L$sD zToeDd%n^BHl_2*5a2%GS{o}nAC~Td0G_Mpb6YE%{Lm}15m{W({bqhBT*f?{5R>5d( zU|=BZw2XCe6mUrifDe4y4+UvLJ5A9@7Vo$C996vKYQZW0WTo7H;Q<>5D0_IN9$o#> zw4T)s=h$GhVHvuXXlYrQw5~1%)D~&`+8X19{Oa5}Vs*8__~GlW{!cv37F&6@%y$76 z8<4V_3er&b=G4_C4e)B{%D*N4CO3uow^mb#iqP|THy7V-w-$SWZCXj2Bad6$Ki)T$ z%$p;JHOXD-$s!Ua0>3)=r0|YdORMHRJAyivtoNDdRua%W2DS&D=Wr^C$>p@R8VTHv zvk5Exq?&A3v)sDcaxL}#6>*2kzdATehHkXsGDNlG4cYvlv;qAwuirX+Y4g$(oo>JA z3F#%3C#*+DKFBK2lK62e7*scNhqTYhAR-p@cX5&g7I4{R4wrorP4@i4eV_5S}QY7=KzBskjAZb-sut<-$^S*xg8d%iOjP_gIzm^TOGuSAm zTmT9Y6s%A=Wp~r$k_OUBJ%5!Jzkv7yu;GKM1|QCu;Ty19gZU*sC8Zeu4NTaN`cd~K zB#2UmdL`}$IYnp|d63^2^naI|8|2ib_$+2S8zAD2_#f^0$?*?|hKC8^m`7o_you@| z0{leqWB`z7kmq4+_WNr9nSmuO z>or{OKb(niUsvO1kL!1SvL#ROLi1LERH}uT`M%~>nA#mh)HCy9#Rr>@3!E#117Ri} zV8aJ3=Ely>M<9=1$Hc_=ExJfX68OI)XC>fYP*&}nG@RgC2zrr<*XOUNve`^RFUf@` zBVN@RU`@Yp0dU?fi0V%PK@9|b_2HrG*v)WlmCYx7F5Ku*+E0nDoY_+UVU(awnS6$T zilB7+GCv=E3*;9FH>!Q`{iW@zDb`S(2_~BM{0TKvO2}_J0u~ll zbt4086AQSfuLNr7DeQl-eF66~;nNTCUZd;M2PM-bQa1dxE1&MLclH-izuNZ>F@Ic= zu`TCn_9n;?CW`O@JgR8w{(I?ZDOnp_Epj5~l8Z|nJ*!L^C^9b*FVDj&wK~(=wwH6A@*&*VklJ5bx*_fIC1H9LbJ_E= z1%IcFAmR!EVK&?Z0GK~|ox;Qk;~HePIz(Yf-g&Q*X~7^a{rohne%FgPAtfaY8lX^> zxiRb&dCo2_NRm0|7xMs$hc^VkdkN9c0T%ywZEbDwvh2kx>nKd3i1*PZKBU%gLDWHn zBHfrc#QGH_rd;_UE72qzWb5^XnVpVl7COnmUa=E!d5TmWs<4nLw{E%K*8tua1eagq z(5oi(t*nX$4>(x<(esF8j_|xY_Et^WOdp0SI{+5yGB_+I^j6H8|JQ4gO;G zv48(&Ud_~BSY+O5N&*Z9xO$#yy2|CpGYidps{I$XU|MMnRG;1_F2qiP&fhsaJJKI|EC0ra|07eAA zNtG}m_s86g(L!$~`80*Qh2E=VjQa5 z$FBABE7=!P3B~5~>b{=#j>2{()vt8>+9kyM>S1sK`aYwB5JjO#`u7`;+slP0gbbDuvlhGsUx_cKvRlas;z06}tm89nZ^NyI*-WXV`zkB4 zgygahV5ysTu(sD3@?0Y1UKx4=odd?0hYcRJS58q(w*>^W+ytOD6H<)8BU?Y1_v+C) zFop0B5?2H83*?JP%E`&OwthQ&2OB(K*;O{WZTTDa5B82o(b?llr0*1YGM~Gahd;zR zFbpP5ieDc-NVu64#^ft;vPy>L^g;pu9u(4;Vv2|ddw$B32N~!!a3$c;k#p$z`L#ZK zY-m@7Yow8!nD`y+I`&;V0Qy35I*7RYppF*ErjfC^?e!DyjwdK42x)uUkqCRNfSRVO zVdkrpko<5}wF|q9Po~N@)be0T@*^+tvXQhOG?r@7E%G zkwqD3#}G6J!$y!)03}$BUH28kp>jvsKGVJ3Mo42W26w{Pxjd7~AO<%V(k7R~*|U7J zOwX!Xt-X)(k5eEy2tmzw+RygeD8j|oqBR}I^(W!M17b5-G|&b)HR+<{7=a(Z0-_K@ z!$EhF(s!kINRG5j1m*X427MHJMU*x#D%<{X0Iv&fm+6Pg8>9K4X#=g3#fqSL3?sauPJV4Bv&37weD0uKYiQR>2D))^36GMwZR+oKRw35b^9##+X z``-nH`6MJ`46V6;NFPL1EEE6Js5TC2s?PM;#=_eJj;NMO?m?JY)P5Ze+d%i-l2dDAgz&1+QPTs%H-wap$W z-X9+KLS&yjJV?+C0Ohxb_#y8>TXfj9!Z>anF!)GtjAV%WP{33eR=)xQB8a~O<);2Q zoyCP>3e(TKqduGtJG;a=_<(QfSi0PY4kHlIPyfAZS*Jyg4Uh#;^_Irj0HCMuIrJav zP_*N(=rwnDcjM(`@}zvFxSmN+ax!^Fp#$*aO7VCrgmVvlE^P427wWY2>OOfO?~AAq z!5!p2KRAdFKb+uB`I?9rB)jI%Vg>Ipv4Cp{`$x!G61+w%vHfUw8#F z9T6P>98A^vT%AKjYe}>Aq~8~}#tN0~oK{{4?~W<+EP>q(&7I;QISD5XcJ*$DlhAdV za;d9M)w15JE$e+-?x4&$28s~ia4z&kSJx@VhPS~uR!%7d{S z`AvbT3l%wf3Ia-4Ow8fchIg|{pGz3NI&k$VTi0s{ zmuJ53Xv#N+IQrrh&^C`Gv2y-;Piaqn_gC|HS!>4OyYDJZ6Okdyfz3ykPtuo`kufpv zM^c&3H@@avT1Ccp-P2Jl;3oI?+7RB=kyH{0K&(eSBZ>hS4M@0^g;pP^vJR7Lh9?cs z8JO7^FjsM@o5z_Iz3qkW)KkP~W1#&!f~_0Yl&Y;qg9}q%z61gX0F~ak@Zy82@Lg_X z+3mNU+&Rj0UK*l_l~m%qYCBqRjjOX27&f8rbq3aOkM6+5rqW}Kb?$4ehVxaHj=X9- z&Nipe+OS*~R4LyfVG1fqbw{m_tudV{1lq4c+NpN%9BkA;=ja4OYi^u_^li1@3CrvU zkG0{`M5+TJd6bNFHEt9m0&RZrVr#LcN1)|ed&X~gIImz~H2NIfG4@=-hQ*huz=Lw< zfwMeA?@Jy6C+d^Lc7}2(tPR7P65QO6QrxBZh}2M*Mb?m1B+Eo9B3N%>asM+a z0F99M14v~!WC8Mk!D#7)Fx4YvET6!8N#xTS-J^LWyHAt2hIX&t{1`P5Q&e|bJDnjF zZV+GW2b8v8d+UFF_9S7qq(LZ}#@ zFY@Nka}P73V{KH}(hI7f6Epxpd(1VGBt*_1PuyOQrCeQm>TJ%x)V%w76e8_ zmwdHRMW4<90Ie`r^@Avol@FXN($rPLkLYJRzM0uR>!<0b3O65Qx>Q?BoFwpw-9Q(WuswnaVBe&E%Hn9eVO^vKkXJGCWTjJ4mMn zYN7xIqZM^01oPZ$8HVOIO6FrYCbTt{`cd3-cv$R8Vzb}D72I}tzJr*5z+<5^Ds<8m zLrak-uRr9uwQA94?Nz}46P@Bh2xF-y8unMNZZmM`!8HZu_f(q>VC7&1+(mM+%&F){ ztJzq@#}AJ84*~>fWH-_zUrnaQgl07huPJ=|Vk5?PRgtdZ$2)#}{7UJzq}EXT@p~_| z9wdHK8Wo@aB({MT*Oo}Mk{G_%m73FtmCc6H`igb zry|6G9k}}D?Q+NT2sZEoB02LApxox}kYFGuhXb)9L}FHa#3ICrUgH>>=FAvQ=Rd(! zB0vwxe~9irSw{=2#$ur5+aXu_r#?33!@WNpEm?2yg1nab_HLpY^RT|jIC2p8{mHAU zW0Mr4qO`rY+L^O|?XnFL(01BRE8Y^x0moYN2@^h|U@Ep+4 zM2};_1Id}j)@yOwN+b{iAlxI@=nZDcE0mAqESj(O7|EuVRw2q^W#x`P@Pya~`igfr06wEUS#@`$+% z7v39i-6ZleL5&ne4!0F6#UtMeVaL&mvsRxY`XT=P{rxJaRz!#hNZ?1Zp`DhxutDca zAul86@>=1+(oT7jwM@&xPuDzUiP*Xgik7Fh7&&QVUWk-%dMTJTcW4Gq{?_R?;OEbW z$i2`G@1R1o_@paQS}cu54pA{DUtTO@u?XycA4xz*n_S5@_j(p}lhUpKgnnd{&qVXT zB}ka|UWnex32wiJlznO&nOgQlKGyTmH$gWa;6d9XFXN=ZIT6#3qIk{`ighVLj%aB zkz@(;3X8<)@ApWsveVBoX5Yh6`8Vt8&6vwun-I$)@8cs%F005cFy#=zW#OC2tW`}S zI_(fiReq#am_@wuSe=2zG|X|3RSIp{{-@$E#shq8^ML6x>zDsNn`!7BmMDi=p2^6r zm4ng_kkz63Q!lJv+aEER2%hYZ2z=SkDf;75FP8UzS^%RXj2hxGx(&np(bPD~m*4!& z%$BlH8O&N%B#ZGK6^&1|faZtMS?)Sg7$Gf<3GPGaG4Bf88Xi{ZqAj!r#f^Y~K%AvW zP{JKU7=7s=UIAQfMS01CqSy2xb;o+k)89X;HZ7DD2|@L16>tW*_p@=_5FbBa@^hn&C8M0Ylo-``bO zx@K2wzr%~y7&vnBMJyskxr(o$vt zRrVbrju~c*N*Tu>8V)hSTF7Pdt_zY`<5NUwkEM90@poCd82*oI99TK{2%)jw!>AFK=bVqN}T`nO8U(6Qc0QDlmhmF>C5g zOhQT|PA5!vPuhH`VevZ#5ZVJKy)q7C$2D$mR4-+r4r=n*qv`r0xtxzrm-P%L8n1Nh zKW0TSb#DGy9#@mpaWfp1z9VPxTtoY?-lGRc`KV5x3;7G-Z~%EGvNPHUzEvt$bxjAy zGry_qTK*}fx~=nI&G5^x65p^%G_7h2GBY(bV$eH-3rh3D6kHFfG#$pQkKUYt%0v4S zciFASrzb(Ht;^gs=C>e+?#_ z`2#B3@p)SbZXV>$pP#?lJpcLMpZ@;-+~2Q$_ilJe{u_-=^>5Mt3venh%l@T}tEDv2 z>xG4d;N`+&Z zjac*kz0Sb5zYMa<9l~kcTwI8_5Lsfx!#pCsh^n`IhF?!x6b0Z9qECR~U*c?68cO1E zzGnGsi&$7$nZuMKksT{Cf9SsO(<7_+oh%>rvi)-q7|lEyF`YKXLp$#K&6;Xr+_OAJ zirL@vM;EK!y^7GQ^M(@5m-Md$TEijzN-}P~5`wX?$3mqwz4Z`boE|iuOK{$LKcg!A zNiOw6C9AqRjAE;z`%8%cCvfxmImh!j+)Iy7NiV}VsA(oA{_r8~ek|xy;5+H&Fx>Mq z{EhkVj+oVii;bo_&!TGhGln}D;F|}@%9($_ON<5MD08;sn=iVGnwiVS1=<`wXNgB5 zB3o)|YOX4+DC!BaF$6fI5+FqrDJM^0e+^^_{Mw)ZhXF1ZK0;*770cFc`D&PDvFAZ! z!DIBHM_XXyiT5jt>2>s43X&pzO~yQ8)sG<2(Jtd}<-Xp!b)!v88;6_s7PzDUKL88k zlMk-pg>mbY0%*H%x@L%a#FQ6pq+!)?Q$#8?h42Wt<&2Eaxl zaZefAT->4Za#7fJva^e71*@sDZJAf4+*VV0d9>FYFlG=l;nvyMxba9XHpiun?N8-xspAtj&iSAZ{8V|4Scrio##SheqJotoSMnJv*_!?Ea}aA5oo|NgD1v<{*N>5ZB7-!$SWlSa4>y2IX%A;**?>>)2ma%M7G10hm zEPZ7ZGgn;q5^n@PL3JbfdfY*z%^0mm^BfdTXk&X}bd(lRxXx{wQa$zeH)gi)=RqA? zh#D?x^h7Ot4g~w|dH<^jiQl-NmkKfca;IanGl$--pb3ytRgHN&uYd{xKq5IZB;%9z zD?szH=28c@*_Y}eQyRYaw|!aQcb{w;_#vpFg7F1ywMFmo^DYo(Kr~bLj~^^rYKm%V z@_Krd1o+p`IWN1sA3r_gP0IS#JPFC1Oz8SZF^S{yYJhH-5T1IS>RRxV4V7+D>kro zGSaO%BR44^vHRMF3t_3AKj%cePaY53hTW2$L2dk4s!$;Ay4v!*C*60Tdkzf4m88y2 z3gSQQeEW@qLzM90A?Bq+O;ionN@;P{OCX}@NfdTVb|YVawjTyLNS%C7ivdJ47iQJh z)1TbBFFQ@g?7~n?OG$dhoj^jskx9DD>n>1Uv)k@BL$2pJ{=6Fy8F;{=f-hvp?cs^e zr-sNgWc&qBX^pS2;>!}rkLG-|;@*PjwByrq=;uABMF-#-MC1&x4AiIB0S`Lnkj$jW z#iCr9<&_iv?&eOt%aCaIhFI54fCQmD<{?NF;DXt0-SH!ai-hZTy6%_Tl9$iIrN1~i z`4eMds6U}w)tP+iwTpg{GZ*!F`;>#IA$c{IZ~nEN);+q%blt-C7N+8}snHv{i9h3T z9s52i?LQO!P4rGDOU{G|b77b1rQZ=e$p(aIRni)zVutA1Cfx2)`{6AN1dAz;sO9W> z>v8ExyB6(%ui3gUdT@C2`1iI&ft9>xWB`R(7uY2N^ zByiW3(uS-6KSfGmf)k7mUQUi4=n-Xv}}Co@HAMLY(!#{W`JprZ=R zg%lI|8X7_HhEqk$v1}Hzg+Fld&fFM!2H$<`#YQZWDus4RKuAVub=C|)65Xb}-vQis z(L5jZ_K>NRFwBf1lDYI_;^ns3^qB@6R38g#i+6WkL>K zptyvDZg(5FQs7$vg1Qhz=D1t(O!_~QspQ3qN=DgJ*Tr7taK+xr9q$R zRZcWBC+f`2Tbx5N!yc&XH?zK)M~(_Y634%(uRSWI(d zMVpS{;3Pkd0jL(3Mo1LA-r3)B?!n+e1r|RAiZu344gXEcC zhoE-=T1gsC9V=^VYR@Trj6zjYUaDyhC1v@Hb@PMS4mb+{CVg8TYZ2~!*ddWE8^Okb zB3Hxc2{zon_gwbVzALqOLdo0es~Tu>|}?H@w7{ z6wPUVVoj7(L!}o3h*GW%`mr#%i+jDB>i!b}aWK@zHT`JGNYbAP`lG)2cF}3gUQrKG;8ONqk8;guz zt%=q=6G`(ej%WAmYWR1p^`BoOYH1VHnrY+cWBjybcTg>LwR2 zue7=~xFSL0)_#)S-r0UO)Q(7nAiU=#xb5J_Ihw#wSj8f3P4Z5Tc)v2KXCkYnrq;DH zA*YCsYMBDS5hN0bPl~g$WQ=#zQ&slg`o1nx0Kvwg*n^>r{&oGUSq6V~ z#}I^^C(^OY#+K9MPE-7Dy+!ZglUdkW-0pGMcYuy2_Y^0;f<&LyOD1d3e7L`3-}h`j zd|?t+A`2ET+M=+A^YOnq%_!?86WtP0F1BX_Ib1KS23-TtAW@d+X|_j#nZ@a&Jtt5 z(l!r;$6+Rihn-7q3CJYH;Mg{sm4=PlHZzWeqSmkZ8?s-TvrJs$af25PL_u>%P?Egn zN%Qv{XTDI$NU@%Tsr*zs@MUA@h&2r%tnD7#85{{WXP}r-DMBhQp4FCT%O8BgNEXSz zfA@z-h8EQXWk*wtRw=hlD0rHZpRSgf8d?IHy z0O$0NwaUs$y*fR*s7>ak+?CbqQxTmgCcLK$)*2c1GHv`}znlEAQi2J8f8*G%vN8@P z)loNPH#J4}h)*q#sPb@xuc{`kn$`2&7>c(nkR3~1UFuoI0=zMBF)mm^NztdYH1|f(>S6AamQ&`jlo4pF6GX#v_7}VI*Ha8xtj5O2K@@aX=Oge?An@w~XslaT?yTGM zI{8J`nNyb1L(3(CP4{MAPKg7Qa$Fqnj}=S^{wBtLiYRq$Z7fsylZTrb6%~j}=+-U2L*QC5+b;f8 z?wlB8r)Ye<8v5|JkRpoo-@KXOTP0yMFtT?3GXY~;pyvxgw7Cy%k$&>oBOm`Q`VTEY zUu)%5*{>DDqAB-dKC4Q(#az&8p_q^s4KNzznh+5Z7Pz)Uj;h81wU6x)oKo#)Ydk>h z>TJQQyVwrz2?Un?z67%uV9shM{uZFY1ux{Ak?C05=w=fg#vC{;iF_;J$<`HuunG^l zonODqw)lncVmgU}7_Tz)8(eD+fLLU;*l&lB!2-#%aMS$@89ncMP|aSke& zXgG0{6qFjK;jtcra$@=k?*w@+b^utx{D~H49}$}ny1CaBp*e^91M~I$xm1E3u6JI% z5_}@)?`MW%bo6v@FD^;#9+u_M`)&)+$1|K zfJ<>yef01ykD;fd#J$!=2*3rLyze^BoG<{U-hLn`GB%BxpuU&8bK`@Vl2>YbCV zj$r%lcW!e0(m@XI!60GN7G!E`g%uNN&xQ0MH~3J9pe-64|NA^R*wubM+inK>oPZ;bfR7z#DW5(8HW20ajD7CAMlfka5( zgY-p})Tu+2vP@-E2(0%=-BX9E3F!UJrqt(6nw&#Fg$m+$i_wAT8FC`f)jw*28O_%F z-OtDBi<9YOUX1Hn90am$JCG?+4fCFE&<8|)0NuX!xtZKXxHXn3R?fFD%<{Q)Lyxl#4sz)&uzG0Y{(!u)r zPqc%!v2UYKb}cVk`|jg4MjGLHZo>J_jbL3d@)yFfX0@~^F?Z6=mPRVFpLdo4EEa)R z1-{64=Y!5-Ln3BEAKbw!4rJ8+KOvGz}2cSbN!M$(A$ROdG^^8;Q7wMu*= z)t+JonnJulINoq@yAj2%^pm)SU|1Bk z!&AKg3Pzip|I&Nc2Kt5>z7v58TP9M)>7rz&aC`Ye)bcT}N~97Jg1e2o5Bz@Ao_p_~VluLMs?`hk&`vEsk1P!5Dy842#AG=8xcSrI=On}}~uXAi) z9AUzP=Bn4x(O2tVNV@%kz!(auy3k_Nv9s>=29l=k+D+-i>k_FvX@z;aG8`g_0zrCZ zjlL%}97|(B_Fe4rT#`y&o{YpNC%*z?79bW$1#D*5#0P^ED05tT3W5qaJe~?5xPsc#LV{-y7*5&Tm!i(TPauPY7Y}rLJuiM{A#Y`#>c&_6{;K4 zxo&io2g~E{_!B88pPnq;)J|JQ&**u?!mB!wgjyzj=Zs#|qAF4;t?Ijv$}>N7J*x5$ zq#^_biKVdGkjS8@THP{!|7~{7E!e<7QA=&4h+?|ltJ@QWV&Y?0epY-)cwsQXTDxn& z5$@$KAghtO8_3kVasi7QDf#1#n}8`Gh4is!g(=2JHyw3oeC4e?e|raqE>qqT^rpNX zo%^p{im*dua~?zT5J;_X?0Q!WpV%$e?1heFd_YUhxO%P{9CGFF3I9Il{k>xV;h~D| zKZi6t8VK3%C#Iy7b3IY&h;oN>zwZQ_pt4ob5_BKu3-DwfE%>Nm|HA8l@)m(V*YW3= zwv_Of$7skQVwCFW=m1}PV(dIKEv*x<-?l8Z$cXdgc~IVip$BiVs;KCdmq6)Lp}Tka z+9U=T?+FV2W`Dns^66!#XR?5%1kj{MhWJ;C>j!WAvCJR609<7FE=64DC|xDN)sca&`(yu zTtk2bsFes@%p!134XL%x1(%eInc0Kuzx^Qp0MY-n|C_A*?s`A1i`Z!W-~`%55F{OP zRrwTU{6Ay4qe0Vx^4q^Isf({h&^Q(vKwk-1w{7jReb=uNcP2wl5O*t_3acn+{DyQa<@fl}=?H=wa!G4WKek{eZH>tvB*8 z?+JXRCa)wH*b$~yq{ER&)$?k->5jYIJYs4q{)$D5O6y2c<0ftg)73K0vhN46wsfo! z1V7_2_bxJ?*7FWXD@IsP(!v@P&nORJmfd|08s(~GZC5G*Z08>(yr41~*?G9TsJEJ) z&|ME{#%51g=MwGo8UZ|EW`%2`nGe92#goq-ypTt{z3ounzqUtoDWMDf3<@FW&IU2- z1VH;+fQC1fA3CF`2>Wz&uc(8#LckEKT%i{)Sn94{DjW!6-iNQ;5*zqCXsb+n`wx5SiuUKNcyM|8A6YgN~Zo zY?i*$G!9*ExkS_SYAfZfGY)@!3@KldHHWJQRTFwdKFf1u#TtT|>AB7tvw8Fu#zo^x zFRIEJYvA_*E5erY`pJ+fuF)6T2^k{;lx4wRwZ*4qX6U+QNnT=q%_H*YMMX~ul&M^) z@>&h4m-htQF+`t= z?2YtBeFi^26%CChHeJFu3QOlAK1aAE?xZL)yU7QP3&Hz7EU@uHSQ|3JyhPIFPomP0 zv}I7n3?0NhyTMo`tHg^o{h60}23D^JKo>3e9y|i12@%|kT%L^}erQCo&&e72>BcJk zgrO(P!7-`B_q7yDkvm>gpOVz;>j=Hv$eX;HR8(J#({*@C zdNBWb>gsNCzmQ(ApD6!T7BFSM55;Q@fFF^Z`3_!ruLOw!hTtnQ{qp$CpDGK9X2e|7=;|p|1mqhSkWEW(McnKKi^@{I{l&^8! zL19!s3q>{>koOM&v)G>rEl>x&F~?jjvE<-{I_Ca?fzBI_Eu9!Xo|X69yp8V+Z^cx$ zDLAW*Jiq$8AN^U7n>R(aQ9=cJAcTDulo_MpeMn=_FWR&Tq@knhgCoaGkS5KSh#2EU zjwxAVZd>Uu(Xyy!qIf{Y)KslL*KsGYe;_#LvD$>iM>hY|7-1}E&d`uQB91El_29I| zkeA8=B@bc9Aj3i`e;9d0jP=*Mw;yNQhTJX(U>?i6XU?rQRJ2<>D>%jFNB{u|`11h4>+ zh;b#r8gLH=?L9D^F0ZASK>Ii^BI5?BQftCOEN+UJ+_j+0#>Y~BU?if!k5D4nK0{l4 z$KJK2w!@!ugFD=OygK~fvbU?62cnQ87{sV~G^78?xEG$jpF=;NEi{rIB^UD)GTv*! zqgQ<}(61ovFo}0)Ng)t=J&Q*b{SA|c%{}Y)1yU{K48(n2ygSZGre;>?fSiFTmLt$k zkVeNq;130tVWO$Vf_jhEVFU0~?YP`hUh=mq|H>wEbYb4W^W%l`Ao-X^XQapmAAK%(OE(CdHVlp z0iJk?(Lt^!#AR36)lbC2@#CXlfPcBFc7X-q)mC)RG0tGlXP*pC-fMmX1}hLxNCTJI zc96OAeXC&+c?lt^A}%d0{PJJrWtYkMq=}iYFD;z^Ah&VoVvtiCBbl~+9wJb3c2@BL z6x3hRcFedxg!W}{+eN$6i~D_i-fFwpQ}mSV{qy(2TJAVUEZeygbn9V`mX4hycj+G~ z0)nEg7z}H|N+KS$GIi9;F%Xjcdq4l$fVt=a(QnVz6B$W@$Vgrq0V=fh_s*oTPp}Rk zUrpI1(r#{z{n0APDqlqEr^Ii8Y6UiPL}tpv*;wa{f18k6`yOK9-N-z5fHVFsGEEbi0n0gXDplVt!!lrDNj<~-uESr zzhgeSOJ-~qlD*5seuw)Aj1ko7wHg%-&x*I;6Vp zO!!AtNV@-?4%&91a@SXcv<*+qdcCBy-d@?F`yE4ls8M0Xw|d@wwmfTKSeOgi-m?^J z`+VXR`WwDkyO`VT62=-2TZ~Z?W5obpG`ek4z>+(iA-%{jBb4j)6MBWY$m{_xhEyGp z)b&>!o%pJJJ)B*xFmEY-E$Z=-Ok?7X#Y9B>AcsDKf}TEz?LnfrAX5z( zkL4YxvOx-v|NZj@CTV$pZ3xZ1gK`N&<3nlyMN;TToI^TrSit>JQg4ZYw*TW*oWmUY zibKkc^cbp|=$Za|Rx6*UZ)z(~dWumlF5PCAK|}u4-rUoocU?D13ywdYE5yq3QN}Pl zchGjrVB=^hxUKf6wBnul(Nc7A)w}X{u%(B$GI9@>-tk;#i(Wcx{V8@W3|(}PjlqhE zP<|wV2@epR57R8LKEhY1wQZPe`S;19^?tgyydkusnSwsml2fV-B{7ELvI2_0`qyz*atB zB7Fccws3syK}0vpnu?8yWy1e7V{itxk(O>4*xIs#kVnT}0mUSzw$yst!uOd8cmCE) zB}e7i!M$e@M9YB@%7dq!$s&=VT2C=ZjYcN zm8pb0h|3d6yok@rx(Ib@l_ZXoVSt--@=447!A-A&o}IkO_Wm;YW)0UT1vRhb4i3*x zk49m!MCd2a^-K>mG&ozL8Yd87uMc3R+xxdL*<&AQgx(QXE4`ao=`t?5QC=>hn^jgSihU z7gxxn4}L>=9a`YqUjH5nR+1Q*RK4cBCJe0`TKxj+w`UWh_e_0b*z1za#h%lK-U!_@ ziY-4rO(0bU3ESrT8*G9-4>kvXai~sAtq4{73gc%e-1va&(t(S{wON!({(A7cdlTRN zAIic+QnF?u#+$vx9+H+H6*^w>5^AJ--dC(S7Jn-c5qxcrf~TXiLB9N0A`kqO^$5vl zHuZ*|N=QhEks@*l*cH55whyrzX~m{$2FZ7A-BwRP?}?Z8tuAVz5CSoDOu)@g0B`saj0wRrchjglhD5-RJcSZJvw!KVg9c&^H zXb*bQf@+x+Es(lCdxnW{fXF+yn58^XyR~d?Y5;~WoNCrCbM9>TA;4xLG=MP44e`8# zst3?zJvKOO@pAN}q<>FBL1E#WB%X#h3sFl5VF(zKA^aSQ`(Cn80A-CBZ^6F-mPDXd z{ZCF_7nJ7H8?gGxiR-0kr(y2t4KDrVGp4Q%F6e7BjR{0~^>620Q9=oB#79k`6+jw_ zO3FIN7YTBUqHr^t)rz}+x%>Fm&7|1;`tB&s^aa(`m;hYby_k3L=ciw`rxPuWw!-cRQ-qbYG3@_6ePg0W8`s485jYa1awlrV&j@ z_c#lsvxvwQDBSDTYMv}fH=+-Y7e}4Qaok@_xJmaZWm;4k&YEb|#`665Vx42&wyaKu zmy^>6+_#WsQj%c}7Ssjbh1MlzrpuO6r2(T=uNr3O|&)2UUxjX$9S|A&`Ih#r&!$Xa`N(c<>V8+4dJhJi5++C-8L`ToJd z!39EF1Pv_<+H-{|=&X*z_w|Y|gQC5IFa#$?N@mKl%|Eg8t{Cuuhmi2Vi@eqvBD><7 zF+#+C<2`abqi<%mlJSrKxez>KER4P|$*&}{_Tjsc6HPo1rOdUso8K=Yk6&|jP#~j6 zoqHrKB&7X>=I$hL5P(dBxhV7s1LaLM9;NIRJ{uJQMmBWgKpF$WLJ3DKID$cN8w~3E zJPjXn*&`aZRgmmy-OXrK z^58?}!g)hlgt}T5emLV#QD$6aIDtY3X@6X2=UNl?1mI!a5)Y@2 zi}RBVejg+z<$XjzI1d)ssF&Z=C(tXJSB}mr8yib(3ccQ0FEN`^SPkIfW#nwjDBx%6 zhZMR1bNrm~zCmh2!WTxyh_T-q@5bOr%A4BbOMr}*xWvR7RBTlrH46VA7peNhG(Yh3 zBe{6u>>W(7pxJZr^6^2)*e$uQa?Guz+6SgfKIsF} zTWhNc7-}HQVg-_0&t|4t6Vxn~6Nf(FGb-(P&TGxV-I0f}ytBFaW9P2&;NO^zqoI4t zKClhFzY=2Cug~&GL&CrDCgt~W|I1JMR^}P+r$X(gu&c1TGKL#`E)v?=gWRb>hNiil zN}?v+*D}T?ZGU9KgqIQ(F1wr2RqYO}|B@=Gw)?Z5Q?`%=C_Iscbe6Yh{w zXc^$|%@B_KRL|B+@i*MA)4+JQPE4d?K;n1^@$nMn+mj*%tN(~iWNznO^5?t^A~8Xqy(PC*x)}a26BbG5 ztBaGo1Loo|GsotGJD>2K-@_2Vg4K`!&qxk@Ia_E2DMuqIg#V`WlimHi<^vxuUk{_tL{u@_h|te_KYP?JbL$vNM!Kta9b)Q`ok;=sd@P! zo`mP-p7O}uXl4f#o1Utl)bgfr*kn|fJNHF4(yyPBmq4u`APsOeuySzJ*lBsU=Ua$j62Xf<*y<0>{+ky$o+AnCeJl5DYJcfDIAFeIJh8DN2EiFIR{)R;~j>*Q0h9u*T_>@7t zlW+Kw;-YN0nlw}azcralu(rz@8D-iy(DyuKD}nloM~6p8(@C|d z+&JIv0v``-p)?rIfm*=D3VdxHuX_qwc2lbBrLI8urXbQ`K=cSn>r$TLzMcqEI@RUbO(sTH}$R1k< zquU;*LVvXxNovG%0&NUVfhR#Ak-e07g29Rk$bd{gj^u@l5Dewo5v<^D{!eFtyBq0! z1iTGaAO+dPOU?|-o>9+x@ndr=YXsaG{9+>9VelWPEo)f(8GR3e2Pib@5@uY%w5!NpWk z0&c(o#*&SL^n^jC7Xn6iJzd0gn^0)9LK6eVmOJsM((isne8LJeBIbROe4R8TQ%&bh!I1bq|TfJN=^FG+o)ioQykJnB($(>6|n%KNJBuDU8YV(%>*K1T@<_sUMm%*?Fjs{=&?v_QkC0v!riq4XIEA^{MeK2IxO+kO(fy!g&-tYupvf|r>5Q68A zrqPiAa_z9Jp%0_*lt>f*HNB6pQ9Sg%dogkoG@!`RunB z0-k81Z{K9+|Ljf2!{glX7a>a@Ou*g5)gn|DBNFByLsF3zaTF5>$EFp~x!78D#%=>> zk=QgVBaEf3NVVSuD!VZGNyE`$hMUop_a%RG_VhArSQO&yv-;SExIqS{3U&h@Om{A< zR;-@$)Q#|?MKYvNU!3!GFX1%s3l7Y0Hfpopfv}8KFGx=%$9k$p9kh}077LK+fuMO1 zCV)By)GHR}oK_OdU#_63%+%PJO5XP4R*Updf4?}G<2z|)w@*63ybFa;Fu8*55R@t= zzS+OQfak?Vm}SfPK-)jTf&>xi1$KJ9lNkCV-6M{y6XCtr@8Qz6=iOzecuBvx5$M6?jHf+1l}}k;^pVh&Cf?vW0mg2W%Yt9I zmZcMrK7(2rc*$7uF+c0y;#9zHl3Jh@8PoIUZ#XPDhNf`!gZTszS6R_^Ewnm(oAb{b zVGxzTJB>&F7(fke9UYUSLnw2Ed8Kx{{Eh*X(;?*HQCCWfhTFO=VhXS2_Y~G(n}$Ro zXrY9?3zh@Ol13PYK*C2U;_d?m#)4*b_;YXp!KyBD`pflfK>2;=n_dvy0C?T8g}?*h zlQbq@$0K|{OVgsJUKO|m3_mx52}Yk`x`;NghZ=A=b{nwpy0Se==hWAFLuVVYuQJ`m1|Ht=??8!6u>#Hv2r-YF zdCzS&q)dz0dv~0nAqJB5BIUR6RA?}0pCm?vh3#y~WxLVIpwGwL@^I#AAD(VLB;4!H zQOtp1afAzDSR=`ylR;eg2uTd|Cc)dVR8}`{Y7CqqK77>_D}6I>dMF;Jw4K*;%>(>& zZ-UJ|$@|{K7e#`Th4!sgs?N-Jxzi0g;~8Z={WEBQ^{eEBD9F<@^dzlj0}^X2I-C}G zGJRj0_64-}L8HXt4y5Yu@sKFh;OeP&rNjiry^FmtU?uYZRFC4{CDqtBfb3mTg-bv-C^VH{Bx#pk*oY#6l| zIAJ3L&V|9D3Vto{xxh<;;3^up(g5qJ_c&sJj|HIv0Qmz#svxv4!AeVu{H7^=LLMjr z@ScGp#SwvznQZx9N+KhTg1P?ruX)^Cxk;8pL2r|uoGtpJ;I$GZEnpM>1BPVsE0RK= z1-qO^=wa3=7SFz#;3g%{!2tn5hGp)F?^$(FpUkk>u>JaWbcR$x&zu-EE`kdIA-Lw@ zA(Zi*u(8m4*J125jL-iBr|!!a8aO0j*?fDLGkQ9v>uwD~Mg}FQX#;Wrls1?DcGs5_ zda#gJ_f9VWBnh-_?%g&Fo1wOUCuW_?6;$YuKl-rWeNhdHI>FNnuYKY{o!0EPw*#lO zb47QT-?^hpkErEWh@!7-+(x>WbbFxX3)m#uK{T**;0_C^cCRW>>|pqa?`Aeq_I&*{ zapUIY-nW$5!Sb4=KxDbwi)hO}$l^HU(irz`kOIHxe*3aYw6+^j@+awqnD-lc=EAgW zmc8&t*T`4M%Pd;?YVjHlhw}nP`VV0@z?(xfuQ1$_T z2y>k(!~(#IX&n}TgcA2b;P3f`qxl0KH9QFAWtjS+>Y9y>KSH6uK+-d=KiE~()P$Ki z73jl;^emb_Tm}_sOK%%DSxKkIEI3J4M=O>^cj84UM;Rt+V}1j=Q36lMz4Ygr`JFT0 zsF_@%HfAn_bW`sw>)HAgV%iMfn89dN;rAb&>*`S9goL#@6L|lG53Gn+BcCj0Z zlibOh+HX;#TZRZAxb5q+*#}9!dy}Ox_GW;!gg}=`bn-4!bz>t7x7(o0IG;fI>Y+if zJ*J!^wpio>;JW}s0(3(9CKkRwTij9mZ-f6(>t%kEUXrs#71es5FkwTu@#f7No@pZa z%{_Q1z6nVhYSLmK!oGu$ZIMo@s$xxZZ6ctl#Gd^fejq*v?z53^~F@HAz{!fZ=HjHpzt<@nFo=EGjn6&0vY^xY8BgFgaN_)5;LxYsR0IHFL2{^jG76n(1p><^Pxc>E=p-b56P`Dy!O(o0>l5Z{I7P$&F} zumaSC5Ym!@z6wYRk`FW$JWq~jq&gf(xH&x1AK3676Am^Vv0BE4#_r=WW!ODowP2gc zsjK6+H_bc!cXdsBcY`@3;on73%p(g!zVnCqmuHf(JM#UiRydhj<`yBtw9+;7k!

    &VqZo1ed-?|!AqZoc6uZ~mC7C5@G z7f(E$;e)&EF}g%Wvf|@ND|w;Jyd&oH=ddZ?TMW ztql26zvV;#n+ank*a1ZOxg z{2jzji9dT5nw_mU%=C0`g;N)*edu|Eg+kG*2JSL3v5q_W?P>m5p3fmFkPkT>>H3Av4 zG?4*q>g2BLynrcHRkbPtAHHEl=wjNtmApi}>PaPj4av-~4wgH+9iqz*KTizD`q7oe zmUlMRzUZKbC6oPcZ6#S>14anfmEfbj&88K8YL8$>DDY_bWJ8e$E zn*>3opt~hK3j<&VN<`6N<^nd+cbJ8Z?ZeO--p|(D`daHw>QW*%u0eLPX^Vlmk+^(E zFe~y4`uyS>zXL1ZZDpn77tP_martjSC32KSy=Lgj@;6;ZUHfK-$=I!BXu%-UM(S~z? zlnulgxKJ8ZoBNgRH=N2yXj>VK=!w+SMh|b`Qxag|ua>`d;WcV{b03k=9-#L8HI3b4 zBe!EJS&(T%QV}RZJ{}>VzHzybf}lL$X}}PR4*wo;5Z2mG?E@gQCFY-KMATqp>6h-c zt+#*(`~zmR+YQjKAlcl_?d>j5hf_yH!{!C`F}9=W8yK}Avbi7=oVc;d|eTvq1VukYhpV z#`ql&|A+VcZ5it56eqiJcccXSMtZxFR1a-%q=Xi?Sh&ajawYi2fp$CI zc3~`5g()sRoORYiMzyl0Cf7uF>3|%Hi3u<|{=C8L=kg&K3ZWFftMzK_4&dU_P%i~S zP#28S)dW+)#uv)T8+)raiG(KS^`&TJ&c(BT-hkEF_hw9e{e%d&)4&o_Bc7iDVva#@ z1{S$S%%B`5_dm5$h**b37O71On3Sv zPE@9;=maklY{LL@QR*~eytnepGUy-a0de+5A_;Zb#+rXEBy;_ z*p2<9iJ$>u43;84$|H|8Yzb!XjDc-z8AF}~eJqR(e7=170+|TqRmdR-L(f5ujsFWn z&E@aRYi5MIN*%|rTynA)oO%C68a?3tw28h!S5aI%a=$>0V6A~4$5YZii$8I+In(+` zQsG0_l3Z8ssHbEp)1?TB@>%23L7sLWKoVo$Z_V%=B)5{$KgivNf({MM9teSe*C0Zv zENhWApB}oo^j1DOLN*s_sr`&*9O?k|g2Vw+CnuG!!*qx1kMM%qZE7*}o9Es3MKB5S z-Ef|ODkN~)j_BPXK!^yJE*wHX;n8KwuBgBUFp1_Yxnd7kVn8wo$r#E}RR0ZbKUP+h zY7Bt>_^iM8V%9LqlU|q@rU$glL`07S7JZqnd{G}EI!lR^r%F0gVz1(+x%!FOk&S|p z(nVxIYRNO(Sn-8qx2G!N?v5E`_P*!JZYAT6* zv^eR4WbLctb!%~N**}?e$IDD|I5RaBfAYhZFMJZ#KPM(o0hIv#Go)IrfW*58k)ajR z2x18!2jIX!{~-BAWTbEHmh7QqE~6&~P4wZz{Kx8(#o|;^vGiY81oMV+xK&bd$xG_$ zwD!yH`b$&^{1$zdu>;BRh{f-@T9|$SA1#!3+N$N}_U|>RUEjD_T*~MT5X#7>W?4%X z%9O(g2~Gj-v`uRzu4KiZv$Oaev*I?2yE{8Utw+tF_c@4lI)Ivi;LhN=IfJ4SjMQ%* z0j;u}L($UG+Gaps4uy#>mv3=9Dw=!u#8XvQHv~QigAc7mMQE^#`yEED-+-$Q90S3| zuUPsZkv3^8+>h9!A&d^%GroLz@tAS6iCH^({bjjIEd3ReJsVj$1kAy@+GKPvK@kHfSs_|mo)-T^g!ll$p}x*`XFh@O`GNuhR{ywWe}80ha&k!VAV)lq zd(RkRArwazQbgrq@;8zTPcnKbrU-qc2D|*-ZW6OZ?D*}MI=XP{)7W=*8F0%YbF#}N zQ0!dty-d8RH49&22-2g{h@5{vR3|7WzAeW*3wCd9hen@xcf8$n&c7RsJnl}_A&zzq zLFSM1zQ)$3sZ$OPdKuWW?cSdovlD=g=Hr*-T$D7Wm%3`A^M=3b6&51NSecU_OyzEh zDX`0%1=a}%7P)NVq;G^NSF;cNYxBCM%Y*bM04Mqo1?)-vpML`$DlH}D??bJo6D01R z%Z2g>Vm*f6CTpvp-DxMwgXDg&?2!G2cgVK)w4p!DEJG;DxP&eKgxqG8Id; zMJqHNM^cL7S*%8(vo~XT;;wjcjyX?1YZtx%H()jsyw@1}AQc2P8p586ATsUvQmyvn z=yH~tAvC9vVhF;1s;kx7mCk5RL>@3*vo~}Zw7sXed-pEsqYF4>07Ky&8B3PtpuRU( z2Pg-~@xf9JXKd99uV?wZF|^vncBa#%Zl^(MFe|2x; zoWsuUZl_Ic2-WLczLgMinM>CtvW8e~bGhIgxf`(D!Df#>$ zimV8N0T8jl-3#+0l$Fwpq{;S%=zo}GYPifJ7;EhGroal6!;(&Np-QJ`of4E(RTDUX z94gy5PRgi(B|?xwAmG2Gq;}9_AuKvvZBO1^5I_vApMu8lxOQmiq&5bwciO+$5&=cE}MD}WJySU=F&h&2~(w7aTTGIsXDY56j(taoNoR0k) zAmb4eV;7Nw`^l`H332EhbnatI-5(O{_a#_cLS#)j8#;3H_!ZH`%1em|^5#r!Pp}#v z22%Cte`$C9^w}=C@Z~`|$pjZ=WZ{U`L5Gl_U~<9N5swC}!-#M(lm+w@fNK&HX`|(W z&@%@OwX_O52uRRd+Tf9@PdO19JKDuta{(l@A7_-NDOqmy%aBDCB?ZN|qz{+^U-h?K z8oFy?BIW!_^>bt-dPMRnhpp%TvZgHQ&vB3ug>A9=sGzX0r*n{>;*eq8B6vPxKaZ`LQkiAwm!tPTJ?Lt|EDD?2hDh5@xBJA?kgWkl zfU}NmY=a)-_s8U$mg>zrKgK{Ya9CvIjRf&TKXJ7jvrhHM%p^h<1O6Wi1p}GtppeR4&t4&U&a0`dm~aMBJuS7UB8i6 zo4Io~PhU|n5bW5b-k*5>=gf|yC&!gRi1{|p%0c~^UT^Ht(YFi+k&Lt-X@zYdtS&3X zINh6@@^baddaxE6++&J(HE3lusHCKhmP1Rzo$x){bIr9E%UTPGV@vaW=@kwOoVd+KeRXw=EV1;9 z$DNAXyuc6)Hip%T2?!wecdDDIe@~BUe3UV*_q`d5L8LP;{^?)8Ty?$ixwv*bIouwy^u90>jdg59P@cz&DHO z?dm9XA)X>@XO@@ba{sjhUkl~5tY3lwnbm->FNDkAYi(U@q0FI9kjfgg~P-@+PC z9mwPVeV+Zp7m&5Ts3KTHPhxAWIO1ofyH?Fhb2Buq&S4dceNiqz?}iTJg)pxcGFx;OophP52*%J=WzPfAW6Y3{SB zrQzUEj`I)ASo#i4`Mhgh*+Fwg_4(cr4W82wpEdBz4eN zHvAkf^5CB3=guh1%&}(6t^{P=jMa_bP04v}ZAM|ZDW@l#U*LqalfmwU==>ieBfd~$ zl4p>LJ}P(bF%-yj<2Vmkc0}uaB{&PW+7x!YLFbeaGjn0_5&j zCsUCv%sI7^!?_?2#E?-Pr3!hP?C5SVASY?xS5~q*P4CWnI*90)1K1lMA0KGfvz?k@ z7%4vt49G*c)zTVO|0;yK!}BKN!vyH`_s^}ES2?5M7Ej4oG0ogt+$mxokKHE1`!pl2 zDMgsTr=Ec^*ef3wNH$C6v?|!`q2#eS=(;qp*ev&Ym>K(sac@y$#NkB{#zE|uyQ`o9 z3`CLxMus{>5*gAS{nYr76O(ggfreK59JJPuI1cv??|}(9y2M4oJ;Ei0)_ckcOW!=@ z?g%Nh9sbO7fmC<+2apXbDs`nobu&)h5Z>4paqd-ZNIBTG8-+IyL^f&EC8!}e&3#KG z%~TpB7eTP?0?q^xZxaMDcO?0Q+7)pK946MAXv)7H$w)W|Tz3dq26-d$t3pCF_*j!w z>0`Mow4Tyl$cVBMMQvGO1tLTH2*Ja{A|kdDOqtI|w-OW?cnM_T8w@If5$*Yhz*d72 z@p=1-{G*lCT^RFCV^>c9$wWaEjz!8d9gaz=SYRMJOsfEZQmDH`bYFw12EbJKM49|X z&x{#~apRNC$RFS5yZDlZz9}H7Aox#Vi5Y zaSyL9S~AC?Z^dGHpMiR}E~nkK2kPO+56I*7g(zr{kgUcXuh&Zwy^0+O0Cfaf3BRB~ z_|`!)C58@Hwi|@vb-7d1UY{y1zY>BFN^}UJ0pGPr4?rQn@AUx{*AwM7w2dLT@Gk3t+ynm9!MCQFTFFGv_1*Ac*pMgB_|J0Ddn4G(zo@`;b;r5 zVpe0B7nqs~X4737;Ohe6J|-_;K3#FhH&Q6GL0QNeFZIMB5W*I(K{NNyapPHEU!N&Tsocxz^($WvCkecM-*^c= zcYYv}o%yAbZn!Ebxp(9)a&~>%#xWBsLV0KzD*boRJoe8Ydqfu2NB=+9SN{-o;NU?+ z5Z%!k$=A+_ED~A*C`0`hG7ES}^WHb_oOkLSR^fJ}U`{PGl$AMe%8Ua$Iq8>*`2*tn z$b#}7I@7}8`Z?p+k%xbR3gQ7yKx4oeWOakM+PSxL4*Xzph}8J&B*5C6KW+Ct<;o2@ zE^Q~j$NB}|Dqidpr=l9|j8%!s-jSRdLSgoPm@5Q6MX$?)J~=u(1f%@^e8>oF?A+)} zf2|Fcehv23f^@?zrD>HnbVdSuOUh+jkW3&=3pxkjmZRc+cX9Rp9yYdZtDXS)WMvbm zRNz-;#>V32Ecs&Mk}Dy*0I#GR9=+BrCpK!cey5UNEQY@@+*O>Q{($6N(0pixnT;js z+b>c-A0c1|54!TX?kH}`>4-cD?Gk&w9g#VS;4-2|2Xr$>YWB)1`0*wk4gDk{Yb$ZL z2#{C?2YE4A_{m+C$nda4Yqiy!NDswSys6*Okv0S5BKCyQMZd+9 z5G1dQhWOJIG`!l#pErO zHm(P1Q1prbk$f%+{WP9AC^@@U4nR4953thDg@rzF+>H)O9H5M!;spno2zuNs_C?^) z(VUJI7c)1XOzHuGE=F`T=$y>&F1Tv00yF`vWhvv`)2pW)rr&E&ZWjx+{++QE5D>ue zHTz8MMe@Q$iR3Ohx14JGqAE2bPa(j>xY|&XLqnukH(Q433u4j1;8>$Ce4{sRZf?BE z{wH*lk)g&=%BVKymM%?|Gxi%LO6|+0-q56|jtFI>F;g@(f#jCj&bx*=_r=u`&Y0Cv>*oyk5Ww|gbkq-~8LO>P==_Cd z_cZ99(b>rvA#mIW6{0hEM&jb)&_1Nbk&&_j1j)2BEsZ@H|C^LOFVEQmVd%^sr9SKl z((kki}&dhh51V(>-VPq>Q+3KW13UV<7Jk98Q zPzx%9SQlxMGobT!AMvFCSGA;$p@9M7DeH9)u#3W{5_OQVT%cOHM=ZvV$9Ue|Ej^Q# zEFUp8?EX;}PxsUDR(>MWbL?xm1s2k9o0!M>qmjZgFVw2zKy|a-nBmbPXMHNt)f5}Z zqyFVd1a0AA{~E8_poN)gft!f?zPR~D-YHUl?ngOaYFHeVf zwTVw!TtLzzg3_Q{2XvaIq6rIoZN#ZGjhfnKvMMML@Cl!scuJ0@EI@9`gWlN{TwOcZ!)9 zO_^`NP@0gFS1BtyD55ML9jv5s%~@T|t|zjo!_%SGfFAk$mc(J;db(UWZQa))d`uk; zKnsX#IIKMQrsa zOYW>6t{{kp&=Z>IpmrHD`#9*{2I6Y+46mgj=@D1*YF=M4?izU=11ZT*?)d0sZ_l@H zK^{<9S66t@tln0z6LtIxV$R@tF-T(2Vn2y{eG2Gk$&PrUX~*xy!k<590($IZK`3N6 z!LIwg&I<1;=xr>^n|K4BJ-*P=bdlJX=E8n4sx==Qoo+PvKgJUA&~^TNcy$knXL1)1 zjU!A|37|HB-aba`W!9GDicUU9TB3~jp% z_RVU>JSY64_<|2bNa&Fs=&rAQ;lFs|%@LWqxHlS``~9t~Z6mAK`zW?uFFQE+sR=Ml z;7|ml;cE}K5@nP&M4^&ri1z`s18&Cv0KmDD`~5>$B>YuA7H#U3HGsVVq;L?EY#vaw z+PO)ycLw_wgiuwrwQ*FB6_=Ethj6=?{AO|GE%&%_)x_FEdB`_1-WLTQhFNoi_=G;jGB9<$^X*8>#`Nu26`18ux7_w;qC+CQ`w(4vFl2PC=9=M16Bg$|iz$*`IKVmf4pwSNwMJ0?5FZL6?g&t7 z7nJ~w#6WWaN@CD*Ro2%ti5-F>6n+EB+#HZO-~-I{J?^Iv)=K1R$b}ShZl&u6>4~9R zL~&^d;hlL#6F9lR{|6Mk3|QoTe`heTh{ z(>(>pAV9D^A4iv*+Cg?-S;=Wzpn_N4Z^<%iThUS=-%R@qaAU{<0vponQB_4Hs=!#k*SrnHe&GzBHDB zdSNgF-MM==vblasXP_FrM-(b>$eGJO4vIW}OiL96u?K+K+lc{;3pGFy>FE>#>EBCn zgs~i7!OMj8e>{AK|3CH>S#N1=+3>dLGsE)1?xC2K?_8_-$_%kT=jM7q(-REb&!?0J zH05SaXc$qZp)4GUxDb7DPw6jTnbHA1KZq|E710i+^`P>6Nzap=iDo7e;69wMew4 zf0DKmB=SD2SA*Tv6VU-Nw)Q2*450>+k+A>-eaZqS8;J>U5?E59G_wHJbATP}K7=is zdU!$(Z;1$5pSF-zWif^DVd(b?4(u%^JQ6&|ZX0G2N}Q4*YKRaq{w7><~f_N-Ik8AF+CN9WuOqf~;BU2%zX#E?{`U5J>sYhDnLEVgy9|@Yol)o_*h1G)!lZZT0 zM67D9fY_5K*Z}f_-Vx&yi*wC97`qckRy|}m+~tWBNX_F!Ry_jzs_x#oqr@st;P^6k z?~t1g8f>8#PN#y5lvGk6Z4ia^X=|)|%lw9EMRZ@O*QLPn(K*Tr;nnS84@*$`!H)(L zzUf!|)OOV+lj*_DqjRWqdUT=e=Ee_;Pxm>XmEdjwNj<`~XgVK-p8>up%!GS_Rq^x9 z^rvOOL#1s?lkMu8NYFL2!7&SnB(zKUh^w^e7#YE;@1%6^#jOPLryq|;&h2OzzmAc) zCAY5Z*`%?A_yN>>e>NhA$$DEL5tz5nwT|B251}WLc*@)qM@L)RXY9A)4t=V|gHM%T)-9gh!77`JBM8Dnnf~_1`Ikd&sA76|dG$5j8ZIMW+)vqi zm>-x~)??y*%f2w8!NtS##6WzTq6};Ymb0Y#yLIo-2ZpHFXdIaEurB~^(a0)z$(263l4x3v^UeY zD_$nY582R>yF>+Zp~y9uW(IbK#$c&R(iq+;L9Ups@V>HzIF}qycYrMcd{li9)X1xm zSdIAb5P$v2{<+uF&d6BA^N2v&fW$91X!;0ni*>05D0(2;qNZr{H0N-u)`DI8F%|zK zAtW%Kp+9TD&A6m1HCjCsEitc_yJW9i>BBAQg3`J#b#=Ti4qNhAj4&F0FhDoX9uS!@^b6{JmBr3cfVJc8E_PUwg|?JMeIbAMxcYu2wxK z0>Wyqpxky-x>~=Zp&S46s*Ll?GxqOiLY%y!9}a6QezFT_a55W@8T{_WKf>>*lvEIY z(pLL9+#j0a2~hHD^HImjDed-la}SmR;m{>?BB=IpebfM!w-j?~H$elrU52Wv2K2$u0Udw(5#yo0TF(}n*UCOpl}rTsZ_(?jhV7)iMrN{`u- z3*)!M&m?u^ND77aHKyLT8RfkOIWWi{$7*p%JP3~irutS69_UuPRxy#H>+m7+?eAAK z&cCJu{CD47q?2V1o&rEGzC~y`9C_cIdQXjCc?@1I1wI5t$g)4SSUcz~yM@7EkCgZJ z7VL6Jc@1F=<|{A7B2+BJMBg87_=-9S?mjjwknszhuNNx+@e>)VkNt{vxZl}5A$+yo zKHWAQ&PPrj9=iH;W|d!irz=ehR}MEX>8C?|i}CNrVQ_f)6mB+D?GPFMQtlVt&&!CUQrY;g8yM4t~2 z4d0JQRzcEFPW<BN2!4qA$TrbsJXQe|Ie;Cct<19#O3Lz4Ws`BgBi_8GB+?(`($t`wK_5);h?rg% zmhXHx#--%e>$cuqFFtt%skG6{b#M?uBhFX!rqV#-jX$yyvM{c51T^?BW42x%K8t42 zpZ^0%$|0p`Sb?f0mvo%Z`;gJwZzz!i0p~VHa`sdMqX5AZJX^hq z)Uxg_pC(v-T3$QiX=?U75G!_+c#$zPqxKmMGfl^mwxtSkU0 zVZ-X!Yi@34by`P3AGduXb_dLgW84lUHY~;`P*>}p!z4*v;QZ|9@9r+UB?P@07_cqV z6Ug8;Q0~sRr1n-KkSUNMg*K$Hf^$qL2v#!kUu!hKp@Noc);ul= zX)!>a#rz-%ia-GW*a3nBWo-OkrPf{VlTSv3_FNztI;#r)Evx(lu9D&AOF|k615(2@ zkH5k1>$kRULL0sno|zqCBrxup{Ymy~u4=*QcG*T3F6JqZsaM+(7s4w}NP zZ-f$~eeRRblf!6}6+>7*jT?Gaf-EvCTO)5z$=M(-U$f%L&{y$sZ1*3HhTdO!uDvt6 z{}ZH0S<83MX1A}|ydQR`lhDL|V#@mER@2-^cad97Eu@5mYfMc2$Vjll(mqHFoc$xo z=`LWsu|aI=xQ7HYzoZWKhe=g^{g0iUG)am?t80YIUz1&vK-4)X6bz#BbVCjSjW;)g zPQJQ-=5sFLjv=-~Qpf+|p{p zi#21Xc&@6Z;gjcd^dW+XmsX)Xw^7?7n)-pK#kb*MV*Ady$CqF<%VQ1h_6WXG(ojBKCKBr9SdBTU6&7n`(PPjOG6wznxOIM3zH zt5=JYWqL?heauyLAfN_W=Mn;%f)FQZW7sA>fE zkksv;yj{%Ndr8V)(lpeQz4}9JWPI?Y;5kAio>?6|U2k4xWX@IrC|Ye7kPU>sAy#YT z2H;;VZf-x&)>h4rBt=t~Qw+em;}PJzP7|Bygo z7oedn!(x1#xFAy8dyn)A*mg8`vpwo`5;H}rDI^XQt5nibMJRV_Uo9);p!_+X4H9e2 zEf!WKbwR^me)Foe?1bRs-h%(|cGs_1DKxFxZ+Bef(FYY2oZU9dd$ph1x3AosdEO(J z^!wckI7`P2#|cJSfk}^Zlm4V$Sx@npuG3J%b_mVNQWkx*LmJlzTpxRBLu$X zVd{m=Ng0OizsEMJ8ZQVeEKZmneG2SR3-|K_Z!E92Ug*--s>+lwb!9;1p?X5_Pem*GiLk61xQT?R48_v zOIq|Zz{B%0V|lqR*DD9^JodkV z!rbLf{AZCZgnIiH;^~9i7Ezd%L)&?(6wN z*fq2>3kwS&D7C;>&0KdOF*g+iSeyhesw(S?s&utHS#ZPdprZ6R)Y|TT)B1ljon=^+ zY1@SXLFsOgl9X;xT0pu)rKDS=Te?%ayA^3rx*G%p6af*WLApdj`K~?h@y+3%aU6lY zpMA%=);iZozZd2%suoO^&QL(XLzV^;mCo}gjzcL4+G1$ZPtaR>=vlo7Vd6$|=W% zq4@H8O0b;25fe=u7OM&KFiXV9pFfPd?pYdrKkUiiacla)HM{o}#&L40syG3UEOPu5 zc{fMI8e3c}7EO7}*iP6&+tFQI=w01A!laDR1O+)27*%R?${~pnc6ljZP%#?C<=BLk zL}GHOfOwj~fn?13bJk6&)5Xam#sj6jTLp_wJec{`q9Q(nfxGeO-Os@f`;jhDQ#21*Dt8|JuICYV|gU&X5$4wUX&41>d@ zFfcW830Oo@%X-~LT!F_%0L}$SW+(Jh$UQvV1onP+skDx^7Pcp~ z6c?sY3gY>It(aPva`W^PoI#g8PjiKeJ>!g2YYZzEou-EfSO2)y34LUEB?W%xM zj+nahK0bEiq*l}P`G;ULA}&A#r|jQiv2CPU>eN1$+3h^cG15xfy0676OdB$~ErYOb zW#J^u-d{+ukExEqvLs0a!Sc8f9?rTb7y9?-*F9pHI!pZFR)QRC)WTf+l|zFprOcYI z-iOU)YuPLE;yvy`^vHY-_k2yU{ls8!S)PLrHTKOLTaNiQ|4CnX8kdeOHTI*u2WZ62 zm=12$6{t_>T(&04G9)C?^W^2Tl&R+tMhPGxE5jsZbu|eQQ<lY-!&*) z{PpV%ogJdYLjn#`*uHpM_Hq5t{7;xwvJdaM@7%T$iRi|3|a~q^v*tOqOc3IXXCLQuYmkXlJ zsbw=}e~ei6+&>uJW8`;8YC;jjQUgClwf;1j_tsl!eQF|UYH879O;XR3AgNl7jEroE z%@%WTKKMRJ>tCTOrpT6hh5dI41TNL`iqp?BepkQu8vK+`a4FCckAtSsz0gzER9-nv z0px;=4GIv_K$}J6Y&LqO=!_MdJmJr0j}!~f#1Q|4nF3MmKPPpK(#@QPk_7!#xNsqO zXuP}y+mBE0A}pz3$9OAn104%GIz!bUH~`xS1&%IZhA+j}>)^T$(nEE}Wx2d!@;496 zEyj`FKYcGmY_+~6)?rEM3`9=FSNu$6z}mHJ{YjgaauoDIrogo|n+s>1-ci9OU8@G~ z7JuNQe@<#PLl%A}5~>+X%KOn{BpB5XSyq28MU9`}M8h0igZ52qEJiQm&FyQ6ya|^4 zUhh4eVuuig)0q*w8JBhm>4W&4i>sEIbs}7YkMWHkKG2b8la09YWk~t?1F@*u7MoNLaf{rvgyggG`*(m+`0Uxo<&*aN$!=x!7$8GN^lJ^1fHnwX zY;LKK<9Tet4*z$x#0QOroAuxKfIHF+PR{fiuREZ3Ql8f&K+&d}3!XTw0`FbN_o`gS zNqN_(aG(h~`}un5iUycZ{U;V4W#4u}A3Il5MSkBS#oPm{seS9n0YY#5z9&IoVW8ge zX9a87veV~+FW^fTqlJyDD>1kR26}pewrFpDJKUtY1r`b=?U19R9-idgPy^Wvp5j5Z z>0F$aMAf)y*K8c>)04Z!-dJAu(jFSciL$!FH|;Q6M?N*ss@BO>2`9*6@v4}N=lJ9JshG+5E$BVsr_ zVqzSB0@@871_C(iWZ)LgKoj>8rEG}utgV|FRu}lc!*s>+SZ0qP%)at^(#13Db+K{A z>g`+8jYCgkW*y!Xa*Q5~CNJ~C&RbTtIoq8hPzp^&u1k29-tIu16rbzLrvRT~WE z5y4Yf%s)+h8TaO3Wh8ErKYcGC>|FIn#VqJ@0N#!)!R3s>q>*xkMa-3EAU%wy59{VG zt^d|c*7iw;KGjd_xmJMz&i?xc2ZJz7>-hbldb#uFsuO$)fK7#w+Pwja#@{Z?xZb3A z+P>g;9C}m9vg~-D>f-Zl{D(QmLU}LRVn6qZYd`-kXKax#lwawgMUotzqM98Sd(&E`y-Se@{VSJ%*0${L0*GhJ%2GPuM zlq8mcI{FnlS_ZL+R`zxpxxUC^_I^RY6md~>)Q1l^M-o*Pqaz&&bzFHYB5FVYIz9&2 zfyG-}>XH%*9it^5`K6{X_=NoajX6zt@9WG1c-7$e6sm48s@D_rl1{@F=A1D^}MGdY}P$)raWWP^!y=eH!)2EMaliO11IYQ4)pHynKk)9r( z4{khV1aXZJC_V6bLDb57?o>7cLPfyMsr3hZ;7Q|2Gi#hJ)S<)|F%1|P2(vVOz&2_2 z!iz?e7!4*ZgK!PXd-kluTFWSv{>5XGdGfC_Gb_7u^zL4(9ObHWU_`$=Fh#L1b3x&)vgg2_L);(Y3Fd3oO37_7X5h=kC?EtpBx z*VjX<_anXxSwFuHV=g$Z0gw^E!+mEv-;TQP&_>jCL^$9{*{Mm~T)P-FJ2MsW;TCTM zfK?Y%X>^PIw^YiB5Wr4MOcao3yA+bwg4!EU+CWY#SZgwlIf&^gF#Ky)pY_m&65j6BiCX4f@2F4e&5m0^qKm&a&f?h^A2+sS`8<)3tJM%6p zCpLTGI!??)l5e1+!j@+uEwA^U0EY~p&BK|EC3^xjmXtK+Jc^%q;1qHNPr zN+ut5KC!YXmN-vLaDOUCCkkOAH{fZoojx+>ds>s2$dEqP4+rEgPd5}PzSV!Ss%s;{ z?WmCqE28*+F945QHt|1mXR^%+kDo`Y?;5U7POu>Gkv8z5qg6iu1Tj#ISrc}$$fjx9I6BI%*fMhYabsvwJ~ zki2UAE=c5EYQ?S;RksVeS}&yj5v(oPuYN*w9Z@E~xJUycW~khE8136PZYHB8v&Ssh z-YzDcfY#z{A=&0Am@a{lap-pnTeKBd&-V*3DL-y`?(oEwm|poMvm9%d$KzDH)VQLE z>}GzlNckd!IR?0I23%?RR>@>lb}Nn|uGNzJ@(SF+MG0k!>dtJ!!rDmhnqxLT0^9?7 zhD@BDwRGlej>=wRv_6E`ax@t?R3-C|MIVVp(_x$uU^=29l})pGmhpq8rv9dw+?>$R zBlkT+7M!=E1OqpElNK62htUy6=0i$2&*wN&{z9B9Bzgm@{YY`qxQZ?jJQEWVS1R>Y z_%F&TVn)qU258vALFRz`3M)4^*_WtdYUf@Z0m{%{r>1k0VO;$|{Q6IHaI1~oUg5wl z{rYJuk6>@{C!4+Tz%y9(U0xA1}|>7uNn% zpGMbps^Ak`TqQz0z-*S^T{($+$YXd&42!U@b=x5)8mR`2j3BR5~B*K-}#eA{%6`2P3<89 zBTOEHTsP>lMMd|<_^QgxiK^@1`am@S;G266nTDlXui7GS^figW+ld&Sf=#dG8;s{= z83GY@7T{|jxFw9F$hao=ChE5t@NSEL2TwNGs;uNrihs<7?2NBB!VVl0{(d_~7? zS@|k68eCsCMTwJ$y-e@6!gvj6bJ~I_1`z|~m0kwYtMTYsxWFp_>NLXo%CRAj|HW~l z(YU&D@N(=1Z)w-M>*tS0_J`)agppAp1NUi^`{EbWSGrsS_O4$M_hF&}q2#?H3EB=C z4`(TM7VvezX<2KS(i2a1bLk(wnp~Mg$C`W{eiAqRfw)anoS&0pjd61#=aI29qFlV^ zUhk&coGm9-II5=q%m2J4A=BH$RNCI9z}Xlr0Xe&$If}N-Puhj9QrUY4_tjQY-S~~Y zjSa!cKSjHRIQC}pP{?(Gb<>T$jPb%?5{>TPv!^6PMAIvtii)-<%VJ<|opGfjp}xP` zq6o^_@`VO#g>t8Yv$dBbHg1aU3pl2i)E-WIrM)M8`I0wVaw$;3T(vi4eAK@2d!Lim zz**DGwutzkeIpEN;gf9P_<)K4Q_czIw~U0$$tibBB}(s#PYR(0OUDXc9jy-j+4TQs z<%w-w4`-`<^r927coYRRqpivK1PvtY;l_?LPDBMbWYrLnG{9lJ+dCtD4+e}MKks0& zju9^u4K5UtxjyESe<1wefwws+e#<%hVJN|p5u+hX;#Z%3d8NB;0CWcjwC*%RIO&L>a8dz!NBz=-OsF0}Bj*A|y9w zahmsO)b|CdzHm)Eyt6jnQG5y)4iQeCjAF2E!TlYfAU8kqq!7Kj-I?YWi8}#h0TmS- zvC<)T!pqgTQ@=1S{{8i`>F+w3^(*_y?h%`7x?4`iDJ!Y*?VISRlI+v{1Qv6 zhAklJ4RUysvzph?#c#)p72@J#Uv5W+PNJJ<0mJ(HB&M_!7QBm z>V^xC*n~U#<+GRL;`SjdWt|qIElUTzMUS6E^b5Ii9-ML%{nSM2aaJdF=PFYd244zl z!RM%e<@h@L+H`{GS5ccI>7Itqt9A!Xvs&7AobT?rQx#5lp*XMn+WxKTte4q(2 zi3Njh3zGo|xj|vhFlEGB7HTT&Ewl6Wmxc{PSueaDxbS-+l}#|4fpc;{uSnu`qMP`y zda;QhxidQ5^72BMjcFVluS!L|D1jFjQB=(JqNR9;H<7dD*v0x4LYS@y3^6)@x}QIP zL@>GkO0x2k&`BPnR)+G1q(17gy;~V)+GZGE4qv=@LQi)&bAD)D;urL8@0?Wd0Z_Z&+nr7cm zl<}APPARpH4JsMK5MENLJuKwCtZ%R<-tW{Z}>j;<_Hib8%c;dB+RZD%G z^6b3QQVi#8RVNDgV&clmjD<6zV64pMKGK%Ww`icg78`CCx_KI7FxU9~)$Bsd_P(qQ z3KV!q`}($TEFn4|{%Z?DFcT11Um$_LefzcxAP`#Pyi2%{UG6I)fu!TaiN%}MYDr_joqJ2V)1|A~_7btx%QGIu1%*TKKfm zhzzOfqQtRV^Otpxbrbq|<@@)}7rn%2dZ}@i{_cBBg2Xa6r;Dib4Qh$UdOo07uqv|y zDT7K41;rtvhcG^v&mGm#N`hZCTyLOa#in9LY=`;ggZ`dQHzu_gu2VMq4lpFft4~ct zYyw4ntY_oBhQPK%U$*(%&_}%A#c)&QrSh*w-aCO}Va@AVd5z!qAlYkXvYBgddjp^H zA4mP1zfW_lCGw4Q)e8?8X_MA1-mI@GaD54fVbcD&NPSfKKy4fKj7}@JQAYrGhk})R zeC-T%bWZFsPsRdCs(JM}F*7snL+0lJXXGzD3dV3zNAEj-HS@n=%aw?Qpu(aQyw->kXuxkSLwhP1zyb1#piaPw zlC4(O_2LI`DFOTf;5xEF$S_qIGzURuDqF&r63&AN3>*;Ob74TKMKpShAP~dRiV};) zZ4vO4K%GDw@4CTk1dOq)Fn+)iB687_0DD9zTrhi_=J6Gw#zjQA;kkim2uw_Z;g}Lg z3CnE@sigRFAdT}2Fz}^XqDfSdqfrhQvSI?bG8$q!Ynz)d-OmLs;vWa!@krddn-nU> zVh}U(v9l8lT7d{}9fF4qrb_`T%;UbTA2+|hJG@M6kB@glP}mXQ`SEd`G3p4(!|y-| zt?89FHGc{k#LqSUuYXw!t&nHTT=LJ^qZmfivv)Tq@*eY$6O*2Tgtan#)B7U}?L&s) zMXzLFKQpSHXFqcYj}Dy~mD#SnuqL;~w79H98~=|Yzvi|?AbE2m9_G;AJtgKQD2_mOx9+Kr>xMjAoEL3bY zH3?u|2Iz3mLcyMs_s@jhNV)F9Q{aS+^3%!nYttZ35(Ih@E}? zlycqLboM;%#Uo8(6?OHZ=4RdL^DTX~Y>~j1imgBCB>7JzWDlD@HDgahsnFCslayz%cT>V0S4|@4EV6f<` z8&63_Ca##0pTrrP+Ql^wE<2)+JZknQs?x``+kz>jONews2cLuKFJXf0hlLW4t!xirP6>|{$nJ1icB-^pckcmy@`uM4QHUM)W$UXP(^MGxSg0Y!()rY{=+FBv_J9vjM6~a}< zPQ60Yo@#1gb3)z|_^CSj`j5a5KfT=t!14-Qh>Iu+cv%xn7@Up{c2V!oNTa;`EaCH)a zBlP}KXSJ7*^v8&9<|OKw!fUzvt6jMs(XHq2%gc?0vOp6@kM0iwAx8Dk?xW~hw6?Zq zz=_|te$&^~f21&@oB)~u$k(3LqkLf9oZ=Az+@EMSumS#|H27XLXcG~ip65;` z-OJsRXB2G)IpKlJcPQnW%8LkHCfj30*j72;kYZDXYqsmEDAh1WI5>- zDby~|41cTbVk7GhqNA~4O_otMQX60+j+R}EZ`>u(Qu6Ng3qyZh^}k=$@nGAAIWd4Q z;4u?R?D=RUL;O!zE!`!;uoggpa$p+HKBI~Joxu0V>h(r=K~IF zDI;YaPq#E-@M8vsjtQ}om;j_<&+pt>L)6QBl{A0%&b(oq$+<;mR-67a((ml+^Z%k# z2Fknly_=l0a4n*_ztW!xN?6`YKxbC#jFQbjQMX3Q4H8irv*aj`)`_j^S@~!@pPVT? zqy(aghDmvV|0teSEYYvznczoaYpcsnUu4Te8D2c|Anv#44ohSb;eY)^O2d;!crfXS z7Q-7Vmj3LUMCT4zN6dZnlN=+3=(9KC8}F1cC$rtQc>%{jIZ$nTmTN3&ivKXR812Wo zW`7grzSS7-azH0+PZ29$5V12!dwh=EY%<=7E(%4tZ>U8RdAs;;PPgkFoaFfN(O1}w zMB}=iw<@y3(u4TUl8cZ_7!GRL?)x2cC8*;XYsP zshl^gz7yCLlP`uHn#woDJ@s&CzS1K%-Js*F^4sLpO5mimtkKe4_*55FA8@6nr4gWi z>awf{v^0tQDlX)$`uYw(@lO~7stuf8yQm~`1P#Hka{xye;lx=!xj@kTa0D6HrhzzP z<7x{tD425hz(hJUaS`0NJKw5-W|v=4fej;7@Gumj-(DXPFED-L23ZxzW#w_%@RZ|?HT>_gj0V>O^wDEU`B~S zTLdDDv6<&jL+gKC+q4f;7{objr@HeE6enK)UAhs6dxk9O^NR~0%IMs@lK{%AAJpgl zgv1aIqG#hrjC0-8W6~1%IFZ7VZPU%b-FeLiws}B3YCLbHpwxKVBFHhBAx4Z1_^z(5 z5DC5w+ee(+@wfL`!FmA@kqAHo9Nw5PTNHz_NCU-9TZJI7aS`+w_@P0xvVlDnkq?El zW#Q7Lj|5_<(M6`fRzGJ~=quvE=T&S?z-%G@T*N@Apid;635->U+AA0uK{gMjr*+KQ zPl!3Wn{yLi80PZ5kz*iuv85{{%9_@`yY~>AUL=y*N6BRzW}9t>+)yZDT&p9i?~mBe zVdQmtpf8VU@OHv+*_{b%czhiks^ue#PwL5TZhvKx4>|A+i#{X0-X17h=^*)znfS4o ztE6Deq}R^pnFbBvxyVucb7uD12joBA>nro7R=V*Fe5;)~PpAoTSx)s@x%cg%I;m?5 zR2CvqdOTz)nD&l_gI&3S98X?5R(VhY=M4ka0Yuma{M7KR^@$A~T>%xAdWE5p;stl_ zdXp9>6?VXG7?r*5O&!|n%(0D_z?=&q{WE>)++}A`r%g4bZF=nA<8P2hN7-d4HfGES zDP$5Ozv~Z}ez#lK_-er##W21jZP3IgDcqRvCG_gHNLcoWo}pn(ZLJNCtED8D+XMAy z{z!m|?<-M$0f(#QBZ0!|16+x#3Np|z2IuD=%*@OPYDZ{4o}M<#9EbZ~wTZrBJO2kM zacHtZbQS(|ZkCM#CvG4dhrlftiK~?40XUrbkdry9Je!X2@rj8EC@g~f^KJh>y|f`E zzYs3xZ}LTx4c%WRC+Q6|1e*BwBr2c1oR^Uf&TM5kC;F!fmzbVoc6}GT`_!pYh2{4_ z9|}2(dU6lmZh**>fzgH(v$&8IA=iKhJ)IF?$B0Wm_yGN-+}s4=URJKT_U9oGp?=uI z`AX%9HzHpG!}6aVomY1e<#fP=DM$yHcK+M9tei{_`tik1KJg=L18wi&3&1BII*nQ) zLrzJ3l?G%}aWV6UzphAqb5uY{i;TqhVONcaBk`OjtM>TApaO1Uh;R{%Y+=2Cxh7P& zyXrB^)pbmv6rJzQg=k5SVv0I#gvk^PCN926RcSg`NsL@w*mgAq21E_Tq1E<>uVBsh z&qsYu{QxR-`>qB4SN9EEIXJ~ex~E=s_AYlp_ZJ`6t^w>NAXp%nU$vtD#1h~0`Niv` zudJBz(mrNLs8He^6KC|+D1iNt&z(kg!Cn{+aA=R7bM^2phBNteEa%>@3L$VEF|Ccb z1acOlb#uV`y;bPCQb{fhNH{9t(@aiI{+T=vzK*53KZ&K8#C*?r4MnDmpI>f`0!yVL z<159AzUQA;th+ru4OoA?41LMNi0w#DjZ!EB@{TNa~#BK2uRVGnOC8{EZC9QH?Rh26yRuxJW0#g=jIjzvwy9>NM zkLUI7q^1=GmBvrQ=FzUs^%C&li2DYNav0#Aa5!hx4)+Tgk8`WH71}(!^sNWN0*+}K z))?#Sa)m^K;KG3CXzUeg@dJb{bkXNT_4+8zUlwM0uzYhiS7{+a>qyR8o{C3|555|Ne3SILVKo_ASjg^53YVe(ac-4mW?s-yKt^^X zvQFoMPkT$CdQEE_F=7J8zYWd1!otGr!`V8G1q|U0pUD_vftzO9Df+~xSsi1hwE&GK zMHH`lcr$5l(6%?uaa(zmF|$ zuEsFZ`(xz=vNXN2X#5J@oq#_|2H7k=qWL9arvi6-V~Qx4O8I0rf?1#aUAfy=*hAv@ zhQ%nh$~K?fK)38lIVxK7#nVtcfB&bqG?$SRubUR|tjF((iJUXQwgx4*D}9kf2nXn<5)m0-H4t2Gar^x>24-h8WGoXrh$RdP(eNJnne9di;^t< zx~*;t+n09_udHb8`C>GPA3`ls=9S_ci(E@v8}{aSjx-#AQ3C0}%;^C{q=6Mv1)ttu zw%XTY{-S9uUu_3|+3ILZ=tkP0&|kC1|1v=A)QIMm|G0t(^e<45piu|LA=uVh{Gb2d z3jkUvl%Lsh|B6 zH4!@||KJh}q>7NQR<5qv#$!!PPu)p|gE#UYe(ilWa8VkJ_e|?@>jt$QfLV~qC;JBZ zOaL8@c@S=B8e%tX-Cd0$Mxz0LePjSr<9ALv$y13;0V^x3+K(T@4&d8v^1b?4n%nG_ z&dw!9#W<*$7#+9z?~IOWZeI1^>d(VJ{IE!ZHWW&-3Mns}_3_^Zgzc+7Jrk~be!h+% z^Wj8izRaKr9~voZ+b%(K?&RCs94KiXv2O&)22S}_f1h1YI{+LTj3|WAI9sqlTZ-bV zGci)aIjrOK+2dH0DGPoZ2mr7z2<#ca(ClEGX*ePmUP!pY+`TloWR;1cmwqC`7`V{` ze@43oX$+#e`T0^F_rA@~myf>2*I=8nca zdb_?=6kM%K?RNqB8a2%EJxSGi&rBA1%pP{cru>PL*S({Kc`;)rBc+l1OC);9{&~Jm z4l!o)r^242HJAW|9>4_M{~KIHQK6A``u%zV9!-{t9C zW7AW;XB89KqJcZ#UQf?z)#+BAjh|SdydDwLq;YPMeK2vf!B-Sb?f7nRO9uHJn5)oH zgLo+8=(xEh_ox)-B)yJBzyb}r8bC)L!hbuwx@F^un5b=2SYWkHHi4`u{*t)aSuvr| zm>2RL;Ca9XSqG6H$oqH7(r3zczZAMc>gxCqcSb<_w;(&}esPy@2liCX+lIBYXkAVq}s0^EbSq*gAuFVsGp=frALai!n)(Gw-z^bHs z-F9brVUTJw!i=?aCIQ!3ihHg67;KYqgkRp32{>-twl`UBeeG4I{*B<2VS0_>Mzx1T zPXc4)p;aB9mM&s+)?Ia-`Qd{gL^rgbJwus&(sY{42pI6Rero|+AwTcg^}iJ_A?EiO ztiNhseBcxfF(<~%_=%k#F6nhk8$pR&IJmgKa{Z^CId|xyH0({!%|!z1K{_Y%mCBJ{ zjw)E1ZV%?{dCi%_nH26R2+YvPZ4BMx4%UfBLOP^zoL<>8e;h@!Q>JqVUNeXKbgG69 zn}ZvsC#|QID7yc!i1sf!G~c4!xB8%mc25UPn+Sq1$Vuu+BDWQ8)Nt$LLpj=AfiExP zNo)OgS9kRBMeP$EiuUN#Epqph`~op*;n$`W9 zY@u({HGC|lqMN1Rc=d?fi~vVg4o@8yf8tM!2sis4>I=Jw1o3UD+iX2u zi)}KHIY_~AhJ29_iNcV84zxySy2^>saUyK*7{Nhvj%T^My0|dN}6 zeB73i!DeSK&nudtg{!ak26>uixpV1M!Dsk8M+ zk3HNLW4fETgdxTF=g3nlIGg3~yLa!DUO#6@=z?PDiC&6!x3o=4P}p;gMb5 zYpQoK-jN9kUM`Z1!z{{KKkV4C%ixnP-1P>gXoCAEIEDNA-rWz6#N=ZNpkIDBW+9hIjFbou zFKbldGs|Wl?K{V<>sNnn-eHS*;h$j;iXtmLd6KlD3uoa>MYW9_VRCHHMSB7GvC#~V z4|G8R8vzX6ta$2+$?yKwG4VD7mmF3psJ9kSEI19hG$`$(i_?!VS}fPa+j)Oz`k=eo}sSgcfCp*eFmRDV}QWI+!bzxQzgngS!1vX!MM55VOlK3CU>Le z(Ss`1D0}}h9n{UE>GWu(&#CF*jbEcn)-4j=Zc6__HXuz4$d8A~eakyry8Fi$5t0mA zi-ULV`$o!Zni8aHA7EHjKIu|NvOfHIoyJ14qIDg=5udJSTI*(KZ)dv^Yb}uZ0e6V9 zs?l#!Z}gV%yTxn2PK{5BgGZiX4DKNgxu>$#)xRpkz5hO~Zi~~$#o9>Wl-B4Nd-m@c zUvsFe=`BG)cWm56a3_)go7=cHxyKl(w9G0#&4aN_R^0q9^GGNzYsKdMhp*QEWcTOMyfO?0p4hiBAAN8%?Cg@@a7U>5J1`;J!r*Vye?og z64&~C-BCm~A3k10ZB-x~1bxcWuXrV-uh)g&tqW@+OiUxdj|r!D+lt13nH5CihmjFp z)>x^c5K8gw8%VePSIpjWH!<2UKjS*qn^^DqCL>63n4zmP&6rKLEJcCQwQ@tgNV5s~ zqLmsq+%lY7zl?+_B|B(QI*`w>`Z+2;^6Oi93nKu|4wSiK5?K=A1i9hIwqwSD*IQ2>W;#uZf9h)MAZ8|3DDjN&k>}4_$RYZlUPa} zxdv=2FpvHN$%+^_?i0*Tw9BAMPiCDrBgceP@lwVjoW3(Nq@b6i-`HpWV-`!5sZbH? z(tVGd6qu}5NBJVOa)g-`uNfZI(T$#!PYg;iObWZZ9|X(97~dnxo%{5{VdL~9DzCA% zGSyw4ajc5~gSnX?W#|vfUR#0k<}#Q$k76ljiV%+ES3V|CtfAM#v#1cv**sI-WXPcP8q}eVWBFS)A_tUXZQQbrI6mrVMoZ zo1Lc|bA0Ol2UZ{8kRb<$2IgCD`?a_@4p`J_!Y4dve0@C*e}6x)Md6Ly4($kCq<7$J zS~sk&D5sp-T^SmY8H6cYpDA2VLoK8LA1|8(bJGH~>dAUgi^P7pWyodDBQj^#ayoC<`OFjTEJn5C!Z~3( z$o%)%cMLiLN8)Wx3N|TLHk}E;Vq}@KwuzMA&_E2mh=^HkfH*h#*+V(az6IGE*hWCS zyO#X+VC=VQa|A#uSn_-ra#P-GPy}}yt67x1#I29p@qIYKu*ucR_{Y8van>6sP_XE{vu;|p?k)0f$V)%Q$Z8E+ zvEF^qSOc{DLU=!;qoc3%)Q3zLVIT#lMkEE@gtu`pP(f!(s>mZg1j1jb&qDdQ+{aYQ zx+>>oZJoNI;Lya}EsT`1+FDH=ismgRCl{6UMXn`d9y-$K0$8FD)0{=LI>V0*4FEWc zey}$43AnUiq1V>dhLAt^+%2?q1aA^z-f$Gb1l}x&m2m0+E0>0r7Q+b1e{sG*7zmm` zm^4yW#`D>hxHgyG=dJAA&A@q27ndhBHbXO5g>0j;&2O#NS5vhvF1eLVYyY2=@?us_ zNDNj~`H@#7(ftDN2F^mZ*kHt=pvI)k<+k+sa{x%(CLa^JBpTh*Trp;+oPbk5R)tSUky;N4iTPBrH%h5V}m&F_dT#b-*3!Ak5^k*ED zv5n}z9m}J};-C8OtvWaJNJ{2y5Qsx%FO2YkB!C~?FZ)yYYnmY;)q{ym9xnSvs{dK0 zA({|U$g1FaP5YLVY*+5_XU}tAS>YK#60s0oFjgwcDnCiJ&ItFZXSIk|sbWIjT^QQto!_}xZ+LmmFS)| zmrGZgW*yU=5#bCKhsp4xH`Fjt0-e+6a=VPOO9BU#F6Sj5Id+#N`(RIxU1ptqW15-s z6kb_9;q){zIW}922V)%`m!r1-2iBLPyXQjI!K&W?fVF3l6)65efD}%>{fgX?358g8v86sv4Pz?^W zN0+M#j=y(xL4+tl%bN_iS90y}Z^OY@fKsq&<1s)|0f^V3L)8;i6inA#~&|z{qy;8{*$>Mik)`?6&o5Fwk+@e zEo3nQ{|sPYoMOy_jU8uItG?vjA<^3U9ZWrJLB|BoEfx@GeAdogGAC3hobKY@f#4=o zz|+@V2nh?D`S?&neUuJh0N@z#hDN-+)ui;NQ*d{{+}zwFMReD6nZR#wry;W6HnQ0=WfH`a>{M<>`09{t=ZxSosiK!RL<8j?*5hhSpHKkwT{#KABLD(IuHSkMzb((Jy`?~jt zx06$?#)i!*5|VuxmRWBRgF@~jmA5n^{pMWwq;(&sFCgV1Ez-T|kHnyfA6^KQ`8T6J z$KE?-G}C0X2iXhDPSQs-;rM^Aj4okIpJ;i;rz=XyhN$=9iBI!7UFtn4TUOn6hZI!J|VX*Dx%poxR<0 z^}_)Su=s#G=*#l`>3P56a@ zG_*PxR|IW=sC>f*0KWq}^J6-EDY*S0x}M)8d=3jr+cAP<>fw&j&85`(F?7#5?4uNU zvslMt?-bY3nojhQ-g-`E}>+ZPzI8RX6qtB5w=E;f;Y# zr`52k9mD-Rb;_Qe7j;O8kLXdOK8tbcJoquJjnz;0T;mqo;~0vQcgd(ns|(IMPN$Rs zJEItkFCGP>rl#&@jXXBELmUzzneu0(rQPXV0!vu}fgYe$? zFFQqxG|RhZo$PcWh9Q0sB8nGHwM_-Zk@zHpmsxL!WJ8lZfd^nP{s68^zoh>?q>>F~ z-=W@@xq&ia$j7yGr)KQ46f{514L+5f_(Q*=%4k$7wQe9A#+tA;DYNR{Di{?}UJe#K zA|1{SI%m81+&Zq+v_B{l69>D+?rAPA(#dILCa$jdFfD-Na)i8wYx>CC$EWe$UPALmAZB@}XV<$puF&?+1;Iq9^}S^Ys~>Wt4YCvVf>muqf)EB<&k zBfbJ#^85FrNDVri5=d{kz`lxHoY(^zBjD$3t5#)l-u$YEY8J6gXcGD_2P#CLP`Ks# zKroQ>I*l<)<{gWxFQ{73HyR6D_cFWDh0;8#`d>sY1*p)7Q{Ic~*4EZZ0AyZO1rNdK z2~m`W^qO3>;}19#5H>Xzb>`7cFu5Y;%+}0R(4Ro8n>36Hust1)(sxT>)xZkF`e)br z;|&5Dy0yF8he-Gu^SsrR0$b{Hy6=Uu@S>C*jq`M|3m?Wllop0#x@gT=@Bg3liM)Lab z(U=>bMDDK~7RwbK<&N691O4AmQjsEX+Vp#3Mj0mXfV&QYL7uSQ%2cci$mE1n!p7X=VSSq?k!OKH?_m63XlOWJ+BJ5#mT^h_?J1HmDDQBM z2Z|v`;^{nJd(7BEY~0Z=27J0}Aj9`Us{t9EndB18vP049^bIsJk+rf0%A0WZ62hawbjo=!U;e=u1K|@qHI{6L05fs)28>)O(%@@ zB3`UQ#fjWQ^UOhuyJ1z6Pd>kE%ZS1Dxi+`G;w~~jv0MM|XiOK1vw@ER1j;ADG16<3 zjo!Bc2{SZ$ht7!_&!F)fs22GYHBi|D?2?s^C`^b2SjZL;Fed2(8mo6+@BXcgU%&WZ zQmmnEE-O+28itbc7=#YsCi5cbhyCE|gTJI%S^7FJVtc^qcYU4vA?l8k<*F8o2#z9a z10%;qwwt{E_73cjlV5PYQZ?EV5(l;s!FU|1Tl&E2zF_Y`NhTO4w4@HEAYkEyK}IZV zEHz9xEknyZji5Q#B8}8!@?BdW_X2RSCI218{VDUmWPunu4&3azEWtbo`hG2VI*C}+ z5Qe&zcT@aK6(VnyfAy0Y5!s_8r z!+o>hL%o_4$@28+lTVbeC2VbNb-{~@@YThmln=tvjPnTZ!-qoFCjT1=DD{g0sH^QF zS#&>wdkl&+2t#mEvdtH`9W4DVs)WURkY8?LXV|2bjYKXGwr%jNZ_Mq7AA)sBP<3V; z>`7;-ZQ6_>KbRx%YGvZASChgQnPEnzXfwARJGC2n)7I%4;8Hw)^*k`b{UB4&L2- zp7lv~5Fp2n^Wi2F9Yl8c2B8cDgCx^~JXRjSa=e{@#w>t{J{)`i&(bwAf@xZ-UAm*+ zXpj6^Mx%)k(Vmr)C+O z=bBUbb}<~avkx#&F!8m{XY7I`333hWiOQ)mK7>v9ItS50MbP!N4@p4*SMDN_czs%-QC!nKO-?Fp-<6czr109xE4@+Gsfr(uIBF6=#Re6N}ILW>CqE zG)0WHICO>ci4nBM>w_uAKH3hOZy`XTLH07Pi-hG z*1^oPlQ6{a-=PFyw!vv9IxsM-7UtaJS0x9+fVGVc0ig3_5ieN*0a8|g9WE+N&C^B_0 zLh||s$Z979*<}-|I1zzq6#`2R$koDV7&@l<2L^8E`u^5MVnde!HXQJefJy-UN^~{l z#eIfto&+!ifCZg6>-Obswb0+c-d7_E$rvAx6sM!Gz4v7#9Da)pDM6q)0FeteK4PIP z9Jsp{N+vnm*3Tg@^8on(RukrJbWCj^O`K}>L@jmr{+D@y^FMy9yx<-Ud`0*GAlL`1 zM-hy4)K)4WsJn49_eOa&>q zIep2v^~@0%8kSs};Ym>BY6`!Z6q}G9u!8C*^VJ@k5u5m;k*)4|w;1oUdy9 z9d4G8<&gajBSwh1?6n3y-0G=cI-48NWiAkXvEK`Fgy|=7wS++p=o3}uZfAUZ)}bO3 zB{(_1!B8h-2v0FMiz$J@C>-&CY?ze%hSgU}{ZDD!L1# znmqJD0*d!lNYWL@^ZO@JZjz18uMJ#rSx(gGM3NZ%Yji6$a#(m@_XV{iywowu4uvh^ z>sIa}-RkhR7~4*9Oj4bpfdO{WWCYlxv+ZB@p2|u+idB{u&kcwhjQ=cH>^hn&Ar6fy z4D>_DP-`(2Q+2BHU?8~GtJS4lLw$QD>sx)ltwj=dG#~D6Q9SsL8@D9I?xz`GEwoFg zaNwclibviK>NZx0PTp*t2Om8HXbqq~g4+p6>pI5V3os@?GYFmD4gr5o?=rqd03sK4 zItj7{%utcuDgFYv0Sp%*!`ea6n$f7h+!(K74}YPlfba-a55vfEc%Fwt>sadmm>JFL5N$TB`2MM4A;@? z4fLU~IRilx4Gie>zW9x+y)7(M#PE;!WCfLL@^#$?3CcNpp&JBm;Lf035`;yzrmxH~|h%m1KWD#4&l^q5wabFyAAMe6E&&$@GH zLKX%i$^9&dRRhXo&=5eRXiVMS*>ObZfa-xh+1-^7R(l&?~WSa4do}6@c@OIg}?7&F4Z1FvcnUjv2TG{6{v`tgtn3Lpq66 zWh}l;WlvTyLpcd-)!gv%H(A^IMA3E>3_|(H8I|cxvd6b<(*sEKfLHxq7j{zJ@EO81 zeGHE;k`ZgCsLTTgzcyPa@&MI z;e95xMc(h=D`$kL=5$D%5X7O-~Tfi6Xrh@){2={%YYksE*7XwECPof}ieVNTXBfHEx ztUoZ=(7IGhI5-b^*4U-C^{V-#U-5{x3>>I=WMr48g!y~eUYET3o>l2^xfn)Rlw$WV z_H>pBI{i$1rt|=1-5In7qe?^+1APwD4%WTw*{#W&*o%*r@Y(q!>I6X>LjactJh32f z1P(e(DPS56rd+uqv{Eexku1mr2#2x}1{k2mxo#8+8ZKbM?W6~vq$8*R7(_m4+tEbz zY+2}i0RD08tT(jW+>D*q6bJm&2L(We-Dw$e$9N?*Vw#3mpAOBZkGJrh!!G`HW%+Lc zdIT>DM%E9yKxyH$EwAjVTLbZFOLdf*mfXI*`%U@XFx8oq4Yhy2i%k zk~w`X7)7lL5POrUc|$(DucBwY0zS!=)Rm0om`{e|giNi|uz`fplDhgT>S@B>#iAj* zcUgnYxQQzd=Kr4J zeOlW5d5Uob|#j27}=$OCbQJ=9)h;*YBNxe6_WYIe4yi9z|SEm4PlLF_33{`_V$^oyD+rE=Od=Yj{; zY)R~-Fd&17U}Jw(SVp2UXc~X_zt594&%+DKwuV^0NgL8NSD~+}oWU>z1pyrE_Ke>I z(dCs!T8#6iGj+=Z)Cz_*=dLrQw$~*hw}@Cu^70t)AHKN{9t^3@Cp*5Ww=&*uLD>WX zIjDl}{QR5yCWDx@2Qa%BDMVTs~>v%!yMG(DF}6r?jl052jvQ&{ZyxfmCgT#JqzzCy<5!U^`bvv%xwVyrS_?XBQ9kr;esh zlp@k`XJVoBjSmDdQQlw@jGFL)4iR z^XX=9(YReA6vKIL2e$@nikHF;Y&( zXq3Xk%7~uBeKFATYqhKU2L{*`{xGf_bgzdzC7z1uCMK>!jdCTecOGJY3A21t_IX-CqVd*CPZ;wU zWuO*u1}nW_tb5e?y-)9t^XKkPN_8~mjpBoX8Al%m!MJG2A4qVjQ* zM=A7HFEjf?2vM|Dx@YByN2PvF-BRYFPfh!B!H)*8u$!*A*oy*zg|JJ zg}oD{uy$CE!FL4AAXFFxe*5+uu7dOJNLeLK&A8(6ruu*H3^4)d#}L@@?wNe)-SfgimY=z=)! zB!ic&)L@|r3p%idJ53_bd~(6v}U&V`GzZPRid_>*g7GKd{!T6&FaC&Pl+mVQw(=!;i1?3 znC2M^ku#lP#T8r-V`#Urc;sf7pdo>4;X%&YlUmGyJCIQPqX-1U18P$4#$kY42RLwIQ`` za~MOow~~t+(}VQQg`c^Nf<)gs9rflhUybV+Cg`5NEk9JADwG5*z)+dwb}e_KW{Jqc z7qf&Evvsw*;79!L{9_f3E#QD{TsMTOD4~S6-cDlV*mdFf=KHfhN6J^vD6sD)&(uo+b)s8aRv~=!Z#;3!rfjs%}{6 zX`w;i*bV_ah`9$?uTtz#msXMa@uTKYg(x!GsF#A$YGi~6uu?tE;FL-_jx>D$)tk@8 zyGdY$3(eTN=dq7Pnt<_6nSNuw)E?*?2c#G06-C26juK%fQm^ZRq07yX+Z`CqG z*GJ=;OHH;E%N~Z&LA|?6X`;)ZkbmN`9!PK82Vg*C?f@2=vN&H?&tTYJ+h0j#C_dXmcKR9ZVXc#+5M0Y+2ixo(ZFNj9JQCpIZIP z=n3E1Zert1beo83^~njza~50E)%hJY*LST7oj%6h#o5_mdpDpCp$^=ls=MMQ5mkw-IYFUM z?}*KOwpjM%PtlowTSeiX3{l1c{QJ|gyS&`Ls_$*VP<#bkLc)>^a_WoP!>A!IM%`X% zgj40xd^-Jf=D>dVRdVakitLp*?Cpb2zva#YKbx3d?fK5y_e!{9RQ224Pp{1v0euIu{%w<4xCx3L?9U4pIP+_)(Q2A3)-ktJV>jzJ`mZxFQQKRXybSS*s? zZ+7WouGL;Y)Ub}JmsJSuJ#;6?TH}*+R^`ZGkv&PoeUaXqQN!z&<0KV$z z>!YU+7XN}c7PY-0_>v2Nu?%%OY&hT=89EnLcv7!Rp z9Ymh!MeN3NTO>q3sa%*-Jv$VZ`pg9(-6W?{S5!xS>SgkE$g^Wok@pc1gIKaTl$9FskBP{c~| z;;(xW1fc-v0I|b@PR=p#KrKcp-q+&r>;j;+$AplDxPTC;!@noCdVsG5Tw^32F*%ba zIgw2xzS1{8gM^JICz7BTgE>hv`<5uf>?^*nzaES5Z1UndHGNSu2b*3?dGtc4Dhkw) zap6+ICsA+BK_t;vKRIvibJNppqt&``ieFHKi)T;D5pRWka)FaQ<`lN{ccbqL?P29( zG=0xn3%?r6X04f89GZ8kDBu92C0P~?FI;>uIC}HiK{L-cLF!$`DXTBmZC~+^eV6A= ztb`*9?ARs>qs@K;81&dvU+wjlUrZ?&Dy&M~iiYp+(L09P<`)?~ss5j>>N_{Il;0oi z?-ywv!?GMPj&icI#wJ&7AB{HZMGo!9?OK*93;&7;{}6aAa3a1dX**~8CnW<8X;)Xu zEK>IbS!jQ$zkS&|y7*@=`>pK`#mCu%xw*OQYp8s(oRtRN5Q2qJ3Lzxr$;MCN0C*xH zSkp|)7Uhs)1r`kpFYlZ8m-)Cg3b8IHibk30G9{f6_rrfZribflTylvl#>?&@TS=U>UDb3q3pu@PS6#!|MTvLSr-qE>e11 z|D$uECPo{dLR@wNOn;}F+|Xeu^YQ9p%foLnU7n0p`QE_Fb5N^QJrqc>`SsUULd7_< zc@eizFV%p}X@KP%9=rqu7y*d~OcTa_qOK~wbn{!o5$yEz^pR~lVt(JLKwkz8PKWc% zVD(LN6NRB#8Vn}X{8SI)X)`6;I=#XweK~fs!F)cEO7hN^1|Jq5%f`l~8`T!GGCO)hrJw{9R{Kw_ldP` zP%MunD)}r z5#&?fdsu#j@MI?@BA^|LaoXou27Fp&rFy^>nCA`CVl-yEe$_TM-sezj<+JH}v1{;W zif0D4I)67dltCxx0AGz3EXfu?k=i2fynpGO)%cvlRLEt~9*hq~#^dgD++RhE2Oehe z=Z+uNSr0x$X#&Zhro{mO#i=9k)w5M-xYc5TC${zv`n_L;@AZ~Zg zy;;Z9G#1=3%6kNl=;4=v&G`Ao?B%TxX(!+<+GoCdF{>TTFWm^1?eW<{pVxHvj-^T( z`W5bp!B>v3a*#mSpdj<-_rDfNtx>CoJRO#V?S1~LIBg>Zqu7%ha1eR$$c-7VD=`Sg z;p$_eCGE?twhTywrFX$UQG^yn9jc~8e$52b6a69?kSK0VSC*kqqk3T@b#i)21AWS| z`BY3^qg(0eJO`@GGK`RwzQj(`gP5}KQgfx5++15Ux$WOLy;zS(9=%1^OP{*8d;Xyp z3ptmfMiYDF%D#g`Z^0Jh2_wgGj1QdAB3Yz3y_Zj_JlS|e@TKM{OAT713vvxq@7-e| zdBFLo>&>lfDPNL_I>Gba;PXfyO3E$);`eHVm7241M|-Y$U)6jLoyFMwC_@_XO8pvS z-Gv0c6VHzHCCv*4lD_s3qlHfm)PG2*JVe|={t8Tjj6yh=%(USsAxM4c>hFJ+WF(6c z*lG_;6EFb7g^sAaK{d?;5zcj9yM85$5^`Ko-&UW(MM{sY&ed2rt%7RP^TMuRY2mT@ z#h)Lw4}p;z1_?8dw!M(iHhiEB$KePy0NiWVDUU&F6PWRN0EFPYIWJSMpXR{J zJpD14p09QLSqb6b!yH))x`!Ev%K)a{1y>`tqlUuQas`_QoVg7moI5*Mkg-DWRr}kH zu?zSwm;`>@9+qMjY$4%&ZB4i6okB#Axh$R|$Ma3PZgD^(x$^JM7Y{cvT2&U3`4$+r zrKYDZz#<057+75DY!o+e2UukME1WF(h_j%GhGq(}0MO9nad2|!(vj|d3=a%{ApP-V z$Tgaw9nK8gXbp%?L>LrZ4__%;?6mhe&eBV6k#aC8G&LGwXMp9b~* zKbWb^0VNC@0}X6*FkeDi3l;i64A^#q*$!%MaCO=4x1#?%FyoaxGWnL->bcCSvG}sk zWe3&d`aDN1uoJskNOs5!DXh!Iim}tF)DwTGIdBkiYmgfm8I5S-lF{H5j{W&jpZKea zszyA{!JODc)Q+g-%pM;@d706|$aLgV}|-^XvC0SPM3MR?7P z-PXKP@4$@hWxIOuTjGf!Rd5hND1AxupU{iB8@s&fGTH;h6%~l2_0wEmlxwng8{pygVm?|J!M|#IRmnlO9Yd;Gnh=^RorWyCd#%Iz#o(-v@YaxM-H1 zmKywWrv|>0^N%~-3+0P({x{7)DwAh z69@DIR9=w&Q4B9rDFNI6^l*9E&cwGoLDx|0@@B}ylEy>h!)W552i1`v=Z$NGa29p% zpg*2U!{h5$K{yY-u2h(waWsyNh`GABOoaQ|)+H{ZC7>SuOg}0I^=Lz5V3W`9G32laM&bbrCtXf4~F*Zd1guKug-_y4PpkQEl`?lLpDL5rP=D}W#c^h~K z`tfsz*5z{I`4k+O{a43W^9@kTw}5E}=L0m5)QqvF`x8W&Jv5c?haM?jdOcDkF)|_}BBSe8 z+w<~qRHGdxTg;eeoUQLj&l((y^$iG2YQrA4KbSxI+X~~tJA&1&JEx_mMSB4}-dP)r&d_v+eZwe$1WAM90| zvSM>rh9^Ag-MsOo6F#`xOjG=x{QVmr#x|3a?1EVBfX|*cgBk$T*^uZ+5tIDj83sIg zQgvf~MhaWmuU{*J7zTl#Tlx4<5zrRgS<46G`Hyw9 zN=bg(f8@0$_hc0AN)fh)XEwA7bF+Qus z+ZpN)nq^2A*MG9HkZLMY?=E{OwIAuHu=x)bqtQbPP!6Cvpm%vtM+OCRB?iHX3j(r9 z&vm_f-vgytBN_byFJS2JgTO+NkQpe=GhJcB*afdg#6VIylIqq#Ih5g!!WQiPUTy`b zUkwYOF*81Etf=t0x;SzJ6g_y8FwjuXKgph>BN;IOQi4|nr2|+p;QlB(iO`7PHBSGd zLn)!X?(@BwQYWArMO|J-%bJ=z9(TIkLxrOSaKnzNkz{YxaK&`#&_=cs(K{yona7i$ zY`<@?Y*AG!lq#~&@-;fw$ygZ>i!AGt&qGNJcr}gi>@=y<*I)ZnH}y%x(lQs9&aO(w z{9FRN^Ze_K0W^j;uT_sD;{6>@8vE~hy?OI4_x^A+);(a$S|P(l*}O&aB8=mPbh^FF(t+lr?!;}0 ziOESU1lOyKaT9?DYV!0K*^MST&JnDAW)#DuRDiKO>T`t9U>P`!YihK-ZpooJ-&c6)w>e`=JJG2s^X zqG72f=$JtW%k(FF?X|w^m}lyD!|LnJ=7%ZH7ly9cI%Z`RnFrFTU$`b~QHut&_?cSR zCpB|n`+2{8mmF$XY!k!E@25%*TTS`T+wa!|r#MMa#B{neK6G?kO)4Y2jbnW0;AeQA zAJ)c=JB7qBW7Y2d{knW>?I0J#CkWrkK?qH?=Lu}s5pf7I<$?#)ZEc(rhC%W$cA`Yy z4s!B2xa8pwoDT%4L(5juDtN&qF{=Qjg$wKX&`-l`Fie1(2}$*Uc;OlUEolhMCWiR| z+|;1Jmxt+i&|cPT-v3s(ljHbrUJDj8=7ql+Xu(AhI?w&somfk9Sil_BdT~`yTTZ;5 zC6ILCE=<#7xL^m2O3vSm53oNs8?=#rw~8smT$tNQ#k@GI<|zGbr~ZcUpj4oiCelg2 zN9&1_M-B%*ry|E&%4tr0y5xB+wb1N$T4Yr5mbY5i1VeJg+!Pdt?keoH<+QV|^9wFU z?pMOyfhw=w8BJ>ag?KT&t_&VH%>stDOU)w_9ttSGba~rL-20-d9@vriN{`>TFSxHy z$m{WATLuNKf<0X}VapHVzLl{`#w+XG`x&|Xw(+J|yM~cLJCs&%fD#c8*@QzP=Dz>t zv^Y@C0xc-XrB!5xy?gv56}Y%JcuyMp4CSY!zhX%S4hC%sncwkU`TE=0Pg1&$*R2vy z_Y$5>aJdpg>@UY9?7xE-qih*Gz&Z8StlF?Z`=$|!PeL!)0r;d!;DhT1%*eVw zn>O*}y(T=3;lkQhBF|z>=wj~)-=nGY9Ba8n_9SCB@tKtPl2v#)nqrJ1&2@=>xSesY zBIOJYmN9GSVj;3t9iM*nGU z0SD96&EMK|yw&U{0Wxu-ua;3CVNtWnDMUp&&rq2gUIwxR1TGRa4>S8YbL1X1XON&T zK{}N{S!i3d1(cy1eS#RuhTUZfwm#VX+uQtbq##ftm3|^J8cQTy7TJOPYIH>(*^&}u zB}u4Qu}uWW_Dw(H?)`WTA~LzGWOHrDl^e;-J*;g1rv=b(5t6wKg@DhS>kQQji8QS(f0h^22DCy=a2gK z_8gIf{<~v4*t?UK_c24~jhc*{)vUgoKp(n}h2MK@nZ1v8;Y{pH1-- zv0fs=3%}Lk^s&0>*U)7{$>R8yfVzO`17?}kG@%*Oxl}D1h-;)S_P-tPf72EYXQWJ> zy}Hsp+N^y%GkLKcnXIZ-#FCOsXClbCI%<|mD@kUnV)#m;HdW$nvwcb=N{iVi(76gpk7YZKbK#lsV|l}s2I6eI&{mhiLq0+#7}J`f3TtjHMqcSupe6fE@ORceeM!Nw9M+YK=wL}pg$=V!LzD$5(HN(n{q0*h-2C7OfoVl=+e+5U5QHK%| zWr^$LL(~IO8aDh?uo4qJnA29?l}LOs{0Wlci>lH<*?`iZs-iSbnSfh!>Zqzq78~kP2sjZ015nUgT3Rx^ z@OC#2pA5BF5wJVoh7;7S^n}}?Z#ZJg8~y7(xsqW4_OR=Ie}OM?JZ|JjkOvw0gCzV* zU)eQ}weT3+kFMH{%uln>__hjWmb&!ri1_i~%(c1g-c7!ao9C%(Y-CFGmuo-E)Znj# zElQkH`rFoqSok8Mg8JaeO`sSDn?Z_}F72bow>9~b0$K_>i}i`}*>tD@X4+C}0-F=XNP@YUHh&riR`YZN z6Q{emLvvR?W=kSP(IdriD#Oa*m&4)im$a1gtL>)kIR|nwtOKQn)$%Kk*>8nANBjLi z>53Fzm5$}U_U`t}&l^^lDKIT>J=^?1&OcEzE8|z!j1YF0` zZyAfYU4xp+rnmbq3Qx}J{PkR1Hq+R>T%ti+n({bBb$H{&@-INZxx2e>PkRhI=H!12 zvt%yh-1Y?qYu4E77c==1iPtf80cZh2jD*@+0R)C>J=JGW!4bXu0T7%Zl~n{$)n7$O z4A!VOO<{KmeqR^8eG11d9L*{NkIE{zpy$RsMQ@G_pm{8IKu;K-ik@KeSQK+S=`ebh zc_QQrPXW3FF<0y!Q8>tePsp6$Ph1(Pj#8jQ`f*na*BTzX`fV9EdS!MkSjA~TZ)w6-sNyH;>} z1UT<9UDKSXQYq901QEz*v2Ss{t&M0i=YucM3dnh8@T2M)8DZxRW5H%?Zq5pR`hh<* z78!awM+WD?4s&$NX$6pBt=J-<>F^FFbh=G%7&ti-pP0SC%%{1x|8<|uapd}~@K-ko zufOq<50Y7?ToyR9)c7}bC+>Q*#!&7%|4z++TBT9u^-xfQMiw%ar%{XOWykMwHdsXyI|AEbdNV zB=dz%U`RKr0io@Z)oIdJ<@wvb70%xuyf!j_#2ida7GkemePgK!H`p)c3&eqoC%S+E zhKQir2DKUI;WN^A`ZaAp9aELC;l9gc?f}uy?&e|>R zIxhRBwpLf`zk;rCU%%j6?V;Bc7Z?V)@;=BI&7Zl8KmwL zw-fDi&F!()*}Gd*8Pp-)8XS?0ZCA^bKd}O>|JcgcdHRZ@LBt8{OT8Bq&%25yU**O^jdz7smmn+6$Grw#Y!r|*oqn`~o9aF$?3 z{L4cPh9N%j|&*I?WAuD5V_zaw;!e3b6;RVx1_m?lRpYO^mrBSw_lLzLW zau8u-t1}JxucZ%#-Obc)px=HTQoyp%Lppj1(#^)FlZn5wqjdu&e!3OF5*@%nMHdgu zABL&$PEwB08HzCLaqL`u^HwEQwAKMfu7F z#1E|h`=wK2d_B@y?+J+J%r2$>N4W=&LcdoT#I0;%lJ$Ti$38J#I_>JCE|#|Hx(N zlE?nxcjo2*t=xM7gQcv}q34a_Z`XS&`%=vel{cXy; zrr>XO?a_j(@3PLYKpQ_4@#Pm|aQbA{Fm=sjW$26v5SnwO{gHYHR-vPx!Ra4fz-dPbZ` zuO)vTcnN?PG&hp32=7)vQPpQcb(UkDWIjMX0=j;2aghNAkL5#x!#_R-%OYuZ0g(I%`ufa{ z-Q~x#v1I{(N=KewSmtH5LqKgfD2<`>sU;v+?u6LhsEx!qwzxaYXrW;b$a{>>N9iw! zVfxsEtQUdS-2<~>WsT1e0JQ@(j}@Sw;F&>!?_NuKCm*8BtL=KqOf;yteJ(-dN*DkUWaOrk8V@BQi31DGFHR9B#5vr!LQy`(f4AI|7q0xLQlWo8*LN(&S;-s%QH8pi#UmsBvM3*uA zwytgEB*epqg(q3oM-z)&Y@-%`Q8l?V{dzri?z?Ee{J{tW^rP$&1(4Rgs#7gbzEJQL@w4Znb12k;;aw{MdoQ2_wt0A(8N0yqvSO!PlK9$AI$ zLJ2(>heXWoH^^Mh^If7LI)ZTiOXI>NFepHM%{UGOM|hThzc+bf2>aaYjc<=;{0WhM z3Q8N`Fh)Wb;>^{(o&;0pk&(pZ?d)g{bF?2+_8=w0snZsofHM%(Ankl`W^JPe<~Ti6tIApx@0KkHJO5Bl<;S$e>ysJQ70REMS277m2(d?4*Ra5R%^uEfQe-#u8(aE#OWIymc6e_iHbtx@vf zLt`!GxA@gY4BnV(R^~p<@vve!WFwu>rAfWW1)nx#^$VS?W`=}@u<_t(xq^l(-RL*3og=g`}4qgp^3_jkTD|)}< zRurTbp0V!U47cwl3+bvWGcAeCsa>GbKEJW3ZL|_ork9H{6!y?RcagZm23AN^G^Q%0 zq2!;}hga%kmQCb0rTzBvpN)#|G@l`W1vyl%=mMPiF{fGAg`Z4VH(kh^?)XoD)D#6p z_M~4MG4H|Ogrh0MP8Z8NYz%3w0s@Q-k|&;1no%F3P;LYbOp`!0CbXTOjTkHc=ksM& zi3hG^KKy123kzbwmr}s83WYzW6Yen*HOohouqw&Vm!}>7_48-4kHAXYe-CjlTM5fr z_G50MNEFLYwqXo}>;F8XJ{PKqE&iG$G5!K&D&e%r*vgo2=&O?x5e-dk#+oWaIXd@b zw?1(<)oue`o}~(0fHWM0X3-`T=gTCTHK9EA(%2MK6};BZX&M1vxXtkL`Lo~{Znl$| zYtBv6YsB6QnmxmpqH1YQBG;2)03!+08yd>*P|o&^<2d}j{Wo<9;?|arJ`G6NHGH&i zcxwACqQVfZ@7Yiq^R>^`wb&`V_*5t25GHI5&IbR(f1@lY$=b{hGRnl#Zhe;py)@)Z z0xKUUC`l`h@L^8AE6GlZ=%mTsQBzMyt`_Q>sV6TN=IiiUaY~M_GcVmFfkIjQso)J!01oQ#rLf7JD+47bF4PQ_T7-FFy>+)14AUJ#c z_h8ZjAmK``u6&S0>9sli;_v z9I}ry5u`p1%`<3wr%)V!yWJKXx;6H5_v)KT9$v$~=1=tF=|zQ)IT5cW>NS86h0t?c zrkj$+?Pl1sn@Xrvs~pWm8oS8J$dD%Oezhs_25z`QW>6K3*8Kchsx7QRb_I(zy$4O) zuX5hsskt?Mpz!|blY%exp>k**eug9%db&b1U>r9ZlS=*AxeiZ!B)sC;5}vpq--JWn zh#quFc-PPe1_nmJ{Qw&|8JTJ~@l?$@B}fsO5%k{#q>O-s1lQWPu`#C8C0+Ik+45l6vxAr>6iPNQ zYSotR1*HfVgDweh)Lj=)zu<#{+{i47e%lSSw6K~1tRbQBIS8P@YfOk_!}C^ERw~-t zm)dFG;^lp0i6@RxVg6ao_~D@A;tpl)C+qIaC5D?KZzOs;SCWBo&1dw z1sh|F4}|I^)Qv8`$NCtB3|U-@>zGDplg)xu8K4XBeNiJzFzC!r1>#4HY{tom!Lyg9 zxeh{H$9Xetv!2QC{$$&5+uyl!4eZxIBEVn}Fn8R4o?D=r{IRhGw`Wyp=egY1e^{J; zw(@CI`Yd&^FmLTlT_PpWjE5}*i28|rn(c?_@bK_hUi*m`kD2Hza*Dka;bm%$Ki@B# zye82(DjJ|?(@rbJG#TFT+Yjq{i}vF^Y3%pOv)Y~&-@h%g(nlM(nYq+Ym$sT3bG!c? zVVqll>DP5--9)G?K|KPcY#fRVoK+33yN&cO_h$;jdF}6D=s7`uMW1Mi2cB<*Uu2L- zdnF(}EGh(DFMzpFE3Y|c?=S71G?Dxx&6RA$YkSV{vJ><6W!AHs`i?5)&N5&3Wz15v zPs6B()P`w1H-5fjiFppAu(1Y|pB*EBMAV#3S>b(igW&aD6W*Yx68}&+CV3p=R-ZOC zr=rpfHaMWsOyd4pJ%7@$kQY$42eADFRTeZbK!eBwiIavBJ#(uM zbv+>N@q`x$Dv`J{K=DZYf6zXpwwZh(rg@M)h)~>-_&c${Q-HOJ0kX>ID)_81I0mvH z=Rt*xnizurTSNWuZBb**&f$mz2z-CMe|!VkO(TAZj?ZFGjwFr!-*CLJkptWla?-<0 zju=2w2Y#Nud`USy|MpkEbv;8UgRae2?BGQY5yM17yTN-4kXk?5{6#ls+A1@?`O#QN zt14cmR}cCdj{+YM~jh^Az>&5?BhE!e~wPP zmyR6d-8;j6_RbcrK!TYPna~`DM`J1i`T+F+xLp;In2?R1;ZStKq?W~}N|lAF;1A3~ zVF%FTvuA%G;;)s3lLbG68k#tcwcnz8Xfi+>Z_TKM8zR~xXa!-4Yy~ER0$PRVf6!PH z|60&pmlvyo2?ne+%ASuedI>e2xTaz6BA2J=XH@=n~wNV4?D2At6qD z31^@U&f?;Z4+5fU?#KRbr8bos)w;B^6TLe2fdpXg-7RD>t|u0r&`@#- zz(awsZ4Mf>5qw_fro8PUSqxt>0pa}Snoh=9!#p>6PPa7dP=7Xx$mDcpQyrT(qBwKY z%C_9JyZd2U_nJa>pA#I!R39JS&AB_vJV{}xh_Vu(rma6rj_+IZxlEW@VX zw}8eUG5QK8@>4vJToCY82d<#xh$T=$3Skrs4=By;x2C>++FL=eib1(mefxLm3pqQr zb_a3Y?Xq*3--YcXihlX_2A<3#;a`G;g@wC>pJf>@>@>-}&2#XGr|3f0@-;jDtTI_n zS5%&roej3zTQKcVHVX}-?tkKXl_&+TG zft=08(+|Hvp3(u&t};VR&I^uvBg*RP*FmcUOv#oHALgD))HXG7d|8A-1bL!B$_Thu zL@0_pCg9Poz1EKuk&DEjv06TY2|c9W0s2hW+&mtLm>uf}^MJetrk%A6+K8w9Ts0%h z(=m@}XR0{1f@w!BmtXHSn<9{|oGZ?J7Oi7!j07GcA-hdjT;b>o1X_5tG1*XO7N)*V zmd(P2pUx}<-=k?JaC2ArVb5=ot~q|Mt(iD*oW#7-;3bpNFK%sw&@jglEs+@JJej!z z_3(yWejAWmL&d0h1|;PXs@?^dR4V~h5I!JSNho5TuN@SERKsWT(K~DCQDL+64OvqZ?mt^MdV#X&b4)-j$%~h0g;LI+=;uksNw~k;0IuG15@(_H= zV&K{%!Y62A!~%}_WiF2&wjR&NfY33bcR?Ojv0#mcB>C;*g@lDK8Mlwe(%V@AQVtIH zA=3`JaDZtrQ^erl-)=S2sKd_-8VZbQw&s%lj1phj__(-y0NjFzv+HJ2aj~*d+RDnx&T^KkHT;@lVEcxO zl7Hy9e&&bkZ2L{P{jFO$qugPOg7BX!1~%Qw*RY*2p0DE=`;p;>W60)YXLrNiu3%J2 z&RvX_;;gX8x^sS>2^O}0Ue?7bbcef1hejQSWt-jlJM=U3$H+~iv!A*KrePZD6ua&o z0&YjV*#zu%ckRQ7w1PP;znQow2T0{S&BZu+w<&CdM=`g2uexG8F5bF&POji1`{^Ik z2deJ6sChUu**O_^yu3sx=(eR%=KVD93E#OBh=V~{Waab3sEKflj`0Kgj=-E?Y}NLh zC9Ua%PAWd7LgojU^#Y)ri6SgL>#li0;4Ax2TJP?!HhZ9%OcJ)89G@vImM9O*KLvrq zqRjmeFH4vsf^+D)zdY(SR(f;4Vdwy>t5J_OS)Va$lxPSE87v_AUE`VowK#m)iF7vd z>1zd|ZyPdh$^=l+2W*Fa4vv-`%((qd*EMBSGI3j?&k#fUT2Vzslw64#gz?s>;S7rM zX4<$97-dciY7n%Q_F|}wxH>x{(OK|N)WUomFagfL-s8iF8kFcAh`tX@?em0J+k^se z#u8xgwe6Dt0xP~IaKi~=z&F0wNe)tJ&y3j=J5jN{nq7?n&_3swiRE$Hbg?bgj9cKoI zDl^VsJ?1sysdzZA{mp`&rMbBo7#5wK&#^|oe-DSMKTIG~KR|XNR`*gp(g4?`#Oc@j z$E0d=Ho@OuF9M@FOUT0l%{(%u1)G|XKVva!!kt18Ga{Lu=Dthhtrv&C&{mm=RGUUO zU;qMmcVyHBCnU6Dyg#`}d-$L9eFYD?iBT;i+#GJrCcsAxkcb!WZ^Ye!b@9KS@6`X{ zhv61-M330XLRc3lQ+h?)ckq!i6y8r7_2E!-EM!BnlH*SRLK8KQbtsr1cc>#pTZZ$G zXm4+?u8B!BoGq>AyMxD_gh3%jJP}Yu0hh#;D^IBqXR#dqN|56N!qL*&8ckdJfQ;9? z6&s3VzJR&whzN1ylh7vcuZ}4OcTn1~TrwME`=i4QJW)ejLHV?O62LT50-@&|KEOgF zexW4PCsxP6#=UN%`mo~q&Iar7b=AQkmB2%;G)b8d`vfdwyW1|)EsPBlz8~Df^YESX z%EqVG`JHJd7^+4tELo!ToH#el9*h<#G|K82X&C-fR5qu0azQqq_<`|Ld6>1+U| zXiZyG`4SvpiR zxOFLmz0Q)T-VbY1jV*Wg9noKJ9*W4GWUQ>A=;>(dh@A}Kr2uyz5dDh!}S!O8%bf>A;!EGTHD ze2C!2KrZ8aMaT^PjE`hc0WMu9RS9JVtUV6?9Aq$}=!EHOhXBNI16N-j_G-|sz-7xD z#(?5;zSD~YsR=~NK)`NHb1k_pHOpU+7Qo>kr5D0Zx#j`q+vsRMXF7n3DBxn_6?yrF zLI|fk;L?bP0{%KcfT4vDvB9Lc+sB0GMQjq8#=yHjej6*t|8~#!eWWt|Abc0@Cnuqa z@&+QPwspvqv8P&tIzBVP|Jr5A@9-*n$c_}PFvrUuN=O<94PK&elBWF3^UvN^eMfD$ z!Do;1lz$EjlXqnI)R-p?U-kaI??$O*=isUw5dFwN_xPc zH3!%mh>-y|JXnm)kF)lCX@NrUu$Mr99fZvwc0{HsRyb!T!@=?J2Ewr0#?B52GDW6C zaQ=eC=Q;ezMm%Xn=pO;|3o;)N9zs_+3Iw&`;LE)(KX9qyLSqYtM#X!isN>*7hH`Vp z{Uf4;0$tiDOnHGi@L$MNLeM@l@^rxH{1~*DU_30FddT6Ek}C5wWQizFXqJ=V2gJv@ zEuZnNI6|3;oP0<}jie`o)EW%3NWwC({-8R5ITF0wDa(8>OR;w4qIp`h*Ewkkm=_4! z<2z6MpPW`R@C8u1B;0uDP5Mws`Zj*$qi|Vo#i{O;%VWa;jvt00{+<46M=;i;!o{~z zX)fb--#aBEuTj+IP2e3#p@B3NOj^~7Y9|V$+85FOua2Uv?;p+5flF~YHsWq^;0ka1Qeo&dylDdAiBQ}iNfV&}{;qAYh zK2(U2k7Ut+i;9wx60y)M>cHNGkj>zV>rJx$(0L1tzcL`^1vDZ8+#Pv`fbO@*#M{!Zn;QQ7k;+tPOPNZHaG%UOxVAS7$nFEH{S6>F?cEsjjS}ue4 z2?kg#r$_;@6i-mIwE+jpwQ&H`IRGp|*N0t!bA`eC?p7mc{Nyv?P(V^w0)@oIUf*yC zc=4t7@5cM5ztSwb*T{Z7wSpxOK=c|XBMlx#1#%E%CnT^YNyEtpnDDYFM<&7Cdmn@T z4~ymPbU#{J0+$28*fWl4IwZR1Wc=oSsfMh_RE+Ysm(gYNcz+(=lbc-faE4Cu_L(0c z4nPlx9sGI$e4T&y!cf)?EnV1wR#u?bX8D))M-}H}sO<~A31u`z1sP;1?&CUEAK&Jm zMJwUI2kshK>0H5MxP7u#YK3v^-{SSTuuuw4Mi3c+tA>;41+Ym}o=%*UKTs$PI4~~O z`!5J3q17_G_;(t%lu4ria9j987JMckz=1LbFji3eFOHTx!&pmSyoXI}r_lVI1e|>c zQo4P%+y4SO=79o(9}y&6063%ISAhBC))7u*J8~netXLv<`|`?4GjivDni>hovzWo> z0eUvNxNs_GFmR0+n^Z$hZ3djZ)Q|$}$ClxS0ii!|bt98Yl<(Ob%Lj_3$O_&lH%_Wi zd0YSBAM64&Gok9nHFL~W; zzp%1^`*%``#ZidN{@wUv>@g=Y>GTAG&CpYpw`1Bmxd%Tk2};V%^32Z~aod+-_+ug$ z{LL6Jns6EDf04Q{6x?}&ySvXtwJ}k}EOiCeNJMse?Qw#!so>MkUNa#!XeqMy4FFnE zeyBuNiWxohHww#6H>P{(O$LV4MTz3XZ?-u`)8-o`ucQ&T}qv2fL2U+cZ#F(wNd zgbTr`+IvOraNny09TPRfKtyNVx-!g08pZZw)IP2Q7BC%JNgpzKc^Bi^5%OqDG6$Qt z_e5zH&%EA?&{mx=U?xo*^GQMIDXAt?bs}< zf@IOA*(sL`&hg~51D+N8eym6bHoR1UnVgn?!&V;d@z>K6h453;Q(wZH9GSJadmNpR za0MXDe}BFsl!@fYVAR0G1Sdv061K<73+N_0(REnPF+5K|kO2$u(HG1>gmaDahs~|yaY(uXRpG>hey<)49o^`)wrjU$ z9;LubNQ6^&DO{KO3D4-+vmX$61jJYj%j@p*2aCR+Ka6z?6n(!ke{UKt$6&auU-wCAOQmsSb8aV zvKSaqcn*nLiI)yoSB(#GI5tzsCz~2F5-p1BG|F86Y<#`0uQ{@rMJ~}|TOjx0nWx=M(}qY-U_jX&m$&cOh>Wbh@&8h> zMq!)zxEsE&wKY`aqzriVP@XC4c;WbJwl`1k+iJqA^TvGCKc@957EkJv!di{jPI&Nk z>}NL&zNo9ta+@?ZXT=8Zcc@diZc4d7xs{RfE9%V)e2)Id#;sI}2aXt|!3@OlXEKnO zK)~s+@$#E)f|IRye9+U7AK5gbd9Ft=@4)L*Yrm3nob!F@!%)xesXnEO*-th3XSer! z#sVD}bQv^qY4UWLX5Jvuc(ZzikPu$}>Eona`8)69^+! zteduB$PobZD6aR?YNfmJNs;le+cue7ZScR@dX* z^Ex!#j~X0p`Rw@chhhV{QhQkk2>04(lo%c@<5`{EtiT78&sEOrw~k?<#+YFs!Oem? z7rVyuZ??%&Oa$zVN}B0NG70osyh&aV24gmvTQ7{zpw%ZctJeSge&8W(i5cXQ?s}u4 zm|BfTP2ZC;tv;E2@~pYO^ELExqtW18Y3L_mF=QwsZPr+e)u(5Q3B7_Bya5n)7DS5z z*a7N~+wI>gD<9z!$c-qDB*0Jlen0WA-MnyH>7af>`+&8;8f$Y*=G>IBJX9kCVh(~< z#JCIzTRG1bmzN8FRTkX@4MEDLJrf_rs*y*2cDC`OwB6oSm4zd^EIONOak1g1?3#T5 zXVJIF#;P->_r|W=Gf%6}1OXw_tet=73Vc^L@tC1fP zGuQULVgD`~i7*=ON|#CbG!l(uGbsAp{(`-fN}P{28O{<=M28+9yCcyK@QX1?4}7&6 zD}xSE;1b}|4fO?(8yNXkfSr-1S0X9zB*<+*3@Je9RYa; zf&|$4p8h!s@jb%v0;i7*pe`44k{7Z)?vpQx)RgP+ecST^O{=@)#RK%O(>ZEnw@w(#^U8m1zM@&b8X(9_4QBF z&-Q42qe_pp*K~|F|eK<|9(=Sq0@as8XHem`|)A zGQCfo{0&M_kd`Bm5zhjcbaXP-h)|(3#7B@<*8~zL*s$DY!`QNlIpETVsIm~azKoe{ zVbiuMtq+!BK<||2d8MnXizMtI?HIEW+_UG0Q&ci|KmR~$Fla3xC4uKJNG~iF(SZ<` z2loqEK;@r*)QKD^iO{7)p=UM|%9l@jB`yjxtCjG|x4uR9#hx4fSJmg_HSPQ!{C&gA>{h1zWwMQW@4f+^(X!%l^Hl2LbSR2eWZ!QR7 zLQ-Fa@{p*1V*k6VW zO5niVmeO4jFdVAO5Ob{Z=I7GVh;@{dN$(1_WVhTs0x1;J*BikiTNX)Mnb)@KpFp!5a3*Z*v|SLgX_xfcLR_{kn4=*OELX^00wf%@6`)TOx3`I=EK?2CZXAyIjDVf{-1 zfBub188}|_5{G)6r85vm^x}Oqv$f?iDQ8Et6mPQ#-8&esj@?~Ly4ssFQrybO7RyMy zP;J#OU^2Ub^{TiyE^z1H2=}ih#)2#jy0cD3;^85}S*h9GW2||`uey&jw!IY>H+M2* z@j1mWG|b=tRTKE7-M?DmpgTDmGFx&Gc&R+(IX|k%wJid`)kX~Qnt1-(ci{D@uWIsv#Up*28yx6nV8U{s&8u-@<@wk?>VLx z?K>9fr!U=LBM2atAfd_V(LDC_n#*d`PgQfC`Ip_0t9+Lm>zz>9c+tKwma(lG17rMQ zWya&wsilP>JNN9>uhONQLxo5>P$o3sWS-5l0mNT6&_XZjLI|rjhSm~@n`Hp025Q3R zpfYm?Y6mD$-tzL;NQ5+!LIBLo5u}XT!OIMOv>6VhB!&W30tlo!THyA@LjoA&WMu=C zm}I5LGZkI9kJ>AUT z6M)_reA8LA>XBkd9nj0y3Kj|^lIR8rCw*C8nlLj_&wL6hj-ZoTxFIzej5a`ovfz; z;vIueD(d^O*GaYZkvCj)MHaNXm|+Z4%Z?P4l};#wp%r_R-fygd)+f(isj&;Uc0u!RY$Gkl`7*%W1!X_vFH8Eoj!IpH)<_uq@7dS0tW< zLhSi8i@R@kmqef9UZAtCu3~@Z=qs)V9g}Dt_z~JFgvVJ5&ZkpMy3z#8^d#RZCeFXT zx8r-7pp~ z56vPTH&0x>7O7y|*(GD(%rElUD5UZWh1KEai#=%~LR_!Pg1&01A#j z1n7qBj`b;sZ>c||yMW}r>sD4)@E;@9pKt&n4-F;`5d$2g5Jdui5UH8HP6$gdQefGn z<@>*|wb=PbY~|nE z@AcYM3Mg61OuY0f0xSf79=n)EW1rAEiPJLDo-qL|PZKzai}yb~D7YGTk~RvGB#1PCRbMORF9n&del-zvCR$YQp3K#pdth<1M`|WwSMh zE?NeSB&?X^C}cDT*Jv6NKQOIcKIaLAP3NpL^9=7|SMu`F^GOIWfamv_>svwQ`f4ho zkinrLBtzA}M`3gPp9|D%8$+}s93Ev~s!il|$fc8k5d1Mc%>XMqKuOWCdfzwidk$kB zB8&rA-JKM~kB@#v$CxW0FgE!FR;vvknS7M3YfqFQ_4OckBZ@!ft_`;buUxW>hoMUxDi5+RVu_VEsk3s z-xDT&@P9J;@NhncV>y(@1E@HGA@W1=Q5ai>ALQAK-|gN2>&&{}j~TyyL8#RUFS;#h zEpWdt!|1&3CQD(*l{RtLuIzicI6 zGpgN8Ok|$i?>~)My_Kma++tdMT9>9>ptm7|`lBM3a@@u|Y$tP3TNx@DH;+?GuI2N;!}p^vnVghLFb_WK;%hsSINLigM*j+cUbVJBll)SSQ`ZhCKe9wAL^U6GXGu`|&Pfd9g&EWyor5d%uNw>jm)9+V@M9^t`hWC2G`*HRDt$*Tdt8<`r zGc`B2;zNVTTT)orV<)ue6bPEs@_1tuTun@vlym#Md+?a<#s`}LwP*YNnT6%iIiihu z!q@Kh*L2o_(Q9&NX+@$sYv6t!di-5lIPZkQ6tiI(ipBdnXXdyr>3 z-h*SPkt^3y3L^?=|DZu)`gH120xqRM0y&NxckWADE31Iw;*^Wo&FCB6_Y-eIw$+>4 zAW<#biM|!s1^#}(=wQ_Y-;;ul&NV1s48-n&0&t+(&HK`nPt;+$LxLC#4DL=y5D<|6 z9sv;4!GURwvINte_}5!VUyn&mC15bFp0?%l^0l$Dl7*C&;E<3w&SsA(cw%^M0=0#XJy93pS)`eBQabahp`g$oD((91b}-X%ih*T?Ix3`C=E;y5jXx771dep@nS!>DPh0RAhNYKPcrn2&vEjMaliw6lV*u{2z{#jQAjBXHKaw!15Rvi0w0yfU@piP{+3hB|}fRPfiM z6t`f`*PxXK>vW9!%`um?k{410+#QX|RzU}beKf+I)NbyjPjvW|gQFYw8`V52vgtmo z{s_tDyP)U#HHg+pzd--7w3G@XuI}D$kd&DS?K>Q0(X^zb>#}^*Eo_-ASs%F!YVt&t z=R0M|e=O~St|w=AR{p)pO$LHpZ9#BE!<}Y48}q2AJ3`k*dhmX{(;<#H6}fn@hTNNt zm(3sa{pMcCH7*DY7@4T7Vj4+utQr3)9Lqf8CiOLP@ni~?01|%sLWw=`G}UfnPrbOI z(d8dC5WX-DLoa2xL^})YXK-k}GLK`n!=jG)F(bP0Q0yxdBO^;X?t+*487z-&$npXFmsOiQ-F>El;oDwY0Q^D! zXB46z1G5Ymo`KL+m63R5V*_QG_9EmPsl;<}#4LekaAm^51Ul(CIDEiiq8ze{Flky8 zdwYAh*#I+o1r8eOpE}bjj%MBcCxL|kt&^89rl-;D7TdO+A!SUf3F)>* zo!9ROc*Vh*V1Kk_e2=bZ@r~iQwxsT0Hr0dOQ>kaiO?GYf`O8AQa-4Pwkn0&%wu|%&IYoL;F%wK>iWU!s+YuhC8V@-M!s> zZQ_ZNrj|B$1$HWm-kmjMJj1*D%Jy+=_Z%v>E=jn7-BQ*RS73uTYfNDk(<5^%Xllt8 z1D;4AOpdyqG`xY_^Cgpp*a$qc(n`G&7`S9Wg9hUmWN84B=`h=ZM=S23o%NQ2iVA_& z;g2yH97C=oxa$W0{P~z1;k90rfn=$*;PR>qqszk1IqqBWMM;NSp1 z?p|_^B_=a{hXr3spl|QrTRDSRbnCDRl=)uzAep{Vk{4AS7mAi`3;faxVD3TYI1ABn z?2tAqAhTg7{#9vC43#AO=isPtIN4iy{~4?90)7oJn!%K$^7}!k#jv_ghF5wc_Y~W1 zEj(19wCA%`;O*R<0GY}A#d#(vt{cD+!`=^+RrC5fC+Pk7d+q`Q%f_Zy^?9H{3rKP2+p>! zSOT}95dmzSy;U%qQBYEXr15FbRbeWuh40Z}1ab$UJmcTCWd!Tn7GfM3crGDjf1guHH-hILEQ~(} zUQw>s9vZtD-*`9kpvmivt7C^OK1Mpf-BIfBIoQc&Fl6n+(4x({P}U52-Hk<2rn-R} z!y>a|cN65^Fv@V}O62o%c2l!xz{J3CozUd@b2LajlmTOpwuNm+MQ9rPyMB5u^DR%0 zoxV*n8yz+u$vbxlnyxfSpL{HBILQYajJi4zXM$X@*eiyn#K?nfC49} zd~+%u3K*k)iBnDxdO&^(C=(*{l;P2T$oa=w;OdX10EEqjq}p)#ZvKY4@>IMUJ}t@P zd2+ULJ z@l?c(pV?K0f>qx{OepxIpGetaeoa4Z*d4AMUTFamY8#NKh>;-{xtJ*lV^3mYVuX-+ z^>r3RYFDB=+{T87F~ML0NmKKSi#f2kK?Dr+l^`@|5ZVyHvk*W@7A1a=#7asWJ;3wQ z%*>LPwhQHkpdnncH@J@_QL71IUg02@iiwFqPwfTMa0Z{RQs_spRpN>71?sF$K^!g2 zg%K3v0Ih?fg7W&v2%?4tq6$Q@vSM`Y|5HfG6A~Qf${O%i{<)MDlh7Fa_)#T)p?6p zTqPuY4hn(wJ0p+D`XJXAY82!R{l9$SV@$%vfEw`NygV8ZJupi_0wu4+Y7DGm7{Zw_ zyM@*a@;4mjbxEn5L$^~?46CGRgB=D54xQl`Fpv=l>kc(F7*D)l31I0~k$<0_aM%t; zEZCrO1`AnpUxMZw0{M`FOJ9ghrZ}1dkpTuQ)}?<03_CevXYnk{Yw1Afk6e zSnTX#4up0_=s*zAp+eFt?sf?afE<)^9^OW)&!k-ZXfZA7i?S@*!n8z)QxI+w#N!N7 zWJHb#dp9E%8PhPFivzHbg6zq-vkpR&y1Kj3t()#b0Uy|19qeb%l%g&l)tg>O8XZ#P z5K$5GJbyBE3KezoIyTolPEXOVN85FWNc!T(?1lP?u~^75_)8O^b?CO5$|wk&RK8ZbcPgih zQ9W+$b00D_!1o3C1lV`Lh=vKsJfeWs(((sM3liPT@n>xx-;_Z2QGyBy7dyKY_>p0E zefxP_m^u>mUu5)}Nf+!NAl3x!$1UZL9sG1@EBPW?G4{V;90D!0v9q%dkATSS)t@n4 zDz{$m%3@4ynP$gNE~VZjzA`c#yc^V{ku^eDUBYL)-_Y8AJN}ygcj<=ypyS?8SjDCf zmuv;gA7cD|d)4n*`T9sNStX z6$~PXc6hh%fp`T;gJ?tIRACVVo}E@h@|+LkYmC<+fkYStEL%{}XAJ8W+zRknkf&Z9 z!;OyO>m5%^qh;K>De@Y3+fARmFpnJ{qMZuxMA9=esZiCRkzk$rFY`vg#vU9CKw3e& zC8CZdK=;eQA$xNVuN>qs@Y2KnG*s0HQZ+&%A|`k!XY8N$+{%zs%J}hRhB{KA*R3nX zL)f1r66oka=rZgyRS^MQ1p~)2IldRjp(&if z>j$=OX;6hdbnlnE^y*>}M&vH2dv+1s3o;--Ld2jD!U#Yk4s7rcO5X}n0)RNdp%`@S z)t$Hsuj?3J^tj17K%U39pL5K@7BoYNKdvW@YW%bfLO*tP_9n>vuxPB~9x@JF?HUU+ zq}gNFAt{C5>ghblbAq8E7oZ!^b|DlEVt@LvR@(Ru&RNd8cP&TvBDfnu5$`HU^x!;( zf(uA916c}E!d6^d9G#dLVsyUxBxefrVe083*wC&!$|>pANvQ!GC&p&cMPAyhS7>f{ zwLTYc;Sr}$(k`W@b`^yF<=?)se#$`34WR1~QgwTMYpV=5K?1MogtHyTd{m&d2_HTzvyb{H66y+c30aT*=0i~5BdE#82aJ4dC*gPGcJXpFMA-G zq~=MyPF{aOZqGy3&p6D|4w6nnQHot@6B z1BxUw?^Wg=5Hx}|KRG!W>=7w@Esivy)jO@WsU@1XpNywe zk_t}uY{YxX43;9|53jZ}#^;XiYnsz7NK|8ea7)(6G| zVERnV%&@`pWc?Q8O#p!+cPO}2K;M{qo+CB{ zABYPegSd^|&{qYl07$Sbcp&{s-(Cf5YG4UHX_))X|XOd;t$#ZH3zudN`m8}M95#BloWEHq$A zVU_RNsfI+C!OXq8LlVIvGn)285$_`S^aggJE@ zq41%`fHWD_cLxisSa*CuOm5BdI~s@?Mf&{AV*tVW{Wl>3(AnYI_0ppAhM z=`BPHI$<#wKp>$3@jK35o@HJ#lW-ht{EdJ#N({7y-Skc1YiEEPZAXfl;9oM)5)qim zKp(rkD}2Bh*9u_32Kya+%&?GBf27(LKj|&;V8I2UG_HigTDWGm(xBW12dx37(o@zB zyGc-l1KbN_1|Z}?&Cdt0UV?1ae+cGub_&uF@CQX!Ij>OyJqlQ)A682)=cf-9%MWSp zWFFDlrn+P?Ia1va>}P1?p+6iZ^ZW^oqb?MiO@(IKRk^BnS-S*Md%)$+lW^U?_Lseu zJIREy#ho@~W(p_92l(%U0TAw4q%G;bkANXS9G;AyLSz_0cuxRwJGeV!K&>-^Bh3Sm zsfu9y{htd5%(l1A{`!p+{6;E(KS`4pLD>c*9chT{?}UAe_Y5|q@xNN42?QQ;cG!rh z5e@C->#fiKU?*6c7~#sC*gun0Zi>O=HZ}ITFPN^42%QuDpfu{C9sH<&4R6;2JRl`5 z91l7k&z0Z6x)q5zwg=l8K;-_5&BPib!LZnYh%=j?#pdhS+O-g^-<{Cj-HQUI}($=nPE309RKleEKBi`t0F*T=OB8->G`uE$HU z?ds09v&H(i1gn#)Y8>Mw8C^docbVpQ>3nvaeQoVr`|R%5nr9(x*^{J8YqDb_d5U-?F=9- zL}kTI+X^sfOYk^^(E?_=?? zIk6?H=0M*|8GBk7c12c%ABp+6dv-v`>2GNOA%0>1cLIJCoj9tg35`z7 z4GqL@h-rtG2uuW+2)7UTh>D5|GG;IJXU@@I%+O~Q>kcQu8J{<736)2YE=r#XxM@j- z3)vjeI8>pV)obUdS&1Q~R;DiK7SgpMPV~5B1sg+*oDkK7aa* znz0XM=R^x!!S{FWd*3~lTV9CkuH?xTdDr-wE=fYCSn^w%>(>XK)9WeDKYie>HjgDa zm9EYPQR@o0(GKWiU1$R%iI`4?o0l8UPn}hW7(f|L??|E?gjos)EA-`pp&0$Wa#wcJ zB*bQ-9=U+Z{Pgq`vHn2oI-to|Py-3*WYbA=vp-tX>tBwKZ7nVFV7-D3^Vj6$Xd&rJ z)-Yy`2aTk8>HgC-7!80HL&CL+@YE#eo;>2h@-sU~4)4($cE0hcd*~yl+kjigfv#6w z)xX+xc^lJ+yGBUbvq6tXPc2>25-`gQi*wC?l=?+DMn!Pe@@|6{u~~GpE&wJyd~<#A zmlE+R*^qde>mQ?Ivq#6P!SMB-9XJ?~3Ry(_xwrBN{ki2^Sg9cV`aktJB!WCOGHOR| zvQQZHr8weIA08xbK~7hM+c2GmKnjx2_FpnPz_UUj@d*jDpe_G#aw392H!$;oxq~TP zouGD3j>-Qy54#_MFck=0pqQ3{G6H$UA&?yDIu=^?TW9owd?Y~5X2E*}bIqG=hIqbx zXz{oMKM()6DzC~97mEzqME#0mg+wjC$UNC9|H5bi_!{{;OYP-qZNZ_Gt@<|^xBt+@ zk#j|I8_ea4*J++sh2gfAO9%=1O=b2vOEm?hE^Hm&rRS@N=DZAE-w?KhohC@(9>ABb zx5JrwZ0752p@8J*oa7@w02%iM;G2@UgVO1NRij8-<;#cCQex0JP(R9mTH*4j?F&IN z1pv@xvPr-x05wk_J8Bam{*WR;G#k~d2|p87sO9nn6QB8CA@bk~gu($jiyuYhY3{t5&`bBmsau$5p~ zg}t_#agGXnPuPG^74tr!00WvyzkrD7yH}FebVC zW_xmW?Bqb-y9@phB#Ra1BpHtQH-Hpp+Z7q|HSTxNqoo{M=9QORPF)c7%hcKjQa;zc z-d0Vp#MAgC^pz36K!Ehf{?WGeQZkQp_QU-5#=FnSH^>CPVg3<5mvQJ=J6t9G6UG>? z0;>W;y0WpACyl(I?F&!tpp<$B>UEr_x&}eDUnt6-+)%9+uZFsK!YV^rM~q#Yl9FG) zf03PQL0I?!7BjiFc(0hz3qV*a!4Hw6!7I(G89Nme} zG9NmkRkzO_Yf5ld@x4A+*9BwlG+2^>R?NYyUezN8hbsqBEpqEX!4nQ#B3Mr)A)$bW z>NY#O-`E;b*c9E;pDr4L)QD*qb_^;LFL%)hH*Rb%|GACXfli*5p6|Lc&f&Oa(W25# zL{OJmEiQ7cPlX;Q@Yt=hf9OR?UHj2;WE;6=CW zNcdh%ltt!+3+kPDIM3MRHDq}znW;Pv&A}=uEzN~Q8)Qv}HwLj|X=?hZvIYRBPfJTX z4Qn40=IxsB8)Yn1rBP1k*^hp5*moYzCt#n3y1L!)_YD$CN3k&_nFz7)q-*_4s_3t1G<4 z#|Q@-}b$6V2=u|dW{Y1IT6a_OP`5MVeVn*M0b9MH;!neX~rk(`*$Zte0Di zd8%m4>ZWk*I_R4yH3>0Ko(EBt+GA;E`wprWu(WQ0VuEsy4$`k+Fp&soW&jmriyV>_ z2hShq@K>ZHzyE(NK#(eHF8Uf=3_}>guFLMay8%xRSQ1OSSM^fTfV!Av$oZjpWmlg! zQCieI-i+anhD3dUQPj^-Oq2q{LyhNym^BJLVw-VuO?89LtM{49Y_S#>dK06_r+BI; z=>8`~sjnBmx5&H8MWE<`8rHIz|F*f~+&EQ=?x=0_a9ku^9URL@VBE@UY9pWHTOj;E z^j{G12$;tDzki6N-am&OO!eI0nUcHC2Z=~vsRI8DjGaitJI})j&N=YFDRRVF%LAKI2y%br*k3Tk^+&TNxcus@Z z0}C`Vb82g8Agv1g8YYB75ihY`Sw@nejojCOARHz+7PGtW(W&S~-6sdrY@s`IH*;Ng zLADlFh$3x#K%AJm0y3Hucj227^wg~RdjvXV>`Fw;4MM1^b9HrfZ(-`Yy4&){f^W)g zhA3To@0ZkSBlOIcvvo|zY=&ViLb@nMK&uIoFS(cj8J|d0q9U3%$fC+>Yg6yHjnCT= z@NlGwWeY&sIj+>kwkh)~>;P$)BoT?JY1jO2giHuVwJyu?ZZ*ld8ooKoQo`p?P#U#a zyS{to_OTZ-Ho!Lg^v?umSnOYedXH-WgePTWC~#7W4h3Hx-W@6R;so|Z{+kI#2iV1d zprLG_lX@IlTm^y6AT*$IYzPiFt9Oq%Ut%J-SI{wp1HL-d!K zRlgpFr2iG#+3A5-R)W7?dheX!zZ8DC%MeDPI}KiiFxvO@PS(D{IgoXI40!W<84K1|X2 zwJvHcG7xV{_5AOGBOZ-_I638wq!oWT$Bwt{bI>IuBP}hho+Oz3HUHZ{9*c7+t#g~w ztsnkk{tq#BJ^W-JOW!ol$-#MT#^9Ca-8gYYT=9wfOs9>|h6uNQ#nPLgi8fdbzkK`r z;>(kHr&S*sG>h{B64l7UuwW?&v?MaW1F9=vlv_N3n21&{fV`s^l@GvBguyKYc@_xI ziVQC{aEJYOejq!C8$5P_nm41`wRCiDPS7{nJvr%qit2 zri%OKz6We<0kH89q+V)s1c84CP;P=pnPXo+E?PBYWud{(0|r@XUELe3tgJ|SC_g_o z$U1?ag^1^E`RN%-piN@b3!JR?_s>Y(j5@v9?l<}p4lp!^G;w$zHsjD+jNZ)pIUTzg z9^isc?gma^Scf2Fkq)mdN>9V1byISWd`1rA8hDW5Z+AF&Sg4WMjSVLh9AEU8N9}G0 z>o)-XaRB8yI_mK75LzAq@8`7haKXM$*c zqkWIxHtIcsaXI;fP^KsvhBu*k@c!g81S}g;y!`p;n6Be@lBb$sV15PaZje}-_cjKO zT0!~Kr;%~3E-aE4l6>dN>M6Ss1i`Ev6q)*0*8cu0*lMlk=35fXJZvX5s527QOuR>U z?MBb=t_8gY3mIxupOU4>(2>^hhU|6HnoD2qFKHZ z=;2F*Efcqp;8qfQ<{@rnKk6(AJsP_dl z6aN4&{FP4*MWY>9tsURao&7c(4i-HKYrPr`XIb?8z6`k0?5%QqkD(%J+o#oa2YRO+ z(U-tW1q0@C3jfMqjm<>zp=IH`ZGkQyTs}jO^M5deR941eZh=axr@(r&Wr;9(yrW6` z@vYc@qUi3cvXeNqwY4cfB2ml=Or%Kk7_fUlcDJ@hP$8*&mXgBqC+FjZ{8$O4kQ@U$ z+bn#cZhOn52-61l$t(7LPmElr?5~-NPFjp#ub;Av$*Fi z{zUutqhe(wF!+{2Z;Zb1IllaB>)PkRY|{ic$TGd5+ZV!%PjJD&0cIQro@9_sgQteI zFAO?sWefCIL2Hhk+B^1RW8*X0JP-_^nE|RGr{sNFi22n8RwBA6MLFKt%{XtGwBvxH zF!)ByR}|wFenONlVwdRQYLJqaMu*Z|uQI2E=CuCFq1hRDvCmLOE*0@z z{>AUu8{HN%bPe}-{07VKwM=|fa$75_Pkdvwe&0AnCbK*}iIqqg-43Yf*jW=<&z&3$ z>}2gLAVx9~o8LWV=k4#vd^;Kuv+sB2g~Fyd7+Km~Xdz3y7j3Pl^g?+zDfP~_$mQ)f zPVQV661Q-o;g$BSf{#>+Gr7=yG=;tk);idPnY;!arpv(}1&1AMr4q4U7g<^D8je|! za9ubX-@L&<58Q7ea_;Hqz=d}JgeH*q5&)WA0Mehkx<2u94#ye>$QY6&VFYT17Kye@ z%DM~>b9kA6o<#s$SX}wkCA5!ZqE91D3U`8}4t+s-nSyrg@lt>{sldE@kw#&z`81re z&*9Uameg?-N!&#F!z()N=mzxy*YPB^pU7*qxWYFWtcNjq#Wn{;^_Vw#q>P{2NLUFZS|0~3oB_yFFgirAt`ZX?qdV-dD5J}LqdD+t3D12n=g1Sh z#MO*l!QN-QsSg|rPz)(N-k=>uVnRuYgiKlB_L|;y<12QnQGY9j9tL@d2p~E9=@Fde z@DGva0+!ggRiJBW23?!E>ZH2KaOXk70Xvse7ly=s~`Yj6lW@~|5h`UTyRY2puF;DvFC0`=?^%Oc%hJq=|YuCc=5n^EoXZfK)7C)hS zh8SLEf5E*w(2(5<_{ve^BwbUGUcJaAV=Jzl=3{NW2kCj0}QAlRx&(NTdh)h%ggKzc5b5v3cWNi^^)E#{QC7L zkBda)ce;pIa&&{{bFFJhUrsg4M9`HP{`$@xj_A*7%%6hg&m2s;&>3{& z18+Siy&<;Z!58y2IYE{#|6ylZbjZc8oHn_ja9XFj->yjv1VUff*hn_*h05rse(a5W zc`0U?xGaMI$!YhQNv*r&!^N=9fyN{Hr^ z19iAQS0XDp)3xGUEf+PS(M)mAU^lUMU#XwMw;5B>d#l=q0@ML z?QDJgK1h>tfj>jz3n`(K%BhJCPa&Z6lFgP~XKz;_>T&b!+WcADC&F?;y9K+AJlg|_tP-h?6 z78Ye7 z<1ZZSklK$QqyD)d3ST%$5G^AF*E|QYzzjDeaBm^#EmF>rDtd3Ng{*u1Eoi?@Kjl?l zwKz;3dh$*S9vdNgEsEP1-yNyV;hBcw9mFC7?*c61q+0r78P@uy7#i~wz_W7vrU;Xh z+heV1hX^wlm&bv+SQU%Zj;45eRxP-3$9P{OQ!_LPpC=FEME?*v@sa=r9f6xbR>Je| z;)&{omLHf%V!Y!gKd?=APVEZ2jx=|n3rEHqGLi))J!KGW5bI_+e@83b58@C~h<%Y) zR16uoj^2jq_-@cK62{gzw5GvuC%O}b8-0_&k*N`|F;IdJ!sSeUGjx;NaRqwVg=l?j zo=d-x0tF5zMOvxzG*Z5gWO`IRcX!tfEXb2#p-)~|G2329A)@;kzUn+;cu{ex<|a__US+e69YrXCy~BEvv+1LQfy#>Ud_TB;P%|-sd`T; zfCe*tPHqFlY!7o0V-g^M$X<(x%E45Hw7f!lkg=5&QgMSo(W9f3J}1MO_yyExIg*7} z_mnXLCX5_?w=QOH*W(GTe2uYF@)&bxqB~J<$Q%n8i`keX`n)4F!1hzxPJOFYHM36h zrs-XOFUg-ViEd&W7x@z>yH` z&nqVx8J%N=P^wqrX=U}%?K8ZBYcd;~ZepKFg_h&2laEiqpzpZxK>|@nPEECgh!&{0 zV3;q|(mgypK;C>6LT(UwCu;o)8o&%e@a50J5dc;m%0tLML2E*M0#G4>WMhEHS>}NZ zig(k9jyZ8`cy2rNLg%w)i+ul5kIOhI70|rXrLvZInl^7blm40$3l4xGr ztyD*St_=Z5p62k#rZXsrNv&2=DM6SFC`5SzsA95f3$$)VuI|GRoeSR9Os^e0SiM>% zaxeHjSkD(hl!44HaQwVGyW1EtD%N}F*g*S9gKLL#Ouwjm6jZ&&SFu=7l>-3-foo_83Uin+90>?<#U~tdM&5B@S=%H$VU)Jv@cPpHB)=V`f zCq~}q8t3c=W?t4cntC-6qz8blarW@+ZT9(thNvjUX#S|Udl_eTx%>T%z`Jx*vr0bL zytpI^TI823SXgtPu|JaSn{_yd{4>-Qd%C#Dif~_m$}aQPAo)d;hYcZ}ot?A?ZJVX- zi!ZN(j>IIEWElC7mdf5hmM{qQgh|!h460502n3~P2$^?wN&ilcnrW>xz$gT!NsvY2 z!?gf=N6t+Oomt=wVS9kPMiG*PLvdyMJ^;iRB_^&}Gu2VNFF-W@dh&bT4bnU5yv>)*9)qGwm?D}Jq_j34!$ns%D34iGv3}8snXavhcg;#3h zazRkmVohQ4Fyqlqn`>IH*pnNpU$@!s)4<=L8*&}@6@i`PS7{fbh39pU!3od<5-i4Z zywzxe3X7cC$GZ|xqe^JL0U!f51K1F$Py!#g3P$ElWoEZ&+s5f=X#9Wrk4LF7qTQZx-U<1q4_ZN$>3fVvGcd z#uR`0M8S&t9yk2DV+LU;S^o8ViVCZS8P@FA2@$Ke8vs`C7GtA6g3}TX^-#Gv$VPZ( zsz%wEDT(Q4e}?V%eah!qU?fYhzU>3h>cY~pB`XqsE4R9pKd#9bMKAoY3qDgKBBHX2 z9Bk#fK99{@lH&GjKHUGtz7T7P-%lod(>!6yrSLC@vqH+{>cQR~;_L%Z9f=%;Wyl;u z!>K=0-$WN4Y?4Da-JnzZnDt725M*Ym>o!Z+zUk1S( z9Pdl#-Deh#zoVa~wKPXC^0|ItC~M%NWiy|xTwY&pvY#H9fAe%JzlOCZXla_?-Dx%s z#|6Uz4kK?1*|OgsK5*sTw*)e;XC%#k%vgG7#ut_I@{dN3;H@jO4jo~5f+ih*KYUQy zC@3r4u(ZeM7xUJCj&)qqzeFyLeRQFCxSF1>ZK1k98;yDLmPh=Foh|x!D04ern}<2? zek(n5@xXTjw{+)pkrk%Qt(XpDEYgQ7Lx&?q4WWnTSpkefj#ku*|0wRGOAbwG{ zOs_KL)@S|dH&GHNN>6ffu{X9YZr<6K3ablSZDqT9CBVYkDxlySW%ItXP(*}tFM8qb ze3;U{76o>u?}f0oPAjBtu(CXo*MdkD$hY!CLYZH?-ucEU&%XU#YQ+aL`~IeJ{+AmI zOAP_lc|S=$brXbP8epvLfoZ>J#WOrXs@Q;tYyrEu`GZ&b>T|3>Gm_2->xjDnjvf+5 zUv`?grq}|UiMYh+h*$p$5DcvBUn}Hyr+FKTKj`dZzZ2Q4#4uAVb25Ut>qrwtmT@sq z$ag04IF!grxMFrnJdWP zv|O39V0u7u3az75)iRawb_WoAh`g0%j!h6b+Rg@;6|Mvl>WC*2|6 z3>kU))+FJ(0u{{JRZbUq4Q2bm#0Du&F8^xDX$p_LcuBlC>|0@hu(H<*t~`c z64m?IehmZ`-zPl?F5xgqz|6RfRX*t>JNFQZ$=i}Qa-C(pd-@4hxhLD}8uz{w(uxgv z17b_DXZT~bPlERFl74UGJ@bnz0NAp-#fP@*{CiW~6DY+QO}=B#_|-2ZmO8SM6U|to zf$s~UufNf++{A>Mvaet70%zZHI1_dEl?)vQ5X~}=WSJj7eiDR7;J<|tB8&DKV@-;( z$JN`b0MzqR@7K!#L4bKU| za`dsv`+^)h)bGcl4cSK|znb87STe1ZJBfXE@jONBybQ^z`0?C{dX~ncKYxaql7q`Q zEG;9oGYP`<{H30Q!QthL9;8IeBwkvP$IU`RLQE{pDZR4LqlrMs^!ki_)52?%p*9vj zUC2onsiwf@G))5G!9tJ}nv9OlrxG(+1>0*v+s@m{PxZM>-(zV1jxFSAb?8oRDr#Z! z5KVDz_OS70R+y1#P5ziz7}evh z!QD^HIBy`Nb5D}1$qbOI?!d^YySIiu1EM*k)xBMPm0%K> zPi#_-&un~_yIhje402s}1eSj;6bdZ6PkM^!s$DDZsVgnway(L~e&_Xfpb@HR;9I%X z=GSjzXqV#2R{*L_*jFG0g^p#OnVBOz4ZyZ#^M!>n;RdN1dky??o2X*un(3a>gYN=b@jUpD)r<5Y5xOdx{D-n~tyT z4wuDrJCgUtEf^g*^-lhKtN_T@)Fq_OE~P1)L;4hUvq_7{7vSvip7Ik-6H85HnX_=r z3v!JN!Bh-y%}+g`hYw|t{%0$FEQg0gDLBF}<`8Cf&KoJT661;)eazK=KB}E}xR%AZ z=Jjzdn;yIMYHt7W%<+J>GR45<2WMv^H#co+V}~-vUBBv27fxZt#ovU~)oNnwff@-$ z>K;F&(YzDniz<+DecQ?0u3GrRF+*?1lcHH8SvH?Kgs>G7_0l@iN{|!Kh{ptOp21YS zXmjw^%~>63PI8Eg@jFwrEZzOkAdbx6+J<7>#DQ9zVf&jeQ-VXIgHY2+x3<}?meI&` z6Im@;9#Z0k+%NdH+iyZhjIv@}{B3urc~*X@KZowX1(!2~9m|oZ<5|W&2aEZ&O9nuY zLbL~%Zn;`H8z7OpTZU6{Hwr1YH-5mFECZwBzesI;c9J%y?N0|!u2mR#yuX%}?TW;j z(#N7CDocJtycqA^1@-3&D(wV|)}u9mAs-f1LWA^J4CsDCB>uvj-UB0hK=Jb{e!O3s zcN{-_dHX@58S}9)Ki*kLGYl_ee4LVkpBvHCK!Swtv8H3My0bqiWt3x> z@`2jcCOpUEEp~rF1{F&}myyTQmoeO*JPT|WwC@EyKq>w5!1QMj#pRA2BI)P;e{9m% z&oMu{;`O(tYVwVQRfjUlYPA${J3L_8Cbczjb`Vyy$L|XOw4T)T`QwOXfT4l-P3dB5 zH_XL$R;;hP}yM)$Y>DcHt?J$T$l3%*BK>X7`W??w-~5Qm6XwzXBTp)J0f^W=XDKHY#E z9Vw|0Zd(v(!|EQ~4-*q96s`yYHU{2NMO9V*(^IF8c)0oi*8tN6cp2qB34z50G}uO! zDg-YnNSUBTE2QNUu8_SZ6gW}Qa(1VzJ1D(4nu46sv{p_=fM!eG^@7786XQM(FWam! zZO2Byjwq)2BaWuTEt%uz!~>?1tHQX*M?ih^f}^WoXbdm@w-maI+i_Gocl7ocvp^ew zE+8U+rRiIEV4^X5a%U45Pih}mt8DJ8z+egqc%rz-ZcjgVLVDM?>+7#Sy?)J5+e)!5 z`E=g+O(yJJ*m59A1b#(0lxSX=tn)4bq1TH1 zvQlvd-3*k`DXL<9A`}B|Dt(={A$Z+&a+)Fgot$Tnq(j3vOJCu+nnPJ$xdW@s(0~MO zLI(&O5Wq7;+=-+gtwxHk5-fzdcF{J;d)lxkb9{S{=|r^Q5Vb**u}D>(x)Cwr0u zPakXnjn>_4jGlq(?zN8VDAwV+;%4q;D;Vg-Rzk#SbB;_&Q@*yAd^Rk?#rr)d~_vFZ1mjE&d zBUxe(D=uhVN)@uycv$~dt7vr1(e%#j!-t(~jz;o9La6qS#HYWCn2KzAm2{$)bkgpO z3y0Md%J#6%%f8;g+68d zdaw7Lv@vo_3C@L6W7|o4lhQ{NZLTygx|fu-)~i>ivEr`0(_PxY^QWe!^2mnvI+(W& z%DwpO@~245WNEYTFj}s2l|MVF*=@`2l4fzqmYZV-582RYq8}YHZy|LGvwk0hLWrz> zase;q@;C-<2?-21ZwTxhL3)6)NmF~0a?R+#r)g+sd=J@ss3*%23~+;E13I~{pDbo zN3i`HMb~u2H<*hKyZFdQFi-!Xy;!=!W4W$O9O_zi6(5E|cO#n|;agO2umF4(q;q|1 zb?y1$TDi?(LUG@-_kqzQ2sRGa67@r`Fm>YEUqOkJzY(svx%IKzcFTV(u{bTMUqa4r zK;(&zfe~Q4;@sRlPZ@`v3u#X9>a9;7d1QJ~J-@TiCK+7t@A#$0KJU`P=$qFS{~n1S zx6o^T7F?MiDlRUGW)mTtb#L>+Q|nff%#T9}XA%1(>i?@U z+OLVAa6$$F=aW1EauO0j+PI+a-{Wk#cQDaKBn$8so!>w&6H@aWZow#4TtAI!xZuRz zSKv=T&4>_lgX9e~PszU-nFf$F@o~hJ{`)WN^b}vG{2TSI5swOFGTYr;I`P6%Ot8e|4?Fe&< zIlr|ps!YAFohFvU8PGTOlIS@vp@F9pHD>dGUw?qu>g?`cj)kDAU+DC>FD>3*(M#_x z8fAs9cVYi{rJB{$7x+Z~P1@;u?uLVhE)(Y>$P<1)9wSe9I;;Fx5>LHaUCl*eIN`(6 zgPS%fEp3eKz#~mBXnZ~Frf_IHxQ@0b(T_W-mpZ%D>izq7-lZelo5+TI#6qq5#NYqY z=9>B1$Cq(NTjEKGp02lKfv_fG&v;>ZfTRv^ zco_UohojwPs6m8=I47S!cb~VO^WogP2U6=h&dq!hEgtYm|8D-EFcuahL&N?SAl;XA zt~U?F?q5*<+N}M13m5`;fq#12y>?-6em#V>$ZG!`K7pQc{o!8!b(E)st?0%ouUdAp z(kO=k;y7#iJspL893->E9-jcynl`>6uxL zLjJstiJzA9JTaa{JhOeBM)e4vZ7~%iRr1YfAKsc}D;+B?QvE}&LuNHK1TvEqV@Sr4 z9=Js>1Sg5xHz=QhoxVVLVc=}_L~FMM6gB}ecGwuwfT-7-CjVLXC&;+VL0kLcB1!Qd z!1T}sGS~QRn3TT&_B+@TA#@qGJPvophrVkLoqv8`RWMf^?+JYBG-pis6|SP^?tT?S zWSPp6X~0SVZGgr99>i4K?lS=%jQG&40c)&xiXqH-*c z>JO{?p%(n}K;sW%mBH>s;z2L5;m7OyM|7>&_G9q+EJJe>743o5~P$KVYEuV!wGjAINlL*E#=uP82!52Rh zwmXpnc+FgNSMN{}^vk7Du((h^#dsn4Jt%p8>AO$)Z}j3d~9=fPQnTgBm0Cbw?>uz!VM9?fj{(TIaH>lg01W&#e+p)XshJr9 z(+4m^2?JZudVM4VntKrX7?_xdO{GF3NG1@Fi185iDi<&I-fDoE?^ zaeL4ipUVDt2+j2t(iTB3w+f9gxwZ-gqelDjgi+D$LiHB_Rf612k~R+3Huz{zFbDWq zt2ZZ9C7B{Nl8`dyW&H@3n1uOH&)1X+v2<87X0=9J)@|8S{P=b1wX>(tcUFe zS5_<_GztJjgay4xkt!W=qnMdVBz;1fwsZS;b1p^%4K+MgR#vdShvHP~kgU2Be^J>m zRkDBDM=@9U^lv)TN0tmy`-~au8={>5u+jvkx(15O%q`ycxUpKI6Uvgq5X;4|96W?ki-ZIu?x> zt<(WFrKPNUo9;aCqCIY|8y%7|`muFTts67il|&Qg^<*uh@79cEcvzF(XVP(pUJ_c5 z8E(yu70Qg{+H~Vl$<~6KBBBTlw3lfC;hQCmd&G+1Tp~}eAV4~yg&ST=( zi3c(cj;2ab-DiIBVi|JRd|~BDfyyu?rIuhPp(-?klc@ZY6fJXNE#t}{=QXUR?9%i0Gq7iSy&MDJ;`GGAERw^Shh#`n!R5 z`M_~2#OcD41^7YWU|h^W?uQ$v>RkKh$a5?eo_rmCPj9>8kGHS+(+SAE4gNMb%aKPx zqQ&CehlOsit1lfI=U~CRh}q%j<)!y_J&PV2l-kI~D;yhZYgv#>20s(-75*O5;j!`s zp#B0|aG)p^<&5Q**_eJ~M8<8+bU5hGAr!e2@=syur26_hg7j5%zp=gWcc_iP^6|aB zy&nEY_79RSLJ;9~UuO{9GC-|jQ=Bzi&x~6p{sHPDq(-6**>OV`IViG2+|OFMj{HDHJ~al(Bv2;yAUX^YgD1@VYp9HZg(w@|_-tI^pk!pwPtn zq_Fjw>Au7Xk(a%k_79!u--rh52r#z)GtA^}A9>|t9GTDcUE%L`Z|_bn)o*k@(hcBi z@FsMk!`IXYLG5>1G->ASs=WLCjs!kQ6O@x`OTsR6IBnxB1Soa}dqc-mT#eM4yV=5M zv`JOf^`X0GmI&4J^^%RE;j4|LY@|k7My8Sy9%C{j!##qq9t3#K;n{AO9y5uRH*gnA zw%W-@HvG>!-wWJGQ9{TrYnlv*$yL9&nPJ7q`L|_-TS9 zp1Dka9DY>x;P=)$5mP5Uce_`(H5IrRsU=DLSGd22J{LNF%B&gm%l3S5=EpJPp;kCp zXwJx)Bg-Qg^E}`-(jslMR8;F7L+EGz_$D36JvzJS?*?xj2(8bTj4Fx?yY?;#DtUdx zEwM@UZ_vy7DeB3uweL&>-J!ICh7N(kZ`&olqou;|6dH!UZ6^@Q;ESx``>e@ln_1UF zcs%zp(tO~V?uK$GY7Sj;MOhh^1nz4N^W*$K=pY;fH2ZNXcPks|w6+5U=>6fxJYUN3 z*#-D$T4@L#jD2FL}Jfl(p#R{h(LG&h)A8C zog+DgmMj$J(O>9nMkJ;qW>ef@bB+SZpLEgLbbWtL>5`HDh<#qVas7Aec__O_GJy6N z*ii(T1qL%r&-t^%kvH{X)qpPQc#9NirI>URl{iTp|b+CZWm{6!&| z6e6g=78Mdq2l#UY`+Zti`zEKR6B80TjM>+`dCNCZaL;v&Y#A)D#r{&c{{!3U+_46_ zrJJQH`a*SktG1%g!`r)Z4@XO4V25$!_MA-$uLXd zzm3#UES_{33?G@DFH?zKpI&jvYS|<4JjbVYKt?IcHHz25E_VZs8wfgsfc;u31}8Dd zc!LG3P)of#g?Jf}!#yCB3xsToPeup zilMVy3$7CeE}T1;k?Q`(f+`~4t-96SvCeq*;vX8BIuqA8s(69f{ZP8fIO&`t<2#J8 zEK6nO{%CJlr;nHVN;4@~FjGzL*3n`A)NBr^DVY0Xj&Xg9oyMaQaT#ar!fPGhXkp0p zpQ4tM&)*+1s3Jm$GE^e3wRjcnP-E~R=Gmzhymh%adHMHkSTNu9^ZNRF!!Wcel7-&T zrl98^@%XtCa{5(*PrPvWErq>L9lEc~-@g;1*S~Mzx&Au}zry0aLCfK?lk5xTPP55; znNJ<>z_-1Q;z5R4I!YFg=gvp*djXsds}jg_D_k7pXlsS{6!0(|Bs5zZ9d+1WB+Ie? znmFJh?~U&Z#~2T4-QV8s1gWDu*#~N8zf_#V`hn6{EFN=Y1t!tGVSX0?xkMa@D`B`e z|L28&P$##rjYW2?ONOcVN9++M;sb~CW%Q2}^mQ;oB1|CaH3}ogeYg+{g8~om)YMe_ z#qow=l_r7`11~ZJd@mw;46iE&(fUwxVGITHgUfc=7kJ33zJ6uqkcR-L#YH5b>Y?!t z8TPIK^w2X=d*L-fDfBr(YaD$(?^RoFkd;DZE?T7wZ5+>r-@K1Dq_9^P{K{H)d<{}f zPKG_$=pk+b36oM4y-gMTPvE4x(GEI)#kYD&HX_MQb*5K7`URQh&!b%AXf!PB^CWnM zA)Z8SJwtRKYFfbbg@%ME$O1L()a(3B^@!%tIm>A)fk|`R4KGIXXMiz5DyEtly znR%Ka!*N#Idnmv^xymOKNg+()zuz75>F$(chNy`T+H=CTj*bpw3;78nKv$z`*z~bq1rws81!5$~dK&?fja-D&$F*NNOK_cj2j8*5Ha5 z?J2?dbGgDoW}j|ragng6_1Q)=FBz@G=%T0o6H=05JBzLHc74+KUx4xvfk~@eTAMa@ z;-r6Mxpu8{!rS)@{_F*WKA0 zK=JH@Qfq4?vANFbeWKRtD^$%2*6zddw}fT+^o#?ccI8#X0}P}H+*0vI4S6E2n;i8s zXW_Y;0e^Zw@;1j0vcaD&$3rF{)B(^HwAMXPfz|aAGkQSqZvziq4N@(S-Ry@J9z)}^ zu8p9P<@jU+>MMcyz!gnP>db*{quL%R?{#KsjH@Hc!3xs4n5VEQFcjRoZen&h;QD1F zMUnXO89EBG2rCN|zfrh6we3-vcmLzQxA3hOVe@l2SVV?zGmELx0e}D8Y^90tj?{g2 z@Ge208e~^{Lr516L{TBe-os@yumBu_nE=9{ut89cNaCP;x&WaC@Wfmn1POEr{5uv{ zfq9>VjEo4Q6oSB*i3uYUIL>dp1YW;>?XMsSLW^{M&y<&uUs(V&hlUwnu;)>e;pViq z>LE$ElJ~WL1Rb-kzv%0jJ+oJ9$7Rmwt+2wTUWn;OLoQlUh9O^7j;UnF2CqMeB zV*9t$!ED&T$ev({;3>iU>n`GgkrW&Y5_>=|1D2ynbrI4g?^EF*--k6UUDG6(sP<{0 zCOFg?K4hJWx#V7FBeycRr@v7H?kbEefWaLIFd_D2|7oj<%0-Wi9EX57B*)K_y0}G> zqE9kpsxu`sZxsT>3hc>93hK>~Tt9yN7nJt=*PZMminy(4>_lJsFbHWQ8gzk@DEMK+ z;afQMe$k@g+_bzX5|w~njmrQ5Sbw2l3K-Wc`e{Wk2vgyH@`o*Wp^I3?tAIS|ACt!8 z2Srxgq=*Uf&Hau~Pj^Hsf7v4^PjOL|gt5NCwliSQYF`MBtR~Q8mm<3OZpa_}&0@G+ zR}aNKv7s4mfSbZ&)b7xLay zvBR&sw?;4U&abm2Xjz&t%_N{uKqa!NN!)mu7QR)i{?D^DBY`lbQ}e%!C#+ZUyyZbW zevI^82ilnK7sRE_76%D)L2-G`$P*t`$$IiuQ6As$let(#J8R@*mEaLZOjdbq_D+?X zi&szG8J|o++a7-U1dE)(ikgRUN{Z;Q`YHc)fuueg1)hUB+OF;0{#i8`h75*+_i_KlP5_k-R9mHi^i(W_KcEbY*EkK}41fki{k-e3*HTKKExj9`#0LGvX$QnT? zO9^!t?c$N1pff?RqfiDD%wyd}q#^*iZs-z(JPR!3B~U3s-!HKPfR9?D-(&g_5%(}T zLc+X~|EoM$^W>q626*(_k(a0U|Fiiri&!`TTC=RK+(OE4t9M89FTAx^VN7PL{mTyuB zHD}^or4-Z3iVgx@A^R{M2Q4i|GERN{m#S$;EQaoYYZp`u>I}1te_NiQAOlJAf6T#t zI@}^J*u9%{6m#sXtgWzpav`AOZ~OuO;#GW1MFM#s<#TLgyJTCMUhzFLJi*Epw{;mZ zM~C-VyAm9D4a3ME8WPVxv`*T`%J=yHdxBjjcBc<2iEj)cu?TcyP}0MjE<){jk-3qY zK2O>Aqz}<-3P~e~63uS-3VJ%P=raexm`xt>H1=oGkl;WN#tL*Vh{GBOrh85+y0(Qs z?Gtx=#BpdaK9JRZRf`wOTN6wwT;+76sCkX2QuMGWTiN*a4~h%+z^MW5*f&aKE+r$H z+Tq`>t+J7m2)&0;RjTf??sx3aqsZD(>_1Ced(bzaV)#SAyW2Xbh2mabA*v66 zq6u$E8I0&%E1FvWiP*mJKTcH0$+{)dkz;5W7*JGA{5Einv^A`eom+-_c6Xb;+1@)s zWq8T5sLON>g&hf>HyrgXQGI{5c(hjXkHGh2ADP=P=ldQ4VkrJw*?XyuLU@9T*XORD z{sU|oqSZX-pT)*MNgwt8H*v4_)dc0*8Rc%d_-=bD$(h;iIQ8>HctdT8-#VDep1gUA z_Zkzyl4YwQ{ggZ->iu9~Kw%~l*Q9-=>**5;Hv?Vg_3>GcD0}i}l-ka`%l~Lq-tg52%~PA%CnU?d zK8;1=ZMp@cc<|4FuOwK^jskTtsFD{3OXpCV0i`}w8cd-m@cqHF1hOs28i4k$ocem= zHqd4Gmw~-W*iy0)jou#NO9%5Q;&t1etXKixuMi-)pmSJ3?@=1ftZBQ@cCrJrHgbjeBVxVV%%i0zkc)VWM+y!&R z#qi^T=v)EyDbQA^fE06}uup%%19!^MtA#3V5&9x-@=m`-tA~XHlTI5XDtzE+(wO4+85%}rPyR*03^Y_G` zyYp8$k@RC34xEeCbsCE_PEENA5Rf2=DpR0rXSqlc9mXMOd`t&K$u<5!DU%^DQ zPsGdF`aK-8D6)@fga*+5n^e*uBcr6fC9F4tNFEx&6R+CW@0|?QwAA_o_sk>>X>4!$ z-Zo^G!RH1cHFkDY_)YYk&p(^}ex=m&4w5HpqP8TqKkbKjeEx2bcGp2dO#M=YdF-4= zNgX)KCHqEv+@OFi``sB%xGjC!n?M?k;eFpyt{XgWz~AYAyr~P`m2>uSbFQoQAIj(y z>b0A^2$T@)1K$m3wn23gnCcg^m^CTRw`fAceZ4aLUL1BPalxFKW(r|0pq1o?aq=xb4&k=9XV#mLEw>kX^U-|S3bz%Z$%|GbvRLdfbT4zHpdC`P_01+6+`s1#T1wT;-S%Ue3Pq8!;{UV& zkCH~XN77c$`@^A)iO1p=;buh?R0EA@J4O>nfb>5J^2CHK1oeU&9oYHc+6^Q`+T70G z9#w)gBE{)%H;b1KJca=4Ah#9`BTSKyyG#O)ca^5>l$FB**dlqZPYMLOD?Z*>QtBX@ zm4M(!G?d!`0n$OGLOSoZ{oDgWhq;}$h`6}8{O`Cx+S9B}TLeV!!0X$wW)BXow=h@3 z;{-BsVNx0AIw+Sw+!W9%Q*J9FrjU1ig=AW624ocGTC^eS%mUYXu?I1ENPBq$J(mdda1^wQ7vI zcJ21?D1EO=u*zp#dAZ2yB~U><#B=*usc%FeARBo#G}{A{tS2W=9u^i*w8JvwGllA7 zwE=R8MJUVS_Ppdk(@=!@~zQ7&MK$l}COLto|90Ht#l1Roi6! zam;$5Sx_l|)MKnfJ>7*>ktXwBoKWe))rTER2aW`f?-&4n7{h;b|kg@r(SvA2;XF9+0Wi7){~(|xNIjZ&p-y$kg!vV+%7h^w0Az}= z3yn-p2Ekkn2u|2evcN^Zf+EO=z$Sv=Jt3My={~a1>?1;F z5ElU(2ZujGKLZW*A!d94-o|wGAM%%5dS-H=5oU= z3R^bg4=MP=z!64VM~Q9MdHAOEvqfon@v|$VGaI>n=>{VFe7QnU=GJ7XsHS$WF#dh; zX)vo-TY67extw#WAHM=JcF^7;1%bb^aalPW1a;5%f?~3bkof#6|yzF0XjYIr~SVoi+ zu1LfEegk*e*T{nu#L!e48Xlfo{e#>|C>(ctdNeP~5_0NK*1O|O`j|GIhV$&k>~JEb ziuW(R13PVR>&nS;!pZ6~>d(G2+;Q!M_?t})x)T@a=NQz>T`R5@&kO0~)4O$LB8m`M zL{{~`T&%fX^6}{s6GqU!-+HqprEQmy(lrmuXwiP=y6!)Z@uLZI=D+)&zaw4r_4N&p zclu8$HP1yg!j*$r(n{Bc?3jS0j-_iFOcLm!oLKH{DdF5%44+9i7bWVHr&c?7pK z;)&vTV7?Z;1ueaL-1EJvuLLw2eab&M?7MNsxuq=Ms4nGZH3shZpnpOUqmUqGl3x}r zVyRWKtRFGjTT+@cTlMC~(&iAbEFCSs2*H1wh|Da4hP5tEjqkcSYYGFy$ zfp5YkdLwk!;|rSt0D$hCFMjAWbp8Ibe`tGxCs}*1>OT|rVhsf%67y1~QTk9MmYE-MXPiRTB%QbrNVzR8G#$(t+1BneM-< z&GXo~t-EEO{87*r`&l!w>@IEcVNjS1go$?ug|mseSD^|iH^fyIE*b3_voqR^#r zQXGxR8A6NuY3iC3FX9!Us)_JI+PTfQL2>r0_5>h)++>l|g9U{$BP?ULIs7WT5=hVa z7Ez@SJ^zUL_A}2Qa=grAw9(PJveb|0Xlo2-hQPgqPjkRzh-$Kf}$Y$2R*Wf zi<3N*q-b5HjYYcbW1T_?AushYGNsn_es?x0`|1|bvy=EOE2;5_BEKbw!}byMR;2HO z*!kp?6sj1>KEj>W+e=GuwfIkNuK`yM9xA{rq0^c9&76w9LBdq#N*aMj&?Rk4LZZtj z%}=CcWVz+#d%+loHSF5GKCX5*bkw@xqSBv uH4Y_tvFnx36IGte&QDoYjfy+3jL zO{9V)YfVRV#x|}+`7~e|chygIe4U5>1$g`X>T&XQIm!a4o}1Sa%#`M99vI}`^S<*u zJTRh^!KZgSZzf*}^+@oZ{8@-$Z>P`_lFEqh(C_xSne%?+Qx`3>&+0?N!gevd(SEVz zWCzR7L?v&Bj)=ydN&a-eTyIW!gN5!ZivD5hqe(_t6%73$%a=uQ5rWZyS#Hj5*`m%= zCI-46ZG8_kZK_iG#C^vC6ASOL#C!zZOqG^8zZdDf2yyr4c%AOD0o1=8PFR=r-WKMi z%QAj{^no++Jj1q$wp*|ytY+>xDyc_Wqix8W&u?YZuiSrOiT@dYNa%|Gcsml6c?1_U zr#%8Na6ii$!UUq9ci9s9t6^3Cme zePy-E+n~!Am&l?56eV{=^GFP8(~5hL>~x(RN8)fT$j7*|F^&^xe{XI1YClDxcvR+J zxSuKi_mmKqbN|w9;$^UNv+iC@QEiZr`Rh{?P6*wa-F@--hkGA)m`B*YD=#^KEzo`d zG-%P?p*8!#;o;-&OckvB{68ROtZGW-zgEZsxQ`vMDm?&oCg9wJqPT=A`wNeB;C7EL zc-2c1AY*c2KM|L}_k#TKV-QfU2S5A^^#QOJBGL{CY9ApJ3O>dmsj`8B)W8%S)_K9- z^YeP@uNWzcISRwn!dBW{U@%DDKbMmF>Icb-YxXcNbe){krZMw-T_+i{yLPegCCf_R zTzo;My5u(LGQFE=MRW(^DR?mlHkh8sQh!%||KW06z>{3nbl$vLo5VBOd;tH>kH_|H zx09gLYI1ARQaKyN9O&HbsyFU?d4bb!MPQZ~cRKFWv^$5ovUVCXNP9T`7gOF^I(dC_ zBmM0=*JRIsT4#?vPsaY6zFHN~;Qdn&Yv&tX_(!O@l9#Azrtjz{X0-auD{5MftyO7{ z{E4E+VdHU50bT-RxTA2B!iMz~Jznnd399cUg#U#!5g#6dpxNY8y|eo!evu3Bi;N-y zR--|+XY7}D65&PS?)O!#N@zWI{@KL%PkOvaWSS-iV|Kk&Txz-y{v+ZE&1`DyknbR9 znYKQM2NvYT5D5sL0Q@hrLuY4P8J=g4LPUMxJArcxGB=R2|5{j305A>)yOZjxENJt-#RS8 zR_nFeR5YhR8)x_>E7`~>YRo#^&yT}2)h|+_`(T#rvxxDfZ1d0@ zwP~RN<)2imSOfx^27HcDI&4BIV#Rf|7MnT6Q=)244_ZE(*%IGTeaD$pNGYFWv9m*% zQ@@z4h-5j^k#@t6MX(c-iOgbI`nE$pv=ns}#XriTK-2jCn=^L7c?Zm8i8>Y8hh{W! zFJjLR8aszXWKU(|aB~OR-HroH)yqm;^iL|sYsAPI~`k)z7z*ER|T=-qCwiQd?l6q4${N- zzIO9KtNj|{^-)*1PNhrhitC6|ggtjyQJSdm#0i6>;|voxTs~o4)sRz`;r=mdT)^Df z7I-yN%4CJdn!>t%5E=c4LoIn|?We)N8}+#aIxnf3aIIAFT!sB8dB z+#p0$zUz~$C@uX7=c*o0BtzmzdLq2JdUwZNbJ|^XUQ+s-^hV8uT=Mg@)`nTADwMY{Bc9nrnE@*Og><%h&g@{vdVj>{&vM^|U!nM#nUbMj7& zxS_I=!bHu2fKafG`Q*L2!eDT226JfcOz2je*YeQ^Iou#W$JaMR(KgoBP=bu(mt4qO zFxn3>gz$nwCbrf-&~c4Y@_5l%99KZv8aX<~L%uxEww9hAEdbii%@>d$2w5{GMn=BS z=m4Wpp6(JzPuA9z?PB59%h9nQd~+$5`M@gXejzCAvAsaNGSx-0yS z&{Fesb~+--^?uSg^3~I(quN~Qfw#ih+1ljllVkWLmR-w*bYBU(jmw@T554`s&D#B; zs`i5*zcXe}9RbCwJH({sb{sVcR1BfC^cK&0+&|bvnG>;h(~oPv#L$k8C#Dg@XU5>* z_-~}pNaDYCd8T`R`(itEN;_5l6bM&^Rm)m6{V)W^YhV<#Ziap5@Q%!({6dFV>tpL z%1>=s9lQeTv(zV=Cf+%|iq-9x{Tnm)RPcyqPU7l=kQy4XP32Gb{Pa5Vc7g2xmM9Cz*=ghBvfzDQ!1`5(? zsn6N^P{|bu$xvD!saS*qsWdAgZoIKk6)nzpi68ebm|h#TpY?o)GeJek#1tt+jbTv9%JN(zTWLvw!%kO}Ktu#K9$S3*+gp z*-4oW|9DYxXXo5CO79_~obi$GsxH#nm1d=N+IeePNUhob3Z*^<>*ispm!&xh!IiUjHY1(n$f?9fxGuiH~oN%1XzZ*JK)UgmJ;+Z2cotFPoL z@s^x0$AsgesO*n?xoVSPyt67SQm#*>%p_Z8Tr(|os zM6o_XPci{I#4)o$Z~`9u;06@9J&c;3pXVCGQU7JJ8D$EEzt?z?+-Nmg((1CiUZGh| zn-b|m#{Cnoe$D*!9>+0Fr;*CIac8!7POEjyXqja-cZ23+QusW&Fm-vR?UNUqvNp3N`vk)XAAOQo6 z`+)JjXIDqg@Id>e+cAFJqnGn%TSp=1C9sb+sRB$-mEiyDMO}ASm5OGUpfdM!Wdu2agDLKZ@^oYXXemCmljh_8N}`QbC0o0+F; zNgN5^--Y@4PZD3k`ty5NAcr6f#J|;C)O(-`x9{Er923}|I9b}fS$}gDK)Z$5H-$oa zSC)>}29B(JjjL;~%g>oARJ{^nxvLHuaxF&2KM<`9ISli`Y2;lN&;C@R1a*MGOarfk zAU*HJC#l~A8ao~3d{$5VjYJ41f zSjOhp$S>KQv!JP0`7Sq?+rL{s77QM-&Yp2hq*?HEcTJ%3Mes43d@{E(Uo~h(ovI12 zO8)15jnD@ou^raWUrhDJE)e{dEI(=Kia1fl9pk z;Y_`s1r*Wy0s?hB8%8Mp9J;tH1v~^VRlK)W<)ZI9bqt<@Q7Ld&KxOLSk00>9H+=lZ z-zqYfWKaiX-#`rfvX)mZKFC2>#2~y|qR*nsra+ltZ@wjLc6S}P<4>uc{$-Oe=6+8z z0JY9L8=FLS61Kmg-vQ&e=0B0$V_3&sl$(=g zZiprxuIYOhdl1XeNSYf477j^KHS`1)efr$O{U!vJp(e!d8}jkM@n8j7NDo(^w&j#U zK)aS?y0#NT4SH`@c z?R(gv?I_gxSoX1c+-Loie-GKU)6w2X2F>X1S$udj@xxZHIed6bq$z3LY-X6mh~(ZB z1^qL6c<~hy+MCD+w;wrESH5Wf8a-4v`JtuR?G1Y z-5nYXA~q+nFtE8S;>)=eM8D6Arn%p@A4C36c804wkZPyw`KM_vFXd6G)EeRfhLAAN zz+JTK5Vh9XB(sKsR1X!5mVzJE_Um%icypOqA60#wmQbnNoAi9CP&y$q2gf-3-yh`I zg?&2WFe!bfc(tkV7`ZZKv2WpsZ2MVkgakv!@_ zwhi1-RSgZnbJiPxiNJ3Nfx8ez%kUqX%C;WM9OyZ~p(QsVRHaE1*Dr~myAWMk|HkPk zuOd!bYA(qPHC~LAEk&_}(1lNsXpdB!kRl=Z;eLTdCXaG-!ot^GYSTH%vIzYWsWz1Zr#TRV)ezh*F^bVKG!6SSFW0$1Q ze{kg@mxWHHRmz0Fu(B4D19%Aap*(2)GRSP+?9-b<_ z3#e3Hc(^NZas#*VJDC*OPc$4*o&f+YB2t@XpzOQ%={^ihRz}Ac9*=w&CH0*KM;8j@ zrWkk1(k#Xq|o)eTq{OxSvsSB``Ks^vUP;Q6NrZ3Ti6#)cdNP6F`8; zifnI?s9s+|co+k57}Qyplv2>q(dAtmJ2|PL`#}p=waJ)mgCob~s|63g;SHvmW`bc- za`JVEl!TYIpC%N^5kg`>YI=dFFo7Dwb|_zhDIuEFMbG0<403h80bOD9^$;C+SNneU zWLb7dDIHh?wX2{uZKx$(BcFe#;a94taMW}lAst@fs zxIepS&`CL-tV|`DENm@i7A06Egq*rOu9=fJlR-ACiJEJ9=IksY>hQ=u;QiT|i0m+G z2wi>uYNlX}w)?$tPEMMaSlEL0ZGC#Lh0V5EIqTGa&Ad<(d-G0uvZN}GiKuX>kzr@- z0M0n4dYKO^rM+Nh*4h%YgMaN4eg-cewVEU1wxx3CM6R-kS9MRL#|YBKe-O~8F9)7^ z63|R#j&Y+^5;q-5yV+++XmosOAg6Lf9Smy|CK%1RsIqjv*2W9#?xr?q?fK7-)4;^b zmVB0}p50UzZJX&0)8FT})r(jXQ5-+SeUswYT&CkbcZQL=6y4GZpUq8!6L0I(#|Ig5hob&QZ!f6HF($pjK4bJV=cq)M5R`ewT7i*j z;koIQCVr>s@7G_81ru?vLkQhWJIaev>p-=ToRL9?kEuvc^pitwCcoQ=O}U6@$u?>K zXZ@l+8z8S z)RpF4Z$#rme&&%rv#T)JP{`mP0=VVhroatdr;y%_r_-;WqoYt?ZsOj| zVfQL^2(BH(&toHotnR(gZll=E(Q`V_{|e*Bu)?rI$GD0FSn;Kq)_~$tPA{mJa9SHS zsv?WoB9Svvph6MV`}Xi-aHr8XyM5iuRNd7&6w=hZ!@`kWT2-9U`B8aR^4x)GF()<7 ztQ-7fkHF$UM&%G9y&)O)RGMTtqnEQ&@}G=swyjB%74rv=DtnYWZ_LqW`<@XrqLhcE z{_^QkQTsnFz>y-0(0#!-i39z^QO67dl4jhJ`6kTuv%A%Jn{N+mN@KB8Epny|Xq1p~ zX5$N^WNE3}a`qk&v{jtlb6TlQivIu?QB%`*xKA~;w1h@E;J78ng?r`6ND@ZOl>Z@| zwo+C+A<$BqlbNc}zUsq{W?c}bTAErqjlSK!`qgbp{^U z--NYXtfvx%i9xov@f}4B;~cGtU%v<-pApQo@HOX|Jczdm-Grit(S(pIHP2B<)PKZO z_Vj1BDT3Y8b6I*EBT4krw(&6ta+f;s1dL(ChqNtBxlv6W9b*%d09eprXy0%9#}7rm z9>+tkz_kf6heI%hf-?;wI@5u+fEI~Ps5o7%s@AB`OGwbdiq|aVJi)uyw_^9cu8!#U zkVjLTam_@3bCHEtK$!lL5mka&TYdWY5XCz)!j?BOI&$)C#{cDhxj|B~yO;P<#LN<9 z&~z|Tk5}*2y>eomJrq;R2kTqT-3E#^W^kgDQ`M> z$40sE1^)bePgY&!f5AT$cZ{7)L;NP*=aYSzq7$lF@6B)26sYBujd>;+yeFbKmvh1P z@cAHnFOf=aEfHQQUa-ZRuiZ8@ijy4XnLYv|xBihvbVDhL7`)7uHg0^41}&$POz&|Y z72 zPko=OL#>W^zUF`4ToEmseEsGprzZs1LEmx3v404})JMR0X+gZl_Bhq#c=Vrdr_NB9 zdVGRQO5G~*aXoR*+#Q^{F`1Uj|3}kRMpc=$Z9o)31!<)vl?EwE5s>cg?gpttgGje@ zcXxN^p}QHnn*-9{=3VQXKQp82EM14^+55h)+7PJ{==d=x4%FsD*5tBQN-15sj&D(C}cnH76`{|MYLlChigj8#tp#ka$*84Gd95 zix&9K_zJ>SM|rLZ0B8=({sSR|NWHKJU0q#ou>U_VmnGOR*e6O(Aa0gB|H{fL#GJ5+ z_V^!~NRHh3rF_kBfkQFU4HdjC%zc_IqjK`LQg#uDSTVriChVd9K*Kgx5XF>*+{8IT z1l_$#>vMQCG}1%*<$f~@0!qi(mxNDk5Msr0^7#&Q$f`OboC0q8xkImhn!46oujDO` z4=b4j(;MS9?P*r}<#`?J&;Sk!f7xnbalx69cck@+R?*U(-0tO{9lp}f{N8z}dYvKv zaipE&rnPkn6T6Y~$s_Z#;t=X&XF6PO>B&|b zZsO%Fx(>R=5|tq8E{xzrmW>{-n!2L94OH1G0_zo@GFQa1l`-%Sl+8jx9Jr=1 z0b7_2V4jW{*JCaV?84X8F5o98MrA=B2c6ipGGJ)!>#@gG;px9nFNa$~g+Vc^! zzdiLF>G+v}9$fOL=SWlOT62yzIwXwJhIP0q>2+00m8g9awi)i+V%5Ypdq)S!-rvB? zFTxen0-v_@9tUs=9!QJKp@%1g5h4UK64URYR+9!F4d|=9lv39C*C<&_)rS1TsLhKp z$LN`5lOs@RA_Yjydw&GHXE0}Ah7vd)l8fl{{_sIm8XiRILE9bUtRE)au6D_-{<2`Q zp?JhvYNqTWY>VE6INPbXs=sI zm94Q>NO0kDtkqn^C|>+yhMa;{SKKNX!fT~>s_PBT6F@t(RydI#13P@GJs3|NZ4}wl3+%Htay!lXvlpC$4 z>R>vp82AQ=7@;bb8Shy1wx^xGp$_4vyr+)UR77)fCldOGPe`2|>+LZ%X5EbWr1X)F ztRxeq|FXD@QA7@_!JF-QF8zr7T_ zot@*szdJysBt;rSif(yjWheNgs=E3{+T)~W(7Xj@jMz9RVjM8g10{sCk4OmcKt(&q z_Q$1Vg-j`MeL15NseWM_QGjZ&2ZTzqB^i2v=M;ce!V6xUS9{6{YoAX!j|r!4nG^dz zx=V+mLyXW<_m`(z&~K5`6Omx{WIx%LToa~yJzgcVW_w;M1N(mz1r<*}yd%ETp2d*? zFLU^?Mb?TM1AIdjRMdn_u&yO3W^No=$vz|DD8Ujr9qINir%SARI<#&^;_=`~PS%I? z`0GSymwY)roA-=D(wEItvCQ9Z#s5}CVo4n>Ldr|cx`c>ln}QUArhneOf&l5X@x{DxT1-nwTUr3f$}&*XhzH&`}pgSQmW{?w{PFR5A8KIKggD0j2w+) z(OI)8I1Ad6iz$$e`y@z27Wo?77DPOB?GSQ|HINegAMg^KvrK>)2RK`i5fL=nJW>Dx ziNOj>ZoI|2Ug}Z^*U;@*7S4AGNbw20J?2-c?L=JQ#zGM~_d{?!!&q#rsuD03rkbpp z)ZljVUQSNf3y3MpttvjAbGe3^@&0R!^t^*|o1}mk@*#%Ycrvg~!KFVyREew{Mygvyh*oXFOYCFtuT?aOo#KiA-0# zxX9-Cg!WR7ryrBNK3j7Wx~{A-HljN%7HfzwXN2l~`mp|j-V`_C%g98r%T2CxQhse$ zQ;*YlHR)5sKl5W7e~*%I{y+8Un*Uu(u#1$B5}SMeh<%GGu|C~gj4h65&*hlN${(Pr}p2k^-q`kn!_nW z?}qI6r(WZaB2iSWI2OkEuJ~eft=OA{8lFMFH{*uC5Kf3X+WN+M?z+joU9b}0!{X|{ zPo-^px@+GILp?6`>&FV_EY=ALhl(2uQ18-3JkUX{iF4NMdwA2R;q9pIn0~qa5V#oGJ9K z+n~aI2vF+UZfAZ5P#~oOkm>yz@#81!78s~R_XV^s*ml6%GC|~IV)ESDv;K<{M3Fw0#}x` z9(zmh=#f5Ol{9mb!EBZIfmYGqs>56;S_M>kd(Z4Js#_dLTo3T^vs*m&n~>(zQ`g*J z9zw`LjMy?f&n{hF(9&!MN%IK5ZhKq!JGb;Df!mz%vCRwdVh7ddS)YPbSDdR$rKb6khR$oe3zn( z7KUqhY@B2N#?0I~oWyQ;s3yloQ^ch9Q0KvnBCTH@051%815zbCcsV%-pTl}T>OF`n zPB1z;I8-z>LBX;##u5r_=%Daq3nOOnh>|EAG=hBARse#AgU+#ziy0txC5Zo>^pLV_LBSjt*1Z6^tRU1 z`=K4c>y?%!U2d%cufx+vJ$BB7F$C)3s^H##gZGS|tAJTzCauIKBJ z?5t{(!Yu+7;BwTckJpVQ8XgrqL;m!`aN*c!m`3%euV;c*)#ASpA~6xRApQ|kV-?*P z)$MwyrjqK`@_N%{((OOAo~QnJw%+(FQc9NCYQw|Cln9(mU)25TDDL*01{Lbqg>IM0 zZ^*gRlIdW>frG(Ws^OyrZ=5&AEBvdrYNhs&tlEyz(E!6q%?a3$C{&QUko!)r#zsNnitk!jeAHQ321!TurT z7Z+_c49z}d+zDZ)f|C+hy04Yap^HD`Tq#D_*r!V_T#NdX+Dai z;q!+R&orR@e{NVkD|?)7TL*3d5DRn)(r5>eJAuXkw9M`R1u)Q-^k0KEzh}l1h~O%H zqkenTM&-ilvyretrNwcRPn3TXU{-+lNBCILJE8DG@j%-PGt1D)eL}ijuqCK9Lkgwm zy2rX>@?ANky(BF{*^U##^5;?4Iw2reFqau3O0H$%LS$gOn17_-MKj>!B-_wb3w73M zLwYmNZW3z0h9LFr**T)y3iez4{WXpdQpCH-I;rG{s@wwB`|pt{CVx%-Q*<=n-r_!s;tpisaU(=Wd=J(vBsZENc4ngqV?Z(o%3 zvrr;>toM&tX(-TXte5IL)U8{3K=L}!_84vzJgT4c>rKTeApE$j1ImsDJDC^}at~gR zmC+q0GVC>&4S1P_g#}>K1bNqt+}skhIQk|gB9&~JaKI1+7TIX=`rGg1od3;gd(xrp z%d+3+Cn$9^k582RYc?QSm1e;sBhUh6+3-v;EnoFqf7j)WQS2LXfT1y&$2At1zUD=y z6%k^F1Ep7TA!nbQdZ|>TaZGGn{6D5G=Z%0Az9cJUp#~jC zldI}6r}XW_NtGEaqKXSBH^6ZdRlov{n_#GTpX1dTQW3e&k;IDV`(|_FZGEHz;>+`a z#XA;@R6|4e&?%oJch?9Rhj=q#crGo+*K0szfQ-)f%VeJCelg=lmGc*W;K%yx-J0bX z4Y}?%T-9vV3o#PfsKMs8;+FoVo@*7un(ioKpDpp+;3Wp$=W{}*f;@U0V~&-}Hy6H; z@vNLf>O1}?2^AkZ_-_9i{&O`VFTZtC)Do%IGRV0}eEE=Xf1SwwPx(*&vNb1K%@XIo zIfqAl*9G>bd9&X!?{-;xC$CgH{RHVb8V5@0o8Z37uG4l#l<(-};~ptlR}m%l!5o<9u_5g*0t+ zynPUF`LV;0eS?K!uNId>z6NUF^WM0T`|{h6#e(_(d#!%!tvoOBE&K~y?fU2s%ziC3j_;Ncon>5#zKH3F3 zlqt&JAR?&HQc%5#F~!}OdJYvN;&oGrMMIAU{iJ2h=O`cnO$WRS8uV1`L5{zEf$-K2 z0KEc{X(o^eJZsgT8_7ZGP#pV;voCnS0P44C{VW|`z264=Hxc0BL9_J6v%*+s-G-JaMG-22qb~i6b}Z9tHL4V zO8bJIAeZQ13;(jZE?si9vzE0Fs;s?z^}uDfkv+L%P|(Qtg8@aTz;`twydI`$7!xk&0kdbmqrRXg1gh)rwY_s`8K*gR>S8HkI`s-@bA=s+sLKV8&i-1_+0fQye&h z0c2trf_{5w9SwBT?~uvB`A8Zr4ptywqIfo0t${9IMb8)h8B8n>As#m6et% zYBoEc?URcptbqLqC^$iOE>dKi79m1)#7mkWhYafM}KgB{~&M3c`*w9-*jd$()eA zT(}1Psd9g*`S|D+9OHS%r`vkX1%MQM`Hf<#HwJ~4_ndkZOYVU+&O~*hWVoSBSSek~ zDQh>VXh@E@51L0RYK`P7+WB@-Ra~~0p-~+DQB_T+P5Xl?aI86UUmEe6;vwZhU*<;6 zQxF%4xdK{d+po$rx+%}=jr~zgAg~R8CfrvB#Aj7LPgA#!Vv?{o%Uy3so|+f9co-^v0iyhx?<& zudN=!3N>P>xR8Ao7s;8<411+k?RQi~b8Ql%e$8w;uMkk^h%!&Dh-BubhIzxed&}aC z-t*S^Ta7W<{ZTAIy-vUdov`b_{Dm9&0$zk7zE|!@-(_EKRH;>fPkwz$O20QxLZ*G# zMiY-45(p{tSkI7NznIl>4Fz@eWQl@2Un$Ph`BbG_`Zm7pi)DrP6gq0gyg~WT0mHXc z3&1Ev5=r%|BDd*rnE9}bRq{gP|3Ga7!0GKA_+w;uVUN6N;apC~e=9W2z5!o7C@Zc9 zb+e$m6QtmQqU)T=L9o9(n}tD8;W^=Rv&iBRFcXQVJ%K?+M134+T31$xfTeJO5yj3( zU*8v8cq=YDge;O90DUEo&QYBDYCHlWY5>4vm!M8({{TmC5S6(Us-X_L_W+%a$n z1_A>>RptL4WsplX(7Hzz5n~|v6LTm!$|FZ`)aZc971)Vm8uj?K3M^%-ksL^=_OtqF&EQY)_8m!_SIx~49>C9Lvu@p<)fK|A|}wVaei5Igv>(92DpWe=m& zp?+?ZZNrB-<%#1ZhDnsn?|abZ{2H)LpKkl)c%aT7bhIkV~yGS z8)~%OP@b^s7W7AltD{U`#oFb|y(?0zc0<3!=ErzKBU_JzHNQ_Y_6M8I(!NoR6>=)L zg`zJT5ylE<;RZ;G=s*8_>l)AKcxWh53wfw^OziXPlfX$MFf3tZ$j~!gFK;I`;eL2p zgVn4z>Jn8NKreS=&UH3xO4H&4Ldy`UN13TswPA+1R&1GX!A-ySJ#n~0vbhX0*xsl! zGwIFZdd7qBjtrYMM9=H>2w%o(6d4yEeaEf1rPT3#)6+ZuhD6~tP3Az3Yj!g30!PfN ze`l`y{l-_$z8FYbzT02mNm;Ev$*A)CG z2s+SEN(G!RRWRse0=~jfkiQdRK3h64oCd%;z?^_sp67Ak8T4q-05K?>4aucfWMs&( z`DhP?^(a1<4zw#@l7?d~rKV>K#(xW_$fCUA4By!sKR`&|RhIvab*xGtc=K5!E~}q?-G89>(8pO~etRso;xT~uxvM4g_lfAoJPbfKCABYhK@d-d* zXau-R@R9X1jtrRqP^@77pJG$f45J& z$3a5N8BQ$=noH_6N-Gbn>eOGA8|zjdUQGl_gZ9E7lhyjm1eaeqlZKVH#cU=fjzsah zyLIxAE^guUSgMrg{YA)sfW0N*SiEG&hJ*IV3sI)dTB74nbA+I{;&Ft*M7^aCU=0TY z2w&GY>T2zmN{`!@_w_9eUqsJK+47C}ZDKGO&f0R~iOel0b9s83L=!{(*i|eDNT#?2 zM~<@#Tf!w;KX){G{3*5Ko zs9Xy02}80=N%Jiloc}b6vWgW;SeI>ggb_kBxyKCCZ?l>_8ay90}ZQ&c^E~u#lSWvL1~Ye zp4_bwco6fwuc~`p?7M2p+z0QQ4JDH4c-nYLj>a2l3W}*anwBi*u+LPo+J*iVga6?% zod9!C1%GqWN`cTl_PMBoA;KKp9dA8&ExO2ay{YcUFbl2v&X+w2J z51hYI6GAXTU6hs6= zqM`2z^1sJTGXTin3={!wryWRrQtzh+${`@oQ!b5;@%QaY;V-C(Pkxk(S(8(UhTgJM zpa|#a*!Bxf0wp{=d>~XNp+oaSq)_jlP+IMEGf4F*u>lgt-63#wD+m=)kVxmqUBa%; zb=(LR`!9y(7vR802x8LnMW>?=%HFJRHmu3J*b)U0v}d zC!Im&0dO}mfnghjgt^4$;7Pl+MsZD5NsxrBJ5xr3OrxrLXJ?&kxJ^i}vNqHDDz$vE z_KX6n4j>u<*$lE4hJZ&8>SdSXE&8y$SZ58LWS*Yv1pqJ@ybPE>CQDIyw52If3%R;- zfvzngyic4(x9UHOYh{giflh}72MGaGc6o6)gzOaEjLwOH)2sFYdQ3Dkh8E`?m`{jo#Amn59pAH zD5eMPD;Fl*uaIx2#j75v(!DrvObVU(L8HCeYFHmd`s#g0abNDqh6?q=Dywa@uW*`v zSTunTlK*dLs_P~Z-iQf4iHF?qf2`7;p7q4!{ zi)bm|#Jj=I5av{&B;Vvwr6ZT@0fQWvZiPQMeTKgkB$ai9i{cE(uUO+~$?@<4??Lm` zf;pIm@etO)U3T-9Y(_>i1rws?@HAj6h5R%2&n-ue@pd>FMfV-S4pkWfCl4I%i9TZH zH21D5SC$IR${I+7bOZI!=k^a=N(e^#gQ67QG6wexx<$b}mm-CU>VLCeR0daXzayne zbP4;kB-OnGt{X6&*@Aozpr0c#6!+O9Bp?99G-zrN1cWwFB=9|M@NMI^{d);`gdZ90 z;U1S{AW@e@)W%cgzx!hK&H;{f<2q<(s!`8@i$Egjf&}fl?ykK}U|P`|jOv$Til$l`h~J z$vtoQfOlBnf0|_=O+EmT7T=mw0!#Xb6D?tuh}S+7=QeY!Lv99-B9AXgaOI-M<>9xt zaRcfbMO+_%H&4|4>?$z!55%dYWGr?nzH5?cMoB*>g640@)UL8(h~95Arjl4$YwI$N zhXTQ$`L@!b`ev(`uxBs<_^kn$0PsuG%TG}r4nHkjZ?moasd9|rk9k++<6;ad$r+|00^+R9&B=(uF~j@95skA(ijCB0UGv}R>F7M0huCAbFI)yb@Xk!LuS;xS;m(#OGgO?XWc1!11Qx@3E(@Tk-_E`YS5fIIo7ZE)i@M%)K> z9B5@x!^S3uk450e?Bb6S@$$p0b+Q7xQdpu?B&B=z`6;=P7K7}#FKi?J?lTiW>WgDz z(%nK~WICGt7GW21d;{j1!@g=#qfx?&804u57u)$L3Kh6>S-djg7j`d-aFymCMFo8v z`usRaeYsc~@e5X+`Z;m);tQeW;Ms`mF-4wfQJ0?@SPA&0|qbRuo#zpY5C;+q#{3vLRoobzp$NFix=$d<P9?#tXqx&?8; zAd_#y{**fvlhUXC9)6P@! zGYog1<#`$YZ+_IHw?w^;IxO_|stD=9%mwe;Vg3X?>&Hl!TjW3FB_3CNnHiDyyK#uL zrgnY=1HM>nNsbgN+SO6)%WMu7$q6KA^xOE!(yaYVT;6#`lQ&K>1jm~LSC9TX$p>-9Ls#Qoz-5+-9_e&<>h7JLm?P=AIF!MLvu~- zzSaitke2i-WYwlADy3@i^v-YI{)`fh^~MXPp?Y1eQ9#+FA21S-@#W; zc~A(#6~yD{WkJ^m&>k#68QL_kI+U%~QK=Y`@HCZa&WP`QJ=;OHJGT^Pq=>@3Rn98j z$B!KcFkoEx2TXrZJYNvBvSkOdQ}*`u*6P|Gjw&o79~seLPSR#>`=~Hu)BIc4FlZKp z_;0n)IwB3sHRc$%P5ukRI%Iz5VMlyO_KtB_3h7O)BQQ_8^)>rb;A9t+#{PLAIU>RZ zwvECeMT?n6c$G4%_I)c|{bOXp8y-?FiaQZ=lfbb1(y1?_LxhH_Q)Ja{%3UXT%l1nSF)?hM{0g2e6ZU>nIkeag zv%wjFReY)?ew1dAy(t^mu*FOSSb3W@Bzk%s4@k4#l?5B5l*@6+2ItiV+L$GE{0EmY zDrPChw+m_%pXlTUH~M&grS?l9rZss}DOwdS+?j|7nT!%Hge4S>ktS8wR@;32OO{4w zIjC04Qej|~&A`@od`KpBw-EoZF5oubj~$jp?E)(^qme8i! z+E|b~=hiww$q7ri<$l~1=38IAPx9;nKj9&eTSCgGtSJ(U%Kp~#-+g0@1yiCu0{qTD2IiXj+AjlF; z(Xr`aCng?)qtU>m`)aqWNTMGsgn;4VhFs>a_lg0=p>m-@CB&w_+GWas*%rvM1`y_s z9Dz0qSQdeu0mN`ou^yUn22SI+V7)9!Gc6RagUkq*2s#vunaogoh;NRYe4|Q`7))5Q zrSZCSAVx~kkTdBtMq7-ul! z_cF#KOI*A);b`x59$KpYhS6z&)-wAsSv7%?imi|L#FsR(h1a@2`phaQib7Lp=PSGX z+T#;Eag@|!@&i`!r===P$Ys%!geAee`pQIv>Vsk#y^3XvppZlUxVl84==9JVuQKL` z!dB0xQ$k-0qK49K{(cQ`&jHWQ*7!wuj%AjOPr)%$Gzou~%nR2^S78HbQr5<012X;~ znrOf!1W2v+)zyXUC9TRmY|<3ksm87&6Q1RCT zhPkIXX083R?W$@mP`9XFlMKhTLEUD4EG9gK*RsE}IvhN|_ker-{tdt0r}md5$Tn1; zsBw)7E9DC0VrwTvG?kPc918LlCNsW-8+W33+DHfr&*}Q-Z3iEn{_c9zQI?P%{pvyF%hhy$tt)^yvRsw0)XH});)0Q+Z zi77Ko&6sJ1t`@%9hFL5c(iJTI1f2j$!_R@PQDxXtTJ%|OHP*^aeH&3T)2eR;-WmM< zD8(b?w_n2moFPEK0c4#3{8c1ihWFF??#4hA9xXynz3cJZvVj@;Gw^2?aEkye8Bn-x zN9Nia&oePFoq>s+nu_AajVNz25V|F|*{ZPuVRJT%CTnPU;SERZd2j32RRWP1G|#&w z7i<jPwg9+8!pAq0JTEPD4Vp24F#`iFBLVR`?XbG|#>_({!M3DjgzSYg$yZx^N=al?9&)2&A8}qF9VVa?I z23~ZupA4$_VDYk(ug$jZ+<1Xx$mwK7@zxs9(E!4u=5I8cS0)ysp^plnEsOyMx|m5> z2gq^54)8pIwOx?uM6PZF?En96MmR8F70HwhS<;J9Cft6MN(r=qk_db7mKRWwo_guM~npPfA2lTB{ps_8Pc|1GHIP~qz5bo3++3z!G{mPo{I z{lQVf(@(!o;#imu(H^?4t0?hIXk(&(8n*r{|C}idqTdPaQ#7 zzJbjzoU;7pM(8hMmDKtx><&;Y>8V;u=$2YfTXT(CVwKeAC_x%Jm~Q?}mw7md5f-J?szrD}XfMp88@C9@ z@heK^B%TxaeS7pGK{qQV&jV{_UfUn{n@@QRPp$wJF7t#Dql;TmQ&oNq{knNe&3|6* z8LwB+|Hr|1&MM@Oihxk-ScJc%u3lRJ&1`r$VV9{b;DdlCcTn5Gjx&X}gjScCz5I#% zb5w_cjz@unaRJ3@GZEUb%M5bGN~o3bwan# z5B>AP+JQJDcVBU&Q zyb5KVFkq`F*II!M>S)Hde|PbDz4PN^H=*mcD%`qylK=N5D+6UF*S)J>XZiYaxW%)~ zvMzWev`;h4{E_gjGj&sS<*!uu3X!3Uy+HUdA!MNvvm-cfHZ4B7nMcIP=U}Y{ zzjJ!2(~=pQ>JlbQf#i|ocav+UlNtFP|6Rd({n4+v{xbS8Rgw4h;N-IGT{c;RjCjxL zZmey%5YS-$nj6LoMOCbp`>^)L$vuV4_|cJJJ!`x2%0@A}Jd4aY3Cph@_lU}TH-}@dDsWZ` zYsR_ujb?Ue(gYipt$@hNWj6`rBt0klG%bgLvZQ47>4_7B@`F&G7IG-u&58(lXN7*> zzh_IN&>eAjA9hj5GY8Z5u-Ik@OwHfcfZ5rgN>%b@K4)l12qU=no}W-Hj~he7dldPv zT}>yg>I-w98A_${qJaQ9M;1o;gU&nexEx#ol|XgAw3M9r4gqzMMZAD$&7^MeoBj4% zko{IrUKNFZpTF=1<_>{@l2jH}7h8^{>S_*AO8KE-NoGDimt7B@^dc=pm}8CF4fryF z!U?ED`hguA>>F3DYh6 zXtm?`Q{T=kO4Tswr*tgu%}hlccsoR1dX;i&r|iGHfWT>6qLRJPMM9mRulK8Fj2Fg=~P0*$lz(dwNgm0GRyhJTddTf1b};fEsz=F+^Ptf!|9hQPHe2` zlDPv73#t+Z0}Y&@OEiR`qP^mtdUBjx(ul0!PB~De@_At(1~(VBLq4l@H)%oM%|x`k z8s2iAtXTi*WR$$xdAe5H2L}&Ul4P-*e-m-7-Qk}1`pcDtp2|?ZAm*P%sKT1;`kN z!-Z2Rk`@d>G79xBj*jO2)90JjyOrxyh;KdxnE{tkNrm&@cdUQmbH_~(Ihfx+Y35}i z+yTdKG=L+Nmjwmp=a&v(a-XpR`Zj(!I@)awVuQ|2Bh#}NmFtbaG)fc zM(_nF)s^Q=c?|pKEFkbgKtKS1+*)9%Lh(ZY3Y|TUs`+9W{GgON5uecSmaBgU41kda zq%hcT^u7bN?z!&KiFq2Me`Ld!wrx26?Pi68IIHH<&NuBH|6#mP1ivvddoU-HKk+Eq z+;wsd5-cU=^V@!`KVSfz@(Y1DPsAmj`bJgD{?q7+0^ zN!x+IV$#R}3_wrBYi)9(xQaG}?bl9LohS=WOzJZ~2mFjJc5fevb0|^T@HFO+vE4=o zyFo5cg(TdVYdUNGki_v&*(3~SZ>ay8$3re&BAd|5t%AQ@Ok`rYLk{7ED%@3ZKf#<- zItCw7NL4-KC5^ds(i^Jt1}f+;S`xF2xT}a3a2^itmr+~N{N|sa?wzv&HsfC3%skfH zclE8DQf2JJb4zMDBf^Om18+J1TGqUr3{FgyMHHO~BH8bg{?Q{}YEu#ydxn2cE{5^2 zj@j6&r5`UWLH#$3w8i8egZMA6!UuH&SNjH3m`#cDo8)Zl3dK@ii`CWTnI4G~+If-K zZIQ1B+FHh2MKtxRj<$6hL@8Z_+{f|qY>M0Y4L+;N;=ZXXD%&c-2{Gz%$d;q}5BEHH zL>`0N+p(R98^4-vhD&1%{(Ttuks8*^J^bgbwd%|sP4|bx(=jvp@vn@X9_sOzXJru| zJiMnz^qpTUTf9vDw01!A^@r-aMiv`V&hoL+{z$B@HAVnUgHk?__Do}7z@wuvqzh~Q zd(m@Ix!g>fx9O+hCO~*pfj6B(YhEK+%P;@KF&<5!NLnRJ z8m0xD%Dk&p`S2Gm zVZjG>hz2zXQniG$`0^Dh#Xr2&(TM9fd5-M&e<`S60yh8z0s*5-B8PM~zz2JKd+Xir z*uY2)*yCshx3xC_4@3eW=lVJ+Kog(kc(~ebk)wQ1$-t2finh_FrK`)z*H#x7yLK*Y zPgZ!quQ8?Yy5Djks0@#efuvzUs6Bdw_ zWz(QBi1d3*@x`(Nbq~N+Lb}%SUl)Fg8ml+)c8O$IVR!?77WVMqUaHyDJ2v)S`(Gz6 z)`+UCivvlp*?sHzcbo;%Z`!G^F)=Y!NqFBjs zoRQ@UC~$HC6s4GJqef{^zHcUvw#yc_)lz*1ZMmAm)IOR^9-LsUM9tw4b< z@=igT#VS8;y3)Vmb$xF7IM%w4kc^IoR^e-yzdje8{6JroF!eKJ+z8)&@q*iY#gHMo zXBxeGaxJfbESn>4Bwl^*kkDZHn5rr%=RccCjRpD6ArKKpw65axfnXCC1yT9MUtXli zJ4!W=6@*oG1uxj~JpF{4e(G&Hen?lcXhe7!v(A^#I_^({t28?9Z3A7)IjkWg zIJ_e&<-e{gB520O_Yv}Eh*?~~cLo1n+{=-fhtMV6%oyjBf7 zQC$pU%%`+mH>7kY4{0Dk;tyHZ;jv+Y3v=$(@?Cw?63Pc$?oG<9z#rz`LrSmOI?B9k z6Y>ZK|N7hgk_;XnYH7L-NPWapXG3eKaX}Dg2XhN5pu|9)wJpfQpV-5AH$03bu48Uj zSGN{z||fAvN&z`CMf>|OSVuEeS71Fw?Mq#a{wbkxI=1N`F|}yxDUL6nVA@ScXjF& ze={Ez%5!Rej(4i(qYKdjK zCG=iLWBC<0uYr51RI8=%w|mUTcbEJ5rCqZ7`88|#HJ=6yn6q*7XxeYvx5)@_ABn+R zhvwVS9^?1nY4;7)KW*MrgU-1@0;^a@y7)=1w`{65bW2<2rL^-FME2%LrK!A$O_2Ey z5bxX$Oc24Uz}V6MDg335ynV@=a^8p!Bxj;>x;_N@!M1Ko36pXh()O2N@I=+uXNcnt}fxzGj;L90cOJzEc;hT#5od|e;QT#u}zo_ zuqoql&+UKxz7t`qWrVmTKh)YJAa4&5(-0h_^tJWtu}HO>jUj63c_6oH!}l6`ZP_*0 zG%W`?O1AL->FS%>_fzQCD@o@+|I@6dgU(uxaoukx#>fpoEU-%_B_$=2XqRT)Yp_Oq z{_bxfPAAt=sUklADK0~aaH~?`MP+62^rDIhPul1X5DQ_U_z8R(7E+y({kG*%=-8O9 z^mEU$ans2ZrpziszfTfgphiincJT99{V8Z#B9&ppy?aF=;T`1|VYdl0wJfKTv>}## z%(Q~b;~br%#7|7A@MsmzpKJ+=?e#h;@a01+6XnzC#cu|V$k%k9?P-2W77sx~W|H2&?95pg>|$Gw2EGO83Q;F%Jk#mNHlGY~-!fMkHx zVV_|m@)kHQkcEHwrmd73cyGg@0Y5nXkj>84?GDhowpGv9`T>uStr+FcytW3|8T(t6 zg?AUGQ2`6IA7nN!&!G$(b`3zvGJF4L-eMcfsfzq=A`EuN7Su0Fu>W8F|L2$d9L4VcwLNl*?LL8+Q^$H&J{b`z{k2=NC9$voa1 z9X%f7}<{zitd}oymaDH5poe8uznzSu!&kB&7UQPIP{kdUnDOIj+t&%J^j;Mm?esM+7ynrzK;Tv(!((A z0QbEGbuSoM7nO*&FH!d_A|rBs8yoww>CuYLs)Cz{Q6u{Mn;B(Y6j?nUi91DC|J3W;C!Nf_J4r;P7n``}SSPq2)d&p?o&1h# z>HSh=p@>4{k!7``II}g?BkiAr6?oE{1n|N;G6G2%2Rt(+rST^=-`xa( z&C7iJYvBvxJt4d47ZBC9w&%m4ok0Yl#L1(Ek$TEh%ug8wvrTcZlO5|ee5X<=d z;u7tu%GAOBap_yGzqY>Xpa7;#hEqKT9hHAza=xYiAcAZ?lT#WR0cOV0@8K0V5 zm`g5aEn@bC!fgEOeu8y?6NsL$J)C2D9#e{96#VaF7r&cJVmn|3;Zml0(WKk*kJ3^}0I}tIsn_p3eGvGE#!j!IN>{%>W2~7HtkeILrz!NZW8BwH90i5z&6RGO6qk^Q>Y~{`9DEQA)$JQ+<)G@VqDY>qBn)e|`oj;fVXohQ@o~&gyVD$lSAx#k z8z`FBnGqt-AY4qR&K6}^FjrSp*zT&9T<@EfPL1e5Lg*ld3fKNxt)C}>JI4F`l>~iJ zBj4u9NJ5JN0@<^&TCEZ81M>A)b&ZI5bZAKnLDx2mz#l>)L&WUF+VNbO`IC%(8#)oE*mdd&~6;YKo1uDv*> za|B-H8q!?NQfG723s3eZqNv6MziIK_f~^L9c||r}XF+4QSg_7yb$K(vh|E-(olkoq zV|B5!j4gC1p=Bq*?MQK+q-)`J^b0jy&?~|3HVsd~m?J2(_wvp%9@sm3diQ(;CbKPk<-CPQ-+Y_|lw5^uJeLxLVHM zZoJa;aT}o62t)}yXSs6_%vsc;u;Hz-%Uinbho-3gA5CW&ROR<}VY)-<29@saP`W`R z57OP;DG2-k0cns10f|G0w9<9xPH7~i8{W-3^Plkp!!Qgo&%?g=y4Sjvf~WvLzbtdI z@Pvr82>LL6rpM%8UMLg_tQ_DxeztMs_@AN!a0mus_6h|8DBby9P!I~*dl_d%goS}b zCOq~v1GatKZE7JR8~Qu<$3mEFAt+`E{r%R>trkzEf6bY3rTKMT^%#8_=Ii64&u2ND zp2V8m)B)%56UHar6cJs|CyQZaDoFcffjdnPmaMh?d5GvPG9fT(;sLb<7?1HHrGaPy z%-fpQ?)&h~7uL|}8_BYQ1`|y?((^hoUpdX!0}B*v4!D}LMCdC04|i7}MoyT$ZhQDS zdt0%t4PusWaavG3j(3bN;sq7{kyZTv6r9`19PK16JG`M)%5(nsAZO&WCCZO+?0CA( z3fqa)llELLPkR%;`37c#uX6Gm*Z8`jQW0Hc(L}-8N zfcO;=mzMyO*_)9^E-LcO^SYZzm<|flR~z!MZ7sn#6dgo!@p%jXzqBVoEecPScZ>ms z8mA%?l->9)&5O;vhrMAaKEwa8lvr72r*B;U&`Jcp?tRZrAW<>KIg9Z{Gu~)o#<#2> z9>LffPw=mTF>SqD$%3U}S*)uuEgM9(-t9;B2Wa-Tfk6s5zW5g`Z5&|}Gns{>wOv2o z4C*WzoDYw>KF;qnSsT)~Qx==Em=2Q>QX{)0ycQukJ~~QRTu@gwz8_~IqcZGm6p~|3 zHuVdPx^a*FSkkRx#nI8*hxv|STsjFKYT4|WdLv8j-fZ8BhhD4hIu>M~IVv(*b=fIl zQWo%^e{Gzy@n`T4uyrGk8l+qm(|&_&E(^}Ot^QxISqy^>So2N*1`R7w*_gBrPvK;9 zMT%KpETx&R?>DgJX;xjW<86j~M|eF@14+U5tHFr@rG;LlD(Y6~9@>y2T zz#Ozl8rpMhN`jNF&y?HhkOaOzPYk_s4~^He?<(6a7UaJ)ISUSFnrAaLzK13z0Q&?9 ziPdA6*MC-5H=TpU_8)KffVhxWZaJKS0{rY%iQxzsP}pJy zE?@rB6vU28HAc1|1o|1hl#?s@PN7xFaCPf3Art}Qph)~L8WMtH&>)#-Q^(Z8r95qZ z=C7F8*qZkC5wMiv%78s*4uSl5wmbd?xU0Y$cyMq~)!wcOOtaC^(TaL-KrP`#eE82* z6BFrsa<>~O2C1A?GBV1kxhYFV+Quu688A-(mQ4U%CTtSm=FUet1NAkU&WR}!`SQST z1Xd6-Hz;ofDJMuWBp{D~(}R$l{KA~*i2?@|q^2vYbcknRmON|DB&kC^AQLQ8tqaDVpK=tx ze}t8xnK9=F2L4qt>IAtxlsibD{d67s^e|5y@2lxp&uI%Sk(yHE#D(zpt@=aNH7V&a zA0q(E$YSFSea4*sUrJK#NqQ}wck%l_JnC3FjM%Ec!FOu-p24GihO1^~Tj9$_ObKe{ zuA|w*f)jJ55~fa|Y;8|>{TAD|Xd!k{$hwr0L@Fe}R7IzQk7o*_Wx8XMWa z0fqGuj?POTS(iibV;aIkH=e>0r2(zZHp?C}+~UM(4Z=1ON#k;($xm|{_u`1ZR2aXwW9CZ3{z>deRsw#Mu7E;}8~f*y311@MQw^ z*%Ei?2z#dp%A*PIsO=E*&4_4IyV#NeNW>5WQ@1g@fLd9flBbt*p|sd-j!s&b>%D{~4QMDzQt|P5p|=PefjY<4v;WGA9A0XIX*W z)x8EI=N{_+P^>Q+n2neJ-8QCIc`_SQ(wNln>^hi&yEeY}fU$vKdejXMH@9S-`k$$i z56>=xC_M0U`yLI|FvQC{gY^}-OZ)b_zeDMiWO_9OVG}B%E4KY~1L6SkL_-R}51{f- z%Hs#oE6v9g?RIUyp&Cs}n4S{4d9^O{4AX`0#@S60-+L%yS>Jg5w|u2a3G*fnl1}q8 zV#W*sQD|i{$%hXsYlv1O9goNG-bV*+tmUkDSV;5B%Ukg_8ZO&N1ac}SYK8~Q>k8g! zi<&W{CQgA)F<-?r^Il!~v=U&-xK`j)Ktd>nDr;`mp2~!_EiH>&1j!T}9ZYQOX%iJG zOACAhThAwy22qq&h6jy5I^@3|C1>N|A@#>pscij=XUPSjC$EuI^5-Fo0Xbh15|Te) z9>lN&Exf%OCtsE635{FY+Ej$IihvOhlz(c^=~!{6OBw4^v4Hm{uJ41%sfL>G-C^T1 zNCQAmK(;_iwb=E}dI0f6AaQ{4TIV}B1OeEu;NO4bF|r^K54wn=%$loih!x820fW$< zzYOj)>epM>P&-NwEkr~05*0#QKd!u7tY5K|BE4WU09gE`-o-0UY&5JvO0D|Yo9Zhu z&qt@T+t6`hoY$sRjO-gwXk`Ku-b>bJnJ(>m-%eLtyp;%@Za57HnUKfnq}l0Ov-X5| zTpOTlyjaBv8yr^-I?Gs{qL90oYFW9|-VuoniWI6%HOo_V9EE-b$}&F5tE9Ne#Aq&( ze^ni#LrjgI{1#CaUZN zcciuOw6wcGY1(hJL=v{MFE~=D8{zo(<=5E>mBhPpqpg5GtJ!coH>X%%9D>a#7XJ*Is zPRH+SPd(iNRv;b^s-)4j#^}LOO-n`zryrSwO9B|qG{1@6bdvbW&M(8pmbZ7_kH52e zLYs&2A%xN1-2^On;r0#`em+s(oG6JwicLnRt4a;H$-{e5vLeL1-3I^&fZPIFOWf`* z4>54eg=Aj8l+1ha^bhw*-KA~D_d6YV-BEJfpB|64f~|tVS4}w6!vg1fG#U6mRG#+Y zZPX2~rSiV6BmH3Lo3hI>B+Y5SwuQzZd}JyL)jCQRp!K!n?Wo3OE@E!ClVE>3yFtUf zH1W`7O1Ye0S~8t(E0W$JfVgl`M_;~vKn##(F#Ue1@$HPyT}<Z{Jv;&eazLI3 zkPc+^I`FO(i0XBjfaEwA3D%%-lx#s%v0I7evk?b;3s|HEZs>m>wW0oP2GE}s#n=gn z<>=#+C^i>~+7fn$|MhtFxXd3NRZOU*D~E#sI#>iGpGHk$ibW~3$ta4)j5CLle1J?j z9Jij~JVVX{e#Deg7M7h^Utrb zX-y>j5s6RkUSV4)oI~`uEIuqih1?W*e2sSp%=0&#_Jxgd;CS6L};jUj=WsI z?Wagc`QpRo8S(;DR;HlT3NJoW!8G<8;ezawRiI?Y?yH;BMIb`Z65&P7w9OLJ|CO&% zdp|B*_Q{s5Pw992>x`}+^)tQ@hm%Lh{U#wjb2wtfMcpd{l!Ne^!{+PWf{D#f+Ybr} zdN!q8&DPW7_1IEPoHsER!kB>v)x0X?HjoCB8{N-FJ4FOXrg>rb9n%X9ay>H93eBd_D z?*|7wTyZN}YKyy0T$W6wRBk_7VU(tn{*43jSMTQv3b@o-Ucsy#V+2_DGylV?23kd_ zM7RGg)_6P5LF+k=fD}i<5k;@>wn_slOfWX6#NMlUHP;y$-SoQ75O4uNP=o2zh_-q@ zXgl3Xo<0$5Xqh+RPDN8JpuQ%_CCgK8AFZKMd5X5$Cpx1^s!C_Ke47PDp2Md(~6^24g}O1Pjlxq^4W?Fcj2a`D>9KA(|J$P zYIU~&HAe?Z?sr;oCF+dQV4MTXqQTbpIZ2v}6eVVa{SUM&Z*HaP8jaW9^ECgBvET|S z7-t0L3XH7!W>$pC0i4csW!Y2|^`nhvHWXNz-`+N#E|pcbm!=8t(~*W++jLI@kL>u| z+z(Nf&97ArV+iLVTMCXm@kod%^4yNtNC<>iB3Y_H?*Q!)%Jd&R_sZ+bw2mQmhncoE zG+}PVqUr_XKi1VZFML@fTW88npvfGmuLv--1clLH&7gS+*wK(e-+>Tp($44Ff;oek z3B0Mn*~!Z(+pYrZpbJm$J?_0^8K}bhASsR@bMx<=Lb{c>=X-@71_r2W!|4O&rNSHH zDg>HP{?ZxTi_4f>1Ife{a%(FfT%~;C!oU#-4JQCuH20?Rxrz6x!b(djM;p6;tsGef zT%|Bsu-VJWEyhG^ItG?36W*F+3>SoEHKm;W$drCe9m#&v&@>Pli8^OgRlD?_Xhd9} z1+y(WDuvQkL|fe9^Qdn@?hO7bO)e!a&GBDlKj-S(=_JfpJBbB435cl9mX3H1Ry*WY zW2t8gu!VJuw{q^$SNWDFr^2JZ&x}kbR>qS2tgj2RIisob`pMNj*ma8V=fWGVYW`r( zfnNpItW7XU_W@Hc2#rzXn{1<(pvYX8w0*|!UWCO+hXpTzzpS)#&Ymt#mGKRh3^_$) zyHy!CysPD{L1WYX6A$|5mMMB_Nr+kJMX7p9_V|N+d^_GC?F2^uR$y_!KF{zo?5W(QSWqh4K#V@6`uHORV*fPTjo{E3bfXU;|k5p21M=20Vm9c~ zDhMU_g`23ugxwuPb!cy=tPpah@<3G|zQidk47qjqR6*1dE^H*u{am9Ey#9qjM;f;r zeU0^3_O0%=jh@CiQo{BAi8tV^|N83=_PD@;0qjI!IbvinGf0LPQ!n?fAeD4K_n-yM z<#Hwp<7Ls;9fFtREYHiHi@WFW$undwx)?&UN6B-sU6yEFTbw1}3^xeVYaD01x9{wd#$Z=11U+(}^(dQ`YuN#=3xfpHRhA?~u>fRr(5 zFTM%ZWZd6Kp?@RAe?NYz5R;I2yd}O?)6daHA^>aS0n9eTKdWr&$*0O1t3Qc3TvhtV5$NPnXhMSi&SyJSSVE2+&|2D1`wJ$c* zUc9Ucy&=f4uTE-JLof_^HM7WRvu? zZDTxcnzQEz!K{&(n8??cX{`D_BfVswkrlV@Rx_}8VM^NWv1I2KRB4ak23<=5DB@55 zo6|h5lg018zv|^}`G2oo`sE)1zqN&vQ{4V+CCg0_h$sZf4aLhGk%;wS#&@)~mT%e# zMf`vv19bZ{rxWO7k=rLR-W}e($5$)_LLum~;_al=)H|1livShE5{qP8i^cWd`5q%C z)lJTSAAP}I7Q7J(ykuI|{veqEGO^DWj=H)erV}vkGZJ6`tu72IZOvutvpv+8y+@1t z2hyn(@cFgK+>bj2&zbl*ZCjs}p}thtc24-`eJ{`-2Tx*_s9#I|m`R%uxlHPtI(~XQ z2Ehu0o-Z;EA+J+qlwB{Xi2^Kv{_Xz{k3_mvGIO7^kr#a~|xsBx`c z(}AfLYyxyg2-0;|wuqU-xkx1>8XT4%35?Co|88GYd%R{* zmNT>hBa4Oo_ke4`tFxF^64LeAj{9^C*~-2yPiC!`BnqDF*cB-KALr;?86+tI!_fG z6-+n%tJOb=Jps*_dy1z!)+3^=NGwIqa-c>!pXc43H~HC}Tc)_nx5z9x_qvAK`evCR zCu;I>?4Hd+0Rl^w_#b~D0#liZLmpsn^6@MySAt9BZXr}^ zzonTSa!9wJ{4q}Yb&?{Tj7dSgP1$AZuAC4?sq!O@?t!!fnw;E48lJH}KkUT=!)WyH z-@h^Z8G@A9bDG)kB9Wf1sh`X&Hcr3`>h^GZf#H@3QcM5}OiE5(HkSsV_wD%(bqO=x zI*oc9=wSx`^8$z|e0c(?Zdr)>dk7&J{9Rd1-Pd6Mcz(jFvlU7-v2g3KGn?;U4BfaU*f%?teh>1k;{ z;2hS;O>6AN;cd~?xPBqUjL1<3eCPcAAG{MU8Q4NUzr7gI(LdBUNi=^@Pyea@_D@rd zAbtw2DaBcfp(%D+^!S44D^Na*a@2()_d&rZ*gVM1Q|_Gk09Ea`@mBx~p|o{kbNEW7 zD*=KDsT@WXWw9aJ3YMf}wZ~-^PYgu;Z)u#-%7?a~#0RtA1YG@wMllz9)x~4CdO4~M z9$#&fchIKD<7NF+`Mv(<);|eT2zR`JiwMupo#axXC-KX%=r(C;SZp|+O+-X$oSZHT z$(+a~#ubVYI0a^?E&W7fa=pGzrw@i1dNNZUP#gPr7KWhr-jFjC7puN}YRr&6icR?W z^*aHZNsE!EBHJ})^X2wyoA*?<$f~78ylAD1?X!fh>drq)a`Pw%9`@BF_co^&(V-t+ zSHqnCVCHPLtr?``s7oAK4ze;Mc+b`_G-e!bM*ASw0k^9OPQl11@fpUPQ*{HyAhGd7 z@8$E2#FE@{;Nq})_oMmh2b!ZV_&)TV4^Y%P-&R2^oSvxxdqQ~xTZW}a;PsBK zh6T~j#;0os@t^&(aE@I#y*=&%Muj=E^+onFxgqAlP#U?9NY5)*@Rw*SXP z7%9z}0R#2|%`Yz*GYD7P16uMcr_z2H{xV>p6!H8b7e^Hjv@ly)u^bT>gIHf23kDEu zUB*~qHV5Q;ovKN4r`GqLds7S3Gp??Qr~{MAm$9+2+>~jyouytO`KA^5^R?dMpFAyC;@ucf;{x*NaAZ1<(PaF_UtEgg9{t|K+G=FcEv!@3&2k2r#30!0` zfMz){H>aETH{R>pscL=7Omj9Yk?Je7r;r`dz-Jiv)W51Te*brd5QU;7-HA6MYO2xv zk$u<_VC&Z_vE=LbNYIctNw6Xg=q`v}j2BHa7MVlqZ@)`_A-w5+tHM=M|EXNZyEIYM zsqR+EDG$}yEg5Xwh5XO(cQoK& z-=;Nx_R!Y%D2v7>Fp5`=e^070yN85y6$W2;mQ|Zp<1vw-oq7kx8q@Tj9$*~aIV6e8 z!S9=;_Rc+CF~u^(R$qGUBjv+KsZkVTJcb}7O~bX2r3&wgd@3!-EPdDh&CUSxAj0#3 zV4a+|7#PLa7L8ZsH@w2<9X(vCc}BxsLh}pc+j-(db}gIghMgBV-NJ+*l+f=AEXD@b z^$`zU5pP8(f<4w~OL1=4Dx&>*M5c^CE|nFhbIdEcd$@DOXZ<;koD}60rx{PDnQe?H z>5=CJTt(vE8}}QGQA!cmK^G#nxjAj;{kmk2!l0+Eex8TDjidH(_UVaML#pNc(t@dj zS=N1Ewg~Q^@xu)}amE$LWUEk5^%7p_e&cmPibJz2`OixpcdLTWr!Lw&$oGZc9i z7m)krKhvM1yo?e;QLiID;k%yu;^5kPCaAMr$w+P%k1`uhAk+YIZr73c%1b^!>iYf? z8?6<$P>nzu6vTcO=@VaUD?)b@`bI#>i-?E_5XIcKhe<)xbuw3BV^hMSzS4MoO-(){ zthBySIg{oHEQum!#Q9?Jj6a}^*xtWpq3Ll0&e)G_zFP37#j08BwWH!6SgC;Jg0S7S zX&5ZKFzR!!d%}L_60En%hG!IB$&Un`!C4x!=%K+heue)jX=a+?qiXm-_+#Q^xls^LkAAS z{ky&I(+v{*1sJZxoYb)UN%iNbICbNl+0z@$&^gF2@=lg8=Y})ebWxE%XKK1 z>CkNy^TFQH$Cw;yZ5=*kHEW;v7;@zBG`CO}<#HTp>YxWDzJdy<{sCg0eS(bOj7 zn<*yBE?#8K;UxTp^bK5mFB+}@^}4|I{1>W*t(jT@a13JTcX#)8=k0VqKs;*+FRRs7 z5O)_UhIpMlqqD$$h?TOd&LZETlClNXD+#<#Z4uLc5k8(4e(qv@>)91lz{96JIzlms z8zGsdEK3nfk41+_pya*es8K;P%dNc>LsYRdSZv&BX)sq>Hkn%%KhRA@>B%!tA_51( z07*}A*q8CmL4<-|FHGTyz6}-UIYR3_2WRW=)i(X1O#zShK0P;;Grk}8pL{K#bgOmd z+HKrgS#|y;NF))8EiP8ki9{XIf7A80ZrT&umQGjJ39p8hR+^=fLY)?4RE4wN9eJ#D z-;OCZmXVju51PBzn8w<#DvS#*>aIy`Si3u4On^*#4dopeCSB}g`^AFT#|Ks-mO&M=-cssu zoA=2&{Go{$MEjybi?)77ZFEH$>a#RA_h&2BNV{&(*5Suo*Z_f0O_9!KbWK!NehSgM z<*_~Cetv~?Wuepgt_WO0SY1^QUJ-y^Ox?H`BzS$@S96pMebB*ixgk1x}EEIE~NMCWmV-#&spPng2E@ z7ntwQ9gwL_S(YrL9exxhLVXTDz}J2v)L4xf+CjUSX)QjYaW`2i>GKzm~M-^K-2`Lr&AN+tyDQOYsB-!xwW`X3>S!P+Dugn@A7jYY#`o@n7}A zka<`VO!yu}VxN3JErEW)YZ16*IXAI^ZByGz`>)Go)l`*qJCE9Lo!niY?(Ql$W3$+UV)R$NNm({kuvT!Xuh9qEE&Jitj3kar3SR~ ztD*698+b?T0?{$iyb}AgeyJ){9edwtzOF zt*uiH%mXTF)eY4n5cjM;%(HUk6*^Ox>AZJ$dN|4Bja{aq%D*C;^pQ3a$C^x+&H4G| zH`WVgh~y^+;^1{GOBcPdq=p`5mEWQ2UExl6ZWD@o;7nfM2ld9ZrxLoQ5z3*uS#lTz zat!(4!WP*e8a4*~fl;LTd~7Az$6r~ar|FsZ>OUwE-8}?asA!G`)R(8!-`n~M zHnBo#q}0mTKthChkX9~b3gWcsg|5e%VI?S+voS;cIJ%iJG)PYRW%1DSo4&#D2&H{% z=qH-QFa?xw)VavxKfhFyLb11-E_HrdHOq{>ph=d0&r0aRFC1yLPDpPSY9~clECv=| zbF4ACY|k+Ex%;js_>SrR899mW`ke8P1|K>dK{M862d^ zK>bPO+w}eRL1=nGX1eT^roNI|B1A#Bwbg87Vuv4xd6|_tLCW>; zMxhx2-n0?Nj;pTjuP;Ct=;6-$rd5wrkq;ysiwcGZl3_PjqxH?+>k{!_cdqad94(vu zcv19s#?03>P+TG?s-p_@Z{=R_!uIxGNAAy9vWTQ)o$~41&11N&C0yhlHfjK-J zms%X+^L8G!XnIMZtS!|4n4d?W7?^_U<_68N$`(;arp%hSw%LbuzBE0y8_u!0oUF@a zc03uK=1Bd0MfxAMDXH9*iQiz(Byr8@qRU&mKGrd_U=+ zl^nPiK>Is#xm>|}KstF2q&YamfYer0r24-81?!9HTLrt!A52`+h##Gk0DvX~H84k4`O<96vjk8&25 zsOLJuEst*;VC?-lCfVY3AValzg0>V+!Mt=qaf~v*l-ufyM3(m$s?-8!m%y?0D`A$` z=LIAgV!TY~TD_-BM?S!Ozjt>O5Z3TMPt@O3hdrZ~cRO31$}!Ajn=9U)WdETLDdpAF zDb^~b7xTMMdwHy)%yjv1OH`E+*j?|MqGDegHm2?x5}5V=*RjjcpdUD5bXrTgTCSH; zjC{6NQ(B2RR-t<8*VEW>azOoW15*M%*P$aum%AeP!dCQly_qVYfGUl8cfVLV-dOJI zlxmc*Trfy6YdpT2(VpSN$+GnHOp!GTmWwPmWqy?aw-13cyjN9S2A+yUm2M`8J=h4% z<*MQknwo00-@E|)z`|B_I`DBqHP zmGbegFfc0S8Gp}Zx#Ih9bzOV>ND7kCm_gSa@SMV4@#9U=7{L`*ZdwjqW{ryg@2ae- znzGN9{$Z-Nsq{);j_C~rO4gqL4V8zFtgI|3?HT(He|h5%WNmPlAxy+QiLLbCVtL+E z`Be5lT{d>WRv!;n5iE?$_+?&tzl)(WKO^;^ReAYdSB!r;>5DBsMbmK|KL_M*cO<^O zg9Dd<0Eij&9D3@^wP#S^^m$2^Zt&(*p2|xfbWg{!uLtU}aWGeU{vz87Dt{(~fi@iQb^nJr3W3FYks!$%G};$v z&Ucp%VZHBL-2nSjnZ66WJA7FrQxAEnr+>|}LFqaMzH*6XC-?(j zTU)^S8+3ItT5@Aupw;N6VNbWZDlzq1h7oqTIEyGt#Ll;dN2+r*KU1?y<=*f}v{K$pO)x6dWqGkqNs`_k$E0=|Uq(rav>; zHX-*|lp^msCuJt*E4dH%%ADC@JDAeK0ixMCWt@JW6xm7-K0;azI)P+(*kRLmEg;)$ z*)kUtWMmSekf@!hH2K|T+09sOldA_@n8FJ!TJ=y>^nFAvB_w={4$Sgp^w1dP)_hr+ z>KR{#MJkGtGMJ;sFDRP~lW@_g@OG0kLQ{9Euc~SqLn_DnfP_yuq&kn)`@wj$A);}9 zDApoESv(YcurTw@v>{(d+hYQ8qb7Y=*}q6Kv;yU>tVFBl6`#@YMztR&nKJ8E%I@B- z>A+9vT!FX4_;1G3b8qw*h6)R7(3SgT2D3XIYd5$X8DH9N!BV-!>H17fi0CG^XXrg! zLPf5QpX=RyuK3AM7<;FL5BZ&Y8H5%s3(f4lN$l2eo?j#6p?2h3arAzzOh4FEiQUpk zkEOSEI5uZ6GT(`WHN$O#8Bf#`Y2KEaer2fy+=lmQ%xQP&k|KocmQ zmtI)wsSh%SyjH$87y2&444$e`aAB~tl;trRQkEUcQ)y?PaS~(ja;a?P#}LtHL*c5Q zH{v_PM(IuWTcZS-Lb$D5jT`C*YM`I=Xx6nAOTlk+9yovnch`8BgYVfhmLW?Eu)23i@6O$T37B)Apoo@1HPaY8FTY8$va*2pyvN_%&rhGL z2WHM)*Vyxq*c?Dm@wim`XmFYfp0SAy=1d zZ5FM_M0Y%Mx`BwCbHB+zcs2bY1tN0hTfeY(WoN_qsdQ^%l6%Uvyu85;g#h&v5Rat% zYr$pB#(jUDF!~hz#rD-5DHW9^D7bQIele;&`R#{S%Ee`Y;UnNz3<0P;7=4FfFv^9s z8Cyi?N#2%dp%#&c2I6wD$2Rn08DgeYA;rd)veNRn)p4JCf0Oeh1Vm;+GS~5^PHCB$ z&(w5AN?kabY3}H7TPNPSqvQiZ`ZgZ*RggNkG3o=F<}7XA{lFn{6RS6IHT1xK_sszI zebVO33S1*KhiNobTAr@JHUX?TJ4MU-{l%%D;l5?3Z$@@`&eArDK}-wQPR(bYKv7(Q zUFs*qM?vQfb_PY#U)qz3WoJDXkauC{nWCYT@3v1PvXt`dQSkZ0)74=6!l|}GA$y-L z->uRljw{4^QSHnOvTgai#UJ)Npt@}h0P7?F@4pmYqvNN|5OGwSXYz;UbU*bix1cn7 zWLXv9!Xb2r(YP?6CD3>yI^|18<dV|GQb2?pd_s zT{OutX|tf3ah^ieqUyK)-GiK=y)JTVPJ>lHiZL>QQG=lJ4>Ik4nDBVrDF5x>z(Whe z!rH3e35ywZ)LM$>Uv;kdLF;F?^p1U3cCt7exw};r=foL2W75VvvV270bG(@u8x#9a=mT*8JN*6|PqB)K&v+PE8EOa& z*vzIfRvJ&d2-SzC-ku}tUb|zj>>UXATT*?#bg&a9SAA>xhAmHPm9>?l_IOzWMT-f< zz+Og`VPbxMG9yslTUBrrlz6u^yG**{Zxgxc<@jg{hGoql_^(+^)sq2|$uEO7GFam- zoAZ>Avkj;=aL}#Ib*UxX-;X}OlX!?M{uk46gA%MU^pN=U7z9oub;W_e&-n7ssTKf{ zGF1{z623Nsn*`}RyhLqBFtuX}x>Y%T#X}XWhwB%W=wd zb!BB7nMhBS?Cbcq;0+9Zjr-WL`rsJ3Wq2_4Njk=Au~ox}-otDtQ=Zlt{C5FuD0M9l zASonYAc2p&OsmK4qbOWY8!0%n%Y$9}ctroXHhuKIoVPk@I}X4li;*Qr8}P~1L11)! zn--Kh)%$7mNsu5#@lR4Ej~}kS8c30dxnJE@*rM`OB5gPmAhv;ZrgXu3MIU1Z{3h`p z`s(9%6M(Y?r_MQ&?Ol~YdrDq%T$S^+S0hLV^Yhi>%5*G?xK_&=d@v|Jh6C3;HW3&+ z3G;tQIhh|*5jHe#Xtgl66$VKh=!^{<>_Wt|f>qK#&Fe-SYT}6zv1vv!^1ExJU8vey zO;{*$(pD>Sx+bBO-1B5P*5SHuKz|_-o%LAl3=4f5h4l2~!)aswDLkFmglc7|_ykZ9 zwIHua>uRFQrmJ@v+Hsst+ll2n(8zXGliF92+FKmIp~+&iE3U_f+x`2NE<2!}951_4 z^)ZL>_dfz6ab`9e-0i|&%>&kw{E2`Ct@LfZNcu17uMmk~DJo)d#n}(SSnwN2-_MM* zXe&#I$`S=msw~Of^4QLW*j}VqdQ|+JZ`!yxJ~W(U842`3f~vTr8t_f2`>CS%_;W51 z+_yXlO>@oN-3h>g%KKtkM}nU*9`Tb#t|5+Y@YSR zSLg6A9RK`5q!~n^6gj%nRS+j0Wz8D}`lLYKP=Q7nuW3ZTp5;M%7!OB2)JNQCq$x>v z8a^r5BXKCEQx)qF8#0v}e5jcKnb~nAJAfGcx033xG@%!NHu}4bT++H_SGffHmeJeF zVzfIGL*gpksQ2kC%PDy)LzukkJzA%OU5{yCHPR2nbz=ioqY?Be%c^(sn3~HnSi?hN zN~}4^`vEE9%15e$As&x6pPM^@x_DKpWji%9Wom0yTE3)lK`3G|#}bs|!Hygp_60Zl7V)!f5mjAxjOq~WY*2aDbqLPilzCkDvySP=U8`u=dwn+gy2M@=zP<$nQyhdpL-V&T*e zyK?Tsa5Af6l=T?5Nk;l@B=D6F7j<)OUaHpYB#NZY?cJ#euj_`|x=D z^c?BN%^B5sxs+hgOv3gbZHZGGv7I{KTklE-=?a|!#Ww;bhseVc7gHaeEnvp=5YY3i zDfw;<--&JK6YoH(+hY>KnQ73F-ge=jV#Sb9s<3eD+#LJfqt|N`4{^+7NSI_IDtYxG z_l`y`+SG+GCB~4$}qjOj4MY3ROjd7dNYFzqOdW{tZDg2r=$@tstv4@qPXcu_^XMorw1}fG`p+*;N}iFb}qn%rpOFnA93GK z?8>mVn^S@F9S&}~=_&TDJvkU2rXv|FChm?q#V>`mps!F;YvXdlMmv<5m|JUbaC>`H z6)Dg~?j7vrAPabu0&m#f{A~B7{B{HRX{ut)*)*nZ6bC(YFi+GUE35wrYUv}_qXP~+ z=K2g#gYot&HT@!C^9LR^sx@nC^B#TR*w6BL3@o9oSH)9jx2huWBkmx=vy!iVR9C@6 zJY$8)3`?@1uIr82Hxj@3Tw|Pxd~v_&u8M5U|5W-qE#I8_jetd00>91MXLslEhMa3FjnjQq6sHo6qn2OHc^ zWjd8$+87=g0U0F>@f=(bvjJrL-Gc*Zpz4AW02lDnf>1Lk-xj^uOayAgTlUnh^KxR``E0L3ticRmSbX`^YtRmMMXb@y-{$o+ob zUATM01*ih*xv=eMp%}a!^_lUc&)xJR1<${pm&wpB&^x-PiOiS}Z@q3}9?G&ivHkMr zt$6tWTE!QG2&4WtKVNpA_wx7JLSER4M74aPth2Fu5h?AW_)_u%e=L6+nXNwlw>#YY z-o4K^c?>Q?emL4zJPpb9X-re_>bc7wmbRA~!lsMJ*y!8fL5@1${aMiKNt>QvCYITE=1x(|*l|xg% zKXRIxnIRrVd4BePHTBspx1Uj6otS15X_wEpyi|K_&(%bxBV?vmyBmW`&_R{eiKC#n z1Xb1GO-lYye&(&AT%|RoH`Jq@y_~8w2}LAhbY|SL>Q$a1jn%*_tAV_{7Wknex+!X2 zQ>pq-Usyt08-g>1P?6yprws^6h~3y@`ZmV)v48ULp(mH3@SN4^8eF|0h{?@GV2vTF z^J)NEE@}=5rS#Ad%K4`z)6I!~F%kxjKk?sG%G*yRzFw(xW~!O``BFr1!`stq^iM60 zf7kg?JW1b1rgXwEFT=2ZuH5-iV6T3z;+BJEfJ=bOZvP8MmF3>sUPSD`{Gz&_ zo1us3EU)QL62IQ`iyn&T`QenNVGJlIpiF*?8=iDJF7+}A@S}uAL*>z01ji))i%~~w zGsI2VCU(AHkg@ZCB>5_T6h#T%Y#{@kpz`GFP} za6<>cMhZak1=G|@z?A`oL?8ulv0A(j%n7`;@dsJ6?#jo#%Jps7`kWxRy?`Rd2UQ@D zfyivtV)VpR2#v9q7cr=tgFe=NbDwj?k%dRB{kwY z+7ZDPorK)BV5M-_``xqnE*?L@)~V^Ve_H0qmoMc-bygkBvH(t%^)y*i;zxJO_R#5O zq8eZ~5C9`yQLaJRw8juXVs-f`h@70z*{c;F1{vL>Akx5&RE;&^vzCHkWS4npv`rGc{X;fY@A}N zZsE|=f8j-8u@HMI=2NEiuXj=?q4hT1Ny7dls2=RldO;VM&d1MsL&7fX$u%{KC#eeD zKFV|IMDPY>waD#txUfUmU4F}fPGB`;s5NQ&Te3sl94n(W=5;itu2+q&*1P34C7QAZj~QA|NWdFtkA5LU~yFZAc`KJg>p zm9F>TcG0Uqz4(m#OlP+9MasX1o?T8_(rHC^{wY%_MwC_4v#p=Uv`>NB(POj`4ce%pmBj7A1Lg4c5td&2A~wlsrMq3FnJq>(?`1@1=uh?QYQ}(p z{Kj8i7U=bu^}ENE(#!^L3%YO&RHDf%WR4EFl}@=d??eH0Dk-mX5@001H!F1@zs#bFLj@kwUQ}v-IJl_^Rn|?>OPb%YAa_<`UH~2oayUsN zlht_ui37#b&uHh|SuNnB;i!N@lXWlu0ka6%_?pv^OoBT>Ct5Y05=-=u}KTLMt^2EAKoF4%}Ei3G%e}7k zFK98G!C<$jr=N|S{^sO#DWs7QZn_#7^OeD)w3C6`v9x;lj9Wk1d??#{9UW{#2>}v_ zjtG&+9AC+UJDoM27b*Dm_BQIqVvp%+>m_>HsAcUrWviCHa-a*S!i4;}k=`Ws(UUdI zj)w_kz%(7BsRaOb83sZ2Eb2AZ&5-R7Mh6GDyReE+&}2NVI0UUz*d339&fo{r4`&7x z3QpT90<;ZuH~5GR%qj@0dU_UTy@%<5SV;I}POm{S@3hm&;-P317^oWhOeBf2jBgYPJcEDv!YRIs3~3H_bQ4HPQsS&5 zQQs*Iy^S%h3Wb?dFVP`Mu*te>%FXuep3dzjFe1X#S5v*LwjvC^4qfdHQ_Q_r1nrO=G$*A*~*1ql?!v#896(C24_2R zJYL+b%2a%nGSmw$97h1Jlfkk<)m*vv_PkZ@%5n%(&Sw!qNs~1qPCrVima@5rt5i-h zGCAK}c=NBr~jFq=M(*f0?Z z$wn2vXZ^LU<~QMBGj%xg>ZP)At|MISUp-%D$=iT}>X*%0l(ssyzzG@;gWnDpMqAXM z(`B2$lPt0<7rP|qEKTk=^oL@7LG0m^Di}8o3^a7FAkx1(@D#zabmKa`+GCD^8_~}j z;9K{WpFuwr;qtNY4A_|^)K*MY+Z3-sIsN&ckrRlq0sH{y>nX6s40)^ee{6kaR25nm z?V(E$kdp2$K^nP)v~+iebPI@dr*un8$DzBsL1`qUyG!bAzBk^#cZYwj4jo6&-g~Vz z*9==}kD-g(HwaH3=QhqJ-{?Wd(6xLPvV{--C5>zW3XXp8TWPIcb}A2UKJ=Fe^81qx zg;jiH90e=n((Hl)1Yk*mghA{(veiA7&Vz*v4~$ybCcT$_{|*EhlERqqfIooQ^TpYj z6L7a{wOK&8qv3nP&m=hDT|(g7&eiLRf3_RmA^;i4331-IoSlIX7ZU)1&T$fNNMv;$Y*TTwmpra^W3R?x#8 z2e7_0=mei;-Nb#vrhWeFko>X@H~0r5&zhi$m0BB&rP2gzQ?x(Z+q5Kx%8xPS0jgSk zjkbrJ*OVRfvxrW!Zb=pmbMJOt_|JOZD7@&^fu`InE`)lBPhI^WWr&s!P4KH+;V+TG zUup>on=FT3aewm$HXM65&Px7O>sJndE*dKa|85&ZI-c`sNiw^{kjF|1Z@m>3j4#YE zP@wg%cOf8kCQ)~b<24$ls%}C_Y^GmAhCHPqTC&KOjr|di;qcpvqTDsil-;6Km(kJ+ zb1p9L3P)FS?D@!hFryhFJzaV=X?>|S#Hn5yCyJw9udG8eVaB&@>~+;D^!jT#Nvvi5 zdjf1Kkiu%OE90*$BkJ_u!=ubyt1|=B5`E#*^udvzOmVlmS4(bwVFGZPTnJ2@!QHI! zD7&AFfT(W5$7Tj#SLg#X(%c^Jnl~3uND0_UaN{vd*IK|fLq7RUv*(BU4abk%RG_bn zD}?V7#f%ytgr+dXlrhcjRM#`x@Dmv`y=#=SbFuNLnp|VLBjpZ2w@M_;SlF_zV+=w1p5a@iu9PM@Qf9! z@M0N!&Ofch@r4CL_2_X*iZE#l$@|+QsIN17{YR0e7G9f|xwU~l2BLV@E;D;-H6n%G z#ldXw$N8DM$BE{2BLmJ}9fW5>e1ZqmZVeHz2V zjJWTE>bk?VumSQ=M^IT-wsw2AF=_ce!KAMvX2(ia%fHVb8*@z+G%rm}O&m;o#Z+v_ z6FNFfby!53!8`G>y+4FP5!{UqI_c`EBDC5{5jMO?z^&HXzA+-k@)e>ty2}DuB zc(z*pi3ErzKzsM%#Rz6Zq8!B{V?zWXE*>7>%i3jCXAG)S>L*079&L0z!1EF!16q-N zfMHXtHZ)8vEkyt~R{)5CdF^Fkf(*XtVx4x2HzB%`PZl4g|F@Z*Hh! z(U3h9(TCi&OCHadj>4&ncQBvPwYd{e1RSS8*%l`E1-Xsyxwt5R%e~f)ducs^M!K)7 zF|Ng%um6omCZjR-`hyuR+LS|@Z`Vr*>h=arKu1C-s}gv{N&vyS+QZZOx)Bg%fsX`M zDa}e=4`%}mQZaqTo!k8H&)BWh!zpH3cuu+;&U6%4Zz+J_|EKY1dbjvScY9nDE*4Eo ze*Y+Uy!~E`R#(E_*}2oeCSO7djJk3Z?sVL%a*|LC!SLTx77mq)NE#vd5vWvkWu-xy z(h15;H<@L4Xt~z!E_Lp!gm8U1w?4WFg)F;ZfHsNUeE<96vbae*)_Nv8dI@EJojJ?* zUXGP)Yv1o!*%}9*6>;B<2zcOGr#8H`nVhwRfjqJJyj7gB4j0ynRT5^Pcbs=2s2QoT z)TpI`rU`#*B^~;R&EJM0s_r|tAEdC}Gu5TUOo#`~Tk)$~2`Bd-Jh(`>m*<)aqAbEd zD=0*MVDKaG$$IV3I~%LH(s#Ub0h680q}blvG!rST2N{o*2uur*daE*MjTUPCh2G#B zRij_hHlEEuL#({Ta(Y~zL%^JDx)27v-nsO%< z&!p=;n?MPoNk4=~S74;Dm|wm|&;GR(bm|6QvPcLRdaJLe^9vt5r$fr|(A;VrZQSf~ zpA0|Dy3J89#jCAIYahp)38!5b7+qlE8Ao7tjuyOyS*gNLf0Fw>J4*>3wuptu9~f*a zUvEA@e9soxjI|F$O&tHrK*WtjfXsq&t`IlcG2V@wQs#@LlT>kpeMsM%~fHAnZ zxWFBy`GnjZOSeTeYlRmPdRKpzJRotl8(1iVA`4u#nubvgd}Z)#_+)=% z^r_p00AM^vy|nmJuMSTN+6$}vu1Qz~)4N2MxrzJx#?vs2Ws^PC%#W`O5zCLp0y4#a zTnb27AsGT+FhFz?EGewu2U3Nh=&zNoAf>{MMqo*$P@V!4xzmPQCEM&hA+)(U9ANC& zGz2Tka@a7V#^=h)M|H_wO=D_YUCn?F5e2Aott!x-&3+JQF`KzB<&NEMXUeRogb=owi9MS; zAE`sA(%^GjKD$sNM(9V}j$=&Mo7)upg7~szB5)#5)pm(9E)}8UjfgNG%rN>^-2udL z;hrPvL%IGZnx7v7Dnf@)sy&>18gv%lk);-*GJy`+Y1xgNU}}Gsu{(^t)sF3FU~Zyw zqa(rGmx{cZ*>D=8;=oD_2x%Qs=|O2+$$Mkhg!?1?rlYUxC-?Y|RWnP5IN>H=j#jka z8tCl{XynyZ%;?4i@-hAq$HGE#{rDSi2$x8!{08*2t#G zu5i(}jTg`bX&Zt+@q=@inKN$0k|K{+n3uGWEZs9IZI zTN_D4#B2F)fG8Bs$kdvcu=?&)l2rMwET}Dx=6fA-&D|kJ&|&wWs5>~ufHi95?w+E} zTHsz+#(}^{fUPKLGYvT``!wY1SF;RnxoJIg}r)K2=yt+WO5f6B`V8ab^MLUh5 zpqnKHK~F%3Y-wi)%o+m7UDJB%8&rjse)OVtg>2C*e|f_3%Wwg~8-OLWZt%2a0KwrQ z=Hlwxa9XjFV=nLQW^vOSwE`4z^h|k4k0rs(pq;21JhvpaahOG%;>7i}4JQYwsmYH3Kc4ZlqWZ@S>}%!$>V=qGw*tO}YZ9?xDwH zUmLmjf&^6?>k0b`TH$!&wM`Gw*^`Sz;wh1gz9JRkP-LhCEBT@VTygOpG25{@hwmI^ z`RE>=yH?#4off`Mef}UyN-}`PY$4h{8HUPCCM?Yooe&qJOaW;)!4OB9#*Js%fu0z- z7uM3&iUk@z!qAMFnD8sJ(9w0vD$F%abHh)$v`)XA4H{g1hehG9FUfWce>{1QV(>@h zpew;16@ZInEEQd;E|jTKx!LU}#Gh+A4Nmh~8i;M4 z8KzDmY8wwfFyB|09a63yv8#^b3)^+?%<(mC<7mJC?{t7;Jf{V8p(*U=6YZyi!ja!W z^XMq6h3EeS!JJfN%;;h&fQi>lb7bWU)8?xGsqnZ9fS&@HV#ju*w#VGe%&e4|(k8o| zBDd!Fdx9VCdXtO9_ID+p8|Z^Qc5^t9gSscJ>ZE8@AUMcDur#xZPnRt5L!H?(-9>Xf z3ya}bhM1{;^lXB9%)F&G4LB6a%gTf+=kh=#HzKsS_9?!jU{=B(Egz@X7)k)lKTvMc zs9XMEB+95&U&}y|K|9t*)oWF$NN>oIItjv1H~?(t1BjhY6$RVMPFXk>Kfc*<5lC9G zCU^JQcr)YmfQT9`p&08Sfl+hkA?LZdxd`7@!Zn)230T%^`poC#a-6S+-Trt0&!7yG z5=OdX2lxqCV!$5l8fSkjGg{!lEajeB9pAYCmJK+yw_fcWsbtEm(|ZdWZ|m3ZV7j$8 z5!U@aVZ4T)uctiHLfH-X`*!Uf{73gpQt{BxV$1io>r;DtM(bbiPQf8E0s`=a^#K#1 zC_tEP%AbG^2;`3+(gyqn+*EYhcoeI;G*UT`SY!E~knl0G@ZppQTUlayC7%WGBf!85 znBnjMksy0I6?!zZLRBxt1zjqy+aba1+}v5}gx60?v%NhLUgDo-9-Fa}FK&Dz%n~A4 zM2FM{uSRRksKZ=mV{<8hAjq0uaYExQONs)TIq8XMY`#r)*zio ze`S=>5x*;$JLBoHhoLuLYtej_)dz{^R#(B+jjpLFE{+R<(H?Wbv4=l7?O4x$Z-vIR zvNb5@k6L8ZswgR=S1o3*Pc|;NxSLT?n3PJjDW5c7+xqwjBH)a?hZQ-w7P$BapmRJ28>}!nq%>3+lv4X$jO@eMy$vSYxuusM&XxcEr zAG>8;@4Y$Ey1`|#-&F=fNa#CQ`$Bxqg|{i`qf+D|d`Ey})61tCsVpK)jfTzS=TVQ5 zf9zRDiryT|;Tf#2BA7{a!!nRGwfGygqg&xK`&$h}0GNPoa`dOUky|Pjb0EE@#?OTL zXnPgk(O*AY_({OXhPo}iV(t<@Z8!@D1D?|5)^9{$Wbn)+wLUnQ+;geYDz~)#+;wIm zX;fA!Mw>3tG7wOA#RW#;j~E}n6G~BR41?B{{AcKt8$~+7`JbWSzyf$%9vdo)VUf0< z5+?OZmtT=F*&Dw?JS1WK4v2P_k9ys_h|sUD=B26E+!_pRr(TO-zMy@-eV$Qs(>xDN z&&5Y>58?EzIr_hTeN7oVAGBc8-QQ2>)vgs8N!$yP$%g*1)m?vh98&nZ)$#oGeaj!k z&+nyrHwF)nW&Azd>>T+sEkA#bO@O04!Hplr)v@24m4H$s!vb#z2M|-EL_S*ieCR1Y zD?y3<4s4L;wCe?Xo#amm6lf?W%pBuWU{YAn3?%u)@MZJXqYBGJ;wq`^H@DA{mX0LA zNCPl)=_VX-1rb(^VigkIFlRPTXjFOaqs&QOy>wuJ(Ex=)IU?8;`CRy0*33EHf~iOF z-)bE2gbBrXGUD%O!V2h_QG{dypxVrX`_;T|w*)I`p0eutjveO_#&`NH`03r| zee{J7Um@8A#R%=A0oUV1;p0DT|8aw|HK{%qoEVi0PYiQ!qqRxT=%uxlp=^stqna<*WD{n3^!Ysej+mrAO7^dD3X)wElQ3{wf^n@Ew_} z%%;^AJD6OY4$u5ZtkXpRYYhW3hZ}_+J2v$0-$Ce6AiXgyPfvgCMRU{wMZMhx#XXm1 zXYl|+9&saEHbJNGqZi;#qB-~SwPRzJZY_=%=UZ|2`Te(m&O=B@SoDS=>zXlf6jhAU)1Rn6HN~no9qdiZMW2kY#}|j%~c)0tm=3j z)*v8gMSXfDL5x)$LMnWQ8~e|}c%md}fLe{={N#oCm2m3e=VVAz?-1M3(%f7mM#?mp zHL`WOoo@ekM#DfnM=?9;BWR_su3Q2C97t-DCmDJPf5;tD-aGnL=o$+|5-TP~C^OCt z<^N#ffk*>-+U=IXlbP3n&Z;PFe6eRd<#mM>Vx}qyOhQn?3K}Nja9)PY3=9N)$GTzZ zWugHN-{iy?faX=NF!D}T0x)1K(7J=PgZFx@ZsCecxD`Tg4G0&`7lnI)oGt?kUghFtE~CCIdBo3 zKflVtYU0zdfiddx6uTkc{-mdh(r>0HmW-U!)`WH72eCm%T$Y{_El}?=_~lzR6@66j z7In7ZcHaq$1tz<&rBKQ*)Sf~UnbLY(i6$k3uYqmMIop%<`nxr9dN=JQ;kU3f)Ms71 zNtw1eV>U*=?;kt)mHcDj4(?}^pASzhPLIw`q-K?5WHX;Le{(s-FqVj#RA8-_Bio>> z_jO?i<@%#m+^&U(8wNiT5a!Kc`PE@XyKwDETWShQir=x zgmhz64n?HSzdHX13kE4sWGag>qcLc3nj$)XHHn!OpD|?Rt!p=~tC5>`bkbunoj2Y{ zge>nf*$xbZtI!*(0ZB-!pJ-?9W@RNniWYQ5514_r{3~Gi2un*N=l8IeAB z7nCyPU@w|cgE4|!>XmWx-B(!cP%w})*ByU90Lfl51=VG(Glb>&70|`4L~d%}Z7b1k zdIm8P0_F|`uY$uhKaOYboe3%y#4hC@7DPjeHXWRuou%KZ0mzpv+|g(LwRo$hwD^Jv z0yxa()J<8NHNSD{yB0QJr`b0{{p)110JDI{ZaMo-c*@EabXCjCuc9PWe(uTrVES1h z8ZGGN=Ce68u(c85^*4$rviUtM>S$#~^s(<6-y^4`@03AU=iQ*>yUP_;x;3Iz~ z>j9auWCLJrOK{22#ut^B_knFKkjQ1LGOpj;k8Fz;kHz8u3dC?&lp{yQ{DX{(FgGGh zs_X(kw>9p3>lKAyDzcl;IayUqn|z|7`p=W>pT%(Y%PBz}IV6>(_uoe$0Kn76)q0O) zamrcYN&olVs}^RdhD${n0`Yr_vO~N{p$E()o^D07f-Cah__^@P_GL(rGKATjPYe+_ zDXHuk40KNM9-BX%i^59CnUNK#6D>!1MCWm{OXoz&l~ocG9xaQ>>;;*q$yAevhxWKq823b=cYj%y14epI6uIq1Iv6f7?4z2 zP?olBKdLEd9+aQ%JXUG4U{;H(y}i~`F5$9^Cz26AYf!c&FDQ^dw%FsK#&RX6j zQv{(W&(661T{jc7tNBVVlLYkpU^ltDe<&>JEYNiWIZb{;$5)k9#Me~u3k4gK8w`x0=olEruC8_PUa_ubPEOdM2<5LY49)B6=!mr} z>BZ*CbW)@ygTu&>l`->_bRI!5FY^lW#^-H)v~gi(XF#?%GfRA}2p6i6F_x%Svn^#T z{V!#U3m_E&V?bJZIzzl)*)t$zziftwhh@SR-*&J97hjG{Cx1CjGI3?RbM%Fiu1ca! zd+%tAJr_Bx?>9xXF68t8Ny{%>J-qZdX=Uhy5rO0ug4}%2AYZ;i0M9 z0O&%3{lh`W)4}|oKYdw`3t5SYTUpO{SpfA31Jz^=AR{19HBZo}TwRuC61h>WbOsXc ziwe=!(UJ9!!K`pD@Vs#SUei9L6@EuwH$nNE-02%guz+2VQMYc|O`Fjy?|a$~KnmM>LvkKd8Z^HB2K`*-NNyS=szrl~ zEu#f2je9|h_+eokzut;o-s``u5pu4IYteg?cukT%W~;<)i`-)Q1jB?MFuR}BA;LQR zuM)Kp!1_omnEALsRgtF&n$$SKwGwH}scmyl@r_j01mCDmb8>buxUWF`qshA=a$f4N z&*e2T?7h|c2Sw$UG-l69zm$`6zaOeuXHuV&a{s4^tSsbdZNik~mSo7KgSCi`3-k0X z$`w|hM=bra34IZf*qN+PfOBVLe{il~kzZyeQ2`_hb=(??DXdU^@ic$r6g9!@fu4z{VM76YuN55t*hahm!IoeOanM?sxUE;&+t^e&%E5TotfDA5yci zlbD)W2y43Y&}24uPg`_2+UEkVGl<8z{c-mJP>LYF^(T+7-8o{z4~SbTs_53b3^CnW z+InH-w}Uw?#>p{}6E#DTB_pWjOGb6vs?3;) z)5WrWDz?{B_?W$y-hA)&#nI?~#2YFy9qww<_?_<`DFcURVCciuA+Nn?P=2TbTVniP zA^&CAGeCvj03cS}5xf(5O`3e~Qixzkk05f`fwq5Z2rKQ5x<7n3=2h?70|&94}7-G=D|d z**-ka;+VrLPX@B4X@4gC2Wh*U%58xmbaTAOnikg|KPV6aw}hiqy}6uxO|xUE7@N@Z ze^c`a3P#S%s7Vt>5|8~{{NDeNLViL+;q~bK--q@ZO=dtHa(}#<``nf&Lj#Bh-X%CV zO%H9#s`J)|tICE3%xA9irJF|f_H3DCth$X5Fv){f3V?<~D+c9C#vSQ~PkQ$V7x(CS zwhj0U?C@o5yXnQICg2$AWJV8jlXBy+LlXmfoy7aL$D3J+peY>IZgHXpZ86lU0Of^=Ub+6PO$VNwe4|4|(HZXKaX! z`-ano|Cq(V;Kjs$F)!%HD{Aa)R&(k&xUt0Tw{7|{pjT+U7#A?Rn^E4%pH(b&BH?oi zB=j#yZJF=5*}zwcnlfUurB`FEZu%?YL9<{6JJ}amX#5=a<{D7c32{ONleGu?F3I|Q zGgZxc38gS1Wx1C1DM^5DQ}>qB`u*y2yNv}Q0YN8NE+8Tyfi=Pz$m_=KxVG+4$5Z-T zx!1JwqX&cn1huydy;!CJ8JMN5ZQtF+&P$?@7YGIrwY6no)o+y=aoL^Bi8G;qowc^I zs;a9)Xlb)l+X;ZLa@`=IyF2L)5EUBInk@Ze6mf-KAHR51;CcS=Xrt9zA>D>nv~uRy zk)5Z#Gi3#79W!SNTkD&Xwp%{k5FMrnZnJAxI=kJ7F#*qPyXq!& zPmS^!%7#C7pt4&LXZ;IK&?i)<$A3Zi`oh%MeiC^i{F(jMm2JV`KsDb!zV{;N9i~h+ zIO-k{lC@)9VN1a$!bj0y%aA1N^Z!rSV;?dJD1}u|hgJCYE2#rH&CH;|IHplk#N&{v zl~ss^&UvSdOqjiV4nSxMruMJFD_( z7C9Ep6>W*q8eB+KiVm|QYu%pB{44w=u**|QE{?C&mQ75zg=_b+(W<3o0W_CeYFC-g zlKf9cpSp4!5;k?p@aCVV2aL1PabYjHEMg(8b$QP-W#Boh-oF!-v-ifN6YbIK| zH}(2_gyfRMD=25TwzLpcw*M|#9*;JCu(t*C>`S?2 zqNSyExZG8GAu@p+tJ|a1CtDD3_Ogz?^CEr8Y*J;!y=woqUtGB6)KtVF1x)z@=~>j6Lm&;5x(^mt3{Bp``&DyL%4_DPF{?UP>fgz5wye90 z_wNepjcDud*S_6k%7&ReD(c~d-#Mo26IE>*_{o&_ZkvOoyxdprvIwmd#f0n={#O|^ z5gB|M#&xvIR5 z2QlO=Wx-mu-CL(I!;8Y>S`F5vXha$TX5ZEZCykiL?k885VnCq-YA{5m|L%2CW_d?4 zc##kh73pzyz5Y7zPEJkvfpAFRI1L=OK7IP6$OxAuc%v`}plT8xz)w$7HT(O^o22uu zsW|P+nFMk1m4po`FVF;K) zKi$SW69D!d3)7sB8>Ooge(HMi2_ABq4x$mMNK9^M^G;B39Hs^1`=g^&5@VE9rwSgw|VVZmf47(8j`&zPOk#Y0xcU9ljqdnFAmN9>8Db3 zMv?Kj6^md9oufi4@bbK{t)E1ekhi%l$Tv4~kJQ3)tG($IVf$IkIT2eQQ(9e-z%?Pb z^4PVg+9du6z(51RD7cyvN}ne(vjGqj?AK)|oO3Fi5{+;W_R-%Mzh)s4JW+t*xvrA+ z4+ouhAm*`cnkQdXanPB}=fN@m*Bha7ZjarC|t?)nibPWv+$$P93YI^AR8aAUIp9tJE@hfFAExY8tXZih}!2*!y1p{n- zpQ8b#Y{KX1;zj5~UHR}P>lPm5@%aH?Wq`|WKnF-m_eq`?_F^ST{pJq(WZBwOogRni zvH}5-3#5a9A>s@;*sM8c-4m;=xIaJMobC8L?KFB^&@L`6vI_}eL`ehye-JFND%mfE z6EE%pOL@Y(aO$V~BV6Q*n|PlrkL|Z*<>g&F7t*YkUttCguVT=)OBdwerVaIFeiWy5 zJvq`bKQ)z+G7r(kKR8c(2&wdWJjgv_;hvJ2GMu*nf}Ms2d?2-$Jh;*{FhEiSC{@{t zAc8of!6$Dej80jt?K*815EDWD$S^Nn4JfRi&L@qb*~P^u_^i4`yc0v;*owWo^;bt= zsoWkn>@e@V7$m))o~+!VAVn(glA`!J?US`^?eDN25=i9yRU;|3CAGMI{n^Jny!bDL z**v>gkvJlTQ%$wV5BX(V#{5ghJ}qgwnmTO$$|@Fcl<8QF&3c*`l|YP;+fqoh{xL<{ z1x2``muM$GW9Huu(tklG@~!Q3Rczu{z@yUe--f%Kr=(d zgdOt|N=JxEIHck-z&R3K-N+KnEXQhS88?2{j&@bx6ZGxys$>V0=FU=(!uF#GYYPLY z%mB7o@@|yVi#A=)29lHWG7K~!4S3z^=*qvagX%-kAWaW{17k@5Z>7jBS&rQ}P zU$sp?Xv=-oxc|^QJPkY~zz7IVp*AXqII@{AhDd^8iABZKu+0x(tQ(#EdjCnhxL--Hap9+a8!#6V`lC)zil zTL5kbmbIKAJuvY@9~BhA&$%+GDqzS1pR9DQy0<+}dP5cG^IKDJJIQJ$Fr*FW{Cpgu7WboR6a>5dj zvv0OP5U_fq0jcGCYh29^R|I*L59&C58;2<}F*H%=UkoL>r^0;Z>$~P$2viWzxDVkl zYq>Ss#HzUK*M1A*bF_TEyuQqqD2H|M$@{WeJsupp3YY?#qtfj@M)pQdOVn(L%N4)rc`Ap81jB$d^g-U5&dqIu{eUIz zCPJF_97{Cp6-BIVGoqrTyl$)~|2!!T&F}b` z6UQj$=V}Y9->-T~jLJRlx<)xuVQ={}>GrvA+bm?{= zij&A=h#()H%}Mi+VeSC8TSg)&b71};KeMkLNdTXRhbQ^+b$c}R=Q?dbfqbFdsG7&N zMkuS_s(ucE5q4=n9=yOS^$3|4=wp^OO?G*>bp)|+1)D!Wrs=C!uhufZtoSY1^n*xK zp{rtr^^pG_DBwjp$sW4MvfJB9J1zt|sP3PhOFkPKLO=^`Uh@{5WT4~Wb=pJ*dz)ZD z|5{%UA?v?szxerrteg6vUlb_`R7j*h?|^@W;FX|cv4!MUQr8Y5ub2LtVo(KQo^h(pE08?lV7%& zxZkahPsHOi`>DA4so(wqvHdK{KD0f;-4o2bGatpM3~?c27E38CY-hSBdwV(R2jk=N zmUY^|P-to_Sv02;EVb&&G!BTH@%xh6q)2~&z2R)c@A!}UW{KGOKWLIVG)ilAvr62S zReu%Ue$8K@ne*A|PXq%8NY^~OUb2_n9x2Ct;Jqm>2LiD^31)rKuM~JLLLPE;QX#Wz zYQ4~wmKV{he6K^c8@}ww2z#oWrk+6%tPEfs|E?ZqYOVry?SRv3GSh)-ufao^E^dWy zT}ML9>l-#C0OSvVN{Km#cTX8>Yno`ts1@>umM4uU&Cz48y6j@t8;%ZoLZU<(BvC9v z-vIM90KEpPWqC;0EBX!@^JDqxjOO+hy@2vvNfBz@MV;lZuV5TO5#Q==IZ0N$`zc6= zMfivVS+m)tyUphd07;x}RtHDk{bNA0Z^WGrvfB&7y)M9Ncw->O1iW42r4V|9%)mr^ zfvd{*{eF}flqNyE3BytEo>GnH7XGyY&OF#q^tOGyx#o%)8Y6LX#VMWe-YJd|(2(7# z0la)(egT2?i@V|WkYPji)ya7E0UW8Xj#t{yK$7_^h+Lu&B+Z%($m z=(#cp5ORTf?B${EOa_G#xXEnvM-c%A4G0tkG4I%R;aCLQkk*jI6pW_N%PKw=jELrwtetukHj`DXRC$go&TcI8d$SnWB_1kwjK5ikO z5TjBMlq)bcy`f$ZTo#sILJ?XN?p;`-+tAh28kmIndOqL_5BNIRVS$!kt2t83Xgb#& z00%!C6haX9CTd_n20V1v&fLEbneN`Zvrp7hK&*^_Q91ZDpyFN5yh z#r2|s(rtBz+IYV~>lgV)jM6M}jCH_SwiPyUv)q7qW@dWP*N?th=w4bUnv<<=@Ag07 z1(t2LaK62dKO>&sU66D?zpoVSJHLz{NqyT;%@Dzv_5o&_Bi4^k@M%Q<1s>=51b`-o za`nqP9zXnlZptlHe0quyP5kQ6;!Di^!^S*z6D6~*W+-~4SsK=70e|b3D|WtR%?j5X zi5$_&na~wGwpv1##brC>;^~?L`~SxUfG@*in$bXll=jJV-Ht9ZU-FY6te<7_f}h^r z-eKo;fV6MXZ2si~;#jFlv+o%BXH^$Q%pD#6Nc`XIt|6W&|h;2$ECyhhjBm}2LG2|?c2uj)Him0GCryZ>Gnh=hTFsAUYE?KcWN<(yO zi~3<|10Mm?xA=!N1s&b}KB{3CrC_6X!nkZl+U80~nK|H@Rdw}|^F_Z544I=3J$p?E zIP7lkZylZgU48~*vlrOL-Huua1puQzNvCD7*7W2T;^IO8YUT3ZzzFI8rHP=ap=6{0o8QUH@Y*_c6?j1tgnjdQ81lpJp-xq>#_#_ zumNRDRlWcDKU&y?7b&ZdP&BZg`8!=8%L}dyh!^@GdiQc=LF1JJVu@eqT)=A$Bqat* zQTv0OvGtcZ2uMwzP{Fb%cwnOol!2#h`zJ(TG}`F2g*tOg4V+&Tr}g0^hP22RR;Bim zM~<|m|K4*OAVRZ6ZH(_Wm6H;zSR%hdDOIiVUgk0YY=UXZTy2)L$us^5BqSC6ep3oS zBE)Ob?1xK{;qcDw8b}8eiUoGLfMGyQfX&CBxRG8HU$!iGrPFbxqX~o;D5xLzyRZ3* zPg==Juk_oae%JJ_(5OikSD!l-IpJ|#lQ!`agF_2^S6$9%Z@zOJyS^HUViL;Q$!iIY z-biXLJ`^(6vnW5*gYsD#!w~Nu_0RU=5(IEMG-oKz{1z@y2YLwd^od+`l?Z7GdS8cG z6iu>SqR!1fNG2JY?vk&`y5^&-fl*rTa<`XOJFsv5LiJ_pOVMkv_p_O`0m?Ns79@IH z{U35)V-0lm*#2uO;da1&_F@Q;Q&SCk+JuZ+aeB!LrO25BI%7hutdBk0cUHr{v+%x1 z7jk382E9jq3ey%?QI2_2p+H{&>afz0U6Uit+zu%ioXaXIfTaIl22g?w@2pJl)7M|a zWYfiL{(gspN$?1Z?gG?IewuIRU0@X_k`tgeS2l<*t z##Ee4431TGwg7hQXizszV{AOAPAQn=_;?ar1ia`$7p?N zSwIn}-lCC@e}M!6a`z<5=klZ>o&N_#vtcRXp+=Pvp+Gro!uz`Bc37j`pDxP_8w?k> zJ^ww3p$>OET~%&WKL4vc>tplA`d_!BTnsSmAU2=7k=*eDz#KSrm&ugurS*HRj4s+d zFIbd8CD&l$qeI-@;%;(^e@VjzRIgLOn376TD~opORH)E5Ch`>3qPT%7P0ZU*lp+nz zD4~|sj2AF#(#3@+r!%z+0T}G(Zx#s7cLh1QAv?^Q7GKrU@#-vukF4w|ziY0ipZoSZ zcmBJcH+h-!w`!~VGuv#GO8|}Ee{|a*YFozFlcoJ}@DarkreZ&az37MQ{j z6paY9bt!m7ygg0EI_xH0(ukXpLH=ZHb|DTgg1G_vgrRHbdE^Q!8><0}^829^j4aar z`En@m$lwc?sgq$7OaUL!xZ{ug8g;`E`g1NBSVR-e@nnb33YX4+y#Wk_kOad9KETq2 zm;KubDGp@0Lj9A%GE1g&us347Egdf-GLK8zo^i507g7XG3j#z?NqTmC1HO;lu2Y1p>-V8u`}LqJo)RR-7E`6XP(Ia7zfE^ElvmYI#6-Cv-{a=+V3J{wZ-#(wdj zYyUS>nOjkT0bU94z)pe90*KvnyxLcL(LX^oU-|qi^pRN=>+}>8g9Cq^y)%rr->J{g zgj)DEVBQf;r=WX^(_%MuO5Oiyil;_u%@<|^b8KmU+|;seLToyCsjcCjp0Z|x3(^o? z`R*1IriZff-!t=#@ZYx>vP;o`JrZaSssO=haZ!8tmnpt66nz5pgL}>@#W;ZK5jD;* zdu)7Vc0WI0tI*U`uRIzmv$YkUGUHk4S_Xfe<+;xwqqQiT6;H_I6mdUbdlLOiVVw>I z9bvV%`^Dy}{dCB>q;G#y4iz@!;2i82=ELy=+DVA{L-)Sk7}lr6j+sH*p%@4WDVbUK zJ`4BfMUBx+k1+*GJ#TV}+{=R{im=GxrSOnhG`r&{nd)t#4$qS2U z-fx@pCE3A0=Hsu`Z!6JoE#05}V*jVPPn080f#1&#b_>6f*}|7N1#(cb`|fQ-TM^m} zXQvH*S^8aG;m?BHytbZG(&r_{S$+k_Ovk~)(T`sx1uoDENmv_}(1FWH0w2Tf@m~Lf z$AYCTT4$yp($&lrU>B!Q2n(ODu7tIv;wxNkAe8d{hcURtKtqGzCroa&2Ixs~%jA3% zKPwG7NMB;o&j+klK82Je`CXNjG4~D(0MwVGYWx?}WZ-*7MkHvu8RrVXR&4{YpzF+d zDdL9MaDQgJnpC@5P&IR`ZPXZ@AR_TSTcZR{i-+EXPkL@Dh4aFR*CsQTY9^|QNn0B4 zGH<@pY_9+w+wH=HH=Yt{7TvpdSb&>3I5Hvz0twGAF3#e!9^k($J0d~o#i+*>smnE? zuuSS@ollSVP@iY-p1`~wZ8I}7u;>86$P(Jxgh^}$(I7S{L2K6Mx+cpAAnR~&aNssJ zKAevzsjCO`thmFGd7Z*+kERBYJ>L#MXnpw&;SbDp_TpXd*9J)B$QK&bf&>%3S@XZ% z96FEa7#SX}G9AJ;C)xQ`zMY+laCQ+HVXMxzP@p&kQG3z>Q5LAP3V_hMxoP^M-J+#M z1dlZHCWY-0SOfjtE2J{PRS0esZobAM zhNj~urv#MQ=RI2UC%;$btfEh8vW|@vZ)G1-Z%r*RYO3C7YG}<~G+RyT>4gqxa~K4@5kxUYtL^U2C;IUN5C^S>ycxPZLDg z76|kT+)sJ5Pd{(78Y1xb?x?R;!^XNTk>7huOQUR$XGQ>9{h5^)*<=gSs^f&~t9)h4AM1`!f9(oXt1l!et%)jlPYHj9wdE;7s{%A|@c@HKB1C zobYf4PCyoacKetrp3etxV{16xICz&O`neiDAgVw{zqIXrdV^=iEIQL9h1P;ZTKmO? z+#-q0LT8+^f>U3cY^r+VnEuoZSUcsK4k_2Z{~@-uJ{A}u5RSs__|P@#Ke1J^IC*Dx;QtNa(iy9 z@WNDb2tBxGvZnt&O}Hsh)Q;v7qe{8 zcO?(%A5Zi=wi4ZUGQWT|t^uXiWS=wh97Be53iGqDMvHLl7Ji z#>*dE*?Nu&fNEzsaJyiAL+L-nV`;iwT*NDjSD%gP5SQ&&J8np{-XFIFThP$Z%vTw~ zk$P-m$r|FZ%!8xkrS$lNxnnGliXEo^j`MZvD_Gji6nAw$I;`D@Zr70{7VtzCl@b5< zzCVN(z`NqIvS{XGX*382F1udUYt9@Z)(62%T&MML`MmuzzoNo%{vy55UDT{S=O*=E_Y9iu$ z1^+tFuoSsWCO&2DyTL({aM&cWn{dV8#15a(+dEpBW=#~f`vw_V-_gG}#np&nAcrxy z8MhUG-cFEWtr3UHCB5B_BaJ)AkN^G+(U`dxl~% zGN@=#T3S(UGbp!@SEM0i3+2m*@s&gLYyTmj4~6ml|nmX10F0cc${s zRISiHg3!H|e2O`1STDP_76<7ysi{wS0?bV7`TZlnlpwx8f70r>hRt>tRp+LiNgyhk zdJmU;p+i$;FwoL^8v#oWVtdQ30t4a8wChmW+Agt~bl@LNwRZgYA$V4ffDR05y_A9i z&mi%>Y)z&pr?&!LM%rDvBw8Tw`9vyzU%|x4_&qMJ`(c2A?My{*$LI_3AhRuFL2P?L znzbrYwRc2sLr~0kVrFI(VEXN)Y|e2mXwJyY<{I2=cxkYy<1h=W>GCf>d0hreI+R#r z4n=E@y7f}1IA`+_^z*OUv^v-0UziIx?4QC|j;Rg)(z6t*CDL}rRj<^K+TXX*1^2b6 zq@>%w6@lO_iHL#$+h1Zw0z%Y0A9i?+aH1^I+gFrlA(CUle6P3FlD@nRJBf~pqUbpY za!z^!nOuF-edoM0P}ztd`K@bI9J#D9n1N%nBWq4A;B@>yQR@ohZ!GCN&Bp<&9hhi% zw@}+9*;99At-Iz5Nn)$~cXtd zeKyAtcXPVleEcoVYi>=T4mucC6(U{X_m|V}+@4J&v(;!vP>(ytR+`JO8=}t+rMy$) zEBH)UT~jkPI~xo*a)2?{d2(X{`X2DWU_G#Ns*1O?FD3RNARrJB5_W_6B;Sd38w`EK zd9ap#YpGpde&QlG@Ix8lKD7QcD{viLflebA9|Qe1c%%G;AurTabe?5HfEg2PX;ZG>_L5DDGCVvCl&as8lS6>{Nts>?-s=ySnBc62IPZ)b z0W5TIVnPy}cu-7@j3|yfp1pOyUCq2uaX=d;NgMhZ&F<;puBf>9U9a+XM>&6jWkKo^ zf;y!X!sgR2FYm00kVGbp>Ih%ei~b6F}W3=9k? zkXJfW>VlM*h@S#!nCR(+y}SegFQUb<7Hl&8t_}}vynrq6aF9{8P^3=1O;^3`Qf^KA z-kaE3dJwGnJ}_nLKDD0)M#Y;X#~!eD{{Bq2>jr-dszq}yTB%}2dU|$Tu{T z3G94OP*5m%E&(|l^qvPuj*n>YuvmtAWpIhb2mJxML_BuAV46aIeDP^C!~qp6+w z%Hpqs9w*v_yQ~P~4}LxvceVAmEu{lroFCTR;9r01+#hZ+ADc*xS)VfM?Hd3(R3yjf zvmyo@6bZ8{bw9U6G*l%=BMR^`8JaDi!Y{(^p1l3<)z{|jTBBCT8z;slOB(HFPfSh6 zC<;^zk~9|km8hgg0jhRf6sd2MSInC`|A(gQ0LOBF|1X8g&fcRWdrOfmvI&uyEvsxL zGka%`jEanxY(n-PS=q@7S=pKKzn}BF{^vT^xz2S4@B2L8ao?YH^GLe86SmAtLBK>E z=W7^$I`PHXs;!=#jg2qe?0pwgety1!^7ojGKXNMllen)vF;j(mNq_G)%BdGW3vh`# z@v>{MIQIHoLp1UvO#tWh%D@LdeaBoG^1V6T%J7?2`pXT?Nir6dRaK_PyG!7g@7&%l zc`E-Vo}uur16I7Nq5R92_fAev_3nyw|7sjfzTO?hR9IC-4t20ywYHtio4_CJ%Vl{s z`ELpfh)J*dHRNE5ux}Ub9%v5Lx~>mGL~lk0JyhE7(P+Fz5WA>rYMQ1bNgiJe=r~_v zle4#Xa5xXQy@7#sqC}2vX^{pkkKIHG#^~s%Zk-z!6m9fq{c3`PgM*`aLZ6V1jt6Mt z#tg0>y-7Tst%MSY&H`jy^+yZg3W|y?gM%^i3zv76H93s!IGUR!R+@dUIA}?m!F3MT zu<6(fW{xb|s!B^N7uM+qqfto(_Bx7hbfezQ7C6Rm5dF)Mi$i^xz~;!}U?;P&v4Q!y zlAfM-fs+^-8p42K2|v};)H*?53GgALpfc>>XSfS~E5c(ea2XnvA5~lMU>tlH7CFiM z5IYG@`@R%`&Ta9=#6d^;wzb+Q_$OXaQe5{HnxDM@k!$$jL;6U zyqsa`n>1WbAIi&d>DBK2aG+4lKuakrO8{uv@-s(wUaZkmiTlelQVI$)J3Bm2PdNy1 zlH{ETI5{EF=*Di5IooXX633ho)7!+}87T67RcS(v;1IacnG zxP&#>{2*tx?bdf>Q9!7^XhAK~dqR7#ee5;S=pz9oc!SH>qV;c{W@>RdSzP+aK=>_i z{PLQVI?UWVgYe##8TZ*pBucmD*IT7+ASg}O$BK?X7rJxkb8!d_YtZy&N3KfRHeB2> z$F*CNwJZbI*;8oUAJiec-?H$?y^i^~3vg^Jvr2rx!&*hgVIq)Y+$L>gJ*7RufN-{`1EH z`gnQSpe*6t;5>`P=pU9I)%Y)?t7&6}QYAn3l}L-lM}7$lyH@4#Qj8wr0w9lg4ge-> z`jEx+>L+n5sRVIYm>Bujn=To8N2V6@hlZ2De4mb6nK(c}SD`1@yuCRW_% z+{-#O2DCXpNX)E`S%3L!GffA#;$2|+ z))n!N61?BR(o8a!EZ*JZMneymTiWJoXl0-O`Ln#79G3TPT&78Xs!)%ZrEFF@&Pr3# ztP}Ux>4g=ML(=bsBpB@Xp{NKS25s_lCWGMmZk6NgH`C(lU(Zk0kuG%m-n`cubG>Ed04tFwnvffhw{<8px<4*h*?RZWT&;7GS zEJb(SZ8lQ4?c)s5ThrQ2R$QdD=9G83*VSR605g_qJ)TTvlIE2rqfLcN3S4P4uHpyCX-5 z_o(*c`O0ylxZLWhD(d%D-3Ap3w?fXB-MmWsr%Js4y=?2~Fa>}s=xqPKi2>VGojcET zXld`I(xS61>j^e#K2*GAdTEe4Kj--eq&wW6u12_f1MV9|kjzh(Erv42{R3zu@2 zWnmTw!#LlMIXT%?RXPPRZSce+^ToS-D0ye!GnPGjQ=m~6wM2-MzdM-?NZAdjPH@RN zo3tMr2Ht=5ckW=^xLR9+V`1ir?^ToYm8z^>l*s7TXR0^TOe!NKkiQH&kO@{?WaQ#` zjGz(y%im05+fA1?{;?<}A|c$(5-_lIe%<)u-k+L90!tvey*7A>P&aShL{UD*{`O9^ zleszMeC>UXW;*M>kJDG?LOntM#Ho*ETFT^IPjb@q6lLirY;Z5Q_-1O?dh(>_#MlkHDQs5fUwcyd(^hOP9UW#^To4q($)m^7Zd;-KFMA<7?2!3+ z;sMEw2BQF4_aNY%OQ``FQDOoO{_WBa8&9}?$MZZ@nBbj zA{15D_skx9nWEP6>FvRYUQPKIWjU8%l%>LYvbEBywWBZoOpmb%#)V2(pn!+#C`;t2 zFB|<3{XIe49MG(mIL?a8csFFq<^+*utBD_9o;?|>-d_EbNsX7pzSI+OSiq;PrS%4& zO9YPzvO*=Zh}^hw2|7Q4@6kMF1%GIC>~C{&3LZV3))q5w{6sxH&HgT9r`YYRKc^lS zZ%1=f&1L~H5%S-Gg#$+x3 zUILH;?QXHMu#|>SZ#A59JJhb`+F&d)6CW-4>@}rJ?zmu@?qaZRt2BC|#AjyDY;UEE zzWD?x5WzKT1%=>tc>_%fr)~*qXJ^L)34Q?J5n&_|vIhfIs8b|uVZrkD?b`{dM!0L> zC>Lmy62Fc|EO9>m**IDznBZY`=|hiXu5WHKOFM!oa+(R^@2Wo*pu+lAG{>-a^nVqb zYA0Ef6PdJ>skWp_{|PN~;m7@Y4LxF7;kNmtqFSxyCXwzZ1st6@%^ZUiJqXdEaB_0m z2GI$}djCb$Ge<#5$wUciEPiTVaXNdxO8_*m{9avc2Dsk-5|5}Y`$bxGnrhQKLawg3 zQ7i>!T~^#Wi5~>7FF1mJ(|n~MV5zFAD(kI5lXh7r6awi6jwLN^xs!~&*Wc=j&8@6H zfV|)5wAv>e9>d0uFC!BVnsb!2i=X`r`PZyJ7YARw9;=Bt7|8vR9UJ&2?g2+GPt>%y zxhrJ4lH|h7c`4&FD$6)Jj~w%dJ#8yFuUy?y?4-G8U39aAo`xnI_Ahq5h0cK_BT=c6 zoc+>zSM*~ri$Wn)59qMwp{V{-LT%iju#I{%IXALPq6g3t|E?vX{#{i4v!(IkwDAT9 z2QIWa58M1gS8ox2ykv5Lb4&6bBTj#OFst4lzk%gd$% z8TUOP&`rb02)V?O6?wGwxG@YAFm%vrK~-@C9+p68-XTqv8PJc>(ZxGkIUheZtsg8v z-M9VnD^fgqdy6kDF7jD@qearIHuQDKpK_Rx^>=&ipfad*WB<+eytg<^e5Czl2qi## zPhQb=H&35f_R!$)fD#oDx z`bu3#^S;4j{?j7&$jp)M15b_V@1`QY-9Ad_OObLzsccaXwe!SEy)r;Rldj78EYM@- z?1*JSW{VquiVG-(tYX~b36o2L3XZ6XIJw!`O|z!IC6ie288_y$hnUg;r0?*2_9p$d zFPS9Fv>yA-J{BHbEH_6Llc~X2!inj_aYum9a6B^B#5~cJUB8OHo0JJ^R%kn!?%vg# zGRhD9L4c|<{kU=er+oT&>IUX(Z<7%lF8`TG=e*4djkUNUC2<4t=C(xCK_Ig8hIaE0N1u$ zJ~29q1-}^tU;jl*1F-?*U&PzD*WEPKq4gDQ?;p`BBGkdHGE_J1Y*A=pd17Kg0k33d zdiGq{=;dn8m6VT~%x$|LjuYQuC9Tlt>1dg}yG?!JO{JR&fHH6vmry|^kz%~pE@LLz z@4x&Cqe?X!AJ<)rG^Ee($q^2neY=@4q49wA(wk5G1Spd~KfX-Vxqr@9-Z?ZU3$~tS zT&~7NZ}hzuQ2Ja9+^4jerptZx&A)>uYtKbEmvl8Xuh-qnKrdL~Bv46}KqGMJ7 zFcEas3aYA6_w3ka8HW033TH{_wY0bu=tGI0%JTB8tJT&u|VFzpsvyC35 zDr-@5v`bxH7u5OTP)&*^A#77nTBt9nh_Ou#k_#sX^nGUdiHiRv--;oAev(`D9nbz6 zCIm)?a3>DA(t*>49YJguAPD&gIBp(&*Ys?v6X(I|h666dEih5*%0bR;5OQ?nfoM*2 zE1!`e$-&^jn};&F0~!cjB&7-yIYu{1J1KdSFozuqdl~cERp_wJgz`xvT z-~qZ>$4oI-@&WFfc1Jxn&LRKTrCzZc`y{;L1aPw9B_2R^zPyWUZYVOSIoD0^3P!U7 zToxPa2SGp79#<)6h|#`jRE_O_yQfrK-(p3U6f(k==~ulvz>tBnKV7`QAX!~ggFsja%>H~% z^1FS-`iVvG;SeTI-KvEJ$BPA7vby_^+HVvd7>{9_(2`nMS}p*ht?UPjNDdPIsA*_o zQ&YnL9{^#Kn@BAn@SdKYebU7X)e}CCgcL)Zl*c<46Ea2Jqc+#3@1L6Gi0MUAm2#5` zYgckl6j4O4nmbKzWnOu$;w~LxF=^iPoqedF$3Di|CT@&yQ~4*zD8H_QDuU|fpW1%2QMf4C_TSL|QVSx~dvD|LAMq}Yd2 z=YfF%ErO)|czrl?)ai59X;Zibuf*l8G9OFr!I=IH0;k>mt{c&F@)9S+w+*CJjbIoaaN^&X8R#Xg0Za2$?96 zkBwhz>m`!?4k51yssFHJii0<)@e_lQ&4$2b2B&&DFgshrO+&51opNH{9n@Cb4Mz(h z0qseKZd4#+7#bdKArSkNlQR#m14A}6pAzCe{4O{F7o$`+Dx8Y&DFlVa8UMXiB8AiCb29 zFB&~xej9Lix^d&KjK#B5%MebPfqdl*2)KFtxOMCB1}(u2(rei@HOa4&-YkIp60oJ_ z25oh9U%<(J{rZK(HY+!%Z~Ow52@W?M$A)54eT&tb19|uN33x)RaZG`Me=I7ug1VO9*uWPut#3UrGKbI`TFVfc7_3s?W=t#i_c?8T`dECs6LMk%S z(*D($oe4kyn` zVGUR{;4dV9ILKgd=Hui0y|yN;IZP`;TOO101%-tb&d1Lm6dTJ|Gs6vz2U6~F+SMbW zGzu-8gmha6hYsZV0IcI+^wAxb!r;V2h(&K=HX!9bCnK3~GzNibSWsBF1wQcE@m|fJ z+I2YnE+zE_e*Ab7u6XcKfHYBuM`c9)(W3x(qHY&&Ce#Y<_Vuz&Cd1DMVINXSIMnYv zKo0Q^A)fGj30R-1ssw^6W~-O2TjzPfYJ%b0{Sba8RD#RnDy~_=ocdLGa7A=L{16W43VvqhRwq=!Q0mIu>nDDq*5*k9?}7Uli3R&Cw&>o2T-qJ}%*Vy%wyY8o9`r~@ z3+#*0=R2lR05kv!#aNt|_gm^D1ZK82jYEma{xEWmL#~*SUFjO(8V2R=-UUVPrw5*5 z^zf~KZ4~fj=KlRXudIw8MxD_}-oNS(BoCq=f*Pgh?i`M(8z%GS{JsLFJJOH{uBd1*R=aB3(x@pxi&!2@YkGmN#a*(B&v2?zW(QI z)2@DS1)tf}C)A!a^ASxES_tr5yJm6cx8N}(;_y3xbsl@Daw%=GF; zNgQC=jjFE?ymEOeCU#y9#L}>Yi3kXpiLCj)w<~^Gm^SIyf}rRx&MW+nx!7BmoU-fd zY3tlJO~ZbJ+5zxdb=bDi66chlOn}#Udbnj3ye_2DDo0`X25#UV9*dE{uF1o9f^7v0 z9TSD873OTbfur#>De~?GmKp3ROc;Ir`gd*A!TLCIp#W;s0*n5|ToXooLIRb6BC3Q> zPRAxS`b~<*QZJlewY5*~IU;*uW~QH)O2QF6CD}osEfITGYU@hA7pEb8xmF9uyWzp5 z<$m+hK2*zq3h{>MJJpY$K9!f`@bfZ!vY86lCoXf@izLP(GtO7PeRHOGL5lC9zN923 zW&NS^hqCUss#8La?M(eqj`dxF&~OzL6kLhPOi%B7(~LkN(3aU;4x>uV<`Io`O)u77 z30-deuhIh$9`Z?Ao0@#3vSK9PACndZ#)d3&@EBO&Rw;T6W8NU~s1JUD*ZD62arMVbd9n3j) z2s~o!@1Pxx?LbvFU+WA1s97w_sFc;V%SY2oK1s!Ob^U~ax_Y&o=-L4zX==@2*h#=jG&=IVpV}A$5K@TB zfx;3#1(dT0mjSKfwue|=aj|9cWz=*mg16zk>$YbFI(eeh>^2Wi=a$dKtDCoOm9-xH zPZARn9o?D8rB6f+DK23YEVdVR>v4cb}y@x|G$um7DW1r%i1R89J0$Xy5c45%Aq=OD_# zG~lT`OZc&OnI@68S=f14S#n2e-<6x}F+;wd8q2%?K5Ayj29U%;GQe$8|MB$%>H<{S zi!RUH?O=g^FT978n9IbPTAuACn$F9UxGn%kh&SD<4jD6Ze_38CZmj!jdnz&ZcInI3Q5e%&XIh+p)w)wt&S9-eSk zj+55wF}d5;T7S@b<fUXYo6}tlG1AYXt=Y z|CVl)g@|W1d2p@(3`*|v<5^!yrG}1Uxr{tquK-P#;5& z+WBwNZRrgh@jep`4PsjXy&Vguo&tt8J{ebCK$AgzWhZw$-@S$xFvC~$(o!gQ!z&zT zFLMQB8{QY3*bgXsj%HuT$;lBuOYJZa1+)mHsddWo-vt%)Nn*d|CG1|@o>_9D;$Drl zxw21p5ok}ZamvEL>wQ{WQbGjA%8e&_%)?o~9iKkU7Cak+$~Ebou>I5|Ta@o=6 zSGxMeYA}(Jr|}5ujW3nnxuT-tb1=zUs=T}ZN*M5yl$eAsxG`eP40=WcZ|lNu%N&Vdwu6__+u{h$@}JZ=iw)i@4sbH z0zZr6tG;|RnmxR@Z=roW*2^6HcN*H-fs%|(1SRC8q$V&r2k2DfVZ!zQM^VeC;l57Y zeH{m-g7XFU@U}11S0ap`AqCYu>_lQS`3l}J9orX4Q$4fkIAjIqL|ie*&t_2=i}s>{ zt9I_WNc{P~vmfOn3|=&_L4!al1i?5aa94mOJEMgD0>0`CnAc$7 zKI1y^^;NZ0MvPp_TBrUG8`>agCQCh@+qat#(=<%1b)ygIxy{YpQJ`H2dtO6BquGEq zkMJRqFwN^7*Io~|6tvRFNdaV~vqbK_K?2{~A8a;4CL+YBVJCoH_C^G*<%&_?Nhkve z|Koe5jmIlGqAX?aWQSh%S8KRPl{yK;_0x!2fgy;*0SD)O8+N7-Mu;4H> zR#3qr$vSVhJLA&wkdb+tye@|Cv_l?RRHre6O7A}?{y55ATUuJyDRYAcD%(}J5l?dL?@)6 z>h0$M1`Wb){s3x6mgUA?k_&vQt>ap|A2q~)b|Zt7m^(5G@Gbv6d~sy#xkUEYYrZ8A zLbJ5mk{@l3h1$pLq@YJ&oDno(h;7%wfg5zO$SQ*h4SbDZm7yy*hL;+FEHK0+Z0vvJ7@`ASe@nlW;~xJa4#xVSgf9SbhVOk=*%JHrnTs7kci

    ^w_!@im zRtDrb8EcC_fF~4KxS0r!C-?G-*e@i?4Dute>qpZDlo|?drmwH9;niI+Cz>z1zrY=! ztCo_fe2IyM# zzSIBo=lVu-E*6l?{mrIvc7TBP5hYgC&*7Vh)E8+y=VK>aSe(UAWwV%sD{&0U06_lpw?-~}3By@smAgi{q1utT{9V`r}-ksHXd z09P2IScSPGgM#=Vj6^DNI0It<@qkMkg!s@#8ZHjTygW_WGj!0W9_B_uj#u zL9Gs;L4wzW{-Kg4JP%P5u~im9mcM%yAo8A!j4UXRy<)p(`OWNBr_i`T01{(XAhstf zImYgiW=H&s(5&zcduAq%ANxG3zrzWEkFRo{T1y5F9bm(9kb3|y3{>byg@`uza=rS8 z6Rz9V&wftl7cX8YC@Anmqwl4x#Wj}o78qXmbQ)X8u$L%LSt{Rw0KmY_&}0&)JlP)z6T!Cw7;*6JQ87Qe@t}JIUMGE(_F$jRK`B(ZWz<=ezsYWT#HV?eC3nQFT35ani;MKyQ^0j5$}Dgl z>NbS|MM31c@HRrT37`%`6qt~9f~3@d@+~m~=xLv#Er%OhL-tH3(GYIZ zB#GZFN{>giD}7V`=^V&|rV=Ro@Hfn3azeM-HmzP5sMmUg#Q!XRc1a@WAzLin&&647 zu89Iqse$}rFsI7`FsU!Is(1+Ww-=0p;AHq>6JoF1=zSj`?^|>drth>G`^WSrX~~Z1 z>}$!6;v)k9x5%xDu?<`^EagNYs$dWrMMEzsuzy<;Thnd$182E714EB2Xt%O+-o|?8Uay7A?%i`xpW=K3B zvF{H&+9zxk>`a!fkFwd{S(jlB;L+YEp29Y zBLgyJexG=V&Hg(*l>goi=4K$<{3Lw?rSO7VK_Dp&GQO$l>DbK7=+?N|*&cjd3t$n|a`m;x|z05pP$X=DT82ICF2p$voBg8w* zGCK)FfJy?QWV*b*V^9{mz&NZnu>2u`O>UmUT2i5$GtZ)48=3rMZyfb{0;U7~(;0_5 z;nK`BR&XRE(*V*{KWV+tt*|DBfa_$QqL*`R69(Hy^s+M z1_)|xeM{@0b6PC`HUarZ#vN-c0Z?@Kd^IPD8TNV$i~n-iJ1qZYag)pbWnS#f?-eNm zttx`&&`sj)cmut?tt4thPNTMcwk8H zXTYphQgU(xpND%g{+c0(L4jlI1IZld_`15fB-PXiFReG#yy}3Nb6kXF*a1=zQBnMb zZh~`K23HikcmL(yYs+Qtb;uJFC}{xCEYhbRk3J~ePpKU0tCgF*j=?uT$V}Cwy%W;$ z1U3TPU6TomI`%{(oApYr$n_52+IJ`15RPT=fj}NOz|ElGGb>3CcZFHNvX{_pVg-Ly z?`%H-sDNKUV3J$i-Te;ym;{rM^F}yep$Zykdc`kRJL9liC8cF-Jh1&{#uGZ=%aX63 zYubhDNvxh=nwxvP_+xf-ldqGaMEuuIthDp->t??7;^IkQQ(2dh>HO53PE4g&MDyWz;jbL(Bs_z^*juhc`8ZA>+c#? z!u+=9x?Ov~YT4fqNu5gH5Q`iT+(1u)^zimsw(?RH&kDgEr5|#%(^JKU*|_xJZp0!sJmfzE^oKa@$x<+#K|VYU*71cz$;I67x`??GJ-Zf?sh zoB*kf*~VF63Ba-e@R?{gHa%XLfbXjQNAXEzVP4)9BtpmikKpzrA;<4#+!PNVu0F4e z+ui}uW5rN`grbrXpP*nH-g|b`QMk$R|7!spKS_j0Fw>Jv1N8CG6Ynx6A{z#mg(*-M zcqMM6ZL6p~(-h`Op?kXhxO@@^uiV^(q5cI(+H#6~&Ob06dqu0M5?v}bqJ?@@mX*;U zKOf|gjn`D-ijRT@kK!D{wOH4-`T*jHy?GL;A3M8+!z+G_WN0lXvWV7m>hH6C?!ieK zpxE?RS$Z4DA}X5p#j0z~0&97bn-PivfE`5uf&A}nV#I?b2`OEywsvu?K>!8%^2u_* z50G5X|AY%b?U1Dj+e^QGecv09b7m+k0F1AJfBj{L7**NolWT?Fpv zWbmQgYP=BtyEz@aylja*28J#@7ur&;A#NRZ206a_FwKRAr|jPH%8D5rTEq?_ah2ax z#<+T(#a2AAv+zpClfYmU6{Ud{33RiV#!}`#7<7F%I=$&uP88=w&(YW9!vPvA)P&00 zvYn#!Me$L{YLASJ3<(Vly;ifc3iKDkND-+xd z4cpNNjmEE|I(x8KDDjvD`sr?K-}O8oT4v!`^h~=LQ{BJ|~~0MGy8phOnLNV0vj=TaGG+nP;Dgfl>0o zE+cU?NT(4qe6?BWv0hY-7j`?=P)cz?t0~Z@vuCYEqPlJ_{AOYyduGV;KVX}pV6*kd z{GAIRTmYYmxu;e`rr1s}84T8r{7*CW?~gmuRREEGla=)YYo3~^`A019HFuoLP$#Lj#m!(zOSupkkRSDT$T3iHlgcPi%YQe+-1M?2j_W)=+G}=| z=j)2om$}1e`De+>H0_7K@4VJ`i*bZ;Tx{`f%T-;3btV~WlEGLYq-0y!E8|R$W+rja$fB zV!t0;lqK&>;9TulgYjJy62M;pjJO?ZGTMLoyA!vr6 zP&g_Ge^GgS9=oHQYo5=o9qUIRz*r9#5**5M7M0{9p7hFNP8JE`lf9W6-s4dR{mOg| zAXi2b(57rZQxTjO90^gCs2;Z~@VeB*LNPZ{A$7 z&7;HpI6=Pinf(I6^??@cFKaxS9b%_9rOPwE8jpkN7s4l(L=I@-w~xP;mZ1I)qGQ)i z_*{@QnM|^jG*c$15-_`Eb&$c$qI+OSe>RL|*wp4Q0Nltc5GwU?KPV%?=qq3dMY~aM zZl_()5d=dl+k_#uWk-CTS69CRi{MdIrL#V(nobt{;cMf&@JfskDZ7I3X_Q%~0btAw z2M--!jHCxlsu|}8#usF-{%$nGwD|ewBJazl^thacu019joGa?rirUDs5o`+oe8W%} zvNir2^a1WG-tQ?mwa|H@n%)acFbPN%6xc#P1MdUc=k1O10cxOMAnFh%YETl2A2Gg- zi^D)k9Cxb$yh#1Sb=>giZ*^m&@%e6&Chm<&GRoOpnD7nQK`oQ2Ghn%OCr{8xJqx#- z@k^fF(Ezy@9G%E-eiC%40`rtvkIR3E^X;R^zuTU{4wpK}_8}(6M)!f?cnS?3YUJ)S zEbb!Ckov}ZyclC6!^7%;5dqaijh<@Lub%EVc-Vj9>r>ovMTcC0tP%1dViOaCOn60D zu!f@AA6v+=P}IQH-Qn2NOX3sCbX+%WvuNJLI(zu5rLEVJgI8jbPe_lKXIUQ#94IE> z{Ub3z>FKl>W3OJmoX}$u(6h%{{-8Z!VUod&hHm+GZ_dj$G?;0XY3)pZ=UI0@!`umY zqaeg58y+3z(GfE-Lv^A#3?jQQkT6c}g1xQ*4yT(&uQr7?CQ4;&m{tNg zV#)Fn6Nn?5G_TU9NG{F_DIK0J1^0q*CI-A>0B|g0KZgQzVXip&Wu4Jc}mIL5%EfChIFl#VzkC><9d z-7;WgwGB~uxvq~rg>GUPE9n;l%G}Ztxm_S|Pfi;8c>W)6M5t`v;`t(sHzF;qDeRIg zPsx_kNwOwuvu+k|6e*PK)|!?yKQv)Ejt*Z+#c)I+6dqJ$&}Jm?jkVVo%<9;Gr2KI? zCAtWDhC_!(Rc)rF?ugm7|b_&yMrN&)p@3~kHGd?f4_A%EcS;9x01Na-tsqFQ8 z;X2Za5e1t=w+qE~7>QAZ6p^lEH6PtUo;|4=YREF7C{~sdy7g3k-Mcx+haZNLld&kkwuE)Uqk|#Tv1VB0u4(I zXtrLolRYkxQT5V$@AHW&8Ue4N#t=v%B}?H7gL+Q4-hhOm%p^?{)97??h zG$5K@OB}|2@G4-?pf6-vK;@2;Wb~3v*x^SA5^9TqLhM|WbaaSl2Ws0tAq_eAb|mRg zNT-h2XhHt4kqXu_zXTzLje*@=r`9D7H?D}Xc7hmvjSpBXnZbcWe-`fR5j{3Cf+&0{ zVm7(UvpTL>?jDF{6!+7JO-LnoqT}Cb?ncj&jO665;qE)SSYw;)m)uSQBnH`RKWO_X zyRynEvwnF5ga9hGR=i`sz z7<>sEkJ@?OyQQQ6DlTSIW@7L_K8m(^_TS7bLgrFG#iBGefzt@&#BD7vcDQe{`&r6a zN@M$KZBJCb(fzlCnB;)80YC=+ibd}+hhYcBJGe~+d=<;0l{rgYN*D_JBm|aO#y^2BX8# z)ObS>973ihCMcNrjPlhk)WM)6{6~(5jsJK?U+xv6-Gj4aA~ILU#Hd2D=g4YYkv-Ao zPGW7c1C|>a?Hp$xa3#a0I%utjqrI#)uZiu#C*dIK=R?>;z^fwX`&$y)J~*898inqRmzU*9unGigiLX8O|f^dT2zSw_O%SD_yb8_=i^&Lf1ag|%L zHYFNAo*NN`9+ZAy+GQey!19nZ#|Em|i}S-zXd)=#RVXI!x3RrlyH$nQ1RzCM7VZWZ zZG-OP`No#|8Q{?%+c@pn%2Xen7QF-ITNUlS4d&s*nGK*9hYDh$|ITb1lFt916b~9` zWII`Yt+b`fRAn}Po?-5r&Z-gh-~*Am5o9_Per})!rGfm57kocGSLn_*tRz~2tp#%q zq9G_31HDoc+@EuYr+PixVLv$r~8@iansW{urB*2;2y)V#>qG~Kz> zZnPd1;gBx2z2I(p-|`M%Lc=IzLC`muzAayzds$@j`BqX#c8Heu5JbiDCU zmucM|at1-MEi7nHFg)^TXl5oLKK?GsS50Cj`ngEk?ht;Kj^wx^G3f{^?sCy^KeuWa zc^`=|7Y~m-_{HuLfd@JGiOB zoiRqn#^G?_2!HEZd2%K``v+Q_PX#fB9_B(@8$nj_Y})Y;Voea@8Oroas7LgEFR*r@ z-6!@V*RqcoasAgELhVd?=RlLB!&^UxGQ4rDpf;#`#$_k*AAdSHGZk*)}%JW)d zU6U_J6UqIpzh9h8e=QKUn}(sGeQGf#7_*Wyjk{pz9Hq}uWu$S^Z#woH5HmCXd?F@# z*wZNd_$qBoI1wr$B7)LGa#f3)O~q6{bPE_m=-Kk}@=R7P0r_l}T~acrE>BOX;q`pi z;+FTGeNGiZGx>&rM;4eJ5D-rA9=6|AUK;$d;(7BgvODw_2h#5b)Z#WYWWN4O1=ta& zj)2k$hWHdFAt5q^H$r535X^CSI_dR6IJB)=L&(y)FVrcbC90?6=8itCe)eDuS?c>X zd$?gB55exSVw=oD@g}vME+F3>It$NYG*I6_c#NM&jI>5;Z2LWMg0pIA4ADjthmi9#BvL~t_ z!Smf|VuDCbh_yiD0~d(|xabrcgu+J$Pa`86jI}n0vk!iHYjR3eNw8Od&0sh+*5~|i z>f~qh8cm$zQBIg#>$YH!{7YPqj$519c;$58VJhDHv|?ftZyb8iyuuY1!+= zeTr)q4R9V(9N+o+2dr`WI_fLqb>_(pl<3J-vkeC=m znu?0uL7w(Uz$aawG}R~|;6LJk10ZjrmNcYG(Ra@uC%J}J{-(Bgsn?6}5yh4|raERS4~95v+}5nMxikM9 zo+4+z{=u;8%&z6b9mBBVmVhN|Nt^@18SJZFJPBp%s*(qY&bZg zav#tSaF@YqF4_~<*B`_)&fSP!h*__V0^W)IY5TVsSgOxkECNxSj=2;9gF4orph4-@ zzCYqg{`b$j5#y$QtZp!9cjA+hK9rWm+T-NK<3O;JiD~$JaowL5v*`Pl>vaG#Wl|tI zPYB|IIEEC>yA_w(2cql#)Z!wAXAH*(!9j%rK^clvOvKI%+}*1!8ZyuKKLJi$u@q#U1ebMjZ?0I;(v@tIN z6uvI5uFW9y1gOI>Pi6xC7CC=dS%bgqZ*$+?r^_6`0VVJU`Dp5nbdg)2Rcm1mLGW@& z>C3B|b3?STu!li(44tQGdl*^YQqz*tQ%HLOM{XqL4Ka`S$h+tFeMMh2zYDEl)P()f?s4Lwzrw*(tk3c|t2U%FqCX8JF zsgATQQhItRTse;|4i+y6lNsigi)?-GrL##496L^yj&*hQ-HVNnfAbl7Ku|D(9snu7 zCfz?oqMZQyR9zj@ibdMIvp?>QW)~OV+#3Rl^s7^snZ8(eeD03PwW$F?zz$%aWmb)l z_gxAaO|gUTkAmnPh?4U(f;7W9OmH+HX@n~HM^9=>X6AsGqUVLTcON!ptV1$C>Zt{l z_NWD9QY&l3>A6Ta;@%jLVdVez<(=@vyG6IoH_GDOoE`hs6&3Mx1##^RnaaQDN+lrX zHU-O&{OT=4d#jdN^+V&=^sVxV;c^J58v6+dvQlT#v%dTz6?0+B-`}WG!eK@f8xV%N zwa*MopM4l@Ry_ATGVe^E>8)uyvwW&jgx)bv#_U)M_0WAx_F!yR{SzHCeiF_leq0hR z{*PpjjEn?!Jj5WA0PP3-3FsAsb+Ij|v4;RNt0T1rd5Z4WmqJF6dy_Bx0(y8>KdC zXc)kcxU|SkJRos#7U)rSKX+?)Prl;s(1j<*ZJ*m|)eSorM`vfJtE;Ph{y360ujjbp z7Nl-6pAW|OQEP!i0gQ_Or+5+%Fg(Is-GUsn$}KWUj!QF0YZ%6QpYS$h}wly^(eJO@~(6+t3Jv!4`dB-V&M`kRVzeH{} zH#`l@gKZg0poE2VFKBcTd>oo4B$+v^h;u{2E0rV0xJuvBo<#9-XD zDn}s>aZp18M+}-jJYT8ABxAwjO|KIP;`^+3E^C-*+&^*&bCX`$3lqdZLZU4FMg{TV zsIZ%7;(f66==(JkF>b|`d*FuvZm7y`(jUYL2&07RC|dOMeckw?JVY~&WoYRmoG`F= zGX9od9wPF4fr6>V-o8k7f$z{#bW-I_<72)Gj~!DeU$Z`ZXq|f?7tZMCl=4=t7@xoT z)=BX*;-wGn+r;`F>okoanqTFJy6Z&2=m55kGHV$+Iyz_yWSpG%!H0pQt%2bKd=A#B z*q{kP95c(y?;&gfq)CR7t#Q{X_H;JEh5_q|^GQWW_ch3lvsc$!lJ%CuRn%H#CK7fY zAd(92UE+78dhb#yVSWwA1aD{c@H7@dAkN{*BL64YT){LCt_IV+C{hAcAAS^bv--P- zY}XCdW#?G@J$H2U>CqsX0Ut{2X5ath<9%s&2tgh=QDH*@RX4uL*MfqugCyl|+B!Nd zi#tdl91>nMH<#7S&XIP9eJN~Bb#p0!8`NGvBm^kMgDD@nTWL8%301XHn!Ss@zif)f!b?nrUmBp7~{4ZZxvD9%a(#={z(E&myZ(Z_^$;@6A!>D0QVZG>Jg?Nhu*_?GfZV! z=UXE=bHgkWhIc&RLtwI?DU>-tF=SOUn9nW7q30iHZ-@78D*V1D|jIUg#}b=3tta^n%VgBIn<#e zn@wW6Il{tZDcE+%CkH-6dPTUxeIl6+c`nfX;e!)-(RkcdII-Tyu?;`Vi*Dl^uBNV5 zF{B2HHEP@TYjsAG-2W#NdnGOXb?F9GV}Y~UgSkvKv2YNW^;3pt&Zgyob1;(O*lGo|q5dJF2AMMRbj57UlkA1$A8To4feFm_m`T8-KKpw!#PA@_6Cfx`p&j7K z8iS&EabM2w#S=!vXpFd`pp!wo)thHJnDTP(wFfo|98M%0@wMCEF0aet=4c;jvxj>T zL)ZTNX!|Lrp}AvF0SZNU`Jt?oRxN2$gljtM8c*p!65!za4qvd4?9f-1mLk~|Fa+*8 zn47R0E$Sq7wH*YR2rUkNktt}4nrHbxmPX`HXN`Z0g@g;<<4dSd^>BApO_y^k)tU0> zvkP(OP+&@T=Spn<#bNPys2oDA!4XO=bemdp9)~g~^p5G(JCWD;v@u7Y4a(XV2v(U0 zu~kX34dU8yv~O1RWA`3@n5DI{vijC{S3l2dR@|rdzB9LTrd5Xf@;jhNW$*9pkEoeJ zNkK_NBLgfc!ZpH>24Z}C{1!n<{0Tul)`FLSC=<|%pj2q?#Kq-^>S&2-x9dD0n0%fR z{?Mo%ow2M?ZBOrKx|i~XMEd_qI`ep_yEcrEEZNGI?6PE+Jv<0W$TEoO4NpUwY{^#H z*P5Q}OT>dBgJemT)=3FtS9W8G2`Ou`CZhK~@9SS5KK$l)&biNZf3NEnjWgzCXS(ze zBldZQYx$-3UDuamlN+IMDoR|}7nclC3uwQ>mm^L4o9sQJCTtKXjP&GR-|`FF{&G6F zu65@AtZy0i@yN3(PtJR_6{42J(GM+W2nW=rYwR=x_=SZj>vR2un>Ov+s#g6fGjPEn zyAHHpI2OyA8GUXn(XcgJR-{OM2SPWip|EC2xVDdlf6`HYngIX?k$o}IeR~`u7^^?s z>IFQpI*K~?_1AChCd-FRo-j3}Su0+G0gb3h1*L&y*tuWMH?t!VCXYTx2pD3Eewtca zbQI_-SbEz!4%_&^Dmqu{UXHj_83CW+CQvPLG>?*Q+QtIdf-TUMNQPV(f=E=*Jx-u{ z3RadM$dQPMGqbQb1)0KKYou*FsPEO)s*np)P*P(0pRb-c5&oZIL!+atcbd4;pI*nu zMwXvHV&DEkpqV;PF*^KFQv2B-f6Z};eNr9tcx^7WE^IJ?GT{~SqvK@1#@i(*SO5_d z*VT2RO~Yq_9=%=`eCI+)R!H$==@6+s!&b2UjeTsDxoGwSObw0uLY9@=nH=aILW|=_ ze^y6Zc%l(jN7iwdwBIOCUfSYNh>U~!LH?(zQ*TqwjTkeY;*bX64gt(4C1Gxd$4m_W zw}l#(XA15-q-W0tGV-Gg^?uOBdR-xXGZwkK7^X<)DsE>V9ANpYDZi(f7W;+z6`diSkRUVnww<1?T6(0 ztBlCFJV`2qIisfv+X&Eo3x^L2K;stra0Q-%US3{);2X2d*B1c`Rn>?$3U&~U+`0&~ zH7hWVa1(BTx(bdB*D08zeH-TP+48$jW%kZpmpH_F`U!4729h6OsQP-%;CYBqeu@#rKm= z5K0H+IxWss9PFwK;=i4?Vdl-x8P>>O>H^kJxCAM`+uOc!QOZm#CN6qx=^xs1{nrld zhMnd56a??*Xnq&%WUkvZQP8go!{NMF+22av|9v=3GmYhMO-xmU5f}~;Ck;Bs;^=cW zhzVijtk+RW=&t7tqD5!{HN?K$t8oC-GK9j4My%WZhDNGtm>=_S!y;fO6wu3ELrzF9 zlg;AjU1faE9a1hlSyfwWXFzm=G1DmNhJ7u0|3tJ;?MP~Nb{w#};@olQ#RNDL?)Kmc zMbI!HcQNqtBYg&zgX++2G#&>ESrp*x_q9s^Wh2?r%(2*(`+r^Yn`~r+Gh_T3hxj~3 z<;svEWI48E-0Gc+(c?BNFK`<$+ZL&5PnWm-IuixW6~G%Ooaw6H4P5r0k$Xo9JMI5^ zI$0MC4`S?m&xLTSa*}Iq9dRFh15SV*2(ufSi!HLy-5j3oL{J%q{`VhV;|Tosa6P?!vOO>9lcrL$&#CF%z;#Z%DgIZMu(*uo|& zeS7^)5~v+$avM84I}fHDkW;Iz_k~gIz|FE4u zPTgwgT0lS#l?nj>Pkfn=3OV2^INWglh0p8VVwJ|-+hY4yXF9>dUhwotR&!cXipNbe zYcs--*y@4MC2}vt__zU%k-NM@_d?Xyy`WufiytiA5;DOP*ZZwtPNg1Zc4BqbH+G7Q z(zDpv-_Knq!JLFg`BHy)0(>$K=N+eZ5ii(_uH3y5c&U8$O$Dd_pyrL1{_He5QJb~l z_e~p*yrldhVp3NCT|2WT^VVxn9&EE{Qw9m|(HQfJsLT3&OUBD5gQAI+^sYw7gdPSj zyPv?oOhB|rL9RKJ`F+;Ua?KEtvjuyT6^15qq;drk(;Yyf#BR772#K2+EWqB4AZDt&C%g7qMY(=;HU zM*sV2o6c^e<3=v?ZB>4IUB-LSt;&d5R8e_ot?ls`%XvBesriGmQuT|z4$iWeCIc4Q~QjO9l_O31)g4iQAg(AHehDs(-j-a^!M4e{ooj34% znF?%}A$RtiewT@Hql2ppgOO}oZwGjY##C3{S@~`j(A79?90PyS6p+f0152Sr{Ye^s6J+|<)Oggh2D^i+pUHGWTnET#3nlk-gb!wb z_+D9w)w#&`d^}iDT!MQc;Pv{(w8>KRfpo5mIGm%&qJ5j5auP7-gnFjG@VA;JhV?yi=J^sBxYY`sEosNNuvd9EM1D5GuFIQ3J;6UF!V=O1<%Yl2W1n@!-OcR_h44CY_?mE1Ohm@uGK@bzn%_7+kr1{ zJ!x6b2%D7v*DmlxQQtnQ_-)UzO*fFK`ZzU^w>fiyGCD9o1l{BNPPD%fBJE+@@QHM6 zfOTKoS#Cd;54#C8NmRA9nc+eQt)JngK)t=KX>c%`KvxR#&w4d@dpoZ39#53cH&8Oak29miIi${ zWs7OSTh7+?^=81{3WiR~C^7ZxitAbMb_(L(JlP!+^my%PE@r}mC zFYzec0*RBRO{Z zIekg7JR(Yhgb@8ix;+#9fCnONbM1@3T~6oqWXA}UXW)9mRKQ)q77msl|+9+W-+04yYfGho7jWK*3%7I1Xz!=h+JiB{0fErc=a@3nu4wSIJmaB;Z2>Nv7L0^wnOy|c2+ z&>j7dERVU|dsc%c5^|hZMZOgGR!k{KF4Xx2h-|f9od$ynn#>48hvCFokjWCX8lI!c z3n^SC;EyK(2B1qOlZi?k4n2okAv72m#D z)OZT6ClL7j4?@tPavGlQo+hAnKy>jdWd6f`%Iz| za3N-`o(!Sf$chMC8T#wV*f@!8@_E@b zy@KI4$W9miH+ndZSNT(7pN!o~;$HmsZxL+K-%qM|2L< z0pos;IiXEwrOY(*c-UJ!1nDV5(=~Hjcss}YuSD4c02Gft^L!P&A_3ij*OMlMJp)Cp WPp_3+qE<2Rb>=kIxYEew=6?Zc;?mLp literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/package.xml b/control/smart_mpc_trajectory_follower/package.xml new file mode 100644 index 0000000000000..70bd15f97d609 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/package.xml @@ -0,0 +1,43 @@ + + + + smart_mpc_trajectory_follower + 1.0.0 + Nodes to follow a trajectory by generating control commands using smart mpc + + + Masayuki Aino + + Apache License 2.0 + + Masayuki Aino + + ament_cmake_auto + ament_cmake_python + autoware_cmake + + autoware_adapi_v1_msgs + autoware_auto_control_msgs + autoware_auto_planning_msgs + autoware_auto_system_msgs + autoware_auto_vehicle_msgs + motion_utils + pybind11_vendor + python3-scipy + rclcpp + rclcpp_components + tier4_autoware_utils + + ros2launch + + ament_cmake_ros + ament_index_python + ament_lint_auto + autoware_lint_common + autoware_testing + ros_testing + + + ament_cmake + + diff --git a/control/smart_mpc_trajectory_follower/setup.py b/control/smart_mpc_trajectory_follower/setup.py new file mode 100644 index 0000000000000..4dca4d72929a8 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/setup.py @@ -0,0 +1,37 @@ +# cspell: ignore numba +import glob +import json +import os +from pathlib import Path + +from setuptools import find_packages +from setuptools import setup + +os.system("pip3 install numba==0.58.1 --force-reinstall") +os.system("pip3 install pybind11") +os.system("pip3 install GPy") +os.system("pip3 install torch") +package_path = {} +package_path["path"] = str(Path(__file__).parent) +with open("smart_mpc_trajectory_follower/package_path.json", "w") as f: + json.dump(package_path, f) +build_cpp_command = "g++ -Ofast -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) " +build_cpp_command += "smart_mpc_trajectory_follower/scripts/proxima_calc.cpp " +build_cpp_command += ( + "-o smart_mpc_trajectory_follower/scripts/proxima_calc$(python3-config --extension-suffix) " +) +build_cpp_command += "-lrt -I/usr/include/eigen3" +os.system(build_cpp_command) + +so_path = ( + "scripts/" + + glob.glob("smart_mpc_trajectory_follower/scripts/proxima_calc.*.so")[0].split("/")[-1] +) +setup( + name="smart_mpc_trajectory_follower", + version="1.0.0", + packages=find_packages(), + package_data={ + "smart_mpc_trajectory_follower": ["package_path.json", so_path], + }, +) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/.gitignore b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/.gitignore new file mode 100644 index 0000000000000..2d04606a236d6 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/.gitignore @@ -0,0 +1,2 @@ +__pycache__/ +*.json diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/__init__.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/__init__.py new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py new file mode 100644 index 0000000000000..fafcb5bdecf05 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/clear_pycache.py @@ -0,0 +1,31 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +from pathlib import Path +import shutil + +import smart_mpc_trajectory_follower + +if __name__ == "__main__": + package_dir = str(Path(smart_mpc_trajectory_follower.__file__).parent) + + remove_dirs = [ + package_dir + "/__pycache__", + package_dir + "/scripts/__pycache__", + package_dir + "/training_and_data_check/__pycache__", + ] + for i in range(len(remove_dirs)): + if os.path.isdir(remove_dirs[i]): + shutil.rmtree(remove_dirs[i]) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/mpc_param.yaml b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/mpc_param.yaml new file mode 100644 index 0000000000000..710d1cc992949 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/mpc_param.yaml @@ -0,0 +1,56 @@ +mpc_parameter: + system: + mode: mppi_ilqr # option: ilqr, mppi, mppi_ilqr + mpc_setting: + ctrl_time_step: 0.03333 + mpc_freq: 3 + N: 50 + steer_ctrl_queue_size: 50 + steer_ctrl_queue_size_core: 15 + acc_ctrl_queue_size: 12 + nx_0: 6 + nu_0: 2 + timing_Q_c: [25] + cost_parameters: + Q: [0.0, 10.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + Q_c: [1e+2, 1e+8, 1e+6, 1e+3, 1.0, 1.0, 1.0, 1.0] + Q_f: [1e+2, 1e+8, 1e+2, 1e+8, 1.0, 1.0, 1.0, 1.0] + R: [10.0, 1000.0] + acc_lim_weight: 100.0 + steer_lim_weight: 100.0 + acc_rate_lim_weight: 10000.0 + steer_rate_lim_weight: 10000.0 + min_steer_rate_transform_for_start: 0.01 + power_steer_rate_transform_for_start: 5 + coef_steer_rate_transform_for_start: 3.0 + min_loose_lateral_cost: 0.00001 + power_loose_lateral_cost: 10 + threshold_loose_lateral_cost: 0.2 + min_loose_yaw_cost: 0.00001 + power_loose_yaw_cost: 1 + threshold_loose_yaw_cost: 0.1 + ilqr: + ls_step: 0.9 + max_iter_ls: 10 + max_iter_ilqr: 1 + ilqr_tol: 0.01 + mppi: + lam: 1.0 + Sigma: [1e-15, 1e-2] + max_iter_mppi: 2 + sample_num: 100 + mppi_tol: 0.5 + mppi_step: 20 + preprocessing: + reference_horizon: 50 + cap_pred_error: [0.5, 2.0] + use_sg_for_nominal_inputs: true + sg_deg_for_nominal_inputs: 0 + sg_window_size_for_nominal_inputs: 10 + to_be_deprecated: + tighten_horizon: 20 + min_tighten_steer_rate: 1.0 + power_tighten_steer_rate_by_lateral_error: 1 + threshold_tighten_steer_rate_by_lateral_error: 0.05 + power_tighten_steer_rate_by_yaw_error: 1 + threshold_tighten_steer_rate_by_yaw_error: 0.05 diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/nominal_param.yaml b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/nominal_param.yaml new file mode 100644 index 0000000000000..aa61a25e9a0ac --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/nominal_param.yaml @@ -0,0 +1,10 @@ +# default parameter is set for sample_vehicle of AWF: https://github.com/autowarefoundation/sample_vehicle_launch/tree/main/sample_vehicle_description +nominal_parameter: + vehicle_info: + wheel_base: 2.79 + acceleration: + acc_time_delay: 0.1 + acc_time_constant: 0.1 + steering: + steer_time_delay: 0.27 + steer_time_constant: 0.24 diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/trained_model_param.yaml b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/trained_model_param.yaml new file mode 100644 index 0000000000000..6d1973586a5eb --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/param/trained_model_param.yaml @@ -0,0 +1,30 @@ +trained_model_parameter: + control_application: + use_trained_model: false + update_trained_model: false + max_train_data_size: 10000 + error_decay: [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5] + use_trained_model_diff: true + use_sg_for_trained_model_diff: true + sg_deg_for_trained_model_diff: 0 + sg_window_size_for_trained_model_diff: 25 + use_sg_for_noise: true + sg_deg_for_noise: 0 + sg_window_size_for_noise: 15 + use_x_noise: false + use_y_noise: false + use_v_noise: false + use_theta_noise: false + use_acc_noise: false + use_steer_noise: false + smoothing: + acc_sigma_for_learning: 5.0 + steer_sigma_for_learning: 5.0 + acc_des_sigma_for_learning: 5.0 + steer_des_sigma_for_learning: 5.0 + x_out_sigma_for_learning: 30.0 + y_out_sigma_for_learning: 30.0 + v_out_sigma_for_learning: 30.0 + theta_out_sigma_for_learning: 10.0 + acc_out_sigma_for_learning: 5.0 + steer_out_sigma_for_learning: 5.0 diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/.gitignore b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/.gitignore new file mode 100644 index 0000000000000..9f6b19213255b --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/.gitignore @@ -0,0 +1,13 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# workspace specific settings +train_drive_*.png +test_feedforward_*/ +test_pure_pursuit_*/ +test_python_*/ +python_sim_log_*/ +sim_setting.json +auto_test_result_*.csv diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv new file mode 100644 index 0000000000000..83fa1f2612704 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/accel_map.csv @@ -0,0 +1,20 @@ +default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 13.89, 15.28, 16.67 +-4.0, -4.40, -4.36, -4.38, -4.12, -4.20, -3.94, -3.98, -3.80, -3.77, -3.76, -3.59, -3.50, -3.40 +-3.5, -4.00, -3.91, -3.85, -3.64, -3.68, -3.55, -3.42, -3.24, -3.25, -3.00, -3.04, -2.93, -2.80 +-3.0, -3.40, -3.37, -3.33, -3.00, -3.00, -2.90, -2.88, -2.65, -2.43, -2.44, -2.43, -2.39, -2.30 +-2.5, -2.80, -2.72, -2.72, -2.62, -2.41, -2.43, -2.26, -2.18, -2.11, -2.03, -1.96, -1.91, -1.85 +-2.0, -2.30, -2.24, -2.12, -2.02, -1.92, -1.81, -1.67, -1.58, -1.51, -1.49, -1.40, -1.35, -1.30 +-1.5, -1.70, -1.61, -1.47, -1.46, -1.40, -1.37, -1.29, -1.24, -1.10, -0.99, -0.83, -0.80, -0.78 +-1.0, -1.30, -1.28, -1.10, -1.09, -1.04, -1.02, -0.98, -0.89, -0.82, -0.61, -0.52, -0.54, -0.56 +-0.8, -0.96, -0.90, -0.82, -0.74, -0.70, -0.65, -0.63, -0.59, -0.55, -0.44, -0.39, -0.39, -0.35 +-0.6, -0.77, -0.71, -0.67, -0.65, -0.58, -0.52, -0.51, -0.50, -0.40, -0.33, -0.30, -0.31, -0.30 +-0.4, -0.45, -0.40, -0.45, -0.44, -0.38, -0.35, -0.31, -0.30, -0.26, -0.30, -0.29, -0.31, -0.25 +-0.2, -0.24, -0.24, -0.25, -0.22, -0.23, -0.25, -0.27, -0.29, -0.24, -0.22, -0.17, -0.18, -0.12 + 0.0, 0.00, 0.00, -0.05, -0.05, -0.05, -0.05, -0.08, -0.08, -0.08, -0.08, -0.10, -0.10, -0.10 + 0.2, 0.16, 0.12, 0.02, 0.02, 0.00, 0.00, -0.05, -0.05, -0.05, -0.05, -0.08, -0.08, -0.08 + 0.4, 0.38, 0.30, 0.22, 0.25, 0.24, 0.23, 0.20, 0.16, 0.16, 0.14, 0.10, 0.05, 0.05 + 0.6, 0.52, 0.52, 0.51, 0.49, 0.43, 0.40, 0.35, 0.33, 0.33, 0.33, 0.32, 0.34, 0.34 + 0.8, 0.82, 0.81, 0.78, 0.68, 0.63, 0.56, 0.53, 0.48, 0.43, 0.41, 0.37, 0.38, 0.40 + 1.0, 1.00, 1.08, 1.01, 0.88, 0.76, 0.69, 0.66, 0.58, 0.54, 0.49, 0.45, 0.40, 0.40 + 1.5, 1.52, 1.50, 1.38, 1.26, 1.14, 1.03, 0.91, 0.82, 0.67, 0.61, 0.51, 0.41, 0.41 + 2.0, 1.80, 1.80, 1.64, 1.43, 1.25, 1.11, 0.96, 0.81, 0.70, 0.59, 0.51, 0.42, 0.42 diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb new file mode 100644 index 0000000000000..dd4dc9ae25cb2 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/plot_auto_test_result.ipynb @@ -0,0 +1,180 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": null, + "id": "e78db57e-3218-4515-9ae5-4458ea071a1c", + "metadata": {}, + "outputs": [], + "source": [ + "# cspell: ignore kernelspec ipykernel codemirror ipython nbconvert pygments nbformat \n", + "\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "import pandas as pd" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "dacb0655-e173-483f-86ac-0f39520c66f7", + "metadata": {}, + "outputs": [], + "source": [ + "import python_simulator" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "03850f4f-99c4-4f1c-8673-8bbabddea001", + "metadata": {}, + "outputs": [], + "source": [ + "# header of auto_test_result_*.csv\n", + "header = [\n", + " \"param_name\", # 0\n", + " \"param_val\", # 1\n", + " \"max_abs_lateral_error\", # 2\n", + " \"max_abs_vel_error\", # 3\n", + " # \"max_abs_yaw_error\", # 4\n", + " # \"max_abs_acc_error\", # 5\n", + " # \"max_abs_steer_error\" # 6\n", + "]\n", + "\n", + "\n", + "plot_param_list = [\n", + " # [label, header_index, unit_for_plot, nominal_value]\n", + " [\"steer_bias\", 2, \"[deg]\", 0.0] ,\n", + " [\"steer_rate_lim\", 2, \"[rad/s]\", python_simulator.steer_rate_lim],\n", + " [\"vel_rate_lim\", 3, \"[m/ss]\", python_simulator.vel_rate_lim],\n", + " [\"steer_dead_band\", 2, \"[rad]\", python_simulator.steer_dead_band],\n", + " [\"wheel_base\",2, \"[m]\", python_simulator.L],\n", + " # [\"adaptive_gear_ratio_coef\", 2,\"[-]\", None],\n", + " [\"acc_time_delay\",3, \"[s]\", python_simulator.acc_time_delay],\n", + " [\"steer_time_delay\",2, \"[s]\", python_simulator.steer_time_delay],\n", + " [\"acc_time_constant\",3, \"[s]\", python_simulator.acc_time_constant],\n", + " [\"steer_time_constant\",2, \"[s]\", python_simulator.steer_time_constant],\n", + " [\"accel_map_scale\",3, \"[-]\", None],\n", + " [\"acc_scaling\",3, \"[-]\", 1],\n", + " [\"steer_scaling\",2, \"[-]\", 1],\n", + "]\n", + "print(plot_param_list)\n", + "print(\"len(plot_param_list)\",len(plot_param_list))\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "4e8af4e4-db9f-4ee9-b41e-690b74ae5cf7", + "metadata": { + "scrolled": true + }, + "outputs": [], + "source": [ + "fig = plt.figure(figsize=(30, 18), tight_layout=True)\n", + "\n", + "ax_list = []\n", + "for i in range(len(plot_param_list)):\n", + " ax_list.append(plt.subplot(4, 3, i+1))\n", + "\n", + "# ff_data_result_csv = \"auto_test_result_final_model_control_trained_with_data_collected_by_ff_control.csv\"\n", + "nominal_data_result_csv = \"auto_test_result_final_model_control_trained_with_data_collected_by_nominal_control.csv\"\n", + "\n", + "df_info_list = [ \n", + " {\"file_name\": \"nominal/auto_test_result_nominal_model_control.csv\", \n", + " \"label_name\": \"nominal\"},\n", + "\n", + " # {\"file_name\": \"poly(selected) (data using FF)/\"+ff_data_result_csv, \n", + " # \"label_name\" : \"poly(selected) (data using FF)\"}, \n", + " # # {\"file_name\": \"poly(full) (data using FF)/\"+ff_data_result_csv, \n", + " # # \"label_name\" : \"poly(full) (data using FF)\"}, \n", + " # {\"file_name\": \"poly(selected)+NN (data using FF)/\"+ff_data_result_csv, \n", + " # \"label_name\" : \"poly(selected)+NN (data using FF)\"}, \n", + " # # {\"file_name\": \"poly(full)+NN (data using FF)/\"ff_data_result_csv, \n", + " # # \"label_name\" : \"poly(full)+NN (data using FF)\"},\n", + " # {\"file_name\": \"NN (data using FF)/\"+ff_data_result_csv, \n", + " # \"label_name\" : \"NN (data using FF)\"},\n", + " \n", + " {\"file_name\": \"poly(selected) (nominal control data)/\"+nominal_data_result_csv, \n", + " \"label_name\" : \"poly(selected) (nominal control data)\"}, \n", + " # {\"file_name\": \"poly(full) (nominal control data)/\"+nominal_data_result_csv, \n", + " # \"label_name\" : \"poly(full) (nominal control data)\"},\n", + " {\"file_name\": \"poly(selected)+NN (nominal control data)/\"+nominal_data_result_csv, \n", + " \"label_name\" : \"poly(selected)+NN (nominal control data)\"}, \n", + " # {\"file_name\": \"poly(full)+NN (nominal control data)/\"+nominal_data_result_csv, \n", + " # \"label_name\" : \"poly(full)+NN (nominal control data)\"},\n", + " {\"file_name\": \"NN (nominal control data)/\"+nominal_data_result_csv, \n", + " \"label_name\" : \"NN (nominal control data)\"}, \n", + "]\n", + "\n", + "cmap = plt.get_cmap(\"tab10\") \n", + "for l in range(len(df_info_list)):\n", + " df = pd.read_csv(df_info_list[l][\"file_name\"], header=None,sep=\",\")\n", + " for i in range(len(plot_param_list)):\n", + " index_bool = df[0].values==plot_param_list[i][0]\n", + " if any(index_bool):\n", + " x = df[1].values[index_bool]\n", + " \n", + " if plot_param_list[i][0]==\"adaptive_gear_ratio_coef\":\n", + " x = np.array(range(len(x)))\n", + " x = np.array([float(x[j]) for j in range(len(x))])\n", + " if plot_param_list[i][0]==\"steer_bias\":\n", + " x *= 180.0/np.pi\n", + " \n", + " \n", + " y = df[plot_param_list[i][1]].values[index_bool]\n", + " ax_list[i].plot(x,y,\"o-\",label=df_info_list[l][\"label_name\"],color=cmap(l))\n", + " else:\n", + " pass\n", + " if i==0:\n", + " ax_list[i].plot([0],[0],\"o-\",label=df_info_list[l][\"label_name\"],color=cmap(l))\n", + "\n", + "\n", + "for i in range(len(plot_param_list)): \n", + " #ax_list[i].set_title(header[plot_param_list[i][1]]+\" / \"+plot_param_list[i][0], fontsize=16)\n", + " ax_list[i].set_xlabel(plot_param_list[i][0] + \" \" + plot_param_list[i][2],fontsize=20)\n", + " ax_list[i].set_ylabel(header[plot_param_list[i][1]],fontsize=20)\n", + " ax_list[i].grid()\n", + "\n", + " if plot_param_list[i][3] is not None:\n", + " ax_list[i].plot([plot_param_list[i][3],plot_param_list[i][3]],[-0.1,2],\"k--\")\n", + " \n", + " # lateral_error\n", + " if 2==plot_param_list[i][1]:\n", + " ax_list[i].set_ylim([-0.01,1.0])\n", + " # vel_error\n", + " if 3==plot_param_list[i][1]:\n", + " ax_list[i].set_ylim([-0.01,1.0])\n", + "\n", + " # if(y.max()>2.0):\n", + " # ax_list[i].set_ylim([-0.1,2.0])\n", + " if i==0:\n", + " ax_list[i].legend(fontsize=13)\n", + "plt.savefig(\"auto_test_result.png\")\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.12" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py new file mode 100644 index 0000000000000..d706c342f04ec --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/python_simulator.py @@ -0,0 +1,1593 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore numba njit simplejson fastmath interp suptitle fftfreq basefmt markerfmt + +import csv +import datetime +import os + +import matplotlib.pyplot as plt +from numba import njit +import numpy as np +import pandas as pd +import scipy.interpolate +import simplejson as json +from smart_mpc_trajectory_follower.scripts import drive_controller +from smart_mpc_trajectory_follower.scripts import drive_functions + +print("\n\n### import python_simulator.py ###") + +ctrl_time_step = drive_functions.ctrl_time_step + +sim_dt = 0.003333 # Simulation time step +ctrl_freq = 10 # int, controlled once in 10 simulations. +acc_time_delay = drive_functions.acc_time_delay +steer_time_delay = drive_functions.steer_time_delay +acc_delay_step_sim = round(acc_time_delay / sim_dt) +steer_delay_step_sim = round(steer_time_delay / sim_dt) +acc_time_constant = drive_functions.acc_time_constant +steer_time_constant = drive_functions.steer_time_constant +steer_dead_band = 0.0012 +steer_scaling = 1.0 +acc_scaling = 1.0 +measurement_steer_bias = 0.00 +L = drive_functions.L +N = drive_functions.N + +steer_rate_lim = 0.35 +vel_rate_lim = 7.0 + +mpc_freq = drive_functions.mpc_freq + + +use_accel_map = False + +vgr_coef_a1 = 15.713 +vgr_coef_b1 = 0.053 +vgr_coef_c1 = 0.042 +vgr_coef_a2 = 15.713 +vgr_coef_b2 = 0.053 +vgr_coef_c2 = 0.042 + + +perturbed_sim_flag = False +if os.path.isfile("sim_setting.json"): + with open("sim_setting.json", "r") as file: + sim_setting_dict = json.load(file) + print("load sim_setting.json") + print("sim_setting_dict", sim_setting_dict) + perturbed_sim_flag = True +else: + print("sim_setting.json not found") + +# Rewriting for para-search +nominal_setting_dict_display = {} +if perturbed_sim_flag: + if "steer_bias" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_bias"] = 1 * measurement_steer_bias + measurement_steer_bias = sim_setting_dict["steer_bias"] + print("nominal steer_bias", nominal_setting_dict_display["steer_bias"]) + print("perturbed steer_bias", measurement_steer_bias) + print("perturbed steer_bias_deg", measurement_steer_bias * 180 / np.pi) + + if "steer_rate_lim" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_rate_lim"] = 1 * steer_rate_lim + steer_rate_lim = sim_setting_dict["steer_rate_lim"] + print("nominal steer_rate_lim", nominal_setting_dict_display["steer_rate_lim"]) + print("perturbed steer_rate_lim", steer_rate_lim) + + if "vel_rate_lim" in sim_setting_dict.keys(): + nominal_setting_dict_display["vel_rate_lim"] = 1 * vel_rate_lim + vel_rate_lim = sim_setting_dict["vel_rate_lim"] + print("nominal vel_rate_lim", nominal_setting_dict_display["vel_rate_lim"]) + print("perturbed vel_rate_lim", vel_rate_lim) + + if "wheel_base" in sim_setting_dict.keys(): + nominal_setting_dict_display["wheel_base"] = 1 * L + L = sim_setting_dict["wheel_base"] + print("nominal wheel_base", nominal_setting_dict_display["wheel_base"]) + print("perturbed wheel_base", L) + + if "steer_dead_band" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_dead_band"] = 1 * steer_dead_band + steer_dead_band = sim_setting_dict["steer_dead_band"] + print("nominal steer_dead_band", nominal_setting_dict_display["steer_dead_band"]) + print("perturbed steer_dead_band", steer_dead_band) + + if "adaptive_gear_ratio_coef" in sim_setting_dict.keys(): + nominal_setting_dict_display["adaptive_gear_ratio_coef"] = [ + 1 * vgr_coef_a1, + 1 * vgr_coef_b1, + 1 * vgr_coef_c1, + 1 * vgr_coef_a2, + 1 * vgr_coef_b2, + 1 * vgr_coef_c2, + ] + vgr_coef_a1 = sim_setting_dict["adaptive_gear_ratio_coef"][0] + vgr_coef_b1 = sim_setting_dict["adaptive_gear_ratio_coef"][1] + vgr_coef_c1 = sim_setting_dict["adaptive_gear_ratio_coef"][2] + vgr_coef_a2 = sim_setting_dict["adaptive_gear_ratio_coef"][3] + vgr_coef_b2 = sim_setting_dict["adaptive_gear_ratio_coef"][4] + vgr_coef_c2 = sim_setting_dict["adaptive_gear_ratio_coef"][5] + print( + "nominal adaptive_gear_ratio_coef", + nominal_setting_dict_display["adaptive_gear_ratio_coef"], + ) + print( + "perturbed: vgr_coef_a1", + vgr_coef_a1, + "vgr_coef_b1", + vgr_coef_b1, + "vgr_coef_c1", + vgr_coef_c1, + ) + print( + "perturbed: vgr_coef_a2", + vgr_coef_a2, + "vgr_coef_b2", + vgr_coef_b2, + "vgr_coef_c2", + vgr_coef_c2, + ) + + if "acc_time_delay" in sim_setting_dict.keys(): + nominal_setting_dict_display["acc_time_delay"] = sim_dt * acc_delay_step_sim + print("nominal acc_time_delay", nominal_setting_dict_display["acc_time_delay"]) + print("nominal acc_delay_step_sim", acc_delay_step_sim) + acc_delay_step_sim = round(sim_setting_dict["acc_time_delay"] / sim_dt) + print("perturbed acc_time_delay", sim_setting_dict["acc_time_delay"]) + print("perturbed acc_delay_step_sim", acc_delay_step_sim) + + if "steer_time_delay" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_time_delay"] = sim_dt * steer_delay_step_sim + print("nominal steer_time_delay", nominal_setting_dict_display["steer_time_delay"]) + print("nominal steer_delay_step_sim", steer_delay_step_sim) + steer_delay_step_sim = round(sim_setting_dict["steer_time_delay"] / sim_dt) + print("perturbed steer_time_delay", sim_setting_dict["steer_time_delay"]) + print("perturbed steer_delay_step_sim", steer_delay_step_sim) + + if "acc_time_constant" in sim_setting_dict.keys(): + nominal_setting_dict_display["acc_time_constant"] = 1 * acc_time_constant + acc_time_constant = sim_setting_dict["acc_time_constant"] + print("nominal acc_time_constant", nominal_setting_dict_display["acc_time_constant"]) + print("perturbed acc_time_constant", acc_time_constant) + + if "steer_time_constant" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_time_constant"] = 1 * steer_time_constant + steer_time_constant = sim_setting_dict["steer_time_constant"] + print("nominal steer_time_constant", nominal_setting_dict_display["steer_time_constant"]) + print("perturbed steer_time_constant", steer_time_constant) + + if "accel_map_scale" in sim_setting_dict.keys(): + nominal_setting_dict_display["accel_map_scale"] = None + use_accel_map = True + accel_map_scale = sim_setting_dict["accel_map_scale"] + df = pd.read_csv("accel_map.csv", header=None) + current_vel_axis = np.array( + [float(df.loc[0].values[1 + i]) for i in range(len(df.loc[0].values[1:]))] + ) + accel_cmd_axis = np.array( + [float(df[0].values[1 + i]) for i in range(len(df[0].values[1:]))] + ) + accel_map_data = np.zeros((len(accel_cmd_axis), len(current_vel_axis))) + for i in range(len(current_vel_axis)): + for j in range(len(accel_cmd_axis)): + accel_map_data[j, i] = float(df[1 + i].values[1 + j]) * ( + accel_map_scale ** (i * 1.0 / (len(current_vel_axis) - 1)) + ) + X1, X2 = np.meshgrid(current_vel_axis, accel_cmd_axis) + xy = [(x, y) for x in current_vel_axis for y in accel_cmd_axis] + z = [ + accel_map_data[j, i] + for i in range(len(current_vel_axis)) + for j in range(len(accel_cmd_axis)) + ] + accel_map_f_ = scipy.interpolate.LinearNDInterpolator(xy, z) + + def accel_map_f(x, y): + res = accel_map_f_( + [np.clip(x, a_min=current_vel_axis.min(), a_max=current_vel_axis.max())], + [np.clip(y, a_min=accel_cmd_axis.min(), a_max=accel_cmd_axis.max())], + ) + return [res] + + print("current_vel_axis", current_vel_axis) + print("accel_cmd_axis", accel_cmd_axis) + print( + "accel_map_f(current_vel_axis[-1],accel_cmd_axis[-1])", + accel_map_f(current_vel_axis[-1], accel_cmd_axis[-1]), + "accel_map_data[-1,-1]", + accel_map_data[-1, -1], + ) + print( + "accel_map_f(current_vel_axis[-1],accel_cmd_axis[-2])", + accel_map_f(current_vel_axis[-1], accel_cmd_axis[-2]), + "accel_map_data[-2,-1]", + accel_map_data[-2, -1], + ) + print("perturbed use_accel_map", use_accel_map) + + if "steer_scaling" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_scaling"] = 1 * steer_scaling + steer_scaling = sim_setting_dict["steer_scaling"] + print("nominal steer_scaling", nominal_setting_dict_display["steer_scaling"]) + print("perturbed steer_scaling", steer_scaling) + + if "acc_scaling" in sim_setting_dict.keys(): + nominal_setting_dict_display["acc_scaling"] = 1 * acc_scaling + acc_scaling = sim_setting_dict["acc_scaling"] + print("nominal acc_scaling", nominal_setting_dict_display["acc_scaling"]) + print("perturbed acc_scaling", acc_scaling) + + if "vehicle_type" in sim_setting_dict.keys(): + nominal_setting_dict_display["steer_rate_lim"] = 1 * steer_rate_lim + nominal_setting_dict_display["vel_rate_lim"] = 1 * vel_rate_lim + nominal_setting_dict_display["wheel_base"] = 1 * L + nominal_setting_dict_display["acc_time_delay"] = sim_dt * acc_delay_step_sim + nominal_setting_dict_display["steer_time_delay"] = sim_dt * steer_delay_step_sim + nominal_setting_dict_display["acc_time_constant"] = 1 * acc_time_constant + nominal_setting_dict_display["steer_time_constant"] = 1 * steer_time_constant + nominal_setting_dict_display["acc_scaling"] = 1 * acc_scaling + if sim_setting_dict["vehicle_type"] == 0: + pass + elif sim_setting_dict["vehicle_type"] == 1: + # heavy-weight bus + steer_rate_lim = 5.0 + vel_rate_lim = 7.0 + L = 4.76 + acc_delay_step_sim = round(1.0 / sim_dt) + steer_delay_step_sim = round(1.0 / sim_dt) + acc_time_constant = 1.0 + steer_time_constant = 1.0 + acc_scaling = 0.2 + elif sim_setting_dict["vehicle_type"] == 2: + # light-weight bus + steer_rate_lim = 5.0 + vel_rate_lim = 7.0 + L = 4.76 + acc_delay_step_sim = round(0.5 / sim_dt) + steer_delay_step_sim = round(0.5 / sim_dt) + acc_time_constant = 0.5 + steer_time_constant = 0.5 + acc_scaling = 0.5 + elif sim_setting_dict["vehicle_type"] == 3: + # small vehicle + steer_rate_lim = 5.0 + vel_rate_lim = 7.0 + L = 1.335 + acc_delay_step_sim = round(0.3 / sim_dt) + steer_delay_step_sim = round(0.3 / sim_dt) + acc_time_constant = 0.3 + steer_time_constant = 0.3 + acc_scaling = 1.5 + elif sim_setting_dict["vehicle_type"] == 4: + # small robot + steer_rate_lim = 60.0 * (np.pi / 180.0) + vel_rate_lim = 3.0 + L = 0.395 + acc_delay_step_sim = round(0.2 / sim_dt) + steer_delay_step_sim = round(0.2 / sim_dt) + acc_time_constant = 0.2 + steer_time_constant = 0.2 + acc_scaling = 3.0 + + print("steer_rate_lim", nominal_setting_dict_display["steer_rate_lim"], steer_rate_lim) + print("vel_rate_lim", nominal_setting_dict_display["vel_rate_lim"], vel_rate_lim) + print("wheel_base", nominal_setting_dict_display["wheel_base"], L) + print( + "acc_time_delay", + nominal_setting_dict_display["acc_time_delay"], + sim_dt * acc_delay_step_sim, + ) + print( + "steer_time_delay", + nominal_setting_dict_display["steer_time_delay"], + sim_dt * steer_delay_step_sim, + ) + print( + "acc_time_constant", + nominal_setting_dict_display["acc_time_constant"], + acc_time_constant, + ) + print( + "steer_time_constant", + nominal_setting_dict_display["steer_time_constant"], + steer_time_constant, + ) + print("acc_scaling", nominal_setting_dict_display["acc_scaling"], acc_scaling) + + +# dynamics +# @njit(cache=False, fastmath=True) # Commented out because we want to use scipy.interpolate2d +def f_sim( + states, + inputs, + L=L, + acc_time_constant=acc_time_constant, + steer_time_constant=steer_time_constant, + steer_dead_band=steer_dead_band, + steer_scaling=steer_scaling, + acc_scaling=acc_scaling, + measurement_steer_bias=measurement_steer_bias, +): + """Time derivative of sim model dynamics.""" + v = states[2] + theta = states[3] + alpha = states[4] + delta = states[5] + + delta_diff = steer_scaling * inputs[1] - delta + if delta_diff >= steer_dead_band: + delta_diff = delta_diff - steer_dead_band + elif delta_diff <= -steer_dead_band: + delta_diff = delta_diff + steer_dead_band + else: + delta_diff = 0.0 + + actual_alpha = alpha + actual_delta = delta - measurement_steer_bias + + # Acceleration input value -> Actual acceleration input value distortion applied + if use_accel_map: + if actual_alpha > 0: + actual_alpha = accel_map_f(v, actual_alpha)[0] # vel, acc_cmd + + # Tire angle input value -> Actual tire angle input value distortion application + steer_tire_angle_cmd = 1 * delta + coeff_from_tire_to_wheel = ( + 20.0 # Assuming a fixed gear ratio of 20 (moving in a range of roughly 15-30) + ) + steer_wheel = coeff_from_tire_to_wheel * steer_tire_angle_cmd + adaptive_gear_ratio1 = vgr_coef_a1 + vgr_coef_b1 * v * v - vgr_coef_c1 * abs(steer_wheel) + adaptive_gear_ratio2 = vgr_coef_a2 + vgr_coef_b2 * v * v - vgr_coef_c2 * abs(steer_wheel) + actual_delta = ( + steer_tire_angle_cmd * (adaptive_gear_ratio1 / adaptive_gear_ratio2) + - measurement_steer_bias + ) + + states_dot = np.zeros(6) + states_dot[0] = v * np.cos(theta) + states_dot[1] = v * np.sin(theta) + states_dot[2] = actual_alpha + states_dot[3] = v * np.tan(actual_delta) / L + states_dot[4] = (acc_scaling * inputs[0] - alpha) / acc_time_constant + states_dot[5] = delta_diff / steer_time_constant + return states_dot + + +def F_sim( + states, + inputs, + L=L, + acc_time_constant=acc_time_constant, + steer_time_constant=steer_time_constant, + steer_dead_band=steer_dead_band, +): + """Sim model dynamics based on the Euler method.""" + states_next = ( + states + + f_sim(states, inputs, L, acc_time_constant, steer_time_constant, steer_dead_band) * sim_dt + ) + return states_next + + +@njit(cache=False, fastmath=True) +def d_inputs_to_inputs(u_old, d_inputs): + """Compute the sequence of input values from the sequence of input change rates.""" + inputs = np.zeros((d_inputs.shape[0] * ctrl_freq * mpc_freq, 2)) + for j in range(mpc_freq): + inputs[ctrl_freq * j : ctrl_freq * (j + 1)] += ( + u_old + (j + 1) * d_inputs[0] * ctrl_time_step + ) + for i in range(1, d_inputs.shape[0]): + for j in range(mpc_freq): + inputs[ctrl_freq * (mpc_freq * i + j) : ctrl_freq * (mpc_freq * i + j + 1)] += ( + inputs[ctrl_freq * mpc_freq * i - 1] + (j + 1) * d_inputs[i] * ctrl_time_step + ) + return inputs + + +def F_true_predict( + x_current, + u_old, + d_inputs, + acc_des_queue, + steer_des_queue, + L=L, + acc_time_constant=acc_time_constant, + steer_time_constant=steer_time_constant, + steer_dead_band=steer_dead_band, +): + """Compute the true predicted trajectory based on simulator dynamics from the input values.""" + inputs = d_inputs_to_inputs(u_old, d_inputs) + predicted_traj = np.zeros((d_inputs.shape[0] + 1, x_current.shape[0])) + predicted_traj[0] += x_current + acc_queue = np.concatenate((np.array(acc_des_queue), inputs[:, 0])) + steer_queue = np.concatenate((np.array(steer_des_queue), inputs[:, 1])) + for i in range(d_inputs.shape[0]): + x_tmp = predicted_traj[i].copy() + for j in range(ctrl_freq * mpc_freq): + x_tmp = F_sim( + x_tmp, + np.array( + [ + acc_queue[ctrl_freq * mpc_freq * i + j], + steer_queue[ctrl_freq * mpc_freq * i + j], + ] + ), + L, + acc_time_constant, + steer_time_constant, + steer_dead_band, + ) + predicted_traj[i + 1] = x_tmp.copy() + return predicted_traj, inputs[:: ctrl_freq * mpc_freq] + + +def get_mpc_trajectory(x_current, trajectory_data, trajectory_interpolator_list): + """Calculate the target trajectory to be used in MPC from the given data.""" + nearest_index = np.argmin( + ((trajectory_data[:, 1:3] - x_current[:2].reshape(1, 2)) ** 2).sum(axis=1) + ) + timestamp_mpc_trajectory = ( + np.arange(N + 1) * mpc_freq * ctrl_freq * sim_dt + trajectory_data[nearest_index, 0] + ) + break_flag = False + if timestamp_mpc_trajectory[-1] >= trajectory_data[-1, 0]: + timestamp_mpc_trajectory -= timestamp_mpc_trajectory[-1] - trajectory_data[-1, 0] - 1e-16 + break_flag = True + + mpc_trajectory = np.array( + [ + trajectory_interpolator_list[i](timestamp_mpc_trajectory) + for i in range(trajectory_data.shape[1] - 1) + ] + ).T + mpc_trajectory = np.hstack( + [ + timestamp_mpc_trajectory.reshape(-1, 1) - trajectory_data[nearest_index, 0], + mpc_trajectory, + ] + ) + + X_des = np.zeros((N + 1, 8)) + X_des[:, :6] = mpc_trajectory[:, 1:7] + X_des[:, [6, 7]] = mpc_trajectory[:, [5, 6]] + U_des = np.zeros((N, 2)) + return X_des, U_des, x_current[:6] - trajectory_data[nearest_index, 1:7], break_flag + + +def get_feedforward_nominal_input(t, trajectory_data): + """Calculate the nominal input for feed-forward driving.""" + total_time = trajectory_data[-1, 0] + t_current = t - (t // total_time) * total_time + nearest_index = np.argmin(np.abs(trajectory_data[:, 0] - t_current)) + return trajectory_data[nearest_index, [5, 6]] + + +def create_additional_sine_data( + seed, + t_range, + acc_width_range, + acc_period_range, + steer_width_range, + steer_period_range, + large_steer_width_range, + large_steer_period_range, + start_large_steer_time, +): + """Create sine wave data to be added randomly to feed-forward runs.""" + np.random.seed(seed=seed) + t_acc = 0.0 + t_steer = 0.0 + t_large_steer = 0.0 + t_acc_list = [] + t_steer_list = [] + t_large_steer_list = [] + t_acc_list.append(t_acc) + t_steer_list.append(t_steer) + t_large_steer_list.append(t_large_steer) + t_large_steer += start_large_steer_time + t_large_steer_list.append(t_large_steer) + width_acc_list = [] + width_steer_list = [] + width_large_steer_list = [] + width_large_steer_list.append(0) + while True: + if max(t_acc, t_large_steer) >= t_steer: + period = ( + steer_period_range[1] - steer_period_range[0] + ) * np.random.uniform() + steer_period_range[0] + t_steer += period + t_steer_list.append(t_steer) + width_steer_list.append(steer_width_range * np.random.uniform()) + elif t_large_steer >= t_acc: + period = ( + acc_period_range[1] - acc_period_range[0] + ) * np.random.uniform() + acc_period_range[0] + t_acc += period + t_acc_list.append(t_acc) + width_acc_list.append(acc_width_range * np.random.uniform()) + else: + period = ( + large_steer_period_range[1] - large_steer_period_range[0] + ) * np.random.uniform() + large_steer_period_range[0] + t_large_steer += period + t_large_steer_list.append(t_large_steer) + width_large_steer_list.append(large_steer_width_range * np.random.uniform()) + if t_acc >= t_range[1] and t_steer >= t_range[1] and t_large_steer >= t_range[1]: + break + return ( + np.array(t_acc_list), + np.array(width_acc_list), + np.array(t_steer_list), + np.array(width_steer_list), + np.array(t_large_steer_list), + np.array(width_large_steer_list), + ) + + +@njit(cache=False, fastmath=True) +def get_current_additional_sine( + t, + t_acc_array, + width_acc_array, + t_steer_array, + width_steer_array, + t_large_steer_array, + width_large_steer_array, +): + """Calculate current values from already created sine wave data.""" + acc_index = 0 + steer_index = 0 + large_steer_index = 0 + for i in range(t_acc_array.shape[0] - 1): + if t < t_acc_array[i + 1]: + break + acc_index += 1 + for i in range(t_steer_array.shape[0] - 1): + if t < t_steer_array[i + 1]: + break + steer_index += 1 + for i in range(t_large_steer_array.shape[0] - 1): + if t < t_large_steer_array[i + 1]: + break + large_steer_index += 1 + acc = width_acc_array[acc_index] * np.sin( + 2 + * np.pi + * (t - t_acc_array[acc_index]) + / (t_acc_array[acc_index + 1] - t_acc_array[acc_index]) + ) + steer = width_steer_array[steer_index] * np.sin( + 2 + * np.pi + * (t - t_steer_array[steer_index]) + / (t_steer_array[steer_index + 1] - t_steer_array[steer_index]) + ) + steer += width_large_steer_array[large_steer_index] * np.sin( + 2 + * np.pi + * (t - t_large_steer_array[large_steer_index]) + / (t_large_steer_array[large_steer_index + 1] - t_large_steer_array[large_steer_index]) + ) + return np.array([acc, steer]) + + +def create_vel_sine_data(seed, t_range, vel_width_range, vel_period_range): + """Create sine wave data for target velocity.""" + np.random.seed(seed=seed) + t_vel = 0.0 + t_vel_list = [] + t_vel_list.append(t_vel) + width_vel_list = [] + while True: + period = ( + vel_period_range[1] - vel_period_range[0] + ) * np.random.uniform() + vel_period_range[0] + t_vel += period + t_vel_list.append(t_vel) + width_vel_list.append(vel_width_range * np.random.uniform()) + if t_vel >= t_range[1]: + break + return ( + np.array(t_vel_list), + np.array(width_vel_list), + ) + + +@njit(cache=False, fastmath=True) +def get_current_vel_sine(t, t_vel_array, width_vel_array, v_mid): + """Calculate current target velocity values from already created sine wave data.""" + vel_index = 0 + for i in range(t_vel_array.shape[0] - 1): + if t < t_vel_array[i + 1]: + break + vel_index += 1 + vel = v_mid + width_vel_array[vel_index] * np.sin( + 2 + * np.pi + * (t - t_vel_array[vel_index]) + / (t_vel_array[vel_index + 1] - t_vel_array[vel_index]) + ) + return vel + + +def get_figure_eight_point(t, circle_radius): + """ + Get the position and yaw angle in world coordinates of the figure eight given the circle radius. + + Here t is a 1-dimensional array of numpy and each t[i] represents the distance traveled. + The return value is a 2-dimensional array of positions and a 1-dimensional array of yaw angles corresponding to t. + """ + sign = -2 * (np.floor(t / (2 * np.pi * circle_radius)) % 2).astype(int) + 1 + x = circle_radius * np.sin(t / circle_radius) + y = sign * circle_radius * (1 - np.cos(t / circle_radius)) + yaw = ( + sign * ((t / circle_radius) % (2 * np.pi) - np.pi) + np.pi + ) # if sign == 1, then yaw = (t/circle_radius)%(2*np.pi). Else, yaw = 2*np.pi - (t/circle_radius)%(2*np.pi). + return np.array([x, y]).T, yaw + + +def pure_pursuit( + x_current, + target_position, + target_vel, + target_yaw, + acc_lim=7.0, + steer_lim=1.0, + wheel_base=drive_functions.L, + lookahead_time=3.0, + min_lookahead=3.0, + acc_kp=0.5, +): + """Calculate acceleration and steer angle input values based on pure pursuit.""" + present_position = x_current[:2] + present_longitudinal_velocity = x_current[2] + present_point_yaw = x_current[3] + longitudinal_vel_err = present_longitudinal_velocity - target_vel + acc_kp = 0.5 + acc_cmd = np.clip(-acc_kp * longitudinal_vel_err, -acc_lim, acc_lim) + + # compute steer cmd + cos_yaw = np.cos(target_yaw) + sin_yaw = np.sin(target_yaw) + diff_position = present_position - target_position + lat_err = -sin_yaw * diff_position[0] + cos_yaw * diff_position[1] + yaw_err = present_point_yaw - target_yaw + while True: + if yaw_err > np.pi: + yaw_err -= 2.0 * np.pi + if yaw_err < (-np.pi): + yaw_err += 2.0 * np.pi + if np.abs(yaw_err) < np.pi: + break + + lookahead = min_lookahead + lookahead_time * np.abs(present_longitudinal_velocity) + steer_kp = 2.0 * wheel_base / (lookahead * lookahead) + steer_kd = 2.0 * wheel_base / lookahead + steer_cmd = np.clip(-steer_kp * lat_err - steer_kd * yaw_err, -steer_lim, steer_lim) + return np.array([acc_cmd, steer_cmd]) + + +def get_pure_pursuit_info(x_current, trajectory_position_data, trajectory_yaw_data, previous_index): + """Calculate the target position and yaw angle required for pure pursuit.""" + search_range = ( + np.arange( + previous_index - trajectory_position_data.shape[0] // 4, + previous_index + trajectory_position_data.shape[0] // 4, + ) + % trajectory_position_data.shape[0] + ) + nearest_index = np.argmin( + ((trajectory_position_data[search_range] - x_current[:2].reshape(1, 2)) ** 2).sum(axis=1) + ) + return ( + trajectory_position_data[search_range[nearest_index]], + trajectory_yaw_data[search_range[nearest_index]], + search_range[nearest_index], + ) + + +class driving_log_updater: + """Class for updating logs when driving on the Python simulator.""" + + def __init__(self): + self.X_history = [] + self.U_history = [] + self.control_cmd_time_stamp_list = [] + self.control_cmd_steer_list = [] + self.control_cmd_acc_list = [] + self.kinematic_state_list = [] + self.acceleration_list = [] + self.steering_status_list = [] + self.control_cmd_orig_list = [] + self.operation_mode_list = [] + + def update(self, t_current, x_current, u_current): + """Update logs.""" + self.X_history.append(x_current) + self.U_history.append(u_current) + self.control_cmd_time_stamp_list.append(t_current) + self.control_cmd_steer_list.append(u_current[1]) + self.control_cmd_acc_list.append(u_current[0]) + if self.control_cmd_time_stamp_list[-1] - self.control_cmd_time_stamp_list[0] > 3.0: + self.control_cmd_time_stamp_list.pop(0) + self.control_cmd_steer_list.pop(0) + self.control_cmd_acc_list.pop(0) + t_sec = int(t_current) + t_n_sec = int(1e9 * (t_current - t_sec)) + kinematic_state = np.zeros(7) + acceleration = np.zeros(4) + steering_status = np.zeros(3) + control_cmd_orig = np.zeros(10) + operation_mode = np.zeros(3) + kinematic_state[0] = t_sec + kinematic_state[1] = t_n_sec + kinematic_state[2] = x_current[0] + kinematic_state[3] = x_current[1] + kinematic_state[4] = np.sin(0.5 * x_current[3]) + kinematic_state[5] = np.cos(0.5 * x_current[3]) + kinematic_state[6] = x_current[2] + self.kinematic_state_list.append(kinematic_state) + acceleration[0] = t_sec + acceleration[1] = t_n_sec + acceleration[3] = x_current[4] + self.acceleration_list.append(acceleration) + steering_status[0] = t_sec + steering_status[1] = t_n_sec + steering_status[2] = x_current[5] + self.steering_status_list.append(steering_status) + control_cmd_orig[0] = t_sec + control_cmd_orig[1] = t_n_sec + control_cmd_orig[4] = u_current[1] + control_cmd_orig[9] = u_current[0] + self.control_cmd_orig_list.append(control_cmd_orig) + operation_mode[0] = t_sec + operation_mode[1] = t_n_sec + operation_mode[2] = 2.0 + self.operation_mode_list.append(operation_mode) + + def save(self, save_dir): + """Save logs in csv format.""" + kinematic_states = np.zeros((len(self.kinematic_state_list), 48)) + kinematic_states[:, [0, 1, 4, 5, 9, 10, 47]] = np.array(self.kinematic_state_list) + np.savetxt(save_dir + "/kinematic_state.csv", kinematic_states, delimiter=",") + np.savetxt(save_dir + "/acceleration.csv", np.array(self.acceleration_list), delimiter=",") + np.savetxt( + save_dir + "/steering_status.csv", + np.array(self.steering_status_list), + delimiter=",", + ) + np.savetxt( + save_dir + "/control_cmd_orig.csv", + np.array(self.control_cmd_orig_list), + delimiter=",", + ) + np.savetxt( + save_dir + "/system_operation_mode_state.csv", + np.array(self.operation_mode_list), + delimiter=",", + ) + with open(save_dir + "/system_operation_mode_state.csv", "w") as f: + writer = csv.writer(f) + for i in range(len(self.operation_mode_list)): + operation_mode_plus_true = self.operation_mode_list[i].tolist() + operation_mode_plus_true.append("True") + writer.writerow(operation_mode_plus_true) + + +def slalom_drive( + save_file=True, + save_dir=None, + load_dir=drive_functions.load_dir, + visualize=True, + use_trained_model=False, + use_trained_model_diff=None, + control_type="mpc", # feedforward_test=False, + straight_line_test=False, + initial_error=np.zeros(6), + t_range=[0, 100], + seed=1, + acc_width_range=0.005, + acc_period_range=[5.0, 20.0], + steer_width_range=0.005, + steer_period_range=[5.0, 20.0], + large_steer_width_range=0.00, + large_steer_period_range=[5.0, 20.0], + start_large_steer_time=40.0, + vel_width_range=5.0, + vel_period_range=[5.0, 20.0], + v_mid=6.0, + circle_radius=30.0, +): + """Perform a slalom driving simulation.""" + if control_type == "pp": + print("\n[run figure_eight_drive]\n") + elif control_type == "ff": + print("\n[run feedforward_drive]\n") + else: + if not straight_line_test: + print("\n[run slalom_drive]\n") + else: + print("\n[straight_line_test]\n") + if save_file: + if save_dir is None: + save_dir_ = "python_sim_log_" + str(datetime.datetime.now()) + else: + save_dir_ = save_dir + if not os.path.isdir(save_dir_): + os.mkdir(save_dir_) + controller = drive_controller.drive_controller( + model_file_name=(load_dir + "/model_for_test_drive.pth"), + load_GP_dir=load_dir, + load_polynomial_reg_dir=load_dir, + use_trained_model=use_trained_model, + use_trained_model_diff=use_trained_model_diff, + load_train_data_dir=load_dir, + ) + mode = controller.mode + if control_type == "mpc": + print("mode:", mode) + + plt.rcParams["figure.figsize"] = (8, 8) + t_eval = np.arange(*t_range, sim_dt) + if not straight_line_test: + trajectory_data = np.loadtxt("slalom_course_data.csv", delimiter=",") + else: + # Test by straight_line. To run, the following create_straight_line_test_csv() must be executed + trajectory_data = np.loadtxt("straight_line.csv", delimiter=",") + trajectory_interpolator_list = [ + scipy.interpolate.interp1d(trajectory_data[:, 0], trajectory_data[:, 1 + i]) + for i in range(trajectory_data.shape[1] - 1) + ] + x_init = trajectory_data[0, 1:7] + initial_error + + x_current = x_init.copy() + + acc_des_queue = [0] * acc_delay_step_sim + steer_des_queue = [0] * steer_delay_step_sim + + calculated = 0 + break_flag = False + + tracking_error_list = [] + + total_abs_max_lateral_deviation = -1 + straight_line_abs_max_lateral_deviation = -1 + total_abs_max_velocity_error = -1 + total_abs_max_yaw_error = -1 + total_abs_max_acc_error = -1 + total_abs_max_steer_error = -1 + prev_u_actual_input = np.zeros(2) + log_updater = driving_log_updater() + + previous_pp_index = 0 + + if control_type != "mpc": # feedforward_test: + ( + t_acc_array, + width_acc_array, + t_steer_array, + width_steer_array, + t_large_steer_array, + width_large_steer_array, + ) = create_additional_sine_data( + seed, + t_range, + acc_width_range, + acc_period_range, + steer_width_range, + steer_period_range, + large_steer_width_range, + large_steer_period_range, + start_large_steer_time, + ) + if control_type == "pp": + t_figure_eight = np.arange(*[0, 4 * np.pi * circle_radius], 0.01) + trajectory_position_data, trajectory_yaw_data = get_figure_eight_point( + t_figure_eight, circle_radius + ) + # plt.plot(trajectory_position_data[:,0],trajectory_position_data[:,1]) + # plt.show() + t_vel_array, width_vel_array = create_vel_sine_data( + seed, t_range, vel_width_range, vel_period_range + ) + + for i in range(t_eval.size): + if i % ctrl_freq == 0: # update u_opt + if control_type == "mpc": # not feedforward_test: + X_des, U_des, tracking_error, break_flag = get_mpc_trajectory( + x_current, trajectory_data, trajectory_interpolator_list + ) + tracking_error_list.append(tracking_error.copy()) + + u_opt = controller.update_input_queue_and_get_optimal_control( + log_updater.control_cmd_time_stamp_list, + log_updater.control_cmd_acc_list, + log_updater.control_cmd_steer_list, + x_current, + X_des, + U_des, + ) + elif control_type == "ff": + u_opt = get_current_additional_sine( + t_eval[i], + t_acc_array, + width_acc_array, + t_steer_array, + width_steer_array, + t_large_steer_array, + width_large_steer_array, + ) + u_opt[0] += get_feedforward_nominal_input(t_eval[i], trajectory_data)[0] + elif control_type == "pp": + target_position, target_yaw, previous_pp_index = get_pure_pursuit_info( + x_current, trajectory_position_data, trajectory_yaw_data, previous_pp_index + ) + target_vel = get_current_vel_sine(t_eval[i], t_vel_array, width_vel_array, v_mid) + u_opt = pure_pursuit(x_current, target_position, target_vel, target_yaw) + u_opt += get_current_additional_sine( + t_eval[i], + t_acc_array, + width_acc_array, + t_steer_array, + width_steer_array, + t_large_steer_array, + width_large_steer_array, + ) + calculated += 1 + log_updater.update(t_eval[i], x_current, u_opt) + if ( + visualize and (control_type in ["ff", "pp"]) and (i == t_eval.size - 1 or break_flag) + ): # feedforward_test and (i == t_eval.size - 1 or break_flag): + X = np.array(log_updater.X_history) + U = np.array(log_updater.U_history) + + if not use_trained_model: + title_str = "control_using_nominal_model: " + else: + title_str = "control_using_trained_model: " + if perturbed_sim_flag: + title_str += ( + "perturbed_sim: " + + str(sim_setting_dict) + + ", nominal_model: " + + str(nominal_setting_dict_display) + ) + fig = plt.figure(figsize=(18, 12), tight_layout=True) + fig.suptitle(title_str) + plt.subplot(231) + + ax1 = plt.subplot(2, 3, 1) + ax1.plot(X[:, 0], X[:, 1], label="trajectory") + ax1.legend() + ax1.set_xlabel("x_position [m]") + ax1.set_ylabel("y_position [m]") + + time_normalize_1 = ctrl_freq * sim_dt + f_s = int(1.0 / time_normalize_1) + + ax2 = plt.subplot(2, 3, 2) + X_acc = np.fft.fft(U[:, 0]) / len(U[:, 0]) # Fourier transform of waveforms + freqs = np.fft.fftfreq(len(U[:, 0])) * f_s + ax2.stem( + freqs, + np.abs(X_acc), + use_line_collection=True, + basefmt="k-", + markerfmt="cx", + label="acc input", + ) + ax2.legend() + ax2.set_xlim([-1.0, 1.0]) + ax2.set_xlabel("freq") + ax2.set_ylabel("amplitude") + + ax3 = plt.subplot(2, 3, 3) + X_steer = np.fft.fft(U[:, 1]) / len(U[:, 1]) # Fourier transform of waveforms + freqs = np.fft.fftfreq(len(U[:, 1])) * f_s + ax3.stem( + freqs, + np.abs(X_steer), + use_line_collection=True, + basefmt="k-", + markerfmt="cx", + label="steer input", + ) + ax3.legend() + ax3.set_xlim([-1.0, 1.0]) + ax3.set_xlabel("freq") + ax3.set_ylabel("amplitude") + + ax5 = plt.subplot(2, 3, 5) + ax5.plot(time_normalize_1 * np.arange(U.shape[0]), U[:, 0], label="acc input") + ax5.legend() + + ax6 = plt.subplot(2, 3, 6) + ax6.plot(time_normalize_1 * np.arange(U.shape[0]), U[:, 1], label="steer input") + ax6.legend() + + if save_file: + png_save_dir = save_dir_ + else: + png_save_dir = "." + if control_type == "ff": + plt.savefig(png_save_dir + "/python_simulator_feedforward_drive.png") + elif control_type == "pp": + plt.savefig(png_save_dir + "/python_simulator_pure_pursuit_drive.png") + plt.close() + + if ( + visualize + and (control_type == "mpc") + and (i % 1000 * ctrl_freq == 999 * ctrl_freq or i == t_eval.size - 1 or break_flag) + ): + fig = plt.figure(figsize=(24, 15), tight_layout=True) + if not use_trained_model: + title_str = "control_using_nominal_model: " + else: + title_str = "control_using_trained_model: " + if perturbed_sim_flag: + title_str += ( + "perturbed_sim: " + + str(sim_setting_dict) + + ", nominal_model: " + + str(nominal_setting_dict_display) + ) + fig.suptitle(title_str) + + plt.subplot(331) + + ax1 = plt.subplot(3, 3, 1) + X = np.array(log_updater.X_history) + U = np.array(log_updater.U_history) + X_des_hist = np.array(controller.X_des_history) + time_normalize_1 = ctrl_freq * sim_dt + time_normalize_2 = ctrl_freq * mpc_freq * sim_dt + ax1.scatter( + trajectory_data[:, 1], + trajectory_data[:, 2], + s=4, + c="orange", + label="reference_trajectory", + ) + ax1.plot(X[:, 0], X[:, 1], label="trajectory") + if mode != "mppi": + ax1.scatter( + controller.nominal_traj_ilqr[:, 0], + controller.nominal_traj_ilqr[:, 1], + s=4, + c="red", + label="pred_trajectory_ilqr", + ) + true_prediction, nominal_inputs = F_true_predict( + x_current, + controller.u_old, + controller.nominal_inputs_ilqr, + acc_des_queue, + steer_des_queue, + ) + ax1.scatter( + true_prediction[:, 0], + true_prediction[:, 1], + s=4, + c="green", + label="true_prediction", + ) + if mode != "ilqr": + ax1.scatter( + controller.nominal_traj_mppi[:, 0], + controller.nominal_traj_mppi[:, 1], + s=4, + c="pink", + label="pred_trajectory_mppi", + ) + + ax1.legend() + ax1.set_xlabel("x_position [m]") + ax1.set_ylabel("y_position [m]") + + ax2 = plt.subplot(3, 3, 2) + tracking_error_array = np.array(tracking_error_list) + lateral_deviation = ( + -np.sin(X_des_hist[:, 3]) * tracking_error_array[:, 0] + + np.cos(X_des_hist[:, 3]) * tracking_error_array[:, 1] + ) + + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + lateral_deviation, + label="lateral_deviation", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + np.zeros(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + 0.05 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -0.05 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + 0.1 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -0.1 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + 0.15 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -0.15 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + 0.2 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -0.2 * np.ones(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax2.set_xlabel("Time [s]") + ax2.set_ylabel("Lateral deviation [m]") + ax2.legend() + + straight_line_index = np.where(X_des_hist[:, 0] < 250.0)[ + 0 + ].max() # Before 250 [m] is considered to be a straight run. + total_abs_max_lateral_deviation = np.abs(lateral_deviation).max() + total_abs_mean_lateral_deviation = np.abs(lateral_deviation).mean() + straight_line_abs_max_lateral_deviation = np.abs( + lateral_deviation[: straight_line_index + 1] + ).max() + ax2.set_title( + "abs_max(lateral_dev) = " + + str(total_abs_max_lateral_deviation) + + "\nabs_max(lateral_dev[straight_line]) = " + + str(straight_line_abs_max_lateral_deviation) + ) + + ax3 = plt.subplot(3, 3, 4) + ax3.plot(time_normalize_1 * np.arange(X.shape[0]), X[:, 2], label="velocity") + ax3.plot( + time_normalize_1 * np.arange(X.shape[0]), X_des_hist[:, 2], label="velocity_target" + ) + ax3.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -tracking_error_array[:, 2], + label="velocity_error", + ) + if mode != "mppi": + ax3.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(true_prediction.shape[0]), + true_prediction[:, 2], + s=4, + label="velocity_true_prediction", + ) + ax3.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(controller.nominal_traj_ilqr.shape[0]), + controller.nominal_traj_ilqr[:, 2], + s=4, + label="velocity_prediction_ilqr", + ) + ax3.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + np.zeros(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax3.set_xlabel("Time [s]") + ax3.set_ylabel("velocity [m/s]") + ax3.legend() + total_abs_max_velocity_error = np.abs(tracking_error_array[:, 2]).max() + total_abs_mean_velocity_error = np.abs(tracking_error_array[:, 2]).mean() + straight_line_abs_max_velocity_error = np.abs( + tracking_error_array[: straight_line_index + 1, 2] + ).max() + ax3.set_title( + "abs_max(velocity_error) = " + + str(total_abs_max_velocity_error) + + "\nabs_max(velocity_error[straight_line]) = " + + str(straight_line_abs_max_velocity_error) + ) + + ax4 = plt.subplot(3, 3, 5) + ax4.plot(time_normalize_1 * np.arange(X.shape[0]), X[:, 3], label="yaw") + ax4.plot(time_normalize_1 * np.arange(X.shape[0]), X_des_hist[:, 3], label="yaw_target") + ax4.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -tracking_error_array[:, 3], + label="yaw_error", + ) + if mode != "mppi": + ax4.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(true_prediction.shape[0]), + true_prediction[:, 3], + s=4, + label="yaw_true_prediction", + ) + ax4.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(controller.nominal_traj_ilqr.shape[0]), + controller.nominal_traj_ilqr[:, 3], + s=4, + label="yaw_prediction_ilqr", + ) + ax4.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + np.zeros(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax4.set_xlabel("Time [s]") + ax4.set_ylabel("yaw [rad]") + ax4.legend() + total_abs_max_yaw_error = np.abs(tracking_error_array[:, 3]).max() + total_abs_mean_yaw_error = np.abs(tracking_error_array[:, 3]).mean() + straight_line_abs_max_yaw_error = np.abs( + tracking_error_array[: straight_line_index + 1, 3] + ).max() + ax4.set_title( + "abs_max(yaw_error) = " + + str(total_abs_max_yaw_error) + + "\nabs_max(yaw_error[straight_line]) = " + + str(straight_line_abs_max_yaw_error) + ) + + ax5 = plt.subplot(3, 3, 7) + ax5.plot(time_normalize_1 * np.arange(X.shape[0]), X[:, 4], label="acc") + ax5.plot(time_normalize_1 * np.arange(X.shape[0]), U[:, 0], label="acc_input") + ax5.plot(time_normalize_1 * np.arange(X.shape[0]), X_des_hist[:, 4], label="acc_target") + ax5.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -tracking_error_array[:, 4], + label="acc_error", + ) + if mode != "mppi": + ax5.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(true_prediction.shape[0]), + true_prediction[:, 4], + s=4, + label="acc_true_prediction", + ) + ax5.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(controller.nominal_traj_ilqr.shape[0]), + controller.nominal_traj_ilqr[:, 4], + s=4, + label="acc_prediction_ilqr", + ) + ax5.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(nominal_inputs.shape[0]), + nominal_inputs[:, 0], + s=4, + label="acc_input_schedule", + ) + ax5.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + np.zeros(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax5.set_xlabel("Time [s]") + ax5.set_ylabel("acc [m/s^2]") + ax5.legend() + total_abs_max_acc_error = np.abs(tracking_error_array[:, 4]).max() + total_abs_mean_acc_error = np.abs(tracking_error_array[:, 4]).mean() + straight_line_abs_max_acc_error = np.abs( + tracking_error_array[: straight_line_index + 1, 4] + ).max() + ax5.set_title( + "abs_max(acc_error) = " + + str(total_abs_max_acc_error) + + "\nabs_max(acc_error[straight_line]) = " + + str(straight_line_abs_max_acc_error) + ) + + ax6 = plt.subplot(3, 3, 8) + ax6.plot(time_normalize_1 * np.arange(X.shape[0]), X[:, 5], label="steer") + ax6.plot(time_normalize_1 * np.arange(X.shape[0]), U[:, 1], label="steer_input") + ax6.plot( + time_normalize_1 * np.arange(X.shape[0]), X_des_hist[:, 7], label="steer_mpc_target" + ) + ax6.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + -tracking_error_array[:, 5], + label="steer_error", + ) + if mode != "mppi": + ax6.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(true_prediction.shape[0]), + true_prediction[:, 5], + s=4, + label="steer_true_prediction", + ) + ax6.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(controller.nominal_traj_ilqr.shape[0]), + controller.nominal_traj_ilqr[:, 5], + s=4, + label="steer_prediction_ilqr", + ) + ax6.scatter( + time_normalize_1 * (X.shape[0] - 1) + + time_normalize_2 * np.arange(nominal_inputs.shape[0]), + nominal_inputs[:, 1], + s=4, + label="steer_input_schedule", + ) + ax6.plot( + time_normalize_1 * np.arange(tracking_error_array.shape[0]), + np.zeros(tracking_error_array.shape[0]), + linestyle="dashed", + ) + ax6.set_xlabel("Time [s]") + ax6.set_ylabel("steer [rad]") + ax6.legend() + total_abs_max_steer_error = np.abs(tracking_error_array[:, 5]).max() + total_abs_mean_steer_error = np.abs(tracking_error_array[:, 5]).mean() + straight_line_abs_max_steer_error = np.abs( + tracking_error_array[: straight_line_index + 1, 5] + ).max() + ax6.set_title( + "abs_max(steer_error) = " + + str(total_abs_max_steer_error) + + "\nabs_max(steer_error[straight_line]) = " + + str(straight_line_abs_max_steer_error) + ) + + ax7 = plt.subplot(3, 3, 3) + f_s = int(1.0 / time_normalize_1) + + steer_state = X[:, 5] + X_steer = np.fft.fft(steer_state) # Fourier transform of waveforms + freqs = np.fft.fftfreq(len(steer_state)) * f_s + ax7.stem( + freqs, + np.abs(X_steer) / len(steer_state), + use_line_collection=True, + basefmt="k-", + markerfmt="rx", + label="steer_state", + ) + + lateral_acc = X[:, 2] * X[:, 2] * np.tan(X[:, 5]) / L + steer_dot = np.zeros(X.shape[0]) + steer_dot[0] = (X[1, 5] - X[0, 5]) / time_normalize_1 + steer_dot[-1] = (X[-1, 5] - X[-2, 5]) / time_normalize_1 + steer_dot[1:-1] = 0.5 * (X[2:, 5] - X[:-2, 5]) / time_normalize_1 + lateral_jerk = 2 * X[:, 2] * np.tan(X[:, 5]) * X[:, 4] / L + X[:, 2] * X[ + :, 2 + ] * steer_dot / (L * np.cos(X[:, 5]) * np.cos(X[:, 5])) + + X_lateral_acc = np.fft.fft(lateral_acc) # Fourier transform of waveforms + freqs = np.fft.fftfreq(len(lateral_acc)) * f_s + ax7.stem( + freqs, + np.abs(X_lateral_acc) / len(lateral_acc), + use_line_collection=True, + basefmt="k-", + markerfmt="gx", + label="lateral_acc", + ) + + X_lateral_jerk = np.fft.fft(lateral_jerk) # Fourier transform of waveforms + freqs = np.fft.fftfreq(len(lateral_jerk)) * f_s + ax7.stem( + freqs, + np.abs(X_lateral_jerk) / len(lateral_jerk), + use_line_collection=True, + basefmt="k-", + markerfmt="bx", + label="lateral_jerk", + ) + + ax7.set_xlabel("Frequency in Hertz[Hz]") + ax7.set_ylabel("Amplitude (normalized dividing by data length)") + ax7.set_xlim(-1, 1) + ax7.legend() + + if use_accel_map: + ax9 = plt.subplot(3, 3, 9, projection="3d") + X1, X2 = np.meshgrid(current_vel_axis, accel_cmd_axis) + ax9.plot_surface(X1, X2, accel_map_data) + + if save_file: + png_save_dir = save_dir_ + else: + png_save_dir = "." + if not use_trained_model: + plt.savefig(png_save_dir + "/python_simulator_nominal_model_fig_" + str(i) + ".png") + else: + plt.savefig(png_save_dir + "/python_simulator_trained_model_fig_" + str(i) + ".png") + plt.close() + + np.savetxt( + save_dir_ + "/lateral_deviation.csv", + np.hstack( + [time_normalize_1 * np.arange(tracking_error_array.shape[0]), lateral_deviation] + ), + delimiter=",", + ) + + np.savetxt( + save_dir_ + "/steer_state.csv", + np.hstack( + [time_normalize_1 * np.arange(tracking_error_array.shape[0]), steer_state] + ), + delimiter=",", + ) + + acc_des_queue.append(u_opt[0]) + steer_des_queue.append(u_opt[1]) + u_actual_input = np.array([acc_des_queue.pop(0), steer_des_queue.pop(0)]) + + # Logic-level restrictions on control inputs + delta_steer_max = steer_rate_lim * sim_dt + u_actual_input[0] = np.clip(u_actual_input[0], -vel_rate_lim, vel_rate_lim) + u_actual_input[1] = np.clip( + u_actual_input[1], + prev_u_actual_input[1] - delta_steer_max, + prev_u_actual_input[1] + delta_steer_max, + ) + + x_next = F_sim(x_current, u_actual_input) + x_current = x_next.copy() + prev_u_actual_input = u_actual_input.copy() + if break_flag: + controller.send_initialize_input_queue() + controller.stop_model_update() + break + if save_file: + log_updater.save(save_dir_) + + if control_type == "mpc" and perturbed_sim_flag: + auto_test_performance_result_dict = { + "total_abs_max_lateral_deviation": total_abs_max_lateral_deviation, + "straight_line_abs_max_lateral_deviation": straight_line_abs_max_lateral_deviation, + "total_abs_max_velocity_error": total_abs_max_velocity_error, + "total_abs_max_yaw_error": total_abs_max_yaw_error, + "total_abs_max_acc_error": total_abs_max_acc_error, + "total_abs_max_steer_error": total_abs_max_steer_error, + "use_trained_model": use_trained_model, + "sim_setting_dict": sim_setting_dict, + "nominal_setting_dict_display": nominal_setting_dict_display, + } + auto_test_performance_result_list = [ + total_abs_max_lateral_deviation, + total_abs_max_velocity_error, + total_abs_max_yaw_error, + total_abs_max_acc_error, + total_abs_max_steer_error, + total_abs_mean_lateral_deviation, + total_abs_mean_velocity_error, + total_abs_mean_yaw_error, + total_abs_mean_acc_error, + total_abs_mean_steer_error, + straight_line_abs_max_lateral_deviation, + ] + + if save_file: + with open(save_dir_ + "/auto_test_performance_result.json", "w") as json_f: + json.dump(auto_test_performance_result_dict, json_f) + print("how_many_time_controlled", calculated) + + return auto_test_performance_result_list + + +def create_straight_line_test_csv( + jerk=0.3, starting_vel=5.0, interval_1=2.0, interval_2=3.0, interval_3=10.0 +): + """Generate data for a straight line driving test.""" + t_1 = 10.0 + t_2 = t_1 + interval_1 # Increasing acceleration. + t_3 = t_2 + interval_2 # Constant acceleration + t_4 = t_3 + interval_1 # Decreasing acceleration. + t_5 = t_4 + interval_3 # acceleration = 0 + t_6 = t_5 + interval_1 # Decreasing acceleration. + t_7 = t_6 + interval_2 # Constant acceleration + t_8 = t_7 + interval_1 # Decreasing acceleration. + vel_t1 = starting_vel + x_t1 = starting_vel * t_1 + vel_t2 = vel_t1 + 0.5 * jerk * interval_1 * interval_1 + x_t2 = x_t1 + vel_t1 * interval_1 + 0.5 * jerk * interval_1 * interval_1 * interval_1 / 3 + vel_t3 = vel_t2 + jerk * interval_1 * interval_2 + x_t3 = x_t2 + vel_t2 * interval_2 + 0.5 * jerk * interval_1 * interval_2 * interval_2 + vel_t4 = vel_t3 + 0.5 * jerk * interval_1 * interval_1 + x_t4 = x_t3 + vel_t4 * interval_1 - 0.5 * jerk * interval_1 * interval_1 * interval_1 / 3 + vel_t5 = vel_t4 + x_t5 = x_t4 + vel_t4 * interval_3 + vel_t6 = vel_t5 - 0.5 * jerk * interval_1 * interval_1 + x_t6 = x_t5 + vel_t5 * interval_1 - 0.5 * jerk * interval_1 * interval_1 * interval_1 / 3 + vel_t7 = vel_t6 - jerk * interval_1 * interval_2 + x_t7 = x_t6 + vel_t6 * interval_2 - 0.5 * jerk * interval_1 * interval_2 * interval_2 + vel_t8 = vel_t7 - 0.5 * jerk * interval_1 * interval_1 + x_t8 = x_t7 + vel_t8 * interval_1 + 0.5 * jerk * interval_1 * interval_1 * interval_1 / 3 + + def calc_longitudinal_state(t): + if t < t_1: + return starting_vel * t, starting_vel, 0.0 + elif t < t_2: + return ( + x_t1 + vel_t1 * (t - t_1) + 0.5 * jerk * (t - t_1) * (t - t_1) * (t - t_1) / 3, + vel_t1 + 0.5 * jerk * (t - t_1) * (t - t_1), + jerk * (t - t_1), + ) + elif t < t_3: + return ( + x_t2 + vel_t2 * (t - t_2) + 0.5 * jerk * (t_2 - t_1) * (t - t_2) * (t - t_2), + vel_t2 + jerk * (t_2 - t_1) * (t - t_2), + jerk * (t_2 - t_1), + ) + elif t < t_4: + return ( + x_t4 - vel_t4 * (t_4 - t) + 0.5 * jerk * (t_4 - t) * (t_4 - t) * (t_4 - t) / 3, + vel_t4 - 0.5 * jerk * (t_4 - t) * (t_4 - t), + jerk * (t_4 - t), + ) + elif t < t_5: + return x_t4 + vel_t4 * (t - t_4), vel_t4, 0.0 + elif t < t_6: + return ( + x_t5 + vel_t5 * (t - t_5) - 0.5 * jerk * (t - t_5) * (t - t_5) * (t - t_5) / 3, + vel_t5 - 0.5 * jerk * (t - t_5) * (t - t_5), + -jerk * (t - t_5), + ) + elif t < t_7: + return ( + x_t6 + vel_t6 * (t - t_6) - 0.5 * jerk * (t_6 - t_5) * (t - t_6) * (t - t_6), + vel_t6 - jerk * (t_6 - t_5) * (t - t_6), + -jerk * (t_6 - t_5), + ) + elif t < t_8: + return ( + x_t8 - vel_t8 * (t_8 - t) - 0.5 * jerk * (t_8 - t) * (t_8 - t) * (t_8 - t) / 3, + vel_t8 + 0.5 * jerk * (t_8 - t) * (t_8 - t), + -jerk * (t_8 - t), + ) + else: + return x_t8 + vel_t8 * (t - t_8), vel_t8, 0.0 + + t_range = [0, 100] + time_stamps = np.arange(*t_range, 0.001) + trajectory_data = np.zeros((time_stamps.shape[0], 9)) + trajectory_data[:, 0] = time_stamps + for i in range(time_stamps.shape[0]): + ( + trajectory_data[i, 1], + trajectory_data[i, 3], + trajectory_data[i, 5], + ) = calc_longitudinal_state(time_stamps[i]) + np.savetxt("straight_line.csv", trajectory_data, delimiter=",") diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py new file mode 100644 index 0000000000000..6b477bb804ac9 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py @@ -0,0 +1,36 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import numpy as np +import python_simulator +from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model + +initial_error = np.array( + [0.001, 0.03, 0.01, -0.001, 0, 2 * python_simulator.measurement_steer_bias] +) + +save_dir = "test_python_sim" +python_simulator.slalom_drive(save_dir=save_dir, initial_error=initial_error) + +model_trainer = train_drive_NN_model.train_drive_NN_model() +model_trainer.add_data_from_csv(save_dir) +model_trainer.save_train_data(save_dir) +model_trainer.get_trained_model() +model_trainer.save_models(save_dir=save_dir) + +save_dir = "test_python_trained_sim" +load_dir = "test_python_sim" +python_simulator.slalom_drive( + save_dir=save_dir, load_dir=load_dir, use_trained_model=True, initial_error=initial_error +) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py new file mode 100644 index 0000000000000..3125719556559 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/run_sim.py @@ -0,0 +1,392 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore oneline + +import argparse +from enum import Enum +from importlib import reload as ir +import json +import os +import time +import traceback +from typing import Dict + +import numpy as np +import python_simulator +from smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model + +parser = argparse.ArgumentParser() +parser.add_argument("--param_name", default=None) +args = parser.parse_args() + +P1 = 0.8 +P2 = 1.2 + +USE_TRAINED_MODEL_DIFF = True +DATA_COLLECTION_MODE = "pp" # option: "pp": pure_pursuit, "ff": feed_forward, "mpc": smart_mpc +USE_POLYNOMIAL_REGRESSION = True +USE_SELECTED_POLYNOMIAL = True +FORCE_NN_MODEL_TO_ZERO = False + + +FIT_INTERCEPT = True # Should be True if FORCE_NN_MODEL_TO_ZERO is True +USE_INTERCEPT = False # Should be True if FORCE_NN_MODEL_TO_ZERO is True + + +class ChangeParam(Enum): + """Parameters to be changed when running the simulation.""" + + steer_bias = [ + -1.0 * np.pi / 180.0, + -0.8 * np.pi / 180.0, + -0.6 * np.pi / 180.0, + -0.4 * np.pi / 180.0, + -0.2 * np.pi / 180.0, + 0.0, + 0.2 * np.pi / 180.0, + 0.4 * np.pi / 180.0, + 0.6 * np.pi / 180.0, + 0.8 * np.pi / 180.0, + 1.0 * np.pi / 180.0, + ] + """steer midpoint (soft + hard)""" + + steer_rate_lim = [0.020, 0.050, 0.100, 0.150, 0.200, 0.300, 0.400, 0.500] + """Maximum steer angular velocity""" + + vel_rate_lim = [0.5, 1.0, 3.0, 5.0, 7.0, 9.0] + """Maximum acceleration/deceleration""" + + wheel_base = [0.5, 1.0, 1.5, 2.0, 3.0, 5.0, 7.0] + """wheel base""" + + steer_dead_band = [0.0000, 0.0012, 0.0025, 0.0050, 0.01] + """steer dead band""" + + adaptive_gear_ratio_coef = [ + [15.713, 0.053, 0.042, 15.713, 0.053, 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, 0.053, 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, 0.053, 0.042], + [15.713, 0.053, 0.042, 15.713, P1 * 0.053, 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, P1 * 0.053, 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, P1 * 0.053, 0.042], + [15.713, 0.053, 0.042, 15.713, P2 * 0.053, 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, P2 * 0.053, 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, P2 * 0.053, 0.042], + [15.713, 0.053, 0.042, 15.713, 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, 15.713, P1 * 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, P1 * 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, P1 * 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, 15.713, P2 * 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, P2 * 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, P2 * 0.053, P1 * 0.042], + [15.713, 0.053, 0.042, 15.713, 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, 15.713, P1 * 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, P1 * 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, P1 * 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, 15.713, P2 * 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, P1 * 15.713, P2 * 0.053, P2 * 0.042], + [15.713, 0.053, 0.042, P2 * 15.713, P2 * 0.053, P2 * 0.042], + ] + """velocity-dependent gear ratio""" + + acc_time_delay = [0.00, 0.1, 0.27, 0.40, 0.60, 0.80, 1.01] + """acc time delay""" + + steer_time_delay = [0.00, 0.1, 0.27, 0.40, 0.60, 0.80, 1.02] + """steer time delay""" + + acc_time_constant = [0.01, 0.1, 0.20, 0.24, 0.40, 0.60, 0.80, 1.01] + """time constant""" + + steer_time_constant = [0.01, 0.1, 0.20, 0.24, 0.40, 0.60, 0.80, 1.02] + """time constant""" + + accel_map_scale = [0.2, 0.5, 1.0, 2.0, 3.0, 4.0, 5.0] + """pedal - real acceleration correspondence""" + + acc_scaling = [0.2, 0.5, 1.0, 2.0, 3.0, 4.0, 5.01] + """Acceleration scaling coefficient""" + + steer_scaling = [0.2, 0.5, 1.0, 2.0, 3.0, 4.0, 5.02] + """Steer scaling coefficient""" + + vehicle_type = [1, 2, 3, 4] + """change to other vehicle parameters""" + + +def run_simulator(change_param: ChangeParam): + """Run the simulator.""" + # initialize parameters + print("reset sim_setting_json") + data: Dict[str, float] = {} + with open("sim_setting.json", "w") as f: + json.dump(data, f) + + param_val_list = change_param.value + start_time = time.time() + + for j in range(len(param_val_list)): + i = j + 0 + with open("sim_setting.json", "r") as f: + data = json.load(f) + + data[change_param.name] = param_val_list[j] + with open("sim_setting.json", "w") as f: + json.dump(data, f) + ir(python_simulator) + + try: + initial_error = np.array( + [0.001, 0.03, 0.01, -0.001, 0, 2 * python_simulator.measurement_steer_bias] + ) + if DATA_COLLECTION_MODE in ["ff", "pp"]: + if DATA_COLLECTION_MODE == "ff": + save_dir = "test_feedforward_sim" + change_param.name + str(i) + else: + save_dir = "test_pure_pursuit_sim" + change_param.name + str(i) + python_simulator.slalom_drive( + save_dir=save_dir, + control_type=DATA_COLLECTION_MODE, + t_range=[0, 200.0], + acc_width_range=0.005, + acc_period_range=[5.0, 20.0], + steer_width_range=0.005, + steer_period_range=[5.0, 20.0], + large_steer_width_range=0.05, + large_steer_period_range=[10.0, 20.0], + start_large_steer_time=150.0, + ) + if FORCE_NN_MODEL_TO_ZERO: + model_trainer = train_drive_NN_model.train_drive_NN_model() + else: + model_trainer = train_drive_NN_model.train_drive_NN_model( + alpha_1_for_polynomial_regression=0.1**5, + alpha_2_for_polynomial_regression=0.1**5, + ) + + model_trainer.add_data_from_csv(save_dir) + start_time_learning = time.time() + model_trainer.get_trained_model( + use_polynomial_reg=USE_POLYNOMIAL_REGRESSION, + use_selected_polynomial=USE_SELECTED_POLYNOMIAL, + force_NN_model_to_zero=FORCE_NN_MODEL_TO_ZERO, + fit_intercept=FIT_INTERCEPT, + use_intercept=USE_INTERCEPT, + ) + learning_computation_time = time.time() - start_time_learning + model_trainer.plot_trained_result(save_dir=save_dir) + model_trainer.save_models(save_dir=save_dir) + load_dir = save_dir + if DATA_COLLECTION_MODE == "ff": + save_dir = "test_python_ff_aided_sim_" + change_param.name + str(i) + elif DATA_COLLECTION_MODE == "pp": + save_dir = "test_python_pp_aided_sim_" + change_param.name + str(i) + auto_test_performance_result_list = python_simulator.slalom_drive( + load_dir=load_dir, + save_dir=save_dir, + use_trained_model=True, + use_trained_model_diff=USE_TRAINED_MODEL_DIFF, + initial_error=initial_error, + ) + + print("learning_computation_time:", learning_computation_time) + if DATA_COLLECTION_MODE == "ff": + f = open(save_dir + "/computational_time_learning_from_ff_data.txt", "w") + f.write(str(learning_computation_time)) + f.close() + f = open( + "auto_test_result_intermediate_model_control_trained_with_data_collected_by_ff_control.csv", + mode="a", + ) + elif DATA_COLLECTION_MODE == "pp": + f = open(save_dir + "/computational_time_learning_from_pp_data.txt", "w") + f.write(str(learning_computation_time)) + f.close() + f = open( + "auto_test_result_intermediate_model_control_trained_with_data_collected_by_pp_control.csv", + mode="a", + ) + else: + save_dir = "test_python_sim_" + change_param.name + str(i) + auto_test_performance_result_list = python_simulator.slalom_drive( + save_dir=save_dir, + initial_error=initial_error, + ) + f = open("auto_test_result_nominal_model_control.csv", mode="a") + + print( + change_param.name, + str(param_val_list[j]).replace(",", "_"), + *auto_test_performance_result_list, + sep=",", + file=f + ) + f.close() + + print(i, "auto_test_performance_result_list", auto_test_performance_result_list) + + skip_learning_for_developing_testcase = False + if not skip_learning_for_developing_testcase: + ir(train_drive_NN_model) + model_trainer = train_drive_NN_model.train_drive_NN_model() + learning_computation_time = None + if DATA_COLLECTION_MODE in ["ff", "pp"]: + model_trainer.add_data_from_csv(load_dir) + model_trainer.add_data_from_csv(save_dir) + start_time_learning = time.time() + model_trainer.update_saved_trained_model( + path=load_dir + "/model_for_test_drive.pth", + use_polynomial_reg=USE_POLYNOMIAL_REGRESSION, + use_selected_polynomial=USE_SELECTED_POLYNOMIAL, + force_NN_model_to_zero=FORCE_NN_MODEL_TO_ZERO, + fit_intercept=FIT_INTERCEPT, + use_intercept=USE_INTERCEPT, + ) + learning_computation_time = time.time() - start_time_learning + model_trainer.plot_trained_result(save_dir=save_dir) + model_trainer.save_models(save_dir=save_dir) + if DATA_COLLECTION_MODE == "ff": + load_dir = "test_python_ff_aided_sim_" + change_param.name + str(i) + save_dir = "test_python_ff_aided_sim_trained_" + change_param.name + str(i) + elif DATA_COLLECTION_MODE == "pp": + load_dir = "test_python_pp_aided_sim_" + change_param.name + str(i) + save_dir = "test_python_pp_aided_sim_trained_" + change_param.name + str(i) + else: + model_trainer.add_data_from_csv(save_dir) + start_time_learning = time.time() + model_trainer.get_trained_model( + use_polynomial_reg=USE_POLYNOMIAL_REGRESSION, + use_selected_polynomial=USE_SELECTED_POLYNOMIAL, + force_NN_model_to_zero=FORCE_NN_MODEL_TO_ZERO, + fit_intercept=FIT_INTERCEPT, + use_intercept=USE_INTERCEPT, + ) + learning_computation_time = time.time() - start_time_learning + model_trainer.plot_trained_result(save_dir=save_dir) + model_trainer.save_models(save_dir=save_dir) + + load_dir = "test_python_sim_" + change_param.name + str(i) + save_dir = "test_python_sim_trained_" + change_param.name + str(i) + auto_test_performance_result_list = python_simulator.slalom_drive( + load_dir=load_dir, + use_trained_model=True, + use_trained_model_diff=USE_TRAINED_MODEL_DIFF, + save_dir=save_dir, + initial_error=initial_error, + ) + print("learning_computation_time: ", learning_computation_time) + f = open(save_dir + "/test_info.txt", "w") + f.write("commit id: " + str(os.popen("git log --oneline -1").read()) + "\n") + f.write( + "computational_time_learning_from_total_data: " + + str(learning_computation_time) + + "\n" + ) + f.write("USE_TRAINED_MODEL_DIFF: " + str(USE_TRAINED_MODEL_DIFF) + "\n") + f.write("USE_POLYNOMIAL_REGRESSION: " + str(USE_POLYNOMIAL_REGRESSION) + "\n") + f.write("USE_SELECTED_POLYNOMIAL: " + str(USE_SELECTED_POLYNOMIAL) + "\n") + f.write("FORCE_NN_MODEL_TO_ZERO: " + str(FORCE_NN_MODEL_TO_ZERO) + "\n") + f.write("FIT_INTERCEPT: " + str(FIT_INTERCEPT) + "\n") + f.write("USE_INTERCEPT: " + str(USE_INTERCEPT) + "\n") + f.close() + + if DATA_COLLECTION_MODE == "ff": + f = open( + "auto_test_result_final_model_control_trained_with_data_collected_by_ff_control.csv", + mode="a", + ) + elif DATA_COLLECTION_MODE == "pp": + f = open( + "auto_test_result_final_model_control_trained_with_data_collected_by_pp_control.csv", + mode="a", + ) + else: + f = open( + "auto_test_result_final_model_control_trained_with_data_collected_by_nominal_control.csv", + mode="a", + ) + print( + change_param.name, + str(param_val_list[j]).replace(",", "_"), + *auto_test_performance_result_list, + sep=",", + file=f + ) + f.close() + print("experiment success") + except Exception: + print("# Catch Exception #") + print(traceback.print_exc()) + auto_test_performance_result_list = [1e16] * 11 + if DATA_COLLECTION_MODE == "ff": + f = open( + "auto_test_result_final_model_control_trained_with_data_collected_by_ff_control.csv", + mode="a", + ) + elif DATA_COLLECTION_MODE == "pp": + f = open( + "auto_test_result_final_model_control_trained_with_data_collected_by_pp_control.csv", + mode="a", + ) + else: + f = open( + "auto_test_result_final_model_control_trained_with_data_collected_by_nominal_control.csv", + mode="a", + ) + print( + change_param.name, + str(param_val_list[j]).replace(",", "_"), + *auto_test_performance_result_list, + sep=",", + file=f + ) + f.close() + print("experiment failure") + print("data:", data) + + print("total_time: ", time.time() - start_time) + + +def yes_no_input(): + """Let the user enter yes or no. Default is no.""" + choice = input("Please respond with 'yes' or 'no' [y/N]: ").lower() + if choice in ["y", "ye", "yes"]: + return True + return False + + +if __name__ == "__main__": + if args.param_name is None: + print("Do you want to run the simulation for all parameters at once?") + if yes_no_input(): + for _, change_param in ChangeParam.__members__.items(): + run_simulator(change_param) + else: + print("Enter the name of the parameter for which the simulation is to be run.") + input_string = input() + for name, change_param in ChangeParam.__members__.items(): + if name == input_string: + run_simulator(change_param) + break + else: + for name, change_param in ChangeParam.__members__.items(): + if name == args.param_name: + run_simulator(change_param) + break diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv new file mode 100644 index 0000000000000..e69c42e769d7a --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/python_simulator/slalom_course_data.csv @@ -0,0 +1,75014 @@ +0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.090909000094137687e-04,1.000000000000000021e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818181800018827537e-03,2.000000000000000042e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.727272700028241306e-03,2.999999999999999889e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636363600037655075e-03,4.000000000000000083e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.545454500047068844e-03,5.000000000000000278e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.454545400056482612e-03,5.999999999999999778e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.363636300065896381e-03,7.000000000000000666e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.272727200075310150e-03,8.000000000000000167e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.181818100084723919e-03,8.999999999999999667e-02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.090909000094137687e-03,1.000000000000000056e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.999999900103551456e-03,1.100000000000000006e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.090909080011296522e-02,1.199999999999999956e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.181818170012237899e-02,1.300000000000000044e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.272727260013179276e-02,1.400000000000000133e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.363636350014120653e-02,1.499999999999999944e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.454545440015062030e-02,1.600000000000000033e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.545454530016003407e-02,1.700000000000000122e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.636363620016944784e-02,1.799999999999999933e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.727272710017885987e-02,1.900000000000000022e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818181800018827537e-02,2.000000000000000111e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909090890019769088e-02,2.099999999999999922e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999999980020710638e-02,2.200000000000000011e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.090909070021652189e-02,2.300000000000000100e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.181818160022593739e-02,2.399999999999999911e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.272727250023535289e-02,2.500000000000000000e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.363636340024476840e-02,2.600000000000000089e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.454545430025418390e-02,2.700000000000000178e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.545454520026359940e-02,2.800000000000000266e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.636363610027301491e-02,2.899999999999999800e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.727272700028243041e-02,2.999999999999999889e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.818181790029184591e-02,3.099999999999999978e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.909090880030126142e-02,3.200000000000000067e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.999999970031067692e-02,3.300000000000000155e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.090909060032009242e-02,3.400000000000000244e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181818150032950793e-02,3.500000000000000333e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272727240033892343e-02,3.599999999999999867e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363636330034833893e-02,3.699999999999999956e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454545420035775444e-02,3.800000000000000044e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545454510036716994e-02,3.900000000000000133e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636363600037658544e-02,4.000000000000000222e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.727272690038600095e-02,4.100000000000000311e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.818181780039541645e-02,4.199999999999999845e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.909090870040483195e-02,4.299999999999999933e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.999999960041424746e-02,4.400000000000000022e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.090909050042366296e-02,4.500000000000000111e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.181818140043307847e-02,4.600000000000000200e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.272727230044249397e-02,4.700000000000000289e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.363636320045190947e-02,4.799999999999999822e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.454545410046132498e-02,4.899999999999999911e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.545454500047074048e-02,5.000000000000000000e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.636363590048015598e-02,5.100000000000000089e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.727272680048957149e-02,5.200000000000000178e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.818181770049898699e-02,5.300000000000000266e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.909090860050840249e-02,5.400000000000000355e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.999999950051781800e-02,5.500000000000000444e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.090909040052723350e-02,5.600000000000000533e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.181818130053664900e-02,5.700000000000000622e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.272727220054606451e-02,5.799999999999999600e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.363636310055548001e-02,5.899999999999999689e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.454545400056489551e-02,5.999999999999999778e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.545454490057431102e-02,6.099999999999999867e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.636363580058372652e-02,6.199999999999999956e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.727272670059314202e-02,6.300000000000000044e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.818181760060255753e-02,6.400000000000000133e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.909090850061197303e-02,6.500000000000000222e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.999999940062138853e-02,6.600000000000000311e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.090909030063080404e-02,6.700000000000000400e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.181818120064021954e-02,6.800000000000000488e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.272727210064962811e-02,6.900000000000000577e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.363636300065904361e-02,7.000000000000000666e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.454545390066845911e-02,7.099999999999999645e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.545454480067787462e-02,7.199999999999999734e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.636363570068729012e-02,7.299999999999999822e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.727272660069670562e-02,7.399999999999999911e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.818181750070612113e-02,7.500000000000000000e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.909090840071553663e-02,7.600000000000000089e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.999999930072495213e-02,7.700000000000000178e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.090909020073436764e-02,7.800000000000000266e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.181818110074378314e-02,7.900000000000000355e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.272727200075319864e-02,8.000000000000000444e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.363636290076261415e-02,8.100000000000000533e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.454545380077202965e-02,8.200000000000000622e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.545454470078144515e-02,8.300000000000000711e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.636363560079086066e-02,8.399999999999999689e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.727272650080027616e-02,8.499999999999999778e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.818181740080969166e-02,8.599999999999999867e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.909090830081910717e-02,8.699999999999999956e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.999999920082852267e-02,8.800000000000000044e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.090909010083793818e-02,8.900000000000000133e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.181818100084735368e-02,9.000000000000000222e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.272727190085676918e-02,9.100000000000000311e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.363636280086618469e-02,9.200000000000000400e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.454545370087560019e-02,9.300000000000000488e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.545454460088501569e-02,9.400000000000000577e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.636363550089443120e-02,9.500000000000000666e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.727272640090384670e-02,9.599999999999999645e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.818181730091326220e-02,9.699999999999999734e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.909090820092267771e-02,9.799999999999999822e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.999999910093209321e-02,9.899999999999999911e-01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.090909000094150871e-02,1.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.181818090095092422e-02,1.010000000000000009e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.272727180096033972e-02,1.020000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.363636270096975522e-02,1.030000000000000027e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.454545360097917073e-02,1.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.545454450098858623e-02,1.050000000000000044e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.636363540099800173e-02,1.060000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.727272630100741724e-02,1.070000000000000062e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.818181720101683274e-02,1.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.909090810102624824e-02,1.090000000000000080e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.999999900103566375e-02,1.100000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.009090899010450793e-01,1.110000000000000098e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.018181808010544948e-01,1.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.027272717010639103e-01,1.130000000000000115e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.036363626010733258e-01,1.140000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.045454535010827413e-01,1.150000000000000133e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.054545444010921568e-01,1.159999999999999920e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.063636353011015723e-01,1.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.072727262011109878e-01,1.179999999999999938e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.081818171011204033e-01,1.189999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.090909080011298188e-01,1.199999999999999956e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.099999989011392343e-01,1.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.109090898011486498e-01,1.219999999999999973e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.118181807011580653e-01,1.229999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.127272716011674808e-01,1.239999999999999991e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.136363625011768963e-01,1.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.145454534011863118e-01,1.260000000000000009e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.154545443011957273e-01,1.270000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.163636352012051428e-01,1.280000000000000027e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.172727261012145583e-01,1.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.181818170012239738e-01,1.300000000000000044e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.190909079012333893e-01,1.310000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.199999988012428048e-01,1.320000000000000062e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.209090897012522203e-01,1.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.218181806012616358e-01,1.340000000000000080e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.227272715012710513e-01,1.350000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.236363624012804668e-01,1.360000000000000098e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.245454533012898823e-01,1.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.254545442012992840e-01,1.380000000000000115e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.263636351013086856e-01,1.390000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.272727260013180872e-01,1.400000000000000133e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.281818169013274888e-01,1.409999999999999920e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.290909078013368905e-01,1.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.299999987013462921e-01,1.429999999999999938e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.309090896013556937e-01,1.439999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.318181805013650953e-01,1.449999999999999956e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.327272714013744970e-01,1.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.336363623013838986e-01,1.469999999999999973e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.345454532013933002e-01,1.479999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.354545441014027019e-01,1.489999999999999991e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.363636350014121035e-01,1.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.372727259014215051e-01,1.510000000000000009e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.381818168014309067e-01,1.520000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.390909077014403084e-01,1.530000000000000027e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.399999986014497100e-01,1.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.409090895014591116e-01,1.550000000000000044e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.418181804014685132e-01,1.560000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.427272713014779149e-01,1.570000000000000062e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.436363622014873165e-01,1.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.445454531014967181e-01,1.590000000000000080e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.454545440015061197e-01,1.600000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.463636349015155214e-01,1.610000000000000098e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.472727258015249230e-01,1.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.481818167015343246e-01,1.630000000000000115e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.490909076015437262e-01,1.640000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.499999985015531279e-01,1.650000000000000133e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.509090894015625295e-01,1.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.518181803015719311e-01,1.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.527272712015813327e-01,1.679999999999999938e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.536363621015907344e-01,1.689999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.545454530016001360e-01,1.699999999999999956e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.554545439016095376e-01,1.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.563636348016189392e-01,1.719999999999999973e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.572727257016283409e-01,1.729999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.581818166016377425e-01,1.739999999999999991e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.590909075016471441e-01,1.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.599999984016565457e-01,1.760000000000000009e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.609090893016659474e-01,1.770000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.618181802016753490e-01,1.780000000000000027e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.627272711016847506e-01,1.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.636363620016941522e-01,1.800000000000000044e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.645454529017035539e-01,1.810000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.654545438017129555e-01,1.820000000000000062e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.663636347017223571e-01,1.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.672727256017317587e-01,1.840000000000000080e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.681818165017411604e-01,1.850000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.690909074017505620e-01,1.860000000000000098e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.699999983017599636e-01,1.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.709090892017693653e-01,1.880000000000000115e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.718181801017787669e-01,1.890000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.727272710017881685e-01,1.900000000000000133e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.736363619017975701e-01,1.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.745454528018069718e-01,1.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.754545437018163734e-01,1.929999999999999938e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.763636346018257750e-01,1.939999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.772727255018351766e-01,1.949999999999999956e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.781818164018445783e-01,1.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.790909073018539799e-01,1.969999999999999973e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.799999982018633815e-01,1.979999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.809090891018727831e-01,1.989999999999999991e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818181800018821848e-01,2.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.827272709018915864e-01,2.010000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.836363618019009880e-01,2.020000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.845454527019103896e-01,2.030000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.854545436019197913e-01,2.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.863636345019291929e-01,2.049999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.872727254019385945e-01,2.060000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.881818163019479961e-01,2.069999999999999840e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.890909072019573978e-01,2.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.899999981019667994e-01,2.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909090890019762010e-01,2.100000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.918181799019856026e-01,2.109999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.927272708019950043e-01,2.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.936363617020044059e-01,2.129999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.945454526020138075e-01,2.140000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.954545435020232091e-01,2.149999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.963636344020326108e-01,2.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.972727253020420124e-01,2.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.981818162020514140e-01,2.180000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.990909071020608156e-01,2.189999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999999980020702173e-01,2.200000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.009090889020796189e-01,2.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.018181798020890205e-01,2.220000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.027272707020984222e-01,2.229999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.036363616021078238e-01,2.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.045454525021172254e-01,2.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.054545434021266270e-01,2.260000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.063636343021360287e-01,2.270000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.072727252021454303e-01,2.280000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.081818161021548319e-01,2.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.090909070021642335e-01,2.300000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.099999979021736352e-01,2.310000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.109090888021830368e-01,2.319999999999999840e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.118181797021924384e-01,2.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.127272706022018400e-01,2.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.136363615022112417e-01,2.350000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.145454524022206433e-01,2.359999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.154545433022300449e-01,2.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.163636342022394465e-01,2.379999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.172727251022488482e-01,2.390000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.181818160022582498e-01,2.399999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.190909069022676514e-01,2.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.199999978022770530e-01,2.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.209090887022864547e-01,2.430000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.218181796022958563e-01,2.439999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.227272705023052579e-01,2.450000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.236363614023146595e-01,2.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.245454523023240612e-01,2.470000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.254545432023334628e-01,2.479999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.263636341023428644e-01,2.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.272727250023522660e-01,2.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.281818159023616677e-01,2.510000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.290909068023710693e-01,2.520000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.299999977023804709e-01,2.530000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.309090886023898725e-01,2.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.318181795023992742e-01,2.550000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.327272704024086758e-01,2.560000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.336363613024180774e-01,2.569999999999999840e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.345454522024274790e-01,2.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.354545431024368807e-01,2.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.363636340024462823e-01,2.600000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.372727249024556839e-01,2.609999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.381818158024650856e-01,2.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.390909067024744872e-01,2.629999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.399999976024838888e-01,2.640000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.409090885024932904e-01,2.649999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.418181794025026921e-01,2.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.427272703025120937e-01,2.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.436363612025214953e-01,2.680000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.445454521025308969e-01,2.689999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.454545430025402986e-01,2.700000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.463636339025497002e-01,2.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.472727248025591018e-01,2.720000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.481818157025685034e-01,2.729999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.490909066025779051e-01,2.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.499999975025873067e-01,2.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.509090884025967361e-01,2.760000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.518181793026061377e-01,2.770000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.527272702026155393e-01,2.780000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.536363611026249409e-01,2.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.545454520026343426e-01,2.800000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.554545429026437442e-01,2.810000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.563636338026531458e-01,2.819999999999999840e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.572727247026625474e-01,2.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.581818156026719491e-01,2.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.590909065026813507e-01,2.850000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.599999974026907523e-01,2.859999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.609090883027001539e-01,2.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.618181792027095556e-01,2.879999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.627272701027189572e-01,2.890000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.636363610027283588e-01,2.899999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.645454519027377605e-01,2.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.654545428027471621e-01,2.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.663636337027565637e-01,2.930000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.672727246027659653e-01,2.939999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.681818155027753670e-01,2.950000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.690909064027847686e-01,2.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.699999973027941702e-01,2.970000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.709090882028035718e-01,2.979999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.718181791028129735e-01,2.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.727272700028223751e-01,3.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.736363609028317767e-01,3.010000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.745454518028411783e-01,3.020000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.754545427028505800e-01,3.030000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.763636336028599816e-01,3.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.772727245028693832e-01,3.050000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.781818154028787848e-01,3.060000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.790909063028881865e-01,3.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.799999972028975881e-01,3.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.809090881029069897e-01,3.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.818181790029163913e-01,3.100000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.827272699029257930e-01,3.109999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.836363608029351946e-01,3.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.845454517029445962e-01,3.129999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.854545426029539978e-01,3.140000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.863636335029633995e-01,3.149999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.872727244029728011e-01,3.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.881818153029822027e-01,3.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.890909062029916043e-01,3.180000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.899999971030010060e-01,3.189999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.909090880030104076e-01,3.200000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.918181789030198092e-01,3.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.927272698030292108e-01,3.220000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.936363607030386125e-01,3.229999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.945454516030480141e-01,3.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.954545425030574157e-01,3.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.963636334030668174e-01,3.260000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.972727243030762190e-01,3.270000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.981818152030856206e-01,3.280000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.990909061030950222e-01,3.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.999999970031044239e-01,3.300000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.009090879031138255e-01,3.310000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.018181788031232271e-01,3.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.027272697031326287e-01,3.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.036363606031420304e-01,3.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.045454515031514320e-01,3.350000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.054545424031608336e-01,3.359999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.063636333031702352e-01,3.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.072727242031796369e-01,3.379999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.081818151031890385e-01,3.390000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.090909060031984401e-01,3.399999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.099999969032078417e-01,3.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.109090878032172434e-01,3.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.118181787032266450e-01,3.430000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127272696032360466e-01,3.439999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136363605032454482e-01,3.450000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145454514032548499e-01,3.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154545423032642515e-01,3.470000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163636332032736531e-01,3.479999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172727241032830547e-01,3.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181818150032924564e-01,3.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190909059033018580e-01,3.510000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199999968033112596e-01,3.520000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209090877033206612e-01,3.530000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218181786033300629e-01,3.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227272695033394645e-01,3.550000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236363604033488661e-01,3.560000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245454513033582677e-01,3.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254545422033676694e-01,3.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263636331033770710e-01,3.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272727240033864726e-01,3.600000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281818149033958742e-01,3.609999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290909058034052759e-01,3.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299999967034146775e-01,3.629999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309090876034240791e-01,3.640000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318181785034334808e-01,3.649999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327272694034428824e-01,3.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336363603034522840e-01,3.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345454512034616856e-01,3.680000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354545421034710873e-01,3.689999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363636330034804889e-01,3.700000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372727239034898905e-01,3.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381818148034992921e-01,3.720000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390909057035086938e-01,3.729999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399999966035180954e-01,3.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409090875035274970e-01,3.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418181784035368986e-01,3.760000000000000231e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427272693035463003e-01,3.770000000000000018e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436363602035557019e-01,3.780000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445454511035651035e-01,3.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454545420035745051e-01,3.800000000000000266e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463636329035839068e-01,3.810000000000000053e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472727238035933084e-01,3.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481818147036027100e-01,3.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490909056036121116e-01,3.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499999965036215133e-01,3.850000000000000089e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509090874036309149e-01,3.859999999999999876e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518181783036403165e-01,3.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527272692036497181e-01,3.879999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536363601036591198e-01,3.890000000000000124e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545454510036685214e-01,3.899999999999999911e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554545419036779230e-01,3.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563636328036873246e-01,3.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572727237036967263e-01,3.930000000000000160e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581818146037061279e-01,3.939999999999999947e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590909055037155295e-01,3.950000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599999964037249311e-01,3.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609090873037343328e-01,3.970000000000000195e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618181782037437344e-01,3.979999999999999982e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627272691037531360e-01,3.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636363600037625377e-01,4.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645454509037719393e-01,4.009999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654545418037813409e-01,4.020000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663636327037907425e-01,4.030000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672727236038001442e-01,4.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.681818145038095458e-01,4.049999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.690909054038189474e-01,4.060000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.699999963038283490e-01,4.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.709090872038377507e-01,4.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.718181781038471523e-01,4.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.727272690038565539e-01,4.099999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.736363599038659555e-01,4.110000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.745454508038753572e-01,4.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.754545417038847588e-01,4.129999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.763636326038941604e-01,4.139999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.772727235039035620e-01,4.150000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.781818144039129637e-01,4.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.790909053039223653e-01,4.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.799999962039317669e-01,4.179999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.809090871039411685e-01,4.190000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.818181780039505702e-01,4.200000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.827272689039599718e-01,4.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.836363598039693734e-01,4.219999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.845454507039787750e-01,4.230000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.854545416039881767e-01,4.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.863636325039975783e-01,4.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.872727234040069799e-01,4.259999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.881818143040163815e-01,4.270000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.890909052040257832e-01,4.280000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.899999961040351848e-01,4.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.909090870040445864e-01,4.299999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.918181779040539880e-01,4.310000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.927272688040633897e-01,4.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.936363597040727913e-01,4.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.945454506040821929e-01,4.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.954545415040915946e-01,4.350000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.963636324041009962e-01,4.360000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.972727233041103978e-01,4.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.981818142041197994e-01,4.379999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.990909051041292011e-01,4.389999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.999999960041386027e-01,4.400000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.009090869041480043e-01,4.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.018181778041574059e-01,4.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.027272687041668076e-01,4.429999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.036363596041762092e-01,4.440000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.045454505041856108e-01,4.450000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.054545414041950124e-01,4.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.063636323042044141e-01,4.469999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.072727232042138157e-01,4.480000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.081818141042232173e-01,4.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.090909050042326189e-01,4.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.099999959042420206e-01,4.509999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.109090868042514222e-01,4.520000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.118181777042608238e-01,4.530000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.127272686042702254e-01,4.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.136363595042796271e-01,4.549999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.145454504042890287e-01,4.560000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.154545413042984303e-01,4.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.163636322043078319e-01,4.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.172727231043172336e-01,4.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.181818140043266352e-01,4.600000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.190909049043360368e-01,4.610000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.199999958043454384e-01,4.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.209090867043548401e-01,4.629999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.218181776043642417e-01,4.639999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.227272685043736433e-01,4.650000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.236363594043830449e-01,4.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.245454503043924466e-01,4.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.254545412044018482e-01,4.679999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.263636321044112498e-01,4.690000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.272727230044206514e-01,4.700000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.281818139044300531e-01,4.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.290909048044394547e-01,4.719999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.299999957044488563e-01,4.730000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.309090866044582580e-01,4.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.318181775044676596e-01,4.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.327272684044770612e-01,4.759999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.336363593044864628e-01,4.770000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.345454502044958645e-01,4.780000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.354545411045052661e-01,4.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.363636320045146677e-01,4.799999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.372727229045240693e-01,4.810000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.381818138045334710e-01,4.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.390909047045428726e-01,4.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.399999956045522742e-01,4.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.409090865045616758e-01,4.850000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.418181774045710775e-01,4.860000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.427272683045804791e-01,4.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.436363592045898807e-01,4.879999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.445454501045992823e-01,4.889999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.454545410046086840e-01,4.900000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.463636319046180856e-01,4.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.472727228046274872e-01,4.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.481818137046368888e-01,4.929999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.490909046046462905e-01,4.940000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.499999955046556921e-01,4.950000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.509090864046650937e-01,4.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.518181773046744953e-01,4.969999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.527272682046838970e-01,4.980000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.536363591046932986e-01,4.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.545454500047027002e-01,5.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.554545409047121018e-01,5.009999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.563636318047215035e-01,5.020000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.572727227047309051e-01,5.030000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.581818136047403067e-01,5.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.590909045047497083e-01,5.049999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.599999954047591100e-01,5.060000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.609090863047685116e-01,5.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.618181772047779132e-01,5.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.627272681047873149e-01,5.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.636363590047967165e-01,5.100000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.645454499048061181e-01,5.110000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.654545408048155197e-01,5.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.663636317048249214e-01,5.129999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.672727226048343230e-01,5.139999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.681818135048437246e-01,5.150000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.690909044048531262e-01,5.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.699999953048625279e-01,5.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.709090862048719295e-01,5.179999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.718181771048813311e-01,5.190000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.727272680048907327e-01,5.200000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.736363589049001344e-01,5.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.745454498049095360e-01,5.219999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.754545407049189376e-01,5.230000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.763636316049283392e-01,5.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.772727225049377409e-01,5.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.781818134049471425e-01,5.259999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.790909043049565441e-01,5.270000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.799999952049659457e-01,5.280000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.809090861049753474e-01,5.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.818181770049847490e-01,5.299999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.827272679049941506e-01,5.310000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.836363588050035522e-01,5.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.845454497050129539e-01,5.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.854545406050223555e-01,5.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.863636315050317571e-01,5.350000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.872727224050411587e-01,5.360000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.881818133050505604e-01,5.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.890909042050599620e-01,5.379999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.899999951050693636e-01,5.389999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.909090860050787652e-01,5.400000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.918181769050881669e-01,5.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.927272678050975685e-01,5.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.936363587051069701e-01,5.429999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.945454496051163717e-01,5.440000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.954545405051257734e-01,5.450000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.963636314051351750e-01,5.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.972727223051445766e-01,5.469999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.981818132051539783e-01,5.480000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.990909041051633799e-01,5.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.999999950051727815e-01,5.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.009090859051822386e-01,5.509999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.018181768051916958e-01,5.520000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.027272677052011529e-01,5.530000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.036363586052106101e-01,5.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.045454495052200672e-01,5.549999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.054545404052295243e-01,5.560000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.063636313052389815e-01,5.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.072727222052484386e-01,5.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.081818131052578957e-01,5.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.090909040052673529e-01,5.600000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.099999949052768100e-01,5.610000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.109090858052862671e-01,5.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.118181767052957243e-01,5.629999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.127272676053051814e-01,5.639999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.136363585053146386e-01,5.650000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.145454494053240957e-01,5.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.154545403053335528e-01,5.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.163636312053430100e-01,5.679999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.172727221053524671e-01,5.690000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.181818130053619242e-01,5.700000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.190909039053713814e-01,5.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.199999948053808385e-01,5.719999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.209090857053902957e-01,5.730000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.218181766053997528e-01,5.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.227272675054092099e-01,5.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.236363584054186671e-01,5.759999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.245454493054281242e-01,5.770000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.254545402054375813e-01,5.780000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.263636311054470385e-01,5.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.272727220054564956e-01,5.799999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.281818129054659527e-01,5.810000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.290909038054754099e-01,5.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.299999947054848670e-01,5.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.309090856054943242e-01,5.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.318181765055037813e-01,5.850000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.327272674055132384e-01,5.860000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.336363583055226956e-01,5.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.345454492055321527e-01,5.879999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.354545401055416098e-01,5.889999999999999680e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.363636310055510670e-01,5.900000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.372727219055605241e-01,5.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.381818128055699813e-01,5.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.390909037055794384e-01,5.929999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.399999946055888955e-01,5.940000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.409090855055983527e-01,5.950000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.418181764056078098e-01,5.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.427272673056172669e-01,5.969999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.436363582056267241e-01,5.980000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.445454491056361812e-01,5.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.454545400056456383e-01,6.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.463636309056550955e-01,6.009999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.472727218056645526e-01,6.020000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.481818127056740098e-01,6.030000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.490909036056834669e-01,6.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.499999945056929240e-01,6.049999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.509090854057023812e-01,6.060000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.518181763057118383e-01,6.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.527272672057212954e-01,6.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.536363581057307526e-01,6.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.545454490057402097e-01,6.100000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.554545399057496669e-01,6.110000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.563636308057591240e-01,6.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.572727217057685811e-01,6.129999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.581818126057780383e-01,6.140000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.590909035057874954e-01,6.150000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.599999944057969525e-01,6.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.609090853058064097e-01,6.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.618181762058158668e-01,6.179999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.627272671058253239e-01,6.190000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.636363580058347811e-01,6.200000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.645454489058442382e-01,6.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.654545398058536954e-01,6.219999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.663636307058631525e-01,6.230000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.672727216058726096e-01,6.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.681818125058820668e-01,6.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.690909034058915239e-01,6.259999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.699999943059009810e-01,6.270000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.709090852059104382e-01,6.280000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.718181761059198953e-01,6.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.727272670059293525e-01,6.299999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.736363579059388096e-01,6.310000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.745454488059482667e-01,6.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.754545397059577239e-01,6.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.763636306059671810e-01,6.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.772727215059766381e-01,6.350000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.781818124059860953e-01,6.360000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.790909033059955524e-01,6.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.799999942060050095e-01,6.379999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.809090851060144667e-01,6.390000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.818181760060239238e-01,6.400000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.827272669060333810e-01,6.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.836363578060428381e-01,6.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.845454487060522952e-01,6.429999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.854545396060617524e-01,6.440000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.863636305060712095e-01,6.450000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.872727214060806666e-01,6.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.881818123060901238e-01,6.469999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.890909032060995809e-01,6.480000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.899999941061090381e-01,6.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.909090850061184952e-01,6.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.918181759061279523e-01,6.509999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.927272668061374095e-01,6.520000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.936363577061468666e-01,6.530000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.945454486061563237e-01,6.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.954545395061657809e-01,6.549999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.963636304061752380e-01,6.560000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.972727213061846951e-01,6.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.981818122061941523e-01,6.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.990909031062036094e-01,6.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.999999940062130666e-01,6.600000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.009090849062225237e-01,6.610000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.018181758062319808e-01,6.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.027272667062414380e-01,6.629999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.036363576062508951e-01,6.640000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.045454485062603522e-01,6.650000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.054545394062698094e-01,6.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.063636303062792665e-01,6.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.072727212062887236e-01,6.679999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.081818121062981808e-01,6.690000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.090909030063076379e-01,6.700000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.099999939063170951e-01,6.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.109090848063265522e-01,6.719999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.118181757063360093e-01,6.730000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.127272666063454665e-01,6.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.136363575063549236e-01,6.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.145454484063643807e-01,6.759999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.154545393063738379e-01,6.770000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.163636302063832950e-01,6.780000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.172727211063927522e-01,6.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.181818120064022093e-01,6.799999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.190909029064116664e-01,6.810000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.199999938064211236e-01,6.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.209090847064305807e-01,6.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.218181756064400378e-01,6.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.227272665064494950e-01,6.850000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.236363574064589521e-01,6.860000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.245454483064684092e-01,6.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.254545392064778664e-01,6.879999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.263636301064873235e-01,6.890000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.272727210064967807e-01,6.900000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.281818119065062378e-01,6.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.290909028065156949e-01,6.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.299999937065251521e-01,6.929999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.309090846065346092e-01,6.940000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.318181755065440663e-01,6.950000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.327272664065535235e-01,6.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.336363573065629806e-01,6.969999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.345454482065724378e-01,6.980000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.354545391065818949e-01,6.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.363636300065913520e-01,7.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.372727209066008092e-01,7.009999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.381818118066102663e-01,7.020000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.390909027066197234e-01,7.030000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.399999936066291806e-01,7.040000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.409090845066386377e-01,7.049999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.418181754066480948e-01,7.060000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.427272663066575520e-01,7.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.436363572066670091e-01,7.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.445454481066764663e-01,7.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.454545390066859234e-01,7.100000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.463636299066953805e-01,7.110000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.472727208067048377e-01,7.120000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.481818117067142948e-01,7.129999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.490909026067237519e-01,7.140000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.499999935067332091e-01,7.150000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.509090844067426662e-01,7.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.518181753067521234e-01,7.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.527272662067615805e-01,7.179999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.536363571067710376e-01,7.190000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.545454480067804948e-01,7.200000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.554545389067899519e-01,7.209999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.563636298067994090e-01,7.219999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.572727207068088662e-01,7.230000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.581818116068183233e-01,7.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.590909025068277804e-01,7.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.599999934068372376e-01,7.259999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.609090843068466947e-01,7.270000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.618181752068561519e-01,7.280000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.627272661068656090e-01,7.290000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.636363570068750661e-01,7.299999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.645454479068845233e-01,7.310000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.654545388068939804e-01,7.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.663636297069034375e-01,7.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.672727206069128947e-01,7.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.681818115069223518e-01,7.350000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.690909024069318090e-01,7.360000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.699999933069412661e-01,7.370000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.709090842069507232e-01,7.379999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.718181751069601804e-01,7.390000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.727272660069696375e-01,7.400000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.736363569069790946e-01,7.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.745454478069885518e-01,7.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.754545387069980089e-01,7.429999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.763636296070074660e-01,7.440000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.772727205070169232e-01,7.450000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.781818114070263803e-01,7.459999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.790909023070358375e-01,7.469999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.799999932070452946e-01,7.480000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.809090841070547517e-01,7.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.818181750070642089e-01,7.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.827272659070736660e-01,7.509999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.836363568070831231e-01,7.520000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.845454477070925803e-01,7.530000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.854545386071020374e-01,7.540000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.863636295071114946e-01,7.549999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.872727204071209517e-01,7.560000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.881818113071304088e-01,7.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.890909022071398660e-01,7.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.899999931071493231e-01,7.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.909090840071587802e-01,7.600000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.918181749071682374e-01,7.610000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.927272658071776945e-01,7.620000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.936363567071871516e-01,7.629999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.945454476071966088e-01,7.640000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.954545385072060659e-01,7.650000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.963636294072155231e-01,7.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.972727203072249802e-01,7.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.981818112072344373e-01,7.679999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.990909021072438945e-01,7.690000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +6.999999930072533516e-01,7.700000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.009090839072628087e-01,7.709999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.018181748072722659e-01,7.719999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.027272657072817230e-01,7.730000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.036363566072911802e-01,7.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.045454475073006373e-01,7.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.054545384073100944e-01,7.759999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.063636293073195516e-01,7.770000000000000462e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.072727202073290087e-01,7.780000000000000249e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.081818111073384658e-01,7.790000000000000036e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.090909020073479230e-01,7.799999999999999822e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.099999929073573801e-01,7.810000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.109090838073668372e-01,7.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.118181747073762944e-01,7.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.127272656073857515e-01,7.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.136363565073952087e-01,7.850000000000000533e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.145454474074046658e-01,7.860000000000000320e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.154545383074141229e-01,7.870000000000000107e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.163636292074235801e-01,7.879999999999999893e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.172727201074330372e-01,7.890000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.181818110074424943e-01,7.900000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.190909019074519515e-01,7.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.199999928074614086e-01,7.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.209090837074708658e-01,7.930000000000000604e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.218181746074803229e-01,7.940000000000000391e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.227272655074897800e-01,7.950000000000000178e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.236363564074992372e-01,7.959999999999999964e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.245454473075086943e-01,7.969999999999999751e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.254545382075181514e-01,7.980000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.263636291075276086e-01,7.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.272727200075370657e-01,8.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.281818109075465228e-01,8.009999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.290909018075559800e-01,8.019999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.299999927075654371e-01,8.029999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.309090836075748943e-01,8.040000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.318181745075843514e-01,8.050000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.327272654075938085e-01,8.060000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.336363563076032657e-01,8.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.345454472076127228e-01,8.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.354545381076221799e-01,8.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.363636290076316371e-01,8.099999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.372727199076410942e-01,8.109999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.381818108076505514e-01,8.120000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.390909017076600085e-01,8.130000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.399999926076694656e-01,8.140000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.409090835076789228e-01,8.150000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.418181744076883799e-01,8.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.427272653076978370e-01,8.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.436363562077072942e-01,8.179999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.445454471077167513e-01,8.189999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.454545380077262084e-01,8.199999999999999289e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.463636289077356656e-01,8.210000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.472727198077451227e-01,8.220000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.481818107077545799e-01,8.230000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.490909016077640370e-01,8.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.499999925077734941e-01,8.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.509090834077829513e-01,8.259999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.518181743077924084e-01,8.269999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.527272652078018655e-01,8.279999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.536363561078113227e-01,8.290000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.545454470078207798e-01,8.300000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.554545379078302370e-01,8.310000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.563636288078396941e-01,8.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.572727197078491512e-01,8.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.581818106078586084e-01,8.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.590909015078680655e-01,8.349999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.599999924078775226e-01,8.359999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.609090833078869798e-01,8.370000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.618181742078964369e-01,8.380000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.627272651079058940e-01,8.390000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.636363560079153512e-01,8.400000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.645454469079248083e-01,8.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.654545378079342655e-01,8.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.663636287079437226e-01,8.429999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.672727196079531797e-01,8.439999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.681818105079626369e-01,8.449999999999999289e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.690909014079720940e-01,8.460000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.699999923079815511e-01,8.470000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.709090832079910083e-01,8.480000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.718181741080004654e-01,8.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.727272650080099226e-01,8.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.736363559080193797e-01,8.509999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.745454468080288368e-01,8.519999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.754545377080382940e-01,8.529999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.763636286080477511e-01,8.540000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.772727195080572082e-01,8.550000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.781818104080666654e-01,8.560000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.790909013080761225e-01,8.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.799999922080855796e-01,8.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.809090831080950368e-01,8.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.818181740081044939e-01,8.599999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.827272649081139511e-01,8.609999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.836363558081234082e-01,8.620000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.845454467081328653e-01,8.630000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.854545376081423225e-01,8.640000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.863636285081517796e-01,8.650000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.872727194081612367e-01,8.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.881818103081706939e-01,8.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.890909012081801510e-01,8.679999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.899999921081896082e-01,8.689999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.909090830081990653e-01,8.700000000000001066e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.918181739082085224e-01,8.710000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.927272648082179796e-01,8.720000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.936363557082274367e-01,8.730000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.945454466082368938e-01,8.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.954545375082463510e-01,8.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.963636284082558081e-01,8.759999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.972727193082652652e-01,8.769999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.981818102082747224e-01,8.779999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.990909011082841795e-01,8.790000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +7.999999920082936367e-01,8.800000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.009090829083030938e-01,8.810000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.018181738083125509e-01,8.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.027272647083220081e-01,8.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.036363556083314652e-01,8.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.045454465083409223e-01,8.849999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.054545374083503795e-01,8.859999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.063636283083598366e-01,8.870000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.072727192083692938e-01,8.880000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.081818101083787509e-01,8.890000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.090909010083882080e-01,8.900000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.099999919083976652e-01,8.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.109090828084071223e-01,8.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.118181737084165794e-01,8.929999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.127272646084260366e-01,8.939999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.136363555084354937e-01,8.950000000000001066e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.145454464084449508e-01,8.960000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.154545373084544080e-01,8.970000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.163636282084638651e-01,8.980000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.172727191084733223e-01,8.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.181818100084827794e-01,9.000000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.190909009084922365e-01,9.009999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.199999918085016937e-01,9.019999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.209090827085111508e-01,9.029999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.218181736085206079e-01,9.040000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.227272645085300651e-01,9.050000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.236363554085395222e-01,9.060000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.245454463085489794e-01,9.070000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.254545372085584365e-01,9.080000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.263636281085678936e-01,9.089999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.272727190085773508e-01,9.099999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.281818099085868079e-01,9.109999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.290909008085962650e-01,9.120000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.299999917086057222e-01,9.130000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.309090826086151793e-01,9.140000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.318181735086246364e-01,9.150000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.327272644086340936e-01,9.160000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.336363553086435507e-01,9.169999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.345454462086530079e-01,9.179999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.354545371086624650e-01,9.189999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.363636280086719221e-01,9.200000000000001066e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.372727189086813793e-01,9.210000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.381818098086908364e-01,9.220000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.390909007087002935e-01,9.230000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.399999916087097507e-01,9.240000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.409090825087192078e-01,9.250000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.418181734087286650e-01,9.259999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.427272643087381221e-01,9.269999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.436363552087475792e-01,9.279999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.445454461087570364e-01,9.290000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.454545370087664935e-01,9.300000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.463636279087759506e-01,9.310000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.472727188087854078e-01,9.320000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.481818097087948649e-01,9.330000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.490909006088043220e-01,9.339999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.499999915088137792e-01,9.349999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.509090824088232363e-01,9.359999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.518181733088326935e-01,9.370000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.527272642088421506e-01,9.380000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.536363551088516077e-01,9.390000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.545454460088610649e-01,9.400000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.554545369088705220e-01,9.410000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.563636278088799791e-01,9.419999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.572727187088894363e-01,9.429999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.581818096088988934e-01,9.439999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.590909005089083506e-01,9.450000000000001066e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.599999914089178077e-01,9.460000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.609090823089272648e-01,9.470000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.618181732089367220e-01,9.480000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.627272641089461791e-01,9.490000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.636363550089556362e-01,9.500000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.645454459089650934e-01,9.509999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.654545368089745505e-01,9.519999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.663636277089840076e-01,9.529999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.672727186089934648e-01,9.540000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.681818095090029219e-01,9.550000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.690909004090123791e-01,9.560000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.699999913090218362e-01,9.570000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.709090822090312933e-01,9.580000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.718181731090407505e-01,9.589999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.727272640090502076e-01,9.599999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.736363549090596647e-01,9.609999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.745454458090691219e-01,9.620000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.754545367090785790e-01,9.630000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.763636276090880362e-01,9.640000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.772727185090974933e-01,9.650000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.781818094091069504e-01,9.660000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.790909003091164076e-01,9.669999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.799999912091258647e-01,9.679999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.809090821091353218e-01,9.689999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.818181730091447790e-01,9.700000000000001066e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.827272639091542361e-01,9.710000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.836363548091636932e-01,9.720000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.845454457091731504e-01,9.730000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.854545366091826075e-01,9.740000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.863636275091920647e-01,9.750000000000000000e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.872727184092015218e-01,9.759999999999999787e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.881818093092109789e-01,9.769999999999999574e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.890909002092204361e-01,9.779999999999999361e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.899999911092298932e-01,9.790000000000000924e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.909090820092393503e-01,9.800000000000000711e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.918181729092488075e-01,9.810000000000000497e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.927272638092582646e-01,9.820000000000000284e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.936363547092677218e-01,9.830000000000000071e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.945454456092771789e-01,9.839999999999999858e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.954545365092866360e-01,9.849999999999999645e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.963636274092960932e-01,9.859999999999999432e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.972727183093055503e-01,9.870000000000000995e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.981818092093150074e-01,9.880000000000000782e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.990909001093244646e-01,9.890000000000000568e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.999999910093339217e-01,9.900000000000000355e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.009090819093433788e-01,9.910000000000000142e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.018181728093528360e-01,9.919999999999999929e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.027272637093622931e-01,9.929999999999999716e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.036363546093717503e-01,9.939999999999999503e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.045454455093812074e-01,9.950000000000001066e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.054545364093906645e-01,9.960000000000000853e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.063636273094001217e-01,9.970000000000000639e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.072727182094095788e-01,9.980000000000000426e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.081818091094190359e-01,9.990000000000000213e+00,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.090909000094284931e-01,1.000000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.099999909094379502e-01,1.000999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.109090818094474074e-01,1.001999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.118181727094568645e-01,1.002999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.127272636094663216e-01,1.004000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.136363545094757788e-01,1.005000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.145454454094852359e-01,1.006000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.154545363094946930e-01,1.007000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.163636272095041502e-01,1.008000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.172727181095136073e-01,1.008999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.181818090095230644e-01,1.009999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.190908999095325216e-01,1.010999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.199999908095419787e-01,1.012000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.209090817095514359e-01,1.013000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.218181726095608930e-01,1.014000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.227272635095703501e-01,1.015000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.236363544095798073e-01,1.016000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.245454453095892644e-01,1.016999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.254545362095987215e-01,1.017999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.263636271096081787e-01,1.018999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.272727180096176358e-01,1.020000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.281818089096270930e-01,1.021000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.290908998096365501e-01,1.022000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.299999907096460072e-01,1.023000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.309090816096554644e-01,1.024000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.318181725096649215e-01,1.025000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.327272634096743786e-01,1.025999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.336363543096838358e-01,1.026999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.345454452096932929e-01,1.027999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.354545361097027500e-01,1.029000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.363636270097122072e-01,1.030000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.372727179097216643e-01,1.031000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.381818088097311215e-01,1.032000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.390908997097405786e-01,1.033000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.399999906097500357e-01,1.033999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.409090815097594929e-01,1.034999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.418181724097689500e-01,1.035999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.427272633097784071e-01,1.037000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.436363542097878643e-01,1.038000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.445454451097973214e-01,1.039000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.454545360098067786e-01,1.040000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.463636269098162357e-01,1.041000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.472727178098256928e-01,1.041999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.481818087098351500e-01,1.042999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.490908996098446071e-01,1.043999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.499999905098540642e-01,1.045000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.509090814098635214e-01,1.046000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.518181723098729785e-01,1.047000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.527272632098824356e-01,1.048000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.536363541098918928e-01,1.049000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.545454450099013499e-01,1.050000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.554545359099108071e-01,1.050999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.563636268099202642e-01,1.051999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.572727177099297213e-01,1.052999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.581818086099391785e-01,1.054000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.590908995099486356e-01,1.055000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.599999904099580927e-01,1.056000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.609090813099675499e-01,1.057000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.618181722099770070e-01,1.058000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.627272631099864642e-01,1.058999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.636363540099959213e-01,1.059999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.645454449100053784e-01,1.060999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.654545358100148356e-01,1.062000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.663636267100242927e-01,1.063000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.672727176100337498e-01,1.064000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.681818085100432070e-01,1.065000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.690908994100526641e-01,1.066000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.699999903100621212e-01,1.066999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.709090812100715784e-01,1.067999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.718181721100810355e-01,1.068999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.727272630100904927e-01,1.070000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.736363539100999498e-01,1.071000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.745454448101094069e-01,1.072000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.754545357101188641e-01,1.073000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.763636266101283212e-01,1.074000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.772727175101377783e-01,1.075000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.781818084101472355e-01,1.075999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.790908993101566926e-01,1.076999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.799999902101661498e-01,1.077999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.809090811101756069e-01,1.079000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.818181720101850640e-01,1.080000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.827272629101945212e-01,1.081000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.836363538102039783e-01,1.082000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.845454447102134354e-01,1.083000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.854545356102228926e-01,1.083999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.863636265102323497e-01,1.084999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.872727174102418068e-01,1.085999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.881818083102512640e-01,1.087000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.890908992102607211e-01,1.088000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.899999901102701783e-01,1.089000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.909090810102796354e-01,1.090000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.918181719102890925e-01,1.091000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.927272628102985497e-01,1.091999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.936363537103080068e-01,1.092999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.945454446103174639e-01,1.093999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.954545355103269211e-01,1.095000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.963636264103363782e-01,1.096000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.972727173103458354e-01,1.097000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.981818082103552925e-01,1.098000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.990908991103647496e-01,1.099000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +9.999999900103742068e-01,1.100000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.000909080910383553e+00,1.100999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.001818171810392899e+00,1.101999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.002727262710402245e+00,1.102999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.003636353610411591e+00,1.104000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.004545444510420937e+00,1.105000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.005454535410430283e+00,1.106000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.006363626310439630e+00,1.107000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.007272717210448976e+00,1.108000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.008181808110458322e+00,1.108999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.009090899010467668e+00,1.109999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.009999989910477014e+00,1.110999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.010909080810486360e+00,1.112000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.011818171710495706e+00,1.113000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.012727262610505052e+00,1.114000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.013636353510514398e+00,1.115000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.014545444410523745e+00,1.116000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.015454535310533091e+00,1.116999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.016363626210542437e+00,1.117999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.017272717110551783e+00,1.118999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.018181808010561129e+00,1.120000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.019090898910570475e+00,1.121000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.019999989810579821e+00,1.122000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.020909080710589167e+00,1.123000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.021818171610598514e+00,1.124000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.022727262510607860e+00,1.125000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.023636353410617206e+00,1.125999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.024545444310626552e+00,1.126999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.025454535210635898e+00,1.127999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.026363626110645244e+00,1.129000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.027272717010654590e+00,1.130000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.028181807910663936e+00,1.131000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.029090898810673282e+00,1.132000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.029999989710682629e+00,1.133000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.030909080610691975e+00,1.133999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.031818171510701321e+00,1.134999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.032727262410710667e+00,1.135999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.033636353310720013e+00,1.137000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.034545444210729359e+00,1.138000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.035454535110738705e+00,1.139000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.036363626010748051e+00,1.140000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.037272716910757397e+00,1.141000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.038181807810766744e+00,1.141999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.039090898710776090e+00,1.142999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.039999989610785436e+00,1.143999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.040909080510794782e+00,1.145000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.041818171410804128e+00,1.146000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.042727262310813474e+00,1.147000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.043636353210822820e+00,1.148000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.044545444110832166e+00,1.149000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.045454535010841512e+00,1.150000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.046363625910850859e+00,1.150999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.047272716810860205e+00,1.151999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.048181807710869551e+00,1.152999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.049090898610878897e+00,1.154000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.049999989510888243e+00,1.155000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.050909080410897589e+00,1.156000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.051818171310906935e+00,1.157000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.052727262210916281e+00,1.158000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.053636353110925628e+00,1.158999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.054545444010934974e+00,1.159999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.055454534910944320e+00,1.160999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.056363625810953666e+00,1.162000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.057272716710963012e+00,1.163000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.058181807610972358e+00,1.164000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.059090898510981704e+00,1.165000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.059999989410991050e+00,1.166000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.060909080311000396e+00,1.166999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.061818171211009743e+00,1.167999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.062727262111019089e+00,1.168999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.063636353011028435e+00,1.170000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.064545443911037781e+00,1.171000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.065454534811047127e+00,1.172000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.066363625711056473e+00,1.173000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.067272716611065819e+00,1.174000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.068181807511075165e+00,1.175000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.069090898411084511e+00,1.175999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.069999989311093858e+00,1.176999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.070909080211103204e+00,1.177999999999999936e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.071818171111112550e+00,1.179000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.072727262011121896e+00,1.180000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.073636352911131242e+00,1.181000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.074545443811140588e+00,1.182000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.075454534711149934e+00,1.183000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.076363625611159280e+00,1.183999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.077272716511168626e+00,1.184999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.078181807411177973e+00,1.185999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.079090898311187319e+00,1.187000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.079999989211196665e+00,1.188000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.080909080111206011e+00,1.189000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.081818171011215357e+00,1.190000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.082727261911224703e+00,1.191000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.083636352811234049e+00,1.191999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.084545443711243395e+00,1.192999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.085454534611252742e+00,1.193999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.086363625511262088e+00,1.195000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.087272716411271434e+00,1.196000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.088181807311280780e+00,1.197000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.089090898211290126e+00,1.198000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.089999989111299472e+00,1.199000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.090909080011308818e+00,1.200000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.091818170911318164e+00,1.200999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.092727261811327510e+00,1.201999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.093636352711336857e+00,1.203000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.094545443611346203e+00,1.204000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.095454534511355549e+00,1.205000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.096363625411364895e+00,1.206000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.097272716311374241e+00,1.207000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.098181807211383587e+00,1.208000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.099090898111392933e+00,1.208999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.099999989011402279e+00,1.209999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.100909079911411625e+00,1.210999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.101818170811420972e+00,1.212000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.102727261711430318e+00,1.213000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.103636352611439664e+00,1.214000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.104545443511449010e+00,1.215000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.105454534411458356e+00,1.216000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.106363625311467702e+00,1.216999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.107272716211477048e+00,1.217999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.108181807111486394e+00,1.218999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.109090898011495741e+00,1.220000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.109999988911505087e+00,1.221000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.110909079811514433e+00,1.222000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.111818170711523779e+00,1.223000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.112727261611533125e+00,1.224000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.113636352511542471e+00,1.225000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.114545443411551817e+00,1.225999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.115454534311561163e+00,1.226999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.116363625211570509e+00,1.228000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.117272716111579856e+00,1.229000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.118181807011589202e+00,1.230000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.119090897911598548e+00,1.231000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.119999988811607894e+00,1.232000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.120909079711617240e+00,1.233000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.121818170611626586e+00,1.233999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.122727261511635932e+00,1.234999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.123636352411645278e+00,1.235999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.124545443311654624e+00,1.237000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.125454534211663971e+00,1.238000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.126363625111673317e+00,1.239000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.127272716011682663e+00,1.240000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.128181806911692009e+00,1.241000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.129090897811701355e+00,1.241999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.129999988711710701e+00,1.242999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.130909079611720047e+00,1.243999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.131818170511729393e+00,1.245000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.132727261411738739e+00,1.246000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.133636352311748086e+00,1.247000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.134545443211757432e+00,1.248000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.135454534111766778e+00,1.249000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.136363625011776124e+00,1.250000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.137272715911785470e+00,1.250999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.138181806811794816e+00,1.251999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.139090897711804162e+00,1.253000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.139999988611813508e+00,1.254000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.140909079511822855e+00,1.255000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.141818170411832201e+00,1.256000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.142727261311841547e+00,1.257000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.143636352211850893e+00,1.258000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.144545443111860239e+00,1.258999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.145454534011869585e+00,1.259999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.146363624911878931e+00,1.260999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.147272715811888277e+00,1.262000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.148181806711897623e+00,1.263000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.149090897611906970e+00,1.264000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.149999988511916316e+00,1.265000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.150909079411925662e+00,1.266000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.151818170311935008e+00,1.266999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.152727261211944354e+00,1.267999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.153636352111953700e+00,1.268999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.154545443011963046e+00,1.270000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.155454533911972392e+00,1.271000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.156363624811981738e+00,1.272000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.157272715711991085e+00,1.273000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.158181806612000431e+00,1.274000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.159090897512009777e+00,1.275000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.159999988412019123e+00,1.275999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.160909079312028469e+00,1.276999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.161818170212037815e+00,1.278000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.162727261112047161e+00,1.279000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.163636352012056507e+00,1.280000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.164545442912065853e+00,1.281000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.165454533812075200e+00,1.282000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.166363624712084546e+00,1.283000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.167272715612093892e+00,1.283999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.168181806512103238e+00,1.284999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.169090897412112584e+00,1.285999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.169999988312121930e+00,1.287000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.170909079212131276e+00,1.288000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.171818170112140622e+00,1.289000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.172727261012149969e+00,1.290000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.173636351912159315e+00,1.291000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.174545442812168661e+00,1.291999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.175454533712178007e+00,1.292999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.176363624612187353e+00,1.293999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.177272715512196699e+00,1.295000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.178181806412206045e+00,1.296000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.179090897312215391e+00,1.297000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.179999988212224737e+00,1.298000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.180909079112234084e+00,1.299000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.181818170012243430e+00,1.300000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.182727260912252776e+00,1.300999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.183636351812262122e+00,1.301999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.184545442712271468e+00,1.303000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.185454533612280814e+00,1.304000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.186363624512290160e+00,1.305000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.187272715412299506e+00,1.306000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.188181806312308852e+00,1.307000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.189090897212318199e+00,1.308000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.189999988112327545e+00,1.308999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.190909079012336891e+00,1.309999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.191818169912346237e+00,1.310999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.192727260812355583e+00,1.312000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.193636351712364929e+00,1.313000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.194545442612374275e+00,1.314000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.195454533512383621e+00,1.315000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.196363624412392967e+00,1.316000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.197272715312402314e+00,1.316999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.198181806212411660e+00,1.317999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.199090897112421006e+00,1.318999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.199999988012430352e+00,1.320000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.200909078912439698e+00,1.321000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.201818169812449044e+00,1.322000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.202727260712458390e+00,1.323000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.203636351612467736e+00,1.324000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.204545442512477083e+00,1.325000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.205454533412486429e+00,1.325999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.206363624312495775e+00,1.326999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.207272715212505121e+00,1.328000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.208181806112514467e+00,1.329000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.209090897012523813e+00,1.330000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.209999987912533159e+00,1.331000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.210909078812542505e+00,1.332000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.211818169712551851e+00,1.333000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.212727260612561198e+00,1.333999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.213636351512570544e+00,1.334999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.214545442412579890e+00,1.335999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.215454533312589236e+00,1.337000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.216363624212598582e+00,1.338000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.217272715112607928e+00,1.339000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.218181806012617274e+00,1.340000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.219090896912626620e+00,1.341000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.219999987812635966e+00,1.341999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.220909078712645313e+00,1.342999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.221818169612654659e+00,1.343999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.222727260512664005e+00,1.345000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.223636351412673351e+00,1.346000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.224545442312682697e+00,1.347000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.225454533212692043e+00,1.348000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.226363624112701389e+00,1.349000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.227272715012710735e+00,1.350000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.228181805912720082e+00,1.350999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.229090896812729428e+00,1.351999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.229999987712738774e+00,1.353000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.230909078612748120e+00,1.354000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.231818169512757466e+00,1.355000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.232727260412766812e+00,1.356000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.233636351312776158e+00,1.357000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.234545442212785504e+00,1.358000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.235454533112794850e+00,1.358999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.236363624012804197e+00,1.359999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.237272714912813543e+00,1.360999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.238181805812822889e+00,1.362000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.239090896712832235e+00,1.363000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.239999987612841581e+00,1.364000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.240909078512850927e+00,1.365000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.241818169412860273e+00,1.366000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.242727260312869619e+00,1.366999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.243636351212878965e+00,1.367999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.244545442112888312e+00,1.368999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.245454533012897658e+00,1.370000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.246363623912907004e+00,1.371000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.247272714812916350e+00,1.372000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.248181805712925696e+00,1.373000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.249090896612935042e+00,1.374000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.249999987512944388e+00,1.375000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.250909078412953734e+00,1.375999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.251818169312963080e+00,1.376999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.252727260212972427e+00,1.378000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.253636351112981773e+00,1.379000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.254545442012991119e+00,1.380000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.255454532913000465e+00,1.381000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.256363623813009811e+00,1.382000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.257272714713019157e+00,1.383000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.258181805613028503e+00,1.383999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.259090896513037849e+00,1.384999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.259999987413047196e+00,1.385999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.260909078313056542e+00,1.387000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.261818169213065888e+00,1.388000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.262727260113075234e+00,1.389000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.263636351013084580e+00,1.390000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.264545441913093926e+00,1.391000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.265454532813103272e+00,1.391999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.266363623713112618e+00,1.392999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.267272714613121964e+00,1.393999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.268181805513131311e+00,1.395000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.269090896413140657e+00,1.396000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.269999987313150003e+00,1.397000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.270909078213159349e+00,1.398000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.271818169113168695e+00,1.399000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.272727260013178041e+00,1.400000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.273636350913187387e+00,1.400999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.274545441813196733e+00,1.401999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.275454532713206079e+00,1.403000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.276363623613215426e+00,1.404000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.277272714513224772e+00,1.405000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.278181805413234118e+00,1.406000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.279090896313243464e+00,1.407000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.279999987213252810e+00,1.408000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.280909078113262156e+00,1.408999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.281818169013271502e+00,1.409999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.282727259913280848e+00,1.410999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.283636350813290194e+00,1.412000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.284545441713299541e+00,1.413000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.285454532613308887e+00,1.414000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.286363623513318233e+00,1.415000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.287272714413327579e+00,1.416000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.288181805313336925e+00,1.416999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.289090896213346271e+00,1.417999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.289999987113355617e+00,1.418999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.290909078013364963e+00,1.420000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.291818168913374310e+00,1.421000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.292727259813383656e+00,1.422000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.293636350713393002e+00,1.423000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.294545441613402348e+00,1.424000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.295454532513411694e+00,1.425000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.296363623413421040e+00,1.425999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.297272714313430386e+00,1.426999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.298181805213439732e+00,1.428000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.299090896113449078e+00,1.429000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.299999987013458425e+00,1.430000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.300909077913467771e+00,1.431000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.301818168813477117e+00,1.432000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.302727259713486463e+00,1.433000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.303636350613495809e+00,1.433999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.304545441513505155e+00,1.434999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.305454532413514501e+00,1.435999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.306363623313523847e+00,1.437000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.307272714213533193e+00,1.438000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.308181805113542540e+00,1.439000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.309090896013551886e+00,1.440000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.309999986913561232e+00,1.441000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.310909077813570578e+00,1.441999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.311818168713579924e+00,1.442999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.312727259613589270e+00,1.443999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.313636350513598616e+00,1.445000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.314545441413607962e+00,1.446000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.315454532313617309e+00,1.447000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.316363623213626655e+00,1.448000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.317272714113636001e+00,1.449000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.318181805013645347e+00,1.450000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.319090895913654693e+00,1.450999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.319999986813664039e+00,1.451999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.320909077713673385e+00,1.453000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.321818168613682731e+00,1.454000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.322727259513692077e+00,1.455000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.323636350413701424e+00,1.456000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.324545441313710770e+00,1.457000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.325454532213720116e+00,1.458000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.326363623113729462e+00,1.458999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.327272714013738808e+00,1.459999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.328181804913748154e+00,1.460999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.329090895813757500e+00,1.462000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.329999986713766846e+00,1.463000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.330909077613776192e+00,1.464000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.331818168513785539e+00,1.465000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.332727259413794885e+00,1.466000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.333636350313804231e+00,1.466999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.334545441213813577e+00,1.467999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.335454532113822923e+00,1.468999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.336363623013832269e+00,1.470000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.337272713913841615e+00,1.471000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.338181804813850961e+00,1.472000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.339090895713860307e+00,1.473000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.339999986613869654e+00,1.474000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.340909077513879000e+00,1.475000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.341818168413888346e+00,1.475999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.342727259313897692e+00,1.476999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.343636350213907038e+00,1.478000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.344545441113916384e+00,1.479000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.345454532013925730e+00,1.480000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.346363622913935076e+00,1.481000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.347272713813944423e+00,1.482000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.348181804713953769e+00,1.483000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.349090895613963115e+00,1.483999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.349999986513972461e+00,1.484999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.350909077413981807e+00,1.485999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.351818168313991153e+00,1.487000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.352727259214000499e+00,1.488000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.353636350114009845e+00,1.489000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.354545441014019191e+00,1.490000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.355454531914028538e+00,1.491000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.356363622814037884e+00,1.491999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.357272713714047230e+00,1.492999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.358181804614056576e+00,1.493999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.359090895514065922e+00,1.495000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.359999986414075268e+00,1.496000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.360909077314084614e+00,1.497000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.361818168214093960e+00,1.498000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.362727259114103306e+00,1.499000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.363636350014112653e+00,1.500000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.364545440914121999e+00,1.500999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.365454531814131345e+00,1.501999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.366363622714140691e+00,1.503000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.367272713614150037e+00,1.504000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.368181804514159383e+00,1.505000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.369090895414168729e+00,1.506000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.369999986314178075e+00,1.507000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.370909077214187421e+00,1.508000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.371818168114196768e+00,1.508999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.372727259014206114e+00,1.509999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.373636349914215460e+00,1.510999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.374545440814224806e+00,1.512000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.375454531714234152e+00,1.513000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.376363622614243498e+00,1.514000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.377272713514252844e+00,1.515000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.378181804414262190e+00,1.516000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.379090895314271537e+00,1.516999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.379999986214280883e+00,1.517999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.380909077114290229e+00,1.518999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.381818168014299575e+00,1.520000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.382727258914308921e+00,1.521000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.383636349814318267e+00,1.522000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.384545440714327613e+00,1.523000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.385454531614336959e+00,1.524000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.386363622514346305e+00,1.525000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.387272713414355652e+00,1.525999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.388181804314364998e+00,1.526999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.389090895214374344e+00,1.528000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.389999986114383690e+00,1.529000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.390909077014393036e+00,1.530000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.391818167914402382e+00,1.531000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.392727258814411728e+00,1.532000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.393636349714421074e+00,1.533000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.394545440614430420e+00,1.533999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.395454531514439767e+00,1.534999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.396363622414449113e+00,1.535999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.397272713314458459e+00,1.537000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.398181804214467805e+00,1.538000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.399090895114477151e+00,1.539000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.399999986014486497e+00,1.540000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.400909076914495843e+00,1.541000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.401818167814505189e+00,1.541999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.402727258714514535e+00,1.542999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.403636349614523882e+00,1.543999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.404545440514533228e+00,1.545000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.405454531414542574e+00,1.546000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.406363622314551920e+00,1.547000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.407272713214561266e+00,1.548000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.408181804114570612e+00,1.549000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.409090895014579958e+00,1.550000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.409999985914589304e+00,1.550999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.410909076814598651e+00,1.551999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.411818167714607997e+00,1.553000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.412727258614617343e+00,1.554000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.413636349514626689e+00,1.555000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.414545440414636035e+00,1.556000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.415454531314645381e+00,1.557000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.416363622214654727e+00,1.558000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.417272713114664073e+00,1.558999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.418181804014673419e+00,1.559999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.419090894914682766e+00,1.561000000000000121e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.419999985814692112e+00,1.562000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.420909076714701458e+00,1.563000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.421818167614710804e+00,1.564000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.422727258514720150e+00,1.565000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.423636349414729496e+00,1.566000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.424545440314738842e+00,1.566999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.425454531214748188e+00,1.567999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.426363622114757534e+00,1.568999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.427272713014766881e+00,1.570000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.428181803914776227e+00,1.571000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.429090894814785573e+00,1.572000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.429999985714794919e+00,1.573000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.430909076614804265e+00,1.574000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.431818167514813611e+00,1.575000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.432727258414822957e+00,1.575999999999999979e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.433636349314832303e+00,1.576999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.434545440214841650e+00,1.578000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.435454531114850996e+00,1.579000000000000092e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.436363622014860342e+00,1.580000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.437272712914869688e+00,1.581000000000000050e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.438181803814879034e+00,1.582000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.439090894714888380e+00,1.583000000000000007e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.439999985614897726e+00,1.583999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.440909076514907072e+00,1.584999999999999964e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.441818167414916418e+00,1.586000000000000121e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.442727258314925765e+00,1.587000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.443636349214935111e+00,1.588000000000000078e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.444545440114944457e+00,1.589000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.445454531014953803e+00,1.590000000000000036e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.446363621914963149e+00,1.591000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.447272712814972495e+00,1.591999999999999993e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.448181803714981841e+00,1.592999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.449090894614991187e+00,1.593999999999999950e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.449999985515000533e+00,1.595000000000000107e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.450909076415009880e+00,1.596000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.451818167315019226e+00,1.597000000000000064e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.452727258215028572e+00,1.598000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.453636349115037918e+00,1.599000000000000021e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.454545440015047264e+00,1.600000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.455454530915056610e+00,1.601000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.456363621815065956e+00,1.601999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.457272712715075302e+00,1.603000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.458181803615084648e+00,1.603999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.459090894515093995e+00,1.605000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.459999985415103341e+00,1.605999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.460909076315112687e+00,1.607000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.461818167215122033e+00,1.608000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.462727258115131379e+00,1.608999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.463636349015140725e+00,1.610000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.464545439915150071e+00,1.610999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.465454530815159417e+00,1.612000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.466363621715168764e+00,1.612999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.467272712615178110e+00,1.614000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.468181803515187456e+00,1.614999999999999858e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.469090894415196802e+00,1.616000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.469999985315206148e+00,1.617000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.470909076215215494e+00,1.617999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.471818167115224840e+00,1.619000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.472727258015234186e+00,1.619999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.473636348915243532e+00,1.621000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.474545439815252879e+00,1.621999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.475454530715262225e+00,1.623000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.476363621615271571e+00,1.624000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.477272712515280917e+00,1.625000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.478181803415290263e+00,1.626000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.479090894315299609e+00,1.626999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.479999985215308955e+00,1.628000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.480909076115318301e+00,1.628999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.481818167015327647e+00,1.630000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.482727257915336994e+00,1.630999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.483636348815346340e+00,1.632000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.484545439715355686e+00,1.633000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.485454530615365032e+00,1.633999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.486363621515374378e+00,1.635000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.487272712415383724e+00,1.635999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.488181803315393070e+00,1.637000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.489090894215402416e+00,1.637999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.489999985115411762e+00,1.639000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.490909076015421109e+00,1.639999999999999858e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.491818166915430455e+00,1.641000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.492727257815439801e+00,1.642000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.493636348715449147e+00,1.642999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.494545439615458493e+00,1.644000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.495454530515467839e+00,1.644999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.496363621415477185e+00,1.646000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.497272712315486531e+00,1.646999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.498181803215495878e+00,1.648000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.499090894115505224e+00,1.649000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.499999985015514570e+00,1.650000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.500909075915523916e+00,1.651000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.501818166815533262e+00,1.651999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.502727257715542608e+00,1.653000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.503636348615551954e+00,1.653999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.504545439515561300e+00,1.655000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.505454530415570646e+00,1.655999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.506363621315579993e+00,1.657000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.507272712215589339e+00,1.658000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.508181803115598685e+00,1.658999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.509090894015608031e+00,1.660000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.509999984915617377e+00,1.660999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.510909075815626723e+00,1.662000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.511818166715636069e+00,1.662999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.512727257615645415e+00,1.664000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.513636348515654761e+00,1.664999999999999858e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.514545439415664108e+00,1.666000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.515454530315673454e+00,1.667000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.516363621215682800e+00,1.667999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.517272712115692146e+00,1.669000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.518181803015701492e+00,1.669999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.519090893915710838e+00,1.671000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.519999984815720184e+00,1.671999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.520909075715729530e+00,1.673000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.521818166615738877e+00,1.674000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.522727257515748223e+00,1.675000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.523636348415757569e+00,1.676000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.524545439315766915e+00,1.676999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.525454530215776261e+00,1.678000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.526363621115785607e+00,1.678999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.527272712015794953e+00,1.680000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.528181802915804299e+00,1.680999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.529090893815813645e+00,1.682000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.529999984715822992e+00,1.683000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.530909075615832338e+00,1.683999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.531818166515841684e+00,1.685000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.532727257415851030e+00,1.685999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.533636348315860376e+00,1.687000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.534545439215869722e+00,1.687999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.535454530115879068e+00,1.689000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.536363621015888414e+00,1.689999999999999858e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.537272711915897760e+00,1.691000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.538181802815907107e+00,1.692000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.539090893715916453e+00,1.692999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.539999984615925799e+00,1.694000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.540909075515935145e+00,1.694999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.541818166415944491e+00,1.696000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.542727257315953837e+00,1.696999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.543636348215963183e+00,1.698000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.544545439115972529e+00,1.699000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.545454530015981875e+00,1.700000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.546363620915991222e+00,1.701000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.547272711816000568e+00,1.701999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.548181802716009914e+00,1.703000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.549090893616019260e+00,1.703999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.549999984516028606e+00,1.705000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.550909075416037952e+00,1.705999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.551818166316047298e+00,1.707000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.552727257216056644e+00,1.708000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.553636348116065991e+00,1.708999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.554545439016075337e+00,1.710000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.555454529916084683e+00,1.710999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.556363620816094029e+00,1.712000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.557272711716103375e+00,1.712999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.558181802616112721e+00,1.714000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.559090893516122067e+00,1.715000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.559999984416131413e+00,1.716000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.560909075316140759e+00,1.717000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.561818166216150106e+00,1.717999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.562727257116159452e+00,1.719000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.563636348016168798e+00,1.719999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.564545438916178144e+00,1.721000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.565454529816187490e+00,1.721999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.566363620716196836e+00,1.723000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.567272711616206182e+00,1.724000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.568181802516215528e+00,1.725000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.569090893416224874e+00,1.726000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.569999984316234221e+00,1.726999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.570909075216243567e+00,1.728000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.571818166116252913e+00,1.728999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.572727257016262259e+00,1.730000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.573636347916271605e+00,1.730999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.574545438816280951e+00,1.732000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.575454529716290297e+00,1.733000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.576363620616299643e+00,1.733999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.577272711516308989e+00,1.735000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.578181802416318336e+00,1.735999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.579090893316327682e+00,1.737000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.579999984216337028e+00,1.737999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.580909075116346374e+00,1.739000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.581818166016355720e+00,1.740000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.582727256916365066e+00,1.741000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.583636347816374412e+00,1.742000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.584545438716383758e+00,1.742999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.585454529616393105e+00,1.744000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.586363620516402451e+00,1.744999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.587272711416411797e+00,1.746000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.588181802316421143e+00,1.746999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.589090893216430489e+00,1.748000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.589999984116439835e+00,1.749000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.590909075016449181e+00,1.750000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.591818165916458527e+00,1.751000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.592727256816467873e+00,1.751999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.593636347716477220e+00,1.753000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.594545438616486566e+00,1.753999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.595454529516495912e+00,1.755000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.596363620416505258e+00,1.755999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.597272711316514604e+00,1.757000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.598181802216523950e+00,1.758000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.599090893116533296e+00,1.758999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.599999984016542642e+00,1.760000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.600909074916551988e+00,1.760999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.601818165816561335e+00,1.762000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.602727256716570681e+00,1.762999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.603636347616580027e+00,1.764000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.604545438516589373e+00,1.765000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.605454529416598719e+00,1.766000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.606363620316608065e+00,1.767000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.607272711216617411e+00,1.767999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.608181802116626757e+00,1.769000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.609090893016636103e+00,1.769999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.609999983916645450e+00,1.771000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.610909074816654796e+00,1.771999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.611818165716664142e+00,1.773000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.612727256616673488e+00,1.774000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.613636347516682834e+00,1.775000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.614545438416692180e+00,1.776000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.615454529316701526e+00,1.776999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.616363620216710872e+00,1.778000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.617272711116720219e+00,1.778999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.618181802016729565e+00,1.780000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.619090892916738911e+00,1.780999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.619999983816748257e+00,1.782000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.620909074716757603e+00,1.783000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.621818165616766949e+00,1.783999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.622727256516776295e+00,1.785000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.623636347416785641e+00,1.785999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.624545438316794987e+00,1.787000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.625454529216804334e+00,1.787999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.626363620116813680e+00,1.789000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.627272711016823026e+00,1.790000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.628181801916832372e+00,1.791000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.629090892816841718e+00,1.792000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.629999983716851064e+00,1.792999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.630909074616860410e+00,1.794000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.631818165516869756e+00,1.794999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.632727256416879102e+00,1.796000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.633636347316888449e+00,1.796999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.634545438216897795e+00,1.798000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.635454529116907141e+00,1.799000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.636363620016916487e+00,1.800000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.637272710916925833e+00,1.801000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.638181801816935179e+00,1.801999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.639090892716944525e+00,1.803000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.639999983616953871e+00,1.803999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.640909074516963218e+00,1.805000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.641818165416972564e+00,1.805999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.642727256316981910e+00,1.807000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.643636347216991256e+00,1.808000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.644545438117000602e+00,1.808999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.645454529017009948e+00,1.810000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.646363619917019294e+00,1.810999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.647272710817028640e+00,1.812000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.648181801717037986e+00,1.812999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.649090892617047333e+00,1.814000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.649999983517056679e+00,1.815000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.650909074417066025e+00,1.816000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.651818165317075371e+00,1.817000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.652727256217084717e+00,1.817999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.653636347117094063e+00,1.819000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.654545438017103409e+00,1.819999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.655454528917112755e+00,1.821000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.656363619817122101e+00,1.821999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.657272710717131448e+00,1.823000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.658181801617140794e+00,1.824000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.659090892517150140e+00,1.825000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.659999983417159486e+00,1.826000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.660909074317168832e+00,1.826999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.661818165217178178e+00,1.828000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.662727256117187524e+00,1.828999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.663636347017196870e+00,1.830000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.664545437917206216e+00,1.830999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.665454528817215563e+00,1.832000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.666363619717224909e+00,1.833000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.667272710617234255e+00,1.833999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.668181801517243601e+00,1.835000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.669090892417252947e+00,1.835999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.669999983317262293e+00,1.837000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.670909074217271639e+00,1.837999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.671818165117280985e+00,1.839000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.672727256017290332e+00,1.840000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.673636346917299678e+00,1.841000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.674545437817309024e+00,1.842000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.675454528717318370e+00,1.842999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.676363619617327716e+00,1.844000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.677272710517337062e+00,1.844999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.678181801417346408e+00,1.846000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.679090892317355754e+00,1.846999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.679999983217365100e+00,1.848000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.680909074117374447e+00,1.849000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.681818165017383793e+00,1.850000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.682727255917393139e+00,1.851000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.683636346817402485e+00,1.851999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.684545437717411831e+00,1.853000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.685454528617421177e+00,1.853999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.686363619517430523e+00,1.855000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.687272710417439869e+00,1.855999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.688181801317449215e+00,1.857000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.689090892217458562e+00,1.858000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.689999983117467908e+00,1.858999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.690909074017477254e+00,1.860000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.691818164917486600e+00,1.860999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.692727255817495946e+00,1.862000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.693636346717505292e+00,1.862999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.694545437617514638e+00,1.864000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.695454528517523984e+00,1.865000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.696363619417533330e+00,1.866000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.697272710317542677e+00,1.867000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.698181801217552023e+00,1.867999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.699090892117561369e+00,1.869000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.699999983017570715e+00,1.869999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.700909073917580061e+00,1.871000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.701818164817589407e+00,1.871999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.702727255717598753e+00,1.873000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.703636346617608099e+00,1.874000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.704545437517617446e+00,1.875000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.705454528417626792e+00,1.876000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.706363619317636138e+00,1.876999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.707272710217645484e+00,1.878000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.708181801117654830e+00,1.878999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.709090892017664176e+00,1.880000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.709999982917673522e+00,1.880999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.710909073817682868e+00,1.882000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.711818164717692214e+00,1.883000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.712727255617701561e+00,1.883999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.713636346517710907e+00,1.885000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.714545437417720253e+00,1.885999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.715454528317729599e+00,1.887000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.716363619217738945e+00,1.887999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.717272710117748291e+00,1.889000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.718181801017757637e+00,1.890000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.719090891917766983e+00,1.891000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.719999982817776329e+00,1.892000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.720909073717785676e+00,1.892999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.721818164617795022e+00,1.894000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.722727255517804368e+00,1.894999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.723636346417813714e+00,1.896000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.724545437317823060e+00,1.896999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.725454528217832406e+00,1.898000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.726363619117841752e+00,1.899000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.727272710017851098e+00,1.900000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.728181800917860444e+00,1.901000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.729090891817869791e+00,1.901999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.729999982717879137e+00,1.903000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.730909073617888483e+00,1.903999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.731818164517897829e+00,1.905000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.732727255417907175e+00,1.905999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.733636346317916521e+00,1.907000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.734545437217925867e+00,1.908000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.735454528117935213e+00,1.908999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.736363619017944560e+00,1.910000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.737272709917953906e+00,1.910999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.738181800817963252e+00,1.912000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.739090891717972598e+00,1.912999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.739999982617981944e+00,1.914000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.740909073517991290e+00,1.915000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.741818164418000636e+00,1.916000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.742727255318009982e+00,1.917000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.743636346218019328e+00,1.917999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.744545437118028675e+00,1.919000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.745454528018038021e+00,1.919999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.746363618918047367e+00,1.921000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.747272709818056713e+00,1.921999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.748181800718066059e+00,1.923000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.749090891618075405e+00,1.924000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.749999982518084751e+00,1.925000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.750909073418094097e+00,1.926000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.751818164318103443e+00,1.926999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.752727255218112790e+00,1.928000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.753636346118122136e+00,1.928999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.754545437018131482e+00,1.930000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.755454527918140828e+00,1.930999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.756363618818150174e+00,1.932000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.757272709718159520e+00,1.933000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.758181800618168866e+00,1.933999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.759090891518178212e+00,1.935000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.759999982418187559e+00,1.935999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.760909073318196905e+00,1.937000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.761818164218206251e+00,1.937999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.762727255118215597e+00,1.939000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.763636346018224943e+00,1.940000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.764545436918234289e+00,1.941000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.765454527818243635e+00,1.942000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.766363618718252981e+00,1.942999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.767272709618262327e+00,1.944000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.768181800518271674e+00,1.944999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.769090891418281020e+00,1.946000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.769999982318290366e+00,1.946999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.770909073218299712e+00,1.948000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.771818164118309058e+00,1.949000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.772727255018318404e+00,1.950000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.773636345918327750e+00,1.951000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.774545436818337096e+00,1.951999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.775454527718346442e+00,1.953000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.776363618618355789e+00,1.953999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.777272709518365135e+00,1.955000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.778181800418374481e+00,1.955999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.779090891318383827e+00,1.957000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.779999982218393173e+00,1.958000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.780909073118402519e+00,1.958999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.781818164018411865e+00,1.960000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.782727254918421211e+00,1.960999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.783636345818430557e+00,1.962000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.784545436718439904e+00,1.962999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.785454527618449250e+00,1.964000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.786363618518458596e+00,1.965000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.787272709418467942e+00,1.966000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.788181800318477288e+00,1.967000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.789090891218486634e+00,1.967999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.789999982118495980e+00,1.969000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.790909073018505326e+00,1.969999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.791818163918514673e+00,1.971000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.792727254818524019e+00,1.971999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.793636345718533365e+00,1.973000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.794545436618542711e+00,1.974000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.795454527518552057e+00,1.975000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.796363618418561403e+00,1.976000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.797272709318570749e+00,1.976999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.798181800218580095e+00,1.978000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.799090891118589441e+00,1.978999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.799999982018598788e+00,1.980000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.800909072918608134e+00,1.980999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.801818163818617480e+00,1.982000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.802727254718626826e+00,1.983000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.803636345618636172e+00,1.983999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.804545436518645518e+00,1.985000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.805454527418654864e+00,1.985999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.806363618318664210e+00,1.987000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.807272709218673556e+00,1.987999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.808181800118682903e+00,1.989000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.809090891018692249e+00,1.990000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.809999981918701595e+00,1.991000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.810909072818710941e+00,1.992000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.811818163718720287e+00,1.992999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.812727254618729633e+00,1.994000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.813636345518738979e+00,1.994999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.814545436418748325e+00,1.996000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.815454527318757671e+00,1.996999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.816363618218767018e+00,1.998000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.817272709118776364e+00,1.999000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818181800018785710e+00,2.000000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.819090890918795056e+00,2.001000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.819999981818804402e+00,2.001999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.820909072718813748e+00,2.003000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.821818163618823094e+00,2.003999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.822727254518832440e+00,2.005000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.823636345418841787e+00,2.005999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.824545436318851133e+00,2.007000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.825454527218860479e+00,2.008000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.826363618118869825e+00,2.008999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.827272709018879171e+00,2.010000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.828181799918888517e+00,2.010999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.829090890818897863e+00,2.012000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.829999981718907209e+00,2.012999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.830909072618916555e+00,2.014000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.831818163518925902e+00,2.015000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.832727254418935248e+00,2.016000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.833636345318944594e+00,2.017000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.834545436218953940e+00,2.017999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.835454527118963286e+00,2.019000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.836363618018972632e+00,2.019999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.837272708918981978e+00,2.021000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.838181799818991324e+00,2.021999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.839090890719000670e+00,2.023000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.839999981619010017e+00,2.024000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.840909072519019363e+00,2.025000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.841818163419028709e+00,2.026000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.842727254319038055e+00,2.026999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.843636345219047401e+00,2.028000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.844545436119056747e+00,2.028999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.845454527019066093e+00,2.030000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.846363617919075439e+00,2.030999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.847272708819084786e+00,2.032000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.848181799719094132e+00,2.033000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.849090890619103478e+00,2.033999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.849999981519112824e+00,2.035000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.850909072419122170e+00,2.035999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.851818163319131516e+00,2.037000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.852727254219140862e+00,2.037999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.853636345119150208e+00,2.039000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.854545436019159554e+00,2.040000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.855454526919168901e+00,2.041000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.856363617819178247e+00,2.042000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.857272708719187593e+00,2.042999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.858181799619196939e+00,2.044000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.859090890519206285e+00,2.044999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.859999981419215631e+00,2.046000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.860909072319224977e+00,2.046999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.861818163219234323e+00,2.048000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.862727254119243669e+00,2.049000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.863636345019253016e+00,2.050000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.864545435919262362e+00,2.051000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.865454526819271708e+00,2.051999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.866363617719281054e+00,2.053000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.867272708619290400e+00,2.053999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.868181799519299746e+00,2.055000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.869090890419309092e+00,2.055999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.869999981319318438e+00,2.057000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.870909072219327784e+00,2.058000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.871818163119337131e+00,2.058999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.872727254019346477e+00,2.060000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.873636344919355823e+00,2.060999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.874545435819365169e+00,2.062000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.875454526719374515e+00,2.062999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.876363617619383861e+00,2.064000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.877272708519393207e+00,2.065000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.878181799419402553e+00,2.066000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.879090890319411900e+00,2.067000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.879999981219421246e+00,2.067999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.880909072119430592e+00,2.069000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.881818163019439938e+00,2.069999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.882727253919449284e+00,2.071000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.883636344819458630e+00,2.071999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.884545435719467976e+00,2.073000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.885454526619477322e+00,2.074000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.886363617519486668e+00,2.075000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.887272708419496015e+00,2.076000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.888181799319505361e+00,2.076999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.889090890219514707e+00,2.078000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.889999981119524053e+00,2.078999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.890909072019533399e+00,2.080000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.891818162919542745e+00,2.080999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.892727253819552091e+00,2.082000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.893636344719561437e+00,2.083000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.894545435619570783e+00,2.083999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.895454526519580130e+00,2.085000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.896363617419589476e+00,2.085999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.897272708319598822e+00,2.087000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.898181799219608168e+00,2.087999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.899090890119617514e+00,2.089000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.899999981019626860e+00,2.090000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.900909071919636206e+00,2.091000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.901818162819645552e+00,2.092000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.902727253719654898e+00,2.092999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.903636344619664245e+00,2.094000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.904545435519673591e+00,2.094999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.905454526419682937e+00,2.096000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.906363617319692283e+00,2.096999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.907272708219701629e+00,2.098000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.908181799119710975e+00,2.099000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909090890019720321e+00,2.100000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909999980919729667e+00,2.101000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.910909071819739014e+00,2.101999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.911818162719748360e+00,2.103000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.912727253619757706e+00,2.103999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.913636344519767052e+00,2.105000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.914545435419776398e+00,2.105999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.915454526319785744e+00,2.107000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.916363617219795090e+00,2.108000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.917272708119804436e+00,2.108999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.918181799019813782e+00,2.110000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.919090889919823129e+00,2.110999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.919999980819832475e+00,2.112000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.920909071719841821e+00,2.112999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.921818162619851167e+00,2.114000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.922727253519860513e+00,2.115000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.923636344419869859e+00,2.116000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.924545435319879205e+00,2.117000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.925454526219888551e+00,2.117999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.926363617119897897e+00,2.119000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.927272708019907244e+00,2.119999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.928181798919916590e+00,2.121000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.929090889819925936e+00,2.121999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.929999980719935282e+00,2.123000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.930909071619944628e+00,2.124000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.931818162519953974e+00,2.125000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.932727253419963320e+00,2.126000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.933636344319972666e+00,2.126999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.934545435219982012e+00,2.128000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.935454526119991359e+00,2.128999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.936363617020000705e+00,2.130000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.937272707920010051e+00,2.130999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.938181798820019397e+00,2.132000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.939090889720028743e+00,2.133000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.939999980620038089e+00,2.133999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.940909071520047435e+00,2.135000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.941818162420056781e+00,2.135999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.942727253320066128e+00,2.137000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.943636344220075474e+00,2.137999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.944545435120084820e+00,2.139000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.945454526020094166e+00,2.140000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.946363616920103512e+00,2.141000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.947272707820112858e+00,2.142000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.948181798720122204e+00,2.142999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.949090889620131550e+00,2.144000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.949999980520140896e+00,2.144999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.950909071420150243e+00,2.146000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.951818162320159589e+00,2.146999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.952727253220168935e+00,2.148000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.953636344120178281e+00,2.149000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.954545435020187627e+00,2.150000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.955454525920196973e+00,2.151000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.956363616820206319e+00,2.151999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.957272707720215665e+00,2.153000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.958181798620225011e+00,2.153999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.959090889520234358e+00,2.155000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.959999980420243704e+00,2.155999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.960909071320253050e+00,2.157000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.961818162220262396e+00,2.158000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.962727253120271742e+00,2.158999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.963636344020281088e+00,2.160000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.964545434920290434e+00,2.160999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.965454525820299780e+00,2.162000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.966363616720309127e+00,2.162999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.967272707620318473e+00,2.164000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.968181798520327819e+00,2.165000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.969090889420337165e+00,2.166000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.969999980320346511e+00,2.167000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.970909071220355857e+00,2.167999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.971818162120365203e+00,2.169000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.972727253020374549e+00,2.169999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.973636343920383895e+00,2.171000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.974545434820393242e+00,2.171999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.975454525720402588e+00,2.173000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.976363616620411934e+00,2.174000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.977272707520421280e+00,2.175000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.978181798420430626e+00,2.176000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.979090889320439972e+00,2.176999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.979999980220449318e+00,2.178000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.980909071120458664e+00,2.178999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.981818162020468010e+00,2.180000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.982727252920477357e+00,2.180999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.983636343820486703e+00,2.182000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.984545434720496049e+00,2.183000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.985454525620505395e+00,2.183999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.986363616520514741e+00,2.185000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.987272707420524087e+00,2.185999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.988181798320533433e+00,2.187000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.989090889220542779e+00,2.187999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.989999980120552125e+00,2.189000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.990909071020561472e+00,2.190000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.991818161920570818e+00,2.191000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.992727252820580164e+00,2.192000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.993636343720589510e+00,2.192999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.994545434620598856e+00,2.194000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.995454525520608202e+00,2.194999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.996363616420617548e+00,2.196000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.997272707320626894e+00,2.196999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.998181798220636241e+00,2.198000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999090889120645587e+00,2.199000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999999980020654933e+00,2.200000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.000909070920664501e+00,2.201000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.001818161820673847e+00,2.201999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.002727252720683193e+00,2.203000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.003636343620692539e+00,2.203999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.004545434520701885e+00,2.205000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.005454525420711231e+00,2.205999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.006363616320720578e+00,2.207000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.007272707220729924e+00,2.208000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.008181798120739270e+00,2.208999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.009090889020748616e+00,2.210000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.009999979920757962e+00,2.210999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.010909070820767308e+00,2.212000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.011818161720776654e+00,2.212999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.012727252620786000e+00,2.214000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.013636343520795347e+00,2.215000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.014545434420804693e+00,2.216000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.015454525320814039e+00,2.217000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.016363616220823385e+00,2.217999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.017272707120832731e+00,2.219000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.018181798020842077e+00,2.219999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.019090888920851423e+00,2.221000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.019999979820860769e+00,2.221999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.020909070720870115e+00,2.223000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.021818161620879462e+00,2.224000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.022727252520888808e+00,2.225000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.023636343420898154e+00,2.226000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.024545434320907500e+00,2.226999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.025454525220916846e+00,2.228000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.026363616120926192e+00,2.228999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.027272707020935538e+00,2.230000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.028181797920944884e+00,2.230999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.029090888820954230e+00,2.232000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.029999979720963577e+00,2.233000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.030909070620972923e+00,2.233999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.031818161520982269e+00,2.235000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.032727252420991615e+00,2.235999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.033636343321000961e+00,2.237000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.034545434221010307e+00,2.237999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.035454525121019653e+00,2.239000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.036363616021028999e+00,2.240000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.037272706921038345e+00,2.241000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.038181797821047692e+00,2.242000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.039090888721057038e+00,2.242999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.039999979621066384e+00,2.244000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.040909070521075730e+00,2.244999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.041818161421085076e+00,2.246000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.042727252321094422e+00,2.246999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.043636343221103768e+00,2.248000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.044545434121113114e+00,2.249000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.045454525021122461e+00,2.250000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.046363615921131807e+00,2.251000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.047272706821141153e+00,2.251999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.048181797721150499e+00,2.253000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.049090888621159845e+00,2.253999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.049999979521169191e+00,2.255000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.050909070421178537e+00,2.255999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.051818161321187883e+00,2.257000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.052727252221197229e+00,2.258000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.053636343121206576e+00,2.258999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.054545434021215922e+00,2.260000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.055454524921225268e+00,2.260999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.056363615821234614e+00,2.262000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.057272706721243960e+00,2.262999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.058181797621253306e+00,2.264000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.059090888521262652e+00,2.265000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.059999979421271998e+00,2.266000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.060909070321281344e+00,2.267000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.061818161221290691e+00,2.267999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.062727252121300037e+00,2.269000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.063636343021309383e+00,2.269999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.064545433921318729e+00,2.271000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.065454524821328075e+00,2.271999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.066363615721337421e+00,2.273000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.067272706621346767e+00,2.274000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.068181797521356113e+00,2.275000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.069090888421365459e+00,2.276000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.069999979321374806e+00,2.276999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.070909070221384152e+00,2.278000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.071818161121393498e+00,2.278999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.072727252021402844e+00,2.280000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.073636342921412190e+00,2.280999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.074545433821421536e+00,2.282000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.075454524721430882e+00,2.283000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.076363615621440228e+00,2.283999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.077272706521449575e+00,2.285000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.078181797421458921e+00,2.285999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.079090888321468267e+00,2.287000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.079999979221477613e+00,2.287999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.080909070121486959e+00,2.289000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.081818161021496305e+00,2.290000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.082727251921505651e+00,2.291000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.083636342821514997e+00,2.292000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.084545433721524343e+00,2.292999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.085454524621533690e+00,2.294000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.086363615521543036e+00,2.294999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.087272706421552382e+00,2.296000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.088181797321561728e+00,2.296999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.089090888221571074e+00,2.298000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.089999979121580420e+00,2.299000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.090909070021589766e+00,2.300000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.091818160921599112e+00,2.301000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.092727251821608458e+00,2.301999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.093636342721617805e+00,2.303000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.094545433621627151e+00,2.303999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.095454524521636497e+00,2.305000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.096363615421645843e+00,2.305999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.097272706321655189e+00,2.307000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.098181797221664535e+00,2.308000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.099090888121673881e+00,2.308999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.099999979021683227e+00,2.310000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.100909069921692574e+00,2.310999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.101818160821701920e+00,2.312000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.102727251721711266e+00,2.312999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.103636342621720612e+00,2.314000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.104545433521729958e+00,2.315000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.105454524421739304e+00,2.316000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.106363615321748650e+00,2.317000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.107272706221757996e+00,2.317999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.108181797121767342e+00,2.319000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.109090888021776689e+00,2.319999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.109999978921786035e+00,2.321000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.110909069821795381e+00,2.321999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.111818160721804727e+00,2.323000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.112727251621814073e+00,2.324000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.113636342521823419e+00,2.325000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.114545433421832765e+00,2.326000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.115454524321842111e+00,2.326999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.116363615221851457e+00,2.328000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.117272706121860804e+00,2.328999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.118181797021870150e+00,2.330000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.119090887921879496e+00,2.330999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.119999978821888842e+00,2.332000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.120909069721898188e+00,2.333000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.121818160621907534e+00,2.333999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.122727251521916880e+00,2.335000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.123636342421926226e+00,2.335999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.124545433321935572e+00,2.337000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.125454524221944919e+00,2.337999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.126363615121954265e+00,2.339000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.127272706021963611e+00,2.340000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.128181796921972957e+00,2.341000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.129090887821982303e+00,2.342000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.129999978721991649e+00,2.342999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.130909069622000995e+00,2.344000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.131818160522010341e+00,2.344999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.132727251422019688e+00,2.346000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.133636342322029034e+00,2.346999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.134545433222038380e+00,2.348000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.135454524122047726e+00,2.349000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.136363615022057072e+00,2.350000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.137272705922066418e+00,2.351000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.138181796822075764e+00,2.351999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.139090887722085110e+00,2.353000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.139999978622094456e+00,2.353999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.140909069522103803e+00,2.355000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.141818160422113149e+00,2.355999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.142727251322122495e+00,2.357000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.143636342222131841e+00,2.358000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.144545433122141187e+00,2.358999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.145454524022150533e+00,2.360000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.146363614922159879e+00,2.360999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.147272705822169225e+00,2.362000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.148181796722178571e+00,2.362999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.149090887622187918e+00,2.364000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.149999978522197264e+00,2.365000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.150909069422206610e+00,2.366000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.151818160322215956e+00,2.367000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.152727251222225302e+00,2.367999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.153636342122234648e+00,2.369000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.154545433022243994e+00,2.369999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.155454523922253340e+00,2.371000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.156363614822262686e+00,2.371999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.157272705722272033e+00,2.373000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.158181796622281379e+00,2.374000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.159090887522290725e+00,2.375000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.159999978422300071e+00,2.376000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.160909069322309417e+00,2.376999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.161818160222318763e+00,2.378000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.162727251122328109e+00,2.378999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.163636342022337455e+00,2.380000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.164545432922346802e+00,2.380999999999999872e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.165454523822356148e+00,2.382000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.166363614722365494e+00,2.383000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.167272705622374840e+00,2.383999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.168181796522384186e+00,2.385000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.169090887422393532e+00,2.385999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.169999978322402878e+00,2.387000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.170909069222412224e+00,2.387999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.171818160122421570e+00,2.389000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.172727251022430917e+00,2.390000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.173636341922440263e+00,2.391000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.174545432822449609e+00,2.392000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.175454523722458955e+00,2.392999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.176363614622468301e+00,2.394000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.177272705522477647e+00,2.394999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.178181796422486993e+00,2.396000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.179090887322496339e+00,2.396999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.179999978222505685e+00,2.398000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.180909069122515032e+00,2.399000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.181818160022524378e+00,2.400000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.182727250922533724e+00,2.401000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.183636341822543070e+00,2.401999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.184545432722552416e+00,2.403000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.185454523622561762e+00,2.403999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.186363614522571108e+00,2.405000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.187272705422580454e+00,2.406000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.188181796322589800e+00,2.407000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.189090887222599147e+00,2.408000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.189999978122608493e+00,2.408999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.190909069022617839e+00,2.410000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.191818159922627185e+00,2.410999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.192727250822636531e+00,2.412000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.193636341722645877e+00,2.412999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.194545432622655223e+00,2.414000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.195454523522664569e+00,2.415000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.196363614422673916e+00,2.416000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.197272705322683262e+00,2.417000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.198181796222692608e+00,2.417999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.199090887122701954e+00,2.419000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.199999978022711300e+00,2.419999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.200909068922720646e+00,2.421000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.201818159822729992e+00,2.421999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.202727250722739338e+00,2.423000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.203636341622748684e+00,2.424000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.204545432522758031e+00,2.425000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.205454523422767377e+00,2.426000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.206363614322776723e+00,2.426999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.207272705222786069e+00,2.428000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.208181796122795415e+00,2.428999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.209090887022804761e+00,2.430000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.209999977922814107e+00,2.431000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.210909068822823453e+00,2.432000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.211818159722832799e+00,2.433000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.212727250622842146e+00,2.433999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.213636341522851492e+00,2.435000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.214545432422860838e+00,2.435999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.215454523322870184e+00,2.437000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.216363614222879530e+00,2.437999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.217272705122888876e+00,2.439000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.218181796022898222e+00,2.440000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.219090886922907568e+00,2.441000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.219999977822916915e+00,2.442000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.220909068722926261e+00,2.442999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.221818159622935607e+00,2.444000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.222727250522944953e+00,2.444999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.223636341422954299e+00,2.446000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.224545432322963645e+00,2.446999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.225454523222972991e+00,2.448000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.226363614122982337e+00,2.449000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.227272705022991683e+00,2.450000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.228181795923001030e+00,2.451000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.229090886823010376e+00,2.451999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.229999977723019722e+00,2.453000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.230909068623029068e+00,2.453999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.231818159523038414e+00,2.455000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.232727250423047760e+00,2.456000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.233636341323057106e+00,2.457000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.234545432223066452e+00,2.458000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.235454523123075798e+00,2.458999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.236363614023085145e+00,2.460000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.237272704923094491e+00,2.460999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.238181795823103837e+00,2.462000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.239090886723113183e+00,2.462999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.239999977623122529e+00,2.464000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.240909068523131875e+00,2.465000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.241818159423141221e+00,2.466000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.242727250323150567e+00,2.467000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.243636341223159913e+00,2.467999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.244545432123169260e+00,2.469000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.245454523023178606e+00,2.469999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.246363613923187952e+00,2.471000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.247272704823197298e+00,2.471999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.248181795723206644e+00,2.473000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.249090886623215990e+00,2.474000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.249999977523225336e+00,2.475000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.250909068423234682e+00,2.476000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.251818159323244029e+00,2.476999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.252727250223253375e+00,2.478000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.253636341123262721e+00,2.478999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.254545432023272067e+00,2.480000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.255454522923281413e+00,2.481000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.256363613823290759e+00,2.482000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.257272704723300105e+00,2.483000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.258181795623309451e+00,2.483999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.259090886523318797e+00,2.485000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.259999977423328144e+00,2.485999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.260909068323337490e+00,2.487000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.261818159223346836e+00,2.487999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.262727250123356182e+00,2.489000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.263636341023365528e+00,2.490000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.264545431923374874e+00,2.491000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.265454522823384220e+00,2.492000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.266363613723393566e+00,2.492999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.267272704623402912e+00,2.494000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.268181795523412259e+00,2.494999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.269090886423421605e+00,2.496000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.269999977323430951e+00,2.496999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.270909068223440297e+00,2.498000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.271818159123449643e+00,2.499000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.272727250023458989e+00,2.500000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.273636340923468335e+00,2.501000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.274545431823477681e+00,2.501999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.275454522723487027e+00,2.503000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.276363613623496374e+00,2.503999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.277272704523505720e+00,2.505000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.278181795423515066e+00,2.506000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.279090886323524412e+00,2.507000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.279999977223533758e+00,2.508000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.280909068123543104e+00,2.508999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.281818159023552450e+00,2.510000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.282727249923561796e+00,2.510999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.283636340823571143e+00,2.512000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.284545431723580489e+00,2.512999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.285454522623589835e+00,2.514000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.286363613523599181e+00,2.515000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.287272704423608527e+00,2.516000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.288181795323617873e+00,2.517000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.289090886223627219e+00,2.517999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.289999977123636565e+00,2.519000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.290909068023645911e+00,2.519999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.291818158923655258e+00,2.521000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.292727249823664604e+00,2.521999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.293636340723673950e+00,2.523000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.294545431623683296e+00,2.524000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.295454522523692642e+00,2.525000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.296363613423701988e+00,2.526000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.297272704323711334e+00,2.526999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.298181795223720680e+00,2.528000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.299090886123730026e+00,2.528999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.299999977023739373e+00,2.530000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.300909067923748719e+00,2.531000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.301818158823758065e+00,2.532000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.302727249723767411e+00,2.533000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.303636340623776757e+00,2.533999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.304545431523786103e+00,2.535000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.305454522423795449e+00,2.535999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.306363613323804795e+00,2.537000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.307272704223814141e+00,2.537999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.308181795123823488e+00,2.539000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.309090886023832834e+00,2.540000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.309999976923842180e+00,2.541000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.310909067823851526e+00,2.542000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.311818158723860872e+00,2.542999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.312727249623870218e+00,2.544000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.313636340523879564e+00,2.544999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.314545431423888910e+00,2.546000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.315454522323898257e+00,2.546999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.316363613223907603e+00,2.548000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.317272704123916949e+00,2.549000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.318181795023926295e+00,2.550000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.319090885923935641e+00,2.551000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.319999976823944987e+00,2.551999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.320909067723954333e+00,2.553000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.321818158623963679e+00,2.553999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.322727249523973025e+00,2.555000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.323636340423982372e+00,2.556000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.324545431323991718e+00,2.557000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.325454522224001064e+00,2.558000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.326363613124010410e+00,2.558999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.327272704024019756e+00,2.560000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.328181794924029102e+00,2.560999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.329090885824038448e+00,2.562000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.329999976724047794e+00,2.562999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.330909067624057140e+00,2.564000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.331818158524066487e+00,2.565000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.332727249424075833e+00,2.566000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.333636340324085179e+00,2.567000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.334545431224094525e+00,2.567999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.335454522124103871e+00,2.569000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.336363613024113217e+00,2.569999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.337272703924122563e+00,2.571000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.338181794824131909e+00,2.571999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.339090885724141256e+00,2.573000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.339999976624150602e+00,2.574000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.340909067524159948e+00,2.575000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.341818158424169294e+00,2.576000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.342727249324178640e+00,2.576999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.343636340224187986e+00,2.578000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.344545431124197332e+00,2.578999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.345454522024206678e+00,2.580000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.346363612924216024e+00,2.581000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.347272703824225371e+00,2.582000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.348181794724234717e+00,2.583000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.349090885624244063e+00,2.583999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.349999976524253409e+00,2.585000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.350909067424262755e+00,2.585999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.351818158324272101e+00,2.587000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.352727249224281447e+00,2.587999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.353636340124290793e+00,2.589000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.354545431024300139e+00,2.590000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.355454521924309486e+00,2.591000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.356363612824318832e+00,2.592000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.357272703724328178e+00,2.592999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.358181794624337524e+00,2.594000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.359090885524346870e+00,2.594999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.359999976424356216e+00,2.596000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.360909067324365562e+00,2.596999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.361818158224374908e+00,2.598000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.362727249124384254e+00,2.599000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.363636340024393601e+00,2.600000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.364545430924402947e+00,2.601000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.365454521824412293e+00,2.601999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.366363612724421639e+00,2.603000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.367272703624430985e+00,2.603999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.368181794524440331e+00,2.605000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.369090885424449677e+00,2.606000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.369999976324459023e+00,2.607000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.370909067224468370e+00,2.608000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.371818158124477716e+00,2.608999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.372727249024487062e+00,2.610000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.373636339924496408e+00,2.610999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.374545430824505754e+00,2.612000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.375454521724515100e+00,2.612999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.376363612624524446e+00,2.614000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.377272703524533792e+00,2.615000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.378181794424543138e+00,2.616000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.379090885324552485e+00,2.617000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.379999976224561831e+00,2.617999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.380909067124571177e+00,2.619000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.381818158024580523e+00,2.619999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.382727248924589869e+00,2.621000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.383636339824599215e+00,2.621999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.384545430724608561e+00,2.623000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.385454521624617907e+00,2.624000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.386363612524627253e+00,2.625000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.387272703424636600e+00,2.626000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.388181794324645946e+00,2.626999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.389090885224655292e+00,2.628000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.389999976124664638e+00,2.628999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.390909067024673984e+00,2.630000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.391818157924683330e+00,2.631000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.392727248824692676e+00,2.632000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.393636339724702022e+00,2.633000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.394545430624711368e+00,2.633999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.395454521524720715e+00,2.635000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.396363612424730061e+00,2.635999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.397272703324739407e+00,2.637000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.398181794224748753e+00,2.637999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.399090885124758099e+00,2.639000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.399999976024767445e+00,2.640000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.400909066924776791e+00,2.641000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.401818157824786137e+00,2.642000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.402727248724795484e+00,2.642999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.403636339624804830e+00,2.644000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.404545430524814176e+00,2.644999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.405454521424823522e+00,2.646000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.406363612324832868e+00,2.646999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.407272703224842214e+00,2.648000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.408181794124851560e+00,2.649000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.409090885024860906e+00,2.650000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.409999975924870252e+00,2.651000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.410909066824879599e+00,2.651999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.411818157724888945e+00,2.653000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.412727248624898291e+00,2.653999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.413636339524907637e+00,2.655000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.414545430424916983e+00,2.656000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.415454521324926329e+00,2.657000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.416363612224935675e+00,2.658000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.417272703124945021e+00,2.658999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.418181794024954367e+00,2.660000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.419090884924963714e+00,2.660999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.419999975824973060e+00,2.662000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.420909066724982406e+00,2.662999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.421818157624991752e+00,2.664000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.422727248525001098e+00,2.665000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.423636339425010444e+00,2.666000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.424545430325019790e+00,2.667000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.425454521225029136e+00,2.667999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.426363612125038483e+00,2.669000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.427272703025047829e+00,2.669999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.428181793925057175e+00,2.671000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.429090884825066521e+00,2.671999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.429999975725075867e+00,2.673000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.430909066625085213e+00,2.674000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.431818157525094559e+00,2.675000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.432727248425103905e+00,2.676000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.433636339325113251e+00,2.676999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.434545430225122598e+00,2.678000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.435454521125131944e+00,2.678999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.436363612025141290e+00,2.680000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.437272702925150636e+00,2.681000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.438181793825159982e+00,2.682000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.439090884725169328e+00,2.683000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.439999975625178674e+00,2.683999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.440909066525188020e+00,2.685000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.441818157425197366e+00,2.685999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.442727248325206713e+00,2.687000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.443636339225216059e+00,2.687999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.444545430125225405e+00,2.689000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.445454521025234751e+00,2.690000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.446363611925244097e+00,2.691000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.447272702825253443e+00,2.692000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.448181793725262789e+00,2.692999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.449090884625272135e+00,2.694000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.449999975525281481e+00,2.694999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.450909066425290828e+00,2.696000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.451818157325300174e+00,2.696999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.452727248225309520e+00,2.698000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.453636339125318866e+00,2.699000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.454545430025328212e+00,2.700000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.455454520925337558e+00,2.701000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.456363611825346904e+00,2.701999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.457272702725356250e+00,2.703000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.458181793625365597e+00,2.703999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.459090884525374943e+00,2.705000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.459999975425384289e+00,2.706000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.460909066325393635e+00,2.707000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.461818157225402981e+00,2.708000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.462727248125412327e+00,2.708999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.463636339025421673e+00,2.710000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.464545429925431019e+00,2.710999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.465454520825440365e+00,2.712000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.466363611725449712e+00,2.712999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.467272702625459058e+00,2.714000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.468181793525468404e+00,2.715000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.469090884425477750e+00,2.716000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.469999975325487096e+00,2.717000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.470909066225496442e+00,2.717999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.471818157125505788e+00,2.719000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.472727248025515134e+00,2.719999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.473636338925524480e+00,2.721000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.474545429825533827e+00,2.721999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.475454520725543173e+00,2.723000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.476363611625552519e+00,2.724000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.477272702525561865e+00,2.725000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.478181793425571211e+00,2.726000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.479090884325580557e+00,2.726999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.479999975225589903e+00,2.728000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.480909066125599249e+00,2.728999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.481818157025608595e+00,2.730000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.482727247925617942e+00,2.731000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.483636338825627288e+00,2.732000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.484545429725636634e+00,2.733000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.485454520625645980e+00,2.733999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.486363611525655326e+00,2.735000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.487272702425664672e+00,2.735999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.488181793325674018e+00,2.737000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.489090884225683364e+00,2.737999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.489999975125692711e+00,2.739000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.490909066025702057e+00,2.740000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.491818156925711403e+00,2.741000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.492727247825720749e+00,2.742000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.493636338725730095e+00,2.742999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.494545429625739441e+00,2.744000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.495454520525748787e+00,2.744999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.496363611425758133e+00,2.746000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.497272702325767479e+00,2.746999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.498181793225776826e+00,2.748000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.499090884125786172e+00,2.749000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.499999975025795518e+00,2.750000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.500909065925804864e+00,2.751000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.501818156825814210e+00,2.751999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.502727247725823556e+00,2.753000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.503636338625832902e+00,2.753999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.504545429525842248e+00,2.755000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.505454520425851594e+00,2.756000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.506363611325860941e+00,2.757000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.507272702225870287e+00,2.758000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.508181793125879633e+00,2.758999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.509090884025888979e+00,2.760000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.509999974925898325e+00,2.760999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.510909065825907671e+00,2.762000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.511818156725917017e+00,2.762999999999999901e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.512727247625926363e+00,2.764000000000000057e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.513636338525935709e+00,2.765000000000000213e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.514545429425945056e+00,2.766000000000000014e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.515454520325954402e+00,2.767000000000000171e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.516363611225963748e+00,2.767999999999999972e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.517272702125973094e+00,2.769000000000000128e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.518181793025982440e+00,2.769999999999999929e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.519090883925991786e+00,2.771000000000000085e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.519999974826001132e+00,2.771999999999999886e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.520909065726010478e+00,2.773000000000000043e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.521818156626019825e+00,2.774000000000000199e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.522727247526029171e+00,2.775000000000000000e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.523636338426038517e+00,2.776000000000000156e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.524545429326047863e+00,2.776999999999999957e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.525454520226057209e+00,2.778000000000000114e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.526363611126066555e+00,2.778999999999999915e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.527272702026075901e+00,2.780000000000000071e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.528181792926085247e+00,2.781000000000000227e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.529090883826094593e+00,2.782000000000000028e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.529999974726103940e+00,2.783000000000000185e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.530909065626113286e+00,2.783999999999999986e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.531818156526122632e+00,2.785000000000000142e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.532727247426131978e+00,2.785999999999999943e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,-2.149391818617624445e-09,0.000000000000000000e+00 +2.533636338326141324e+00,2.787000000000000099e+01,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,-1.953992542859966880e-12,0.000000000000000000e+00,3.868905273511724332e-08,0.000000000000000000e+00 +2.534545429226150670e+00,2.787999999999999901e+01,0.000000000000000000e+00,1.100000010988609311e+01,0.000000000000000000e+00,3.321787322861943736e-11,0.000000000000000000e+00,1.374987440287883992e-04,0.000000000000000000e+00 +2.535454520126160016e+00,2.789000000000000057e+01,0.000000000000000000e+00,1.100000010988612331e+01,0.000000000000000000e+00,1.250320748325238896e-07,0.000000000000000000e+00,-7.068131846101998184e-01,0.000000000000000000e+00 +2.536363611026169362e+00,2.790000000000000213e+01,0.000000000000000000e+00,1.100000010999978883e+01,0.000000000000000000e+00,-6.424324020609722616e-04,0.000000000000000000e+00,-9.999997522990923260e-01,0.000000000000000000e+00 +2.537272701926169383e+00,2.791000000000000014e+01,0.000000000000000000e+00,1.099999952597033825e+01,0.000000000000000000e+00,-1.551523076878348704e-03,0.000000000000000000e+00,-9.999998818725062133e-01,0.000000000000000000e+00 +2.538181792874436127e+00,2.792000000000000171e+01,0.000000000000000000e+00,1.099999811549475304e+01,0.000000000000000000e+00,-2.460613917756629323e-03,0.000000000000000000e+00,-9.999999237093354365e-01,0.000000000000000000e+00 +2.539090883939271404e+00,2.792999999999999972e+01,0.000000000000000000e+00,1.099999587857262640e+01,0.000000000000000000e+00,-3.369704913236638930e-03,0.000000000000000000e+00,-9.999999465892952522e-01,0.000000000000000000e+00 +2.539999975188976133e+00,2.794000000000000128e+01,0.000000000000000000e+00,1.099999281520337568e+01,0.000000000000000000e+00,-4.278796114386303889e-03,0.000000000000000000e+00,-9.999999569593628346e-01,0.000000000000000000e+00 +2.540909066691852125e+00,2.794999999999999929e+01,0.000000000000000000e+00,1.099998892538618556e+01,0.000000000000000000e+00,-5.187887578134568398e-03,0.000000000000000000e+00,-9.999999677142844545e-01,0.000000000000000000e+00 +2.541818158516201187e+00,2.796000000000000085e+01,0.000000000000000000e+00,1.099998420912000263e+01,0.000000000000000000e+00,-6.096979373133058940e-03,0.000000000000000000e+00,-9.999999745532950346e-01,0.000000000000000000e+00 +2.542727250730325572e+00,2.796999999999999886e+01,0.000000000000000000e+00,1.099997866640352484e+01,0.000000000000000000e+00,-7.006071564123844859e-03,0.000000000000000000e+00,-9.999999753246419099e-01,0.000000000000000000e+00 +2.543636343402527089e+00,2.798000000000000043e+01,0.000000000000000000e+00,1.099997229723520498e+01,0.000000000000000000e+00,-7.915164213893132947e-03,0.000000000000000000e+00,-9.999999829218478853e-01,0.000000000000000000e+00 +2.544545436601108435e+00,2.799000000000000199e+01,0.000000000000000000e+00,1.099996510161325247e+01,0.000000000000000000e+00,-8.824257396948869889e-03,0.000000000000000000e+00,-9.999999844454455777e-01,0.000000000000000000e+00 +2.545454530394372750e+00,2.800000000000000000e+01,0.000000000000000000e+00,1.099995707953562274e+01,0.000000000000000000e+00,-9.733351176072574384e-03,0.000000000000000000e+00,-9.999999841906479503e-01,0.000000000000000000e+00 +2.546363624850623175e+00,2.801000000000000156e+01,0.000000000000000000e+00,1.099994823100002783e+01,0.000000000000000000e+00,-1.064244561795094600e-02,0.000000000000000000e+00,-9.999999907509873331e-01,0.000000000000000000e+00 +2.547272720038164184e+00,2.801999999999999957e+01,0.000000000000000000e+00,1.099993855600393289e+01,0.000000000000000000e+00,-1.155154079708350760e-02,0.000000000000000000e+00,-9.999999890764927901e-01,0.000000000000000000e+00 +2.548181816025299806e+00,2.803000000000000114e+01,0.000000000000000000e+00,1.099992805454454903e+01,0.000000000000000000e+00,-1.246063677428846904e-02,0.000000000000000000e+00,-9.999999920586462032e-01,0.000000000000000000e+00 +2.549090912880334958e+00,2.803999999999999915e+01,0.000000000000000000e+00,1.099991672661884579e+01,0.000000000000000000e+00,-1.336973362210421706e-02,0.000000000000000000e+00,-9.999999910948353943e-01,0.000000000000000000e+00 +2.550000010671575446e+00,2.805000000000000071e+01,0.000000000000000000e+00,1.099990457222354046e+01,0.000000000000000000e+00,-1.427883140524917674e-02,0.000000000000000000e+00,-9.999999947769593334e-01,0.000000000000000000e+00 +2.550909109467327962e+00,2.806000000000000227e+01,0.000000000000000000e+00,1.099989159135510519e+01,0.000000000000000000e+00,-1.518793019625334050e-02,0.000000000000000000e+00,-9.999999945016497804e-01,0.000000000000000000e+00 +2.551818209335899201e+00,2.807000000000000028e+01,0.000000000000000000e+00,1.099987778400975991e+01,0.000000000000000000e+00,-1.609703005982613885e-02,0.000000000000000000e+00,-9.999999967106418808e-01,0.000000000000000000e+00 +2.552727310345597189e+00,2.808000000000000185e+01,0.000000000000000000e+00,1.099986315018347938e+01,0.000000000000000000e+00,-1.700613106653397349e-02,0.000000000000000000e+00,-9.999999949491740203e-01,0.000000000000000000e+00 +2.553636412564730840e+00,2.808999999999999986e+01,0.000000000000000000e+00,1.099984768987198791e+01,0.000000000000000000e+00,-1.791523328107606436e-02,0.000000000000000000e+00,-9.999999978074770590e-01,0.000000000000000000e+00 +2.554545516061609955e+00,2.810000000000000142e+01,0.000000000000000000e+00,1.099983140307076468e+01,0.000000000000000000e+00,-1.882433677596192373e-02,0.000000000000000000e+00,-9.999999966807078255e-01,0.000000000000000000e+00 +2.555454620904544782e+00,2.810999999999999943e+01,0.000000000000000000e+00,1.099981428977503661e+01,0.000000000000000000e+00,-1.973344161587932757e-02,0.000000000000000000e+00,-9.999999980089230300e-01,0.000000000000000000e+00 +2.556363727161847343e+00,2.812000000000000099e+01,0.000000000000000000e+00,1.099979634997978550e+01,0.000000000000000000e+00,-2.064254787137173239e-02,0.000000000000000000e+00,-9.999999974851963014e-01,0.000000000000000000e+00 +2.557272834901830105e+00,2.812999999999999901e+01,0.000000000000000000e+00,1.099977758367974268e+01,0.000000000000000000e+00,-2.155165560906819808e-02,0.000000000000000000e+00,-1.000000001548723816e+00,0.000000000000000000e+00 +2.558181944192806867e+00,2.814000000000000057e+01,0.000000000000000000e+00,1.099975799086939254e+01,0.000000000000000000e+00,-2.246076490145281282e-02,0.000000000000000000e+00,-9.999999994438935058e-01,0.000000000000000000e+00 +2.559091055103092316e+00,2.815000000000000213e+01,0.000000000000000000e+00,1.099973757154296727e+01,0.000000000000000000e+00,-2.336987581123279797e-02,0.000000000000000000e+00,-9.999999976091591414e-01,0.000000000000000000e+00 +2.560000167701002916e+00,2.816000000000000014e+01,0.000000000000000000e+00,1.099971632569445568e+01,0.000000000000000000e+00,-2.427898840696983071e-02,0.000000000000000000e+00,-1.000000002482432704e+00,0.000000000000000000e+00 +2.560909282054856018e+00,2.817000000000000171e+01,0.000000000000000000e+00,1.099969425331759787e+01,0.000000000000000000e+00,-2.518810276307964502e-02,0.000000000000000000e+00,-9.999999990084799117e-01,0.000000000000000000e+00 +2.561818398232970306e+00,2.817999999999999972e+01,0.000000000000000000e+00,1.099967135440587995e+01,0.000000000000000000e+00,-2.609721894029236322e-02,0.000000000000000000e+00,-1.000000002221549833e+00,0.000000000000000000e+00 +2.562727516303665798e+00,2.819000000000000128e+01,0.000000000000000000e+00,1.099964762895254644e+01,0.000000000000000000e+00,-2.700633701300732964e-02,0.000000000000000000e+00,-9.999999992149618544e-01,0.000000000000000000e+00 +2.563636636335263841e+00,2.819999999999999929e+01,0.000000000000000000e+00,1.099962307695058783e+01,0.000000000000000000e+00,-2.791545704389161719e-02,0.000000000000000000e+00,-1.000000002872786675e+00,0.000000000000000000e+00 +2.564545758396087560e+00,2.821000000000000085e+01,0.000000000000000000e+00,1.099959769839275125e+01,0.000000000000000000e+00,-2.882457910732691767e-02,0.000000000000000000e+00,-1.000000002436897351e+00,0.000000000000000000e+00 +2.565454882554461413e+00,2.821999999999999886e+01,0.000000000000000000e+00,1.099957149327152983e+01,0.000000000000000000e+00,-2.973370326791600557e-02,0.000000000000000000e+00,-1.000000002193541349e+00,0.000000000000000000e+00 +2.566364008878711189e+00,2.823000000000000043e+01,0.000000000000000000e+00,1.099954446157917154e+01,0.000000000000000000e+00,-3.064282959415993643e-02,0.000000000000000000e+00,-9.999999999808436568e-01,0.000000000000000000e+00 +2.567273137437164454e+00,2.824000000000000199e+01,0.000000000000000000e+00,1.099951660330767567e+01,0.000000000000000000e+00,-3.155195815259596165e-02,0.000000000000000000e+00,-1.000000004382590735e+00,0.000000000000000000e+00 +2.568182268298150994e+00,2.825000000000000000e+01,0.000000000000000000e+00,1.099948791844879459e+01,0.000000000000000000e+00,-3.246108901756677295e-02,0.000000000000000000e+00,-1.000000002490071704e+00,0.000000000000000000e+00 +2.569091401530001484e+00,2.826000000000000156e+01,0.000000000000000000e+00,1.099945840699402666e+01,0.000000000000000000e+00,-3.337022225168109063e-02,0.000000000000000000e+00,-1.000000000737105932e+00,0.000000000000000000e+00 +2.570000537201048818e+00,2.826999999999999957e+01,0.000000000000000000e+00,1.099942806893462688e+01,0.000000000000000000e+00,-3.427935792339857624e-02,0.000000000000000000e+00,-1.000000005556918925e+00,0.000000000000000000e+00 +2.570909675379627668e+00,2.828000000000000114e+01,0.000000000000000000e+00,1.099939690426160155e+01,0.000000000000000000e+00,-3.518849610702940583e-02,0.000000000000000000e+00,-1.000000001890707590e+00,0.000000000000000000e+00 +2.571818816134074481e+00,2.828999999999999915e+01,0.000000000000000000e+00,1.099936491296570296e+01,0.000000000000000000e+00,-3.609763686319510806e-02,0.000000000000000000e+00,-1.000000002618423922e+00,0.000000000000000000e+00 +2.572727959532727482e+00,2.830000000000000071e+01,0.000000000000000000e+00,1.099933209503744180e+01,0.000000000000000000e+00,-3.700678026422879463e-02,0.000000000000000000e+00,-1.000000005575435447e+00,0.000000000000000000e+00 +2.573637105643927558e+00,2.831000000000000227e+01,0.000000000000000000e+00,1.099929845046707655e+01,0.000000000000000000e+00,-3.791592638049762209e-02,0.000000000000000000e+00,-1.000000002149413092e+00,0.000000000000000000e+00 +2.574546254536016487e+00,2.832000000000000028e+01,0.000000000000000000e+00,1.099926397924461519e+01,0.000000000000000000e+00,-3.882507527454090446e-02,0.000000000000000000e+00,-1.000000005218870447e+00,0.000000000000000000e+00 +2.575455406277339154e+00,2.833000000000000185e+01,0.000000000000000000e+00,1.099922868135982235e+01,0.000000000000000000e+00,-3.973422702060850492e-02,0.000000000000000000e+00,-1.000000001872545452e+00,0.000000000000000000e+00 +2.576364560936242221e+00,2.833999999999999986e+01,0.000000000000000000e+00,1.099919255680220864e+01,0.000000000000000000e+00,-4.064338168121413991e-02,0.000000000000000000e+00,-1.000000004987995128e+00,0.000000000000000000e+00 +2.577273718581074569e+00,2.835000000000000142e+01,0.000000000000000000e+00,1.099915560556104133e+01,0.000000000000000000e+00,-4.155253933058138116e-02,0.000000000000000000e+00,-1.000000005951412030e+00,0.000000000000000000e+00 +2.578182879280187301e+00,2.835999999999999943e+01,0.000000000000000000e+00,1.099911782762533363e+01,0.000000000000000000e+00,-4.246170003510475743e-02,0.000000000000000000e+00,-1.000000002596025617e+00,0.000000000000000000e+00 +2.579092043101933296e+00,2.837000000000000099e+01,0.000000000000000000e+00,1.099907922298385188e+01,0.000000000000000000e+00,-4.337086385921111453e-02,0.000000000000000000e+00,-1.000000003499848189e+00,0.000000000000000000e+00 +2.580001210114668542e+00,2.837999999999999901e+01,0.000000000000000000e+00,1.099903979162511725e+01,0.000000000000000000e+00,-4.428003087512843994e-02,0.000000000000000000e+00,-1.000000004346146776e+00,0.000000000000000000e+00 +2.580910380386751246e+00,2.839000000000000057e+01,0.000000000000000000e+00,1.099899953353739868e+01,0.000000000000000000e+00,-4.518920115116250441e-02,0.000000000000000000e+00,-1.000000007264918001e+00,0.000000000000000000e+00 +2.581819553986541838e+00,2.840000000000000213e+01,0.000000000000000000e+00,1.099895844870871642e+01,0.000000000000000000e+00,-4.609837475755805547e-02,0.000000000000000000e+00,-1.000000003640809210e+00,0.000000000000000000e+00 +2.582728730982402965e+00,2.841000000000000014e+01,0.000000000000000000e+00,1.099891653712684025e+01,0.000000000000000000e+00,-4.700755175672947234e-02,0.000000000000000000e+00,-1.000000004199039783e+00,0.000000000000000000e+00 +2.583637911442700386e+00,2.842000000000000171e+01,0.000000000000000000e+00,1.099887379877929661e+01,0.000000000000000000e+00,-4.791673222084476963e-02,0.000000000000000000e+00,-1.000000004621376837e+00,0.000000000000000000e+00 +2.584547095435802522e+00,2.842999999999999972e+01,0.000000000000000000e+00,1.099883023365335966e+01,0.000000000000000000e+00,-4.882591621814853095e-02,0.000000000000000000e+00,-1.000000004887296789e+00,0.000000000000000000e+00 +2.585456283030080016e+00,2.844000000000000128e+01,0.000000000000000000e+00,1.099878584173605489e+01,0.000000000000000000e+00,-4.973510381686932491e-02,0.000000000000000000e+00,-1.000000004975793555e+00,0.000000000000000000e+00 +2.586365474293906175e+00,2.844999999999999929e+01,0.000000000000000000e+00,1.099874062301415911e+01,0.000000000000000000e+00,-5.064429508521931661e-02,0.000000000000000000e+00,-1.000000007014415715e+00,0.000000000000000000e+00 +2.587274669295656970e+00,2.846000000000000085e+01,0.000000000000000000e+00,1.099869457747420043e+01,0.000000000000000000e+00,-5.155349009334777438e-02,0.000000000000000000e+00,-1.000000004534691511e+00,0.000000000000000000e+00 +2.588183868103711927e+00,2.846999999999999886e+01,0.000000000000000000e+00,1.099864770510245648e+01,0.000000000000000000e+00,-5.246268890552566178e-02,0.000000000000000000e+00,-1.000000003961180495e+00,0.000000000000000000e+00 +2.589093070786452788e+00,2.848000000000000043e+01,0.000000000000000000e+00,1.099860000588495978e+01,0.000000000000000000e+00,-5.337189159186796900e-02,0.000000000000000000e+00,-1.000000007420102088e+00,0.000000000000000000e+00 +2.590002277412264409e+00,2.849000000000000199e+01,0.000000000000000000e+00,1.099855147980749237e+01,0.000000000000000000e+00,-5.428109822442578336e-02,0.000000000000000000e+00,-1.000000004144240062e+00,0.000000000000000000e+00 +2.590911488049534306e+00,2.850000000000000000e+01,0.000000000000000000e+00,1.099850212685558404e+01,0.000000000000000000e+00,-5.519030886546352765e-02,0.000000000000000000e+00,-1.000000004854519897e+00,0.000000000000000000e+00 +2.591820702766653106e+00,2.851000000000000156e+01,0.000000000000000000e+00,1.099845194701452122e+01,0.000000000000000000e+00,-5.609952358699617225e-02,0.000000000000000000e+00,-1.000000007378212041e+00,0.000000000000000000e+00 +2.592729921632014989e+00,2.851999999999999957e+01,0.000000000000000000e+00,1.099840094026933812e+01,0.000000000000000000e+00,-5.700874245906630694e-02,0.000000000000000000e+00,-1.000000005244867429e+00,0.000000000000000000e+00 +2.593639144714016354e+00,2.853000000000000114e+01,0.000000000000000000e+00,1.099834910660481846e+01,0.000000000000000000e+00,-5.791796554583657219e-02,0.000000000000000000e+00,-1.000000004876296700e+00,0.000000000000000000e+00 +2.594548372081057597e+00,2.853999999999999915e+01,0.000000000000000000e+00,1.099829644600550083e+01,0.000000000000000000e+00,-5.882719291731159511e-02,0.000000000000000000e+00,-1.000000006247519835e+00,0.000000000000000000e+00 +2.595457603801542223e+00,2.855000000000000071e+01,0.000000000000000000e+00,1.099824295845567335e+01,0.000000000000000000e+00,-5.973642464347652531e-02,0.000000000000000000e+00,-1.000000005035709405e+00,0.000000000000000000e+00 +2.596366839943876403e+00,2.856000000000000227e+01,0.000000000000000000e+00,1.099818864393937368e+01,0.000000000000000000e+00,-6.064566079038932744e-02,0.000000000000000000e+00,-1.000000007661270063e+00,0.000000000000000000e+00 +2.597276080576469859e+00,2.857000000000000028e+01,0.000000000000000000e+00,1.099813350244039256e+01,0.000000000000000000e+00,-6.155490142994893971e-02,0.000000000000000000e+00,-1.000000005503293599e+00,0.000000000000000000e+00 +2.598185325767736309e+00,2.858000000000000185e+01,0.000000000000000000e+00,1.099807753394226850e+01,0.000000000000000000e+00,-6.246414662621919967e-02,0.000000000000000000e+00,-1.000000004981354218e+00,0.000000000000000000e+00 +2.599094575586092137e+00,2.858999999999999986e+01,0.000000000000000000e+00,1.099802073842829486e+01,0.000000000000000000e+00,-6.337339644910429393e-02,0.000000000000000000e+00,-1.000000006068411551e+00,0.000000000000000000e+00 +2.600003830099957280e+00,2.860000000000000142e+01,0.000000000000000000e+00,1.099796311588151454e+01,0.000000000000000000e+00,-6.428265096848731486e-02,0.000000000000000000e+00,-1.000000006588535273e+00,0.000000000000000000e+00 +2.600913089377755671e+00,2.860999999999999943e+01,0.000000000000000000e+00,1.099790466628471997e+01,0.000000000000000000e+00,-6.519191025227641378e-02,0.000000000000000000e+00,-1.000000006513994677e+00,0.000000000000000000e+00 +2.601822353487914352e+00,2.862000000000000099e+01,0.000000000000000000e+00,1.099784538962045488e+01,0.000000000000000000e+00,-6.610117436835809268e-02,0.000000000000000000e+00,-1.000000005816713777e+00,0.000000000000000000e+00 +2.602731622498864361e+00,2.862999999999999901e+01,0.000000000000000000e+00,1.099778528587101434e+01,0.000000000000000000e+00,-6.701044338459694050e-02,0.000000000000000000e+00,-1.000000006616680315e+00,0.000000000000000000e+00 +2.603640896479039846e+00,2.864000000000000057e+01,0.000000000000000000e+00,1.099772435501844470e+01,0.000000000000000000e+00,-6.791971737078886240e-02,0.000000000000000000e+00,-1.000000006736448510e+00,0.000000000000000000e+00 +2.604550175496879394e+00,2.865000000000000213e+01,0.000000000000000000e+00,1.099766259704454185e+01,0.000000000000000000e+00,-6.882899639475360820e-02,0.000000000000000000e+00,-1.000000006146736453e+00,0.000000000000000000e+00 +2.605459459620824703e+00,2.866000000000000014e+01,0.000000000000000000e+00,1.099760001193085301e+01,0.000000000000000000e+00,-6.973828052428807101e-02,0.000000000000000000e+00,-1.000000006966289989e+00,0.000000000000000000e+00 +2.606368748919321909e+00,2.867000000000000171e+01,0.000000000000000000e+00,1.099753659965867669e+01,0.000000000000000000e+00,-7.064756982911951644e-02,0.000000000000000000e+00,-1.000000004868101922e+00,0.000000000000000000e+00 +2.607278043460820260e+00,2.867999999999999972e+01,0.000000000000000000e+00,1.099747236020906094e+01,0.000000000000000000e+00,-7.155686437504459041e-02,0.000000000000000000e+00,-1.000000006266980712e+00,0.000000000000000000e+00 +2.608187343313773887e+00,2.869000000000000128e+01,0.000000000000000000e+00,1.099740729356280688e+01,0.000000000000000000e+00,-7.246616423369681148e-02,0.000000000000000000e+00,-1.000000008983468414e+00,0.000000000000000000e+00 +2.609096648546640473e+00,2.869999999999999929e+01,0.000000000000000000e+00,1.099734139970046343e+01,0.000000000000000000e+00,-7.337546947473194692e-02,0.000000000000000000e+00,-1.000000004392872288e+00,0.000000000000000000e+00 +2.610005959227881256e+00,2.871000000000000085e+01,0.000000000000000000e+00,1.099727467860232899e+01,0.000000000000000000e+00,-7.428478015996729800e-02,0.000000000000000000e+00,-1.000000007501998356e+00,0.000000000000000000e+00 +2.610915275425962356e+00,2.871999999999999886e+01,0.000000000000000000e+00,1.099720713024845864e+01,0.000000000000000000e+00,-7.519409636487006665e-02,0.000000000000000000e+00,-1.000000005388657742e+00,0.000000000000000000e+00 +2.611824597209353449e+00,2.873000000000000043e+01,0.000000000000000000e+00,1.099713875461865165e+01,0.000000000000000000e+00,-7.610341815316129521e-02,0.000000000000000000e+00,-1.000000008761930959e+00,0.000000000000000000e+00 +2.612733924646529093e+00,2.874000000000000199e+01,0.000000000000000000e+00,1.099706955169246214e+01,0.000000000000000000e+00,-7.701274559830419142e-02,0.000000000000000000e+00,-1.000000004699226119e+00,0.000000000000000000e+00 +2.613643257805966957e+00,2.875000000000000000e+01,0.000000000000000000e+00,1.099699952144919024e+01,0.000000000000000000e+00,-7.792207876201535932e-02,0.000000000000000000e+00,-1.000000008205061519e+00,0.000000000000000000e+00 +2.614552596756150038e+00,2.876000000000000156e+01,0.000000000000000000e+00,1.099692866386789269e+01,0.000000000000000000e+00,-7.883141771965976319e-02,0.000000000000000000e+00,-1.000000006356274840e+00,0.000000000000000000e+00 +2.615461941565565329e+00,2.876999999999999957e+01,0.000000000000000000e+00,1.099685697892737046e+01,0.000000000000000000e+00,-7.974076253485523624e-02,0.000000000000000000e+00,-1.000000007711652428e+00,0.000000000000000000e+00 +2.616371292302704266e+00,2.878000000000000114e+01,0.000000000000000000e+00,1.099678446660617936e+01,0.000000000000000000e+00,-8.065011327900685478e-02,0.000000000000000000e+00,-1.000000005792201385e+00,0.000000000000000000e+00 +2.617280649036062723e+00,2.878999999999999915e+01,0.000000000000000000e+00,1.099671112688262298e+01,0.000000000000000000e+00,-8.155947001763248771e-02,0.000000000000000000e+00,-1.000000007007449287e+00,0.000000000000000000e+00 +2.618190011834141018e+00,2.880000000000000071e+01,0.000000000000000000e+00,1.099663695973475797e+01,0.000000000000000000e+00,-8.246883282208303245e-02,0.000000000000000000e+00,-1.000000007025783066e+00,0.000000000000000000e+00 +2.619099380765443907e+00,2.881000000000000227e+01,0.000000000000000000e+00,1.099656196514038875e+01,0.000000000000000000e+00,-8.337820175977496417e-02,0.000000000000000000e+00,-1.000000007959658710e+00,0.000000000000000000e+00 +2.620008755898481034e+00,2.882000000000000028e+01,0.000000000000000000e+00,1.099648614307707106e+01,0.000000000000000000e+00,-8.428757690005035663e-02,0.000000000000000000e+00,-1.000000005476903819e+00,0.000000000000000000e+00 +2.620918137301766482e+00,2.883000000000000185e+01,0.000000000000000000e+00,1.099640949352211017e+01,0.000000000000000000e+00,-8.519695830831636174e-02,0.000000000000000000e+00,-1.000000008133109963e+00,0.000000000000000000e+00 +2.621827525043819218e+00,2.883999999999999986e+01,0.000000000000000000e+00,1.099633201645256442e+01,0.000000000000000000e+00,-8.610634605776512629e-02,0.000000000000000000e+00,-1.000000005151403082e+00,0.000000000000000000e+00 +2.622736919193162652e+00,2.885000000000000142e+01,0.000000000000000000e+00,1.099625371184523814e+01,0.000000000000000000e+00,-8.701574021179322993e-02,0.000000000000000000e+00,-1.000000009382264077e+00,0.000000000000000000e+00 +2.623646319818325523e+00,2.885999999999999943e+01,0.000000000000000000e+00,1.099617457967669054e+01,0.000000000000000000e+00,-8.792514084548819220e-02,0.000000000000000000e+00,-1.000000005752423871e+00,0.000000000000000000e+00 +2.624555726987841009e+00,2.887000000000000099e+01,0.000000000000000000e+00,1.099609461992322501e+01,0.000000000000000000e+00,-8.883454802023479924e-02,0.000000000000000000e+00,-1.000000007111351286e+00,0.000000000000000000e+00 +2.625465140770247174e+00,2.887999999999999901e+01,0.000000000000000000e+00,1.099601383256090159e+01,0.000000000000000000e+00,-8.974396180910808318e-02,0.000000000000000000e+00,-1.000000006976840883e+00,0.000000000000000000e+00 +2.626374561234087412e+00,2.889000000000000057e+01,0.000000000000000000e+00,1.099593221756552630e+01,0.000000000000000000e+00,-9.065338227929309323e-02,0.000000000000000000e+00,-1.000000007457819917e+00,0.000000000000000000e+00 +2.627283988447909557e+00,2.890000000000000213e+01,0.000000000000000000e+00,1.099584977491265647e+01,0.000000000000000000e+00,-9.156280949989778484e-02,0.000000000000000000e+00,-1.000000008515018912e+00,0.000000000000000000e+00 +2.628193422480267216e+00,2.891000000000000014e+01,0.000000000000000000e+00,1.099576650457759897e+01,0.000000000000000000e+00,-9.247224353999948521e-02,0.000000000000000000e+00,-1.000000005813249881e+00,0.000000000000000000e+00 +2.629102863399718881e+00,2.892000000000000171e+01,0.000000000000000000e+00,1.099568240653541018e+01,0.000000000000000000e+00,-9.338168446473806006e-02,0.000000000000000000e+00,-1.000000007903408594e+00,0.000000000000000000e+00 +2.630012311274827930e+00,2.892999999999999972e+01,0.000000000000000000e+00,1.099559748076089960e+01,0.000000000000000000e+00,-9.429113234703506707e-02,0.000000000000000000e+00,-1.000000006154061261e+00,0.000000000000000000e+00 +2.630921766174163512e+00,2.894000000000000128e+01,0.000000000000000000e+00,1.099551172722862269e+01,0.000000000000000000e+00,-9.520058725196749172e-02,0.000000000000000000e+00,-1.000000009115097122e+00,0.000000000000000000e+00 +2.631831228166299663e+00,2.894999999999999929e+01,0.000000000000000000e+00,1.099542514591288800e+01,0.000000000000000000e+00,-9.611004925239331753e-02,0.000000000000000000e+00,-1.000000006006940501e+00,0.000000000000000000e+00 +2.632740697319815304e+00,2.896000000000000085e+01,0.000000000000000000e+00,1.099533773678775006e+01,0.000000000000000000e+00,-9.701951841137226862e-02,0.000000000000000000e+00,-1.000000007526119061e+00,0.000000000000000000e+00 +2.633650173703295572e+00,2.896999999999999886e+01,0.000000000000000000e+00,1.099524949982701827e+01,0.000000000000000000e+00,-9.792899480169756088e-02,0.000000000000000000e+00,-1.000000007187601181e+00,0.000000000000000000e+00 +2.634559657385330933e+00,2.898000000000000043e+01,0.000000000000000000e+00,1.099516043500424800e+01,0.000000000000000000e+00,-9.883847849026991539e-02,0.000000000000000000e+00,-1.000000007096567112e+00,0.000000000000000000e+00 +2.635469148434516740e+00,2.899000000000000199e+01,0.000000000000000000e+00,1.099507054229274594e+01,0.000000000000000000e+00,-9.974796954591014231e-02,0.000000000000000000e+00,-1.000000009357537634e+00,0.000000000000000000e+00 +2.636378646919454560e+00,2.900000000000000000e+01,0.000000000000000000e+00,1.099497982166556831e+01,0.000000000000000000e+00,-1.006574680393586552e-01,0.000000000000000000e+00,-1.000000005337384978e+00,0.000000000000000000e+00 +2.637288152908751293e+00,2.901000000000000156e+01,0.000000000000000000e+00,1.099488827309551908e+01,0.000000000000000000e+00,-1.015669740335096299e-01,0.000000000000000000e+00,-1.000000007877145825e+00,0.000000000000000000e+00 +2.638197666471019165e+00,2.901999999999999957e+01,0.000000000000000000e+00,1.099479589655515710e+01,0.000000000000000000e+00,-1.024764876029418403e-01,0.000000000000000000e+00,-1.000000008342868396e+00,0.000000000000000000e+00 +2.639107187674876620e+00,2.903000000000000114e+01,0.000000000000000000e+00,1.099470269201678541e+01,0.000000000000000000e+00,-1.033860088143871425e-01,0.000000000000000000e+00,-1.000000006690217047e+00,0.000000000000000000e+00 +2.640016716588947432e+00,2.903999999999999915e+01,0.000000000000000000e+00,1.099460865945245835e+01,0.000000000000000000e+00,-1.042955377345427675e-01,0.000000000000000000e+00,-1.000000007168975635e+00,0.000000000000000000e+00 +2.640926253281861147e+00,2.905000000000000071e+01,0.000000000000000000e+00,1.099451379883398161e+01,0.000000000000000000e+00,-1.052050744339770305e-01,0.000000000000000000e+00,-1.000000007586481443e+00,0.000000000000000000e+00 +2.641835797822253529e+00,2.906000000000000227e+01,0.000000000000000000e+00,1.099441811013290859e+01,0.000000000000000000e+00,-1.061146189812698232e-01,0.000000000000000000e+00,-1.000000007896988174e+00,0.000000000000000000e+00 +2.642745350278766114e+00,2.907000000000000028e+01,0.000000000000000000e+00,1.099432159332054226e+01,0.000000000000000000e+00,-1.070241714449653297e-01,0.000000000000000000e+00,-1.000000008054433565e+00,0.000000000000000000e+00 +2.643654910720046658e+00,2.908000000000000185e+01,0.000000000000000000e+00,1.099422424836793510e+01,0.000000000000000000e+00,-1.079337318935717910e-01,0.000000000000000000e+00,-1.000000008012318808e+00,0.000000000000000000e+00 +2.644564479214748243e+00,2.908999999999999986e+01,0.000000000000000000e+00,1.099412607524588914e+01,0.000000000000000000e+00,-1.088433003955611572e-01,0.000000000000000000e+00,-1.000000005576669571e+00,0.000000000000000000e+00 +2.645474055831530613e+00,2.910000000000000142e+01,0.000000000000000000e+00,1.099402707392495593e+01,0.000000000000000000e+00,-1.097528770174158452e-01,0.000000000000000000e+00,-1.000000009288492420e+00,0.000000000000000000e+00 +2.646383640639059287e+00,2.910999999999999943e+01,0.000000000000000000e+00,1.099392724437543833e+01,0.000000000000000000e+00,-1.106624618333930943e-01,0.000000000000000000e+00,-1.000000006217621307e+00,0.000000000000000000e+00 +2.647293233706005999e+00,2.912000000000000099e+01,0.000000000000000000e+00,1.099382658656738343e+01,0.000000000000000000e+00,-1.115720549059952688e-01,0.000000000000000000e+00,-1.000000009198247497e+00,0.000000000000000000e+00 +2.648202835101048702e+00,2.912999999999999901e+01,0.000000000000000000e+00,1.099372510047059315e+01,0.000000000000000000e+00,-1.124816563094047789e-01,0.000000000000000000e+00,-1.000000007446770089e+00,0.000000000000000000e+00 +2.649112444892872009e+00,2.914000000000000057e+01,0.000000000000000000e+00,1.099362278605461363e+01,0.000000000000000000e+00,-1.133912661080015843e-01,0.000000000000000000e+00,-1.000000007355222431e+00,0.000000000000000000e+00 +2.650022063150166307e+00,2.915000000000000213e+01,0.000000000000000000e+00,1.099351964328874409e+01,0.000000000000000000e+00,-1.143008843719861556e-01,0.000000000000000000e+00,-1.000000006727357116e+00,0.000000000000000000e+00 +2.650931689941628200e+00,2.916000000000000014e+01,0.000000000000000000e+00,1.099341567214203153e+01,0.000000000000000000e+00,-1.152105111695676115e-01,0.000000000000000000e+00,-1.000000009807132884e+00,0.000000000000000000e+00 +2.651841325335961397e+00,2.917000000000000171e+01,0.000000000000000000e+00,1.099331087258327244e+01,0.000000000000000000e+00,-1.161201465728219362e-01,0.000000000000000000e+00,-1.000000005810255832e+00,0.000000000000000000e+00 +2.652750969401875825e+00,2.917999999999999972e+01,0.000000000000000000e+00,1.099320524458100934e+01,0.000000000000000000e+00,-1.170297906440218166e-01,0.000000000000000000e+00,-1.000000007567074300e+00,0.000000000000000000e+00 +2.653660622208088071e+00,2.919000000000000128e+01,0.000000000000000000e+00,1.099309878810353958e+01,0.000000000000000000e+00,-1.179394434571174460e-01,0.000000000000000000e+00,-1.000000008586194422e+00,0.000000000000000000e+00 +2.654570283823320942e+00,2.919999999999999929e+01,0.000000000000000000e+00,1.099299150311890472e+01,0.000000000000000000e+00,-1.188491050801607773e-01,0.000000000000000000e+00,-1.000000008816333441e+00,0.000000000000000000e+00 +2.655479954316303903e+00,2.921000000000000085e+01,0.000000000000000000e+00,1.099288338959489586e+01,0.000000000000000000e+00,-1.197587755811637261e-01,0.000000000000000000e+00,-1.000000006059188706e+00,0.000000000000000000e+00 +2.656389633755773527e+00,2.921999999999999886e+01,0.000000000000000000e+00,1.099277444749905364e+01,0.000000000000000000e+00,-1.206684550261451216e-01,0.000000000000000000e+00,-1.000000008849080801e+00,0.000000000000000000e+00 +2.657299322210472603e+00,2.923000000000000043e+01,0.000000000000000000e+00,1.099266467679866999e+01,0.000000000000000000e+00,-1.215781434888940221e-01,0.000000000000000000e+00,-1.000000008546974684e+00,0.000000000000000000e+00 +2.658209019749151025e+00,2.924000000000000199e+01,0.000000000000000000e+00,1.099255407746078106e+01,0.000000000000000000e+00,-1.224878410353475167e-01,0.000000000000000000e+00,-1.000000005100149414e+00,0.000000000000000000e+00 +2.659118726440565350e+00,2.925000000000000000e+01,0.000000000000000000e+00,1.099244264945217431e+01,0.000000000000000000e+00,-1.233975477314014912e-01,0.000000000000000000e+00,-1.000000011334015060e+00,0.000000000000000000e+00 +2.660028442353479239e+00,2.926000000000000156e+01,0.000000000000000000e+00,1.099233039273938850e+01,0.000000000000000000e+00,-1.243072636546261184e-01,0.000000000000000000e+00,-1.000000005730329988e+00,0.000000000000000000e+00 +2.660938167556663014e+00,2.926999999999999957e+01,0.000000000000000000e+00,1.099221730728870305e+01,0.000000000000000000e+00,-1.252169888630230987e-01,0.000000000000000000e+00,-1.000000007552775072e+00,0.000000000000000000e+00 +2.661847902118894549e+00,2.928000000000000114e+01,0.000000000000000000e+00,1.099210339306615580e+01,0.000000000000000000e+00,-1.261267234321256370e-01,0.000000000000000000e+00,-1.000000008161123777e+00,0.000000000000000000e+00 +2.662757646108958376e+00,2.928999999999999915e+01,0.000000000000000000e+00,1.099198865003752701e+01,0.000000000000000000e+00,-1.270364674296138030e-01,0.000000000000000000e+00,-1.000000009646602628e+00,0.000000000000000000e+00 +2.663667399595645691e+00,2.930000000000000071e+01,0.000000000000000000e+00,1.099187307816834647e+01,0.000000000000000000e+00,-1.279462209250772364e-01,0.000000000000000000e+00,-1.000000005515347956e+00,0.000000000000000000e+00 +2.664577162647755681e+00,2.931000000000000227e+01,0.000000000000000000e+00,1.099175667742389173e+01,0.000000000000000000e+00,-1.288559839822048803e-01,0.000000000000000000e+00,-1.000000008588793010e+00,0.000000000000000000e+00 +2.665486935334094198e+00,2.932000000000000028e+01,0.000000000000000000e+00,1.099163944776919344e+01,0.000000000000000000e+00,-1.297657566763573134e-01,0.000000000000000000e+00,-1.000000008079667380e+00,0.000000000000000000e+00 +2.666396717723474641e+00,2.933000000000000185e+01,0.000000000000000000e+00,1.099152138916902466e+01,0.000000000000000000e+00,-1.306755390730885147e-01,0.000000000000000000e+00,-1.000000008223838277e+00,0.000000000000000000e+00 +2.667306509884717514e+00,2.933999999999999986e+01,0.000000000000000000e+00,1.099140250158790977e+01,0.000000000000000000e+00,-1.315853312418134302e-01,0.000000000000000000e+00,-1.000000008964164300e+00,0.000000000000000000e+00 +2.668216311886650871e+00,2.935000000000000142e+01,0.000000000000000000e+00,1.099128278499012090e+01,0.000000000000000000e+00,-1.324951332519024028e-01,0.000000000000000000e+00,-1.000000005951335424e+00,0.000000000000000000e+00 +2.669126123798109873e+00,2.935999999999999943e+01,0.000000000000000000e+00,1.099116223933967795e+01,0.000000000000000000e+00,-1.334049451687761567e-01,0.000000000000000000e+00,-1.000000009857383132e+00,0.000000000000000000e+00 +2.670035945687937673e+00,2.937000000000000099e+01,0.000000000000000000e+00,1.099104086460035212e+01,0.000000000000000000e+00,-1.343147670675724215e-01,0.000000000000000000e+00,-1.000000005602464492e+00,0.000000000000000000e+00 +2.670945777624984530e+00,2.937999999999999901e+01,0.000000000000000000e+00,1.099091866073565704e+01,0.000000000000000000e+00,-1.352245990097165340e-01,0.000000000000000000e+00,-1.000000010295156949e+00,0.000000000000000000e+00 +2.671855619678108251e+00,2.939000000000000057e+01,0.000000000000000000e+00,1.099079562770886120e+01,0.000000000000000000e+00,-1.361344410722072629e-01,0.000000000000000000e+00,-1.000000006709547806e+00,0.000000000000000000e+00 +2.672765471916174640e+00,2.940000000000000213e+01,0.000000000000000000e+00,1.099067176548297375e+01,0.000000000000000000e+00,-1.370442933163782406e-01,0.000000000000000000e+00,-1.000000007661176804e+00,0.000000000000000000e+00 +2.673675334408056603e+00,2.941000000000000014e+01,0.000000000000000000e+00,1.099054707402075870e+01,0.000000000000000000e+00,-1.379541558152309055e-01,0.000000000000000000e+00,-1.000000008798532569e+00,0.000000000000000000e+00 +2.674585207222635486e+00,2.942000000000000171e+01,0.000000000000000000e+00,1.099042155328472425e+01,0.000000000000000000e+00,-1.388640286378152455e-01,0.000000000000000000e+00,-1.000000010061316891e+00,0.000000000000000000e+00 +2.675495090428799738e+00,2.942999999999999972e+01,0.000000000000000000e+00,1.099029520323712639e+01,0.000000000000000000e+00,-1.397739118531341751e-01,0.000000000000000000e+00,-1.000000004952089183e+00,0.000000000000000000e+00 +2.676404984095446249e+00,2.944000000000000128e+01,0.000000000000000000e+00,1.099016802383996882e+01,0.000000000000000000e+00,-1.406838055242864705e-01,0.000000000000000000e+00,-1.000000008429140275e+00,0.000000000000000000e+00 +2.677314888291479456e+00,2.944999999999999929e+01,0.000000000000000000e+00,1.099004001505500838e+01,0.000000000000000000e+00,-1.415937097279892087e-01,0.000000000000000000e+00,-1.000000009702717296e+00,0.000000000000000000e+00 +2.678224803085811345e+00,2.946000000000000085e+01,0.000000000000000000e+00,1.098991117684374252e+01,0.000000000000000000e+00,-1.425036245311499250e-01,0.000000000000000000e+00,-1.000000006565810118e+00,0.000000000000000000e+00 +2.679134728547362787e+00,2.946999999999999886e+01,0.000000000000000000e+00,1.098978150916741825e+01,0.000000000000000000e+00,-1.434135499986758655e-01,0.000000000000000000e+00,-1.000000009683381874e+00,0.000000000000000000e+00 +2.680044664745062200e+00,2.948000000000000043e+01,0.000000000000000000e+00,1.098965101198703387e+01,0.000000000000000000e+00,-1.443234862051866185e-01,0.000000000000000000e+00,-1.000000006120180807e+00,0.000000000000000000e+00 +2.680954611747846439e+00,2.949000000000000199e+01,0.000000000000000000e+00,1.098951968526333012e+01,0.000000000000000000e+00,-1.452334332135396811e-01,0.000000000000000000e+00,-1.000000010830690345e+00,0.000000000000000000e+00 +2.681864569624659911e+00,2.950000000000000000e+01,0.000000000000000000e+00,1.098938752895680082e+01,0.000000000000000000e+00,-1.461433911002084363e-01,0.000000000000000000e+00,-1.000000006588832369e+00,0.000000000000000000e+00 +2.682774538444455459e+00,2.951000000000000156e+01,0.000000000000000000e+00,1.098925454302768046e+01,0.000000000000000000e+00,-1.470533599259995494e-01,0.000000000000000000e+00,-1.000000006202534930e+00,0.000000000000000000e+00 +2.683684518276194364e+00,2.951999999999999957e+01,0.000000000000000000e+00,1.098912072743595836e+01,0.000000000000000000e+00,-1.479633397633826064e-01,0.000000000000000000e+00,-1.000000011752236073e+00,0.000000000000000000e+00 +2.684594509188846345e+00,2.953000000000000114e+01,0.000000000000000000e+00,1.098898608214136807e+01,0.000000000000000000e+00,-1.488733306867288109e-01,0.000000000000000000e+00,-1.000000006012148557e+00,0.000000000000000000e+00 +2.685504511251389115e+00,2.953999999999999915e+01,0.000000000000000000e+00,1.098885060710338557e+01,0.000000000000000000e+00,-1.497833327547424265e-01,0.000000000000000000e+00,-1.000000008223235426e+00,0.000000000000000000e+00 +2.686414524532808823e+00,2.955000000000000071e+01,0.000000000000000000e+00,1.098871430228124346e+01,0.000000000000000000e+00,-1.506933460436452876e-01,0.000000000000000000e+00,-1.000000007594457729e+00,0.000000000000000000e+00 +2.687324549102100057e+00,2.956000000000000227e+01,0.000000000000000000e+00,1.098857716763391501e+01,0.000000000000000000e+00,-1.516033706198478548e-01,0.000000000000000000e+00,-1.000000010494840774e+00,0.000000000000000000e+00 +2.688234585028266732e+00,2.957000000000000028e+01,0.000000000000000000e+00,1.098843920312012301e+01,0.000000000000000000e+00,-1.525134065555650564e-01,0.000000000000000000e+00,-1.000000006133386021e+00,0.000000000000000000e+00 +2.689144632380320310e+00,2.958000000000000185e+01,0.000000000000000000e+00,1.098830040869833446e+01,0.000000000000000000e+00,-1.534234539132001973e-01,0.000000000000000000e+00,-1.000000009457583161e+00,0.000000000000000000e+00 +2.690054691227281136e+00,2.958999999999999986e+01,0.000000000000000000e+00,1.098816078432676946e+01,0.000000000000000000e+00,-1.543335127687680552e-01,0.000000000000000000e+00,-1.000000007531091972e+00,0.000000000000000000e+00 +2.690964761638178437e+00,2.960000000000000142e+01,0.000000000000000000e+00,1.098802032996338873e+01,0.000000000000000000e+00,-1.552435831865193738e-01,0.000000000000000000e+00,-1.000000008865563839e+00,0.000000000000000000e+00 +2.691874843682050322e+00,2.960999999999999943e+01,0.000000000000000000e+00,1.098787904556590433e+01,0.000000000000000000e+00,-1.561536652384597490e-01,0.000000000000000000e+00,-1.000000006958730703e+00,0.000000000000000000e+00 +2.692784937427943337e+00,2.962000000000000099e+01,0.000000000000000000e+00,1.098773693109177252e+01,0.000000000000000000e+00,-1.570637589906860032e-01,0.000000000000000000e+00,-1.000000008176301414e+00,0.000000000000000000e+00 +2.693695042944913354e+00,2.962999999999999901e+01,0.000000000000000000e+00,1.098759398649819907e+01,0.000000000000000000e+00,-1.579738645150971510e-01,0.000000000000000000e+00,-1.000000010304540110e+00,0.000000000000000000e+00 +2.694605160302024238e+00,2.964000000000000057e+01,0.000000000000000000e+00,1.098745021174213399e+01,0.000000000000000000e+00,-1.588839818815864502e-01,0.000000000000000000e+00,-1.000000006840737310e+00,0.000000000000000000e+00 +2.695515289568349626e+00,2.965000000000000213e+01,0.000000000000000000e+00,1.098730560678027324e+01,0.000000000000000000e+00,-1.597941111541378301e-01,0.000000000000000000e+00,-1.000000008437904153e+00,0.000000000000000000e+00 +2.696425430812972035e+00,2.966000000000000014e+01,0.000000000000000000e+00,1.098716017156906410e+01,0.000000000000000000e+00,-1.607042524064397626e-01,0.000000000000000000e+00,-1.000000006448017009e+00,0.000000000000000000e+00 +2.697335584104982420e+00,2.967000000000000171e+01,0.000000000000000000e+00,1.098701390606469630e+01,0.000000000000000000e+00,-1.616144057043189253e-01,0.000000000000000000e+00,-1.000000011522421017e+00,0.000000000000000000e+00 +2.698245749513481506e+00,2.967999999999999972e+01,0.000000000000000000e+00,1.098686681022310907e+01,0.000000000000000000e+00,-1.625245711233054557e-01,0.000000000000000000e+00,-1.000000006435671329e+00,0.000000000000000000e+00 +2.699155927107579345e+00,2.969000000000000128e+01,0.000000000000000000e+00,1.098671888399998231e+01,0.000000000000000000e+00,-1.634347487232606921e-01,0.000000000000000000e+00,-1.000000008270919727e+00,0.000000000000000000e+00 +2.700066116956394424e+00,2.969999999999999929e+01,0.000000000000000000e+00,1.098657012735075078e+01,0.000000000000000000e+00,-1.643449385796037221e-01,0.000000000000000000e+00,-1.000000008379288152e+00,0.000000000000000000e+00 +2.700976319129054559e+00,2.971000000000000085e+01,0.000000000000000000e+00,1.098642054023058989e+01,0.000000000000000000e+00,-1.652551407598909228e-01,0.000000000000000000e+00,-1.000000008832856002e+00,0.000000000000000000e+00 +2.701886533694697778e+00,2.971999999999999886e+01,0.000000000000000000e+00,1.098627012259442282e+01,0.000000000000000000e+00,-1.661653553335739608e-01,0.000000000000000000e+00,-1.000000007415114744e+00,0.000000000000000000e+00 +2.702796760722470548e+00,2.973000000000000043e+01,0.000000000000000000e+00,1.098611887439691870e+01,0.000000000000000000e+00,-1.670755823680963592e-01,0.000000000000000000e+00,-1.000000010485116331e+00,0.000000000000000000e+00 +2.703707000281529549e+00,2.974000000000000199e+01,0.000000000000000000e+00,1.098596679559249445e+01,0.000000000000000000e+00,-1.679858219366992533e-01,0.000000000000000000e+00,-1.000000007249588929e+00,0.000000000000000000e+00 +2.704617252441040343e+00,2.975000000000000000e+01,0.000000000000000000e+00,1.098581388613530940e+01,0.000000000000000000e+00,-1.688960741028088242e-01,0.000000000000000000e+00,-1.000000006210802317e+00,0.000000000000000000e+00 +2.705527517270177817e+00,2.976000000000000156e+01,0.000000000000000000e+00,1.098566014597927420e+01,0.000000000000000000e+00,-1.698063389375998600e-01,0.000000000000000000e+00,-1.000000011581890558e+00,0.000000000000000000e+00 +2.706437794838127076e+00,2.976999999999999957e+01,0.000000000000000000e+00,1.098550557507804371e+01,0.000000000000000000e+00,-1.707166165160919347e-01,0.000000000000000000e+00,-1.000000006137840902e+00,0.000000000000000000e+00 +2.707348085214082545e+00,2.978000000000000114e+01,0.000000000000000000e+00,1.098535017338501341e+01,0.000000000000000000e+00,-1.716269068976347401e-01,0.000000000000000000e+00,-1.000000009097649745e+00,0.000000000000000000e+00 +2.708258388467248423e+00,2.978999999999999915e+01,0.000000000000000000e+00,1.098519394085333367e+01,0.000000000000000000e+00,-1.725372101590823548e-01,0.000000000000000000e+00,-1.000000007523550449e+00,0.000000000000000000e+00 +2.709168704666838678e+00,2.980000000000000071e+01,0.000000000000000000e+00,1.098503687743589374e+01,0.000000000000000000e+00,-1.734475263655214650e-01,0.000000000000000000e+00,-1.000000009914289834e+00,0.000000000000000000e+00 +2.710079033882077049e+00,2.981000000000000227e+01,0.000000000000000000e+00,1.098487898308533239e+01,0.000000000000000000e+00,-1.743578555897850324e-01,0.000000000000000000e+00,-1.000000007619256559e+00,0.000000000000000000e+00 +2.710989376182197041e+00,2.982000000000000028e+01,0.000000000000000000e+00,1.098472025775403083e+01,0.000000000000000000e+00,-1.752681978968410048e-01,0.000000000000000000e+00,-1.000000009135990631e+00,0.000000000000000000e+00 +2.711899731636441935e+00,2.983000000000000185e+01,0.000000000000000000e+00,1.098456070139411977e+01,0.000000000000000000e+00,-1.761785533594028286e-01,0.000000000000000000e+00,-1.000000005813653781e+00,0.000000000000000000e+00 +2.712810100314065220e+00,2.983999999999999986e+01,0.000000000000000000e+00,1.098440031395747241e+01,0.000000000000000000e+00,-1.770889220423186028e-01,0.000000000000000000e+00,-1.000000010434922482e+00,0.000000000000000000e+00 +2.713720482284330160e+00,2.985000000000000142e+01,0.000000000000000000e+00,1.098423909539571142e+01,0.000000000000000000e+00,-1.779993040220833600e-01,0.000000000000000000e+00,-1.000000010061744105e+00,0.000000000000000000e+00 +2.714630877616510229e+00,2.985999999999999943e+01,0.000000000000000000e+00,1.098407704566019838e+01,0.000000000000000000e+00,-1.789096993634237687e-01,0.000000000000000000e+00,-1.000000004616370619e+00,0.000000000000000000e+00 +2.715541286379889119e+00,2.987000000000000099e+01,0.000000000000000000e+00,1.098391416470204440e+01,0.000000000000000000e+00,-1.798201081310056293e-01,0.000000000000000000e+00,-1.000000011165291358e+00,0.000000000000000000e+00 +2.716451708643760732e+00,2.987999999999999901e+01,0.000000000000000000e+00,1.098375045247211013e+01,0.000000000000000000e+00,-1.807305304050424166e-01,0.000000000000000000e+00,-1.000000008197934775e+00,0.000000000000000000e+00 +2.717362144477428743e+00,2.989000000000000057e+01,0.000000000000000000e+00,1.098358590892099151e+01,0.000000000000000000e+00,-1.816409662461743180e-01,0.000000000000000000e+00,-1.000000006350405979e+00,0.000000000000000000e+00 +2.718272593950207927e+00,2.990000000000000213e+01,0.000000000000000000e+00,1.098342053399903762e+01,0.000000000000000000e+00,-1.825514157247350444e-01,0.000000000000000000e+00,-1.000000009828530878e+00,0.000000000000000000e+00 +2.719183057131422387e+00,2.991000000000000014e+01,0.000000000000000000e+00,1.098325432765634169e+01,0.000000000000000000e+00,-1.834618789148979301e-01,0.000000000000000000e+00,-1.000000009980004156e+00,0.000000000000000000e+00 +2.720093534090406884e+00,2.992000000000000171e+01,0.000000000000000000e+00,1.098308728984273763e+01,0.000000000000000000e+00,-1.843723558829691855e-01,0.000000000000000000e+00,-1.000000006724346635e+00,0.000000000000000000e+00 +2.721004024896507278e+00,2.992999999999999972e+01,0.000000000000000000e+00,1.098291942050780712e+01,0.000000000000000000e+00,-1.852828466951920439e-01,0.000000000000000000e+00,-1.000000008551526598e+00,0.000000000000000000e+00 +2.721914529619079204e+00,2.994000000000000128e+01,0.000000000000000000e+00,1.098275071960087956e+01,0.000000000000000000e+00,-1.861933514255502409e-01,0.000000000000000000e+00,-1.000000008951434038e+00,0.000000000000000000e+00 +2.722825048327489394e+00,2.994999999999999929e+01,0.000000000000000000e+00,1.098258118707102504e+01,0.000000000000000000e+00,-1.871038701421106898e-01,0.000000000000000000e+00,-1.000000007842234417e+00,0.000000000000000000e+00 +2.723735581091114355e+00,2.996000000000000085e+01,0.000000000000000000e+00,1.098241082286705961e+01,0.000000000000000000e+00,-1.880144029128763272e-01,0.000000000000000000e+00,-1.000000009426604164e+00,0.000000000000000000e+00 +2.724646127979342136e+00,2.996999999999999886e+01,0.000000000000000000e+00,1.098223962693754530e+01,0.000000000000000000e+00,-1.889249498096874091e-01,0.000000000000000000e+00,-1.000000007193966090e+00,0.000000000000000000e+00 +2.725556689061571003e+00,2.998000000000000043e+01,0.000000000000000000e+00,1.098206759923078657e+01,0.000000000000000000e+00,-1.898355108984667305e-01,0.000000000000000000e+00,-1.000000009631071940e+00,0.000000000000000000e+00 +2.726467264407209878e+00,2.999000000000000199e+01,0.000000000000000000e+00,1.098189473969483565e+01,0.000000000000000000e+00,-1.907460862528755074e-01,0.000000000000000000e+00,-1.000000008084378722e+00,0.000000000000000000e+00 +2.727377854085678788e+00,3.000000000000000000e+01,0.000000000000000000e+00,1.098172104827748541e+01,0.000000000000000000e+00,-1.916566759387061392e-01,0.000000000000000000e+00,-1.000000006754657278e+00,0.000000000000000000e+00 +2.728288458166408859e+00,3.001000000000000156e+01,0.000000000000000000e+00,1.098154652492627648e+01,0.000000000000000000e+00,-1.925672800255869566e-01,0.000000000000000000e+00,-1.000000009841744752e+00,0.000000000000000000e+00 +2.729199076718841432e+00,3.001999999999999957e+01,0.000000000000000000e+00,1.098137116958849369e+01,0.000000000000000000e+00,-1.934778985869816670e-01,0.000000000000000000e+00,-1.000000008691671605e+00,0.000000000000000000e+00 +2.730109709812429397e+00,3.003000000000000114e+01,0.000000000000000000e+00,1.098119498221116253e+01,0.000000000000000000e+00,-1.943885316884845504e-01,0.000000000000000000e+00,-1.000000009645686028e+00,0.000000000000000000e+00 +2.731020357516636299e+00,3.003999999999999915e+01,0.000000000000000000e+00,1.098101796274105624e+01,0.000000000000000000e+00,-1.952991794014753701e-01,0.000000000000000000e+00,-1.000000008333773005e+00,0.000000000000000000e+00 +2.731931019900937230e+00,3.005000000000000071e+01,0.000000000000000000e+00,1.098084011112469049e+01,0.000000000000000000e+00,-1.962098417933654526e-01,0.000000000000000000e+00,-1.000000006811990971e+00,0.000000000000000000e+00 +2.732841697034817940e+00,3.006000000000000227e+01,0.000000000000000000e+00,1.098066142730832695e+01,0.000000000000000000e+00,-1.971205189334495622e-01,0.000000000000000000e+00,-1.000000009277186575e+00,0.000000000000000000e+00 +2.733752388987775284e+00,3.007000000000000028e+01,0.000000000000000000e+00,1.098048191123797146e+01,0.000000000000000000e+00,-1.980312108948556749e-01,0.000000000000000000e+00,-1.000000009216665653e+00,0.000000000000000000e+00 +2.734663095829318102e+00,3.008000000000000185e+01,0.000000000000000000e+00,1.098030156285937053e+01,0.000000000000000000e+00,-1.989419177447920295e-01,0.000000000000000000e+00,-1.000000006543239506e+00,0.000000000000000000e+00 +2.735573817628965454e+00,3.008999999999999986e+01,0.000000000000000000e+00,1.098012038211801666e+01,0.000000000000000000e+00,-1.998526395503986419e-01,0.000000000000000000e+00,-1.000000009735726891e+00,0.000000000000000000e+00 +2.736484554456248830e+00,3.010000000000000142e+01,0.000000000000000000e+00,1.097993836895914832e+01,0.000000000000000000e+00,-2.007633763865487309e-01,0.000000000000000000e+00,-1.000000010138997641e+00,0.000000000000000000e+00 +2.737395306380710380e+00,3.010999999999999943e+01,0.000000000000000000e+00,1.097975552332774285e+01,0.000000000000000000e+00,-2.016741283202445056e-01,0.000000000000000000e+00,-1.000000005523132840e+00,0.000000000000000000e+00 +2.738306073471904245e+00,3.012000000000000099e+01,0.000000000000000000e+00,1.097957184516852358e+01,0.000000000000000000e+00,-2.025848954164685689e-01,0.000000000000000000e+00,-1.000000010789386051e+00,0.000000000000000000e+00 +2.739216855799395667e+00,3.012999999999999901e+01,0.000000000000000000e+00,1.097938733442596160e+01,0.000000000000000000e+00,-2.034956777537866024e-01,0.000000000000000000e+00,-1.000000008716336763e+00,0.000000000000000000e+00 +2.740127653432761434e+00,3.014000000000000057e+01,0.000000000000000000e+00,1.097920199104426331e+01,0.000000000000000000e+00,-2.044064753950910751e-01,0.000000000000000000e+00,-1.000000007779966671e+00,0.000000000000000000e+00 +2.741038466441589883e+00,3.015000000000000213e+01,0.000000000000000000e+00,1.097901581496738466e+01,0.000000000000000000e+00,-2.053172884110057717e-01,0.000000000000000000e+00,-1.000000007889576104e+00,0.000000000000000000e+00 +2.741949294895481781e+00,3.016000000000000014e+01,0.000000000000000000e+00,1.097882880613902401e+01,0.000000000000000000e+00,-2.062281168720835889e-01,0.000000000000000000e+00,-1.000000008954380792e+00,0.000000000000000000e+00 +2.742860138864048558e+00,3.017000000000000171e+01,0.000000000000000000e+00,1.097864096450262217e+01,0.000000000000000000e+00,-2.071389608488065082e-01,0.000000000000000000e+00,-1.000000008741768420e+00,0.000000000000000000e+00 +2.743770998416914075e+00,3.017999999999999972e+01,0.000000000000000000e+00,1.097845229000136236e+01,0.000000000000000000e+00,-2.080498204096347392e-01,0.000000000000000000e+00,-1.000000009301324821e+00,0.000000000000000000e+00 +2.744681873623714186e+00,3.019000000000000128e+01,0.000000000000000000e+00,1.097826278257817201e+01,0.000000000000000000e+00,-2.089606956249071834e-01,0.000000000000000000e+00,-1.000000008399886564e+00,0.000000000000000000e+00 +2.745592764554096288e+00,3.019999999999999929e+01,0.000000000000000000e+00,1.097807244217572098e+01,0.000000000000000000e+00,-2.098715865629404986e-01,0.000000000000000000e+00,-1.000000008085884629e+00,0.000000000000000000e+00 +2.746503671277719327e+00,3.021000000000000085e+01,0.000000000000000000e+00,1.097788126873642334e+01,0.000000000000000000e+00,-2.107824932939291462e-01,0.000000000000000000e+00,-1.000000008266379359e+00,0.000000000000000000e+00 +2.747414593864255128e+00,3.021999999999999886e+01,0.000000000000000000e+00,1.097768926220243557e+01,0.000000000000000000e+00,-2.116934158879949512e-01,0.000000000000000000e+00,-1.000000008847890198e+00,0.000000000000000000e+00 +2.748325532383387060e+00,3.023000000000000043e+01,0.000000000000000000e+00,1.097749642251565660e+01,0.000000000000000000e+00,-2.126043544151866582e-01,0.000000000000000000e+00,-1.000000009736578876e+00,0.000000000000000000e+00 +2.749236486904810484e+00,3.024000000000000199e+01,0.000000000000000000e+00,1.097730274961772778e+01,0.000000000000000000e+00,-2.135153089454796538e-01,0.000000000000000000e+00,-1.000000006557109966e+00,0.000000000000000000e+00 +2.750147457498233194e+00,3.025000000000000000e+01,0.000000000000000000e+00,1.097710824345003289e+01,0.000000000000000000e+00,-2.144262795448756975e-01,0.000000000000000000e+00,-1.000000009917631383e+00,0.000000000000000000e+00 +2.751058444233374978e+00,3.026000000000000156e+01,0.000000000000000000e+00,1.097691290395370167e+01,0.000000000000000000e+00,-2.153372662890524480e-01,0.000000000000000000e+00,-1.000000009020362013e+00,0.000000000000000000e+00 +2.751969447179968498e+00,3.026999999999999957e+01,0.000000000000000000e+00,1.097671673106960100e+01,0.000000000000000000e+00,-2.162482692438633392e-01,0.000000000000000000e+00,-1.000000008050958566e+00,0.000000000000000000e+00 +2.752880466407757520e+00,3.028000000000000114e+01,0.000000000000000000e+00,1.097651972473834370e+01,0.000000000000000000e+00,-2.171592884789871336e-01,0.000000000000000000e+00,-1.000000006913519979e+00,0.000000000000000000e+00 +2.753791501986499579e+00,3.028999999999999915e+01,0.000000000000000000e+00,1.097632188490028504e+01,0.000000000000000000e+00,-2.180703240640275986e-01,0.000000000000000000e+00,-1.000000011932100419e+00,0.000000000000000000e+00 +2.754702553985963753e+00,3.030000000000000071e+01,0.000000000000000000e+00,1.097612321149552272e+01,0.000000000000000000e+00,-2.189813760743624660e-01,0.000000000000000000e+00,-1.000000005888757926e+00,0.000000000000000000e+00 +2.755613622475931557e+00,3.031000000000000227e+01,0.000000000000000000e+00,1.097592370446389154e+01,0.000000000000000000e+00,-2.198924445696955332e-01,0.000000000000000000e+00,-1.000000010087394253e+00,0.000000000000000000e+00 +2.756524707526197826e+00,3.032000000000000028e+01,0.000000000000000000e+00,1.097572336374497759e+01,0.000000000000000000e+00,-2.208035296291522565e-01,0.000000000000000000e+00,-1.000000007310015038e+00,0.000000000000000000e+00 +2.757435809206569388e+00,3.033000000000000185e+01,0.000000000000000000e+00,1.097552218927810053e+01,0.000000000000000000e+00,-2.217146313161838522e-01,0.000000000000000000e+00,-1.000000010298332631e+00,0.000000000000000000e+00 +2.758346927586865505e+00,3.033999999999999986e+01,0.000000000000000000e+00,1.097532018100232776e+01,0.000000000000000000e+00,-2.226257497058630463e-01,0.000000000000000000e+00,-1.000000008254406048e+00,0.000000000000000000e+00 +2.759258062736918760e+00,3.035000000000000142e+01,0.000000000000000000e+00,1.097511733885646379e+01,0.000000000000000000e+00,-2.235368848634371741e-01,0.000000000000000000e+00,-1.000000007499098453e+00,0.000000000000000000e+00 +2.760169214726574172e+00,3.035999999999999943e+01,0.000000000000000000e+00,1.097491366277905911e+01,0.000000000000000000e+00,-2.244480368599253428e-01,0.000000000000000000e+00,-1.000000010072356504e+00,0.000000000000000000e+00 +2.761080383625689638e+00,3.037000000000000099e+01,0.000000000000000000e+00,1.097470915270840486e+01,0.000000000000000000e+00,-2.253592057682182737e-01,0.000000000000000000e+00,-1.000000007316094841e+00,0.000000000000000000e+00 +2.761991569504135491e+00,3.037999999999999901e+01,0.000000000000000000e+00,1.097450380858253105e+01,0.000000000000000000e+00,-2.262703916533305992e-01,0.000000000000000000e+00,-1.000000009827938463e+00,0.000000000000000000e+00 +2.762902772431795828e+00,3.039000000000000057e+01,0.000000000000000000e+00,1.097429763033921368e+01,0.000000000000000000e+00,-2.271815945899461897e-01,0.000000000000000000e+00,-1.000000008949225805e+00,0.000000000000000000e+00 +2.763813992478567183e+00,3.040000000000000213e+01,0.000000000000000000e+00,1.097409061791596585e+01,0.000000000000000000e+00,-2.280928146448722160e-01,0.000000000000000000e+00,-1.000000006718676726e+00,0.000000000000000000e+00 +2.764725229714358967e+00,3.041000000000000014e+01,0.000000000000000000e+00,1.097388277125004485e+01,0.000000000000000000e+00,-2.290040518867864638e-01,0.000000000000000000e+00,-1.000000011591642535e+00,0.000000000000000000e+00 +2.765636484209094359e+00,3.042000000000000171e+01,0.000000000000000000e+00,1.097367409027845042e+01,0.000000000000000000e+00,-2.299153063920847118e-01,0.000000000000000000e+00,-1.000000006352623982e+00,0.000000000000000000e+00 +2.766547756032708971e+00,3.042999999999999972e+01,0.000000000000000000e+00,1.097346457493791760e+01,0.000000000000000000e+00,-2.308265782214882489e-01,0.000000000000000000e+00,-1.000000010151779417e+00,0.000000000000000000e+00 +2.767459045255151739e+00,3.044000000000000128e+01,0.000000000000000000e+00,1.097325422516493099e+01,0.000000000000000000e+00,-2.317378674531823668e-01,0.000000000000000000e+00,-1.000000007912596578e+00,0.000000000000000000e+00 +2.768370351946385366e+00,3.044999999999999929e+01,0.000000000000000000e+00,1.097304304089570870e+01,0.000000000000000000e+00,-2.326491741516267531e-01,0.000000000000000000e+00,-1.000000008088195003e+00,0.000000000000000000e+00 +2.769281676176385432e+00,3.046000000000000085e+01,0.000000000000000000e+00,1.097283102206621486e+01,0.000000000000000000e+00,-2.335604983889976172e-01,0.000000000000000000e+00,-1.000000008435877996e+00,0.000000000000000000e+00 +2.770193018015140840e+00,3.046999999999999886e+01,0.000000000000000000e+00,1.097261816861215245e+01,0.000000000000000000e+00,-2.344718402354407927e-01,0.000000000000000000e+00,-1.000000010990150345e+00,0.000000000000000000e+00 +2.771104377532653817e+00,3.048000000000000043e+01,0.000000000000000000e+00,1.097240448046896510e+01,0.000000000000000000e+00,-2.353831997629697026e-01,0.000000000000000000e+00,-1.000000007092099130e+00,0.000000000000000000e+00 +2.772015754798940357e+00,3.049000000000000199e+01,0.000000000000000000e+00,1.097218995757183535e+01,0.000000000000000000e+00,-2.362945770357198216e-01,0.000000000000000000e+00,-1.000000007330198892e+00,0.000000000000000000e+00 +2.772927149884029774e+00,3.050000000000000000e+01,0.000000000000000000e+00,1.097197459985569168e+01,0.000000000000000000e+00,-2.372059721274900890e-01,0.000000000000000000e+00,-1.000000011598464411e+00,0.000000000000000000e+00 +2.773838562857965151e+00,3.051000000000000156e+01,0.000000000000000000e+00,1.097175840725519969e+01,0.000000000000000000e+00,-2.381173851119966489e-01,0.000000000000000000e+00,-1.000000006960718890e+00,0.000000000000000000e+00 +2.774749993790803337e+00,3.051999999999999957e+01,0.000000000000000000e+00,1.097154137970476206e+01,0.000000000000000000e+00,-2.390288160511790660e-01,0.000000000000000000e+00,-1.000000008279711583e+00,0.000000000000000000e+00 +2.775661442752614505e+00,3.053000000000000114e+01,0.000000000000000000e+00,1.097132351713852927e+01,0.000000000000000000e+00,-2.399402650205367526e-01,0.000000000000000000e+00,-1.000000011171827019e+00,0.000000000000000000e+00 +2.776572909813482593e+00,3.053999999999999915e+01,0.000000000000000000e+00,1.097110481949038707e+01,0.000000000000000000e+00,-2.408517320915876669e-01,0.000000000000000000e+00,-1.000000006977236344e+00,0.000000000000000000e+00 +2.777484395043505749e+00,3.055000000000000071e+01,0.000000000000000000e+00,1.097088528669396013e+01,0.000000000000000000e+00,-2.417632173279703478e-01,0.000000000000000000e+00,-1.000000008417742281e+00,0.000000000000000000e+00 +2.778395898512795448e+00,3.056000000000000227e+01,0.000000000000000000e+00,1.097066491868261906e+01,0.000000000000000000e+00,-2.426747208049327698e-01,0.000000000000000000e+00,-1.000000008970702403e+00,0.000000000000000000e+00 +2.779307420291477371e+00,3.057000000000000028e+01,0.000000000000000000e+00,1.097044371538946983e+01,0.000000000000000000e+00,-2.435862425917915963e-01,0.000000000000000000e+00,-1.000000008528101114e+00,0.000000000000000000e+00 +2.780218960449690968e+00,3.058000000000000185e+01,0.000000000000000000e+00,1.097022167674735904e+01,0.000000000000000000e+00,-2.444977827577789475e-01,0.000000000000000000e+00,-1.000000009118867217e+00,0.000000000000000000e+00 +2.781130519057589900e+00,3.058999999999999986e+01,0.000000000000000000e+00,1.096999880268887395e+01,0.000000000000000000e+00,-2.454093413739903973e-01,0.000000000000000000e+00,-1.000000008496246151e+00,0.000000000000000000e+00 +2.782042096185342039e+00,3.060000000000000142e+01,0.000000000000000000e+00,1.096977509314634069e+01,0.000000000000000000e+00,-2.463209185094875631e-01,0.000000000000000000e+00,-1.000000008688124442e+00,0.000000000000000000e+00 +2.782953691903129023e+00,3.060999999999999943e+01,0.000000000000000000e+00,1.096955054805182606e+01,0.000000000000000000e+00,-2.472325142351947391e-01,0.000000000000000000e+00,-1.000000009584535166e+00,0.000000000000000000e+00 +2.783865306281147145e+00,3.062000000000000099e+01,0.000000000000000000e+00,1.096932516733713570e+01,0.000000000000000000e+00,-2.481441286219502051e-01,0.000000000000000000e+00,-1.000000008937359741e+00,0.000000000000000000e+00 +2.784776939389606465e+00,3.062999999999999901e+01,0.000000000000000000e+00,1.096909895093381415e+01,0.000000000000000000e+00,-2.490557617385570632e-01,0.000000000000000000e+00,-1.000000006636111882e+00,0.000000000000000000e+00 +2.785688591298731698e+00,3.064000000000000057e+01,0.000000000000000000e+00,1.096887189877314661e+01,0.000000000000000000e+00,-2.499674136537319014e-01,0.000000000000000000e+00,-1.000000011118222787e+00,0.000000000000000000e+00 +2.786600262078761325e+00,3.065000000000000213e+01,0.000000000000000000e+00,1.096864401078615892e+01,0.000000000000000000e+00,-2.508790844438977263e-01,0.000000000000000000e+00,-1.000000007311304451e+00,0.000000000000000000e+00 +2.787511951799948928e+00,3.066000000000000014e+01,0.000000000000000000e+00,1.096841528690361045e+01,0.000000000000000000e+00,-2.517907741717509973e-01,0.000000000000000000e+00,-1.000000010063514688e+00,0.000000000000000000e+00 +2.788423660532562298e+00,3.067000000000000171e+01,0.000000000000000000e+00,1.096818572705600658e+01,0.000000000000000000e+00,-2.527024829135393613e-01,0.000000000000000000e+00,-1.000000006439524469e+00,0.000000000000000000e+00 +2.789335388346883882e+00,3.067999999999999972e+01,0.000000000000000000e+00,1.096795533117358623e+01,0.000000000000000000e+00,-2.536142107337318596e-01,0.000000000000000000e+00,-1.000000011285321788e+00,0.000000000000000000e+00 +2.790247135313210336e+00,3.069000000000000128e+01,0.000000000000000000e+00,1.096772409918633251e+01,0.000000000000000000e+00,-2.545259577103475279e-01,0.000000000000000000e+00,-1.000000007391790735e+00,0.000000000000000000e+00 +2.791158901501852974e+00,3.069999999999999929e+01,0.000000000000000000e+00,1.096749203102396031e+01,0.000000000000000000e+00,-2.554377239057298299e-01,0.000000000000000000e+00,-1.000000009603166262e+00,0.000000000000000000e+00 +2.792070686983138206e+00,3.071000000000000085e+01,0.000000000000000000e+00,1.096725912661593050e+01,0.000000000000000000e+00,-2.563495093957711690e-01,0.000000000000000000e+00,-1.000000007121135903e+00,0.000000000000000000e+00 +2.792982491827407099e+00,3.071999999999999886e+01,0.000000000000000000e+00,1.096702538589143749e+01,0.000000000000000000e+00,-2.572613142465330904e-01,0.000000000000000000e+00,-1.000000010514170645e+00,0.000000000000000000e+00 +2.793894316105015374e+00,3.073000000000000043e+01,0.000000000000000000e+00,1.096679080877941814e+01,0.000000000000000000e+00,-2.581731385337282525e-01,0.000000000000000000e+00,-1.000000008983821687e+00,0.000000000000000000e+00 +2.794806159886333408e+00,3.074000000000000199e+01,0.000000000000000000e+00,1.096655539520854283e+01,0.000000000000000000e+00,-2.590849823232380111e-01,0.000000000000000000e+00,-1.000000006688120058e+00,0.000000000000000000e+00 +2.795718023241746675e+00,3.075000000000000000e+01,0.000000000000000000e+00,1.096631914510722439e+01,0.000000000000000000e+00,-2.599968456847498999e-01,0.000000000000000000e+00,-1.000000009919517208e+00,0.000000000000000000e+00 +2.796629906241655750e+00,3.076000000000000156e+01,0.000000000000000000e+00,1.096608205840361450e+01,0.000000000000000000e+00,-2.609087286937043504e-01,0.000000000000000000e+00,-1.000000010016043106e+00,0.000000000000000000e+00 +2.797541808956475862e+00,3.076999999999999957e+01,0.000000000000000000e+00,1.096584413502559840e+01,0.000000000000000000e+00,-2.618206314176582672e-01,0.000000000000000000e+00,-1.000000006861171631e+00,0.000000000000000000e+00 +2.798453731456637783e+00,3.078000000000000114e+01,0.000000000000000000e+00,1.096560537490080200e+01,0.000000000000000000e+00,-2.627325539240771834e-01,0.000000000000000000e+00,-1.000000011017838641e+00,0.000000000000000000e+00 +2.799365673812587385e+00,3.078999999999999915e+01,0.000000000000000000e+00,1.096536577795659184e+01,0.000000000000000000e+00,-2.636444962900743594e-01,0.000000000000000000e+00,-1.000000007415819514e+00,0.000000000000000000e+00 +2.800277636094785194e+00,3.080000000000000071e+01,0.000000000000000000e+00,1.096512534412006623e+01,0.000000000000000000e+00,-2.645564585790352030e-01,0.000000000000000000e+00,-1.000000008752730540e+00,0.000000000000000000e+00 +2.801189618373707724e+00,3.081000000000000227e+01,0.000000000000000000e+00,1.096488407331806769e+01,0.000000000000000000e+00,-2.654684408659399031e-01,0.000000000000000000e+00,-1.000000008502013094e+00,0.000000000000000000e+00 +2.802101620719846142e+00,3.082000000000000028e+01,0.000000000000000000e+00,1.096464196547717229e+01,0.000000000000000000e+00,-2.663804432198320082e-01,0.000000000000000000e+00,-1.000000008680163699e+00,0.000000000000000000e+00 +2.803013643203707161e+00,3.083000000000000185e+01,0.000000000000000000e+00,1.096439902052369497e+01,0.000000000000000000e+00,-2.672924657116094171e-01,0.000000000000000000e+00,-1.000000009167637538e+00,0.000000000000000000e+00 +2.803925685895813036e+00,3.083999999999999986e+01,0.000000000000000000e+00,1.096415523838368777e+01,0.000000000000000000e+00,-2.682045084120764367e-01,0.000000000000000000e+00,-1.000000009844108639e+00,0.000000000000000000e+00 +2.804837748866701119e+00,3.085000000000000142e+01,0.000000000000000000e+00,1.096391061898293984e+01,0.000000000000000000e+00,-2.691165713919431157e-01,0.000000000000000000e+00,-1.000000006318700896e+00,0.000000000000000000e+00 +2.805749832186925197e+00,3.085999999999999943e+01,0.000000000000000000e+00,1.096366516224697740e+01,0.000000000000000000e+00,-2.700286547179301944e-01,0.000000000000000000e+00,-1.000000011281997336e+00,0.000000000000000000e+00 +2.806661935927053708e+00,3.087000000000000099e+01,0.000000000000000000e+00,1.096341886810106736e+01,0.000000000000000000e+00,-2.709407584683488635e-01,0.000000000000000000e+00,-1.000000007530619683e+00,0.000000000000000000e+00 +2.807574060157670637e+00,3.087999999999999901e+01,0.000000000000000000e+00,1.096317173647020660e+01,0.000000000000000000e+00,-2.718528827058348529e-01,0.000000000000000000e+00,-1.000000009889167263e+00,0.000000000000000000e+00 +2.808486204949376841e+00,3.089000000000000057e+01,0.000000000000000000e+00,1.096292376727913620e+01,0.000000000000000000e+00,-2.727650275065612306e-01,0.000000000000000000e+00,-1.000000007559667337e+00,0.000000000000000000e+00 +2.809398370372787390e+00,3.090000000000000213e+01,0.000000000000000000e+00,1.096267496045232903e+01,0.000000000000000000e+00,-2.736771929368676526e-01,0.000000000000000000e+00,-1.000000008959624376e+00,0.000000000000000000e+00 +2.810310556498534673e+00,3.091000000000000014e+01,0.000000000000000000e+00,1.096242531591399860e+01,0.000000000000000000e+00,-2.745893790707876203e-01,0.000000000000000000e+00,-1.000000009695590775e+00,0.000000000000000000e+00 +2.811222763397265734e+00,3.092000000000000171e+01,0.000000000000000000e+00,1.096217483358809197e+01,0.000000000000000000e+00,-2.755015859783629950e-01,0.000000000000000000e+00,-1.000000007509580735e+00,0.000000000000000000e+00 +2.812134991139644047e+00,3.092999999999999972e+01,0.000000000000000000e+00,1.096192351339829330e+01,0.000000000000000000e+00,-2.764138137275917173e-01,0.000000000000000000e+00,-1.000000010816089357e+00,0.000000000000000000e+00 +2.813047239796349075e+00,3.094000000000000128e+01,0.000000000000000000e+00,1.096167135526802561e+01,0.000000000000000000e+00,-2.773260623941636305e-01,0.000000000000000000e+00,-1.000000006683198661e+00,0.000000000000000000e+00 +2.813959509438076267e+00,3.094999999999999929e+01,0.000000000000000000e+00,1.096141835912044371e+01,0.000000000000000000e+00,-2.782383320419875572e-01,0.000000000000000000e+00,-1.000000009927459521e+00,0.000000000000000000e+00 +2.814871800135537061e+00,3.096000000000000085e+01,0.000000000000000000e+00,1.096116452487844484e+01,0.000000000000000000e+00,-2.791506227485049396e-01,0.000000000000000000e+00,-1.000000009751006225e+00,0.000000000000000000e+00 +2.815784111959458880e+00,3.097000000000000242e+01,0.000000000000000000e+00,1.096090985246465621e+01,0.000000000000000000e+00,-2.800629345813228088e-01,0.000000000000000000e+00,-1.000000008162832188e+00,0.000000000000000000e+00 +2.816696444980586023e+00,3.098000000000000043e+01,0.000000000000000000e+00,1.096065434180144393e+01,0.000000000000000000e+00,-2.809752676098970503e-01,0.000000000000000000e+00,-1.000000007171014449e+00,0.000000000000000000e+00 +2.817608799269678332e+00,3.099000000000000199e+01,0.000000000000000000e+00,1.096039799281091121e+01,0.000000000000000000e+00,-2.818876219055317933e-01,0.000000000000000000e+00,-1.000000010916272997e+00,0.000000000000000000e+00 +2.818521174897512083e+00,3.100000000000000000e+01,0.000000000000000000e+00,1.096014080541489655e+01,0.000000000000000000e+00,-2.827999975433254098e-01,0.000000000000000000e+00,-1.000000008601923840e+00,0.000000000000000000e+00 +2.819433571934880423e+00,3.101000000000000156e+01,0.000000000000000000e+00,1.095988277953497025e+01,0.000000000000000000e+00,-2.837123945885420828e-01,0.000000000000000000e+00,-1.000000008636002136e+00,0.000000000000000000e+00 +2.820345990452592488e+00,3.101999999999999957e+01,0.000000000000000000e+00,1.095962391509244327e+01,0.000000000000000000e+00,-2.846248131141336790e-01,0.000000000000000000e+00,-1.000000008756446013e+00,0.000000000000000000e+00 +2.821258430521473848e+00,3.103000000000000114e+01,0.000000000000000000e+00,1.095936421200836008e+01,0.000000000000000000e+00,-2.855372531910047029e-01,0.000000000000000000e+00,-1.000000008834886822e+00,0.000000000000000000e+00 +2.822170892212366944e+00,3.103999999999999915e+01,0.000000000000000000e+00,1.095910367020350051e+01,0.000000000000000000e+00,-2.864497148899590728e-01,0.000000000000000000e+00,-1.000000008742358171e+00,0.000000000000000000e+00 +2.823083375596130207e+00,3.105000000000000071e+01,0.000000000000000000e+00,1.095884228959837969e+01,0.000000000000000000e+00,-2.873621982816996212e-01,0.000000000000000000e+00,-1.000000008349297032e+00,0.000000000000000000e+00 +2.823995880743639386e+00,3.106000000000000227e+01,0.000000000000000000e+00,1.095858007011324808e+01,0.000000000000000000e+00,-2.882747034368275951e-01,0.000000000000000000e+00,-1.000000009659419264e+00,0.000000000000000000e+00 +2.824908407725786663e+00,3.107000000000000028e+01,0.000000000000000000e+00,1.095831701166809147e+01,0.000000000000000000e+00,-2.891872304277893768e-01,0.000000000000000000e+00,-1.000000008275683028e+00,0.000000000000000000e+00 +2.825820956613481094e+00,3.108000000000000185e+01,0.000000000000000000e+00,1.095805311418262917e+01,0.000000000000000000e+00,-2.900997793230357114e-01,0.000000000000000000e+00,-1.000000008334009705e+00,0.000000000000000000e+00 +2.826733527477648167e+00,3.108999999999999986e+01,0.000000000000000000e+00,1.095778837757631763e+01,0.000000000000000000e+00,-2.910123501948083113e-01,0.000000000000000000e+00,-1.000000009702839865e+00,0.000000000000000000e+00 +2.827646120389231132e+00,3.110000000000000142e+01,0.000000000000000000e+00,1.095752280176834681e+01,0.000000000000000000e+00,-2.919249431152458052e-01,0.000000000000000000e+00,-1.000000007984864991e+00,0.000000000000000000e+00 +2.828558735419189230e+00,3.110999999999999943e+01,0.000000000000000000e+00,1.095725638667764024e+01,0.000000000000000000e+00,-2.928375581524907956e-01,0.000000000000000000e+00,-1.000000011579076586e+00,0.000000000000000000e+00 +2.829471372638499016e+00,3.112000000000000099e+01,0.000000000000000000e+00,1.095698913222285853e+01,0.000000000000000000e+00,-2.937501953823679068e-01,0.000000000000000000e+00,-1.000000005424202199e+00,0.000000000000000000e+00 +2.830384032118153925e+00,3.112999999999999901e+01,0.000000000000000000e+00,1.095672103832239230e+01,0.000000000000000000e+00,-2.946628548669733560e-01,0.000000000000000000e+00,-1.000000010713646859e+00,0.000000000000000000e+00 +2.831296713929165154e+00,3.114000000000000057e+01,0.000000000000000000e+00,1.095645210489437460e+01,0.000000000000000000e+00,-2.955755366877626522e-01,0.000000000000000000e+00,-1.000000008120468520e+00,0.000000000000000000e+00 +2.832209418142560331e+00,3.115000000000000213e+01,0.000000000000000000e+00,1.095618233185666313e+01,0.000000000000000000e+00,-2.964882409085694559e-01,0.000000000000000000e+00,-1.000000010305989839e+00,0.000000000000000000e+00 +2.833122144829384847e+00,3.116000000000000014e+01,0.000000000000000000e+00,1.095591171912685624e+01,0.000000000000000000e+00,-2.974009676048004480e-01,0.000000000000000000e+00,-1.000000008606322766e+00,0.000000000000000000e+00 +2.834034894060700971e+00,3.117000000000000171e+01,0.000000000000000000e+00,1.095564026662228230e+01,0.000000000000000000e+00,-2.983137168439719544e-01,0.000000000000000000e+00,-1.000000007151569337e+00,0.000000000000000000e+00 +2.834947665907588288e+00,3.117999999999999972e+01,0.000000000000000000e+00,1.095536797426000675e+01,0.000000000000000000e+00,-2.992264886973872162e-01,0.000000000000000000e+00,-1.000000010070204670e+00,0.000000000000000000e+00 +2.835860460441144593e+00,3.119000000000000128e+01,0.000000000000000000e+00,1.095509484195682859e+01,0.000000000000000000e+00,-3.001392832401353350e-01,0.000000000000000000e+00,-1.000000008698520793e+00,0.000000000000000000e+00 +2.836773277732483667e+00,3.119999999999999929e+01,0.000000000000000000e+00,1.095482086962927681e+01,0.000000000000000000e+00,-3.010521005394147798e-01,0.000000000000000000e+00,-1.000000009296259762e+00,0.000000000000000000e+00 +2.837686117852738388e+00,3.121000000000000085e+01,0.000000000000000000e+00,1.095454605719361751e+01,0.000000000000000000e+00,-3.019649406681553794e-01,0.000000000000000000e+00,-1.000000007463342167e+00,0.000000000000000000e+00 +2.838598980873058064e+00,3.122000000000000242e+01,0.000000000000000000e+00,1.095427040456584855e+01,0.000000000000000000e+00,-3.028778036952879948e-01,0.000000000000000000e+00,-1.000000011589173399e+00,0.000000000000000000e+00 +2.839511866864609768e+00,3.123000000000000043e+01,0.000000000000000000e+00,1.095399391166170311e+01,0.000000000000000000e+00,-3.037906896974195137e-01,0.000000000000000000e+00,-1.000000006615358261e+00,0.000000000000000000e+00 +2.840424775898579224e+00,3.124000000000000199e+01,0.000000000000000000e+00,1.095371657839664259e+01,0.000000000000000000e+00,-3.047035987374279720e-01,0.000000000000000000e+00,-1.000000009455923822e+00,0.000000000000000000e+00 +2.841337708046168586e+00,3.125000000000000000e+01,0.000000000000000000e+00,1.095343840468586905e+01,0.000000000000000000e+00,-3.056165308936498737e-01,0.000000000000000000e+00,-1.000000009315316518e+00,0.000000000000000000e+00 +2.842250663378598663e+00,3.126000000000000156e+01,0.000000000000000000e+00,1.095315939044431097e+01,0.000000000000000000e+00,-3.065294862345842031e-01,0.000000000000000000e+00,-1.000000008186032074e+00,0.000000000000000000e+00 +2.843163641967107580e+00,3.126999999999999957e+01,0.000000000000000000e+00,1.095287953558663219e+01,0.000000000000000000e+00,-3.074424648305666974e-01,0.000000000000000000e+00,-1.000000010191000932e+00,0.000000000000000000e+00 +2.844076643882951672e+00,3.128000000000000114e+01,0.000000000000000000e+00,1.095259884002723005e+01,0.000000000000000000e+00,-3.083554667557151796e-01,0.000000000000000000e+00,-1.000000006666609709e+00,0.000000000000000000e+00 +2.844989669197405480e+00,3.128999999999999915e+01,0.000000000000000000e+00,1.095231730368023193e+01,0.000000000000000000e+00,-3.092684920762555634e-01,0.000000000000000000e+00,-1.000000010257979133e+00,0.000000000000000000e+00 +2.845902717981760865e+00,3.130000000000000071e+01,0.000000000000000000e+00,1.095203492645950227e+01,0.000000000000000000e+00,-3.101815408699770127e-01,0.000000000000000000e+00,-1.000000010169938225e+00,0.000000000000000000e+00 +2.846815790307328342e+00,3.131000000000000227e+01,0.000000000000000000e+00,1.095175170827863198e+01,0.000000000000000000e+00,-3.110946132048305057e-01,0.000000000000000000e+00,-1.000000006262163899e+00,0.000000000000000000e+00 +2.847728886245436630e+00,3.132000000000000028e+01,0.000000000000000000e+00,1.095146764905094727e+01,0.000000000000000000e+00,-3.120077091486567755e-01,0.000000000000000000e+00,-1.000000011176107373e+00,0.000000000000000000e+00 +2.848642005867432214e+00,3.133000000000000185e+01,0.000000000000000000e+00,1.095118274868950969e+01,0.000000000000000000e+00,-3.129208287808576405e-01,0.000000000000000000e+00,-1.000000007725817985e+00,0.000000000000000000e+00 +2.849555149244680230e+00,3.133999999999999986e+01,0.000000000000000000e+00,1.095089700710710545e+01,0.000000000000000000e+00,-3.138339721651605685e-01,0.000000000000000000e+00,-1.000000008551527042e+00,0.000000000000000000e+00 +2.850468316448564021e+00,3.135000000000000142e+01,0.000000000000000000e+00,1.095061042421625963e+01,0.000000000000000000e+00,-3.147471393768533909e-01,0.000000000000000000e+00,-1.000000009249166766e+00,0.000000000000000000e+00 +2.851381507550485139e+00,3.135999999999999943e+01,0.000000000000000000e+00,1.095032299992922553e+01,0.000000000000000000e+00,-3.156603304872208637e-01,0.000000000000000000e+00,-1.000000009675471091e+00,0.000000000000000000e+00 +2.852294722621863787e+00,3.137000000000000099e+01,0.000000000000000000e+00,1.095003473415798823e+01,0.000000000000000000e+00,-3.165735455674353327e-01,0.000000000000000000e+00,-1.000000009686578206e+00,0.000000000000000000e+00 +2.853207961734138376e+00,3.137999999999999901e+01,0.000000000000000000e+00,1.094974562681426455e+01,0.000000000000000000e+00,-3.174867846885562339e-01,0.000000000000000000e+00,-1.000000007008488012e+00,0.000000000000000000e+00 +2.854121224958766412e+00,3.139000000000000057e+01,0.000000000000000000e+00,1.094945567780950313e+01,0.000000000000000000e+00,-3.184000479195847610e-01,0.000000000000000000e+00,-1.000000010015661411e+00,0.000000000000000000e+00 +2.855034512367223165e+00,3.140000000000000213e+01,0.000000000000000000e+00,1.094916488705488611e+01,0.000000000000000000e+00,-3.193133353371888083e-01,0.000000000000000000e+00,-1.000000007913760092e+00,0.000000000000000000e+00 +2.855947824031003446e+00,3.141000000000000014e+01,0.000000000000000000e+00,1.094887325446132209e+01,0.000000000000000000e+00,-3.202266470081967520e-01,0.000000000000000000e+00,-1.000000009076136287e+00,0.000000000000000000e+00 +2.856861160021620272e+00,3.142000000000000171e+01,0.000000000000000000e+00,1.094858077993945500e+01,0.000000000000000000e+00,-3.211399830071030026e-01,0.000000000000000000e+00,-1.000000009097161691e+00,0.000000000000000000e+00 +2.857774520410605312e+00,3.142999999999999972e+01,0.000000000000000000e+00,1.094828746339965697e+01,0.000000000000000000e+00,-3.220533434043970633e-01,0.000000000000000000e+00,-1.000000009959574943e+00,0.000000000000000000e+00 +2.858687905269509333e+00,3.144000000000000128e+01,0.000000000000000000e+00,1.094799330475203192e+01,0.000000000000000000e+00,-3.229667282723981958e-01,0.000000000000000000e+00,-1.000000007258110113e+00,0.000000000000000000e+00 +2.859601314669902195e+00,3.144999999999999929e+01,0.000000000000000000e+00,1.094769830390641374e+01,0.000000000000000000e+00,-3.238801376794208098e-01,0.000000000000000000e+00,-1.000000011490709717e+00,0.000000000000000000e+00 +2.860514748683372410e+00,3.146000000000000085e+01,0.000000000000000000e+00,1.094740246077236989e+01,0.000000000000000000e+00,-3.247935717033871850e-01,0.000000000000000000e+00,-1.000000005477201137e+00,0.000000000000000000e+00 +2.861428207381527589e+00,3.147000000000000242e+01,0.000000000000000000e+00,1.094710577525919248e+01,0.000000000000000000e+00,-3.257070304065457500e-01,0.000000000000000000e+00,-1.000000012487242795e+00,0.000000000000000000e+00 +2.862341690835994434e+00,3.148000000000000043e+01,0.000000000000000000e+00,1.094680824727591251e+01,0.000000000000000000e+00,-3.266205138724196932e-01,0.000000000000000000e+00,-1.000000006825749965e+00,0.000000000000000000e+00 +2.863255199118419192e+00,3.149000000000000199e+01,0.000000000000000000e+00,1.094650987673128029e+01,0.000000000000000000e+00,-3.275340221610796299e-01,0.000000000000000000e+00,-1.000000009631059061e+00,0.000000000000000000e+00 +2.864168732300466313e+00,3.150000000000000000e+01,0.000000000000000000e+00,1.094621066353378680e+01,0.000000000000000000e+00,-3.284475553519249913e-01,0.000000000000000000e+00,-1.000000007981280525e+00,0.000000000000000000e+00 +2.865082290453820235e+00,3.151000000000000156e+01,0.000000000000000000e+00,1.094591060759164591e+01,0.000000000000000000e+00,-3.293611135125701916e-01,0.000000000000000000e+00,-1.000000010239892934e+00,0.000000000000000000e+00 +2.865995873650184489e+00,3.151999999999999957e+01,0.000000000000000000e+00,1.094560970881280504e+01,0.000000000000000000e+00,-3.302746967182893512e-01,0.000000000000000000e+00,-1.000000007743010233e+00,0.000000000000000000e+00 +2.866909481961281703e+00,3.153000000000000114e+01,0.000000000000000000e+00,1.094530796710493803e+01,0.000000000000000000e+00,-3.311883050364608505e-01,0.000000000000000000e+00,-1.000000008852273359e+00,0.000000000000000000e+00 +2.867823115458854932e+00,3.153999999999999915e+01,0.000000000000000000e+00,1.094500538237545229e+01,0.000000000000000000e+00,-3.321019385421216108e-01,0.000000000000000000e+00,-1.000000009159406789e+00,0.000000000000000000e+00 +2.868736774214665441e+00,3.155000000000000071e+01,0.000000000000000000e+00,1.094470195453148165e+01,0.000000000000000000e+00,-3.330155973063006480e-01,0.000000000000000000e+00,-1.000000010640176740e+00,0.000000000000000000e+00 +2.869650458300494922e+00,3.156000000000000227e+01,0.000000000000000000e+00,1.094439768347988995e+01,0.000000000000000000e+00,-3.339292814018516853e-01,0.000000000000000000e+00,-1.000000006758849924e+00,0.000000000000000000e+00 +2.870564167788144161e+00,3.157000000000000028e+01,0.000000000000000000e+00,1.094409256912726924e+01,0.000000000000000000e+00,-3.348429908956763734e-01,0.000000000000000000e+00,-1.000000010128632377e+00,0.000000000000000000e+00 +2.871477902749433486e+00,3.158000000000000185e+01,0.000000000000000000e+00,1.094378661137994513e+01,0.000000000000000000e+00,-3.357567258662207399e-01,0.000000000000000000e+00,-1.000000007829763504e+00,0.000000000000000000e+00 +2.872391663256203653e+00,3.158999999999999986e+01,0.000000000000000000e+00,1.094347981014396609e+01,0.000000000000000000e+00,-3.366704863801455172e-01,0.000000000000000000e+00,-1.000000010346135060e+00,0.000000000000000000e+00 +2.873305449380314958e+00,3.160000000000000142e+01,0.000000000000000000e+00,1.094317216532511416e+01,0.000000000000000000e+00,-3.375842725137108147e-01,0.000000000000000000e+00,-1.000000009013308100e+00,0.000000000000000000e+00 +2.874219261193646791e+00,3.160999999999999943e+01,0.000000000000000000e+00,1.094286367682889605e+01,0.000000000000000000e+00,-3.384980843352792812e-01,0.000000000000000000e+00,-1.000000007931270973e+00,0.000000000000000000e+00 +2.875133098768099416e+00,3.162000000000000099e+01,0.000000000000000000e+00,1.094255434456055021e+01,0.000000000000000000e+00,-3.394119219169798862e-01,0.000000000000000000e+00,-1.000000009071583262e+00,0.000000000000000000e+00 +2.876046962175592636e+00,3.162999999999999901e+01,0.000000000000000000e+00,1.094224416842504333e+01,0.000000000000000000e+00,-3.403257853327633087e-01,0.000000000000000000e+00,-1.000000010150868146e+00,0.000000000000000000e+00 +2.876960851488066240e+00,3.164000000000000057e+01,0.000000000000000000e+00,1.094193314832706854e+01,0.000000000000000000e+00,-3.412396746545136583e-01,0.000000000000000000e+00,-1.000000006759558024e+00,0.000000000000000000e+00 +2.877874766777479998e+00,3.165000000000000213e+01,0.000000000000000000e+00,1.094162128417104718e+01,0.000000000000000000e+00,-3.421535899501051414e-01,0.000000000000000000e+00,-1.000000011500989716e+00,0.000000000000000000e+00 +2.878788708115814110e+00,3.166000000000000014e+01,0.000000000000000000e+00,1.094130857586113237e+01,0.000000000000000000e+00,-3.430675312989504566e-01,0.000000000000000000e+00,-1.000000007204771668e+00,0.000000000000000000e+00 +2.879702675575068760e+00,3.167000000000000171e+01,0.000000000000000000e+00,1.094099502330119833e+01,0.000000000000000000e+00,-3.439814987647899502e-01,0.000000000000000000e+00,-1.000000008599013279e+00,0.000000000000000000e+00 +2.880616669227264115e+00,3.167999999999999972e+01,0.000000000000000000e+00,1.094068062639485461e+01,0.000000000000000000e+00,-3.448954924248449072e-01,0.000000000000000000e+00,-1.000000011272075717e+00,0.000000000000000000e+00 +2.881530689144441215e+00,3.169000000000000128e+01,0.000000000000000000e+00,1.094036538504543365e+01,0.000000000000000000e+00,-3.458095123523250436e-01,0.000000000000000000e+00,-1.000000006560543886e+00,0.000000000000000000e+00 +2.882444735398661528e+00,3.169999999999999929e+01,0.000000000000000000e+00,1.094004929915599433e+01,0.000000000000000000e+00,-3.467235586125417823e-01,0.000000000000000000e+00,-1.000000009188553696e+00,0.000000000000000000e+00 +2.883358808062006062e+00,3.171000000000000085e+01,0.000000000000000000e+00,1.093973236862932907e+01,0.000000000000000000e+00,-3.476376312842853200e-01,0.000000000000000000e+00,-1.000000010491441715e+00,0.000000000000000000e+00 +2.884272907206577141e+00,3.172000000000000242e+01,0.000000000000000000e+00,1.093941459336795141e+01,0.000000000000000000e+00,-3.485517304384465609e-01,0.000000000000000000e+00,-1.000000008183590028e+00,0.000000000000000000e+00 +2.885187032904497073e+00,3.173000000000000043e+01,0.000000000000000000e+00,1.093909597327410310e+01,0.000000000000000000e+00,-3.494658561438475086e-01,0.000000000000000000e+00,-1.000000008482060387e+00,0.000000000000000000e+00 +2.886101185227909482e+00,3.174000000000000199e+01,0.000000000000000000e+00,1.093877650824975589e+01,0.000000000000000000e+00,-3.503800084750138266e-01,0.000000000000000000e+00,-1.000000009099680787e+00,0.000000000000000000e+00 +2.887015364248977978e+00,3.175000000000000000e+01,0.000000000000000000e+00,1.093845619819660619e+01,0.000000000000000000e+00,-3.512941875044011675e-01,0.000000000000000000e+00,-1.000000009874884466e+00,0.000000000000000000e+00 +2.887929570039887484e+00,3.176000000000000156e+01,0.000000000000000000e+00,1.093813504301607686e+01,0.000000000000000000e+00,-3.522083933043382298e-01,0.000000000000000000e+00,-1.000000008520170569e+00,0.000000000000000000e+00 +2.888843802672842909e+00,3.176999999999999957e+01,0.000000000000000000e+00,1.093781304260931719e+01,0.000000000000000000e+00,-3.531226259450832017e-01,0.000000000000000000e+00,-1.000000009123835909e+00,0.000000000000000000e+00 +2.889758062220070922e+00,3.178000000000000114e+01,0.000000000000000000e+00,1.093749019687720470e+01,0.000000000000000000e+00,-3.540368855006527093e-01,0.000000000000000000e+00,-1.000000009397556733e+00,0.000000000000000000e+00 +2.890672348753818621e+00,3.178999999999999915e+01,0.000000000000000000e+00,1.093716650572034155e+01,0.000000000000000000e+00,-3.549511720429922579e-01,0.000000000000000000e+00,-1.000000007052970652e+00,0.000000000000000000e+00 +2.891586662346353531e+00,3.180000000000000071e+01,0.000000000000000000e+00,1.093684196903905637e+01,0.000000000000000000e+00,-3.558654856419760093e-01,0.000000000000000000e+00,-1.000000010425613484e+00,0.000000000000000000e+00 +2.892501003069965382e+00,3.181000000000000227e+01,0.000000000000000000e+00,1.093651658673340599e+01,0.000000000000000000e+00,-3.567798263751204568e-01,0.000000000000000000e+00,-1.000000008726783296e+00,0.000000000000000000e+00 +2.893415370996964331e+00,3.182000000000000028e+01,0.000000000000000000e+00,1.093619035870316836e+01,0.000000000000000000e+00,-3.576941943100988008e-01,0.000000000000000000e+00,-1.000000010290758024e+00,0.000000000000000000e+00 +2.894329766199681409e+00,3.183000000000000185e+01,0.000000000000000000e+00,1.093586328484785142e+01,0.000000000000000000e+00,-3.586085895222257958e-01,0.000000000000000000e+00,-1.000000006453981349e+00,0.000000000000000000e+00 +2.895244188750469405e+00,3.183999999999999986e+01,0.000000000000000000e+00,1.093553536506668600e+01,0.000000000000000000e+00,-3.595230120789155159e-01,0.000000000000000000e+00,-1.000000009797074929e+00,0.000000000000000000e+00 +2.896158638721701983e+00,3.185000000000000142e+01,0.000000000000000000e+00,1.093520659925863292e+01,0.000000000000000000e+00,-3.604374620591072054e-01,0.000000000000000000e+00,-1.000000009531622824e+00,0.000000000000000000e+00 +2.897073116185774566e+00,3.185999999999999943e+01,0.000000000000000000e+00,1.093487698732237234e+01,0.000000000000000000e+00,-3.613519395318962601e-01,0.000000000000000000e+00,-1.000000009739698159e+00,0.000000000000000000e+00 +2.897987621215103449e+00,3.187000000000000099e+01,0.000000000000000000e+00,1.093454652915631264e+01,0.000000000000000000e+00,-3.622664445701322400e-01,0.000000000000000000e+00,-1.000000008129915408e+00,0.000000000000000000e+00 +2.898902153882126687e+00,3.187999999999999901e+01,0.000000000000000000e+00,1.093421522465858686e+01,0.000000000000000000e+00,-3.631809772445906415e-01,0.000000000000000000e+00,-1.000000008782473637e+00,0.000000000000000000e+00 +2.899816714259303652e+00,3.189000000000000057e+01,0.000000000000000000e+00,1.093388307372705448e+01,0.000000000000000000e+00,-3.640955376297999035e-01,0.000000000000000000e+00,-1.000000009404981682e+00,0.000000000000000000e+00 +2.900731302419115476e+00,3.190000000000000213e+01,0.000000000000000000e+00,1.093355007625929787e+01,0.000000000000000000e+00,-3.650101257982136249e-01,0.000000000000000000e+00,-1.000000007705200256e+00,0.000000000000000000e+00 +2.901645918434065052e+00,3.191000000000000014e+01,0.000000000000000000e+00,1.093321623215262406e+01,0.000000000000000000e+00,-3.659247418202105084e-01,0.000000000000000000e+00,-1.000000009884581154e+00,0.000000000000000000e+00 +2.902560562376676589e+00,3.192000000000000171e+01,0.000000000000000000e+00,1.093288154130406653e+01,0.000000000000000000e+00,-3.668393857718628692e-01,0.000000000000000000e+00,-1.000000009402863599e+00,0.000000000000000000e+00 +2.903475234319496057e+00,3.192999999999999972e+01,0.000000000000000000e+00,1.093254600361037987e+01,0.000000000000000000e+00,-3.677540577232829011e-01,0.000000000000000000e+00,-1.000000010336702827e+00,0.000000000000000000e+00 +2.904389934335091628e+00,3.194000000000000128e+01,0.000000000000000000e+00,1.093220961896804511e+01,0.000000000000000000e+00,-3.686687577483332978e-01,0.000000000000000000e+00,-1.000000006146150699e+00,0.000000000000000000e+00 +2.905304662496052792e+00,3.194999999999999929e+01,0.000000000000000000e+00,1.093187238727326616e+01,0.000000000000000000e+00,-3.695834859149164653e-01,0.000000000000000000e+00,-1.000000011521111620e+00,0.000000000000000000e+00 +2.906219418874991245e+00,3.196000000000000085e+01,0.000000000000000000e+00,1.093153430842197515e+01,0.000000000000000000e+00,-3.704982423043939876e-01,0.000000000000000000e+00,-1.000000007183533324e+00,0.000000000000000000e+00 +2.907134203544540885e+00,3.197000000000000242e+01,0.000000000000000000e+00,1.093119538230982002e+01,0.000000000000000000e+00,-3.714130269805149820e-01,0.000000000000000000e+00,-1.000000009944029378e+00,0.000000000000000000e+00 +2.908049016577357371e+00,3.198000000000000043e+01,0.000000000000000000e+00,1.093085560883218044e+01,0.000000000000000000e+00,-3.723278400224283580e-01,0.000000000000000000e+00,-1.000000006893797089e+00,0.000000000000000000e+00 +2.908963858046118567e+00,3.199000000000000199e+01,0.000000000000000000e+00,1.093051498788415365e+01,0.000000000000000000e+00,-3.732426814974962315e-01,0.000000000000000000e+00,-1.000000010594855882e+00,0.000000000000000000e+00 +2.909878728023524541e+00,3.200000000000000000e+01,0.000000000000000000e+00,1.093017351936056514e+01,0.000000000000000000e+00,-3.741575514845950079e-01,0.000000000000000000e+00,-1.000000010261321570e+00,0.000000000000000000e+00 +2.910793626582297566e+00,3.200999999999999801e+01,0.000000000000000000e+00,1.092983120315595791e+01,0.000000000000000000e+00,-3.750724500527559124e-01,0.000000000000000000e+00,-1.000000007842163363e+00,0.000000000000000000e+00 +2.911708553795182119e+00,3.202000000000000313e+01,0.000000000000000000e+00,1.092948803916460143e+01,0.000000000000000000e+00,-3.759873772728152819e-01,0.000000000000000000e+00,-1.000000009528996037e+00,0.000000000000000000e+00 +2.912623509734944882e+00,3.203000000000000114e+01,0.000000000000000000e+00,1.092914402728048984e+01,0.000000000000000000e+00,-3.769023332212966815e-01,0.000000000000000000e+00,-1.000000008780545624e+00,0.000000000000000000e+00 +2.913538494474375629e+00,3.203999999999999915e+01,0.000000000000000000e+00,1.092879916739733659e+01,0.000000000000000000e+00,-3.778173179687612793e-01,0.000000000000000000e+00,-1.000000007543550673e+00,0.000000000000000000e+00 +2.914453508086285893e+00,3.204999999999999716e+01,0.000000000000000000e+00,1.092845345940857982e+01,0.000000000000000000e+00,-3.787323315875738006e-01,0.000000000000000000e+00,-1.000000009885108065e+00,0.000000000000000000e+00 +2.915368550643509860e+00,3.206000000000000227e+01,0.000000000000000000e+00,1.092810690320738054e+01,0.000000000000000000e+00,-3.796473741538430313e-01,0.000000000000000000e+00,-1.000000009263804168e+00,0.000000000000000000e+00 +2.916283622218904803e+00,3.207000000000000028e+01,0.000000000000000000e+00,1.092775949868661911e+01,0.000000000000000000e+00,-3.805624457377148051e-01,0.000000000000000000e+00,-1.000000009745912521e+00,0.000000000000000000e+00 +2.917198722885349760e+00,3.207999999999999829e+01,0.000000000000000000e+00,1.092741124573890055e+01,0.000000000000000000e+00,-3.814775464130784055e-01,0.000000000000000000e+00,-1.000000006911550443e+00,0.000000000000000000e+00 +2.918113852715747747e+00,3.209000000000000341e+01,0.000000000000000000e+00,1.092706214425655098e+01,0.000000000000000000e+00,-3.823926762498011667e-01,0.000000000000000000e+00,-1.000000011188136861e+00,0.000000000000000000e+00 +2.919029011783023098e+00,3.210000000000000142e+01,0.000000000000000000e+00,1.092671219413162120e+01,0.000000000000000000e+00,-3.833078353273156602e-01,0.000000000000000000e+00,-1.000000007550122305e+00,0.000000000000000000e+00 +2.919944200160124570e+00,3.210999999999999943e+01,0.000000000000000000e+00,1.092636139525587780e+01,0.000000000000000000e+00,-3.842230237113267166e-01,0.000000000000000000e+00,-1.000000010665033079e+00,0.000000000000000000e+00 +2.920859417920022238e+00,3.211999999999999744e+01,0.000000000000000000e+00,1.092600974752081555e+01,0.000000000000000000e+00,-3.851382414809853549e-01,0.000000000000000000e+00,-1.000000007628682352e+00,0.000000000000000000e+00 +2.921774665135710602e+00,3.213000000000000256e+01,0.000000000000000000e+00,1.092565725081764505e+01,0.000000000000000000e+00,-3.860534887036556340e-01,0.000000000000000000e+00,-1.000000008864790679e+00,0.000000000000000000e+00 +2.922689941880205922e+00,3.214000000000000057e+01,0.000000000000000000e+00,1.092530390503730331e+01,0.000000000000000000e+00,-3.869687654562646850e-01,0.000000000000000000e+00,-1.000000009951131252e+00,0.000000000000000000e+00 +2.923605248226548436e+00,3.214999999999999858e+01,0.000000000000000000e+00,1.092494971007044491e+01,0.000000000000000000e+00,-3.878840718117154140e-01,0.000000000000000000e+00,-1.000000008586880318e+00,0.000000000000000000e+00 +2.924520584247801036e+00,3.216000000000000369e+01,0.000000000000000000e+00,1.092459466580744554e+01,0.000000000000000000e+00,-3.887994078408278376e-01,0.000000000000000000e+00,-1.000000008831331444e+00,0.000000000000000000e+00 +2.925435950017050146e+00,3.217000000000000171e+01,0.000000000000000000e+00,1.092423877213840377e+01,0.000000000000000000e+00,-3.897147736181607036e-01,0.000000000000000000e+00,-1.000000010502144265e+00,0.000000000000000000e+00 +2.926351345607405285e+00,3.217999999999999972e+01,0.000000000000000000e+00,1.092388202895313754e+01,0.000000000000000000e+00,-3.906301692181292640e-01,0.000000000000000000e+00,-1.000000007057403550e+00,0.000000000000000000e+00 +2.927266771091999065e+00,3.218999999999999773e+01,0.000000000000000000e+00,1.092352443614118407e+01,0.000000000000000000e+00,-3.915455947091835975e-01,0.000000000000000000e+00,-1.000000008913568994e+00,0.000000000000000000e+00 +2.928182226543988076e+00,3.220000000000000284e+01,0.000000000000000000e+00,1.092316599359180529e+01,0.000000000000000000e+00,-3.924610501693325260e-01,0.000000000000000000e+00,-1.000000009527425737e+00,0.000000000000000000e+00 +2.929097712036552004e+00,3.221000000000000085e+01,0.000000000000000000e+00,1.092280670119397890e+01,0.000000000000000000e+00,-3.933765356706185878e-01,0.000000000000000000e+00,-1.000000010835027542e+00,0.000000000000000000e+00 +2.930013227642894069e+00,3.221999999999999886e+01,0.000000000000000000e+00,1.092244655883640370e+01,0.000000000000000000e+00,-3.942920512868802185e-01,0.000000000000000000e+00,-1.000000006294209598e+00,0.000000000000000000e+00 +2.930928773436241030e+00,3.223000000000000398e+01,0.000000000000000000e+00,1.092208556640749784e+01,0.000000000000000000e+00,-3.952075970859898479e-01,0.000000000000000000e+00,-1.000000010554795038e+00,0.000000000000000000e+00 +2.931844349489843626e+00,3.224000000000000199e+01,0.000000000000000000e+00,1.092172372379540413e+01,0.000000000000000000e+00,-3.961231731492560471e-01,0.000000000000000000e+00,-1.000000008596958923e+00,0.000000000000000000e+00 +2.932759955876975688e+00,3.225000000000000000e+01,0.000000000000000000e+00,1.092136103088797761e+01,0.000000000000000000e+00,-3.970387795442596457e-01,0.000000000000000000e+00,-1.000000008711755539e+00,0.000000000000000000e+00 +2.933675592670935472e+00,3.225999999999999801e+01,0.000000000000000000e+00,1.092099748757279798e+01,0.000000000000000000e+00,-3.979544163461962714e-01,0.000000000000000000e+00,-1.000000010711815435e+00,0.000000000000000000e+00 +2.934591259945044772e+00,3.227000000000000313e+01,0.000000000000000000e+00,1.092063309373716251e+01,0.000000000000000000e+00,-3.988700836301140029e-01,0.000000000000000000e+00,-1.000000005936508840e+00,0.000000000000000000e+00 +2.935506957772649361e+00,3.228000000000000114e+01,0.000000000000000000e+00,1.092026784926808602e+01,0.000000000000000000e+00,-3.997857814631544660e-01,0.000000000000000000e+00,-1.000000011146424672e+00,0.000000000000000000e+00 +2.936422686227118550e+00,3.228999999999999915e+01,0.000000000000000000e+00,1.091990175405230801e+01,0.000000000000000000e+00,-4.007015099278307679e-01,0.000000000000000000e+00,-1.000000009206037044e+00,0.000000000000000000e+00 +2.937338445381846075e+00,3.229999999999999716e+01,0.000000000000000000e+00,1.091953480797627840e+01,0.000000000000000000e+00,-4.016172690909889376e-01,0.000000000000000000e+00,-1.000000008400835139e+00,0.000000000000000000e+00 +2.938254235310250095e+00,3.231000000000000227e+01,0.000000000000000000e+00,1.091916701092617181e+01,0.000000000000000000e+00,-4.025330590270861930e-01,0.000000000000000000e+00,-1.000000008541777730e+00,0.000000000000000000e+00 +2.939170056085771865e+00,3.232000000000000028e+01,0.000000000000000000e+00,1.091879836278788041e+01,0.000000000000000000e+00,-4.034488798104308716e-01,0.000000000000000000e+00,-1.000000009439295123e+00,0.000000000000000000e+00 +2.940085907781877950e+00,3.232999999999999829e+01,0.000000000000000000e+00,1.091842886344701391e+01,0.000000000000000000e+00,-4.043647315151819854e-01,0.000000000000000000e+00,-1.000000008785776773e+00,0.000000000000000000e+00 +2.941001790472058453e+00,3.234000000000000341e+01,0.000000000000000000e+00,1.091805851278889961e+01,0.000000000000000000e+00,-4.052806142134093847e-01,0.000000000000000000e+00,-1.000000010626179048e+00,0.000000000000000000e+00 +2.941917704229828345e+00,3.235000000000000142e+01,0.000000000000000000e+00,1.091768731069858411e+01,0.000000000000000000e+00,-4.061965279809119367e-01,0.000000000000000000e+00,-1.000000008417087694e+00,0.000000000000000000e+00 +2.942833649128726581e+00,3.235999999999999943e+01,0.000000000000000000e+00,1.091731525706082984e+01,0.000000000000000000e+00,-4.071124728875197274e-01,0.000000000000000000e+00,-1.000000008319932299e+00,0.000000000000000000e+00 +2.943749625242316537e+00,3.236999999999999744e+01,0.000000000000000000e+00,1.091694235176012029e+01,0.000000000000000000e+00,-4.080284490087306426e-01,0.000000000000000000e+00,-1.000000008025065501e+00,0.000000000000000000e+00 +2.944665632644186459e+00,3.238000000000000256e+01,0.000000000000000000e+00,1.091656859468065477e+01,0.000000000000000000e+00,-4.089444564179516295e-01,0.000000000000000000e+00,-1.000000009457086003e+00,0.000000000000000000e+00 +2.945581671407949020e+00,3.239000000000000057e+01,0.000000000000000000e+00,1.091619398570635013e+01,0.000000000000000000e+00,-4.098604951903772053e-01,0.000000000000000000e+00,-1.000000010306162812e+00,0.000000000000000000e+00 +2.946497741607241316e+00,3.239999999999999858e+01,0.000000000000000000e+00,1.091581852472083902e+01,0.000000000000000000e+00,-4.107765653991107269e-01,0.000000000000000000e+00,-1.000000008262470486e+00,0.000000000000000000e+00 +2.947413843315725313e+00,3.241000000000000369e+01,0.000000000000000000e+00,1.091544221160747163e+01,0.000000000000000000e+00,-4.116926671151641681e-01,0.000000000000000000e+00,-1.000000009482227670e+00,0.000000000000000000e+00 +2.948329976607088287e+00,3.242000000000000171e+01,0.000000000000000000e+00,1.091506504624931750e+01,0.000000000000000000e+00,-4.126088004152139166e-01,0.000000000000000000e+00,-1.000000009537465040e+00,0.000000000000000000e+00 +2.949246141555041056e+00,3.242999999999999972e+01,0.000000000000000000e+00,1.091468702852916017e+01,0.000000000000000000e+00,-4.135249653719047513e-01,0.000000000000000000e+00,-1.000000008233904669e+00,0.000000000000000000e+00 +2.950162338233320636e+00,3.243999999999999773e+01,0.000000000000000000e+00,1.091430815832950074e+01,0.000000000000000000e+00,-4.144411620577282407e-01,0.000000000000000000e+00,-1.000000007492426235e+00,0.000000000000000000e+00 +2.951078566715688467e+00,3.245000000000000284e+01,0.000000000000000000e+00,1.091392843553255787e+01,0.000000000000000000e+00,-4.153573905469607475e-01,0.000000000000000000e+00,-1.000000011348578299e+00,0.000000000000000000e+00 +2.951994827075930861e+00,3.246000000000000085e+01,0.000000000000000000e+00,1.091354786002026600e+01,0.000000000000000000e+00,-4.162736509176013233e-01,0.000000000000000000e+00,-1.000000009026585701e+00,0.000000000000000000e+00 +2.952911119387859440e+00,3.246999999999999886e+01,0.000000000000000000e+00,1.091316643167427181e+01,0.000000000000000000e+00,-4.171899432378007866e-01,0.000000000000000000e+00,-1.000000006677562059e+00,0.000000000000000000e+00 +2.953827443725310697e+00,3.248000000000000398e+01,0.000000000000000000e+00,1.091278415037594307e+01,0.000000000000000000e+00,-4.181062675813709273e-01,0.000000000000000000e+00,-1.000000012565809504e+00,0.000000000000000000e+00 +2.954743800162146883e+00,3.249000000000000199e+01,0.000000000000000000e+00,1.091240101600636336e+01,0.000000000000000000e+00,-4.190226240297217908e-01,0.000000000000000000e+00,-1.000000005338856468e+00,0.000000000000000000e+00 +2.955660188772255115e+00,3.250000000000000000e+01,0.000000000000000000e+00,1.091201702844632493e+01,0.000000000000000000e+00,-4.199390126447223315e-01,0.000000000000000000e+00,-1.000000012297848961e+00,0.000000000000000000e+00 +2.956576609629547825e+00,3.250999999999999801e+01,0.000000000000000000e+00,1.091163218757634645e+01,0.000000000000000000e+00,-4.208554335132849156e-01,0.000000000000000000e+00,-1.000000007860841533e+00,0.000000000000000000e+00 +2.957493062807962758e+00,3.252000000000000313e+01,0.000000000000000000e+00,1.091124649327664997e+01,0.000000000000000000e+00,-4.217718866989040305e-01,0.000000000000000000e+00,-1.000000008749894365e+00,0.000000000000000000e+00 +2.958409548381463416e+00,3.253000000000000114e+01,0.000000000000000000e+00,1.091085994542718218e+01,0.000000000000000000e+00,-4.226883722804240517e-01,0.000000000000000000e+00,-1.000000008419470010e+00,0.000000000000000000e+00 +2.959326066424039059e+00,3.253999999999999915e+01,0.000000000000000000e+00,1.091047254390760024e+01,0.000000000000000000e+00,-4.236048903307162994e-01,0.000000000000000000e+00,-1.000000008784224015e+00,0.000000000000000000e+00 +2.960242617009703814e+00,3.254999999999999716e+01,0.000000000000000000e+00,1.091008428859727708e+01,0.000000000000000000e+00,-4.245214409244324472e-01,0.000000000000000000e+00,-1.000000009642697085e+00,0.000000000000000000e+00 +2.961159200212498455e+00,3.256000000000000227e+01,0.000000000000000000e+00,1.090969517937529965e+01,0.000000000000000000e+00,-4.254380241360652404e-01,0.000000000000000000e+00,-1.000000010793449245e+00,0.000000000000000000e+00 +2.962075816106488180e+00,3.257000000000000028e+01,0.000000000000000000e+00,1.090930521612046888e+01,0.000000000000000000e+00,-4.263546400399485514e-01,0.000000000000000000e+00,-1.000000005692372351e+00,0.000000000000000000e+00 +2.962992464765765277e+00,3.257999999999999829e+01,0.000000000000000000e+00,1.090891439871129975e+01,0.000000000000000000e+00,-4.272712887044434193e-01,0.000000000000000000e+00,-1.000000011049552384e+00,0.000000000000000000e+00 +2.963909146264446903e+00,3.259000000000000341e+01,0.000000000000000000e+00,1.090852272702602654e+01,0.000000000000000000e+00,-4.281879702132539434e-01,0.000000000000000000e+00,-1.000000009749367091e+00,0.000000000000000000e+00 +2.964825860676676417e+00,3.260000000000000142e+01,0.000000000000000000e+00,1.090813020094258867e+01,0.000000000000000000e+00,-4.291046846344210297e-01,0.000000000000000000e+00,-1.000000007930720081e+00,0.000000000000000000e+00 +2.965742608076623821e+00,3.260999999999999943e+01,0.000000000000000000e+00,1.090773682033864489e+01,0.000000000000000000e+00,-4.300214320416387292e-01,0.000000000000000000e+00,-1.000000009616670349e+00,0.000000000000000000e+00 +2.966659388538483988e+00,3.261999999999999744e+01,0.000000000000000000e+00,1.090734258509156795e+01,0.000000000000000000e+00,-4.309382125123153440e-01,0.000000000000000000e+00,-1.000000008261833662e+00,0.000000000000000000e+00 +2.967576202136478880e+00,3.263000000000000256e+01,0.000000000000000000e+00,1.090694749507844108e+01,0.000000000000000000e+00,-4.318550261178847327e-01,0.000000000000000000e+00,-1.000000010001369510e+00,0.000000000000000000e+00 +2.968493048944856216e+00,3.264000000000000057e+01,0.000000000000000000e+00,1.090655155017606326e+01,0.000000000000000000e+00,-4.327718729354316229e-01,0.000000000000000000e+00,-1.000000008289665621e+00,0.000000000000000000e+00 +2.969409929037889917e+00,3.264999999999999858e+01,0.000000000000000000e+00,1.090615475026094394e+01,0.000000000000000000e+00,-4.336887530360657439e-01,0.000000000000000000e+00,-1.000000009260372691e+00,0.000000000000000000e+00 +2.970326842489880104e+00,3.266000000000000369e+01,0.000000000000000000e+00,1.090575709520930836e+01,0.000000000000000000e+00,-4.346056664965468053e-01,0.000000000000000000e+00,-1.000000008480468550e+00,0.000000000000000000e+00 +2.971243789375153543e+00,3.267000000000000171e+01,0.000000000000000000e+00,1.090535858489709220e+01,0.000000000000000000e+00,-4.355226133895963025e-01,0.000000000000000000e+00,-1.000000009968397885e+00,0.000000000000000000e+00 +2.972160769768063204e+00,3.267999999999999972e+01,0.000000000000000000e+00,1.090495921919994515e+01,0.000000000000000000e+00,-4.364395937916468182e-01,0.000000000000000000e+00,-1.000000009291244663e+00,0.000000000000000000e+00 +2.973077783742988700e+00,3.268999999999999773e+01,0.000000000000000000e+00,1.090455899799322736e+01,0.000000000000000000e+00,-4.373566077750926095e-01,0.000000000000000000e+00,-1.000000008353453040e+00,0.000000000000000000e+00 +2.973994831374336290e+00,3.270000000000000284e+01,0.000000000000000000e+00,1.090415792115201299e+01,0.000000000000000000e+00,-4.382736554141007379e-01,0.000000000000000000e+00,-1.000000009058451100e+00,0.000000000000000000e+00 +2.974911912736538877e+00,3.271000000000000085e+01,0.000000000000000000e+00,1.090375598855108841e+01,0.000000000000000000e+00,-4.391907367846104582e-01,0.000000000000000000e+00,-1.000000009084703212e+00,0.000000000000000000e+00 +2.975829027904055568e+00,3.271999999999999886e+01,0.000000000000000000e+00,1.090335320006495046e+01,0.000000000000000000e+00,-4.401078519604587624e-01,0.000000000000000000e+00,-1.000000008222508230e+00,0.000000000000000000e+00 +2.976746176951372558e+00,3.273000000000000398e+01,0.000000000000000000e+00,1.090294955556780820e+01,0.000000000000000000e+00,-4.410250010153169975e-01,0.000000000000000000e+00,-1.000000010485214919e+00,0.000000000000000000e+00 +2.977663359953003130e+00,3.274000000000000199e+01,0.000000000000000000e+00,1.090254505493358295e+01,0.000000000000000000e+00,-4.419421840265642110e-01,0.000000000000000000e+00,-1.000000009326479589e+00,0.000000000000000000e+00 +2.978580576983486772e+00,3.275000000000000000e+01,0.000000000000000000e+00,1.090213969803590466e+01,0.000000000000000000e+00,-4.428594010656022317e-01,0.000000000000000000e+00,-1.000000008758827885e+00,0.000000000000000000e+00 +2.979497828117390501e+00,3.275999999999999801e+01,0.000000000000000000e+00,1.090173348474811732e+01,0.000000000000000000e+00,-4.437766522075399789e-01,0.000000000000000000e+00,-1.000000008570168575e+00,0.000000000000000000e+00 +2.980415113429307983e+00,3.277000000000000313e+01,0.000000000000000000e+00,1.090132641494327537e+01,0.000000000000000000e+00,-4.446939375273188944e-01,0.000000000000000000e+00,-1.000000008547705654e+00,0.000000000000000000e+00 +2.981332432993860415e+00,3.278000000000000114e+01,0.000000000000000000e+00,1.090091848849414369e+01,0.000000000000000000e+00,-4.456112570997123323e-01,0.000000000000000000e+00,-1.000000008478844515e+00,0.000000000000000000e+00 +2.982249786885695642e+00,3.278999999999999915e+01,0.000000000000000000e+00,1.090050970527319762e+01,0.000000000000000000e+00,-4.465286109993257813e-01,0.000000000000000000e+00,-1.000000010260633454e+00,0.000000000000000000e+00 +2.983167175179489039e+00,3.279999999999999716e+01,0.000000000000000000e+00,1.090010006515262297e+01,0.000000000000000000e+00,-4.474459993025322602e-01,0.000000000000000000e+00,-1.000000009457510330e+00,0.000000000000000000e+00 +2.984084597949943074e+00,3.281000000000000227e+01,0.000000000000000000e+00,1.089968956800431421e+01,0.000000000000000000e+00,-4.483634220816629656e-01,0.000000000000000000e+00,-1.000000007966221238e+00,0.000000000000000000e+00 +2.985002055271787746e+00,3.282000000000000028e+01,0.000000000000000000e+00,1.089927821369987804e+01,0.000000000000000000e+00,-4.492808794108163473e-01,0.000000000000000000e+00,-1.000000009792296307e+00,0.000000000000000000e+00 +2.985919547219780146e+00,3.282999999999999829e+01,0.000000000000000000e+00,1.089886600211063161e+01,0.000000000000000000e+00,-4.501983713677932264e-01,0.000000000000000000e+00,-1.000000008388875372e+00,0.000000000000000000e+00 +2.986837073868705339e+00,3.284000000000000341e+01,0.000000000000000000e+00,1.089845293310759899e+01,0.000000000000000000e+00,-4.511158980244153183e-01,0.000000000000000000e+00,-1.000000009870793960e+00,0.000000000000000000e+00 +2.987754635293375038e+00,3.285000000000000142e+01,0.000000000000000000e+00,1.089803900656151647e+01,0.000000000000000000e+00,-4.520334594581422727e-01,0.000000000000000000e+00,-1.000000007691230985e+00,0.000000000000000000e+00 +2.988672231568629822e+00,3.285999999999999943e+01,0.000000000000000000e+00,1.089762422234282724e+01,0.000000000000000000e+00,-4.529510557404543003e-01,0.000000000000000000e+00,-1.000000010072377599e+00,0.000000000000000000e+00 +2.989589862769336470e+00,3.286999999999999744e+01,0.000000000000000000e+00,1.089720858032168671e+01,0.000000000000000000e+00,-4.538686869504038324e-01,0.000000000000000000e+00,-1.000000010466909783e+00,0.000000000000000000e+00 +2.990507528970390627e+00,3.288000000000000256e+01,0.000000000000000000e+00,1.089679208036795544e+01,0.000000000000000000e+00,-4.547863531610632504e-01,0.000000000000000000e+00,-1.000000006548348308e+00,0.000000000000000000e+00 +2.991425230246715472e+00,3.289000000000000057e+01,0.000000000000000000e+00,1.089637472235120441e+01,0.000000000000000000e+00,-4.557040544433975104e-01,0.000000000000000000e+00,-1.000000010753145707e+00,0.000000000000000000e+00 +2.992342966673261717e+00,3.289999999999999858e+01,0.000000000000000000e+00,1.089595650614071687e+01,0.000000000000000000e+00,-4.566217908798123615e-01,0.000000000000000000e+00,-1.000000008097694515e+00,0.000000000000000000e+00 +2.993260738325008496e+00,3.291000000000000369e+01,0.000000000000000000e+00,1.089553743160547761e+01,0.000000000000000000e+00,-4.575395625389908072e-01,0.000000000000000000e+00,-1.000000008907715454e+00,0.000000000000000000e+00 +2.994178545276962478e+00,3.292000000000000171e+01,0.000000000000000000e+00,1.089511749861418544e+01,0.000000000000000000e+00,-4.584573694991201376e-01,0.000000000000000000e+00,-1.000000010853269394e+00,0.000000000000000000e+00 +2.995096387604158306e+00,3.292999999999999972e+01,0.000000000000000000e+00,1.089469670703524429e+01,0.000000000000000000e+00,-4.593752118362775527e-01,0.000000000000000000e+00,-1.000000007388015755e+00,0.000000000000000000e+00 +2.996014265381659047e+00,3.293999999999999773e+01,0.000000000000000000e+00,1.089427505673676499e+01,0.000000000000000000e+00,-4.602930896205597588e-01,0.000000000000000000e+00,-1.000000008833257237e+00,0.000000000000000000e+00 +2.996932178684556192e+00,3.295000000000000284e+01,0.000000000000000000e+00,1.089385254758657062e+01,0.000000000000000000e+00,-4.612110029315651394e-01,0.000000000000000000e+00,-1.000000008641429350e+00,0.000000000000000000e+00 +2.997850127587969205e+00,3.296000000000000085e+01,0.000000000000000000e+00,1.089342917945218758e+01,0.000000000000000000e+00,-4.621289518429105292e-01,0.000000000000000000e+00,-1.000000010806311623e+00,0.000000000000000000e+00 +2.998768112167045974e+00,3.296999999999999886e+01,0.000000000000000000e+00,1.089300495220085097e+01,0.000000000000000000e+00,-4.630469364319071413e-01,0.000000000000000000e+00,-1.000000008780938865e+00,0.000000000000000000e+00 +2.999686132496962365e+00,3.298000000000000398e+01,0.000000000000000000e+00,1.089257986569950098e+01,0.000000000000000000e+00,-4.639649567698845845e-01,0.000000000000000000e+00,-1.000000008665870466e+00,0.000000000000000000e+00 +3.000604188652923110e+00,3.299000000000000199e+01,0.000000000000000000e+00,1.089215391981478831e+01,0.000000000000000000e+00,-4.648830129338011319e-01,0.000000000000000000e+00,-1.000000008128933304e+00,0.000000000000000000e+00 +3.001522280710161361e+00,3.300000000000000000e+01,0.000000000000000000e+00,1.089172711441306873e+01,0.000000000000000000e+00,-4.658011049985026353e-01,0.000000000000000000e+00,-1.000000009052755656e+00,0.000000000000000000e+00 +3.002440408743939138e+00,3.300999999999999801e+01,0.000000000000000000e+00,1.089129944936040495e+01,0.000000000000000000e+00,-4.667192330405919853e-01,0.000000000000000000e+00,-1.000000011211882089e+00,0.000000000000000000e+00 +3.003358572829546880e+00,3.302000000000000313e+01,0.000000000000000000e+00,1.089087092452256478e+01,0.000000000000000000e+00,-4.676373971364938820e-01,0.000000000000000000e+00,-1.000000008059489076e+00,0.000000000000000000e+00 +3.004276773042303450e+00,3.303000000000000114e+01,0.000000000000000000e+00,1.089044153976502116e+01,0.000000000000000000e+00,-4.685555973566505883e-01,0.000000000000000000e+00,-1.000000007797851698e+00,0.000000000000000000e+00 +3.005195009457557020e+00,3.303999999999999915e+01,0.000000000000000000e+00,1.089001129495295750e+01,0.000000000000000000e+00,-4.694738337790642091e-01,0.000000000000000000e+00,-1.000000010199157963e+00,0.000000000000000000e+00 +3.006113282150684185e+00,3.304999999999999716e+01,0.000000000000000000e+00,1.088958018995126054e+01,0.000000000000000000e+00,-4.703921064815568265e-01,0.000000000000000000e+00,-1.000000008716428246e+00,0.000000000000000000e+00 +3.007031591197090403e+00,3.306000000000000227e+01,0.000000000000000000e+00,1.088914822462452037e+01,0.000000000000000000e+00,-4.713104155359675862e-01,0.000000000000000000e+00,-1.000000009441223359e+00,0.000000000000000000e+00 +3.007949936672210889e+00,3.307000000000000028e+01,0.000000000000000000e+00,1.088871539883703576e+01,0.000000000000000000e+00,-4.722287610197583585e-01,0.000000000000000000e+00,-1.000000007932696500e+00,0.000000000000000000e+00 +3.008868318651509277e+00,3.307999999999999829e+01,0.000000000000000000e+00,1.088828171245280885e+01,0.000000000000000000e+00,-4.731471430063419192e-01,0.000000000000000000e+00,-1.000000010279890716e+00,0.000000000000000000e+00 +3.009786737210478513e+00,3.309000000000000341e+01,0.000000000000000000e+00,1.088784716533554864e+01,0.000000000000000000e+00,-4.740655615747522145e-01,0.000000000000000000e+00,-1.000000009935221978e+00,0.000000000000000000e+00 +3.010705192424640408e+00,3.310000000000000142e+01,0.000000000000000000e+00,1.088741175734866573e+01,0.000000000000000000e+00,-4.749840167980391437e-01,0.000000000000000000e+00,-1.000000006669406138e+00,0.000000000000000000e+00 +3.011623684369546528e+00,3.310999999999999943e+01,0.000000000000000000e+00,1.088697548835527762e+01,0.000000000000000000e+00,-4.759025087490709738e-01,0.000000000000000000e+00,-1.000000010779606097e+00,0.000000000000000000e+00 +3.012542213120777301e+00,3.311999999999999744e+01,0.000000000000000000e+00,1.088653835821820870e+01,0.000000000000000000e+00,-4.768210375102032161e-01,0.000000000000000000e+00,-1.000000007295851479e+00,0.000000000000000000e+00 +3.013460778753942915e+00,3.313000000000000256e+01,0.000000000000000000e+00,1.088610036679998139e+01,0.000000000000000000e+00,-4.777396031500706908e-01,0.000000000000000000e+00,-1.000000010724267030e+00,0.000000000000000000e+00 +3.014379381344683306e+00,3.314000000000000057e+01,0.000000000000000000e+00,1.088566151396282855e+01,0.000000000000000000e+00,-4.786582057506622023e-01,0.000000000000000000e+00,-1.000000008200987667e+00,0.000000000000000000e+00 +3.015298020968666837e+00,3.314999999999999858e+01,0.000000000000000000e+00,1.088522179956868108e+01,0.000000000000000000e+00,-4.795768453821795951e-01,0.000000000000000000e+00,-1.000000010018813557e+00,0.000000000000000000e+00 +3.016216697701592508e+00,3.316000000000000369e+01,0.000000000000000000e+00,1.088478122347917854e+01,0.000000000000000000e+00,-4.804955221243094043e-01,0.000000000000000000e+00,-1.000000007524849410e+00,0.000000000000000000e+00 +3.017135411619188634e+00,3.317000000000000171e+01,0.000000000000000000e+00,1.088433978555566028e+01,0.000000000000000000e+00,-4.814142360488187777e-01,0.000000000000000000e+00,-1.000000011008240985e+00,0.000000000000000000e+00 +3.018054162797213280e+00,3.317999999999999972e+01,0.000000000000000000e+00,1.088389748565917259e+01,0.000000000000000000e+00,-4.823329872369572779e-01,0.000000000000000000e+00,-1.000000007607745323e+00,0.000000000000000000e+00 +3.018972951311454267e+00,3.318999999999999773e+01,0.000000000000000000e+00,1.088345432365045973e+01,0.000000000000000000e+00,-4.832517757581881734e-01,0.000000000000000000e+00,-1.000000009714412164e+00,0.000000000000000000e+00 +3.019891777237729169e+00,3.320000000000000284e+01,0.000000000000000000e+00,1.088301029938997466e+01,0.000000000000000000e+00,-4.841706016933890466e-01,0.000000000000000000e+00,-1.000000008675708374e+00,0.000000000000000000e+00 +3.020810640651885759e+00,3.321000000000000085e+01,0.000000000000000000e+00,1.088256541273786837e+01,0.000000000000000000e+00,-4.850894651155175374e-01,0.000000000000000000e+00,-1.000000010567642095e+00,0.000000000000000000e+00 +3.021729541629802007e+00,3.321999999999999886e+01,0.000000000000000000e+00,1.088211966355399696e+01,0.000000000000000000e+00,-4.860083661031441848e-01,0.000000000000000000e+00,-1.000000006738372083e+00,0.000000000000000000e+00 +3.022648480247385194e+00,3.323000000000000398e+01,0.000000000000000000e+00,1.088167305169791632e+01,0.000000000000000000e+00,-4.869273047269194188e-01,0.000000000000000000e+00,-1.000000009572864501e+00,0.000000000000000000e+00 +3.023567456580573243e+00,3.324000000000000199e+01,0.000000000000000000e+00,1.088122557702888926e+01,0.000000000000000000e+00,-4.878462810689046525e-01,0.000000000000000000e+00,-1.000000010418111263e+00,0.000000000000000000e+00 +3.024486470705334273e+00,3.325000000000000000e+01,0.000000000000000000e+00,1.088077723940587482e+01,0.000000000000000000e+00,-4.887652952032400244e-01,0.000000000000000000e+00,-1.000000006933875918e+00,0.000000000000000000e+00 +3.025405522697666605e+00,3.325999999999999801e+01,0.000000000000000000e+00,1.088032803868753540e+01,0.000000000000000000e+00,-4.896843472019449250e-01,0.000000000000000000e+00,-1.000000011499337926e+00,0.000000000000000000e+00 +3.026324612633598754e+00,3.327000000000000313e+01,0.000000000000000000e+00,1.087987797473223850e+01,0.000000000000000000e+00,-4.906034371484461754e-01,0.000000000000000000e+00,-1.000000007051550233e+00,0.000000000000000000e+00 +3.027243740589190324e+00,3.328000000000000114e+01,0.000000000000000000e+00,1.087942704739804611e+01,0.000000000000000000e+00,-4.915225651105188942e-01,0.000000000000000000e+00,-1.000000010172873210e+00,0.000000000000000000e+00 +3.028162906640530672e+00,3.328999999999999915e+01,0.000000000000000000e+00,1.087897525654272890e+01,0.000000000000000000e+00,-4.924417311712095957e-01,0.000000000000000000e+00,-1.000000010109102222e+00,0.000000000000000000e+00 +3.029082110863739796e+00,3.329999999999999716e+01,0.000000000000000000e+00,1.087852260202375199e+01,0.000000000000000000e+00,-4.933609354037108985e-01,0.000000000000000000e+00,-1.000000006620135107e+00,0.000000000000000000e+00 +3.030001353334968339e+00,3.331000000000000227e+01,0.000000000000000000e+00,1.087806908369828385e+01,0.000000000000000000e+00,-4.942801778810249624e-01,0.000000000000000000e+00,-1.000000009975011928e+00,0.000000000000000000e+00 +3.030920634130398028e+00,3.332000000000000028e+01,0.000000000000000000e+00,1.087761470142319631e+01,0.000000000000000000e+00,-4.951994586856243719e-01,0.000000000000000000e+00,-1.000000009420612956e+00,0.000000000000000000e+00 +3.031839953326240789e+00,3.332999999999999829e+01,0.000000000000000000e+00,1.087715945505505566e+01,0.000000000000000000e+00,-4.961187778901277046e-01,0.000000000000000000e+00,-1.000000008918423555e+00,0.000000000000000000e+00 +3.032759310998739632e+00,3.334000000000000341e+01,0.000000000000000000e+00,1.087670334445013154e+01,0.000000000000000000e+00,-4.970381355708259341e-01,0.000000000000000000e+00,-1.000000008225324200e+00,0.000000000000000000e+00 +3.033678707224168658e+00,3.335000000000000142e+01,0.000000000000000000e+00,1.087624636946439338e+01,0.000000000000000000e+00,-4.979575318038174103e-01,0.000000000000000000e+00,-1.000000011299739144e+00,0.000000000000000000e+00 +3.034598142078832606e+00,3.335999999999999943e+01,0.000000000000000000e+00,1.087578852995351042e+01,0.000000000000000000e+00,-4.988769666688709359e-01,0.000000000000000000e+00,-1.000000007390857482e+00,0.000000000000000000e+00 +3.035517615639067746e+00,3.336999999999999744e+01,0.000000000000000000e+00,1.087532982577284812e+01,0.000000000000000000e+00,-4.997964402359016955e-01,0.000000000000000000e+00,-1.000000008861131606e+00,0.000000000000000000e+00 +3.036437127981240547e+00,3.338000000000000256e+01,0.000000000000000000e+00,1.087487025677747710e+01,0.000000000000000000e+00,-5.007159525862225902e-01,0.000000000000000000e+00,-1.000000009160865400e+00,0.000000000000000000e+00 +3.037356679181749453e+00,3.339000000000000057e+01,0.000000000000000000e+00,1.087440982282216240e+01,0.000000000000000000e+00,-5.016355037951555351e-01,0.000000000000000000e+00,-1.000000010145302376e+00,0.000000000000000000e+00 +3.038276269317023992e+00,3.339999999999999858e+01,0.000000000000000000e+00,1.087394852376136889e+01,0.000000000000000000e+00,-5.025550939397596117e-01,0.000000000000000000e+00,-1.000000007366421029e+00,0.000000000000000000e+00 +3.039195898463524781e+00,3.341000000000000369e+01,0.000000000000000000e+00,1.087348635944925945e+01,0.000000000000000000e+00,-5.034747230930347595e-01,0.000000000000000000e+00,-1.000000011079182016e+00,0.000000000000000000e+00 +3.040115566697743965e+00,3.342000000000000171e+01,0.000000000000000000e+00,1.087302332973969854e+01,0.000000000000000000e+00,-5.043943913374430155e-01,0.000000000000000000e+00,-1.000000008433601151e+00,0.000000000000000000e+00 +3.041035274096204777e+00,3.342999999999999972e+01,0.000000000000000000e+00,1.087255943448624329e+01,0.000000000000000000e+00,-5.053140987436604004e-01,0.000000000000000000e+00,-1.000000007582512618e+00,0.000000000000000000e+00 +3.041955020735462423e+00,3.343999999999999773e+01,0.000000000000000000e+00,1.087209467354215420e+01,0.000000000000000000e+00,-5.062338453898922452e-01,0.000000000000000000e+00,-1.000000010376147275e+00,0.000000000000000000e+00 +3.042874806692103640e+00,3.345000000000000284e+01,0.000000000000000000e+00,1.087162904676038799e+01,0.000000000000000000e+00,-5.071536313560774945e-01,0.000000000000000000e+00,-1.000000008165914389e+00,0.000000000000000000e+00 +3.043794632042746695e+00,3.346000000000000085e+01,0.000000000000000000e+00,1.087116255399359588e+01,0.000000000000000000e+00,-5.080734567142319857e-01,0.000000000000000000e+00,-1.000000011199420280e+00,0.000000000000000000e+00 +3.044714496864041831e+00,3.346999999999999886e+01,0.000000000000000000e+00,1.087069519509413063e+01,0.000000000000000000e+00,-5.089933215458291027e-01,0.000000000000000000e+00,-1.000000006630050953e+00,0.000000000000000000e+00 +3.045634401232670818e+00,3.348000000000000398e+01,0.000000000000000000e+00,1.087022696991403770e+01,0.000000000000000000e+00,-5.099132259205569895e-01,0.000000000000000000e+00,-1.000000011000064415e+00,0.000000000000000000e+00 +3.046554345225346960e+00,3.349000000000000199e+01,0.000000000000000000e+00,1.086975787830506590e+01,0.000000000000000000e+00,-5.108331699233527035e-01,0.000000000000000000e+00,-1.000000007265156921e+00,0.000000000000000000e+00 +3.047474328918816422e+00,3.350000000000000000e+01,0.000000000000000000e+00,1.086928792011865319e+01,0.000000000000000000e+00,-5.117531536235058187e-01,0.000000000000000000e+00,-1.000000009865030348e+00,0.000000000000000000e+00 +3.048394352389856454e+00,3.350999999999999801e+01,0.000000000000000000e+00,1.086881709520594086e+01,0.000000000000000000e+00,-5.126731771036218133e-01,0.000000000000000000e+00,-1.000000008052895684e+00,0.000000000000000000e+00 +3.049314415715276727e+00,3.352000000000000313e+01,0.000000000000000000e+00,1.086834540341776112e+01,0.000000000000000000e+00,-5.135932404364512704e-01,0.000000000000000000e+00,-1.000000012067747690e+00,0.000000000000000000e+00 +3.050234518971919329e+00,3.353000000000000114e+01,0.000000000000000000e+00,1.086787284460464598e+01,0.000000000000000000e+00,-5.145133437041973234e-01,0.000000000000000000e+00,-1.000000006967409760e+00,0.000000000000000000e+00 +3.051154662236657877e+00,3.353999999999999915e+01,0.000000000000000000e+00,1.086739941861681835e+01,0.000000000000000000e+00,-5.154334869753470771e-01,0.000000000000000000e+00,-1.000000007184807860e+00,0.000000000000000000e+00 +3.052074845586399299e+00,3.354999999999999716e+01,0.000000000000000000e+00,1.086692512530420451e+01,0.000000000000000000e+00,-5.163536703316997656e-01,0.000000000000000000e+00,-1.000000012463180932e+00,0.000000000000000000e+00 +3.052995069098082048e+00,3.356000000000000227e+01,0.000000000000000000e+00,1.086644996451642164e+01,0.000000000000000000e+00,-5.172738938548513410e-01,0.000000000000000000e+00,-1.000000007862295703e+00,0.000000000000000000e+00 +3.053915332848677000e+00,3.357000000000000028e+01,0.000000000000000000e+00,1.086597393610277784e+01,0.000000000000000000e+00,-5.181941576126818383e-01,0.000000000000000000e+00,-1.000000007810648572e+00,0.000000000000000000e+00 +3.054835636915188335e+00,3.357999999999999829e+01,0.000000000000000000e+00,1.086549703991228455e+01,0.000000000000000000e+00,-5.191144616863812011e-01,0.000000000000000000e+00,-1.000000009951792945e+00,0.000000000000000000e+00 +3.055755981374651764e+00,3.359000000000000341e+01,0.000000000000000000e+00,1.086501927579364413e+01,0.000000000000000000e+00,-5.200348061550037482e-01,0.000000000000000000e+00,-1.000000009834343340e+00,0.000000000000000000e+00 +3.056676366304136305e+00,3.360000000000000142e+01,0.000000000000000000e+00,1.086454064359525162e+01,0.000000000000000000e+00,-5.209551910935397157e-01,0.000000000000000000e+00,-1.000000007200274155e+00,0.000000000000000000e+00 +3.057596791780743395e+00,3.360999999999999943e+01,0.000000000000000000e+00,1.086406114316519833e+01,0.000000000000000000e+00,-5.218756165767742816e-01,0.000000000000000000e+00,-1.000000010178152321e+00,0.000000000000000000e+00 +3.058517257881607776e+00,3.361999999999999744e+01,0.000000000000000000e+00,1.086358077435127178e+01,0.000000000000000000e+00,-5.227960826870071687e-01,0.000000000000000000e+00,-1.000000010121199434e+00,0.000000000000000000e+00 +3.059437764683896166e+00,3.363000000000000256e+01,0.000000000000000000e+00,1.086309953700094866e+01,0.000000000000000000e+00,-5.237165894986122172e-01,0.000000000000000000e+00,-1.000000008866802403e+00,0.000000000000000000e+00 +3.060358312264809033e+00,3.364000000000000057e+01,0.000000000000000000e+00,1.086261743096140187e+01,0.000000000000000000e+00,-5.246371370876872220e-01,0.000000000000000000e+00,-1.000000008250861105e+00,0.000000000000000000e+00 +3.061278900701579264e+00,3.364999999999999858e+01,0.000000000000000000e+00,1.086213445607949879e+01,0.000000000000000000e+00,-5.255577255320529328e-01,0.000000000000000000e+00,-1.000000008011864727e+00,0.000000000000000000e+00 +3.062199530071473053e+00,3.366000000000000369e+01,0.000000000000000000e+00,1.086165061220179950e+01,0.000000000000000000e+00,-5.264783549093224879e-01,0.000000000000000000e+00,-1.000000009983858407e+00,0.000000000000000000e+00 +3.063120200451789454e+00,3.367000000000000171e+01,0.000000000000000000e+00,1.086116589917455677e+01,0.000000000000000000e+00,-5.273990252988307592e-01,0.000000000000000000e+00,-1.000000009712673776e+00,0.000000000000000000e+00 +3.064040911919861276e+00,3.367999999999999972e+01,0.000000000000000000e+00,1.086068031684371427e+01,0.000000000000000000e+00,-5.283197367758450946e-01,0.000000000000000000e+00,-1.000000009032026238e+00,0.000000000000000000e+00 +3.064961664553054188e+00,3.368999999999999773e+01,0.000000000000000000e+00,1.086019386505491013e+01,0.000000000000000000e+00,-5.292404894173542429e-01,0.000000000000000000e+00,-1.000000007678110814e+00,0.000000000000000000e+00 +3.065882458428767166e+00,3.370000000000000284e+01,0.000000000000000000e+00,1.085970654365347521e+01,0.000000000000000000e+00,-5.301612833001373426e-01,0.000000000000000000e+00,-1.000000009577035831e+00,0.000000000000000000e+00 +3.066803293624432936e+00,3.371000000000000085e+01,0.000000000000000000e+00,1.085921835248443301e+01,0.000000000000000000e+00,-5.310821185046221693e-01,0.000000000000000000e+00,-1.000000010273772277e+00,0.000000000000000000e+00 +3.067724170217517976e+00,3.371999999999999886e+01,0.000000000000000000e+00,1.085872929139249621e+01,0.000000000000000000e+00,-5.320029951071678642e-01,0.000000000000000000e+00,-1.000000007409159064e+00,0.000000000000000000e+00 +3.068645088285521183e+00,3.373000000000000398e+01,0.000000000000000000e+00,1.085823936022207015e+01,0.000000000000000000e+00,-5.329239131819943909e-01,0.000000000000000000e+00,-1.000000011189741800e+00,0.000000000000000000e+00 +3.069566047905976092e+00,3.374000000000000199e+01,0.000000000000000000e+00,1.085774855881725465e+01,0.000000000000000000e+00,-5.338448728127547227e-01,0.000000000000000000e+00,-1.000000006688514853e+00,0.000000000000000000e+00 +3.070487049156449988e+00,3.375000000000000000e+01,0.000000000000000000e+00,1.085725688702183511e+01,0.000000000000000000e+00,-5.347658740693885804e-01,0.000000000000000000e+00,-1.000000010392430916e+00,0.000000000000000000e+00 +3.071408092114543020e+00,3.375999999999999801e+01,0.000000000000000000e+00,1.085676434467929496e+01,0.000000000000000000e+00,-5.356869170370536226e-01,0.000000000000000000e+00,-1.000000009469026008e+00,0.000000000000000000e+00 +3.072329176857890420e+00,3.377000000000000313e+01,0.000000000000000000e+00,1.085627093163280144e+01,0.000000000000000000e+00,-5.366080017891226017e-01,0.000000000000000000e+00,-1.000000007838819815e+00,0.000000000000000000e+00 +3.073250303464160282e+00,3.378000000000000114e+01,0.000000000000000000e+00,1.085577664772521622e+01,0.000000000000000000e+00,-5.375291284026129102e-01,0.000000000000000000e+00,-1.000000009419492963e+00,0.000000000000000000e+00 +3.074171472011055339e+00,3.378999999999999915e+01,0.000000000000000000e+00,1.085528149279909194e+01,0.000000000000000000e+00,-5.384502969581846932e-01,0.000000000000000000e+00,-1.000000009754957064e+00,0.000000000000000000e+00 +3.075092682576311631e+00,3.379999999999999716e+01,0.000000000000000000e+00,1.085478546669666855e+01,0.000000000000000000e+00,-5.393715075324275743e-01,0.000000000000000000e+00,-1.000000008575250732e+00,0.000000000000000000e+00 +3.076013935237700725e+00,3.381000000000000227e+01,0.000000000000000000e+00,1.085428856925987695e+01,0.000000000000000000e+00,-5.402927602017164599e-01,0.000000000000000000e+00,-1.000000007703587546e+00,0.000000000000000000e+00 +3.076935230073027050e+00,3.382000000000000028e+01,0.000000000000000000e+00,1.085379080033033894e+01,0.000000000000000000e+00,-5.412140550441399967e-01,0.000000000000000000e+00,-1.000000011053345128e+00,0.000000000000000000e+00 +3.077856567160129675e+00,3.382999999999999829e+01,0.000000000000000000e+00,1.085329215974936545e+01,0.000000000000000000e+00,-5.421353921414266974e-01,0.000000000000000000e+00,-1.000000007889881415e+00,0.000000000000000000e+00 +3.078777946576882751e+00,3.384000000000000341e+01,0.000000000000000000e+00,1.085279264735795302e+01,0.000000000000000000e+00,-5.430567715654492922e-01,0.000000000000000000e+00,-1.000000010496005176e+00,0.000000000000000000e+00 +3.079699368401194182e+00,3.385000000000000142e+01,0.000000000000000000e+00,1.085229226299679262e+01,0.000000000000000000e+00,-5.439781933994317642e-01,0.000000000000000000e+00,-1.000000008137208019e+00,0.000000000000000000e+00 +3.080620832711006063e+00,3.385999999999999943e+01,0.000000000000000000e+00,1.085179100650625905e+01,0.000000000000000000e+00,-5.448996577167418698e-01,0.000000000000000000e+00,-1.000000008908388915e+00,0.000000000000000000e+00 +3.081542339584296020e+00,3.386999999999999744e+01,0.000000000000000000e+00,1.085128887772641981e+01,0.000000000000000000e+00,-5.458211645982408156e-01,0.000000000000000000e+00,-1.000000008351580982e+00,0.000000000000000000e+00 +3.082463889099075427e+00,3.388000000000000256e+01,0.000000000000000000e+00,1.085078587649702797e+01,0.000000000000000000e+00,-5.467427141207166219e-01,0.000000000000000000e+00,-1.000000010374976434e+00,0.000000000000000000e+00 +3.083385481333390743e+00,3.389000000000000057e+01,0.000000000000000000e+00,1.085028200265752574e+01,0.000000000000000000e+00,-5.476643063645936227e-01,0.000000000000000000e+00,-1.000000008429109410e+00,0.000000000000000000e+00 +3.084307116365323509e+00,3.389999999999999858e+01,0.000000000000000000e+00,1.084977725604704091e+01,0.000000000000000000e+00,-5.485859414042950633e-01,0.000000000000000000e+00,-1.000000008512304417e+00,0.000000000000000000e+00 +3.085228794272989905e+00,3.391000000000000369e+01,0.000000000000000000e+00,1.084927163650439219e+01,0.000000000000000000e+00,-5.495076193198070724e-01,0.000000000000000000e+00,-1.000000010347150692e+00,0.000000000000000000e+00 +3.086150515134540750e+00,3.392000000000000171e+01,0.000000000000000000e+00,1.084876514386808388e+01,0.000000000000000000e+00,-5.504293401908952887e-01,0.000000000000000000e+00,-1.000000007384612477e+00,0.000000000000000000e+00 +3.087072279028162392e+00,3.392999999999999972e+01,0.000000000000000000e+00,1.084825777797630586e+01,0.000000000000000000e+00,-5.513511040913239292e-01,0.000000000000000000e+00,-1.000000009800113387e+00,0.000000000000000000e+00 +3.087994086032076257e+00,3.393999999999999773e+01,0.000000000000000000e+00,1.084774953866693892e+01,0.000000000000000000e+00,-5.522729111042714578e-01,0.000000000000000000e+00,-1.000000008952859787e+00,0.000000000000000000e+00 +3.088915936224538417e+00,3.395000000000000284e+01,0.000000000000000000e+00,1.084724042577754588e+01,0.000000000000000000e+00,-5.531947613049866819e-01,0.000000000000000000e+00,-1.000000010835306430e+00,0.000000000000000000e+00 +3.089837829683840464e+00,3.396000000000000085e+01,0.000000000000000000e+00,1.084673043914537871e+01,0.000000000000000000e+00,-5.541166547742776283e-01,0.000000000000000000e+00,-1.000000006807321151e+00,0.000000000000000000e+00 +3.090759766488309079e+00,3.396999999999999886e+01,0.000000000000000000e+00,1.084621957860737318e+01,0.000000000000000000e+00,-5.550385915850223340e-01,0.000000000000000000e+00,-1.000000011218327378e+00,0.000000000000000000e+00 +3.091681746716306911e+00,3.398000000000000398e+01,0.000000000000000000e+00,1.084570784400015597e+01,0.000000000000000000e+00,-5.559605718233633365e-01,0.000000000000000000e+00,-1.000000007069310026e+00,0.000000000000000000e+00 +3.092603770446231692e+00,3.399000000000000199e+01,0.000000000000000000e+00,1.084519523516003225e+01,0.000000000000000000e+00,-5.568825955598062372e-01,0.000000000000000000e+00,-1.000000008706387833e+00,0.000000000000000000e+00 +3.093525837756516683e+00,3.400000000000000000e+01,0.000000000000000000e+00,1.084468175192299988e+01,0.000000000000000000e+00,-5.578046628781191396e-01,0.000000000000000000e+00,-1.000000009578523974e+00,0.000000000000000000e+00 +3.094447948725630670e+00,3.400999999999999801e+01,0.000000000000000000e+00,1.084416739412473696e+01,0.000000000000000000e+00,-5.587267738560657282e-01,0.000000000000000000e+00,-1.000000009403214873e+00,0.000000000000000000e+00 +3.095370103432078412e+00,3.402000000000000313e+01,0.000000000000000000e+00,1.084365216160060719e+01,0.000000000000000000e+00,-5.596489285711847561e-01,0.000000000000000000e+00,-1.000000009986553584e+00,0.000000000000000000e+00 +3.096292301954400195e+00,3.403000000000000114e+01,0.000000000000000000e+00,1.084313605418565984e+01,0.000000000000000000e+00,-5.605711271027161713e-01,0.000000000000000000e+00,-1.000000008955836961e+00,0.000000000000000000e+00 +3.097214544371172273e+00,3.403999999999999915e+01,0.000000000000000000e+00,1.084261907171462802e+01,0.000000000000000000e+00,-5.614933695277476433e-01,0.000000000000000000e+00,-1.000000008115582872e+00,0.000000000000000000e+00 +3.098136830761006433e+00,3.404999999999999716e+01,0.000000000000000000e+00,1.084210121402193039e+01,0.000000000000000000e+00,-5.624156559250668153e-01,0.000000000000000000e+00,-1.000000009268440238e+00,0.000000000000000000e+00 +3.099059161202550872e+00,3.406000000000000227e+01,0.000000000000000000e+00,1.084158248094166943e+01,0.000000000000000000e+00,-5.633379863751599714e-01,0.000000000000000000e+00,-1.000000007952798642e+00,0.000000000000000000e+00 +3.099981535774489760e+00,3.407000000000000028e+01,0.000000000000000000e+00,1.084106287230762966e+01,0.000000000000000000e+00,-5.642603609544344367e-01,0.000000000000000000e+00,-1.000000010145678742e+00,0.000000000000000000e+00 +3.100903954555543240e+00,3.407999999999999829e+01,0.000000000000000000e+00,1.084054238795328118e+01,0.000000000000000000e+00,-5.651827797448466528e-01,0.000000000000000000e+00,-1.000000009297131509e+00,0.000000000000000000e+00 +3.101826417624467869e+00,3.409000000000000341e+01,0.000000000000000000e+00,1.084002102771177434e+01,0.000000000000000000e+00,-5.661052428223476429e-01,0.000000000000000000e+00,-1.000000009294877978e+00,0.000000000000000000e+00 +3.102748925060056173e+00,3.410000000000000142e+01,0.000000000000000000e+00,1.083949879141594508e+01,0.000000000000000000e+00,-5.670277502665107550e-01,0.000000000000000000e+00,-1.000000007763421905e+00,0.000000000000000000e+00 +3.103671476941137541e+00,3.410999999999999943e+01,0.000000000000000000e+00,1.083897567889831137e+01,0.000000000000000000e+00,-5.679503021547542829e-01,0.000000000000000000e+00,-1.000000010675528461e+00,0.000000000000000000e+00 +3.104594073346577332e+00,3.411999999999999744e+01,0.000000000000000000e+00,1.083845168999107500e+01,0.000000000000000000e+00,-5.688728985700431950e-01,0.000000000000000000e+00,-1.000000007306321548e+00,0.000000000000000000e+00 +3.105516714355277319e+00,3.413000000000000256e+01,0.000000000000000000e+00,1.083792682452611622e+01,0.000000000000000000e+00,-5.697955395854843452e-01,0.000000000000000000e+00,-1.000000009887349162e+00,0.000000000000000000e+00 +3.106439400046176136e+00,3.414000000000000057e+01,0.000000000000000000e+00,1.083740108233500266e+01,0.000000000000000000e+00,-5.707182252855061977e-01,0.000000000000000000e+00,-1.000000009780607657e+00,0.000000000000000000e+00 +3.107362130498249275e+00,3.414999999999999858e+01,0.000000000000000000e+00,1.083687446324897863e+01,0.000000000000000000e+00,-5.716409557466041180e-01,0.000000000000000000e+00,-1.000000006695833443e+00,0.000000000000000000e+00 +3.108284905790508201e+00,3.416000000000000369e+01,0.000000000000000000e+00,1.083634696709897227e+01,0.000000000000000000e+00,-5.725637310450419903e-01,0.000000000000000000e+00,-1.000000010771604275e+00,0.000000000000000000e+00 +3.109207726002002126e+00,3.417000000000000171e+01,0.000000000000000000e+00,1.083581859371559553e+01,0.000000000000000000e+00,-5.734865512664761855e-01,0.000000000000000000e+00,-1.000000009198806827e+00,0.000000000000000000e+00 +3.110130591211816675e+00,3.417999999999999972e+01,0.000000000000000000e+00,1.083528934292913526e+01,0.000000000000000000e+00,-5.744094164847798334e-01,0.000000000000000000e+00,-1.000000007942915881e+00,0.000000000000000000e+00 +3.111053501499073892e+00,3.418999999999999773e+01,0.000000000000000000e+00,1.083475921456956392e+01,0.000000000000000000e+00,-5.753323267793678530e-01,0.000000000000000000e+00,-1.000000010880165435e+00,0.000000000000000000e+00 +3.111976456942934011e+00,3.420000000000000284e+01,0.000000000000000000e+00,1.083422820846653423e+01,0.000000000000000000e+00,-5.762552822332698277e-01,0.000000000000000000e+00,-1.000000007290074544e+00,0.000000000000000000e+00 +3.112899457622593236e+00,3.421000000000000085e+01,0.000000000000000000e+00,1.083369632444937558e+01,0.000000000000000000e+00,-5.771782829196580034e-01,0.000000000000000000e+00,-1.000000009388587463e+00,0.000000000000000000e+00 +3.113822503617285964e+00,3.421999999999999886e+01,0.000000000000000000e+00,1.083316356234710298e+01,0.000000000000000000e+00,-5.781013289230167995e-01,0.000000000000000000e+00,-1.000000010624286784e+00,0.000000000000000000e+00 +3.114745595006283008e+00,3.423000000000000398e+01,0.000000000000000000e+00,1.083262992198840635e+01,0.000000000000000000e+00,-5.790244203218211094e-01,0.000000000000000000e+00,-1.000000006532137720e+00,0.000000000000000000e+00 +3.115668731868892927e+00,3.424000000000000199e+01,0.000000000000000000e+00,1.083209540320165587e+01,0.000000000000000000e+00,-5.799475571904612048e-01,0.000000000000000000e+00,-1.000000011407327749e+00,0.000000000000000000e+00 +3.116591914284461584e+00,3.425000000000000000e+01,0.000000000000000000e+00,1.083156000581490552e+01,0.000000000000000000e+00,-5.808707396165611048e-01,0.000000000000000000e+00,-1.000000008276336505e+00,0.000000000000000000e+00 +3.117515142332372591e+00,3.425999999999999801e+01,0.000000000000000000e+00,1.083102372965588067e+01,0.000000000000000000e+00,-5.817939676721131104e-01,0.000000000000000000e+00,-1.000000007263313284e+00,0.000000000000000000e+00 +3.118438416092046861e+00,3.427000000000000313e+01,0.000000000000000000e+00,1.083048657455199226e+01,0.000000000000000000e+00,-5.827172414384933496e-01,0.000000000000000000e+00,-1.000000010152100494e+00,0.000000000000000000e+00 +3.119361735642942612e+00,3.428000000000000114e+01,0.000000000000000000e+00,1.082994854033032794e+01,0.000000000000000000e+00,-5.836405609987629362e-01,0.000000000000000000e+00,-1.000000010392144922e+00,0.000000000000000000e+00 +3.120285101064556699e+00,3.428999999999999915e+01,0.000000000000000000e+00,1.082940962681765029e+01,0.000000000000000000e+00,-5.845639264299726801e-01,0.000000000000000000e+00,-1.000000007683818026e+00,0.000000000000000000e+00 +3.121208512436422833e+00,3.430000000000000426e+01,0.000000000000000000e+00,1.082886983384040214e+01,0.000000000000000000e+00,-5.854873378089341385e-01,0.000000000000000000e+00,-1.000000010059635569e+00,0.000000000000000000e+00 +3.122131969838112919e+00,3.431000000000000227e+01,0.000000000000000000e+00,1.082832916122470657e+01,0.000000000000000000e+00,-5.864107952199140161e-01,0.000000000000000000e+00,-1.000000006802818087e+00,0.000000000000000000e+00 +3.123055473349237054e+00,3.432000000000000028e+01,0.000000000000000000e+00,1.082778760879635982e+01,0.000000000000000000e+00,-5.873342987373206814e-01,0.000000000000000000e+00,-1.000000012191081700e+00,0.000000000000000000e+00 +3.123979023049443082e+00,3.432999999999999829e+01,0.000000000000000000e+00,1.082724517638084016e+01,0.000000000000000000e+00,-5.882578484487859249e-01,0.000000000000000000e+00,-1.000000007177459738e+00,0.000000000000000000e+00 +3.124902619018417038e+00,3.434000000000000341e+01,0.000000000000000000e+00,1.082670186380329547e+01,0.000000000000000000e+00,-5.891814444243891336e-01,0.000000000000000000e+00,-1.000000008119941386e+00,0.000000000000000000e+00 +3.125826261335883149e+00,3.435000000000000142e+01,0.000000000000000000e+00,1.082615767088855918e+01,0.000000000000000000e+00,-5.901050867493553564e-01,0.000000000000000000e+00,-1.000000010548612872e+00,0.000000000000000000e+00 +3.126749950081604279e+00,3.435999999999999943e+01,0.000000000000000000e+00,1.082561259746113613e+01,0.000000000000000000e+00,-5.910287755048199143e-01,0.000000000000000000e+00,-1.000000007912829503e+00,0.000000000000000000e+00 +3.127673685335380593e+00,3.436999999999999744e+01,0.000000000000000000e+00,1.082506664334520607e+01,0.000000000000000000e+00,-5.919525107659056040e-01,0.000000000000000000e+00,-1.000000010317336319e+00,0.000000000000000000e+00 +3.128597467177051339e+00,3.438000000000000256e+01,0.000000000000000000e+00,1.082451980836462901e+01,0.000000000000000000e+00,-5.928762926171075032e-01,0.000000000000000000e+00,-1.000000009129029310e+00,0.000000000000000000e+00 +3.129521295686494398e+00,3.439000000000000057e+01,0.000000000000000000e+00,1.082397209234293634e+01,0.000000000000000000e+00,-5.938001211349843711e-01,0.000000000000000000e+00,-1.000000008205276014e+00,0.000000000000000000e+00 +3.130445170943626287e+00,3.439999999999999858e+01,0.000000000000000000e+00,1.082342349510333790e+01,0.000000000000000000e+00,-5.947239963996967527e-01,0.000000000000000000e+00,-1.000000009319174321e+00,0.000000000000000000e+00 +3.131369093028401274e+00,3.441000000000000369e+01,0.000000000000000000e+00,1.082287401646871849e+01,0.000000000000000000e+00,-5.956479184930820736e-01,0.000000000000000000e+00,-1.000000008001527885e+00,0.000000000000000000e+00 +3.132293062020813590e+00,3.442000000000000171e+01,0.000000000000000000e+00,1.082232365626163606e+01,0.000000000000000000e+00,-5.965718874928873650e-01,0.000000000000000000e+00,-1.000000010185877031e+00,0.000000000000000000e+00 +3.133217078000895217e+00,3.442999999999999972e+01,0.000000000000000000e+00,1.082177241430432524e+01,0.000000000000000000e+00,-5.974959034823807968e-01,0.000000000000000000e+00,-1.000000009321201366e+00,0.000000000000000000e+00 +3.134141141048717216e+00,3.443999999999999773e+01,0.000000000000000000e+00,1.082122029041869204e+01,0.000000000000000000e+00,-5.984199665388163503e-01,0.000000000000000000e+00,-1.000000007179324690e+00,0.000000000000000000e+00 +3.135065251244390172e+00,3.445000000000000284e+01,0.000000000000000000e+00,1.082066728442631920e+01,0.000000000000000000e+00,-5.993440767411238879e-01,0.000000000000000000e+00,-1.000000011769081043e+00,0.000000000000000000e+00 +3.135989408668063305e+00,3.446000000000000085e+01,0.000000000000000000e+00,1.082011339614846435e+01,0.000000000000000000e+00,-6.002682341756735429e-01,0.000000000000000000e+00,-1.000000006140633557e+00,0.000000000000000000e+00 +3.136913613399924916e+00,3.446999999999999886e+01,0.000000000000000000e+00,1.081955862540605295e+01,0.000000000000000000e+00,-6.011924389132103919e-01,0.000000000000000000e+00,-1.000000010780071946e+00,0.000000000000000000e+00 +3.137837865520202385e+00,3.448000000000000398e+01,0.000000000000000000e+00,1.081900297201969252e+01,0.000000000000000000e+00,-6.021166910434515573e-01,0.000000000000000000e+00,-1.000000008737382373e+00,0.000000000000000000e+00 +3.138762165109163060e+00,3.449000000000000199e+01,0.000000000000000000e+00,1.081844643580965482e+01,0.000000000000000000e+00,-6.030409906404879949e-01,0.000000000000000000e+00,-1.000000008018806952e+00,0.000000000000000000e+00 +3.139686512247112482e+00,3.450000000000000000e+01,0.000000000000000000e+00,1.081788901659589008e+01,0.000000000000000000e+00,-6.039653377858495986e-01,0.000000000000000000e+00,-1.000000010388202076e+00,0.000000000000000000e+00 +3.140610907014396602e+00,3.450999999999999801e+01,0.000000000000000000e+00,1.081733071419801995e+01,0.000000000000000000e+00,-6.048897325627363708e-01,0.000000000000000000e+00,-1.000000009295053172e+00,0.000000000000000000e+00 +3.141535349491400009e+00,3.452000000000000313e+01,0.000000000000000000e+00,1.081677152843533563e+01,0.000000000000000000e+00,-6.058141750483326815e-01,0.000000000000000000e+00,-1.000000008582246691e+00,0.000000000000000000e+00 +3.142459839758547702e+00,3.453000000000000114e+01,0.000000000000000000e+00,1.081621145912680326e+01,0.000000000000000000e+00,-6.067386653234146943e-01,0.000000000000000000e+00,-1.000000007934359170e+00,0.000000000000000000e+00 +3.143384377896304205e+00,3.453999999999999915e+01,0.000000000000000000e+00,1.081565050609106038e+01,0.000000000000000000e+00,-6.076632034685066630e-01,0.000000000000000000e+00,-1.000000009112573363e+00,0.000000000000000000e+00 +3.144308963985173122e+00,3.455000000000000426e+01,0.000000000000000000e+00,1.081508866914641587e+01,0.000000000000000000e+00,-6.085877895658009518e-01,0.000000000000000000e+00,-1.000000009722062044e+00,0.000000000000000000e+00 +3.145233598105698469e+00,3.456000000000000227e+01,0.000000000000000000e+00,1.081452594811084822e+01,0.000000000000000000e+00,-6.095124236953156638e-01,0.000000000000000000e+00,-1.000000009445301208e+00,0.000000000000000000e+00 +3.146158280338464230e+00,3.457000000000000028e+01,0.000000000000000000e+00,1.081396234280200730e+01,0.000000000000000000e+00,-6.104371059368151053e-01,0.000000000000000000e+00,-1.000000007964626736e+00,0.000000000000000000e+00 +3.147083010764093469e+00,3.457999999999999829e+01,0.000000000000000000e+00,1.081339785303721435e+01,0.000000000000000000e+00,-6.113618363698096747e-01,0.000000000000000000e+00,-1.000000011192617944e+00,0.000000000000000000e+00 +3.148007789463250550e+00,3.459000000000000341e+01,0.000000000000000000e+00,1.081283247863346197e+01,0.000000000000000000e+00,-6.122866150793174755e-01,0.000000000000000000e+00,-1.000000006347242509e+00,0.000000000000000000e+00 +3.148932616516639360e+00,3.460000000000000142e+01,0.000000000000000000e+00,1.081226621940740884e+01,0.000000000000000000e+00,-6.132114421385762570e-01,0.000000000000000000e+00,-1.000000009724011152e+00,0.000000000000000000e+00 +3.149857492005003756e+00,3.460999999999999943e+01,0.000000000000000000e+00,1.081169907517539031e+01,0.000000000000000000e+00,-6.141363176359341258e-01,0.000000000000000000e+00,-1.000000010617012380e+00,0.000000000000000000e+00 +3.150782416009128006e+00,3.461999999999999744e+01,0.000000000000000000e+00,1.081113104575340422e+01,0.000000000000000000e+00,-6.150612416498785207e-01,0.000000000000000000e+00,-1.000000006629848892e+00,0.000000000000000000e+00 +3.151707388609837235e+00,3.463000000000000256e+01,0.000000000000000000e+00,1.081056213095711982e+01,0.000000000000000000e+00,-6.159862142567202881e-01,0.000000000000000000e+00,-1.000000009897527908e+00,0.000000000000000000e+00 +3.152632409887996534e+00,3.464000000000000057e+01,0.000000000000000000e+00,1.080999233060187947e+01,0.000000000000000000e+00,-6.169112355440351525e-01,0.000000000000000000e+00,-1.000000009715955818e+00,0.000000000000000000e+00 +3.153557479924511853e+00,3.464999999999999858e+01,0.000000000000000000e+00,1.080942164450268805e+01,0.000000000000000000e+00,-6.178363055895383926e-01,0.000000000000000000e+00,-1.000000007838670157e+00,0.000000000000000000e+00 +3.154482598800329551e+00,3.466000000000000369e+01,0.000000000000000000e+00,1.080885007247422180e+01,0.000000000000000000e+00,-6.187614244726076240e-01,0.000000000000000000e+00,-1.000000010167834352e+00,0.000000000000000000e+00 +3.155407766596436403e+00,3.467000000000000171e+01,0.000000000000000000e+00,1.080827761433082657e+01,0.000000000000000000e+00,-6.196865922781213953e-01,0.000000000000000000e+00,-1.000000008076721736e+00,0.000000000000000000e+00 +3.156332983393860481e+00,3.467999999999999972e+01,0.000000000000000000e+00,1.080770426988651245e+01,0.000000000000000000e+00,-6.206118090830180511e-01,0.000000000000000000e+00,-1.000000009540790602e+00,0.000000000000000000e+00 +3.157258249273670270e+00,3.468999999999999773e+01,0.000000000000000000e+00,1.080713003895496094e+01,0.000000000000000000e+00,-6.215370749716555565e-01,0.000000000000000000e+00,-1.000000010083538671e+00,0.000000000000000000e+00 +3.158183564316975556e+00,3.470000000000000284e+01,0.000000000000000000e+00,1.080655492134951778e+01,0.000000000000000000e+00,-6.224623900242911567e-01,0.000000000000000000e+00,-1.000000007303967209e+00,0.000000000000000000e+00 +3.159108928604926536e+00,3.471000000000000085e+01,0.000000000000000000e+00,1.080597891688319656e+01,0.000000000000000000e+00,-6.233877543190011750e-01,0.000000000000000000e+00,-1.000000009172350435e+00,0.000000000000000000e+00 +3.160034342218715597e+00,3.471999999999999886e+01,0.000000000000000000e+00,1.080540202536868044e+01,0.000000000000000000e+00,-6.243131679412783352e-01,0.000000000000000000e+00,-1.000000009137084200e+00,0.000000000000000000e+00 +3.160959805239575093e+00,3.473000000000000398e+01,0.000000000000000000e+00,1.080482424661831509e+01,0.000000000000000000e+00,-6.252386309705939560e-01,0.000000000000000000e+00,-1.000000008943787488e+00,0.000000000000000000e+00 +3.161885317748779567e+00,3.474000000000000199e+01,0.000000000000000000e+00,1.080424558044411398e+01,0.000000000000000000e+00,-6.261641434880759194e-01,0.000000000000000000e+00,-1.000000010336179024e+00,0.000000000000000000e+00 +3.162810879827644417e+00,3.475000000000000000e+01,0.000000000000000000e+00,1.080366602665775666e+01,0.000000000000000000e+00,-6.270897055765073391e-01,0.000000000000000000e+00,-1.000000006763933857e+00,0.000000000000000000e+00 +3.163736491557526342e+00,3.475999999999999801e+01,0.000000000000000000e+00,1.080308558507058692e+01,0.000000000000000000e+00,-6.280153173126499233e-01,0.000000000000000000e+00,-1.000000010336254963e+00,0.000000000000000000e+00 +3.164662153019823787e+00,3.477000000000000313e+01,0.000000000000000000e+00,1.080250425549361815e+01,0.000000000000000000e+00,-6.289409787845151589e-01,0.000000000000000000e+00,-1.000000010354604507e+00,0.000000000000000000e+00 +3.165587864295976495e+00,3.478000000000000114e+01,0.000000000000000000e+00,1.080192203773752269e+01,0.000000000000000000e+00,-6.298666900702534210e-01,0.000000000000000000e+00,-1.000000006488054094e+00,0.000000000000000000e+00 +3.166513625467466397e+00,3.478999999999999915e+01,0.000000000000000000e+00,1.080133893161264069e+01,0.000000000000000000e+00,-6.307924512477498524e-01,0.000000000000000000e+00,-1.000000010839577014e+00,0.000000000000000000e+00 +3.167439436615817172e+00,3.480000000000000426e+01,0.000000000000000000e+00,1.080075493692898014e+01,0.000000000000000000e+00,-6.317182624061358220e-01,0.000000000000000000e+00,-1.000000008567390353e+00,0.000000000000000000e+00 +3.168365297822593352e+00,3.481000000000000227e+01,0.000000000000000000e+00,1.080017005349620618e+01,0.000000000000000000e+00,-6.326441236208443231e-01,0.000000000000000000e+00,-1.000000007627198872e+00,0.000000000000000000e+00 +3.169291209169402546e+00,3.482000000000000028e+01,0.000000000000000000e+00,1.079958428112365354e+01,0.000000000000000000e+00,-6.335700349747155347e-01,0.000000000000000000e+00,-1.000000009755509067e+00,0.000000000000000000e+00 +3.170217170737893664e+00,3.482999999999999829e+01,0.000000000000000000e+00,1.079899761962031945e+01,0.000000000000000000e+00,-6.344959965522397605e-01,0.000000000000000000e+00,-1.000000008400521168e+00,0.000000000000000000e+00 +3.171143182609757805e+00,3.484000000000000341e+01,0.000000000000000000e+00,1.079841006879486187e+01,0.000000000000000000e+00,-6.354220084318827899e-01,0.000000000000000000e+00,-1.000000011512754750e+00,0.000000000000000000e+00 +3.172069244866728255e+00,3.485000000000000142e+01,0.000000000000000000e+00,1.079782162845560478e+01,0.000000000000000000e+00,-6.363480706995147118e-01,0.000000000000000000e+00,-1.000000006327100621e+00,0.000000000000000000e+00 +3.172995357590580490e+00,3.485999999999999943e+01,0.000000000000000000e+00,1.079723229841053111e+01,0.000000000000000000e+00,-6.372741834292265928e-01,0.000000000000000000e+00,-1.000000009075514784e+00,0.000000000000000000e+00 +3.173921520863132617e+00,3.486999999999999744e+01,0.000000000000000000e+00,1.079664207846729340e+01,0.000000000000000000e+00,-6.382003467101839966e-01,0.000000000000000000e+00,-1.000000011133854949e+00,0.000000000000000000e+00 +3.174847734766244489e+00,3.488000000000000256e+01,0.000000000000000000e+00,1.079605096843319956e+01,0.000000000000000000e+00,-6.391265606236082863e-01,0.000000000000000000e+00,-1.000000005952637050e+00,0.000000000000000000e+00 +3.175773999381819035e+00,3.489000000000000057e+01,0.000000000000000000e+00,1.079545896811521999e+01,0.000000000000000000e+00,-6.400528252446966437e-01,0.000000000000000000e+00,-1.000000011825915802e+00,0.000000000000000000e+00 +3.176700314791801816e+00,3.489999999999999858e+01,0.000000000000000000e+00,1.079486607731999293e+01,0.000000000000000000e+00,-6.409791406656337731e-01,0.000000000000000000e+00,-1.000000007709587635e+00,0.000000000000000000e+00 +3.177626681078180138e+00,3.491000000000000369e+01,0.000000000000000000e+00,1.079427229585380843e+01,0.000000000000000000e+00,-6.419055069591541596e-01,0.000000000000000000e+00,-1.000000009824051350e+00,0.000000000000000000e+00 +3.178553098322985271e+00,3.492000000000000171e+01,0.000000000000000000e+00,1.079367762352262616e+01,0.000000000000000000e+00,-6.428319242130603461e-01,0.000000000000000000e+00,-1.000000007477707120e+00,0.000000000000000000e+00 +3.179479566608290231e+00,3.492999999999999972e+01,0.000000000000000000e+00,1.079308206013206117e+01,0.000000000000000000e+00,-6.437583925052932088e-01,0.000000000000000000e+00,-1.000000008606694690e+00,0.000000000000000000e+00 +3.180406086016211553e+00,3.493999999999999773e+01,0.000000000000000000e+00,1.079248560548739277e+01,0.000000000000000000e+00,-6.446849119211888191e-01,0.000000000000000000e+00,-1.000000010797001737e+00,0.000000000000000000e+00 +3.181332656628908406e+00,3.495000000000000284e+01,0.000000000000000000e+00,1.079188825939355745e+01,0.000000000000000000e+00,-6.456114825438900029e-01,0.000000000000000000e+00,-1.000000007498239141e+00,0.000000000000000000e+00 +3.182259278528583479e+00,3.496000000000000085e+01,0.000000000000000000e+00,1.079129002165515061e+01,0.000000000000000000e+00,-6.465381044505130737e-01,0.000000000000000000e+00,-1.000000010779088511e+00,0.000000000000000000e+00 +3.183185951797482094e+00,3.496999999999999886e+01,0.000000000000000000e+00,1.079069089207643195e+01,0.000000000000000000e+00,-6.474647777294003648e-01,0.000000000000000000e+00,-1.000000007881794328e+00,0.000000000000000000e+00 +3.184112676517893092e+00,3.498000000000000398e+01,0.000000000000000000e+00,1.079009087046131476e+01,0.000000000000000000e+00,-6.483915024571155206e-01,0.000000000000000000e+00,-1.000000008802874207e+00,0.000000000000000000e+00 +3.185039452772148394e+00,3.499000000000000199e+01,0.000000000000000000e+00,1.078948995661337662e+01,0.000000000000000000e+00,-6.493182787195290739e-01,0.000000000000000000e+00,-1.000000009058548356e+00,0.000000000000000000e+00 +3.185966280642623438e+00,3.500000000000000000e+01,0.000000000000000000e+00,1.078888815033585047e+01,0.000000000000000000e+00,-6.502451065983998468e-01,0.000000000000000000e+00,-1.000000010369148429e+00,0.000000000000000000e+00 +3.186893160211737186e+00,3.500999999999999801e+01,0.000000000000000000e+00,1.078828545143162820e+01,0.000000000000000000e+00,-6.511719861771245732e-01,0.000000000000000000e+00,-1.000000006184015744e+00,0.000000000000000000e+00 +3.187820091561952118e+00,3.502000000000000313e+01,0.000000000000000000e+00,1.078768185970325888e+01,0.000000000000000000e+00,-6.520989175330716980e-01,0.000000000000000000e+00,-1.000000010626306057e+00,0.000000000000000000e+00 +3.188747074775774237e+00,3.503000000000000114e+01,0.000000000000000000e+00,1.078707737495295405e+01,0.000000000000000000e+00,-6.530259007567443819e-01,0.000000000000000000e+00,-1.000000008874810664e+00,0.000000000000000000e+00 +3.189674109935753510e+00,3.503999999999999915e+01,0.000000000000000000e+00,1.078647199698257531e+01,0.000000000000000000e+00,-6.539529359249510732e-01,0.000000000000000000e+00,-1.000000008848027200e+00,0.000000000000000000e+00 +3.190601197124483868e+00,3.505000000000000426e+01,0.000000000000000000e+00,1.078586572559364676e+01,0.000000000000000000e+00,-6.548800231218842027e-01,0.000000000000000000e+00,-1.000000010194882716e+00,0.000000000000000000e+00 +3.191528336424602319e+00,3.506000000000000227e+01,0.000000000000000000e+00,1.078525856058734789e+01,0.000000000000000000e+00,-6.558071624314548709e-01,0.000000000000000000e+00,-1.000000006364012206e+00,0.000000000000000000e+00 +3.192455527918790725e+00,3.507000000000000028e+01,0.000000000000000000e+00,1.078465050176451356e+01,0.000000000000000000e+00,-6.567343539315440015e-01,0.000000000000000000e+00,-1.000000011466918082e+00,0.000000000000000000e+00 +3.193382771689774469e+00,3.507999999999999829e+01,0.000000000000000000e+00,1.078404154892563938e+01,0.000000000000000000e+00,-6.576615977131605728e-01,0.000000000000000000e+00,-1.000000006555467058e+00,0.000000000000000000e+00 +3.194310067820323784e+00,3.509000000000000341e+01,0.000000000000000000e+00,1.078343170187086919e+01,0.000000000000000000e+00,-6.585888938497885814e-01,0.000000000000000000e+00,-1.000000011934646604e+00,0.000000000000000000e+00 +3.195237416393251983e+00,3.510000000000000142e+01,0.000000000000000000e+00,1.078282096040001115e+01,0.000000000000000000e+00,-6.595162424337844831e-01,0.000000000000000000e+00,-1.000000006593234403e+00,0.000000000000000000e+00 +3.196164817491417676e+00,3.510999999999999943e+01,0.000000000000000000e+00,1.078220932431251988e+01,0.000000000000000000e+00,-6.604436435380648396e-01,0.000000000000000000e+00,-1.000000008765568493e+00,0.000000000000000000e+00 +3.197092271197723434e+00,3.511999999999999744e+01,0.000000000000000000e+00,1.078159679340751431e+01,0.000000000000000000e+00,-6.613710972525004284e-01,0.000000000000000000e+00,-1.000000009833220238e+00,0.000000000000000000e+00 +3.198019777595116686e+00,3.513000000000000256e+01,0.000000000000000000e+00,1.078098336748376163e+01,0.000000000000000000e+00,-6.622986036590140513e-01,0.000000000000000000e+00,-1.000000009440115578e+00,0.000000000000000000e+00 +3.198947336766588823e+00,3.514000000000000057e+01,0.000000000000000000e+00,1.078036904633968440e+01,0.000000000000000000e+00,-6.632261628392426278e-01,0.000000000000000000e+00,-1.000000009293799064e+00,0.000000000000000000e+00 +3.199874948795176532e+00,3.514999999999999858e+01,0.000000000000000000e+00,1.077975382977336061e+01,0.000000000000000000e+00,-6.641537748764514415e-01,0.000000000000000000e+00,-1.000000006971919486e+00,0.000000000000000000e+00 +3.200802613763960913e+00,3.516000000000000369e+01,0.000000000000000000e+00,1.077913771758252182e+01,0.000000000000000000e+00,-6.650814398517034265e-01,0.000000000000000000e+00,-1.000000010371705050e+00,0.000000000000000000e+00 +3.201730331756067915e+00,3.517000000000000171e+01,0.000000000000000000e+00,1.077852070956455499e+01,0.000000000000000000e+00,-6.660091578534323986e-01,0.000000000000000000e+00,-1.000000008813508812e+00,0.000000000000000000e+00 +3.202658102854668343e+00,3.517999999999999972e+01,0.000000000000000000e+00,1.077790280551649538e+01,0.000000000000000000e+00,-6.669369289602097295e-01,0.000000000000000000e+00,-1.000000008128877571e+00,0.000000000000000000e+00 +3.203585927142978296e+00,3.518999999999999773e+01,0.000000000000000000e+00,1.077728400523503538e+01,0.000000000000000000e+00,-6.678647532560616495e-01,0.000000000000000000e+00,-1.000000010019699737e+00,0.000000000000000000e+00 +3.204513804704258284e+00,3.520000000000000284e+01,0.000000000000000000e+00,1.077666430851651924e+01,0.000000000000000000e+00,-6.687926308266387565e-01,0.000000000000000000e+00,-1.000000007934506163e+00,0.000000000000000000e+00 +3.205441735621814558e+00,3.521000000000000085e+01,0.000000000000000000e+00,1.077604371515694126e+01,0.000000000000000000e+00,-6.697205617515579190e-01,0.000000000000000000e+00,-1.000000009763084563e+00,0.000000000000000000e+00 +3.206369719978998667e+00,3.521999999999999886e+01,0.000000000000000000e+00,1.077542222495195112e+01,0.000000000000000000e+00,-6.706485461178022245e-01,0.000000000000000000e+00,-1.000000008953226383e+00,0.000000000000000000e+00 +3.207297757859207454e+00,3.523000000000000398e+01,0.000000000000000000e+00,1.077479983769684679e+01,0.000000000000000000e+00,-6.715765840063200320e-01,0.000000000000000000e+00,-1.000000009266714285e+00,0.000000000000000000e+00 +3.208225849345883063e+00,3.524000000000000199e+01,0.000000000000000000e+00,1.077417655318657985e+01,0.000000000000000000e+00,-6.725046755015959832e-01,0.000000000000000000e+00,-1.000000008276321628e+00,0.000000000000000000e+00 +3.209153994522512932e+00,3.525000000000000000e+01,0.000000000000000000e+00,1.077355237121575193e+01,0.000000000000000000e+00,-6.734328206859075960e-01,0.000000000000000000e+00,-1.000000009740587004e+00,0.000000000000000000e+00 +3.210082193472630685e+00,3.525999999999999801e+01,0.000000000000000000e+00,1.077292729157861650e+01,0.000000000000000000e+00,-6.743610196450664507e-01,0.000000000000000000e+00,-1.000000007108218236e+00,0.000000000000000000e+00 +3.211010446279814801e+00,3.527000000000000313e+01,0.000000000000000000e+00,1.077230131406907532e+01,0.000000000000000000e+00,-6.752892724588489548e-01,0.000000000000000000e+00,-1.000000010319803456e+00,0.000000000000000000e+00 +3.211938753027690385e+00,3.528000000000000114e+01,0.000000000000000000e+00,1.077167443848068373e+01,0.000000000000000000e+00,-6.762175792163045429e-01,0.000000000000000000e+00,-1.000000008700941745e+00,0.000000000000000000e+00 +3.212867113799927843e+00,3.528999999999999915e+01,0.000000000000000000e+00,1.077104666460664184e+01,0.000000000000000000e+00,-6.771459399966197612e-01,0.000000000000000000e+00,-1.000000008066960655e+00,0.000000000000000000e+00 +3.213795528680243763e+00,3.530000000000000426e+01,0.000000000000000000e+00,1.077041799223980334e+01,0.000000000000000000e+00,-6.780743548844253565e-01,0.000000000000000000e+00,-1.000000010109248549e+00,0.000000000000000000e+00 +3.214723997752400919e+00,3.531000000000000227e+01,0.000000000000000000e+00,1.076978842117267021e+01,0.000000000000000000e+00,-6.790028239659686715e-01,0.000000000000000000e+00,-1.000000008276117791e+00,0.000000000000000000e+00 +3.215652521100207828e+00,3.532000000000000028e+01,0.000000000000000000e+00,1.076915795119739094e+01,0.000000000000000000e+00,-6.799313473214602110e-01,0.000000000000000000e+00,-1.000000010438848452e+00,0.000000000000000000e+00 +3.216581098807519634e+00,3.532999999999999829e+01,0.000000000000000000e+00,1.076852658210576585e+01,0.000000000000000000e+00,-6.808599250384651524e-01,0.000000000000000000e+00,-1.000000007985097250e+00,0.000000000000000000e+00 +3.217509730958237224e+00,3.534000000000000341e+01,0.000000000000000000e+00,1.076789431368923999e+01,0.000000000000000000e+00,-6.817885571965979219e-01,0.000000000000000000e+00,-1.000000006723685164e+00,0.000000000000000000e+00 +3.218438417636308113e+00,3.535000000000000142e+01,0.000000000000000000e+00,1.076726114573891024e+01,0.000000000000000000e+00,-6.827172438809131494e-01,0.000000000000000000e+00,-1.000000012459226539e+00,0.000000000000000000e+00 +3.219367158925726891e+00,3.535999999999999943e+01,0.000000000000000000e+00,1.076662707804551999e+01,0.000000000000000000e+00,-6.836459851819031153e-01,0.000000000000000000e+00,-1.000000006283458420e+00,0.000000000000000000e+00 +3.220295954910533442e+00,3.536999999999999744e+01,0.000000000000000000e+00,1.076599211039945381e+01,0.000000000000000000e+00,-6.845747811725458876e-01,0.000000000000000000e+00,-1.000000010474745959e+00,0.000000000000000000e+00 +3.221224805674815617e+00,3.538000000000000256e+01,0.000000000000000000e+00,1.076535624259075341e+01,0.000000000000000000e+00,-6.855036319465575012e-01,0.000000000000000000e+00,-1.000000008184633415e+00,0.000000000000000000e+00 +3.222153711302707002e+00,3.539000000000000057e+01,0.000000000000000000e+00,1.076471947440909815e+01,0.000000000000000000e+00,-6.864325375820518049e-01,0.000000000000000000e+00,-1.000000009331917461e+00,0.000000000000000000e+00 +3.223082671878388705e+00,3.539999999999999858e+01,0.000000000000000000e+00,1.076408180564381922e+01,0.000000000000000000e+00,-6.873614981664025736e-01,0.000000000000000000e+00,-1.000000007364882482e+00,0.000000000000000000e+00 +3.224011687486088462e+00,3.541000000000000369e+01,0.000000000000000000e+00,1.076344323608389075e+01,0.000000000000000000e+00,-6.882905137809444129e-01,0.000000000000000000e+00,-1.000000010138302642e+00,0.000000000000000000e+00 +3.224940758210081082e+00,3.542000000000000171e+01,0.000000000000000000e+00,1.076280376551793516e+01,0.000000000000000000e+00,-6.892195845143560540e-01,0.000000000000000000e+00,-1.000000009042222970e+00,0.000000000000000000e+00 +3.225869884134688004e+00,3.542999999999999972e+01,0.000000000000000000e+00,1.076216339373421604e+01,0.000000000000000000e+00,-6.901487104473643663e-01,0.000000000000000000e+00,-1.000000009871719664e+00,0.000000000000000000e+00 +3.226799065344278628e+00,3.543999999999999773e+01,0.000000000000000000e+00,1.076152212052064527e+01,0.000000000000000000e+00,-6.910778916661274307e-01,0.000000000000000000e+00,-1.000000008131881168e+00,0.000000000000000000e+00 +3.227728301923268983e+00,3.545000000000000284e+01,0.000000000000000000e+00,1.076087994566477768e+01,0.000000000000000000e+00,-6.920071282526740752e-01,0.000000000000000000e+00,-1.000000007557850124e+00,0.000000000000000000e+00 +3.228657593956122618e+00,3.546000000000000085e+01,0.000000000000000000e+00,1.076023686895381459e+01,0.000000000000000000e+00,-6.929364202925510918e-01,0.000000000000000000e+00,-1.000000009824604019e+00,0.000000000000000000e+00 +3.229586941527350596e+00,3.546999999999999886e+01,0.000000000000000000e+00,1.075959289017460030e+01,0.000000000000000000e+00,-6.938657678729095446e-01,0.000000000000000000e+00,-1.000000008379844818e+00,0.000000000000000000e+00 +3.230516344721511501e+00,3.548000000000000398e+01,0.000000000000000000e+00,1.075894800911362026e+01,0.000000000000000000e+00,-6.947951710748587750e-01,0.000000000000000000e+00,-1.000000011067343930e+00,0.000000000000000000e+00 +3.231445803623211876e+00,3.549000000000000199e+01,0.000000000000000000e+00,1.075830222555700644e+01,0.000000000000000000e+00,-6.957246299868455885e-01,0.000000000000000000e+00,-1.000000007222804355e+00,0.000000000000000000e+00 +3.232375318317105339e+00,3.550000000000000000e+01,0.000000000000000000e+00,1.075765553929053020e+01,0.000000000000000000e+00,-6.966541446874525700e-01,0.000000000000000000e+00,-1.000000008798977547e+00,0.000000000000000000e+00 +3.233304888887893469e+00,3.550999999999999801e+01,0.000000000000000000e+00,1.075700795009961119e+01,0.000000000000000000e+00,-6.975837152664199348e-01,0.000000000000000000e+00,-1.000000009242137500e+00,0.000000000000000000e+00 +3.234234515420325806e+00,3.552000000000000313e+01,0.000000000000000000e+00,1.075635945776930669e+01,0.000000000000000000e+00,-6.985133418074441769e-01,0.000000000000000000e+00,-1.000000008167820642e+00,0.000000000000000000e+00 +3.235164197999200297e+00,3.553000000000000114e+01,0.000000000000000000e+00,1.075571006208431690e+01,0.000000000000000000e+00,-6.994430243939121494e-01,0.000000000000000000e+00,-1.000000009299824466e+00,0.000000000000000000e+00 +3.236093936709362406e+00,3.553999999999999915e+01,0.000000000000000000e+00,1.075505976282898501e+01,0.000000000000000000e+00,-7.003727631127206754e-01,0.000000000000000000e+00,-1.000000008140979446e+00,0.000000000000000000e+00 +3.237023731635706003e+00,3.555000000000000426e+01,0.000000000000000000e+00,1.075440855978729360e+01,0.000000000000000000e+00,-7.013025580466336617e-01,0.000000000000000000e+00,-1.000000010467746447e+00,0.000000000000000000e+00 +3.237953582863172919e+00,3.556000000000000227e+01,0.000000000000000000e+00,1.075375645274286818e+01,0.000000000000000000e+00,-7.022324092838341247e-01,0.000000000000000000e+00,-1.000000007673407909e+00,0.000000000000000000e+00 +3.238883490476753835e+00,3.557000000000000028e+01,0.000000000000000000e+00,1.075310344147897190e+01,0.000000000000000000e+00,-7.031623169045505550e-01,0.000000000000000000e+00,-1.000000009640239496e+00,0.000000000000000000e+00 +3.239813454561487394e+00,3.557999999999999829e+01,0.000000000000000000e+00,1.075244952577851265e+01,0.000000000000000000e+00,-7.040922809982491648e-01,0.000000000000000000e+00,-1.000000009815410928e+00,0.000000000000000000e+00 +3.240743475202461088e+00,3.559000000000000341e+01,0.000000000000000000e+00,1.075179470542403415e+01,0.000000000000000000e+00,-7.050223016483512239e-01,0.000000000000000000e+00,-1.000000007808456770e+00,0.000000000000000000e+00 +3.241673552484810372e+00,3.560000000000000142e+01,0.000000000000000000e+00,1.075113898019772130e+01,0.000000000000000000e+00,-7.059523789379631431e-01,0.000000000000000000e+00,-1.000000007335546393e+00,0.000000000000000000e+00 +3.242603686493720438e+00,3.560999999999999943e+01,0.000000000000000000e+00,1.075048234988140017e+01,0.000000000000000000e+00,-7.068825129536961960e-01,0.000000000000000000e+00,-1.000000010056086630e+00,0.000000000000000000e+00 +3.243533877314424441e+00,3.561999999999999744e+01,0.000000000000000000e+00,1.074982481425653447e+01,0.000000000000000000e+00,-7.078127037837542712e-01,0.000000000000000000e+00,-1.000000009417545632e+00,0.000000000000000000e+00 +3.244464125032204826e+00,3.563000000000000256e+01,0.000000000000000000e+00,1.074916637310422374e+01,0.000000000000000000e+00,-7.087429515102952049e-01,0.000000000000000000e+00,-1.000000009132232526e+00,0.000000000000000000e+00 +3.245394429732392894e+00,3.564000000000000057e+01,0.000000000000000000e+00,1.074850702620520870e+01,0.000000000000000000e+00,-7.096732562189788096e-01,0.000000000000000000e+00,-1.000000008805699281e+00,0.000000000000000000e+00 +3.246324791500368789e+00,3.564999999999999858e+01,0.000000000000000000e+00,1.074784677333986771e+01,0.000000000000000000e+00,-7.106036179951470411e-01,0.000000000000000000e+00,-1.000000008041945776e+00,0.000000000000000000e+00 +3.247255210421561955e+00,3.566000000000000369e+01,0.000000000000000000e+00,1.074718561428821673e+01,0.000000000000000000e+00,-7.115340369238225549e-01,0.000000000000000000e+00,-1.000000008496877424e+00,0.000000000000000000e+00 +3.248185686581451126e+00,3.567000000000000171e+01,0.000000000000000000e+00,1.074652354882990934e+01,0.000000000000000000e+00,-7.124645130916179570e-01,0.000000000000000000e+00,-1.000000009772562537e+00,0.000000000000000000e+00 +3.249116220065564775e+00,3.567999999999999972e+01,0.000000000000000000e+00,1.074586057674423500e+01,0.000000000000000000e+00,-7.133950465848251099e-01,0.000000000000000000e+00,-1.000000007369072685e+00,0.000000000000000000e+00 +3.250046810959479782e+00,3.568999999999999773e+01,0.000000000000000000e+00,1.074519669781011899e+01,0.000000000000000000e+00,-7.143256374855978530e-01,0.000000000000000000e+00,-1.000000011143053147e+00,0.000000000000000000e+00 +3.250977459348823650e+00,3.570000000000000284e+01,0.000000000000000000e+00,1.074453191180612599e+01,0.000000000000000000e+00,-7.152562858853119820e-01,0.000000000000000000e+00,-1.000000008389413164e+00,0.000000000000000000e+00 +3.251908165319272737e+00,3.571000000000000085e+01,0.000000000000000000e+00,1.074386621851045120e+01,0.000000000000000000e+00,-7.161869918635692667e-01,0.000000000000000000e+00,-1.000000006911803130e+00,0.000000000000000000e+00 +3.252838928956553577e+00,3.571999999999999886e+01,0.000000000000000000e+00,1.074319961770093101e+01,0.000000000000000000e+00,-7.171177555072834053e-01,0.000000000000000000e+00,-1.000000010409191509e+00,0.000000000000000000e+00 +3.253769750346442446e+00,3.573000000000000398e+01,0.000000000000000000e+00,1.074253210915503587e+01,0.000000000000000000e+00,-7.180485769068611912e-01,0.000000000000000000e+00,-1.000000008228242088e+00,0.000000000000000000e+00 +3.254700629574764914e+00,3.574000000000000199e+01,0.000000000000000000e+00,1.074186369264986673e+01,0.000000000000000000e+00,-7.189794561428431985e-01,0.000000000000000000e+00,-1.000000010216940183e+00,0.000000000000000000e+00 +3.255631566727397175e+00,3.575000000000000000e+01,0.000000000000000000e+00,1.074119436796216398e+01,0.000000000000000000e+00,-7.199103933049868509e-01,0.000000000000000000e+00,-1.000000007772677169e+00,0.000000000000000000e+00 +3.256562561890265162e+00,3.575999999999999801e+01,0.000000000000000000e+00,1.074052413486829849e+01,0.000000000000000000e+00,-7.208413884750913825e-01,0.000000000000000000e+00,-1.000000008689834852e+00,0.000000000000000000e+00 +3.257493615149345434e+00,3.577000000000000313e+01,0.000000000000000000e+00,1.073985299314427877e+01,0.000000000000000000e+00,-7.217724417422624050e-01,0.000000000000000000e+00,-1.000000008464147383e+00,0.000000000000000000e+00 +3.258424726590664289e+00,3.578000000000000114e+01,0.000000000000000000e+00,1.073918094256574385e+01,0.000000000000000000e+00,-7.227035531914624000e-01,0.000000000000000000e+00,-1.000000008739336588e+00,0.000000000000000000e+00 +3.259355896300298649e+00,3.578999999999999915e+01,0.000000000000000000e+00,1.073850798290796682e+01,0.000000000000000000e+00,-7.236347229092345845e-01,0.000000000000000000e+00,-1.000000009108125365e+00,0.000000000000000000e+00 +3.260287124364375622e+00,3.580000000000000426e+01,0.000000000000000000e+00,1.073783411394585308e+01,0.000000000000000000e+00,-7.245659509817934385e-01,0.000000000000000000e+00,-1.000000009163714676e+00,0.000000000000000000e+00 +3.261218410869073381e+00,3.581000000000000227e+01,0.000000000000000000e+00,1.073715933545394030e+01,0.000000000000000000e+00,-7.254972374950251490e-01,0.000000000000000000e+00,-1.000000010545605722e+00,0.000000000000000000e+00 +3.262149755900619841e+00,3.582000000000000028e+01,0.000000000000000000e+00,1.073648364720639847e+01,0.000000000000000000e+00,-7.264285825363934190e-01,0.000000000000000000e+00,-1.000000006702032485e+00,0.000000000000000000e+00 +3.263081159545294874e+00,3.582999999999999829e+01,0.000000000000000000e+00,1.073580704897702809e+01,0.000000000000000000e+00,-7.273599861873105699e-01,0.000000000000000000e+00,-1.000000009509294685e+00,0.000000000000000000e+00 +3.264012621889428090e+00,3.584000000000000341e+01,0.000000000000000000e+00,1.073512954053926549e+01,0.000000000000000000e+00,-7.282914485403011451e-01,0.000000000000000000e+00,-1.000000008318417510e+00,0.000000000000000000e+00 +3.264944143019400169e+00,3.585000000000000142e+01,0.000000000000000000e+00,1.073445112166617221e+01,0.000000000000000000e+00,-7.292229696780220261e-01,0.000000000000000000e+00,-1.000000008860704614e+00,0.000000000000000000e+00 +3.265875723021643307e+00,3.585999999999999943e+01,0.000000000000000000e+00,1.073377179213044386e+01,0.000000000000000000e+00,-7.301545496885195607e-01,0.000000000000000000e+00,-1.000000008676629859e+00,0.000000000000000000e+00 +3.266807361982640323e+00,3.586999999999999744e+01,0.000000000000000000e+00,1.073309155170440476e+01,0.000000000000000000e+00,-7.310861886576001112e-01,0.000000000000000000e+00,-1.000000009399782064e+00,0.000000000000000000e+00 +3.267739059988925554e+00,3.588000000000000256e+01,0.000000000000000000e+00,1.073241040016000980e+01,0.000000000000000000e+00,-7.320178866726431144e-01,0.000000000000000000e+00,-1.000000008570186116e+00,0.000000000000000000e+00 +3.268670817127084405e+00,3.589000000000000057e+01,0.000000000000000000e+00,1.073172833726884257e+01,0.000000000000000000e+00,-7.329496438187873553e-01,0.000000000000000000e+00,-1.000000007819629610e+00,0.000000000000000000e+00 +3.269602633483753795e+00,3.589999999999999858e+01,0.000000000000000000e+00,1.073104536280211718e+01,0.000000000000000000e+00,-7.338814601827432504e-01,0.000000000000000000e+00,-1.000000010824159791e+00,0.000000000000000000e+00 +3.270534509145622160e+00,3.591000000000000369e+01,0.000000000000000000e+00,1.073036147653067651e+01,0.000000000000000000e+00,-7.348133358546983240e-01,0.000000000000000000e+00,-1.000000006939364638e+00,0.000000000000000000e+00 +3.271466444199429446e+00,3.592000000000000171e+01,0.000000000000000000e+00,1.072967667822498861e+01,0.000000000000000000e+00,-7.357452709149724379e-01,0.000000000000000000e+00,-1.000000010066307565e+00,0.000000000000000000e+00 +3.272398438731966674e+00,3.592999999999999972e+01,0.000000000000000000e+00,1.072899096765515559e+01,0.000000000000000000e+00,-7.366772654568916057e-01,0.000000000000000000e+00,-1.000000007516009815e+00,0.000000000000000000e+00 +3.273330492830077709e+00,3.593999999999999773e+01,0.000000000000000000e+00,1.072830434459090121e+01,0.000000000000000000e+00,-7.376093195620080367e-01,0.000000000000000000e+00,-1.000000009094651032e+00,0.000000000000000000e+00 +3.274262606580657486e+00,3.595000000000000284e+01,0.000000000000000000e+00,1.072761680880158153e+01,0.000000000000000000e+00,-7.385414333210652549e-01,0.000000000000000000e+00,-1.000000010292423358e+00,0.000000000000000000e+00 +3.275194780070653344e+00,3.596000000000000085e+01,0.000000000000000000e+00,1.072692836005617600e+01,0.000000000000000000e+00,-7.394736068206555490e-01,0.000000000000000000e+00,-1.000000006602000946e+00,0.000000000000000000e+00 +3.276127013387064579e+00,3.596999999999999886e+01,0.000000000000000000e+00,1.072623899812329107e+01,0.000000000000000000e+00,-7.404058401432213055e-01,0.000000000000000000e+00,-1.000000009866079953e+00,0.000000000000000000e+00 +3.277059306616942447e+00,3.598000000000000398e+01,0.000000000000000000e+00,1.072554872277116367e+01,0.000000000000000000e+00,-7.413381333822970376e-01,0.000000000000000000e+00,-1.000000009442850502e+00,0.000000000000000000e+00 +3.277991659847390160e+00,3.599000000000000199e+01,0.000000000000000000e+00,1.072485753376765061e+01,0.000000000000000000e+00,-7.422704866215488195e-01,0.000000000000000000e+00,-1.000000006954475440e+00,0.000000000000000000e+00 +3.278924073165563779e+00,3.600000000000000000e+01,0.000000000000000000e+00,1.072416543088023744e+01,0.000000000000000000e+00,-7.432028999462069185e-01,0.000000000000000000e+00,-1.000000010150131180e+00,0.000000000000000000e+00 +3.279856546658671768e+00,3.600999999999999801e+01,0.000000000000000000e+00,1.072347241387603667e+01,0.000000000000000000e+00,-7.441353734487795579e-01,0.000000000000000000e+00,-1.000000008389524409e+00,0.000000000000000000e+00 +3.280789080413974990e+00,3.602000000000000313e+01,0.000000000000000000e+00,1.072277848252178067e+01,0.000000000000000000e+00,-7.450679072119060775e-01,0.000000000000000000e+00,-1.000000009419517610e+00,0.000000000000000000e+00 +3.281721674518786713e+00,3.603000000000000114e+01,0.000000000000000000e+00,1.072208363658383057e+01,0.000000000000000000e+00,-7.460005013255022188e-01,0.000000000000000000e+00,-1.000000008728607170e+00,0.000000000000000000e+00 +3.282654329060473053e+00,3.603999999999999915e+01,0.000000000000000000e+00,1.072138787582816910e+01,0.000000000000000000e+00,-7.469331558753292688e-01,0.000000000000000000e+00,-1.000000007932776880e+00,0.000000000000000000e+00 +3.283587044126452970e+00,3.605000000000000426e+01,0.000000000000000000e+00,1.072069120002040421e+01,0.000000000000000000e+00,-7.478658709487082668e-01,0.000000000000000000e+00,-1.000000008646060756e+00,0.000000000000000000e+00 +3.284519819804198715e+00,3.606000000000000227e+01,0.000000000000000000e+00,1.071999360892576725e+01,0.000000000000000000e+00,-7.487986466345186720e-01,0.000000000000000000e+00,-1.000000010439062281e+00,0.000000000000000000e+00 +3.285452656181234943e+00,3.607000000000000028e+01,0.000000000000000000e+00,1.071929510230911120e+01,0.000000000000000000e+00,-7.497314830212926662e-01,0.000000000000000000e+00,-1.000000006759306670e+00,0.000000000000000000e+00 +3.286385553345139598e+00,3.607999999999999829e+01,0.000000000000000000e+00,1.071859567993491069e+01,0.000000000000000000e+00,-7.506643801915029446e-01,0.000000000000000000e+00,-1.000000009423743341e+00,0.000000000000000000e+00 +3.287318511383543918e+00,3.609000000000000341e+01,0.000000000000000000e+00,1.071789534156726731e+01,0.000000000000000000e+00,-7.515973382386991197e-01,0.000000000000000000e+00,-1.000000009836412795e+00,0.000000000000000000e+00 +3.288251530384132426e+00,3.610000000000000142e+01,0.000000000000000000e+00,1.071719408696989895e+01,0.000000000000000000e+00,-7.525303572484650649e-01,0.000000000000000000e+00,-1.000000007566684390e+00,0.000000000000000000e+00 +3.289184610434642941e+00,3.610999999999999943e+01,0.000000000000000000e+00,1.071649191590614691e+01,0.000000000000000000e+00,-7.534634373060358215e-01,0.000000000000000000e+00,-1.000000008303398191e+00,0.000000000000000000e+00 +3.290117751622867015e+00,3.611999999999999744e+01,0.000000000000000000e+00,1.071578882813897593e+01,0.000000000000000000e+00,-7.543965785020079196e-01,0.000000000000000000e+00,-1.000000009571801129e+00,0.000000000000000000e+00 +3.291050954036649046e+00,3.613000000000000256e+01,0.000000000000000000e+00,1.071508482343096880e+01,0.000000000000000000e+00,-7.553297809247225825e-01,0.000000000000000000e+00,-1.000000008897683479e+00,0.000000000000000000e+00 +3.291984217763888498e+00,3.614000000000000057e+01,0.000000000000000000e+00,1.071437990154432818e+01,0.000000000000000000e+00,-7.562630446602657264e-01,0.000000000000000000e+00,-1.000000007886654663e+00,0.000000000000000000e+00 +3.292917542892537242e+00,3.614999999999999858e+01,0.000000000000000000e+00,1.071367406224087837e+01,0.000000000000000000e+00,-7.571963697962752482e-01,0.000000000000000000e+00,-1.000000008141418650e+00,0.000000000000000000e+00 +3.293850929510601766e+00,3.616000000000000369e+01,0.000000000000000000e+00,1.071296730528206353e+01,0.000000000000000000e+00,-7.581297564219388052e-01,0.000000000000000000e+00,-1.000000011263199928e+00,0.000000000000000000e+00 +3.294784377706142298e+00,3.617000000000000171e+01,0.000000000000000000e+00,1.071225963042894591e+01,0.000000000000000000e+00,-7.590632046279929268e-01,0.000000000000000000e+00,-1.000000006621697635e+00,0.000000000000000000e+00 +3.295717887567273241e+00,3.617999999999999972e+01,0.000000000000000000e+00,1.071155103744220405e+01,0.000000000000000000e+00,-7.599967144953052589e-01,0.000000000000000000e+00,-1.000000010086351088e+00,0.000000000000000000e+00 +3.296651459182163180e+00,3.618999999999999773e+01,0.000000000000000000e+00,1.071084152608214168e+01,0.000000000000000000e+00,-7.609302861196114431e-01,0.000000000000000000e+00,-1.000000006949565146e+00,0.000000000000000000e+00 +3.297585092639034876e+00,3.620000000000000284e+01,0.000000000000000000e+00,1.071013109610867353e+01,0.000000000000000000e+00,-7.618639195829713939e-01,0.000000000000000000e+00,-1.000000008999511580e+00,0.000000000000000000e+00 +3.298518788026165272e+00,3.621000000000000085e+01,0.000000000000000000e+00,1.070941974728133772e+01,0.000000000000000000e+00,-7.627976149785047344e-01,0.000000000000000000e+00,-1.000000009680807267e+00,0.000000000000000000e+00 +3.299452545431886374e+00,3.621999999999999886e+01,0.000000000000000000e+00,1.070870747935928513e+01,0.000000000000000000e+00,-7.637313723932653842e-01,0.000000000000000000e+00,-1.000000008552340836e+00,0.000000000000000000e+00 +3.300386364944584372e+00,3.623000000000000398e+01,0.000000000000000000e+00,1.070799429210128473e+01,0.000000000000000000e+00,-7.646651919139496600e-01,0.000000000000000000e+00,-1.000000009245813004e+00,0.000000000000000000e+00 +3.301320246652700074e+00,3.624000000000000199e+01,0.000000000000000000e+00,1.070728018526572356e+01,0.000000000000000000e+00,-7.655990736306997890e-01,0.000000000000000000e+00,-1.000000007243823319e+00,0.000000000000000000e+00 +3.302254190644728915e+00,3.625000000000000000e+01,0.000000000000000000e+00,1.070656515861060321e+01,0.000000000000000000e+00,-7.665330176294941067e-01,0.000000000000000000e+00,-1.000000010248026650e+00,0.000000000000000000e+00 +3.303188197009221838e+00,3.625999999999999801e+01,0.000000000000000000e+00,1.070584921189354333e+01,0.000000000000000000e+00,-7.674670240035587065e-01,0.000000000000000000e+00,-1.000000007630956089e+00,0.000000000000000000e+00 +3.304122265834783967e+00,3.627000000000000313e+01,0.000000000000000000e+00,1.070513234487177456e+01,0.000000000000000000e+00,-7.684010928362488002e-01,0.000000000000000000e+00,-1.000000009127862466e+00,0.000000000000000000e+00 +3.305056397210076380e+00,3.628000000000000114e+01,0.000000000000000000e+00,1.070441455730214741e+01,0.000000000000000000e+00,-7.693352242200676150e-01,0.000000000000000000e+00,-1.000000008183153266e+00,0.000000000000000000e+00 +3.305990591223814334e+00,3.628999999999999915e+01,0.000000000000000000e+00,1.070369584894112336e+01,0.000000000000000000e+00,-7.702694182414501212e-01,0.000000000000000000e+00,-1.000000008420739661e+00,0.000000000000000000e+00 +3.306924847964769043e+00,3.630000000000000426e+01,0.000000000000000000e+00,1.070297621954478018e+01,0.000000000000000000e+00,-7.712036749902717592e-01,0.000000000000000000e+00,-1.000000009391135647e+00,0.000000000000000000e+00 +3.307859167521766341e+00,3.631000000000000227e+01,0.000000000000000000e+00,1.070225566886880841e+01,0.000000000000000000e+00,-7.721379945560435942e-01,0.000000000000000000e+00,-1.000000008609975399e+00,0.000000000000000000e+00 +3.308793549983688465e+00,3.632000000000000028e+01,0.000000000000000000e+00,1.070153419666851136e+01,0.000000000000000000e+00,-7.730723770260109484e-01,0.000000000000000000e+00,-1.000000007661897561e+00,0.000000000000000000e+00 +3.309727995439473158e+00,3.632999999999999829e+01,0.000000000000000000e+00,1.070081180269880683e+01,0.000000000000000000e+00,-7.740068224889551374e-01,0.000000000000000000e+00,-1.000000010163722974e+00,0.000000000000000000e+00 +3.310662503978112792e+00,3.634000000000000341e+01,0.000000000000000000e+00,1.070008848671422541e+01,0.000000000000000000e+00,-7.749413310370930619e-01,0.000000000000000000e+00,-1.000000007526679502e+00,0.000000000000000000e+00 +3.311597075688656577e+00,3.635000000000000142e+01,0.000000000000000000e+00,1.069936424846890688e+01,0.000000000000000000e+00,-7.758759027546712206e-01,0.000000000000000000e+00,-1.000000009467475914e+00,0.000000000000000000e+00 +3.312531710660209239e+00,3.635999999999999943e+01,0.000000000000000000e+00,1.069863908771660732e+01,0.000000000000000000e+00,-7.768105377350725815e-01,0.000000000000000000e+00,-1.000000009430361825e+00,0.000000000000000000e+00 +3.313466408981931455e+00,3.636999999999999744e+01,0.000000000000000000e+00,1.069791300421069025e+01,0.000000000000000000e+00,-7.777452360656093022e-01,0.000000000000000000e+00,-1.000000006961674348e+00,0.000000000000000000e+00 +3.314401170743039859e+00,3.638000000000000256e+01,0.000000000000000000e+00,1.069718599770413192e+01,0.000000000000000000e+00,-7.786799978332251682e-01,0.000000000000000000e+00,-1.000000009737543882e+00,0.000000000000000000e+00 +3.315335996032807486e+00,3.639000000000000057e+01,0.000000000000000000e+00,1.069645806794952136e+01,0.000000000000000000e+00,-7.796148231320955135e-01,0.000000000000000000e+00,-1.000000007136817137e+00,0.000000000000000000e+00 +3.316270884940563324e+00,3.639999999999999858e+01,0.000000000000000000e+00,1.069572921469905324e+01,0.000000000000000000e+00,-7.805497120465233474e-01,0.000000000000000000e+00,-1.000000008865291612e+00,0.000000000000000000e+00 +3.317205837555692760e+00,3.641000000000000369e+01,0.000000000000000000e+00,1.069499943770453676e+01,0.000000000000000000e+00,-7.814846646699414867e-01,0.000000000000000000e+00,-1.000000010398780725e+00,0.000000000000000000e+00 +3.318140853967638026e+00,3.642000000000000171e+01,0.000000000000000000e+00,1.069426873671738676e+01,0.000000000000000000e+00,-7.824196810916098643e-01,0.000000000000000000e+00,-1.000000007215529507e+00,0.000000000000000000e+00 +3.319075934265897754e+00,3.642999999999999972e+01,0.000000000000000000e+00,1.069353711148862729e+01,0.000000000000000000e+00,-7.833547613966167500e-01,0.000000000000000000e+00,-1.000000009013665148e+00,0.000000000000000000e+00 +3.320011078540027416e+00,3.643999999999999773e+01,0.000000000000000000e+00,1.069280456176889516e+01,0.000000000000000000e+00,-7.842899056791753365e-01,0.000000000000000000e+00,-1.000000009237081988e+00,0.000000000000000000e+00 +3.320946286879638887e+00,3.645000000000000284e+01,0.000000000000000000e+00,1.069207108730843103e+01,0.000000000000000000e+00,-7.852251140274252306e-01,0.000000000000000000e+00,-1.000000007424769022e+00,0.000000000000000000e+00 +3.321881559374400883e+00,3.646000000000000085e+01,0.000000000000000000e+00,1.069133668785708480e+01,0.000000000000000000e+00,-7.861603865291314497e-01,0.000000000000000000e+00,-1.000000009206110985e+00,0.000000000000000000e+00 +3.322816896114039409e+00,3.646999999999999886e+01,0.000000000000000000e+00,1.069060136316431553e+01,0.000000000000000000e+00,-7.870957232773809764e-01,0.000000000000000000e+00,-1.000000008025594633e+00,0.000000000000000000e+00 +3.323752297188337756e+00,3.648000000000000398e+01,0.000000000000000000e+00,1.068986511297918618e+01,0.000000000000000000e+00,-7.880311243591865411e-01,0.000000000000000000e+00,-1.000000009509546928e+00,0.000000000000000000e+00 +3.324687762687136061e+00,3.649000000000000199e+01,0.000000000000000000e+00,1.068912793705036890e+01,0.000000000000000000e+00,-7.889665898668807298e-01,0.000000000000000000e+00,-1.000000009132164802e+00,0.000000000000000000e+00 +3.325623292700331746e+00,3.650000000000000000e+01,0.000000000000000000e+00,1.068838983512613972e+01,0.000000000000000000e+00,-7.899021198886199135e-01,0.000000000000000000e+00,-1.000000006428310773e+00,0.000000000000000000e+00 +3.326558887317879964e+00,3.650999999999999801e+01,0.000000000000000000e+00,1.068765080695438208e+01,0.000000000000000000e+00,-7.908377145121823215e-01,0.000000000000000000e+00,-1.000000009047803395e+00,0.000000000000000000e+00 +3.327494546629792715e+00,3.652000000000000313e+01,0.000000000000000000e+00,1.068691085228258686e+01,0.000000000000000000e+00,-7.917733738325608561e-01,0.000000000000000000e+00,-1.000000010433866882e+00,0.000000000000000000e+00 +3.328430270726140172e+00,3.653000000000000114e+01,0.000000000000000000e+00,1.068616997085784526e+01,0.000000000000000000e+00,-7.927090979386717251e-01,0.000000000000000000e+00,-1.000000008089759085e+00,0.000000000000000000e+00 +3.329366059697050240e+00,3.653999999999999915e+01,0.000000000000000000e+00,1.068542816242685412e+01,0.000000000000000000e+00,-7.936448869171521814e-01,0.000000000000000000e+00,-1.000000007631857590e+00,0.000000000000000000e+00 +3.330301913632708555e+00,3.655000000000000426e+01,0.000000000000000000e+00,1.068468542673591770e+01,0.000000000000000000e+00,-7.945807408599526722e-01,0.000000000000000000e+00,-1.000000008588873834e+00,0.000000000000000000e+00 +3.331237832623358042e+00,3.656000000000000227e+01,0.000000000000000000e+00,1.068394176353094238e+01,0.000000000000000000e+00,-7.955166598586408400e-01,0.000000000000000000e+00,-1.000000008460381729e+00,0.000000000000000000e+00 +3.332173816759300689e+00,3.657000000000000028e+01,0.000000000000000000e+00,1.068319717255743662e+01,0.000000000000000000e+00,-7.964526440025022636e-01,0.000000000000000000e+00,-1.000000008801960938e+00,0.000000000000000000e+00 +3.333109866130895771e+00,3.657999999999999829e+01,0.000000000000000000e+00,1.068245165356051274e+01,0.000000000000000000e+00,-7.973886933823365331e-01,0.000000000000000000e+00,-1.000000009139891510e+00,0.000000000000000000e+00 +3.334045980828561184e+00,3.659000000000000341e+01,0.000000000000000000e+00,1.068170520628488518e+01,0.000000000000000000e+00,-7.983248080885581022e-01,0.000000000000000000e+00,-1.000000006973045918e+00,0.000000000000000000e+00 +3.334982160942773444e+00,3.660000000000000142e+01,0.000000000000000000e+00,1.068095783047487046e+01,0.000000000000000000e+00,-7.992609882092982510e-01,0.000000000000000000e+00,-1.000000009933400547e+00,0.000000000000000000e+00 +3.335918406564066796e+00,3.660999999999999943e+01,0.000000000000000000e+00,1.068020952587438899e+01,0.000000000000000000e+00,-8.001972338398916085e-01,0.000000000000000000e+00,-1.000000009437446158e+00,0.000000000000000000e+00 +3.336854717783034108e+00,3.661999999999999744e+01,0.000000000000000000e+00,1.067946029222695792e+01,0.000000000000000000e+00,-8.011335450676955183e-01,0.000000000000000000e+00,-1.000000007035654948e+00,0.000000000000000000e+00 +3.337791094690327753e+00,3.663000000000000256e+01,0.000000000000000000e+00,1.067871012927569829e+01,0.000000000000000000e+00,-8.020699219815771164e-01,0.000000000000000000e+00,-1.000000008327994516e+00,0.000000000000000000e+00 +3.338727537376657839e+00,3.664000000000000057e+01,0.000000000000000000e+00,1.067795903676333324e+01,0.000000000000000000e+00,-8.030063646757059637e-01,0.000000000000000000e+00,-1.000000008782959027e+00,0.000000000000000000e+00 +3.339664045932793979e+00,3.664999999999999858e+01,0.000000000000000000e+00,1.067720701443218267e+01,0.000000000000000000e+00,-8.039428732400674127e-01,0.000000000000000000e+00,-1.000000009946130808e+00,0.000000000000000000e+00 +3.340600620449564406e+00,3.666000000000000369e+01,0.000000000000000000e+00,1.067645406202416680e+01,0.000000000000000000e+00,-8.048794477661531666e-01,0.000000000000000000e+00,-1.000000007287163761e+00,0.000000000000000000e+00 +3.341537261017856419e+00,3.667000000000000171e+01,0.000000000000000000e+00,1.067570017928080439e+01,0.000000000000000000e+00,-8.058160883412708309e-01,0.000000000000000000e+00,-1.000000008424174247e+00,0.000000000000000000e+00 +3.342473967728616824e+00,3.667999999999999972e+01,0.000000000000000000e+00,1.067494536594321630e+01,0.000000000000000000e+00,-8.067527950599223674e-01,0.000000000000000000e+00,-1.000000006799838914e+00,0.000000000000000000e+00 +3.343410740672851489e+00,3.668999999999999773e+01,0.000000000000000000e+00,1.067418962175211838e+01,0.000000000000000000e+00,-8.076895680105270481e-01,0.000000000000000000e+00,-1.000000012051770470e+00,0.000000000000000000e+00 +3.344347579941625792e+00,3.670000000000000284e+01,0.000000000000000000e+00,1.067343294644782681e+01,0.000000000000000000e+00,-8.086264072905918754e-01,0.000000000000000000e+00,-1.000000005479752208e+00,0.000000000000000000e+00 +3.345284485626064175e+00,3.671000000000000085e+01,0.000000000000000000e+00,1.067267533977024918e+01,0.000000000000000000e+00,-8.095633129801643735e-01,0.000000000000000000e+00,-1.000000010884071866e+00,0.000000000000000000e+00 +3.346221457817351030e+00,3.671999999999999886e+01,0.000000000000000000e+00,1.067191680145890054e+01,0.000000000000000000e+00,-8.105002851816495157e-01,0.000000000000000000e+00,-1.000000005519097179e+00,0.000000000000000000e+00 +3.347158496606730704e+00,3.673000000000000398e+01,0.000000000000000000e+00,1.067115733125288202e+01,0.000000000000000000e+00,-8.114373239762008305e-01,0.000000000000000000e+00,-1.000000011153490131e+00,0.000000000000000000e+00 +3.348095602085507050e+00,3.674000000000000199e+01,0.000000000000000000e+00,1.067039692889090041e+01,0.000000000000000000e+00,-8.123744294654290377e-01,0.000000000000000000e+00,-1.000000007068572172e+00,0.000000000000000000e+00 +3.349032774345043428e+00,3.675000000000000000e+01,0.000000000000000000e+00,1.066963559411124862e+01,0.000000000000000000e+00,-8.133116017315900059e-01,0.000000000000000000e+00,-1.000000008958072284e+00,0.000000000000000000e+00 +3.349970013476764041e+00,3.675999999999999801e+01,0.000000000000000000e+00,1.066887332665182342e+01,0.000000000000000000e+00,-8.142488408717064585e-01,0.000000000000000000e+00,-1.000000008241309413e+00,0.000000000000000000e+00 +3.350907319572152598e+00,3.677000000000000313e+01,0.000000000000000000e+00,1.066811012625011124e+01,0.000000000000000000e+00,-8.151861469748197253e-01,0.000000000000000000e+00,-1.000000008471611856e+00,0.000000000000000000e+00 +3.351844692722753649e+00,3.678000000000000114e+01,0.000000000000000000e+00,1.066734599264319527e+01,0.000000000000000000e+00,-8.161235201333616462e-01,0.000000000000000000e+00,-1.000000009157100855e+00,0.000000000000000000e+00 +3.352782133020171251e+00,3.678999999999999915e+01,0.000000000000000000e+00,1.066658092556775195e+01,0.000000000000000000e+00,-8.170609604393634928e-01,0.000000000000000000e+00,-1.000000007783499401e+00,0.000000000000000000e+00 +3.353719640556070747e+00,3.680000000000000426e+01,0.000000000000000000e+00,1.066581492476005089e+01,0.000000000000000000e+00,-8.179984679825599292e-01,0.000000000000000000e+00,-1.000000007899476628e+00,0.000000000000000000e+00 +3.354657215422177430e+00,3.681000000000000227e+01,0.000000000000000000e+00,1.066504798995595671e+01,0.000000000000000000e+00,-8.189360428560729099e-01,0.000000000000000000e+00,-1.000000009010193258e+00,0.000000000000000000e+00 +3.355594857710277434e+00,3.682000000000000028e+01,0.000000000000000000e+00,1.066428012089092547e+01,0.000000000000000000e+00,-8.198736851526213787e-01,0.000000000000000000e+00,-1.000000008598491918e+00,0.000000000000000000e+00 +3.356532567512218179e+00,3.682999999999999829e+01,0.000000000000000000e+00,1.066351131730000468e+01,0.000000000000000000e+00,-8.208113949626248962e-01,0.000000000000000000e+00,-1.000000008189261047e+00,0.000000000000000000e+00 +3.357470344919907035e+00,3.684000000000000341e+01,0.000000000000000000e+00,1.066274157891783503e+01,0.000000000000000000e+00,-8.217491723779936086e-01,0.000000000000000000e+00,-1.000000009304231163e+00,0.000000000000000000e+00 +3.358408190025313100e+00,3.685000000000000142e+01,0.000000000000000000e+00,1.066197090547864867e+01,0.000000000000000000e+00,-8.226870174921258050e-01,0.000000000000000000e+00,-1.000000007405841274e+00,0.000000000000000000e+00 +3.359346102920466759e+00,3.685999999999999943e+01,0.000000000000000000e+00,1.066119929671626743e+01,0.000000000000000000e+00,-8.236249303942253519e-01,0.000000000000000000e+00,-1.000000008053033129e+00,0.000000000000000000e+00 +3.360284083697458790e+00,3.686999999999999744e+01,0.000000000000000000e+00,1.066042675236410631e+01,0.000000000000000000e+00,-8.245629111787708965e-01,0.000000000000000000e+00,-1.000000008725446365e+00,0.000000000000000000e+00 +3.361222132448441702e+00,3.688000000000000256e+01,0.000000000000000000e+00,1.065965327215516822e+01,0.000000000000000000e+00,-8.255009599379387053e-01,0.000000000000000000e+00,-1.000000008921960060e+00,0.000000000000000000e+00 +3.362160249265629730e+00,3.689000000000000057e+01,0.000000000000000000e+00,1.065887885582204575e+01,0.000000000000000000e+00,-8.264390767634963719e-01,0.000000000000000000e+00,-1.000000008140417451e+00,0.000000000000000000e+00 +3.363098434241297952e+00,3.689999999999999858e+01,0.000000000000000000e+00,1.065810350309692112e+01,0.000000000000000000e+00,-8.273772617468018176e-01,0.000000000000000000e+00,-1.000000007896077792e+00,0.000000000000000000e+00 +3.364036687467783615e+00,3.691000000000000369e+01,0.000000000000000000e+00,1.065732721371156622e+01,0.000000000000000000e+00,-8.283155149806961104e-01,0.000000000000000000e+00,-1.000000007684628489e+00,0.000000000000000000e+00 +3.364975009037485698e+00,3.692000000000000171e+01,0.000000000000000000e+00,1.065654998739734083e+01,0.000000000000000000e+00,-8.292538365576089809e-01,0.000000000000000000e+00,-1.000000009017814495e+00,0.000000000000000000e+00 +3.365913399042865350e+00,3.692999999999999972e+01,0.000000000000000000e+00,1.065577182388519262e+01,0.000000000000000000e+00,-8.301922265714506421e-01,0.000000000000000000e+00,-1.000000009372103316e+00,0.000000000000000000e+00 +3.366851857576444562e+00,3.693999999999999773e+01,0.000000000000000000e+00,1.065499272290565536e+01,0.000000000000000000e+00,-8.311306851138253737e-01,0.000000000000000000e+00,-1.000000008241143101e+00,0.000000000000000000e+00 +3.367790384730808828e+00,3.695000000000000284e+01,0.000000000000000000e+00,1.065421268418885070e+01,0.000000000000000000e+00,-8.320692122759241194e-01,0.000000000000000000e+00,-1.000000007133725832e+00,0.000000000000000000e+00 +3.368728980598604927e+00,3.696000000000000085e+01,0.000000000000000000e+00,1.065343170746448820e+01,0.000000000000000000e+00,-8.330078081504158627e-01,0.000000000000000000e+00,-1.000000007557255932e+00,0.000000000000000000e+00 +3.369667645272542256e+00,3.696999999999999886e+01,0.000000000000000000e+00,1.065264979246186350e+01,0.000000000000000000e+00,-8.339464728314468500e-01,0.000000000000000000e+00,-1.000000011016212609e+00,0.000000000000000000e+00 +3.370606378845392381e+00,3.698000000000000398e+01,0.000000000000000000e+00,1.065186693890985659e+01,0.000000000000000000e+00,-8.348852064146383700e-01,0.000000000000000000e+00,-1.000000006921535345e+00,0.000000000000000000e+00 +3.371545181409989933e+00,3.699000000000000199e+01,0.000000000000000000e+00,1.065108314653693000e+01,0.000000000000000000e+00,-8.358240089857338351e-01,0.000000000000000000e+00,-1.000000006856106571e+00,0.000000000000000000e+00 +3.372484053059231712e+00,3.700000000000000000e+01,0.000000000000000000e+00,1.065029841507113773e+01,0.000000000000000000e+00,-8.367628806414125764e-01,0.000000000000000000e+00,-1.000000010304537001e+00,0.000000000000000000e+00 +3.373422993886077581e+00,3.700999999999999801e+01,0.000000000000000000e+00,1.064951274424011451e+01,0.000000000000000000e+00,-8.377018214779335947e-01,0.000000000000000000e+00,-1.000000006678815501e+00,0.000000000000000000e+00 +3.374362003983549574e+00,3.702000000000000313e+01,0.000000000000000000e+00,1.064872613377107591e+01,0.000000000000000000e+00,-8.386408315816772374e-01,0.000000000000000000e+00,-1.000000009567796555e+00,0.000000000000000000e+00 +3.375301083444733674e+00,3.703000000000000114e+01,0.000000000000000000e+00,1.064793858339082711e+01,0.000000000000000000e+00,-8.395799110518463726e-01,0.000000000000000000e+00,-1.000000008382001537e+00,0.000000000000000000e+00 +3.376240232362778482e+00,3.703999999999999915e+01,0.000000000000000000e+00,1.064715009282575053e+01,0.000000000000000000e+00,-8.405190599777632166e-01,0.000000000000000000e+00,-1.000000006634828020e+00,0.000000000000000000e+00 +3.377179450830896101e+00,3.705000000000000426e+01,0.000000000000000000e+00,1.064636066180181473e+01,0.000000000000000000e+00,-8.414582784521121850e-01,0.000000000000000000e+00,-1.000000009848358573e+00,0.000000000000000000e+00 +3.378118738942361254e+00,3.706000000000000227e+01,0.000000000000000000e+00,1.064557029004457078e+01,0.000000000000000000e+00,-8.423975665728277162e-01,0.000000000000000000e+00,-1.000000007436397720e+00,0.000000000000000000e+00 +3.379058096790512611e+00,3.707000000000000028e+01,0.000000000000000000e+00,1.064477897727914701e+01,0.000000000000000000e+00,-8.433369244279644850e-01,0.000000000000000000e+00,-1.000000008945861607e+00,0.000000000000000000e+00 +3.379997524468752346e+00,3.707999999999999829e+01,0.000000000000000000e+00,1.064398672323025785e+01,0.000000000000000000e+00,-8.442763521146081640e-01,0.000000000000000000e+00,-1.000000007816584269e+00,0.000000000000000000e+00 +3.380937022070546139e+00,3.709000000000000341e+01,0.000000000000000000e+00,1.064319352762219495e+01,0.000000000000000000e+00,-8.452158497237456380e-01,0.000000000000000000e+00,-1.000000007553009329e+00,0.000000000000000000e+00 +3.381876589689423618e+00,3.710000000000000142e+01,0.000000000000000000e+00,1.064239939017883252e+01,0.000000000000000000e+00,-8.461554173497196629e-01,0.000000000000000000e+00,-1.000000009643292609e+00,0.000000000000000000e+00 +3.382816227418977917e+00,3.710999999999999943e+01,0.000000000000000000e+00,1.064160431062362377e+01,0.000000000000000000e+00,-8.470950550883353802e-01,0.000000000000000000e+00,-1.000000007528486945e+00,0.000000000000000000e+00 +3.383755935352867006e+00,3.711999999999999744e+01,0.000000000000000000e+00,1.064080828867959916e+01,0.000000000000000000e+00,-8.480347630292989214e-01,0.000000000000000000e+00,-1.000000006719739432e+00,0.000000000000000000e+00 +3.384695713584811916e+00,3.713000000000000256e+01,0.000000000000000000e+00,1.064001132406937167e+01,0.000000000000000000e+00,-8.489745412675588909e-01,0.000000000000000000e+00,-1.000000010712703391e+00,0.000000000000000000e+00 +3.385635562208598515e+00,3.714000000000000057e+01,0.000000000000000000e+00,1.063921341651513153e+01,0.000000000000000000e+00,-8.499143899014137693e-01,0.000000000000000000e+00,-1.000000006914053996e+00,0.000000000000000000e+00 +3.386575481318076619e+00,3.714999999999999858e+01,0.000000000000000000e+00,1.063841456573864264e+01,0.000000000000000000e+00,-8.508543090173906753e-01,0.000000000000000000e+00,-1.000000006862960644e+00,0.000000000000000000e+00 +3.387515471007160883e+00,3.716000000000000369e+01,0.000000000000000000e+00,1.063761477146125323e+01,0.000000000000000000e+00,-8.517942987129262233e-01,0.000000000000000000e+00,-1.000000010028247566e+00,0.000000000000000000e+00 +3.388455531369830354e+00,3.717000000000000171e+01,0.000000000000000000e+00,1.063681403340388520e+01,0.000000000000000000e+00,-8.527343590850230415e-01,0.000000000000000000e+00,-1.000000007840228244e+00,0.000000000000000000e+00 +3.389395662500128914e+00,3.717999999999999972e+01,0.000000000000000000e+00,1.063601235128703415e+01,0.000000000000000000e+00,-8.536744902226924836e-01,0.000000000000000000e+00,-1.000000007808266256e+00,0.000000000000000000e+00 +3.390335864492164841e+00,3.718999999999999773e+01,0.000000000000000000e+00,1.063520972483077642e+01,0.000000000000000000e+00,-8.546146922220698716e-01,0.000000000000000000e+00,-1.000000007391196544e+00,0.000000000000000000e+00 +3.391276137440111693e+00,3.720000000000000284e+01,0.000000000000000000e+00,1.063440615375476206e+01,0.000000000000000000e+00,-8.555549651769664976e-01,0.000000000000000000e+00,-1.000000008064972912e+00,0.000000000000000000e+00 +3.392216481438207865e+00,3.721000000000000085e+01,0.000000000000000000e+00,1.063360163777821654e+01,0.000000000000000000e+00,-8.564953091826464915e-01,0.000000000000000000e+00,-1.000000009295301417e+00,0.000000000000000000e+00 +3.393156896580757032e+00,3.721999999999999886e+01,0.000000000000000000e+00,1.063279617661993903e+01,0.000000000000000000e+00,-8.574357243339368884e-01,0.000000000000000000e+00,-1.000000008539225993e+00,0.000000000000000000e+00 +3.394097382962127707e+00,3.723000000000000398e+01,0.000000000000000000e+00,1.063198976999830236e+01,0.000000000000000000e+00,-8.583762107233384731e-01,0.000000000000000000e+00,-1.000000007270474001e+00,0.000000000000000000e+00 +3.395037940676754129e+00,3.724000000000000199e+01,0.000000000000000000e+00,1.063118241763125482e+01,0.000000000000000000e+00,-8.593167684448030919e-01,0.000000000000000000e+00,-1.000000006959724130e+00,0.000000000000000000e+00 +3.395978569819135817e+00,3.725000000000000000e+01,0.000000000000000000e+00,1.063037411923631836e+01,0.000000000000000000e+00,-8.602573975937313211e-01,0.000000000000000000e+00,-1.000000009076141838e+00,0.000000000000000000e+00 +3.396919270483838016e+00,3.725999999999999801e+01,0.000000000000000000e+00,1.062956487453058685e+01,0.000000000000000000e+00,-8.611980982669715790e-01,0.000000000000000000e+00,-1.000000007059146601e+00,0.000000000000000000e+00 +3.397860042765491695e+00,3.727000000000000313e+01,0.000000000000000000e+00,1.062875468323072425e+01,0.000000000000000000e+00,-8.621388705552665011e-01,0.000000000000000000e+00,-1.000000010404207940e+00,0.000000000000000000e+00 +3.398800886758793993e+00,3.728000000000000114e+01,0.000000000000000000e+00,1.062794354505297001e+01,0.000000000000000000e+00,-8.630797145583574137e-01,0.000000000000000000e+00,-1.000000006529835117e+00,0.000000000000000000e+00 +3.399741802558507331e+00,3.728999999999999915e+01,0.000000000000000000e+00,1.062713145971313011e+01,0.000000000000000000e+00,-8.640206303642146146e-01,0.000000000000000000e+00,-1.000000006934482322e+00,0.000000000000000000e+00 +3.400682790259460297e+00,3.730000000000000426e+01,0.000000000000000000e+00,1.062631842692658779e+01,0.000000000000000000e+00,-8.649616180716928060e-01,0.000000000000000000e+00,-1.000000009067353091e+00,0.000000000000000000e+00 +3.401623849956548096e+00,3.731000000000000227e+01,0.000000000000000000e+00,1.062550444640829284e+01,0.000000000000000000e+00,-8.659026777773133343e-01,0.000000000000000000e+00,-1.000000008372633697e+00,0.000000000000000000e+00 +3.402564981744731654e+00,3.732000000000000028e+01,0.000000000000000000e+00,1.062468951787276339e+01,0.000000000000000000e+00,-8.668438095733765891e-01,0.000000000000000000e+00,-1.000000008317499800e+00,0.000000000000000000e+00 +3.403506185719038513e+00,3.732999999999999829e+01,0.000000000000000000e+00,1.062387364103408949e+01,0.000000000000000000e+00,-8.677850135555120747e-01,0.000000000000000000e+00,-1.000000006350904691e+00,0.000000000000000000e+00 +3.404447461974563272e+00,3.734000000000000341e+01,0.000000000000000000e+00,1.062305681560592951e+01,0.000000000000000000e+00,-8.687262898170147185e-01,0.000000000000000000e+00,-1.000000007940586855e+00,0.000000000000000000e+00 +3.405388810606466254e+00,3.735000000000000142e+01,0.000000000000000000e+00,1.062223904130151197e+01,0.000000000000000000e+00,-8.696676384563927220e-01,0.000000000000000000e+00,-1.000000010532374528e+00,0.000000000000000000e+00 +3.406330231709975287e+00,3.735999999999999943e+01,0.000000000000000000e+00,1.062142031783363016e+01,0.000000000000000000e+00,-8.706090595698172674e-01,0.000000000000000000e+00,-1.000000005561120453e+00,0.000000000000000000e+00 +3.407271725380384808e+00,3.736999999999999744e+01,0.000000000000000000e+00,1.062060064491464395e+01,0.000000000000000000e+00,-8.715505532454626003e-01,0.000000000000000000e+00,-1.000000008510179894e+00,0.000000000000000000e+00 +3.408213291713056314e+00,3.738000000000000256e+01,0.000000000000000000e+00,1.061978002225648687e+01,0.000000000000000000e+00,-8.724921195861469192e-01,0.000000000000000000e+00,-1.000000006803986485e+00,0.000000000000000000e+00 +3.409154930803417916e+00,3.739000000000000057e+01,0.000000000000000000e+00,1.061895844957065194e+01,0.000000000000000000e+00,-8.734337586829156175e-01,0.000000000000000000e+00,-1.000000009907975551e+00,0.000000000000000000e+00 +3.410096642746965667e+00,3.739999999999999858e+01,0.000000000000000000e+00,1.061813592656820227e+01,0.000000000000000000e+00,-8.743754706357940165e-01,0.000000000000000000e+00,-1.000000007253391443e+00,0.000000000000000000e+00 +3.411038427639262682e+00,3.741000000000000369e+01,0.000000000000000000e+00,1.061731245295976223e+01,0.000000000000000000e+00,-8.753172555349223449e-01,0.000000000000000000e+00,-1.000000006298198629e+00,0.000000000000000000e+00 +3.411980285575939575e+00,3.742000000000000171e+01,0.000000000000000000e+00,1.061648802845552630e+01,0.000000000000000000e+00,-8.762591134775313817e-01,0.000000000000000000e+00,-1.000000010490809110e+00,0.000000000000000000e+00 +3.412922216652694463e+00,3.742999999999999972e+01,0.000000000000000000e+00,1.061566265276525201e+01,0.000000000000000000e+00,-8.772010445641680310e-01,0.000000000000000000e+00,-1.000000005259786162e+00,0.000000000000000000e+00 +3.413864220965293406e+00,3.743999999999999773e+01,0.000000000000000000e+00,1.061483632559825629e+01,0.000000000000000000e+00,-8.781430488817216773e-01,0.000000000000000000e+00,-1.000000010067166434e+00,0.000000000000000000e+00 +3.414806298609569968e+00,3.745000000000000284e+01,0.000000000000000000e+00,1.061400904666342804e+01,0.000000000000000000e+00,-8.790851265354822086e-01,0.000000000000000000e+00,-1.000000006339388126e+00,0.000000000000000000e+00 +3.415748449681425658e+00,3.746000000000000085e+01,0.000000000000000000e+00,1.061318081566921023e+01,0.000000000000000000e+00,-8.800272776133105657e-01,0.000000000000000000e+00,-1.000000007526845813e+00,0.000000000000000000e+00 +3.416690674276830375e+00,3.746999999999999886e+01,0.000000000000000000e+00,1.061235163232361600e+01,0.000000000000000000e+00,-8.809695022158071653e-01,0.000000000000000000e+00,-1.000000009065880269e+00,0.000000000000000000e+00 +3.417632972491821963e+00,3.748000000000000398e+01,0.000000000000000000e+00,1.061152149633421615e+01,0.000000000000000000e+00,-8.819118004393413646e-01,0.000000000000000000e+00,-1.000000006394246688e+00,0.000000000000000000e+00 +3.418575344422506213e+00,3.749000000000000199e+01,0.000000000000000000e+00,1.061069040740814273e+01,0.000000000000000000e+00,-8.828541723760515714e-01,0.000000000000000000e+00,-1.000000008950983954e+00,0.000000000000000000e+00 +3.419517790165058191e+00,3.750000000000000000e+01,0.000000000000000000e+00,1.060985836525209258e+01,0.000000000000000000e+00,-8.837966181270394683e-01,0.000000000000000000e+00,-1.000000006171839484e+00,0.000000000000000000e+00 +3.420460309815720912e+00,3.750999999999999801e+01,0.000000000000000000e+00,1.060902536957231845e+01,0.000000000000000000e+00,-8.847391377835194248e-01,0.000000000000000000e+00,-1.000000009490229491e+00,0.000000000000000000e+00 +3.421402903470806223e+00,3.752000000000000313e+01,0.000000000000000000e+00,1.060819142007463789e+01,0.000000000000000000e+00,-8.856817314475503577e-01,0.000000000000000000e+00,-1.000000006344108128e+00,0.000000000000000000e+00 +3.422345571226694805e+00,3.753000000000000114e+01,0.000000000000000000e+00,1.060735651646442257e+01,0.000000000000000000e+00,-8.866243992094194892e-01,0.000000000000000000e+00,-1.000000008161220810e+00,0.000000000000000000e+00 +3.423288313179836173e+00,3.753999999999999915e+01,0.000000000000000000e+00,1.060652065844660896e+01,0.000000000000000000e+00,-8.875671411702549252e-01,0.000000000000000000e+00,-1.000000006378147788e+00,0.000000000000000000e+00 +3.424231129426749121e+00,3.755000000000000426e+01,0.000000000000000000e+00,1.060568384572568768e+01,0.000000000000000000e+00,-8.885099574231811737e-01,0.000000000000000000e+00,-1.000000010417499974e+00,0.000000000000000000e+00 +3.425174020064020830e+00,3.756000000000000227e+01,0.000000000000000000e+00,1.060484607800571055e+01,0.000000000000000000e+00,-8.894528480702755813e-01,0.000000000000000000e+00,-1.000000005722496255e+00,0.000000000000000000e+00 +3.426116985188308650e+00,3.757000000000000028e+01,0.000000000000000000e+00,1.060400735499028180e+01,0.000000000000000000e+00,-8.903958131999595293e-01,0.000000000000000000e+00,-1.000000007705815763e+00,0.000000000000000000e+00 +3.427060024896338764e+00,3.757999999999999829e+01,0.000000000000000000e+00,1.060316767638257041e+01,0.000000000000000000e+00,-8.913388529152566075e-01,0.000000000000000000e+00,-1.000000007803227398e+00,0.000000000000000000e+00 +3.428003139284907075e+00,3.759000000000000341e+01,0.000000000000000000e+00,1.060232704188529596e+01,0.000000000000000000e+00,-8.922819673111843652e-01,0.000000000000000000e+00,-1.000000007438965000e+00,0.000000000000000000e+00 +3.428946328450879211e+00,3.760000000000000142e+01,0.000000000000000000e+00,1.060148545120073571e+01,0.000000000000000000e+00,-8.932251564841728886e-01,0.000000000000000000e+00,-1.000000008035975441e+00,0.000000000000000000e+00 +3.429889592491190520e+00,3.760999999999999943e+01,0.000000000000000000e+00,1.060064290403072285e+01,0.000000000000000000e+00,-8.941684205320641343e-01,0.000000000000000000e+00,-1.000000007021611070e+00,0.000000000000000000e+00 +3.430832931502846073e+00,3.761999999999999744e+01,0.000000000000000000e+00,1.059979940007664467e+01,0.000000000000000000e+00,-8.951117595503432778e-01,0.000000000000000000e+00,-1.000000007811894465e+00,0.000000000000000000e+00 +3.431776345582920662e+00,3.763000000000000256e+01,0.000000000000000000e+00,1.059895493903944441e+01,0.000000000000000000e+00,-8.960551736377878607e-01,0.000000000000000000e+00,-1.000000005837583306e+00,0.000000000000000000e+00 +3.432719834828560135e+00,3.764000000000000057e+01,0.000000000000000000e+00,1.059810952061961764e+01,0.000000000000000000e+00,-8.969986628889349278e-01,0.000000000000000000e+00,-1.000000008501524373e+00,0.000000000000000000e+00 +3.433663399336979616e+00,3.764999999999999858e+01,0.000000000000000000e+00,1.059726314451721585e+01,0.000000000000000000e+00,-8.979422274053762143e-01,0.000000000000000000e+00,-1.000000009237452359e+00,0.000000000000000000e+00 +3.434607039205465284e+00,3.766000000000000369e+01,0.000000000000000000e+00,1.059641581043183933e+01,0.000000000000000000e+00,-8.988858672825786877e-01,0.000000000000000000e+00,-1.000000005470723874e+00,0.000000000000000000e+00 +3.435550754531373485e+00,3.767000000000000171e+01,0.000000000000000000e+00,1.059556751806264252e+01,0.000000000000000000e+00,-8.998295826136496478e-01,0.000000000000000000e+00,-1.000000008586833022e+00,0.000000000000000000e+00 +3.436494545412131174e+00,3.767999999999999972e+01,0.000000000000000000e+00,1.059471826710833575e+01,0.000000000000000000e+00,-9.007733735025115207e-01,0.000000000000000000e+00,-1.000000006036100508e+00,0.000000000000000000e+00 +3.437438411945236361e+00,3.768999999999999773e+01,0.000000000000000000e+00,1.059386805726717462e+01,0.000000000000000000e+00,-9.017172400413138167e-01,0.000000000000000000e+00,-1.000000007204865593e+00,0.000000000000000000e+00 +3.438382354228257221e+00,3.770000000000000284e+01,0.000000000000000000e+00,1.059301688823697063e+01,0.000000000000000000e+00,-9.026611823311357918e-01,0.000000000000000000e+00,-1.000000009512606702e+00,0.000000000000000000e+00 +3.439326372358833872e+00,3.771000000000000085e+01,0.000000000000000000e+00,1.059216475971508231e+01,0.000000000000000000e+00,-9.036052004706924823e-01,0.000000000000000000e+00,-1.000000004400766196e+00,0.000000000000000000e+00 +3.440270466434677044e+00,3.771999999999999886e+01,0.000000000000000000e+00,1.059131167139841700e+01,0.000000000000000000e+00,-9.045492945506902194e-01,0.000000000000000000e+00,-1.000000009219042640e+00,0.000000000000000000e+00 +3.441214636553568518e+00,3.773000000000000398e+01,0.000000000000000000e+00,1.059045762298343796e+01,0.000000000000000000e+00,-9.054934646782859531e-01,0.000000000000000000e+00,-1.000000007435512650e+00,0.000000000000000000e+00 +3.442158882813361576e+00,3.774000000000000199e+01,0.000000000000000000e+00,1.058960261416614834e+01,0.000000000000000000e+00,-9.064377109451000614e-01,0.000000000000000000e+00,-1.000000006431534416e+00,0.000000000000000000e+00 +3.443103205311981441e+00,3.775000000000000000e+01,0.000000000000000000e+00,1.058874664464210547e+01,0.000000000000000000e+00,-9.073820334497932905e-01,0.000000000000000000e+00,-1.000000007607738883e+00,0.000000000000000000e+00 +3.444047604147424391e+00,3.775999999999999801e+01,0.000000000000000000e+00,1.058788971410641366e+01,0.000000000000000000e+00,-9.083264322924209377e-01,0.000000000000000000e+00,-1.000000006388439333e+00,0.000000000000000000e+00 +3.444992079417758646e+00,3.777000000000000313e+01,0.000000000000000000e+00,1.058703182225372252e+01,0.000000000000000000e+00,-9.092709075687889220e-01,0.000000000000000000e+00,-1.000000008154554365e+00,0.000000000000000000e+00 +3.445936631221124369e+00,3.778000000000000114e+01,0.000000000000000000e+00,1.058617296877823044e+01,0.000000000000000000e+00,-9.102154593798570392e-01,0.000000000000000000e+00,-1.000000006338304548e+00,0.000000000000000000e+00 +3.446881259655733665e+00,3.778999999999999915e+01,0.000000000000000000e+00,1.058531315337367928e+01,0.000000000000000000e+00,-9.111600878204536569e-01,0.000000000000000000e+00,-1.000000006317760759e+00,0.000000000000000000e+00 +3.447825964819870581e+00,3.780000000000000426e+01,0.000000000000000000e+00,1.058445237573335973e+01,0.000000000000000000e+00,-9.121047929905591323e-01,0.000000000000000000e+00,-1.000000009485136232e+00,0.000000000000000000e+00 +3.448770746811891996e+00,3.781000000000000227e+01,0.000000000000000000e+00,1.058359063555010593e+01,0.000000000000000000e+00,-9.130495749915418235e-01,0.000000000000000000e+00,-1.000000005292850602e+00,0.000000000000000000e+00 +3.449715605730226287e+00,3.782000000000000028e+01,0.000000000000000000e+00,1.058272793251629373e+01,0.000000000000000000e+00,-9.139944339148772245e-01,0.000000000000000000e+00,-1.000000007071680130e+00,0.000000000000000000e+00 +3.450660541673375103e+00,3.782999999999999829e+01,0.000000000000000000e+00,1.058186426632384958e+01,0.000000000000000000e+00,-9.149393698647083628e-01,0.000000000000000000e+00,-1.000000008251707539e+00,0.000000000000000000e+00 +3.451605554739912485e+00,3.784000000000000341e+01,0.000000000000000000e+00,1.058099963666423804e+01,0.000000000000000000e+00,-9.158843829390436175e-01,0.000000000000000000e+00,-1.000000006243470851e+00,0.000000000000000000e+00 +3.452550645028484855e+00,3.785000000000000142e+01,0.000000000000000000e+00,1.058013404322846718e+01,0.000000000000000000e+00,-9.168294732335167119e-01,0.000000000000000000e+00,-1.000000006411764231e+00,0.000000000000000000e+00 +3.453495812637811913e+00,3.785999999999999943e+01,0.000000000000000000e+00,1.057926748570709030e+01,0.000000000000000000e+00,-9.177746408489041441e-01,0.000000000000000000e+00,-1.000000006164485367e+00,0.000000000000000000e+00 +3.454441057666686632e+00,3.786999999999999744e+01,0.000000000000000000e+00,1.057839996379020064e+01,0.000000000000000000e+00,-9.187198858836057580e-01,0.000000000000000000e+00,-1.000000008872399482e+00,0.000000000000000000e+00 +3.455386380213974373e+00,3.788000000000000256e+01,0.000000000000000000e+00,1.057753147716743314e+01,0.000000000000000000e+00,-9.196652084392809012e-01,0.000000000000000000e+00,-1.000000005979117423e+00,0.000000000000000000e+00 +3.456331780378614660e+00,3.789000000000000057e+01,0.000000000000000000e+00,1.057666202552796086e+01,0.000000000000000000e+00,-9.206106086095736663e-01,0.000000000000000000e+00,-1.000000006816678555e+00,0.000000000000000000e+00 +3.457277258259619401e+00,3.789999999999999858e+01,0.000000000000000000e+00,1.057579160856050216e+01,0.000000000000000000e+00,-9.215560864970234745e-01,0.000000000000000000e+00,-1.000000004815005727e+00,0.000000000000000000e+00 +3.458222813956074670e+00,3.791000000000000369e+01,0.000000000000000000e+00,1.057492022595331171e+01,0.000000000000000000e+00,-9.225016421980317682e-01,0.000000000000000000e+00,-1.000000009298367409e+00,0.000000000000000000e+00 +3.459168447567140259e+00,3.792000000000000171e+01,0.000000000000000000e+00,1.057404787739418595e+01,0.000000000000000000e+00,-9.234472758178903229e-01,0.000000000000000000e+00,-1.000000005751249699e+00,0.000000000000000000e+00 +3.460114159192049677e+00,3.792999999999999972e+01,0.000000000000000000e+00,1.057317456257045407e+01,0.000000000000000000e+00,-9.243929874482387232e-01,0.000000000000000000e+00,-1.000000007466562479e+00,0.000000000000000000e+00 +3.461059948930110153e+00,3.793999999999999773e+01,0.000000000000000000e+00,1.057230028116899057e+01,0.000000000000000000e+00,-9.253387771933608841e-01,0.000000000000000000e+00,-1.000000005887819565e+00,0.000000000000000000e+00 +3.462005816880703080e+00,3.795000000000000284e+01,0.000000000000000000e+00,1.057142503287620272e+01,0.000000000000000000e+00,-9.262846451495226896e-01,0.000000000000000000e+00,-1.000000006358582327e+00,0.000000000000000000e+00 +3.462951763143283568e+00,3.796000000000000085e+01,0.000000000000000000e+00,1.057054881737803775e+01,0.000000000000000000e+00,-9.272305914181181441e-01,0.000000000000000000e+00,-1.000000006278041642e+00,0.000000000000000000e+00 +3.463897787817381779e+00,3.796999999999999886e+01,0.000000000000000000e+00,1.056967163435997747e+01,0.000000000000000000e+00,-9.281766160981556046e-01,0.000000000000000000e+00,-1.000000007015254155e+00,0.000000000000000000e+00 +3.464843891002602039e+00,3.798000000000000398e+01,0.000000000000000000e+00,1.056879348350704007e+01,0.000000000000000000e+00,-9.291227192900129994e-01,0.000000000000000000e+00,-1.000000005968933792e+00,0.000000000000000000e+00 +3.465790072798623278e+00,3.799000000000000199e+01,0.000000000000000000e+00,1.056791436450377830e+01,0.000000000000000000e+00,-9.300689010916817212e-01,0.000000000000000000e+00,-1.000000006489250248e+00,0.000000000000000000e+00 +3.466736333305198592e+00,3.800000000000000000e+01,0.000000000000000000e+00,1.056703427703428133e+01,0.000000000000000000e+00,-9.310151616043975675e-01,0.000000000000000000e+00,-1.000000005972540462e+00,0.000000000000000000e+00 +3.467682672622156570e+00,3.800999999999999801e+01,0.000000000000000000e+00,1.056615322078217112e+01,0.000000000000000000e+00,-9.319615009270075801e-01,0.000000000000000000e+00,-1.000000007765490473e+00,0.000000000000000000e+00 +3.468629090849400409e+00,3.802000000000000313e+01,0.000000000000000000e+00,1.056527119543060422e+01,0.000000000000000000e+00,-9.329079191616008737e-01,0.000000000000000000e+00,-1.000000005296448391e+00,0.000000000000000000e+00 +3.469575588086908802e+00,3.803000000000000114e+01,0.000000000000000000e+00,1.056438820066226825e+01,0.000000000000000000e+00,-9.338544164041221451e-01,0.000000000000000000e+00,-1.000000005875242959e+00,0.000000000000000000e+00 +3.470522164434735046e+00,3.803999999999999915e+01,0.000000000000000000e+00,1.056350423615938716e+01,0.000000000000000000e+00,-9.348009927575096079e-01,0.000000000000000000e+00,-1.000000006893461579e+00,0.000000000000000000e+00 +3.471468819993007937e+00,3.805000000000000426e+01,0.000000000000000000e+00,1.056261930160371421e+01,0.000000000000000000e+00,-9.357476483223082786e-01,0.000000000000000000e+00,-1.000000003763109380e+00,0.000000000000000000e+00 +3.472415554861932208e+00,3.806000000000000227e+01,0.000000000000000000e+00,1.056173339667653366e+01,0.000000000000000000e+00,-9.366943831947951438e-01,0.000000000000000000e+00,-1.000000009729252737e+00,0.000000000000000000e+00 +3.473362369141787642e+00,3.807000000000000028e+01,0.000000000000000000e+00,1.056084652105866439e+01,0.000000000000000000e+00,-9.376411974838624319e-01,0.000000000000000000e+00,-1.000000002367821716e+00,0.000000000000000000e+00 +3.474309262932930409e+00,3.807999999999999829e+01,0.000000000000000000e+00,1.055995867443044745e+01,0.000000000000000000e+00,-9.385880912772470719e-01,0.000000000000000000e+00,-1.000000008788153982e+00,0.000000000000000000e+00 +3.475256236335791726e+00,3.809000000000000341e+01,0.000000000000000000e+00,1.055906985647176555e+01,0.000000000000000000e+00,-9.395350646884305101e-01,0.000000000000000000e+00,-1.000000004587427993e+00,0.000000000000000000e+00 +3.476203289450879197e+00,3.810000000000000142e+01,0.000000000000000000e+00,1.055818006686201826e+01,0.000000000000000000e+00,-9.404821178078627275e-01,0.000000000000000000e+00,-1.000000004981659307e+00,0.000000000000000000e+00 +3.477150422378777250e+00,3.810999999999999943e+01,0.000000000000000000e+00,1.055728930528014331e+01,0.000000000000000000e+00,-9.414292507404788957e-01,0.000000000000000000e+00,-1.000000007355912102e+00,0.000000000000000000e+00 +3.478097635220145367e+00,3.811999999999999744e+01,0.000000000000000000e+00,1.055639757140460233e+01,0.000000000000000000e+00,-9.423764635888146612e-01,0.000000000000000000e+00,-1.000000005137340331e+00,0.000000000000000000e+00 +3.479044928075720300e+00,3.813000000000000256e+01,0.000000000000000000e+00,1.055550486491338269e+01,0.000000000000000000e+00,-9.433237564492561456e-01,0.000000000000000000e+00,-1.000000005610628406e+00,0.000000000000000000e+00 +3.479992301046315184e+00,3.814000000000000057e+01,0.000000000000000000e+00,1.055461118548400279e+01,0.000000000000000000e+00,-9.442711294251662224e-01,0.000000000000000000e+00,-1.000000004180987334e+00,0.000000000000000000e+00 +3.480939754232819539e+00,3.814999999999999858e+01,0.000000000000000000e+00,1.055371653279350497e+01,0.000000000000000000e+00,-9.452185826156317416e-01,0.000000000000000000e+00,-1.000000006147219400e+00,0.000000000000000000e+00 +3.481887287736199710e+00,3.816000000000000369e+01,0.000000000000000000e+00,1.055282090651845905e+01,0.000000000000000000e+00,-9.461661161248366980e-01,0.000000000000000000e+00,-1.000000006913327466e+00,0.000000000000000000e+00 +3.482834901657499316e+00,3.817000000000000171e+01,0.000000000000000000e+00,1.055192430633495704e+01,0.000000000000000000e+00,-9.471137300526876190e-01,0.000000000000000000e+00,-1.000000003862924647e+00,0.000000000000000000e+00 +3.483782596097839246e+00,3.817999999999999972e+01,0.000000000000000000e+00,1.055102673191861662e+01,0.000000000000000000e+00,-9.480614244966882875e-01,0.000000000000000000e+00,-1.000000006244539774e+00,0.000000000000000000e+00 +3.484730371158416773e+00,3.818999999999999773e+01,0.000000000000000000e+00,1.055012818294458299e+01,0.000000000000000000e+00,-9.490091995631843025e-01,0.000000000000000000e+00,-1.000000003528127124e+00,0.000000000000000000e+00 +3.485678226940507329e+00,3.820000000000000284e+01,0.000000000000000000e+00,1.054922865908751994e+01,0.000000000000000000e+00,-9.499570553486189617e-01,0.000000000000000000e+00,-1.000000004956935751e+00,0.000000000000000000e+00 +3.486626163545463175e+00,3.821000000000000085e+01,0.000000000000000000e+00,1.054832816002161877e+01,0.000000000000000000e+00,-9.509049919582738264e-01,0.000000000000000000e+00,-1.000000005931683367e+00,0.000000000000000000e+00 +3.487574181074714730e+00,3.821999999999999886e+01,0.000000000000000000e+00,1.054742668542058937e+01,0.000000000000000000e+00,-9.518530094931488827e-01,0.000000000000000000e+00,-1.000000005806871428e+00,0.000000000000000000e+00 +3.488522279629770129e+00,3.823000000000000398e+01,0.000000000000000000e+00,1.054652423495766378e+01,0.000000000000000000e+00,-9.528011080537097666e-01,0.000000000000000000e+00,-1.000000003936962312e+00,0.000000000000000000e+00 +3.489470459312215223e+00,3.824000000000000199e+01,0.000000000000000000e+00,1.054562080830559623e+01,0.000000000000000000e+00,-9.537492877398876523e-01,0.000000000000000000e+00,-1.000000003625953537e+00,0.000000000000000000e+00 +3.490418720223713578e+00,3.825000000000000000e+01,0.000000000000000000e+00,1.054471640513666308e+01,0.000000000000000000e+00,-9.546975486548243683e-01,0.000000000000000000e+00,-1.000000006198436653e+00,0.000000000000000000e+00 +3.491367062466007365e+00,3.825999999999999801e+01,0.000000000000000000e+00,1.054381102512265933e+01,0.000000000000000000e+00,-9.556458909029964532e-01,0.000000000000000000e+00,-1.000000003103471924e+00,0.000000000000000000e+00 +3.492315486140916914e+00,3.827000000000000313e+01,0.000000000000000000e+00,1.054290466793489678e+01,0.000000000000000000e+00,-9.565943145808495363e-01,0.000000000000000000e+00,-1.000000003565278517e+00,0.000000000000000000e+00 +3.493263991350341158e+00,3.828000000000000114e+01,0.000000000000000000e+00,1.054199733324421118e+01,0.000000000000000000e+00,-9.575428197936555197e-01,0.000000000000000000e+00,-1.000000004954610500e+00,0.000000000000000000e+00 +3.494212578196257635e+00,3.828999999999999915e+01,0.000000000000000000e+00,1.054108902072095333e+01,0.000000000000000000e+00,-9.584914066442716818e-01,0.000000000000000000e+00,-1.000000004643097240e+00,0.000000000000000000e+00 +3.495161246780722042e+00,3.830000000000000426e+01,0.000000000000000000e+00,1.054017973003499087e+01,0.000000000000000000e+00,-9.594400752331407878e-01,0.000000000000000000e+00,-1.000000003949846006e+00,0.000000000000000000e+00 +3.496109997205869568e+00,3.831000000000000227e+01,0.000000000000000000e+00,1.053926946085571004e+01,0.000000000000000000e+00,-9.603888256620355390e-01,0.000000000000000000e+00,-1.000000004191960556e+00,0.000000000000000000e+00 +3.497058829573914007e+00,3.832000000000000028e+01,0.000000000000000000e+00,1.053835821285201391e+01,0.000000000000000000e+00,-9.613376580340572408e-01,0.000000000000000000e+00,-1.000000002738387739e+00,0.000000000000000000e+00 +3.498007743987148199e+00,3.832999999999999829e+01,0.000000000000000000e+00,1.053744598569232060e+01,0.000000000000000000e+00,-9.622865724498899098e-01,0.000000000000000000e+00,-1.000000002875800043e+00,0.000000000000000000e+00 +3.498956740547944477e+00,3.834000000000000341e+01,0.000000000000000000e+00,1.053653277904456509e+01,0.000000000000000000e+00,-9.632355690134154491e-01,0.000000000000000000e+00,-1.000000003942830729e+00,0.000000000000000000e+00 +3.499905819358754666e+00,3.835000000000000142e+01,0.000000000000000000e+00,1.053561859257619560e+01,0.000000000000000000e+00,-9.641846478279678667e-01,0.000000000000000000e+00,-1.000000003306333429e+00,0.000000000000000000e+00 +3.500854980522110083e+00,3.835999999999999943e+01,0.000000000000000000e+00,1.053470342595417364e+01,0.000000000000000000e+00,-9.651338089944616616e-01,0.000000000000000000e+00,-1.000000004246544449e+00,0.000000000000000000e+00 +3.501804224140621535e+00,3.836999999999999744e+01,0.000000000000000000e+00,1.053378727884497579e+01,0.000000000000000000e+00,-9.660830526170043342e-01,0.000000000000000000e+00,-1.000000000186457516e+00,0.000000000000000000e+00 +3.502753550316980213e+00,3.838000000000000256e+01,0.000000000000000000e+00,1.053287015091459011e+01,0.000000000000000000e+00,-9.670323787935398707e-01,0.000000000000000000e+00,-1.000000004258011277e+00,0.000000000000000000e+00 +3.503702959153956353e+00,3.839000000000000057e+01,0.000000000000000000e+00,1.053195204182852152e+01,0.000000000000000000e+00,-9.679817876345585548e-01,0.000000000000000000e+00,-1.000000001997586541e+00,0.000000000000000000e+00 +3.504652450754401016e+00,3.839999999999999858e+01,0.000000000000000000e+00,1.053103295125177929e+01,0.000000000000000000e+00,-9.689312792368997007e-01,0.000000000000000000e+00,-1.000000000621528162e+00,0.000000000000000000e+00 +3.505602025221244755e+00,3.841000000000000369e+01,0.000000000000000000e+00,1.053011287884888958e+01,0.000000000000000000e+00,-9.698808537043337452e-01,0.000000000000000000e+00,-1.000000003399165616e+00,0.000000000000000000e+00 +3.506551682657499391e+00,3.842000000000000171e+01,0.000000000000000000e+00,1.052919182428388822e+01,0.000000000000000000e+00,-9.708305111438164658e-01,0.000000000000000000e+00,-1.000000001780899206e+00,0.000000000000000000e+00 +3.507501423166256682e+00,3.842999999999999972e+01,0.000000000000000000e+00,1.052826978722031726e+01,0.000000000000000000e+00,-9.717802516542652924e-01,0.000000000000000000e+00,-1.000000001004722527e+00,0.000000000000000000e+00 +3.508451246850689653e+00,3.843999999999999773e+01,0.000000000000000000e+00,1.052734676732123198e+01,0.000000000000000000e+00,-9.727300753396523891e-01,0.000000000000000000e+00,-1.000000000397345490e+00,0.000000000000000000e+00 +3.509401153814051266e+00,3.845000000000000284e+01,0.000000000000000000e+00,1.052642276424919565e+01,0.000000000000000000e+00,-9.736799823033913670e-01,0.000000000000000000e+00,-1.000000001253016579e+00,0.000000000000000000e+00 +3.510351144159675751e+00,3.846000000000000085e+01,0.000000000000000000e+00,1.052549777766627948e+01,0.000000000000000000e+00,-9.746299726502063443e-01,0.000000000000000000e+00,-1.000000000927199428e+00,0.000000000000000000e+00 +3.511301217990979051e+00,3.846999999999999886e+01,0.000000000000000000e+00,1.052457180723406083e+01,0.000000000000000000e+00,-9.755800464823903839e-01,0.000000000000000000e+00,-9.999999987446468452e-01,0.000000000000000000e+00 +3.512251375411457488e+00,3.848000000000000398e+01,0.000000000000000000e+00,1.052364485261362503e+01,0.000000000000000000e+00,-9.765302039016758862e-01,0.000000000000000000e+00,-9.999999999300648312e-01,0.000000000000000000e+00 +3.513201616524689097e+00,3.849000000000000199e+01,0.000000000000000000e+00,1.052271691346556537e+01,0.000000000000000000e+00,-9.774804450148408819e-01,0.000000000000000000e+00,-9.999999979016394036e-01,0.000000000000000000e+00 +3.514151941434333182e+00,3.850000000000000000e+01,0.000000000000000000e+00,1.052178798944997773e+01,0.000000000000000000e+00,-9.784307699224908950e-01,0.000000000000000000e+00,-9.999999998468808160e-01,0.000000000000000000e+00 +3.515102350244131202e+00,3.850999999999999801e+01,0.000000000000000000e+00,1.052085808022646596e+01,0.000000000000000000e+00,-9.793811787321433648e-01,0.000000000000000000e+00,-9.999999991833902202e-01,0.000000000000000000e+00 +3.516052843057905886e+00,3.852000000000000313e+01,0.000000000000000000e+00,1.051992718545413474e+01,0.000000000000000000e+00,-9.803316715451420027e-01,0.000000000000000000e+00,-9.999999952297764505e-01,0.000000000000000000e+00 +3.517003419979562562e+00,3.853000000000000114e+01,0.000000000000000000e+00,1.051899530479159495e+01,0.000000000000000000e+00,-9.812822484622640840e-01,0.000000000000000000e+00,-9.999999990964523189e-01,0.000000000000000000e+00 +3.517954081113087828e+00,3.853999999999999915e+01,0.000000000000000000e+00,1.051806243789696360e+01,0.000000000000000000e+00,-9.822329095949303701e-01,0.000000000000000000e+00,-9.999999943726602947e-01,0.000000000000000000e+00 +3.518904826562550880e+00,3.855000000000000426e+01,0.000000000000000000e+00,1.051712858442785326e+01,0.000000000000000000e+00,-9.831836550390433693e-01,0.000000000000000000e+00,-9.999999960943609656e-01,0.000000000000000000e+00 +3.519855656432103519e+00,3.856000000000000227e+01,0.000000000000000000e+00,1.051619374404138618e+01,0.000000000000000000e+00,-9.841344849048824228e-01,0.000000000000000000e+00,-9.999999937477069833e-01,0.000000000000000000e+00 +3.520806570825979698e+00,3.857000000000000028e+01,0.000000000000000000e+00,1.051525791639418017e+01,0.000000000000000000e+00,-9.850853992928132463e-01,0.000000000000000000e+00,-9.999999945019688585e-01,0.000000000000000000e+00 +3.521757569848496416e+00,3.857999999999999829e+01,0.000000000000000000e+00,1.051432110114235741e+01,0.000000000000000000e+00,-9.860363983101011476e-01,0.000000000000000000e+00,-9.999999917735693522e-01,0.000000000000000000e+00 +3.522708653604052831e+00,3.859000000000000341e+01,0.000000000000000000e+00,1.051338329794153736e+01,0.000000000000000000e+00,-9.869874820578334873e-01,0.000000000000000000e+00,-9.999999907624605999e-01,0.000000000000000000e+00 +3.523659822197131586e+00,3.860000000000000142e+01,0.000000000000000000e+00,1.051244450644684214e+01,0.000000000000000000e+00,-9.879386506421257153e-01,0.000000000000000000e+00,-9.999999907744037131e-01,0.000000000000000000e+00 +3.524611075732298371e+00,3.860999999999999943e+01,0.000000000000000000e+00,1.051150472631289112e+01,0.000000000000000000e+00,-9.888899041685164093e-01,0.000000000000000000e+00,-9.999999852263977695e-01,0.000000000000000000e+00 +3.525562414314201476e+00,3.861999999999999744e+01,0.000000000000000000e+00,1.051056395719380099e+01,0.000000000000000000e+00,-9.898412427363649790e-01,0.000000000000000000e+00,-9.999999871617533120e-01,0.000000000000000000e+00 +3.526513838047573568e+00,3.863000000000000256e+01,0.000000000000000000e+00,1.050962219874319103e+01,0.000000000000000000e+00,-9.907926664575225084e-01,0.000000000000000000e+00,-9.999999801832151203e-01,0.000000000000000000e+00 +3.527465347037230359e+00,3.864000000000000057e+01,0.000000000000000000e+00,1.050867945061417075e+01,0.000000000000000000e+00,-9.917441754283233823e-01,0.000000000000000000e+00,-9.999999812522254450e-01,0.000000000000000000e+00 +3.528416941388071049e+00,3.864999999999999858e+01,0.000000000000000000e+00,1.050773571245935400e+01,0.000000000000000000e+00,-9.926957697613237874e-01,0.000000000000000000e+00,-9.999999739736591398e-01,0.000000000000000000e+00 +3.529368621205078771e+00,3.866000000000000369e+01,0.000000000000000000e+00,1.050679098393084310e+01,0.000000000000000000e+00,-9.936474495535628781e-01,0.000000000000000000e+00,-9.999999694174910303e-01,0.000000000000000000e+00 +3.530320386593321036e+00,3.867000000000000171e+01,0.000000000000000000e+00,1.050584526468024293e+01,0.000000000000000000e+00,-9.945992149126976489e-01,0.000000000000000000e+00,-9.999999609977534565e-01,0.000000000000000000e+00 +3.531272237657948843e+00,3.867999999999999972e+01,0.000000000000000000e+00,1.050489855435865039e+01,0.000000000000000000e+00,-9.955510659402010409e-01,0.000000000000000000e+00,-9.999999480135192131e-01,0.000000000000000000e+00 +3.532224174504197567e+00,3.868999999999999773e+01,0.000000000000000000e+00,1.050395085261665962e+01,0.000000000000000000e+00,-9.965030027369620180e-01,0.000000000000000000e+00,-9.999999278030429206e-01,0.000000000000000000e+00 +3.533176197237387406e+00,3.870000000000000284e+01,0.000000000000000000e+00,1.050300215910436208e+01,0.000000000000000000e+00,-9.974550254014187267e-01,0.000000000000000000e+00,-9.999998879089063708e-01,0.000000000000000000e+00 +3.534128305962922934e+00,3.871000000000000085e+01,0.000000000000000000e+00,1.050205247347134829e+01,0.000000000000000000e+00,-9.984071340202311795e-01,0.000000000000000000e+00,-9.999997629901256069e-01,0.000000000000000000e+00 +3.535080500786293101e+00,3.871999999999999886e+01,0.000000000000000000e+00,1.050110179536671851e+01,0.000000000000000000e+00,-9.993593286179216495e-01,0.000000000000000000e+00,-6.727857980971431173e-01,0.000000000000000000e+00 +3.536032781813071679e+00,3.873000000000000398e+01,0.000000000000000000e+00,1.050015012443914131e+01,0.000000000000000000e+00,-1.000000009768535758e+00,0.000000000000000000e+00,1.331986913231571269e-09,0.000000000000000000e+00 +3.536985149148918151e+00,3.874000000000000199e+01,0.000000000000000000e+00,1.049919775709399161e+01,0.000000000000000000e+00,-1.000000009767267217e+00,0.000000000000000000e+00,-5.550802009066833936e-10,0.000000000000000000e+00 +3.537937602872655685e+00,3.875000000000000000e+01,0.000000000000000000e+00,1.049824530336095130e+01,0.000000000000000000e+00,-1.000000009767795905e+00,0.000000000000000000e+00,-4.734420902236212219e-10,0.000000000000000000e+00 +3.538890143007796141e+00,3.875999999999999801e+01,0.000000000000000000e+00,1.049729276321650673e+01,0.000000000000000000e+00,-1.000000009768246878e+00,0.000000000000000000e+00,-3.745703629596014956e-10,0.000000000000000000e+00 +3.539842769577862036e+00,3.877000000000000313e+01,0.000000000000000000e+00,1.049634013663713539e+01,0.000000000000000000e+00,-1.000000009768603704e+00,0.000000000000000000e+00,-2.510116187605813913e-10,0.000000000000000000e+00 +3.540795482606386546e+00,3.878000000000000114e+01,0.000000000000000000e+00,1.049538742359930410e+01,0.000000000000000000e+00,-1.000000009768842846e+00,0.000000000000000000e+00,-9.531516589893741352e-11,0.000000000000000000e+00 +3.541748282116913948e+00,3.878999999999999915e+01,0.000000000000000000e+00,1.049443462407946903e+01,0.000000000000000000e+00,-1.000000009768933662e+00,0.000000000000000000e+00,-1.856496304465185476e-09,0.000000000000000000e+00 +3.542701168132998735e+00,3.880000000000000426e+01,0.000000000000000000e+00,1.049348173805407569e+01,0.000000000000000000e+00,-1.000000009770702691e+00,0.000000000000000000e+00,3.425130880016944413e-10,0.000000000000000000e+00 +3.543654140678206055e+00,3.881000000000000227e+01,0.000000000000000000e+00,1.049252876549955715e+01,0.000000000000000000e+00,-1.000000009770376286e+00,0.000000000000000000e+00,-1.316342313485929744e-09,0.000000000000000000e+00 +3.544607199776112161e+00,3.882000000000000028e+01,0.000000000000000000e+00,1.049157570639233938e+01,0.000000000000000000e+00,-1.000000009771630838e+00,0.000000000000000000e+00,9.984656096939117952e-10,0.000000000000000000e+00 +3.545560345450303519e+00,3.882999999999999829e+01,0.000000000000000000e+00,1.049062256070883414e+01,0.000000000000000000e+00,-1.000000009770679155e+00,0.000000000000000000e+00,-5.285377155994273624e-10,0.000000000000000000e+00 +3.546513577724377697e+00,3.884000000000000341e+01,0.000000000000000000e+00,1.048966932842544608e+01,0.000000000000000000e+00,-1.000000009771182974e+00,0.000000000000000000e+00,-1.977003300172590319e-09,0.000000000000000000e+00 +3.547466896621942922e+00,3.885000000000000142e+01,0.000000000000000000e+00,1.048871600951856564e+01,0.000000000000000000e+00,-1.000000009773067688e+00,0.000000000000000000e+00,5.675682349703224464e-10,0.000000000000000000e+00 +3.548420302166618079e+00,3.885999999999999943e+01,0.000000000000000000e+00,1.048776260396457261e+01,0.000000000000000000e+00,-1.000000009772526566e+00,0.000000000000000000e+00,-7.044472089433113665e-10,0.000000000000000000e+00 +3.549373794382033154e+00,3.886999999999999744e+01,0.000000000000000000e+00,1.048680911173983965e+01,0.000000000000000000e+00,-1.000000009773198251e+00,0.000000000000000000e+00,7.730750761986430122e-11,0.000000000000000000e+00 +3.550327373291827904e+00,3.888000000000000256e+01,0.000000000000000000e+00,1.048585553282072524e+01,0.000000000000000000e+00,-1.000000009773124532e+00,0.000000000000000000e+00,-9.872109232125198039e-10,0.000000000000000000e+00 +3.551281038919654076e+00,3.889000000000000057e+01,0.000000000000000000e+00,1.048490186718357897e+01,0.000000000000000000e+00,-1.000000009774066001e+00,0.000000000000000000e+00,1.583118807088020779e-11,0.000000000000000000e+00 +3.552234791289173188e+00,3.889999999999999858e+01,0.000000000000000000e+00,1.048394811480473798e+01,0.000000000000000000e+00,-1.000000009774050902e+00,0.000000000000000000e+00,1.140440227019388288e-09,0.000000000000000000e+00 +3.553188630424057859e+00,3.891000000000000369e+01,0.000000000000000000e+00,1.048299427566053055e+01,0.000000000000000000e+00,-1.000000009772963105e+00,0.000000000000000000e+00,-3.461511252597032751e-09,0.000000000000000000e+00 +3.554142556347991366e+00,3.892000000000000171e+01,0.000000000000000000e+00,1.048204034972727428e+01,0.000000000000000000e+00,-1.000000009776265131e+00,0.000000000000000000e+00,1.834054640511582547e-09,0.000000000000000000e+00 +3.555096569084668090e+00,3.892999999999999972e+01,0.000000000000000000e+00,1.048108633698127079e+01,0.000000000000000000e+00,-1.000000009774515419e+00,0.000000000000000000e+00,-2.484824764169536035e-09,0.000000000000000000e+00 +3.556050668657793068e+00,3.893999999999999773e+01,0.000000000000000000e+00,1.048013223739881994e+01,0.000000000000000000e+00,-1.000000009776886190e+00,0.000000000000000000e+00,1.154452889501012943e-09,0.000000000000000000e+00 +3.557004855091081996e+00,3.895000000000000284e+01,0.000000000000000000e+00,1.047917805095620203e+01,0.000000000000000000e+00,-1.000000009775784626e+00,0.000000000000000000e+00,-9.002563112569981901e-10,0.000000000000000000e+00 +3.557959128408261229e+00,3.896000000000000085e+01,0.000000000000000000e+00,1.047822377762969381e+01,0.000000000000000000e+00,-1.000000009776643717e+00,0.000000000000000000e+00,-8.361919214117356645e-10,0.000000000000000000e+00 +3.558913488633068667e+00,3.896999999999999886e+01,0.000000000000000000e+00,1.047726941739555606e+01,0.000000000000000000e+00,-1.000000009777441745e+00,0.000000000000000000e+00,1.352115971495825772e-09,0.000000000000000000e+00 +3.559867935789251980e+00,3.898000000000000398e+01,0.000000000000000000e+00,1.047631497023004066e+01,0.000000000000000000e+00,-1.000000009776151222e+00,0.000000000000000000e+00,-2.126387846754180781e-09,0.000000000000000000e+00 +3.560822469900570386e+00,3.899000000000000199e+01,0.000000000000000000e+00,1.047536043610939060e+01,0.000000000000000000e+00,-1.000000009778180932e+00,0.000000000000000000e+00,4.337984907586192674e-10,0.000000000000000000e+00 +3.561777090990793759e+00,3.900000000000000000e+01,0.000000000000000000e+00,1.047440581500983292e+01,0.000000000000000000e+00,-1.000000009777766818e+00,0.000000000000000000e+00,-7.070387315095659463e-10,0.000000000000000000e+00 +3.562731799083702633e+00,3.900999999999999801e+01,0.000000000000000000e+00,1.047345110690758929e+01,0.000000000000000000e+00,-1.000000009778441834e+00,0.000000000000000000e+00,-1.642784988469152852e-09,0.000000000000000000e+00 +3.563686594203088198e+00,3.902000000000000313e+01,0.000000000000000000e+00,1.047249631177886720e+01,0.000000000000000000e+00,-1.000000009780010357e+00,0.000000000000000000e+00,1.531017883954534221e-09,0.000000000000000000e+00 +3.564641476372753193e+00,3.903000000000000114e+01,0.000000000000000000e+00,1.047154142959986345e+01,0.000000000000000000e+00,-1.000000009778548415e+00,0.000000000000000000e+00,-9.202940849019349806e-10,0.000000000000000000e+00 +3.565596445616510568e+00,3.903999999999999915e+01,0.000000000000000000e+00,1.047058646034676777e+01,0.000000000000000000e+00,-1.000000009779427268e+00,0.000000000000000000e+00,-1.194785244512043035e-09,0.000000000000000000e+00 +3.566551501958184378e+00,3.905000000000000426e+01,0.000000000000000000e+00,1.046963140399575387e+01,0.000000000000000000e+00,-1.000000009780568355e+00,0.000000000000000000e+00,7.127607367574336102e-10,0.000000000000000000e+00 +3.567506645421609779e+00,3.906000000000000227e+01,0.000000000000000000e+00,1.046867626052298661e+01,0.000000000000000000e+00,-1.000000009779887566e+00,0.000000000000000000e+00,-1.031154004220268593e-09,0.000000000000000000e+00 +3.568461876030632585e+00,3.907000000000000028e+01,0.000000000000000000e+00,1.046772102990462194e+01,0.000000000000000000e+00,-1.000000009780872556e+00,0.000000000000000000e+00,-5.773563635687723986e-10,0.000000000000000000e+00 +3.569417193809109268e+00,3.907999999999999829e+01,0.000000000000000000e+00,1.046676571211680162e+01,0.000000000000000000e+00,-1.000000009781424115e+00,0.000000000000000000e+00,1.336351092999157383e-10,0.000000000000000000e+00 +3.570372598780906959e+00,3.909000000000000341e+01,0.000000000000000000e+00,1.046581030713565852e+01,0.000000000000000000e+00,-1.000000009781296439e+00,0.000000000000000000e+00,-8.352012913236518606e-10,0.000000000000000000e+00 +3.571328090969904778e+00,3.910000000000000142e+01,0.000000000000000000e+00,1.046485481493731484e+01,0.000000000000000000e+00,-1.000000009782094468e+00,0.000000000000000000e+00,-1.530597841048300013e-09,0.000000000000000000e+00 +3.572283670399991617e+00,3.910999999999999943e+01,0.000000000000000000e+00,1.046389923549788037e+01,0.000000000000000000e+00,-1.000000009783557076e+00,0.000000000000000000e+00,1.944497289893693002e-09,0.000000000000000000e+00 +3.573239337095067913e+00,3.911999999999999744e+01,0.000000000000000000e+00,1.046294356879345422e+01,0.000000000000000000e+00,-1.000000009781698784e+00,0.000000000000000000e+00,-2.071865584574173501e-09,0.000000000000000000e+00 +3.574195091079044762e+00,3.913000000000000256e+01,0.000000000000000000e+00,1.046198781480012840e+01,0.000000000000000000e+00,-1.000000009783678978e+00,0.000000000000000000e+00,4.251141150454048582e-11,0.000000000000000000e+00 +3.575150932375844359e+00,3.914000000000000057e+01,0.000000000000000000e+00,1.046103197349397718e+01,0.000000000000000000e+00,-1.000000009783638344e+00,0.000000000000000000e+00,5.147359617044300720e-10,0.000000000000000000e+00 +3.576106861009399562e+00,3.914999999999999858e+01,0.000000000000000000e+00,1.046007604485106945e+01,0.000000000000000000e+00,-1.000000009783146293e+00,0.000000000000000000e+00,-2.588309287872465894e-09,0.000000000000000000e+00 +3.577062877003654329e+00,3.916000000000000369e+01,0.000000000000000000e+00,1.045912002884746173e+01,0.000000000000000000e+00,-1.000000009785620758e+00,0.000000000000000000e+00,2.400887996372725904e-09,0.000000000000000000e+00 +3.578018980382563718e+00,3.917000000000000171e+01,0.000000000000000000e+00,1.045816392545919626e+01,0.000000000000000000e+00,-1.000000009783325261e+00,0.000000000000000000e+00,-2.000092666820220087e-09,0.000000000000000000e+00 +3.578975171170093450e+00,3.917999999999999972e+01,0.000000000000000000e+00,1.045720773466231179e+01,0.000000000000000000e+00,-1.000000009785237731e+00,0.000000000000000000e+00,-2.375371790943502317e-10,0.000000000000000000e+00 +3.579931449390220344e+00,3.918999999999999773e+01,0.000000000000000000e+00,1.045625145643282750e+01,0.000000000000000000e+00,-1.000000009785464883e+00,0.000000000000000000e+00,-7.638571395776949739e-11,0.000000000000000000e+00 +3.580887815066932323e+00,3.920000000000000284e+01,0.000000000000000000e+00,1.045529509074675723e+01,0.000000000000000000e+00,-1.000000009785537936e+00,0.000000000000000000e+00,-1.508073597322544006e-09,0.000000000000000000e+00 +3.581844268224227523e+00,3.921000000000000085e+01,0.000000000000000000e+00,1.045433863758010240e+01,0.000000000000000000e+00,-1.000000009786980337e+00,0.000000000000000000e+00,1.300408781717526602e-09,0.000000000000000000e+00 +3.582800808886116073e+00,3.921999999999999886e+01,0.000000000000000000e+00,1.045338209690885201e+01,0.000000000000000000e+00,-1.000000009785736443e+00,0.000000000000000000e+00,-1.351354374361587008e-09,0.000000000000000000e+00 +3.583757437076618757e+00,3.923000000000000398e+01,0.000000000000000000e+00,1.045242546870898792e+01,0.000000000000000000e+00,-1.000000009787029187e+00,0.000000000000000000e+00,2.520502486506695360e-10,0.000000000000000000e+00 +3.584714152819767019e+00,3.924000000000000199e+01,0.000000000000000000e+00,1.045146875295647604e+01,0.000000000000000000e+00,-1.000000009786788047e+00,0.000000000000000000e+00,-1.646763220696881965e-09,0.000000000000000000e+00 +3.585670956139603849e+00,3.925000000000000000e+01,0.000000000000000000e+00,1.045051194962727514e+01,0.000000000000000000e+00,-1.000000009788363675e+00,0.000000000000000000e+00,7.223653608432401876e-10,0.000000000000000000e+00 +3.586627847060182894e+00,3.925999999999999801e+01,0.000000000000000000e+00,1.044955505869732981e+01,0.000000000000000000e+00,-1.000000009787672450e+00,0.000000000000000000e+00,-3.935173382607775318e-10,0.000000000000000000e+00 +3.587584825605568462e+00,3.927000000000000313e+01,0.000000000000000000e+00,1.044859808014257752e+01,0.000000000000000000e+00,-1.000000009788049038e+00,0.000000000000000000e+00,-1.106666155210158469e-09,0.000000000000000000e+00 +3.588541891799836847e+00,3.928000000000000114e+01,0.000000000000000000e+00,1.044764101393894151e+01,0.000000000000000000e+00,-1.000000009789108191e+00,0.000000000000000000e+00,5.298519861937421208e-10,0.000000000000000000e+00 +3.589499045667074117e+00,3.928999999999999915e+01,0.000000000000000000e+00,1.044668386006233440e+01,0.000000000000000000e+00,-1.000000009788601041e+00,0.000000000000000000e+00,-1.293889497132110234e-09,0.000000000000000000e+00 +3.590456287231378774e+00,3.930000000000000426e+01,0.000000000000000000e+00,1.044572661848865991e+01,0.000000000000000000e+00,-1.000000009789839606e+00,0.000000000000000000e+00,1.184990267996312361e-09,0.000000000000000000e+00 +3.591413616516859086e+00,3.931000000000000227e+01,0.000000000000000000e+00,1.044476928919380754e+01,0.000000000000000000e+00,-1.000000009788705180e+00,0.000000000000000000e+00,-1.717139137928723846e-09,0.000000000000000000e+00 +3.592371033547634873e+00,3.932000000000000028e+01,0.000000000000000000e+00,1.044381187215365969e+01,0.000000000000000000e+00,-1.000000009790349198e+00,0.000000000000000000e+00,-3.028603657869206455e-10,0.000000000000000000e+00 +3.593328538347837497e+00,3.932999999999999829e+01,0.000000000000000000e+00,1.044285436734408279e+01,0.000000000000000000e+00,-1.000000009790639188e+00,0.000000000000000000e+00,-3.774972980882510912e-10,0.000000000000000000e+00 +3.594286130941608537e+00,3.934000000000000341e+01,0.000000000000000000e+00,1.044189677474093614e+01,0.000000000000000000e+00,-1.000000009791000677e+00,0.000000000000000000e+00,3.941563634826026890e-12,0.000000000000000000e+00 +3.595243811353101560e+00,3.935000000000000142e+01,0.000000000000000000e+00,1.044093909432006662e+01,0.000000000000000000e+00,-1.000000009790996902e+00,0.000000000000000000e+00,-1.087308118038723688e-09,0.000000000000000000e+00 +3.596201579606480347e+00,3.935999999999999943e+01,0.000000000000000000e+00,1.043998132605731044e+01,0.000000000000000000e+00,-1.000000009792038291e+00,0.000000000000000000e+00,2.292641972150439835e-10,0.000000000000000000e+00 +3.597159435725920229e+00,3.936999999999999744e+01,0.000000000000000000e+00,1.043902346992849139e+01,0.000000000000000000e+00,-1.000000009791818689e+00,0.000000000000000000e+00,8.877667465562426661e-11,0.000000000000000000e+00 +3.598117379735607191e+00,3.938000000000000256e+01,0.000000000000000000e+00,1.043806552590942438e+01,0.000000000000000000e+00,-1.000000009791733646e+00,0.000000000000000000e+00,-1.500025883142925769e-09,0.000000000000000000e+00 +3.599075411659738766e+00,3.939000000000000057e+01,0.000000000000000000e+00,1.043710749397591186e+01,0.000000000000000000e+00,-1.000000009793170719e+00,0.000000000000000000e+00,1.275785627238010609e-09,0.000000000000000000e+00 +3.600033531522523589e+00,3.939999999999999858e+01,0.000000000000000000e+00,1.043614937410374388e+01,0.000000000000000000e+00,-1.000000009791948363e+00,0.000000000000000000e+00,-1.250641771744785054e-09,0.000000000000000000e+00 +3.600991739348181397e+00,3.941000000000000369e+01,0.000000000000000000e+00,1.043519116626870336e+01,0.000000000000000000e+00,-1.000000009793146738e+00,0.000000000000000000e+00,-1.332088084613020660e-09,0.000000000000000000e+00 +3.601950035160942587e+00,3.942000000000000171e+01,0.000000000000000000e+00,1.043423287044655723e+01,0.000000000000000000e+00,-1.000000009794423272e+00,0.000000000000000000e+00,1.037955571705508404e-09,0.000000000000000000e+00 +3.602908418985049543e+00,3.942999999999999972e+01,0.000000000000000000e+00,1.043327448661306356e+01,0.000000000000000000e+00,-1.000000009793428513e+00,0.000000000000000000e+00,6.532959518301426727e-11,0.000000000000000000e+00 +3.603866890844754867e+00,3.943999999999999773e+01,0.000000000000000000e+00,1.043231601474397152e+01,0.000000000000000000e+00,-1.000000009793365896e+00,0.000000000000000000e+00,-2.307405373943909324e-09,0.000000000000000000e+00 +3.604825450764322703e+00,3.945000000000000284e+01,0.000000000000000000e+00,1.043135745481501608e+01,0.000000000000000000e+00,-1.000000009795577682e+00,0.000000000000000000e+00,1.660271259054413988e-09,0.000000000000000000e+00 +3.605784098768028301e+00,3.946000000000000085e+01,0.000000000000000000e+00,1.043039880680191978e+01,0.000000000000000000e+00,-1.000000009793986067e+00,0.000000000000000000e+00,-1.555434856170416613e-09,0.000000000000000000e+00 +3.606742834880158455e+00,3.946999999999999886e+01,0.000000000000000000e+00,1.042944007068039980e+01,0.000000000000000000e+00,-1.000000009795477318e+00,0.000000000000000000e+00,-3.492227757325948000e-10,0.000000000000000000e+00 +3.607701659125010618e+00,3.948000000000000398e+01,0.000000000000000000e+00,1.042848124642615559e+01,0.000000000000000000e+00,-1.000000009795812161e+00,0.000000000000000000e+00,-5.115133888312723040e-10,0.000000000000000000e+00 +3.608660571526893346e+00,3.949000000000000199e+01,0.000000000000000000e+00,1.042752233401487949e+01,0.000000000000000000e+00,-1.000000009796302658e+00,0.000000000000000000e+00,-1.023395784035447221e-10,0.000000000000000000e+00 +3.609619572110126740e+00,3.950000000000000000e+01,0.000000000000000000e+00,1.042656333342225139e+01,0.000000000000000000e+00,-1.000000009796400802e+00,0.000000000000000000e+00,8.860125494837712726e-10,0.000000000000000000e+00 +3.610578660899042003e+00,3.950999999999999801e+01,0.000000000000000000e+00,1.042560424462394053e+01,0.000000000000000000e+00,-1.000000009795551037e+00,0.000000000000000000e+00,-1.400544251239362763e-09,0.000000000000000000e+00 +3.611537837917981442e+00,3.952000000000000313e+01,0.000000000000000000e+00,1.042464506759560550e+01,0.000000000000000000e+00,-1.000000009796894407e+00,0.000000000000000000e+00,-1.161071675671800028e-09,0.000000000000000000e+00 +3.612497103191298464e+00,3.953000000000000114e+01,0.000000000000000000e+00,1.042368580231289066e+01,0.000000000000000000e+00,-1.000000009798008183e+00,0.000000000000000000e+00,1.610908144302707714e-09,0.000000000000000000e+00 +3.613456456743358025e+00,3.953999999999999915e+01,0.000000000000000000e+00,1.042272644875143151e+01,0.000000000000000000e+00,-1.000000009796462752e+00,0.000000000000000000e+00,-2.726720250016731327e-09,0.000000000000000000e+00 +3.614415898598535737e+00,3.955000000000000426e+01,0.000000000000000000e+00,1.042176700688685465e+01,0.000000000000000000e+00,-1.000000009799078882e+00,0.000000000000000000e+00,1.272522016001938282e-09,0.000000000000000000e+00 +3.615375428781218758e+00,3.956000000000000227e+01,0.000000000000000000e+00,1.042080747669476892e+01,0.000000000000000000e+00,-1.000000009797857858e+00,0.000000000000000000e+00,1.089839401285538654e-10,0.000000000000000000e+00 +3.616335047315805795e+00,3.957000000000000028e+01,0.000000000000000000e+00,1.041984785815077963e+01,0.000000000000000000e+00,-1.000000009797753275e+00,0.000000000000000000e+00,-4.208567550895440611e-10,0.000000000000000000e+00 +3.617294754226706210e+00,3.957999999999999829e+01,0.000000000000000000e+00,1.041888815123047607e+01,0.000000000000000000e+00,-1.000000009798157175e+00,0.000000000000000000e+00,-2.237113792489224764e-09,0.000000000000000000e+00 +3.618254549538341358e+00,3.959000000000000341e+01,0.000000000000000000e+00,1.041792835590943689e+01,0.000000000000000000e+00,-1.000000009800304346e+00,0.000000000000000000e+00,4.520080311697824710e-10,0.000000000000000000e+00 +3.619214433275142806e+00,3.960000000000000142e+01,0.000000000000000000e+00,1.041696847216322830e+01,0.000000000000000000e+00,-1.000000009799870471e+00,0.000000000000000000e+00,-5.875100388251697412e-11,0.000000000000000000e+00 +3.620174405461554112e+00,3.960999999999999943e+01,0.000000000000000000e+00,1.041600849996740941e+01,0.000000000000000000e+00,-1.000000009799926870e+00,0.000000000000000000e+00,9.551940373079359323e-11,0.000000000000000000e+00 +3.621134466122029938e+00,3.961999999999999744e+01,0.000000000000000000e+00,1.041504843929752511e+01,0.000000000000000000e+00,-1.000000009799835166e+00,0.000000000000000000e+00,9.218044789491826949e-10,0.000000000000000000e+00 +3.622094615281036045e+00,3.963000000000000256e+01,0.000000000000000000e+00,1.041408829012910964e+01,0.000000000000000000e+00,-1.000000009798950096e+00,0.000000000000000000e+00,-3.351581138780341865e-09,0.000000000000000000e+00 +3.623054852963049743e+00,3.964000000000000057e+01,0.000000000000000000e+00,1.041312805243768658e+01,0.000000000000000000e+00,-1.000000009802168410e+00,0.000000000000000000e+00,2.695075731012101353e-09,0.000000000000000000e+00 +3.624015179192559444e+00,3.964999999999999858e+01,0.000000000000000000e+00,1.041216772619876352e+01,0.000000000000000000e+00,-1.000000009799580258e+00,0.000000000000000000e+00,-2.119841322068360240e-09,0.000000000000000000e+00 +3.624975593994065104e+00,3.966000000000000369e+01,0.000000000000000000e+00,1.041120731138784627e+01,0.000000000000000000e+00,-1.000000009801616185e+00,0.000000000000000000e+00,-4.526411227100935217e-10,0.000000000000000000e+00 +3.625936097392077340e+00,3.967000000000000171e+01,0.000000000000000000e+00,1.041024680798041935e+01,0.000000000000000000e+00,-1.000000009802050949e+00,0.000000000000000000e+00,-9.246156558600320705e-13,0.000000000000000000e+00 +3.626896689411119201e+00,3.967999999999999972e+01,0.000000000000000000e+00,1.040928621595196191e+01,0.000000000000000000e+00,-1.000000009802051837e+00,0.000000000000000000e+00,-7.544167559296256762e-10,0.000000000000000000e+00 +3.627857370075723953e+00,3.968999999999999773e+01,0.000000000000000000e+00,1.040832553527794069e+01,0.000000000000000000e+00,-1.000000009802776590e+00,0.000000000000000000e+00,1.142845146783187183e-09,0.000000000000000000e+00 +3.628818139410436405e+00,3.970000000000000284e+01,0.000000000000000000e+00,1.040736476593380999e+01,0.000000000000000000e+00,-1.000000009801678580e+00,0.000000000000000000e+00,-1.997772356465649962e-09,0.000000000000000000e+00 +3.629778997439813359e+00,3.971000000000000085e+01,0.000000000000000000e+00,1.040640390789501524e+01,0.000000000000000000e+00,-1.000000009803598156e+00,0.000000000000000000e+00,-5.474014765428256870e-10,0.000000000000000000e+00 +3.630739944188421831e+00,3.971999999999999886e+01,0.000000000000000000e+00,1.040544296113698586e+01,0.000000000000000000e+00,-1.000000009804124179e+00,0.000000000000000000e+00,1.651987817033560966e-09,0.000000000000000000e+00 +3.631700979680841268e+00,3.973000000000000398e+01,0.000000000000000000e+00,1.040448192563514418e+01,0.000000000000000000e+00,-1.000000009802536560e+00,0.000000000000000000e+00,-1.160212109286622233e-09,0.000000000000000000e+00 +3.632662103941662224e+00,3.974000000000000199e+01,0.000000000000000000e+00,1.040352080136490187e+01,0.000000000000000000e+00,-1.000000009803651668e+00,0.000000000000000000e+00,-1.282537353856703944e-09,0.000000000000000000e+00 +3.633623316995485908e+00,3.975000000000000000e+01,0.000000000000000000e+00,1.040255958830165461e+01,0.000000000000000000e+00,-1.000000009804884460e+00,0.000000000000000000e+00,1.290272285908789710e-09,0.000000000000000000e+00 +3.634584618866925965e+00,3.975999999999999801e+01,0.000000000000000000e+00,1.040159828642078921e+01,0.000000000000000000e+00,-1.000000009803644119e+00,0.000000000000000000e+00,-1.121781842464603614e-09,0.000000000000000000e+00 +3.635546009580606253e+00,3.977000000000000313e+01,0.000000000000000000e+00,1.040063689569768357e+01,0.000000000000000000e+00,-1.000000009804722589e+00,0.000000000000000000e+00,-8.221482905287071007e-10,0.000000000000000000e+00 +3.636507489161163065e+00,3.978000000000000114e+01,0.000000000000000000e+00,1.039967541610769963e+01,0.000000000000000000e+00,-1.000000009805513068e+00,0.000000000000000000e+00,2.743319881112415315e-10,0.000000000000000000e+00 +3.637469057633243796e+00,3.978999999999999915e+01,0.000000000000000000e+00,1.039871384762619044e+01,0.000000000000000000e+00,-1.000000009805249279e+00,0.000000000000000000e+00,2.542185117135095065e-10,0.000000000000000000e+00 +3.638430715021506501e+00,3.980000000000000426e+01,0.000000000000000000e+00,1.039775219022849839e+01,0.000000000000000000e+00,-1.000000009805004808e+00,0.000000000000000000e+00,-2.793836256874794422e-09,0.000000000000000000e+00 +3.639392461350621666e+00,3.981000000000000227e+01,0.000000000000000000e+00,1.039679044388995344e+01,0.000000000000000000e+00,-1.000000009807691770e+00,0.000000000000000000e+00,2.659912723290692692e-09,0.000000000000000000e+00 +3.640354296645270438e+00,3.982000000000000028e+01,0.000000000000000000e+00,1.039582860858587132e+01,0.000000000000000000e+00,-1.000000009805133372e+00,0.000000000000000000e+00,-2.578643995810042890e-09,0.000000000000000000e+00 +3.641316220930145509e+00,3.982999999999999829e+01,0.000000000000000000e+00,1.039486668429156424e+01,0.000000000000000000e+00,-1.000000009807613832e+00,0.000000000000000000e+00,6.993615920470528158e-10,0.000000000000000000e+00 +3.642278234229951561e+00,3.984000000000000341e+01,0.000000000000000000e+00,1.039390467098232307e+01,0.000000000000000000e+00,-1.000000009806941037e+00,0.000000000000000000e+00,9.808619439261007155e-10,0.000000000000000000e+00 +3.643240336569404381e+00,3.985000000000000142e+01,0.000000000000000000e+00,1.039294256863343513e+01,0.000000000000000000e+00,-1.000000009805997347e+00,0.000000000000000000e+00,-1.722234141736918600e-09,0.000000000000000000e+00 +3.644202527973230854e+00,3.985999999999999943e+01,0.000000000000000000e+00,1.039198037722017354e+01,0.000000000000000000e+00,-1.000000009807654466e+00,0.000000000000000000e+00,2.715907699621521002e-10,0.000000000000000000e+00 +3.645164808466169415e+00,3.986999999999999744e+01,0.000000000000000000e+00,1.039101809671779719e+01,0.000000000000000000e+00,-1.000000009807393120e+00,0.000000000000000000e+00,-7.032557460550281094e-10,0.000000000000000000e+00 +3.646127178072970487e+00,3.988000000000000256e+01,0.000000000000000000e+00,1.039005572710155789e+01,0.000000000000000000e+00,-1.000000009808069912e+00,0.000000000000000000e+00,-8.026247194556094852e-10,0.000000000000000000e+00 +3.647089636818395153e+00,3.989000000000000057e+01,0.000000000000000000e+00,1.038909326834669322e+01,0.000000000000000000e+00,-1.000000009808842405e+00,0.000000000000000000e+00,-1.845473688239474910e-11,0.000000000000000000e+00 +3.648052184727216929e+00,3.989999999999999858e+01,0.000000000000000000e+00,1.038813072042843011e+01,0.000000000000000000e+00,-1.000000009808860169e+00,0.000000000000000000e+00,-2.604183442969909186e-10,0.000000000000000000e+00 +3.649014821824219990e+00,3.991000000000000369e+01,0.000000000000000000e+00,1.038716808332198482e+01,0.000000000000000000e+00,-1.000000009809110857e+00,0.000000000000000000e+00,3.969339583997285848e-10,0.000000000000000000e+00 +3.649977548134200056e+00,3.992000000000000171e+01,0.000000000000000000e+00,1.038620535700256120e+01,0.000000000000000000e+00,-1.000000009808728718e+00,0.000000000000000000e+00,-1.871482002082109607e-09,0.000000000000000000e+00 +3.650940363681964840e+00,3.992999999999999972e+01,0.000000000000000000e+00,1.038524254144535242e+01,0.000000000000000000e+00,-1.000000009810530610e+00,0.000000000000000000e+00,6.078581935409210540e-10,0.000000000000000000e+00 +3.651903268492333154e+00,3.993999999999999773e+01,0.000000000000000000e+00,1.038427963662553744e+01,0.000000000000000000e+00,-1.000000009809945301e+00,0.000000000000000000e+00,1.773139644126739390e-10,0.000000000000000000e+00 +3.652866262590135360e+00,3.995000000000000284e+01,0.000000000000000000e+00,1.038331664251828812e+01,0.000000000000000000e+00,-1.000000009809774548e+00,0.000000000000000000e+00,6.778344758596459056e-10,0.000000000000000000e+00 +3.653829346000213807e+00,3.996000000000000085e+01,0.000000000000000000e+00,1.038235355909876212e+01,0.000000000000000000e+00,-1.000000009809121737e+00,0.000000000000000000e+00,-1.712871776507003598e-09,0.000000000000000000e+00 +3.654792518747421504e+00,3.996999999999999886e+01,0.000000000000000000e+00,1.038139038634210642e+01,0.000000000000000000e+00,-1.000000009810771529e+00,0.000000000000000000e+00,-1.241313434939877852e-09,0.000000000000000000e+00 +3.655755780856623893e+00,3.998000000000000398e+01,0.000000000000000000e+00,1.038042712422345382e+01,0.000000000000000000e+00,-1.000000009811967239e+00,0.000000000000000000e+00,2.097705725957636166e-09,0.000000000000000000e+00 +3.656719132352697077e+00,3.999000000000000199e+01,0.000000000000000000e+00,1.037946377271792819e+01,0.000000000000000000e+00,-1.000000009809946411e+00,0.000000000000000000e+00,-3.170581200279810381e-09,0.000000000000000000e+00 +3.657682573260529590e+00,4.000000000000000000e+01,0.000000000000000000e+00,1.037850033180064457e+01,0.000000000000000000e+00,-1.000000009813001078e+00,0.000000000000000000e+00,2.100081742366627784e-09,0.000000000000000000e+00 +3.658646103605020627e+00,4.000999999999999801e+01,0.000000000000000000e+00,1.037753680144669843e+01,0.000000000000000000e+00,-1.000000009810977586e+00,0.000000000000000000e+00,-1.218501180090262118e-09,0.000000000000000000e+00 +3.659609723411081372e+00,4.002000000000000313e+01,0.000000000000000000e+00,1.037657318163118347e+01,0.000000000000000000e+00,-1.000000009812151758e+00,0.000000000000000000e+00,2.757962324831392543e-10,0.000000000000000000e+00 +3.660573432703635000e+00,4.003000000000000114e+01,0.000000000000000000e+00,1.037560947232917385e+01,0.000000000000000000e+00,-1.000000009811885970e+00,0.000000000000000000e+00,-1.061613207309193924e-09,0.000000000000000000e+00 +3.661537231507615342e+00,4.003999999999999915e+01,0.000000000000000000e+00,1.037464567351573663e+01,0.000000000000000000e+00,-1.000000009812909152e+00,0.000000000000000000e+00,-1.396232627896651525e-09,0.000000000000000000e+00 +3.662501119847968667e+00,4.005000000000000426e+01,0.000000000000000000e+00,1.037368178516592465e+01,0.000000000000000000e+00,-1.000000009814254964e+00,0.000000000000000000e+00,1.190177152031786823e-09,0.000000000000000000e+00 +3.663465097749652344e+00,4.006000000000000227e+01,0.000000000000000000e+00,1.037271780725478010e+01,0.000000000000000000e+00,-1.000000009813107660e+00,0.000000000000000000e+00,9.705710199930193029e-10,0.000000000000000000e+00 +3.664429165237635733e+00,4.007000000000000028e+01,0.000000000000000000e+00,1.037175373975733628e+01,0.000000000000000000e+00,-1.000000009812171964e+00,0.000000000000000000e+00,-2.044596263441125982e-09,0.000000000000000000e+00 +3.665393322336899296e+00,4.007999999999999829e+01,0.000000000000000000e+00,1.037078958264861228e+01,0.000000000000000000e+00,-1.000000009814143276e+00,0.000000000000000000e+00,-2.040261197816899513e-10,0.000000000000000000e+00 +3.666357569072435485e+00,4.009000000000000341e+01,0.000000000000000000e+00,1.036982533590361300e+01,0.000000000000000000e+00,-1.000000009814340007e+00,0.000000000000000000e+00,7.665234789838299679e-10,0.000000000000000000e+00 +3.667321905469247856e+00,4.010000000000000142e+01,0.000000000000000000e+00,1.036886099949733619e+01,0.000000000000000000e+00,-1.000000009813600821e+00,0.000000000000000000e+00,-1.033064285332775287e-09,0.000000000000000000e+00 +3.668286331552352397e+00,4.010999999999999943e+01,0.000000000000000000e+00,1.036789657340476722e+01,0.000000000000000000e+00,-1.000000009814597135e+00,0.000000000000000000e+00,-1.774486042278676702e-09,0.000000000000000000e+00 +3.669250847346776201e+00,4.011999999999999744e+01,0.000000000000000000e+00,1.036693205760087722e+01,0.000000000000000000e+00,-1.000000009816308655e+00,0.000000000000000000e+00,2.367526091005545720e-09,0.000000000000000000e+00 +3.670215452877557905e+00,4.013000000000000256e+01,0.000000000000000000e+00,1.036596745206062664e+01,0.000000000000000000e+00,-1.000000009814024926e+00,0.000000000000000000e+00,-1.962435514008406979e-09,0.000000000000000000e+00 +3.671180148169748136e+00,4.014000000000000057e+01,0.000000000000000000e+00,1.036500275675896887e+01,0.000000000000000000e+00,-1.000000009815918078e+00,0.000000000000000000e+00,5.157645683406119718e-10,0.000000000000000000e+00 +3.672144933248409071e+00,4.014999999999999858e+01,0.000000000000000000e+00,1.036403797167083773e+01,0.000000000000000000e+00,-1.000000009815420476e+00,0.000000000000000000e+00,2.660278196675911310e-10,0.000000000000000000e+00 +3.673109808138614429e+00,4.016000000000000369e+01,0.000000000000000000e+00,1.036307309677116173e+01,0.000000000000000000e+00,-1.000000009815163793e+00,0.000000000000000000e+00,-2.701679796084160129e-09,0.000000000000000000e+00 +3.674074772865449923e+00,4.017000000000000171e+01,0.000000000000000000e+00,1.036210813203485515e+01,0.000000000000000000e+00,-1.000000009817770819e+00,0.000000000000000000e+00,1.158938248947628970e-09,0.000000000000000000e+00 +3.675039827454012364e+00,4.017999999999999972e+01,0.000000000000000000e+00,1.036114307743681806e+01,0.000000000000000000e+00,-1.000000009816652380e+00,0.000000000000000000e+00,4.099733211580504643e-10,0.000000000000000000e+00 +3.676004971929410559e+00,4.018999999999999773e+01,0.000000000000000000e+00,1.036017793295194522e+01,0.000000000000000000e+00,-1.000000009816256696e+00,0.000000000000000000e+00,-1.124216043776019743e-09,0.000000000000000000e+00 +3.676970206316765299e+00,4.020000000000000284e+01,0.000000000000000000e+00,1.035921269855511540e+01,0.000000000000000000e+00,-1.000000009817341828e+00,0.000000000000000000e+00,3.774640164506447402e-10,0.000000000000000000e+00 +3.677935530641208928e+00,4.021000000000000085e+01,0.000000000000000000e+00,1.035824737422119490e+01,0.000000000000000000e+00,-1.000000009816977453e+00,0.000000000000000000e+00,-7.957975592899420307e-10,0.000000000000000000e+00 +3.678900944927885330e+00,4.021999999999999886e+01,0.000000000000000000e+00,1.035728195992504119e+01,0.000000000000000000e+00,-1.000000009817745728e+00,0.000000000000000000e+00,1.081585866591960033e-09,0.000000000000000000e+00 +3.679866449201949941e+00,4.023000000000000398e+01,0.000000000000000000e+00,1.035631645564149750e+01,0.000000000000000000e+00,-1.000000009816701452e+00,0.000000000000000000e+00,-1.604405939459557155e-09,0.000000000000000000e+00 +3.680832043488570182e+00,4.024000000000000199e+01,0.000000000000000000e+00,1.035535086134539817e+01,0.000000000000000000e+00,-1.000000009818250657e+00,0.000000000000000000e+00,-1.222794218783348069e-09,0.000000000000000000e+00 +3.681797727812925469e+00,4.025000000000000000e+01,0.000000000000000000e+00,1.035438517701156158e+01,0.000000000000000000e+00,-1.000000009819431490e+00,0.000000000000000000e+00,2.231540786114521249e-09,0.000000000000000000e+00 +3.682763502200206318e+00,4.025999999999999801e+01,0.000000000000000000e+00,1.035341940261479721e+01,0.000000000000000000e+00,-1.000000009817276325e+00,0.000000000000000000e+00,-2.659161829178143775e-09,0.000000000000000000e+00 +3.683729366675615680e+00,4.027000000000000313e+01,0.000000000000000000e+00,1.035245353812990565e+01,0.000000000000000000e+00,-1.000000009819844715e+00,0.000000000000000000e+00,1.252795018453944635e-09,0.000000000000000000e+00 +3.684695321264367607e+00,4.028000000000000114e+01,0.000000000000000000e+00,1.035148758353166798e+01,0.000000000000000000e+00,-1.000000009818634572e+00,0.000000000000000000e+00,-1.257734806460970285e-09,0.000000000000000000e+00 +3.685661365991688587e+00,4.028999999999999915e+01,0.000000000000000000e+00,1.035052153879486170e+01,0.000000000000000000e+00,-1.000000009819849600e+00,0.000000000000000000e+00,1.239920692825930594e-09,0.000000000000000000e+00 +3.686627500882816655e+00,4.030000000000000426e+01,0.000000000000000000e+00,1.034955540389424655e+01,0.000000000000000000e+00,-1.000000009818651669e+00,0.000000000000000000e+00,-2.665063592454366022e-09,0.000000000000000000e+00 +3.687593725963000946e+00,4.031000000000000227e+01,0.000000000000000000e+00,1.034858917880457518e+01,0.000000000000000000e+00,-1.000000009821226721e+00,0.000000000000000000e+00,2.258095618492829173e-09,0.000000000000000000e+00 +3.688560041257503475e+00,4.032000000000000028e+01,0.000000000000000000e+00,1.034762286350058247e+01,0.000000000000000000e+00,-1.000000009819044688e+00,0.000000000000000000e+00,-3.007602684306723492e-09,0.000000000000000000e+00 +3.689526446791596914e+00,4.032999999999999829e+01,0.000000000000000000e+00,1.034665645795699973e+01,0.000000000000000000e+00,-1.000000009821951252e+00,0.000000000000000000e+00,2.469955430839292325e-09,0.000000000000000000e+00 +3.690492942590566816e+00,4.034000000000000341e+01,0.000000000000000000e+00,1.034568996214853698e+01,0.000000000000000000e+00,-1.000000009819564051e+00,0.000000000000000000e+00,-2.220707725799407170e-09,0.000000000000000000e+00 +3.691459528679709834e+00,4.035000000000000142e+01,0.000000000000000000e+00,1.034472337604990244e+01,0.000000000000000000e+00,-1.000000009821710556e+00,0.000000000000000000e+00,1.943253552769301201e-09,0.000000000000000000e+00 +3.692426205084334612e+00,4.035999999999999943e+01,0.000000000000000000e+00,1.034375669963578304e+01,0.000000000000000000e+00,-1.000000009819832059e+00,0.000000000000000000e+00,-2.140135289590144334e-09,0.000000000000000000e+00 +3.693392971829762228e+00,4.036999999999999744e+01,0.000000000000000000e+00,1.034278993288086212e+01,0.000000000000000000e+00,-1.000000009821901070e+00,0.000000000000000000e+00,-1.155629346488862183e-09,0.000000000000000000e+00 +3.694359828941324420e+00,4.038000000000000256e+01,0.000000000000000000e+00,1.034182307575980353e+01,0.000000000000000000e+00,-1.000000009823018399e+00,0.000000000000000000e+00,1.101327550741970882e-09,0.000000000000000000e+00 +3.695326776444365802e+00,4.039000000000000057e+01,0.000000000000000000e+00,1.034085612824726397e+01,0.000000000000000000e+00,-1.000000009821953473e+00,0.000000000000000000e+00,8.399248345087538346e-10,0.000000000000000000e+00 +3.696293814364242092e+00,4.039999999999999858e+01,0.000000000000000000e+00,1.033988909031788950e+01,0.000000000000000000e+00,-1.000000009821141234e+00,0.000000000000000000e+00,-1.929717892237766894e-09,0.000000000000000000e+00 +3.697260942726321442e+00,4.041000000000000369e+01,0.000000000000000000e+00,1.033892196194631197e+01,0.000000000000000000e+00,-1.000000009823007519e+00,0.000000000000000000e+00,3.966972783651817612e-10,0.000000000000000000e+00 +3.698228161555983551e+00,4.042000000000000171e+01,0.000000000000000000e+00,1.033795474310714901e+01,0.000000000000000000e+00,-1.000000009822623825e+00,0.000000000000000000e+00,2.306964512049410685e-10,0.000000000000000000e+00 +3.699195470878619663e+00,4.042999999999999972e+01,0.000000000000000000e+00,1.033698743377501117e+01,0.000000000000000000e+00,-1.000000009822400671e+00,0.000000000000000000e+00,-5.191905921897238757e-10,0.000000000000000000e+00 +3.700162870719633901e+00,4.043999999999999773e+01,0.000000000000000000e+00,1.033602003392449475e+01,0.000000000000000000e+00,-1.000000009822902935e+00,0.000000000000000000e+00,-1.844767206386712347e-09,0.000000000000000000e+00 +3.701130361104441491e+00,4.045000000000000284e+01,0.000000000000000000e+00,1.033505254353018366e+01,0.000000000000000000e+00,-1.000000009824687730e+00,0.000000000000000000e+00,1.954746976857493172e-09,0.000000000000000000e+00 +3.702097942058469648e+00,4.046000000000000085e+01,0.000000000000000000e+00,1.033408496256664932e+01,0.000000000000000000e+00,-1.000000009822796354e+00,0.000000000000000000e+00,-2.394444122630523275e-09,0.000000000000000000e+00 +3.703065613607157580e+00,4.046999999999999886e+01,0.000000000000000000e+00,1.033311729100845611e+01,0.000000000000000000e+00,-1.000000009825113390e+00,0.000000000000000000e+00,2.190705481343007861e-09,0.000000000000000000e+00 +3.704033375775956483e+00,4.048000000000000398e+01,0.000000000000000000e+00,1.033214952883014881e+01,0.000000000000000000e+00,-1.000000009822993308e+00,0.000000000000000000e+00,-1.353118015879677759e-09,0.000000000000000000e+00 +3.705001228590329543e+00,4.049000000000000199e+01,0.000000000000000000e+00,1.033118167600626869e+01,0.000000000000000000e+00,-1.000000009824302927e+00,0.000000000000000000e+00,-1.637215776765382466e-09,0.000000000000000000e+00 +3.705969172075751494e+00,4.050000000000000000e+01,0.000000000000000000e+00,1.033021373251133745e+01,0.000000000000000000e+00,-1.000000009825887659e+00,0.000000000000000000e+00,1.344377557860297739e-09,0.000000000000000000e+00 +3.706937206257709061e+00,4.050999999999999801e+01,0.000000000000000000e+00,1.032924569831986794e+01,0.000000000000000000e+00,-1.000000009824586256e+00,0.000000000000000000e+00,1.766036025797900987e-11,0.000000000000000000e+00 +3.707905331161701401e+00,4.052000000000000313e+01,0.000000000000000000e+00,1.032827757340636410e+01,0.000000000000000000e+00,-1.000000009824569158e+00,0.000000000000000000e+00,-1.816782611830385726e-09,0.000000000000000000e+00 +3.708873546813239219e+00,4.053000000000000114e+01,0.000000000000000000e+00,1.032730935774531389e+01,0.000000000000000000e+00,-1.000000009826328196e+00,0.000000000000000000e+00,1.532952943617603097e-09,0.000000000000000000e+00 +3.709841853237845211e+00,4.053999999999999915e+01,0.000000000000000000e+00,1.032634105131119284e+01,0.000000000000000000e+00,-1.000000009824843827e+00,0.000000000000000000e+00,-1.292283128621949042e-09,0.000000000000000000e+00 +3.710810250461054505e+00,4.055000000000000426e+01,0.000000000000000000e+00,1.032537265407846938e+01,0.000000000000000000e+00,-1.000000009826095271e+00,0.000000000000000000e+00,-8.116134252542157719e-10,0.000000000000000000e+00 +3.711778738508413333e+00,4.056000000000000227e+01,0.000000000000000000e+00,1.032440416602159416e+01,0.000000000000000000e+00,-1.000000009826881309e+00,0.000000000000000000e+00,1.087780926839975619e-09,0.000000000000000000e+00 +3.712747317405480363e+00,4.057000000000000028e+01,0.000000000000000000e+00,1.032343558711500897e+01,0.000000000000000000e+00,-1.000000009825827707e+00,0.000000000000000000e+00,-1.266016952331221404e-09,0.000000000000000000e+00 +3.713715987177826250e+00,4.057999999999999829e+01,0.000000000000000000e+00,1.032246691733314492e+01,0.000000000000000000e+00,-1.000000009827054059e+00,0.000000000000000000e+00,-2.904024928143365826e-10,0.000000000000000000e+00 +3.714684747851034086e+00,4.059000000000000341e+01,0.000000000000000000e+00,1.032149815665041714e+01,0.000000000000000000e+00,-1.000000009827335390e+00,0.000000000000000000e+00,2.356004303879861151e-10,0.000000000000000000e+00 +3.715653599450698064e+00,4.060000000000000142e+01,0.000000000000000000e+00,1.032052930504123189e+01,0.000000000000000000e+00,-1.000000009827107128e+00,0.000000000000000000e+00,3.205973375164968129e-10,0.000000000000000000e+00 +3.716622542002425256e+00,4.060999999999999943e+01,0.000000000000000000e+00,1.031956036247998298e+01,0.000000000000000000e+00,-1.000000009826796488e+00,0.000000000000000000e+00,-2.612199082203043849e-11,0.000000000000000000e+00 +3.717591575531833836e+00,4.061999999999999744e+01,0.000000000000000000e+00,1.031859132894105180e+01,0.000000000000000000e+00,-1.000000009826821801e+00,0.000000000000000000e+00,-2.687333859822107255e-09,0.000000000000000000e+00 +3.718560700064554858e+00,4.063000000000000256e+01,0.000000000000000000e+00,1.031762220439880728e+01,0.000000000000000000e+00,-1.000000009829426162e+00,0.000000000000000000e+00,1.801391555771032958e-09,0.000000000000000000e+00 +3.719529915626230920e+00,4.064000000000000057e+01,0.000000000000000000e+00,1.031665298882760418e+01,0.000000000000000000e+00,-1.000000009827680225e+00,0.000000000000000000e+00,2.093752023266322087e-10,0.000000000000000000e+00 +3.720499222242517057e+00,4.064999999999999858e+01,0.000000000000000000e+00,1.031568368220179188e+01,0.000000000000000000e+00,-1.000000009827477276e+00,0.000000000000000000e+00,-1.779292953937162037e-09,0.000000000000000000e+00 +3.721468619939080291e+00,4.066000000000000369e+01,0.000000000000000000e+00,1.031471428449570205e+01,0.000000000000000000e+00,-1.000000009829202119e+00,0.000000000000000000e+00,1.512989790417109814e-09,0.000000000000000000e+00 +3.722438108741599194e+00,4.067000000000000171e+01,0.000000000000000000e+00,1.031374479568365388e+01,0.000000000000000000e+00,-1.000000009827735292e+00,0.000000000000000000e+00,-1.246049606458460508e-09,0.000000000000000000e+00 +3.723407688675764771e+00,4.067999999999999972e+01,0.000000000000000000e+00,1.031277521573995948e+01,0.000000000000000000e+00,-1.000000009828943437e+00,0.000000000000000000e+00,-5.974338920881184356e-10,0.000000000000000000e+00 +3.724377359767280016e+00,4.068999999999999773e+01,0.000000000000000000e+00,1.031180554463891319e+01,0.000000000000000000e+00,-1.000000009829522751e+00,0.000000000000000000e+00,-3.132283318289193590e-10,0.000000000000000000e+00 +3.725347122041860359e+00,4.070000000000000284e+01,0.000000000000000000e+00,1.031083578235480047e+01,0.000000000000000000e+00,-1.000000009829826508e+00,0.000000000000000000e+00,-3.844012503545204305e-10,0.000000000000000000e+00 +3.726316975525232777e+00,4.071000000000000085e+01,0.000000000000000000e+00,1.030986592886189435e+01,0.000000000000000000e+00,-1.000000009830199321e+00,0.000000000000000000e+00,1.085791325752082580e-09,0.000000000000000000e+00 +3.727286920243137125e+00,4.071999999999999886e+01,0.000000000000000000e+00,1.030889598413445540e+01,0.000000000000000000e+00,-1.000000009829146164e+00,0.000000000000000000e+00,-1.558603751749465624e-09,0.000000000000000000e+00 +3.728256956221324359e+00,4.073000000000000398e+01,0.000000000000000000e+00,1.030792594814673357e+01,0.000000000000000000e+00,-1.000000009830658065e+00,0.000000000000000000e+00,1.130676756307843673e-09,0.000000000000000000e+00 +3.729227083485558314e+00,4.074000000000000199e+01,0.000000000000000000e+00,1.030695582087296280e+01,0.000000000000000000e+00,-1.000000009829561165e+00,0.000000000000000000e+00,-2.163417298078054458e-09,0.000000000000000000e+00 +3.730197302061614373e+00,4.075000000000000000e+01,0.000000000000000000e+00,1.030598560228736993e+01,0.000000000000000000e+00,-1.000000009831660153e+00,0.000000000000000000e+00,1.778077865605639959e-09,0.000000000000000000e+00 +3.731167611975280352e+00,4.075999999999999801e+01,0.000000000000000000e+00,1.030501529236416403e+01,0.000000000000000000e+00,-1.000000009829934866e+00,0.000000000000000000e+00,-2.131433195459657458e-09,0.000000000000000000e+00 +3.732138013252356501e+00,4.077000000000000313e+01,0.000000000000000000e+00,1.030404489107754884e+01,0.000000000000000000e+00,-1.000000009832003212e+00,0.000000000000000000e+00,1.208956783670473200e-09,0.000000000000000000e+00 +3.733108505918655062e+00,4.078000000000000114e+01,0.000000000000000000e+00,1.030307439840170858e+01,0.000000000000000000e+00,-1.000000009830829928e+00,0.000000000000000000e+00,-1.395751445635280903e-09,0.000000000000000000e+00 +3.734079089999999823e+00,4.078999999999999915e+01,0.000000000000000000e+00,1.030210381431082212e+01,0.000000000000000000e+00,-1.000000009832184622e+00,0.000000000000000000e+00,1.378006006578411330e-09,0.000000000000000000e+00 +3.735049765522227450e+00,4.080000000000000426e+01,0.000000000000000000e+00,1.030113313877905057e+01,0.000000000000000000e+00,-1.000000009830847025e+00,0.000000000000000000e+00,-1.774038441135113367e-09,0.000000000000000000e+00 +3.736020532511186598e+00,4.081000000000000227e+01,0.000000000000000000e+00,1.030016237178054794e+01,0.000000000000000000e+00,-1.000000009832569203e+00,0.000000000000000000e+00,4.681684456783137945e-10,0.000000000000000000e+00 +3.736991390992737916e+00,4.082000000000000028e+01,0.000000000000000000e+00,1.029919151328945048e+01,0.000000000000000000e+00,-1.000000009832114678e+00,0.000000000000000000e+00,-1.311983004720164694e-09,0.000000000000000000e+00 +3.737962340992754484e+00,4.082999999999999829e+01,0.000000000000000000e+00,1.029822056327988733e+01,0.000000000000000000e+00,-1.000000009833388548e+00,0.000000000000000000e+00,2.316162286085931535e-09,0.000000000000000000e+00 +3.738933382537121375e+00,4.084000000000000341e+01,0.000000000000000000e+00,1.029724952172597163e+01,0.000000000000000000e+00,-1.000000009831139458e+00,0.000000000000000000e+00,-1.826872512791022710e-09,0.000000000000000000e+00 +3.739904515651736094e+00,4.085000000000000142e+01,0.000000000000000000e+00,1.029627838860180944e+01,0.000000000000000000e+00,-1.000000009832913594e+00,0.000000000000000000e+00,-5.450379631716620584e-10,0.000000000000000000e+00 +3.740875740362508139e+00,4.085999999999999943e+01,0.000000000000000000e+00,1.029530716388148726e+01,0.000000000000000000e+00,-1.000000009833442949e+00,0.000000000000000000e+00,5.175543420283299259e-10,0.000000000000000000e+00 +3.741847056695359441e+00,4.086999999999999744e+01,0.000000000000000000e+00,1.029433584753908448e+01,0.000000000000000000e+00,-1.000000009832940240e+00,0.000000000000000000e+00,-5.120195889160583786e-10,0.000000000000000000e+00 +3.742818464676223922e+00,4.088000000000000256e+01,0.000000000000000000e+00,1.029336443954866809e+01,0.000000000000000000e+00,-1.000000009833437620e+00,0.000000000000000000e+00,-1.742530797146791671e-09,0.000000000000000000e+00 +3.743789964331047937e+00,4.089000000000000057e+01,0.000000000000000000e+00,1.029239293988429083e+01,0.000000000000000000e+00,-1.000000009835130488e+00,0.000000000000000000e+00,2.480083875680534700e-09,0.000000000000000000e+00 +3.744761555685789833e+00,4.089999999999999858e+01,0.000000000000000000e+00,1.029142134851999302e+01,0.000000000000000000e+00,-1.000000009832720860e+00,0.000000000000000000e+00,-2.889349460370711568e-09,0.000000000000000000e+00 +3.745733238766420836e+00,4.091000000000000369e+01,0.000000000000000000e+00,1.029044966542980788e+01,0.000000000000000000e+00,-1.000000009835528392e+00,0.000000000000000000e+00,9.731554478934600537e-10,0.000000000000000000e+00 +3.746705013598923273e+00,4.092000000000000171e+01,0.000000000000000000e+00,1.028947789058774731e+01,0.000000000000000000e+00,-1.000000009834582704e+00,0.000000000000000000e+00,9.058926905543088771e-10,0.000000000000000000e+00 +3.747676880209293238e+00,4.092999999999999972e+01,0.000000000000000000e+00,1.028850602396781966e+01,0.000000000000000000e+00,-1.000000009833702297e+00,0.000000000000000000e+00,-1.199366309064388073e-09,0.000000000000000000e+00 +3.748648838623537483e+00,4.093999999999999773e+01,0.000000000000000000e+00,1.028753406554401728e+01,0.000000000000000000e+00,-1.000000009834868031e+00,0.000000000000000000e+00,3.065519108771413083e-10,0.000000000000000000e+00 +3.749620888867676527e+00,4.095000000000000284e+01,0.000000000000000000e+00,1.028656201529031833e+01,0.000000000000000000e+00,-1.000000009834570047e+00,0.000000000000000000e+00,-2.087416689672010639e-09,0.000000000000000000e+00 +3.750593030967741992e+00,4.096000000000000085e+01,0.000000000000000000e+00,1.028558987318069207e+01,0.000000000000000000e+00,-1.000000009836599313e+00,0.000000000000000000e+00,1.024539479279353447e-09,0.000000000000000000e+00 +3.751565264949778822e+00,4.096999999999999886e+01,0.000000000000000000e+00,1.028461763918909178e+01,0.000000000000000000e+00,-1.000000009835603221e+00,0.000000000000000000e+00,2.546262904456106175e-10,0.000000000000000000e+00 +3.752537590839843507e+00,4.098000000000000398e+01,0.000000000000000000e+00,1.028364531328946363e+01,0.000000000000000000e+00,-1.000000009835355641e+00,0.000000000000000000e+00,-6.304544599709462575e-10,0.000000000000000000e+00 +3.753510008664005415e+00,4.099000000000000199e+01,0.000000000000000000e+00,1.028267289545573782e+01,0.000000000000000000e+00,-1.000000009835968706e+00,0.000000000000000000e+00,2.573179969806686310e-10,0.000000000000000000e+00 +3.754482518448345463e+00,4.100000000000000000e+01,0.000000000000000000e+00,1.028170038566183209e+01,0.000000000000000000e+00,-1.000000009835718462e+00,0.000000000000000000e+00,-8.305539812134053421e-10,0.000000000000000000e+00 +3.755455120218957887e+00,4.100999999999999801e+01,0.000000000000000000e+00,1.028072778388165354e+01,0.000000000000000000e+00,-1.000000009836526260e+00,0.000000000000000000e+00,-1.294336338877521369e-10,0.000000000000000000e+00 +3.756427814001948473e+00,4.102000000000000313e+01,0.000000000000000000e+00,1.027975509008909505e+01,0.000000000000000000e+00,-1.000000009836652159e+00,0.000000000000000000e+00,4.912078067380971794e-10,0.000000000000000000e+00 +3.757400599823435883e+00,4.103000000000000114e+01,0.000000000000000000e+00,1.027878230425803885e+01,0.000000000000000000e+00,-1.000000009836174319e+00,0.000000000000000000e+00,-8.364805991224624674e-10,0.000000000000000000e+00 +3.758373477709550770e+00,4.103999999999999915e+01,0.000000000000000000e+00,1.027780942636235473e+01,0.000000000000000000e+00,-1.000000009836988113e+00,0.000000000000000000e+00,-3.500790692898514731e-10,0.000000000000000000e+00 +3.759346447686436221e+00,4.105000000000000426e+01,0.000000000000000000e+00,1.027683645637589827e+01,0.000000000000000000e+00,-1.000000009837328729e+00,0.000000000000000000e+00,8.192078766098170858e-11,0.000000000000000000e+00 +3.760319509780247760e+00,4.106000000000000227e+01,0.000000000000000000e+00,1.027586339427251438e+01,0.000000000000000000e+00,-1.000000009837249015e+00,0.000000000000000000e+00,-1.407352577051332127e-09,0.000000000000000000e+00 +3.761292664017153342e+00,4.107000000000000028e+01,0.000000000000000000e+00,1.027489024002603557e+01,0.000000000000000000e+00,-1.000000009838618586e+00,0.000000000000000000e+00,8.176838455276793769e-10,0.000000000000000000e+00 +3.762265910423333359e+00,4.107999999999999829e+01,0.000000000000000000e+00,1.027391699361028010e+01,0.000000000000000000e+00,-1.000000009837822779e+00,0.000000000000000000e+00,-7.361651319288758672e-10,0.000000000000000000e+00 +3.763239249024980637e+00,4.109000000000000341e+01,0.000000000000000000e+00,1.027294365499905737e+01,0.000000000000000000e+00,-1.000000009838539317e+00,0.000000000000000000e+00,1.440484158206501925e-09,0.000000000000000000e+00 +3.764212679848299992e+00,4.110000000000000142e+01,0.000000000000000000e+00,1.027197022416616079e+01,0.000000000000000000e+00,-1.000000009837137105e+00,0.000000000000000000e+00,-2.017399061865480912e-09,0.000000000000000000e+00 +3.765186202919509117e+00,4.110999999999999943e+01,0.000000000000000000e+00,1.027099670108537488e+01,0.000000000000000000e+00,-1.000000009839101089e+00,0.000000000000000000e+00,1.464157657803790709e-10,0.000000000000000000e+00 +3.766159818264838144e+00,4.111999999999999744e+01,0.000000000000000000e+00,1.027002308573046641e+01,0.000000000000000000e+00,-1.000000009838958537e+00,0.000000000000000000e+00,4.417141034509500373e-10,0.000000000000000000e+00 +3.767133525910529190e+00,4.113000000000000256e+01,0.000000000000000000e+00,1.026904937807519502e+01,0.000000000000000000e+00,-1.000000009838528436e+00,0.000000000000000000e+00,-1.120483897751023553e-09,0.000000000000000000e+00 +3.768107325882837255e+00,4.114000000000000057e+01,0.000000000000000000e+00,1.026807557809330618e+01,0.000000000000000000e+00,-1.000000009839619564e+00,0.000000000000000000e+00,1.087774061560757001e-09,0.000000000000000000e+00 +3.769081218208029771e+00,4.114999999999999858e+01,0.000000000000000000e+00,1.026710168575853110e+01,0.000000000000000000e+00,-1.000000009838560189e+00,0.000000000000000000e+00,-2.289557482050795024e-09,0.000000000000000000e+00 +3.770055202912386161e+00,4.116000000000000369e+01,0.000000000000000000e+00,1.026612770104459216e+01,0.000000000000000000e+00,-1.000000009840790183e+00,0.000000000000000000e+00,1.864662304441483392e-09,0.000000000000000000e+00 +3.771029280022198726e+00,4.117000000000000171e+01,0.000000000000000000e+00,1.026515362392519393e+01,0.000000000000000000e+00,-1.000000009838973858e+00,0.000000000000000000e+00,-1.420017594112675873e-09,0.000000000000000000e+00 +3.772003449563772204e+00,4.117999999999999972e+01,0.000000000000000000e+00,1.026417945437403567e+01,0.000000000000000000e+00,-1.000000009840357196e+00,0.000000000000000000e+00,9.699873739291907793e-10,0.000000000000000000e+00 +3.772977711563423764e+00,4.118999999999999773e+01,0.000000000000000000e+00,1.026320519236479711e+01,0.000000000000000000e+00,-1.000000009839412174e+00,0.000000000000000000e+00,-3.149425070924783076e-10,0.000000000000000000e+00 +3.773952066047483012e+00,4.120000000000000284e+01,0.000000000000000000e+00,1.026223083787115087e+01,0.000000000000000000e+00,-1.000000009839719040e+00,0.000000000000000000e+00,-1.523292895181796920e-09,0.000000000000000000e+00 +3.774926513042291987e+00,4.121000000000000085e+01,0.000000000000000000e+00,1.026125639086675356e+01,0.000000000000000000e+00,-1.000000009841203408e+00,0.000000000000000000e+00,1.095026252218148025e-09,0.000000000000000000e+00 +3.775901052574205607e+00,4.121999999999999886e+01,0.000000000000000000e+00,1.026028185132524939e+01,0.000000000000000000e+00,-1.000000009840136261e+00,0.000000000000000000e+00,-1.803910614190791725e-09,0.000000000000000000e+00 +3.776875684669590783e+00,4.123000000000000398e+01,0.000000000000000000e+00,1.025930721922027367e+01,0.000000000000000000e+00,-1.000000009841894411e+00,0.000000000000000000e+00,1.010075761032573719e-09,0.000000000000000000e+00 +3.777850409354827299e+00,4.124000000000000199e+01,0.000000000000000000e+00,1.025833249452544393e+01,0.000000000000000000e+00,-1.000000009840909865e+00,0.000000000000000000e+00,1.954358737133528199e-10,0.000000000000000000e+00 +3.778825226656307379e+00,4.125000000000000000e+01,0.000000000000000000e+00,1.025735767721437064e+01,0.000000000000000000e+00,-1.000000009840719351e+00,0.000000000000000000e+00,-2.367100256679165294e-09,0.000000000000000000e+00 +3.779800136600436122e+00,4.125999999999999801e+01,0.000000000000000000e+00,1.025638276726064824e+01,0.000000000000000000e+00,-1.000000009843027060e+00,0.000000000000000000e+00,2.674548565255930664e-09,0.000000000000000000e+00 +3.780775139213630620e+00,4.127000000000000313e+01,0.000000000000000000e+00,1.025540776463785697e+01,0.000000000000000000e+00,-1.000000009840419368e+00,0.000000000000000000e+00,-1.489716740993537651e-09,0.000000000000000000e+00 +3.781750234522320397e+00,4.128000000000000114e+01,0.000000000000000000e+00,1.025443266931957176e+01,0.000000000000000000e+00,-1.000000009841871984e+00,0.000000000000000000e+00,-1.769183507263362700e-09,0.000000000000000000e+00 +3.782725422552948302e+00,4.128999999999999915e+01,0.000000000000000000e+00,1.025345748127934620e+01,0.000000000000000000e+00,-1.000000009843597271e+00,0.000000000000000000e+00,1.841187439202275805e-09,0.000000000000000000e+00 +3.783700703331969173e+00,4.130000000000000426e+01,0.000000000000000000e+00,1.025248220049072501e+01,0.000000000000000000e+00,-1.000000009841801596e+00,0.000000000000000000e+00,1.274844681436971984e-11,0.000000000000000000e+00 +3.784676076885850726e+00,4.131000000000000227e+01,0.000000000000000000e+00,1.025150682692724402e+01,0.000000000000000000e+00,-1.000000009841789161e+00,0.000000000000000000e+00,-1.642116892451931163e-09,0.000000000000000000e+00 +3.785651543241073114e+00,4.132000000000000028e+01,0.000000000000000000e+00,1.025053136056242131e+01,0.000000000000000000e+00,-1.000000009843390991e+00,0.000000000000000000e+00,6.184096280980732786e-10,0.000000000000000000e+00 +3.786627102424128921e+00,4.132999999999999829e+01,0.000000000000000000e+00,1.024955580136976252e+01,0.000000000000000000e+00,-1.000000009842787696e+00,0.000000000000000000e+00,-6.636403585956568515e-10,0.000000000000000000e+00 +3.787602754461524057e+00,4.134000000000000341e+01,0.000000000000000000e+00,1.024858014932276440e+01,0.000000000000000000e+00,-1.000000009843435178e+00,0.000000000000000000e+00,1.192436371476619168e-10,0.000000000000000000e+00 +3.788578499379775977e+00,4.135000000000000142e+01,0.000000000000000000e+00,1.024760440439490772e+01,0.000000000000000000e+00,-1.000000009843318827e+00,0.000000000000000000e+00,-7.552136475782833240e-10,0.000000000000000000e+00 +3.789554337205415457e+00,4.135999999999999943e+01,0.000000000000000000e+00,1.024662856655966259e+01,0.000000000000000000e+00,-1.000000009844055793e+00,0.000000000000000000e+00,4.527665097831807030e-10,0.000000000000000000e+00 +3.790530267964986155e+00,4.136999999999999744e+01,0.000000000000000000e+00,1.024565263579048491e+01,0.000000000000000000e+00,-1.000000009843613924e+00,0.000000000000000000e+00,2.070242621459015586e-11,0.000000000000000000e+00 +3.791506291685043717e+00,4.138000000000000256e+01,0.000000000000000000e+00,1.024467661206081992e+01,0.000000000000000000e+00,-1.000000009843593718e+00,0.000000000000000000e+00,-1.765225532625968302e-10,0.000000000000000000e+00 +3.792482408392156668e+00,4.139000000000000057e+01,0.000000000000000000e+00,1.024370049534409866e+01,0.000000000000000000e+00,-1.000000009843766025e+00,0.000000000000000000e+00,-1.303321980080022935e-10,0.000000000000000000e+00 +3.793458618112905967e+00,4.139999999999999858e+01,0.000000000000000000e+00,1.024272428561373971e+01,0.000000000000000000e+00,-1.000000009843893256e+00,0.000000000000000000e+00,-1.695749147179982266e-09,0.000000000000000000e+00 +3.794434920873885897e+00,4.141000000000000369e+01,0.000000000000000000e+00,1.024174798284314925e+01,0.000000000000000000e+00,-1.000000009845548821e+00,0.000000000000000000e+00,7.270377256041082019e-10,0.000000000000000000e+00 +3.795411316701702731e+00,4.142000000000000171e+01,0.000000000000000000e+00,1.024077158700571921e+01,0.000000000000000000e+00,-1.000000009844838944e+00,0.000000000000000000e+00,1.555353127516292909e-09,0.000000000000000000e+00 +3.796387805622976064e+00,4.142999999999999972e+01,0.000000000000000000e+00,1.023979509807483268e+01,0.000000000000000000e+00,-1.000000009843320159e+00,0.000000000000000000e+00,-2.925558540465919083e-09,0.000000000000000000e+00 +3.797364387664337482e+00,4.143999999999999773e+01,0.000000000000000000e+00,1.023881851602385851e+01,0.000000000000000000e+00,-1.000000009846177207e+00,0.000000000000000000e+00,3.314725693118255553e-10,0.000000000000000000e+00 +3.798341062852431893e+00,4.145000000000000284e+01,0.000000000000000000e+00,1.023784184082614779e+01,0.000000000000000000e+00,-1.000000009845853466e+00,0.000000000000000000e+00,2.021380610642300298e-09,0.000000000000000000e+00 +3.799317831213916197e+00,4.146000000000000085e+01,0.000000000000000000e+00,1.023686507245504629e+01,0.000000000000000000e+00,-1.000000009843879045e+00,0.000000000000000000e+00,-3.429563748840219421e-09,0.000000000000000000e+00 +3.800294692775460614e+00,4.146999999999999886e+01,0.000000000000000000e+00,1.023588821088388556e+01,0.000000000000000000e+00,-1.000000009847229254e+00,0.000000000000000000e+00,2.601701351023507213e-09,0.000000000000000000e+00 +3.801271647563748246e+00,4.148000000000000398e+01,0.000000000000000000e+00,1.023491125608597763e+01,0.000000000000000000e+00,-1.000000009844687510e+00,0.000000000000000000e+00,-2.211246441990256579e-09,0.000000000000000000e+00 +3.802248695605474627e+00,4.149000000000000199e+01,0.000000000000000000e+00,1.023393420803463272e+01,0.000000000000000000e+00,-1.000000009846848004e+00,0.000000000000000000e+00,7.512520936839294774e-10,0.000000000000000000e+00 +3.803225836927347725e+00,4.150000000000000000e+01,0.000000000000000000e+00,1.023295706670313798e+01,0.000000000000000000e+00,-1.000000009846113924e+00,0.000000000000000000e+00,3.331005484727267909e-10,0.000000000000000000e+00 +3.804203071556088389e+00,4.150999999999999801e+01,0.000000000000000000e+00,1.023197983206477524e+01,0.000000000000000000e+00,-1.000000009845788407e+00,0.000000000000000000e+00,-1.595367446610903570e-09,0.000000000000000000e+00 +3.805180399518430789e+00,4.152000000000000313e+01,0.000000000000000000e+00,1.023100250409281031e+01,0.000000000000000000e+00,-1.000000009847347604e+00,0.000000000000000000e+00,5.538499460162221622e-10,0.000000000000000000e+00 +3.806157820841121087e+00,4.153000000000000114e+01,0.000000000000000000e+00,1.023002508276049483e+01,0.000000000000000000e+00,-1.000000009846806259e+00,0.000000000000000000e+00,1.210039704343860403e-09,0.000000000000000000e+00 +3.807135335550919208e+00,4.153999999999999915e+01,0.000000000000000000e+00,1.022904756804107151e+01,0.000000000000000000e+00,-1.000000009845623428e+00,0.000000000000000000e+00,-1.474758223525067314e-09,0.000000000000000000e+00 +3.808112943674596629e+00,4.155000000000000426e+01,0.000000000000000000e+00,1.022806995990776890e+01,0.000000000000000000e+00,-1.000000009847065163e+00,0.000000000000000000e+00,-1.915435411211910360e-09,0.000000000000000000e+00 +3.809090645238938588e+00,4.156000000000000227e+01,0.000000000000000000e+00,1.022709225833379953e+01,0.000000000000000000e+00,-1.000000009848937887e+00,0.000000000000000000e+00,1.753566323677926369e-09,0.000000000000000000e+00 +3.810068440270742762e+00,4.157000000000000028e+01,0.000000000000000000e+00,1.022611446329236529e+01,0.000000000000000000e+00,-1.000000009847223259e+00,0.000000000000000000e+00,2.509072168241491618e-10,0.000000000000000000e+00 +3.811046328796819260e+00,4.157999999999999829e+01,0.000000000000000000e+00,1.022513657475665916e+01,0.000000000000000000e+00,-1.000000009846977900e+00,0.000000000000000000e+00,-8.396073848049328128e-10,0.000000000000000000e+00 +3.812024310843991959e+00,4.159000000000000341e+01,0.000000000000000000e+00,1.022415859269985638e+01,0.000000000000000000e+00,-1.000000009847799021e+00,0.000000000000000000e+00,-1.508560695217887546e-09,0.000000000000000000e+00 +3.813002386439096725e+00,4.160000000000000142e+01,0.000000000000000000e+00,1.022318051709511977e+01,0.000000000000000000e+00,-1.000000009849274507e+00,0.000000000000000000e+00,1.964459799162846893e-09,0.000000000000000000e+00 +3.813980555608982748e+00,4.160999999999999943e+01,0.000000000000000000e+00,1.022220234791559967e+01,0.000000000000000000e+00,-1.000000009847352933e+00,0.000000000000000000e+00,-1.550036095785758955e-09,0.000000000000000000e+00 +3.814958818380511651e+00,4.161999999999999744e+01,0.000000000000000000e+00,1.022122408513443759e+01,0.000000000000000000e+00,-1.000000009848869276e+00,0.000000000000000000e+00,9.511758079127836033e-10,0.000000000000000000e+00 +3.815937174780557939e+00,4.163000000000000256e+01,0.000000000000000000e+00,1.022024572872475545e+01,0.000000000000000000e+00,-1.000000009847938687e+00,0.000000000000000000e+00,-1.658214355599691538e-09,0.000000000000000000e+00 +3.816915624836009435e+00,4.164000000000000057e+01,0.000000000000000000e+00,1.021926727865966811e+01,0.000000000000000000e+00,-1.000000009849561167e+00,0.000000000000000000e+00,1.763343382920374382e-09,0.000000000000000000e+00 +3.817894168573766844e+00,4.164999999999999858e+01,0.000000000000000000e+00,1.021828873491227263e+01,0.000000000000000000e+00,-1.000000009847835658e+00,0.000000000000000000e+00,-1.761586293233172250e-09,0.000000000000000000e+00 +3.818872806020742861e+00,4.166000000000000369e+01,0.000000000000000000e+00,1.021731009745565899e+01,0.000000000000000000e+00,-1.000000009849559612e+00,0.000000000000000000e+00,-1.093058977764490786e-09,0.000000000000000000e+00 +3.819851537203863945e+00,4.167000000000000171e+01,0.000000000000000000e+00,1.021633136626289762e+01,0.000000000000000000e+00,-1.000000009850629423e+00,0.000000000000000000e+00,1.921176780792077451e-09,0.000000000000000000e+00 +3.820830362150069437e+00,4.167999999999999972e+01,0.000000000000000000e+00,1.021535254130705006e+01,0.000000000000000000e+00,-1.000000009848748928e+00,0.000000000000000000e+00,-1.267959530835281046e-10,0.000000000000000000e+00 +3.821809280886311111e+00,4.168999999999999773e+01,0.000000000000000000e+00,1.021437362256116721e+01,0.000000000000000000e+00,-1.000000009848873050e+00,0.000000000000000000e+00,-1.663612148516650167e-09,0.000000000000000000e+00 +3.822788293439554064e+00,4.170000000000000284e+01,0.000000000000000000e+00,1.021339460999828219e+01,0.000000000000000000e+00,-1.000000009850501748e+00,0.000000000000000000e+00,1.024605219512247831e-09,0.000000000000000000e+00 +3.823767399836775827e+00,4.171000000000000085e+01,0.000000000000000000e+00,1.021241550359141570e+01,0.000000000000000000e+00,-1.000000009849498550e+00,0.000000000000000000e+00,-1.318389480650783306e-09,0.000000000000000000e+00 +3.824746600104967253e+00,4.171999999999999886e+01,0.000000000000000000e+00,1.021143630331357954e+01,0.000000000000000000e+00,-1.000000009850789517e+00,0.000000000000000000e+00,5.806796903936834491e-10,0.000000000000000000e+00 +3.825725894271132077e+00,4.173000000000000398e+01,0.000000000000000000e+00,1.021045700913776777e+01,0.000000000000000000e+00,-1.000000009850220861e+00,0.000000000000000000e+00,-6.794729147415943502e-10,0.000000000000000000e+00 +3.826705282362286908e+00,4.174000000000000199e+01,0.000000000000000000e+00,1.020947762103696554e+01,0.000000000000000000e+00,-1.000000009850886329e+00,0.000000000000000000e+00,4.672203374624302524e-10,0.000000000000000000e+00 +3.827684764405461681e+00,4.175000000000000000e+01,0.000000000000000000e+00,1.020849813898414205e+01,0.000000000000000000e+00,-1.000000009850428695e+00,0.000000000000000000e+00,-1.525970671415271846e-09,0.000000000000000000e+00 +3.828664340427698765e+00,4.175999999999999801e+01,0.000000000000000000e+00,1.020751856295225579e+01,0.000000000000000000e+00,-1.000000009851923499e+00,0.000000000000000000e+00,7.565658535909542261e-10,0.000000000000000000e+00 +3.829644010456053405e+00,4.177000000000000313e+01,0.000000000000000000e+00,1.020653889291424932e+01,0.000000000000000000e+00,-1.000000009851182314e+00,0.000000000000000000e+00,-8.226694032948671269e-11,0.000000000000000000e+00 +3.830623774517594615e+00,4.178000000000000114e+01,0.000000000000000000e+00,1.020555912884305627e+01,0.000000000000000000e+00,-1.000000009851262917e+00,0.000000000000000000e+00,-3.297159996688369406e-10,0.000000000000000000e+00 +3.831603632639403845e+00,4.178999999999999915e+01,0.000000000000000000e+00,1.020457927071159432e+01,0.000000000000000000e+00,-1.000000009851585991e+00,0.000000000000000000e+00,2.197895619413580615e-11,0.000000000000000000e+00 +3.832583584848575420e+00,4.180000000000000426e+01,0.000000000000000000e+00,1.020359931849276869e+01,0.000000000000000000e+00,-1.000000009851564453e+00,0.000000000000000000e+00,-8.670658544900750270e-10,0.000000000000000000e+00 +3.833563631172216990e+00,4.181000000000000227e+01,0.000000000000000000e+00,1.020261927215947217e+01,0.000000000000000000e+00,-1.000000009852414218e+00,0.000000000000000000e+00,7.102143632802247911e-10,0.000000000000000000e+00 +3.834543771637449083e+00,4.182000000000000028e+01,0.000000000000000000e+00,1.020163913168458336e+01,0.000000000000000000e+00,-1.000000009851718108e+00,0.000000000000000000e+00,-7.837657499815944695e-10,0.000000000000000000e+00 +3.835524006271405106e+00,4.182999999999999829e+01,0.000000000000000000e+00,1.020065889704097017e+01,0.000000000000000000e+00,-1.000000009852486382e+00,0.000000000000000000e+00,2.065681162588842562e-10,0.000000000000000000e+00 +3.836504335101232233e+00,4.184000000000000341e+01,0.000000000000000000e+00,1.019967856820148455e+01,0.000000000000000000e+00,-1.000000009852283878e+00,0.000000000000000000e+00,-7.700264233331265955e-12,0.000000000000000000e+00 +3.837484758154089626e+00,4.185000000000000142e+01,0.000000000000000000e+00,1.019869814513896777e+01,0.000000000000000000e+00,-1.000000009852291427e+00,0.000000000000000000e+00,4.323056303838843913e-10,0.000000000000000000e+00 +3.838465275457150216e+00,4.185999999999999943e+01,0.000000000000000000e+00,1.019771762782624691e+01,0.000000000000000000e+00,-1.000000009851867544e+00,0.000000000000000000e+00,-2.160188165444551839e-09,0.000000000000000000e+00 +3.839445887037599814e+00,4.186999999999999744e+01,0.000000000000000000e+00,1.019673701623613660e+01,0.000000000000000000e+00,-1.000000009853985850e+00,0.000000000000000000e+00,1.460364135280013899e-09,0.000000000000000000e+00 +3.840426592922637106e+00,4.188000000000000256e+01,0.000000000000000000e+00,1.019575631034143548e+01,0.000000000000000000e+00,-1.000000009852553662e+00,0.000000000000000000e+00,2.202787039431934125e-10,0.000000000000000000e+00 +3.841407393139474102e+00,4.189000000000000057e+01,0.000000000000000000e+00,1.019477551011493510e+01,0.000000000000000000e+00,-1.000000009852337612e+00,0.000000000000000000e+00,-2.175863538305672326e-09,0.000000000000000000e+00 +3.842388287715335693e+00,4.189999999999999858e+01,0.000000000000000000e+00,1.019379461552940924e+01,0.000000000000000000e+00,-1.000000009854471905e+00,0.000000000000000000e+00,1.665013753356577721e-09,0.000000000000000000e+00 +3.843369276677460533e+00,4.191000000000000369e+01,0.000000000000000000e+00,1.019281362655761747e+01,0.000000000000000000e+00,-1.000000009852838545e+00,0.000000000000000000e+00,-1.169878719135571426e-09,0.000000000000000000e+00 +3.844350360053099269e+00,4.192000000000000171e+01,0.000000000000000000e+00,1.019183254317231224e+01,0.000000000000000000e+00,-1.000000009853986294e+00,0.000000000000000000e+00,4.030476787739687404e-10,0.000000000000000000e+00 +3.845331537869516314e+00,4.192999999999999972e+01,0.000000000000000000e+00,1.019085136534622649e+01,0.000000000000000000e+00,-1.000000009853590832e+00,0.000000000000000000e+00,-9.881750509525438334e-10,0.000000000000000000e+00 +3.846312810153989403e+00,4.193999999999999773e+01,0.000000000000000000e+00,1.018987009305208424e+01,0.000000000000000000e+00,-1.000000009854560501e+00,0.000000000000000000e+00,1.997880814600392244e-10,0.000000000000000000e+00 +3.847294176933809151e+00,4.195000000000000284e+01,0.000000000000000000e+00,1.018888872626259356e+01,0.000000000000000000e+00,-1.000000009854364436e+00,0.000000000000000000e+00,2.873232470247065050e-10,0.000000000000000000e+00 +3.848275638236279050e+00,4.196000000000000085e+01,0.000000000000000000e+00,1.018790726495045185e+01,0.000000000000000000e+00,-1.000000009854082439e+00,0.000000000000000000e+00,-7.162029725023695876e-10,0.000000000000000000e+00 +3.849257194088716361e+00,4.196999999999999886e+01,0.000000000000000000e+00,1.018692570908834227e+01,0.000000000000000000e+00,-1.000000009854785432e+00,0.000000000000000000e+00,-9.570318465524424423e-10,0.000000000000000000e+00 +3.850238844518450776e+00,4.198000000000000398e+01,0.000000000000000000e+00,1.018594405864893382e+01,0.000000000000000000e+00,-1.000000009855724903e+00,0.000000000000000000e+00,1.415619263213844555e-09,0.000000000000000000e+00 +3.851220589552825757e+00,4.199000000000000199e+01,0.000000000000000000e+00,1.018496231360488302e+01,0.000000000000000000e+00,-1.000000009854335126e+00,0.000000000000000000e+00,-9.597873620079493776e-10,0.000000000000000000e+00 +3.852202429219197644e+00,4.200000000000000000e+01,0.000000000000000000e+00,1.018398047392883576e+01,0.000000000000000000e+00,-1.000000009855277483e+00,0.000000000000000000e+00,-7.037159129833833247e-10,0.000000000000000000e+00 +3.853184363544936097e+00,4.200999999999999801e+01,0.000000000000000000e+00,1.018299853959342016e+01,0.000000000000000000e+00,-1.000000009855968486e+00,0.000000000000000000e+00,2.193247491045906022e-09,0.000000000000000000e+00 +3.854166392557423659e+00,4.202000000000000313e+01,0.000000000000000000e+00,1.018201651057125368e+01,0.000000000000000000e+00,-1.000000009853814653e+00,0.000000000000000000e+00,-3.311936499791518807e-09,0.000000000000000000e+00 +3.855148516284056637e+00,4.203000000000000114e+01,0.000000000000000000e+00,1.018103438683494311e+01,0.000000000000000000e+00,-1.000000009857067385e+00,0.000000000000000000e+00,1.207861959981106831e-09,0.000000000000000000e+00 +3.856130734752244216e+00,4.203999999999999915e+01,0.000000000000000000e+00,1.018005216835707394e+01,0.000000000000000000e+00,-1.000000009855881000e+00,0.000000000000000000e+00,1.028493676136769878e-09,0.000000000000000000e+00 +3.857113047989408461e+00,4.205000000000000426e+01,0.000000000000000000e+00,1.017906985511022810e+01,0.000000000000000000e+00,-1.000000009854870697e+00,0.000000000000000000e+00,-1.997119386304512502e-09,0.000000000000000000e+00 +3.858095456022985204e+00,4.206000000000000227e+01,0.000000000000000000e+00,1.017808744706696977e+01,0.000000000000000000e+00,-1.000000009856832683e+00,0.000000000000000000e+00,1.342659706149992833e-09,0.000000000000000000e+00 +3.859077958880423598e+00,4.207000000000000028e+01,0.000000000000000000e+00,1.017710494419984713e+01,0.000000000000000000e+00,-1.000000009855513516e+00,0.000000000000000000e+00,-1.825217235891289196e-09,0.000000000000000000e+00 +3.860060556589185676e+00,4.207999999999999829e+01,0.000000000000000000e+00,1.017612234648140124e+01,0.000000000000000000e+00,-1.000000009857306971e+00,0.000000000000000000e+00,1.388947269727517901e-09,0.000000000000000000e+00 +3.861043249176746350e+00,4.209000000000000341e+01,0.000000000000000000e+00,1.017513965388415365e+01,0.000000000000000000e+00,-1.000000009855942062e+00,0.000000000000000000e+00,-4.541263077652490643e-11,0.000000000000000000e+00 +3.862026036670594742e+00,4.210000000000000142e+01,0.000000000000000000e+00,1.017415686638061878e+01,0.000000000000000000e+00,-1.000000009855986693e+00,0.000000000000000000e+00,-2.436909121553648080e-09,0.000000000000000000e+00 +3.863008919098232852e+00,4.210999999999999943e+01,0.000000000000000000e+00,1.017317398394329331e+01,0.000000000000000000e+00,-1.000000009858381889e+00,0.000000000000000000e+00,1.576711081872610017e-09,0.000000000000000000e+00 +3.863991896487176003e+00,4.211999999999999744e+01,0.000000000000000000e+00,1.017219100654465969e+01,0.000000000000000000e+00,-1.000000009856832017e+00,0.000000000000000000e+00,-8.648486230291463852e-10,0.000000000000000000e+00 +3.864974968864952398e+00,4.213000000000000256e+01,0.000000000000000000e+00,1.017120793415719326e+01,0.000000000000000000e+00,-1.000000009857682226e+00,0.000000000000000000e+00,1.277386020861317037e-09,0.000000000000000000e+00 +3.865958136259104005e+00,4.214000000000000057e+01,0.000000000000000000e+00,1.017022476675334985e+01,0.000000000000000000e+00,-1.000000009856426342e+00,0.000000000000000000e+00,-1.176319060159207739e-09,0.000000000000000000e+00 +3.866941398697186116e+00,4.214999999999999858e+01,0.000000000000000000e+00,1.016924150430557638e+01,0.000000000000000000e+00,-1.000000009857582972e+00,0.000000000000000000e+00,-8.661784714040485233e-10,0.000000000000000000e+00 +3.867924756206766901e+00,4.216000000000000369e+01,0.000000000000000000e+00,1.016825814678630202e+01,0.000000000000000000e+00,-1.000000009858434735e+00,0.000000000000000000e+00,3.788599916078586610e-10,0.000000000000000000e+00 +3.868908208815428296e+00,4.217000000000000171e+01,0.000000000000000000e+00,1.016727469416794527e+01,0.000000000000000000e+00,-1.000000009858062144e+00,0.000000000000000000e+00,7.312329127631128815e-10,0.000000000000000000e+00 +3.869891756550765560e+00,4.217999999999999972e+01,0.000000000000000000e+00,1.016629114642291221e+01,0.000000000000000000e+00,-1.000000009857342942e+00,0.000000000000000000e+00,-1.634787427260303184e-09,0.000000000000000000e+00 +3.870875399440386833e+00,4.218999999999999773e+01,0.000000000000000000e+00,1.016530750352359469e+01,0.000000000000000000e+00,-1.000000009858950989e+00,0.000000000000000000e+00,6.338081941480278847e-10,0.000000000000000000e+00 +3.871859137511914462e+00,4.220000000000000284e+01,0.000000000000000000e+00,1.016432376544236860e+01,0.000000000000000000e+00,-1.000000009858327488e+00,0.000000000000000000e+00,2.026726062835326226e-10,0.000000000000000000e+00 +3.872842970792983230e+00,4.221000000000000085e+01,0.000000000000000000e+00,1.016333993215160092e+01,0.000000000000000000e+00,-1.000000009858128092e+00,0.000000000000000000e+00,-1.082320418057649073e-09,0.000000000000000000e+00 +3.873826899311241689e+00,4.221999999999999886e+01,0.000000000000000000e+00,1.016235600362364266e+01,0.000000000000000000e+00,-1.000000009859193018e+00,0.000000000000000000e+00,4.580687537582228028e-10,0.000000000000000000e+00 +3.874810923094352155e+00,4.223000000000000398e+01,0.000000000000000000e+00,1.016137197983083063e+01,0.000000000000000000e+00,-1.000000009858742267e+00,0.000000000000000000e+00,-6.716939090258029530e-10,0.000000000000000000e+00 +3.875795042169989824e+00,4.224000000000000199e+01,0.000000000000000000e+00,1.016038786074549094e+01,0.000000000000000000e+00,-1.000000009859403294e+00,0.000000000000000000e+00,1.041622582699506910e-09,0.000000000000000000e+00 +3.876779256565843212e+00,4.225000000000000000e+01,0.000000000000000000e+00,1.015940364633993376e+01,0.000000000000000000e+00,-1.000000009858378114e+00,0.000000000000000000e+00,-1.728876365304482463e-09,0.000000000000000000e+00 +3.877763566309614607e+00,4.225999999999999801e+01,0.000000000000000000e+00,1.015841933658645857e+01,0.000000000000000000e+00,-1.000000009860079864e+00,0.000000000000000000e+00,2.028255489663020839e-09,0.000000000000000000e+00 +3.878747971429019614e+00,4.227000000000000313e+01,0.000000000000000000e+00,1.015743493145734710e+01,0.000000000000000000e+00,-1.000000009858083239e+00,0.000000000000000000e+00,-2.343815448562319642e-09,0.000000000000000000e+00 +3.879732471951787609e+00,4.228000000000000114e+01,0.000000000000000000e+00,1.015645043092487398e+01,0.000000000000000000e+00,-1.000000009860390726e+00,0.000000000000000000e+00,-1.713940617765286995e-10,0.000000000000000000e+00 +3.880717067905660400e+00,4.228999999999999915e+01,0.000000000000000000e+00,1.015546583496129252e+01,0.000000000000000000e+00,-1.000000009860559480e+00,0.000000000000000000e+00,1.221740795061438516e-09,0.000000000000000000e+00 +3.881701759318394451e+00,4.230000000000000426e+01,0.000000000000000000e+00,1.015448114353884890e+01,0.000000000000000000e+00,-1.000000009859356442e+00,0.000000000000000000e+00,1.488133517465603879e-11,0.000000000000000000e+00 +3.882686546217758661e+00,4.231000000000000227e+01,0.000000000000000000e+00,1.015349635662977512e+01,0.000000000000000000e+00,-1.000000009859341787e+00,0.000000000000000000e+00,-1.949265848720150331e-09,0.000000000000000000e+00 +3.883671428631536138e+00,4.232000000000000028e+01,0.000000000000000000e+00,1.015251147420628719e+01,0.000000000000000000e+00,-1.000000009861261585e+00,0.000000000000000000e+00,8.307133821372529099e-10,0.000000000000000000e+00 +3.884656406587523314e+00,4.232999999999999829e+01,0.000000000000000000e+00,1.015152649624058689e+01,0.000000000000000000e+00,-1.000000009860443351e+00,0.000000000000000000e+00,1.040037905878456228e-09,0.000000000000000000e+00 +3.885641480113529944e+00,4.234000000000000341e+01,0.000000000000000000e+00,1.015054142270486714e+01,0.000000000000000000e+00,-1.000000009859418837e+00,0.000000000000000000e+00,-1.311077900820172467e-09,0.000000000000000000e+00 +3.886626649237379105e+00,4.235000000000000142e+01,0.000000000000000000e+00,1.014955625357130486e+01,0.000000000000000000e+00,-1.000000009860710470e+00,0.000000000000000000e+00,-7.209439812955098453e-10,0.000000000000000000e+00 +3.887611913986907641e+00,4.235999999999999943e+01,0.000000000000000000e+00,1.014857098881206099e+01,0.000000000000000000e+00,-1.000000009861420791e+00,0.000000000000000000e+00,9.879060950391167815e-10,0.000000000000000000e+00 +3.888597274389965719e+00,4.236999999999999744e+01,0.000000000000000000e+00,1.014758562839928580e+01,0.000000000000000000e+00,-1.000000009860447348e+00,0.000000000000000000e+00,-1.663324524977383844e-09,0.000000000000000000e+00 +3.889582730474417271e+00,4.238000000000000256e+01,0.000000000000000000e+00,1.014660017230511713e+01,0.000000000000000000e+00,-1.000000009862086481e+00,0.000000000000000000e+00,4.816909353253148802e-10,0.000000000000000000e+00 +3.890568282268139555e+00,4.239000000000000057e+01,0.000000000000000000e+00,1.014561462050167506e+01,0.000000000000000000e+00,-1.000000009861611749e+00,0.000000000000000000e+00,1.155675621937159764e-10,0.000000000000000000e+00 +3.891553929799023592e+00,4.239999999999999858e+01,0.000000000000000000e+00,1.014462897296107080e+01,0.000000000000000000e+00,-1.000000009861497841e+00,0.000000000000000000e+00,9.059796852561735459e-10,0.000000000000000000e+00 +3.892539673094973729e+00,4.241000000000000369e+01,0.000000000000000000e+00,1.014364322965539955e+01,0.000000000000000000e+00,-1.000000009860604777e+00,0.000000000000000000e+00,-2.621950453117049986e-09,0.000000000000000000e+00 +3.893525512183908077e+00,4.242000000000000171e+01,0.000000000000000000e+00,1.014265739055674409e+01,0.000000000000000000e+00,-1.000000009863189598e+00,0.000000000000000000e+00,2.335450880243637391e-09,0.000000000000000000e+00 +3.894511447093758072e+00,4.242999999999999972e+01,0.000000000000000000e+00,1.014167145563716943e+01,0.000000000000000000e+00,-1.000000009860886996e+00,0.000000000000000000e+00,-2.487002149910309279e-09,0.000000000000000000e+00 +3.895497477852468915e+00,4.243999999999999773e+01,0.000000000000000000e+00,1.014068542486873525e+01,0.000000000000000000e+00,-1.000000009863339256e+00,0.000000000000000000e+00,1.192266936837603810e-09,0.000000000000000000e+00 +3.896483604487999575e+00,4.245000000000000284e+01,0.000000000000000000e+00,1.013969929822347815e+01,0.000000000000000000e+00,-1.000000009862163530e+00,0.000000000000000000e+00,5.932611657670530563e-10,0.000000000000000000e+00 +3.897469827028321898e+00,4.246000000000000085e+01,0.000000000000000000e+00,1.013871307567342939e+01,0.000000000000000000e+00,-1.000000009861578443e+00,0.000000000000000000e+00,-6.197681722792435867e-10,0.000000000000000000e+00 +3.898456145501422387e+00,4.246999999999999886e+01,0.000000000000000000e+00,1.013772675719060246e+01,0.000000000000000000e+00,-1.000000009862189732e+00,0.000000000000000000e+00,-6.111539751113000769e-10,0.000000000000000000e+00 +3.899442559935299979e+00,4.248000000000000398e+01,0.000000000000000000e+00,1.013674034274699665e+01,0.000000000000000000e+00,-1.000000009862792583e+00,0.000000000000000000e+00,-1.197205043614230521e-09,0.000000000000000000e+00 +3.900429070357968264e+00,4.249000000000000199e+01,0.000000000000000000e+00,1.013575383231459881e+01,0.000000000000000000e+00,-1.000000009863973638e+00,0.000000000000000000e+00,1.281260576910070624e-09,0.000000000000000000e+00 +3.901415676797453713e+00,4.250000000000000000e+01,0.000000000000000000e+00,1.013476722586538159e+01,0.000000000000000000e+00,-1.000000009862709538e+00,0.000000000000000000e+00,-4.658266696276079273e-10,0.000000000000000000e+00 +3.902402379281796563e+00,4.250999999999999801e+01,0.000000000000000000e+00,1.013378052337130697e+01,0.000000000000000000e+00,-1.000000009863169170e+00,0.000000000000000000e+00,8.696834746320124823e-10,0.000000000000000000e+00 +3.903389177839051261e+00,4.252000000000000313e+01,0.000000000000000000e+00,1.013279372480431917e+01,0.000000000000000000e+00,-1.000000009862310968e+00,0.000000000000000000e+00,-1.998839748188742485e-09,0.000000000000000000e+00 +3.904376072497285577e+00,4.253000000000000114e+01,0.000000000000000000e+00,1.013180683013635175e+01,0.000000000000000000e+00,-1.000000009864283612e+00,0.000000000000000000e+00,5.804259655517848861e-11,0.000000000000000000e+00 +3.905363063284581049e+00,4.253999999999999915e+01,0.000000000000000000e+00,1.013081983933932051e+01,0.000000000000000000e+00,-1.000000009864226325e+00,0.000000000000000000e+00,1.576220367877092818e-09,0.000000000000000000e+00 +3.906350150229032536e+00,4.255000000000000426e+01,0.000000000000000000e+00,1.012983275238513237e+01,0.000000000000000000e+00,-1.000000009862670458e+00,0.000000000000000000e+00,-1.078302296673923712e-09,0.000000000000000000e+00 +3.907337333358748666e+00,4.256000000000000227e+01,0.000000000000000000e+00,1.012884556924568003e+01,0.000000000000000000e+00,-1.000000009863734940e+00,0.000000000000000000e+00,-6.047710273838021633e-10,0.000000000000000000e+00 +3.908324612701851830e+00,4.257000000000000028e+01,0.000000000000000000e+00,1.012785828989283843e+01,0.000000000000000000e+00,-1.000000009864332018e+00,0.000000000000000000e+00,-6.388943907606038091e-10,0.000000000000000000e+00 +3.909311988286478634e+00,4.257999999999999829e+01,0.000000000000000000e+00,1.012687091429847186e+01,0.000000000000000000e+00,-1.000000009864962847e+00,0.000000000000000000e+00,6.505249129388319894e-10,0.000000000000000000e+00 +3.910299460140778560e+00,4.259000000000000341e+01,0.000000000000000000e+00,1.012588344243443039e+01,0.000000000000000000e+00,-1.000000009864320472e+00,0.000000000000000000e+00,-3.709856351012243893e-10,0.000000000000000000e+00 +3.911287028292915746e+00,4.260000000000000142e+01,0.000000000000000000e+00,1.012489587427255167e+01,0.000000000000000000e+00,-1.000000009864686845e+00,0.000000000000000000e+00,-4.923510924438742625e-11,0.000000000000000000e+00 +3.912274692771067208e+00,4.260999999999999943e+01,0.000000000000000000e+00,1.012390820978465733e+01,0.000000000000000000e+00,-1.000000009864735473e+00,0.000000000000000000e+00,-1.966964298896550859e-10,0.000000000000000000e+00 +3.913262453603423729e+00,4.261999999999999744e+01,0.000000000000000000e+00,1.012292044894255660e+01,0.000000000000000000e+00,-1.000000009864929762e+00,0.000000000000000000e+00,1.016877517990091963e-09,0.000000000000000000e+00 +3.914250310818190748e+00,4.263000000000000256e+01,0.000000000000000000e+00,1.012193259171804449e+01,0.000000000000000000e+00,-1.000000009863925232e+00,0.000000000000000000e+00,-1.859823233118325336e-09,0.000000000000000000e+00 +3.915238264443586580e+00,4.264000000000000057e+01,0.000000000000000000e+00,1.012094463808290357e+01,0.000000000000000000e+00,-1.000000009865762651e+00,0.000000000000000000e+00,2.840588658189877602e-10,0.000000000000000000e+00 +3.916226314507843753e+00,4.264999999999999858e+01,0.000000000000000000e+00,1.011995658800889863e+01,0.000000000000000000e+00,-1.000000009865481987e+00,0.000000000000000000e+00,1.775194592329894065e-10,0.000000000000000000e+00 +3.917214461039208118e+00,4.266000000000000369e+01,0.000000000000000000e+00,1.011896844146778562e+01,0.000000000000000000e+00,-1.000000009865306572e+00,0.000000000000000000e+00,-3.493870953992763123e-10,0.000000000000000000e+00 +3.918202704065939734e+00,4.267000000000000171e+01,0.000000000000000000e+00,1.011798019843130447e+01,0.000000000000000000e+00,-1.000000009865651851e+00,0.000000000000000000e+00,5.315557138782725843e-10,0.000000000000000000e+00 +3.919191043616312875e+00,4.267999999999999972e+01,0.000000000000000000e+00,1.011699185887118091e+01,0.000000000000000000e+00,-1.000000009865126493e+00,0.000000000000000000e+00,-8.064660222594786474e-10,0.000000000000000000e+00 +3.920179479718614690e+00,4.268999999999999773e+01,0.000000000000000000e+00,1.011600342275912823e+01,0.000000000000000000e+00,-1.000000009865923634e+00,0.000000000000000000e+00,-7.172129319081820831e-10,0.000000000000000000e+00 +3.921168012401146541e+00,4.270000000000000284e+01,0.000000000000000000e+00,1.011501489006684373e+01,0.000000000000000000e+00,-1.000000009866632622e+00,0.000000000000000000e+00,8.074314223847145465e-10,0.000000000000000000e+00 +3.922156641692223555e+00,4.271000000000000085e+01,0.000000000000000000e+00,1.011402626076601230e+01,0.000000000000000000e+00,-1.000000009865834372e+00,0.000000000000000000e+00,1.435043812809562743e-10,0.000000000000000000e+00 +3.923145367620175072e+00,4.271999999999999886e+01,0.000000000000000000e+00,1.011303753482830636e+01,0.000000000000000000e+00,-1.000000009865692485e+00,0.000000000000000000e+00,-8.824993516370946593e-10,0.000000000000000000e+00 +3.924134190213343754e+00,4.273000000000000398e+01,0.000000000000000000e+00,1.011204871222538237e+01,0.000000000000000000e+00,-1.000000009866565120e+00,0.000000000000000000e+00,-4.432273250184005335e-10,0.000000000000000000e+00 +3.925123109500086471e+00,4.274000000000000199e+01,0.000000000000000000e+00,1.011105979292888257e+01,0.000000000000000000e+00,-1.000000009867003437e+00,0.000000000000000000e+00,1.468748526475066586e-09,0.000000000000000000e+00 +3.926112125508773865e+00,4.275000000000000000e+01,0.000000000000000000e+00,1.011007077691043676e+01,0.000000000000000000e+00,-1.000000009865550821e+00,0.000000000000000000e+00,-2.399110385749954988e-09,0.000000000000000000e+00 +3.927101238267790340e+00,4.275999999999999801e+01,0.000000000000000000e+00,1.010908166414166232e+01,0.000000000000000000e+00,-1.000000009867923811e+00,0.000000000000000000e+00,6.736245799851910147e-10,0.000000000000000000e+00 +3.928090447805534069e+00,4.277000000000000313e+01,0.000000000000000000e+00,1.010809245459415706e+01,0.000000000000000000e+00,-1.000000009867257456e+00,0.000000000000000000e+00,1.616451014329880936e-09,0.000000000000000000e+00 +3.929079754150417880e+00,4.278000000000000114e+01,0.000000000000000000e+00,1.010710314823951173e+01,0.000000000000000000e+00,-1.000000009865658290e+00,0.000000000000000000e+00,-1.373242945225729414e-09,0.000000000000000000e+00 +3.930069157330867480e+00,4.278999999999999915e+01,0.000000000000000000e+00,1.010611374504930104e+01,0.000000000000000000e+00,-1.000000009867016981e+00,0.000000000000000000e+00,-1.026409274681572224e-09,0.000000000000000000e+00 +3.931058657375323229e+00,4.280000000000000426e+01,0.000000000000000000e+00,1.010512424499508199e+01,0.000000000000000000e+00,-1.000000009868032613e+00,0.000000000000000000e+00,8.501713947125812914e-10,0.000000000000000000e+00 +3.932048254312238811e+00,4.281000000000000227e+01,0.000000000000000000e+00,1.010413464804840089e+01,0.000000000000000000e+00,-1.000000009867191286e+00,0.000000000000000000e+00,-1.174059441072234486e-09,0.000000000000000000e+00 +3.933037948170082565e+00,4.282000000000000028e+01,0.000000000000000000e+00,1.010314495418079161e+01,0.000000000000000000e+00,-1.000000009868353246e+00,0.000000000000000000e+00,1.644374692281074446e-10,0.000000000000000000e+00 +3.934027738977336153e+00,4.282999999999999829e+01,0.000000000000000000e+00,1.010215516336377028e+01,0.000000000000000000e+00,-1.000000009868190487e+00,0.000000000000000000e+00,1.248749943326601748e-09,0.000000000000000000e+00 +3.935017626762495890e+00,4.284000000000000341e+01,0.000000000000000000e+00,1.010116527556884236e+01,0.000000000000000000e+00,-1.000000009866954365e+00,0.000000000000000000e+00,-1.537514292860295929e-09,0.000000000000000000e+00 +3.936007611554070973e+00,4.285000000000000142e+01,0.000000000000000000e+00,1.010017529076749909e+01,0.000000000000000000e+00,-1.000000009868476480e+00,0.000000000000000000e+00,8.800313331607615934e-10,0.000000000000000000e+00 +3.936997693380585694e+00,4.285999999999999943e+01,0.000000000000000000e+00,1.009918520893121396e+01,0.000000000000000000e+00,-1.000000009867605177e+00,0.000000000000000000e+00,-5.516475190863353466e-10,0.000000000000000000e+00 +3.937987872270577228e+00,4.286999999999999744e+01,0.000000000000000000e+00,1.009819503003145158e+01,0.000000000000000000e+00,-1.000000009868151407e+00,0.000000000000000000e+00,-3.861154027998505412e-10,0.000000000000000000e+00 +3.938978148252597844e+00,4.288000000000000256e+01,0.000000000000000000e+00,1.009720475403965878e+01,0.000000000000000000e+00,-1.000000009868533768e+00,0.000000000000000000e+00,-4.257614667029521384e-10,0.000000000000000000e+00 +3.939968521355213138e+00,4.289000000000000057e+01,0.000000000000000000e+00,1.009621438092726997e+01,0.000000000000000000e+00,-1.000000009868955431e+00,0.000000000000000000e+00,-6.604372063947868872e-10,0.000000000000000000e+00 +3.940958991607002915e+00,4.289999999999999858e+01,0.000000000000000000e+00,1.009522391066570535e+01,0.000000000000000000e+00,-1.000000009869609574e+00,0.000000000000000000e+00,7.303100235877850855e-10,0.000000000000000000e+00 +3.941949559036560746e+00,4.291000000000000369e+01,0.000000000000000000e+00,1.009423334322637089e+01,0.000000000000000000e+00,-1.000000009868886153e+00,0.000000000000000000e+00,1.347063402885384076e-10,0.000000000000000000e+00 +3.942940223672494859e+00,4.292000000000000171e+01,0.000000000000000000e+00,1.009324267858066015e+01,0.000000000000000000e+00,-1.000000009868752704e+00,0.000000000000000000e+00,-6.259532181757295359e-10,0.000000000000000000e+00 +3.943930985543426804e+00,4.292999999999999972e+01,0.000000000000000000e+00,1.009225191669995070e+01,0.000000000000000000e+00,-1.000000009869372875e+00,0.000000000000000000e+00,2.675670527039151570e-10,0.000000000000000000e+00 +3.944921844677992340e+00,4.293999999999999773e+01,0.000000000000000000e+00,1.009126105755560587e+01,0.000000000000000000e+00,-1.000000009869107753e+00,0.000000000000000000e+00,-7.943317214883420399e-10,0.000000000000000000e+00 +3.945912801104841883e+00,4.295000000000000284e+01,0.000000000000000000e+00,1.009027010111897660e+01,0.000000000000000000e+00,-1.000000009869894901e+00,0.000000000000000000e+00,1.625475522706713381e-09,0.000000000000000000e+00 +3.946903854852639171e+00,4.296000000000000085e+01,0.000000000000000000e+00,1.008927904736139780e+01,0.000000000000000000e+00,-1.000000009868283968e+00,0.000000000000000000e+00,-1.506581561583462027e-09,0.000000000000000000e+00 +3.947895005950062153e+00,4.296999999999999886e+01,0.000000000000000000e+00,1.008828789625419375e+01,0.000000000000000000e+00,-1.000000009869777218e+00,0.000000000000000000e+00,-1.136825324399071949e-09,0.000000000000000000e+00 +3.948886254425803433e+00,4.298000000000000398e+01,0.000000000000000000e+00,1.008729664776866919e+01,0.000000000000000000e+00,-1.000000009870904094e+00,0.000000000000000000e+00,9.331130942281500475e-10,0.000000000000000000e+00 +3.949877600308568937e+00,4.299000000000000199e+01,0.000000000000000000e+00,1.008630530187611818e+01,0.000000000000000000e+00,-1.000000009869979056e+00,0.000000000000000000e+00,-7.081645795222143725e-10,0.000000000000000000e+00 +3.950869043627079247e+00,4.300000000000000000e+01,0.000000000000000000e+00,1.008531385854782236e+01,0.000000000000000000e+00,-1.000000009870681161e+00,0.000000000000000000e+00,1.178142832399144950e-09,0.000000000000000000e+00 +3.951860584410068711e+00,4.300999999999999801e+01,0.000000000000000000e+00,1.008432231775504562e+01,0.000000000000000000e+00,-1.000000009869512985e+00,0.000000000000000000e+00,-6.254000036396387750e-10,0.000000000000000000e+00 +3.952852222686286332e+00,4.302000000000000313e+01,0.000000000000000000e+00,1.008333067946904116e+01,0.000000000000000000e+00,-1.000000009870133155e+00,0.000000000000000000e+00,-6.889246617786391273e-10,0.000000000000000000e+00 +3.953843958484494436e+00,4.303000000000000114e+01,0.000000000000000000e+00,1.008233894366104444e+01,0.000000000000000000e+00,-1.000000009870816386e+00,0.000000000000000000e+00,9.966821363156291239e-10,0.000000000000000000e+00 +3.954835791833470005e+00,4.303999999999999915e+01,0.000000000000000000e+00,1.008134711030227848e+01,0.000000000000000000e+00,-1.000000009869827844e+00,0.000000000000000000e+00,-9.762136598651824342e-10,0.000000000000000000e+00 +3.955827722762004228e+00,4.305000000000000426e+01,0.000000000000000000e+00,1.008035517936395387e+01,0.000000000000000000e+00,-1.000000009870796180e+00,0.000000000000000000e+00,-1.179801859550519995e-09,0.000000000000000000e+00 +3.956819751298902510e+00,4.306000000000000227e+01,0.000000000000000000e+00,1.007936315081726342e+01,0.000000000000000000e+00,-1.000000009871966578e+00,0.000000000000000000e+00,3.945714251971840408e-10,0.000000000000000000e+00 +3.957811877472984019e+00,4.307000000000000028e+01,0.000000000000000000e+00,1.007837102463338752e+01,0.000000000000000000e+00,-1.000000009871575113e+00,0.000000000000000000e+00,1.950508240493688827e-09,0.000000000000000000e+00 +3.958804101313082580e+00,4.307999999999999829e+01,0.000000000000000000e+00,1.007737880078349413e+01,0.000000000000000000e+00,-1.000000009869639772e+00,0.000000000000000000e+00,-1.912500305019027405e-09,0.000000000000000000e+00 +3.959796422848045783e+00,4.309000000000000341e+01,0.000000000000000000e+00,1.007638647923873698e+01,0.000000000000000000e+00,-1.000000009871537587e+00,0.000000000000000000e+00,-3.604463087570587490e-10,0.000000000000000000e+00 +3.960788842106735874e+00,4.310000000000000142e+01,0.000000000000000000e+00,1.007539405997025028e+01,0.000000000000000000e+00,-1.000000009871895301e+00,0.000000000000000000e+00,-5.991186500820051131e-10,0.000000000000000000e+00 +3.961781359118028867e+00,4.310999999999999943e+01,0.000000000000000000e+00,1.007440154294915935e+01,0.000000000000000000e+00,-1.000000009872489937e+00,0.000000000000000000e+00,9.873970177171639891e-10,0.000000000000000000e+00 +3.962773973910814984e+00,4.311999999999999744e+01,0.000000000000000000e+00,1.007340892814657352e+01,0.000000000000000000e+00,-1.000000009871509832e+00,0.000000000000000000e+00,8.036628757775030197e-10,0.000000000000000000e+00 +3.963766686513999105e+00,4.313000000000000256e+01,0.000000000000000000e+00,1.007241621553358968e+01,0.000000000000000000e+00,-1.000000009870712026e+00,0.000000000000000000e+00,-1.139286180993972530e-09,0.000000000000000000e+00 +3.964759496956500318e+00,4.314000000000000057e+01,0.000000000000000000e+00,1.007142340508128875e+01,0.000000000000000000e+00,-1.000000009871843121e+00,0.000000000000000000e+00,-1.227060680257375210e-09,0.000000000000000000e+00 +3.965752405267251479e+00,4.314999999999999858e+01,0.000000000000000000e+00,1.007043049676073565e+01,0.000000000000000000e+00,-1.000000009873061479e+00,0.000000000000000000e+00,5.494060257969197015e-10,0.000000000000000000e+00 +3.966745411475200100e+00,4.316000000000000369e+01,0.000000000000000000e+00,1.006943749054298287e+01,0.000000000000000000e+00,-1.000000009872515916e+00,0.000000000000000000e+00,5.965285870772313713e-10,0.000000000000000000e+00 +3.967738515609307903e+00,4.317000000000000171e+01,0.000000000000000000e+00,1.006844438639907047e+01,0.000000000000000000e+00,-1.000000009871923501e+00,0.000000000000000000e+00,-1.074450389127655354e-09,0.000000000000000000e+00 +3.968731717698551265e+00,4.317999999999999972e+01,0.000000000000000000e+00,1.006745118430002250e+01,0.000000000000000000e+00,-1.000000009872990647e+00,0.000000000000000000e+00,9.484900725938992287e-10,0.000000000000000000e+00 +3.969725017771919884e+00,4.318999999999999773e+01,0.000000000000000000e+00,1.006645788421684706e+01,0.000000000000000000e+00,-1.000000009872048512e+00,0.000000000000000000e+00,-5.266137476137553250e-10,0.000000000000000000e+00 +3.970718415858418560e+00,4.320000000000000284e+01,0.000000000000000000e+00,1.006546448612054157e+01,0.000000000000000000e+00,-1.000000009872571649e+00,0.000000000000000000e+00,-8.917578519978199195e-11,0.000000000000000000e+00 +3.971711911987066301e+00,4.321000000000000085e+01,0.000000000000000000e+00,1.006447098998208567e+01,0.000000000000000000e+00,-1.000000009872660245e+00,0.000000000000000000e+00,-1.328342226535406523e-09,0.000000000000000000e+00 +3.972705506186895885e+00,4.321999999999999886e+01,0.000000000000000000e+00,1.006347739577244660e+01,0.000000000000000000e+00,-1.000000009873980078e+00,0.000000000000000000e+00,1.163525427112224722e-09,0.000000000000000000e+00 +3.973699198486955186e+00,4.323000000000000398e+01,0.000000000000000000e+00,1.006248370346257559e+01,0.000000000000000000e+00,-1.000000009872823892e+00,0.000000000000000000e+00,1.993013634901922888e-10,0.000000000000000000e+00 +3.974692988916305847e+00,4.324000000000000199e+01,0.000000000000000000e+00,1.006148991302341322e+01,0.000000000000000000e+00,-1.000000009872625828e+00,0.000000000000000000e+00,-6.114730475724768812e-10,0.000000000000000000e+00 +3.975686877504024608e+00,4.325000000000000000e+01,0.000000000000000000e+00,1.006049602442588231e+01,0.000000000000000000e+00,-1.000000009873233564e+00,0.000000000000000000e+00,-1.259014128366692767e-09,0.000000000000000000e+00 +3.976680864279201533e+00,4.325999999999999801e+01,0.000000000000000000e+00,1.005950203764089146e+01,0.000000000000000000e+00,-1.000000009874485007e+00,0.000000000000000000e+00,1.860860609505771734e-09,0.000000000000000000e+00 +3.977674949270941784e+00,4.327000000000000313e+01,0.000000000000000000e+00,1.005850795263933506e+01,0.000000000000000000e+00,-1.000000009872635154e+00,0.000000000000000000e+00,-2.026174431487427420e-09,0.000000000000000000e+00 +3.978669132508364736e+00,4.328000000000000114e+01,0.000000000000000000e+00,1.005751376939209685e+01,0.000000000000000000e+00,-1.000000009874649542e+00,0.000000000000000000e+00,1.468339961480170374e-09,0.000000000000000000e+00 +3.979663414020603973e+00,4.328999999999999915e+01,0.000000000000000000e+00,1.005651948787003924e+01,0.000000000000000000e+00,-1.000000009873189599e+00,0.000000000000000000e+00,-2.021754484786149819e-09,0.000000000000000000e+00 +3.980657793836808178e+00,4.330000000000000426e+01,0.000000000000000000e+00,1.005552510804401756e+01,0.000000000000000000e+00,-1.000000009875199991e+00,0.000000000000000000e+00,1.887141514460300619e-09,0.000000000000000000e+00 +3.981652271986139358e+00,4.331000000000000227e+01,0.000000000000000000e+00,1.005453062988486579e+01,0.000000000000000000e+00,-1.000000009873323270e+00,0.000000000000000000e+00,-1.166063101185358461e-09,0.000000000000000000e+00 +3.982646848497774617e+00,4.332000000000000028e+01,0.000000000000000000e+00,1.005353605336341083e+01,0.000000000000000000e+00,-1.000000009874483009e+00,0.000000000000000000e+00,-3.940068523486144260e-10,0.000000000000000000e+00 +3.983641523400905271e+00,4.332999999999999829e+01,0.000000000000000000e+00,1.005254137845045825e+01,0.000000000000000000e+00,-1.000000009874874918e+00,0.000000000000000000e+00,6.205272969260160988e-10,0.000000000000000000e+00 +3.984636296724737292e+00,4.334000000000000341e+01,0.000000000000000000e+00,1.005154660511680298e+01,0.000000000000000000e+00,-1.000000009874257634e+00,0.000000000000000000e+00,9.329307284342166852e-11,0.000000000000000000e+00 +3.985631168498490862e+00,4.335000000000000142e+01,0.000000000000000000e+00,1.005055173333322571e+01,0.000000000000000000e+00,-1.000000009874164819e+00,0.000000000000000000e+00,-1.964986129632230310e-09,0.000000000000000000e+00 +3.986626138751400816e+00,4.335999999999999943e+01,0.000000000000000000e+00,1.004955676307049117e+01,0.000000000000000000e+00,-1.000000009876119922e+00,0.000000000000000000e+00,1.632975008373224196e-09,0.000000000000000000e+00 +3.987621207512716648e+00,4.336999999999999744e+01,0.000000000000000000e+00,1.004856169429934809e+01,0.000000000000000000e+00,-1.000000009874494999e+00,0.000000000000000000e+00,1.311962599947595097e-10,0.000000000000000000e+00 +3.988616374811701615e+00,4.338000000000000256e+01,0.000000000000000000e+00,1.004756652699053632e+01,0.000000000000000000e+00,-1.000000009874364437e+00,0.000000000000000000e+00,-1.076015129434789753e-09,0.000000000000000000e+00 +3.989611640677634075e+00,4.339000000000000057e+01,0.000000000000000000e+00,1.004657126111477616e+01,0.000000000000000000e+00,-1.000000009875435358e+00,0.000000000000000000e+00,-1.862707100348712492e-10,0.000000000000000000e+00 +3.990607005139807040e+00,4.339999999999999858e+01,0.000000000000000000e+00,1.004557589664277373e+01,0.000000000000000000e+00,-1.000000009875620766e+00,0.000000000000000000e+00,1.016468894854430115e-09,0.000000000000000000e+00 +3.991602468227527289e+00,4.341000000000000369e+01,0.000000000000000000e+00,1.004458043354522268e+01,0.000000000000000000e+00,-1.000000009874608908e+00,0.000000000000000000e+00,-1.041794099989384628e-09,0.000000000000000000e+00 +3.992598029970116702e+00,4.342000000000000171e+01,0.000000000000000000e+00,1.004358487179280246e+01,0.000000000000000000e+00,-1.000000009875646079e+00,0.000000000000000000e+00,-9.734490539287227444e-10,0.000000000000000000e+00 +3.993593690396911811e+00,4.342999999999999972e+01,0.000000000000000000e+00,1.004258921135617477e+01,0.000000000000000000e+00,-1.000000009876615303e+00,0.000000000000000000e+00,1.229791368753769743e-09,0.000000000000000000e+00 +3.994589449537262915e+00,4.343999999999999773e+01,0.000000000000000000e+00,1.004159345220598887e+01,0.000000000000000000e+00,-1.000000009875390727e+00,0.000000000000000000e+00,2.040158710585266841e-10,0.000000000000000000e+00 +3.995585307420535859e+00,4.345000000000000284e+01,0.000000000000000000e+00,1.004059759431288157e+01,0.000000000000000000e+00,-1.000000009875187557e+00,0.000000000000000000e+00,-2.247296210248747020e-09,0.000000000000000000e+00 +3.996581264076110251e+00,4.346000000000000085e+01,0.000000000000000000e+00,1.003960163764747193e+01,0.000000000000000000e+00,-1.000000009877425766e+00,0.000000000000000000e+00,2.837821729767593352e-09,0.000000000000000000e+00 +3.997577319533380802e+00,4.346999999999999886e+01,0.000000000000000000e+00,1.003860558218036303e+01,0.000000000000000000e+00,-1.000000009874599138e+00,0.000000000000000000e+00,-2.435425296785145888e-09,0.000000000000000000e+00 +3.998573473821756430e+00,4.348000000000000398e+01,0.000000000000000000e+00,1.003760942788215083e+01,0.000000000000000000e+00,-1.000000009877025198e+00,0.000000000000000000e+00,-1.524497161547209203e-10,0.000000000000000000e+00 +3.999569726970660710e+00,4.349000000000000199e+01,0.000000000000000000e+00,1.003661317472340642e+01,0.000000000000000000e+00,-1.000000009877177076e+00,0.000000000000000000e+00,7.445671771744354981e-10,0.000000000000000000e+00 +4.000566079009532316e+00,4.350000000000000000e+01,0.000000000000000000e+00,1.003561682267469379e+01,0.000000000000000000e+00,-1.000000009876435225e+00,0.000000000000000000e+00,2.671797132511190940e-10,0.000000000000000000e+00 +4.001562529967824133e+00,4.350999999999999801e+01,0.000000000000000000e+00,1.003462037170656096e+01,0.000000000000000000e+00,-1.000000009876168994e+00,0.000000000000000000e+00,2.147920516631956915e-10,0.000000000000000000e+00 +4.002559079875003256e+00,4.352000000000000313e+01,0.000000000000000000e+00,1.003362382178953993e+01,0.000000000000000000e+00,-1.000000009875954943e+00,0.000000000000000000e+00,-1.190373401623234981e-09,0.000000000000000000e+00 +4.003555728760551879e+00,4.353000000000000114e+01,0.000000000000000000e+00,1.003262717289414852e+01,0.000000000000000000e+00,-1.000000009877141327e+00,0.000000000000000000e+00,-3.615542066094868567e-10,0.000000000000000000e+00 +4.004552476653966409e+00,4.353999999999999915e+01,0.000000000000000000e+00,1.003163042499088853e+01,0.000000000000000000e+00,-1.000000009877501705e+00,0.000000000000000000e+00,9.217268437081104442e-10,0.000000000000000000e+00 +4.005549323584759236e+00,4.355000000000000426e+01,0.000000000000000000e+00,1.003063357805024935e+01,0.000000000000000000e+00,-1.000000009876582885e+00,0.000000000000000000e+00,-9.035945419932881816e-10,0.000000000000000000e+00 +4.006546269582456077e+00,4.356000000000000227e+01,0.000000000000000000e+00,1.002963663204270617e+01,0.000000000000000000e+00,-1.000000009877483720e+00,0.000000000000000000e+00,-4.656712837025911374e-10,0.000000000000000000e+00 +4.007543314676597745e+00,4.357000000000000028e+01,0.000000000000000000e+00,1.002863958693871638e+01,0.000000000000000000e+00,-1.000000009877948015e+00,0.000000000000000000e+00,4.580538532990661218e-10,0.000000000000000000e+00 +4.008540458896739267e+00,4.357999999999999829e+01,0.000000000000000000e+00,1.002764244270872496e+01,0.000000000000000000e+00,-1.000000009877491269e+00,0.000000000000000000e+00,9.128994008535011751e-11,0.000000000000000000e+00 +4.009537702272451654e+00,4.359000000000000341e+01,0.000000000000000000e+00,1.002664519932316267e+01,0.000000000000000000e+00,-1.000000009877400231e+00,0.000000000000000000e+00,2.310964245943445851e-10,0.000000000000000000e+00 +4.010535044833319240e+00,4.360000000000000142e+01,0.000000000000000000e+00,1.002564785675244430e+01,0.000000000000000000e+00,-1.000000009877169749e+00,0.000000000000000000e+00,-8.973574441421906299e-10,0.000000000000000000e+00 +4.011532486608941461e+00,4.360999999999999943e+01,0.000000000000000000e+00,1.002465041496697040e+01,0.000000000000000000e+00,-1.000000009878064811e+00,0.000000000000000000e+00,2.858080690519313389e-10,0.000000000000000000e+00 +4.012530027628932849e+00,4.361999999999999744e+01,0.000000000000000000e+00,1.002365287393712556e+01,0.000000000000000000e+00,-1.000000009877779705e+00,0.000000000000000000e+00,2.210118156002930246e-10,0.000000000000000000e+00 +4.013527667922922149e+00,4.363000000000000256e+01,0.000000000000000000e+00,1.002265523363328192e+01,0.000000000000000000e+00,-1.000000009877559215e+00,0.000000000000000000e+00,-1.080468851261997343e-09,0.000000000000000000e+00 +4.014525407520553202e+00,4.364000000000000057e+01,0.000000000000000000e+00,1.002165749402579564e+01,0.000000000000000000e+00,-1.000000009878637242e+00,0.000000000000000000e+00,-4.027711511908436287e-11,0.000000000000000000e+00 +4.015523246451484951e+00,4.364999999999999858e+01,0.000000000000000000e+00,1.002065965508500689e+01,0.000000000000000000e+00,-1.000000009878677432e+00,0.000000000000000000e+00,-2.164957512018109102e-10,0.000000000000000000e+00 +4.016521184745390549e+00,4.366000000000000369e+01,0.000000000000000000e+00,1.001966171678124340e+01,0.000000000000000000e+00,-1.000000009878893481e+00,0.000000000000000000e+00,1.853268252211831753e-10,0.000000000000000000e+00 +4.017519222431957360e+00,4.367000000000000171e+01,0.000000000000000000e+00,1.001866367908481692e+01,0.000000000000000000e+00,-1.000000009878708518e+00,0.000000000000000000e+00,1.175251012433100281e-09,0.000000000000000000e+00 +4.018517359540888734e+00,4.367999999999999972e+01,0.000000000000000000e+00,1.001766554196602499e+01,0.000000000000000000e+00,-1.000000009877535456e+00,0.000000000000000000e+00,-2.584938735576684493e-09,0.000000000000000000e+00 +4.019515596101902233e+00,4.368999999999999773e+01,0.000000000000000000e+00,1.001666730539515093e+01,0.000000000000000000e+00,-1.000000009880115837e+00,0.000000000000000000e+00,1.394317713232999786e-09,0.000000000000000000e+00 +4.020513932144730518e+00,4.370000000000000284e+01,0.000000000000000000e+00,1.001566896934245854e+01,0.000000000000000000e+00,-1.000000009878723839e+00,0.000000000000000000e+00,6.451607177396228647e-10,0.000000000000000000e+00 +4.021512367699121349e+00,4.371000000000000085e+01,0.000000000000000000e+00,1.001467053377820449e+01,0.000000000000000000e+00,-1.000000009878079688e+00,0.000000000000000000e+00,-1.256614882958043252e-09,0.000000000000000000e+00 +4.022510902794836696e+00,4.371999999999999886e+01,0.000000000000000000e+00,1.001367199867262592e+01,0.000000000000000000e+00,-1.000000009879334462e+00,0.000000000000000000e+00,-7.359724899648510492e-10,0.000000000000000000e+00 +4.023509537461652741e+00,4.373000000000000398e+01,0.000000000000000000e+00,1.001267336399594399e+01,0.000000000000000000e+00,-1.000000009880069429e+00,0.000000000000000000e+00,4.337580457737485569e-10,0.000000000000000000e+00 +4.024508271729361653e+00,4.374000000000000199e+01,0.000000000000000000e+00,1.001167462971836741e+01,0.000000000000000000e+00,-1.000000009879636220e+00,0.000000000000000000e+00,4.819547116336901548e-10,0.000000000000000000e+00 +4.025507105627769810e+00,4.375000000000000000e+01,0.000000000000000000e+00,1.001067579581009070e+01,0.000000000000000000e+00,-1.000000009879154828e+00,0.000000000000000000e+00,-5.797105567911289716e-10,0.000000000000000000e+00 +4.026506039186699581e+00,4.375999999999999801e+01,0.000000000000000000e+00,1.000967686224129238e+01,0.000000000000000000e+00,-1.000000009879733920e+00,0.000000000000000000e+00,8.201374606480265059e-10,0.000000000000000000e+00 +4.027505072435986655e+00,4.377000000000000313e+01,0.000000000000000000e+00,1.000867782898213498e+01,0.000000000000000000e+00,-1.000000009878914575e+00,0.000000000000000000e+00,-6.493773655754830278e-10,0.000000000000000000e+00 +4.028504205405482708e+00,4.378000000000000114e+01,0.000000000000000000e+00,1.000767869600276860e+01,0.000000000000000000e+00,-1.000000009879563390e+00,0.000000000000000000e+00,-1.416843517303726217e-09,0.000000000000000000e+00 +4.029503438125053627e+00,4.378999999999999915e+01,0.000000000000000000e+00,1.000667946327332558e+01,0.000000000000000000e+00,-1.000000009880979146e+00,0.000000000000000000e+00,2.084836157132255253e-09,0.000000000000000000e+00 +4.030502770624580400e+00,4.380000000000000426e+01,0.000000000000000000e+00,1.000568013076392404e+01,0.000000000000000000e+00,-1.000000009878895701e+00,0.000000000000000000e+00,-2.585178604554294665e-09,0.000000000000000000e+00 +4.031502202933960000e+00,4.381000000000000227e+01,0.000000000000000000e+00,1.000468069844467145e+01,0.000000000000000000e+00,-1.000000009881479412e+00,0.000000000000000000e+00,2.368992001860225306e-09,0.000000000000000000e+00 +4.032501735083102723e+00,4.382000000000000028e+01,0.000000000000000000e+00,1.000368116628565218e+01,0.000000000000000000e+00,-1.000000009879111529e+00,0.000000000000000000e+00,-2.602876490043987696e-09,0.000000000000000000e+00 +4.033501367101933965e+00,4.382999999999999829e+01,0.000000000000000000e+00,1.000268153425694528e+01,0.000000000000000000e+00,-1.000000009881713448e+00,0.000000000000000000e+00,2.066901191484119280e-09,0.000000000000000000e+00 +4.034501099020395110e+00,4.384000000000000341e+01,0.000000000000000000e+00,1.000168180232860493e+01,0.000000000000000000e+00,-1.000000009879647100e+00,0.000000000000000000e+00,-1.387123849946202913e-09,0.000000000000000000e+00 +4.035500930868441749e+00,4.385000000000000142e+01,0.000000000000000000e+00,1.000068197047067997e+01,0.000000000000000000e+00,-1.000000009881033991e+00,0.000000000000000000e+00,1.263297904730180555e-09,0.000000000000000000e+00 +4.036500862676045465e+00,4.385999999999999943e+01,0.000000000000000000e+00,9.999682038653196159e+00,0.000000000000000000e+00,-1.000000009879770779e+00,0.000000000000000000e+00,-2.408885323154053096e-09,0.000000000000000000e+00 +4.037500894473191160e+00,4.386999999999999744e+01,0.000000000000000000e+00,9.998682006846170367e+00,0.000000000000000000e+00,-1.000000009882179741e+00,0.000000000000000000e+00,1.818305631308584088e-09,0.000000000000000000e+00 +4.038501026289879725e+00,4.388000000000000256e+01,0.000000000000000000e+00,9.997681875019598152e+00,0.000000000000000000e+00,-1.000000009880361196e+00,0.000000000000000000e+00,-2.544041295132184408e-10,0.000000000000000000e+00 +4.039501258156127150e+00,4.389000000000000057e+01,0.000000000000000000e+00,9.996681643143467966e+00,0.000000000000000000e+00,-1.000000009880615659e+00,0.000000000000000000e+00,-1.511400011992322631e-09,0.000000000000000000e+00 +4.040501590101964524e+00,4.389999999999999858e+01,0.000000000000000000e+00,9.995681311187746942e+00,0.000000000000000000e+00,-1.000000009882127561e+00,0.000000000000000000e+00,1.606908665974222445e-09,0.000000000000000000e+00 +4.041502022157437146e+00,4.391000000000000369e+01,0.000000000000000000e+00,9.994680879122388006e+00,0.000000000000000000e+00,-1.000000009880519958e+00,0.000000000000000000e+00,-1.538616401729598366e-09,0.000000000000000000e+00 +4.042502554352606303e+00,4.392000000000000171e+01,0.000000000000000000e+00,9.993680346917333424e+00,0.000000000000000000e+00,-1.000000009882059393e+00,0.000000000000000000e+00,1.485205348970402345e-09,0.000000000000000000e+00 +4.043503186717547493e+00,4.392999999999999972e+01,0.000000000000000000e+00,9.992679714542504144e+00,0.000000000000000000e+00,-1.000000009880573248e+00,0.000000000000000000e+00,-1.731345729285020054e-09,0.000000000000000000e+00 +4.044503919282351312e+00,4.393999999999999773e+01,0.000000000000000000e+00,9.991678981967812234e+00,0.000000000000000000e+00,-1.000000009882305863e+00,0.000000000000000000e+00,1.240418372198838099e-09,0.000000000000000000e+00 +4.045504752077124344e+00,4.395000000000000284e+01,0.000000000000000000e+00,9.990678149163148447e+00,0.000000000000000000e+00,-1.000000009881064411e+00,0.000000000000000000e+00,-2.004081043328384587e-09,0.000000000000000000e+00 +4.046505685131988272e+00,4.396000000000000085e+01,0.000000000000000000e+00,9.989677216098394652e+00,0.000000000000000000e+00,-1.000000009883070362e+00,0.000000000000000000e+00,9.577988673095752806e-10,0.000000000000000000e+00 +4.047506718477078103e+00,4.396999999999999886e+01,0.000000000000000000e+00,9.988676182743411402e+00,0.000000000000000000e+00,-1.000000009882111573e+00,0.000000000000000000e+00,1.270874839301322339e-09,0.000000000000000000e+00 +4.048507852142545715e+00,4.398000000000000398e+01,0.000000000000000000e+00,9.987675049068050370e+00,0.000000000000000000e+00,-1.000000009880839258e+00,0.000000000000000000e+00,-2.823144015776352878e-09,0.000000000000000000e+00 +4.049509086158557203e+00,4.399000000000000199e+01,0.000000000000000000e+00,9.986673815042145463e+00,0.000000000000000000e+00,-1.000000009883665886e+00,0.000000000000000000e+00,2.860780032595460789e-09,0.000000000000000000e+00 +4.050510420555294644e+00,4.400000000000000000e+01,0.000000000000000000e+00,9.985672480635511050e+00,0.000000000000000000e+00,-1.000000009880801288e+00,0.000000000000000000e+00,-2.927676311033328775e-09,0.000000000000000000e+00 +4.051511855362954329e+00,4.400999999999999801e+01,0.000000000000000000e+00,9.984671045817956170e+00,0.000000000000000000e+00,-1.000000009883733165e+00,0.000000000000000000e+00,1.080143026915283032e-09,0.000000000000000000e+00 +4.052513390611748534e+00,4.402000000000000313e+01,0.000000000000000000e+00,9.983669510559263216e+00,0.000000000000000000e+00,-1.000000009882651364e+00,0.000000000000000000e+00,7.240133963800976971e-10,0.000000000000000000e+00 +4.053515026331903748e+00,4.403000000000000114e+01,0.000000000000000000e+00,9.982667874829209254e+00,0.000000000000000000e+00,-1.000000009881926166e+00,0.000000000000000000e+00,-4.415462308373593782e-10,0.000000000000000000e+00 +4.054516762553662446e+00,4.403999999999999915e+01,0.000000000000000000e+00,9.981666138597551807e+00,0.000000000000000000e+00,-1.000000009882368479e+00,0.000000000000000000e+00,-6.360996577864369090e-10,0.000000000000000000e+00 +4.055518599307281313e+00,4.405000000000000426e+01,0.000000000000000000e+00,9.980664301834032415e+00,0.000000000000000000e+00,-1.000000009883005747e+00,0.000000000000000000e+00,1.500335352031898376e-10,0.000000000000000000e+00 +4.056520536623033024e+00,4.406000000000000227e+01,0.000000000000000000e+00,9.979662364508378403e+00,0.000000000000000000e+00,-1.000000009882855423e+00,0.000000000000000000e+00,-1.610316466901959490e-09,0.000000000000000000e+00 +4.057522574531205350e+00,4.407000000000000028e+01,0.000000000000000000e+00,9.978660326590302887e+00,0.000000000000000000e+00,-1.000000009884469021e+00,0.000000000000000000e+00,2.937363684498875843e-09,0.000000000000000000e+00 +4.058524713062101164e+00,4.407999999999999829e+01,0.000000000000000000e+00,9.977658188049501220e+00,0.000000000000000000e+00,-1.000000009881525376e+00,0.000000000000000000e+00,-2.114680595187323161e-09,0.000000000000000000e+00 +4.059526952246038434e+00,4.409000000000000341e+01,0.000000000000000000e+00,9.976655948855659872e+00,0.000000000000000000e+00,-1.000000009883644791e+00,0.000000000000000000e+00,-8.371477473617780107e-10,0.000000000000000000e+00 +4.060529292113351119e+00,4.410000000000000142e+01,0.000000000000000000e+00,9.975653608978440445e+00,0.000000000000000000e+00,-1.000000009884483898e+00,0.000000000000000000e+00,1.472337130856253674e-09,0.000000000000000000e+00 +4.061531732694387387e+00,4.410999999999999943e+01,0.000000000000000000e+00,9.974651168387495659e+00,0.000000000000000000e+00,-1.000000009883007968e+00,0.000000000000000000e+00,-4.768502030025496364e-10,0.000000000000000000e+00 +4.062534274019510505e+00,4.411999999999999744e+01,0.000000000000000000e+00,9.973648627052464022e+00,0.000000000000000000e+00,-1.000000009883486030e+00,0.000000000000000000e+00,3.955266436132132194e-10,0.000000000000000000e+00 +4.063536916119100617e+00,4.413000000000000256e+01,0.000000000000000000e+00,9.972645984942964503e+00,0.000000000000000000e+00,-1.000000009883089458e+00,0.000000000000000000e+00,-1.200632627326409106e-09,0.000000000000000000e+00 +4.064539659023551188e+00,4.414000000000000057e+01,0.000000000000000000e+00,9.971643242028603638e+00,0.000000000000000000e+00,-1.000000009884293384e+00,0.000000000000000000e+00,4.472582159941790584e-11,0.000000000000000000e+00 +4.065542502763272559e+00,4.414999999999999858e+01,0.000000000000000000e+00,9.970640398278970196e+00,0.000000000000000000e+00,-1.000000009884248531e+00,0.000000000000000000e+00,6.094940777959135746e-10,0.000000000000000000e+00 +4.066545447368689281e+00,4.416000000000000369e+01,0.000000000000000000e+00,9.969637453663640514e+00,0.000000000000000000e+00,-1.000000009883637242e+00,0.000000000000000000e+00,-1.260704547392564377e-09,0.000000000000000000e+00 +4.067548492870241006e+00,4.417000000000000171e+01,0.000000000000000000e+00,9.968634408152174942e+00,0.000000000000000000e+00,-1.000000009884901786e+00,0.000000000000000000e+00,1.506495501277431699e-09,0.000000000000000000e+00 +4.068551639298384259e+00,4.417999999999999972e+01,0.000000000000000000e+00,9.967631261714116064e+00,0.000000000000000000e+00,-1.000000009883390550e+00,0.000000000000000000e+00,-1.669239745890568826e-09,0.000000000000000000e+00 +4.069554886683588890e+00,4.418999999999999773e+01,0.000000000000000000e+00,9.966628014318995810e+00,0.000000000000000000e+00,-1.000000009885065211e+00,0.000000000000000000e+00,-1.876654510933330382e-10,0.000000000000000000e+00 +4.070558235056341623e+00,4.420000000000000284e+01,0.000000000000000000e+00,9.965624665936324789e+00,0.000000000000000000e+00,-1.000000009885253505e+00,0.000000000000000000e+00,6.678270212788956938e-10,0.000000000000000000e+00 +4.071561684447144280e+00,4.421000000000000085e+01,0.000000000000000000e+00,9.964621216535602954e+00,0.000000000000000000e+00,-1.000000009884583374e+00,0.000000000000000000e+00,9.076045743900761619e-10,0.000000000000000000e+00 +4.072565234886512897e+00,4.421999999999999886e+01,0.000000000000000000e+00,9.963617666086314273e+00,0.000000000000000000e+00,-1.000000009883672547e+00,0.000000000000000000e+00,-1.220563176391702378e-09,0.000000000000000000e+00 +4.073568886404980383e+00,4.423000000000000398e+01,0.000000000000000000e+00,9.962614014557926723e+00,0.000000000000000000e+00,-1.000000009884897567e+00,0.000000000000000000e+00,-4.145559154462920275e-10,0.000000000000000000e+00 +4.074572639033094745e+00,4.424000000000000199e+01,0.000000000000000000e+00,9.961610261919890519e+00,0.000000000000000000e+00,-1.000000009885313679e+00,0.000000000000000000e+00,-1.913312369996745917e-10,0.000000000000000000e+00 +4.075576492801418205e+00,4.425000000000000000e+01,0.000000000000000000e+00,9.960606408141643442e+00,0.000000000000000000e+00,-1.000000009885505747e+00,0.000000000000000000e+00,1.221963650377024283e-09,0.000000000000000000e+00 +4.076580447740529856e+00,4.425999999999999801e+01,0.000000000000000000e+00,9.959602453192607285e+00,0.000000000000000000e+00,-1.000000009884278951e+00,0.000000000000000000e+00,-1.449401365110610757e-09,0.000000000000000000e+00 +4.077584503881023004e+00,4.427000000000000313e+01,0.000000000000000000e+00,9.958598397042189632e+00,0.000000000000000000e+00,-1.000000009885734231e+00,0.000000000000000000e+00,6.149494722812304858e-10,0.000000000000000000e+00 +4.078588661253506942e+00,4.428000000000000114e+01,0.000000000000000000e+00,9.957594239659778523e+00,0.000000000000000000e+00,-1.000000009885116725e+00,0.000000000000000000e+00,3.789705555318625821e-10,0.000000000000000000e+00 +4.079592919888606950e+00,4.428999999999999915e+01,0.000000000000000000e+00,9.956589981014751345e+00,0.000000000000000000e+00,-1.000000009884736141e+00,0.000000000000000000e+00,-2.146030441035011579e-09,0.000000000000000000e+00 +4.080597279816962519e+00,4.430000000000000426e+01,0.000000000000000000e+00,9.955585621076467717e+00,0.000000000000000000e+00,-1.000000009886891528e+00,0.000000000000000000e+00,1.855564273418949589e-09,0.000000000000000000e+00 +4.081601741069230016e+00,4.431000000000000227e+01,0.000000000000000000e+00,9.954581159814269498e+00,0.000000000000000000e+00,-1.000000009885027685e+00,0.000000000000000000e+00,6.807912005741367091e-11,0.000000000000000000e+00 +4.082606303676080017e+00,4.432000000000000028e+01,0.000000000000000000e+00,9.953576597197489662e+00,0.000000000000000000e+00,-1.000000009884959296e+00,0.000000000000000000e+00,-2.213011162493804573e-09,0.000000000000000000e+00 +4.083610967668199088e+00,4.432999999999999829e+01,0.000000000000000000e+00,9.952571933195439868e+00,0.000000000000000000e+00,-1.000000009887182628e+00,0.000000000000000000e+00,2.060745646948968921e-09,0.000000000000000000e+00 +4.084615733076288890e+00,4.434000000000000341e+01,0.000000000000000000e+00,9.951567167777415790e+00,0.000000000000000000e+00,-1.000000009885112062e+00,0.000000000000000000e+00,-1.177986698662123418e-09,0.000000000000000000e+00 +4.085620599931067076e+00,4.435000000000000142e+01,0.000000000000000000e+00,9.950562300912704217e+00,0.000000000000000000e+00,-1.000000009886295782e+00,0.000000000000000000e+00,3.994719364197633977e-10,0.000000000000000000e+00 +4.086625568263267283e+00,4.435999999999999943e+01,0.000000000000000000e+00,9.949557332570568846e+00,0.000000000000000000e+00,-1.000000009885894325e+00,0.000000000000000000e+00,-2.337381767660776007e-10,0.000000000000000000e+00 +4.087630638103637359e+00,4.436999999999999744e+01,0.000000000000000000e+00,9.948552262720262718e+00,0.000000000000000000e+00,-1.000000009886129249e+00,0.000000000000000000e+00,-1.306636724018658293e-09,0.000000000000000000e+00 +4.088635809482942030e+00,4.438000000000000256e+01,0.000000000000000000e+00,9.947547091331021107e+00,0.000000000000000000e+00,-1.000000009887442642e+00,0.000000000000000000e+00,2.463915467294464880e-09,0.000000000000000000e+00 +4.089641082431960228e+00,4.439000000000000057e+01,0.000000000000000000e+00,9.946541818372063304e+00,0.000000000000000000e+00,-1.000000009884965735e+00,0.000000000000000000e+00,-2.971638938613543675e-09,0.000000000000000000e+00 +4.090646456981487766e+00,4.439999999999999858e+01,0.000000000000000000e+00,9.945536443812597938e+00,0.000000000000000000e+00,-1.000000009887953345e+00,0.000000000000000000e+00,1.729581842811806379e-09,0.000000000000000000e+00 +4.091651933162334664e+00,4.441000000000000369e+01,0.000000000000000000e+00,9.944530967621808770e+00,0.000000000000000000e+00,-1.000000009886214292e+00,0.000000000000000000e+00,-9.943206912766067693e-10,0.000000000000000000e+00 +4.092657511005327819e+00,4.442000000000000171e+01,0.000000000000000000e+00,9.943525389768874234e+00,0.000000000000000000e+00,-1.000000009887214159e+00,0.000000000000000000e+00,1.165995246651827902e-09,0.000000000000000000e+00 +4.093663190541309227e+00,4.442999999999999972e+01,0.000000000000000000e+00,9.942519710222949669e+00,0.000000000000000000e+00,-1.000000009886041541e+00,0.000000000000000000e+00,-5.607514466980111094e-10,0.000000000000000000e+00 +4.094668971801135982e+00,4.443999999999999773e+01,0.000000000000000000e+00,9.941513928953179757e+00,0.000000000000000000e+00,-1.000000009886605534e+00,0.000000000000000000e+00,-8.940211107479974688e-10,0.000000000000000000e+00 +4.095674854815681165e+00,4.445000000000000284e+01,0.000000000000000000e+00,9.940508045928689640e+00,0.000000000000000000e+00,-1.000000009887504815e+00,0.000000000000000000e+00,1.750338292177178104e-10,0.000000000000000000e+00 +4.096680839615833847e+00,4.446000000000000085e+01,0.000000000000000000e+00,9.939502061118590248e+00,0.000000000000000000e+00,-1.000000009887328734e+00,0.000000000000000000e+00,-8.525690478511618791e-10,0.000000000000000000e+00 +4.097686926232498195e+00,4.446999999999999886e+01,0.000000000000000000e+00,9.938495974491978302e+00,0.000000000000000000e+00,-1.000000009888186492e+00,0.000000000000000000e+00,1.298695569082692669e-09,0.000000000000000000e+00 +4.098693114696594364e+00,4.448000000000000398e+01,0.000000000000000000e+00,9.937489786017932758e+00,0.000000000000000000e+00,-1.000000009886879759e+00,0.000000000000000000e+00,-3.784260678823149307e-10,0.000000000000000000e+00 +4.099699405039057609e+00,4.449000000000000199e+01,0.000000000000000000e+00,9.936483495665520138e+00,0.000000000000000000e+00,-1.000000009887260566e+00,0.000000000000000000e+00,-6.091711786456178509e-10,0.000000000000000000e+00 +4.100705797290840060e+00,4.450000000000000000e+01,0.000000000000000000e+00,9.935477103403787424e+00,0.000000000000000000e+00,-1.000000009887873631e+00,0.000000000000000000e+00,6.159484494162231247e-10,0.000000000000000000e+00 +4.101712291482908057e+00,4.450999999999999801e+01,0.000000000000000000e+00,9.934470609201767388e+00,0.000000000000000000e+00,-1.000000009887253682e+00,0.000000000000000000e+00,-1.989717832606706291e-10,0.000000000000000000e+00 +4.102718887646244816e+00,4.452000000000000313e+01,0.000000000000000000e+00,9.933464013028478590e+00,0.000000000000000000e+00,-1.000000009887453967e+00,0.000000000000000000e+00,-1.288553636327458022e-09,0.000000000000000000e+00 +4.103725585811847765e+00,4.453000000000000114e+01,0.000000000000000000e+00,9.932457314852921826e+00,0.000000000000000000e+00,-1.000000009888751151e+00,0.000000000000000000e+00,8.632125665449650494e-10,0.000000000000000000e+00 +4.104732386010732093e+00,4.453999999999999915e+01,0.000000000000000000e+00,9.931450514644081906e+00,0.000000000000000000e+00,-1.000000009887882069e+00,0.000000000000000000e+00,-7.436018719748603699e-10,0.000000000000000000e+00 +4.105739288273926313e+00,4.455000000000000426e+01,0.000000000000000000e+00,9.930443612370931206e+00,0.000000000000000000e+00,-1.000000009888630803e+00,0.000000000000000000e+00,9.117680907423109688e-10,0.000000000000000000e+00 +4.106746292632476703e+00,4.456000000000000227e+01,0.000000000000000000e+00,9.929436608002422560e+00,0.000000000000000000e+00,-1.000000009887712649e+00,0.000000000000000000e+00,-1.167429860324205549e-09,0.000000000000000000e+00 +4.107753399117444637e+00,4.457000000000000028e+01,0.000000000000000000e+00,9.928429501507496369e+00,0.000000000000000000e+00,-1.000000009888888375e+00,0.000000000000000000e+00,1.787452550377439051e-09,0.000000000000000000e+00 +4.108760607759907479e+00,4.457999999999999829e+01,0.000000000000000000e+00,9.927422292855073493e+00,0.000000000000000000e+00,-1.000000009887088037e+00,0.000000000000000000e+00,-2.470393259646526111e-09,0.000000000000000000e+00 +4.109767918590957692e+00,4.459000000000000341e+01,0.000000000000000000e+00,9.926414982014064137e+00,0.000000000000000000e+00,-1.000000009889576491e+00,0.000000000000000000e+00,1.827425024988973302e-09,0.000000000000000000e+00 +4.110775331641703723e+00,4.460000000000000142e+01,0.000000000000000000e+00,9.925407568953355408e+00,0.000000000000000000e+00,-1.000000009887735519e+00,0.000000000000000000e+00,-1.063594033462875423e-09,0.000000000000000000e+00 +4.111782846943270009e+00,4.460999999999999943e+01,0.000000000000000000e+00,9.924400053641827313e+00,0.000000000000000000e+00,-1.000000009888807107e+00,0.000000000000000000e+00,-6.289244181688363411e-10,0.000000000000000000e+00 +4.112790464526796086e+00,4.461999999999999744e+01,0.000000000000000000e+00,9.923392436048336762e+00,0.000000000000000000e+00,-1.000000009889440822e+00,0.000000000000000000e+00,1.389706929403474902e-09,0.000000000000000000e+00 +4.113798184423439253e+00,4.463000000000000256e+01,0.000000000000000000e+00,9.922384716141728234e+00,0.000000000000000000e+00,-1.000000009888040386e+00,0.000000000000000000e+00,-1.992144285164554420e-09,0.000000000000000000e+00 +4.114806006664370130e+00,4.464000000000000057e+01,0.000000000000000000e+00,9.921376893890831994e+00,0.000000000000000000e+00,-1.000000009890048114e+00,0.000000000000000000e+00,1.478645688375196511e-09,0.000000000000000000e+00 +4.115813931280777105e+00,4.464999999999999858e+01,0.000000000000000000e+00,9.920368969264456993e+00,0.000000000000000000e+00,-1.000000009888557750e+00,0.000000000000000000e+00,-4.271160188063790197e-10,0.000000000000000000e+00 +4.116821958303862772e+00,4.466000000000000369e+01,0.000000000000000000e+00,9.919360942231403300e+00,0.000000000000000000e+00,-1.000000009888988295e+00,0.000000000000000000e+00,-7.043724779721933048e-10,0.000000000000000000e+00 +4.117830087764846603e+00,4.467000000000000171e+01,0.000000000000000000e+00,9.918352812760449666e+00,0.000000000000000000e+00,-1.000000009889698394e+00,0.000000000000000000e+00,6.571713127740337916e-10,0.000000000000000000e+00 +4.118838319694964945e+00,4.467999999999999972e+01,0.000000000000000000e+00,9.917344580820360633e+00,0.000000000000000000e+00,-1.000000009889035812e+00,0.000000000000000000e+00,1.728642894592620746e-10,0.000000000000000000e+00 +4.119846654125467467e+00,4.468999999999999773e+01,0.000000000000000000e+00,9.916336246379886532e+00,0.000000000000000000e+00,-1.000000009888861507e+00,0.000000000000000000e+00,-2.144179997270952419e-09,0.000000000000000000e+00 +4.120855091087621602e+00,4.470000000000000284e+01,0.000000000000000000e+00,9.915327809407759929e+00,0.000000000000000000e+00,-1.000000009891023778e+00,0.000000000000000000e+00,2.449770442842339208e-09,0.000000000000000000e+00 +4.121863630612710772e+00,4.471000000000000085e+01,0.000000000000000000e+00,9.914319269872695628e+00,0.000000000000000000e+00,-1.000000009888553087e+00,0.000000000000000000e+00,-1.752991626213701706e-09,0.000000000000000000e+00 +4.122872272732032606e+00,4.471999999999999886e+01,0.000000000000000000e+00,9.913310627743399550e+00,0.000000000000000000e+00,-1.000000009890321229e+00,0.000000000000000000e+00,9.760108126902584415e-10,0.000000000000000000e+00 +4.123881017476902500e+00,4.473000000000000398e+01,0.000000000000000000e+00,9.912301882988552748e+00,0.000000000000000000e+00,-1.000000009889336683e+00,0.000000000000000000e+00,-1.574576195448875621e-09,0.000000000000000000e+00 +4.124889864878650947e+00,4.474000000000000199e+01,0.000000000000000000e+00,9.911293035576827393e+00,0.000000000000000000e+00,-1.000000009890925190e+00,0.000000000000000000e+00,1.080567830873007631e-09,0.000000000000000000e+00 +4.125898814968624428e+00,4.475000000000000000e+01,0.000000000000000000e+00,9.910284085476874338e+00,0.000000000000000000e+00,-1.000000009889834951e+00,0.000000000000000000e+00,2.255538242315901212e-10,0.000000000000000000e+00 +4.126907867778185413e+00,4.475999999999999801e+01,0.000000000000000000e+00,9.909275032657333782e+00,0.000000000000000000e+00,-1.000000009889607355e+00,0.000000000000000000e+00,-6.380873073187635551e-10,0.000000000000000000e+00 +4.127917023338712355e+00,4.477000000000000313e+01,0.000000000000000000e+00,9.908265877086826379e+00,0.000000000000000000e+00,-1.000000009890251285e+00,0.000000000000000000e+00,2.459686066065962694e-10,0.000000000000000000e+00 +4.128926281681599697e+00,4.478000000000000114e+01,0.000000000000000000e+00,9.907256618733956799e+00,0.000000000000000000e+00,-1.000000009890003039e+00,0.000000000000000000e+00,-6.003398514425876552e-10,0.000000000000000000e+00 +4.129935642838258758e+00,4.478999999999999915e+01,0.000000000000000000e+00,9.906247257567315501e+00,0.000000000000000000e+00,-1.000000009890608998e+00,0.000000000000000000e+00,3.222456131343446969e-10,0.000000000000000000e+00 +4.130945106840115066e+00,4.480000000000000426e+01,0.000000000000000000e+00,9.905237793555475179e+00,0.000000000000000000e+00,-1.000000009890283703e+00,0.000000000000000000e+00,-4.623148495597997321e-10,0.000000000000000000e+00 +4.131954673718611026e+00,4.481000000000000227e+01,0.000000000000000000e+00,9.904228226666994317e+00,0.000000000000000000e+00,-1.000000009890750441e+00,0.000000000000000000e+00,-1.198553341804300896e-09,0.000000000000000000e+00 +4.132964343505205029e+00,4.482000000000000028e+01,0.000000000000000000e+00,9.903218556870413636e+00,0.000000000000000000e+00,-1.000000009891960584e+00,0.000000000000000000e+00,1.607876811423302477e-09,0.000000000000000000e+00 +4.133974116231372342e+00,4.482999999999999829e+01,0.000000000000000000e+00,9.902208784134257868e+00,0.000000000000000000e+00,-1.000000009890336994e+00,0.000000000000000000e+00,-7.418521894046789533e-10,0.000000000000000000e+00 +4.134983991928602443e+00,4.484000000000000341e+01,0.000000000000000000e+00,9.901198908427039314e+00,0.000000000000000000e+00,-1.000000009891086172e+00,0.000000000000000000e+00,4.733387293197258056e-10,0.000000000000000000e+00 +4.135993970628403460e+00,4.485000000000000142e+01,0.000000000000000000e+00,9.900188929717248953e+00,0.000000000000000000e+00,-1.000000009890608110e+00,0.000000000000000000e+00,3.934927535852200430e-11,0.000000000000000000e+00 +4.137004052362296846e+00,4.485999999999999943e+01,0.000000000000000000e+00,9.899178847973365336e+00,0.000000000000000000e+00,-1.000000009890568364e+00,0.000000000000000000e+00,-2.031226558821194220e-09,0.000000000000000000e+00 +4.138014237161821818e+00,4.486999999999999744e+01,0.000000000000000000e+00,9.898168663163849246e+00,0.000000000000000000e+00,-1.000000009892620279e+00,0.000000000000000000e+00,1.234743675074911907e-09,0.000000000000000000e+00 +4.139024525058532689e+00,4.488000000000000256e+01,0.000000000000000000e+00,9.897158375257143703e+00,0.000000000000000000e+00,-1.000000009891372832e+00,0.000000000000000000e+00,1.145394655829084851e-09,0.000000000000000000e+00 +4.140034916084001537e+00,4.489000000000000057e+01,0.000000000000000000e+00,9.896147984221681071e+00,0.000000000000000000e+00,-1.000000009890215535e+00,0.000000000000000000e+00,-2.285061981586650802e-09,0.000000000000000000e+00 +4.141045410269814653e+00,4.489999999999999858e+01,0.000000000000000000e+00,9.895137490025874172e+00,0.000000000000000000e+00,-1.000000009892524577e+00,0.000000000000000000e+00,1.390803479314501559e-09,0.000000000000000000e+00 +4.142056007647575200e+00,4.491000000000000369e+01,0.000000000000000000e+00,9.894126892638116288e+00,0.000000000000000000e+00,-1.000000009891119035e+00,0.000000000000000000e+00,9.007443737511229516e-12,0.000000000000000000e+00 +4.143066708248902330e+00,4.492000000000000171e+01,0.000000000000000000e+00,9.893116192026791822e+00,0.000000000000000000e+00,-1.000000009891109931e+00,0.000000000000000000e+00,-1.201162710140535393e-09,0.000000000000000000e+00 +4.144077512105432071e+00,4.492999999999999972e+01,0.000000000000000000e+00,9.892105388160263857e+00,0.000000000000000000e+00,-1.000000009892324071e+00,0.000000000000000000e+00,1.247825192288464336e-09,0.000000000000000000e+00 +4.145088419248816436e+00,4.493999999999999773e+01,0.000000000000000000e+00,9.891094481006879491e+00,0.000000000000000000e+00,-1.000000009891062636e+00,0.000000000000000000e+00,-1.323908039452469701e-09,0.000000000000000000e+00 +4.146099429710722539e+00,4.495000000000000284e+01,0.000000000000000000e+00,9.890083470534973387e+00,0.000000000000000000e+00,-1.000000009892401120e+00,0.000000000000000000e+00,-2.143334724645147879e-10,0.000000000000000000e+00 +4.147110543522834369e+00,4.496000000000000085e+01,0.000000000000000000e+00,9.889072356712858891e+00,0.000000000000000000e+00,-1.000000009892617836e+00,0.000000000000000000e+00,1.111302054764257901e-09,0.000000000000000000e+00 +4.148121760716852791e+00,4.496999999999999886e+01,0.000000000000000000e+00,9.888061139508836916e+00,0.000000000000000000e+00,-1.000000009891494068e+00,0.000000000000000000e+00,-8.099533831106975229e-10,0.000000000000000000e+00 +4.149133081324493766e+00,4.498000000000000398e+01,0.000000000000000000e+00,9.887049818891192388e+00,0.000000000000000000e+00,-1.000000009892313191e+00,0.000000000000000000e+00,-7.545473185716972054e-10,0.000000000000000000e+00 +4.150144505377490134e+00,4.499000000000000199e+01,0.000000000000000000e+00,9.886038394828190690e+00,0.000000000000000000e+00,-1.000000009893076358e+00,0.000000000000000000e+00,1.286791941234773878e-09,0.000000000000000000e+00 +4.151156032907590721e+00,4.500000000000000000e+01,0.000000000000000000e+00,9.885026867288082997e+00,0.000000000000000000e+00,-1.000000009891774733e+00,0.000000000000000000e+00,-1.618092727931846745e-09,0.000000000000000000e+00 +4.152167663946560339e+00,4.500999999999999801e+01,0.000000000000000000e+00,9.884015236239106272e+00,0.000000000000000000e+00,-1.000000009893411645e+00,0.000000000000000000e+00,9.575442322542754203e-10,0.000000000000000000e+00 +4.153179398526180677e+00,4.502000000000000313e+01,0.000000000000000000e+00,9.883003501649476163e+00,0.000000000000000000e+00,-1.000000009892442865e+00,0.000000000000000000e+00,3.456286482594422728e-10,0.000000000000000000e+00 +4.154191236678249410e+00,4.503000000000000114e+01,0.000000000000000000e+00,9.881991663487397659e+00,0.000000000000000000e+00,-1.000000009892093145e+00,0.000000000000000000e+00,3.028055250012287195e-11,0.000000000000000000e+00 +4.155203178434580202e+00,4.503999999999999915e+01,0.000000000000000000e+00,9.880979721721056208e+00,0.000000000000000000e+00,-1.000000009892062502e+00,0.000000000000000000e+00,-1.712431235213092966e-09,0.000000000000000000e+00 +4.156215223827003591e+00,4.505000000000000426e+01,0.000000000000000000e+00,9.879967676318621272e+00,0.000000000000000000e+00,-1.000000009893795561e+00,0.000000000000000000e+00,3.317015801272694500e-10,0.000000000000000000e+00 +4.157227372887366101e+00,4.506000000000000227e+01,0.000000000000000000e+00,9.878955527248244550e+00,0.000000000000000000e+00,-1.000000009893459829e+00,0.000000000000000000e+00,9.708735407532193230e-10,0.000000000000000000e+00 +4.158239625647530247e+00,4.507000000000000028e+01,0.000000000000000000e+00,9.877943274478065305e+00,0.000000000000000000e+00,-1.000000009892477060e+00,0.000000000000000000e+00,-1.515600712190666337e-09,0.000000000000000000e+00 +4.159251982139375414e+00,4.507999999999999829e+01,0.000000000000000000e+00,9.876930917976205038e+00,0.000000000000000000e+00,-1.000000009894011388e+00,0.000000000000000000e+00,1.550096667207863326e-09,0.000000000000000000e+00 +4.160264442394797868e+00,4.509000000000000341e+01,0.000000000000000000e+00,9.875918457710765708e+00,0.000000000000000000e+00,-1.000000009892441977e+00,0.000000000000000000e+00,-2.192894412214211604e-10,0.000000000000000000e+00 +4.161277006445708082e+00,4.510000000000000142e+01,0.000000000000000000e+00,9.874905893649838617e+00,0.000000000000000000e+00,-1.000000009892664021e+00,0.000000000000000000e+00,-1.612927741449792424e-09,0.000000000000000000e+00 +4.162289674324035182e+00,4.510999999999999943e+01,0.000000000000000000e+00,9.873893225761493753e+00,0.000000000000000000e+00,-1.000000009894297381e+00,0.000000000000000000e+00,8.440912173486691922e-10,0.000000000000000000e+00 +4.163302446061723394e+00,4.511999999999999744e+01,0.000000000000000000e+00,9.872880454013785112e+00,0.000000000000000000e+00,-1.000000009893442510e+00,0.000000000000000000e+00,2.352251888195054227e-10,0.000000000000000000e+00 +4.164315321690733818e+00,4.513000000000000256e+01,0.000000000000000000e+00,9.871867578374754260e+00,0.000000000000000000e+00,-1.000000009893204256e+00,0.000000000000000000e+00,3.572951746189289907e-11,0.000000000000000000e+00 +4.165328301243043541e+00,4.514000000000000057e+01,0.000000000000000000e+00,9.870854598812423220e+00,0.000000000000000000e+00,-1.000000009893168063e+00,0.000000000000000000e+00,-1.473307800497305817e-09,0.000000000000000000e+00 +4.166341384750646526e+00,4.514999999999999858e+01,0.000000000000000000e+00,9.869841515294798029e+00,0.000000000000000000e+00,-1.000000009894660646e+00,0.000000000000000000e+00,9.108061269095287491e-10,0.000000000000000000e+00 +4.167354572245552724e+00,4.516000000000000369e+01,0.000000000000000000e+00,9.868828327789866961e+00,0.000000000000000000e+00,-1.000000009893737829e+00,0.000000000000000000e+00,2.774211230290195821e-10,0.000000000000000000e+00 +4.168367863759788960e+00,4.517000000000000171e+01,0.000000000000000000e+00,9.867815036265605855e+00,0.000000000000000000e+00,-1.000000009893456721e+00,0.000000000000000000e+00,-1.630612966871694754e-09,0.000000000000000000e+00 +4.169381259325398048e+00,4.517999999999999972e+01,0.000000000000000000e+00,9.866801640689971009e+00,0.000000000000000000e+00,-1.000000009895109176e+00,0.000000000000000000e+00,2.117037750748167150e-09,0.000000000000000000e+00 +4.170394758974439675e+00,4.518999999999999773e+01,0.000000000000000000e+00,9.865788141030900960e+00,0.000000000000000000e+00,-1.000000009892963559e+00,0.000000000000000000e+00,-2.304777636114832141e-09,0.000000000000000000e+00 +4.171408362738989517e+00,4.520000000000000284e+01,0.000000000000000000e+00,9.864774537256323583e+00,0.000000000000000000e+00,-1.000000009895299691e+00,0.000000000000000000e+00,6.799063570737923349e-10,0.000000000000000000e+00 +4.172422070651140125e+00,4.521000000000000085e+01,0.000000000000000000e+00,9.863760829334141889e+00,0.000000000000000000e+00,-1.000000009894610464e+00,0.000000000000000000e+00,7.067758866221856414e-10,0.000000000000000000e+00 +4.173435882743000924e+00,4.521999999999999886e+01,0.000000000000000000e+00,9.862747017232250002e+00,0.000000000000000000e+00,-1.000000009893893926e+00,0.000000000000000000e+00,-4.820123452582021288e-10,0.000000000000000000e+00 +4.174449799046696441e+00,4.523000000000000398e+01,0.000000000000000000e+00,9.861733100918522510e+00,0.000000000000000000e+00,-1.000000009894382647e+00,0.000000000000000000e+00,5.809392504105135362e-10,0.000000000000000000e+00 +4.175463819594369852e+00,4.524000000000000199e+01,0.000000000000000000e+00,9.860719080360816235e+00,0.000000000000000000e+00,-1.000000009893793562e+00,0.000000000000000000e+00,-1.276051948558683644e-09,0.000000000000000000e+00 +4.176477944418178545e+00,4.525000000000000000e+01,0.000000000000000000e+00,9.859704955526973791e+00,0.000000000000000000e+00,-1.000000009895087638e+00,0.000000000000000000e+00,-8.584222917078780376e-10,0.000000000000000000e+00 +4.177492173550298560e+00,4.525999999999999801e+01,0.000000000000000000e+00,9.858690726384818248e+00,0.000000000000000000e+00,-1.000000009895958275e+00,0.000000000000000000e+00,1.842977264697371522e-09,0.000000000000000000e+00 +4.178506507022920147e+00,4.527000000000000313e+01,0.000000000000000000e+00,9.857676392902158469e+00,0.000000000000000000e+00,-1.000000009894088882e+00,0.000000000000000000e+00,-6.588420019023710795e-11,0.000000000000000000e+00 +4.179520944868252208e+00,4.528000000000000114e+01,0.000000000000000000e+00,9.856661955046789103e+00,0.000000000000000000e+00,-1.000000009894155717e+00,0.000000000000000000e+00,-1.392399159483474357e-09,0.000000000000000000e+00 +4.180535487118519633e+00,4.528999999999999915e+01,0.000000000000000000e+00,9.855647412786483486e+00,0.000000000000000000e+00,-1.000000009895568365e+00,0.000000000000000000e+00,-4.006948198312277079e-10,0.000000000000000000e+00 +4.181550133805963299e+00,4.530000000000000426e+01,0.000000000000000000e+00,9.854632766088998963e+00,0.000000000000000000e+00,-1.000000009895974928e+00,0.000000000000000000e+00,1.194302115810369731e-09,0.000000000000000000e+00 +4.182564884962841845e+00,4.531000000000000227e+01,0.000000000000000000e+00,9.853618014922078672e+00,0.000000000000000000e+00,-1.000000009894763009e+00,0.000000000000000000e+00,-4.550920855947531846e-11,0.000000000000000000e+00 +4.183579740621429011e+00,4.532000000000000028e+01,0.000000000000000000e+00,9.852603159253449761e+00,0.000000000000000000e+00,-1.000000009894809194e+00,0.000000000000000000e+00,-6.574090714818540532e-10,0.000000000000000000e+00 +4.184594700814016299e+00,4.532999999999999829e+01,0.000000000000000000e+00,9.851588199050819838e+00,0.000000000000000000e+00,-1.000000009895476438e+00,0.000000000000000000e+00,-6.308726955520108391e-10,0.000000000000000000e+00 +4.185609765572911201e+00,4.534000000000000341e+01,0.000000000000000000e+00,9.850573134281880527e+00,0.000000000000000000e+00,-1.000000009896116815e+00,0.000000000000000000e+00,4.593259901762170427e-11,0.000000000000000000e+00 +4.186624934930438080e+00,4.535000000000000142e+01,0.000000000000000000e+00,9.849557964914307462e+00,0.000000000000000000e+00,-1.000000009896070186e+00,0.000000000000000000e+00,1.383522267551738094e-09,0.000000000000000000e+00 +4.187640208918938178e+00,4.535999999999999943e+01,0.000000000000000000e+00,9.848542690915760289e+00,0.000000000000000000e+00,-1.000000009894665531e+00,0.000000000000000000e+00,-1.775038361232788665e-09,0.000000000000000000e+00 +4.188655587570768724e+00,4.536999999999999744e+01,0.000000000000000000e+00,9.847527312253882670e+00,0.000000000000000000e+00,-1.000000009896467867e+00,0.000000000000000000e+00,9.201172030951351721e-10,0.000000000000000000e+00 +4.189671070918304707e+00,4.538000000000000256e+01,0.000000000000000000e+00,9.846511828896296947e+00,0.000000000000000000e+00,-1.000000009895533504e+00,0.000000000000000000e+00,-8.563991034945938447e-10,0.000000000000000000e+00 +4.190686658993937108e+00,4.539000000000000057e+01,0.000000000000000000e+00,9.845496240810614808e+00,0.000000000000000000e+00,-1.000000009896403252e+00,0.000000000000000000e+00,1.518710987744838767e-09,0.000000000000000000e+00 +4.191702351830073781e+00,4.539999999999999858e+01,0.000000000000000000e+00,9.844480547964426620e+00,0.000000000000000000e+00,-1.000000009894860709e+00,0.000000000000000000e+00,-2.273568937102909786e-09,0.000000000000000000e+00 +4.192718149459138566e+00,4.541000000000000369e+01,0.000000000000000000e+00,9.843464750325310320e+00,0.000000000000000000e+00,-1.000000009897170195e+00,0.000000000000000000e+00,1.551401513873097385e-09,0.000000000000000000e+00 +4.193734051913573957e+00,4.542000000000000171e+01,0.000000000000000000e+00,9.842448847860820749e+00,0.000000000000000000e+00,-1.000000009895594122e+00,0.000000000000000000e+00,-7.666603032040644676e-10,0.000000000000000000e+00 +4.194750059225836658e+00,4.542999999999999972e+01,0.000000000000000000e+00,9.841432840538503868e+00,0.000000000000000000e+00,-1.000000009896373054e+00,0.000000000000000000e+00,1.111630095969470697e-09,0.000000000000000000e+00 +4.195766171428402025e+00,4.543999999999999773e+01,0.000000000000000000e+00,9.840416728325882545e+00,0.000000000000000000e+00,-1.000000009895243513e+00,0.000000000000000000e+00,-1.406491866978358880e-09,0.000000000000000000e+00 +4.196782388553761400e+00,4.545000000000000284e+01,0.000000000000000000e+00,9.839400511190467213e+00,0.000000000000000000e+00,-1.000000009896672815e+00,0.000000000000000000e+00,2.940721685731866466e-10,0.000000000000000000e+00 +4.197798710634423003e+00,4.546000000000000085e+01,0.000000000000000000e+00,9.838384189099746990e+00,0.000000000000000000e+00,-1.000000009896373943e+00,0.000000000000000000e+00,-6.566787751890199446e-10,0.000000000000000000e+00 +4.198815137702912814e+00,4.546999999999999886e+01,0.000000000000000000e+00,9.837367762021198558e+00,0.000000000000000000e+00,-1.000000009897041409e+00,0.000000000000000000e+00,9.119596279569487022e-10,0.000000000000000000e+00 +4.199831669791771915e+00,4.548000000000000398e+01,0.000000000000000000e+00,9.836351229922279060e+00,0.000000000000000000e+00,-1.000000009896114372e+00,0.000000000000000000e+00,-1.863481562251953910e-09,0.000000000000000000e+00 +4.200848306933559151e+00,4.549000000000000199e+01,0.000000000000000000e+00,9.835334592770431428e+00,0.000000000000000000e+00,-1.000000009898008857e+00,0.000000000000000000e+00,1.340248987254536104e-09,0.000000000000000000e+00 +4.201865049160849352e+00,4.550000000000000000e+01,0.000000000000000000e+00,9.834317850533077277e+00,0.000000000000000000e+00,-1.000000009896646169e+00,0.000000000000000000e+00,2.238248652374520107e-10,0.000000000000000000e+00 +4.202881896506236004e+00,4.550999999999999801e+01,0.000000000000000000e+00,9.833301003177627564e+00,0.000000000000000000e+00,-1.000000009896418574e+00,0.000000000000000000e+00,-1.763120884860288285e-09,0.000000000000000000e+00 +4.203898849002327687e+00,4.552000000000000313e+01,0.000000000000000000e+00,9.832284050671471931e+00,0.000000000000000000e+00,-1.000000009898211584e+00,0.000000000000000000e+00,2.261582709570792768e-09,0.000000000000000000e+00 +4.204915906681750748e+00,4.553000000000000114e+01,0.000000000000000000e+00,9.831266992981982256e+00,0.000000000000000000e+00,-1.000000009895911424e+00,0.000000000000000000e+00,-1.430943255864500672e-09,0.000000000000000000e+00 +4.205933069577147521e+00,4.553999999999999915e+01,0.000000000000000000e+00,9.830249830076519757e+00,0.000000000000000000e+00,-1.000000009897366926e+00,0.000000000000000000e+00,-8.060910299805843054e-10,0.000000000000000000e+00 +4.206950337721178101e+00,4.555000000000000426e+01,0.000000000000000000e+00,9.829232561922420786e+00,0.000000000000000000e+00,-1.000000009898186937e+00,0.000000000000000000e+00,7.110676422504457090e-10,0.000000000000000000e+00 +4.207967711146519463e+00,4.556000000000000227e+01,0.000000000000000000e+00,9.828215188487009257e+00,0.000000000000000000e+00,-1.000000009897463515e+00,0.000000000000000000e+00,1.416532331176982376e-09,0.000000000000000000e+00 +4.208985189885865452e+00,4.557000000000000028e+01,0.000000000000000000e+00,9.827197709737593101e+00,0.000000000000000000e+00,-1.000000009896022224e+00,0.000000000000000000e+00,-2.107449225810979823e-09,0.000000000000000000e+00 +4.210002773971925905e+00,4.557999999999999829e+01,0.000000000000000000e+00,9.826180125641462482e+00,0.000000000000000000e+00,-1.000000009898166731e+00,0.000000000000000000e+00,4.435701627209874525e-10,0.000000000000000000e+00 +4.211020463437429306e+00,4.559000000000000341e+01,0.000000000000000000e+00,9.825162436165886248e+00,0.000000000000000000e+00,-1.000000009897715314e+00,0.000000000000000000e+00,5.035188910855939578e-10,0.000000000000000000e+00 +4.212038258315119243e+00,4.560000000000000142e+01,0.000000000000000000e+00,9.824144641278122592e+00,0.000000000000000000e+00,-1.000000009897202835e+00,0.000000000000000000e+00,-1.991616662141854230e-10,0.000000000000000000e+00 +4.213056158637757065e+00,4.560999999999999943e+01,0.000000000000000000e+00,9.823126740945410162e+00,0.000000000000000000e+00,-1.000000009897405562e+00,0.000000000000000000e+00,-1.652238014463713396e-09,0.000000000000000000e+00 +4.214074164438121883e+00,4.561999999999999744e+01,0.000000000000000000e+00,9.822108735134969848e+00,0.000000000000000000e+00,-1.000000009899087550e+00,0.000000000000000000e+00,1.297663020906127201e-09,0.000000000000000000e+00 +4.215092275749008799e+00,4.563000000000000256e+01,0.000000000000000000e+00,9.821090623814004772e+00,0.000000000000000000e+00,-1.000000009897766384e+00,0.000000000000000000e+00,9.289867998740243765e-11,0.000000000000000000e+00 +4.216110492603229787e+00,4.564000000000000057e+01,0.000000000000000000e+00,9.820072406949705623e+00,0.000000000000000000e+00,-1.000000009897671793e+00,0.000000000000000000e+00,-1.129495942731028492e-10,0.000000000000000000e+00 +4.217128815033614586e+00,4.564999999999999858e+01,0.000000000000000000e+00,9.819054084509241775e+00,0.000000000000000000e+00,-1.000000009897786812e+00,0.000000000000000000e+00,-1.021019497343828653e-09,0.000000000000000000e+00 +4.218147243073009811e+00,4.566000000000000369e+01,0.000000000000000000e+00,9.818035656459766614e+00,0.000000000000000000e+00,-1.000000009898826647e+00,0.000000000000000000e+00,8.050894546431022853e-10,0.000000000000000000e+00 +4.219165776754278063e+00,4.567000000000000171e+01,0.000000000000000000e+00,9.817017122768415760e+00,0.000000000000000000e+00,-1.000000009898006637e+00,0.000000000000000000e+00,2.404336704489820844e-10,0.000000000000000000e+00 +4.220184416110300596e+00,4.567999999999999972e+01,0.000000000000000000e+00,9.815998483402310626e+00,0.000000000000000000e+00,-1.000000009897761721e+00,0.000000000000000000e+00,-9.908413890601797750e-10,0.000000000000000000e+00 +4.221203161173974650e+00,4.568999999999999773e+01,0.000000000000000000e+00,9.814979738328553083e+00,0.000000000000000000e+00,-1.000000009898771136e+00,0.000000000000000000e+00,5.474560605441009142e-10,0.000000000000000000e+00 +4.222222011978215228e+00,4.570000000000000284e+01,0.000000000000000000e+00,9.813960887514227238e+00,0.000000000000000000e+00,-1.000000009898213360e+00,0.000000000000000000e+00,-2.689055141933972445e-10,0.000000000000000000e+00 +4.223240968555953323e+00,4.571000000000000085e+01,0.000000000000000000e+00,9.812941930926402989e+00,0.000000000000000000e+00,-1.000000009898487363e+00,0.000000000000000000e+00,-1.713713355372096470e-09,0.000000000000000000e+00 +4.224260030940138577e+00,4.571999999999999886e+01,0.000000000000000000e+00,9.811922868532130693e+00,0.000000000000000000e+00,-1.000000009900233744e+00,0.000000000000000000e+00,3.063666195786103791e-09,0.000000000000000000e+00 +4.225279199163736621e+00,4.573000000000000398e+01,0.000000000000000000e+00,9.810903700298442942e+00,0.000000000000000000e+00,-1.000000009897111353e+00,0.000000000000000000e+00,-3.025007106634984424e-09,0.000000000000000000e+00 +4.226298473259729960e+00,4.574000000000000199e+01,0.000000000000000000e+00,9.809884426192361673e+00,0.000000000000000000e+00,-1.000000009900194664e+00,0.000000000000000000e+00,2.261440370803871276e-09,0.000000000000000000e+00 +4.227317853261118863e+00,4.575000000000000000e+01,0.000000000000000000e+00,9.808865046180880398e+00,0.000000000000000000e+00,-1.000000009897889397e+00,0.000000000000000000e+00,-1.581667640534813016e-09,0.000000000000000000e+00 +4.228337339200921363e+00,4.575999999999999801e+01,0.000000000000000000e+00,9.807845560230987303e+00,0.000000000000000000e+00,-1.000000009899501885e+00,0.000000000000000000e+00,8.421472137734747172e-10,0.000000000000000000e+00 +4.229356931112171480e+00,4.577000000000000313e+01,0.000000000000000000e+00,9.806825968309643926e+00,0.000000000000000000e+00,-1.000000009898643238e+00,0.000000000000000000e+00,-7.083579250924127034e-10,0.000000000000000000e+00 +4.230376629027920998e+00,4.578000000000000114e+01,0.000000000000000000e+00,9.805806270383801149e+00,0.000000000000000000e+00,-1.000000009899365550e+00,0.000000000000000000e+00,6.122641778531889173e-10,0.000000000000000000e+00 +4.231396432981238576e+00,4.578999999999999915e+01,0.000000000000000000e+00,9.804786466420388535e+00,0.000000000000000000e+00,-1.000000009898741160e+00,0.000000000000000000e+00,-2.015994541949623907e-09,0.000000000000000000e+00 +4.232416343005209747e+00,4.580000000000000426e+01,0.000000000000000000e+00,9.803766556386321440e+00,0.000000000000000000e+00,-1.000000009900797293e+00,0.000000000000000000e+00,1.665308205919376797e-09,0.000000000000000000e+00 +4.233436359132938698e+00,4.581000000000000227e+01,0.000000000000000000e+00,9.802746540248493901e+00,0.000000000000000000e+00,-1.000000009899098652e+00,0.000000000000000000e+00,-2.844877606401570574e-10,0.000000000000000000e+00 +4.234456481397544714e+00,4.582000000000000028e+01,0.000000000000000000e+00,9.801726417973789296e+00,0.000000000000000000e+00,-1.000000009899388864e+00,0.000000000000000000e+00,6.831783855525346818e-10,0.000000000000000000e+00 +4.235476709832166620e+00,4.582999999999999829e+01,0.000000000000000000e+00,9.800706189529067913e+00,0.000000000000000000e+00,-1.000000009898691866e+00,0.000000000000000000e+00,-2.246049759116563950e-09,0.000000000000000000e+00 +4.236497044469958340e+00,4.584000000000000341e+01,0.000000000000000000e+00,9.799685854881175828e+00,0.000000000000000000e+00,-1.000000009900983589e+00,0.000000000000000000e+00,1.176980752616347291e-09,0.000000000000000000e+00 +4.237517485344093338e+00,4.585000000000000142e+01,0.000000000000000000e+00,9.798665413996937801e+00,0.000000000000000000e+00,-1.000000009899782549e+00,0.000000000000000000e+00,7.277852944702569464e-10,0.000000000000000000e+00 +4.238538032487760177e+00,4.585999999999999943e+01,0.000000000000000000e+00,9.797644866843167932e+00,0.000000000000000000e+00,-1.000000009899039810e+00,0.000000000000000000e+00,-1.692550034882774614e-10,0.000000000000000000e+00 +4.239558685934165183e+00,4.586999999999999744e+01,0.000000000000000000e+00,9.796624213386659008e+00,0.000000000000000000e+00,-1.000000009899212561e+00,0.000000000000000000e+00,-1.500948411611701269e-09,0.000000000000000000e+00 +4.240579445716533336e+00,4.588000000000000256e+01,0.000000000000000000e+00,9.795603453594186050e+00,0.000000000000000000e+00,-1.000000009900744669e+00,0.000000000000000000e+00,1.533417933693193462e-10,0.000000000000000000e+00 +4.241600311868105599e+00,4.589000000000000057e+01,0.000000000000000000e+00,9.794582587432506315e+00,0.000000000000000000e+00,-1.000000009900588127e+00,0.000000000000000000e+00,1.395591119636261141e-09,0.000000000000000000e+00 +4.242621284422140704e+00,4.589999999999999858e+01,0.000000000000000000e+00,9.793561614868362852e+00,0.000000000000000000e+00,-1.000000009899163267e+00,0.000000000000000000e+00,-1.169069002527496754e-09,0.000000000000000000e+00 +4.243642363411915142e+00,4.591000000000000369e+01,0.000000000000000000e+00,9.792540535868480944e+00,0.000000000000000000e+00,-1.000000009900356979e+00,0.000000000000000000e+00,-7.123271482779612160e-10,0.000000000000000000e+00 +4.244663548870721392e+00,4.592000000000000171e+01,0.000000000000000000e+00,9.791519350399564559e+00,0.000000000000000000e+00,-1.000000009901084397e+00,0.000000000000000000e+00,1.072727606185518416e-09,0.000000000000000000e+00 +4.245684840831870588e+00,4.592999999999999972e+01,0.000000000000000000e+00,9.790498058428303452e+00,0.000000000000000000e+00,-1.000000009899988829e+00,0.000000000000000000e+00,-9.106581348285161549e-10,0.000000000000000000e+00 +4.246706239328690735e+00,4.593999999999999773e+01,0.000000000000000000e+00,9.789476659921371393e+00,0.000000000000000000e+00,-1.000000009900918974e+00,0.000000000000000000e+00,1.619406855644416705e-10,0.000000000000000000e+00 +4.247727744394527605e+00,4.595000000000000284e+01,0.000000000000000000e+00,9.788455154845420836e+00,0.000000000000000000e+00,-1.000000009900753550e+00,0.000000000000000000e+00,8.956884943315918997e-10,0.000000000000000000e+00 +4.248749356062743843e+00,4.596000000000000085e+01,0.000000000000000000e+00,9.787433543167090022e+00,0.000000000000000000e+00,-1.000000009899838505e+00,0.000000000000000000e+00,-3.974868423395918287e-10,0.000000000000000000e+00 +4.249771074366719859e+00,4.596999999999999886e+01,0.000000000000000000e+00,9.786411824852999430e+00,0.000000000000000000e+00,-1.000000009900244624e+00,0.000000000000000000e+00,-3.022670746670845979e-10,0.000000000000000000e+00 +4.250792899339852937e+00,4.598000000000000398e+01,0.000000000000000000e+00,9.785389999869750000e+00,0.000000000000000000e+00,-1.000000009900553488e+00,0.000000000000000000e+00,-5.077817373177052271e-10,0.000000000000000000e+00 +4.251814831015558127e+00,4.599000000000000199e+01,0.000000000000000000e+00,9.784368068183926681e+00,0.000000000000000000e+00,-1.000000009901072406e+00,0.000000000000000000e+00,-1.001770248141211243e-09,0.000000000000000000e+00 +4.252836869427269129e+00,4.600000000000000000e+01,0.000000000000000000e+00,9.783346029762096663e+00,0.000000000000000000e+00,-1.000000009902096254e+00,0.000000000000000000e+00,1.628385467335939397e-09,0.000000000000000000e+00 +4.253859014608434741e+00,4.600999999999999801e+01,0.000000000000000000e+00,9.782323884570809369e+00,0.000000000000000000e+00,-1.000000009900431808e+00,0.000000000000000000e+00,-1.106473976175774614e-09,0.000000000000000000e+00 +4.254881266592523303e+00,4.602000000000000313e+01,0.000000000000000000e+00,9.781301632576600014e+00,0.000000000000000000e+00,-1.000000009901562903e+00,0.000000000000000000e+00,1.006886004986664931e-09,0.000000000000000000e+00 +4.255903625413020031e+00,4.603000000000000114e+01,0.000000000000000000e+00,9.780279273745980717e+00,0.000000000000000000e+00,-1.000000009900533504e+00,0.000000000000000000e+00,-5.183748236532816452e-10,0.000000000000000000e+00 +4.256926091103427012e+00,4.603999999999999915e+01,0.000000000000000000e+00,9.779256808045451166e+00,0.000000000000000000e+00,-1.000000009901063525e+00,0.000000000000000000e+00,-5.715206956308365778e-10,0.000000000000000000e+00 +4.257948663697264102e+00,4.605000000000000426e+01,0.000000000000000000e+00,9.778234235441489730e+00,0.000000000000000000e+00,-1.000000009901647946e+00,0.000000000000000000e+00,8.591454851912144036e-10,0.000000000000000000e+00 +4.258971343228068918e+00,4.606000000000000227e+01,0.000000000000000000e+00,9.777211555900558793e+00,0.000000000000000000e+00,-1.000000009900769316e+00,0.000000000000000000e+00,-1.309533372966068924e-09,0.000000000000000000e+00 +4.259994129729396839e+00,4.607000000000000028e+01,0.000000000000000000e+00,9.776188769389104749e+00,0.000000000000000000e+00,-1.000000009902108689e+00,0.000000000000000000e+00,1.425314432253107638e-09,0.000000000000000000e+00 +4.261017023234820122e+00,4.607999999999999829e+01,0.000000000000000000e+00,9.775165875873552679e+00,0.000000000000000000e+00,-1.000000009900650744e+00,0.000000000000000000e+00,-1.110222435209822747e-09,0.000000000000000000e+00 +4.262040023777928788e+00,4.609000000000000341e+01,0.000000000000000000e+00,9.774142875320315227e+00,0.000000000000000000e+00,-1.000000009901786502e+00,0.000000000000000000e+00,-4.166967731004112844e-10,0.000000000000000000e+00 +4.263063131392331506e+00,4.610000000000000142e+01,0.000000000000000000e+00,9.773119767695781945e+00,0.000000000000000000e+00,-1.000000009902212827e+00,0.000000000000000000e+00,1.236939055090723463e-10,0.000000000000000000e+00 +4.264086346111652936e+00,4.610999999999999943e+01,0.000000000000000000e+00,9.772096552966328176e+00,0.000000000000000000e+00,-1.000000009902086262e+00,0.000000000000000000e+00,5.227147736007939252e-10,0.000000000000000000e+00 +4.265109667969536389e+00,4.611999999999999744e+01,0.000000000000000000e+00,9.771073231098311496e+00,0.000000000000000000e+00,-1.000000009901551357e+00,0.000000000000000000e+00,-9.023425022322646312e-10,0.000000000000000000e+00 +4.266133096999642937e+00,4.613000000000000256e+01,0.000000000000000000e+00,9.770049802058071720e+00,0.000000000000000000e+00,-1.000000009902474840e+00,0.000000000000000000e+00,9.475881753793136681e-10,0.000000000000000000e+00 +4.267156633235649643e+00,4.614000000000000057e+01,0.000000000000000000e+00,9.769026265811929122e+00,0.000000000000000000e+00,-1.000000009901504949e+00,0.000000000000000000e+00,-6.967340563554616844e-10,0.000000000000000000e+00 +4.268180276711253107e+00,4.614999999999999858e+01,0.000000000000000000e+00,9.768002622326189766e+00,0.000000000000000000e+00,-1.000000009902218157e+00,0.000000000000000000e+00,-7.370031898249338222e-10,0.000000000000000000e+00 +4.269204027460166806e+00,4.616000000000000369e+01,0.000000000000000000e+00,9.766978871567138398e+00,0.000000000000000000e+00,-1.000000009902972664e+00,0.000000000000000000e+00,8.379875984173650310e-10,0.000000000000000000e+00 +4.270227885516121979e+00,4.617000000000000171e+01,0.000000000000000000e+00,9.765955013501043780e+00,0.000000000000000000e+00,-1.000000009902114684e+00,0.000000000000000000e+00,6.518443733801534482e-10,0.000000000000000000e+00 +4.271251850912867631e+00,4.617999999999999972e+01,0.000000000000000000e+00,9.764931048094158683e+00,0.000000000000000000e+00,-1.000000009901447218e+00,0.000000000000000000e+00,-1.282086376783303739e-09,0.000000000000000000e+00 +4.272275923684170529e+00,4.618999999999999773e+01,0.000000000000000000e+00,9.763906975312716341e+00,0.000000000000000000e+00,-1.000000009902760167e+00,0.000000000000000000e+00,1.302981742981699934e-10,0.000000000000000000e+00 +4.273300103863814314e+00,4.620000000000000284e+01,0.000000000000000000e+00,9.762882795122930446e+00,0.000000000000000000e+00,-1.000000009902626719e+00,0.000000000000000000e+00,-1.810109203399001119e-10,0.000000000000000000e+00 +4.274324391485601282e+00,4.621000000000000085e+01,0.000000000000000000e+00,9.761858507491000481e+00,0.000000000000000000e+00,-1.000000009902812126e+00,0.000000000000000000e+00,1.183925650137048653e-09,0.000000000000000000e+00 +4.275348786583350602e+00,4.621999999999999886e+01,0.000000000000000000e+00,9.760834112383106387e+00,0.000000000000000000e+00,-1.000000009901599318e+00,0.000000000000000000e+00,-8.409281350384756605e-10,0.000000000000000000e+00 +4.276373289190900984e+00,4.623000000000000398e+01,0.000000000000000000e+00,9.759809609765412119e+00,0.000000000000000000e+00,-1.000000009902460851e+00,0.000000000000000000e+00,-1.164606563250443805e-09,0.000000000000000000e+00 +4.277397899342106236e+00,4.624000000000000199e+01,0.000000000000000000e+00,9.758784999604060317e+00,0.000000000000000000e+00,-1.000000009903654119e+00,0.000000000000000000e+00,2.236225897698538304e-10,0.000000000000000000e+00 +4.278422617070840595e+00,4.625000000000000000e+01,0.000000000000000000e+00,9.757760281865177632e+00,0.000000000000000000e+00,-1.000000009903424969e+00,0.000000000000000000e+00,1.643626779084899774e-09,0.000000000000000000e+00 +4.279447442410994285e+00,4.625999999999999801e+01,0.000000000000000000e+00,9.756735456514874727e+00,0.000000000000000000e+00,-1.000000009901740539e+00,0.000000000000000000e+00,-1.963869220873600749e-09,0.000000000000000000e+00 +4.280472375396476181e+00,4.627000000000000313e+01,0.000000000000000000e+00,9.755710523519244504e+00,0.000000000000000000e+00,-1.000000009903753373e+00,0.000000000000000000e+00,1.250332307506442656e-09,0.000000000000000000e+00 +4.281497416061212036e+00,4.628000000000000114e+01,0.000000000000000000e+00,9.754685482844356770e+00,0.000000000000000000e+00,-1.000000009902471731e+00,0.000000000000000000e+00,-5.380282605967985652e-10,0.000000000000000000e+00 +4.282522564439146251e+00,4.628999999999999915e+01,0.000000000000000000e+00,9.753660334456270675e+00,0.000000000000000000e+00,-1.000000009903023290e+00,0.000000000000000000e+00,-5.522656521620092622e-10,0.000000000000000000e+00 +4.283547820564241881e+00,4.630000000000000426e+01,0.000000000000000000e+00,9.752635078321022277e+00,0.000000000000000000e+00,-1.000000009903589504e+00,0.000000000000000000e+00,-4.716502566411580974e-10,0.000000000000000000e+00 +4.284573184470477969e+00,4.631000000000000227e+01,0.000000000000000000e+00,9.751609714404631646e+00,0.000000000000000000e+00,-1.000000009904073117e+00,0.000000000000000000e+00,1.405707778310613398e-09,0.000000000000000000e+00 +4.285598656191852207e+00,4.632000000000000028e+01,0.000000000000000000e+00,9.750584242673101087e+00,0.000000000000000000e+00,-1.000000009902631604e+00,0.000000000000000000e+00,2.468173673585945885e-11,0.000000000000000000e+00 +4.286624235762380053e+00,4.632999999999999829e+01,0.000000000000000000e+00,9.749558663092416921e+00,0.000000000000000000e+00,-1.000000009902606291e+00,0.000000000000000000e+00,-1.223132849369971034e-09,0.000000000000000000e+00 +4.287649923216095615e+00,4.634000000000000341e+01,0.000000000000000000e+00,9.748532975628544150e+00,0.000000000000000000e+00,-1.000000009903860843e+00,0.000000000000000000e+00,-6.366115519479087180e-10,0.000000000000000000e+00 +4.288675718587050767e+00,4.635000000000000142e+01,0.000000000000000000e+00,9.747507180247430014e+00,0.000000000000000000e+00,-1.000000009904513876e+00,0.000000000000000000e+00,1.794705040994141984e-09,0.000000000000000000e+00 +4.289701621909314255e+00,4.635999999999999943e+01,0.000000000000000000e+00,9.746481276915005765e+00,0.000000000000000000e+00,-1.000000009902672682e+00,0.000000000000000000e+00,-2.354599099981485877e-09,0.000000000000000000e+00 +4.290727633216973480e+00,4.636999999999999744e+01,0.000000000000000000e+00,9.745455265597186667e+00,0.000000000000000000e+00,-1.000000009905088527e+00,0.000000000000000000e+00,2.116103004873856827e-09,0.000000000000000000e+00 +4.291753752544133604e+00,4.638000000000000256e+01,0.000000000000000000e+00,9.744429146259863117e+00,0.000000000000000000e+00,-1.000000009902917153e+00,0.000000000000000000e+00,-1.653930690048941038e-09,0.000000000000000000e+00 +4.292779979924917555e+00,4.639000000000000057e+01,0.000000000000000000e+00,9.743402918868916629e+00,0.000000000000000000e+00,-1.000000009904614462e+00,0.000000000000000000e+00,1.531520449630742273e-09,0.000000000000000000e+00 +4.293806315393466910e+00,4.639999999999999858e+01,0.000000000000000000e+00,9.742376583390202072e+00,0.000000000000000000e+00,-1.000000009903042608e+00,0.000000000000000000e+00,-1.808470445333434104e-09,0.000000000000000000e+00 +4.294832758983940124e+00,4.641000000000000369e+01,0.000000000000000000e+00,9.741350139789563656e+00,0.000000000000000000e+00,-1.000000009904898901e+00,0.000000000000000000e+00,1.828395939798914173e-09,0.000000000000000000e+00 +4.295859310730515190e+00,4.642000000000000171e+01,0.000000000000000000e+00,9.740323588032820723e+00,0.000000000000000000e+00,-1.000000009903021958e+00,0.000000000000000000e+00,-1.031865345135875706e-09,0.000000000000000000e+00 +4.296885970667386978e+00,4.642999999999999972e+01,0.000000000000000000e+00,9.739296928085781957e+00,0.000000000000000000e+00,-1.000000009904081333e+00,0.000000000000000000e+00,-2.631833498130208351e-10,0.000000000000000000e+00 +4.297912738828769008e+00,4.643999999999999773e+01,0.000000000000000000e+00,9.738270159914231172e+00,0.000000000000000000e+00,-1.000000009904351561e+00,0.000000000000000000e+00,-9.083949801658094483e-10,0.000000000000000000e+00 +4.298939615248891677e+00,4.645000000000000284e+01,0.000000000000000000e+00,9.737243283483937972e+00,0.000000000000000000e+00,-1.000000009905284371e+00,0.000000000000000000e+00,4.136101772479422438e-10,0.000000000000000000e+00 +4.299966599962004921e+00,4.646000000000000085e+01,0.000000000000000000e+00,9.736216298760652421e+00,0.000000000000000000e+00,-1.000000009904859599e+00,0.000000000000000000e+00,3.469808253944350052e-10,0.000000000000000000e+00 +4.300993693002375551e+00,4.646999999999999886e+01,0.000000000000000000e+00,9.735189205710108595e+00,0.000000000000000000e+00,-1.000000009904503218e+00,0.000000000000000000e+00,5.884001068144443592e-10,0.000000000000000000e+00 +4.302020894404289031e+00,4.648000000000000398e+01,0.000000000000000000e+00,9.734162004298021031e+00,0.000000000000000000e+00,-1.000000009903898812e+00,0.000000000000000000e+00,-5.323572919510249346e-10,0.000000000000000000e+00 +4.303048204202049476e+00,4.649000000000000199e+01,0.000000000000000000e+00,9.733134694490086503e+00,0.000000000000000000e+00,-1.000000009904445708e+00,0.000000000000000000e+00,3.639444040697560586e-10,0.000000000000000000e+00 +4.304075622429977876e+00,4.650000000000000000e+01,0.000000000000000000e+00,9.732107276251982242e+00,0.000000000000000000e+00,-1.000000009904071785e+00,0.000000000000000000e+00,-1.759022999008122471e-09,0.000000000000000000e+00 +4.305103149122413875e+00,4.650999999999999801e+01,0.000000000000000000e+00,9.731079749549369495e+00,0.000000000000000000e+00,-1.000000009905879228e+00,0.000000000000000000e+00,1.523965519857821880e-09,0.000000000000000000e+00 +4.306130784313715765e+00,4.652000000000000313e+01,0.000000000000000000e+00,9.730052114347888192e+00,0.000000000000000000e+00,-1.000000009904313147e+00,0.000000000000000000e+00,1.313587391199248019e-10,0.000000000000000000e+00 +4.307158528038258716e+00,4.653000000000000114e+01,0.000000000000000000e+00,9.729024370613165829e+00,0.000000000000000000e+00,-1.000000009904178144e+00,0.000000000000000000e+00,-8.764245300957897644e-10,0.000000000000000000e+00 +4.308186380330437437e+00,4.653999999999999915e+01,0.000000000000000000e+00,9.727996518310806806e+00,0.000000000000000000e+00,-1.000000009905078979e+00,0.000000000000000000e+00,-1.486761825553923467e-09,0.000000000000000000e+00 +4.309214341224664402e+00,4.655000000000000426e+01,0.000000000000000000e+00,9.726968557406397764e+00,0.000000000000000000e+00,-1.000000009906607312e+00,0.000000000000000000e+00,1.673429225918727215e-09,0.000000000000000000e+00 +4.310242410755369846e+00,4.656000000000000227e+01,0.000000000000000000e+00,9.725940487865507578e+00,0.000000000000000000e+00,-1.000000009904886911e+00,0.000000000000000000e+00,2.129358316568328410e-10,0.000000000000000000e+00 +4.311270588957002659e+00,4.657000000000000028e+01,0.000000000000000000e+00,9.724912309653690912e+00,0.000000000000000000e+00,-1.000000009904667975e+00,0.000000000000000000e+00,-8.119209812095879122e-10,0.000000000000000000e+00 +4.312298875864029490e+00,4.657999999999999829e+01,0.000000000000000000e+00,9.723884022736479338e+00,0.000000000000000000e+00,-1.000000009905502862e+00,0.000000000000000000e+00,2.904037901392389802e-10,0.000000000000000000e+00 +4.313327271510935645e+00,4.659000000000000341e+01,0.000000000000000000e+00,9.722855627079386664e+00,0.000000000000000000e+00,-1.000000009905204212e+00,0.000000000000000000e+00,1.729285016802825881e-10,0.000000000000000000e+00 +4.314355775932224191e+00,4.660000000000000142e+01,0.000000000000000000e+00,9.721827122647910713e+00,0.000000000000000000e+00,-1.000000009905026355e+00,0.000000000000000000e+00,-1.150791914890892048e-09,0.000000000000000000e+00 +4.315384389162416845e+00,4.660999999999999943e+01,0.000000000000000000e+00,9.720798509407529764e+00,0.000000000000000000e+00,-1.000000009906210074e+00,0.000000000000000000e+00,1.368457848141962491e-09,0.000000000000000000e+00 +4.316413111236053091e+00,4.661999999999999744e+01,0.000000000000000000e+00,9.719769787323702559e+00,0.000000000000000000e+00,-1.000000009904802312e+00,0.000000000000000000e+00,-6.500565996474303719e-10,0.000000000000000000e+00 +4.317441942187691950e+00,4.663000000000000256e+01,0.000000000000000000e+00,9.718740956361873629e+00,0.000000000000000000e+00,-1.000000009905471110e+00,0.000000000000000000e+00,-4.790746671173486681e-10,0.000000000000000000e+00 +4.318470882051909321e+00,4.664000000000000057e+01,0.000000000000000000e+00,9.717712016487464410e+00,0.000000000000000000e+00,-1.000000009905964049e+00,0.000000000000000000e+00,2.151292228899759653e-10,0.000000000000000000e+00 +4.319499930863299753e+00,4.664999999999999858e+01,0.000000000000000000e+00,9.716682967665880355e+00,0.000000000000000000e+00,-1.000000009905742671e+00,0.000000000000000000e+00,-2.317194771011700607e-10,0.000000000000000000e+00 +4.320529088656476446e+00,4.666000000000000369e+01,0.000000000000000000e+00,9.715653809862509149e+00,0.000000000000000000e+00,-1.000000009905981146e+00,0.000000000000000000e+00,-1.298699724103176144e-10,0.000000000000000000e+00 +4.321558355466070367e+00,4.667000000000000171e+01,0.000000000000000000e+00,9.714624543042718940e+00,0.000000000000000000e+00,-1.000000009906114817e+00,0.000000000000000000e+00,5.334458762483650383e-10,0.000000000000000000e+00 +4.322587731326732019e+00,4.667999999999999972e+01,0.000000000000000000e+00,9.713595167171860112e+00,0.000000000000000000e+00,-1.000000009905565701e+00,0.000000000000000000e+00,-1.580972077150238643e-09,0.000000000000000000e+00 +4.323617216273128783e+00,4.668999999999999773e+01,0.000000000000000000e+00,9.712565682215265284e+00,0.000000000000000000e+00,-1.000000009907193288e+00,0.000000000000000000e+00,1.919178638366184416e-09,0.000000000000000000e+00 +4.324646810339947578e+00,4.670000000000000284e+01,0.000000000000000000e+00,9.711536088138245759e+00,0.000000000000000000e+00,-1.000000009905217313e+00,0.000000000000000000e+00,-6.837925988875420356e-10,0.000000000000000000e+00 +4.325676513561893088e+00,4.671000000000000085e+01,0.000000000000000000e+00,9.710506384906100408e+00,0.000000000000000000e+00,-1.000000009905921416e+00,0.000000000000000000e+00,-9.978734183256995063e-10,0.000000000000000000e+00 +4.326706325973688649e+00,4.671999999999999886e+01,0.000000000000000000e+00,9.709476572484103229e+00,0.000000000000000000e+00,-1.000000009906949039e+00,0.000000000000000000e+00,9.880658764881343276e-10,0.000000000000000000e+00 +4.327736247610076248e+00,4.673000000000000398e+01,0.000000000000000000e+00,9.708446650837512237e+00,0.000000000000000000e+00,-1.000000009905931408e+00,0.000000000000000000e+00,2.623496880642506902e-10,0.000000000000000000e+00 +4.328766278505815635e+00,4.674000000000000199e+01,0.000000000000000000e+00,9.707416619931569457e+00,0.000000000000000000e+00,-1.000000009905661180e+00,0.000000000000000000e+00,-1.485772011226867035e-09,0.000000000000000000e+00 +4.329796418695685212e+00,4.675000000000000000e+01,0.000000000000000000e+00,9.706386479731495598e+00,0.000000000000000000e+00,-1.000000009907191734e+00,0.000000000000000000e+00,7.773989459367915340e-10,0.000000000000000000e+00 +4.330826668214482034e+00,4.675999999999999801e+01,0.000000000000000000e+00,9.705356230202491830e+00,0.000000000000000000e+00,-1.000000009906390819e+00,0.000000000000000000e+00,-1.303788303824162036e-09,0.000000000000000000e+00 +4.331857027097021806e+00,4.677000000000000313e+01,0.000000000000000000e+00,9.704325871309745111e+00,0.000000000000000000e+00,-1.000000009907734189e+00,0.000000000000000000e+00,2.323728991364776922e-09,0.000000000000000000e+00 +4.332887495378137999e+00,4.678000000000000114e+01,0.000000000000000000e+00,9.703295403018419307e+00,0.000000000000000000e+00,-1.000000009905339660e+00,0.000000000000000000e+00,-1.710724129021873459e-09,0.000000000000000000e+00 +4.333918073092683620e+00,4.678999999999999915e+01,0.000000000000000000e+00,9.702264825293665851e+00,0.000000000000000000e+00,-1.000000009907102694e+00,0.000000000000000000e+00,-1.227971269205905232e-11,0.000000000000000000e+00 +4.334948760275528556e+00,4.680000000000000426e+01,0.000000000000000000e+00,9.701234138100609528e+00,0.000000000000000000e+00,-1.000000009907115350e+00,0.000000000000000000e+00,7.412281159791910895e-10,0.000000000000000000e+00 +4.335979556961563119e+00,4.681000000000000227e+01,0.000000000000000000e+00,9.700203341404362689e+00,0.000000000000000000e+00,-1.000000009906351295e+00,0.000000000000000000e+00,-1.108170137687501736e-09,0.000000000000000000e+00 +4.337010463185695386e+00,4.682000000000000028e+01,0.000000000000000000e+00,9.699172435170018147e+00,0.000000000000000000e+00,-1.000000009907493714e+00,0.000000000000000000e+00,1.138634179492645499e-09,0.000000000000000000e+00 +4.338041478982851196e+00,4.682999999999999829e+01,0.000000000000000000e+00,9.698141419362647397e+00,0.000000000000000000e+00,-1.000000009906319764e+00,0.000000000000000000e+00,-8.615833339857814481e-10,0.000000000000000000e+00 +4.339072604387975929e+00,4.684000000000000341e+01,0.000000000000000000e+00,9.697110293947307724e+00,0.000000000000000000e+00,-1.000000009907208165e+00,0.000000000000000000e+00,-4.110441665071776217e-10,0.000000000000000000e+00 +4.340103839436033617e+00,4.685000000000000142e+01,0.000000000000000000e+00,9.696079058889033320e+00,0.000000000000000000e+00,-1.000000009907632048e+00,0.000000000000000000e+00,8.301821641482323214e-10,0.000000000000000000e+00 +4.341135184162006055e+00,4.685999999999999943e+01,0.000000000000000000e+00,9.695047714152842389e+00,0.000000000000000000e+00,-1.000000009906775844e+00,0.000000000000000000e+00,-4.636986966907224191e-10,0.000000000000000000e+00 +4.342166638600894579e+00,4.686999999999999744e+01,0.000000000000000000e+00,9.694016259703735372e+00,0.000000000000000000e+00,-1.000000009907254128e+00,0.000000000000000000e+00,-9.391374997910737760e-10,0.000000000000000000e+00 +4.343198202787718287e+00,4.688000000000000256e+01,0.000000000000000000e+00,9.692984695506691395e+00,0.000000000000000000e+00,-1.000000009908222909e+00,0.000000000000000000e+00,1.084961805953837496e-09,0.000000000000000000e+00 +4.344229876757515818e+00,4.689000000000000057e+01,0.000000000000000000e+00,9.691953021526671819e+00,0.000000000000000000e+00,-1.000000009907103582e+00,0.000000000000000000e+00,-1.054717685600219602e-09,0.000000000000000000e+00 +4.345261660545343574e+00,4.689999999999999858e+01,0.000000000000000000e+00,9.690921237728622017e+00,0.000000000000000000e+00,-1.000000009908191823e+00,0.000000000000000000e+00,9.990885298355231765e-10,0.000000000000000000e+00 +4.346293554186277497e+00,4.691000000000000369e+01,0.000000000000000000e+00,9.689889344077464273e+00,0.000000000000000000e+00,-1.000000009907160869e+00,0.000000000000000000e+00,5.856621586492773679e-10,0.000000000000000000e+00 +4.347325557715411293e+00,4.692000000000000171e+01,0.000000000000000000e+00,9.688857340538106655e+00,0.000000000000000000e+00,-1.000000009906556464e+00,0.000000000000000000e+00,-2.281085417926166280e-09,0.000000000000000000e+00 +4.348357671167857319e+00,4.692999999999999972e+01,0.000000000000000000e+00,9.687825227075435919e+00,0.000000000000000000e+00,-1.000000009908910803e+00,0.000000000000000000e+00,7.500987956723836182e-10,0.000000000000000000e+00 +4.349389894578747473e+00,4.693999999999999773e+01,0.000000000000000000e+00,9.686793003654317502e+00,0.000000000000000000e+00,-1.000000009908136533e+00,0.000000000000000000e+00,1.353346358956407849e-09,0.000000000000000000e+00 +4.350422227983232304e+00,4.695000000000000284e+01,0.000000000000000000e+00,9.685760670239604408e+00,0.000000000000000000e+00,-1.000000009906739429e+00,0.000000000000000000e+00,-2.121636844252565837e-09,0.000000000000000000e+00 +4.351454671416480124e+00,4.696000000000000085e+01,0.000000000000000000e+00,9.684728226796128325e+00,0.000000000000000000e+00,-1.000000009908929899e+00,0.000000000000000000e+00,2.002921355534573623e-09,0.000000000000000000e+00 +4.352487224913678787e+00,4.696999999999999886e+01,0.000000000000000000e+00,9.683695673288697847e+00,0.000000000000000000e+00,-1.000000009906861775e+00,0.000000000000000000e+00,-1.257444199817932013e-09,0.000000000000000000e+00 +4.353519888510035685e+00,4.698000000000000398e+01,0.000000000000000000e+00,9.682663009682110911e+00,0.000000000000000000e+00,-1.000000009908160292e+00,0.000000000000000000e+00,-2.255332253654825572e-10,0.000000000000000000e+00 +4.354552662240775085e+00,4.699000000000000199e+01,0.000000000000000000e+00,9.681630235941138807e+00,0.000000000000000000e+00,-1.000000009908393217e+00,0.000000000000000000e+00,1.135069985686447981e-10,0.000000000000000000e+00 +4.355585546141140796e+00,4.700000000000000000e+01,0.000000000000000000e+00,9.680597352030538616e+00,0.000000000000000000e+00,-1.000000009908275977e+00,0.000000000000000000e+00,-2.276346354923650556e-10,0.000000000000000000e+00 +4.356618540246396165e+00,4.700999999999999801e+01,0.000000000000000000e+00,9.679564357915047879e+00,0.000000000000000000e+00,-1.000000009908511123e+00,0.000000000000000000e+00,4.302888677486721961e-10,0.000000000000000000e+00 +4.357651644591823192e+00,4.702000000000000313e+01,0.000000000000000000e+00,9.678531253559384595e+00,0.000000000000000000e+00,-1.000000009908066589e+00,0.000000000000000000e+00,4.347559806816699647e-10,0.000000000000000000e+00 +4.358684859212721641e+00,4.703000000000000114e+01,0.000000000000000000e+00,9.677498038928249002e+00,0.000000000000000000e+00,-1.000000009907617393e+00,0.000000000000000000e+00,-1.863255893920153812e-09,0.000000000000000000e+00 +4.359718184144410813e+00,4.703999999999999915e+01,0.000000000000000000e+00,9.676464713986321797e+00,0.000000000000000000e+00,-1.000000009909542742e+00,0.000000000000000000e+00,1.866064992327913888e-09,0.000000000000000000e+00 +4.360751619422229552e+00,4.705000000000000426e+01,0.000000000000000000e+00,9.675431278698262361e+00,0.000000000000000000e+00,-1.000000009907614285e+00,0.000000000000000000e+00,-1.669933687538573891e-09,0.000000000000000000e+00 +4.361785165081534466e+00,4.706000000000000227e+01,0.000000000000000000e+00,9.674397733028717639e+00,0.000000000000000000e+00,-1.000000009909340237e+00,0.000000000000000000e+00,8.463702420720842067e-10,0.000000000000000000e+00 +4.362818821157701699e+00,4.707000000000000028e+01,0.000000000000000000e+00,9.673364076942307932e+00,0.000000000000000000e+00,-1.000000009908465382e+00,0.000000000000000000e+00,-5.492227105272968975e-10,0.000000000000000000e+00 +4.363852587686125162e+00,4.707999999999999829e+01,0.000000000000000000e+00,9.672330310403641107e+00,0.000000000000000000e+00,-1.000000009909033150e+00,0.000000000000000000e+00,8.071014369392255985e-10,0.000000000000000000e+00 +4.364886464702219193e+00,4.709000000000000341e+01,0.000000000000000000e+00,9.671296433377301938e+00,0.000000000000000000e+00,-1.000000009908198706e+00,0.000000000000000000e+00,-1.719255832047099084e-09,0.000000000000000000e+00 +4.365920452241416783e+00,4.710000000000000142e+01,0.000000000000000000e+00,9.670262445827859210e+00,0.000000000000000000e+00,-1.000000009909976395e+00,0.000000000000000000e+00,1.853918040357121891e-09,0.000000000000000000e+00 +4.366954550339169572e+00,4.710999999999999943e+01,0.000000000000000000e+00,9.669228347719858618e+00,0.000000000000000000e+00,-1.000000009908059262e+00,0.000000000000000000e+00,-1.749804990545485904e-09,0.000000000000000000e+00 +4.367988759030947854e+00,4.711999999999999744e+01,0.000000000000000000e+00,9.668194139017833422e+00,0.000000000000000000e+00,-1.000000009909868925e+00,0.000000000000000000e+00,7.704758778744880310e-10,0.000000000000000000e+00 +4.369023078352241463e+00,4.713000000000000256e+01,0.000000000000000000e+00,9.667159819686290234e+00,0.000000000000000000e+00,-1.000000009909072007e+00,0.000000000000000000e+00,1.123928701571351029e-09,0.000000000000000000e+00 +4.370057508338557994e+00,4.714000000000000057e+01,0.000000000000000000e+00,9.666125389689723235e+00,0.000000000000000000e+00,-1.000000009907909382e+00,0.000000000000000000e+00,-2.334542467422709242e-09,0.000000000000000000e+00 +4.371092049025425474e+00,4.714999999999999858e+01,0.000000000000000000e+00,9.665090848992605288e+00,0.000000000000000000e+00,-1.000000009910324561e+00,0.000000000000000000e+00,2.026544551881607712e-09,0.000000000000000000e+00 +4.372126700448390579e+00,4.716000000000000369e+01,0.000000000000000000e+00,9.664056197559386163e+00,0.000000000000000000e+00,-1.000000009908227794e+00,0.000000000000000000e+00,-7.160706590182567950e-10,0.000000000000000000e+00 +4.373161462643019526e+00,4.717000000000000171e+01,0.000000000000000000e+00,9.663021435354504973e+00,0.000000000000000000e+00,-1.000000009908968757e+00,0.000000000000000000e+00,-5.917624860953313063e-10,0.000000000000000000e+00 +4.374196335644895406e+00,4.717999999999999972e+01,0.000000000000000000e+00,9.661986562342374185e+00,0.000000000000000000e+00,-1.000000009909581156e+00,0.000000000000000000e+00,-9.059990369657953634e-10,0.000000000000000000e+00 +4.375231319489622628e+00,4.718999999999999773e+01,0.000000000000000000e+00,9.660951578487390279e+00,0.000000000000000000e+00,-1.000000009910518850e+00,0.000000000000000000e+00,1.670223270580147192e-09,0.000000000000000000e+00 +4.376266414212824252e+00,4.720000000000000284e+01,0.000000000000000000e+00,9.659916483753930194e+00,0.000000000000000000e+00,-1.000000009908790011e+00,0.000000000000000000e+00,-1.138959072138531500e-09,0.000000000000000000e+00 +4.377301619850141989e+00,4.721000000000000085e+01,0.000000000000000000e+00,9.658881278106354884e+00,0.000000000000000000e+00,-1.000000009909969068e+00,0.000000000000000000e+00,6.264675936528943385e-10,0.000000000000000000e+00 +4.378336936437236204e+00,4.721999999999999886e+01,0.000000000000000000e+00,9.657845961509000432e+00,0.000000000000000000e+00,-1.000000009909320475e+00,0.000000000000000000e+00,3.495490323248622166e-10,0.000000000000000000e+00 +4.379372364009787688e+00,4.723000000000000398e+01,0.000000000000000000e+00,9.656810533926188711e+00,0.000000000000000000e+00,-1.000000009908958543e+00,0.000000000000000000e+00,-1.954906051211514581e-09,0.000000000000000000e+00 +4.380407902603494996e+00,4.724000000000000199e+01,0.000000000000000000e+00,9.655774995322220278e+00,0.000000000000000000e+00,-1.000000009910982923e+00,0.000000000000000000e+00,2.008082336106562640e-09,0.000000000000000000e+00 +4.381443552254076224e+00,4.725000000000000000e+01,0.000000000000000000e+00,9.654739345661374372e+00,0.000000000000000000e+00,-1.000000009908903253e+00,0.000000000000000000e+00,-9.979308857944445252e-10,0.000000000000000000e+00 +4.382479312997269894e+00,4.725999999999999801e+01,0.000000000000000000e+00,9.653703584907917801e+00,0.000000000000000000e+00,-1.000000009909936871e+00,0.000000000000000000e+00,-1.022045974360196228e-09,0.000000000000000000e+00 +4.383515184868831405e+00,4.727000000000000313e+01,0.000000000000000000e+00,9.652667713026090723e+00,0.000000000000000000e+00,-1.000000009910995580e+00,0.000000000000000000e+00,1.945708427683064758e-09,0.000000000000000000e+00 +4.384551167904537472e+00,4.728000000000000114e+01,0.000000000000000000e+00,9.651631729980117314e+00,0.000000000000000000e+00,-1.000000009908979859e+00,0.000000000000000000e+00,-2.010006694319244450e-09,0.000000000000000000e+00 +4.385587262140182574e+00,4.728999999999999915e+01,0.000000000000000000e+00,9.650595635734205757e+00,0.000000000000000000e+00,-1.000000009911062415e+00,0.000000000000000000e+00,2.017290941287482035e-09,0.000000000000000000e+00 +4.386623467611580729e+00,4.730000000000000426e+01,0.000000000000000000e+00,9.649559430252537595e+00,0.000000000000000000e+00,-1.000000009908972087e+00,0.000000000000000000e+00,-2.503880469671563457e-09,0.000000000000000000e+00 +4.387659784354565495e+00,4.731000000000000227e+01,0.000000000000000000e+00,9.648523113499283710e+00,0.000000000000000000e+00,-1.000000009911566901e+00,0.000000000000000000e+00,9.822915475553411163e-10,0.000000000000000000e+00 +4.388696212404989971e+00,4.732000000000000028e+01,0.000000000000000000e+00,9.647486685438586562e+00,0.000000000000000000e+00,-1.000000009910548826e+00,0.000000000000000000e+00,9.102090398378183856e-10,0.000000000000000000e+00 +4.389732751798725907e+00,4.732999999999999829e+01,0.000000000000000000e+00,9.646450146034577955e+00,0.000000000000000000e+00,-1.000000009909605359e+00,0.000000000000000000e+00,-1.050836849013539651e-09,0.000000000000000000e+00 +4.390769402571664592e+00,4.734000000000000341e+01,0.000000000000000000e+00,9.645413495251366598e+00,0.000000000000000000e+00,-1.000000009910694709e+00,0.000000000000000000e+00,7.131901056209210563e-11,0.000000000000000000e+00 +4.391806164759715969e+00,4.735000000000000142e+01,0.000000000000000000e+00,9.644376733053039885e+00,0.000000000000000000e+00,-1.000000009910620768e+00,0.000000000000000000e+00,9.840108969511866671e-10,0.000000000000000000e+00 +4.392843038398810407e+00,4.735999999999999943e+01,0.000000000000000000e+00,9.643339859403669223e+00,0.000000000000000000e+00,-1.000000009909600474e+00,0.000000000000000000e+00,-1.602726814545462273e-09,0.000000000000000000e+00 +4.393880023524896927e+00,4.736999999999999744e+01,0.000000000000000000e+00,9.642302874267306478e+00,0.000000000000000000e+00,-1.000000009911262477e+00,0.000000000000000000e+00,5.842847215803521430e-10,0.000000000000000000e+00 +4.394917120173944092e+00,4.738000000000000256e+01,0.000000000000000000e+00,9.641265777607980425e+00,0.000000000000000000e+00,-1.000000009910656518e+00,0.000000000000000000e+00,-7.004668317452569017e-10,0.000000000000000000e+00 +4.395954328381939114e+00,4.739000000000000057e+01,0.000000000000000000e+00,9.640228569389705626e+00,0.000000000000000000e+00,-1.000000009911383048e+00,0.000000000000000000e+00,1.162110427959477451e-09,0.000000000000000000e+00 +4.396991648184889634e+00,4.739999999999999858e+01,0.000000000000000000e+00,9.639191249576473552e+00,0.000000000000000000e+00,-1.000000009910177567e+00,0.000000000000000000e+00,-4.180065296216029585e-10,0.000000000000000000e+00 +4.398029079618821946e+00,4.741000000000000369e+01,0.000000000000000000e+00,9.638153818132259687e+00,0.000000000000000000e+00,-1.000000009910611221e+00,0.000000000000000000e+00,-4.748882025936815201e-10,0.000000000000000000e+00 +4.399066622719782771e+00,4.742000000000000171e+01,0.000000000000000000e+00,9.637116275021016421e+00,0.000000000000000000e+00,-1.000000009911103938e+00,0.000000000000000000e+00,-6.458126681877157987e-10,0.000000000000000000e+00 +4.400104277523836593e+00,4.742999999999999972e+01,0.000000000000000000e+00,9.636078620206678380e+00,0.000000000000000000e+00,-1.000000009911774068e+00,0.000000000000000000e+00,7.323985222066888463e-10,0.000000000000000000e+00 +4.401142044067068326e+00,4.743999999999999773e+01,0.000000000000000000e+00,9.635040853653160653e+00,0.000000000000000000e+00,-1.000000009911014009e+00,0.000000000000000000e+00,3.746104878465202918e-10,0.000000000000000000e+00 +4.402179922385582422e+00,4.745000000000000284e+01,0.000000000000000000e+00,9.634002975324360563e+00,0.000000000000000000e+00,-1.000000009910625209e+00,0.000000000000000000e+00,-5.668822718931555145e-11,0.000000000000000000e+00 +4.403217912515501986e+00,4.746000000000000085e+01,0.000000000000000000e+00,9.632964985184154116e+00,0.000000000000000000e+00,-1.000000009910684051e+00,0.000000000000000000e+00,-5.469289791530026194e-10,0.000000000000000000e+00 +4.404256014492969662e+00,4.746999999999999886e+01,0.000000000000000000e+00,9.631926883196397782e+00,0.000000000000000000e+00,-1.000000009911251819e+00,0.000000000000000000e+00,5.652630086736128253e-10,0.000000000000000000e+00 +4.405294228354148522e+00,4.748000000000000398e+01,0.000000000000000000e+00,9.630888669324928486e+00,0.000000000000000000e+00,-1.000000009910664955e+00,0.000000000000000000e+00,-1.650270317314472226e-09,0.000000000000000000e+00 +4.406332554135221180e+00,4.749000000000000199e+01,0.000000000000000000e+00,9.629850343533565393e+00,0.000000000000000000e+00,-1.000000009912378474e+00,0.000000000000000000e+00,1.058223050301956526e-09,0.000000000000000000e+00 +4.407370991872388899e+00,4.750000000000000000e+01,0.000000000000000000e+00,9.628811905786104575e+00,0.000000000000000000e+00,-1.000000009911279575e+00,0.000000000000000000e+00,4.669448206370685638e-10,0.000000000000000000e+00 +4.408409541601872483e+00,4.750999999999999801e+01,0.000000000000000000e+00,9.627773356046327891e+00,0.000000000000000000e+00,-1.000000009910794629e+00,0.000000000000000000e+00,-1.761756967581579767e-09,0.000000000000000000e+00 +4.409448203359912277e+00,4.752000000000000313e+01,0.000000000000000000e+00,9.626734694277994109e+00,0.000000000000000000e+00,-1.000000009912624499e+00,0.000000000000000000e+00,9.717368225678536846e-10,0.000000000000000000e+00 +4.410486977182769053e+00,4.753000000000000114e+01,0.000000000000000000e+00,9.625695920444840681e+00,0.000000000000000000e+00,-1.000000009911615084e+00,0.000000000000000000e+00,4.486263746497903021e-10,0.000000000000000000e+00 +4.411525863106722234e+00,4.753999999999999915e+01,0.000000000000000000e+00,9.624657034510590847e+00,0.000000000000000000e+00,-1.000000009911149013e+00,0.000000000000000000e+00,-2.457668644081851728e-11,0.000000000000000000e+00 +4.412564861168070784e+00,4.755000000000000426e+01,0.000000000000000000e+00,9.623618036438944756e+00,0.000000000000000000e+00,-1.000000009911174548e+00,0.000000000000000000e+00,-2.078749533806557646e-09,0.000000000000000000e+00 +4.413603971403134096e+00,4.756000000000000227e+01,0.000000000000000000e+00,9.622578926193583015e+00,0.000000000000000000e+00,-1.000000009913334598e+00,0.000000000000000000e+00,2.524655875289014191e-09,0.000000000000000000e+00 +4.414643193848250213e+00,4.757000000000000028e+01,0.000000000000000000e+00,9.621539703738164917e+00,0.000000000000000000e+00,-1.000000009910710919e+00,0.000000000000000000e+00,-1.005608649362511535e-09,0.000000000000000000e+00 +4.415682528539777607e+00,4.757999999999999829e+01,0.000000000000000000e+00,9.620500369036337318e+00,0.000000000000000000e+00,-1.000000009911756083e+00,0.000000000000000000e+00,-1.141361082796191550e-09,0.000000000000000000e+00 +4.416721975514093401e+00,4.759000000000000341e+01,0.000000000000000000e+00,9.619460922051718654e+00,0.000000000000000000e+00,-1.000000009912942467e+00,0.000000000000000000e+00,4.861420834465437680e-10,0.000000000000000000e+00 +4.417761534807595147e+00,4.760000000000000142e+01,0.000000000000000000e+00,9.618421362747911374e+00,0.000000000000000000e+00,-1.000000009912437093e+00,0.000000000000000000e+00,6.005640623040681010e-10,0.000000000000000000e+00 +4.418801206456700825e+00,4.760999999999999943e+01,0.000000000000000000e+00,9.617381691088500162e+00,0.000000000000000000e+00,-1.000000009911812704e+00,0.000000000000000000e+00,8.616692942174285615e-10,0.000000000000000000e+00 +4.419840990497846178e+00,4.761999999999999744e+01,0.000000000000000000e+00,9.616341907037048387e+00,0.000000000000000000e+00,-1.000000009910916754e+00,0.000000000000000000e+00,-2.003084441202552696e-09,0.000000000000000000e+00 +4.420880886967488266e+00,4.763000000000000256e+01,0.000000000000000000e+00,9.615302010557099877e+00,0.000000000000000000e+00,-1.000000009912999754e+00,0.000000000000000000e+00,2.344258477913573576e-10,0.000000000000000000e+00 +4.421920895902102799e+00,4.764000000000000057e+01,0.000000000000000000e+00,9.614262001612175368e+00,0.000000000000000000e+00,-1.000000009912755949e+00,0.000000000000000000e+00,1.015735464708250101e-09,0.000000000000000000e+00 +4.422961017338185918e+00,4.764999999999999858e+01,0.000000000000000000e+00,9.613221880165781386e+00,0.000000000000000000e+00,-1.000000009911699461e+00,0.000000000000000000e+00,-1.285221017177166366e-09,0.000000000000000000e+00 +4.424001251312253302e+00,4.766000000000000369e+01,0.000000000000000000e+00,9.612181646181403138e+00,0.000000000000000000e+00,-1.000000009913036392e+00,0.000000000000000000e+00,1.553367612781203407e-09,0.000000000000000000e+00 +4.425041597860841058e+00,4.767000000000000171e+01,0.000000000000000000e+00,9.611141299622502743e+00,0.000000000000000000e+00,-1.000000009911420351e+00,0.000000000000000000e+00,-1.943953578071008935e-09,0.000000000000000000e+00 +4.426082057020503058e+00,4.767999999999999972e+01,0.000000000000000000e+00,9.610100840452528104e+00,0.000000000000000000e+00,-1.000000009913442955e+00,0.000000000000000000e+00,1.364823920003352290e-09,0.000000000000000000e+00 +4.427122628827815376e+00,4.768999999999999773e+01,0.000000000000000000e+00,9.609060268634900481e+00,0.000000000000000000e+00,-1.000000009912022758e+00,0.000000000000000000e+00,-1.632234593153136635e-09,0.000000000000000000e+00 +4.428163313319371852e+00,4.770000000000000284e+01,0.000000000000000000e+00,9.608019584133028701e+00,0.000000000000000000e+00,-1.000000009913721399e+00,0.000000000000000000e+00,2.201251316093712877e-09,0.000000000000000000e+00 +4.429204110531787641e+00,4.771000000000000085e+01,0.000000000000000000e+00,9.606978786910294943e+00,0.000000000000000000e+00,-1.000000009911430343e+00,0.000000000000000000e+00,-1.880182921084102285e-09,0.000000000000000000e+00 +4.430245020501696551e+00,4.771999999999999886e+01,0.000000000000000000e+00,9.605937876930068953e+00,0.000000000000000000e+00,-1.000000009913387444e+00,0.000000000000000000e+00,8.945578379347887675e-10,0.000000000000000000e+00 +4.431286043265753705e+00,4.773000000000000398e+01,0.000000000000000000e+00,9.604896854155692054e+00,0.000000000000000000e+00,-1.000000009912456189e+00,0.000000000000000000e+00,-9.371152027073415547e-10,0.000000000000000000e+00 +4.432327178860631989e+00,4.774000000000000199e+01,0.000000000000000000e+00,9.603855718550493137e+00,0.000000000000000000e+00,-1.000000009913431853e+00,0.000000000000000000e+00,8.346543741134887788e-10,0.000000000000000000e+00 +4.433368427323026495e+00,4.775000000000000000e+01,0.000000000000000000e+00,9.602814470077776221e+00,0.000000000000000000e+00,-1.000000009912562771e+00,0.000000000000000000e+00,-3.311389134459560669e-10,0.000000000000000000e+00 +4.434409788689650966e+00,4.775999999999999801e+01,0.000000000000000000e+00,9.601773108700829340e+00,0.000000000000000000e+00,-1.000000009912907606e+00,0.000000000000000000e+00,-1.142976949436328501e-09,0.000000000000000000e+00 +4.435451262997238686e+00,4.777000000000000313e+01,0.000000000000000000e+00,9.600731634382917434e+00,0.000000000000000000e+00,-1.000000009914097987e+00,0.000000000000000000e+00,1.686672772366063352e-09,0.000000000000000000e+00 +4.436492850282544254e+00,4.778000000000000114e+01,0.000000000000000000e+00,9.599690047087285905e+00,0.000000000000000000e+00,-1.000000009912341170e+00,0.000000000000000000e+00,-1.651319054713722581e-09,0.000000000000000000e+00 +4.437534550582340032e+00,4.778999999999999915e+01,0.000000000000000000e+00,9.598648346777164164e+00,0.000000000000000000e+00,-1.000000009914061350e+00,0.000000000000000000e+00,1.952935919680579762e-09,0.000000000000000000e+00 +4.438576363933420588e+00,4.780000000000000426e+01,0.000000000000000000e+00,9.597606533415754981e+00,0.000000000000000000e+00,-1.000000009912026755e+00,0.000000000000000000e+00,-2.216766840325916165e-09,0.000000000000000000e+00 +4.439618290372599141e+00,4.781000000000000227e+01,0.000000000000000000e+00,9.596564606966248689e+00,0.000000000000000000e+00,-1.000000009914336463e+00,0.000000000000000000e+00,5.817262533240410701e-10,0.000000000000000000e+00 +4.440660329936709338e+00,4.782000000000000028e+01,0.000000000000000000e+00,9.595522567391807200e+00,0.000000000000000000e+00,-1.000000009913730281e+00,0.000000000000000000e+00,5.441639280760729612e-10,0.000000000000000000e+00 +4.441702482662605256e+00,4.782999999999999829e+01,0.000000000000000000e+00,9.594480414655579992e+00,0.000000000000000000e+00,-1.000000009913163179e+00,0.000000000000000000e+00,-6.781071517602812575e-10,0.000000000000000000e+00 +4.442744748587159620e+00,4.784000000000000341e+01,0.000000000000000000e+00,9.593438148720693448e+00,0.000000000000000000e+00,-1.000000009913869947e+00,0.000000000000000000e+00,1.834077389084258219e-09,0.000000000000000000e+00 +4.443787127747266474e+00,4.785000000000000142e+01,0.000000000000000000e+00,9.592395769550252638e+00,0.000000000000000000e+00,-1.000000009911958143e+00,0.000000000000000000e+00,-1.714388487819240064e-09,0.000000000000000000e+00 +4.444829620179839402e+00,4.785999999999999943e+01,0.000000000000000000e+00,9.591353277107346642e+00,0.000000000000000000e+00,-1.000000009913745380e+00,0.000000000000000000e+00,1.337456780442150814e-10,0.000000000000000000e+00 +4.445872225921812415e+00,4.787000000000000455e+01,0.000000000000000000e+00,9.590310671355037897e+00,0.000000000000000000e+00,-1.000000009913605936e+00,0.000000000000000000e+00,-7.810920697466422882e-10,0.000000000000000000e+00 +4.446914945010138176e+00,4.788000000000000256e+01,0.000000000000000000e+00,9.589267952256374627e+00,0.000000000000000000e+00,-1.000000009914420396e+00,0.000000000000000000e+00,4.588523436124811664e-10,0.000000000000000000e+00 +4.447957777481791553e+00,4.789000000000000057e+01,0.000000000000000000e+00,9.588225119774381966e+00,0.000000000000000000e+00,-1.000000009913941890e+00,0.000000000000000000e+00,5.984657394472356757e-10,0.000000000000000000e+00 +4.449000723373766952e+00,4.789999999999999858e+01,0.000000000000000000e+00,9.587182173872067281e+00,0.000000000000000000e+00,-1.000000009913317722e+00,0.000000000000000000e+00,-3.463528441136588152e-10,0.000000000000000000e+00 +4.450043782723077435e+00,4.791000000000000369e+01,0.000000000000000000e+00,9.586139114512416626e+00,0.000000000000000000e+00,-1.000000009913678989e+00,0.000000000000000000e+00,-7.283899716683858399e-10,0.000000000000000000e+00 +4.451086955566757375e+00,4.792000000000000171e+01,0.000000000000000000e+00,9.585095941658394736e+00,0.000000000000000000e+00,-1.000000009914438825e+00,0.000000000000000000e+00,-5.348465248775090242e-10,0.000000000000000000e+00 +4.452130241941861577e+00,4.792999999999999972e+01,0.000000000000000000e+00,9.584052655272946808e+00,0.000000000000000000e+00,-1.000000009914996824e+00,0.000000000000000000e+00,1.880803454474884389e-09,0.000000000000000000e+00 +4.453173641885464384e+00,4.793999999999999773e+01,0.000000000000000000e+00,9.583009255318998498e+00,0.000000000000000000e+00,-1.000000009913034393e+00,0.000000000000000000e+00,-1.626319961776159282e-09,0.000000000000000000e+00 +4.454217155434660569e+00,4.795000000000000284e+01,0.000000000000000000e+00,9.581965741759457700e+00,0.000000000000000000e+00,-1.000000009914731480e+00,0.000000000000000000e+00,3.793553231003413418e-10,0.000000000000000000e+00 +4.455260782626565330e+00,4.796000000000000085e+01,0.000000000000000000e+00,9.580922114557205660e+00,0.000000000000000000e+00,-1.000000009914335575e+00,0.000000000000000000e+00,-2.450755659737491467e-10,0.000000000000000000e+00 +4.456304523498313408e+00,4.796999999999999886e+01,0.000000000000000000e+00,9.579878373675109415e+00,0.000000000000000000e+00,-1.000000009914591370e+00,0.000000000000000000e+00,1.406903828182474785e-09,0.000000000000000000e+00 +4.457348378087060858e+00,4.798000000000000398e+01,0.000000000000000000e+00,9.578834519076012910e+00,0.000000000000000000e+00,-1.000000009913122767e+00,0.000000000000000000e+00,-1.171299539505268545e-09,0.000000000000000000e+00 +4.458392346429982389e+00,4.799000000000000199e+01,0.000000000000000000e+00,9.577790550722742324e+00,0.000000000000000000e+00,-1.000000009914345567e+00,0.000000000000000000e+00,-1.444877750813817908e-09,0.000000000000000000e+00 +4.459436428564274024e+00,4.800000000000000000e+01,0.000000000000000000e+00,9.576746468578098970e+00,0.000000000000000000e+00,-1.000000009915854138e+00,0.000000000000000000e+00,2.228535200614578196e-09,0.000000000000000000e+00 +4.460480624527152216e+00,4.800999999999999801e+01,0.000000000000000000e+00,9.575702272604866394e+00,0.000000000000000000e+00,-1.000000009913527110e+00,0.000000000000000000e+00,-1.541731568602997177e-09,0.000000000000000000e+00 +4.461524934355853844e+00,4.802000000000000313e+01,0.000000000000000000e+00,9.574657962765812158e+00,0.000000000000000000e+00,-1.000000009915137156e+00,0.000000000000000000e+00,2.910495567004822061e-10,0.000000000000000000e+00 +4.462569358087635329e+00,4.803000000000000114e+01,0.000000000000000000e+00,9.573613539023675401e+00,0.000000000000000000e+00,-1.000000009914833177e+00,0.000000000000000000e+00,1.225718541464593473e-09,0.000000000000000000e+00 +4.463613895759773520e+00,4.803999999999999915e+01,0.000000000000000000e+00,9.572569001341181050e+00,0.000000000000000000e+00,-1.000000009913552868e+00,0.000000000000000000e+00,-1.979300335641400317e-09,0.000000000000000000e+00 +4.464658547409565692e+00,4.805000000000000426e+01,0.000000000000000000e+00,9.571524349681032717e+00,0.000000000000000000e+00,-1.000000009915620547e+00,0.000000000000000000e+00,4.582158318980302599e-10,0.000000000000000000e+00 +4.465703313074329550e+00,4.806000000000000227e+01,0.000000000000000000e+00,9.570479584005909146e+00,0.000000000000000000e+00,-1.000000009915141819e+00,0.000000000000000000e+00,4.131142608289614669e-10,0.000000000000000000e+00 +4.466748192791404115e+00,4.807000000000000028e+01,0.000000000000000000e+00,9.569434704278474868e+00,0.000000000000000000e+00,-1.000000009914710164e+00,0.000000000000000000e+00,-4.723522317198425329e-10,0.000000000000000000e+00 +4.467793186598147059e+00,4.807999999999999829e+01,0.000000000000000000e+00,9.568389710461371322e+00,0.000000000000000000e+00,-1.000000009915203769e+00,0.000000000000000000e+00,1.069953250040966341e-09,0.000000000000000000e+00 +4.468838294531937372e+00,4.809000000000000341e+01,0.000000000000000000e+00,9.567344602517218632e+00,0.000000000000000000e+00,-1.000000009914085553e+00,0.000000000000000000e+00,-1.451162101146932685e-09,0.000000000000000000e+00 +4.469883516630174469e+00,4.810000000000000142e+01,0.000000000000000000e+00,9.566299380408619157e+00,0.000000000000000000e+00,-1.000000009915602339e+00,0.000000000000000000e+00,1.091810615589945602e-10,0.000000000000000000e+00 +4.470928852930278197e+00,4.810999999999999943e+01,0.000000000000000000e+00,9.565254044098150388e+00,0.000000000000000000e+00,-1.000000009915488208e+00,0.000000000000000000e+00,8.858841353361541656e-10,0.000000000000000000e+00 +4.471974303469688827e+00,4.812000000000000455e+01,0.000000000000000000e+00,9.564208593548373827e+00,0.000000000000000000e+00,-1.000000009914562060e+00,0.000000000000000000e+00,-7.294843955305255028e-10,0.000000000000000000e+00 +4.473019868285867062e+00,4.813000000000000256e+01,0.000000000000000000e+00,9.563163028721829662e+00,0.000000000000000000e+00,-1.000000009915324783e+00,0.000000000000000000e+00,1.518265860930536193e-10,0.000000000000000000e+00 +4.474065547416293143e+00,4.814000000000000057e+01,0.000000000000000000e+00,9.562117349581034986e+00,0.000000000000000000e+00,-1.000000009915166022e+00,0.000000000000000000e+00,2.940654948251294070e-10,0.000000000000000000e+00 +4.475111340898469514e+00,4.814999999999999858e+01,0.000000000000000000e+00,9.561071556088489132e+00,0.000000000000000000e+00,-1.000000009914858490e+00,0.000000000000000000e+00,-2.880889771542012080e-10,0.000000000000000000e+00 +4.476157248769918162e+00,4.816000000000000369e+01,0.000000000000000000e+00,9.560025648206670112e+00,0.000000000000000000e+00,-1.000000009915159804e+00,0.000000000000000000e+00,-1.578903025464511058e-09,0.000000000000000000e+00 +4.477203271068182389e+00,4.817000000000000171e+01,0.000000000000000000e+00,9.558979625898034627e+00,0.000000000000000000e+00,-1.000000009916811372e+00,0.000000000000000000e+00,1.304925206558251940e-09,0.000000000000000000e+00 +4.478249407830825035e+00,4.817999999999999972e+01,0.000000000000000000e+00,9.557933489125018056e+00,0.000000000000000000e+00,-1.000000009915446242e+00,0.000000000000000000e+00,2.610413705555763367e-10,0.000000000000000000e+00 +4.479295659095429372e+00,4.818999999999999773e+01,0.000000000000000000e+00,9.556887237850039796e+00,0.000000000000000000e+00,-1.000000009915173127e+00,0.000000000000000000e+00,1.748573526858184192e-10,0.000000000000000000e+00 +4.480342024899599984e+00,4.820000000000000284e+01,0.000000000000000000e+00,9.555840872035494371e+00,0.000000000000000000e+00,-1.000000009914990162e+00,0.000000000000000000e+00,-5.631318006212238620e-10,0.000000000000000000e+00 +4.481388505280961887e+00,4.821000000000000085e+01,0.000000000000000000e+00,9.554794391643756768e+00,0.000000000000000000e+00,-1.000000009915579469e+00,0.000000000000000000e+00,-3.159048322744507338e-10,0.000000000000000000e+00 +4.482435100277160522e+00,4.821999999999999886e+01,0.000000000000000000e+00,9.553747796637180656e+00,0.000000000000000000e+00,-1.000000009915910093e+00,0.000000000000000000e+00,-6.902899436557727382e-10,0.000000000000000000e+00 +4.483481809925861761e+00,4.823000000000000398e+01,0.000000000000000000e+00,9.552701086978100165e+00,0.000000000000000000e+00,-1.000000009916632626e+00,0.000000000000000000e+00,1.569208821582712410e-09,0.000000000000000000e+00 +4.484528634264752789e+00,4.824000000000000199e+01,0.000000000000000000e+00,9.551654262628828107e+00,0.000000000000000000e+00,-1.000000009914989940e+00,0.000000000000000000e+00,-1.627361426884710235e-09,0.000000000000000000e+00 +4.485575573331541221e+00,4.825000000000000000e+01,0.000000000000000000e+00,9.550607323551659533e+00,0.000000000000000000e+00,-1.000000009916693688e+00,0.000000000000000000e+00,1.080900825026605349e-09,0.000000000000000000e+00 +4.486622627163954213e+00,4.825999999999999801e+01,0.000000000000000000e+00,9.549560269708862847e+00,0.000000000000000000e+00,-1.000000009915561927e+00,0.000000000000000000e+00,-1.675138386463270817e-11,0.000000000000000000e+00 +4.487669795799741124e+00,4.827000000000000313e+01,0.000000000000000000e+00,9.548513101062692243e+00,0.000000000000000000e+00,-1.000000009915579469e+00,0.000000000000000000e+00,-4.261593596485371977e-11,0.000000000000000000e+00 +4.488717079276671740e+00,4.828000000000000114e+01,0.000000000000000000e+00,9.547465817575377045e+00,0.000000000000000000e+00,-1.000000009915624100e+00,0.000000000000000000e+00,-6.035535445344985498e-10,0.000000000000000000e+00 +4.489764477632536277e+00,4.828999999999999915e+01,0.000000000000000000e+00,9.546418419209127038e+00,0.000000000000000000e+00,-1.000000009916256261e+00,0.000000000000000000e+00,-6.549967882597807441e-11,0.000000000000000000e+00 +4.490811990905145379e+00,4.830000000000000426e+01,0.000000000000000000e+00,9.545370905926130689e+00,0.000000000000000000e+00,-1.000000009916324872e+00,0.000000000000000000e+00,-3.242832110853962032e-11,0.000000000000000000e+00 +4.491859619132330117e+00,4.831000000000000227e+01,0.000000000000000000e+00,9.544323277688556928e+00,0.000000000000000000e+00,-1.000000009916358845e+00,0.000000000000000000e+00,-4.906099612755678762e-10,0.000000000000000000e+00 +4.492907362351943767e+00,4.832000000000000028e+01,0.000000000000000000e+00,9.543275534458553366e+00,0.000000000000000000e+00,-1.000000009916872878e+00,0.000000000000000000e+00,1.934676988160224188e-10,0.000000000000000000e+00 +4.493955220601859146e+00,4.832999999999999829e+01,0.000000000000000000e+00,9.542227676198246300e+00,0.000000000000000000e+00,-1.000000009916670152e+00,0.000000000000000000e+00,4.159204742477031109e-10,0.000000000000000000e+00 +4.495003193919970386e+00,4.834000000000000341e+01,0.000000000000000000e+00,9.541179702869742485e+00,0.000000000000000000e+00,-1.000000009916234278e+00,0.000000000000000000e+00,1.908829297355837968e-10,0.000000000000000000e+00 +4.496051282344192046e+00,4.835000000000000142e+01,0.000000000000000000e+00,9.540131614435127361e+00,0.000000000000000000e+00,-1.000000009916034216e+00,0.000000000000000000e+00,-4.653981457306327364e-10,0.000000000000000000e+00 +4.497099485912460004e+00,4.835999999999999943e+01,0.000000000000000000e+00,9.539083410856465051e+00,0.000000000000000000e+00,-1.000000009916522048e+00,0.000000000000000000e+00,7.752253346756591180e-11,0.000000000000000000e+00 +4.498147804662731453e+00,4.837000000000000455e+01,0.000000000000000000e+00,9.538035092095798362e+00,0.000000000000000000e+00,-1.000000009916440780e+00,0.000000000000000000e+00,2.172933833863919111e-10,0.000000000000000000e+00 +4.499196238632982237e+00,4.838000000000000256e+01,0.000000000000000000e+00,9.536986658115150561e+00,0.000000000000000000e+00,-1.000000009916212962e+00,0.000000000000000000e+00,-3.070572830280886231e-11,0.000000000000000000e+00 +4.500244787861211293e+00,4.839000000000000057e+01,0.000000000000000000e+00,9.535938108876523600e+00,0.000000000000000000e+00,-1.000000009916245158e+00,0.000000000000000000e+00,-6.519485715113141384e-10,0.000000000000000000e+00 +4.501293452385437988e+00,4.839999999999999858e+01,0.000000000000000000e+00,9.534889444341898113e+00,0.000000000000000000e+00,-1.000000009916928834e+00,0.000000000000000000e+00,-1.609049777351288766e-11,0.000000000000000000e+00 +4.502342232243702114e+00,4.841000000000000369e+01,0.000000000000000000e+00,9.533840664473233417e+00,0.000000000000000000e+00,-1.000000009916945709e+00,0.000000000000000000e+00,2.749902311005743407e-10,0.000000000000000000e+00 +4.503391127474064781e+00,4.842000000000000171e+01,0.000000000000000000e+00,9.532791769232469292e+00,0.000000000000000000e+00,-1.000000009916657273e+00,0.000000000000000000e+00,-1.376916590941794909e-09,0.000000000000000000e+00 +4.504440138114607528e+00,4.842999999999999972e+01,0.000000000000000000e+00,9.531742758581524200e+00,0.000000000000000000e+00,-1.000000009918101673e+00,0.000000000000000000e+00,1.499097156610516689e-09,0.000000000000000000e+00 +4.505489264203433208e+00,4.843999999999999773e+01,0.000000000000000000e+00,9.530693632482293509e+00,0.000000000000000000e+00,-1.000000009916528931e+00,0.000000000000000000e+00,-7.662901789377759370e-10,0.000000000000000000e+00 +4.506538505778665105e+00,4.845000000000000284e+01,0.000000000000000000e+00,9.529644390896656603e+00,0.000000000000000000e+00,-1.000000009917332955e+00,0.000000000000000000e+00,1.523524409173935799e-09,0.000000000000000000e+00 +4.507587862878448703e+00,4.846000000000000085e+01,0.000000000000000000e+00,9.528595033786466217e+00,0.000000000000000000e+00,-1.000000009915734234e+00,0.000000000000000000e+00,-1.295487881233781973e-09,0.000000000000000000e+00 +4.508637335540949920e+00,4.846999999999999886e+01,0.000000000000000000e+00,9.527545561113559103e+00,0.000000000000000000e+00,-1.000000009917093813e+00,0.000000000000000000e+00,-1.143660972666269402e-09,0.000000000000000000e+00 +4.509686923804355096e+00,4.848000000000000398e+01,0.000000000000000000e+00,9.526495972839745363e+00,0.000000000000000000e+00,-1.000000009918294186e+00,0.000000000000000000e+00,1.991350042381009539e-09,0.000000000000000000e+00 +4.510736627706871893e+00,4.849000000000000199e+01,0.000000000000000000e+00,9.525446268926817339e+00,0.000000000000000000e+00,-1.000000009916203858e+00,0.000000000000000000e+00,-1.547599611789463633e-09,0.000000000000000000e+00 +4.511786447286729285e+00,4.850000000000000000e+01,0.000000000000000000e+00,9.524396449336549608e+00,0.000000000000000000e+00,-1.000000009917828558e+00,0.000000000000000000e+00,-4.610353045898225528e-10,0.000000000000000000e+00 +4.512836382582177563e+00,4.850999999999999801e+01,0.000000000000000000e+00,9.523346514030688326e+00,0.000000000000000000e+00,-1.000000009918312616e+00,0.000000000000000000e+00,2.038693297329749247e-09,0.000000000000000000e+00 +4.513886433631487449e+00,4.852000000000000313e+01,0.000000000000000000e+00,9.522296462970963660e+00,0.000000000000000000e+00,-1.000000009916171884e+00,0.000000000000000000e+00,-2.085830499592068619e-09,0.000000000000000000e+00 +4.514936600472950978e+00,4.853000000000000114e+01,0.000000000000000000e+00,9.521246296119086239e+00,0.000000000000000000e+00,-1.000000009918362354e+00,0.000000000000000000e+00,1.676514108167034496e-09,0.000000000000000000e+00 +4.515986883144881503e+00,4.853999999999999915e+01,0.000000000000000000e+00,9.520196013436738269e+00,0.000000000000000000e+00,-1.000000009916601540e+00,0.000000000000000000e+00,-1.154405247602641867e-09,0.000000000000000000e+00 +4.517037281685613692e+00,4.855000000000000426e+01,0.000000000000000000e+00,9.519145614885589524e+00,0.000000000000000000e+00,-1.000000009917814126e+00,0.000000000000000000e+00,7.078697331464454273e-10,0.000000000000000000e+00 +4.518087796133502643e+00,4.856000000000000227e+01,0.000000000000000000e+00,9.518095100427281352e+00,0.000000000000000000e+00,-1.000000009917070498e+00,0.000000000000000000e+00,-7.714062081678369208e-10,0.000000000000000000e+00 +4.519138426526925656e+00,4.857000000000000028e+01,0.000000000000000000e+00,9.517044470023439118e+00,0.000000000000000000e+00,-1.000000009917880961e+00,0.000000000000000000e+00,-7.474418037938891195e-10,0.000000000000000000e+00 +4.520189172904280461e+00,4.857999999999999829e+01,0.000000000000000000e+00,9.515993723635663315e+00,0.000000000000000000e+00,-1.000000009918666333e+00,0.000000000000000000e+00,7.923656500626594314e-10,0.000000000000000000e+00 +4.521240035303986105e+00,4.859000000000000341e+01,0.000000000000000000e+00,9.514942861225534898e+00,0.000000000000000000e+00,-1.000000009917833665e+00,0.000000000000000000e+00,6.456538722311496255e-10,0.000000000000000000e+00 +4.522291013764482059e+00,4.860000000000000142e+01,0.000000000000000000e+00,9.513891882754615281e+00,0.000000000000000000e+00,-1.000000009917155097e+00,0.000000000000000000e+00,-1.170963386390085437e-09,0.000000000000000000e+00 +4.523342108324230892e+00,4.860999999999999943e+01,0.000000000000000000e+00,9.512840788184442786e+00,0.000000000000000000e+00,-1.000000009918385890e+00,0.000000000000000000e+00,1.801770553271648518e-10,0.000000000000000000e+00 +4.524393319021714710e+00,4.862000000000000455e+01,0.000000000000000000e+00,9.511789577476532642e+00,0.000000000000000000e+00,-1.000000009918196486e+00,0.000000000000000000e+00,1.498493486011742781e-09,0.000000000000000000e+00 +4.525444645895437823e+00,4.863000000000000256e+01,0.000000000000000000e+00,9.510738250592382315e+00,0.000000000000000000e+00,-1.000000009916621080e+00,0.000000000000000000e+00,-2.022267453220486578e-09,0.000000000000000000e+00 +4.526496088983925858e+00,4.864000000000000057e+01,0.000000000000000000e+00,9.509686807493467953e+00,0.000000000000000000e+00,-1.000000009918747379e+00,0.000000000000000000e+00,8.813712589645413640e-10,0.000000000000000000e+00 +4.527547648325724872e+00,4.864999999999999858e+01,0.000000000000000000e+00,9.508635248141239060e+00,0.000000000000000000e+00,-1.000000009917820565e+00,0.000000000000000000e+00,-1.022100254127783348e-09,0.000000000000000000e+00 +4.528599323959402234e+00,4.866000000000000369e+01,0.000000000000000000e+00,9.507583572497130930e+00,0.000000000000000000e+00,-1.000000009918895483e+00,0.000000000000000000e+00,1.918785732311665774e-09,0.000000000000000000e+00 +4.529651115923548410e+00,4.867000000000000171e+01,0.000000000000000000e+00,9.506531780522552211e+00,0.000000000000000000e+00,-1.000000009916877319e+00,0.000000000000000000e+00,-1.520673696895002232e-09,0.000000000000000000e+00 +4.530703024256773404e+00,4.867999999999999972e+01,0.000000000000000000e+00,9.505479872178895562e+00,0.000000000000000000e+00,-1.000000009918476929e+00,0.000000000000000000e+00,-8.695838954104096062e-11,0.000000000000000000e+00 +4.531755048997709423e+00,4.868999999999999773e+01,0.000000000000000000e+00,9.504427847427525222e+00,0.000000000000000000e+00,-1.000000009918568411e+00,0.000000000000000000e+00,-1.867710129882151594e-10,0.000000000000000000e+00 +4.532807190185009105e+00,4.870000000000000284e+01,0.000000000000000000e+00,9.503375706229789444e+00,0.000000000000000000e+00,-1.000000009918764921e+00,0.000000000000000000e+00,-1.998334119024305328e-10,0.000000000000000000e+00 +4.533859447857348179e+00,4.871000000000000085e+01,0.000000000000000000e+00,9.502323448547013385e+00,0.000000000000000000e+00,-1.000000009918975197e+00,0.000000000000000000e+00,1.492782306621756370e-09,0.000000000000000000e+00 +4.534911822053421915e+00,4.871999999999999886e+01,0.000000000000000000e+00,9.501271074340500888e+00,0.000000000000000000e+00,-1.000000009917404231e+00,0.000000000000000000e+00,-1.509494630112102281e-09,0.000000000000000000e+00 +4.535964312811948673e+00,4.873000000000000398e+01,0.000000000000000000e+00,9.500218583571536257e+00,0.000000000000000000e+00,-1.000000009918992960e+00,0.000000000000000000e+00,4.313870816875241015e-10,0.000000000000000000e+00 +4.537016920171667245e+00,4.874000000000000199e+01,0.000000000000000000e+00,9.499165976201377148e+00,0.000000000000000000e+00,-1.000000009918538879e+00,0.000000000000000000e+00,-6.882445409216473818e-10,0.000000000000000000e+00 +4.538069644171337735e+00,4.875000000000000000e+01,0.000000000000000000e+00,9.498113252191265232e+00,0.000000000000000000e+00,-1.000000009919263411e+00,0.000000000000000000e+00,1.559819953494003754e-09,0.000000000000000000e+00 +4.539122484849742456e+00,4.875999999999999801e+01,0.000000000000000000e+00,9.497060411502417310e+00,0.000000000000000000e+00,-1.000000009917621169e+00,0.000000000000000000e+00,-8.236859631544843582e-10,0.000000000000000000e+00 +4.540175442245684145e+00,4.877000000000000313e+01,0.000000000000000000e+00,9.496007454096032419e+00,0.000000000000000000e+00,-1.000000009918488475e+00,0.000000000000000000e+00,-1.411454817417531051e-09,0.000000000000000000e+00 +4.541228516397988635e+00,4.878000000000000114e+01,0.000000000000000000e+00,9.494954379933282951e+00,0.000000000000000000e+00,-1.000000009919974842e+00,0.000000000000000000e+00,1.409611649277529662e-09,0.000000000000000000e+00 +4.542281707345502184e+00,4.878999999999999915e+01,0.000000000000000000e+00,9.493901188975321759e+00,0.000000000000000000e+00,-1.000000009918490251e+00,0.000000000000000000e+00,-3.516259990557121933e-10,0.000000000000000000e+00 +4.543335015127092369e+00,4.880000000000000426e+01,0.000000000000000000e+00,9.492847881183283931e+00,0.000000000000000000e+00,-1.000000009918860622e+00,0.000000000000000000e+00,-2.742294190265382805e-10,0.000000000000000000e+00 +4.544388439781649858e+00,4.881000000000000227e+01,0.000000000000000000e+00,9.491794456518277912e+00,0.000000000000000000e+00,-1.000000009919149502e+00,0.000000000000000000e+00,5.437612515328184361e-11,0.000000000000000000e+00 +4.545441981348084859e+00,4.882000000000000028e+01,0.000000000000000000e+00,9.490740914941392603e+00,0.000000000000000000e+00,-1.000000009919092214e+00,0.000000000000000000e+00,6.501229715148814309e-10,0.000000000000000000e+00 +4.546495639865330674e+00,4.882999999999999829e+01,0.000000000000000000e+00,9.489687256413695593e+00,0.000000000000000000e+00,-1.000000009918407207e+00,0.000000000000000000e+00,-7.227469131953817734e-11,0.000000000000000000e+00 +4.547549415372341031e+00,4.884000000000000341e+01,0.000000000000000000e+00,9.488633480896233152e+00,0.000000000000000000e+00,-1.000000009918483368e+00,0.000000000000000000e+00,-2.095943993206800039e-09,0.000000000000000000e+00 +4.548603307908092752e+00,4.885000000000000142e+01,0.000000000000000000e+00,9.487579588350028459e+00,0.000000000000000000e+00,-1.000000009920692268e+00,0.000000000000000000e+00,2.588249677303721095e-09,0.000000000000000000e+00 +4.549657317511583088e+00,4.885999999999999943e+01,0.000000000000000000e+00,9.486525578736081599e+00,0.000000000000000000e+00,-1.000000009917964228e+00,0.000000000000000000e+00,-1.993105792097456256e-09,0.000000000000000000e+00 +4.550711444221831492e+00,4.887000000000000455e+01,0.000000000000000000e+00,9.485471452015378446e+00,0.000000000000000000e+00,-1.000000009920065214e+00,0.000000000000000000e+00,1.760781328271589281e-09,0.000000000000000000e+00 +4.551765688077878735e+00,4.888000000000000256e+01,0.000000000000000000e+00,9.484417208148872902e+00,0.000000000000000000e+00,-1.000000009918208921e+00,0.000000000000000000e+00,-2.118810050326343082e-09,0.000000000000000000e+00 +4.552820049118787793e+00,4.889000000000000057e+01,0.000000000000000000e+00,9.483362847097506432e+00,0.000000000000000000e+00,-1.000000009920442912e+00,0.000000000000000000e+00,7.660644127436439814e-10,0.000000000000000000e+00 +4.553874527383642956e+00,4.889999999999999858e+01,0.000000000000000000e+00,9.482308368822190303e+00,0.000000000000000000e+00,-1.000000009919635113e+00,0.000000000000000000e+00,8.428298148376362094e-10,0.000000000000000000e+00 +4.554929122911550721e+00,4.891000000000000369e+01,0.000000000000000000e+00,9.481253773283821573e+00,0.000000000000000000e+00,-1.000000009918746269e+00,0.000000000000000000e+00,-2.745260667760729723e-10,0.000000000000000000e+00 +4.555983835741638011e+00,4.892000000000000171e+01,0.000000000000000000e+00,9.480199060443272430e+00,0.000000000000000000e+00,-1.000000009919035815e+00,0.000000000000000000e+00,-9.731540075203881517e-10,0.000000000000000000e+00 +4.557038665913055731e+00,4.892999999999999972e+01,0.000000000000000000e+00,9.479144230261391968e+00,0.000000000000000000e+00,-1.000000009920062327e+00,0.000000000000000000e+00,3.580252613416462996e-10,0.000000000000000000e+00 +4.558093613464974325e+00,4.893999999999999773e+01,0.000000000000000000e+00,9.478089282699007967e+00,0.000000000000000000e+00,-1.000000009919684629e+00,0.000000000000000000e+00,5.408715576868162337e-10,0.000000000000000000e+00 +4.559148678436587332e+00,4.895000000000000284e+01,0.000000000000000000e+00,9.477034217716928666e+00,0.000000000000000000e+00,-1.000000009919113975e+00,0.000000000000000000e+00,-4.080284854025145742e-10,0.000000000000000000e+00 +4.560203860867110492e+00,4.896000000000000085e+01,0.000000000000000000e+00,9.475979035275939211e+00,0.000000000000000000e+00,-1.000000009919544519e+00,0.000000000000000000e+00,-8.782471748345736702e-10,0.000000000000000000e+00 +4.561259160795779977e+00,4.896999999999999886e+01,0.000000000000000000e+00,9.474923735336801656e+00,0.000000000000000000e+00,-1.000000009920471333e+00,0.000000000000000000e+00,7.409779766621985908e-10,0.000000000000000000e+00 +4.562314578261855047e+00,4.898000000000000398e+01,0.000000000000000000e+00,9.473868317860256738e+00,0.000000000000000000e+00,-1.000000009919689292e+00,0.000000000000000000e+00,-3.205918933972603154e-10,0.000000000000000000e+00 +4.563370113304615394e+00,4.899000000000000199e+01,0.000000000000000000e+00,9.472812782807025656e+00,0.000000000000000000e+00,-1.000000009920027688e+00,0.000000000000000000e+00,7.363957788576990183e-10,0.000000000000000000e+00 +4.564425765963363801e+00,4.900000000000000000e+01,0.000000000000000000e+00,9.471757130137804737e+00,0.000000000000000000e+00,-1.000000009919250310e+00,0.000000000000000000e+00,-8.545108891533348519e-10,0.000000000000000000e+00 +4.565481536277425256e+00,4.900999999999999801e+01,0.000000000000000000e+00,9.470701359813270770e+00,0.000000000000000000e+00,-1.000000009920152477e+00,0.000000000000000000e+00,-2.967217498083601652e-10,0.000000000000000000e+00 +4.566537424286146063e+00,4.902000000000000313e+01,0.000000000000000000e+00,9.469645471794075675e+00,0.000000000000000000e+00,-1.000000009920465782e+00,0.000000000000000000e+00,8.305600565880276587e-10,0.000000000000000000e+00 +4.567593430028893842e+00,4.903000000000000114e+01,0.000000000000000000e+00,9.468589466040851832e+00,0.000000000000000000e+00,-1.000000009919588706e+00,0.000000000000000000e+00,-6.427187226362570944e-10,0.000000000000000000e+00 +4.568649553545059305e+00,4.903999999999999915e+01,0.000000000000000000e+00,9.467533342514210304e+00,0.000000000000000000e+00,-1.000000009920267496e+00,0.000000000000000000e+00,7.778194392416577412e-11,0.000000000000000000e+00 +4.569705794874054483e+00,4.905000000000000426e+01,0.000000000000000000e+00,9.466477101174737285e+00,0.000000000000000000e+00,-1.000000009920185340e+00,0.000000000000000000e+00,-1.784581162599907973e-10,0.000000000000000000e+00 +4.570762154055312720e+00,4.906000000000000227e+01,0.000000000000000000e+00,9.465420741982999431e+00,0.000000000000000000e+00,-1.000000009920373856e+00,0.000000000000000000e+00,1.960928653292923149e-10,0.000000000000000000e+00 +4.571818631128291344e+00,4.907000000000000028e+01,0.000000000000000000e+00,9.464364264899540302e+00,0.000000000000000000e+00,-1.000000009920166688e+00,0.000000000000000000e+00,-3.740689622837840991e-10,0.000000000000000000e+00 +4.572875226132468107e+00,4.907999999999999829e+01,0.000000000000000000e+00,9.463307669884882145e+00,0.000000000000000000e+00,-1.000000009920561928e+00,0.000000000000000000e+00,-2.828318051687495195e-10,0.000000000000000000e+00 +4.573931939107342970e+00,4.909000000000000341e+01,0.000000000000000000e+00,9.462250956899524112e+00,0.000000000000000000e+00,-1.000000009920860800e+00,0.000000000000000000e+00,4.855507543010073562e-10,0.000000000000000000e+00 +4.574988770092438095e+00,4.910000000000000142e+01,0.000000000000000000e+00,9.461194125903944041e+00,0.000000000000000000e+00,-1.000000009920347654e+00,0.000000000000000000e+00,3.552464826062877809e-10,0.000000000000000000e+00 +4.576045719127298739e+00,4.910999999999999943e+01,0.000000000000000000e+00,9.460137176858598451e+00,0.000000000000000000e+00,-1.000000009919972177e+00,0.000000000000000000e+00,-6.568489963506971543e-10,0.000000000000000000e+00 +4.577102786251490585e+00,4.912000000000000455e+01,0.000000000000000000e+00,9.459080109723920771e+00,0.000000000000000000e+00,-1.000000009920666511e+00,0.000000000000000000e+00,6.431234055520517773e-10,0.000000000000000000e+00 +4.578159971504602410e+00,4.913000000000000256e+01,0.000000000000000000e+00,9.458022924460321335e+00,0.000000000000000000e+00,-1.000000009919986610e+00,0.000000000000000000e+00,-2.086242284073698923e-09,0.000000000000000000e+00 +4.579217274926244308e+00,4.914000000000000057e+01,0.000000000000000000e+00,9.456965621028190938e+00,0.000000000000000000e+00,-1.000000009922192401e+00,0.000000000000000000e+00,2.293686029519535515e-09,0.000000000000000000e+00 +4.580274696556049463e+00,4.914999999999999858e+01,0.000000000000000000e+00,9.455908199387893731e+00,0.000000000000000000e+00,-1.000000009919767008e+00,0.000000000000000000e+00,-5.013924560012991736e-10,0.000000000000000000e+00 +4.581332236433673266e+00,4.916000000000000369e+01,0.000000000000000000e+00,9.454850659499779653e+00,0.000000000000000000e+00,-1.000000009920297250e+00,0.000000000000000000e+00,-9.231055553242779401e-10,0.000000000000000000e+00 +4.582389894598792424e+00,4.917000000000000171e+01,0.000000000000000000e+00,9.453793001324168443e+00,0.000000000000000000e+00,-1.000000009921273580e+00,0.000000000000000000e+00,1.042654625695352775e-09,0.000000000000000000e+00 +4.583447671091105846e+00,4.917999999999999972e+01,0.000000000000000000e+00,9.452735224821360305e+00,0.000000000000000000e+00,-1.000000009920170685e+00,0.000000000000000000e+00,-9.399003428167694944e-10,0.000000000000000000e+00 +4.584505565950335537e+00,4.918999999999999773e+01,0.000000000000000000e+00,9.451677329951635897e+00,0.000000000000000000e+00,-1.000000009921165001e+00,0.000000000000000000e+00,-5.036865500659165560e-10,0.000000000000000000e+00 +4.585563579216225705e+00,4.920000000000000284e+01,0.000000000000000000e+00,9.450619316675249237e+00,0.000000000000000000e+00,-1.000000009921697908e+00,0.000000000000000000e+00,7.772692256261563947e-10,0.000000000000000000e+00 +4.586621710928541873e+00,4.921000000000000085e+01,0.000000000000000000e+00,9.449561184952434800e+00,0.000000000000000000e+00,-1.000000009920875454e+00,0.000000000000000000e+00,-2.536752912753457808e-10,0.000000000000000000e+00 +4.587679961127071770e+00,4.921999999999999886e+01,0.000000000000000000e+00,9.448502934743405746e+00,0.000000000000000000e+00,-1.000000009921143906e+00,0.000000000000000000e+00,-4.076392823783345112e-10,0.000000000000000000e+00 +4.588738329851627107e+00,4.923000000000000398e+01,0.000000000000000000e+00,9.447444566008350364e+00,0.000000000000000000e+00,-1.000000009921575339e+00,0.000000000000000000e+00,1.915669040659390052e-09,0.000000000000000000e+00 +4.589796817142040020e+00,4.924000000000000199e+01,0.000000000000000000e+00,9.446386078707435630e+00,0.000000000000000000e+00,-1.000000009919547628e+00,0.000000000000000000e+00,-2.780471272319967497e-09,0.000000000000000000e+00 +4.590855423038165739e+00,4.925000000000000000e+01,0.000000000000000000e+00,9.445327472800808977e+00,0.000000000000000000e+00,-1.000000009922491051e+00,0.000000000000000000e+00,1.372252925836107953e-09,0.000000000000000000e+00 +4.591914147579881700e+00,4.925999999999999801e+01,0.000000000000000000e+00,9.444268748248587642e+00,0.000000000000000000e+00,-1.000000009921038213e+00,0.000000000000000000e+00,1.228870668884257124e-10,0.000000000000000000e+00 +4.592972990807088429e+00,4.927000000000000313e+01,0.000000000000000000e+00,9.443209905010876426e+00,0.000000000000000000e+00,-1.000000009920908095e+00,0.000000000000000000e+00,-1.717290512504889392e-10,0.000000000000000000e+00 +4.594031952759706883e+00,4.928000000000000114e+01,0.000000000000000000e+00,9.442150943047751710e+00,0.000000000000000000e+00,-1.000000009921089950e+00,0.000000000000000000e+00,-1.081205623105702096e-09,0.000000000000000000e+00 +4.595091033477682885e+00,4.928999999999999915e+01,0.000000000000000000e+00,9.441091862319268557e+00,0.000000000000000000e+00,-1.000000009922235034e+00,0.000000000000000000e+00,5.777522720807204861e-10,0.000000000000000000e+00 +4.596150233000982688e+00,4.930000000000000426e+01,0.000000000000000000e+00,9.440032662785458939e+00,0.000000000000000000e+00,-1.000000009921623079e+00,0.000000000000000000e+00,1.652362191089946016e-09,0.000000000000000000e+00 +4.597209551369596525e+00,4.931000000000000227e+01,0.000000000000000000e+00,9.438973344406335286e+00,0.000000000000000000e+00,-1.000000009919872701e+00,0.000000000000000000e+00,-2.588193700027692636e-09,0.000000000000000000e+00 +4.598268988623535058e+00,4.932000000000000028e+01,0.000000000000000000e+00,9.437913907141886938e+00,0.000000000000000000e+00,-1.000000009922614730e+00,0.000000000000000000e+00,5.333398365986696669e-10,0.000000000000000000e+00 +4.599328544802833818e+00,4.932999999999999829e+01,0.000000000000000000e+00,9.436854350952074810e+00,0.000000000000000000e+00,-1.000000009922049626e+00,0.000000000000000000e+00,1.535511022416376135e-09,0.000000000000000000e+00 +4.600388219947548762e+00,4.934000000000000341e+01,0.000000000000000000e+00,9.435794675796845610e+00,0.000000000000000000e+00,-1.000000009920422483e+00,0.000000000000000000e+00,-1.145427963424457896e-09,0.000000000000000000e+00 +4.601448014097759831e+00,4.935000000000000142e+01,0.000000000000000000e+00,9.434734881636121173e+00,0.000000000000000000e+00,-1.000000009921636401e+00,0.000000000000000000e+00,-1.166039139714728498e-09,0.000000000000000000e+00 +4.602507927293568279e+00,4.935999999999999943e+01,0.000000000000000000e+00,9.433674968429796692e+00,0.000000000000000000e+00,-1.000000009922872302e+00,0.000000000000000000e+00,1.486815668936596235e-09,0.000000000000000000e+00 +4.603567959575098456e+00,4.937000000000000455e+01,0.000000000000000000e+00,9.432614936137747819e+00,0.000000000000000000e+00,-1.000000009921296229e+00,0.000000000000000000e+00,-1.075296409294850171e-09,0.000000000000000000e+00 +4.604628110982497802e+00,4.938000000000000256e+01,0.000000000000000000e+00,9.431554784719830664e+00,0.000000000000000000e+00,-1.000000009922436206e+00,0.000000000000000000e+00,6.485817476037894809e-10,0.000000000000000000e+00 +4.605688381555935074e+00,4.939000000000000057e+01,0.000000000000000000e+00,9.430494514135872919e+00,0.000000000000000000e+00,-1.000000009921748534e+00,0.000000000000000000e+00,3.511621948827560527e-10,0.000000000000000000e+00 +4.606748771335602122e+00,4.939999999999999858e+01,0.000000000000000000e+00,9.429434124345684509e+00,0.000000000000000000e+00,-1.000000009921376165e+00,0.000000000000000000e+00,-3.701758795458680287e-10,0.000000000000000000e+00 +4.607809280361714777e+00,4.941000000000000369e+01,0.000000000000000000e+00,9.428373615309050493e+00,0.000000000000000000e+00,-1.000000009921768740e+00,0.000000000000000000e+00,7.976309274033141008e-11,0.000000000000000000e+00 +4.608869908674509297e+00,4.942000000000000171e+01,0.000000000000000000e+00,9.427312986985732834e+00,0.000000000000000000e+00,-1.000000009921684141e+00,0.000000000000000000e+00,-1.441644682328896161e-09,0.000000000000000000e+00 +4.609930656314245923e+00,4.942999999999999972e+01,0.000000000000000000e+00,9.426252239335472183e+00,0.000000000000000000e+00,-1.000000009923213362e+00,0.000000000000000000e+00,1.395854014243985966e-09,0.000000000000000000e+00 +4.610991523321206209e+00,4.943999999999999773e+01,0.000000000000000000e+00,9.425191372317984317e+00,0.000000000000000000e+00,-1.000000009921732547e+00,0.000000000000000000e+00,-8.620296312895131319e-10,0.000000000000000000e+00 +4.612052509735696582e+00,4.945000000000000284e+01,0.000000000000000000e+00,9.424130385892967254e+00,0.000000000000000000e+00,-1.000000009922647148e+00,0.000000000000000000e+00,1.269148137482486448e-09,0.000000000000000000e+00 +4.613113615598043893e+00,4.946000000000000085e+01,0.000000000000000000e+00,9.423069280020090588e+00,0.000000000000000000e+00,-1.000000009921300448e+00,0.000000000000000000e+00,-1.661110072028282190e-09,0.000000000000000000e+00 +4.614174840948599865e+00,4.946999999999999886e+01,0.000000000000000000e+00,9.422008054659006149e+00,0.000000000000000000e+00,-1.000000009923063260e+00,0.000000000000000000e+00,1.405267637880503826e-09,0.000000000000000000e+00 +4.615236185827736648e+00,4.948000000000000398e+01,0.000000000000000000e+00,9.420946709769337346e+00,0.000000000000000000e+00,-1.000000009921571786e+00,0.000000000000000000e+00,-5.560191497126364698e-10,0.000000000000000000e+00 +4.616297650275851261e+00,4.949000000000000199e+01,0.000000000000000000e+00,9.419885245310691602e+00,0.000000000000000000e+00,-1.000000009922161981e+00,0.000000000000000000e+00,3.551595716752577092e-10,0.000000000000000000e+00 +4.617359234333362039e+00,4.950000000000000000e+01,0.000000000000000000e+00,9.418823661242647916e+00,0.000000000000000000e+00,-1.000000009921784949e+00,0.000000000000000000e+00,-2.149958150123297182e-09,0.000000000000000000e+00 +4.618420938040710411e+00,4.950999999999999801e+01,0.000000000000000000e+00,9.417761957524765748e+00,0.000000000000000000e+00,-1.000000009924067568e+00,0.000000000000000000e+00,2.974679699136779352e-09,0.000000000000000000e+00 +4.619482761438360896e+00,4.952000000000000313e+01,0.000000000000000000e+00,9.416700134116577914e+00,0.000000000000000000e+00,-1.000000009920908983e+00,0.000000000000000000e+00,-1.586804850135752576e-09,0.000000000000000000e+00 +4.620544704566800220e+00,4.953000000000000114e+01,0.000000000000000000e+00,9.415638190977603017e+00,0.000000000000000000e+00,-1.000000009922594080e+00,0.000000000000000000e+00,-6.292981903320301844e-11,0.000000000000000000e+00 +4.621606767466539090e+00,4.953999999999999915e+01,0.000000000000000000e+00,9.414576128067325911e+00,0.000000000000000000e+00,-1.000000009922660915e+00,0.000000000000000000e+00,-3.150316946198263940e-10,0.000000000000000000e+00 +4.622668950178109526e+00,4.955000000000000426e+01,0.000000000000000000e+00,9.413513945345215461e+00,0.000000000000000000e+00,-1.000000009922995536e+00,0.000000000000000000e+00,-7.512250625911920901e-10,0.000000000000000000e+00 +4.623731252742068421e+00,4.956000000000000227e+01,0.000000000000000000e+00,9.412451642770715665e+00,0.000000000000000000e+00,-1.000000009923793565e+00,0.000000000000000000e+00,1.791743374412421246e-09,0.000000000000000000e+00 +4.624793675198993093e+00,4.957000000000000028e+01,0.000000000000000000e+00,9.411389220303247427e+00,0.000000000000000000e+00,-1.000000009921889976e+00,0.000000000000000000e+00,-5.393640107343484722e-10,0.000000000000000000e+00 +4.625856217589485730e+00,4.957999999999999829e+01,0.000000000000000000e+00,9.410326677902212111e+00,0.000000000000000000e+00,-1.000000009922463073e+00,0.000000000000000000e+00,-1.431733806999923237e-09,0.000000000000000000e+00 +4.626918879954170727e+00,4.959000000000000341e+01,0.000000000000000000e+00,9.409264015526982661e+00,0.000000000000000000e+00,-1.000000009923984523e+00,0.000000000000000000e+00,2.273550481589939096e-09,0.000000000000000000e+00 +4.627981662333695567e+00,4.960000000000000142e+01,0.000000000000000000e+00,9.408201233136910702e+00,0.000000000000000000e+00,-1.000000009921568234e+00,0.000000000000000000e+00,-1.988348582160284271e-09,0.000000000000000000e+00 +4.629044564768730829e+00,4.960999999999999943e+01,0.000000000000000000e+00,9.407138330691330097e+00,0.000000000000000000e+00,-1.000000009923681654e+00,0.000000000000000000e+00,1.523573866714368520e-09,0.000000000000000000e+00 +4.630107587299969296e+00,4.962000000000000455e+01,0.000000000000000000e+00,9.406075308149542735e+00,0.000000000000000000e+00,-1.000000009922062061e+00,0.000000000000000000e+00,-1.324361143617030941e-09,0.000000000000000000e+00 +4.631170729968126842e+00,4.963000000000000256e+01,0.000000000000000000e+00,9.405012165470836294e+00,0.000000000000000000e+00,-1.000000009923470046e+00,0.000000000000000000e+00,4.876255711744193650e-10,0.000000000000000000e+00 +4.632233992813943324e+00,4.964000000000000057e+01,0.000000000000000000e+00,9.403948902614468253e+00,0.000000000000000000e+00,-1.000000009922951572e+00,0.000000000000000000e+00,-8.834734678711389210e-10,0.000000000000000000e+00 +4.633297375878181690e+00,4.964999999999999858e+01,0.000000000000000000e+00,9.402885519539678327e+00,0.000000000000000000e+00,-1.000000009923891042e+00,0.000000000000000000e+00,8.641652541413408038e-10,0.000000000000000000e+00 +4.634360879201626204e+00,4.966000000000000369e+01,0.000000000000000000e+00,9.401822016205679589e+00,0.000000000000000000e+00,-1.000000009922972000e+00,0.000000000000000000e+00,-5.367280931626262629e-10,0.000000000000000000e+00 +4.635424502825086002e+00,4.967000000000000171e+01,0.000000000000000000e+00,9.400758392571665567e+00,0.000000000000000000e+00,-1.000000009923542876e+00,0.000000000000000000e+00,1.211937288909028366e-09,0.000000000000000000e+00 +4.636488246789392420e+00,4.967999999999999972e+01,0.000000000000000000e+00,9.399694648596803148e+00,0.000000000000000000e+00,-1.000000009922253685e+00,0.000000000000000000e+00,-1.724195841480606539e-09,0.000000000000000000e+00 +4.637552111135399890e+00,4.968999999999999773e+01,0.000000000000000000e+00,9.398630784240239677e+00,0.000000000000000000e+00,-1.000000009924087996e+00,0.000000000000000000e+00,1.659097631161674645e-09,0.000000000000000000e+00 +4.638616095903986825e+00,4.970000000000000284e+01,0.000000000000000000e+00,9.397566799461094078e+00,0.000000000000000000e+00,-1.000000009922322741e+00,0.000000000000000000e+00,-1.176886960085012205e-09,0.000000000000000000e+00 +4.639680201136052951e+00,4.971000000000000085e+01,0.000000000000000000e+00,9.396502694218469287e+00,0.000000000000000000e+00,-1.000000009923575073e+00,0.000000000000000000e+00,-8.007767191655742866e-10,0.000000000000000000e+00 +4.640744426872522865e+00,4.971999999999999886e+01,0.000000000000000000e+00,9.395438468471438043e+00,0.000000000000000000e+00,-1.000000009924427280e+00,0.000000000000000000e+00,1.232530754607480502e-09,0.000000000000000000e+00 +4.641808773154344259e+00,4.973000000000000398e+01,0.000000000000000000e+00,9.394374122179053543e+00,0.000000000000000000e+00,-1.000000009923115440e+00,0.000000000000000000e+00,2.361318142420174504e-10,0.000000000000000000e+00 +4.642873240022487025e+00,4.974000000000000199e+01,0.000000000000000000e+00,9.393309655300347671e+00,0.000000000000000000e+00,-1.000000009922864086e+00,0.000000000000000000e+00,-6.382345217929920956e-10,0.000000000000000000e+00 +4.643937827517945038e+00,4.975000000000000000e+01,0.000000000000000000e+00,9.392245067794325664e+00,0.000000000000000000e+00,-1.000000009923543542e+00,0.000000000000000000e+00,-1.373091452236026886e-09,0.000000000000000000e+00 +4.645002535681735267e+00,4.975999999999999801e+01,0.000000000000000000e+00,9.391180359619969664e+00,0.000000000000000000e+00,-1.000000009925005484e+00,0.000000000000000000e+00,1.180466214019319018e-09,0.000000000000000000e+00 +4.646067364554897772e+00,4.977000000000000313e+01,0.000000000000000000e+00,9.390115530736238725e+00,0.000000000000000000e+00,-1.000000009923748490e+00,0.000000000000000000e+00,7.706250526951205224e-10,0.000000000000000000e+00 +4.647132314178495704e+00,4.978000000000000114e+01,0.000000000000000000e+00,9.389050581102072357e+00,0.000000000000000000e+00,-1.000000009922927813e+00,0.000000000000000000e+00,-1.017168078325459127e-09,0.000000000000000000e+00 +4.648197384593616199e+00,4.978999999999999915e+01,0.000000000000000000e+00,9.387985510676383427e+00,0.000000000000000000e+00,-1.000000009924011168e+00,0.000000000000000000e+00,5.305183653419342349e-10,0.000000000000000000e+00 +4.649262575841368594e+00,4.980000000000000426e+01,0.000000000000000000e+00,9.386920319418059933e+00,0.000000000000000000e+00,-1.000000009923446065e+00,0.000000000000000000e+00,-8.331007110110361929e-10,0.000000000000000000e+00 +4.650327887962886209e+00,4.981000000000000227e+01,0.000000000000000000e+00,9.385855007285970331e+00,0.000000000000000000e+00,-1.000000009924333577e+00,0.000000000000000000e+00,1.169376427820480589e-09,0.000000000000000000e+00 +4.651393320999326342e+00,4.982000000000000028e+01,0.000000000000000000e+00,9.384789574238956433e+00,0.000000000000000000e+00,-1.000000009923087685e+00,0.000000000000000000e+00,-1.269684865597708058e-09,0.000000000000000000e+00 +4.652458874991868498e+00,4.982999999999999829e+01,0.000000000000000000e+00,9.383724020235840513e+00,0.000000000000000000e+00,-1.000000009924440603e+00,0.000000000000000000e+00,-3.104571886270202608e-10,0.000000000000000000e+00 +4.653524549981716163e+00,4.984000000000000341e+01,0.000000000000000000e+00,9.382658345235416419e+00,0.000000000000000000e+00,-1.000000009924771449e+00,0.000000000000000000e+00,9.327241515060025983e-10,0.000000000000000000e+00 +4.654590346010095914e+00,4.985000000000000142e+01,0.000000000000000000e+00,9.381592549196458464e+00,0.000000000000000000e+00,-1.000000009923777355e+00,0.000000000000000000e+00,9.136617000921203655e-10,0.000000000000000000e+00 +4.655656263118258309e+00,4.985999999999999943e+01,0.000000000000000000e+00,9.380526632077717863e+00,0.000000000000000000e+00,-1.000000009922803468e+00,0.000000000000000000e+00,-1.913972518744747853e-09,0.000000000000000000e+00 +4.656722301347477000e+00,4.987000000000000455e+01,0.000000000000000000e+00,9.379460593837920968e+00,0.000000000000000000e+00,-1.000000009924843836e+00,0.000000000000000000e+00,2.819919774145539435e-10,0.000000000000000000e+00 +4.657788460739048730e+00,4.988000000000000256e+01,0.000000000000000000e+00,9.378394434435767479e+00,0.000000000000000000e+00,-1.000000009924543187e+00,0.000000000000000000e+00,1.265071296367932087e-09,0.000000000000000000e+00 +4.658854741334294225e+00,4.989000000000000057e+01,0.000000000000000000e+00,9.377328153829939339e+00,0.000000000000000000e+00,-1.000000009923194266e+00,0.000000000000000000e+00,-2.071774199543694363e-09,0.000000000000000000e+00 +4.659921143174558189e+00,4.989999999999999858e+01,0.000000000000000000e+00,9.376261751979093617e+00,0.000000000000000000e+00,-1.000000009925403610e+00,0.000000000000000000e+00,1.222936452796590142e-09,0.000000000000000000e+00 +4.660987666301207533e+00,4.991000000000000369e+01,0.000000000000000000e+00,9.375195228841858963e+00,0.000000000000000000e+00,-1.000000009924099320e+00,0.000000000000000000e+00,2.314863210999750482e-10,0.000000000000000000e+00 +4.662054310755633146e+00,4.992000000000000171e+01,0.000000000000000000e+00,9.374128584376848039e+00,0.000000000000000000e+00,-1.000000009923852407e+00,0.000000000000000000e+00,-3.434433218756760435e-10,0.000000000000000000e+00 +4.663121076579249902e+00,4.992999999999999972e+01,0.000000000000000000e+00,9.373061818542645085e+00,0.000000000000000000e+00,-1.000000009924218780e+00,0.000000000000000000e+00,-4.859690282698520208e-10,0.000000000000000000e+00 +4.664187963813495763e+00,4.993999999999999773e+01,0.000000000000000000e+00,9.371994931297811249e+00,0.000000000000000000e+00,-1.000000009924737254e+00,0.000000000000000000e+00,-1.791741785128179182e-10,0.000000000000000000e+00 +4.665254972499832675e+00,4.995000000000000284e+01,0.000000000000000000e+00,9.370927922600884585e+00,0.000000000000000000e+00,-1.000000009924928435e+00,0.000000000000000000e+00,5.919773546869569729e-10,0.000000000000000000e+00 +4.666322102679745676e+00,4.996000000000000085e+01,0.000000000000000000e+00,9.369860792410380057e+00,0.000000000000000000e+00,-1.000000009924296718e+00,0.000000000000000000e+00,2.850322041859025898e-10,0.000000000000000000e+00 +4.667389354394744672e+00,4.996999999999999886e+01,0.000000000000000000e+00,9.368793540684789534e+00,0.000000000000000000e+00,-1.000000009923992517e+00,0.000000000000000000e+00,-1.082374918408190228e-09,0.000000000000000000e+00 +4.668456727686361774e+00,4.998000000000000398e+01,0.000000000000000000e+00,9.367726167382580016e+00,0.000000000000000000e+00,-1.000000009925147815e+00,0.000000000000000000e+00,-3.764896031147039663e-10,0.000000000000000000e+00 +4.669524222596153074e+00,4.999000000000000199e+01,0.000000000000000000e+00,9.366658672462193636e+00,0.000000000000000000e+00,-1.000000009925549715e+00,0.000000000000000000e+00,8.602119076895593336e-10,0.000000000000000000e+00 +4.670591839165698644e+00,5.000000000000000000e+01,0.000000000000000000e+00,9.365591055882051208e+00,0.000000000000000000e+00,-1.000000009924631339e+00,0.000000000000000000e+00,1.085332262299419364e-09,0.000000000000000000e+00 +4.671659577436602540e+00,5.000999999999999801e+01,0.000000000000000000e+00,9.364523317600550456e+00,0.000000000000000000e+00,-1.000000009923472488e+00,0.000000000000000000e+00,-1.240951234203537527e-09,0.000000000000000000e+00 +4.672727437450491905e+00,5.002000000000000313e+01,0.000000000000000000e+00,9.363455457576064234e+00,0.000000000000000000e+00,-1.000000009924797650e+00,0.000000000000000000e+00,-1.427929154532323982e-09,0.000000000000000000e+00 +4.673795419249017868e+00,5.003000000000000114e+01,0.000000000000000000e+00,9.362387475766938749e+00,0.000000000000000000e+00,-1.000000009926322653e+00,0.000000000000000000e+00,2.095082795711782205e-09,0.000000000000000000e+00 +4.674863522873855537e+00,5.003999999999999915e+01,0.000000000000000000e+00,9.361319372131498895e+00,0.000000000000000000e+00,-1.000000009924084887e+00,0.000000000000000000e+00,-1.552736954786799716e-09,0.000000000000000000e+00 +4.675931748366703111e+00,5.005000000000000426e+01,0.000000000000000000e+00,9.360251146628050023e+00,0.000000000000000000e+00,-1.000000009925743560e+00,0.000000000000000000e+00,1.655855916497765191e-09,0.000000000000000000e+00 +4.677000095769283661e+00,5.006000000000000227e+01,0.000000000000000000e+00,9.359182799214865511e+00,0.000000000000000000e+00,-1.000000009923974531e+00,0.000000000000000000e+00,-7.144700489836332865e-10,0.000000000000000000e+00 +4.678068565123343348e+00,5.007000000000000028e+01,0.000000000000000000e+00,9.358114329850202751e+00,0.000000000000000000e+00,-1.000000009924737920e+00,0.000000000000000000e+00,-8.650375961131471676e-10,0.000000000000000000e+00 +4.679137156470651426e+00,5.007999999999999829e+01,0.000000000000000000e+00,9.357045738492288933e+00,0.000000000000000000e+00,-1.000000009925662292e+00,0.000000000000000000e+00,-3.357533343218652072e-10,0.000000000000000000e+00 +4.680205869853002909e+00,5.009000000000000341e+01,0.000000000000000000e+00,9.355977025099329936e+00,0.000000000000000000e+00,-1.000000009926021116e+00,0.000000000000000000e+00,8.887306382682187519e-10,0.000000000000000000e+00 +4.681274705312215012e+00,5.010000000000000142e+01,0.000000000000000000e+00,9.354908189629508541e+00,0.000000000000000000e+00,-1.000000009925071209e+00,0.000000000000000000e+00,-2.833310202155969620e-10,0.000000000000000000e+00 +4.682343662890129821e+00,5.010999999999999943e+01,0.000000000000000000e+00,9.353839232040984442e+00,0.000000000000000000e+00,-1.000000009925374078e+00,0.000000000000000000e+00,8.278800573727842093e-10,0.000000000000000000e+00 +4.683412742628612513e+00,5.012000000000000455e+01,0.000000000000000000e+00,9.352770152291890682e+00,0.000000000000000000e+00,-1.000000009924489008e+00,0.000000000000000000e+00,-4.228226664363685544e-10,0.000000000000000000e+00 +4.684481944569553136e+00,5.013000000000000256e+01,0.000000000000000000e+00,9.351700950340338991e+00,0.000000000000000000e+00,-1.000000009924941091e+00,0.000000000000000000e+00,-9.105429447596154503e-10,0.000000000000000000e+00 +4.685551268754864829e+00,5.014000000000000057e+01,0.000000000000000000e+00,9.350631626144414454e+00,0.000000000000000000e+00,-1.000000009925914757e+00,0.000000000000000000e+00,9.336929101604648144e-10,0.000000000000000000e+00 +4.686620715226484712e+00,5.014999999999999858e+01,0.000000000000000000e+00,9.349562179662179062e+00,0.000000000000000000e+00,-1.000000009924916222e+00,0.000000000000000000e+00,-1.085550774547828417e-09,0.000000000000000000e+00 +4.687690284026374776e+00,5.016000000000000369e+01,0.000000000000000000e+00,9.348492610851673490e+00,0.000000000000000000e+00,-1.000000009926077293e+00,0.000000000000000000e+00,8.134991023462425473e-10,0.000000000000000000e+00 +4.688759975196520102e+00,5.017000000000000171e+01,0.000000000000000000e+00,9.347422919670909991e+00,0.000000000000000000e+00,-1.000000009925207101e+00,0.000000000000000000e+00,4.356568596628304754e-10,0.000000000000000000e+00 +4.689829788778930642e+00,5.017999999999999972e+01,0.000000000000000000e+00,9.346353106077881279e+00,0.000000000000000000e+00,-1.000000009924741029e+00,0.000000000000000000e+00,-2.199618189176343489e-09,0.000000000000000000e+00 +4.690899724815639438e+00,5.018999999999999773e+01,0.000000000000000000e+00,9.345283170030553421e+00,0.000000000000000000e+00,-1.000000009927094480e+00,0.000000000000000000e+00,2.234227556113110494e-09,0.000000000000000000e+00 +4.691969783348704404e+00,5.020000000000000284e+01,0.000000000000000000e+00,9.344213111486865841e+00,0.000000000000000000e+00,-1.000000009924703726e+00,0.000000000000000000e+00,-1.761739943476281014e-09,0.000000000000000000e+00 +4.693039964420207433e+00,5.021000000000000085e+01,0.000000000000000000e+00,9.343142930404741975e+00,0.000000000000000000e+00,-1.000000009926589106e+00,0.000000000000000000e+00,1.342262629038663726e-09,0.000000000000000000e+00 +4.694110268072253511e+00,5.021999999999999886e+01,0.000000000000000000e+00,9.342072626742071506e+00,0.000000000000000000e+00,-1.000000009925152478e+00,0.000000000000000000e+00,-8.442632280134582963e-10,0.000000000000000000e+00 +4.695180694346972494e+00,5.023000000000000398e+01,0.000000000000000000e+00,9.341002200456728133e+00,0.000000000000000000e+00,-1.000000009926056199e+00,0.000000000000000000e+00,9.988957793671728683e-10,0.000000000000000000e+00 +4.696251243286519106e+00,5.024000000000000199e+01,0.000000000000000000e+00,9.339931651506555355e+00,0.000000000000000000e+00,-1.000000009924986832e+00,0.000000000000000000e+00,-8.619051237981621684e-10,0.000000000000000000e+00 +4.697321914933071163e+00,5.025000000000000000e+01,0.000000000000000000e+00,9.338860979849377131e+00,0.000000000000000000e+00,-1.000000009925909650e+00,0.000000000000000000e+00,-2.104748352171252469e-10,0.000000000000000000e+00 +4.698392709328830463e+00,5.025999999999999801e+01,0.000000000000000000e+00,9.337790185442988999e+00,0.000000000000000000e+00,-1.000000009926135025e+00,0.000000000000000000e+00,-1.291731896009503120e-10,0.000000000000000000e+00 +4.699463626516024561e+00,5.027000000000000313e+01,0.000000000000000000e+00,9.336719268245165182e+00,0.000000000000000000e+00,-1.000000009926273359e+00,0.000000000000000000e+00,9.472305237204138453e-10,0.000000000000000000e+00 +4.700534666536903217e+00,5.028000000000000114e+01,0.000000000000000000e+00,9.335648228213655031e+00,0.000000000000000000e+00,-1.000000009925258837e+00,0.000000000000000000e+00,-1.608386637268693861e-09,0.000000000000000000e+00 +4.701605829433741945e+00,5.028999999999999915e+01,0.000000000000000000e+00,9.334577065306184807e+00,0.000000000000000000e+00,-1.000000009926981681e+00,0.000000000000000000e+00,1.509541930713730161e-09,0.000000000000000000e+00 +4.702677115248839357e+00,5.030000000000000426e+01,0.000000000000000000e+00,9.333505779480452347e+00,0.000000000000000000e+00,-1.000000009925364530e+00,0.000000000000000000e+00,-5.183208963028953684e-10,0.000000000000000000e+00 +4.703748524024519817e+00,5.031000000000000227e+01,0.000000000000000000e+00,9.332434370694137726e+00,0.000000000000000000e+00,-1.000000009925919864e+00,0.000000000000000000e+00,6.506760446884827283e-11,0.000000000000000000e+00 +4.704820055803130785e+00,5.032000000000000028e+01,0.000000000000000000e+00,9.331362838904890822e+00,0.000000000000000000e+00,-1.000000009925850142e+00,0.000000000000000000e+00,-1.366055606342174474e-09,0.000000000000000000e+00 +4.705891710627044588e+00,5.032999999999999829e+01,0.000000000000000000e+00,9.330291184070340194e+00,0.000000000000000000e+00,-1.000000009927314082e+00,0.000000000000000000e+00,1.392624179071174093e-09,0.000000000000000000e+00 +4.706963488538657536e+00,5.034000000000000341e+01,0.000000000000000000e+00,9.329219406148087756e+00,0.000000000000000000e+00,-1.000000009925821498e+00,0.000000000000000000e+00,-9.214044620297444288e-10,0.000000000000000000e+00 +4.708035389580389918e+00,5.035000000000000142e+01,0.000000000000000000e+00,9.328147505095715886e+00,0.000000000000000000e+00,-1.000000009926809152e+00,0.000000000000000000e+00,9.867505637978444195e-10,0.000000000000000000e+00 +4.709107413794686892e+00,5.035999999999999943e+01,0.000000000000000000e+00,9.327075480870776758e+00,0.000000000000000000e+00,-1.000000009925751332e+00,0.000000000000000000e+00,-5.950059968405195052e-10,0.000000000000000000e+00 +4.710179561224018485e+00,5.037000000000000455e+01,0.000000000000000000e+00,9.326003333430803011e+00,0.000000000000000000e+00,-1.000000009926389266e+00,0.000000000000000000e+00,5.321927025052000635e-10,0.000000000000000000e+00 +4.711251831910878707e+00,5.038000000000000256e+01,0.000000000000000000e+00,9.324931062733298859e+00,0.000000000000000000e+00,-1.000000009925818611e+00,0.000000000000000000e+00,-1.794339179231813595e-09,0.000000000000000000e+00 +4.712324225897785546e+00,5.039000000000000057e+01,0.000000000000000000e+00,9.323858668735747202e+00,0.000000000000000000e+00,-1.000000009927742850e+00,0.000000000000000000e+00,1.709457043203045636e-09,0.000000000000000000e+00 +4.713396743227282748e+00,5.039999999999999858e+01,0.000000000000000000e+00,9.322786151395602516e+00,0.000000000000000000e+00,-1.000000009925909428e+00,0.000000000000000000e+00,2.504789985022499547e-10,0.000000000000000000e+00 +4.714469383941937153e+00,5.041000000000000369e+01,0.000000000000000000e+00,9.321713510670301517e+00,0.000000000000000000e+00,-1.000000009925640754e+00,0.000000000000000000e+00,-1.520708651512208167e-09,0.000000000000000000e+00 +4.715542148084340468e+00,5.042000000000000171e+01,0.000000000000000000e+00,9.320640746517250719e+00,0.000000000000000000e+00,-1.000000009927272115e+00,0.000000000000000000e+00,1.043284347872341001e-09,0.000000000000000000e+00 +4.716615035697108382e+00,5.042999999999999972e+01,0.000000000000000000e+00,9.319567858893831769e+00,0.000000000000000000e+00,-1.000000009926152789e+00,0.000000000000000000e+00,-1.300799547210443355e-09,0.000000000000000000e+00 +4.717688046822882342e+00,5.043999999999999773e+01,0.000000000000000000e+00,9.318494847757406774e+00,0.000000000000000000e+00,-1.000000009927548561e+00,0.000000000000000000e+00,7.225372302326086010e-10,0.000000000000000000e+00 +4.718761181504327773e+00,5.045000000000000284e+01,0.000000000000000000e+00,9.317421713065307642e+00,0.000000000000000000e+00,-1.000000009926773181e+00,0.000000000000000000e+00,9.589273739520387889e-10,0.000000000000000000e+00 +4.719834439784134972e+00,5.046000000000000085e+01,0.000000000000000000e+00,9.316348454774846743e+00,0.000000000000000000e+00,-1.000000009925744004e+00,0.000000000000000000e+00,-2.114361964539262149e-09,0.000000000000000000e+00 +4.720907821705018215e+00,5.046999999999999886e+01,0.000000000000000000e+00,9.315275072843309800e+00,0.000000000000000000e+00,-1.000000009928013522e+00,0.000000000000000000e+00,2.311651186339620842e-09,0.000000000000000000e+00 +4.721981327309715759e+00,5.048000000000000398e+01,0.000000000000000000e+00,9.314201567227954115e+00,0.000000000000000000e+00,-1.000000009925531952e+00,0.000000000000000000e+00,-2.703095846793720377e-09,0.000000000000000000e+00 +4.723054956640992508e+00,5.049000000000000199e+01,0.000000000000000000e+00,9.313127937886021002e+00,0.000000000000000000e+00,-1.000000009928434075e+00,0.000000000000000000e+00,2.895101739017842506e-09,0.000000000000000000e+00 +4.724128709741636456e+00,5.050000000000000000e+01,0.000000000000000000e+00,9.312054184774716248e+00,0.000000000000000000e+00,-1.000000009925325450e+00,0.000000000000000000e+00,-2.448973685275562656e-09,0.000000000000000000e+00 +4.725202586654461356e+00,5.050999999999999801e+01,0.000000000000000000e+00,9.310980307851233206e+00,0.000000000000000000e+00,-1.000000009927955347e+00,0.000000000000000000e+00,1.309524694679924706e-09,0.000000000000000000e+00 +4.726276587422304054e+00,5.052000000000000313e+01,0.000000000000000000e+00,9.309906307072727927e+00,0.000000000000000000e+00,-1.000000009926548916e+00,0.000000000000000000e+00,-1.215108664198127705e-09,0.000000000000000000e+00 +4.727350712088027151e+00,5.053000000000000114e+01,0.000000000000000000e+00,9.308832182396342247e+00,0.000000000000000000e+00,-1.000000009927854094e+00,0.000000000000000000e+00,7.740824986129780166e-10,0.000000000000000000e+00 +4.728424960694518120e+00,5.053999999999999915e+01,0.000000000000000000e+00,9.307757933779186033e+00,0.000000000000000000e+00,-1.000000009927022537e+00,0.000000000000000000e+00,-4.036338206929890029e-10,0.000000000000000000e+00 +4.729499333284689300e+00,5.055000000000000426e+01,0.000000000000000000e+00,9.306683561178349606e+00,0.000000000000000000e+00,-1.000000009927456190e+00,0.000000000000000000e+00,1.425884223407849731e-09,0.000000000000000000e+00 +4.730573829901477012e+00,5.056000000000000227e+01,0.000000000000000000e+00,9.305609064550894871e+00,0.000000000000000000e+00,-1.000000009925924083e+00,0.000000000000000000e+00,-1.413322037214295812e-09,0.000000000000000000e+00 +4.731648450587842447e+00,5.057000000000000028e+01,0.000000000000000000e+00,9.304534443853862413e+00,0.000000000000000000e+00,-1.000000009927442868e+00,0.000000000000000000e+00,3.264314245863065217e-10,0.000000000000000000e+00 +4.732723195386772552e+00,5.057999999999999829e+01,0.000000000000000000e+00,9.303459699044262621e+00,0.000000000000000000e+00,-1.000000009927092037e+00,0.000000000000000000e+00,-1.027933637375172353e-09,0.000000000000000000e+00 +4.733798064341278256e+00,5.059000000000000341e+01,0.000000000000000000e+00,9.302384830079086342e+00,0.000000000000000000e+00,-1.000000009928196931e+00,0.000000000000000000e+00,6.917508076561519959e-10,0.000000000000000000e+00 +4.734873057494396242e+00,5.060000000000000142e+01,0.000000000000000000e+00,9.301309836915296003e+00,0.000000000000000000e+00,-1.000000009927453304e+00,0.000000000000000000e+00,8.893206206507744797e-10,0.000000000000000000e+00 +4.735948174889186291e+00,5.060999999999999943e+01,0.000000000000000000e+00,9.300234719509832715e+00,0.000000000000000000e+00,-1.000000009926497180e+00,0.000000000000000000e+00,-1.951281755389020528e-09,0.000000000000000000e+00 +4.737023416568734824e+00,5.062000000000000455e+01,0.000000000000000000e+00,9.299159477819610942e+00,0.000000000000000000e+00,-1.000000009928595279e+00,0.000000000000000000e+00,1.404496136461852213e-09,0.000000000000000000e+00 +4.738098782576152246e+00,5.063000000000000256e+01,0.000000000000000000e+00,9.298084111801516727e+00,0.000000000000000000e+00,-1.000000009927084932e+00,0.000000000000000000e+00,2.198787725020382312e-10,0.000000000000000000e+00 +4.739174272954573830e+00,5.064000000000000057e+01,0.000000000000000000e+00,9.297008621412418350e+00,0.000000000000000000e+00,-1.000000009926848454e+00,0.000000000000000000e+00,-8.773490076886055020e-10,0.000000000000000000e+00 +4.740249887747160606e+00,5.064999999999999858e+01,0.000000000000000000e+00,9.295933006609153892e+00,0.000000000000000000e+00,-1.000000009927792144e+00,0.000000000000000000e+00,-3.362438076363341228e-10,0.000000000000000000e+00 +4.741325626997098475e+00,5.066000000000000369e+01,0.000000000000000000e+00,9.294857267348536567e+00,0.000000000000000000e+00,-1.000000009928153855e+00,0.000000000000000000e+00,3.262983070335242719e-10,0.000000000000000000e+00 +4.742401490747597315e+00,5.067000000000000171e+01,0.000000000000000000e+00,9.293781403587356493e+00,0.000000000000000000e+00,-1.000000009927802802e+00,0.000000000000000000e+00,1.126125084724454188e-09,0.000000000000000000e+00 +4.743477479041892764e+00,5.067999999999999972e+01,0.000000000000000000e+00,9.292705415282378922e+00,0.000000000000000000e+00,-1.000000009926591105e+00,0.000000000000000000e+00,-9.858901800323495550e-10,0.000000000000000000e+00 +4.744553591923245328e+00,5.068999999999999773e+01,0.000000000000000000e+00,9.291629302390344236e+00,0.000000000000000000e+00,-1.000000009927652034e+00,0.000000000000000000e+00,1.442146154133816698e-10,0.000000000000000000e+00 +4.745629829434940383e+00,5.070000000000000284e+01,0.000000000000000000e+00,9.290553064867964395e+00,0.000000000000000000e+00,-1.000000009927496825e+00,0.000000000000000000e+00,-1.602267777452525587e-09,0.000000000000000000e+00 +4.746706191620289061e+00,5.071000000000000085e+01,0.000000000000000000e+00,9.289476702671930042e+00,0.000000000000000000e+00,-1.000000009929221445e+00,0.000000000000000000e+00,1.459551083285028320e-09,0.000000000000000000e+00 +4.747782678522627364e+00,5.071999999999999886e+01,0.000000000000000000e+00,9.288400215758903400e+00,0.000000000000000000e+00,-1.000000009927650257e+00,0.000000000000000000e+00,1.480831314218920447e-10,0.000000000000000000e+00 +4.748859290185315274e+00,5.073000000000000398e+01,0.000000000000000000e+00,9.287323604085527151e+00,0.000000000000000000e+00,-1.000000009927490829e+00,0.000000000000000000e+00,-9.193288047940234664e-10,0.000000000000000000e+00 +4.749936026651739418e+00,5.074000000000000199e+01,0.000000000000000000e+00,9.286246867608413780e+00,0.000000000000000000e+00,-1.000000009928480704e+00,0.000000000000000000e+00,1.338831288308504751e-09,0.000000000000000000e+00 +4.751012887965310405e+00,5.075000000000000000e+01,0.000000000000000000e+00,9.285170006284150901e+00,0.000000000000000000e+00,-1.000000009927038969e+00,0.000000000000000000e+00,-7.197471172823538425e-10,0.000000000000000000e+00 +4.752089874169465489e+00,5.075999999999999801e+01,0.000000000000000000e+00,9.284093020069304814e+00,0.000000000000000000e+00,-1.000000009927814126e+00,0.000000000000000000e+00,-9.501374071851792666e-10,0.000000000000000000e+00 +4.753166985307665016e+00,5.077000000000000313e+01,0.000000000000000000e+00,9.283015908920411619e+00,0.000000000000000000e+00,-1.000000009928837530e+00,0.000000000000000000e+00,6.645449366429059358e-10,0.000000000000000000e+00 +4.754244221423396866e+00,5.078000000000000114e+01,0.000000000000000000e+00,9.281938672793984324e+00,0.000000000000000000e+00,-1.000000009928121658e+00,0.000000000000000000e+00,-4.517721656941289312e-10,0.000000000000000000e+00 +4.755321582560172011e+00,5.078999999999999915e+01,0.000000000000000000e+00,9.280861311646512846e+00,0.000000000000000000e+00,-1.000000009928608380e+00,0.000000000000000000e+00,3.126180783079082547e-10,0.000000000000000000e+00 +4.756399068761528071e+00,5.080000000000000426e+01,0.000000000000000000e+00,9.279783825434458677e+00,0.000000000000000000e+00,-1.000000009928271538e+00,0.000000000000000000e+00,1.442162100722472119e-09,0.000000000000000000e+00 +4.757476680071027531e+00,5.081000000000000227e+01,0.000000000000000000e+00,9.278706214114260220e+00,0.000000000000000000e+00,-1.000000009926717448e+00,0.000000000000000000e+00,-1.631953059844072441e-09,0.000000000000000000e+00 +4.758554416532258635e+00,5.082000000000000028e+01,0.000000000000000000e+00,9.277628477642331006e+00,0.000000000000000000e+00,-1.000000009928476263e+00,0.000000000000000000e+00,2.842865342943849308e-10,0.000000000000000000e+00 +4.759632278188833610e+00,5.082999999999999829e+01,0.000000000000000000e+00,9.276550615975054370e+00,0.000000000000000000e+00,-1.000000009928169842e+00,0.000000000000000000e+00,-4.381211651289560636e-10,0.000000000000000000e+00 +4.760710265084391324e+00,5.084000000000000341e+01,0.000000000000000000e+00,9.275472629068794106e+00,0.000000000000000000e+00,-1.000000009928642131e+00,0.000000000000000000e+00,-7.231145549160386059e-10,0.000000000000000000e+00 +4.761788377262595517e+00,5.085000000000000142e+01,0.000000000000000000e+00,9.274394516879885586e+00,0.000000000000000000e+00,-1.000000009929421729e+00,0.000000000000000000e+00,9.748864747229774655e-10,0.000000000000000000e+00 +4.762866614767135687e+00,5.085999999999999943e+01,0.000000000000000000e+00,9.273316279364639314e+00,0.000000000000000000e+00,-1.000000009928370570e+00,0.000000000000000000e+00,8.915859048752336618e-11,0.000000000000000000e+00 +4.763944977641726197e+00,5.087000000000000455e+01,0.000000000000000000e+00,9.272237916479342701e+00,0.000000000000000000e+00,-1.000000009928274425e+00,0.000000000000000000e+00,-3.057392851329293621e-10,0.000000000000000000e+00 +4.765023465930106283e+00,5.088000000000000256e+01,0.000000000000000000e+00,9.271159428180254736e+00,0.000000000000000000e+00,-1.000000009928604161e+00,0.000000000000000000e+00,-1.922742610887064575e-10,0.000000000000000000e+00 +4.766102079676042713e+00,5.089000000000000057e+01,0.000000000000000000e+00,9.270080814423609539e+00,0.000000000000000000e+00,-1.000000009928811551e+00,0.000000000000000000e+00,4.464607636142050080e-10,0.000000000000000000e+00 +4.767180818923325347e+00,5.089999999999999858e+01,0.000000000000000000e+00,9.269002075165616361e+00,0.000000000000000000e+00,-1.000000009928329936e+00,0.000000000000000000e+00,1.018775292395575055e-10,0.000000000000000000e+00 +4.768259683715770691e+00,5.091000000000000369e+01,0.000000000000000000e+00,9.267923210362459585e+00,0.000000000000000000e+00,-1.000000009928220024e+00,0.000000000000000000e+00,3.187675246618992442e-10,0.000000000000000000e+00 +4.769338674097221009e+00,5.092000000000000171e+01,0.000000000000000000e+00,9.266844219970296948e+00,0.000000000000000000e+00,-1.000000009927876077e+00,0.000000000000000000e+00,-1.936457015941705206e-09,0.000000000000000000e+00 +4.770417790111543432e+00,5.092999999999999972e+01,0.000000000000000000e+00,9.265765103945261316e+00,0.000000000000000000e+00,-1.000000009929965739e+00,0.000000000000000000e+00,9.811803321094757281e-10,0.000000000000000000e+00 +4.771497031802630850e+00,5.093999999999999773e+01,0.000000000000000000e+00,9.264685862243457137e+00,0.000000000000000000e+00,-1.000000009928906808e+00,0.000000000000000000e+00,1.461827497653045345e-09,0.000000000000000000e+00 +4.772576399214401910e+00,5.095000000000000284e+01,0.000000000000000000e+00,9.263606494820969317e+00,0.000000000000000000e+00,-1.000000009927328959e+00,0.000000000000000000e+00,-1.998311229760257207e-09,0.000000000000000000e+00 +4.773655892390800126e+00,5.096000000000000085e+01,0.000000000000000000e+00,9.262527001633854340e+00,0.000000000000000000e+00,-1.000000009929486122e+00,0.000000000000000000e+00,-2.348744717798525835e-10,0.000000000000000000e+00 +4.774735511375795660e+00,5.096999999999999886e+01,0.000000000000000000e+00,9.261447382638138492e+00,0.000000000000000000e+00,-1.000000009929739697e+00,0.000000000000000000e+00,2.194648162479366909e-09,0.000000000000000000e+00 +4.775815256213384430e+00,5.098000000000000398e+01,0.000000000000000000e+00,9.260367637789828521e+00,0.000000000000000000e+00,-1.000000009927370037e+00,0.000000000000000000e+00,-2.307484106706724615e-09,0.000000000000000000e+00 +4.776895126947586334e+00,5.099000000000000199e+01,0.000000000000000000e+00,9.259287767044906303e+00,0.000000000000000000e+00,-1.000000009929861822e+00,0.000000000000000000e+00,1.510319157221037921e-09,0.000000000000000000e+00 +4.777975123622448805e+00,5.100000000000000000e+01,0.000000000000000000e+00,9.258207770359319966e+00,0.000000000000000000e+00,-1.000000009928230682e+00,0.000000000000000000e+00,-1.565442268509325518e-09,0.000000000000000000e+00 +4.779055246282043257e+00,5.100999999999999801e+01,0.000000000000000000e+00,9.257127647689001648e+00,0.000000000000000000e+00,-1.000000009929921552e+00,0.000000000000000000e+00,6.657749118869000186e-10,0.000000000000000000e+00 +4.780135494970468635e+00,5.102000000000000313e+01,0.000000000000000000e+00,9.256047398989849739e+00,0.000000000000000000e+00,-1.000000009929202349e+00,0.000000000000000000e+00,6.087666458888904612e-10,0.000000000000000000e+00 +4.781215869731847867e+00,5.103000000000000114e+01,0.000000000000000000e+00,9.254967024217743088e+00,0.000000000000000000e+00,-1.000000009928544653e+00,0.000000000000000000e+00,-1.954319737158776828e-10,0.000000000000000000e+00 +4.782296370610331415e+00,5.103999999999999915e+01,0.000000000000000000e+00,9.253886523328532121e+00,0.000000000000000000e+00,-1.000000009928755818e+00,0.000000000000000000e+00,-1.727449827662552129e-09,0.000000000000000000e+00 +4.783376997650093720e+00,5.105000000000000426e+01,0.000000000000000000e+00,9.252805896278040620e+00,0.000000000000000000e+00,-1.000000009930622547e+00,0.000000000000000000e+00,2.113706255822044751e-09,0.000000000000000000e+00 +4.784457750895335870e+00,5.106000000000000227e+01,0.000000000000000000e+00,9.251725143022065723e+00,0.000000000000000000e+00,-1.000000009928338152e+00,0.000000000000000000e+00,-8.211019730066481622e-10,0.000000000000000000e+00 +4.785538630390285597e+00,5.107000000000000028e+01,0.000000000000000000e+00,9.250644263516385024e+00,0.000000000000000000e+00,-1.000000009929225664e+00,0.000000000000000000e+00,1.318703727810070684e-10,0.000000000000000000e+00 +4.786619636179194615e+00,5.107999999999999829e+01,0.000000000000000000e+00,9.249563257716742370e+00,0.000000000000000000e+00,-1.000000009929083111e+00,0.000000000000000000e+00,-1.091192238528139306e-09,0.000000000000000000e+00 +4.787700768306342169e+00,5.109000000000000341e+01,0.000000000000000000e+00,9.248482125578860291e+00,0.000000000000000000e+00,-1.000000009930262834e+00,0.000000000000000000e+00,1.606922875489015897e-09,0.000000000000000000e+00 +4.788782026816032378e+00,5.110000000000000142e+01,0.000000000000000000e+00,9.247400867058432894e+00,0.000000000000000000e+00,-1.000000009928525335e+00,0.000000000000000000e+00,-8.722569085520653490e-10,0.000000000000000000e+00 +4.789863411752596001e+00,5.110999999999999943e+01,0.000000000000000000e+00,9.246319482111132970e+00,0.000000000000000000e+00,-1.000000009929468581e+00,0.000000000000000000e+00,-9.142433622120387577e-10,0.000000000000000000e+00 +4.790944923160388669e+00,5.112000000000000455e+01,0.000000000000000000e+00,9.245237970692601337e+00,0.000000000000000000e+00,-1.000000009930457345e+00,0.000000000000000000e+00,1.497968448663653604e-09,0.000000000000000000e+00 +4.792026561083793545e+00,5.113000000000000256e+01,0.000000000000000000e+00,9.244156332758455719e+00,0.000000000000000000e+00,-1.000000009928837086e+00,0.000000000000000000e+00,-1.209195520519125339e-09,0.000000000000000000e+00 +4.793108325567217776e+00,5.114000000000000057e+01,0.000000000000000000e+00,9.243074568264290747e+00,0.000000000000000000e+00,-1.000000009930145151e+00,0.000000000000000000e+00,1.609267112673513620e-09,0.000000000000000000e+00 +4.794190216655096037e+00,5.114999999999999858e+01,0.000000000000000000e+00,9.241992677165669079e+00,0.000000000000000000e+00,-1.000000009928404099e+00,0.000000000000000000e+00,-2.169927139491484773e-09,0.000000000000000000e+00 +4.795272234391888766e+00,5.116000000000000369e+01,0.000000000000000000e+00,9.240910659418133832e+00,0.000000000000000000e+00,-1.000000009930751999e+00,0.000000000000000000e+00,1.127515948906646523e-09,0.000000000000000000e+00 +4.796354378822082154e+00,5.117000000000000171e+01,0.000000000000000000e+00,9.239828514977194374e+00,0.000000000000000000e+00,-1.000000009929531863e+00,0.000000000000000000e+00,-6.171375449126914214e-10,0.000000000000000000e+00 +4.797436649990188151e+00,5.117999999999999972e+01,0.000000000000000000e+00,9.238746243798342306e+00,0.000000000000000000e+00,-1.000000009930199774e+00,0.000000000000000000e+00,1.714981903114901410e-09,0.000000000000000000e+00 +4.798519047940744464e+00,5.118999999999999773e+01,0.000000000000000000e+00,9.237663845837037258e+00,0.000000000000000000e+00,-1.000000009928343481e+00,0.000000000000000000e+00,-2.471663969990352000e-09,0.000000000000000000e+00 +4.799601572718316334e+00,5.120000000000000284e+01,0.000000000000000000e+00,9.236581321048717541e+00,0.000000000000000000e+00,-1.000000009931019118e+00,0.000000000000000000e+00,2.000890283863105629e-09,0.000000000000000000e+00 +4.800684224367494757e+00,5.121000000000000085e+01,0.000000000000000000e+00,9.235498669388787718e+00,0.000000000000000000e+00,-1.000000009928852851e+00,0.000000000000000000e+00,-1.521613948770923656e-09,0.000000000000000000e+00 +4.801767002932895601e+00,5.121999999999999886e+01,0.000000000000000000e+00,9.234415890812636363e+00,0.000000000000000000e+00,-1.000000009930500422e+00,0.000000000000000000e+00,6.173911659076846155e-10,0.000000000000000000e+00 +4.802849908459161377e+00,5.123000000000000398e+01,0.000000000000000000e+00,9.233332985275616522e+00,0.000000000000000000e+00,-1.000000009929831846e+00,0.000000000000000000e+00,-6.542225773567997287e-10,0.000000000000000000e+00 +4.803932940990962130e+00,5.124000000000000199e+01,0.000000000000000000e+00,9.232249952733061704e+00,0.000000000000000000e+00,-1.000000009930540390e+00,0.000000000000000000e+00,7.408596254072037979e-10,0.000000000000000000e+00 +4.805016100572991888e+00,5.125000000000000000e+01,0.000000000000000000e+00,9.231166793140275217e+00,0.000000000000000000e+00,-1.000000009929737921e+00,0.000000000000000000e+00,2.777385211750765325e-10,0.000000000000000000e+00 +4.806099387249973098e+00,5.125999999999999801e+01,0.000000000000000000e+00,9.230083506452537279e+00,0.000000000000000000e+00,-1.000000009929437050e+00,0.000000000000000000e+00,-5.101181221336484829e-10,0.000000000000000000e+00 +4.807182801066653077e+00,5.127000000000000313e+01,0.000000000000000000e+00,9.229000092625099683e+00,0.000000000000000000e+00,-1.000000009929989719e+00,0.000000000000000000e+00,-9.201131060595877769e-11,0.000000000000000000e+00 +4.808266342067805788e+00,5.128000000000000114e+01,0.000000000000000000e+00,9.227916551613187579e+00,0.000000000000000000e+00,-1.000000009930089417e+00,0.000000000000000000e+00,3.811156898070439579e-11,0.000000000000000000e+00 +4.809350010298230949e+00,5.128999999999999915e+01,0.000000000000000000e+00,9.226832883372001248e+00,0.000000000000000000e+00,-1.000000009930048117e+00,0.000000000000000000e+00,-1.020286694224216317e-10,0.000000000000000000e+00 +4.810433805802755813e+00,5.130000000000000426e+01,0.000000000000000000e+00,9.225749087856714326e+00,0.000000000000000000e+00,-1.000000009930158695e+00,0.000000000000000000e+00,-4.934903497543624375e-10,0.000000000000000000e+00 +4.811517728626232504e+00,5.131000000000000227e+01,0.000000000000000000e+00,9.224665165022473801e+00,0.000000000000000000e+00,-1.000000009930693601e+00,0.000000000000000000e+00,3.940904442224110862e-10,0.000000000000000000e+00 +4.812601778813540676e+00,5.132000000000000028e+01,0.000000000000000000e+00,9.223581114824400018e+00,0.000000000000000000e+00,-1.000000009930266387e+00,0.000000000000000000e+00,-4.444260741458305775e-10,0.000000000000000000e+00 +4.813685956409585742e+00,5.132999999999999829e+01,0.000000000000000000e+00,9.222496937217588453e+00,0.000000000000000000e+00,-1.000000009930748224e+00,0.000000000000000000e+00,1.543021586546056649e-09,0.000000000000000000e+00 +4.814770261459299761e+00,5.134000000000000341e+01,0.000000000000000000e+00,9.221412632157106160e+00,0.000000000000000000e+00,-1.000000009929075118e+00,0.000000000000000000e+00,-1.179192640168142360e-09,0.000000000000000000e+00 +4.815854694007641434e+00,5.135000000000000142e+01,0.000000000000000000e+00,9.220328199597997099e+00,0.000000000000000000e+00,-1.000000009930353873e+00,0.000000000000000000e+00,-1.037788602692707358e-09,0.000000000000000000e+00 +4.816939254099595225e+00,5.135999999999999943e+01,0.000000000000000000e+00,9.219243639495273257e+00,0.000000000000000000e+00,-1.000000009931479417e+00,0.000000000000000000e+00,1.981986062329204868e-09,0.000000000000000000e+00 +4.818023941780172237e+00,5.137000000000000455e+01,0.000000000000000000e+00,9.218158951803923529e+00,0.000000000000000000e+00,-1.000000009929329581e+00,0.000000000000000000e+00,-1.158717518071883580e-09,0.000000000000000000e+00 +4.819108757094410223e+00,5.138000000000000256e+01,0.000000000000000000e+00,9.217074136478913715e+00,0.000000000000000000e+00,-1.000000009930586575e+00,0.000000000000000000e+00,1.262753178067896607e-10,0.000000000000000000e+00 +4.820193700087373578e+00,5.139000000000000057e+01,0.000000000000000000e+00,9.215989193475175867e+00,0.000000000000000000e+00,-1.000000009930449574e+00,0.000000000000000000e+00,-1.825353726077029593e-10,0.000000000000000000e+00 +4.821278770804153346e+00,5.139999999999999858e+01,0.000000000000000000e+00,9.214904122747620718e+00,0.000000000000000000e+00,-1.000000009930647638e+00,0.000000000000000000e+00,-5.567491827117859407e-10,0.000000000000000000e+00 +4.822363969289866326e+00,5.141000000000000369e+01,0.000000000000000000e+00,9.213818924251130582e+00,0.000000000000000000e+00,-1.000000009931251821e+00,0.000000000000000000e+00,5.294734290109276410e-10,0.000000000000000000e+00 +4.823449295589656849e+00,5.142000000000000171e+01,0.000000000000000000e+00,9.212733597940561125e+00,0.000000000000000000e+00,-1.000000009930677169e+00,0.000000000000000000e+00,7.916618255172640802e-11,0.000000000000000000e+00 +4.824534749748695894e+00,5.142999999999999972e+01,0.000000000000000000e+00,9.211648143770743147e+00,0.000000000000000000e+00,-1.000000009930591238e+00,0.000000000000000000e+00,-3.808528790938652988e-10,0.000000000000000000e+00 +4.825620331812179309e+00,5.143999999999999773e+01,0.000000000000000000e+00,9.210562561696479023e+00,0.000000000000000000e+00,-1.000000009931004685e+00,0.000000000000000000e+00,6.744923581541991772e-10,0.000000000000000000e+00 +4.826706041825331361e+00,5.145000000000000284e+01,0.000000000000000000e+00,9.209476851672544484e+00,0.000000000000000000e+00,-1.000000009930272382e+00,0.000000000000000000e+00,-1.255782086009762186e-09,0.000000000000000000e+00 +4.827791879833402966e+00,5.146000000000000085e+01,0.000000000000000000e+00,9.208391013653690393e+00,0.000000000000000000e+00,-1.000000009931635958e+00,0.000000000000000000e+00,1.379132305847499894e-09,0.000000000000000000e+00 +4.828877845881670794e+00,5.146999999999999886e+01,0.000000000000000000e+00,9.207305047594637415e+00,0.000000000000000000e+00,-1.000000009930138267e+00,0.000000000000000000e+00,-4.403707414839274721e-10,0.000000000000000000e+00 +4.829963940015438162e+00,5.148000000000000398e+01,0.000000000000000000e+00,9.206218953450084896e+00,0.000000000000000000e+00,-1.000000009930616551e+00,0.000000000000000000e+00,-6.696770536219193944e-10,0.000000000000000000e+00 +4.831050162280035920e+00,5.149000000000000199e+01,0.000000000000000000e+00,9.205132731174700211e+00,0.000000000000000000e+00,-1.000000009931343969e+00,0.000000000000000000e+00,7.082286959896397341e-10,0.000000000000000000e+00 +4.832136512720821564e+00,5.150000000000000000e+01,0.000000000000000000e+00,9.204046380723125864e+00,0.000000000000000000e+00,-1.000000009930574585e+00,0.000000000000000000e+00,-8.033819459157290052e-10,0.000000000000000000e+00 +4.833222991383178346e+00,5.150999999999999801e+01,0.000000000000000000e+00,9.202959902049979490e+00,0.000000000000000000e+00,-1.000000009931447442e+00,0.000000000000000000e+00,8.339391257609288708e-10,0.000000000000000000e+00 +4.834309598312517942e+00,5.152000000000000313e+01,0.000000000000000000e+00,9.201873295109848527e+00,0.000000000000000000e+00,-1.000000009930541278e+00,0.000000000000000000e+00,-3.794271276950975022e-10,0.000000000000000000e+00 +4.835396333554276893e+00,5.153000000000000114e+01,0.000000000000000000e+00,9.200786559857297320e+00,0.000000000000000000e+00,-1.000000009930953615e+00,0.000000000000000000e+00,8.886984822571273687e-11,0.000000000000000000e+00 +4.836483197153920166e+00,5.153999999999999915e+01,0.000000000000000000e+00,9.199699696246860015e+00,0.000000000000000000e+00,-1.000000009930857026e+00,0.000000000000000000e+00,-7.511168527840550394e-10,0.000000000000000000e+00 +4.837570189156939371e+00,5.155000000000000426e+01,0.000000000000000000e+00,9.198612704233045889e+00,0.000000000000000000e+00,-1.000000009931673484e+00,0.000000000000000000e+00,1.270436445384815943e-10,0.000000000000000000e+00 +4.838657309608852763e+00,5.156000000000000227e+01,0.000000000000000000e+00,9.197525583770335800e+00,0.000000000000000000e+00,-1.000000009931535372e+00,0.000000000000000000e+00,-2.646770171158853035e-10,0.000000000000000000e+00 +4.839744558555204357e+00,5.157000000000000028e+01,0.000000000000000000e+00,9.196438334813185733e+00,0.000000000000000000e+00,-1.000000009931823142e+00,0.000000000000000000e+00,1.097993894167770205e-09,0.000000000000000000e+00 +4.840831936041567474e+00,5.157999999999999829e+01,0.000000000000000000e+00,9.195350957316023255e+00,0.000000000000000000e+00,-1.000000009930629208e+00,0.000000000000000000e+00,-2.727815502140230996e-10,0.000000000000000000e+00 +4.841919442113540306e+00,5.159000000000000341e+01,0.000000000000000000e+00,9.194263451233251061e+00,0.000000000000000000e+00,-1.000000009930925859e+00,0.000000000000000000e+00,1.482155568409768736e-10,0.000000000000000000e+00 +4.843007076816748580e+00,5.160000000000000142e+01,0.000000000000000000e+00,9.193175816519241650e+00,0.000000000000000000e+00,-1.000000009930764655e+00,0.000000000000000000e+00,-6.236156506626296996e-10,0.000000000000000000e+00 +4.844094840196845553e+00,5.160999999999999943e+01,0.000000000000000000e+00,9.192088053128342651e+00,0.000000000000000000e+00,-1.000000009931443001e+00,0.000000000000000000e+00,-1.067471011980930257e-09,0.000000000000000000e+00 +4.845182732299510242e+00,5.162000000000000455e+01,0.000000000000000000e+00,9.191000161014873271e+00,0.000000000000000000e+00,-1.000000009932604295e+00,0.000000000000000000e+00,1.835914474856754756e-09,0.000000000000000000e+00 +4.846270753170450973e+00,5.163000000000000256e+01,0.000000000000000000e+00,9.189912140133126073e+00,0.000000000000000000e+00,-1.000000009930606781e+00,0.000000000000000000e+00,-8.982590946807983005e-10,0.000000000000000000e+00 +4.847358902855400942e+00,5.164000000000000057e+01,0.000000000000000000e+00,9.188823990437370526e+00,0.000000000000000000e+00,-1.000000009931584222e+00,0.000000000000000000e+00,-2.468797839145601618e-10,0.000000000000000000e+00 +4.848447181400120876e+00,5.164999999999999858e+01,0.000000000000000000e+00,9.187735711881842349e+00,0.000000000000000000e+00,-1.000000009931852896e+00,0.000000000000000000e+00,8.068544663618101867e-10,0.000000000000000000e+00 +4.849535588850399037e+00,5.166000000000000369e+01,0.000000000000000000e+00,9.186647304420754168e+00,0.000000000000000000e+00,-1.000000009930974709e+00,0.000000000000000000e+00,-7.168016986133125291e-10,0.000000000000000000e+00 +4.850624125252051222e+00,5.167000000000000171e+01,0.000000000000000000e+00,9.185558768008291963e+00,0.000000000000000000e+00,-1.000000009931754974e+00,0.000000000000000000e+00,-2.998217538457345602e-10,0.000000000000000000e+00 +4.851712790650918983e+00,5.167999999999999972e+01,0.000000000000000000e+00,9.184470102598611518e+00,0.000000000000000000e+00,-1.000000009932081380e+00,0.000000000000000000e+00,5.757119025870033912e-10,0.000000000000000000e+00 +4.852801585092873182e+00,5.168999999999999773e+01,0.000000000000000000e+00,9.183381308145843747e+00,0.000000000000000000e+00,-1.000000009931454548e+00,0.000000000000000000e+00,-1.066255991506328901e-09,0.000000000000000000e+00 +4.853890508623809552e+00,5.170000000000000284e+01,0.000000000000000000e+00,9.182292384604092916e+00,0.000000000000000000e+00,-1.000000009932615619e+00,0.000000000000000000e+00,7.851721045140172843e-10,0.000000000000000000e+00 +4.854979561289652246e+00,5.171000000000000085e+01,0.000000000000000000e+00,9.181203331927433098e+00,0.000000000000000000e+00,-1.000000009931760525e+00,0.000000000000000000e+00,1.573827506595288622e-10,0.000000000000000000e+00 +4.856068743136352950e+00,5.171999999999999886e+01,0.000000000000000000e+00,9.180114150069915269e+00,0.000000000000000000e+00,-1.000000009931589107e+00,0.000000000000000000e+00,6.482095526388305304e-11,0.000000000000000000e+00 +4.857158054209889109e+00,5.173000000000000398e+01,0.000000000000000000e+00,9.179024838985560208e+00,0.000000000000000000e+00,-1.000000009931518496e+00,0.000000000000000000e+00,5.268625360161410278e-10,0.000000000000000000e+00 +4.858247494556267476e+00,5.174000000000000199e+01,0.000000000000000000e+00,9.177935398628362051e+00,0.000000000000000000e+00,-1.000000009930944511e+00,0.000000000000000000e+00,-1.430817340914319300e-09,0.000000000000000000e+00 +4.859337064221520563e+00,5.175000000000000000e+01,0.000000000000000000e+00,9.176845828952288286e+00,0.000000000000000000e+00,-1.000000009932503486e+00,0.000000000000000000e+00,1.968388356925012835e-10,0.000000000000000000e+00 +4.860426763251709303e+00,5.175999999999999801e+01,0.000000000000000000e+00,9.175756129911276204e+00,0.000000000000000000e+00,-1.000000009932288991e+00,0.000000000000000000e+00,9.390501710173876007e-10,0.000000000000000000e+00 +4.861516591692921274e+00,5.177000000000000313e+01,0.000000000000000000e+00,9.174666301459240003e+00,0.000000000000000000e+00,-1.000000009931265588e+00,0.000000000000000000e+00,-6.796049674499654596e-10,0.000000000000000000e+00 +4.862606549591271587e+00,5.178000000000000114e+01,0.000000000000000000e+00,9.173576343550065459e+00,0.000000000000000000e+00,-1.000000009932006328e+00,0.000000000000000000e+00,-1.525670408079937383e-10,0.000000000000000000e+00 +4.863696636992902000e+00,5.178999999999999915e+01,0.000000000000000000e+00,9.172486256137608152e+00,0.000000000000000000e+00,-1.000000009932172640e+00,0.000000000000000000e+00,-4.527586516232840802e-10,0.000000000000000000e+00 +4.864786853943983580e+00,5.180000000000000426e+01,0.000000000000000000e+00,9.171396039175698789e+00,0.000000000000000000e+00,-1.000000009932666245e+00,0.000000000000000000e+00,1.429186933309069119e-09,0.000000000000000000e+00 +4.865877200490712262e+00,5.181000000000000227e+01,0.000000000000000000e+00,9.170305692618139659e+00,0.000000000000000000e+00,-1.000000009931107936e+00,0.000000000000000000e+00,-1.958637040495456597e-09,0.000000000000000000e+00 +4.866967676679314181e+00,5.182000000000000028e+01,0.000000000000000000e+00,9.169215216418708181e+00,0.000000000000000000e+00,-1.000000009933243783e+00,0.000000000000000000e+00,1.354330417138554813e-09,0.000000000000000000e+00 +4.868058282556041227e+00,5.182999999999999829e+01,0.000000000000000000e+00,9.168124610531148022e+00,0.000000000000000000e+00,-1.000000009931766742e+00,0.000000000000000000e+00,-5.622693460668910826e-10,0.000000000000000000e+00 +4.869149018167172827e+00,5.184000000000000341e+01,0.000000000000000000e+00,9.167033874909183311e+00,0.000000000000000000e+00,-1.000000009932380030e+00,0.000000000000000000e+00,-2.212578081201295485e-10,0.000000000000000000e+00 +4.870239883559016825e+00,5.185000000000000142e+01,0.000000000000000000e+00,9.165943009506504424e+00,0.000000000000000000e+00,-1.000000009932621392e+00,0.000000000000000000e+00,9.020219997187344691e-10,0.000000000000000000e+00 +4.871330878777907714e+00,5.185999999999999943e+01,0.000000000000000000e+00,9.164852014276776870e+00,0.000000000000000000e+00,-1.000000009931637290e+00,0.000000000000000000e+00,-1.571024589313390558e-10,0.000000000000000000e+00 +4.872422003870208407e+00,5.187000000000000455e+01,0.000000000000000000e+00,9.163760889173639512e+00,0.000000000000000000e+00,-1.000000009931808709e+00,0.000000000000000000e+00,-3.949476276218451461e-10,0.000000000000000000e+00 +4.873513258882308463e+00,5.188000000000000256e+01,0.000000000000000000e+00,9.162669634150701015e+00,0.000000000000000000e+00,-1.000000009932239697e+00,0.000000000000000000e+00,-1.283376073240530132e-09,0.000000000000000000e+00 +4.874604643860625863e+00,5.189000000000000057e+01,0.000000000000000000e+00,9.161578249161543397e+00,0.000000000000000000e+00,-1.000000009933640355e+00,0.000000000000000000e+00,1.669532794032342266e-09,0.000000000000000000e+00 +4.875696158851606121e+00,5.189999999999999858e+01,0.000000000000000000e+00,9.160486734159720257e+00,0.000000000000000000e+00,-1.000000009931818035e+00,0.000000000000000000e+00,-4.629467433169837034e-10,0.000000000000000000e+00 +4.876787803901722285e+00,5.191000000000000369e+01,0.000000000000000000e+00,9.159395089098762099e+00,0.000000000000000000e+00,-1.000000009932323408e+00,0.000000000000000000e+00,-2.068368766397696999e-10,0.000000000000000000e+00 +4.877879579057474935e+00,5.192000000000000171e+01,0.000000000000000000e+00,9.158303313932165679e+00,0.000000000000000000e+00,-1.000000009932549228e+00,0.000000000000000000e+00,-5.232328887216355964e-10,0.000000000000000000e+00 +4.878971484365392186e+00,5.192999999999999972e+01,0.000000000000000000e+00,9.157211408613402881e+00,0.000000000000000000e+00,-1.000000009933120548e+00,0.000000000000000000e+00,9.637886505948218789e-11,0.000000000000000000e+00 +4.880063519872030575e+00,5.193999999999999773e+01,0.000000000000000000e+00,9.156119373095917169e+00,0.000000000000000000e+00,-1.000000009933015299e+00,0.000000000000000000e+00,1.670367772307469624e-09,0.000000000000000000e+00 +4.881155685623974172e+00,5.195000000000000284e+01,0.000000000000000000e+00,9.155027207333125361e+00,0.000000000000000000e+00,-1.000000009931190981e+00,0.000000000000000000e+00,-1.736641884347786836e-09,0.000000000000000000e+00 +4.882247981667833692e+00,5.196000000000000085e+01,0.000000000000000000e+00,9.153934911278417630e+00,0.000000000000000000e+00,-1.000000009933087908e+00,0.000000000000000000e+00,3.170827702979457407e-10,0.000000000000000000e+00 +4.883340408050250048e+00,5.196999999999999886e+01,0.000000000000000000e+00,9.152842484885150398e+00,0.000000000000000000e+00,-1.000000009932741518e+00,0.000000000000000000e+00,4.060613908407734962e-10,0.000000000000000000e+00 +4.884432964817889911e+00,5.198000000000000398e+01,0.000000000000000000e+00,9.151749928106658771e+00,0.000000000000000000e+00,-1.000000009932297873e+00,0.000000000000000000e+00,-1.447665687056161867e-09,0.000000000000000000e+00 +4.885525652017448373e+00,5.199000000000000199e+01,0.000000000000000000e+00,9.150657240896247657e+00,0.000000000000000000e+00,-1.000000009933879719e+00,0.000000000000000000e+00,7.253719036537287657e-10,0.000000000000000000e+00 +4.886618469695648059e+00,5.200000000000000000e+01,0.000000000000000000e+00,9.149564423207191766e+00,0.000000000000000000e+00,-1.000000009933087020e+00,0.000000000000000000e+00,9.936611443418813449e-10,0.000000000000000000e+00 +4.887711417899240907e+00,5.200999999999999801e+01,0.000000000000000000e+00,9.148471474992742714e+00,0.000000000000000000e+00,-1.000000009932000999e+00,0.000000000000000000e+00,-6.209894220855008342e-10,0.000000000000000000e+00 +4.888804496675005495e+00,5.202000000000000313e+01,0.000000000000000000e+00,9.147378396206121920e+00,0.000000000000000000e+00,-1.000000009932679790e+00,0.000000000000000000e+00,-1.125446928837495101e-09,0.000000000000000000e+00 +4.889897706069747940e+00,5.203000000000000114e+01,0.000000000000000000e+00,9.146285186800520606e+00,0.000000000000000000e+00,-1.000000009933910139e+00,0.000000000000000000e+00,9.847753028767885206e-10,0.000000000000000000e+00 +4.890991046130303666e+00,5.203999999999999915e+01,0.000000000000000000e+00,9.145191846729103347e+00,0.000000000000000000e+00,-1.000000009932833445e+00,0.000000000000000000e+00,-2.148417660183674968e-10,0.000000000000000000e+00 +4.892084516903535629e+00,5.205000000000000426e+01,0.000000000000000000e+00,9.144098375945009849e+00,0.000000000000000000e+00,-1.000000009933068368e+00,0.000000000000000000e+00,1.238136524339964833e-09,0.000000000000000000e+00 +4.893178118436335211e+00,5.206000000000000227e+01,0.000000000000000000e+00,9.143004774401347845e+00,0.000000000000000000e+00,-1.000000009931714340e+00,0.000000000000000000e+00,-2.061825299133792442e-09,0.000000000000000000e+00 +4.894271850775620436e+00,5.207000000000000028e+01,0.000000000000000000e+00,9.141911042051200198e+00,0.000000000000000000e+00,-1.000000009933969425e+00,0.000000000000000000e+00,1.783683696887725426e-09,0.000000000000000000e+00 +4.895365713968338639e+00,5.207999999999999829e+01,0.000000000000000000e+00,9.140817178847616020e+00,0.000000000000000000e+00,-1.000000009932018319e+00,0.000000000000000000e+00,-2.052198466613935764e-09,0.000000000000000000e+00 +4.896459708061463800e+00,5.209000000000000341e+01,0.000000000000000000e+00,9.139723184743624884e+00,0.000000000000000000e+00,-1.000000009934263412e+00,0.000000000000000000e+00,1.293962160218716948e-09,0.000000000000000000e+00 +4.897553833102000098e+00,5.210000000000000142e+01,0.000000000000000000e+00,9.138629059692219059e+00,0.000000000000000000e+00,-1.000000009932847655e+00,0.000000000000000000e+00,-3.145234082629442308e-11,0.000000000000000000e+00 +4.898648089136979245e+00,5.210999999999999943e+01,0.000000000000000000e+00,9.137534803646371273e+00,0.000000000000000000e+00,-1.000000009932882072e+00,0.000000000000000000e+00,-7.283895696617131425e-11,0.000000000000000000e+00 +4.899742476213459597e+00,5.212000000000000455e+01,0.000000000000000000e+00,9.136440416559020505e+00,0.000000000000000000e+00,-1.000000009932961786e+00,0.000000000000000000e+00,-2.935524997029959469e-10,0.000000000000000000e+00 +4.900836994378528821e+00,5.213000000000000256e+01,0.000000000000000000e+00,9.135345898383079088e+00,0.000000000000000000e+00,-1.000000009933283085e+00,0.000000000000000000e+00,-6.742581996338559994e-10,0.000000000000000000e+00 +4.901931643679303896e+00,5.214000000000000057e+01,0.000000000000000000e+00,9.134251249071430934e+00,0.000000000000000000e+00,-1.000000009934021161e+00,0.000000000000000000e+00,2.869918861988745617e-10,0.000000000000000000e+00 +4.903026424162927555e+00,5.214999999999999858e+01,0.000000000000000000e+00,9.133156468576931530e+00,0.000000000000000000e+00,-1.000000009933706968e+00,0.000000000000000000e+00,1.127347477787735833e-09,0.000000000000000000e+00 +4.904121335876572729e+00,5.216000000000000369e+01,0.000000000000000000e+00,9.132061556852409723e+00,0.000000000000000000e+00,-1.000000009932472622e+00,0.000000000000000000e+00,-1.095985362793145392e-09,0.000000000000000000e+00 +4.905216378867439886e+00,5.217000000000000171e+01,0.000000000000000000e+00,9.130966513850665933e+00,0.000000000000000000e+00,-1.000000009933672773e+00,0.000000000000000000e+00,-4.365168427682527129e-10,0.000000000000000000e+00 +4.906311553182757912e+00,5.217999999999999972e+01,0.000000000000000000e+00,9.129871339524468610e+00,0.000000000000000000e+00,-1.000000009934150835e+00,0.000000000000000000e+00,1.642266050294332512e-09,0.000000000000000000e+00 +4.907406858869784116e+00,5.218999999999999773e+01,0.000000000000000000e+00,9.128776033826561331e+00,0.000000000000000000e+00,-1.000000009932352052e+00,0.000000000000000000e+00,-2.242465086115768973e-09,0.000000000000000000e+00 +4.908502295975804230e+00,5.220000000000000284e+01,0.000000000000000000e+00,9.127680596709661032e+00,0.000000000000000000e+00,-1.000000009934808531e+00,0.000000000000000000e+00,1.253748930701758244e-09,0.000000000000000000e+00 +4.909597864548131518e+00,5.221000000000000085e+01,0.000000000000000000e+00,9.126585028126449117e+00,0.000000000000000000e+00,-1.000000009933434963e+00,0.000000000000000000e+00,3.076240611731495348e-10,0.000000000000000000e+00 +4.910693564634109443e+00,5.221999999999999886e+01,0.000000000000000000e+00,9.125489328029587455e+00,0.000000000000000000e+00,-1.000000009933097900e+00,0.000000000000000000e+00,-6.188215364089612969e-10,0.000000000000000000e+00 +4.911789396281108111e+00,5.223000000000000398e+01,0.000000000000000000e+00,9.124393496371704160e+00,0.000000000000000000e+00,-1.000000009933776024e+00,0.000000000000000000e+00,-2.755390394752036881e-11,0.000000000000000000e+00 +4.912885359536526053e+00,5.224000000000000199e+01,0.000000000000000000e+00,9.123297533105398927e+00,0.000000000000000000e+00,-1.000000009933806222e+00,0.000000000000000000e+00,6.219141518800335243e-10,0.000000000000000000e+00 +4.913981454447791997e+00,5.225000000000000000e+01,0.000000000000000000e+00,9.122201438183244804e+00,0.000000000000000000e+00,-1.000000009933124545e+00,0.000000000000000000e+00,-1.290266186365124750e-10,0.000000000000000000e+00 +4.915077681062361314e+00,5.225999999999999801e+01,0.000000000000000000e+00,9.121105211557786419e+00,0.000000000000000000e+00,-1.000000009933265988e+00,0.000000000000000000e+00,-7.809526735462051562e-10,0.000000000000000000e+00 +4.916174039427718689e+00,5.227000000000000313e+01,0.000000000000000000e+00,9.120008853181538200e+00,0.000000000000000000e+00,-1.000000009934122192e+00,0.000000000000000000e+00,1.634214351513008442e-10,0.000000000000000000e+00 +4.917270529591378114e+00,5.228000000000000114e+01,0.000000000000000000e+00,9.118912363006986155e+00,0.000000000000000000e+00,-1.000000009933943002e+00,0.000000000000000000e+00,-2.316377255180411288e-10,0.000000000000000000e+00 +4.918367151600881115e+00,5.228999999999999915e+01,0.000000000000000000e+00,9.117815740986589645e+00,0.000000000000000000e+00,-1.000000009934197021e+00,0.000000000000000000e+00,1.008434229584724960e-09,0.000000000000000000e+00 +4.919463905503797641e+00,5.230000000000000426e+01,0.000000000000000000e+00,9.116718987072777836e+00,0.000000000000000000e+00,-1.000000009933091016e+00,0.000000000000000000e+00,-5.269300445609567807e-10,0.000000000000000000e+00 +4.920560791347726948e+00,5.231000000000000227e+01,0.000000000000000000e+00,9.115622101217953244e+00,0.000000000000000000e+00,-1.000000009933668998e+00,0.000000000000000000e+00,-3.870030841907895746e-10,0.000000000000000000e+00 +4.921657809180296717e+00,5.232000000000000028e+01,0.000000000000000000e+00,9.114525083374486414e+00,0.000000000000000000e+00,-1.000000009934093548e+00,0.000000000000000000e+00,-2.873840192128389424e-11,0.000000000000000000e+00 +4.922754959049163048e+00,5.232999999999999829e+01,0.000000000000000000e+00,9.113427933494721245e+00,0.000000000000000000e+00,-1.000000009934125078e+00,0.000000000000000000e+00,-9.075789959950024822e-10,0.000000000000000000e+00 +4.923852241002010466e+00,5.234000000000000341e+01,0.000000000000000000e+00,9.112330651530973213e+00,0.000000000000000000e+00,-1.000000009935120948e+00,0.000000000000000000e+00,1.421601395660423733e-09,0.000000000000000000e+00 +4.924949655086552802e+00,5.235000000000000142e+01,0.000000000000000000e+00,9.111233237435527599e+00,0.000000000000000000e+00,-1.000000009933560863e+00,0.000000000000000000e+00,-3.953137760681406686e-10,0.000000000000000000e+00 +4.926047201350533200e+00,5.235999999999999943e+01,0.000000000000000000e+00,9.110135691160644811e+00,0.000000000000000000e+00,-1.000000009933994738e+00,0.000000000000000000e+00,-4.385552849414393036e-10,0.000000000000000000e+00 +4.927144879841722336e+00,5.237000000000000455e+01,0.000000000000000000e+00,9.109038012658551509e+00,0.000000000000000000e+00,-1.000000009934476131e+00,0.000000000000000000e+00,1.310248537356219929e-09,0.000000000000000000e+00 +4.928242690607920196e+00,5.238000000000000256e+01,0.000000000000000000e+00,9.107940201881447706e+00,0.000000000000000000e+00,-1.000000009933037726e+00,0.000000000000000000e+00,-1.023723179603394770e-09,0.000000000000000000e+00 +4.929340633696955187e+00,5.239000000000000057e+01,0.000000000000000000e+00,9.106842258781506771e+00,0.000000000000000000e+00,-1.000000009934161715e+00,0.000000000000000000e+00,-5.115976734408270281e-11,0.000000000000000000e+00 +4.930438709156685029e+00,5.239999999999999858e+01,0.000000000000000000e+00,9.105744183310868323e+00,0.000000000000000000e+00,-1.000000009934217893e+00,0.000000000000000000e+00,-1.734774215229767310e-10,0.000000000000000000e+00 +4.931536917034996748e+00,5.241000000000000369e+01,0.000000000000000000e+00,9.104645975421647108e+00,0.000000000000000000e+00,-1.000000009934408407e+00,0.000000000000000000e+00,1.037100047039120110e-10,0.000000000000000000e+00 +4.932635257379804905e+00,5.242000000000000171e+01,0.000000000000000000e+00,9.103547635065927679e+00,0.000000000000000000e+00,-1.000000009934294498e+00,0.000000000000000000e+00,-6.727198027411820111e-10,0.000000000000000000e+00 +4.933733730239054260e+00,5.242999999999999972e+01,0.000000000000000000e+00,9.102449162195766164e+00,0.000000000000000000e+00,-1.000000009935033463e+00,0.000000000000000000e+00,4.622369428095955318e-10,0.000000000000000000e+00 +4.934832335660717106e+00,5.243999999999999773e+01,0.000000000000000000e+00,9.101350556763188493e+00,0.000000000000000000e+00,-1.000000009934525647e+00,0.000000000000000000e+00,5.848501352384054294e-10,0.000000000000000000e+00 +4.935931073692795934e+00,5.245000000000000284e+01,0.000000000000000000e+00,9.100251818720193953e+00,0.000000000000000000e+00,-1.000000009933883049e+00,0.000000000000000000e+00,-2.847112504106686294e-10,0.000000000000000000e+00 +4.937029944383322544e+00,5.246000000000000085e+01,0.000000000000000000e+00,9.099152948018751630e+00,0.000000000000000000e+00,-1.000000009934195910e+00,0.000000000000000000e+00,-6.532010816894168618e-10,0.000000000000000000e+00 +4.938128947780356270e+00,5.246999999999999886e+01,0.000000000000000000e+00,9.098053944610800414e+00,0.000000000000000000e+00,-1.000000009934913781e+00,0.000000000000000000e+00,9.680672819495350735e-10,0.000000000000000000e+00 +4.939228083931985758e+00,5.248000000000000398e+01,0.000000000000000000e+00,9.096954808448250773e+00,0.000000000000000000e+00,-1.000000009933849743e+00,0.000000000000000000e+00,-1.280837445891033359e-09,0.000000000000000000e+00 +4.940327352886329848e+00,5.249000000000000199e+01,0.000000000000000000e+00,9.095855539482986529e+00,0.000000000000000000e+00,-1.000000009935257728e+00,0.000000000000000000e+00,1.440237836815087541e-09,0.000000000000000000e+00 +4.941426754691535805e+00,5.250000000000000000e+01,0.000000000000000000e+00,9.094756137666857754e+00,0.000000000000000000e+00,-1.000000009933674328e+00,0.000000000000000000e+00,-1.136137806734577076e-09,0.000000000000000000e+00 +4.942526289395779315e+00,5.250999999999999801e+01,0.000000000000000000e+00,9.093656602951691426e+00,0.000000000000000000e+00,-1.000000009934923551e+00,0.000000000000000000e+00,-1.728432963893721742e-10,0.000000000000000000e+00 +4.943625957047266262e+00,5.252000000000000313e+01,0.000000000000000000e+00,9.092556935289278996e+00,0.000000000000000000e+00,-1.000000009935113621e+00,0.000000000000000000e+00,-5.713637591246691176e-11,0.000000000000000000e+00 +4.944725757694231838e+00,5.253000000000000114e+01,0.000000000000000000e+00,9.091457134631387049e+00,0.000000000000000000e+00,-1.000000009935176459e+00,0.000000000000000000e+00,6.994826711514468392e-10,0.000000000000000000e+00 +4.945825691384938771e+00,5.253999999999999915e+01,0.000000000000000000e+00,9.090357200929751968e+00,0.000000000000000000e+00,-1.000000009934407075e+00,0.000000000000000000e+00,6.493401175731385959e-10,0.000000000000000000e+00 +4.946925758167680875e+00,5.255000000000000426e+01,0.000000000000000000e+00,9.089257134136081717e+00,0.000000000000000000e+00,-1.000000009933692757e+00,0.000000000000000000e+00,-1.653124419258770089e-09,0.000000000000000000e+00 +4.948025958090779497e+00,5.256000000000000227e+01,0.000000000000000000e+00,9.088156934202054060e+00,0.000000000000000000e+00,-1.000000009935511525e+00,0.000000000000000000e+00,1.149035657362828986e-09,0.000000000000000000e+00 +4.949126291202586181e+00,5.257000000000000028e+01,0.000000000000000000e+00,9.087056601079314788e+00,0.000000000000000000e+00,-1.000000009934247203e+00,0.000000000000000000e+00,-1.195102600175363469e-09,0.000000000000000000e+00 +4.950226757551481782e+00,5.257999999999999829e+01,0.000000000000000000e+00,9.085956134719486599e+00,0.000000000000000000e+00,-1.000000009935562373e+00,0.000000000000000000e+00,1.604507840800552395e-09,0.000000000000000000e+00 +4.951327357185876465e+00,5.259000000000000341e+01,0.000000000000000000e+00,9.084855535074156663e+00,0.000000000000000000e+00,-1.000000009933796452e+00,0.000000000000000000e+00,-2.164501908626841461e-09,0.000000000000000000e+00 +4.952428090154209706e+00,5.260000000000000142e+01,0.000000000000000000e+00,9.083754802094889058e+00,0.000000000000000000e+00,-1.000000009936178991e+00,0.000000000000000000e+00,2.180577344589270490e-09,0.000000000000000000e+00 +4.953528956504949399e+00,5.260999999999999943e+01,0.000000000000000000e+00,9.082653935733210560e+00,0.000000000000000000e+00,-1.000000009933778466e+00,0.000000000000000000e+00,-1.464970327028992419e-09,0.000000000000000000e+00 +4.954629956286594528e+00,5.262000000000000455e+01,0.000000000000000000e+00,9.081552935940628402e+00,0.000000000000000000e+00,-1.000000009935391398e+00,0.000000000000000000e+00,1.113113428239215731e-10,0.000000000000000000e+00 +4.955731089547671608e+00,5.263000000000000256e+01,0.000000000000000000e+00,9.080451802668610739e+00,0.000000000000000000e+00,-1.000000009935268830e+00,0.000000000000000000e+00,-3.982124032802071594e-10,0.000000000000000000e+00 +4.956832356336738243e+00,5.264000000000000057e+01,0.000000000000000000e+00,9.079350535868602634e+00,0.000000000000000000e+00,-1.000000009935707368e+00,0.000000000000000000e+00,1.422101074233619656e-09,0.000000000000000000e+00 +4.957933756702380457e+00,5.264999999999999858e+01,0.000000000000000000e+00,9.078249135492017174e+00,0.000000000000000000e+00,-1.000000009934141065e+00,0.000000000000000000e+00,-1.728729705740662188e-09,0.000000000000000000e+00 +4.959035290693214471e+00,5.266000000000000369e+01,0.000000000000000000e+00,9.077147601490240802e+00,0.000000000000000000e+00,-1.000000009936045320e+00,0.000000000000000000e+00,1.882708117085137846e-09,0.000000000000000000e+00 +4.960136958357884929e+00,5.267000000000000171e+01,0.000000000000000000e+00,9.076045933814624433e+00,0.000000000000000000e+00,-1.000000009933971201e+00,0.000000000000000000e+00,-8.980119021968040089e-10,0.000000000000000000e+00 +4.961238759745066673e+00,5.267999999999999972e+01,0.000000000000000000e+00,9.074944132416497666e+00,0.000000000000000000e+00,-1.000000009934960632e+00,0.000000000000000000e+00,-1.266655642959027156e-09,0.000000000000000000e+00 +4.962340694903463856e+00,5.268999999999999773e+01,0.000000000000000000e+00,9.073842197247152797e+00,0.000000000000000000e+00,-1.000000009936356404e+00,0.000000000000000000e+00,7.944347354126418564e-10,0.000000000000000000e+00 +4.963442763881810826e+00,5.270000000000000284e+01,0.000000000000000000e+00,9.072740128257855474e+00,0.000000000000000000e+00,-1.000000009935480882e+00,0.000000000000000000e+00,9.176288903004376669e-10,0.000000000000000000e+00 +4.964544966728870357e+00,5.271000000000000085e+01,0.000000000000000000e+00,9.071637925399844704e+00,0.000000000000000000e+00,-1.000000009934469469e+00,0.000000000000000000e+00,-8.740083536531424199e-10,0.000000000000000000e+00 +4.965647303493436304e+00,5.271999999999999886e+01,0.000000000000000000e+00,9.070535588624327517e+00,0.000000000000000000e+00,-1.000000009935432921e+00,0.000000000000000000e+00,-1.742164919917864177e-10,0.000000000000000000e+00 +4.966749774224330949e+00,5.273000000000000398e+01,0.000000000000000000e+00,9.069433117882478967e+00,0.000000000000000000e+00,-1.000000009935624989e+00,0.000000000000000000e+00,1.129752287083911745e-10,0.000000000000000000e+00 +4.967852378970407656e+00,5.274000000000000199e+01,0.000000000000000000e+00,9.068330513125447467e+00,0.000000000000000000e+00,-1.000000009935500422e+00,0.000000000000000000e+00,9.665154557359422749e-12,0.000000000000000000e+00 +4.968955117780547326e+00,5.275000000000000000e+01,0.000000000000000000e+00,9.067227774304351229e+00,0.000000000000000000e+00,-1.000000009935489764e+00,0.000000000000000000e+00,9.965978594107868749e-10,0.000000000000000000e+00 +4.970057990703662831e+00,5.275999999999999801e+01,0.000000000000000000e+00,9.066124901370278266e+00,0.000000000000000000e+00,-1.000000009934390643e+00,0.000000000000000000e+00,-1.285958137086170224e-09,0.000000000000000000e+00 +4.971160997788695468e+00,5.277000000000000313e+01,0.000000000000000000e+00,9.065021894274288172e+00,0.000000000000000000e+00,-1.000000009935809064e+00,0.000000000000000000e+00,4.838865449182747475e-10,0.000000000000000000e+00 +4.972264139084615842e+00,5.278000000000000114e+01,0.000000000000000000e+00,9.063918752967406789e+00,0.000000000000000000e+00,-1.000000009935275269e+00,0.000000000000000000e+00,-9.732905834469813006e-10,0.000000000000000000e+00 +4.973367414640426531e+00,5.278999999999999915e+01,0.000000000000000000e+00,9.062815477400635089e+00,0.000000000000000000e+00,-1.000000009936349077e+00,0.000000000000000000e+00,1.661395567374316342e-09,0.000000000000000000e+00 +4.974470824505157651e+00,5.280000000000000426e+01,0.000000000000000000e+00,9.061712067524940295e+00,0.000000000000000000e+00,-1.000000009934515877e+00,0.000000000000000000e+00,-1.805259956407429133e-09,0.000000000000000000e+00 +4.975574368727870400e+00,5.281000000000000227e+01,0.000000000000000000e+00,9.060608523291264760e+00,0.000000000000000000e+00,-1.000000009936508061e+00,0.000000000000000000e+00,1.776874080710221063e-09,0.000000000000000000e+00 +4.976678047357655288e+00,5.282000000000000028e+01,0.000000000000000000e+00,9.059504844650513533e+00,0.000000000000000000e+00,-1.000000009934546963e+00,0.000000000000000000e+00,-2.155042264656369417e-09,0.000000000000000000e+00 +4.977781860443633022e+00,5.282999999999999829e+01,0.000000000000000000e+00,9.058401031553570348e+00,0.000000000000000000e+00,-1.000000009936925727e+00,0.000000000000000000e+00,1.000253842640483846e-09,0.000000000000000000e+00 +4.978885808034953619e+00,5.284000000000000341e+01,0.000000000000000000e+00,9.057297083951279859e+00,0.000000000000000000e+00,-1.000000009935821499e+00,0.000000000000000000e+00,1.057851199117359607e-09,0.000000000000000000e+00 +4.979989890180798184e+00,5.285000000000000142e+01,0.000000000000000000e+00,9.056193001794465403e+00,0.000000000000000000e+00,-1.000000009934653544e+00,0.000000000000000000e+00,-1.957791596961986686e-09,0.000000000000000000e+00 +4.981094106930377130e+00,5.285999999999999943e+01,0.000000000000000000e+00,9.055088785033916565e+00,0.000000000000000000e+00,-1.000000009936815371e+00,0.000000000000000000e+00,7.149813123681482900e-10,0.000000000000000000e+00 +4.982198458332931068e+00,5.287000000000000455e+01,0.000000000000000000e+00,9.053984433620389183e+00,0.000000000000000000e+00,-1.000000009936025780e+00,0.000000000000000000e+00,3.554366685119180719e-10,0.000000000000000000e+00 +4.983302944437729920e+00,5.288000000000000256e+01,0.000000000000000000e+00,9.052879947504615998e+00,0.000000000000000000e+00,-1.000000009935633205e+00,0.000000000000000000e+00,-1.005071575688700378e-10,0.000000000000000000e+00 +4.984407565294074693e+00,5.289000000000000057e+01,0.000000000000000000e+00,9.051775326637296004e+00,0.000000000000000000e+00,-1.000000009935744227e+00,0.000000000000000000e+00,8.228521905462989679e-10,0.000000000000000000e+00 +4.985512320951295706e+00,5.289999999999999858e+01,0.000000000000000000e+00,9.050670570969097994e+00,0.000000000000000000e+00,-1.000000009934835177e+00,0.000000000000000000e+00,-1.218854284455507892e-09,0.000000000000000000e+00 +4.986617211458754362e+00,5.291000000000000369e+01,0.000000000000000000e+00,9.049565680450662342e+00,0.000000000000000000e+00,-1.000000009936181877e+00,0.000000000000000000e+00,-3.837967821254287816e-10,0.000000000000000000e+00 +4.987722236865841374e+00,5.292000000000000171e+01,0.000000000000000000e+00,9.048460655032595668e+00,0.000000000000000000e+00,-1.000000009936605982e+00,0.000000000000000000e+00,4.379972879491557649e-10,0.000000000000000000e+00 +4.988827397221977655e+00,5.292999999999999972e+01,0.000000000000000000e+00,9.047355494665477949e+00,0.000000000000000000e+00,-1.000000009936121925e+00,0.000000000000000000e+00,-1.858247740697109183e-10,0.000000000000000000e+00 +4.989932692576614315e+00,5.293999999999999773e+01,0.000000000000000000e+00,9.046250199299858963e+00,0.000000000000000000e+00,-1.000000009936327316e+00,0.000000000000000000e+00,6.733065364817464116e-10,0.000000000000000000e+00 +4.991038122979232661e+00,5.295000000000000284e+01,0.000000000000000000e+00,9.045144768886256514e+00,0.000000000000000000e+00,-1.000000009935583023e+00,0.000000000000000000e+00,1.299451361062999315e-10,0.000000000000000000e+00 +4.992143688479345087e+00,5.296000000000000085e+01,0.000000000000000000e+00,9.044039203375159985e+00,0.000000000000000000e+00,-1.000000009935439360e+00,0.000000000000000000e+00,-3.409889829904204902e-10,0.000000000000000000e+00 +4.993249389126492410e+00,5.296999999999999886e+01,0.000000000000000000e+00,9.042933502717026784e+00,0.000000000000000000e+00,-1.000000009935816392e+00,0.000000000000000000e+00,-7.188405857167391708e-10,0.000000000000000000e+00 +4.994355224970247420e+00,5.298000000000000398e+01,0.000000000000000000e+00,9.041827666862284119e+00,0.000000000000000000e+00,-1.000000009936611312e+00,0.000000000000000000e+00,4.704015449043715160e-10,0.000000000000000000e+00 +4.995461196060213105e+00,5.299000000000000199e+01,0.000000000000000000e+00,9.040721695761329002e+00,0.000000000000000000e+00,-1.000000009936091061e+00,0.000000000000000000e+00,-1.109313265485514213e-09,0.000000000000000000e+00 +4.996567302446021763e+00,5.300000000000000000e+01,0.000000000000000000e+00,9.039615589364530024e+00,0.000000000000000000e+00,-1.000000009937318080e+00,0.000000000000000000e+00,1.822937107545300652e-09,0.000000000000000000e+00 +4.997673544177336780e+00,5.300999999999999801e+01,0.000000000000000000e+00,9.038509347622222023e+00,0.000000000000000000e+00,-1.000000009935301470e+00,0.000000000000000000e+00,-8.728235279600102745e-10,0.000000000000000000e+00 +4.998779921303851737e+00,5.302000000000000313e+01,0.000000000000000000e+00,9.037402970484714970e+00,0.000000000000000000e+00,-1.000000009936267142e+00,0.000000000000000000e+00,-4.663586073629150599e-10,0.000000000000000000e+00 +4.999886433875290415e+00,5.303000000000000114e+01,0.000000000000000000e+00,9.036296457902281531e+00,0.000000000000000000e+00,-1.000000009936783174e+00,0.000000000000000000e+00,1.609181623338258329e-10,0.000000000000000000e+00 +5.000993081941407681e+00,5.303999999999999915e+01,0.000000000000000000e+00,9.035189809825167728e+00,0.000000000000000000e+00,-1.000000009936605094e+00,0.000000000000000000e+00,1.028987751330163383e-09,0.000000000000000000e+00 +5.002099865551988600e+00,5.305000000000000426e+01,0.000000000000000000e+00,9.034083026203589384e+00,0.000000000000000000e+00,-1.000000009935466228e+00,0.000000000000000000e+00,-7.398015133972276477e-10,0.000000000000000000e+00 +5.003206784756848435e+00,5.306000000000000227e+01,0.000000000000000000e+00,9.032976106987732123e+00,0.000000000000000000e+00,-1.000000009936285128e+00,0.000000000000000000e+00,-7.732064520302219275e-10,0.000000000000000000e+00 +5.004313839605832648e+00,5.307000000000000028e+01,0.000000000000000000e+00,9.031869052127747821e+00,0.000000000000000000e+00,-1.000000009937141110e+00,0.000000000000000000e+00,9.477888061128090179e-10,0.000000000000000000e+00 +5.005421030148818673e+00,5.307999999999999829e+01,0.000000000000000000e+00,9.030761861573759930e+00,0.000000000000000000e+00,-1.000000009936091727e+00,0.000000000000000000e+00,-1.351125287724829979e-09,0.000000000000000000e+00 +5.006528356435712368e+00,5.309000000000000341e+01,0.000000000000000000e+00,9.029654535275863481e+00,0.000000000000000000e+00,-1.000000009937587864e+00,0.000000000000000000e+00,1.044196747284435915e-09,0.000000000000000000e+00 +5.007635818516452453e+00,5.310000000000000142e+01,0.000000000000000000e+00,9.028547073184117977e+00,0.000000000000000000e+00,-1.000000009936431455e+00,0.000000000000000000e+00,9.123572504168490806e-10,0.000000000000000000e+00 +5.008743416441006957e+00,5.310999999999999943e+01,0.000000000000000000e+00,9.027439475248558054e+00,0.000000000000000000e+00,-1.000000009935420930e+00,0.000000000000000000e+00,-1.723464140472576968e-09,0.000000000000000000e+00 +5.009851150259374997e+00,5.312000000000000455e+01,0.000000000000000000e+00,9.026331741419184596e+00,0.000000000000000000e+00,-1.000000009937330070e+00,0.000000000000000000e+00,3.962398820786134259e-10,0.000000000000000000e+00 +5.010959020021585886e+00,5.313000000000000256e+01,0.000000000000000000e+00,9.025223871645964735e+00,0.000000000000000000e+00,-1.000000009936891088e+00,0.000000000000000000e+00,5.511006239583871416e-11,0.000000000000000000e+00 +5.012067025777700024e+00,5.314000000000000057e+01,0.000000000000000000e+00,9.024115865878840737e+00,0.000000000000000000e+00,-1.000000009936830025e+00,0.000000000000000000e+00,1.687162755963363609e-10,0.000000000000000000e+00 +5.013175167577808011e+00,5.314999999999999858e+01,0.000000000000000000e+00,9.023007724067721114e+00,0.000000000000000000e+00,-1.000000009936643064e+00,0.000000000000000000e+00,7.595307112571331937e-10,0.000000000000000000e+00 +5.014283445472032419e+00,5.316000000000000369e+01,0.000000000000000000e+00,9.021899446162484182e+00,0.000000000000000000e+00,-1.000000009935801293e+00,0.000000000000000000e+00,-1.043299942340741270e-09,0.000000000000000000e+00 +5.015391859510525130e+00,5.317000000000000171e+01,0.000000000000000000e+00,9.020791032112978058e+00,0.000000000000000000e+00,-1.000000009936957701e+00,0.000000000000000000e+00,5.648510705959752338e-10,0.000000000000000000e+00 +5.016500409743470890e+00,5.317999999999999972e+01,0.000000000000000000e+00,9.019682481869017110e+00,0.000000000000000000e+00,-1.000000009936331535e+00,0.000000000000000000e+00,-1.622044907737699973e-09,0.000000000000000000e+00 +5.017609096221082865e+00,5.318999999999999773e+01,0.000000000000000000e+00,9.018573795380389058e+00,0.000000000000000000e+00,-1.000000009938129875e+00,0.000000000000000000e+00,1.089173703962530157e-09,0.000000000000000000e+00 +5.018717918993606197e+00,5.320000000000000284e+01,0.000000000000000000e+00,9.017464972596846096e+00,0.000000000000000000e+00,-1.000000009936922174e+00,0.000000000000000000e+00,4.945630234745970507e-11,0.000000000000000000e+00 +5.019826878111317114e+00,5.321000000000000085e+01,0.000000000000000000e+00,9.016356013468115549e+00,0.000000000000000000e+00,-1.000000009936867329e+00,0.000000000000000000e+00,1.059876380777873481e-09,0.000000000000000000e+00 +5.020935973624522930e+00,5.321999999999999886e+01,0.000000000000000000e+00,9.015246917943889216e+00,0.000000000000000000e+00,-1.000000009935691825e+00,0.000000000000000000e+00,-1.634258857976387406e-09,0.000000000000000000e+00 +5.022045205583560268e+00,5.323000000000000398e+01,0.000000000000000000e+00,9.014137685973830472e+00,0.000000000000000000e+00,-1.000000009937504597e+00,0.000000000000000000e+00,6.513013246536045975e-10,0.000000000000000000e+00 +5.023154574038799502e+00,5.324000000000000199e+01,0.000000000000000000e+00,9.013028317507567166e+00,0.000000000000000000e+00,-1.000000009936782064e+00,0.000000000000000000e+00,-7.226673760412044331e-10,0.000000000000000000e+00 +5.024264079040639430e+00,5.325000000000000000e+01,0.000000000000000000e+00,9.011918812494702280e+00,0.000000000000000000e+00,-1.000000009937583867e+00,0.000000000000000000e+00,3.801991109440002475e-11,0.000000000000000000e+00 +5.025373720639511710e+00,5.325999999999999801e+01,0.000000000000000000e+00,9.010809170884803265e+00,0.000000000000000000e+00,-1.000000009937541678e+00,0.000000000000000000e+00,1.511005339927474313e-09,0.000000000000000000e+00 +5.026483498885877310e+00,5.327000000000000313e+01,0.000000000000000000e+00,9.009699392627409154e+00,0.000000000000000000e+00,-1.000000009935864798e+00,0.000000000000000000e+00,-2.049168632082988191e-09,0.000000000000000000e+00 +5.027593413830230062e+00,5.328000000000000114e+01,0.000000000000000000e+00,9.008589477672028778e+00,0.000000000000000000e+00,-1.000000009938139200e+00,0.000000000000000000e+00,9.151412263619270119e-10,0.000000000000000000e+00 +5.028703465523093108e+00,5.328999999999999915e+01,0.000000000000000000e+00,9.007479425968133668e+00,0.000000000000000000e+00,-1.000000009937123346e+00,0.000000000000000000e+00,3.318103207235164186e-10,0.000000000000000000e+00 +5.029813654015022450e+00,5.330000000000000426e+01,0.000000000000000000e+00,9.006369237465172262e+00,0.000000000000000000e+00,-1.000000009936754974e+00,0.000000000000000000e+00,-8.921177833872059176e-10,0.000000000000000000e+00 +5.030923979356604292e+00,5.331000000000000227e+01,0.000000000000000000e+00,9.005258912112557468e+00,0.000000000000000000e+00,-1.000000009937745515e+00,0.000000000000000000e+00,1.586458169471361315e-09,0.000000000000000000e+00 +5.032034441598455921e+00,5.332000000000000028e+01,0.000000000000000000e+00,9.004148449859670222e+00,0.000000000000000000e+00,-1.000000009935983813e+00,0.000000000000000000e+00,-2.293822802040601537e-09,0.000000000000000000e+00 +5.033145040791226599e+00,5.332999999999999829e+01,0.000000000000000000e+00,9.003037850655864816e+00,0.000000000000000000e+00,-1.000000009938531331e+00,0.000000000000000000e+00,1.890925972011321755e-09,0.000000000000000000e+00 +5.034255776985595787e+00,5.334000000000000341e+01,0.000000000000000000e+00,9.001927114450456457e+00,0.000000000000000000e+00,-1.000000009936431011e+00,0.000000000000000000e+00,-1.676418175586746427e-09,0.000000000000000000e+00 +5.035366650232274921e+00,5.335000000000000142e+01,0.000000000000000000e+00,9.000816241192739042e+00,0.000000000000000000e+00,-1.000000009938293299e+00,0.000000000000000000e+00,1.421791723018487230e-09,0.000000000000000000e+00 +5.036477660582006521e+00,5.335999999999999943e+01,0.000000000000000000e+00,8.999705230831965608e+00,0.000000000000000000e+00,-1.000000009936713674e+00,0.000000000000000000e+00,-3.067445748367496278e-10,0.000000000000000000e+00 +5.037588808085565084e+00,5.337000000000000455e+01,0.000000000000000000e+00,8.998594083317366099e+00,0.000000000000000000e+00,-1.000000009937054513e+00,0.000000000000000000e+00,-1.082964383316123464e-09,0.000000000000000000e+00 +5.038700092793755303e+00,5.338000000000000256e+01,0.000000000000000000e+00,8.997482798598133158e+00,0.000000000000000000e+00,-1.000000009938257994e+00,0.000000000000000000e+00,5.522036706856524160e-10,0.000000000000000000e+00 +5.039811514757413846e+00,5.339000000000000057e+01,0.000000000000000000e+00,8.996371376623429228e+00,0.000000000000000000e+00,-1.000000009937644263e+00,0.000000000000000000e+00,3.054323868236168791e-10,0.000000000000000000e+00 +5.040923074027408468e+00,5.339999999999999858e+01,0.000000000000000000e+00,8.995259817342388331e+00,0.000000000000000000e+00,-1.000000009937304757e+00,0.000000000000000000e+00,-3.613204182422698485e-10,0.000000000000000000e+00 +5.042034770654638898e+00,5.341000000000000369e+01,0.000000000000000000e+00,8.994148120704110738e+00,0.000000000000000000e+00,-1.000000009937706436e+00,0.000000000000000000e+00,1.446700736682084437e-09,0.000000000000000000e+00 +5.043146604690035950e+00,5.342000000000000171e+01,0.000000000000000000e+00,8.993036286657664746e+00,0.000000000000000000e+00,-1.000000009936097944e+00,0.000000000000000000e+00,-1.431944856281000369e-09,0.000000000000000000e+00 +5.044258576184561527e+00,5.342999999999999972e+01,0.000000000000000000e+00,8.991924315152090230e+00,0.000000000000000000e+00,-1.000000009937690226e+00,0.000000000000000000e+00,-3.547972917245015187e-10,0.000000000000000000e+00 +5.045370685189210391e+00,5.343999999999999773e+01,0.000000000000000000e+00,8.990812206136389761e+00,0.000000000000000000e+00,-1.000000009938084800e+00,0.000000000000000000e+00,3.892904621320072489e-10,0.000000000000000000e+00 +5.046482931755007506e+00,5.345000000000000284e+01,0.000000000000000000e+00,8.989699959559539266e+00,0.000000000000000000e+00,-1.000000009937651813e+00,0.000000000000000000e+00,-6.124078905307120161e-10,0.000000000000000000e+00 +5.047595315933009807e+00,5.346000000000000085e+01,0.000000000000000000e+00,8.988587575370482696e+00,0.000000000000000000e+00,-1.000000009938333045e+00,0.000000000000000000e+00,9.685944380615863908e-10,0.000000000000000000e+00 +5.048707837774305318e+00,5.346999999999999886e+01,0.000000000000000000e+00,8.987475053518130252e+00,0.000000000000000000e+00,-1.000000009937255463e+00,0.000000000000000000e+00,-5.865128201396570631e-10,0.000000000000000000e+00 +5.049820497330014923e+00,5.348000000000000398e+01,0.000000000000000000e+00,8.986362393951363714e+00,0.000000000000000000e+00,-1.000000009937908052e+00,0.000000000000000000e+00,4.850752461859235275e-10,0.000000000000000000e+00 +5.050933294651290595e+00,5.349000000000000199e+01,0.000000000000000000e+00,8.985249596619029333e+00,0.000000000000000000e+00,-1.000000009937368262e+00,0.000000000000000000e+00,-9.955679722202005443e-11,0.000000000000000000e+00 +5.052046229789315390e+00,5.350000000000000000e+01,0.000000000000000000e+00,8.984136661469944940e+00,0.000000000000000000e+00,-1.000000009937479062e+00,0.000000000000000000e+00,-8.829334788555070760e-10,0.000000000000000000e+00 +5.053159302795304342e+00,5.350999999999999801e+01,0.000000000000000000e+00,8.983023588452894614e+00,0.000000000000000000e+00,-1.000000009938461831e+00,0.000000000000000000e+00,1.024442956027861517e-09,0.000000000000000000e+00 +5.054272513720504456e+00,5.352000000000000313e+01,0.000000000000000000e+00,8.981910377516630462e+00,0.000000000000000000e+00,-1.000000009937321410e+00,0.000000000000000000e+00,-1.522912188416758215e-09,0.000000000000000000e+00 +5.055385862616194714e+00,5.353000000000000114e+01,0.000000000000000000e+00,8.980797028609876165e+00,0.000000000000000000e+00,-1.000000009939016943e+00,0.000000000000000000e+00,1.529702897828197075e-09,0.000000000000000000e+00 +5.056499349533686072e+00,5.353999999999999915e+01,0.000000000000000000e+00,8.979683541681318104e+00,0.000000000000000000e+00,-1.000000009937313639e+00,0.000000000000000000e+00,-1.258344158462394431e-09,0.000000000000000000e+00 +5.057612974524319682e+00,5.355000000000000426e+01,0.000000000000000000e+00,8.978569916679617791e+00,0.000000000000000000e+00,-1.000000009938714962e+00,0.000000000000000000e+00,1.594914407952717464e-09,0.000000000000000000e+00 +5.058726737639470450e+00,5.356000000000000227e+01,0.000000000000000000e+00,8.977456153553397655e+00,0.000000000000000000e+00,-1.000000009936938605e+00,0.000000000000000000e+00,-1.344545402919676099e-09,0.000000000000000000e+00 +5.059840638930544365e+00,5.357000000000000028e+01,0.000000000000000000e+00,8.976342252251255260e+00,0.000000000000000000e+00,-1.000000009938436296e+00,0.000000000000000000e+00,-3.149174423135332920e-11,0.000000000000000000e+00 +5.060954678448978505e+00,5.357999999999999829e+01,0.000000000000000000e+00,8.975228212721749088e+00,0.000000000000000000e+00,-1.000000009938471379e+00,0.000000000000000000e+00,1.259912013847384021e-09,0.000000000000000000e+00 +5.062068856246243698e+00,5.359000000000000341e+01,0.000000000000000000e+00,8.974114034913410975e+00,0.000000000000000000e+00,-1.000000009937067613e+00,0.000000000000000000e+00,-1.738789536102168170e-09,0.000000000000000000e+00 +5.063183172373840968e+00,5.360000000000000142e+01,0.000000000000000000e+00,8.972999718774740785e+00,0.000000000000000000e+00,-1.000000009939005174e+00,0.000000000000000000e+00,1.009153728927937576e-09,0.000000000000000000e+00 +5.064297626883304204e+00,5.360999999999999943e+01,0.000000000000000000e+00,8.971885264254201076e+00,0.000000000000000000e+00,-1.000000009937880519e+00,0.000000000000000000e+00,-4.874812385231581432e-10,0.000000000000000000e+00 +5.065412219826199269e+00,5.362000000000000455e+01,0.000000000000000000e+00,8.970770671300229537e+00,0.000000000000000000e+00,-1.000000009938423862e+00,0.000000000000000000e+00,9.447634961907032379e-10,0.000000000000000000e+00 +5.066526951254124000e+00,5.363000000000000256e+01,0.000000000000000000e+00,8.969655939861226557e+00,0.000000000000000000e+00,-1.000000009937370704e+00,0.000000000000000000e+00,-1.819583964980878913e-09,0.000000000000000000e+00 +5.067641821218707321e+00,5.364000000000000057e+01,0.000000000000000000e+00,8.968541069885564099e+00,0.000000000000000000e+00,-1.000000009939399304e+00,0.000000000000000000e+00,1.246228232062304288e-09,0.000000000000000000e+00 +5.068756829771611905e+00,5.364999999999999858e+01,0.000000000000000000e+00,8.967426061321576825e+00,0.000000000000000000e+00,-1.000000009938009748e+00,0.000000000000000000e+00,1.618820053085210768e-10,0.000000000000000000e+00 +5.069871976964531513e+00,5.366000000000000369e+01,0.000000000000000000e+00,8.966310914117574526e+00,0.000000000000000000e+00,-1.000000009937829226e+00,0.000000000000000000e+00,-7.631200057159374025e-10,0.000000000000000000e+00 +5.070987262849192767e+00,5.367000000000000171e+01,0.000000000000000000e+00,8.965195628221829693e+00,0.000000000000000000e+00,-1.000000009938680323e+00,0.000000000000000000e+00,-7.863159619309328880e-11,0.000000000000000000e+00 +5.072102687477353378e+00,5.367999999999999972e+01,0.000000000000000000e+00,8.964080203582582840e+00,0.000000000000000000e+00,-1.000000009938768031e+00,0.000000000000000000e+00,8.091080256359005779e-10,0.000000000000000000e+00 +5.073218250900804804e+00,5.368999999999999773e+01,0.000000000000000000e+00,8.962964640148044282e+00,0.000000000000000000e+00,-1.000000009937865419e+00,0.000000000000000000e+00,-9.312042592857827943e-10,0.000000000000000000e+00 +5.074333953171368705e+00,5.370000000000000284e+01,0.000000000000000000e+00,8.961848937866392362e+00,0.000000000000000000e+00,-1.000000009938904366e+00,0.000000000000000000e+00,4.318148548769789568e-10,0.000000000000000000e+00 +5.075449794340901377e+00,5.371000000000000085e+01,0.000000000000000000e+00,8.960733096685769894e+00,0.000000000000000000e+00,-1.000000009938422529e+00,0.000000000000000000e+00,6.386880633338103583e-10,0.000000000000000000e+00 +5.076565774461289315e+00,5.371999999999999886e+01,0.000000000000000000e+00,8.959617116554291272e+00,0.000000000000000000e+00,-1.000000009937709766e+00,0.000000000000000000e+00,-2.862796451168852615e-10,0.000000000000000000e+00 +5.077681893584451878e+00,5.373000000000000398e+01,0.000000000000000000e+00,8.958500997420037137e+00,0.000000000000000000e+00,-1.000000009938029288e+00,0.000000000000000000e+00,-8.943383918858068762e-10,0.000000000000000000e+00 +5.078798151762341284e+00,5.374000000000000199e+01,0.000000000000000000e+00,8.957384739231054382e+00,0.000000000000000000e+00,-1.000000009939027601e+00,0.000000000000000000e+00,2.625399421370964859e-10,0.000000000000000000e+00 +5.079914549046941730e+00,5.375000000000000000e+01,0.000000000000000000e+00,8.956268341935357924e+00,0.000000000000000000e+00,-1.000000009938734502e+00,0.000000000000000000e+00,3.551802243139456304e-10,0.000000000000000000e+00 +5.081031085490270272e+00,5.375999999999999801e+01,0.000000000000000000e+00,8.955151805480932481e+00,0.000000000000000000e+00,-1.000000009938337930e+00,0.000000000000000000e+00,-5.921583684891865898e-10,0.000000000000000000e+00 +5.082147761144375941e+00,5.377000000000000313e+01,0.000000000000000000e+00,8.954035129815729022e+00,0.000000000000000000e+00,-1.000000009938999179e+00,0.000000000000000000e+00,2.916682347961979304e-10,0.000000000000000000e+00 +5.083264576061339746e+00,5.378000000000000114e+01,0.000000000000000000e+00,8.952918314887664764e+00,0.000000000000000000e+00,-1.000000009938673440e+00,0.000000000000000000e+00,1.813007855661641492e-10,0.000000000000000000e+00 +5.084381530293276441e+00,5.378999999999999915e+01,0.000000000000000000e+00,8.951801360644626726e+00,0.000000000000000000e+00,-1.000000009938470935e+00,0.000000000000000000e+00,-9.006265059303863490e-10,0.000000000000000000e+00 +5.085498623892332759e+00,5.380000000000000426e+01,0.000000000000000000e+00,8.950684267034468178e+00,0.000000000000000000e+00,-1.000000009939477019e+00,0.000000000000000000e+00,1.338945841023147031e-09,0.000000000000000000e+00 +5.086615856910687405e+00,5.381000000000000227e+01,0.000000000000000000e+00,8.949567034005008637e+00,0.000000000000000000e+00,-1.000000009937981105e+00,0.000000000000000000e+00,-1.933548593255201572e-10,0.000000000000000000e+00 +5.087733229400552837e+00,5.382000000000000028e+01,0.000000000000000000e+00,8.948449661504039199e+00,0.000000000000000000e+00,-1.000000009938197154e+00,0.000000000000000000e+00,-1.204094711686797890e-09,0.000000000000000000e+00 +5.088850741414172596e+00,5.382999999999999829e+01,0.000000000000000000e+00,8.947332149479313657e+00,0.000000000000000000e+00,-1.000000009939542744e+00,0.000000000000000000e+00,1.172157031035857620e-09,0.000000000000000000e+00 +5.089968393003823088e+00,5.384000000000000341e+01,0.000000000000000000e+00,8.946214497878553829e+00,0.000000000000000000e+00,-1.000000009938232681e+00,0.000000000000000000e+00,-1.573672553427527704e-09,0.000000000000000000e+00 +5.091086184221815358e+00,5.385000000000000142e+01,0.000000000000000000e+00,8.945096706649453111e+00,0.000000000000000000e+00,-1.000000009939991719e+00,0.000000000000000000e+00,1.955622823094816092e-09,0.000000000000000000e+00 +5.092204115120490648e+00,5.385999999999999943e+01,0.000000000000000000e+00,8.943978775739665821e+00,0.000000000000000000e+00,-1.000000009937805467e+00,0.000000000000000000e+00,-1.010854776961942288e-09,0.000000000000000000e+00 +5.093322185752223952e+00,5.387000000000000455e+01,0.000000000000000000e+00,8.942860705096821405e+00,0.000000000000000000e+00,-1.000000009938935674e+00,0.000000000000000000e+00,-5.005984923822444947e-10,0.000000000000000000e+00 +5.094440396169423124e+00,5.388000000000000256e+01,0.000000000000000000e+00,8.941742494668508456e+00,0.000000000000000000e+00,-1.000000009939495449e+00,0.000000000000000000e+00,6.665208286316600110e-10,0.000000000000000000e+00 +5.095558746424528884e+00,5.389000000000000057e+01,0.000000000000000000e+00,8.940624144402287143e+00,0.000000000000000000e+00,-1.000000009938750045e+00,0.000000000000000000e+00,-3.279579071991407189e-10,0.000000000000000000e+00 +5.096677236570013925e+00,5.389999999999999858e+01,0.000000000000000000e+00,8.939505654245685662e+00,0.000000000000000000e+00,-1.000000009939116863e+00,0.000000000000000000e+00,-6.191118314811626634e-10,0.000000000000000000e+00 +5.097795866658384689e+00,5.391000000000000369e+01,0.000000000000000000e+00,8.938387024146196680e+00,0.000000000000000000e+00,-1.000000009939809420e+00,0.000000000000000000e+00,1.234099278682810834e-09,0.000000000000000000e+00 +5.098914636742180484e+00,5.392000000000000171e+01,0.000000000000000000e+00,8.937268254051280891e+00,0.000000000000000000e+00,-1.000000009938428747e+00,0.000000000000000000e+00,-4.226925782975060974e-10,0.000000000000000000e+00 +5.100033546873972590e+00,5.392999999999999972e+01,0.000000000000000000e+00,8.936149343908368792e+00,0.000000000000000000e+00,-1.000000009938901702e+00,0.000000000000000000e+00,1.109181076596139080e-10,0.000000000000000000e+00 +5.101152597106366038e+00,5.393999999999999773e+01,0.000000000000000000e+00,8.935030293664853573e+00,0.000000000000000000e+00,-1.000000009938777579e+00,0.000000000000000000e+00,-1.398107373861284179e-09,0.000000000000000000e+00 +5.102271787491997834e+00,5.395000000000000284e+01,0.000000000000000000e+00,8.933911103268098231e+00,0.000000000000000000e+00,-1.000000009940342327e+00,0.000000000000000000e+00,2.163452405939778372e-09,0.000000000000000000e+00 +5.103391118083539624e+00,5.396000000000000085e+01,0.000000000000000000e+00,8.932791772665430230e+00,0.000000000000000000e+00,-1.000000009937920709e+00,0.000000000000000000e+00,-1.942221873062253022e-09,0.000000000000000000e+00 +5.104510588933694137e+00,5.396999999999999886e+01,0.000000000000000000e+00,8.931672301804150393e+00,0.000000000000000000e+00,-1.000000009940094969e+00,0.000000000000000000e+00,4.854946177261023646e-10,0.000000000000000000e+00 +5.105630200095198745e+00,5.398000000000000398e+01,0.000000000000000000e+00,8.930552690631516910e+00,0.000000000000000000e+00,-1.000000009939551404e+00,0.000000000000000000e+00,9.627372968394000524e-10,0.000000000000000000e+00 +5.106749951620822792e+00,5.399000000000000199e+01,0.000000000000000000e+00,8.929432939094763100e+00,0.000000000000000000e+00,-1.000000009938473378e+00,0.000000000000000000e+00,-4.839849810773858661e-10,0.000000000000000000e+00 +5.107869843563369372e+00,5.400000000000000000e+01,0.000000000000000000e+00,8.928313047141086756e+00,0.000000000000000000e+00,-1.000000009939015388e+00,0.000000000000000000e+00,-9.989735581982002953e-10,0.000000000000000000e+00 +5.108989875975673556e+00,5.400999999999999801e+01,0.000000000000000000e+00,8.927193014717650144e+00,0.000000000000000000e+00,-1.000000009940134271e+00,0.000000000000000000e+00,8.561273163857469894e-10,0.000000000000000000e+00 +5.110110048910605052e+00,5.402000000000000313e+01,0.000000000000000000e+00,8.926072841771583555e+00,0.000000000000000000e+00,-1.000000009939175261e+00,0.000000000000000000e+00,-5.585237443231321516e-10,0.000000000000000000e+00 +5.111230362421066431e+00,5.403000000000000114e+01,0.000000000000000000e+00,8.924952528249987083e+00,0.000000000000000000e+00,-1.000000009939800982e+00,0.000000000000000000e+00,4.423238229701358531e-10,0.000000000000000000e+00 +5.112350816559993127e+00,5.403999999999999915e+01,0.000000000000000000e+00,8.923832074099923517e+00,0.000000000000000000e+00,-1.000000009939305379e+00,0.000000000000000000e+00,-3.630087421713459462e-10,0.000000000000000000e+00 +5.113471411380353437e+00,5.405000000000000426e+01,0.000000000000000000e+00,8.922711479268425450e+00,0.000000000000000000e+00,-1.000000009939712164e+00,0.000000000000000000e+00,1.292164692307832687e-09,0.000000000000000000e+00 +5.114592146935149408e+00,5.406000000000000227e+01,0.000000000000000000e+00,8.921590743702489945e+00,0.000000000000000000e+00,-1.000000009938263990e+00,0.000000000000000000e+00,-1.639666326838662496e-09,0.000000000000000000e+00 +5.115713023277415950e+00,5.407000000000000028e+01,0.000000000000000000e+00,8.920469867349083870e+00,0.000000000000000000e+00,-1.000000009940101853e+00,0.000000000000000000e+00,7.627838240855959895e-10,0.000000000000000000e+00 +5.116834040460221722e+00,5.407999999999999829e+01,0.000000000000000000e+00,8.919348850155135011e+00,0.000000000000000000e+00,-1.000000009939246759e+00,0.000000000000000000e+00,3.960986583242458127e-11,0.000000000000000000e+00 +5.117955198536669137e+00,5.409000000000000341e+01,0.000000000000000000e+00,8.918227692067544510e+00,0.000000000000000000e+00,-1.000000009939202350e+00,0.000000000000000000e+00,-9.572501161393300106e-10,0.000000000000000000e+00 +5.119076497559892580e+00,5.410000000000000142e+01,0.000000000000000000e+00,8.917106393033176204e+00,0.000000000000000000e+00,-1.000000009940275714e+00,0.000000000000000000e+00,6.201345486673816453e-10,0.000000000000000000e+00 +5.120197937583061076e+00,5.410999999999999943e+01,0.000000000000000000e+00,8.915984952998860180e+00,0.000000000000000000e+00,-1.000000009939580270e+00,0.000000000000000000e+00,-8.550524513318186006e-10,0.000000000000000000e+00 +5.121319518659376513e+00,5.412000000000000455e+01,0.000000000000000000e+00,8.914863371911396328e+00,0.000000000000000000e+00,-1.000000009940539281e+00,0.000000000000000000e+00,1.701773842029347582e-09,0.000000000000000000e+00 +5.122441240842075416e+00,5.413000000000000256e+01,0.000000000000000000e+00,8.913741649717547233e+00,0.000000000000000000e+00,-1.000000009938630363e+00,0.000000000000000000e+00,-1.568752157413950191e-09,0.000000000000000000e+00 +5.123563104184425399e+00,5.414000000000000057e+01,0.000000000000000000e+00,8.912619786364047059e+00,0.000000000000000000e+00,-1.000000009940390289e+00,0.000000000000000000e+00,6.495075175216148689e-10,0.000000000000000000e+00 +5.124685108739730488e+00,5.414999999999999858e+01,0.000000000000000000e+00,8.911497781797589113e+00,0.000000000000000000e+00,-1.000000009939661538e+00,0.000000000000000000e+00,-8.785650018867951312e-11,0.000000000000000000e+00 +5.125807254561325799e+00,5.416000000000000369e+01,0.000000000000000000e+00,8.910375635964840058e+00,0.000000000000000000e+00,-1.000000009939760126e+00,0.000000000000000000e+00,4.748402010771449237e-10,0.000000000000000000e+00 +5.126929541702581083e+00,5.417000000000000171e+01,0.000000000000000000e+00,8.909253348812429252e+00,0.000000000000000000e+00,-1.000000009939227219e+00,0.000000000000000000e+00,-4.587565553192623864e-10,0.000000000000000000e+00 +5.128051970216899846e+00,5.417999999999999972e+01,0.000000000000000000e+00,8.908130920286954080e+00,0.000000000000000000e+00,-1.000000009939742140e+00,0.000000000000000000e+00,-4.490065472551348895e-11,0.000000000000000000e+00 +5.129174540157719342e+00,5.418999999999999773e+01,0.000000000000000000e+00,8.907008350334976399e+00,0.000000000000000000e+00,-1.000000009939792545e+00,0.000000000000000000e+00,-1.079655444701868854e-09,0.000000000000000000e+00 +5.130297251578509687e+00,5.420000000000000284e+01,0.000000000000000000e+00,8.905885638903026091e+00,0.000000000000000000e+00,-1.000000009941004686e+00,0.000000000000000000e+00,2.096747340847055656e-09,0.000000000000000000e+00 +5.131420104532775639e+00,5.421000000000000085e+01,0.000000000000000000e+00,8.904762785937597513e+00,0.000000000000000000e+00,-1.000000009938650347e+00,0.000000000000000000e+00,-1.762920143187232522e-09,0.000000000000000000e+00 +5.132543099074055704e+00,5.421999999999999886e+01,0.000000000000000000e+00,8.903639791385156599e+00,0.000000000000000000e+00,-1.000000009940630097e+00,0.000000000000000000e+00,4.369181447519120268e-11,0.000000000000000000e+00 +5.133666235255921251e+00,5.423000000000000398e+01,0.000000000000000000e+00,8.902516655192126649e+00,0.000000000000000000e+00,-1.000000009940581025e+00,0.000000000000000000e+00,4.971540820754727357e-10,0.000000000000000000e+00 +5.134789513131977401e+00,5.424000000000000199e+01,0.000000000000000000e+00,8.901393377304904320e+00,0.000000000000000000e+00,-1.000000009940022583e+00,0.000000000000000000e+00,1.028573917938196266e-09,0.000000000000000000e+00 +5.135912932755863913e+00,5.425000000000000000e+01,0.000000000000000000e+00,8.900269957669850740e+00,0.000000000000000000e+00,-1.000000009938867063e+00,0.000000000000000000e+00,-1.151169659672810158e-09,0.000000000000000000e+00 +5.137036494181254298e+00,5.425999999999999801e+01,0.000000000000000000e+00,8.899146396233293288e+00,0.000000000000000000e+00,-1.000000009940160473e+00,0.000000000000000000e+00,-3.902614705300234095e-10,0.000000000000000000e+00 +5.138160197461855816e+00,5.427000000000000313e+01,0.000000000000000000e+00,8.898022692941522038e+00,0.000000000000000000e+00,-1.000000009940599011e+00,0.000000000000000000e+00,5.202170638821673974e-10,0.000000000000000000e+00 +5.139284042651409479e+00,5.428000000000000114e+01,0.000000000000000000e+00,8.896898847740796867e+00,0.000000000000000000e+00,-1.000000009940014367e+00,0.000000000000000000e+00,1.981434914873685154e-10,0.000000000000000000e+00 +5.140408029803690049e+00,5.428999999999999915e+01,0.000000000000000000e+00,8.895774860577343901e+00,0.000000000000000000e+00,-1.000000009939791656e+00,0.000000000000000000e+00,-1.332312070325562616e-09,0.000000000000000000e+00 +5.141532158972506927e+00,5.430000000000000426e+01,0.000000000000000000e+00,8.894650731397353738e+00,0.000000000000000000e+00,-1.000000009941289347e+00,0.000000000000000000e+00,1.575464844901934668e-09,0.000000000000000000e+00 +5.142656430211702379e+00,5.431000000000000227e+01,0.000000000000000000e+00,8.893526460146981449e+00,0.000000000000000000e+00,-1.000000009939518097e+00,0.000000000000000000e+00,-8.931837531643792959e-10,0.000000000000000000e+00 +5.143780843575154194e+00,5.432000000000000028e+01,0.000000000000000000e+00,8.892402046772353685e+00,0.000000000000000000e+00,-1.000000009940522405e+00,0.000000000000000000e+00,1.121916524788002830e-09,0.000000000000000000e+00 +5.144905399116773026e+00,5.432999999999999829e+01,0.000000000000000000e+00,8.891277491219556239e+00,0.000000000000000000e+00,-1.000000009939260748e+00,0.000000000000000000e+00,-2.188467429279778721e-09,0.000000000000000000e+00 +5.146030096890504169e+00,5.434000000000000341e+01,0.000000000000000000e+00,8.890152793434646483e+00,0.000000000000000000e+00,-1.000000009941722112e+00,0.000000000000000000e+00,1.838988148953050635e-09,0.000000000000000000e+00 +5.147154936950326665e+00,5.435000000000000142e+01,0.000000000000000000e+00,8.889027953363640933e+00,0.000000000000000000e+00,-1.000000009939653545e+00,0.000000000000000000e+00,-8.137815366397636270e-10,0.000000000000000000e+00 +5.148279919350254197e+00,5.435999999999999943e+01,0.000000000000000000e+00,8.887902970952531234e+00,0.000000000000000000e+00,-1.000000009940569035e+00,0.000000000000000000e+00,-2.940531246657778765e-10,0.000000000000000000e+00 +5.149405044144335086e+00,5.437000000000000455e+01,0.000000000000000000e+00,8.886777846147266402e+00,0.000000000000000000e+00,-1.000000009940899881e+00,0.000000000000000000e+00,6.130922162834629948e-10,0.000000000000000000e+00 +5.150530311386649629e+00,5.438000000000000256e+01,0.000000000000000000e+00,8.885652578893765252e+00,0.000000000000000000e+00,-1.000000009940209988e+00,0.000000000000000000e+00,5.285697048686176571e-10,0.000000000000000000e+00 +5.151655721131315424e+00,5.439000000000000057e+01,0.000000000000000000e+00,8.884527169137912850e+00,0.000000000000000000e+00,-1.000000009939615131e+00,0.000000000000000000e+00,-5.219926466524008785e-10,0.000000000000000000e+00 +5.152781273432482045e+00,5.439999999999999858e+01,0.000000000000000000e+00,8.883401616825558733e+00,0.000000000000000000e+00,-1.000000009940202661e+00,0.000000000000000000e+00,-1.112299179812466412e-09,0.000000000000000000e+00 +5.153906968344334594e+00,5.441000000000000369e+01,0.000000000000000000e+00,8.882275921902516913e+00,0.000000000000000000e+00,-1.000000009941454771e+00,0.000000000000000000e+00,1.583725942674912034e-09,0.000000000000000000e+00 +5.155032805921091033e+00,5.442000000000000171e+01,0.000000000000000000e+00,8.881150084314567650e+00,0.000000000000000000e+00,-1.000000009939671752e+00,0.000000000000000000e+00,-8.183847566268876688e-10,0.000000000000000000e+00 +5.156158786217005741e+00,5.442999999999999972e+01,0.000000000000000000e+00,8.880024104007461005e+00,0.000000000000000000e+00,-1.000000009940593237e+00,0.000000000000000000e+00,1.135734591685876694e-10,0.000000000000000000e+00 +5.157284909286365959e+00,5.443999999999999773e+01,0.000000000000000000e+00,8.878897980926906186e+00,0.000000000000000000e+00,-1.000000009940465340e+00,0.000000000000000000e+00,-1.200453288016410448e-09,0.000000000000000000e+00 +5.158411175183494457e+00,5.445000000000000284e+01,0.000000000000000000e+00,8.877771715018582199e+00,0.000000000000000000e+00,-1.000000009941817369e+00,0.000000000000000000e+00,2.265570627118153389e-09,0.000000000000000000e+00 +5.159537583962747753e+00,5.446000000000000085e+01,0.000000000000000000e+00,8.876645306228130750e+00,0.000000000000000000e+00,-1.000000009939265411e+00,0.000000000000000000e+00,-2.065028434324925091e-09,0.000000000000000000e+00 +5.160664135678516118e+00,5.446999999999999886e+01,0.000000000000000000e+00,8.875518754501165120e+00,0.000000000000000000e+00,-1.000000009941591772e+00,0.000000000000000000e+00,1.230937355170309039e-09,0.000000000000000000e+00 +5.161790830385226236e+00,5.448000000000000398e+01,0.000000000000000000e+00,8.874392059783254183e+00,0.000000000000000000e+00,-1.000000009940204881e+00,0.000000000000000000e+00,-4.199158682860051949e-10,0.000000000000000000e+00 +5.162917668137337657e+00,5.449000000000000199e+01,0.000000000000000000e+00,8.873265222019941945e+00,0.000000000000000000e+00,-1.000000009940678058e+00,0.000000000000000000e+00,4.334573475360564075e-12,0.000000000000000000e+00 +5.164044648989345454e+00,5.450000000000000000e+01,0.000000000000000000e+00,8.872138241156731553e+00,0.000000000000000000e+00,-1.000000009940673174e+00,0.000000000000000000e+00,-2.704824321210928191e-10,0.000000000000000000e+00 +5.165171772995778454e+00,5.450999999999999801e+01,0.000000000000000000e+00,8.871011117139094182e+00,0.000000000000000000e+00,-1.000000009940978041e+00,0.000000000000000000e+00,1.784602703864383976e-10,0.000000000000000000e+00 +5.166299040211201010e+00,5.452000000000000313e+01,0.000000000000000000e+00,8.869883849912465479e+00,0.000000000000000000e+00,-1.000000009940776868e+00,0.000000000000000000e+00,-2.284631432014285834e-11,0.000000000000000000e+00 +5.167426450690212114e+00,5.453000000000000114e+01,0.000000000000000000e+00,8.868756439422247340e+00,0.000000000000000000e+00,-1.000000009940802626e+00,0.000000000000000000e+00,-8.497354827798229914e-10,0.000000000000000000e+00 +5.168554004487444509e+00,5.453999999999999915e+01,0.000000000000000000e+00,8.867628885613806133e+00,0.000000000000000000e+00,-1.000000009941760748e+00,0.000000000000000000e+00,1.913679995341879156e-09,0.000000000000000000e+00 +5.169681701657566464e+00,5.455000000000000426e+01,0.000000000000000000e+00,8.866501188432472702e+00,0.000000000000000000e+00,-1.000000009939602696e+00,0.000000000000000000e+00,-1.487397238233597121e-09,0.000000000000000000e+00 +5.170809542255280888e+00,5.456000000000000227e+01,0.000000000000000000e+00,8.865373347823547689e+00,0.000000000000000000e+00,-1.000000009941280243e+00,0.000000000000000000e+00,1.464570191962604092e-10,0.000000000000000000e+00 +5.171937526335326218e+00,5.457000000000000028e+01,0.000000000000000000e+00,8.864245363732289107e+00,0.000000000000000000e+00,-1.000000009941115042e+00,0.000000000000000000e+00,-1.444701269055381668e-10,0.000000000000000000e+00 +5.173065653952473752e+00,5.457999999999999829e+01,0.000000000000000000e+00,8.863117236103926544e+00,0.000000000000000000e+00,-1.000000009941278023e+00,0.000000000000000000e+00,4.577585131210810879e-10,0.000000000000000000e+00 +5.174193925161531205e+00,5.459000000000000341e+01,0.000000000000000000e+00,8.861988964883652287e+00,0.000000000000000000e+00,-1.000000009940761547e+00,0.000000000000000000e+00,-8.144545554789813524e-10,0.000000000000000000e+00 +5.175322340017340927e+00,5.460000000000000142e+01,0.000000000000000000e+00,8.860860550016624870e+00,0.000000000000000000e+00,-1.000000009941680590e+00,0.000000000000000000e+00,1.644638499555849668e-09,0.000000000000000000e+00 +5.176450898574780801e+00,5.460999999999999943e+01,0.000000000000000000e+00,8.859731991447965527e+00,0.000000000000000000e+00,-1.000000009939824519e+00,0.000000000000000000e+00,-1.904303507709676938e-09,0.000000000000000000e+00 +5.177579600888761568e+00,5.462000000000000455e+01,0.000000000000000000e+00,8.858603289122765290e+00,0.000000000000000000e+00,-1.000000009941973911e+00,0.000000000000000000e+00,1.113914969737055770e-09,0.000000000000000000e+00 +5.178708447014231275e+00,5.463000000000000256e+01,0.000000000000000000e+00,8.857474442986072560e+00,0.000000000000000000e+00,-1.000000009940716472e+00,0.000000000000000000e+00,-4.303258656358172758e-10,0.000000000000000000e+00 +5.179837437006171719e+00,5.464000000000000057e+01,0.000000000000000000e+00,8.856345452982909094e+00,0.000000000000000000e+00,-1.000000009941202306e+00,0.000000000000000000e+00,4.568188158255836111e-10,0.000000000000000000e+00 +5.180966570919600223e+00,5.464999999999999858e+01,0.000000000000000000e+00,8.855216319058255792e+00,0.000000000000000000e+00,-1.000000009940686496e+00,0.000000000000000000e+00,-3.796834560554683077e-10,0.000000000000000000e+00 +5.182095848809568750e+00,5.466000000000000369e+01,0.000000000000000000e+00,8.854087041157061577e+00,0.000000000000000000e+00,-1.000000009941115264e+00,0.000000000000000000e+00,-1.293629486438817851e-10,0.000000000000000000e+00 +5.183225270731164791e+00,5.467000000000000171e+01,0.000000000000000000e+00,8.852957619224238073e+00,0.000000000000000000e+00,-1.000000009941261370e+00,0.000000000000000000e+00,-1.607984708168569707e-10,0.000000000000000000e+00 +5.184354836739510475e+00,5.467999999999999972e+01,0.000000000000000000e+00,8.851828053204663149e+00,0.000000000000000000e+00,-1.000000009941443002e+00,0.000000000000000000e+00,-4.491169014813646101e-10,0.000000000000000000e+00 +5.185484546889763458e+00,5.468999999999999773e+01,0.000000000000000000e+00,8.850698343043179150e+00,0.000000000000000000e+00,-1.000000009941950374e+00,0.000000000000000000e+00,4.225287106317051471e-10,0.000000000000000000e+00 +5.186614401237116923e+00,5.470000000000000284e+01,0.000000000000000000e+00,8.849568488684592893e+00,0.000000000000000000e+00,-1.000000009941472978e+00,0.000000000000000000e+00,1.085858413595787377e-09,0.000000000000000000e+00 +5.187744399836798692e+00,5.471000000000000085e+01,0.000000000000000000e+00,8.848438490073677443e+00,0.000000000000000000e+00,-1.000000009940245960e+00,0.000000000000000000e+00,-1.215393130573522537e-09,0.000000000000000000e+00 +5.188874542744072116e+00,5.471999999999999886e+01,0.000000000000000000e+00,8.847308347155170338e+00,0.000000000000000000e+00,-1.000000009941619528e+00,0.000000000000000000e+00,4.983929108688982359e-10,0.000000000000000000e+00 +5.190004830014235182e+00,5.473000000000000398e+01,0.000000000000000000e+00,8.846178059873770039e+00,0.000000000000000000e+00,-1.000000009941056200e+00,0.000000000000000000e+00,-7.018251359609313596e-10,0.000000000000000000e+00 +5.191135261702622294e+00,5.474000000000000199e+01,0.000000000000000000e+00,8.845047628174144805e+00,0.000000000000000000e+00,-1.000000009941849566e+00,0.000000000000000000e+00,7.692968830754348515e-10,0.000000000000000000e+00 +5.192265837864603384e+00,5.475000000000000000e+01,0.000000000000000000e+00,8.843917052000923817e+00,0.000000000000000000e+00,-1.000000009940979817e+00,0.000000000000000000e+00,-6.223104950862295745e-10,0.000000000000000000e+00 +5.193396558555582132e+00,5.475999999999999801e+01,0.000000000000000000e+00,8.842786331298704283e+00,0.000000000000000000e+00,-1.000000009941683476e+00,0.000000000000000000e+00,-6.832955630846512982e-10,0.000000000000000000e+00 +5.194527423830999524e+00,5.477000000000000313e+01,0.000000000000000000e+00,8.841655466012044329e+00,0.000000000000000000e+00,-1.000000009942456192e+00,0.000000000000000000e+00,1.999758194077798310e-09,0.000000000000000000e+00 +5.195658433746330296e+00,5.478000000000000114e+01,0.000000000000000000e+00,8.840524456085468330e+00,0.000000000000000000e+00,-1.000000009940194445e+00,0.000000000000000000e+00,-2.269609916921937317e-09,0.000000000000000000e+00 +5.196789588357085599e+00,5.478999999999999915e+01,0.000000000000000000e+00,8.839393301463468688e+00,0.000000000000000000e+00,-1.000000009942761725e+00,0.000000000000000000e+00,1.807290617603110526e-09,0.000000000000000000e+00 +5.197920887718812999e+00,5.480000000000000426e+01,0.000000000000000000e+00,8.838262002090493397e+00,0.000000000000000000e+00,-1.000000009940717138e+00,0.000000000000000000e+00,-1.015980241821312200e-09,0.000000000000000000e+00 +5.199052331887093814e+00,5.481000000000000227e+01,0.000000000000000000e+00,8.837130557910965578e+00,0.000000000000000000e+00,-1.000000009941866663e+00,0.000000000000000000e+00,3.904851955170501401e-10,0.000000000000000000e+00 +5.200183920917545777e+00,5.482000000000000028e+01,0.000000000000000000e+00,8.835998968869263948e+00,0.000000000000000000e+00,-1.000000009941424794e+00,0.000000000000000000e+00,-8.874062226426211522e-10,0.000000000000000000e+00 +5.201315654865821259e+00,5.482999999999999829e+01,0.000000000000000000e+00,8.834867234909737022e+00,0.000000000000000000e+00,-1.000000009942429102e+00,0.000000000000000000e+00,7.238800691492947720e-10,0.000000000000000000e+00 +5.202447533787610823e+00,5.484000000000000341e+01,0.000000000000000000e+00,8.833735355976694237e+00,0.000000000000000000e+00,-1.000000009941609758e+00,0.000000000000000000e+00,-2.977531614683531154e-10,0.000000000000000000e+00 +5.203579557738637895e+00,5.485000000000000142e+01,0.000000000000000000e+00,8.832603332014413056e+00,0.000000000000000000e+00,-1.000000009941946821e+00,0.000000000000000000e+00,2.326021053937553394e-10,0.000000000000000000e+00 +5.204711726774663205e+00,5.485999999999999943e+01,0.000000000000000000e+00,8.831471162967131860e+00,0.000000000000000000e+00,-1.000000009941683476e+00,0.000000000000000000e+00,9.526443391848344220e-10,0.000000000000000000e+00 +5.205844040951483009e+00,5.487000000000000455e+01,0.000000000000000000e+00,8.830338848779055283e+00,0.000000000000000000e+00,-1.000000009940604784e+00,0.000000000000000000e+00,-2.267191059522493522e-09,0.000000000000000000e+00 +5.206976500324928203e+00,5.488000000000000256e+01,0.000000000000000000e+00,8.829206389394352428e+00,0.000000000000000000e+00,-1.000000009943172286e+00,0.000000000000000000e+00,1.678364911486097734e-09,0.000000000000000000e+00 +5.208109104950866985e+00,5.489000000000000057e+01,0.000000000000000000e+00,8.828073784757151543e+00,0.000000000000000000e+00,-1.000000009941271362e+00,0.000000000000000000e+00,3.499003688076988619e-10,0.000000000000000000e+00 +5.209241854885203082e+00,5.489999999999999858e+01,0.000000000000000000e+00,8.826941034811554232e+00,0.000000000000000000e+00,-1.000000009940875012e+00,0.000000000000000000e+00,-2.071693188953241245e-09,0.000000000000000000e+00 +5.210374750183875747e+00,5.491000000000000369e+01,0.000000000000000000e+00,8.825808139501619465e+00,0.000000000000000000e+00,-1.000000009943222024e+00,0.000000000000000000e+00,1.358676012389919504e-09,0.000000000000000000e+00 +5.211507790902860648e+00,5.492000000000000171e+01,0.000000000000000000e+00,8.824675098771368909e+00,0.000000000000000000e+00,-1.000000009941682588e+00,0.000000000000000000e+00,-4.061984410997487038e-10,0.000000000000000000e+00 +5.212640977098168094e+00,5.492999999999999972e+01,0.000000000000000000e+00,8.823541912564795808e+00,0.000000000000000000e+00,-1.000000009942142887e+00,0.000000000000000000e+00,9.615851161297153450e-10,0.000000000000000000e+00 +5.213774308825845694e+00,5.493999999999999773e+01,0.000000000000000000e+00,8.822408580825850777e+00,0.000000000000000000e+00,-1.000000009941053092e+00,0.000000000000000000e+00,-1.428087838078361283e-09,0.000000000000000000e+00 +5.214907786141975699e+00,5.495000000000000284e+01,0.000000000000000000e+00,8.821275103498452452e+00,0.000000000000000000e+00,-1.000000009942671797e+00,0.000000000000000000e+00,7.456833887924087004e-10,0.000000000000000000e+00 +5.216041409102678550e+00,5.496000000000000085e+01,0.000000000000000000e+00,8.820141480526478617e+00,0.000000000000000000e+00,-1.000000009941826473e+00,0.000000000000000000e+00,5.955691549326629501e-10,0.000000000000000000e+00 +5.217175177764108440e+00,5.496999999999999886e+01,0.000000000000000000e+00,8.819007711853776854e+00,0.000000000000000000e+00,-1.000000009941151236e+00,0.000000000000000000e+00,-1.851098827557823178e-09,0.000000000000000000e+00 +5.218309092182456865e+00,5.498000000000000398e+01,0.000000000000000000e+00,8.817873797424155669e+00,0.000000000000000000e+00,-1.000000009943250223e+00,0.000000000000000000e+00,1.719285820715599279e-09,0.000000000000000000e+00 +5.219443152413951736e+00,5.499000000000000199e+01,0.000000000000000000e+00,8.816739737181384484e+00,0.000000000000000000e+00,-1.000000009941300450e+00,0.000000000000000000e+00,-1.099841192419792935e-09,0.000000000000000000e+00 +5.220577358514856492e+00,5.500000000000000000e+01,0.000000000000000000e+00,8.815605531069204304e+00,0.000000000000000000e+00,-1.000000009942547896e+00,0.000000000000000000e+00,7.657574316320464546e-10,0.000000000000000000e+00 +5.221711710541470985e+00,5.500999999999999801e+01,0.000000000000000000e+00,8.814471179031311721e+00,0.000000000000000000e+00,-1.000000009941679258e+00,0.000000000000000000e+00,-9.431774608382045529e-10,0.000000000000000000e+00 +5.222846208550130598e+00,5.502000000000000313e+01,0.000000000000000000e+00,8.813336681011373130e+00,0.000000000000000000e+00,-1.000000009942749291e+00,0.000000000000000000e+00,7.003937869973710064e-10,0.000000000000000000e+00 +5.223980852597208013e+00,5.503000000000000114e+01,0.000000000000000000e+00,8.812202036953014073e+00,0.000000000000000000e+00,-1.000000009941954593e+00,0.000000000000000000e+00,2.019316381248861485e-10,0.000000000000000000e+00 +5.225115642739112332e+00,5.503999999999999915e+01,0.000000000000000000e+00,8.811067246799828112e+00,0.000000000000000000e+00,-1.000000009941725443e+00,0.000000000000000000e+00,-1.032809926379136574e-09,0.000000000000000000e+00 +5.226250579032287291e+00,5.505000000000000426e+01,0.000000000000000000e+00,8.809932310495369734e+00,0.000000000000000000e+00,-1.000000009942897616e+00,0.000000000000000000e+00,1.158460419653585816e-09,0.000000000000000000e+00 +5.227385661533214822e+00,5.506000000000000227e+01,0.000000000000000000e+00,8.808797227983156120e+00,0.000000000000000000e+00,-1.000000009941582668e+00,0.000000000000000000e+00,-1.471458100834983219e-09,0.000000000000000000e+00 +5.228520890298412382e+00,5.507000000000000028e+01,0.000000000000000000e+00,8.807661999206672476e+00,0.000000000000000000e+00,-1.000000009943253110e+00,0.000000000000000000e+00,7.523554159882388008e-10,0.000000000000000000e+00 +5.229656265384433844e+00,5.507999999999999829e+01,0.000000000000000000e+00,8.806526624109361379e+00,0.000000000000000000e+00,-1.000000009942398904e+00,0.000000000000000000e+00,9.634461379134778371e-10,0.000000000000000000e+00 +5.230791786847870384e+00,5.509000000000000341e+01,0.000000000000000000e+00,8.805391102634635203e+00,0.000000000000000000e+00,-1.000000009941304890e+00,0.000000000000000000e+00,-8.104260844725833294e-10,0.000000000000000000e+00 +5.231927454745348705e+00,5.510000000000000142e+01,0.000000000000000000e+00,8.804255434725867246e+00,0.000000000000000000e+00,-1.000000009942225265e+00,0.000000000000000000e+00,-4.121008080649108322e-10,0.000000000000000000e+00 +5.233063269133531925e+00,5.510999999999999943e+01,0.000000000000000000e+00,8.803119620326391725e+00,0.000000000000000000e+00,-1.000000009942693335e+00,0.000000000000000000e+00,-5.701816781498633505e-10,0.000000000000000000e+00 +5.234199230069120468e+00,5.512000000000000455e+01,0.000000000000000000e+00,8.801983659379509106e+00,0.000000000000000000e+00,-1.000000009943341039e+00,0.000000000000000000e+00,1.493186799931477499e-09,0.000000000000000000e+00 +5.235335337608850281e+00,5.513000000000000256e+01,0.000000000000000000e+00,8.800847551828482551e+00,0.000000000000000000e+00,-1.000000009941644619e+00,0.000000000000000000e+00,-1.077535247712862893e-09,0.000000000000000000e+00 +5.236471591809495507e+00,5.514000000000000057e+01,0.000000000000000000e+00,8.799711297616541472e+00,0.000000000000000000e+00,-1.000000009942868973e+00,0.000000000000000000e+00,9.769642092667997027e-13,0.000000000000000000e+00 +5.237607992727864925e+00,5.514999999999999858e+01,0.000000000000000000e+00,8.798574896686872648e+00,0.000000000000000000e+00,-1.000000009942867862e+00,0.000000000000000000e+00,6.251763477882031878e-10,0.000000000000000000e+00 +5.238744540420806395e+00,5.516000000000000369e+01,0.000000000000000000e+00,8.797438348982630885e+00,0.000000000000000000e+00,-1.000000009942157320e+00,0.000000000000000000e+00,-5.536002829712843944e-10,0.000000000000000000e+00 +5.239881234945202415e+00,5.517000000000000171e+01,0.000000000000000000e+00,8.796301654446933682e+00,0.000000000000000000e+00,-1.000000009942786594e+00,0.000000000000000000e+00,6.156396018489992351e-10,0.000000000000000000e+00 +5.241018076357973676e+00,5.517999999999999972e+01,0.000000000000000000e+00,8.795164813022859462e+00,0.000000000000000000e+00,-1.000000009942086709e+00,0.000000000000000000e+00,-1.340092946543755038e-09,0.000000000000000000e+00 +5.242155064716076396e+00,5.518999999999999773e+01,0.000000000000000000e+00,8.794027824653452896e+00,0.000000000000000000e+00,-1.000000009943610380e+00,0.000000000000000000e+00,1.850346712882003289e-09,0.000000000000000000e+00 +5.243292200076504095e+00,5.520000000000000284e+01,0.000000000000000000e+00,8.792890689281717798e+00,0.000000000000000000e+00,-1.000000009941506285e+00,0.000000000000000000e+00,-7.790131617609675340e-10,0.000000000000000000e+00 +5.244429482496287598e+00,5.521000000000000085e+01,0.000000000000000000e+00,8.791753406850627783e+00,0.000000000000000000e+00,-1.000000009942392243e+00,0.000000000000000000e+00,-9.585112532048209316e-10,0.000000000000000000e+00 +5.245566912032494145e+00,5.521999999999999886e+01,0.000000000000000000e+00,8.790615977303112061e+00,0.000000000000000000e+00,-1.000000009943482482e+00,0.000000000000000000e+00,1.334324891041218008e-09,0.000000000000000000e+00 +5.246704488742228278e+00,5.523000000000000398e+01,0.000000000000000000e+00,8.789478400582066087e+00,0.000000000000000000e+00,-1.000000009941964585e+00,0.000000000000000000e+00,-7.371405690070545184e-10,0.000000000000000000e+00 +5.247842212682631846e+00,5.524000000000000199e+01,0.000000000000000000e+00,8.788340676630351567e+00,0.000000000000000000e+00,-1.000000009942803247e+00,0.000000000000000000e+00,-2.839292286726449363e-10,0.000000000000000000e+00 +5.248980083910882222e+00,5.525000000000000000e+01,0.000000000000000000e+00,8.787202805390787574e+00,0.000000000000000000e+00,-1.000000009943126322e+00,0.000000000000000000e+00,-2.556007777668052788e-11,0.000000000000000000e+00 +5.250118102484194971e+00,5.525999999999999801e+01,0.000000000000000000e+00,8.786064786806159432e+00,0.000000000000000000e+00,-1.000000009943155410e+00,0.000000000000000000e+00,6.398946372937297753e-11,0.000000000000000000e+00 +5.251256268459822074e+00,5.527000000000000313e+01,0.000000000000000000e+00,8.784926620819215159e+00,0.000000000000000000e+00,-1.000000009943082580e+00,0.000000000000000000e+00,1.131374425272811986e-11,0.000000000000000000e+00 +5.252394581895053705e+00,5.528000000000000114e+01,0.000000000000000000e+00,8.783788307372665471e+00,0.000000000000000000e+00,-1.000000009943069701e+00,0.000000000000000000e+00,1.212169127969200680e-09,0.000000000000000000e+00 +5.253533042847215562e+00,5.528999999999999915e+01,0.000000000000000000e+00,8.782649846409183780e+00,0.000000000000000000e+00,-1.000000009941689694e+00,0.000000000000000000e+00,-1.788083380065992319e-09,0.000000000000000000e+00 +5.254671651373671537e+00,5.530000000000000426e+01,0.000000000000000000e+00,8.781511237871407971e+00,0.000000000000000000e+00,-1.000000009943725621e+00,0.000000000000000000e+00,6.280586650127829895e-10,0.000000000000000000e+00 +5.255810407531822825e+00,5.531000000000000227e+01,0.000000000000000000e+00,8.780372481701933296e+00,0.000000000000000000e+00,-1.000000009943010415e+00,0.000000000000000000e+00,2.653452335098800761e-10,0.000000000000000000e+00 +5.256949311379107037e+00,5.532000000000000028e+01,0.000000000000000000e+00,8.779233577843324809e+00,0.000000000000000000e+00,-1.000000009942708212e+00,0.000000000000000000e+00,-1.089704231297265721e-10,0.000000000000000000e+00 +5.258088362972999974e+00,5.532999999999999829e+01,0.000000000000000000e+00,8.778094526238106710e+00,0.000000000000000000e+00,-1.000000009942832335e+00,0.000000000000000000e+00,-4.697399759886219340e-10,0.000000000000000000e+00 +5.259227562371013853e+00,5.534000000000000341e+01,0.000000000000000000e+00,8.776955326828765891e+00,0.000000000000000000e+00,-1.000000009943367463e+00,0.000000000000000000e+00,5.788160466631317524e-10,0.000000000000000000e+00 +5.260366909630699084e+00,5.535000000000000142e+01,0.000000000000000000e+00,8.775815979557751945e+00,0.000000000000000000e+00,-1.000000009942707990e+00,0.000000000000000000e+00,-1.044071984834147957e-09,0.000000000000000000e+00 +5.261506404809642490e+00,5.535999999999999943e+01,0.000000000000000000e+00,8.774676484367478935e+00,0.000000000000000000e+00,-1.000000009943897705e+00,0.000000000000000000e+00,1.530054625925321385e-09,0.000000000000000000e+00 +5.262646047965469087e+00,5.537000000000000455e+01,0.000000000000000000e+00,8.773536841200320069e+00,0.000000000000000000e+00,-1.000000009942153989e+00,0.000000000000000000e+00,-1.248547878757230263e-09,0.000000000000000000e+00 +5.263785839155840307e+00,5.538000000000000256e+01,0.000000000000000000e+00,8.772397049998616581e+00,0.000000000000000000e+00,-1.000000009943577073e+00,0.000000000000000000e+00,2.201085684050071736e-10,0.000000000000000000e+00 +5.264925778438456661e+00,5.539000000000000057e+01,0.000000000000000000e+00,8.771257110704665294e+00,0.000000000000000000e+00,-1.000000009943326162e+00,0.000000000000000000e+00,4.921611278241464311e-10,0.000000000000000000e+00 +5.266065865871055074e+00,5.539999999999999858e+01,0.000000000000000000e+00,8.770117023260731060e+00,0.000000000000000000e+00,-1.000000009942765056e+00,0.000000000000000000e+00,-4.052450269888115306e-10,0.000000000000000000e+00 +5.267206101511409777e+00,5.541000000000000369e+01,0.000000000000000000e+00,8.768976787609039647e+00,0.000000000000000000e+00,-1.000000009943227131e+00,0.000000000000000000e+00,2.873925483928495018e-10,0.000000000000000000e+00 +5.268346485417332303e+00,5.542000000000000171e+01,0.000000000000000000e+00,8.767836403691777747e+00,0.000000000000000000e+00,-1.000000009942899393e+00,0.000000000000000000e+00,-1.364742389983838887e-10,0.000000000000000000e+00 +5.269487017646673266e+00,5.542999999999999972e+01,0.000000000000000000e+00,8.766695871451096522e+00,0.000000000000000000e+00,-1.000000009943055046e+00,0.000000000000000000e+00,-2.843978978581696312e-10,0.000000000000000000e+00 +5.270627698257319693e+00,5.543999999999999773e+01,0.000000000000000000e+00,8.765555190829108057e+00,0.000000000000000000e+00,-1.000000009943379453e+00,0.000000000000000000e+00,-1.300157951849866039e-10,0.000000000000000000e+00 +5.271768527307196806e+00,5.545000000000000284e+01,0.000000000000000000e+00,8.764414361767887129e+00,0.000000000000000000e+00,-1.000000009943527779e+00,0.000000000000000000e+00,3.528262845861091742e-10,0.000000000000000000e+00 +5.272909504854267126e+00,5.546000000000000085e+01,0.000000000000000000e+00,8.763273384209471217e+00,0.000000000000000000e+00,-1.000000009943125212e+00,0.000000000000000000e+00,-1.741524630919916552e-10,0.000000000000000000e+00 +5.274050630956531371e+00,5.546999999999999886e+01,0.000000000000000000e+00,8.762132258095860493e+00,0.000000000000000000e+00,-1.000000009943323942e+00,0.000000000000000000e+00,-3.192703664897169184e-10,0.000000000000000000e+00 +5.275191905672027559e+00,5.548000000000000398e+01,0.000000000000000000e+00,8.760990983369016050e+00,0.000000000000000000e+00,-1.000000009943688317e+00,0.000000000000000000e+00,-5.738725805879106922e-11,0.000000000000000000e+00 +5.276333329058831900e+00,5.549000000000000199e+01,0.000000000000000000e+00,8.759849559970861677e+00,0.000000000000000000e+00,-1.000000009943753820e+00,0.000000000000000000e+00,6.383743812637814388e-10,0.000000000000000000e+00 +5.277474901175057909e+00,5.550000000000000000e+01,0.000000000000000000e+00,8.758707987843283860e+00,0.000000000000000000e+00,-1.000000009943025070e+00,0.000000000000000000e+00,-9.309871792996426759e-10,0.000000000000000000e+00 +5.278616622078858178e+00,5.550999999999999801e+01,0.000000000000000000e+00,8.757566266928131782e+00,0.000000000000000000e+00,-1.000000009944087997e+00,0.000000000000000000e+00,7.115182880810263568e-10,0.000000000000000000e+00 +5.279758491828421718e+00,5.552000000000000313e+01,0.000000000000000000e+00,8.756424397167213769e+00,0.000000000000000000e+00,-1.000000009943275536e+00,0.000000000000000000e+00,1.421295577748001507e-10,0.000000000000000000e+00 +5.280900510481975729e+00,5.553000000000000114e+01,0.000000000000000000e+00,8.755282378502304397e+00,0.000000000000000000e+00,-1.000000009943113222e+00,0.000000000000000000e+00,1.127556665710146797e-10,0.000000000000000000e+00 +5.282042678097785604e+00,5.553999999999999915e+01,0.000000000000000000e+00,8.754140210875137385e+00,0.000000000000000000e+00,-1.000000009942984436e+00,0.000000000000000000e+00,-7.118230771979650676e-10,0.000000000000000000e+00 +5.283184994734155815e+00,5.555000000000000426e+01,0.000000000000000000e+00,8.752997894227409148e+00,0.000000000000000000e+00,-1.000000009943797563e+00,0.000000000000000000e+00,4.176701756607382455e-10,0.000000000000000000e+00 +5.284327460449427250e+00,5.556000000000000227e+01,0.000000000000000000e+00,8.751855428500777023e+00,0.000000000000000000e+00,-1.000000009943320389e+00,0.000000000000000000e+00,-5.559787825890776138e-10,0.000000000000000000e+00 +5.285470075301979875e+00,5.557000000000000028e+01,0.000000000000000000e+00,8.750712813636862819e+00,0.000000000000000000e+00,-1.000000009943955659e+00,0.000000000000000000e+00,4.768241189593261018e-10,0.000000000000000000e+00 +5.286612839350231852e+00,5.557999999999999829e+01,0.000000000000000000e+00,8.749570049577247488e+00,0.000000000000000000e+00,-1.000000009943410761e+00,0.000000000000000000e+00,-5.387370049509445081e-10,0.000000000000000000e+00 +5.287755752652638641e+00,5.559000000000000341e+01,0.000000000000000000e+00,8.748427136263476456e+00,0.000000000000000000e+00,-1.000000009944026491e+00,0.000000000000000000e+00,5.046721640591947597e-10,0.000000000000000000e+00 +5.288898815267693898e+00,5.560000000000000142e+01,0.000000000000000000e+00,8.747284073637054291e+00,0.000000000000000000e+00,-1.000000009943449619e+00,0.000000000000000000e+00,-4.459491494539652911e-10,0.000000000000000000e+00 +5.290042027253930357e+00,5.560999999999999943e+01,0.000000000000000000e+00,8.746140861639450037e+00,0.000000000000000000e+00,-1.000000009943959434e+00,0.000000000000000000e+00,7.146682883448368305e-10,0.000000000000000000e+00 +5.291185388669918943e+00,5.562000000000000455e+01,0.000000000000000000e+00,8.744997500212091879e+00,0.000000000000000000e+00,-1.000000009943142310e+00,0.000000000000000000e+00,-1.422353494741148212e-09,0.000000000000000000e+00 +5.292328899574267886e+00,5.563000000000000256e+01,0.000000000000000000e+00,8.743853989296372475e+00,0.000000000000000000e+00,-1.000000009944768786e+00,0.000000000000000000e+00,1.321014021353150943e-09,0.000000000000000000e+00 +5.293472560025625384e+00,5.564000000000000057e+01,0.000000000000000000e+00,8.742710328833641853e+00,0.000000000000000000e+00,-1.000000009943257995e+00,0.000000000000000000e+00,-5.363733599176823516e-10,0.000000000000000000e+00 +5.294616370082676049e+00,5.564999999999999858e+01,0.000000000000000000e+00,8.741566518765218063e+00,0.000000000000000000e+00,-1.000000009943871504e+00,0.000000000000000000e+00,-1.770208127885614917e-10,0.000000000000000000e+00 +5.295760329804143574e+00,5.566000000000000369e+01,0.000000000000000000e+00,8.740422559032374750e+00,0.000000000000000000e+00,-1.000000009944074009e+00,0.000000000000000000e+00,-2.901441692627271564e-10,0.000000000000000000e+00 +5.296904439248791618e+00,5.567000000000000171e+01,0.000000000000000000e+00,8.739278449576350027e+00,0.000000000000000000e+00,-1.000000009944405965e+00,0.000000000000000000e+00,5.086075741975640992e-10,0.000000000000000000e+00 +5.298048698475419371e+00,5.567999999999999972e+01,0.000000000000000000e+00,8.738134190338342933e+00,0.000000000000000000e+00,-1.000000009943823986e+00,0.000000000000000000e+00,8.888310693220258442e-10,0.000000000000000000e+00 +5.299193107542866876e+00,5.568999999999999773e+01,0.000000000000000000e+00,8.736989781259515198e+00,0.000000000000000000e+00,-1.000000009942806800e+00,0.000000000000000000e+00,-1.833689365070888207e-09,0.000000000000000000e+00 +5.300337666510012369e+00,5.570000000000000284e+01,0.000000000000000000e+00,8.735845222280989475e+00,0.000000000000000000e+00,-1.000000009944905566e+00,0.000000000000000000e+00,1.859247788073298910e-09,0.000000000000000000e+00 +5.301482375435772276e+00,5.571000000000000085e+01,0.000000000000000000e+00,8.734700513343845785e+00,0.000000000000000000e+00,-1.000000009942777268e+00,0.000000000000000000e+00,-1.562649610509478216e-09,0.000000000000000000e+00 +5.302627234379101218e+00,5.571999999999999886e+01,0.000000000000000000e+00,8.733555654389133949e+00,0.000000000000000000e+00,-1.000000009944566282e+00,0.000000000000000000e+00,1.277958444899071972e-10,0.000000000000000000e+00 +5.303772243398992892e+00,5.573000000000000398e+01,0.000000000000000000e+00,8.732410645357855827e+00,0.000000000000000000e+00,-1.000000009944419954e+00,0.000000000000000000e+00,1.799377775422625971e-10,0.000000000000000000e+00 +5.304917402554479189e+00,5.574000000000000199e+01,0.000000000000000000e+00,8.731265486190981306e+00,0.000000000000000000e+00,-1.000000009944213897e+00,0.000000000000000000e+00,-2.307089170498436927e-11,0.000000000000000000e+00 +5.306062711904631968e+00,5.575000000000000000e+01,0.000000000000000000e+00,8.730120176829439416e+00,0.000000000000000000e+00,-1.000000009944240320e+00,0.000000000000000000e+00,8.998405989411541721e-10,0.000000000000000000e+00 +5.307208171508560390e+00,5.575999999999999801e+01,0.000000000000000000e+00,8.728974717214120105e+00,0.000000000000000000e+00,-1.000000009943209589e+00,0.000000000000000000e+00,-1.085597997965510238e-09,0.000000000000000000e+00 +5.308353781425413587e+00,5.577000000000000313e+01,0.000000000000000000e+00,8.727829107285876020e+00,0.000000000000000000e+00,-1.000000009944453261e+00,0.000000000000000000e+00,8.162718545509786599e-10,0.000000000000000000e+00 +5.309499541714378879e+00,5.578000000000000114e+01,0.000000000000000000e+00,8.726683346985517176e+00,0.000000000000000000e+00,-1.000000009943518009e+00,0.000000000000000000e+00,-1.487776007683789869e-09,0.000000000000000000e+00 +5.310645452434681779e+00,5.578999999999999915e+01,0.000000000000000000e+00,8.725537436253819834e+00,0.000000000000000000e+00,-1.000000009945222867e+00,0.000000000000000000e+00,1.499980380603217803e-09,0.000000000000000000e+00 +5.311791513645587770e+00,5.580000000000000426e+01,0.000000000000000000e+00,8.724391375031515850e+00,0.000000000000000000e+00,-1.000000009943503798e+00,0.000000000000000000e+00,-1.013738872080781090e-09,0.000000000000000000e+00 +5.312937725406401412e+00,5.581000000000000227e+01,0.000000000000000000e+00,8.723245163259305102e+00,0.000000000000000000e+00,-1.000000009944665758e+00,0.000000000000000000e+00,4.640931064152485642e-10,0.000000000000000000e+00 +5.314084087776465459e+00,5.582000000000000028e+01,0.000000000000000000e+00,8.722098800877841285e+00,0.000000000000000000e+00,-1.000000009944133739e+00,0.000000000000000000e+00,5.529264174632117501e-10,0.000000000000000000e+00 +5.315230600815161743e+00,5.582999999999999829e+01,0.000000000000000000e+00,8.720952287827744343e+00,0.000000000000000000e+00,-1.000000009943499801e+00,0.000000000000000000e+00,-7.190003224955979910e-10,0.000000000000000000e+00 +5.316377264581911177e+00,5.584000000000000341e+01,0.000000000000000000e+00,8.719805624049593362e+00,0.000000000000000000e+00,-1.000000009944324253e+00,0.000000000000000000e+00,-6.222901144535917059e-10,0.000000000000000000e+00 +5.317524079136173754e+00,5.585000000000000142e+01,0.000000000000000000e+00,8.718658809483926575e+00,0.000000000000000000e+00,-1.000000009945037904e+00,0.000000000000000000e+00,8.698138660670214963e-10,0.000000000000000000e+00 +5.318671044537448545e+00,5.585999999999999943e+01,0.000000000000000000e+00,8.717511844071244909e+00,0.000000000000000000e+00,-1.000000009944040258e+00,0.000000000000000000e+00,-2.671233533217591131e-10,0.000000000000000000e+00 +5.319818160845274591e+00,5.587000000000000455e+01,0.000000000000000000e+00,8.716364727752011987e+00,0.000000000000000000e+00,-1.000000009944346679e+00,0.000000000000000000e+00,4.625658012031254807e-11,0.000000000000000000e+00 +5.320965428119229124e+00,5.588000000000000256e+01,0.000000000000000000e+00,8.715217460466648802e+00,0.000000000000000000e+00,-1.000000009944293611e+00,0.000000000000000000e+00,4.865009882862459562e-10,0.000000000000000000e+00 +5.322112846418928456e+00,5.589000000000000057e+01,0.000000000000000000e+00,8.714070042155539042e+00,0.000000000000000000e+00,-1.000000009943735391e+00,0.000000000000000000e+00,-1.616619176352463558e-09,0.000000000000000000e+00 +5.323260415804028867e+00,5.589999999999999858e+01,0.000000000000000000e+00,8.712922472759027315e+00,0.000000000000000000e+00,-1.000000009945590573e+00,0.000000000000000000e+00,1.857271131077956759e-09,0.000000000000000000e+00 +5.324408136334225716e+00,5.591000000000000369e+01,0.000000000000000000e+00,8.711774752217415596e+00,0.000000000000000000e+00,-1.000000009943458945e+00,0.000000000000000000e+00,-1.202037765108499408e-09,0.000000000000000000e+00 +5.325556008069253444e+00,5.592000000000000171e+01,0.000000000000000000e+00,8.710626880470973887e+00,0.000000000000000000e+00,-1.000000009944838730e+00,0.000000000000000000e+00,2.088879520669418293e-11,0.000000000000000000e+00 +5.326704031068886458e+00,5.592999999999999972e+01,0.000000000000000000e+00,8.709478857459924228e+00,0.000000000000000000e+00,-1.000000009944814749e+00,0.000000000000000000e+00,1.599329338990286842e-10,0.000000000000000000e+00 +5.327852205392937357e+00,5.593999999999999773e+01,0.000000000000000000e+00,8.708330683124454907e+00,0.000000000000000000e+00,-1.000000009944631119e+00,0.000000000000000000e+00,5.911130895499873302e-10,0.000000000000000000e+00 +5.329000531101259597e+00,5.595000000000000284e+01,0.000000000000000000e+00,8.707182357404713358e+00,0.000000000000000000e+00,-1.000000009943952328e+00,0.000000000000000000e+00,-1.352207976872156436e-09,0.000000000000000000e+00 +5.330149008253744825e+00,5.596000000000000085e+01,0.000000000000000000e+00,8.706033880240807932e+00,0.000000000000000000e+00,-1.000000009945505308e+00,0.000000000000000000e+00,1.092217237172134274e-09,0.000000000000000000e+00 +5.331297636910324655e+00,5.596999999999999886e+01,0.000000000000000000e+00,8.704885251572804350e+00,0.000000000000000000e+00,-1.000000009944250756e+00,0.000000000000000000e+00,-1.285360416391137964e-10,0.000000000000000000e+00 +5.332446417130970673e+00,5.598000000000000398e+01,0.000000000000000000e+00,8.703736471340734582e+00,0.000000000000000000e+00,-1.000000009944398416e+00,0.000000000000000000e+00,3.996653457679108687e-10,0.000000000000000000e+00 +5.333595348975693540e+00,5.599000000000000199e+01,0.000000000000000000e+00,8.702587539484586188e+00,0.000000000000000000e+00,-1.000000009943939228e+00,0.000000000000000000e+00,-1.332943729778538956e-09,0.000000000000000000e+00 +5.334744432504543887e+00,5.600000000000000000e+01,0.000000000000000000e+00,8.701438455944309425e+00,0.000000000000000000e+00,-1.000000009945470891e+00,0.000000000000000000e+00,1.427440994572849486e-09,0.000000000000000000e+00 +5.335893667777611427e+00,5.600999999999999801e+01,0.000000000000000000e+00,8.700289220659811917e+00,0.000000000000000000e+00,-1.000000009943830426e+00,0.000000000000000000e+00,-7.066715650244324786e-10,0.000000000000000000e+00 +5.337043054855026725e+00,5.602000000000000313e+01,0.000000000000000000e+00,8.699139833570967539e+00,0.000000000000000000e+00,-1.000000009944642665e+00,0.000000000000000000e+00,-9.822171088404634851e-10,0.000000000000000000e+00 +5.338192593796958541e+00,5.603000000000000114e+01,0.000000000000000000e+00,8.697990294617603979e+00,0.000000000000000000e+00,-1.000000009945771762e+00,0.000000000000000000e+00,6.265272859571237690e-10,0.000000000000000000e+00 +5.339342284663616489e+00,5.603999999999999915e+01,0.000000000000000000e+00,8.696840603739511621e+00,0.000000000000000000e+00,-1.000000009945051449e+00,0.000000000000000000e+00,1.158651921571986441e-10,0.000000000000000000e+00 +5.340492127515249265e+00,5.605000000000000426e+01,0.000000000000000000e+00,8.695690760876443548e+00,0.000000000000000000e+00,-1.000000009944918222e+00,0.000000000000000000e+00,2.013856961989664175e-10,0.000000000000000000e+00 +5.341642122412146421e+00,5.606000000000000227e+01,0.000000000000000000e+00,8.694540765968110207e+00,0.000000000000000000e+00,-1.000000009944686630e+00,0.000000000000000000e+00,9.104595800014792758e-10,0.000000000000000000e+00 +5.342792269414635697e+00,5.607000000000000028e+01,0.000000000000000000e+00,8.693390618954182969e+00,0.000000000000000000e+00,-1.000000009943639467e+00,0.000000000000000000e+00,-1.756591641754636087e-09,0.000000000000000000e+00 +5.343942568583086583e+00,5.607999999999999829e+01,0.000000000000000000e+00,8.692240319774294122e+00,0.000000000000000000e+00,-1.000000009945660073e+00,0.000000000000000000e+00,2.841055779680470809e-10,0.000000000000000000e+00 +5.345093019977906756e+00,5.609000000000000341e+01,0.000000000000000000e+00,8.691089868368031546e+00,0.000000000000000000e+00,-1.000000009945333224e+00,0.000000000000000000e+00,3.467867880292930303e-10,0.000000000000000000e+00 +5.346243623659545641e+00,5.610000000000000142e+01,0.000000000000000000e+00,8.689939264674949371e+00,0.000000000000000000e+00,-1.000000009944934209e+00,0.000000000000000000e+00,1.144225599592428809e-09,0.000000000000000000e+00 +5.347394379688491739e+00,5.610999999999999943e+01,0.000000000000000000e+00,8.688788508634559093e+00,0.000000000000000000e+00,-1.000000009943617485e+00,0.000000000000000000e+00,-1.318675601081169815e-09,0.000000000000000000e+00 +5.348545288125273522e+00,5.612000000000000455e+01,0.000000000000000000e+00,8.687637600186333131e+00,0.000000000000000000e+00,-1.000000009945135160e+00,0.000000000000000000e+00,-3.082610807747023942e-10,0.000000000000000000e+00 +5.349696349030459430e+00,5.613000000000000256e+01,0.000000000000000000e+00,8.686486539269699492e+00,0.000000000000000000e+00,-1.000000009945489987e+00,0.000000000000000000e+00,1.801487498660025910e-10,0.000000000000000000e+00 +5.350847562464658758e+00,5.614000000000000057e+01,0.000000000000000000e+00,8.685335325824050656e+00,0.000000000000000000e+00,-1.000000009945282597e+00,0.000000000000000000e+00,1.741464261510809515e-10,0.000000000000000000e+00 +5.351998928488520768e+00,5.614999999999999858e+01,0.000000000000000000e+00,8.684183959788738250e+00,0.000000000000000000e+00,-1.000000009945082091e+00,0.000000000000000000e+00,-2.965688790136384722e-10,0.000000000000000000e+00 +5.353150447162733805e+00,5.616000000000000369e+01,0.000000000000000000e+00,8.683032441103073040e+00,0.000000000000000000e+00,-1.000000009945423596e+00,0.000000000000000000e+00,1.474164480367836368e-09,0.000000000000000000e+00 +5.354302118548027956e+00,5.617000000000000171e+01,0.000000000000000000e+00,8.681880769706324941e+00,0.000000000000000000e+00,-1.000000009943725843e+00,0.000000000000000000e+00,-1.181334260564000948e-09,0.000000000000000000e+00 +5.355453942705173276e+00,5.617999999999999972e+01,0.000000000000000000e+00,8.680728945537726560e+00,0.000000000000000000e+00,-1.000000009945086532e+00,0.000000000000000000e+00,-1.998826863252616584e-10,0.000000000000000000e+00 +5.356605919694978901e+00,5.618999999999999773e+01,0.000000000000000000e+00,8.679576968536464321e+00,0.000000000000000000e+00,-1.000000009945316792e+00,0.000000000000000000e+00,-9.086999021390302767e-10,0.000000000000000000e+00 +5.357758049578295712e+00,5.620000000000000284e+01,0.000000000000000000e+00,8.678424838641689121e+00,0.000000000000000000e+00,-1.000000009946363733e+00,0.000000000000000000e+00,2.071907620250788629e-09,0.000000000000000000e+00 +5.358910332416014555e+00,5.621000000000000085e+01,0.000000000000000000e+00,8.677272555792509223e+00,0.000000000000000000e+00,-1.000000009943976309e+00,0.000000000000000000e+00,-1.930980387902015366e-09,0.000000000000000000e+00 +5.360062768269066247e+00,5.621999999999999886e+01,0.000000000000000000e+00,8.676120119927997365e+00,0.000000000000000000e+00,-1.000000009946201640e+00,0.000000000000000000e+00,1.823803978403722980e-09,0.000000000000000000e+00 +5.361215357198423348e+00,5.623000000000000398e+01,0.000000000000000000e+00,8.674967530987176545e+00,0.000000000000000000e+00,-1.000000009944099544e+00,0.000000000000000000e+00,-1.345471472101632093e-09,0.000000000000000000e+00 +5.362368099265097499e+00,5.624000000000000199e+01,0.000000000000000000e+00,8.673814788909039564e+00,0.000000000000000000e+00,-1.000000009945650525e+00,0.000000000000000000e+00,6.226673224261719548e-10,0.000000000000000000e+00 +5.363520994530141195e+00,5.625000000000000000e+01,0.000000000000000000e+00,8.672661893632529484e+00,0.000000000000000000e+00,-1.000000009944932655e+00,0.000000000000000000e+00,-2.638233363833412288e-10,0.000000000000000000e+00 +5.364674043054647790e+00,5.625999999999999801e+01,0.000000000000000000e+00,8.671508845096555618e+00,0.000000000000000000e+00,-1.000000009945236856e+00,0.000000000000000000e+00,-1.302767423848012492e-09,0.000000000000000000e+00 +5.365827244899751491e+00,5.627000000000000313e+01,0.000000000000000000e+00,8.670355643239982868e+00,0.000000000000000000e+00,-1.000000009946739210e+00,0.000000000000000000e+00,1.540357075259526409e-09,0.000000000000000000e+00 +5.366980600126627365e+00,5.628000000000000114e+01,0.000000000000000000e+00,8.669202288001635281e+00,0.000000000000000000e+00,-1.000000009944962631e+00,0.000000000000000000e+00,2.808501462102516680e-10,0.000000000000000000e+00 +5.368134108796489556e+00,5.628999999999999915e+01,0.000000000000000000e+00,8.668048779320301378e+00,0.000000000000000000e+00,-1.000000009944638668e+00,0.000000000000000000e+00,-1.045301021751233891e-09,0.000000000000000000e+00 +5.369287770970594842e+00,5.630000000000000426e+01,0.000000000000000000e+00,8.666895117134723492e+00,0.000000000000000000e+00,-1.000000009945844592e+00,0.000000000000000000e+00,2.590292608775820671e-10,0.000000000000000000e+00 +5.370441586710239967e+00,5.631000000000000227e+01,0.000000000000000000e+00,8.665741301383603101e+00,0.000000000000000000e+00,-1.000000009945545720e+00,0.000000000000000000e+00,2.182021371537113989e-10,0.000000000000000000e+00 +5.371595556076761646e+00,5.632000000000000028e+01,0.000000000000000000e+00,8.664587332005604381e+00,0.000000000000000000e+00,-1.000000009945293922e+00,0.000000000000000000e+00,1.958555518651140621e-10,0.000000000000000000e+00 +5.372749679131539224e+00,5.632999999999999829e+01,0.000000000000000000e+00,8.663433208939348873e+00,0.000000000000000000e+00,-1.000000009945067880e+00,0.000000000000000000e+00,-1.112842287514273788e-09,0.000000000000000000e+00 +5.373903955935991128e+00,5.634000000000000341e+01,0.000000000000000000e+00,8.662278932123417263e+00,0.000000000000000000e+00,-1.000000009946352408e+00,0.000000000000000000e+00,1.653365215859745404e-09,0.000000000000000000e+00 +5.375058386551578415e+00,5.635000000000000142e+01,0.000000000000000000e+00,8.661124501496347605e+00,0.000000000000000000e+00,-1.000000009944443713e+00,0.000000000000000000e+00,-8.081101378129596039e-10,0.000000000000000000e+00 +5.376212971039802113e+00,5.635999999999999943e+01,0.000000000000000000e+00,8.659969916996642425e+00,0.000000000000000000e+00,-1.000000009945376744e+00,0.000000000000000000e+00,-4.707258218063565707e-10,0.000000000000000000e+00 +5.377367709462204104e+00,5.637000000000000455e+01,0.000000000000000000e+00,8.658815178562756287e+00,0.000000000000000000e+00,-1.000000009945920310e+00,0.000000000000000000e+00,2.768606201437677226e-11,0.000000000000000000e+00 +5.378522601880367127e+00,5.638000000000000256e+01,0.000000000000000000e+00,8.657660286133106453e+00,0.000000000000000000e+00,-1.000000009945888335e+00,0.000000000000000000e+00,7.166657833114037422e-10,0.000000000000000000e+00 +5.379677648355916553e+00,5.639000000000000057e+01,0.000000000000000000e+00,8.656505239646069327e+00,0.000000000000000000e+00,-1.000000009945060553e+00,0.000000000000000000e+00,-1.038719206537471900e-09,0.000000000000000000e+00 +5.380832848950516833e+00,5.639999999999999858e+01,0.000000000000000000e+00,8.655350039039980459e+00,0.000000000000000000e+00,-1.000000009946260482e+00,0.000000000000000000e+00,1.168499258183143910e-10,0.000000000000000000e+00 +5.381988203725875053e+00,5.641000000000000369e+01,0.000000000000000000e+00,8.654194684253130987e+00,0.000000000000000000e+00,-1.000000009946125479e+00,0.000000000000000000e+00,2.171427480758500282e-10,0.000000000000000000e+00 +5.383143712743738263e+00,5.642000000000000171e+01,0.000000000000000000e+00,8.653039175223774748e+00,0.000000000000000000e+00,-1.000000009945874568e+00,0.000000000000000000e+00,6.229051276135483549e-10,0.000000000000000000e+00 +5.384299376065896148e+00,5.642999999999999972e+01,0.000000000000000000e+00,8.651883511890122946e+00,0.000000000000000000e+00,-1.000000009945154700e+00,0.000000000000000000e+00,3.304298976758659512e-11,0.000000000000000000e+00 +5.385455193754178360e+00,5.643999999999999773e+01,0.000000000000000000e+00,8.650727694190345929e+00,0.000000000000000000e+00,-1.000000009945116508e+00,0.000000000000000000e+00,-1.523231998644224236e-09,0.000000000000000000e+00 +5.386611165870456297e+00,5.645000000000000284e+01,0.000000000000000000e+00,8.649571722062571411e+00,0.000000000000000000e+00,-1.000000009946877322e+00,0.000000000000000000e+00,1.300431987207543510e-09,0.000000000000000000e+00 +5.387767292476643100e+00,5.646000000000000085e+01,0.000000000000000000e+00,8.648415595444884474e+00,0.000000000000000000e+00,-1.000000009945373858e+00,0.000000000000000000e+00,-7.719742776954515617e-10,0.000000000000000000e+00 +5.388923573634693653e+00,5.646999999999999886e+01,0.000000000000000000e+00,8.647259314275334674e+00,0.000000000000000000e+00,-1.000000009946266477e+00,0.000000000000000000e+00,1.591552055835793117e-09,0.000000000000000000e+00 +5.390080009406602812e+00,5.648000000000000398e+01,0.000000000000000000e+00,8.646102878491923605e+00,0.000000000000000000e+00,-1.000000009944425949e+00,0.000000000000000000e+00,-2.207601590415522556e-09,0.000000000000000000e+00 +5.391236599854407174e+00,5.649000000000000199e+01,0.000000000000000000e+00,8.644946288032617332e+00,0.000000000000000000e+00,-1.000000009946979240e+00,0.000000000000000000e+00,1.140796696880782573e-09,0.000000000000000000e+00 +5.392393345040185970e+00,5.650000000000000000e+01,0.000000000000000000e+00,8.643789542835332185e+00,0.000000000000000000e+00,-1.000000009945659629e+00,0.000000000000000000e+00,-2.857847875965948903e-10,0.000000000000000000e+00 +5.393550245026059287e+00,5.650999999999999801e+01,0.000000000000000000e+00,8.642632642837952517e+00,0.000000000000000000e+00,-1.000000009945990254e+00,0.000000000000000000e+00,1.809664103501737858e-10,0.000000000000000000e+00 +5.394707299874188955e+00,5.652000000000000313e+01,0.000000000000000000e+00,8.641475587978314721e+00,0.000000000000000000e+00,-1.000000009945780866e+00,0.000000000000000000e+00,-8.519441066084646097e-11,0.000000000000000000e+00 +5.395864509646778551e+00,5.653000000000000114e+01,0.000000000000000000e+00,8.640318378194216109e+00,0.000000000000000000e+00,-1.000000009945879453e+00,0.000000000000000000e+00,2.720484162450497978e-10,0.000000000000000000e+00 +5.397021874406072506e+00,5.653999999999999915e+01,0.000000000000000000e+00,8.639161013423411362e+00,0.000000000000000000e+00,-1.000000009945564594e+00,0.000000000000000000e+00,-4.450407498333655791e-11,0.000000000000000000e+00 +5.398179394214356996e+00,5.655000000000000426e+01,0.000000000000000000e+00,8.638003493603614302e+00,0.000000000000000000e+00,-1.000000009945616108e+00,0.000000000000000000e+00,-1.004851764085697627e-09,0.000000000000000000e+00 +5.399337069133961720e+00,5.656000000000000227e+01,0.000000000000000000e+00,8.636845818672496122e+00,0.000000000000000000e+00,-1.000000009946779400e+00,0.000000000000000000e+00,1.395557603311553628e-09,0.000000000000000000e+00 +5.400494899227255452e+00,5.657000000000000028e+01,0.000000000000000000e+00,8.635687988567685380e+00,0.000000000000000000e+00,-1.000000009945163582e+00,0.000000000000000000e+00,-7.648939123504948991e-10,0.000000000000000000e+00 +5.401652884556651379e+00,5.657999999999999829e+01,0.000000000000000000e+00,8.634530003226773331e+00,0.000000000000000000e+00,-1.000000009946049317e+00,0.000000000000000000e+00,-8.309364981414731750e-10,0.000000000000000000e+00 +5.402811025184602656e+00,5.659000000000000341e+01,0.000000000000000000e+00,8.633371862587303269e+00,0.000000000000000000e+00,-1.000000009947011659e+00,0.000000000000000000e+00,1.224383840677692128e-09,0.000000000000000000e+00 +5.403969321173605067e+00,5.660000000000000142e+01,0.000000000000000000e+00,8.632213566586779407e+00,0.000000000000000000e+00,-1.000000009945593460e+00,0.000000000000000000e+00,-1.189526641503791865e-09,0.000000000000000000e+00 +5.405127772586196144e+00,5.660999999999999943e+01,0.000000000000000000e+00,8.631055115162666880e+00,0.000000000000000000e+00,-1.000000009946971469e+00,0.000000000000000000e+00,1.224055279814705416e-09,0.000000000000000000e+00 +5.406286379484955162e+00,5.662000000000000455e+01,0.000000000000000000e+00,8.629896508252382858e+00,0.000000000000000000e+00,-1.000000009945553270e+00,0.000000000000000000e+00,-7.708960947971762149e-10,0.000000000000000000e+00 +5.407445141932504917e+00,5.663000000000000256e+01,0.000000000000000000e+00,8.628737745793308989e+00,0.000000000000000000e+00,-1.000000009946446555e+00,0.000000000000000000e+00,7.951253354630478748e-10,0.000000000000000000e+00 +5.408604059991508173e+00,5.664000000000000057e+01,0.000000000000000000e+00,8.627578827722778954e+00,0.000000000000000000e+00,-1.000000009945525070e+00,0.000000000000000000e+00,-6.632178784288513634e-10,0.000000000000000000e+00 +5.409763133724670325e+00,5.664999999999999858e+01,0.000000000000000000e+00,8.626419753978089133e+00,0.000000000000000000e+00,-1.000000009946293789e+00,0.000000000000000000e+00,1.741144019266301670e-10,0.000000000000000000e+00 +5.410922363194739404e+00,5.666000000000000369e+01,0.000000000000000000e+00,8.625260524496489722e+00,0.000000000000000000e+00,-1.000000009946091950e+00,0.000000000000000000e+00,-6.302898733183225449e-10,0.000000000000000000e+00 +5.412081748464506070e+00,5.667000000000000171e+01,0.000000000000000000e+00,8.624101139215191836e+00,0.000000000000000000e+00,-1.000000009946822699e+00,0.000000000000000000e+00,9.180199014612894835e-10,0.000000000000000000e+00 +5.413241289596801842e+00,5.667999999999999972e+01,0.000000000000000000e+00,8.622941598071362179e+00,0.000000000000000000e+00,-1.000000009945758217e+00,0.000000000000000000e+00,-4.363550388132216532e-10,0.000000000000000000e+00 +5.414400986654501757e+00,5.668999999999999773e+01,0.000000000000000000e+00,8.621781901002128379e+00,0.000000000000000000e+00,-1.000000009946264257e+00,0.000000000000000000e+00,-6.999120090181727763e-10,0.000000000000000000e+00 +5.415560839700521711e+00,5.670000000000000284e+01,0.000000000000000000e+00,8.620622047944571875e+00,0.000000000000000000e+00,-1.000000009947076052e+00,0.000000000000000000e+00,1.475627961324936972e-09,0.000000000000000000e+00 +5.416720848797822008e+00,5.671000000000000085e+01,0.000000000000000000e+00,8.619462038835733253e+00,0.000000000000000000e+00,-1.000000009945364310e+00,0.000000000000000000e+00,-1.800219083520657962e-09,0.000000000000000000e+00 +5.417881014009402918e+00,5.671999999999999886e+01,0.000000000000000000e+00,8.618301873612614017e+00,0.000000000000000000e+00,-1.000000009947452861e+00,0.000000000000000000e+00,1.381462083074535072e-09,0.000000000000000000e+00 +5.419041335398309123e+00,5.673000000000000398e+01,0.000000000000000000e+00,8.617141552212165934e+00,0.000000000000000000e+00,-1.000000009945849921e+00,0.000000000000000000e+00,-8.267757289261717232e-10,0.000000000000000000e+00 +5.420201813027626159e+00,5.674000000000000199e+01,0.000000000000000000e+00,8.615981074571307019e+00,0.000000000000000000e+00,-1.000000009946809376e+00,0.000000000000000000e+00,8.402476243566864760e-10,0.000000000000000000e+00 +5.421362446960483084e+00,5.675000000000000000e+01,0.000000000000000000e+00,8.614820440626905551e+00,0.000000000000000000e+00,-1.000000009945834156e+00,0.000000000000000000e+00,-1.500458680331938605e-09,0.000000000000000000e+00 +5.422523237260050699e+00,5.675999999999999801e+01,0.000000000000000000e+00,8.613659650315792504e+00,0.000000000000000000e+00,-1.000000009947575874e+00,0.000000000000000000e+00,1.409215950676817759e-09,0.000000000000000000e+00 +5.423684183989543328e+00,5.677000000000000313e+01,0.000000000000000000e+00,8.612498703574750891e+00,0.000000000000000000e+00,-1.000000009945939849e+00,0.000000000000000000e+00,-9.454702263428054183e-10,0.000000000000000000e+00 +5.424845287212217926e+00,5.678000000000000114e+01,0.000000000000000000e+00,8.611337600340528198e+00,0.000000000000000000e+00,-1.000000009947037638e+00,0.000000000000000000e+00,6.900772708735340539e-10,0.000000000000000000e+00 +5.426006546991373192e+00,5.678999999999999915e+01,0.000000000000000000e+00,8.610176340549822172e+00,0.000000000000000000e+00,-1.000000009946236279e+00,0.000000000000000000e+00,-2.418481652898379774e-10,0.000000000000000000e+00 +5.427167963390350458e+00,5.680000000000000426e+01,0.000000000000000000e+00,8.609014924139293257e+00,0.000000000000000000e+00,-1.000000009946517165e+00,0.000000000000000000e+00,2.402862744253629080e-10,0.000000000000000000e+00 +5.428329536472534578e+00,5.681000000000000227e+01,0.000000000000000000e+00,8.607853351045555712e+00,0.000000000000000000e+00,-1.000000009946238055e+00,0.000000000000000000e+00,-4.669372829858419321e-10,0.000000000000000000e+00 +5.429491266301352148e+00,5.682000000000000028e+01,0.000000000000000000e+00,8.606691621205182940e+00,0.000000000000000000e+00,-1.000000009946780510e+00,0.000000000000000000e+00,2.987001535879873711e-10,0.000000000000000000e+00 +5.430653152940274175e+00,5.682999999999999829e+01,0.000000000000000000e+00,8.605529734554703936e+00,0.000000000000000000e+00,-1.000000009946433455e+00,0.000000000000000000e+00,-6.439434586768955122e-11,0.000000000000000000e+00 +5.431815196452813410e+00,5.684000000000000341e+01,0.000000000000000000e+00,8.604367691030606835e+00,0.000000000000000000e+00,-1.000000009946508284e+00,0.000000000000000000e+00,-2.107340427316808007e-10,0.000000000000000000e+00 +5.432977396902525236e+00,5.685000000000000142e+01,0.000000000000000000e+00,8.603205490569335367e+00,0.000000000000000000e+00,-1.000000009946753199e+00,0.000000000000000000e+00,-1.100330129803581129e-10,0.000000000000000000e+00 +5.434139754353008556e+00,5.685999999999999943e+01,0.000000000000000000e+00,8.602043133107290629e+00,0.000000000000000000e+00,-1.000000009946881097e+00,0.000000000000000000e+00,2.674052176654441415e-10,0.000000000000000000e+00 +5.435302268867904907e+00,5.687000000000000455e+01,0.000000000000000000e+00,8.600880618580831083e+00,0.000000000000000000e+00,-1.000000009946570234e+00,0.000000000000000000e+00,-3.626670584885304862e-10,0.000000000000000000e+00 +5.436464940510898458e+00,5.688000000000000256e+01,0.000000000000000000e+00,8.599717946926272560e+00,0.000000000000000000e+00,-1.000000009946991897e+00,0.000000000000000000e+00,6.582118797350235934e-10,0.000000000000000000e+00 +5.437627769345717788e+00,5.689000000000000057e+01,0.000000000000000000e+00,8.598555118079886483e+00,0.000000000000000000e+00,-1.000000009946226509e+00,0.000000000000000000e+00,-5.811795884421748744e-10,0.000000000000000000e+00 +5.438790755436133217e+00,5.689999999999999858e+01,0.000000000000000000e+00,8.597392131977903418e+00,0.000000000000000000e+00,-1.000000009946902413e+00,0.000000000000000000e+00,-1.097677610115098621e-10,0.000000000000000000e+00 +5.439953898845959479e+00,5.691000000000000369e+01,0.000000000000000000e+00,8.596228988556507744e+00,0.000000000000000000e+00,-1.000000009947030088e+00,0.000000000000000000e+00,7.886939586024930932e-10,0.000000000000000000e+00 +5.441117199639053048e+00,5.692000000000000171e+01,0.000000000000000000e+00,8.595065687751842987e+00,0.000000000000000000e+00,-1.000000009946112600e+00,0.000000000000000000e+00,-1.793215291859080615e-09,0.000000000000000000e+00 +5.442280657879313921e+00,5.692999999999999972e+01,0.000000000000000000e+00,8.593902229500010037e+00,0.000000000000000000e+00,-1.000000009948198931e+00,0.000000000000000000e+00,1.361903483586370187e-09,0.000000000000000000e+00 +5.443444273630686503e+00,5.693999999999999773e+01,0.000000000000000000e+00,8.592738613737061826e+00,0.000000000000000000e+00,-1.000000009946614199e+00,0.000000000000000000e+00,-2.138835772047374953e-10,0.000000000000000000e+00 +5.444608046957156944e+00,5.695000000000000284e+01,0.000000000000000000e+00,8.591574840399015756e+00,0.000000000000000000e+00,-1.000000009946863111e+00,0.000000000000000000e+00,7.058537512144881376e-11,0.000000000000000000e+00 +5.445771977922755802e+00,5.696000000000000085e+01,0.000000000000000000e+00,8.590410909421839492e+00,0.000000000000000000e+00,-1.000000009946780954e+00,0.000000000000000000e+00,-3.780574613915030191e-10,0.000000000000000000e+00 +5.446936066591556269e+00,5.696999999999999886e+01,0.000000000000000000e+00,8.589246820741459842e+00,0.000000000000000000e+00,-1.000000009947221047e+00,0.000000000000000000e+00,1.092251101617288403e-09,0.000000000000000000e+00 +5.448100313027675945e+00,5.698000000000000398e+01,0.000000000000000000e+00,8.588082574293759208e+00,0.000000000000000000e+00,-1.000000009945949397e+00,0.000000000000000000e+00,-2.040041632951231472e-09,0.000000000000000000e+00 +5.449264717295275062e+00,5.699000000000000199e+01,0.000000000000000000e+00,8.586918170014579132e+00,0.000000000000000000e+00,-1.000000009948324831e+00,0.000000000000000000e+00,2.047010416134676562e-09,0.000000000000000000e+00 +5.450429279458557374e+00,5.700000000000000000e+01,0.000000000000000000e+00,8.585753607839711421e+00,0.000000000000000000e+00,-1.000000009945940960e+00,0.000000000000000000e+00,-1.025654104095999801e-09,0.000000000000000000e+00 +5.451593999581770156e+00,5.700999999999999801e+01,0.000000000000000000e+00,8.584588887704914129e+00,0.000000000000000000e+00,-1.000000009947135560e+00,0.000000000000000000e+00,-7.489309115047994619e-10,0.000000000000000000e+00 +5.452758877729205089e+00,5.702000000000000313e+01,0.000000000000000000e+00,8.583424009545892019e+00,0.000000000000000000e+00,-1.000000009948007973e+00,0.000000000000000000e+00,1.595812576125682682e-09,0.000000000000000000e+00 +5.453923913965196490e+00,5.703000000000000114e+01,0.000000000000000000e+00,8.582258973298310778e+00,0.000000000000000000e+00,-1.000000009946148793e+00,0.000000000000000000e+00,-5.040429181673918259e-10,0.000000000000000000e+00 +5.455089108354123084e+00,5.703999999999999915e+01,0.000000000000000000e+00,8.581093778897795232e+00,0.000000000000000000e+00,-1.000000009946736101e+00,0.000000000000000000e+00,-4.738693932386532320e-10,0.000000000000000000e+00 +5.456254460960406227e+00,5.705000000000000426e+01,0.000000000000000000e+00,8.579928426279920473e+00,0.000000000000000000e+00,-1.000000009947288326e+00,0.000000000000000000e+00,4.069350882603719522e-10,0.000000000000000000e+00 +5.457419971848512574e+00,5.706000000000000227e+01,0.000000000000000000e+00,8.578762915380220733e+00,0.000000000000000000e+00,-1.000000009946814039e+00,0.000000000000000000e+00,-4.459296040183490204e-10,0.000000000000000000e+00 +5.458585641082951412e+00,5.707000000000000028e+01,0.000000000000000000e+00,8.577597246134187614e+00,0.000000000000000000e+00,-1.000000009947333846e+00,0.000000000000000000e+00,-3.866356659199521693e-10,0.000000000000000000e+00 +5.459751468728275547e+00,5.707999999999999829e+01,0.000000000000000000e+00,8.576431418477266533e+00,0.000000000000000000e+00,-1.000000009947784596e+00,0.000000000000000000e+00,6.149147202597203758e-10,0.000000000000000000e+00 +5.460917454849083086e+00,5.709000000000000341e+01,0.000000000000000000e+00,8.575265432344860272e+00,0.000000000000000000e+00,-1.000000009947067614e+00,0.000000000000000000e+00,-2.380114281315365333e-11,0.000000000000000000e+00 +5.462083599510014764e+00,5.710000000000000142e+01,0.000000000000000000e+00,8.574099287672328984e+00,0.000000000000000000e+00,-1.000000009947095370e+00,0.000000000000000000e+00,-9.648623053842478796e-10,0.000000000000000000e+00 +5.463249902775755729e+00,5.710999999999999943e+01,0.000000000000000000e+00,8.572932984394986633e+00,0.000000000000000000e+00,-1.000000009948220692e+00,0.000000000000000000e+00,1.739295123002570867e-09,0.000000000000000000e+00 +5.464416364711035534e+00,5.712000000000000455e+01,0.000000000000000000e+00,8.571766522448102776e+00,0.000000000000000000e+00,-1.000000009946191870e+00,0.000000000000000000e+00,-1.019795914986619356e-09,0.000000000000000000e+00 +5.465582985380627257e+00,5.713000000000000256e+01,0.000000000000000000e+00,8.570599901766907891e+00,0.000000000000000000e+00,-1.000000009947381585e+00,0.000000000000000000e+00,-7.212580228110128581e-11,0.000000000000000000e+00 +5.466749764849347493e+00,5.714000000000000057e+01,0.000000000000000000e+00,8.569433122286580939e+00,0.000000000000000000e+00,-1.000000009947465740e+00,0.000000000000000000e+00,-6.090851251014793549e-10,0.000000000000000000e+00 +5.467916703182058136e+00,5.714999999999999858e+01,0.000000000000000000e+00,8.568266183942261804e+00,0.000000000000000000e+00,-1.000000009948176505e+00,0.000000000000000000e+00,1.314463006548851313e-09,0.000000000000000000e+00 +5.469083800443665488e+00,5.716000000000000369e+01,0.000000000000000000e+00,8.567099086669044183e+00,0.000000000000000000e+00,-1.000000009946642399e+00,0.000000000000000000e+00,-7.911574751208529562e-10,0.000000000000000000e+00 +5.470251056699118486e+00,5.717000000000000171e+01,0.000000000000000000e+00,8.565931830401980918e+00,0.000000000000000000e+00,-1.000000009947565882e+00,0.000000000000000000e+00,-3.745075310770729517e-10,0.000000000000000000e+00 +5.471418472013411360e+00,5.717999999999999972e+01,0.000000000000000000e+00,8.564764415076075110e+00,0.000000000000000000e+00,-1.000000009948003088e+00,0.000000000000000000e+00,1.289012745550835704e-09,0.000000000000000000e+00 +5.472586046451582753e+00,5.718999999999999773e+01,0.000000000000000000e+00,8.563596840626289008e+00,0.000000000000000000e+00,-1.000000009946498070e+00,0.000000000000000000e+00,-9.800333459561526359e-10,0.000000000000000000e+00 +5.473753780078714826e+00,5.720000000000000284e+01,0.000000000000000000e+00,8.562429106987542227e+00,0.000000000000000000e+00,-1.000000009947642488e+00,0.000000000000000000e+00,6.667652847226548715e-10,0.000000000000000000e+00 +5.474921672959935037e+00,5.721000000000000085e+01,0.000000000000000000e+00,8.561261214094704641e+00,0.000000000000000000e+00,-1.000000009946863777e+00,0.000000000000000000e+00,-1.555383361078696598e-09,0.000000000000000000e+00 +5.476089725160414368e+00,5.721999999999999886e+01,0.000000000000000000e+00,8.560093161882607049e+00,0.000000000000000000e+00,-1.000000009948680546e+00,0.000000000000000000e+00,1.499099839103304198e-09,0.000000000000000000e+00 +5.477257936745369094e+00,5.723000000000000398e+01,0.000000000000000000e+00,8.558924950286030509e+00,0.000000000000000000e+00,-1.000000009946929280e+00,0.000000000000000000e+00,-5.520845332136685791e-10,0.000000000000000000e+00 +5.478426307780059012e+00,5.724000000000000199e+01,0.000000000000000000e+00,8.557756579239718775e+00,0.000000000000000000e+00,-1.000000009947574320e+00,0.000000000000000000e+00,1.305439927254445055e-10,0.000000000000000000e+00 +5.479594838329789219e+00,5.725000000000000000e+01,0.000000000000000000e+00,8.556588048678364089e+00,0.000000000000000000e+00,-1.000000009947421775e+00,0.000000000000000000e+00,-3.241304826994204505e-10,0.000000000000000000e+00 +5.480763528459910106e+00,5.725999999999999801e+01,0.000000000000000000e+00,8.555419358536617835e+00,0.000000000000000000e+00,-1.000000009947800583e+00,0.000000000000000000e+00,7.148513569126999723e-10,0.000000000000000000e+00 +5.481932378235815584e+00,5.727000000000000313e+01,0.000000000000000000e+00,8.554250508749085213e+00,0.000000000000000000e+00,-1.000000009946965029e+00,0.000000000000000000e+00,-6.207321470739659897e-10,0.000000000000000000e+00 +5.483101387722943976e+00,5.728000000000000114e+01,0.000000000000000000e+00,8.553081499250328790e+00,0.000000000000000000e+00,-1.000000009947690671e+00,0.000000000000000000e+00,-3.997743593036493648e-10,0.000000000000000000e+00 +5.484270556986778899e+00,5.728999999999999915e+01,0.000000000000000000e+00,8.551912329974863169e+00,0.000000000000000000e+00,-1.000000009948158075e+00,0.000000000000000000e+00,1.086174228947105717e-10,0.000000000000000000e+00 +5.485439886092849271e+00,5.730000000000000426e+01,0.000000000000000000e+00,8.550743000857160325e+00,0.000000000000000000e+00,-1.000000009948031066e+00,0.000000000000000000e+00,9.360326512603167209e-10,0.000000000000000000e+00 +5.486609375106727526e+00,5.731000000000000227e+01,0.000000000000000000e+00,8.549573511831647821e+00,0.000000000000000000e+00,-1.000000009946936386e+00,0.000000000000000000e+00,-4.840886015416034781e-10,0.000000000000000000e+00 +5.487779024094032287e+00,5.732000000000000028e+01,0.000000000000000000e+00,8.548403862832708811e+00,0.000000000000000000e+00,-1.000000009947502599e+00,0.000000000000000000e+00,-2.232197303151665329e-10,0.000000000000000000e+00 +5.488948833120425697e+00,5.732999999999999829e+01,0.000000000000000000e+00,8.547234053794678488e+00,0.000000000000000000e+00,-1.000000009947763724e+00,0.000000000000000000e+00,-8.473977086741077747e-10,0.000000000000000000e+00 +5.490118802251616081e+00,5.734000000000000341e+01,0.000000000000000000e+00,8.546064084651849413e+00,0.000000000000000000e+00,-1.000000009948755153e+00,0.000000000000000000e+00,1.567613492421602845e-09,0.000000000000000000e+00 +5.491288931553356178e+00,5.735000000000000142e+01,0.000000000000000000e+00,8.544893955338467961e+00,0.000000000000000000e+00,-1.000000009946920843e+00,0.000000000000000000e+00,-7.308582964596638484e-10,0.000000000000000000e+00 +5.492459221091444022e+00,5.735999999999999943e+01,0.000000000000000000e+00,8.543723665788739652e+00,0.000000000000000000e+00,-1.000000009947776158e+00,0.000000000000000000e+00,7.246875189562236920e-11,0.000000000000000000e+00 +5.493629670931722053e+00,5.737000000000000455e+01,0.000000000000000000e+00,8.542553215936818489e+00,0.000000000000000000e+00,-1.000000009947691337e+00,0.000000000000000000e+00,-1.178688828403360006e-09,0.000000000000000000e+00 +5.494800281140078013e+00,5.738000000000000256e+01,0.000000000000000000e+00,8.541382605716817622e+00,0.000000000000000000e+00,-1.000000009949071123e+00,0.000000000000000000e+00,2.028569053863439967e-09,0.000000000000000000e+00 +5.495971051782444938e+00,5.739000000000000057e+01,0.000000000000000000e+00,8.540211835062802237e+00,0.000000000000000000e+00,-1.000000009946696133e+00,0.000000000000000000e+00,-1.937837107279944509e-09,0.000000000000000000e+00 +5.497141982924802051e+00,5.739999999999999858e+01,0.000000000000000000e+00,8.539040903908798441e+00,0.000000000000000000e+00,-1.000000009948965207e+00,0.000000000000000000e+00,1.207024133848731005e-09,0.000000000000000000e+00 +5.498313074633172093e+00,5.741000000000000369e+01,0.000000000000000000e+00,8.537869812188777274e+00,0.000000000000000000e+00,-1.000000009947551671e+00,0.000000000000000000e+00,-1.647439710604114455e-10,0.000000000000000000e+00 +5.499484326973623993e+00,5.742000000000000171e+01,0.000000000000000000e+00,8.536698559836674249e+00,0.000000000000000000e+00,-1.000000009947744628e+00,0.000000000000000000e+00,-8.397188415737769527e-10,0.000000000000000000e+00 +5.500655740012271977e+00,5.742999999999999972e+01,0.000000000000000000e+00,8.535527146786373365e+00,0.000000000000000000e+00,-1.000000009948728286e+00,0.000000000000000000e+00,1.801641526130188105e-09,0.000000000000000000e+00 +5.501827313815275566e+00,5.743999999999999773e+01,0.000000000000000000e+00,8.534355572971714210e+00,0.000000000000000000e+00,-1.000000009946617530e+00,0.000000000000000000e+00,-1.268328594370419963e-09,0.000000000000000000e+00 +5.502999048448839581e+00,5.745000000000000284e+01,0.000000000000000000e+00,8.533183838326495518e+00,0.000000000000000000e+00,-1.000000009948103674e+00,0.000000000000000000e+00,-9.585527269283242751e-10,0.000000000000000000e+00 +5.504170943979214137e+00,5.746000000000000085e+01,0.000000000000000000e+00,8.532011942784462732e+00,0.000000000000000000e+00,-1.000000009949226998e+00,0.000000000000000000e+00,1.466522557815753127e-09,0.000000000000000000e+00 +5.505343000472695536e+00,5.746999999999999886e+01,0.000000000000000000e+00,8.530839886279320439e+00,0.000000000000000000e+00,-1.000000009947508151e+00,0.000000000000000000e+00,-4.271481822373216497e-10,0.000000000000000000e+00 +5.506515217995624489e+00,5.748000000000000398e+01,0.000000000000000000e+00,8.529667668744730591e+00,0.000000000000000000e+00,-1.000000009948008861e+00,0.000000000000000000e+00,-1.409111215610287902e-10,0.000000000000000000e+00 +5.507687596614388781e+00,5.749000000000000199e+01,0.000000000000000000e+00,8.528495290114303629e+00,0.000000000000000000e+00,-1.000000009948174062e+00,0.000000000000000000e+00,-2.295172117165685979e-10,0.000000000000000000e+00 +5.508860136395420604e+00,5.750000000000000000e+01,0.000000000000000000e+00,8.527322750321607359e+00,0.000000000000000000e+00,-1.000000009948443180e+00,0.000000000000000000e+00,6.308962109196424835e-10,0.000000000000000000e+00 +5.510032837405198336e+00,5.750999999999999801e+01,0.000000000000000000e+00,8.526150049300163403e+00,0.000000000000000000e+00,-1.000000009947703328e+00,0.000000000000000000e+00,-1.109406772867837026e-10,0.000000000000000000e+00 +5.511205699710245653e+00,5.752000000000000313e+01,0.000000000000000000e+00,8.524977186983448973e+00,0.000000000000000000e+00,-1.000000009947833446e+00,0.000000000000000000e+00,-1.130076339312750762e-09,0.000000000000000000e+00 +5.512378723377132417e+00,5.753000000000000114e+01,0.000000000000000000e+00,8.523804163304893322e+00,0.000000000000000000e+00,-1.000000009949159052e+00,0.000000000000000000e+00,1.476657020707090022e-09,0.000000000000000000e+00 +5.513551908472473784e+00,5.753999999999999915e+01,0.000000000000000000e+00,8.522630978197879514e+00,0.000000000000000000e+00,-1.000000009947426660e+00,0.000000000000000000e+00,-1.293269049740348759e-09,0.000000000000000000e+00 +5.514725255062931986e+00,5.755000000000000426e+01,0.000000000000000000e+00,8.521457631595749760e+00,0.000000000000000000e+00,-1.000000009948944113e+00,0.000000000000000000e+00,9.169328337213623768e-10,0.000000000000000000e+00 +5.515898763215213663e+00,5.756000000000000227e+01,0.000000000000000000e+00,8.520284123431792977e+00,0.000000000000000000e+00,-1.000000009947868085e+00,0.000000000000000000e+00,3.965387023788355327e-10,0.000000000000000000e+00 +5.517072432996072529e+00,5.757000000000000028e+01,0.000000000000000000e+00,8.519110453639259006e+00,0.000000000000000000e+00,-1.000000009947402679e+00,0.000000000000000000e+00,-1.529755127873248663e-09,0.000000000000000000e+00 +5.518246264472306706e+00,5.757999999999999829e+01,0.000000000000000000e+00,8.517936622151347947e+00,0.000000000000000000e+00,-1.000000009949198354e+00,0.000000000000000000e+00,1.615223038723912221e-09,0.000000000000000000e+00 +5.519420257710762279e+00,5.759000000000000341e+01,0.000000000000000000e+00,8.516762628901211940e+00,0.000000000000000000e+00,-1.000000009947302093e+00,0.000000000000000000e+00,-1.736976445930907321e-09,0.000000000000000000e+00 +5.520594412778330629e+00,5.760000000000000142e+01,0.000000000000000000e+00,8.515588473821964044e+00,0.000000000000000000e+00,-1.000000009949341573e+00,0.000000000000000000e+00,1.333420705349308312e-09,0.000000000000000000e+00 +5.521768729741948434e+00,5.760999999999999943e+01,0.000000000000000000e+00,8.514414156846662252e+00,0.000000000000000000e+00,-1.000000009947775714e+00,0.000000000000000000e+00,-7.378932676920805923e-10,0.000000000000000000e+00 +5.522943208668600334e+00,5.762000000000000455e+01,0.000000000000000000e+00,8.513239677908327252e+00,0.000000000000000000e+00,-1.000000009948642354e+00,0.000000000000000000e+00,-1.888428621972341877e-10,0.000000000000000000e+00 +5.524117849625315380e+00,5.763000000000000256e+01,0.000000000000000000e+00,8.512065036939926443e+00,0.000000000000000000e+00,-1.000000009948864177e+00,0.000000000000000000e+00,4.366034253096280526e-10,0.000000000000000000e+00 +5.525292652679169692e+00,5.764000000000000057e+01,0.000000000000000000e+00,8.510890233874384592e+00,0.000000000000000000e+00,-1.000000009948351254e+00,0.000000000000000000e+00,-1.164115111877222051e-10,0.000000000000000000e+00 +5.526467617897284690e+00,5.764999999999999858e+01,0.000000000000000000e+00,8.509715268644580277e+00,0.000000000000000000e+00,-1.000000009948488033e+00,0.000000000000000000e+00,7.588378041240381489e-10,0.000000000000000000e+00 +5.527642745346829756e+00,5.766000000000000369e+01,0.000000000000000000e+00,8.508540141183344119e+00,0.000000000000000000e+00,-1.000000009947596302e+00,0.000000000000000000e+00,-7.651565508258193927e-10,0.000000000000000000e+00 +5.528818035095020456e+00,5.767000000000000171e+01,0.000000000000000000e+00,8.507364851423462326e+00,0.000000000000000000e+00,-1.000000009948495583e+00,0.000000000000000000e+00,-7.960306965570589199e-10,0.000000000000000000e+00 +5.529993487209117653e+00,5.767999999999999972e+01,0.000000000000000000e+00,8.506189399297671372e+00,0.000000000000000000e+00,-1.000000009949431279e+00,0.000000000000000000e+00,1.982057885735017458e-09,0.000000000000000000e+00 +5.531169101756429285e+00,5.768999999999999773e+01,0.000000000000000000e+00,8.505013784738663318e+00,0.000000000000000000e+00,-1.000000009947101143e+00,0.000000000000000000e+00,-1.394651656389967591e-09,0.000000000000000000e+00 +5.532344878804309474e+00,5.770000000000000284e+01,0.000000000000000000e+00,8.503838007679087596e+00,0.000000000000000000e+00,-1.000000009948740942e+00,0.000000000000000000e+00,-6.121646039169004833e-10,0.000000000000000000e+00 +5.533520818420159415e+00,5.771000000000000085e+01,0.000000000000000000e+00,8.502662068051538569e+00,0.000000000000000000e+00,-1.000000009949460811e+00,0.000000000000000000e+00,5.057872272187251664e-10,0.000000000000000000e+00 +5.534696920671426490e+00,5.771999999999999886e+01,0.000000000000000000e+00,8.501485965788569743e+00,0.000000000000000000e+00,-1.000000009948865953e+00,0.000000000000000000e+00,7.084572224337227072e-10,0.000000000000000000e+00 +5.535873185625605153e+00,5.773000000000000398e+01,0.000000000000000000e+00,8.500309700822688441e+00,0.000000000000000000e+00,-1.000000009948032620e+00,0.000000000000000000e+00,2.812297384796781582e-11,0.000000000000000000e+00 +5.537049613350236044e+00,5.774000000000000199e+01,0.000000000000000000e+00,8.499133273086354023e+00,0.000000000000000000e+00,-1.000000009947999535e+00,0.000000000000000000e+00,-1.499935981075014443e-09,0.000000000000000000e+00 +5.538226203912907764e+00,5.775000000000000000e+01,0.000000000000000000e+00,8.497956682511977888e+00,0.000000000000000000e+00,-1.000000009949764346e+00,0.000000000000000000e+00,1.286694453607166115e-09,0.000000000000000000e+00 +5.539402957381253323e+00,5.775999999999999801e+01,0.000000000000000000e+00,8.496779929031923473e+00,0.000000000000000000e+00,-1.000000009948250224e+00,0.000000000000000000e+00,-5.578865869303983345e-10,0.000000000000000000e+00 +5.540579873822955470e+00,5.777000000000000313e+01,0.000000000000000000e+00,8.495603012578513358e+00,0.000000000000000000e+00,-1.000000009948906809e+00,0.000000000000000000e+00,6.941962357462678945e-10,0.000000000000000000e+00 +5.541756953305741362e+00,5.778000000000000114e+01,0.000000000000000000e+00,8.494425933084016833e+00,0.000000000000000000e+00,-1.000000009948089685e+00,0.000000000000000000e+00,-1.334822304431506247e-09,0.000000000000000000e+00 +5.542934195897386118e+00,5.778999999999999915e+01,0.000000000000000000e+00,8.493248690480660557e+00,0.000000000000000000e+00,-1.000000009949661095e+00,0.000000000000000000e+00,1.078723388604471838e-09,0.000000000000000000e+00 +5.544111601665711930e+00,5.780000000000000426e+01,0.000000000000000000e+00,8.492071284700619671e+00,0.000000000000000000e+00,-1.000000009948391000e+00,0.000000000000000000e+00,2.777516217547851668e-10,0.000000000000000000e+00 +5.545289170678588064e+00,5.781000000000000227e+01,0.000000000000000000e+00,8.490893715676028464e+00,0.000000000000000000e+00,-1.000000009948063928e+00,0.000000000000000000e+00,-1.140263998609305886e-09,0.000000000000000000e+00 +5.546466903003930859e+00,5.782000000000000028e+01,0.000000000000000000e+00,8.489715983338969707e+00,0.000000000000000000e+00,-1.000000009949406854e+00,0.000000000000000000e+00,6.986164410139709974e-10,0.000000000000000000e+00 +5.547644798709702840e+00,5.782999999999999829e+01,0.000000000000000000e+00,8.488538087621478212e+00,0.000000000000000000e+00,-1.000000009948583957e+00,0.000000000000000000e+00,-5.748743962473825073e-10,0.000000000000000000e+00 +5.548822857863914493e+00,5.784000000000000341e+01,0.000000000000000000e+00,8.487360028455546157e+00,0.000000000000000000e+00,-1.000000009949261193e+00,0.000000000000000000e+00,1.931686816984287076e-10,0.000000000000000000e+00 +5.550001080534624265e+00,5.785000000000000142e+01,0.000000000000000000e+00,8.486181805773114206e+00,0.000000000000000000e+00,-1.000000009949033597e+00,0.000000000000000000e+00,4.757884988121821912e-10,0.000000000000000000e+00 +5.551179466789935901e+00,5.785999999999999943e+01,0.000000000000000000e+00,8.485003419506078615e+00,0.000000000000000000e+00,-1.000000009948472934e+00,0.000000000000000000e+00,3.061580002116621173e-10,0.000000000000000000e+00 +5.552358016698001997e+00,5.787000000000000455e+01,0.000000000000000000e+00,8.483824869586287676e+00,0.000000000000000000e+00,-1.000000009948112112e+00,0.000000000000000000e+00,-1.560341220558552330e-09,0.000000000000000000e+00 +5.553536730327022219e+00,5.788000000000000256e+01,0.000000000000000000e+00,8.482646155945541722e+00,0.000000000000000000e+00,-1.000000009949951307e+00,0.000000000000000000e+00,1.301704690342733982e-09,0.000000000000000000e+00 +5.554715607745242423e+00,5.789000000000000057e+01,0.000000000000000000e+00,8.481467278515591346e+00,0.000000000000000000e+00,-1.000000009948416757e+00,0.000000000000000000e+00,-2.372912704313644645e-11,0.000000000000000000e+00 +5.555894649020958198e+00,5.789999999999999858e+01,0.000000000000000000e+00,8.480288237228146286e+00,0.000000000000000000e+00,-1.000000009948444735e+00,0.000000000000000000e+00,-3.890282651156285016e-10,0.000000000000000000e+00 +5.557073854222510434e+00,5.791000000000000369e+01,0.000000000000000000e+00,8.479109032014862990e+00,0.000000000000000000e+00,-1.000000009948903479e+00,0.000000000000000000e+00,-1.039649257234788601e-09,0.000000000000000000e+00 +5.558253223418287980e+00,5.792000000000000171e+01,0.000000000000000000e+00,8.477929662807351718e+00,0.000000000000000000e+00,-1.000000009950129609e+00,0.000000000000000000e+00,1.888314226042198943e-09,0.000000000000000000e+00 +5.559432756676728538e+00,5.792999999999999972e+01,0.000000000000000000e+00,8.476750129537174772e+00,0.000000000000000000e+00,-1.000000009947902280e+00,0.000000000000000000e+00,-1.785847141922951804e-09,0.000000000000000000e+00 +5.560612454066315991e+00,5.793999999999999773e+01,0.000000000000000000e+00,8.475570432135851817e+00,0.000000000000000000e+00,-1.000000009950009039e+00,0.000000000000000000e+00,7.371616513357744472e-10,0.000000000000000000e+00 +5.561792315655582186e+00,5.795000000000000284e+01,0.000000000000000000e+00,8.474390570534845679e+00,0.000000000000000000e+00,-1.000000009949139290e+00,0.000000000000000000e+00,5.554756868746149568e-10,0.000000000000000000e+00 +5.562972341513107821e+00,5.796000000000000085e+01,0.000000000000000000e+00,8.473210544665580102e+00,0.000000000000000000e+00,-1.000000009948483815e+00,0.000000000000000000e+00,-1.019547289738804264e-09,0.000000000000000000e+00 +5.564152531707519778e+00,5.796999999999999886e+01,0.000000000000000000e+00,8.472030354459427315e+00,0.000000000000000000e+00,-1.000000009949687074e+00,0.000000000000000000e+00,1.146760398657790477e-09,0.000000000000000000e+00 +5.565332886307492899e+00,5.798000000000000398e+01,0.000000000000000000e+00,8.470849999847709810e+00,0.000000000000000000e+00,-1.000000009948333490e+00,0.000000000000000000e+00,-5.633315092078181882e-10,0.000000000000000000e+00 +5.566513405381750879e+00,5.799000000000000199e+01,0.000000000000000000e+00,8.469669480761707447e+00,0.000000000000000000e+00,-1.000000009948998514e+00,0.000000000000000000e+00,-1.015736047840087317e-09,0.000000000000000000e+00 +5.567694088999064483e+00,5.800000000000000000e+01,0.000000000000000000e+00,8.468488797132646795e+00,0.000000000000000000e+00,-1.000000009950197777e+00,0.000000000000000000e+00,1.095510698425501295e-09,0.000000000000000000e+00 +5.568874937228253330e+00,5.800999999999999801e+01,0.000000000000000000e+00,8.467307948891708236e+00,0.000000000000000000e+00,-1.000000009948904145e+00,0.000000000000000000e+00,-5.653520985208741590e-10,0.000000000000000000e+00 +5.570055950138184109e+00,5.802000000000000313e+01,0.000000000000000000e+00,8.466126935970027745e+00,0.000000000000000000e+00,-1.000000009949571833e+00,0.000000000000000000e+00,4.039814435285913364e-10,0.000000000000000000e+00 +5.571237127797771471e+00,5.803000000000000114e+01,0.000000000000000000e+00,8.464945758298688006e+00,0.000000000000000000e+00,-1.000000009949094659e+00,0.000000000000000000e+00,2.169053249251692478e-10,0.000000000000000000e+00 +5.572418470275978919e+00,5.803999999999999915e+01,0.000000000000000000e+00,8.463764415808727293e+00,0.000000000000000000e+00,-1.000000009948838420e+00,0.000000000000000000e+00,1.802280563625428935e-10,0.000000000000000000e+00 +5.573599977641817027e+00,5.805000000000000426e+01,0.000000000000000000e+00,8.462582908431134143e+00,0.000000000000000000e+00,-1.000000009948625479e+00,0.000000000000000000e+00,-9.446089306460360183e-10,0.000000000000000000e+00 +5.574781649964346109e+00,5.806000000000000227e+01,0.000000000000000000e+00,8.461401236096849132e+00,0.000000000000000000e+00,-1.000000009949741697e+00,0.000000000000000000e+00,6.927166919521240172e-10,0.000000000000000000e+00 +5.575963487312673550e+00,5.807000000000000028e+01,0.000000000000000000e+00,8.460219398736763097e+00,0.000000000000000000e+00,-1.000000009948923019e+00,0.000000000000000000e+00,-1.233641206777143349e-09,0.000000000000000000e+00 +5.577145489755954699e+00,5.807999999999999829e+01,0.000000000000000000e+00,8.459037396281722465e+00,0.000000000000000000e+00,-1.000000009950381186e+00,0.000000000000000000e+00,9.393296367133905183e-10,0.000000000000000000e+00 +5.578327657363393755e+00,5.809000000000000341e+01,0.000000000000000000e+00,8.457855228662520375e+00,0.000000000000000000e+00,-1.000000009949270741e+00,0.000000000000000000e+00,8.886795952907322006e-10,0.000000000000000000e+00 +5.579509990204243763e+00,5.810000000000000142e+01,0.000000000000000000e+00,8.456672895809907331e+00,0.000000000000000000e+00,-1.000000009948220026e+00,0.000000000000000000e+00,-1.349732876023282117e-09,0.000000000000000000e+00 +5.580692488347804847e+00,5.810999999999999943e+01,0.000000000000000000e+00,8.455490397654582324e+00,0.000000000000000000e+00,-1.000000009949816082e+00,0.000000000000000000e+00,6.098107088532885592e-10,0.000000000000000000e+00 +5.581875151863426865e+00,5.812000000000000455e+01,0.000000000000000000e+00,8.454307734127192830e+00,0.000000000000000000e+00,-1.000000009949094881e+00,0.000000000000000000e+00,-8.203510048629031836e-10,0.000000000000000000e+00 +5.583057980820507638e+00,5.813000000000000256e+01,0.000000000000000000e+00,8.453124905158343694e+00,0.000000000000000000e+00,-1.000000009950065216e+00,0.000000000000000000e+00,7.434681259373343315e-10,0.000000000000000000e+00 +5.584240975288493836e+00,5.814000000000000057e+01,0.000000000000000000e+00,8.451941910678586467e+00,0.000000000000000000e+00,-1.000000009949185698e+00,0.000000000000000000e+00,2.563583267886515320e-10,0.000000000000000000e+00 +5.585424135336880092e+00,5.814999999999999858e+01,0.000000000000000000e+00,8.450758750618428294e+00,0.000000000000000000e+00,-1.000000009948882385e+00,0.000000000000000000e+00,-9.765021799661055308e-10,0.000000000000000000e+00 +5.586607461035210775e+00,5.816000000000000369e+01,0.000000000000000000e+00,8.449575424908324806e+00,0.000000000000000000e+00,-1.000000009950037905e+00,0.000000000000000000e+00,8.834944037670777786e-10,0.000000000000000000e+00 +5.587790952453078219e+00,5.817000000000000171e+01,0.000000000000000000e+00,8.448391933478681892e+00,0.000000000000000000e+00,-1.000000009948992297e+00,0.000000000000000000e+00,-4.706682901444828330e-10,0.000000000000000000e+00 +5.588974609660122717e+00,5.817999999999999972e+01,0.000000000000000000e+00,8.447208276259861037e+00,0.000000000000000000e+00,-1.000000009949549407e+00,0.000000000000000000e+00,6.714852147429240107e-11,0.000000000000000000e+00 +5.590158432726035187e+00,5.818999999999999773e+01,0.000000000000000000e+00,8.446024453182170433e+00,0.000000000000000000e+00,-1.000000009949469915e+00,0.000000000000000000e+00,-1.271142163609545418e-09,0.000000000000000000e+00 +5.591342421720553624e+00,5.820000000000000284e+01,0.000000000000000000e+00,8.444840464175872086e+00,0.000000000000000000e+00,-1.000000009950974933e+00,0.000000000000000000e+00,1.883381842086750132e-09,0.000000000000000000e+00 +5.592526576713465758e+00,5.821000000000000085e+01,0.000000000000000000e+00,8.443656309171176488e+00,0.000000000000000000e+00,-1.000000009948744717e+00,0.000000000000000000e+00,-5.701474589378984368e-10,0.000000000000000000e+00 +5.593710897774608171e+00,5.821999999999999886e+01,0.000000000000000000e+00,8.442471988098251501e+00,0.000000000000000000e+00,-1.000000009949419955e+00,0.000000000000000000e+00,-9.952279841310667263e-10,0.000000000000000000e+00 +5.594895384973866292e+00,5.823000000000000398e+01,0.000000000000000000e+00,8.441287500887208139e+00,0.000000000000000000e+00,-1.000000009950598789e+00,0.000000000000000000e+00,1.904894128468652545e-09,0.000000000000000000e+00 +5.596080038381175292e+00,5.824000000000000199e+01,0.000000000000000000e+00,8.440102847468111236e+00,0.000000000000000000e+00,-1.000000009948342150e+00,0.000000000000000000e+00,-1.959724726407464550e-09,0.000000000000000000e+00 +5.597264858066518300e+00,5.825000000000000000e+01,0.000000000000000000e+00,8.438918027770981212e+00,0.000000000000000000e+00,-1.000000009950664071e+00,0.000000000000000000e+00,1.365262497506666567e-09,0.000000000000000000e+00 +5.598449844099928185e+00,5.825999999999999801e+01,0.000000000000000000e+00,8.437733041725779870e+00,0.000000000000000000e+00,-1.000000009949046254e+00,0.000000000000000000e+00,-7.379925659769047527e-10,0.000000000000000000e+00 +5.599634996551486665e+00,5.827000000000000313e+01,0.000000000000000000e+00,8.436547889262429933e+00,0.000000000000000000e+00,-1.000000009949920887e+00,0.000000000000000000e+00,6.194969841508881323e-10,0.000000000000000000e+00 +5.600820315491325196e+00,5.828000000000000114e+01,0.000000000000000000e+00,8.435362570310797281e+00,0.000000000000000000e+00,-1.000000009949186586e+00,0.000000000000000000e+00,-8.507287495429868810e-10,0.000000000000000000e+00 +5.602005800989624085e+00,5.828999999999999915e+01,0.000000000000000000e+00,8.434177084800703383e+00,0.000000000000000000e+00,-1.000000009950195112e+00,0.000000000000000000e+00,-5.618290555986973693e-11,0.000000000000000000e+00 +5.603191453116613374e+00,5.830000000000000426e+01,0.000000000000000000e+00,8.432991432661916420e+00,0.000000000000000000e+00,-1.000000009950261726e+00,0.000000000000000000e+00,5.076348180465306786e-10,0.000000000000000000e+00 +5.604377271942571959e+00,5.831000000000000227e+01,0.000000000000000000e+00,8.431805613824158385e+00,0.000000000000000000e+00,-1.000000009949659763e+00,0.000000000000000000e+00,-3.862424820271045634e-10,0.000000000000000000e+00 +5.605563257537828470e+00,5.832000000000000028e+01,0.000000000000000000e+00,8.430619628217101535e+00,0.000000000000000000e+00,-1.000000009950117841e+00,0.000000000000000000e+00,1.084995901238146494e-09,0.000000000000000000e+00 +5.606749409972761278e+00,5.832999999999999829e+01,0.000000000000000000e+00,8.429433475770366613e+00,0.000000000000000000e+00,-1.000000009948830870e+00,0.000000000000000000e+00,-1.356054058642282056e-09,0.000000000000000000e+00 +5.607935729317797602e+00,5.834000000000000341e+01,0.000000000000000000e+00,8.428247156413528174e+00,0.000000000000000000e+00,-1.000000009950439583e+00,0.000000000000000000e+00,-1.010581277430434542e-10,0.000000000000000000e+00 +5.609122215643414400e+00,5.835000000000000142e+01,0.000000000000000000e+00,8.427060670076105708e+00,0.000000000000000000e+00,-1.000000009950559487e+00,0.000000000000000000e+00,1.096887683970895759e-09,0.000000000000000000e+00 +5.610308869020138367e+00,5.835999999999999943e+01,0.000000000000000000e+00,8.425874016687574297e+00,0.000000000000000000e+00,-1.000000009949257862e+00,0.000000000000000000e+00,-2.490194343221210938e-10,0.000000000000000000e+00 +5.611495689518545049e+00,5.837000000000000455e+01,0.000000000000000000e+00,8.424687196177359283e+00,0.000000000000000000e+00,-1.000000009949553403e+00,0.000000000000000000e+00,-3.196951685217521274e-10,0.000000000000000000e+00 +5.612682677209261506e+00,5.838000000000000256e+01,0.000000000000000000e+00,8.423500208474832718e+00,0.000000000000000000e+00,-1.000000009949932878e+00,0.000000000000000000e+00,-3.417207601526754750e-10,0.000000000000000000e+00 +5.613869832162963647e+00,5.839000000000000057e+01,0.000000000000000000e+00,8.422313053509318692e+00,0.000000000000000000e+00,-1.000000009950338553e+00,0.000000000000000000e+00,9.793866486968627993e-10,0.000000000000000000e+00 +5.615057154450376231e+00,5.839999999999999858e+01,0.000000000000000000e+00,8.421125731210091558e+00,0.000000000000000000e+00,-1.000000009949175706e+00,0.000000000000000000e+00,-1.361262110215687761e-09,0.000000000000000000e+00 +5.616244644142275533e+00,5.841000000000000369e+01,0.000000000000000000e+00,8.419938241506377707e+00,0.000000000000000000e+00,-1.000000009950792190e+00,0.000000000000000000e+00,2.308958297505631261e-10,0.000000000000000000e+00 +5.617432301309486675e+00,5.842000000000000171e+01,0.000000000000000000e+00,8.418750584327348463e+00,0.000000000000000000e+00,-1.000000009950517965e+00,0.000000000000000000e+00,7.509131338344179911e-10,0.000000000000000000e+00 +5.618620126022884520e+00,5.842999999999999972e+01,0.000000000000000000e+00,8.417562759602130740e+00,0.000000000000000000e+00,-1.000000009949626012e+00,0.000000000000000000e+00,2.349426517516101969e-10,0.000000000000000000e+00 +5.619808118353395443e+00,5.843999999999999773e+01,0.000000000000000000e+00,8.416374767259799938e+00,0.000000000000000000e+00,-1.000000009949346902e+00,0.000000000000000000e+00,-1.280882792160623932e-09,0.000000000000000000e+00 +5.620996278371993782e+00,5.845000000000000284e+01,0.000000000000000000e+00,8.415186607229379945e+00,0.000000000000000000e+00,-1.000000009950868796e+00,0.000000000000000000e+00,1.270611814189410293e-09,0.000000000000000000e+00 +5.622184606149705388e+00,5.846000000000000085e+01,0.000000000000000000e+00,8.413998279439843131e+00,0.000000000000000000e+00,-1.000000009949358892e+00,0.000000000000000000e+00,-8.812690551555699531e-10,0.000000000000000000e+00 +5.623373101757605852e+00,5.846999999999999886e+01,0.000000000000000000e+00,8.412809783820117460e+00,0.000000000000000000e+00,-1.000000009950406277e+00,0.000000000000000000e+00,-1.548587771524196154e-10,0.000000000000000000e+00 +5.624561765266821389e+00,5.848000000000000398e+01,0.000000000000000000e+00,8.411621120299074050e+00,0.000000000000000000e+00,-1.000000009950590352e+00,0.000000000000000000e+00,9.693648908982099067e-10,0.000000000000000000e+00 +5.625750596748527954e+00,5.849000000000000199e+01,0.000000000000000000e+00,8.410432288805537837e+00,0.000000000000000000e+00,-1.000000009949437940e+00,0.000000000000000000e+00,-1.243188835133378951e-09,0.000000000000000000e+00 +5.626939596273952127e+00,5.850000000000000000e+01,0.000000000000000000e+00,8.409243289268284016e+00,0.000000000000000000e+00,-1.000000009950916091e+00,0.000000000000000000e+00,7.821814338170272554e-10,0.000000000000000000e+00 +5.628128763914370225e+00,5.850999999999999801e+01,0.000000000000000000e+00,8.408054121616032717e+00,0.000000000000000000e+00,-1.000000009949985946e+00,0.000000000000000000e+00,-4.577793412386402067e-10,0.000000000000000000e+00 +5.629318099741109194e+00,5.852000000000000313e+01,0.000000000000000000e+00,8.406864785777459659e+00,0.000000000000000000e+00,-1.000000009950530400e+00,0.000000000000000000e+00,9.744168623484114387e-11,0.000000000000000000e+00 +5.630507603825547491e+00,5.853000000000000114e+01,0.000000000000000000e+00,8.405675281681185496e+00,0.000000000000000000e+00,-1.000000009950414492e+00,0.000000000000000000e+00,1.225687764057078420e-09,0.000000000000000000e+00 +5.631697276239112426e+00,5.853999999999999915e+01,0.000000000000000000e+00,8.404485609255782919e+00,0.000000000000000000e+00,-1.000000009948956325e+00,0.000000000000000000e+00,-2.056146862611911964e-09,0.000000000000000000e+00 +5.632887117053282822e+00,5.855000000000000426e+01,0.000000000000000000e+00,8.403295768429774881e+00,0.000000000000000000e+00,-1.000000009951402813e+00,0.000000000000000000e+00,1.580049614859098860e-09,0.000000000000000000e+00 +5.634077126339588126e+00,5.856000000000000227e+01,0.000000000000000000e+00,8.402105759131627494e+00,0.000000000000000000e+00,-1.000000009949522539e+00,0.000000000000000000e+00,-3.766731710472094254e-10,0.000000000000000000e+00 +5.635267304169607527e+00,5.857000000000000028e+01,0.000000000000000000e+00,8.400915581289766010e+00,0.000000000000000000e+00,-1.000000009949970847e+00,0.000000000000000000e+00,-3.633756307486738448e-10,0.000000000000000000e+00 +5.636457650614972614e+00,5.857999999999999829e+01,0.000000000000000000e+00,8.399725234832557064e+00,0.000000000000000000e+00,-1.000000009950403390e+00,0.000000000000000000e+00,-8.529164818613496513e-10,0.000000000000000000e+00 +5.637648165747363826e+00,5.859000000000000341e+01,0.000000000000000000e+00,8.398534719688319328e+00,0.000000000000000000e+00,-1.000000009951418800e+00,0.000000000000000000e+00,1.948581058420178990e-09,0.000000000000000000e+00 +5.638838849638514006e+00,5.860000000000000142e+01,0.000000000000000000e+00,8.397344035785319960e+00,0.000000000000000000e+00,-1.000000009949098656e+00,0.000000000000000000e+00,-1.945880842179183671e-09,0.000000000000000000e+00 +5.640029702360205732e+00,5.860999999999999943e+01,0.000000000000000000e+00,8.396153183051779934e+00,0.000000000000000000e+00,-1.000000009951415914e+00,0.000000000000000000e+00,1.279669602471221171e-09,0.000000000000000000e+00 +5.641220723984273100e+00,5.862000000000000455e+01,0.000000000000000000e+00,8.394962161415859825e+00,0.000000000000000000e+00,-1.000000009949891799e+00,0.000000000000000000e+00,-8.647356046067183416e-10,0.000000000000000000e+00 +5.642411914582601717e+00,5.863000000000000256e+01,0.000000000000000000e+00,8.393770970805679354e+00,0.000000000000000000e+00,-1.000000009950921864e+00,0.000000000000000000e+00,4.228943047470254438e-10,0.000000000000000000e+00 +5.643603274227126043e+00,5.864000000000000057e+01,0.000000000000000000e+00,8.392579611149299623e+00,0.000000000000000000e+00,-1.000000009950418045e+00,0.000000000000000000e+00,1.695809591894162325e-10,0.000000000000000000e+00 +5.644794802989833826e+00,5.864999999999999858e+01,0.000000000000000000e+00,8.391388082374735546e+00,0.000000000000000000e+00,-1.000000009950215984e+00,0.000000000000000000e+00,-3.359462200096895706e-10,0.000000000000000000e+00 +5.645986500942762554e+00,5.866000000000000369e+01,0.000000000000000000e+00,8.390196384409948749e+00,0.000000000000000000e+00,-1.000000009950616331e+00,0.000000000000000000e+00,1.924476770186584433e-10,0.000000000000000000e+00 +5.647178368158002115e+00,5.867000000000000171e+01,0.000000000000000000e+00,8.389004517182849341e+00,0.000000000000000000e+00,-1.000000009950386959e+00,0.000000000000000000e+00,-7.102601667700759312e-10,0.000000000000000000e+00 +5.648370404707692138e+00,5.867999999999999972e+01,0.000000000000000000e+00,8.387812480621297695e+00,0.000000000000000000e+00,-1.000000009951233615e+00,0.000000000000000000e+00,7.420074537644095482e-10,0.000000000000000000e+00 +5.649562610664024653e+00,5.868999999999999773e+01,0.000000000000000000e+00,8.386620274653100893e+00,0.000000000000000000e+00,-1.000000009950348989e+00,0.000000000000000000e+00,8.350121774368558502e-10,0.000000000000000000e+00 +5.650754986099243204e+00,5.870000000000000284e+01,0.000000000000000000e+00,8.385427899206018054e+00,0.000000000000000000e+00,-1.000000009949353341e+00,0.000000000000000000e+00,-1.642788801763266481e-09,0.000000000000000000e+00 +5.651947531085641074e+00,5.871000000000000085e+01,0.000000000000000000e+00,8.384235354207755009e+00,0.000000000000000000e+00,-1.000000009951312441e+00,0.000000000000000000e+00,8.383119043386404390e-10,0.000000000000000000e+00 +5.653140245695564836e+00,5.871999999999999886e+01,0.000000000000000000e+00,8.383042639585962519e+00,0.000000000000000000e+00,-1.000000009950312574e+00,0.000000000000000000e+00,-4.277518780464126982e-10,0.000000000000000000e+00 +5.654333130001410801e+00,5.873000000000000398e+01,0.000000000000000000e+00,8.381849755268246938e+00,0.000000000000000000e+00,-1.000000009950822832e+00,0.000000000000000000e+00,-4.100101371941266586e-10,0.000000000000000000e+00 +5.655526184075627683e+00,5.874000000000000199e+01,0.000000000000000000e+00,8.380656701182157775e+00,0.000000000000000000e+00,-1.000000009951311997e+00,0.000000000000000000e+00,9.265319559400789037e-10,0.000000000000000000e+00 +5.656719407990716597e+00,5.875000000000000000e+01,0.000000000000000000e+00,8.379463477255194803e+00,0.000000000000000000e+00,-1.000000009950206437e+00,0.000000000000000000e+00,-1.248472435042166072e-10,0.000000000000000000e+00 +5.657912801819228399e+00,5.875999999999999801e+01,0.000000000000000000e+00,8.378270083414808056e+00,0.000000000000000000e+00,-1.000000009950355429e+00,0.000000000000000000e+00,-1.032308032230949992e-09,0.000000000000000000e+00 +5.659106365633767233e+00,5.877000000000000313e+01,0.000000000000000000e+00,8.377076519588392500e+00,0.000000000000000000e+00,-1.000000009951587554e+00,0.000000000000000000e+00,7.338033929333011467e-10,0.000000000000000000e+00 +5.660300099506988758e+00,5.878000000000000114e+01,0.000000000000000000e+00,8.375882785703291589e+00,0.000000000000000000e+00,-1.000000009950711588e+00,0.000000000000000000e+00,2.222484402939580558e-10,0.000000000000000000e+00 +5.661494003511599260e+00,5.878999999999999915e+01,0.000000000000000000e+00,8.374688881686800812e+00,0.000000000000000000e+00,-1.000000009950446245e+00,0.000000000000000000e+00,-3.737704513049437654e-11,0.000000000000000000e+00 +5.662688077720358315e+00,5.880000000000000426e+01,0.000000000000000000e+00,8.373494807466160594e+00,0.000000000000000000e+00,-1.000000009950490876e+00,0.000000000000000000e+00,-8.180873124008748681e-12,0.000000000000000000e+00 +5.663882322206076125e+00,5.881000000000000227e+01,0.000000000000000000e+00,8.372300562968559845e+00,0.000000000000000000e+00,-1.000000009950500646e+00,0.000000000000000000e+00,-8.993958938417343819e-10,0.000000000000000000e+00 +5.665076737041615296e+00,5.882000000000000028e+01,0.000000000000000000e+00,8.371106148121135959e+00,0.000000000000000000e+00,-1.000000009951574897e+00,0.000000000000000000e+00,1.059864357535172259e-09,0.000000000000000000e+00 +5.666271322299889945e+00,5.882999999999999829e+01,0.000000000000000000e+00,8.369911562850973041e+00,0.000000000000000000e+00,-1.000000009950308799e+00,0.000000000000000000e+00,-3.179882731360719703e-10,0.000000000000000000e+00 +5.667466078053867484e+00,5.884000000000000341e+01,0.000000000000000000e+00,8.368716807085107234e+00,0.000000000000000000e+00,-1.000000009950688717e+00,0.000000000000000000e+00,-1.728152427957574272e-11,0.000000000000000000e+00 +5.668661004376566837e+00,5.885000000000000142e+01,0.000000000000000000e+00,8.367521880750517838e+00,0.000000000000000000e+00,-1.000000009950709368e+00,0.000000000000000000e+00,-4.908738484342226515e-10,0.000000000000000000e+00 +5.669856101341058441e+00,5.885999999999999943e+01,0.000000000000000000e+00,8.366326783774134412e+00,0.000000000000000000e+00,-1.000000009951296009e+00,0.000000000000000000e+00,7.856203680618637292e-10,0.000000000000000000e+00 +5.671051369020465138e+00,5.887000000000000455e+01,0.000000000000000000e+00,8.365131516082833230e+00,0.000000000000000000e+00,-1.000000009950356983e+00,0.000000000000000000e+00,-1.124861014587478053e-09,0.000000000000000000e+00 +5.672246807487962172e+00,5.888000000000000256e+01,0.000000000000000000e+00,8.363936077603440822e+00,0.000000000000000000e+00,-1.000000009951701685e+00,0.000000000000000000e+00,1.272902180902013379e-09,0.000000000000000000e+00 +5.673442416816778078e+00,5.889000000000000057e+01,0.000000000000000000e+00,8.362740468262726878e+00,0.000000000000000000e+00,-1.000000009950179791e+00,0.000000000000000000e+00,-6.846395474210326093e-10,0.000000000000000000e+00 +5.674638197080192015e+00,5.889999999999999858e+01,0.000000000000000000e+00,8.361544687987414903e+00,0.000000000000000000e+00,-1.000000009950998470e+00,0.000000000000000000e+00,-7.467389536738395842e-10,0.000000000000000000e+00 +5.675834148351536435e+00,5.891000000000000369e+01,0.000000000000000000e+00,8.360348736704169781e+00,0.000000000000000000e+00,-1.000000009951891533e+00,0.000000000000000000e+00,1.121618954761740445e-09,0.000000000000000000e+00 +5.677030270704196191e+00,5.892000000000000171e+01,0.000000000000000000e+00,8.359152614339606657e+00,0.000000000000000000e+00,-1.000000009950549940e+00,0.000000000000000000e+00,-1.002296559469903479e-11,0.000000000000000000e+00 +5.678226564211608540e+00,5.892999999999999972e+01,0.000000000000000000e+00,8.357956320820290941e+00,0.000000000000000000e+00,-1.000000009950561930e+00,0.000000000000000000e+00,-3.789623461062382178e-10,0.000000000000000000e+00 +5.679423028947263141e+00,5.893999999999999773e+01,0.000000000000000000e+00,8.356759856072731196e+00,0.000000000000000000e+00,-1.000000009951015345e+00,0.000000000000000000e+00,5.065715493097434520e-11,0.000000000000000000e+00 +5.680619664984702055e+00,5.895000000000000284e+01,0.000000000000000000e+00,8.355563220023384474e+00,0.000000000000000000e+00,-1.000000009950954727e+00,0.000000000000000000e+00,7.476890168488345523e-11,0.000000000000000000e+00 +5.681816472397520634e+00,5.896000000000000085e+01,0.000000000000000000e+00,8.354366412598656311e+00,0.000000000000000000e+00,-1.000000009950865243e+00,0.000000000000000000e+00,-2.687955842762924144e-10,0.000000000000000000e+00 +5.683013451259366633e+00,5.896999999999999886e+01,0.000000000000000000e+00,8.353169433724898951e+00,0.000000000000000000e+00,-1.000000009951186986e+00,0.000000000000000000e+00,2.958368049819351705e-10,0.000000000000000000e+00 +5.684210601643941096e+00,5.898000000000000398e+01,0.000000000000000000e+00,8.351972283328411351e+00,0.000000000000000000e+00,-1.000000009950832824e+00,0.000000000000000000e+00,-6.730018190781184709e-10,0.000000000000000000e+00 +5.685407923624997473e+00,5.899000000000000199e+01,0.000000000000000000e+00,8.350774961335440949e+00,0.000000000000000000e+00,-1.000000009951638624e+00,0.000000000000000000e+00,5.796368391738268541e-10,0.000000000000000000e+00 +5.686605417276341612e+00,5.900000000000000000e+01,0.000000000000000000e+00,8.349577467672180120e+00,0.000000000000000000e+00,-1.000000009950944513e+00,0.000000000000000000e+00,-8.654372245307792189e-10,0.000000000000000000e+00 +5.687803082671832655e+00,5.900999999999999801e+01,0.000000000000000000e+00,8.348379802264771499e+00,0.000000000000000000e+00,-1.000000009951981017e+00,0.000000000000000000e+00,1.221967408516308378e-09,0.000000000000000000e+00 +5.689000919885382146e+00,5.902000000000000313e+01,0.000000000000000000e+00,8.347181965039300877e+00,0.000000000000000000e+00,-1.000000009950517299e+00,0.000000000000000000e+00,-5.502883316621894291e-10,0.000000000000000000e+00 +5.690198928990955807e+00,5.903000000000000114e+01,0.000000000000000000e+00,8.345983955921806086e+00,0.000000000000000000e+00,-1.000000009951176549e+00,0.000000000000000000e+00,4.447633704487937215e-11,0.000000000000000000e+00 +5.691397110062572651e+00,5.903999999999999915e+01,0.000000000000000000e+00,8.344785774838266335e+00,0.000000000000000000e+00,-1.000000009951123259e+00,0.000000000000000000e+00,-6.685316095293206891e-10,0.000000000000000000e+00 +5.692595463174303205e+00,5.905000000000000426e+01,0.000000000000000000e+00,8.343587421714611096e+00,0.000000000000000000e+00,-1.000000009951924396e+00,0.000000000000000000e+00,1.057862335018598603e-09,0.000000000000000000e+00 +5.693793988400272177e+00,5.906000000000000227e+01,0.000000000000000000e+00,8.342388896476714777e+00,0.000000000000000000e+00,-1.000000009950656521e+00,0.000000000000000000e+00,-9.217455054526120148e-10,0.000000000000000000e+00 +5.694992685814656674e+00,5.907000000000000028e+01,0.000000000000000000e+00,8.341190199050402043e+00,0.000000000000000000e+00,-1.000000009951761415e+00,0.000000000000000000e+00,8.480840456892965927e-10,0.000000000000000000e+00 +5.696191555491688874e+00,5.907999999999999829e+01,0.000000000000000000e+00,8.339991329361438943e+00,0.000000000000000000e+00,-1.000000009950744673e+00,0.000000000000000000e+00,-1.011480513590172208e-09,0.000000000000000000e+00 +5.697390597505652465e+00,5.909000000000000341e+01,0.000000000000000000e+00,8.338792287335543563e+00,0.000000000000000000e+00,-1.000000009951957480e+00,0.000000000000000000e+00,9.509734597069685607e-10,0.000000000000000000e+00 +5.698589811930886206e+00,5.910000000000000142e+01,0.000000000000000000e+00,8.337593072898375368e+00,0.000000000000000000e+00,-1.000000009950817059e+00,0.000000000000000000e+00,-6.392599534325713515e-10,0.000000000000000000e+00 +5.699789198841781257e+00,5.910999999999999943e+01,0.000000000000000000e+00,8.336393685975545864e+00,0.000000000000000000e+00,-1.000000009951583779e+00,0.000000000000000000e+00,4.305545190059571544e-10,0.000000000000000000e+00 +5.700988758312782068e+00,5.912000000000000455e+01,0.000000000000000000e+00,8.335194126492607936e+00,0.000000000000000000e+00,-1.000000009951067304e+00,0.000000000000000000e+00,-7.404990332048760225e-10,0.000000000000000000e+00 +5.702188490418386380e+00,5.913000000000000256e+01,0.000000000000000000e+00,8.333994394375064729e+00,0.000000000000000000e+00,-1.000000009951955704e+00,0.000000000000000000e+00,8.218152626286925537e-10,0.000000000000000000e+00 +5.703388395233147001e+00,5.914000000000000057e+01,0.000000000000000000e+00,8.332794489548362549e+00,0.000000000000000000e+00,-1.000000009950969604e+00,0.000000000000000000e+00,-1.014493204691683716e-09,0.000000000000000000e+00 +5.704588472831670032e+00,5.914999999999999858e+01,0.000000000000000000e+00,8.331594411937897959e+00,0.000000000000000000e+00,-1.000000009952187074e+00,0.000000000000000000e+00,1.189540734109166470e-09,0.000000000000000000e+00 +5.705788723288613973e+00,5.916000000000000369e+01,0.000000000000000000e+00,8.330394161469008907e+00,0.000000000000000000e+00,-1.000000009950759328e+00,0.000000000000000000e+00,-1.160328779168275692e-09,0.000000000000000000e+00 +5.706989146678692393e+00,5.917000000000000171e+01,0.000000000000000000e+00,8.329193738066985375e+00,0.000000000000000000e+00,-1.000000009952152213e+00,0.000000000000000000e+00,6.034763614895538491e-10,0.000000000000000000e+00 +5.708189743076672151e+00,5.917999999999999972e+01,0.000000000000000000e+00,8.327993141657056952e+00,0.000000000000000000e+00,-1.000000009951427682e+00,0.000000000000000000e+00,3.546738646264698730e-10,0.000000000000000000e+00 +5.709390512557374286e+00,5.918999999999999773e+01,0.000000000000000000e+00,8.326792372164405265e+00,0.000000000000000000e+00,-1.000000009951001800e+00,0.000000000000000000e+00,-6.345491115060272803e-10,0.000000000000000000e+00 +5.710591455195674015e+00,5.920000000000000284e+01,0.000000000000000000e+00,8.325591429514155095e+00,0.000000000000000000e+00,-1.000000009951763857e+00,0.000000000000000000e+00,1.364305662883468555e-10,0.000000000000000000e+00 +5.711792571066499846e+00,5.921000000000000085e+01,0.000000000000000000e+00,8.324390313631376159e+00,0.000000000000000000e+00,-1.000000009951599989e+00,0.000000000000000000e+00,2.417688833629103886e-10,0.000000000000000000e+00 +5.712993860244834465e+00,5.921999999999999886e+01,0.000000000000000000e+00,8.323189024441086659e+00,0.000000000000000000e+00,-1.000000009951309554e+00,0.000000000000000000e+00,-2.796204377814995889e-10,0.000000000000000000e+00 +5.714195322805715627e+00,5.923000000000000398e+01,0.000000000000000000e+00,8.321987561868249728e+00,0.000000000000000000e+00,-1.000000009951645508e+00,0.000000000000000000e+00,-1.598392360916641867e-10,0.000000000000000000e+00 +5.715396958824233486e+00,5.924000000000000199e+01,0.000000000000000000e+00,8.320785925837773433e+00,0.000000000000000000e+00,-1.000000009951837576e+00,0.000000000000000000e+00,6.394493843170263846e-10,0.000000000000000000e+00 +5.716598768375534156e+00,5.925000000000000000e+01,0.000000000000000000e+00,8.319584116274512553e+00,0.000000000000000000e+00,-1.000000009951069080e+00,0.000000000000000000e+00,-3.040686692520965691e-10,0.000000000000000000e+00 +5.717800751534817039e+00,5.925999999999999801e+01,0.000000000000000000e+00,8.318382133103268572e+00,0.000000000000000000e+00,-1.000000009951434565e+00,0.000000000000000000e+00,-4.920546193295984196e-10,0.000000000000000000e+00 +5.719002908377336603e+00,5.927000000000000313e+01,0.000000000000000000e+00,8.317179976248786133e+00,0.000000000000000000e+00,-1.000000009952026092e+00,0.000000000000000000e+00,1.126538814569091131e-10,0.000000000000000000e+00 +5.720205238978400608e+00,5.928000000000000114e+01,0.000000000000000000e+00,8.315977645635756588e+00,0.000000000000000000e+00,-1.000000009951890645e+00,0.000000000000000000e+00,3.190783053698928317e-10,0.000000000000000000e+00 +5.721407743413371882e+00,5.928999999999999915e+01,0.000000000000000000e+00,8.314775141188817997e+00,0.000000000000000000e+00,-1.000000009951506952e+00,0.000000000000000000e+00,1.654240861294105480e-10,0.000000000000000000e+00 +5.722610421757668320e+00,5.930000000000000426e+01,0.000000000000000000e+00,8.313572462832553356e+00,0.000000000000000000e+00,-1.000000009951308000e+00,0.000000000000000000e+00,-3.090177070404308668e-10,0.000000000000000000e+00 +5.723813274086761105e+00,5.931000000000000227e+01,0.000000000000000000e+00,8.312369610491490590e+00,0.000000000000000000e+00,-1.000000009951679703e+00,0.000000000000000000e+00,1.607619355578757386e-10,0.000000000000000000e+00 +5.725016300476177378e+00,5.932000000000000028e+01,0.000000000000000000e+00,8.311166584090102560e+00,0.000000000000000000e+00,-1.000000009951486302e+00,0.000000000000000000e+00,-8.413405185174034003e-10,0.000000000000000000e+00 +5.726219501001497569e+00,5.932999999999999829e+01,0.000000000000000000e+00,8.309963383552808835e+00,0.000000000000000000e+00,-1.000000009952498603e+00,0.000000000000000000e+00,4.040949754808986454e-10,0.000000000000000000e+00 +5.727422875738358066e+00,5.934000000000000341e+01,0.000000000000000000e+00,8.308760008803972141e+00,0.000000000000000000e+00,-1.000000009952012325e+00,0.000000000000000000e+00,2.544138244995481634e-10,0.000000000000000000e+00 +5.728626424762448544e+00,5.935000000000000142e+01,0.000000000000000000e+00,8.307556459767903689e+00,0.000000000000000000e+00,-1.000000009951706126e+00,0.000000000000000000e+00,-2.471828443282084779e-11,0.000000000000000000e+00 +5.729830148149515523e+00,5.935999999999999943e+01,0.000000000000000000e+00,8.306352736368857848e+00,0.000000000000000000e+00,-1.000000009951735880e+00,0.000000000000000000e+00,-3.945130556258332991e-10,0.000000000000000000e+00 +5.731034045975358815e+00,5.937000000000000455e+01,0.000000000000000000e+00,8.305148838531033917e+00,0.000000000000000000e+00,-1.000000009952210833e+00,0.000000000000000000e+00,4.084711386319881767e-10,0.000000000000000000e+00 +5.732238118315833297e+00,5.938000000000000256e+01,0.000000000000000000e+00,8.303944766178576131e+00,0.000000000000000000e+00,-1.000000009951719004e+00,0.000000000000000000e+00,-2.839523047785121144e-11,0.000000000000000000e+00 +5.733442365246849803e+00,5.939000000000000057e+01,0.000000000000000000e+00,8.302740519235575434e+00,0.000000000000000000e+00,-1.000000009951753199e+00,0.000000000000000000e+00,7.842583953105583683e-10,0.000000000000000000e+00 +5.734646786844373345e+00,5.939999999999999858e+01,0.000000000000000000e+00,8.301536097626065924e+00,0.000000000000000000e+00,-1.000000009950808622e+00,0.000000000000000000e+00,-2.012895942950546272e-09,0.000000000000000000e+00 +5.735851383184424002e+00,5.941000000000000369e+01,0.000000000000000000e+00,8.300331501274028412e+00,0.000000000000000000e+00,-1.000000009953233349e+00,0.000000000000000000e+00,1.412508790505121669e-09,0.000000000000000000e+00 +5.737056154343077807e+00,5.942000000000000171e+01,0.000000000000000000e+00,8.299126730103383309e+00,0.000000000000000000e+00,-1.000000009951531599e+00,0.000000000000000000e+00,8.145071316757890007e-11,0.000000000000000000e+00 +5.738261100396464975e+00,5.942999999999999972e+01,0.000000000000000000e+00,8.297921784038004844e+00,0.000000000000000000e+00,-1.000000009951433455e+00,0.000000000000000000e+00,-1.069207835885877809e-09,0.000000000000000000e+00 +5.739466221420771674e+00,5.943999999999999773e+01,0.000000000000000000e+00,8.296716663001705072e+00,0.000000000000000000e+00,-1.000000009952721980e+00,0.000000000000000000e+00,4.436116746055619212e-10,0.000000000000000000e+00 +5.740671517492240028e+00,5.945000000000000284e+01,0.000000000000000000e+00,8.295511366918240981e+00,0.000000000000000000e+00,-1.000000009952187296e+00,0.000000000000000000e+00,9.893239905460285832e-10,0.000000000000000000e+00 +5.741876988687165451e+00,5.946000000000000085e+01,0.000000000000000000e+00,8.294305895711318044e+00,0.000000000000000000e+00,-1.000000009950994695e+00,0.000000000000000000e+00,-6.143930801470567428e-10,0.000000000000000000e+00 +5.743082635081901088e+00,5.946999999999999886e+01,0.000000000000000000e+00,8.293100249304584892e+00,0.000000000000000000e+00,-1.000000009951735436e+00,0.000000000000000000e+00,-6.612604462941709764e-10,0.000000000000000000e+00 +5.744288456752854266e+00,5.948000000000000398e+01,0.000000000000000000e+00,8.291894427621631536e+00,0.000000000000000000e+00,-1.000000009952532798e+00,0.000000000000000000e+00,-3.358294850204636198e-10,0.000000000000000000e+00 +5.745494453776488264e+00,5.949000000000000199e+01,0.000000000000000000e+00,8.290688430585994695e+00,0.000000000000000000e+00,-1.000000009952937807e+00,0.000000000000000000e+00,1.621467042780576349e-09,0.000000000000000000e+00 +5.746700626229322317e+00,5.950000000000000000e+01,0.000000000000000000e+00,8.289482258121156022e+00,0.000000000000000000e+00,-1.000000009950982038e+00,0.000000000000000000e+00,-8.542386167307356093e-10,0.000000000000000000e+00 +5.747906974187929841e+00,5.950999999999999801e+01,0.000000000000000000e+00,8.288275910150543879e+00,0.000000000000000000e+00,-1.000000009952012547e+00,0.000000000000000000e+00,-3.989915547554540648e-10,0.000000000000000000e+00 +5.749113497728941979e+00,5.952000000000000313e+01,0.000000000000000000e+00,8.287069386597524456e+00,0.000000000000000000e+00,-1.000000009952493940e+00,0.000000000000000000e+00,5.840474378140512940e-10,0.000000000000000000e+00 +5.750320196929044059e+00,5.953000000000000114e+01,0.000000000000000000e+00,8.285862687385412428e+00,0.000000000000000000e+00,-1.000000009951789171e+00,0.000000000000000000e+00,-3.057799299640463374e-10,0.000000000000000000e+00 +5.751527071864978247e+00,5.953999999999999915e+01,0.000000000000000000e+00,8.284655812437467404e+00,0.000000000000000000e+00,-1.000000009952158209e+00,0.000000000000000000e+00,-5.890281132053758891e-10,0.000000000000000000e+00 +5.752734122613542667e+00,5.955000000000000426e+01,0.000000000000000000e+00,8.283448761676890371e+00,0.000000000000000000e+00,-1.000000009952869195e+00,0.000000000000000000e+00,9.913800630520706416e-10,0.000000000000000000e+00 +5.753941349251590509e+00,5.956000000000000227e+01,0.000000000000000000e+00,8.282241535026827250e+00,0.000000000000000000e+00,-1.000000009951672375e+00,0.000000000000000000e+00,-4.005400913895324575e-10,0.000000000000000000e+00 +5.755148751856031808e+00,5.957000000000000028e+01,0.000000000000000000e+00,8.281034132410370674e+00,0.000000000000000000e+00,-1.000000009952155988e+00,0.000000000000000000e+00,1.494911028221331001e-10,0.000000000000000000e+00 +5.756356330503831664e+00,5.957999999999999829e+01,0.000000000000000000e+00,8.279826553750552875e+00,0.000000000000000000e+00,-1.000000009951975466e+00,0.000000000000000000e+00,-9.744001324669222742e-10,0.000000000000000000e+00 +5.757564085272012022e+00,5.959000000000000341e+01,0.000000000000000000e+00,8.278618798970352799e+00,0.000000000000000000e+00,-1.000000009953152302e+00,0.000000000000000000e+00,1.138411281287852091e-09,0.000000000000000000e+00 +5.758772016237651670e+00,5.960000000000000142e+01,0.000000000000000000e+00,8.277410867992690768e+00,0.000000000000000000e+00,-1.000000009951777180e+00,0.000000000000000000e+00,-7.781899039623019926e-10,0.000000000000000000e+00 +5.759980123477884462e+00,5.960999999999999943e+01,0.000000000000000000e+00,8.276202760740435593e+00,0.000000000000000000e+00,-1.000000009952717317e+00,0.000000000000000000e+00,6.193002400610774196e-10,0.000000000000000000e+00 +5.761188407069900208e+00,5.962000000000000455e+01,0.000000000000000000e+00,8.274994477136393911e+00,0.000000000000000000e+00,-1.000000009951969027e+00,0.000000000000000000e+00,-7.143880715233818653e-10,0.000000000000000000e+00 +5.762396867090946451e+00,5.963000000000000256e+01,0.000000000000000000e+00,8.273786017103320845e+00,0.000000000000000000e+00,-1.000000009952832336e+00,0.000000000000000000e+00,1.342405174286608660e-09,0.000000000000000000e+00 +5.763605503618326686e+00,5.964000000000000057e+01,0.000000000000000000e+00,8.272577380563911120e+00,0.000000000000000000e+00,-1.000000009951209856e+00,0.000000000000000000e+00,-1.683134221732876318e-09,0.000000000000000000e+00 +5.764814316729400367e+00,5.964999999999999858e+01,0.000000000000000000e+00,8.271368567440807951e+00,0.000000000000000000e+00,-1.000000009953244451e+00,0.000000000000000000e+00,1.190676056033596267e-09,0.000000000000000000e+00 +5.766023306501584678e+00,5.966000000000000369e+01,0.000000000000000000e+00,8.270159577656590599e+00,0.000000000000000000e+00,-1.000000009951804936e+00,0.000000000000000000e+00,-9.361683323415205185e-10,0.000000000000000000e+00 +5.767232473012351868e+00,5.967000000000000171e+01,0.000000000000000000e+00,8.268950411133790368e+00,0.000000000000000000e+00,-1.000000009952936919e+00,0.000000000000000000e+00,4.823371198014673505e-10,0.000000000000000000e+00 +5.768441816339231032e+00,5.967999999999999972e+01,0.000000000000000000e+00,8.267741067794874610e+00,0.000000000000000000e+00,-1.000000009952353608e+00,0.000000000000000000e+00,6.258267082362485070e-10,0.000000000000000000e+00 +5.769651336559808996e+00,5.968999999999999773e+01,0.000000000000000000e+00,8.266531547562259163e+00,0.000000000000000000e+00,-1.000000009951596658e+00,0.000000000000000000e+00,-1.678416616155626734e-09,0.000000000000000000e+00 +5.770861033751728542e+00,5.970000000000000284e+01,0.000000000000000000e+00,8.265321850358301248e+00,0.000000000000000000e+00,-1.000000009953627034e+00,0.000000000000000000e+00,8.924918617101965366e-10,0.000000000000000000e+00 +5.772070907992689293e+00,5.971000000000000085e+01,0.000000000000000000e+00,8.264111976105297686e+00,0.000000000000000000e+00,-1.000000009952547231e+00,0.000000000000000000e+00,1.094578382098545612e-09,0.000000000000000000e+00 +5.773280959360448605e+00,5.971999999999999886e+01,0.000000000000000000e+00,8.262901924725495562e+00,0.000000000000000000e+00,-1.000000009951222735e+00,0.000000000000000000e+00,-1.029652043661665989e-09,0.000000000000000000e+00 +5.774491187932819791e+00,5.973000000000000398e+01,0.000000000000000000e+00,8.261691696141081565e+00,0.000000000000000000e+00,-1.000000009952468849e+00,0.000000000000000000e+00,-5.879457340125997208e-10,0.000000000000000000e+00 +5.775701593787673005e+00,5.974000000000000199e+01,0.000000000000000000e+00,8.260481290274181987e+00,0.000000000000000000e+00,-1.000000009953180502e+00,0.000000000000000000e+00,3.209841783031701158e-11,0.000000000000000000e+00 +5.776912177002936133e+00,5.975000000000000000e+01,0.000000000000000000e+00,8.259270707046869830e+00,0.000000000000000000e+00,-1.000000009953141644e+00,0.000000000000000000e+00,8.709316953795639349e-10,0.000000000000000000e+00 +5.778122937656593905e+00,5.975999999999999801e+01,0.000000000000000000e+00,8.258059946381161254e+00,0.000000000000000000e+00,-1.000000009952087154e+00,0.000000000000000000e+00,-4.551138307755229184e-10,0.000000000000000000e+00 +5.779333875826687894e+00,5.977000000000000313e+01,0.000000000000000000e+00,8.256849008199015572e+00,0.000000000000000000e+00,-1.000000009952638269e+00,0.000000000000000000e+00,-2.696914889424195971e-10,0.000000000000000000e+00 +5.780544991591318293e+00,5.978000000000000114e+01,0.000000000000000000e+00,8.255637892422331703e+00,0.000000000000000000e+00,-1.000000009952964897e+00,0.000000000000000000e+00,2.542537237812897547e-10,0.000000000000000000e+00 +5.781756285028640363e+00,5.978999999999999915e+01,0.000000000000000000e+00,8.254426598972953499e+00,0.000000000000000000e+00,-1.000000009952656921e+00,0.000000000000000000e+00,1.156712198604877084e-09,0.000000000000000000e+00 +5.782967756216868871e+00,5.980000000000000426e+01,0.000000000000000000e+00,8.253215127772667969e+00,0.000000000000000000e+00,-1.000000009951255597e+00,0.000000000000000000e+00,-1.152144235756641814e-09,0.000000000000000000e+00 +5.784179405234274540e+00,5.981000000000000227e+01,0.000000000000000000e+00,8.252003478743205278e+00,0.000000000000000000e+00,-1.000000009952651592e+00,0.000000000000000000e+00,-5.806599428867458563e-10,0.000000000000000000e+00 +5.785391232159185826e+00,5.982000000000000028e+01,0.000000000000000000e+00,8.250791651806233418e+00,0.000000000000000000e+00,-1.000000009953355251e+00,0.000000000000000000e+00,4.889724829186999698e-10,0.000000000000000000e+00 +5.786603237069988914e+00,5.982999999999999829e+01,0.000000000000000000e+00,8.249579646883367090e+00,0.000000000000000000e+00,-1.000000009952762614e+00,0.000000000000000000e+00,-3.200110319646674355e-10,0.000000000000000000e+00 +5.787815420045127723e+00,5.984000000000000341e+01,0.000000000000000000e+00,8.248367463896164153e+00,0.000000000000000000e+00,-1.000000009953150526e+00,0.000000000000000000e+00,6.593419781270301905e-10,0.000000000000000000e+00 +5.789027781163103015e+00,5.985000000000000142e+01,0.000000000000000000e+00,8.247155102766122070e+00,0.000000000000000000e+00,-1.000000009952351165e+00,0.000000000000000000e+00,-1.582188160218473770e-10,0.000000000000000000e+00 +5.790240320502474169e+00,5.985999999999999943e+01,0.000000000000000000e+00,8.245942563414683235e+00,0.000000000000000000e+00,-1.000000009952543012e+00,0.000000000000000000e+00,-3.151094308070738732e-10,0.000000000000000000e+00 +5.791453038141858300e+00,5.987000000000000455e+01,0.000000000000000000e+00,8.244729845763229648e+00,0.000000000000000000e+00,-1.000000009952925151e+00,0.000000000000000000e+00,2.282880133301189719e-10,0.000000000000000000e+00 +5.792665934159929364e+00,5.988000000000000256e+01,0.000000000000000000e+00,8.243516949733086463e+00,0.000000000000000000e+00,-1.000000009952648261e+00,0.000000000000000000e+00,3.051324249981902917e-10,0.000000000000000000e+00 +5.793879008635420824e+00,5.989000000000000057e+01,0.000000000000000000e+00,8.242303875245521994e+00,0.000000000000000000e+00,-1.000000009952278113e+00,0.000000000000000000e+00,-1.250913750079421676e-09,0.000000000000000000e+00 +5.795092261647122100e+00,5.989999999999999858e+01,0.000000000000000000e+00,8.241090622221745932e+00,0.000000000000000000e+00,-1.000000009953795788e+00,0.000000000000000000e+00,1.634823468131353807e-09,0.000000000000000000e+00 +5.796305693273882120e+00,5.991000000000000369e+01,0.000000000000000000e+00,8.239877190582907573e+00,0.000000000000000000e+00,-1.000000009951812041e+00,0.000000000000000000e+00,-6.498811218269669964e-10,0.000000000000000000e+00 +5.797519303594607543e+00,5.992000000000000171e+01,0.000000000000000000e+00,8.238663580250104701e+00,0.000000000000000000e+00,-1.000000009952600744e+00,0.000000000000000000e+00,-8.250372107038821628e-10,0.000000000000000000e+00 +5.798733092688262758e+00,5.992999999999999972e+01,0.000000000000000000e+00,8.237449791144369371e+00,0.000000000000000000e+00,-1.000000009953602165e+00,0.000000000000000000e+00,1.147748506001431741e-09,0.000000000000000000e+00 +5.799947060633869889e+00,5.993999999999999773e+01,0.000000000000000000e+00,8.236235823186678573e+00,0.000000000000000000e+00,-1.000000009952208835e+00,0.000000000000000000e+00,-7.174428414549481331e-10,0.000000000000000000e+00 +5.801161207510510565e+00,5.995000000000000284e+01,0.000000000000000000e+00,8.235021676297954230e+00,0.000000000000000000e+00,-1.000000009953079916e+00,0.000000000000000000e+00,-3.530914862033574007e-10,0.000000000000000000e+00 +5.802375533397324148e+00,5.996000000000000085e+01,0.000000000000000000e+00,8.233807350399054314e+00,0.000000000000000000e+00,-1.000000009953508684e+00,0.000000000000000000e+00,1.075024230087127864e-09,0.000000000000000000e+00 +5.803590038373507731e+00,5.996999999999999886e+01,0.000000000000000000e+00,8.232592845410781734e+00,0.000000000000000000e+00,-1.000000009952203062e+00,0.000000000000000000e+00,-1.208675468463839876e-09,0.000000000000000000e+00 +5.804804722518317917e+00,5.998000000000000398e+01,0.000000000000000000e+00,8.231378161253882553e+00,0.000000000000000000e+00,-1.000000009953671221e+00,0.000000000000000000e+00,1.265339633302012467e-09,0.000000000000000000e+00 +5.806019585911069036e+00,5.999000000000000199e+01,0.000000000000000000e+00,8.230163297849038884e+00,0.000000000000000000e+00,-1.000000009952134006e+00,0.000000000000000000e+00,-1.092457595376162977e-09,0.000000000000000000e+00 +5.807234628631134044e+00,6.000000000000000000e+01,0.000000000000000000e+00,8.228948255116881327e+00,0.000000000000000000e+00,-1.000000009953461388e+00,0.000000000000000000e+00,1.841811112770001487e-10,0.000000000000000000e+00 +5.808449850757944510e+00,6.000999999999999801e+01,0.000000000000000000e+00,8.227733032977974759e+00,0.000000000000000000e+00,-1.000000009953237567e+00,0.000000000000000000e+00,3.215385766095754114e-10,0.000000000000000000e+00 +5.809665252370991517e+00,6.002000000000000313e+01,0.000000000000000000e+00,8.226517631352830762e+00,0.000000000000000000e+00,-1.000000009952846769e+00,0.000000000000000000e+00,-6.367715346765826971e-10,0.000000000000000000e+00 +5.810880833549822988e+00,6.003000000000000114e+01,0.000000000000000000e+00,8.225302050161900524e+00,0.000000000000000000e+00,-1.000000009953620816e+00,0.000000000000000000e+00,9.559293563509682794e-10,0.000000000000000000e+00 +5.812096594374047243e+00,6.003999999999999915e+01,0.000000000000000000e+00,8.224086289325574839e+00,0.000000000000000000e+00,-1.000000009952458635e+00,0.000000000000000000e+00,-8.681345913131584814e-10,0.000000000000000000e+00 +5.813312534923331221e+00,6.005000000000000426e+01,0.000000000000000000e+00,8.222870348764189430e+00,0.000000000000000000e+00,-1.000000009953514235e+00,0.000000000000000000e+00,1.141152498713186662e-09,0.000000000000000000e+00 +5.814528655277399594e+00,6.006000000000000227e+01,0.000000000000000000e+00,8.221654228398016073e+00,0.000000000000000000e+00,-1.000000009952126456e+00,0.000000000000000000e+00,-1.382689721071951941e-09,0.000000000000000000e+00 +5.815744955516037429e+00,6.007000000000000028e+01,0.000000000000000000e+00,8.220437928147273254e+00,0.000000000000000000e+00,-1.000000009953808222e+00,0.000000000000000000e+00,1.208168646158620550e-09,0.000000000000000000e+00 +5.816961435719088414e+00,6.007999999999999829e+01,0.000000000000000000e+00,8.219221447932113733e+00,0.000000000000000000e+00,-1.000000009952338509e+00,0.000000000000000000e+00,-6.497120253942849938e-10,0.000000000000000000e+00 +5.818178095966454855e+00,6.009000000000000341e+01,0.000000000000000000e+00,8.218004787672638756e+00,0.000000000000000000e+00,-1.000000009953128988e+00,0.000000000000000000e+00,-9.120168604501232468e-10,0.000000000000000000e+00 +5.819394936338098567e+00,6.010000000000000142e+01,0.000000000000000000e+00,8.216787947288883842e+00,0.000000000000000000e+00,-1.000000009954238767e+00,0.000000000000000000e+00,1.660106575149401756e-09,0.000000000000000000e+00 +5.820611956914039986e+00,6.010999999999999943e+01,0.000000000000000000e+00,8.215570926700827670e+00,0.000000000000000000e+00,-1.000000009952218383e+00,0.000000000000000000e+00,-1.287354312700722236e-09,0.000000000000000000e+00 +5.821829157774359942e+00,6.012000000000000455e+01,0.000000000000000000e+00,8.214353725828393848e+00,0.000000000000000000e+00,-1.000000009953785352e+00,0.000000000000000000e+00,1.080327319115816288e-09,0.000000000000000000e+00 +5.823046538999197885e+00,6.013000000000000256e+01,0.000000000000000000e+00,8.213136344591438487e+00,0.000000000000000000e+00,-1.000000009952470181e+00,0.000000000000000000e+00,-7.869190482992406789e-10,0.000000000000000000e+00 +5.824264100668752775e+00,6.014000000000000057e+01,0.000000000000000000e+00,8.211918782909766179e+00,0.000000000000000000e+00,-1.000000009953428304e+00,0.000000000000000000e+00,3.444425762592417539e-10,0.000000000000000000e+00 +5.825481842863282189e+00,6.014999999999999858e+01,0.000000000000000000e+00,8.210701040703115794e+00,0.000000000000000000e+00,-1.000000009953008862e+00,0.000000000000000000e+00,-2.774821924222990510e-10,0.000000000000000000e+00 +5.826699765663104991e+00,6.016000000000000369e+01,0.000000000000000000e+00,8.209483117891171133e+00,0.000000000000000000e+00,-1.000000009953346813e+00,0.000000000000000000e+00,-2.140051065336708993e-10,0.000000000000000000e+00 +5.827917869148597774e+00,6.017000000000000171e+01,0.000000000000000000e+00,8.208265014393553827e+00,0.000000000000000000e+00,-1.000000009953607494e+00,0.000000000000000000e+00,5.744838232983546957e-10,0.000000000000000000e+00 +5.829136153400198417e+00,6.017999999999999972e+01,0.000000000000000000e+00,8.207046730129826884e+00,0.000000000000000000e+00,-1.000000009952907609e+00,0.000000000000000000e+00,-2.624155846261844030e-10,0.000000000000000000e+00 +5.830354618498403418e+00,6.018999999999999773e+01,0.000000000000000000e+00,8.205828265019494694e+00,0.000000000000000000e+00,-1.000000009953227353e+00,0.000000000000000000e+00,-2.900719353140742735e-10,0.000000000000000000e+00 +5.831573264523768785e+00,6.020000000000000284e+01,0.000000000000000000e+00,8.204609618981999475e+00,0.000000000000000000e+00,-1.000000009953580848e+00,0.000000000000000000e+00,-6.624025899930285903e-10,0.000000000000000000e+00 +5.832792091556911807e+00,6.021000000000000085e+01,0.000000000000000000e+00,8.203390791936724824e+00,0.000000000000000000e+00,-1.000000009954388203e+00,0.000000000000000000e+00,1.053019941647774893e-09,0.000000000000000000e+00 +5.834011099678508394e+00,6.021999999999999886e+01,0.000000000000000000e+00,8.202171783802993943e+00,0.000000000000000000e+00,-1.000000009953104563e+00,0.000000000000000000e+00,1.161956219701012494e-10,0.000000000000000000e+00 +5.835230288969294854e+00,6.023000000000000398e+01,0.000000000000000000e+00,8.200952594500073189e+00,0.000000000000000000e+00,-1.000000009952962898e+00,0.000000000000000000e+00,1.560577527978460188e-10,0.000000000000000000e+00 +5.836449659510067001e+00,6.024000000000000199e+01,0.000000000000000000e+00,8.199733223947164973e+00,0.000000000000000000e+00,-1.000000009952772606e+00,0.000000000000000000e+00,-1.175448132024812049e-09,0.000000000000000000e+00 +5.837669211381681045e+00,6.025000000000000000e+01,0.000000000000000000e+00,8.198513672063413082e+00,0.000000000000000000e+00,-1.000000009954206126e+00,0.000000000000000000e+00,9.415293591866097261e-10,0.000000000000000000e+00 +5.838888944665053593e+00,6.025999999999999801e+01,0.000000000000000000e+00,8.197293938767899135e+00,0.000000000000000000e+00,-1.000000009953057711e+00,0.000000000000000000e+00,-6.164898496276299253e-10,0.000000000000000000e+00 +5.840108859441160760e+00,6.027000000000000313e+01,0.000000000000000000e+00,8.196074023979649681e+00,0.000000000000000000e+00,-1.000000009953809776e+00,0.000000000000000000e+00,1.628805146638831236e-10,0.000000000000000000e+00 +5.841328955791039945e+00,6.028000000000000114e+01,0.000000000000000000e+00,8.194853927617625544e+00,0.000000000000000000e+00,-1.000000009953611046e+00,0.000000000000000000e+00,9.336486140344665125e-10,0.000000000000000000e+00 +5.842549233795788943e+00,6.028999999999999915e+01,0.000000000000000000e+00,8.193633649600730706e+00,0.000000000000000000e+00,-1.000000009952471736e+00,0.000000000000000000e+00,-1.839001149809597822e-09,0.000000000000000000e+00 +5.843769693536564169e+00,6.030000000000000426e+01,0.000000000000000000e+00,8.192413189847808752e+00,0.000000000000000000e+00,-1.000000009954716162e+00,0.000000000000000000e+00,1.427069162271000896e-09,0.000000000000000000e+00 +5.844990335094584211e+00,6.031000000000000227e+01,0.000000000000000000e+00,8.191192548277637542e+00,0.000000000000000000e+00,-1.000000009952974223e+00,0.000000000000000000e+00,4.292391867263317774e-11,0.000000000000000000e+00 +5.846211158551127163e+00,6.032000000000000028e+01,0.000000000000000000e+00,8.189971724808943421e+00,0.000000000000000000e+00,-1.000000009952921820e+00,0.000000000000000000e+00,-1.179140710930974598e-09,0.000000000000000000e+00 +5.847432163987532405e+00,6.032999999999999829e+01,0.000000000000000000e+00,8.188750719360385233e+00,0.000000000000000000e+00,-1.000000009954361557e+00,0.000000000000000000e+00,1.376792467744288603e-09,0.000000000000000000e+00 +5.848653351485199714e+00,6.034000000000000341e+01,0.000000000000000000e+00,8.187529531850561426e+00,0.000000000000000000e+00,-1.000000009952680236e+00,0.000000000000000000e+00,-1.776728233754976981e-09,0.000000000000000000e+00 +5.849874721125590149e+00,6.035000000000000142e+01,0.000000000000000000e+00,8.186308162198015381e+00,0.000000000000000000e+00,-1.000000009954850277e+00,0.000000000000000000e+00,1.312579628081775228e-09,0.000000000000000000e+00 +5.851096272990224278e+00,6.035999999999999943e+01,0.000000000000000000e+00,8.185086610321221201e+00,0.000000000000000000e+00,-1.000000009953246893e+00,0.000000000000000000e+00,-2.962450545945480845e-11,0.000000000000000000e+00 +5.852318007160683955e+00,6.037000000000000455e+01,0.000000000000000000e+00,8.183864876138601474e+00,0.000000000000000000e+00,-1.000000009953283087e+00,0.000000000000000000e+00,-9.970883357939832114e-10,0.000000000000000000e+00 +5.853539923718612314e+00,6.038000000000000256e+01,0.000000000000000000e+00,8.182642959568511287e+00,0.000000000000000000e+00,-1.000000009954501445e+00,0.000000000000000000e+00,8.308737310193502985e-10,0.000000000000000000e+00 +5.854762022745712891e+00,6.039000000000000057e+01,0.000000000000000000e+00,8.181420860529245331e+00,0.000000000000000000e+00,-1.000000009953486035e+00,0.000000000000000000e+00,7.381009793656705368e-10,0.000000000000000000e+00 +5.855984304323750500e+00,6.039999999999999858e+01,0.000000000000000000e+00,8.180198578939041454e+00,0.000000000000000000e+00,-1.000000009952583868e+00,0.000000000000000000e+00,-1.230226697738292973e-09,0.000000000000000000e+00 +5.857206768534552133e+00,6.041000000000000369e+01,0.000000000000000000e+00,8.178976114716073553e+00,0.000000000000000000e+00,-1.000000009954087776e+00,0.000000000000000000e+00,-2.765916523087014994e-10,0.000000000000000000e+00 +5.858429415460003398e+00,6.042000000000000171e+01,0.000000000000000000e+00,8.177753467778451579e+00,0.000000000000000000e+00,-1.000000009954425950e+00,0.000000000000000000e+00,1.263088591982140181e-09,0.000000000000000000e+00 +5.859652245182053854e+00,6.042999999999999972e+01,0.000000000000000000e+00,8.176530638044228638e+00,0.000000000000000000e+00,-1.000000009952881408e+00,0.000000000000000000e+00,-1.319363466182719290e-09,0.000000000000000000e+00 +5.860875257782712566e+00,6.043999999999999773e+01,0.000000000000000000e+00,8.175307625431397440e+00,0.000000000000000000e+00,-1.000000009954495006e+00,0.000000000000000000e+00,1.521025585337946860e-09,0.000000000000000000e+00 +5.862098453344050775e+00,6.045000000000000284e+01,0.000000000000000000e+00,8.174084429857883194e+00,0.000000000000000000e+00,-1.000000009952634494e+00,0.000000000000000000e+00,-8.595893743425383756e-10,0.000000000000000000e+00 +5.863321831948200114e+00,6.046000000000000085e+01,0.000000000000000000e+00,8.172861051241557817e+00,0.000000000000000000e+00,-1.000000009953686098e+00,0.000000000000000000e+00,-1.081584863125144282e-10,0.000000000000000000e+00 +5.864545393677355278e+00,6.046999999999999886e+01,0.000000000000000000e+00,8.171637489500223950e+00,0.000000000000000000e+00,-1.000000009953818436e+00,0.000000000000000000e+00,-9.286447315850964178e-10,0.000000000000000000e+00 +5.865769138613770473e+00,6.048000000000000398e+01,0.000000000000000000e+00,8.170413744551627389e+00,0.000000000000000000e+00,-1.000000009954954860e+00,0.000000000000000000e+00,1.466414862809868480e-09,0.000000000000000000e+00 +5.866993066839763848e+00,6.049000000000000199e+01,0.000000000000000000e+00,8.169189816313449981e+00,0.000000000000000000e+00,-1.000000009953160074e+00,0.000000000000000000e+00,-1.181227650888975905e-09,0.000000000000000000e+00 +5.868217178437713066e+00,6.050000000000000000e+01,0.000000000000000000e+00,8.167965704703316732e+00,0.000000000000000000e+00,-1.000000009954606028e+00,0.000000000000000000e+00,6.579932060693768497e-10,0.000000000000000000e+00 +5.869441473490058847e+00,6.050999999999999801e+01,0.000000000000000000e+00,8.166741409638783367e+00,0.000000000000000000e+00,-1.000000009953800451e+00,0.000000000000000000e+00,-8.631692940381930967e-11,0.000000000000000000e+00 +5.870665952079303196e+00,6.052000000000000313e+01,0.000000000000000000e+00,8.165516931037350545e+00,0.000000000000000000e+00,-1.000000009953906144e+00,0.000000000000000000e+00,1.852997378541981078e-10,0.000000000000000000e+00 +5.871890614288010291e+00,6.053000000000000114e+01,0.000000000000000000e+00,8.164292268816453202e+00,0.000000000000000000e+00,-1.000000009953679214e+00,0.000000000000000000e+00,3.310240455713674472e-10,0.000000000000000000e+00 +5.873115460198805593e+00,6.053999999999999915e+01,0.000000000000000000e+00,8.163067422893465874e+00,0.000000000000000000e+00,-1.000000009953273761e+00,0.000000000000000000e+00,-7.888283232045349333e-10,0.000000000000000000e+00 +5.874340489894377626e+00,6.055000000000000426e+01,0.000000000000000000e+00,8.161842393185700928e+00,0.000000000000000000e+00,-1.000000009954240099e+00,0.000000000000000000e+00,4.195458456251998706e-10,0.000000000000000000e+00 +5.875565703457475308e+00,6.056000000000000227e+01,0.000000000000000000e+00,8.160617179610406779e+00,0.000000000000000000e+00,-1.000000009953726066e+00,0.000000000000000000e+00,-7.340497142261205648e-10,0.000000000000000000e+00 +5.876791100970911508e+00,6.057000000000000028e+01,0.000000000000000000e+00,8.159391782084773226e+00,0.000000000000000000e+00,-1.000000009954625568e+00,0.000000000000000000e+00,5.266754124049297238e-10,0.000000000000000000e+00 +5.878016682517560376e+00,6.057999999999999829e+01,0.000000000000000000e+00,8.158166200525924339e+00,0.000000000000000000e+00,-1.000000009953980085e+00,0.000000000000000000e+00,6.959693830670543504e-10,0.000000000000000000e+00 +5.879242448180358238e+00,6.059000000000000341e+01,0.000000000000000000e+00,8.156940434850925570e+00,0.000000000000000000e+00,-1.000000009953126989e+00,0.000000000000000000e+00,-1.363112594192374082e-09,0.000000000000000000e+00 +5.880468398042303591e+00,6.060000000000000142e+01,0.000000000000000000e+00,8.155714484976778422e+00,0.000000000000000000e+00,-1.000000009954798097e+00,0.000000000000000000e+00,1.484240195612100393e-09,0.000000000000000000e+00 +5.881694532186457103e+00,6.060999999999999943e+01,0.000000000000000000e+00,8.154488350820418674e+00,0.000000000000000000e+00,-1.000000009952978219e+00,0.000000000000000000e+00,-1.353287391792785912e-09,0.000000000000000000e+00 +5.882920850695943393e+00,6.062000000000000455e+01,0.000000000000000000e+00,8.153262032298727036e+00,0.000000000000000000e+00,-1.000000009954637781e+00,0.000000000000000000e+00,8.005535058602790990e-10,0.000000000000000000e+00 +5.884147353653947476e+00,6.063000000000000256e+01,0.000000000000000000e+00,8.152035529328513164e+00,0.000000000000000000e+00,-1.000000009953655900e+00,0.000000000000000000e+00,-2.783957651987745458e-10,0.000000000000000000e+00 +5.885374041143719204e+00,6.064000000000000057e+01,0.000000000000000000e+00,8.150808841826531648e+00,0.000000000000000000e+00,-1.000000009953997404e+00,0.000000000000000000e+00,-1.002472109210054347e-09,0.000000000000000000e+00 +5.886600913248568823e+00,6.064999999999999858e+01,0.000000000000000000e+00,8.149581969709469575e+00,0.000000000000000000e+00,-1.000000009955227309e+00,0.000000000000000000e+00,1.030731475714422320e-09,0.000000000000000000e+00 +5.887827970051870530e+00,6.066000000000000369e+01,0.000000000000000000e+00,8.148354912893951862e+00,0.000000000000000000e+00,-1.000000009953962543e+00,0.000000000000000000e+00,-3.401480705154253841e-11,0.000000000000000000e+00 +5.889055211637061582e+00,6.067000000000000171e+01,0.000000000000000000e+00,8.147127671296544804e+00,0.000000000000000000e+00,-1.000000009954004287e+00,0.000000000000000000e+00,5.662250581996582867e-10,0.000000000000000000e+00 +5.890282638087641409e+00,6.067999999999999972e+01,0.000000000000000000e+00,8.145900244833747195e+00,0.000000000000000000e+00,-1.000000009953309288e+00,0.000000000000000000e+00,-6.621845471141162370e-10,0.000000000000000000e+00 +5.891510249487172501e+00,6.068999999999999773e+01,0.000000000000000000e+00,8.144672633421997432e+00,0.000000000000000000e+00,-1.000000009954122193e+00,0.000000000000000000e+00,-1.381679191488773046e-10,0.000000000000000000e+00 +5.892738045919280410e+00,6.070000000000000284e+01,0.000000000000000000e+00,8.143444836977668189e+00,0.000000000000000000e+00,-1.000000009954291835e+00,0.000000000000000000e+00,-1.752153543817272155e-10,0.000000000000000000e+00 +5.893966027467652857e+00,6.071000000000000085e+01,0.000000000000000000e+00,8.142216855417071741e+00,0.000000000000000000e+00,-1.000000009954506996e+00,0.000000000000000000e+00,4.483679605690035688e-10,0.000000000000000000e+00 +5.895194194216042405e+00,6.071999999999999886e+01,0.000000000000000000e+00,8.140988688656456418e+00,0.000000000000000000e+00,-1.000000009953956326e+00,0.000000000000000000e+00,-5.775482061544629999e-10,0.000000000000000000e+00 +5.896422546248263785e+00,6.073000000000000398e+01,0.000000000000000000e+00,8.139760336612008373e+00,0.000000000000000000e+00,-1.000000009954665758e+00,0.000000000000000000e+00,3.231613084211886364e-10,0.000000000000000000e+00 +5.897651083648194792e+00,6.074000000000000199e+01,0.000000000000000000e+00,8.138531799199848038e+00,0.000000000000000000e+00,-1.000000009954268743e+00,0.000000000000000000e+00,-3.366659116357099729e-10,0.000000000000000000e+00 +5.898879806499776279e+00,6.075000000000000000e+01,0.000000000000000000e+00,8.137303076336035446e+00,0.000000000000000000e+00,-1.000000009954682412e+00,0.000000000000000000e+00,1.017433995339449883e-09,0.000000000000000000e+00 +5.900108714887013051e+00,6.075999999999999801e+01,0.000000000000000000e+00,8.136074167936564905e+00,0.000000000000000000e+00,-1.000000009953432079e+00,0.000000000000000000e+00,-1.451218784943240670e-09,0.000000000000000000e+00 +5.901337808893973857e+00,6.077000000000000313e+01,0.000000000000000000e+00,8.134845073917370328e+00,0.000000000000000000e+00,-1.000000009955215763e+00,0.000000000000000000e+00,1.709300233232015585e-09,0.000000000000000000e+00 +5.902567088604790513e+00,6.078000000000000114e+01,0.000000000000000000e+00,8.133615794194316351e+00,0.000000000000000000e+00,-1.000000009953114555e+00,0.000000000000000000e+00,-1.212926729583708101e-09,0.000000000000000000e+00 +5.903796554103657002e+00,6.078999999999999915e+01,0.000000000000000000e+00,8.132386328683212540e+00,0.000000000000000000e+00,-1.000000009954605806e+00,0.000000000000000000e+00,4.050302878696775467e-10,0.000000000000000000e+00 +5.905026205474833034e+00,6.080000000000000426e+01,0.000000000000000000e+00,8.131156677299795632e+00,0.000000000000000000e+00,-1.000000009954107760e+00,0.000000000000000000e+00,-4.425230185858675335e-10,0.000000000000000000e+00 +5.906256042802641382e+00,6.081000000000000227e+01,0.000000000000000000e+00,8.129926839959745521e+00,0.000000000000000000e+00,-1.000000009954651992e+00,0.000000000000000000e+00,-1.868388617011959448e-10,0.000000000000000000e+00 +5.907486066171467876e+00,6.082000000000000028e+01,0.000000000000000000e+00,8.128696816578674600e+00,0.000000000000000000e+00,-1.000000009954881808e+00,0.000000000000000000e+00,4.169395861074840203e-11,0.000000000000000000e+00 +5.908716275665763185e+00,6.082999999999999829e+01,0.000000000000000000e+00,8.127466607072133087e+00,0.000000000000000000e+00,-1.000000009954830515e+00,0.000000000000000000e+00,2.885651518782137441e-10,0.000000000000000000e+00 +5.909946671370041038e+00,6.084000000000000341e+01,0.000000000000000000e+00,8.126236211355607253e+00,0.000000000000000000e+00,-1.000000009954475466e+00,0.000000000000000000e+00,5.979738216684289944e-10,0.000000000000000000e+00 +5.911177253368879114e+00,6.085000000000000142e+01,0.000000000000000000e+00,8.125005629344519420e+00,0.000000000000000000e+00,-1.000000009953739610e+00,0.000000000000000000e+00,-1.576795343193795214e-10,0.000000000000000000e+00 +5.912408021746919928e+00,6.085999999999999943e+01,0.000000000000000000e+00,8.123774860954227961e+00,0.000000000000000000e+00,-1.000000009953933677e+00,0.000000000000000000e+00,-7.599579518835533251e-10,0.000000000000000000e+00 +5.913638976588869944e+00,6.087000000000000455e+01,0.000000000000000000e+00,8.122543906100025524e+00,0.000000000000000000e+00,-1.000000009954869151e+00,0.000000000000000000e+00,7.394624915726423086e-12,0.000000000000000000e+00 +5.914870117979498687e+00,6.088000000000000256e+01,0.000000000000000000e+00,8.121312764697140807e+00,0.000000000000000000e+00,-1.000000009954860047e+00,0.000000000000000000e+00,1.016516649845428779e-09,0.000000000000000000e+00 +5.916101446003641406e+00,6.089000000000000057e+01,0.000000000000000000e+00,8.120081436660740337e+00,0.000000000000000000e+00,-1.000000009953608382e+00,0.000000000000000000e+00,-1.200991804886024523e-09,0.000000000000000000e+00 +5.917332960746197301e+00,6.089999999999999858e+01,0.000000000000000000e+00,8.118849921905926692e+00,0.000000000000000000e+00,-1.000000009955087421e+00,0.000000000000000000e+00,4.276115464998588185e-10,0.000000000000000000e+00 +5.918564662292129519e+00,6.091000000000000369e+01,0.000000000000000000e+00,8.117618220347733171e+00,0.000000000000000000e+00,-1.000000009954560731e+00,0.000000000000000000e+00,9.120515053186901007e-11,0.000000000000000000e+00 +5.919796550726465156e+00,6.092000000000000171e+01,0.000000000000000000e+00,8.116386331901134454e+00,0.000000000000000000e+00,-1.000000009954448377e+00,0.000000000000000000e+00,1.778771199131594536e-10,0.000000000000000000e+00 +5.921028626134297035e+00,6.092999999999999972e+01,0.000000000000000000e+00,8.115154256481037720e+00,0.000000000000000000e+00,-1.000000009954229219e+00,0.000000000000000000e+00,-4.378680716510024516e-10,0.000000000000000000e+00 +5.922260888600781925e+00,6.093999999999999773e+01,0.000000000000000000e+00,8.113921994002286198e+00,0.000000000000000000e+00,-1.000000009954768787e+00,0.000000000000000000e+00,-5.408561115859380570e-10,0.000000000000000000e+00 +5.923493338211142323e+00,6.095000000000000284e+01,0.000000000000000000e+00,8.112689544379657391e+00,0.000000000000000000e+00,-1.000000009955435365e+00,0.000000000000000000e+00,1.083349297379393562e-09,0.000000000000000000e+00 +5.924725975050663784e+00,6.096000000000000085e+01,0.000000000000000000e+00,8.111456907527864857e+00,0.000000000000000000e+00,-1.000000009954099989e+00,0.000000000000000000e+00,-1.972210242616292806e-10,0.000000000000000000e+00 +5.925958799204696703e+00,6.096999999999999886e+01,0.000000000000000000e+00,8.110224083361559977e+00,0.000000000000000000e+00,-1.000000009954343128e+00,0.000000000000000000e+00,-8.282024079737618190e-10,0.000000000000000000e+00 +5.927191810758658086e+00,6.098000000000000398e+01,0.000000000000000000e+00,8.108991071795324856e+00,0.000000000000000000e+00,-1.000000009955364311e+00,0.000000000000000000e+00,4.022445943972109420e-10,0.000000000000000000e+00 +5.928425009798028000e+00,6.099000000000000199e+01,0.000000000000000000e+00,8.107757872743677652e+00,0.000000000000000000e+00,-1.000000009954868263e+00,0.000000000000000000e+00,1.202949697757765830e-09,0.000000000000000000e+00 +5.929658396408353127e+00,6.100000000000000000e+01,0.000000000000000000e+00,8.106524486121074347e+00,0.000000000000000000e+00,-1.000000009953384561e+00,0.000000000000000000e+00,-1.881910483056877630e-09,0.000000000000000000e+00 +5.930891970675244096e+00,6.100999999999999801e+01,0.000000000000000000e+00,8.105290911841905199e+00,0.000000000000000000e+00,-1.000000009955706037e+00,0.000000000000000000e+00,1.699310842919993488e-09,0.000000000000000000e+00 +5.932125732684377262e+00,6.102000000000000313e+01,0.000000000000000000e+00,8.104057149820489414e+00,0.000000000000000000e+00,-1.000000009953609492e+00,0.000000000000000000e+00,-2.013058327477819482e-09,0.000000000000000000e+00 +5.933359682521492928e+00,6.103000000000000114e+01,0.000000000000000000e+00,8.102823199971091128e+00,0.000000000000000000e+00,-1.000000009956093505e+00,0.000000000000000000e+00,2.194649737347006933e-09,0.000000000000000000e+00 +5.934593820272398901e+00,6.103999999999999915e+01,0.000000000000000000e+00,8.101589062207898095e+00,0.000000000000000000e+00,-1.000000009953385005e+00,0.000000000000000000e+00,-1.961895763900918991e-09,0.000000000000000000e+00 +5.935828146022966934e+00,6.105000000000000426e+01,0.000000000000000000e+00,8.100354736445044779e+00,0.000000000000000000e+00,-1.000000009955806624e+00,0.000000000000000000e+00,7.232331710237521761e-10,0.000000000000000000e+00 +5.937062659859133618e+00,6.106000000000000227e+01,0.000000000000000000e+00,8.099120222596587482e+00,0.000000000000000000e+00,-1.000000009954913782e+00,0.000000000000000000e+00,9.677007177309401616e-10,0.000000000000000000e+00 +5.938297361866902158e+00,6.107000000000000028e+01,0.000000000000000000e+00,8.097885520576527441e+00,0.000000000000000000e+00,-1.000000009953718960e+00,0.000000000000000000e+00,-1.180087642528165912e-09,0.000000000000000000e+00 +5.939532252132341483e+00,6.107999999999999829e+01,0.000000000000000000e+00,8.096650630298796614e+00,0.000000000000000000e+00,-1.000000009955176239e+00,0.000000000000000000e+00,1.504773323182127544e-10,0.000000000000000000e+00 +5.940767330741585361e+00,6.109000000000000341e+01,0.000000000000000000e+00,8.095415551677257682e+00,0.000000000000000000e+00,-1.000000009954990388e+00,0.000000000000000000e+00,3.451283227922171636e-10,0.000000000000000000e+00 +5.942002597780833284e+00,6.110000000000000142e+01,0.000000000000000000e+00,8.094180284625712929e+00,0.000000000000000000e+00,-1.000000009954564062e+00,0.000000000000000000e+00,-5.479873374586174630e-10,0.000000000000000000e+00 +5.943238053336350468e+00,6.110999999999999943e+01,0.000000000000000000e+00,8.092944829057897138e+00,0.000000000000000000e+00,-1.000000009955241076e+00,0.000000000000000000e+00,-1.563385421405965074e-10,0.000000000000000000e+00 +5.944473697494468745e+00,6.112000000000000455e+01,0.000000000000000000e+00,8.091709184887477591e+00,0.000000000000000000e+00,-1.000000009955434255e+00,0.000000000000000000e+00,4.033637228689188087e-10,0.000000000000000000e+00 +5.945709530341585669e+00,6.113000000000000256e+01,0.000000000000000000e+00,8.090473352028057619e+00,0.000000000000000000e+00,-1.000000009954935765e+00,0.000000000000000000e+00,1.329370009739597268e-11,0.000000000000000000e+00 +5.946945551964163634e+00,6.114000000000000057e+01,0.000000000000000000e+00,8.089237330393174830e+00,0.000000000000000000e+00,-1.000000009954919333e+00,0.000000000000000000e+00,1.045731051475519390e-09,0.000000000000000000e+00 +5.948181762448732535e+00,6.114999999999999858e+01,0.000000000000000000e+00,8.088001119896299329e+00,0.000000000000000000e+00,-1.000000009953626590e+00,0.000000000000000000e+00,-1.102141997062568629e-09,0.000000000000000000e+00 +5.949418161881887990e+00,6.116000000000000369e+01,0.000000000000000000e+00,8.086764720450837274e+00,0.000000000000000000e+00,-1.000000009954989277e+00,0.000000000000000000e+00,-5.726240080665183713e-10,0.000000000000000000e+00 +5.950654750350291344e+00,6.117000000000000171e+01,0.000000000000000000e+00,8.085528131970123766e+00,0.000000000000000000e+00,-1.000000009955697378e+00,0.000000000000000000e+00,3.547607449754900520e-10,0.000000000000000000e+00 +5.951891527940670557e+00,6.117999999999999972e+01,0.000000000000000000e+00,8.084291354367431737e+00,0.000000000000000000e+00,-1.000000009955258617e+00,0.000000000000000000e+00,5.659866051459630502e-10,0.000000000000000000e+00 +5.953128494739819310e+00,6.118999999999999773e+01,0.000000000000000000e+00,8.083054387555968390e+00,0.000000000000000000e+00,-1.000000009954558511e+00,0.000000000000000000e+00,1.071494774989226216e-10,0.000000000000000000e+00 +5.954365650834598789e+00,6.120000000000000284e+01,0.000000000000000000e+00,8.081817231448873429e+00,0.000000000000000000e+00,-1.000000009954425950e+00,0.000000000000000000e+00,-9.729908662973362114e-10,0.000000000000000000e+00 +5.955602996311935904e+00,6.121000000000000085e+01,0.000000000000000000e+00,8.080579885959219055e+00,0.000000000000000000e+00,-1.000000009955629876e+00,0.000000000000000000e+00,8.508329556282360015e-10,0.000000000000000000e+00 +5.956840531258824178e+00,6.121999999999999886e+01,0.000000000000000000e+00,8.079342351000009970e+00,0.000000000000000000e+00,-1.000000009954576941e+00,0.000000000000000000e+00,-1.743743097731178332e-10,0.000000000000000000e+00 +5.958078255762324638e+00,6.123000000000000398e+01,0.000000000000000000e+00,8.078104626484188699e+00,0.000000000000000000e+00,-1.000000009954792768e+00,0.000000000000000000e+00,-5.216078292361818069e-10,0.000000000000000000e+00 +5.959316169909563143e+00,6.124000000000000199e+01,0.000000000000000000e+00,8.076866712324626718e+00,0.000000000000000000e+00,-1.000000009955438474e+00,0.000000000000000000e+00,-1.449087139961568554e-10,0.000000000000000000e+00 +5.960554273787733948e+00,6.125000000000000000e+01,0.000000000000000000e+00,8.075628608434129774e+00,0.000000000000000000e+00,-1.000000009955617886e+00,0.000000000000000000e+00,1.001294828151170859e-09,0.000000000000000000e+00 +5.961792567484097916e+00,6.125999999999999801e+01,0.000000000000000000e+00,8.074390314725437889e+00,0.000000000000000000e+00,-1.000000009954377989e+00,0.000000000000000000e+00,-5.106107451599683215e-10,0.000000000000000000e+00 +5.963031051085982526e+00,6.127000000000000313e+01,0.000000000000000000e+00,8.073151831111225363e+00,0.000000000000000000e+00,-1.000000009955010372e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +5.964269724680781870e+00,6.128000000000000114e+01,0.000000000000000000e+00,8.071913157504095437e+00,0.000000000000000000e+00,-1.000000009955010372e+00,0.000000000000000000e+00,-8.947285242091416285e-10,0.000000000000000000e+00 +5.965508588355956654e+00,6.128999999999999915e+01,0.000000000000000000e+00,8.070674293816587408e+00,0.000000000000000000e+00,-1.000000009956118818e+00,0.000000000000000000e+00,1.482025089535614130e-09,0.000000000000000000e+00 +5.966747642199036861e+00,6.130000000000000426e+01,0.000000000000000000e+00,8.069435239961171291e+00,0.000000000000000000e+00,-1.000000009954282509e+00,0.000000000000000000e+00,-9.225847208540487499e-10,0.000000000000000000e+00 +5.967986886297617311e+00,6.131000000000000227e+01,0.000000000000000000e+00,8.068195995850254931e+00,0.000000000000000000e+00,-1.000000009955425817e+00,0.000000000000000000e+00,3.762148723948207449e-11,0.000000000000000000e+00 +5.969226320739361213e+00,6.132000000000000028e+01,0.000000000000000000e+00,8.066956561396171566e+00,0.000000000000000000e+00,-1.000000009955379188e+00,0.000000000000000000e+00,-2.179919830251706431e-10,0.000000000000000000e+00 +5.970465945611999281e+00,6.132999999999999829e+01,0.000000000000000000e+00,8.065716936511192259e+00,0.000000000000000000e+00,-1.000000009955649416e+00,0.000000000000000000e+00,6.705312796184226941e-10,0.000000000000000000e+00 +5.971705761003329727e+00,6.134000000000000341e+01,0.000000000000000000e+00,8.064477121107518798e+00,0.000000000000000000e+00,-1.000000009954818081e+00,0.000000000000000000e+00,-7.159113197860524735e-10,0.000000000000000000e+00 +5.972945767001217376e+00,6.135000000000000142e+01,0.000000000000000000e+00,8.063237115097287244e+00,0.000000000000000000e+00,-1.000000009955705815e+00,0.000000000000000000e+00,2.909397236912767579e-10,0.000000000000000000e+00 +5.974185963693594559e+00,6.135999999999999943e+01,0.000000000000000000e+00,8.061996918392562606e+00,0.000000000000000000e+00,-1.000000009955344993e+00,0.000000000000000000e+00,2.728147331072575870e-10,0.000000000000000000e+00 +5.975426351168462880e+00,6.137000000000000455e+01,0.000000000000000000e+00,8.060756530905345940e+00,0.000000000000000000e+00,-1.000000009955006597e+00,0.000000000000000000e+00,4.320691863314408500e-10,0.000000000000000000e+00 +5.976666929513889670e+00,6.138000000000000256e+01,0.000000000000000000e+00,8.059515952547569029e+00,0.000000000000000000e+00,-1.000000009954470581e+00,0.000000000000000000e+00,-1.490892462833710681e-09,0.000000000000000000e+00 +5.977907698818011539e+00,6.139000000000000057e+01,0.000000000000000000e+00,8.058275183231096150e+00,0.000000000000000000e+00,-1.000000009956320435e+00,0.000000000000000000e+00,1.473127832686085519e-09,0.000000000000000000e+00 +5.979148659169031710e+00,6.139999999999999858e+01,0.000000000000000000e+00,8.057034222867720530e+00,0.000000000000000000e+00,-1.000000009954492342e+00,0.000000000000000000e+00,-1.010260147905262324e-09,0.000000000000000000e+00 +5.980389810655221794e+00,6.141000000000000369e+01,0.000000000000000000e+00,8.055793071369174996e+00,0.000000000000000000e+00,-1.000000009955746227e+00,0.000000000000000000e+00,3.337798897534689362e-10,0.000000000000000000e+00 +5.981631153364922682e+00,6.142000000000000171e+01,0.000000000000000000e+00,8.054551728647115993e+00,0.000000000000000000e+00,-1.000000009955331892e+00,0.000000000000000000e+00,-2.131855949671326628e-10,0.000000000000000000e+00 +5.982872687386540989e+00,6.142999999999999972e+01,0.000000000000000000e+00,8.053310194613137796e+00,0.000000000000000000e+00,-1.000000009955596569e+00,0.000000000000000000e+00,-2.973766755874162485e-10,0.000000000000000000e+00 +5.984114412808552608e+00,6.143999999999999773e+01,0.000000000000000000e+00,8.052068469178763621e+00,0.000000000000000000e+00,-1.000000009955965830e+00,0.000000000000000000e+00,1.280328339076966433e-09,0.000000000000000000e+00 +5.985356329719502710e+00,6.145000000000000284e+01,0.000000000000000000e+00,8.050826552255449187e+00,0.000000000000000000e+00,-1.000000009954375768e+00,0.000000000000000000e+00,-1.190748736603043248e-09,0.000000000000000000e+00 +5.986598438208003081e+00,6.146000000000000085e+01,0.000000000000000000e+00,8.049584443754584484e+00,0.000000000000000000e+00,-1.000000009955854807e+00,0.000000000000000000e+00,3.984040591904262692e-10,0.000000000000000000e+00 +5.987840738362734783e+00,6.146999999999999886e+01,0.000000000000000000e+00,8.048342143587484898e+00,0.000000000000000000e+00,-1.000000009955359870e+00,0.000000000000000000e+00,3.382963171330268477e-10,0.000000000000000000e+00 +5.989083230272446379e+00,6.148000000000000398e+01,0.000000000000000000e+00,8.047099651665403641e+00,0.000000000000000000e+00,-1.000000009954939539e+00,0.000000000000000000e+00,-1.321349739048863965e-09,0.000000000000000000e+00 +5.990325914025956600e+00,6.149000000000000199e+01,0.000000000000000000e+00,8.045856967899522871e+00,0.000000000000000000e+00,-1.000000009956581559e+00,0.000000000000000000e+00,1.218241033920249799e-09,0.000000000000000000e+00 +5.991568789712150789e+00,6.150000000000000000e+01,0.000000000000000000e+00,8.044614092200953692e+00,0.000000000000000000e+00,-1.000000009955067437e+00,0.000000000000000000e+00,-4.554971052586605213e-11,0.000000000000000000e+00 +5.992811857419984456e+00,6.150999999999999801e+01,0.000000000000000000e+00,8.043371024480745035e+00,0.000000000000000000e+00,-1.000000009955124058e+00,0.000000000000000000e+00,-4.639994593347512874e-10,0.000000000000000000e+00 +5.994055117238481500e+00,6.152000000000000313e+01,0.000000000000000000e+00,8.042127764649871224e+00,0.000000000000000000e+00,-1.000000009955700930e+00,0.000000000000000000e+00,1.035712427709817456e-11,0.000000000000000000e+00 +5.995298569256734211e+00,6.153000000000000114e+01,0.000000000000000000e+00,8.040884312619239083e+00,0.000000000000000000e+00,-1.000000009955688052e+00,0.000000000000000000e+00,2.756711609804641469e-10,0.000000000000000000e+00 +5.996542213563904156e+00,6.153999999999999915e+01,0.000000000000000000e+00,8.039640668299687931e+00,0.000000000000000000e+00,-1.000000009955345215e+00,0.000000000000000000e+00,3.807743797042569158e-10,0.000000000000000000e+00 +5.997786050249221290e+00,6.155000000000000426e+01,0.000000000000000000e+00,8.038396831601987813e+00,0.000000000000000000e+00,-1.000000009954871594e+00,0.000000000000000000e+00,-7.730326751535666928e-10,0.000000000000000000e+00 +5.999030079401985738e+00,6.156000000000000227e+01,0.000000000000000000e+00,8.037152802436839494e+00,0.000000000000000000e+00,-1.000000009955833269e+00,0.000000000000000000e+00,3.053461582462764866e-10,0.000000000000000000e+00 +6.000274301111565123e+00,6.157000000000000028e+01,0.000000000000000000e+00,8.035908580714872684e+00,0.000000000000000000e+00,-1.000000009955453351e+00,0.000000000000000000e+00,-9.255320467397975243e-10,0.000000000000000000e+00 +6.001518715467398124e+00,6.157999999999999829e+01,0.000000000000000000e+00,8.034664166346651371e+00,0.000000000000000000e+00,-1.000000009956605096e+00,0.000000000000000000e+00,1.317880564606415405e-09,0.000000000000000000e+00 +6.002763322558990922e+00,6.159000000000000341e+01,0.000000000000000000e+00,8.033419559242666708e+00,0.000000000000000000e+00,-1.000000009954964852e+00,0.000000000000000000e+00,-9.432615273147253346e-10,0.000000000000000000e+00 +6.004008122475919862e+00,6.160000000000000142e+01,0.000000000000000000e+00,8.032174759313345902e+00,0.000000000000000000e+00,-1.000000009956139024e+00,0.000000000000000000e+00,3.661527699010469229e-10,0.000000000000000000e+00 +6.005253115307830569e+00,6.160999999999999943e+01,0.000000000000000000e+00,8.030929766469039777e+00,0.000000000000000000e+00,-1.000000009955683167e+00,0.000000000000000000e+00,7.082968219144232157e-10,0.000000000000000000e+00 +6.006498301144438834e+00,6.162000000000000455e+01,0.000000000000000000e+00,8.029684580620035206e+00,0.000000000000000000e+00,-1.000000009954801206e+00,0.000000000000000000e+00,-1.012179659291677434e-09,0.000000000000000000e+00 +6.007743680075528836e+00,6.163000000000000256e+01,0.000000000000000000e+00,8.028439201676548009e+00,0.000000000000000000e+00,-1.000000009956061753e+00,0.000000000000000000e+00,-1.645405896676933197e-10,0.000000000000000000e+00 +6.008989252190954922e+00,6.164000000000000057e+01,0.000000000000000000e+00,8.027193629548721177e+00,0.000000000000000000e+00,-1.000000009956266700e+00,0.000000000000000000e+00,1.007231436047191555e-09,0.000000000000000000e+00 +6.010235017580640715e+00,6.164999999999999858e+01,0.000000000000000000e+00,8.025947864146631971e+00,0.000000000000000000e+00,-1.000000009955011926e+00,0.000000000000000000e+00,-8.794754415744872185e-10,0.000000000000000000e+00 +6.011480976334580895e+00,6.166000000000000369e+01,0.000000000000000000e+00,8.024701905380288380e+00,0.000000000000000000e+00,-1.000000009956107716e+00,0.000000000000000000e+00,-5.470254216159427854e-11,0.000000000000000000e+00 +6.012727128542838528e+00,6.167000000000000171e+01,0.000000000000000000e+00,8.023455753159623782e+00,0.000000000000000000e+00,-1.000000009956175884e+00,0.000000000000000000e+00,1.241572692295842968e-09,0.000000000000000000e+00 +6.013973474295547739e+00,6.167999999999999972e+01,0.000000000000000000e+00,8.022209407394505831e+00,0.000000000000000000e+00,-1.000000009954628455e+00,0.000000000000000000e+00,-1.514807586044561568e-09,0.000000000000000000e+00 +6.015220013682911926e+00,6.169000000000000483e+01,0.000000000000000000e+00,8.020962867994732903e+00,0.000000000000000000e+00,-1.000000009956516722e+00,0.000000000000000000e+00,8.712708410347821118e-10,0.000000000000000000e+00 +6.016466746795204656e+00,6.170000000000000284e+01,0.000000000000000000e+00,8.019716134870026991e+00,0.000000000000000000e+00,-1.000000009955430480e+00,0.000000000000000000e+00,-6.957330475940091955e-10,0.000000000000000000e+00 +6.017713673722769663e+00,6.171000000000000085e+01,0.000000000000000000e+00,8.018469207930047915e+00,0.000000000000000000e+00,-1.000000009956298008e+00,0.000000000000000000e+00,6.904615454573265179e-10,0.000000000000000000e+00 +6.018960794556021732e+00,6.171999999999999886e+01,0.000000000000000000e+00,8.017222087084379112e+00,0.000000000000000000e+00,-1.000000009955436919e+00,0.000000000000000000e+00,-6.333883681063627197e-10,0.000000000000000000e+00 +6.020208109385444928e+00,6.173000000000000398e+01,0.000000000000000000e+00,8.015974772242538293e+00,0.000000000000000000e+00,-1.000000009956226954e+00,0.000000000000000000e+00,-4.894735866326934218e-11,0.000000000000000000e+00 +6.021455618301594370e+00,6.174000000000000199e+01,0.000000000000000000e+00,8.014727263313968564e+00,0.000000000000000000e+00,-1.000000009956288016e+00,0.000000000000000000e+00,1.349135189858312474e-09,0.000000000000000000e+00 +6.022703321395095344e+00,6.175000000000000000e+01,0.000000000000000000e+00,8.013479560208045527e+00,0.000000000000000000e+00,-1.000000009954604696e+00,0.000000000000000000e+00,-2.092515485952942026e-09,0.000000000000000000e+00 +6.023951218756643300e+00,6.175999999999999801e+01,0.000000000000000000e+00,8.012231662834075507e+00,0.000000000000000000e+00,-1.000000009957215941e+00,0.000000000000000000e+00,1.082209992842468331e-09,0.000000000000000000e+00 +6.025199310477004744e+00,6.177000000000000313e+01,0.000000000000000000e+00,8.010983571101286671e+00,0.000000000000000000e+00,-1.000000009955865243e+00,0.000000000000000000e+00,6.570871249699938849e-10,0.000000000000000000e+00 +6.026447596647017235e+00,6.178000000000000114e+01,0.000000000000000000e+00,8.009735284918846787e+00,0.000000000000000000e+00,-1.000000009955045011e+00,0.000000000000000000e+00,-1.035631326564311116e-09,0.000000000000000000e+00 +6.027696077357588500e+00,6.178999999999999915e+01,0.000000000000000000e+00,8.008486804195847242e+00,0.000000000000000000e+00,-1.000000009956337976e+00,0.000000000000000000e+00,6.126041238830802553e-10,0.000000000000000000e+00 +6.028944752699697318e+00,6.180000000000000426e+01,0.000000000000000000e+00,8.007238128841306590e+00,0.000000000000000000e+00,-1.000000009955573033e+00,0.000000000000000000e+00,-4.747163951714103535e-11,0.000000000000000000e+00 +6.030193622764392636e+00,6.181000000000000227e+01,0.000000000000000000e+00,8.005989258764177663e+00,0.000000000000000000e+00,-1.000000009955632319e+00,0.000000000000000000e+00,-6.861870746905857336e-10,0.000000000000000000e+00 +6.031442687642796230e+00,6.182000000000000028e+01,0.000000000000000000e+00,8.004740193873338683e+00,0.000000000000000000e+00,-1.000000009956489411e+00,0.000000000000000000e+00,-1.155316093019480579e-10,0.000000000000000000e+00 +6.032691947426100043e+00,6.182999999999999829e+01,0.000000000000000000e+00,8.003490934077596819e+00,0.000000000000000000e+00,-1.000000009956633740e+00,0.000000000000000000e+00,5.750799095299875549e-10,0.000000000000000000e+00 +6.033941402205566185e+00,6.184000000000000341e+01,0.000000000000000000e+00,8.002241479285689962e+00,0.000000000000000000e+00,-1.000000009955915203e+00,0.000000000000000000e+00,2.978008222083787044e-10,0.000000000000000000e+00 +6.035191052072529594e+00,6.185000000000000142e+01,0.000000000000000000e+00,8.000991829406284950e+00,0.000000000000000000e+00,-1.000000009955543057e+00,0.000000000000000000e+00,-3.276008116653892235e-10,0.000000000000000000e+00 +6.036440897118396265e+00,6.185999999999999943e+01,0.000000000000000000e+00,7.999741984347975787e+00,0.000000000000000000e+00,-1.000000009955952507e+00,0.000000000000000000e+00,-1.142160609631958799e-10,0.000000000000000000e+00 +6.037690937434642358e+00,6.187000000000000455e+01,0.000000000000000000e+00,7.998491944019284539e+00,0.000000000000000000e+00,-1.000000009956095282e+00,0.000000000000000000e+00,-1.491858466312878520e-10,0.000000000000000000e+00 +6.038941173112815974e+00,6.188000000000000256e+01,0.000000000000000000e+00,7.997241708328663101e+00,0.000000000000000000e+00,-1.000000009956281799e+00,0.000000000000000000e+00,1.857428616894148062e-10,0.000000000000000000e+00 +6.040191604244538048e+00,6.189000000000000057e+01,0.000000000000000000e+00,7.995991277184491430e+00,0.000000000000000000e+00,-1.000000009956049540e+00,0.000000000000000000e+00,-1.951237929814943212e-10,0.000000000000000000e+00 +6.041442230921499679e+00,6.189999999999999858e+01,0.000000000000000000e+00,7.994740650495078427e+00,0.000000000000000000e+00,-1.000000009956293567e+00,0.000000000000000000e+00,4.617266664994113216e-10,0.000000000000000000e+00 +6.042693053235464795e+00,6.191000000000000369e+01,0.000000000000000000e+00,7.993489828168660161e+00,0.000000000000000000e+00,-1.000000009955716029e+00,0.000000000000000000e+00,-6.313359461617357173e-10,0.000000000000000000e+00 +6.043944071278267494e+00,6.192000000000000171e+01,0.000000000000000000e+00,7.992238810113402536e+00,0.000000000000000000e+00,-1.000000009956505842e+00,0.000000000000000000e+00,5.481842909480571832e-10,0.000000000000000000e+00 +6.045195285141815589e+00,6.192999999999999972e+01,0.000000000000000000e+00,7.990987596237396851e+00,0.000000000000000000e+00,-1.000000009955819946e+00,0.000000000000000000e+00,-4.881252486044002931e-10,0.000000000000000000e+00 +6.046446694918087950e+00,6.194000000000000483e+01,0.000000000000000000e+00,7.989736186448666011e+00,0.000000000000000000e+00,-1.000000009956430791e+00,0.000000000000000000e+00,2.810139258920749009e-10,0.000000000000000000e+00 +6.047698300699135388e+00,6.195000000000000284e+01,0.000000000000000000e+00,7.988484580655157430e+00,0.000000000000000000e+00,-1.000000009956079072e+00,0.000000000000000000e+00,7.006509615512050467e-11,0.000000000000000000e+00 +6.048950102577080656e+00,6.196000000000000085e+01,0.000000000000000000e+00,7.987232778764749241e+00,0.000000000000000000e+00,-1.000000009955991365e+00,0.000000000000000000e+00,-5.024387675298788122e-10,0.000000000000000000e+00 +6.050202100644119341e+00,6.196999999999999886e+01,0.000000000000000000e+00,7.985980780685245861e+00,0.000000000000000000e+00,-1.000000009956620417e+00,0.000000000000000000e+00,3.131548811083938177e-10,0.000000000000000000e+00 +6.051454294992518967e+00,6.198000000000000398e+01,0.000000000000000000e+00,7.984728586324378874e+00,0.000000000000000000e+00,-1.000000009956228286e+00,0.000000000000000000e+00,3.017587969261568602e-10,0.000000000000000000e+00 +6.052706685714619006e+00,6.199000000000000199e+01,0.000000000000000000e+00,7.983476195589809699e+00,0.000000000000000000e+00,-1.000000009955850366e+00,0.000000000000000000e+00,-4.855391932894300865e-10,0.000000000000000000e+00 +6.053959272902831756e+00,6.200000000000000000e+01,0.000000000000000000e+00,7.982223608389126035e+00,0.000000000000000000e+00,-1.000000009956458547e+00,0.000000000000000000e+00,2.663931760384675903e-10,0.000000000000000000e+00 +6.055212056649642349e+00,6.200999999999999801e+01,0.000000000000000000e+00,7.980970824629841864e+00,0.000000000000000000e+00,-1.000000009956124813e+00,0.000000000000000000e+00,-2.216936523605091446e-10,0.000000000000000000e+00 +6.056465037047608746e+00,6.202000000000000313e+01,0.000000000000000000e+00,7.979717844219401002e+00,0.000000000000000000e+00,-1.000000009956402591e+00,0.000000000000000000e+00,3.648245936737681244e-10,0.000000000000000000e+00 +6.057718214189359962e+00,6.203000000000000114e+01,0.000000000000000000e+00,7.978464667065172655e+00,0.000000000000000000e+00,-1.000000009955945401e+00,0.000000000000000000e+00,-7.516792873109585353e-10,0.000000000000000000e+00 +6.058971588167598732e+00,6.203999999999999915e+01,0.000000000000000000e+00,7.977211293074454979e+00,0.000000000000000000e+00,-1.000000009956887537e+00,0.000000000000000000e+00,4.382188109956208850e-10,0.000000000000000000e+00 +6.060225159075101509e+00,6.205000000000000426e+01,0.000000000000000000e+00,7.975957722154470630e+00,0.000000000000000000e+00,-1.000000009956338198e+00,0.000000000000000000e+00,2.798209042476976330e-11,0.000000000000000000e+00 +6.061478927004715800e+00,6.206000000000000227e+01,0.000000000000000000e+00,7.974703954212372992e+00,0.000000000000000000e+00,-1.000000009956303115e+00,0.000000000000000000e+00,3.298888599334060399e-10,0.000000000000000000e+00 +6.062732892049363720e+00,6.207000000000000028e+01,0.000000000000000000e+00,7.973449989155239948e+00,0.000000000000000000e+00,-1.000000009955889446e+00,0.000000000000000000e+00,-8.646934223540501168e-10,0.000000000000000000e+00 +6.063987054302040214e+00,6.207999999999999829e+01,0.000000000000000000e+00,7.972195826890077441e+00,0.000000000000000000e+00,-1.000000009956973912e+00,0.000000000000000000e+00,1.013075772544434196e-09,0.000000000000000000e+00 +6.065241413855812169e+00,6.209000000000000341e+01,0.000000000000000000e+00,7.970941467323815921e+00,0.000000000000000000e+00,-1.000000009955703151e+00,0.000000000000000000e+00,-7.601740037922641178e-10,0.000000000000000000e+00 +6.066495970803821081e+00,6.210000000000000142e+01,0.000000000000000000e+00,7.969686910363317445e+00,0.000000000000000000e+00,-1.000000009956656832e+00,0.000000000000000000e+00,7.591695460153731616e-11,0.000000000000000000e+00 +6.067750725239280385e+00,6.210999999999999943e+01,0.000000000000000000e+00,7.968432155915365023e+00,0.000000000000000000e+00,-1.000000009956561575e+00,0.000000000000000000e+00,1.859584085798681710e-10,0.000000000000000000e+00 +6.069005677255478126e+00,6.212000000000000455e+01,0.000000000000000000e+00,7.967177203886672388e+00,0.000000000000000000e+00,-1.000000009956328206e+00,0.000000000000000000e+00,-3.773423568251892808e-10,0.000000000000000000e+00 +6.070260826945775179e+00,6.213000000000000256e+01,0.000000000000000000e+00,7.965922054183878664e+00,0.000000000000000000e+00,-1.000000009956801827e+00,0.000000000000000000e+00,6.921275330200931051e-10,0.000000000000000000e+00 +6.071516174403606136e+00,6.214000000000000057e+01,0.000000000000000000e+00,7.964666706713548372e+00,0.000000000000000000e+00,-1.000000009955932967e+00,0.000000000000000000e+00,-4.994275832838969764e-10,0.000000000000000000e+00 +6.072771719722479311e+00,6.214999999999999858e+01,0.000000000000000000e+00,7.963411161382174974e+00,0.000000000000000000e+00,-1.000000009956560021e+00,0.000000000000000000e+00,4.455945862665417953e-11,0.000000000000000000e+00 +6.074027462995976734e+00,6.216000000000000369e+01,0.000000000000000000e+00,7.962155418096174664e+00,0.000000000000000000e+00,-1.000000009956504066e+00,0.000000000000000000e+00,-4.409276413482179362e-10,0.000000000000000000e+00 +6.075283404317754155e+00,6.217000000000000171e+01,0.000000000000000000e+00,7.960899476761892579e+00,0.000000000000000000e+00,-1.000000009957057845e+00,0.000000000000000000e+00,9.099989763143905567e-10,0.000000000000000000e+00 +6.076539543781541042e+00,6.217999999999999972e+01,0.000000000000000000e+00,7.959643337285598363e+00,0.000000000000000000e+00,-1.000000009955914759e+00,0.000000000000000000e+00,-9.155110555689604893e-10,0.000000000000000000e+00 +6.077795881481140583e+00,6.219000000000000483e+01,0.000000000000000000e+00,7.958386999573490606e+00,0.000000000000000000e+00,-1.000000009957064950e+00,0.000000000000000000e+00,3.240892389392908843e-10,0.000000000000000000e+00 +6.079052417510430573e+00,6.220000000000000284e+01,0.000000000000000000e+00,7.957130463531688847e+00,0.000000000000000000e+00,-1.000000009956657721e+00,0.000000000000000000e+00,1.796874134243726328e-10,0.000000000000000000e+00 +6.080309151963363412e+00,6.221000000000000085e+01,0.000000000000000000e+00,7.955873729066243349e+00,0.000000000000000000e+00,-1.000000009956431901e+00,0.000000000000000000e+00,-1.715328632672834910e-10,0.000000000000000000e+00 +6.081566084933964333e+00,6.221999999999999886e+01,0.000000000000000000e+00,7.954616796083127994e+00,0.000000000000000000e+00,-1.000000009956647506e+00,0.000000000000000000e+00,4.468687751855230155e-10,0.000000000000000000e+00 +6.082823216516333176e+00,6.223000000000000398e+01,0.000000000000000000e+00,7.953359664488242053e+00,0.000000000000000000e+00,-1.000000009956085734e+00,0.000000000000000000e+00,-7.231772475542041841e-10,0.000000000000000000e+00 +6.084080546804645273e+00,6.224000000000000199e+01,0.000000000000000000e+00,7.952102334187411969e+00,0.000000000000000000e+00,-1.000000009956995006e+00,0.000000000000000000e+00,3.035275122901950141e-10,0.000000000000000000e+00 +6.085338075893148790e+00,6.225000000000000000e+01,0.000000000000000000e+00,7.950844805086386913e+00,0.000000000000000000e+00,-1.000000009956613312e+00,0.000000000000000000e+00,2.084987230601026041e-10,0.000000000000000000e+00 +6.086595803876168276e+00,6.225999999999999801e+01,0.000000000000000000e+00,7.949587077090845000e+00,0.000000000000000000e+00,-1.000000009956351077e+00,0.000000000000000000e+00,-3.939843641568688884e-10,0.000000000000000000e+00 +6.087853730848101108e+00,6.227000000000000313e+01,0.000000000000000000e+00,7.948329150106387964e+00,0.000000000000000000e+00,-1.000000009956846680e+00,0.000000000000000000e+00,2.327881476247367926e-10,0.000000000000000000e+00 +6.089111856903420161e+00,6.228000000000000114e+01,0.000000000000000000e+00,7.947071024038542042e+00,0.000000000000000000e+00,-1.000000009956553804e+00,0.000000000000000000e+00,-1.046410317785374624e-10,0.000000000000000000e+00 +6.090370182136672916e+00,6.228999999999999915e+01,0.000000000000000000e+00,7.945812698792760642e+00,0.000000000000000000e+00,-1.000000009956685476e+00,0.000000000000000000e+00,-2.307736892697349884e-10,0.000000000000000000e+00 +6.091628706642482349e+00,6.230000000000000426e+01,0.000000000000000000e+00,7.944554174274420788e+00,0.000000000000000000e+00,-1.000000009956975910e+00,0.000000000000000000e+00,4.671192200484656241e-10,0.000000000000000000e+00 +6.092887430515545155e+00,6.231000000000000227e+01,0.000000000000000000e+00,7.943295450388824896e+00,0.000000000000000000e+00,-1.000000009956387936e+00,0.000000000000000000e+00,-7.612413624764206683e-10,0.000000000000000000e+00 +6.094146353850634412e+00,6.232000000000000028e+01,0.000000000000000000e+00,7.942036527041201666e+00,0.000000000000000000e+00,-1.000000009957346281e+00,0.000000000000000000e+00,6.200418052121762088e-10,0.000000000000000000e+00 +6.095405476742596917e+00,6.232999999999999829e+01,0.000000000000000000e+00,7.940777404136701634e+00,0.000000000000000000e+00,-1.000000009956565572e+00,0.000000000000000000e+00,1.810813364599626771e-10,0.000000000000000000e+00 +6.096664799286355851e+00,6.234000000000000341e+01,0.000000000000000000e+00,7.939518081580404285e+00,0.000000000000000000e+00,-1.000000009956337532e+00,0.000000000000000000e+00,-3.442996735120502363e-10,0.000000000000000000e+00 +6.097924321576909001e+00,6.235000000000000142e+01,0.000000000000000000e+00,7.938258559277310944e+00,0.000000000000000000e+00,-1.000000009956771185e+00,0.000000000000000000e+00,-3.430112006953233777e-10,0.000000000000000000e+00 +6.099184043709329650e+00,6.235999999999999943e+01,0.000000000000000000e+00,7.936998837132347440e+00,0.000000000000000000e+00,-1.000000009957203284e+00,0.000000000000000000e+00,2.363335181020271206e-10,0.000000000000000000e+00 +6.100443965778766575e+00,6.237000000000000455e+01,0.000000000000000000e+00,7.935738915050364994e+00,0.000000000000000000e+00,-1.000000009956905522e+00,0.000000000000000000e+00,3.279245790668012746e-10,0.000000000000000000e+00 +6.101704087880444050e+00,6.238000000000000256e+01,0.000000000000000000e+00,7.934478792936140223e+00,0.000000000000000000e+00,-1.000000009956492297e+00,0.000000000000000000e+00,-5.738209336268564202e-10,0.000000000000000000e+00 +6.102964410109662730e+00,6.239000000000000057e+01,0.000000000000000000e+00,7.933218470694373359e+00,0.000000000000000000e+00,-1.000000009957215497e+00,0.000000000000000000e+00,3.794332089829417647e-10,0.000000000000000000e+00 +6.104224932561796990e+00,6.239999999999999858e+01,0.000000000000000000e+00,7.931957948229687361e+00,0.000000000000000000e+00,-1.000000009956737212e+00,0.000000000000000000e+00,-1.134244013969425034e-10,0.000000000000000000e+00 +6.105485655332299366e+00,6.241000000000000369e+01,0.000000000000000000e+00,7.930697225446632359e+00,0.000000000000000000e+00,-1.000000009956880209e+00,0.000000000000000000e+00,2.361458801686019042e-10,0.000000000000000000e+00 +6.106746578516696111e+00,6.242000000000000171e+01,0.000000000000000000e+00,7.929436302249680324e+00,0.000000000000000000e+00,-1.000000009956582447e+00,0.000000000000000000e+00,-1.942039471765388212e-10,0.000000000000000000e+00 +6.108007702210591638e+00,6.242999999999999972e+01,0.000000000000000000e+00,7.928175178543228618e+00,0.000000000000000000e+00,-1.000000009956827363e+00,0.000000000000000000e+00,-2.344864155694366020e-10,0.000000000000000000e+00 +6.109269026509664080e+00,6.244000000000000483e+01,0.000000000000000000e+00,7.926913854231597334e+00,0.000000000000000000e+00,-1.000000009957123126e+00,0.000000000000000000e+00,1.684442931470994980e-10,0.000000000000000000e+00 +6.110530551509668840e+00,6.245000000000000284e+01,0.000000000000000000e+00,7.925652329219031067e+00,0.000000000000000000e+00,-1.000000009956910629e+00,0.000000000000000000e+00,-4.874779902394425076e-11,0.000000000000000000e+00 +6.111792277306437704e+00,6.246000000000000085e+01,0.000000000000000000e+00,7.924390603409698919e+00,0.000000000000000000e+00,-1.000000009956972136e+00,0.000000000000000000e+00,-2.734368952972115378e-10,0.000000000000000000e+00 +6.113054203995878844e+00,6.246999999999999886e+01,0.000000000000000000e+00,7.923128676707692719e+00,0.000000000000000000e+00,-1.000000009957317193e+00,0.000000000000000000e+00,6.620200656659813454e-10,0.000000000000000000e+00 +6.114316331673975924e+00,6.248000000000000398e+01,0.000000000000000000e+00,7.921866549017027914e+00,0.000000000000000000e+00,-1.000000009956481639e+00,0.000000000000000000e+00,-5.336829447192861774e-10,0.000000000000000000e+00 +6.115578660436789882e+00,6.249000000000000199e+01,0.000000000000000000e+00,7.920604220241645343e+00,0.000000000000000000e+00,-1.000000009957155322e+00,0.000000000000000000e+00,9.514715422544407013e-11,0.000000000000000000e+00 +6.116841190380458038e+00,6.250000000000000000e+01,0.000000000000000000e+00,7.919341690285405910e+00,0.000000000000000000e+00,-1.000000009957035196e+00,0.000000000000000000e+00,-1.842852557536268581e-10,0.000000000000000000e+00 +6.118103921601194095e+00,6.250999999999999801e+01,0.000000000000000000e+00,7.918078959052096799e+00,0.000000000000000000e+00,-1.000000009957267899e+00,0.000000000000000000e+00,3.526882428741219285e-10,0.000000000000000000e+00 +6.119366854195288141e+00,6.252000000000000313e+01,0.000000000000000000e+00,7.916816026445427035e+00,0.000000000000000000e+00,-1.000000009956822478e+00,0.000000000000000000e+00,-4.674219636750718195e-10,0.000000000000000000e+00 +6.120629988259108423e+00,6.253000000000000114e+01,0.000000000000000000e+00,7.915552892369030147e+00,0.000000000000000000e+00,-1.000000009957412894e+00,0.000000000000000000e+00,7.496188799905637481e-10,0.000000000000000000e+00 +6.121893323889098681e+00,6.253999999999999915e+01,0.000000000000000000e+00,7.914289556726460617e+00,0.000000000000000000e+00,-1.000000009956465874e+00,0.000000000000000000e+00,-9.515916488050676335e-10,0.000000000000000000e+00 +6.123156861181779931e+00,6.255000000000000426e+01,0.000000000000000000e+00,7.913026019421199209e+00,0.000000000000000000e+00,-1.000000009957668246e+00,0.000000000000000000e+00,6.037205713733948704e-10,0.000000000000000000e+00 +6.124420600233750456e+00,6.256000000000000227e+01,0.000000000000000000e+00,7.911762280356644972e+00,0.000000000000000000e+00,-1.000000009956905300e+00,0.000000000000000000e+00,-9.345985170549597663e-11,0.000000000000000000e+00 +6.125684541141685813e+00,6.257000000000000028e+01,0.000000000000000000e+00,7.910498339436125015e+00,0.000000000000000000e+00,-1.000000009957023428e+00,0.000000000000000000e+00,-2.076163471634528995e-10,0.000000000000000000e+00 +6.126948684002337941e+00,6.257999999999999829e+01,0.000000000000000000e+00,7.909234196562885622e+00,0.000000000000000000e+00,-1.000000009957285885e+00,0.000000000000000000e+00,3.140090574994411606e-10,0.000000000000000000e+00 +6.128213028912537830e+00,6.259000000000000341e+01,0.000000000000000000e+00,7.907969851640096692e+00,0.000000000000000000e+00,-1.000000009956888869e+00,0.000000000000000000e+00,-1.404737633173186983e-10,0.000000000000000000e+00 +6.129477575969191960e+00,6.260000000000000142e+01,0.000000000000000000e+00,7.906705304570851744e+00,0.000000000000000000e+00,-1.000000009957066505e+00,0.000000000000000000e+00,-4.059042582975137871e-10,0.000000000000000000e+00 +6.130742325269284976e+00,6.260999999999999943e+01,0.000000000000000000e+00,7.905440555258165247e+00,0.000000000000000000e+00,-1.000000009957579872e+00,0.000000000000000000e+00,6.824841331819207267e-10,0.000000000000000000e+00 +6.132007276909879678e+00,6.262000000000000455e+01,0.000000000000000000e+00,7.904175603604974398e+00,0.000000000000000000e+00,-1.000000009956716562e+00,0.000000000000000000e+00,-7.071215503567804850e-10,0.000000000000000000e+00 +6.133272430988116142e+00,6.263000000000000256e+01,0.000000000000000000e+00,7.902910449514140900e+00,0.000000000000000000e+00,-1.000000009957611180e+00,0.000000000000000000e+00,4.751994686032888779e-10,0.000000000000000000e+00 +6.134537787601212599e+00,6.264000000000000057e+01,0.000000000000000000e+00,7.901645092888444744e+00,0.000000000000000000e+00,-1.000000009957009883e+00,0.000000000000000000e+00,-1.554502649336689115e-10,0.000000000000000000e+00 +6.135803346846463668e+00,6.264999999999999858e+01,0.000000000000000000e+00,7.900379533630592199e+00,0.000000000000000000e+00,-1.000000009957206615e+00,0.000000000000000000e+00,2.294541541212072667e-10,0.000000000000000000e+00 +6.137069108821243901e+00,6.266000000000000369e+01,0.000000000000000000e+00,7.899113771643208715e+00,0.000000000000000000e+00,-1.000000009956916180e+00,0.000000000000000000e+00,-5.335532925107831452e-10,0.000000000000000000e+00 +6.138335073623004234e+00,6.267000000000000171e+01,0.000000000000000000e+00,7.897847806828843353e+00,0.000000000000000000e+00,-1.000000009957591640e+00,0.000000000000000000e+00,3.817749377847155546e-10,0.000000000000000000e+00 +6.139601241349274652e+00,6.267999999999999972e+01,0.000000000000000000e+00,7.896581639089965243e+00,0.000000000000000000e+00,-1.000000009957108249e+00,0.000000000000000000e+00,-2.950961008571708647e-10,0.000000000000000000e+00 +6.140867612097662409e+00,6.269000000000000483e+01,0.000000000000000000e+00,7.895315268328968017e+00,0.000000000000000000e+00,-1.000000009957481950e+00,0.000000000000000000e+00,2.613890229836377728e-10,0.000000000000000000e+00 +6.142134185965853810e+00,6.270000000000000284e+01,0.000000000000000000e+00,7.894048694448164483e+00,0.000000000000000000e+00,-1.000000009957150882e+00,0.000000000000000000e+00,-1.097272158184681455e-10,0.000000000000000000e+00 +6.143400963051613317e+00,6.271000000000000085e+01,0.000000000000000000e+00,7.892781917349791065e+00,0.000000000000000000e+00,-1.000000009957289882e+00,0.000000000000000000e+00,-2.460579698206701180e-10,0.000000000000000000e+00 +6.144667943452784442e+00,6.271999999999999886e+01,0.000000000000000000e+00,7.891514936936004254e+00,0.000000000000000000e+00,-1.000000009957601632e+00,0.000000000000000000e+00,4.606713403899566142e-10,0.000000000000000000e+00 +6.145935127267287967e+00,6.273000000000000398e+01,0.000000000000000000e+00,7.890247753108882378e+00,0.000000000000000000e+00,-1.000000009957017877e+00,0.000000000000000000e+00,-7.002691819563411571e-10,0.000000000000000000e+00 +6.147202514593124612e+00,6.274000000000000199e+01,0.000000000000000000e+00,7.888980365770426495e+00,0.000000000000000000e+00,-1.000000009957905389e+00,0.000000000000000000e+00,7.504306484431679839e-10,0.000000000000000000e+00 +6.148470105528372365e+00,6.275000000000000000e+01,0.000000000000000000e+00,7.887712774822555950e+00,0.000000000000000000e+00,-1.000000009956954150e+00,0.000000000000000000e+00,-6.611625852349677428e-10,0.000000000000000000e+00 +6.149737900171189153e+00,6.275999999999999801e+01,0.000000000000000000e+00,7.886444980167115482e+00,0.000000000000000000e+00,-1.000000009957792368e+00,0.000000000000000000e+00,6.475725186451783749e-10,0.000000000000000000e+00 +6.151005898619811951e+00,6.277000000000000313e+01,0.000000000000000000e+00,7.885176981705866339e+00,0.000000000000000000e+00,-1.000000009956971248e+00,0.000000000000000000e+00,-2.405683024534224567e-10,0.000000000000000000e+00 +6.152274100972555892e+00,6.278000000000000114e+01,0.000000000000000000e+00,7.883908779340495165e+00,0.000000000000000000e+00,-1.000000009957276337e+00,0.000000000000000000e+00,-5.083682607144267720e-10,0.000000000000000000e+00 +6.153542507327815159e+00,6.278999999999999915e+01,0.000000000000000000e+00,7.882640372972606002e+00,0.000000000000000000e+00,-1.000000009957921154e+00,0.000000000000000000e+00,4.514017942080250689e-10,0.000000000000000000e+00 +6.154811117784063867e+00,6.280000000000000426e+01,0.000000000000000000e+00,7.881371762503724732e+00,0.000000000000000000e+00,-1.000000009957348501e+00,0.000000000000000000e+00,-6.597560618857088875e-11,0.000000000000000000e+00 +6.156079932439854296e+00,6.281000000000000227e+01,0.000000000000000000e+00,7.880102947835299965e+00,0.000000000000000000e+00,-1.000000009957432212e+00,0.000000000000000000e+00,2.026192372460328657e-10,0.000000000000000000e+00 +6.157348951393819547e+00,6.282000000000000028e+01,0.000000000000000000e+00,7.878833928868698600e+00,0.000000000000000000e+00,-1.000000009957175084e+00,0.000000000000000000e+00,-3.418430315928907811e-10,0.000000000000000000e+00 +6.158618174744670881e+00,6.282999999999999829e+01,0.000000000000000000e+00,7.877564705505209375e+00,0.000000000000000000e+00,-1.000000009957608960e+00,0.000000000000000000e+00,1.084485860539270373e-11,0.000000000000000000e+00 +6.159887602591199496e+00,6.284000000000000341e+01,0.000000000000000000e+00,7.876295277646040205e+00,0.000000000000000000e+00,-1.000000009957595193e+00,0.000000000000000000e+00,2.130146647554926175e-10,0.000000000000000000e+00 +6.161157235032276525e+00,6.285000000000000142e+01,0.000000000000000000e+00,7.875025645192320845e+00,0.000000000000000000e+00,-1.000000009957324743e+00,0.000000000000000000e+00,-2.297669543023841298e-10,0.000000000000000000e+00 +6.162427072166852149e+00,6.285999999999999943e+01,0.000000000000000000e+00,7.873755808045101112e+00,0.000000000000000000e+00,-1.000000009957616509e+00,0.000000000000000000e+00,-1.601465697868967238e-10,0.000000000000000000e+00 +6.163697114093956486e+00,6.287000000000000455e+01,0.000000000000000000e+00,7.872485766105350002e+00,0.000000000000000000e+00,-1.000000009957819902e+00,0.000000000000000000e+00,4.775653453359355012e-10,0.000000000000000000e+00 +6.164967360912700478e+00,6.288000000000000256e+01,0.000000000000000000e+00,7.871215519273957462e+00,0.000000000000000000e+00,-1.000000009957213276e+00,0.000000000000000000e+00,-4.622827686979661867e-10,0.000000000000000000e+00 +6.166237812722273226e+00,6.289000000000000057e+01,0.000000000000000000e+00,7.869945067451734388e+00,0.000000000000000000e+00,-1.000000009957800584e+00,0.000000000000000000e+00,3.785039174553185609e-10,0.000000000000000000e+00 +6.167508469621945544e+00,6.289999999999999858e+01,0.000000000000000000e+00,7.868674410539409081e+00,0.000000000000000000e+00,-1.000000009957319635e+00,0.000000000000000000e+00,-2.456558561285329008e-10,0.000000000000000000e+00 +6.168779331711067293e+00,6.291000000000000369e+01,0.000000000000000000e+00,7.867403548437632566e+00,0.000000000000000000e+00,-1.000000009957631830e+00,0.000000000000000000e+00,-7.773769581508874599e-11,0.000000000000000000e+00 +6.170050399089070048e+00,6.292000000000000171e+01,0.000000000000000000e+00,7.866132481046973268e+00,0.000000000000000000e+00,-1.000000009957730640e+00,0.000000000000000000e+00,-1.612141593555795176e-10,0.000000000000000000e+00 +6.171321671855463542e+00,6.292999999999999972e+01,0.000000000000000000e+00,7.864861208267920567e+00,0.000000000000000000e+00,-1.000000009957935587e+00,0.000000000000000000e+00,6.581993149171025549e-10,0.000000000000000000e+00 +6.172593150109840110e+00,6.294000000000000483e+01,0.000000000000000000e+00,7.863589730000883016e+00,0.000000000000000000e+00,-1.000000009957098701e+00,0.000000000000000000e+00,-8.581922622087198331e-10,0.000000000000000000e+00 +6.173864833951871134e+00,6.295000000000000284e+01,0.000000000000000000e+00,7.862318046146190120e+00,0.000000000000000000e+00,-1.000000009958190050e+00,0.000000000000000000e+00,2.891020464006042109e-10,0.000000000000000000e+00 +6.175136723481308820e+00,6.296000000000000085e+01,0.000000000000000000e+00,7.861046156604087010e+00,0.000000000000000000e+00,-1.000000009957822344e+00,0.000000000000000000e+00,3.122704666883515772e-10,0.000000000000000000e+00 +6.176408818797986200e+00,6.296999999999999886e+01,0.000000000000000000e+00,7.859774061274742429e+00,0.000000000000000000e+00,-1.000000009957425107e+00,0.000000000000000000e+00,-1.828991006695075353e-10,0.000000000000000000e+00 +6.177681120001817128e+00,6.298000000000000398e+01,0.000000000000000000e+00,7.858501760058242525e+00,0.000000000000000000e+00,-1.000000009957657809e+00,0.000000000000000000e+00,-4.170401625489361232e-11,0.000000000000000000e+00 +6.178953627192797171e+00,6.299000000000000199e+01,0.000000000000000000e+00,7.857229252854591728e+00,0.000000000000000000e+00,-1.000000009957710878e+00,0.000000000000000000e+00,2.433794234531417666e-10,0.000000000000000000e+00 +6.180226340471000945e+00,6.300000000000000000e+01,0.000000000000000000e+00,7.855956539563714536e+00,0.000000000000000000e+00,-1.000000009957401126e+00,0.000000000000000000e+00,-3.675393418247795712e-10,0.000000000000000000e+00 +6.181499259936585666e+00,6.300999999999999801e+01,0.000000000000000000e+00,7.854683620085454621e+00,0.000000000000000000e+00,-1.000000009957868974e+00,0.000000000000000000e+00,-1.723161039778193642e-10,0.000000000000000000e+00 +6.182772385689789374e+00,6.302000000000000313e+01,0.000000000000000000e+00,7.853410494319573054e+00,0.000000000000000000e+00,-1.000000009958088354e+00,0.000000000000000000e+00,3.365548340913799113e-10,0.000000000000000000e+00 +6.184045717830931821e+00,6.303000000000000114e+01,0.000000000000000000e+00,7.852137162165750972e+00,0.000000000000000000e+00,-1.000000009957659808e+00,0.000000000000000000e+00,1.210006137629233944e-10,0.000000000000000000e+00 +6.185319256460412696e+00,6.303999999999999915e+01,0.000000000000000000e+00,7.850863623523588686e+00,0.000000000000000000e+00,-1.000000009957505709e+00,0.000000000000000000e+00,-2.138957825540065037e-10,0.000000000000000000e+00 +6.186593001678714288e+00,6.305000000000000426e+01,0.000000000000000000e+00,7.849589878292603906e+00,0.000000000000000000e+00,-1.000000009957778158e+00,0.000000000000000000e+00,-6.361800654223870354e-11,0.000000000000000000e+00 +6.187866953586399710e+00,6.306000000000000227e+01,0.000000000000000000e+00,7.848315926372232632e+00,0.000000000000000000e+00,-1.000000009957859204e+00,0.000000000000000000e+00,8.086017610679432004e-11,0.000000000000000000e+00 +6.189141112284114676e+00,6.307000000000000028e+01,0.000000000000000000e+00,7.847041767661830036e+00,0.000000000000000000e+00,-1.000000009957756175e+00,0.000000000000000000e+00,-2.691997631706916764e-10,0.000000000000000000e+00 +6.190415477872585726e+00,6.307999999999999829e+01,0.000000000000000000e+00,7.845767402060669582e+00,0.000000000000000000e+00,-1.000000009958099234e+00,0.000000000000000000e+00,3.641010575329683638e-11,0.000000000000000000e+00 +6.191690050452621108e+00,6.309000000000000341e+01,0.000000000000000000e+00,7.844492829467942130e+00,0.000000000000000000e+00,-1.000000009958052827e+00,0.000000000000000000e+00,-3.779765265209497234e-11,0.000000000000000000e+00 +6.192964830125110787e+00,6.310000000000000142e+01,0.000000000000000000e+00,7.843218049782757717e+00,0.000000000000000000e+00,-1.000000009958101010e+00,0.000000000000000000e+00,6.576071100101652388e-10,0.000000000000000000e+00 +6.194239816991028214e+00,6.310999999999999943e+01,0.000000000000000000e+00,7.841943062904143780e+00,0.000000000000000000e+00,-1.000000009957262570e+00,0.000000000000000000e+00,-5.507609015068705234e-10,0.000000000000000000e+00 +6.195515011151427665e+00,6.312000000000000455e+01,0.000000000000000000e+00,7.840667868731046930e+00,0.000000000000000000e+00,-1.000000009957964897e+00,0.000000000000000000e+00,-3.274779616609513228e-10,0.000000000000000000e+00 +6.196790412707446016e+00,6.313000000000000256e+01,0.000000000000000000e+00,7.839392467162328515e+00,0.000000000000000000e+00,-1.000000009958382563e+00,0.000000000000000000e+00,2.913923100595846795e-10,0.000000000000000000e+00 +6.198066021760301858e+00,6.314000000000000057e+01,0.000000000000000000e+00,7.838116858096769946e+00,0.000000000000000000e+00,-1.000000009958010860e+00,0.000000000000000000e+00,2.723744093140788931e-10,0.000000000000000000e+00 +6.199341838411296379e+00,6.314999999999999858e+01,0.000000000000000000e+00,7.836841041433070920e+00,0.000000000000000000e+00,-1.000000009957663361e+00,0.000000000000000000e+00,-3.266220768243205210e-10,0.000000000000000000e+00 +6.200617862761813370e+00,6.316000000000000369e+01,0.000000000000000000e+00,7.835565017069847649e+00,0.000000000000000000e+00,-1.000000009958080138e+00,0.000000000000000000e+00,1.889471603297522098e-10,0.000000000000000000e+00 +6.201894094913319222e+00,6.317000000000000171e+01,0.000000000000000000e+00,7.834288784905632852e+00,0.000000000000000000e+00,-1.000000009957838998e+00,0.000000000000000000e+00,-3.047711849813931702e-10,0.000000000000000000e+00 +6.203170534967362926e+00,6.317999999999999972e+01,0.000000000000000000e+00,7.833012344838878427e+00,0.000000000000000000e+00,-1.000000009958228020e+00,0.000000000000000000e+00,4.311670487945469135e-10,0.000000000000000000e+00 +6.204447183025576074e+00,6.319000000000000483e+01,0.000000000000000000e+00,7.831735696767951893e+00,0.000000000000000000e+00,-1.000000009957677571e+00,0.000000000000000000e+00,-2.707614683543124739e-10,0.000000000000000000e+00 +6.205724039189673746e+00,6.320000000000000284e+01,0.000000000000000000e+00,7.830458840591139946e+00,0.000000000000000000e+00,-1.000000009958023295e+00,0.000000000000000000e+00,-1.724801450523652194e-10,0.000000000000000000e+00 +6.207001103561452737e+00,6.321000000000000085e+01,0.000000000000000000e+00,7.829181776206644017e+00,0.000000000000000000e+00,-1.000000009958243563e+00,0.000000000000000000e+00,2.388599487203697126e-10,0.000000000000000000e+00 +6.208278376242793328e+00,6.321999999999999886e+01,0.000000000000000000e+00,7.827904503512583823e+00,0.000000000000000000e+00,-1.000000009957938474e+00,0.000000000000000000e+00,-6.709235696691034058e-11,0.000000000000000000e+00 +6.209555857335659290e+00,6.323000000000000398e+01,0.000000000000000000e+00,7.826627022406996481e+00,0.000000000000000000e+00,-1.000000009958024183e+00,0.000000000000000000e+00,5.630667388478431622e-11,0.000000000000000000e+00 +6.210833546942097882e+00,6.324000000000000199e+01,0.000000000000000000e+00,7.825349332787834733e+00,0.000000000000000000e+00,-1.000000009957952241e+00,0.000000000000000000e+00,-4.204935374418141545e-10,0.000000000000000000e+00 +6.212111445164238965e+00,6.325000000000000000e+01,0.000000000000000000e+00,7.824071434552968718e+00,0.000000000000000000e+00,-1.000000009958489589e+00,0.000000000000000000e+00,7.362647100802695975e-10,0.000000000000000000e+00 +6.213389552104295888e+00,6.325999999999999801e+01,0.000000000000000000e+00,7.822793327600184199e+00,0.000000000000000000e+00,-1.000000009957548563e+00,0.000000000000000000e+00,-7.649787873098825713e-10,0.000000000000000000e+00 +6.214667867864565487e+00,6.327000000000000313e+01,0.000000000000000000e+00,7.821515011827186115e+00,0.000000000000000000e+00,-1.000000009958526448e+00,0.000000000000000000e+00,5.706879042413988591e-10,0.000000000000000000e+00 +6.215946392547428090e+00,6.328000000000000114e+01,0.000000000000000000e+00,7.820236487131591474e+00,0.000000000000000000e+00,-1.000000009957796809e+00,0.000000000000000000e+00,-6.331065057115066842e-10,0.000000000000000000e+00 +6.217225126255347512e+00,6.328999999999999915e+01,0.000000000000000000e+00,7.818957753410938238e+00,0.000000000000000000e+00,-1.000000009958606384e+00,0.000000000000000000e+00,5.722374741888292639e-10,0.000000000000000000e+00 +6.218504069090872832e+00,6.330000000000000426e+01,0.000000000000000000e+00,7.817678810562676439e+00,0.000000000000000000e+00,-1.000000009957874525e+00,0.000000000000000000e+00,-9.998630800831745287e-11,0.000000000000000000e+00 +6.219783221156635733e+00,6.331000000000000227e+01,0.000000000000000000e+00,7.816399658484176172e+00,0.000000000000000000e+00,-1.000000009958002423e+00,0.000000000000000000e+00,-4.179299212843078421e-10,0.000000000000000000e+00 +6.221062582555351383e+00,6.332000000000000028e+01,0.000000000000000000e+00,7.815120297072720490e+00,0.000000000000000000e+00,-1.000000009958537106e+00,0.000000000000000000e+00,2.188219981793238162e-10,0.000000000000000000e+00 +6.222342153389820218e+00,6.332999999999999829e+01,0.000000000000000000e+00,7.813840726225508959e+00,0.000000000000000000e+00,-1.000000009958257108e+00,0.000000000000000000e+00,2.415149478386593147e-10,0.000000000000000000e+00 +6.223621933762926162e+00,6.334000000000000341e+01,0.000000000000000000e+00,7.812560945839658544e+00,0.000000000000000000e+00,-1.000000009957948022e+00,0.000000000000000000e+00,-2.902215015507747093e-10,0.000000000000000000e+00 +6.224901923777637514e+00,6.335000000000000142e+01,0.000000000000000000e+00,7.811280955812200943e+00,0.000000000000000000e+00,-1.000000009958319502e+00,0.000000000000000000e+00,3.090794878536882373e-10,0.000000000000000000e+00 +6.226182123537006952e+00,6.335999999999999943e+01,0.000000000000000000e+00,7.810000756040082592e+00,0.000000000000000000e+00,-1.000000009957923819e+00,0.000000000000000000e+00,-6.114678245027723125e-10,0.000000000000000000e+00 +6.227462533144172419e+00,6.337000000000000455e+01,0.000000000000000000e+00,7.808720346420167324e+00,0.000000000000000000e+00,-1.000000009958706748e+00,0.000000000000000000e+00,2.585221378417761518e-10,0.000000000000000000e+00 +6.228743152702354458e+00,6.338000000000000256e+01,0.000000000000000000e+00,7.807439726849231931e+00,0.000000000000000000e+00,-1.000000009958375680e+00,0.000000000000000000e+00,2.690546997656807898e-10,0.000000000000000000e+00 +6.230023982314859765e+00,6.339000000000000057e+01,0.000000000000000000e+00,7.806158897223971493e+00,0.000000000000000000e+00,-1.000000009958031066e+00,0.000000000000000000e+00,2.201310644761465836e-11,0.000000000000000000e+00 +6.231305022085079415e+00,6.339999999999999858e+01,0.000000000000000000e+00,7.804877857440994937e+00,0.000000000000000000e+00,-1.000000009958002867e+00,0.000000000000000000e+00,-4.232061751679096514e-10,0.000000000000000000e+00 +6.232586272116489745e+00,6.341000000000000369e+01,0.000000000000000000e+00,7.803596607396825924e+00,0.000000000000000000e+00,-1.000000009958545100e+00,0.000000000000000000e+00,7.520119921467444603e-11,0.000000000000000000e+00 +6.233867732512651472e+00,6.342000000000000171e+01,0.000000000000000000e+00,7.802315146987902850e+00,0.000000000000000000e+00,-1.000000009958448732e+00,0.000000000000000000e+00,-4.729621217175899258e-11,0.000000000000000000e+00 +6.235149403377210575e+00,6.342999999999999972e+01,0.000000000000000000e+00,7.801033476110580622e+00,0.000000000000000000e+00,-1.000000009958509350e+00,0.000000000000000000e+00,3.519784469098552503e-10,0.000000000000000000e+00 +6.236431284813897413e+00,6.344000000000000483e+01,0.000000000000000000e+00,7.799751594661127996e+00,0.000000000000000000e+00,-1.000000009958058156e+00,0.000000000000000000e+00,-2.900920375261104279e-10,0.000000000000000000e+00 +6.237713376926528497e+00,6.345000000000000284e+01,0.000000000000000000e+00,7.798469502535729347e+00,0.000000000000000000e+00,-1.000000009958430081e+00,0.000000000000000000e+00,2.486589202464208212e-10,0.000000000000000000e+00 +6.238995679819006490e+00,6.346000000000000085e+01,0.000000000000000000e+00,7.797187199630482013e+00,0.000000000000000000e+00,-1.000000009958111225e+00,0.000000000000000000e+00,-1.331387657125446982e-10,0.000000000000000000e+00 +6.240278193595317546e+00,6.346999999999999886e+01,0.000000000000000000e+00,7.795904685841399839e+00,0.000000000000000000e+00,-1.000000009958281977e+00,0.000000000000000000e+00,-2.954882849233457324e-10,0.000000000000000000e+00 +6.241560918359533972e+00,6.348000000000000398e+01,0.000000000000000000e+00,7.794621961064409632e+00,0.000000000000000000e+00,-1.000000009958661007e+00,0.000000000000000000e+00,3.612083084356992073e-10,0.000000000000000000e+00 +6.242843854215814225e+00,6.349000000000000199e+01,0.000000000000000000e+00,7.793339025195352932e+00,0.000000000000000000e+00,-1.000000009958197600e+00,0.000000000000000000e+00,-2.616468953963251794e-10,0.000000000000000000e+00 +6.244127001268402033e+00,6.350000000000000000e+01,0.000000000000000000e+00,7.792055878129986901e+00,0.000000000000000000e+00,-1.000000009958533331e+00,0.000000000000000000e+00,5.450079502391393299e-11,0.000000000000000000e+00 +6.245410359621628160e+00,6.350999999999999801e+01,0.000000000000000000e+00,7.790772519763980775e+00,0.000000000000000000e+00,-1.000000009958463387e+00,0.000000000000000000e+00,-2.484134972920121472e-10,0.000000000000000000e+00 +6.246693929379906862e+00,6.352000000000000313e+01,0.000000000000000000e+00,7.789488949992919409e+00,0.000000000000000000e+00,-1.000000009958782243e+00,0.000000000000000000e+00,5.067769009654389155e-10,0.000000000000000000e+00 +6.247977710647740324e+00,6.353000000000000114e+01,0.000000000000000000e+00,7.788205168712300619e+00,0.000000000000000000e+00,-1.000000009958131653e+00,0.000000000000000000e+00,-3.140461354607445794e-10,0.000000000000000000e+00 +6.249261703529716883e+00,6.353999999999999915e+01,0.000000000000000000e+00,7.786921175817537843e+00,0.000000000000000000e+00,-1.000000009958534886e+00,0.000000000000000000e+00,4.391771343609584217e-11,0.000000000000000000e+00 +6.250545908130510142e+00,6.355000000000000426e+01,0.000000000000000000e+00,7.785636971203955703e+00,0.000000000000000000e+00,-1.000000009958478486e+00,0.000000000000000000e+00,2.472124920065800627e-11,0.000000000000000000e+00 +6.251830324554880747e+00,6.356000000000000227e+01,0.000000000000000000e+00,7.784352554766794441e+00,0.000000000000000000e+00,-1.000000009958446734e+00,0.000000000000000000e+00,-3.109523804229011032e-10,0.000000000000000000e+00 +6.253114952907674606e+00,6.357000000000000028e+01,0.000000000000000000e+00,7.783067926401207259e+00,0.000000000000000000e+00,-1.000000009958846192e+00,0.000000000000000000e+00,1.740285560522195622e-10,0.000000000000000000e+00 +6.254399793293826448e+00,6.357999999999999829e+01,0.000000000000000000e+00,7.781783086002260319e+00,0.000000000000000000e+00,-1.000000009958622593e+00,0.000000000000000000e+00,-7.429982689057749991e-11,0.000000000000000000e+00 +6.255684845818354489e+00,6.359000000000000341e+01,0.000000000000000000e+00,7.780498033464934515e+00,0.000000000000000000e+00,-1.000000009958718072e+00,0.000000000000000000e+00,8.119802776215310741e-11,0.000000000000000000e+00 +6.256970110586366651e+00,6.360000000000000142e+01,0.000000000000000000e+00,7.779212768684122814e+00,0.000000000000000000e+00,-1.000000009958613711e+00,0.000000000000000000e+00,1.630601621202612367e-10,0.000000000000000000e+00 +6.258255587703056122e+00,6.360999999999999943e+01,0.000000000000000000e+00,7.777927291554632028e+00,0.000000000000000000e+00,-1.000000009958404101e+00,0.000000000000000000e+00,2.322877936032026100e-10,0.000000000000000000e+00 +6.259541277273703130e+00,6.362000000000000455e+01,0.000000000000000000e+00,7.776641601971181927e+00,0.000000000000000000e+00,-1.000000009958105451e+00,0.000000000000000000e+00,-7.238583420546439207e-10,0.000000000000000000e+00 +6.260827179403674947e+00,6.363000000000000256e+01,0.000000000000000000e+00,7.775355699828405243e+00,0.000000000000000000e+00,-1.000000009959036262e+00,0.000000000000000000e+00,5.773335023434841422e-10,0.000000000000000000e+00 +6.262113294198425884e+00,6.364000000000000057e+01,0.000000000000000000e+00,7.774069585020845885e+00,0.000000000000000000e+00,-1.000000009958293745e+00,0.000000000000000000e+00,-6.357558542198609698e-10,0.000000000000000000e+00 +6.263399621763498182e+00,6.364999999999999858e+01,0.000000000000000000e+00,7.772783257442964278e+00,0.000000000000000000e+00,-1.000000009959111535e+00,0.000000000000000000e+00,5.301978893005273873e-10,0.000000000000000000e+00 +6.264686162204520237e+00,6.366000000000000369e+01,0.000000000000000000e+00,7.771496716989129361e+00,0.000000000000000000e+00,-1.000000009958429414e+00,0.000000000000000000e+00,-1.580666929071226621e-10,0.000000000000000000e+00 +6.265972915627209261e+00,6.367000000000000171e+01,0.000000000000000000e+00,7.770209963553626586e+00,0.000000000000000000e+00,-1.000000009958632807e+00,0.000000000000000000e+00,4.416852995947025571e-11,0.000000000000000000e+00 +6.267259882137368621e+00,6.367999999999999972e+01,0.000000000000000000e+00,7.768922997030650812e+00,0.000000000000000000e+00,-1.000000009958575964e+00,0.000000000000000000e+00,-4.107337948850981374e-10,0.000000000000000000e+00 +6.268547061840890500e+00,6.369000000000000483e+01,0.000000000000000000e+00,7.767635817314310742e+00,0.000000000000000000e+00,-1.000000009959104652e+00,0.000000000000000000e+00,6.828331278351775471e-10,0.000000000000000000e+00 +6.269834454843754123e+00,6.370000000000000284e+01,0.000000000000000000e+00,7.766348424298626263e+00,0.000000000000000000e+00,-1.000000009958225577e+00,0.000000000000000000e+00,-3.655888627277079079e-10,0.000000000000000000e+00 +6.271122061252025759e+00,6.371000000000000085e+01,0.000000000000000000e+00,7.765060817877531996e+00,0.000000000000000000e+00,-1.000000009958696312e+00,0.000000000000000000e+00,-2.784566626361998467e-10,0.000000000000000000e+00 +6.272409881171861379e+00,6.371999999999999886e+01,0.000000000000000000e+00,7.763772997944871079e+00,0.000000000000000000e+00,-1.000000009959054914e+00,0.000000000000000000e+00,4.687294726005065503e-10,0.000000000000000000e+00 +6.273697914709503998e+00,6.373000000000000398e+01,0.000000000000000000e+00,7.762484964394400500e+00,0.000000000000000000e+00,-1.000000009958451175e+00,0.000000000000000000e+00,-2.032145512536275980e-10,0.000000000000000000e+00 +6.274986161971285448e+00,6.374000000000000199e+01,0.000000000000000000e+00,7.761196717119790200e+00,0.000000000000000000e+00,-1.000000009958712965e+00,0.000000000000000000e+00,-9.116425533043079460e-11,0.000000000000000000e+00 +6.276274623063624603e+00,6.375000000000000000e+01,0.000000000000000000e+00,7.759908256014619532e+00,0.000000000000000000e+00,-1.000000009958830427e+00,0.000000000000000000e+00,-2.040086183346125671e-10,0.000000000000000000e+00 +6.277563298093030042e+00,6.375999999999999801e+01,0.000000000000000000e+00,7.758619580972380803e+00,0.000000000000000000e+00,-1.000000009959093328e+00,0.000000000000000000e+00,5.512830782785997308e-11,0.000000000000000000e+00 +6.278852187166097387e+00,6.377000000000000313e+01,0.000000000000000000e+00,7.757330691886477503e+00,0.000000000000000000e+00,-1.000000009959022274e+00,0.000000000000000000e+00,2.135867051653413202e-10,0.000000000000000000e+00 +6.280141290389511077e+00,6.378000000000000114e+01,0.000000000000000000e+00,7.756041588650225194e+00,0.000000000000000000e+00,-1.000000009958746938e+00,0.000000000000000000e+00,3.335876587676863841e-10,0.000000000000000000e+00 +6.281430607870045257e+00,6.378999999999999915e+01,0.000000000000000000e+00,7.754752271156850618e+00,0.000000000000000000e+00,-1.000000009958316838e+00,0.000000000000000000e+00,-5.914729606409658973e-10,0.000000000000000000e+00 +6.282720139714562890e+00,6.380000000000000426e+01,0.000000000000000000e+00,7.753462739299491702e+00,0.000000000000000000e+00,-1.000000009959079561e+00,0.000000000000000000e+00,1.721614570748706610e-10,0.000000000000000000e+00 +6.284009886030013980e+00,6.381000000000000227e+01,0.000000000000000000e+00,7.752172992971195775e+00,0.000000000000000000e+00,-1.000000009958857516e+00,0.000000000000000000e+00,1.549195370581307936e-11,0.000000000000000000e+00 +6.285299846923439127e+00,6.382000000000000028e+01,0.000000000000000000e+00,7.750883032064924016e+00,0.000000000000000000e+00,-1.000000009958837532e+00,0.000000000000000000e+00,6.935798295520188741e-11,0.000000000000000000e+00 +6.286590022501967745e+00,6.382999999999999829e+01,0.000000000000000000e+00,7.749592856473547009e+00,0.000000000000000000e+00,-1.000000009958748048e+00,0.000000000000000000e+00,-1.373162716748120017e-10,0.000000000000000000e+00 +6.287880412872817182e+00,6.384000000000000341e+01,0.000000000000000000e+00,7.748302466089846519e+00,0.000000000000000000e+00,-1.000000009958925240e+00,0.000000000000000000e+00,-8.774390675605085568e-12,0.000000000000000000e+00 +6.289171018143296266e+00,6.385000000000000142e+01,0.000000000000000000e+00,7.747011860806514605e+00,0.000000000000000000e+00,-1.000000009958936564e+00,0.000000000000000000e+00,-1.599769434823552192e-11,0.000000000000000000e+00 +6.290461838420800866e+00,6.385999999999999943e+01,0.000000000000000000e+00,7.745721040516154510e+00,0.000000000000000000e+00,-1.000000009958957214e+00,0.000000000000000000e+00,-9.579818315436079385e-11,0.000000000000000000e+00 +6.291752873812818336e+00,6.387000000000000455e+01,0.000000000000000000e+00,7.744430005111279769e+00,0.000000000000000000e+00,-1.000000009959080893e+00,0.000000000000000000e+00,3.470170761924365380e-10,0.000000000000000000e+00 +6.293044124426923958e+00,6.388000000000000256e+01,0.000000000000000000e+00,7.743138754484314212e+00,0.000000000000000000e+00,-1.000000009958632807e+00,0.000000000000000000e+00,-7.551263039239387715e-10,0.000000000000000000e+00 +6.294335590370784494e+00,6.389000000000000057e+01,0.000000000000000000e+00,7.741847288527592852e+00,0.000000000000000000e+00,-1.000000009959608027e+00,0.000000000000000000e+00,9.203715652445316907e-10,0.000000000000000000e+00 +6.295627271752154641e+00,6.389999999999999858e+01,0.000000000000000000e+00,7.740555607133358329e+00,0.000000000000000000e+00,-1.000000009958419200e+00,0.000000000000000000e+00,-4.195465361125922369e-10,0.000000000000000000e+00 +6.296919168678879686e+00,6.391000000000000369e+01,0.000000000000000000e+00,7.739263710193768020e+00,0.000000000000000000e+00,-1.000000009958961211e+00,0.000000000000000000e+00,-4.529865180751440571e-10,0.000000000000000000e+00 +6.298211281258895511e+00,6.392000000000000171e+01,0.000000000000000000e+00,7.737971597600884266e+00,0.000000000000000000e+00,-1.000000009959546521e+00,0.000000000000000000e+00,8.814236961572360802e-10,0.000000000000000000e+00 +6.299503609600227705e+00,6.392999999999999972e+01,0.000000000000000000e+00,7.736679269246681478e+00,0.000000000000000000e+00,-1.000000009958407432e+00,0.000000000000000000e+00,-6.072733697412461500e-10,0.000000000000000000e+00 +6.300796153810991562e+00,6.394000000000000483e+01,0.000000000000000000e+00,7.735386725023046139e+00,0.000000000000000000e+00,-1.000000009959192360e+00,0.000000000000000000e+00,-7.007811628344301732e-11,0.000000000000000000e+00 +6.302088913999392972e+00,6.395000000000000284e+01,0.000000000000000000e+00,7.734093964821769696e+00,0.000000000000000000e+00,-1.000000009959282954e+00,0.000000000000000000e+00,4.289849969502052883e-10,0.000000000000000000e+00 +6.303381890273729304e+00,6.396000000000000085e+01,0.000000000000000000e+00,7.732800988534556552e+00,0.000000000000000000e+00,-1.000000009958728286e+00,0.000000000000000000e+00,-6.394207581484387357e-10,0.000000000000000000e+00 +6.304675082742386749e+00,6.396999999999999886e+01,0.000000000000000000e+00,7.731507796053020520e+00,0.000000000000000000e+00,-1.000000009959555181e+00,0.000000000000000000e+00,5.059231583663559895e-10,0.000000000000000000e+00 +6.305968491513842977e+00,6.398000000000000398e+01,0.000000000000000000e+00,7.730214387268682152e+00,0.000000000000000000e+00,-1.000000009958900815e+00,0.000000000000000000e+00,-3.201183725266807780e-10,0.000000000000000000e+00 +6.307262116696667142e+00,6.399000000000000199e+01,0.000000000000000000e+00,7.728920762072974959e+00,0.000000000000000000e+00,-1.000000009959314928e+00,0.000000000000000000e+00,1.323163336132862961e-10,0.000000000000000000e+00 +6.308555958399518104e+00,6.400000000000000000e+01,0.000000000000000000e+00,7.727626920357238305e+00,0.000000000000000000e+00,-1.000000009959143732e+00,0.000000000000000000e+00,3.337382450417886644e-10,0.000000000000000000e+00 +6.309850016731146205e+00,6.401000000000000512e+01,0.000000000000000000e+00,7.726332862012722735e+00,0.000000000000000000e+00,-1.000000009958711855e+00,0.000000000000000000e+00,-1.818525959536795370e-10,0.000000000000000000e+00 +6.311144291800392381e+00,6.401999999999999602e+01,0.000000000000000000e+00,7.725038586930587314e+00,0.000000000000000000e+00,-1.000000009958947222e+00,0.000000000000000000e+00,-2.895431702118773739e-10,0.000000000000000000e+00 +6.312438783716189050e+00,6.403000000000000114e+01,0.000000000000000000e+00,7.723744095001898735e+00,0.000000000000000000e+00,-1.000000009959322034e+00,0.000000000000000000e+00,7.357417379240814591e-11,0.000000000000000000e+00 +6.313733492587560114e+00,6.404000000000000625e+01,0.000000000000000000e+00,7.722449386117633097e+00,0.000000000000000000e+00,-1.000000009959226777e+00,0.000000000000000000e+00,-8.779408501729486099e-11,0.000000000000000000e+00 +6.315028418523620957e+00,6.404999999999999716e+01,0.000000000000000000e+00,7.721154460168675904e+00,0.000000000000000000e+00,-1.000000009959340463e+00,0.000000000000000000e+00,3.495744570321852829e-10,0.000000000000000000e+00 +6.316323561633577555e+00,6.406000000000000227e+01,0.000000000000000000e+00,7.719859317045820291e+00,0.000000000000000000e+00,-1.000000009958887714e+00,0.000000000000000000e+00,-6.680054677971627477e-10,0.000000000000000000e+00 +6.317618922026728256e+00,6.407000000000000739e+01,0.000000000000000000e+00,7.718563956639768797e+00,0.000000000000000000e+00,-1.000000009959753022e+00,0.000000000000000000e+00,6.291600193014576700e-10,0.000000000000000000e+00 +6.318914499812463781e+00,6.407999999999999829e+01,0.000000000000000000e+00,7.717268378841129817e+00,0.000000000000000000e+00,-1.000000009958937897e+00,0.000000000000000000e+00,-4.575252748108175531e-10,0.000000000000000000e+00 +6.320210295100265441e+00,6.409000000000000341e+01,0.000000000000000000e+00,7.715972583540423813e+00,0.000000000000000000e+00,-1.000000009959530756e+00,0.000000000000000000e+00,3.685286970521828280e-10,0.000000000000000000e+00 +6.321506307999706031e+00,6.409999999999999432e+01,0.000000000000000000e+00,7.714676570628075325e+00,0.000000000000000000e+00,-1.000000009959053138e+00,0.000000000000000000e+00,-1.199101617874654631e-12,0.000000000000000000e+00 +6.322802538620451607e+00,6.410999999999999943e+01,0.000000000000000000e+00,7.713380339994420076e+00,0.000000000000000000e+00,-1.000000009959054692e+00,0.000000000000000000e+00,-4.447919531128775892e-10,0.000000000000000000e+00 +6.324098987072260591e+00,6.412000000000000455e+01,0.000000000000000000e+00,7.712083891529699642e+00,0.000000000000000000e+00,-1.000000009959631342e+00,0.000000000000000000e+00,6.877105309307135155e-10,0.000000000000000000e+00 +6.325395653464982892e+00,6.412999999999999545e+01,0.000000000000000000e+00,7.710787225124063227e+00,0.000000000000000000e+00,-1.000000009958739611e+00,0.000000000000000000e+00,-7.654972141397584206e-10,0.000000000000000000e+00 +6.326692537908560787e+00,6.414000000000000057e+01,0.000000000000000000e+00,7.709490340667570329e+00,0.000000000000000000e+00,-1.000000009959732372e+00,0.000000000000000000e+00,5.419719432920527953e-10,0.000000000000000000e+00 +6.327989640513028924e+00,6.415000000000000568e+01,0.000000000000000000e+00,7.708193238050183638e+00,0.000000000000000000e+00,-1.000000009959029379e+00,0.000000000000000000e+00,-7.753379131695787838e-11,0.000000000000000000e+00 +6.329286961388514321e+00,6.415999999999999659e+01,0.000000000000000000e+00,7.706895917161777909e+00,0.000000000000000000e+00,-1.000000009959129965e+00,0.000000000000000000e+00,-4.468138134974131482e-10,0.000000000000000000e+00 +6.330584500645238144e+00,6.417000000000000171e+01,0.000000000000000000e+00,7.705598377892131978e+00,0.000000000000000000e+00,-1.000000009959709724e+00,0.000000000000000000e+00,5.536752467807146238e-10,0.000000000000000000e+00 +6.331882258393512153e+00,6.418000000000000682e+01,0.000000000000000000e+00,7.704300620130932309e+00,0.000000000000000000e+00,-1.000000009958991187e+00,0.000000000000000000e+00,-7.030970372298856893e-10,0.000000000000000000e+00 +6.333180234743743142e+00,6.418999999999999773e+01,0.000000000000000000e+00,7.703002643767774771e+00,0.000000000000000000e+00,-1.000000009959903791e+00,0.000000000000000000e+00,5.936833730517220663e-10,0.000000000000000000e+00 +6.334478429806429389e+00,6.420000000000000284e+01,0.000000000000000000e+00,7.701704448692158422e+00,0.000000000000000000e+00,-1.000000009959133074e+00,0.000000000000000000e+00,-2.353127764065467982e-10,0.000000000000000000e+00 +6.335776843692163318e+00,6.421000000000000796e+01,0.000000000000000000e+00,7.700406034793493504e+00,0.000000000000000000e+00,-1.000000009959438607e+00,0.000000000000000000e+00,3.795830626982866342e-11,0.000000000000000000e+00 +6.337075476511629724e+00,6.421999999999999886e+01,0.000000000000000000e+00,7.699107401961093444e+00,0.000000000000000000e+00,-1.000000009959389313e+00,0.000000000000000000e+00,-1.022308066283613469e-10,0.000000000000000000e+00 +6.338374328375607547e+00,6.423000000000000398e+01,0.000000000000000000e+00,7.697808550084180190e+00,0.000000000000000000e+00,-1.000000009959522096e+00,0.000000000000000000e+00,-6.341342944263208702e-11,0.000000000000000000e+00 +6.339673399394968101e+00,6.423999999999999488e+01,0.000000000000000000e+00,7.696509479051881542e+00,0.000000000000000000e+00,-1.000000009959604474e+00,0.000000000000000000e+00,2.190897497232782427e-10,0.000000000000000000e+00 +6.340972689680676844e+00,6.425000000000000000e+01,0.000000000000000000e+00,7.695210188753232039e+00,0.000000000000000000e+00,-1.000000009959319813e+00,0.000000000000000000e+00,2.851786763409057157e-10,0.000000000000000000e+00 +6.342272199343793382e+00,6.426000000000000512e+01,0.000000000000000000e+00,7.693910679077172965e+00,0.000000000000000000e+00,-1.000000009958949221e+00,0.000000000000000000e+00,-8.504372175465439785e-10,0.000000000000000000e+00 +6.343571928495470580e+00,6.426999999999999602e+01,0.000000000000000000e+00,7.692610949912551455e+00,0.000000000000000000e+00,-1.000000009960054559e+00,0.000000000000000000e+00,5.575247406078747407e-10,0.000000000000000000e+00 +6.344871877246955449e+00,6.428000000000000114e+01,0.000000000000000000e+00,7.691311001148118720e+00,0.000000000000000000e+00,-1.000000009959329805e+00,0.000000000000000000e+00,-1.560942098921409613e-10,0.000000000000000000e+00 +6.346172045709589149e+00,6.429000000000000625e+01,0.000000000000000000e+00,7.690010832672536267e+00,0.000000000000000000e+00,-1.000000009959532754e+00,0.000000000000000000e+00,2.282961482809749031e-10,0.000000000000000000e+00 +6.347472433994806096e+00,6.429999999999999716e+01,0.000000000000000000e+00,7.688710444374367903e+00,0.000000000000000000e+00,-1.000000009959235880e+00,0.000000000000000000e+00,-3.250578625399746440e-10,0.000000000000000000e+00 +6.348773042214135742e+00,6.431000000000000227e+01,0.000000000000000000e+00,7.687409836142085062e+00,0.000000000000000000e+00,-1.000000009959658653e+00,0.000000000000000000e+00,3.509484841203864100e-10,0.000000000000000000e+00 +6.350073870479201688e+00,6.432000000000000739e+01,0.000000000000000000e+00,7.686109007864063258e+00,0.000000000000000000e+00,-1.000000009959202130e+00,0.000000000000000000e+00,-3.029319792559872672e-10,0.000000000000000000e+00 +6.351374918901721678e+00,6.432999999999999829e+01,0.000000000000000000e+00,7.684807959428585633e+00,0.000000000000000000e+00,-1.000000009959596259e+00,0.000000000000000000e+00,-1.208110064271447656e-10,0.000000000000000000e+00 +6.352676187593508494e+00,6.434000000000000341e+01,0.000000000000000000e+00,7.683506690723838517e+00,0.000000000000000000e+00,-1.000000009959753466e+00,0.000000000000000000e+00,-8.581588474130464345e-11,0.000000000000000000e+00 +6.353977676666469954e+00,6.434999999999999432e+01,0.000000000000000000e+00,7.682205201637914982e+00,0.000000000000000000e+00,-1.000000009959865155e+00,0.000000000000000000e+00,3.926733688024537851e-10,0.000000000000000000e+00 +6.355279386232607131e+00,6.435999999999999943e+01,0.000000000000000000e+00,7.680903492058813065e+00,0.000000000000000000e+00,-1.000000009959354008e+00,0.000000000000000000e+00,-1.916985575850317423e-10,0.000000000000000000e+00 +6.356581316404017024e+00,6.437000000000000455e+01,0.000000000000000000e+00,7.679601561874436655e+00,0.000000000000000000e+00,-1.000000009959603586e+00,0.000000000000000000e+00,-1.993395276807245095e-10,0.000000000000000000e+00 +6.357883467292891666e+00,6.437999999999999545e+01,0.000000000000000000e+00,7.678299410972592831e+00,0.000000000000000000e+00,-1.000000009959863156e+00,0.000000000000000000e+00,4.352673420851666874e-10,0.000000000000000000e+00 +6.359185839011518127e+00,6.439000000000000057e+01,0.000000000000000000e+00,7.676997039240994525e+00,0.000000000000000000e+00,-1.000000009959296277e+00,0.000000000000000000e+00,-3.153576182989468395e-10,0.000000000000000000e+00 +6.360488431672279397e+00,6.440000000000000568e+01,0.000000000000000000e+00,7.675694446567260520e+00,0.000000000000000000e+00,-1.000000009959707059e+00,0.000000000000000000e+00,2.331546067969372871e-10,0.000000000000000000e+00 +6.361791245387652616e+00,6.440999999999999659e+01,0.000000000000000000e+00,7.674391632838911903e+00,0.000000000000000000e+00,-1.000000009959403302e+00,0.000000000000000000e+00,-4.689565574438932908e-10,0.000000000000000000e+00 +6.363094280270210845e+00,6.442000000000000171e+01,0.000000000000000000e+00,7.673088597943376499e+00,0.000000000000000000e+00,-1.000000009960014369e+00,0.000000000000000000e+00,2.606764927216202067e-10,0.000000000000000000e+00 +6.364397536432622182e+00,6.443000000000000682e+01,0.000000000000000000e+00,7.671785341767984434e+00,0.000000000000000000e+00,-1.000000009959674641e+00,0.000000000000000000e+00,-1.257167166418498633e-10,0.000000000000000000e+00 +6.365701013987651535e+00,6.443999999999999773e+01,0.000000000000000000e+00,7.670481864199972577e+00,0.000000000000000000e+00,-1.000000009959838509e+00,0.000000000000000000e+00,7.494032106531963506e-12,0.000000000000000000e+00 +6.367004713048159736e+00,6.445000000000000284e+01,0.000000000000000000e+00,7.669178165126480096e+00,0.000000000000000000e+00,-1.000000009959828740e+00,0.000000000000000000e+00,2.045182462565998180e-10,0.000000000000000000e+00 +6.368308633727101764e+00,6.446000000000000796e+01,0.000000000000000000e+00,7.667874244434551123e+00,0.000000000000000000e+00,-1.000000009959562064e+00,0.000000000000000000e+00,1.072644367548784530e-11,0.000000000000000000e+00 +6.369612776137530297e+00,6.446999999999999886e+01,0.000000000000000000e+00,7.666570102011133869e+00,0.000000000000000000e+00,-1.000000009959548075e+00,0.000000000000000000e+00,1.515065271193696205e-11,0.000000000000000000e+00 +6.370917140392593936e+00,6.448000000000000398e+01,0.000000000000000000e+00,7.665265737743079733e+00,0.000000000000000000e+00,-1.000000009959528313e+00,0.000000000000000000e+00,-2.360716861604584043e-10,0.000000000000000000e+00 +6.372221726605536318e+00,6.448999999999999488e+01,0.000000000000000000e+00,7.663961151517144188e+00,0.000000000000000000e+00,-1.000000009959836289e+00,0.000000000000000000e+00,-1.540075809574718136e-10,0.000000000000000000e+00 +6.373526534889698780e+00,6.450000000000000000e+01,0.000000000000000000e+00,7.662656343219985899e+00,0.000000000000000000e+00,-1.000000009960037239e+00,0.000000000000000000e+00,3.283801395784674265e-10,0.000000000000000000e+00 +6.374831565358518581e+00,6.451000000000000512e+01,0.000000000000000000e+00,7.661351312738167607e+00,0.000000000000000000e+00,-1.000000009959608693e+00,0.000000000000000000e+00,-2.852848213544125454e-10,0.000000000000000000e+00 +6.376136818125530681e+00,6.451999999999999602e+01,0.000000000000000000e+00,7.660046059958156128e+00,0.000000000000000000e+00,-1.000000009959981062e+00,0.000000000000000000e+00,1.583511739915675855e-10,0.000000000000000000e+00 +6.377442293304364185e+00,6.453000000000000114e+01,0.000000000000000000e+00,7.658740584766319692e+00,0.000000000000000000e+00,-1.000000009959774339e+00,0.000000000000000000e+00,1.627457000190927821e-10,0.000000000000000000e+00 +6.378747991008747675e+00,6.454000000000000625e+01,0.000000000000000000e+00,7.657434887048931493e+00,0.000000000000000000e+00,-1.000000009959561842e+00,0.000000000000000000e+00,-2.033549356663782135e-10,0.000000000000000000e+00 +6.380053911352505658e+00,6.454999999999999716e+01,0.000000000000000000e+00,7.656128966692167026e+00,0.000000000000000000e+00,-1.000000009959827407e+00,0.000000000000000000e+00,-3.512204404018341038e-10,0.000000000000000000e+00 +6.381360054449559449e+00,6.456000000000000227e+01,0.000000000000000000e+00,7.654822823582104085e+00,0.000000000000000000e+00,-1.000000009960286151e+00,0.000000000000000000e+00,3.074779206326822187e-10,0.000000000000000000e+00 +6.382666420413928066e+00,6.457000000000000739e+01,0.000000000000000000e+00,7.653516457604723655e+00,0.000000000000000000e+00,-1.000000009959884473e+00,0.000000000000000000e+00,2.792150408624696619e-10,0.000000000000000000e+00 +6.383973009359727335e+00,6.457999999999999829e+01,0.000000000000000000e+00,7.652209868645910795e+00,0.000000000000000000e+00,-1.000000009959519653e+00,0.000000000000000000e+00,-3.671824072824805949e-10,0.000000000000000000e+00 +6.385279821401170786e+00,6.459000000000000341e+01,0.000000000000000000e+00,7.650903056591451978e+00,0.000000000000000000e+00,-1.000000009959999492e+00,0.000000000000000000e+00,-2.888030969084957780e-12,0.000000000000000000e+00 +6.386586856652569644e+00,6.459999999999999432e+01,0.000000000000000000e+00,7.649596021327035089e+00,0.000000000000000000e+00,-1.000000009960003267e+00,0.000000000000000000e+00,3.996691741599559243e-10,0.000000000000000000e+00 +6.387894115228331948e+00,6.460999999999999943e+01,0.000000000000000000e+00,7.648288762738252089e+00,0.000000000000000000e+00,-1.000000009959480796e+00,0.000000000000000000e+00,-6.495849306781001094e-10,0.000000000000000000e+00 +6.389201597242965214e+00,6.462000000000000455e+01,0.000000000000000000e+00,7.646981280710597240e+00,0.000000000000000000e+00,-1.000000009960330116e+00,0.000000000000000000e+00,5.548969023241808188e-10,0.000000000000000000e+00 +6.390509302811072878e+00,6.462999999999999545e+01,0.000000000000000000e+00,7.645673575129464439e+00,0.000000000000000000e+00,-1.000000009959604474e+00,0.000000000000000000e+00,-5.929998225335179838e-10,0.000000000000000000e+00 +6.391817232047357855e+00,6.464000000000000057e+01,0.000000000000000000e+00,7.644365645880153437e+00,0.000000000000000000e+00,-1.000000009960380076e+00,0.000000000000000000e+00,6.485727762163954783e-10,0.000000000000000000e+00 +6.393125385066619870e+00,6.465000000000000568e+01,0.000000000000000000e+00,7.643057492847861845e+00,0.000000000000000000e+00,-1.000000009959531644e+00,0.000000000000000000e+00,-3.239763291828305378e-10,0.000000000000000000e+00 +6.394433761983758124e+00,6.465999999999999659e+01,0.000000000000000000e+00,7.641749115917693125e+00,0.000000000000000000e+00,-1.000000009959955527e+00,0.000000000000000000e+00,-3.262964021180031346e-10,0.000000000000000000e+00 +6.395742362913768631e+00,6.467000000000000171e+01,0.000000000000000000e+00,7.640440514974648600e+00,0.000000000000000000e+00,-1.000000009960382519e+00,0.000000000000000000e+00,1.896707789881636852e-10,0.000000000000000000e+00 +6.397051187971747765e+00,6.468000000000000682e+01,0.000000000000000000e+00,7.639131689903632783e+00,0.000000000000000000e+00,-1.000000009960134273e+00,0.000000000000000000e+00,2.566392930797122719e-10,0.000000000000000000e+00 +6.398360237272889606e+00,6.468999999999999773e+01,0.000000000000000000e+00,7.637822640589452483e+00,0.000000000000000000e+00,-1.000000009959798319e+00,0.000000000000000000e+00,-5.613552498473747196e-11,0.000000000000000000e+00 +6.399669510932486816e+00,6.470000000000000284e+01,0.000000000000000000e+00,7.636513366916815038e+00,0.000000000000000000e+00,-1.000000009959871816e+00,0.000000000000000000e+00,-1.612559910477238106e-10,0.000000000000000000e+00 +6.400979009065931535e+00,6.471000000000000796e+01,0.000000000000000000e+00,7.635203868770328306e+00,0.000000000000000000e+00,-1.000000009960082981e+00,0.000000000000000000e+00,1.085027729000433993e-11,0.000000000000000000e+00 +6.402288731788713605e+00,6.471999999999999886e+01,0.000000000000000000e+00,7.633894146034501560e+00,0.000000000000000000e+00,-1.000000009960068770e+00,0.000000000000000000e+00,1.118742906399188404e-11,0.000000000000000000e+00 +6.403598679216422340e+00,6.473000000000000398e+01,0.000000000000000000e+00,7.632584198593745484e+00,0.000000000000000000e+00,-1.000000009960054115e+00,0.000000000000000000e+00,-9.050093923266410570e-11,0.000000000000000000e+00 +6.404908851464747421e+00,6.473999999999999488e+01,0.000000000000000000e+00,7.631274026332371285e+00,0.000000000000000000e+00,-1.000000009960172687e+00,0.000000000000000000e+00,2.924678048510303733e-10,0.000000000000000000e+00 +6.406219248649476228e+00,6.475000000000000000e+01,0.000000000000000000e+00,7.629963629134590697e+00,0.000000000000000000e+00,-1.000000009959789438e+00,0.000000000000000000e+00,-3.215576908765494625e-10,0.000000000000000000e+00 +6.407529870886496504e+00,6.476000000000000512e+01,0.000000000000000000e+00,7.628653006884516863e+00,0.000000000000000000e+00,-1.000000009960210878e+00,0.000000000000000000e+00,2.053008306544875624e-10,0.000000000000000000e+00 +6.408840718291795469e+00,6.476999999999999602e+01,0.000000000000000000e+00,7.627342159466161675e+00,0.000000000000000000e+00,-1.000000009959941760e+00,0.000000000000000000e+00,-1.253271530555757318e-10,0.000000000000000000e+00 +6.410151790981459818e+00,6.478000000000000114e+01,0.000000000000000000e+00,7.626031086763439326e+00,0.000000000000000000e+00,-1.000000009960106073e+00,0.000000000000000000e+00,-2.089555719801091476e-10,0.000000000000000000e+00 +6.411463089071675725e+00,6.479000000000000625e+01,0.000000000000000000e+00,7.624719788660162756e+00,0.000000000000000000e+00,-1.000000009960380076e+00,0.000000000000000000e+00,2.336378492529217292e-11,0.000000000000000000e+00 +6.412774612678729724e+00,6.479999999999999716e+01,0.000000000000000000e+00,7.623408265040045428e+00,0.000000000000000000e+00,-1.000000009960349434e+00,0.000000000000000000e+00,1.252625140530846061e-10,0.000000000000000000e+00 +6.414086361919008716e+00,6.481000000000000227e+01,0.000000000000000000e+00,7.622096515786701332e+00,0.000000000000000000e+00,-1.000000009960185121e+00,0.000000000000000000e+00,1.673828510043284221e-10,0.000000000000000000e+00 +6.415398336908998189e+00,6.482000000000000739e+01,0.000000000000000000e+00,7.620784540783644090e+00,0.000000000000000000e+00,-1.000000009959965519e+00,0.000000000000000000e+00,-2.962961816102485027e-10,0.000000000000000000e+00 +6.416710537765285771e+00,6.482999999999999829e+01,0.000000000000000000e+00,7.619472339914286962e+00,0.000000000000000000e+00,-1.000000009960354319e+00,0.000000000000000000e+00,3.524150057119581676e-10,0.000000000000000000e+00 +6.418022964604558567e+00,6.484000000000000341e+01,0.000000000000000000e+00,7.618159913061941957e+00,0.000000000000000000e+00,-1.000000009959891800e+00,0.000000000000000000e+00,-3.951510575842020040e-10,0.000000000000000000e+00 +6.419335617543604044e+00,6.484999999999999432e+01,0.000000000000000000e+00,7.616847260109822493e+00,0.000000000000000000e+00,-1.000000009960410496e+00,0.000000000000000000e+00,1.097640616578859793e-10,0.000000000000000000e+00 +6.420648496699310925e+00,6.485999999999999943e+01,0.000000000000000000e+00,7.615534380941038961e+00,0.000000000000000000e+00,-1.000000009960266389e+00,0.000000000000000000e+00,-1.242876417338148691e-10,0.000000000000000000e+00 +6.421961602188667406e+00,6.487000000000000455e+01,0.000000000000000000e+00,7.614221275438603165e+00,0.000000000000000000e+00,-1.000000009960429592e+00,0.000000000000000000e+00,5.188748340838838425e-10,0.000000000000000000e+00 +6.423274934128764713e+00,6.487999999999999545e+01,0.000000000000000000e+00,7.612907943485424767e+00,0.000000000000000000e+00,-1.000000009959748137e+00,0.000000000000000000e+00,-4.645233315491813961e-10,0.000000000000000000e+00 +6.424588492636792658e+00,6.489000000000000057e+01,0.000000000000000000e+00,7.611594384964313953e+00,0.000000000000000000e+00,-1.000000009960358316e+00,0.000000000000000000e+00,8.551974148378478020e-11,0.000000000000000000e+00 +6.425902277830044085e+00,6.490000000000000568e+01,0.000000000000000000e+00,7.610280599757976994e+00,0.000000000000000000e+00,-1.000000009960245961e+00,0.000000000000000000e+00,-3.344157241551800723e-10,0.000000000000000000e+00 +6.427216289825911311e+00,6.490999999999999659e+01,0.000000000000000000e+00,7.608966587749021571e+00,0.000000000000000000e+00,-1.000000009960685388e+00,0.000000000000000000e+00,4.051492891715059105e-10,0.000000000000000000e+00 +6.428530528741889682e+00,6.492000000000000171e+01,0.000000000000000000e+00,7.607652348819952337e+00,0.000000000000000000e+00,-1.000000009960152925e+00,0.000000000000000000e+00,-1.961205503993027625e-10,0.000000000000000000e+00 +6.429844994695574911e+00,6.493000000000000682e+01,0.000000000000000000e+00,7.606337882853174470e+00,0.000000000000000000e+00,-1.000000009960410718e+00,0.000000000000000000e+00,-1.047146699877147916e-11,0.000000000000000000e+00 +6.431159687804664848e+00,6.493999999999999773e+01,0.000000000000000000e+00,7.605023189730989230e+00,0.000000000000000000e+00,-1.000000009960424485e+00,0.000000000000000000e+00,4.897097671867604825e-12,0.000000000000000000e+00 +6.432474608186959486e+00,6.495000000000000284e+01,0.000000000000000000e+00,7.603708269335597514e+00,0.000000000000000000e+00,-1.000000009960418046e+00,0.000000000000000000e+00,4.352598263667666565e-10,0.000000000000000000e+00 +6.433789755960359180e+00,6.496000000000000796e+01,0.000000000000000000e+00,7.602393121549098076e+00,0.000000000000000000e+00,-1.000000009959845615e+00,0.000000000000000000e+00,-7.015620487473406728e-10,0.000000000000000000e+00 +6.435105131242868204e+00,6.496999999999999886e+01,0.000000000000000000e+00,7.601077746253488421e+00,0.000000000000000000e+00,-1.000000009960768432e+00,0.000000000000000000e+00,2.594115255048293171e-10,0.000000000000000000e+00 +6.436420734152591194e+00,6.498000000000000398e+01,0.000000000000000000e+00,7.599762143330661246e+00,0.000000000000000000e+00,-1.000000009960427150e+00,0.000000000000000000e+00,3.091474686596600196e-10,0.000000000000000000e+00 +6.437736564807735817e+00,6.498999999999999488e+01,0.000000000000000000e+00,7.598446312662410662e+00,0.000000000000000000e+00,-1.000000009960020364e+00,0.000000000000000000e+00,-4.788256599072209325e-10,0.000000000000000000e+00 +6.439052623326611879e+00,6.500000000000000000e+01,0.000000000000000000e+00,7.597130254130426863e+00,0.000000000000000000e+00,-1.000000009960650527e+00,0.000000000000000000e+00,1.804984910851360960e-11,0.000000000000000000e+00 +6.440368909827631327e+00,6.501000000000000512e+01,0.000000000000000000e+00,7.595813967616296125e+00,0.000000000000000000e+00,-1.000000009960626768e+00,0.000000000000000000e+00,3.329367175747181888e-10,0.000000000000000000e+00 +6.441685424429310025e+00,6.501999999999999602e+01,0.000000000000000000e+00,7.594497453001504361e+00,0.000000000000000000e+00,-1.000000009960188452e+00,0.000000000000000000e+00,2.580065295430489793e-11,0.000000000000000000e+00 +6.443002167250265089e+00,6.503000000000000114e+01,0.000000000000000000e+00,7.593180710167434455e+00,0.000000000000000000e+00,-1.000000009960154479e+00,0.000000000000000000e+00,-3.186586892626508606e-10,0.000000000000000000e+00 +6.444319138409216663e+00,6.504000000000000625e+01,0.000000000000000000e+00,7.591863738995365374e+00,0.000000000000000000e+00,-1.000000009960574143e+00,0.000000000000000000e+00,-1.164841077737798683e-10,0.000000000000000000e+00 +6.445636338024988810e+00,6.504999999999999716e+01,0.000000000000000000e+00,7.590546539366473056e+00,0.000000000000000000e+00,-1.000000009960727576e+00,0.000000000000000000e+00,1.921401494548508996e-10,0.000000000000000000e+00 +6.446953766216507731e+00,6.506000000000000227e+01,0.000000000000000000e+00,7.589229111161831298e+00,0.000000000000000000e+00,-1.000000009960474445e+00,0.000000000000000000e+00,1.680091937534454899e-10,0.000000000000000000e+00 +6.448271423102803546e+00,6.507000000000000739e+01,0.000000000000000000e+00,7.587911454262410871e+00,0.000000000000000000e+00,-1.000000009960253067e+00,0.000000000000000000e+00,-1.165919522338929152e-10,0.000000000000000000e+00 +6.449589308803009402e+00,6.507999999999999829e+01,0.000000000000000000e+00,7.586593568549078626e+00,0.000000000000000000e+00,-1.000000009960406722e+00,0.000000000000000000e+00,-7.698449124464554517e-11,0.000000000000000000e+00 +6.450907423436361476e+00,6.509000000000000341e+01,0.000000000000000000e+00,7.585275453902597498e+00,0.000000000000000000e+00,-1.000000009960508196e+00,0.000000000000000000e+00,-1.529316698199680720e-10,0.000000000000000000e+00 +6.452225767122199862e+00,6.509999999999999432e+01,0.000000000000000000e+00,7.583957110203627394e+00,0.000000000000000000e+00,-1.000000009960709813e+00,0.000000000000000000e+00,2.397982906672250496e-10,0.000000000000000000e+00 +6.453544339979969457e+00,6.510999999999999943e+01,0.000000000000000000e+00,7.582638537332724304e+00,0.000000000000000000e+00,-1.000000009960393621e+00,0.000000000000000000e+00,-3.587930557781512608e-10,0.000000000000000000e+00 +6.454863142129216413e+00,6.512000000000000455e+01,0.000000000000000000e+00,7.581319735170341190e+00,0.000000000000000000e+00,-1.000000009960866798e+00,0.000000000000000000e+00,1.668240625097585354e-10,0.000000000000000000e+00 +6.456182173689593462e+00,6.512999999999999545e+01,0.000000000000000000e+00,7.580000703596825318e+00,0.000000000000000000e+00,-1.000000009960646752e+00,0.000000000000000000e+00,3.574900707556873143e-10,0.000000000000000000e+00 +6.457501434780856364e+00,6.514000000000000057e+01,0.000000000000000000e+00,7.578681442492421816e+00,0.000000000000000000e+00,-1.000000009960175129e+00,0.000000000000000000e+00,-2.233082668598439293e-10,0.000000000000000000e+00 +6.458820925522864798e+00,6.515000000000000568e+01,0.000000000000000000e+00,7.577361951737271006e+00,0.000000000000000000e+00,-1.000000009960469782e+00,0.000000000000000000e+00,-4.817032832132596372e-10,0.000000000000000000e+00 +6.460140646035583245e+00,6.515999999999999659e+01,0.000000000000000000e+00,7.576042231211407518e+00,0.000000000000000000e+00,-1.000000009961105496e+00,0.000000000000000000e+00,6.738970532323506322e-10,0.000000000000000000e+00 +6.461460596439080106e+00,6.517000000000000171e+01,0.000000000000000000e+00,7.574722280794762064e+00,0.000000000000000000e+00,-1.000000009960215985e+00,0.000000000000000000e+00,-2.512797767086321991e-10,0.000000000000000000e+00 +6.462780776853529474e+00,6.518000000000000682e+01,0.000000000000000000e+00,7.573402100367163214e+00,0.000000000000000000e+00,-1.000000009960547720e+00,0.000000000000000000e+00,-1.254498275676563925e-10,0.000000000000000000e+00 +6.464101187399209358e+00,6.518999999999999773e+01,0.000000000000000000e+00,7.572081689808331184e+00,0.000000000000000000e+00,-1.000000009960713365e+00,0.000000000000000000e+00,1.054200109320518522e-10,0.000000000000000000e+00 +6.465421828196502574e+00,6.520000000000000284e+01,0.000000000000000000e+00,7.570761048997883158e+00,0.000000000000000000e+00,-1.000000009960574143e+00,0.000000000000000000e+00,-5.036415751735225528e-10,0.000000000000000000e+00 +6.466742699365897629e+00,6.521000000000000796e+01,0.000000000000000000e+00,7.569440177815331516e+00,0.000000000000000000e+00,-1.000000009961239389e+00,0.000000000000000000e+00,6.660825541056549554e-10,0.000000000000000000e+00 +6.468063801027986948e+00,6.521999999999999886e+01,0.000000000000000000e+00,7.568119076140082058e+00,0.000000000000000000e+00,-1.000000009960359426e+00,0.000000000000000000e+00,-3.828087903434053563e-10,0.000000000000000000e+00 +6.469385133303469537e+00,6.523000000000000398e+01,0.000000000000000000e+00,7.566797743851438440e+00,0.000000000000000000e+00,-1.000000009960865244e+00,0.000000000000000000e+00,4.936329516577304247e-10,0.000000000000000000e+00 +6.470706696313149209e+00,6.523999999999999488e+01,0.000000000000000000e+00,7.565476180828595076e+00,0.000000000000000000e+00,-1.000000009960212877e+00,0.000000000000000000e+00,-6.993312005218897276e-10,0.000000000000000000e+00 +6.472028490177934579e+00,6.525000000000000000e+01,0.000000000000000000e+00,7.564154386950644238e+00,0.000000000000000000e+00,-1.000000009961137248e+00,0.000000000000000000e+00,1.798829829185808448e-10,0.000000000000000000e+00 +6.473350515018840845e+00,6.526000000000000512e+01,0.000000000000000000e+00,7.562832362096568950e+00,0.000000000000000000e+00,-1.000000009960899439e+00,0.000000000000000000e+00,1.548301806287408081e-10,0.000000000000000000e+00 +6.474672770956988899e+00,6.526999999999999602e+01,0.000000000000000000e+00,7.561510106145250099e+00,0.000000000000000000e+00,-1.000000009960694713e+00,0.000000000000000000e+00,3.161542922985095380e-10,0.000000000000000000e+00 +6.475995258113605324e+00,6.528000000000000114e+01,0.000000000000000000e+00,7.560187618975461099e+00,0.000000000000000000e+00,-1.000000009960276603e+00,0.000000000000000000e+00,-7.844559833596849224e-10,0.000000000000000000e+00 +6.477317976610022399e+00,6.529000000000000625e+01,0.000000000000000000e+00,7.558864900465869674e+00,0.000000000000000000e+00,-1.000000009961314218e+00,0.000000000000000000e+00,4.805274003157619223e-10,0.000000000000000000e+00 +6.478640926567678981e+00,6.529999999999999716e+01,0.000000000000000000e+00,7.557541950495035188e+00,0.000000000000000000e+00,-1.000000009960678504e+00,0.000000000000000000e+00,1.245158671118699212e-10,0.000000000000000000e+00 +6.479964108108119625e+00,6.531000000000000227e+01,0.000000000000000000e+00,7.556218768941414865e+00,0.000000000000000000e+00,-1.000000009960513747e+00,0.000000000000000000e+00,-2.546927133918034906e-10,0.000000000000000000e+00 +6.481287521352996350e+00,6.532000000000000739e+01,0.000000000000000000e+00,7.554895355683356684e+00,0.000000000000000000e+00,-1.000000009960850811e+00,0.000000000000000000e+00,-7.565632132807017337e-11,0.000000000000000000e+00 +6.482611166424065985e+00,6.532999999999999829e+01,0.000000000000000000e+00,7.553571710599102040e+00,0.000000000000000000e+00,-1.000000009960950953e+00,0.000000000000000000e+00,2.291095969981421178e-10,0.000000000000000000e+00 +6.483935043443194601e+00,6.534000000000000341e+01,0.000000000000000000e+00,7.552247833566786639e+00,0.000000000000000000e+00,-1.000000009960647640e+00,0.000000000000000000e+00,-2.792098251022934006e-10,0.000000000000000000e+00 +6.485259152532353077e+00,6.534999999999999432e+01,0.000000000000000000e+00,7.550923724464439601e+00,0.000000000000000000e+00,-1.000000009961017344e+00,0.000000000000000000e+00,-5.365254000696807851e-12,0.000000000000000000e+00 +6.486583493813618873e+00,6.535999999999999943e+01,0.000000000000000000e+00,7.549599383169981692e+00,0.000000000000000000e+00,-1.000000009961024450e+00,0.000000000000000000e+00,1.121476686481041716e-10,0.000000000000000000e+00 +6.487908067409178692e+00,6.537000000000000455e+01,0.000000000000000000e+00,7.548274809561227983e+00,0.000000000000000000e+00,-1.000000009960875902e+00,0.000000000000000000e+00,1.483307522689811062e-10,0.000000000000000000e+00 +6.489232873441324045e+00,6.537999999999999545e+01,0.000000000000000000e+00,7.546950003515886074e+00,0.000000000000000000e+00,-1.000000009960679392e+00,0.000000000000000000e+00,1.786359661026345290e-10,0.000000000000000000e+00 +6.490557912032455690e+00,6.539000000000000057e+01,0.000000000000000000e+00,7.545624964911556098e+00,0.000000000000000000e+00,-1.000000009960442693e+00,0.000000000000000000e+00,-7.328485284513052813e-10,0.000000000000000000e+00 +6.491883183305080962e+00,6.540000000000000568e+01,0.000000000000000000e+00,7.544299693625730718e+00,0.000000000000000000e+00,-1.000000009961413916e+00,0.000000000000000000e+00,5.226533660110339599e-10,0.000000000000000000e+00 +6.493208687381814670e+00,6.540999999999999659e+01,0.000000000000000000e+00,7.542974189535793350e+00,0.000000000000000000e+00,-1.000000009960721137e+00,0.000000000000000000e+00,-2.378324947902760396e-11,0.000000000000000000e+00 +6.494534424385379090e+00,6.542000000000000171e+01,0.000000000000000000e+00,7.541648452519023493e+00,0.000000000000000000e+00,-1.000000009960752667e+00,0.000000000000000000e+00,-2.746315055841818793e-10,0.000000000000000000e+00 +6.495860394438604857e+00,6.543000000000000682e+01,0.000000000000000000e+00,7.540322482452589625e+00,0.000000000000000000e+00,-1.000000009961116820e+00,0.000000000000000000e+00,3.505958918349643266e-10,0.000000000000000000e+00 +6.497186597664430963e+00,6.543999999999999773e+01,0.000000000000000000e+00,7.538996279213552754e+00,0.000000000000000000e+00,-1.000000009960651859e+00,0.000000000000000000e+00,-5.971134637395790408e-10,0.000000000000000000e+00 +6.498513034185903869e+00,6.545000000000000284e+01,0.000000000000000000e+00,7.537669842678867305e+00,0.000000000000000000e+00,-1.000000009961443892e+00,0.000000000000000000e+00,4.917327433637932625e-10,0.000000000000000000e+00 +6.499839704126179285e+00,6.546000000000000796e+01,0.000000000000000000e+00,7.536343172725376682e+00,0.000000000000000000e+00,-1.000000009960791525e+00,0.000000000000000000e+00,-3.450559753961296658e-10,0.000000000000000000e+00 +6.501166607608519499e+00,6.546999999999999886e+01,0.000000000000000000e+00,7.535016269229819486e+00,0.000000000000000000e+00,-1.000000009961249381e+00,0.000000000000000000e+00,5.014309802682640989e-10,0.000000000000000000e+00 +6.502493744756296934e+00,6.548000000000000398e+01,0.000000000000000000e+00,7.533689132068822403e+00,0.000000000000000000e+00,-1.000000009960583913e+00,0.000000000000000000e+00,-4.240586093339097028e-10,0.000000000000000000e+00 +6.503821115692991484e+00,6.548999999999999488e+01,0.000000000000000000e+00,7.532361761118906429e+00,0.000000000000000000e+00,-1.000000009961146796e+00,0.000000000000000000e+00,-1.973573943852071276e-11,0.000000000000000000e+00 +6.505148720542193175e+00,6.550000000000000000e+01,0.000000000000000000e+00,7.531034156256480649e+00,0.000000000000000000e+00,-1.000000009961172998e+00,0.000000000000000000e+00,2.780911012990500399e-10,0.000000000000000000e+00 +6.506476559427599504e+00,6.551000000000000512e+01,0.000000000000000000e+00,7.529706317357847567e+00,0.000000000000000000e+00,-1.000000009960803737e+00,0.000000000000000000e+00,-4.612856703187851319e-10,0.000000000000000000e+00 +6.507804632473018103e+00,6.551999999999999602e+01,0.000000000000000000e+00,7.528378244299200439e+00,0.000000000000000000e+00,-1.000000009961416358e+00,0.000000000000000000e+00,3.567270739542769935e-10,0.000000000000000000e+00 +6.509132939802364959e+00,6.553000000000000114e+01,0.000000000000000000e+00,7.527049936956621501e+00,0.000000000000000000e+00,-1.000000009960942515e+00,0.000000000000000000e+00,2.904790361675370586e-10,0.000000000000000000e+00 +6.510461481539666195e+00,6.554000000000000625e+01,0.000000000000000000e+00,7.525721395206086406e+00,0.000000000000000000e+00,-1.000000009960556602e+00,0.000000000000000000e+00,-5.816910548064854689e-10,0.000000000000000000e+00 +6.511790257809057181e+00,6.554999999999999716e+01,0.000000000000000000e+00,7.524392618923459786e+00,0.000000000000000000e+00,-1.000000009961329539e+00,0.000000000000000000e+00,3.314769560157447651e-10,0.000000000000000000e+00 +6.513119268734783418e+00,6.556000000000000227e+01,0.000000000000000000e+00,7.523063607984495249e+00,0.000000000000000000e+00,-1.000000009960889003e+00,0.000000000000000000e+00,-4.136048280172135449e-10,0.000000000000000000e+00 +6.514448514441198768e+00,6.557000000000000739e+01,0.000000000000000000e+00,7.521734362264839824e+00,0.000000000000000000e+00,-1.000000009961438785e+00,0.000000000000000000e+00,2.765785845662132974e-10,0.000000000000000000e+00 +6.515777995052767224e+00,6.557999999999999829e+01,0.000000000000000000e+00,7.520404881640027739e+00,0.000000000000000000e+00,-1.000000009961071079e+00,0.000000000000000000e+00,-3.389826621564674949e-11,0.000000000000000000e+00 +6.517107710694063805e+00,6.559000000000000341e+01,0.000000000000000000e+00,7.519075165985485754e+00,0.000000000000000000e+00,-1.000000009961116154e+00,0.000000000000000000e+00,-2.626233727397490968e-10,0.000000000000000000e+00 +6.518437661489772772e+00,6.559999999999999432e+01,0.000000000000000000e+00,7.517745215176528717e+00,0.000000000000000000e+00,-1.000000009961465430e+00,0.000000000000000000e+00,6.712153835014516865e-10,0.000000000000000000e+00 +6.519767847564689411e+00,6.560999999999999943e+01,0.000000000000000000e+00,7.516415029088361344e+00,0.000000000000000000e+00,-1.000000009960572589e+00,0.000000000000000000e+00,-6.685931498779490200e-10,0.000000000000000000e+00 +6.521098269043719142e+00,6.562000000000000455e+01,0.000000000000000000e+00,7.515084607596079991e+00,0.000000000000000000e+00,-1.000000009961462100e+00,0.000000000000000000e+00,3.123776434281713561e-10,0.000000000000000000e+00 +6.522428926051877518e+00,6.562999999999999545e+01,0.000000000000000000e+00,7.513753950574666440e+00,0.000000000000000000e+00,-1.000000009961046432e+00,0.000000000000000000e+00,-3.226663412106179780e-10,0.000000000000000000e+00 +6.523759818714291114e+00,6.564000000000000057e+01,0.000000000000000000e+00,7.512423057898995893e+00,0.000000000000000000e+00,-1.000000009961475866e+00,0.000000000000000000e+00,5.132722191526541626e-10,0.000000000000000000e+00 +6.525090947156197529e+00,6.565000000000000568e+01,0.000000000000000000e+00,7.511091929443829862e+00,0.000000000000000000e+00,-1.000000009960792635e+00,0.000000000000000000e+00,-6.112477617706088281e-10,0.000000000000000000e+00 +6.526422311502944495e+00,6.565999999999999659e+01,0.000000000000000000e+00,7.509760565083821504e+00,0.000000000000000000e+00,-1.000000009961606429e+00,0.000000000000000000e+00,3.908624260819166003e-10,0.000000000000000000e+00 +6.527753911879991655e+00,6.567000000000000171e+01,0.000000000000000000e+00,7.508428964693509400e+00,0.000000000000000000e+00,-1.000000009961085956e+00,0.000000000000000000e+00,8.986241111163642750e-11,0.000000000000000000e+00 +6.529085748412909673e+00,6.568000000000000682e+01,0.000000000000000000e+00,7.507097128147324661e+00,0.000000000000000000e+00,-1.000000009960966274e+00,0.000000000000000000e+00,-4.328966350230745928e-10,0.000000000000000000e+00 +6.530417821227381125e+00,6.568999999999999773e+01,0.000000000000000000e+00,7.505765055319584711e+00,0.000000000000000000e+00,-1.000000009961542924e+00,0.000000000000000000e+00,4.008208200466345819e-10,0.000000000000000000e+00 +6.531750130449198721e+00,6.570000000000000284e+01,0.000000000000000000e+00,7.504432746084495065e+00,0.000000000000000000e+00,-1.000000009961008907e+00,0.000000000000000000e+00,-3.325972333364435837e-10,0.000000000000000000e+00 +6.533082676204267969e+00,6.571000000000000796e+01,0.000000000000000000e+00,7.503100200316151991e+00,0.000000000000000000e+00,-1.000000009961452108e+00,0.000000000000000000e+00,-5.364593801408636680e-11,0.000000000000000000e+00 +6.534415458618606287e+00,6.571999999999999886e+01,0.000000000000000000e+00,7.501767417888537182e+00,0.000000000000000000e+00,-1.000000009961523606e+00,0.000000000000000000e+00,3.154886904939344310e-10,0.000000000000000000e+00 +6.535748477818342117e+00,6.573000000000000398e+01,0.000000000000000000e+00,7.500434398675522196e+00,0.000000000000000000e+00,-1.000000009961103054e+00,0.000000000000000000e+00,-1.458917549710338522e-10,0.000000000000000000e+00 +6.537081733929716698e+00,6.573999999999999488e+01,0.000000000000000000e+00,7.499101142550866683e+00,0.000000000000000000e+00,-1.000000009961297565e+00,0.000000000000000000e+00,1.395383088511087725e-10,0.000000000000000000e+00 +6.538415227079083181e+00,6.575000000000000000e+01,0.000000000000000000e+00,7.497767649388216604e+00,0.000000000000000000e+00,-1.000000009961111491e+00,0.000000000000000000e+00,-2.477280217025793937e-10,0.000000000000000000e+00 +6.539748957392907514e+00,6.576000000000000512e+01,0.000000000000000000e+00,7.496433919061106899e+00,0.000000000000000000e+00,-1.000000009961441894e+00,0.000000000000000000e+00,-2.303727107739865941e-10,0.000000000000000000e+00 +6.541082924997767556e+00,6.576999999999999602e+01,0.000000000000000000e+00,7.495099951442958819e+00,0.000000000000000000e+00,-1.000000009961749203e+00,0.000000000000000000e+00,7.690483111581583909e-10,0.000000000000000000e+00 +6.542417130020353966e+00,6.578000000000000114e+01,0.000000000000000000e+00,7.493765746407081707e+00,0.000000000000000000e+00,-1.000000009960723135e+00,0.000000000000000000e+00,-6.627513863919222304e-10,0.000000000000000000e+00 +6.543751572587470200e+00,6.579000000000000625e+01,0.000000000000000000e+00,7.492431303826673883e+00,0.000000000000000000e+00,-1.000000009961607539e+00,0.000000000000000000e+00,4.325500266843940367e-11,0.000000000000000000e+00 +6.545086252826032513e+00,6.579999999999999716e+01,0.000000000000000000e+00,7.491096623574816427e+00,0.000000000000000000e+00,-1.000000009961549807e+00,0.000000000000000000e+00,-2.727906447988525645e-11,0.000000000000000000e+00 +6.546421170863069960e+00,6.581000000000000227e+01,0.000000000000000000e+00,7.489761705524481172e+00,0.000000000000000000e+00,-1.000000009961586223e+00,0.000000000000000000e+00,2.030597699419576452e-10,0.000000000000000000e+00 +6.547756326825725282e+00,6.582000000000000739e+01,0.000000000000000000e+00,7.488426549548525379e+00,0.000000000000000000e+00,-1.000000009961315106e+00,0.000000000000000000e+00,3.145950840221136498e-10,0.000000000000000000e+00 +6.549091720841254904e+00,6.582999999999999829e+01,0.000000000000000000e+00,7.487091155519693508e+00,0.000000000000000000e+00,-1.000000009960894998e+00,0.000000000000000000e+00,-6.082971135256478852e-10,0.000000000000000000e+00 +6.550427353037028055e+00,6.584000000000000341e+01,0.000000000000000000e+00,7.485755523310616333e+00,0.000000000000000000e+00,-1.000000009961707459e+00,0.000000000000000000e+00,3.158126092703865690e-12,0.000000000000000000e+00 +6.551763223540527648e+00,6.584999999999999432e+01,0.000000000000000000e+00,7.484419652793809163e+00,0.000000000000000000e+00,-1.000000009961703240e+00,0.000000000000000000e+00,2.369833756984179386e-10,0.000000000000000000e+00 +6.553099332479350281e+00,6.585999999999999943e+01,0.000000000000000000e+00,7.483083543841676288e+00,0.000000000000000000e+00,-1.000000009961386604e+00,0.000000000000000000e+00,1.729703040606974463e-10,0.000000000000000000e+00 +6.554435679981207130e+00,6.587000000000000455e+01,0.000000000000000000e+00,7.481747196326507421e+00,0.000000000000000000e+00,-1.000000009961155456e+00,0.000000000000000000e+00,-1.079833040232232048e-10,0.000000000000000000e+00 +6.555772266173923057e+00,6.587999999999999545e+01,0.000000000000000000e+00,7.480410610120477699e+00,0.000000000000000000e+00,-1.000000009961299785e+00,0.000000000000000000e+00,-5.263660890147246662e-10,0.000000000000000000e+00 +6.557109091185436611e+00,6.589000000000000057e+01,0.000000000000000000e+00,7.479073785095647686e+00,0.000000000000000000e+00,-1.000000009962003444e+00,0.000000000000000000e+00,4.887404736372611511e-10,0.000000000000000000e+00 +6.558446155143800915e+00,6.590000000000000568e+01,0.000000000000000000e+00,7.477736721123963370e+00,0.000000000000000000e+00,-1.000000009961349967e+00,0.000000000000000000e+00,3.586444767306797972e-11,0.000000000000000000e+00 +6.559783458177184556e+00,6.590999999999999659e+01,0.000000000000000000e+00,7.476399418077258829e+00,0.000000000000000000e+00,-1.000000009961302005e+00,0.000000000000000000e+00,-3.134257764731943190e-10,0.000000000000000000e+00 +6.561121000413868920e+00,6.592000000000000171e+01,0.000000000000000000e+00,7.475061875827250901e+00,0.000000000000000000e+00,-1.000000009961721226e+00,0.000000000000000000e+00,1.692993104228389823e-11,0.000000000000000000e+00 +6.562458781982251743e+00,6.593000000000000682e+01,0.000000000000000000e+00,7.473724094245541849e+00,0.000000000000000000e+00,-1.000000009961698577e+00,0.000000000000000000e+00,1.150033578881029004e-10,0.000000000000000000e+00 +6.563796803010844449e+00,6.593999999999999773e+01,0.000000000000000000e+00,7.472386073203620249e+00,0.000000000000000000e+00,-1.000000009961544700e+00,0.000000000000000000e+00,6.105867089576237845e-11,0.000000000000000000e+00 +6.565135063628273926e+00,6.595000000000000284e+01,0.000000000000000000e+00,7.471047812572859215e+00,0.000000000000000000e+00,-1.000000009961462988e+00,0.000000000000000000e+00,-6.386787560687225183e-11,0.000000000000000000e+00 +6.566473563963283411e+00,6.596000000000000796e+01,0.000000000000000000e+00,7.469709312224516395e+00,0.000000000000000000e+00,-1.000000009961548475e+00,0.000000000000000000e+00,-1.791297345388737581e-10,0.000000000000000000e+00 +6.567812304144729829e+00,6.596999999999999886e+01,0.000000000000000000e+00,7.468370572029733978e+00,0.000000000000000000e+00,-1.000000009961788283e+00,0.000000000000000000e+00,2.916969740463027364e-10,0.000000000000000000e+00 +6.569151284301586458e+00,6.598000000000000398e+01,0.000000000000000000e+00,7.467031591859538686e+00,0.000000000000000000e+00,-1.000000009961397707e+00,0.000000000000000000e+00,-5.670408152837952245e-11,0.000000000000000000e+00 +6.570490504562942036e+00,6.598999999999999488e+01,0.000000000000000000e+00,7.465692371584842668e+00,0.000000000000000000e+00,-1.000000009961473646e+00,0.000000000000000000e+00,-1.525099376089146173e-10,0.000000000000000000e+00 +6.571829965058000766e+00,6.600000000000000000e+01,0.000000000000000000e+00,7.464352911076440833e+00,0.000000000000000000e+00,-1.000000009961677927e+00,0.000000000000000000e+00,8.535709359779024416e-11,0.000000000000000000e+00 +6.573169665916083204e+00,6.601000000000000512e+01,0.000000000000000000e+00,7.463013210205012626e+00,0.000000000000000000e+00,-1.000000009961563574e+00,0.000000000000000000e+00,-2.518825166111597511e-10,0.000000000000000000e+00 +6.574509607266626254e+00,6.601999999999999602e+01,0.000000000000000000e+00,7.461673268841122031e+00,0.000000000000000000e+00,-1.000000009961901082e+00,0.000000000000000000e+00,4.016142086376212885e-10,0.000000000000000000e+00 +6.575849789239181398e+00,6.603000000000000114e+01,0.000000000000000000e+00,7.460333086855215790e+00,0.000000000000000000e+00,-1.000000009961362846e+00,0.000000000000000000e+00,-3.458827776493243142e-10,0.000000000000000000e+00 +6.577190211963418243e+00,6.604000000000000625e+01,0.000000000000000000e+00,7.458992664117626070e+00,0.000000000000000000e+00,-1.000000009961826475e+00,0.000000000000000000e+00,6.012111557651019599e-11,0.000000000000000000e+00 +6.578530875569122749e+00,6.604999999999999716e+01,0.000000000000000000e+00,7.457652000498566025e+00,0.000000000000000000e+00,-1.000000009961745873e+00,0.000000000000000000e+00,2.174237917852343691e-10,0.000000000000000000e+00 +6.579871780186197228e+00,6.606000000000000227e+01,0.000000000000000000e+00,7.456311095868134231e+00,0.000000000000000000e+00,-1.000000009961454328e+00,0.000000000000000000e+00,-2.851001147848847781e-10,0.000000000000000000e+00 +6.581212925944659453e+00,6.607000000000000739e+01,0.000000000000000000e+00,7.454969950096312026e+00,0.000000000000000000e+00,-1.000000009961836689e+00,0.000000000000000000e+00,1.153769092536089867e-10,0.000000000000000000e+00 +6.582554312974646216e+00,6.607999999999999829e+01,0.000000000000000000e+00,7.453628563052962619e+00,0.000000000000000000e+00,-1.000000009961681924e+00,0.000000000000000000e+00,1.986045611449228647e-11,0.000000000000000000e+00 +6.583895941406409769e+00,6.609000000000000341e+01,0.000000000000000000e+00,7.452286934607833757e+00,0.000000000000000000e+00,-1.000000009961655278e+00,0.000000000000000000e+00,4.467798292094016757e-12,0.000000000000000000e+00 +6.585237811370321381e+00,6.609999999999999432e+01,0.000000000000000000e+00,7.450945064630555059e+00,0.000000000000000000e+00,-1.000000009961649283e+00,0.000000000000000000e+00,-3.426349699264781160e-10,0.000000000000000000e+00 +6.586579922996867786e+00,6.610999999999999943e+01,0.000000000000000000e+00,7.449602952990638904e+00,0.000000000000000000e+00,-1.000000009962109138e+00,0.000000000000000000e+00,5.409051352662650827e-10,0.000000000000000000e+00 +6.587922276416654732e+00,6.612000000000000455e+01,0.000000000000000000e+00,7.448260599557479544e+00,0.000000000000000000e+00,-1.000000009961383052e+00,0.000000000000000000e+00,-2.211192211911316780e-10,0.000000000000000000e+00 +6.589264871760404318e+00,6.612999999999999545e+01,0.000000000000000000e+00,7.446918004200355767e+00,0.000000000000000000e+00,-1.000000009961679925e+00,0.000000000000000000e+00,-8.102385034143675784e-11,0.000000000000000000e+00 +6.590607709158957661e+00,6.614000000000000057e+01,0.000000000000000000e+00,7.445575166788425570e+00,0.000000000000000000e+00,-1.000000009961788727e+00,0.000000000000000000e+00,5.802906785185552324e-11,0.000000000000000000e+00 +6.591950788743273115e+00,6.615000000000000568e+01,0.000000000000000000e+00,7.444232087190730596e+00,0.000000000000000000e+00,-1.000000009961710790e+00,0.000000000000000000e+00,-2.142225238310576860e-10,0.000000000000000000e+00 +6.593294110644427164e+00,6.615999999999999659e+01,0.000000000000000000e+00,7.442888765276194363e+00,0.000000000000000000e+00,-1.000000009961998559e+00,0.000000000000000000e+00,1.703885547543694589e-10,0.000000000000000000e+00 +6.594637674993615306e+00,6.617000000000000171e+01,0.000000000000000000e+00,7.441545200913621372e+00,0.000000000000000000e+00,-1.000000009961769631e+00,0.000000000000000000e+00,-1.817590460585490647e-10,0.000000000000000000e+00 +6.595981481922151168e+00,6.618000000000000682e+01,0.000000000000000000e+00,7.440201393971698884e+00,0.000000000000000000e+00,-1.000000009962013880e+00,0.000000000000000000e+00,2.877882560769751243e-10,0.000000000000000000e+00 +6.597325531561466505e+00,6.618999999999999773e+01,0.000000000000000000e+00,7.438857344318994258e+00,0.000000000000000000e+00,-1.000000009961627079e+00,0.000000000000000000e+00,-3.042538494088106515e-10,0.000000000000000000e+00 +6.598669824043112087e+00,6.620000000000000284e+01,0.000000000000000000e+00,7.437513051823957611e+00,0.000000000000000000e+00,-1.000000009962036085e+00,0.000000000000000000e+00,9.165601042054430437e-11,0.000000000000000000e+00 +6.600014359498756811e+00,6.621000000000000796e+01,0.000000000000000000e+00,7.436168516354918268e+00,0.000000000000000000e+00,-1.000000009961912850e+00,0.000000000000000000e+00,8.404410000883219808e-11,0.000000000000000000e+00 +6.601359138060190368e+00,6.621999999999999886e+01,0.000000000000000000e+00,7.434823737780088315e+00,0.000000000000000000e+00,-1.000000009961799829e+00,0.000000000000000000e+00,-2.426767874327657704e-10,0.000000000000000000e+00 +6.602704159859319688e+00,6.623000000000000398e+01,0.000000000000000000e+00,7.433478715967559936e+00,0.000000000000000000e+00,-1.000000009962126235e+00,0.000000000000000000e+00,1.762802186145629552e-10,0.000000000000000000e+00 +6.604049425028172493e+00,6.623999999999999488e+01,0.000000000000000000e+00,7.432133450785305406e+00,0.000000000000000000e+00,-1.000000009961889091e+00,0.000000000000000000e+00,-4.752763591189630324e-11,0.000000000000000000e+00 +6.605394933698895521e+00,6.625000000000000000e+01,0.000000000000000000e+00,7.430787942101178878e+00,0.000000000000000000e+00,-1.000000009961953040e+00,0.000000000000000000e+00,1.508069264817385795e-10,0.000000000000000000e+00 +6.606740686003754526e+00,6.626000000000000512e+01,0.000000000000000000e+00,7.429442189782913708e+00,0.000000000000000000e+00,-1.000000009961750091e+00,0.000000000000000000e+00,-1.255397009997060557e-10,0.000000000000000000e+00 +6.608086682075135165e+00,6.626999999999999602e+01,0.000000000000000000e+00,7.428096193698124239e+00,0.000000000000000000e+00,-1.000000009961919067e+00,0.000000000000000000e+00,1.878630931844629890e-10,0.000000000000000000e+00 +6.609432922045543890e+00,6.628000000000000114e+01,0.000000000000000000e+00,7.426749953714304020e+00,0.000000000000000000e+00,-1.000000009961666159e+00,0.000000000000000000e+00,-2.946887659957533751e-10,0.000000000000000000e+00 +6.610779406047607054e+00,6.629000000000000625e+01,0.000000000000000000e+00,7.425403469698827585e+00,0.000000000000000000e+00,-1.000000009962062952e+00,0.000000000000000000e+00,-2.011500351402643886e-11,0.000000000000000000e+00 +6.612126134214070916e+00,6.629999999999999716e+01,0.000000000000000000e+00,7.424056741518947788e+00,0.000000000000000000e+00,-1.000000009962090042e+00,0.000000000000000000e+00,1.170414939739228858e-10,0.000000000000000000e+00 +6.613473106677801638e+00,6.631000000000000227e+01,0.000000000000000000e+00,7.422709769041798467e+00,0.000000000000000000e+00,-1.000000009961932390e+00,0.000000000000000000e+00,-2.884302151745099133e-10,0.000000000000000000e+00 +6.614820323571786176e+00,6.632000000000000739e+01,0.000000000000000000e+00,7.421362552134392665e+00,0.000000000000000000e+00,-1.000000009962320968e+00,0.000000000000000000e+00,3.157325656453101745e-10,0.000000000000000000e+00 +6.616167785029133164e+00,6.632999999999999829e+01,0.000000000000000000e+00,7.420015090663621748e+00,0.000000000000000000e+00,-1.000000009961895531e+00,0.000000000000000000e+00,5.717082888124284438e-11,0.000000000000000000e+00 +6.617515491183071141e+00,6.634000000000000341e+01,0.000000000000000000e+00,7.418667384496258066e+00,0.000000000000000000e+00,-1.000000009961818481e+00,0.000000000000000000e+00,-1.647275068460686972e-13,0.000000000000000000e+00 +6.618863442166949440e+00,6.634999999999999432e+01,0.000000000000000000e+00,7.417319433498951398e+00,0.000000000000000000e+00,-1.000000009961818703e+00,0.000000000000000000e+00,-2.608809608931026357e-10,0.000000000000000000e+00 +6.620211638114239960e+00,6.635999999999999943e+01,0.000000000000000000e+00,7.415971237538230731e+00,0.000000000000000000e+00,-1.000000009962170422e+00,0.000000000000000000e+00,-1.514942291288606162e-10,0.000000000000000000e+00 +6.621560079158533618e+00,6.637000000000000455e+01,0.000000000000000000e+00,7.414622796480503375e+00,0.000000000000000000e+00,-1.000000009962374703e+00,0.000000000000000000e+00,4.129113489697711455e-10,0.000000000000000000e+00 +6.622908765433544787e+00,6.637999999999999545e+01,0.000000000000000000e+00,7.413274110192055844e+00,0.000000000000000000e+00,-1.000000009961817815e+00,0.000000000000000000e+00,5.234526516775414664e-11,0.000000000000000000e+00 +6.624257697073108631e+00,6.639000000000000057e+01,0.000000000000000000e+00,7.411925178539053860e+00,0.000000000000000000e+00,-1.000000009961747205e+00,0.000000000000000000e+00,-6.584757770008388344e-10,0.000000000000000000e+00 +6.625606874211182884e+00,6.640000000000000568e+01,0.000000000000000000e+00,7.410576001387539691e+00,0.000000000000000000e+00,-1.000000009962635605e+00,0.000000000000000000e+00,8.046389476220621215e-10,0.000000000000000000e+00 +6.626956296981846073e+00,6.640999999999999659e+01,0.000000000000000000e+00,7.409226578603433033e+00,0.000000000000000000e+00,-1.000000009961549807e+00,0.000000000000000000e+00,-8.390411821074806458e-10,0.000000000000000000e+00 +6.628305965519299292e+00,6.642000000000000171e+01,0.000000000000000000e+00,7.407876910052535457e+00,0.000000000000000000e+00,-1.000000009962682235e+00,0.000000000000000000e+00,8.365855111886410234e-10,0.000000000000000000e+00 +6.629655879957865316e+00,6.643000000000000682e+01,0.000000000000000000e+00,7.406526995600520635e+00,0.000000000000000000e+00,-1.000000009961552916e+00,0.000000000000000000e+00,-4.210123163148023435e-10,0.000000000000000000e+00 +6.631006040431990378e+00,6.643999999999999773e+01,0.000000000000000000e+00,7.405176835112945888e+00,0.000000000000000000e+00,-1.000000009962121350e+00,0.000000000000000000e+00,-1.389416232215987396e-10,0.000000000000000000e+00 +6.632356447076242389e+00,6.645000000000000284e+01,0.000000000000000000e+00,7.403826428455240638e+00,0.000000000000000000e+00,-1.000000009962308978e+00,0.000000000000000000e+00,-1.810021665378074163e-10,0.000000000000000000e+00 +6.633707100025312720e+00,6.646000000000000796e+01,0.000000000000000000e+00,7.402475775492714405e+00,0.000000000000000000e+00,-1.000000009962553449e+00,0.000000000000000000e+00,5.129924684002586949e-10,0.000000000000000000e+00 +6.635057999414015306e+00,6.646999999999999886e+01,0.000000000000000000e+00,7.401124876090553251e+00,0.000000000000000000e+00,-1.000000009961860448e+00,0.000000000000000000e+00,-4.046001188514601286e-10,0.000000000000000000e+00 +6.636409145377286656e+00,6.648000000000000398e+01,0.000000000000000000e+00,7.399773730113821557e+00,0.000000000000000000e+00,-1.000000009962407121e+00,0.000000000000000000e+00,5.591400676591659233e-10,0.000000000000000000e+00 +6.637760538050187620e+00,6.648999999999999488e+01,0.000000000000000000e+00,7.398422337427457585e+00,0.000000000000000000e+00,-1.000000009961651504e+00,0.000000000000000000e+00,-4.013310965852507153e-10,0.000000000000000000e+00 +6.639112177567900730e+00,6.650000000000000000e+01,0.000000000000000000e+00,7.397070697896279690e+00,0.000000000000000000e+00,-1.000000009962193959e+00,0.000000000000000000e+00,-2.811925144907341307e-10,0.000000000000000000e+00 +6.640464064065733751e+00,6.651000000000000512e+01,0.000000000000000000e+00,7.395718811384979219e+00,0.000000000000000000e+00,-1.000000009962574099e+00,0.000000000000000000e+00,5.187644919227884887e-10,0.000000000000000000e+00 +6.641816197679116129e+00,6.651999999999999602e+01,0.000000000000000000e+00,7.394366677758125839e+00,0.000000000000000000e+00,-1.000000009961872660e+00,0.000000000000000000e+00,-3.431527585754264366e-10,0.000000000000000000e+00 +6.643168578543603431e+00,6.653000000000000114e+01,0.000000000000000000e+00,7.393014296880166647e+00,0.000000000000000000e+00,-1.000000009962336733e+00,0.000000000000000000e+00,1.337886835086029920e-10,0.000000000000000000e+00 +6.644521206794872903e+00,6.654000000000000625e+01,0.000000000000000000e+00,7.391661668615421732e+00,0.000000000000000000e+00,-1.000000009962155767e+00,0.000000000000000000e+00,-3.907884334569304559e-10,0.000000000000000000e+00 +6.645874082568727914e+00,6.654999999999999716e+01,0.000000000000000000e+00,7.390308792828089501e+00,0.000000000000000000e+00,-1.000000009962684455e+00,0.000000000000000000e+00,5.960032808516672687e-10,0.000000000000000000e+00 +6.647227206001094402e+00,6.656000000000000227e+01,0.000000000000000000e+00,7.388955669382242242e+00,0.000000000000000000e+00,-1.000000009961877989e+00,0.000000000000000000e+00,-6.989287182694504465e-10,0.000000000000000000e+00 +6.648580577228023536e+00,6.657000000000000739e+01,0.000000000000000000e+00,7.387602298141830559e+00,0.000000000000000000e+00,-1.000000009962823899e+00,0.000000000000000000e+00,6.610720251545648987e-10,0.000000000000000000e+00 +6.649934196385691720e+00,6.657999999999999829e+01,0.000000000000000000e+00,7.386248678970676274e+00,0.000000000000000000e+00,-1.000000009961929059e+00,0.000000000000000000e+00,-8.544799449658406908e-11,0.000000000000000000e+00 +6.651288063610399703e+00,6.659000000000000341e+01,0.000000000000000000e+00,7.384894811732481301e+00,0.000000000000000000e+00,-1.000000009962044745e+00,0.000000000000000000e+00,-4.258498404145883963e-10,0.000000000000000000e+00 +6.652642179038572579e+00,6.659999999999999432e+01,0.000000000000000000e+00,7.383540696290818772e+00,0.000000000000000000e+00,-1.000000009962621395e+00,0.000000000000000000e+00,2.101807433129116859e-10,0.000000000000000000e+00 +6.653996542806760672e+00,6.660999999999999943e+01,0.000000000000000000e+00,7.382186332509137472e+00,0.000000000000000000e+00,-1.000000009962336733e+00,0.000000000000000000e+00,-2.622679436295931795e-11,0.000000000000000000e+00 +6.655351155051640433e+00,6.662000000000000455e+01,0.000000000000000000e+00,7.380831720250762729e+00,0.000000000000000000e+00,-1.000000009962372260e+00,0.000000000000000000e+00,-7.882983282671268106e-11,0.000000000000000000e+00 +6.656706015910012653e+00,6.662999999999999545e+01,0.000000000000000000e+00,7.379476859378892861e+00,0.000000000000000000e+00,-1.000000009962479064e+00,0.000000000000000000e+00,1.400979935344038453e-10,0.000000000000000000e+00 +6.658061125518804246e+00,6.664000000000000057e+01,0.000000000000000000e+00,7.378121749756600956e+00,0.000000000000000000e+00,-1.000000009962289216e+00,0.000000000000000000e+00,2.342729144489283647e-10,0.000000000000000000e+00 +6.659416484015068249e+00,6.665000000000000568e+01,0.000000000000000000e+00,7.376766391246834864e+00,0.000000000000000000e+00,-1.000000009961971692e+00,0.000000000000000000e+00,-6.735337487919098557e-10,0.000000000000000000e+00 +6.660772091535982042e+00,6.665999999999999659e+01,0.000000000000000000e+00,7.375410783712416318e+00,0.000000000000000000e+00,-1.000000009962884739e+00,0.000000000000000000e+00,4.040132318343332369e-10,0.000000000000000000e+00 +6.662127948218850904e+00,6.667000000000000171e+01,0.000000000000000000e+00,7.374054927016039152e+00,0.000000000000000000e+00,-1.000000009962336955e+00,0.000000000000000000e+00,1.722512306838924308e-10,0.000000000000000000e+00 +6.663484054201105344e+00,6.668000000000000682e+01,0.000000000000000000e+00,7.372698821020274629e+00,0.000000000000000000e+00,-1.000000009962103364e+00,0.000000000000000000e+00,-3.130074010158248754e-10,0.000000000000000000e+00 +6.664840409620302886e+00,6.668999999999999773e+01,0.000000000000000000e+00,7.371342465587565229e+00,0.000000000000000000e+00,-1.000000009962527914e+00,0.000000000000000000e+00,2.782503603415444871e-12,0.000000000000000000e+00 +6.666197014614126282e+00,6.670000000000000284e+01,0.000000000000000000e+00,7.369985860580226422e+00,0.000000000000000000e+00,-1.000000009962524139e+00,0.000000000000000000e+00,2.415423223704230166e-10,0.000000000000000000e+00 +6.667553869320386184e+00,6.671000000000000796e+01,0.000000000000000000e+00,7.368629005860448444e+00,0.000000000000000000e+00,-1.000000009962196401e+00,0.000000000000000000e+00,-4.717061724312115337e-10,0.000000000000000000e+00 +6.668910973877020254e+00,6.671999999999999886e+01,0.000000000000000000e+00,7.367271901290294522e+00,0.000000000000000000e+00,-1.000000009962836556e+00,0.000000000000000000e+00,3.634887538665373497e-10,0.000000000000000000e+00 +6.670268328422092274e+00,6.673000000000000398e+01,0.000000000000000000e+00,7.365914546731699097e+00,0.000000000000000000e+00,-1.000000009962343173e+00,0.000000000000000000e+00,-5.724465549042034053e-11,0.000000000000000000e+00 +6.671625933093793925e+00,6.673999999999999488e+01,0.000000000000000000e+00,7.364556942046472265e+00,0.000000000000000000e+00,-1.000000009962420888e+00,0.000000000000000000e+00,2.835541076941746149e-10,0.000000000000000000e+00 +6.672983788030443897e+00,6.675000000000000000e+01,0.000000000000000000e+00,7.363199087096294448e+00,0.000000000000000000e+00,-1.000000009962035863e+00,0.000000000000000000e+00,-4.515755742353625566e-10,0.000000000000000000e+00 +6.674341893370488776e+00,6.676000000000000512e+01,0.000000000000000000e+00,7.361840981742719947e+00,0.000000000000000000e+00,-1.000000009962649150e+00,0.000000000000000000e+00,-2.468332179191069564e-10,0.000000000000000000e+00 +6.675700249252502161e+00,6.676999999999999602e+01,0.000000000000000000e+00,7.360482625847173388e+00,0.000000000000000000e+00,-1.000000009962984437e+00,0.000000000000000000e+00,5.050158361245619020e-10,0.000000000000000000e+00 +6.677058855815186433e+00,6.678000000000000114e+01,0.000000000000000000e+00,7.359124019270953276e+00,0.000000000000000000e+00,-1.000000009962298320e+00,0.000000000000000000e+00,-3.104702192361321658e-11,0.000000000000000000e+00 +6.678417713197370986e+00,6.679000000000000625e+01,0.000000000000000000e+00,7.357765161875231108e+00,0.000000000000000000e+00,-1.000000009962340508e+00,0.000000000000000000e+00,-3.210322794951998477e-10,0.000000000000000000e+00 +6.679776821538013998e+00,6.679999999999999716e+01,0.000000000000000000e+00,7.356406053521047816e+00,0.000000000000000000e+00,-1.000000009962776826e+00,0.000000000000000000e+00,2.048346645881025996e-10,0.000000000000000000e+00 +6.681136180976202432e+00,6.681000000000000227e+01,0.000000000000000000e+00,7.355046694069316437e+00,0.000000000000000000e+00,-1.000000009962498382e+00,0.000000000000000000e+00,1.945079788931226672e-10,0.000000000000000000e+00 +6.682495791651151151e+00,6.682000000000000739e+01,0.000000000000000000e+00,7.353687083380822997e+00,0.000000000000000000e+00,-1.000000009962233927e+00,0.000000000000000000e+00,-2.614187315617732359e-10,0.000000000000000000e+00 +6.683855653702202915e+00,6.682999999999999829e+01,0.000000000000000000e+00,7.352327221316223849e+00,0.000000000000000000e+00,-1.000000009962589420e+00,0.000000000000000000e+00,-1.121558135484922684e-10,0.000000000000000000e+00 +6.685215767268831044e+00,6.684000000000000341e+01,0.000000000000000000e+00,7.350967107736045669e+00,0.000000000000000000e+00,-1.000000009962741965e+00,0.000000000000000000e+00,2.521814797307662330e-10,0.000000000000000000e+00 +6.686576132490636759e+00,6.684999999999999432e+01,0.000000000000000000e+00,7.349606742500687240e+00,0.000000000000000000e+00,-1.000000009962398906e+00,0.000000000000000000e+00,-5.173251465812529289e-10,0.000000000000000000e+00 +6.687936749507350065e+00,6.685999999999999943e+01,0.000000000000000000e+00,7.348246125470418555e+00,0.000000000000000000e+00,-1.000000009963102787e+00,0.000000000000000000e+00,5.479041773466178512e-10,0.000000000000000000e+00 +6.689297618458832417e+00,6.687000000000000455e+01,0.000000000000000000e+00,7.346885256505378159e+00,0.000000000000000000e+00,-1.000000009962357161e+00,0.000000000000000000e+00,-2.977188627433750247e-10,0.000000000000000000e+00 +6.690658739485072282e+00,6.687999999999999545e+01,0.000000000000000000e+00,7.345524135465578475e+00,0.000000000000000000e+00,-1.000000009962762393e+00,0.000000000000000000e+00,3.922636781127301528e-10,0.000000000000000000e+00 +6.692020112726188685e+00,6.689000000000000057e+01,0.000000000000000000e+00,7.344162762210898698e+00,0.000000000000000000e+00,-1.000000009962228376e+00,0.000000000000000000e+00,-6.454436143961291714e-10,0.000000000000000000e+00 +6.693381738322431218e+00,6.690000000000000568e+01,0.000000000000000000e+00,7.342801136601091017e+00,0.000000000000000000e+00,-1.000000009963107228e+00,0.000000000000000000e+00,5.127700391984831321e-10,0.000000000000000000e+00 +6.694743616414179144e+00,6.690999999999999659e+01,0.000000000000000000e+00,7.341439258495774389e+00,0.000000000000000000e+00,-1.000000009962408898e+00,0.000000000000000000e+00,-3.529224911123696214e-10,0.000000000000000000e+00 +6.696105747141941400e+00,6.692000000000000171e+01,0.000000000000000000e+00,7.340077127754441655e+00,0.000000000000000000e+00,-1.000000009962889624e+00,0.000000000000000000e+00,2.011203465024143098e-10,0.000000000000000000e+00 +6.697468130646358375e+00,6.693000000000000682e+01,0.000000000000000000e+00,7.338714744236451537e+00,0.000000000000000000e+00,-1.000000009962615621e+00,0.000000000000000000e+00,-1.275915738560482779e-10,0.000000000000000000e+00 +6.698830767068199243e+00,6.693999999999999773e+01,0.000000000000000000e+00,7.337352107801034862e+00,0.000000000000000000e+00,-1.000000009962789482e+00,0.000000000000000000e+00,1.885006903618213298e-10,0.000000000000000000e+00 +6.700193656548365517e+00,6.695000000000000284e+01,0.000000000000000000e+00,7.335989218307290116e+00,0.000000000000000000e+00,-1.000000009962532577e+00,0.000000000000000000e+00,-1.940039941806577651e-10,0.000000000000000000e+00 +6.701556799227889272e+00,6.696000000000000796e+01,0.000000000000000000e+00,7.334626075614186114e+00,0.000000000000000000e+00,-1.000000009962797032e+00,0.000000000000000000e+00,2.506437175668947589e-10,0.000000000000000000e+00 +6.702920195247933144e+00,6.696999999999999886e+01,0.000000000000000000e+00,7.333262679580559329e+00,0.000000000000000000e+00,-1.000000009962455305e+00,0.000000000000000000e+00,-2.965155085802573178e-10,0.000000000000000000e+00 +6.704283844749790333e+00,6.698000000000000398e+01,0.000000000000000000e+00,7.331899030065116563e+00,0.000000000000000000e+00,-1.000000009962859648e+00,0.000000000000000000e+00,1.668708839068054970e-10,0.000000000000000000e+00 +6.705647747874887266e+00,6.698999999999999488e+01,0.000000000000000000e+00,7.330535126926431388e+00,0.000000000000000000e+00,-1.000000009962632053e+00,0.000000000000000000e+00,-1.772571590224565951e-10,0.000000000000000000e+00 +6.707011904764780041e+00,6.700000000000000000e+01,0.000000000000000000e+00,7.329170970022947706e+00,0.000000000000000000e+00,-1.000000009962873859e+00,0.000000000000000000e+00,1.957765655577504864e-10,0.000000000000000000e+00 +6.708376315561157988e+00,6.701000000000000512e+01,0.000000000000000000e+00,7.327806559212976190e+00,0.000000000000000000e+00,-1.000000009962606740e+00,0.000000000000000000e+00,-5.369429710944744290e-11,0.000000000000000000e+00 +6.709740980405841881e+00,6.701999999999999602e+01,0.000000000000000000e+00,7.326441894354696949e+00,0.000000000000000000e+00,-1.000000009962680014e+00,0.000000000000000000e+00,-3.552924420728999664e-10,0.000000000000000000e+00 +6.711105899440783951e+00,6.703000000000000114e+01,0.000000000000000000e+00,7.325076975306156868e+00,0.000000000000000000e+00,-1.000000009963164960e+00,0.000000000000000000e+00,3.363589226020454180e-10,0.000000000000000000e+00 +6.712471072808068762e+00,6.704000000000000625e+01,0.000000000000000000e+00,7.323711801925270493e+00,0.000000000000000000e+00,-1.000000009962705771e+00,0.000000000000000000e+00,-2.688093216592351755e-10,0.000000000000000000e+00 +6.713836500649914107e+00,6.704999999999999716e+01,0.000000000000000000e+00,7.322346374069821806e+00,0.000000000000000000e+00,-1.000000009963072811e+00,0.000000000000000000e+00,3.040409639501043928e-10,0.000000000000000000e+00 +6.715202183108670120e+00,6.706000000000000227e+01,0.000000000000000000e+00,7.320980691597459789e+00,0.000000000000000000e+00,-1.000000009962657588e+00,0.000000000000000000e+00,-2.327836667951902097e-10,0.000000000000000000e+00 +6.716568120326818381e+00,6.707000000000000739e+01,0.000000000000000000e+00,7.319614754365702858e+00,0.000000000000000000e+00,-1.000000009962975556e+00,0.000000000000000000e+00,1.176703419627671235e-10,0.000000000000000000e+00 +6.717934312446975476e+00,6.707999999999999829e+01,0.000000000000000000e+00,7.318248562231934429e+00,0.000000000000000000e+00,-1.000000009962814795e+00,0.000000000000000000e+00,2.063721565644839582e-11,0.000000000000000000e+00 +6.719300759611889440e+00,6.709000000000000341e+01,0.000000000000000000e+00,7.316882115053406466e+00,0.000000000000000000e+00,-1.000000009962786596e+00,0.000000000000000000e+00,4.581581239826572801e-11,0.000000000000000000e+00 +6.720667461964443312e+00,6.709999999999999432e+01,0.000000000000000000e+00,7.315515412687236818e+00,0.000000000000000000e+00,-1.000000009962723979e+00,0.000000000000000000e+00,-1.890767529292945539e-10,0.000000000000000000e+00 +6.722034419647651582e+00,6.710999999999999943e+01,0.000000000000000000e+00,7.314148454990410109e+00,0.000000000000000000e+00,-1.000000009962982439e+00,0.000000000000000000e+00,3.600556991381895433e-10,0.000000000000000000e+00 +6.723401632804663741e+00,6.712000000000000455e+01,0.000000000000000000e+00,7.312781241819776845e+00,0.000000000000000000e+00,-1.000000009962490166e+00,0.000000000000000000e+00,-5.886143128818563769e-10,0.000000000000000000e+00 +6.724769101578761621e+00,6.712999999999999545e+01,0.000000000000000000e+00,7.311413773032055197e+00,0.000000000000000000e+00,-1.000000009963295078e+00,0.000000000000000000e+00,3.836235939064179645e-10,0.000000000000000000e+00 +6.726136826113362943e+00,6.714000000000000057e+01,0.000000000000000000e+00,7.310046048483826553e+00,0.000000000000000000e+00,-1.000000009962770386e+00,0.000000000000000000e+00,4.625995417435226001e-11,0.000000000000000000e+00 +6.727504806552018657e+00,6.715000000000000568e+01,0.000000000000000000e+00,7.308678068031541741e+00,0.000000000000000000e+00,-1.000000009962707104e+00,0.000000000000000000e+00,-5.559892781964683921e-10,0.000000000000000000e+00 +6.728873043038413826e+00,6.715999999999999659e+01,0.000000000000000000e+00,7.307309831531514810e+00,0.000000000000000000e+00,-1.000000009963467829e+00,0.000000000000000000e+00,5.678920536125243023e-10,0.000000000000000000e+00 +6.730241535716368517e+00,6.717000000000000171e+01,0.000000000000000000e+00,7.305941338839924803e+00,0.000000000000000000e+00,-1.000000009962690672e+00,0.000000000000000000e+00,-2.817839318672843540e-10,0.000000000000000000e+00 +6.731610284729837801e+00,6.718000000000000682e+01,0.000000000000000000e+00,7.304572589812819317e+00,0.000000000000000000e+00,-1.000000009963076364e+00,0.000000000000000000e+00,3.080065835282429188e-10,0.000000000000000000e+00 +6.732979290222909974e+00,6.718999999999999773e+01,0.000000000000000000e+00,7.303203584306107388e+00,0.000000000000000000e+00,-1.000000009962654701e+00,0.000000000000000000e+00,-4.112471316775121356e-10,0.000000000000000000e+00 +6.734348552339810112e+00,6.720000000000000284e+01,0.000000000000000000e+00,7.301834322175565717e+00,0.000000000000000000e+00,-1.000000009963217806e+00,0.000000000000000000e+00,2.415786046770305903e-11,0.000000000000000000e+00 +6.735718071224897407e+00,6.721000000000000796e+01,0.000000000000000000e+00,7.300464803276833337e+00,0.000000000000000000e+00,-1.000000009963184722e+00,0.000000000000000000e+00,2.867599987909467534e-10,0.000000000000000000e+00 +6.737087847022666942e+00,6.721999999999999886e+01,0.000000000000000000e+00,7.299095027465416052e+00,0.000000000000000000e+00,-1.000000009962791925e+00,0.000000000000000000e+00,-4.862174015051456336e-13,0.000000000000000000e+00 +6.738457879877749690e+00,6.723000000000000398e+01,0.000000000000000000e+00,7.297724994596683779e+00,0.000000000000000000e+00,-1.000000009962792591e+00,0.000000000000000000e+00,-2.694759230429230111e-10,0.000000000000000000e+00 +6.739828169934911628e+00,6.723999999999999488e+01,0.000000000000000000e+00,7.296354704525869650e+00,0.000000000000000000e+00,-1.000000009963161851e+00,0.000000000000000000e+00,4.811745107345241023e-11,0.000000000000000000e+00 +6.741198717339055513e+00,6.725000000000000000e+01,0.000000000000000000e+00,7.294984157108070910e+00,0.000000000000000000e+00,-1.000000009963095904e+00,0.000000000000000000e+00,1.010762610062040693e-10,0.000000000000000000e+00 +6.742569522235219104e+00,6.726000000000000512e+01,0.000000000000000000e+00,7.293613352198249800e+00,0.000000000000000000e+00,-1.000000009962957348e+00,0.000000000000000000e+00,-1.473751820690962158e-11,0.000000000000000000e+00 +6.743940584768576940e+00,6.726999999999999602e+01,0.000000000000000000e+00,7.292242289651231779e+00,0.000000000000000000e+00,-1.000000009962977554e+00,0.000000000000000000e+00,-2.030480635011909683e-10,0.000000000000000000e+00 +6.745311905084440340e+00,6.728000000000000114e+01,0.000000000000000000e+00,7.290870969321705530e+00,0.000000000000000000e+00,-1.000000009963255998e+00,0.000000000000000000e+00,1.034476182359205156e-10,0.000000000000000000e+00 +6.746683483328257402e+00,6.729000000000000625e+01,0.000000000000000000e+00,7.289499391064222955e+00,0.000000000000000000e+00,-1.000000009963114111e+00,0.000000000000000000e+00,5.600335282869786537e-11,0.000000000000000000e+00 +6.748055319645612116e+00,6.729999999999999716e+01,0.000000000000000000e+00,7.288127554733200064e+00,0.000000000000000000e+00,-1.000000009963037284e+00,0.000000000000000000e+00,2.230002798069807764e-10,0.000000000000000000e+00 +6.749427414182227025e+00,6.731000000000000227e+01,0.000000000000000000e+00,7.286755460182915201e+00,0.000000000000000000e+00,-1.000000009962731307e+00,0.000000000000000000e+00,-7.145020600100639331e-10,0.000000000000000000e+00 +6.750799767083959679e+00,6.732000000000000739e+01,0.000000000000000000e+00,7.285383107267509928e+00,0.000000000000000000e+00,-1.000000009963711856e+00,0.000000000000000000e+00,6.404395174557835611e-10,0.000000000000000000e+00 +6.752172378496807070e+00,6.732999999999999829e+01,0.000000000000000000e+00,7.284010495840986366e+00,0.000000000000000000e+00,-1.000000009962832781e+00,0.000000000000000000e+00,-3.305914975881613177e-10,0.000000000000000000e+00 +6.753545248566902082e+00,6.734000000000000341e+01,0.000000000000000000e+00,7.282637625757213407e+00,0.000000000000000000e+00,-1.000000009963286640e+00,0.000000000000000000e+00,2.401349535718791602e-10,0.000000000000000000e+00 +6.754918377440517041e+00,6.734999999999999432e+01,0.000000000000000000e+00,7.281264496869917835e+00,0.000000000000000000e+00,-1.000000009962956904e+00,0.000000000000000000e+00,-3.784848032133964501e-10,0.000000000000000000e+00 +6.756291765264060167e+00,6.735999999999999943e+01,0.000000000000000000e+00,7.279891109032691432e+00,0.000000000000000000e+00,-1.000000009963476710e+00,0.000000000000000000e+00,2.657461136312765444e-10,0.000000000000000000e+00 +6.757665412184080012e+00,6.737000000000000455e+01,0.000000000000000000e+00,7.278517462098985646e+00,0.000000000000000000e+00,-1.000000009963111669e+00,0.000000000000000000e+00,-8.484816555136481468e-11,0.000000000000000000e+00 +6.759039318347261016e+00,6.737999999999999545e+01,0.000000000000000000e+00,7.277143555922116036e+00,0.000000000000000000e+00,-1.000000009963228242e+00,0.000000000000000000e+00,7.885350273384422435e-11,0.000000000000000000e+00 +6.760413483900427956e+00,6.739000000000000057e+01,0.000000000000000000e+00,7.275769390355257826e+00,0.000000000000000000e+00,-1.000000009963119885e+00,0.000000000000000000e+00,-8.691633928162031699e-11,0.000000000000000000e+00 +6.761787908990543272e+00,6.740000000000000568e+01,0.000000000000000000e+00,7.274394965251448575e+00,0.000000000000000000e+00,-1.000000009963239345e+00,0.000000000000000000e+00,4.554977240280663241e-10,0.000000000000000000e+00 +6.763162593764708852e+00,6.740999999999999659e+01,0.000000000000000000e+00,7.273020280463586396e+00,0.000000000000000000e+00,-1.000000009962613179e+00,0.000000000000000000e+00,-5.466554686554934314e-10,0.000000000000000000e+00 +6.764537538370165137e+00,6.742000000000000171e+01,0.000000000000000000e+00,7.271645335844431735e+00,0.000000000000000000e+00,-1.000000009963364800e+00,0.000000000000000000e+00,-1.763175540401755565e-10,0.000000000000000000e+00 +6.765912742954292014e+00,6.743000000000000682e+01,0.000000000000000000e+00,7.270270131246602929e+00,0.000000000000000000e+00,-1.000000009963607273e+00,0.000000000000000000e+00,2.542560707910678997e-10,0.000000000000000000e+00 +6.767288207664608812e+00,6.743999999999999773e+01,0.000000000000000000e+00,7.268894666522581538e+00,0.000000000000000000e+00,-1.000000009963257552e+00,0.000000000000000000e+00,3.728383530724946269e-10,0.000000000000000000e+00 +6.768663932648774306e+00,6.745000000000000284e+01,0.000000000000000000e+00,7.267518941524709675e+00,0.000000000000000000e+00,-1.000000009962744629e+00,0.000000000000000000e+00,-6.596860265373874416e-10,0.000000000000000000e+00 +6.770039918054585826e+00,6.746000000000000796e+01,0.000000000000000000e+00,7.266142956105189121e+00,0.000000000000000000e+00,-1.000000009963652348e+00,0.000000000000000000e+00,5.380715153127281531e-10,0.000000000000000000e+00 +6.771416164029982809e+00,6.746999999999999886e+01,0.000000000000000000e+00,7.264766710116079551e+00,0.000000000000000000e+00,-1.000000009962911829e+00,0.000000000000000000e+00,-6.262062950106588316e-10,0.000000000000000000e+00 +6.772792670723043251e+00,6.748000000000000398e+01,0.000000000000000000e+00,7.263390203409304746e+00,0.000000000000000000e+00,-1.000000009963773806e+00,0.000000000000000000e+00,6.344741856392711428e-10,0.000000000000000000e+00 +6.774169438281986366e+00,6.748999999999999488e+01,0.000000000000000000e+00,7.262013435836643716e+00,0.000000000000000000e+00,-1.000000009962900283e+00,0.000000000000000000e+00,-2.683184864789506308e-10,0.000000000000000000e+00 +6.775546466855171701e+00,6.750000000000000000e+01,0.000000000000000000e+00,7.260636407249739577e+00,0.000000000000000000e+00,-1.000000009963269765e+00,0.000000000000000000e+00,4.385143587741622531e-11,0.000000000000000000e+00 +6.776923756591098247e+00,6.751000000000000512e+01,0.000000000000000000e+00,7.259259117500090674e+00,0.000000000000000000e+00,-1.000000009963209369e+00,0.000000000000000000e+00,-2.040639222656873559e-10,0.000000000000000000e+00 +6.778301307638407103e+00,6.751999999999999602e+01,0.000000000000000000e+00,7.257881566439056797e+00,0.000000000000000000e+00,-1.000000009963490477e+00,0.000000000000000000e+00,2.336781495268310208e-11,0.000000000000000000e+00 +6.779679120145880589e+00,6.753000000000000114e+01,0.000000000000000000e+00,7.256503753917855626e+00,0.000000000000000000e+00,-1.000000009963458281e+00,0.000000000000000000e+00,-1.111774581331230910e-10,0.000000000000000000e+00 +6.781057194262441357e+00,6.754000000000000625e+01,0.000000000000000000e+00,7.255125679787564508e+00,0.000000000000000000e+00,-1.000000009963611491e+00,0.000000000000000000e+00,4.269048015412179349e-10,0.000000000000000000e+00 +6.782435530137154167e+00,6.754999999999999716e+01,0.000000000000000000e+00,7.253747343899118682e+00,0.000000000000000000e+00,-1.000000009963023073e+00,0.000000000000000000e+00,-1.338454689920924347e-10,0.000000000000000000e+00 +6.783814127919225001e+00,6.756000000000000227e+01,0.000000000000000000e+00,7.252368746103313057e+00,0.000000000000000000e+00,-1.000000009963207592e+00,0.000000000000000000e+00,-2.906680582163474282e-10,0.000000000000000000e+00 +6.785192987758001948e+00,6.757000000000000739e+01,0.000000000000000000e+00,7.250989886250798655e+00,0.000000000000000000e+00,-1.000000009963608383e+00,0.000000000000000000e+00,5.506347691359211124e-11,0.000000000000000000e+00 +6.786572109802974317e+00,6.757999999999999829e+01,0.000000000000000000e+00,7.249610764192085277e+00,0.000000000000000000e+00,-1.000000009963532444e+00,0.000000000000000000e+00,6.841382071479964228e-11,0.000000000000000000e+00 +6.787951494203774416e+00,6.759000000000000341e+01,0.000000000000000000e+00,7.248231379777541505e+00,0.000000000000000000e+00,-1.000000009963438075e+00,0.000000000000000000e+00,3.160921842023232190e-10,0.000000000000000000e+00 +6.789331141110176659e+00,6.759999999999999432e+01,0.000000000000000000e+00,7.246851732857392925e+00,0.000000000000000000e+00,-1.000000009963001979e+00,0.000000000000000000e+00,-5.010813163534670973e-10,0.000000000000000000e+00 +6.790711050672098459e+00,6.760999999999999943e+01,0.000000000000000000e+00,7.245471823281723012e+00,0.000000000000000000e+00,-1.000000009963693426e+00,0.000000000000000000e+00,4.858630144058029933e-11,0.000000000000000000e+00 +6.792091223039599335e+00,6.762000000000000455e+01,0.000000000000000000e+00,7.244091650900470469e+00,0.000000000000000000e+00,-1.000000009963626368e+00,0.000000000000000000e+00,1.997771244081821489e-10,0.000000000000000000e+00 +6.793471658362881804e+00,6.762999999999999545e+01,0.000000000000000000e+00,7.242711215563433669e+00,0.000000000000000000e+00,-1.000000009963350589e+00,0.000000000000000000e+00,5.258830187958013688e-11,0.000000000000000000e+00 +6.794852356792292269e+00,6.764000000000000057e+01,0.000000000000000000e+00,7.241330517120267096e+00,0.000000000000000000e+00,-1.000000009963277980e+00,0.000000000000000000e+00,-2.913511853335642912e-10,0.000000000000000000e+00 +6.796233318478319241e+00,6.765000000000000568e+01,0.000000000000000000e+00,7.239949555420481353e+00,0.000000000000000000e+00,-1.000000009963680325e+00,0.000000000000000000e+00,1.985375797307463443e-10,0.000000000000000000e+00 +6.797614543571595114e+00,6.765999999999999659e+01,0.000000000000000000e+00,7.238568330313443155e+00,0.000000000000000000e+00,-1.000000009963406100e+00,0.000000000000000000e+00,2.266271913629481741e-10,0.000000000000000000e+00 +6.798996032222897057e+00,6.767000000000000171e+01,0.000000000000000000e+00,7.237186841648377111e+00,0.000000000000000000e+00,-1.000000009963093017e+00,0.000000000000000000e+00,-5.714414809987828700e-10,0.000000000000000000e+00 +6.800377784583144347e+00,6.768000000000000682e+01,0.000000000000000000e+00,7.235805089274363056e+00,0.000000000000000000e+00,-1.000000009963882608e+00,0.000000000000000000e+00,2.318426949049025435e-10,0.000000000000000000e+00 +6.801759800803401923e+00,6.768999999999999773e+01,0.000000000000000000e+00,7.234423073040335161e+00,0.000000000000000000e+00,-1.000000009963562198e+00,0.000000000000000000e+00,4.105867951118801769e-10,0.000000000000000000e+00 +6.803142081034878608e+00,6.770000000000000284e+01,0.000000000000000000e+00,7.233040792795086382e+00,0.000000000000000000e+00,-1.000000009962994652e+00,0.000000000000000000e+00,-3.974992770975979936e-10,0.000000000000000000e+00 +6.804524625428927109e+00,6.771000000000000796e+01,0.000000000000000000e+00,7.231658248387264010e+00,0.000000000000000000e+00,-1.000000009963544212e+00,0.000000000000000000e+00,-2.320309759644611352e-10,0.000000000000000000e+00 +6.805907434137044909e+00,6.771999999999999886e+01,0.000000000000000000e+00,7.230275439665368786e+00,0.000000000000000000e+00,-1.000000009963865066e+00,0.000000000000000000e+00,7.834565029078310697e-11,0.000000000000000000e+00 +6.807290507310874261e+00,6.773000000000000398e+01,0.000000000000000000e+00,7.228892366477758458e+00,0.000000000000000000e+00,-1.000000009963756709e+00,0.000000000000000000e+00,1.711075561831096915e-10,0.000000000000000000e+00 +6.808673845102203082e+00,6.773999999999999488e+01,0.000000000000000000e+00,7.227509028672645996e+00,0.000000000000000000e+00,-1.000000009963520009e+00,0.000000000000000000e+00,1.479652694688344778e-10,0.000000000000000000e+00 +6.810057447662964947e+00,6.775000000000000000e+01,0.000000000000000000e+00,7.226125426098098714e+00,0.000000000000000000e+00,-1.000000009963315284e+00,0.000000000000000000e+00,-3.526739719497933170e-10,0.000000000000000000e+00 +6.811441315145237319e+00,6.776000000000000512e+01,0.000000000000000000e+00,7.224741558602038261e+00,0.000000000000000000e+00,-1.000000009963803338e+00,0.000000000000000000e+00,1.625069678571092512e-10,0.000000000000000000e+00 +6.812825447701244208e+00,6.776999999999999602e+01,0.000000000000000000e+00,7.223357426032239736e+00,0.000000000000000000e+00,-1.000000009963578407e+00,0.000000000000000000e+00,-5.934457919813793152e-11,0.000000000000000000e+00 +6.814209845483356176e+00,6.778000000000000114e+01,0.000000000000000000e+00,7.221973028236334358e+00,0.000000000000000000e+00,-1.000000009963660563e+00,0.000000000000000000e+00,1.122520103483778267e-11,0.000000000000000000e+00 +6.815594508644088556e+00,6.779000000000000625e+01,0.000000000000000000e+00,7.220588365061805902e+00,0.000000000000000000e+00,-1.000000009963645020e+00,0.000000000000000000e+00,1.314700006494069743e-11,0.000000000000000000e+00 +6.816979437336103231e+00,6.779999999999999716e+01,0.000000000000000000e+00,7.219203436355992487e+00,0.000000000000000000e+00,-1.000000009963626812e+00,0.000000000000000000e+00,4.937194338689211847e-11,0.000000000000000000e+00 +6.818364631712208634e+00,6.781000000000000227e+01,0.000000000000000000e+00,7.217818241966085679e+00,0.000000000000000000e+00,-1.000000009963558423e+00,0.000000000000000000e+00,2.218105798341932293e-10,0.000000000000000000e+00 +6.819750091925359747e+00,6.782000000000000739e+01,0.000000000000000000e+00,7.216432781739130498e+00,0.000000000000000000e+00,-1.000000009963251113e+00,0.000000000000000000e+00,-2.909903858236586883e-10,0.000000000000000000e+00 +6.821135818128658102e+00,6.782999999999999829e+01,0.000000000000000000e+00,7.215047055522025410e+00,0.000000000000000000e+00,-1.000000009963654346e+00,0.000000000000000000e+00,6.408249091835593834e-13,0.000000000000000000e+00 +6.822521810475353554e+00,6.784000000000000341e+01,0.000000000000000000e+00,7.213661063161520559e+00,0.000000000000000000e+00,-1.000000009963653458e+00,0.000000000000000000e+00,-1.867645771291022744e-10,0.000000000000000000e+00 +6.823908069118841624e+00,6.784999999999999432e+01,0.000000000000000000e+00,7.212274804504220427e+00,0.000000000000000000e+00,-1.000000009963912362e+00,0.000000000000000000e+00,1.739171126600510112e-10,0.000000000000000000e+00 +6.825294594212665267e+00,6.785999999999999943e+01,0.000000000000000000e+00,7.210888279396581169e+00,0.000000000000000000e+00,-1.000000009963671221e+00,0.000000000000000000e+00,-1.999822410107283630e-10,0.000000000000000000e+00 +6.826681385910516653e+00,6.787000000000000455e+01,0.000000000000000000e+00,7.209501487684912391e+00,0.000000000000000000e+00,-1.000000009963948555e+00,0.000000000000000000e+00,1.812140589598625447e-10,0.000000000000000000e+00 +6.828068444366233614e+00,6.787999999999999545e+01,0.000000000000000000e+00,7.208114429215374486e+00,0.000000000000000000e+00,-1.000000009963697201e+00,0.000000000000000000e+00,3.505145196310103918e-11,0.000000000000000000e+00 +6.829455769733804082e+00,6.789000000000000057e+01,0.000000000000000000e+00,7.206727103833981296e+00,0.000000000000000000e+00,-1.000000009963648573e+00,0.000000000000000000e+00,-7.200966926579991229e-11,0.000000000000000000e+00 +6.830843362167362542e+00,6.790000000000000568e+01,0.000000000000000000e+00,7.205339511386597451e+00,0.000000000000000000e+00,-1.000000009963748493e+00,0.000000000000000000e+00,-3.647787424556945784e-11,0.000000000000000000e+00 +6.832231221821192690e+00,6.790999999999999659e+01,0.000000000000000000e+00,7.203951651718939253e+00,0.000000000000000000e+00,-1.000000009963799119e+00,0.000000000000000000e+00,2.452184651354801321e-10,0.000000000000000000e+00 +6.833619348849726549e+00,6.792000000000000171e+01,0.000000000000000000e+00,7.202563524676574680e+00,0.000000000000000000e+00,-1.000000009963458725e+00,0.000000000000000000e+00,-4.414041427504532345e-11,0.000000000000000000e+00 +6.835007743407544467e+00,6.793000000000000682e+01,0.000000000000000000e+00,7.201175130104923383e+00,0.000000000000000000e+00,-1.000000009963520009e+00,0.000000000000000000e+00,-3.389842023931430068e-10,0.000000000000000000e+00 +6.836396405649376895e+00,6.793999999999999773e+01,0.000000000000000000e+00,7.199786467849254912e+00,0.000000000000000000e+00,-1.000000009963990744e+00,0.000000000000000000e+00,-7.465806374197474458e-11,0.000000000000000000e+00 +6.837785335730102609e+00,6.795000000000000284e+01,0.000000000000000000e+00,7.198397537754689601e+00,0.000000000000000000e+00,-1.000000009964094438e+00,0.000000000000000000e+00,3.923986903228762681e-10,0.000000000000000000e+00 +6.839174533804750489e+00,6.796000000000000796e+01,0.000000000000000000e+00,7.197008339666199461e+00,0.000000000000000000e+00,-1.000000009963549319e+00,0.000000000000000000e+00,-2.130209812273308124e-10,0.000000000000000000e+00 +6.840564000028498626e+00,6.796999999999999886e+01,0.000000000000000000e+00,7.195618873428607287e+00,0.000000000000000000e+00,-1.000000009963845304e+00,0.000000000000000000e+00,5.432344389801282827e-11,0.000000000000000000e+00 +6.841953734556675215e+00,6.798000000000000398e+01,0.000000000000000000e+00,7.194229138886583996e+00,0.000000000000000000e+00,-1.000000009963769809e+00,0.000000000000000000e+00,-8.067070822765309323e-11,0.000000000000000000e+00 +6.843343737544757666e+00,6.798999999999999488e+01,0.000000000000000000e+00,7.192839135884652180e+00,0.000000000000000000e+00,-1.000000009963881942e+00,0.000000000000000000e+00,-5.238590087431141017e-11,0.000000000000000000e+00 +6.844734009148373488e+00,6.800000000000000000e+01,0.000000000000000000e+00,7.191448864267183438e+00,0.000000000000000000e+00,-1.000000009963954772e+00,0.000000000000000000e+00,2.438347838248586662e-10,0.000000000000000000e+00 +6.846124549523302072e+00,6.801000000000000512e+01,0.000000000000000000e+00,7.190058323878399271e+00,0.000000000000000000e+00,-1.000000009963615710e+00,0.000000000000000000e+00,-5.268495077714589072e-12,0.000000000000000000e+00 +6.847515358825472909e+00,6.801999999999999602e+01,0.000000000000000000e+00,7.188667514562371075e+00,0.000000000000000000e+00,-1.000000009963623038e+00,0.000000000000000000e+00,-2.340036292813526778e-10,0.000000000000000000e+00 +6.848906437210965592e+00,6.803000000000000114e+01,0.000000000000000000e+00,7.187276436163018367e+00,0.000000000000000000e+00,-1.000000009963948555e+00,0.000000000000000000e+00,1.216072719047160921e-10,0.000000000000000000e+00 +6.850297784836010706e+00,6.804000000000000625e+01,0.000000000000000000e+00,7.185885088524109676e+00,0.000000000000000000e+00,-1.000000009963779357e+00,0.000000000000000000e+00,-2.088623403313074422e-10,0.000000000000000000e+00 +6.851689401856991601e+00,6.804999999999999716e+01,0.000000000000000000e+00,7.184493471489263428e+00,0.000000000000000000e+00,-1.000000009964070014e+00,0.000000000000000000e+00,2.566802325271450055e-10,0.000000000000000000e+00 +6.853081288430440843e+00,6.806000000000000227e+01,0.000000000000000000e+00,7.183101584901945280e+00,0.000000000000000000e+00,-1.000000009963712744e+00,0.000000000000000000e+00,-2.094194236018921005e-10,0.000000000000000000e+00 +6.854473444713044650e+00,6.807000000000000739e+01,0.000000000000000000e+00,7.181709428605470791e+00,0.000000000000000000e+00,-1.000000009964004288e+00,0.000000000000000000e+00,-1.258186608048487395e-10,0.000000000000000000e+00 +6.855865870861639344e+00,6.807999999999999829e+01,0.000000000000000000e+00,7.180317002443001861e+00,0.000000000000000000e+00,-1.000000009964179482e+00,0.000000000000000000e+00,1.556086236394886846e-10,0.000000000000000000e+00 +6.857258567033214902e+00,6.809000000000000341e+01,0.000000000000000000e+00,7.178924306257549404e+00,0.000000000000000000e+00,-1.000000009963962766e+00,0.000000000000000000e+00,2.832611588003889263e-10,0.000000000000000000e+00 +6.858651533384912291e+00,6.809999999999999432e+01,0.000000000000000000e+00,7.177531339891972451e+00,0.000000000000000000e+00,-1.000000009963568193e+00,0.000000000000000000e+00,-5.507938174590755643e-10,0.000000000000000000e+00 +6.860044770074026133e+00,6.810999999999999943e+01,0.000000000000000000e+00,7.176138103188977269e+00,0.000000000000000000e+00,-1.000000009964335579e+00,0.000000000000000000e+00,5.054336963031910020e-10,0.000000000000000000e+00 +6.861438277258002039e+00,6.812000000000000455e+01,0.000000000000000000e+00,7.174744595991115581e+00,0.000000000000000000e+00,-1.000000009963631253e+00,0.000000000000000000e+00,-5.577489765721231832e-10,0.000000000000000000e+00 +6.862832055094441053e+00,6.812999999999999545e+01,0.000000000000000000e+00,7.173350818140789897e+00,0.000000000000000000e+00,-1.000000009964408632e+00,0.000000000000000000e+00,4.824602856811844075e-10,0.000000000000000000e+00 +6.864226103741094320e+00,6.814000000000000057e+01,0.000000000000000000e+00,7.171956769480245519e+00,0.000000000000000000e+00,-1.000000009963736058e+00,0.000000000000000000e+00,-3.812431371960235698e-10,0.000000000000000000e+00 +6.865620423355868418e+00,6.815000000000000568e+01,0.000000000000000000e+00,7.170562449851578535e+00,0.000000000000000000e+00,-1.000000009964267633e+00,0.000000000000000000e+00,6.152201705017846172e-10,0.000000000000000000e+00 +6.867015014096822689e+00,6.815999999999999659e+01,0.000000000000000000e+00,7.169167859096727824e+00,0.000000000000000000e+00,-1.000000009963409653e+00,0.000000000000000000e+00,-5.321638275148723876e-10,0.000000000000000000e+00 +6.868409876122171021e+00,6.817000000000000171e+01,0.000000000000000000e+00,7.167772997057482165e+00,0.000000000000000000e+00,-1.000000009964151948e+00,0.000000000000000000e+00,-6.191189107730112242e-11,0.000000000000000000e+00 +6.869805009590280065e+00,6.818000000000000682e+01,0.000000000000000000e+00,7.166377863575472240e+00,0.000000000000000000e+00,-1.000000009964238323e+00,0.000000000000000000e+00,3.071123195019934127e-10,0.000000000000000000e+00 +6.871200414659670130e+00,6.818999999999999773e+01,0.000000000000000000e+00,7.164982458492177742e+00,0.000000000000000000e+00,-1.000000009963809777e+00,0.000000000000000000e+00,-2.290961806978572126e-10,0.000000000000000000e+00 +6.872596091489017844e+00,6.820000000000000284e+01,0.000000000000000000e+00,7.163586781648923818e+00,0.000000000000000000e+00,-1.000000009964129521e+00,0.000000000000000000e+00,-1.929441221491000513e-10,0.000000000000000000e+00 +6.873992040237152601e+00,6.821000000000000796e+01,0.000000000000000000e+00,7.162190832886879299e+00,0.000000000000000000e+00,-1.000000009964398862e+00,0.000000000000000000e+00,5.217859060980123373e-10,0.000000000000000000e+00 +6.875388261063060114e+00,6.821999999999999886e+01,0.000000000000000000e+00,7.160794612047059360e+00,0.000000000000000000e+00,-1.000000009963670333e+00,0.000000000000000000e+00,-2.531305170445400995e-10,0.000000000000000000e+00 +6.876784754125879751e+00,6.823000000000000398e+01,0.000000000000000000e+00,7.159398118970325520e+00,0.000000000000000000e+00,-1.000000009964023828e+00,0.000000000000000000e+00,-1.316276341813400201e-10,0.000000000000000000e+00 +6.878181519584906312e+00,6.823999999999999488e+01,0.000000000000000000e+00,7.158001353497381203e+00,0.000000000000000000e+00,-1.000000009964207681e+00,0.000000000000000000e+00,8.407902631901974402e-11,0.000000000000000000e+00 +6.879578557599590916e+00,6.825000000000000000e+01,0.000000000000000000e+00,7.156604315468776178e+00,0.000000000000000000e+00,-1.000000009964090220e+00,0.000000000000000000e+00,4.767256133499115246e-11,0.000000000000000000e+00 +6.880975868329539225e+00,6.826000000000000512e+01,0.000000000000000000e+00,7.155207004724904785e+00,0.000000000000000000e+00,-1.000000009964023606e+00,0.000000000000000000e+00,-1.310739467829790365e-10,0.000000000000000000e+00 +6.882373451934513220e+00,6.826999999999999602e+01,0.000000000000000000e+00,7.153809421106005040e+00,0.000000000000000000e+00,-1.000000009964206793e+00,0.000000000000000000e+00,1.115102280206151766e-10,0.000000000000000000e+00 +6.883771308574431202e+00,6.828000000000000114e+01,0.000000000000000000e+00,7.152411564452158643e+00,0.000000000000000000e+00,-1.000000009964050918e+00,0.000000000000000000e+00,-2.429876232137707320e-11,0.000000000000000000e+00 +6.885169438409366904e+00,6.829000000000000625e+01,0.000000000000000000e+00,7.151013434603291863e+00,0.000000000000000000e+00,-1.000000009964084891e+00,0.000000000000000000e+00,2.540550324640126330e-11,0.000000000000000000e+00 +6.886567841599551265e+00,6.829999999999999716e+01,0.000000000000000000e+00,7.149615031399173759e+00,0.000000000000000000e+00,-1.000000009964049363e+00,0.000000000000000000e+00,-8.350425920768878496e-11,0.000000000000000000e+00 +6.887966518305371544e+00,6.831000000000000227e+01,0.000000000000000000e+00,7.148216354679417073e+00,0.000000000000000000e+00,-1.000000009964166159e+00,0.000000000000000000e+00,-2.412578772118026830e-10,0.000000000000000000e+00 +6.889365468687372207e+00,6.832000000000000739e+01,0.000000000000000000e+00,7.146817404283477337e+00,0.000000000000000000e+00,-1.000000009964503667e+00,0.000000000000000000e+00,1.158445940313987679e-10,0.000000000000000000e+00 +6.890764692906254041e+00,6.832999999999999829e+01,0.000000000000000000e+00,7.145418180050652879e+00,0.000000000000000000e+00,-1.000000009964341574e+00,0.000000000000000000e+00,1.903921868176180005e-10,0.000000000000000000e+00 +6.892164191122875927e+00,6.834000000000000341e+01,0.000000000000000000e+00,7.144018681820085703e+00,0.000000000000000000e+00,-1.000000009964075121e+00,0.000000000000000000e+00,9.295664121881253747e-11,0.000000000000000000e+00 +6.893563963498254843e+00,6.835000000000000853e+01,0.000000000000000000e+00,7.142618909430759722e+00,0.000000000000000000e+00,-1.000000009963945002e+00,0.000000000000000000e+00,-6.550097374702144043e-11,0.000000000000000000e+00 +6.894964010193564086e+00,6.835999999999999943e+01,0.000000000000000000e+00,7.141218862721500749e+00,0.000000000000000000e+00,-1.000000009964036707e+00,0.000000000000000000e+00,-1.748993040524963169e-10,0.000000000000000000e+00 +6.896364331370135048e+00,6.837000000000000455e+01,0.000000000000000000e+00,7.139818541530976503e+00,0.000000000000000000e+00,-1.000000009964281622e+00,0.000000000000000000e+00,-1.238164744274004603e-10,0.000000000000000000e+00 +6.897764927189458994e+00,6.837999999999999545e+01,0.000000000000000000e+00,7.138417945697696609e+00,0.000000000000000000e+00,-1.000000009964455039e+00,0.000000000000000000e+00,1.978138896292664089e-10,0.000000000000000000e+00 +6.899165797813184398e+00,6.839000000000000057e+01,0.000000000000000000e+00,7.137017075060012594e+00,0.000000000000000000e+00,-1.000000009964177927e+00,0.000000000000000000e+00,-3.961840341937257523e-12,0.000000000000000000e+00 +6.900566943403117826e+00,6.840000000000000568e+01,0.000000000000000000e+00,7.135615929456117890e+00,0.000000000000000000e+00,-1.000000009964183478e+00,0.000000000000000000e+00,-1.647802020750957459e-10,0.000000000000000000e+00 +6.901968364121225719e+00,6.840999999999999659e+01,0.000000000000000000e+00,7.134214508724046055e+00,0.000000000000000000e+00,-1.000000009964414405e+00,0.000000000000000000e+00,2.783288020464380520e-10,0.000000000000000000e+00 +6.903370060129632613e+00,6.842000000000000171e+01,0.000000000000000000e+00,7.132812812701671668e+00,0.000000000000000000e+00,-1.000000009964024272e+00,0.000000000000000000e+00,-3.710849498830274598e-10,0.000000000000000000e+00 +6.904772031590623804e+00,6.843000000000000682e+01,0.000000000000000000e+00,7.131410841226711206e+00,0.000000000000000000e+00,-1.000000009964544523e+00,0.000000000000000000e+00,2.582674314863978654e-10,0.000000000000000000e+00 +6.906174278666642685e+00,6.843999999999999773e+01,0.000000000000000000e+00,7.130008594136719502e+00,0.000000000000000000e+00,-1.000000009964182368e+00,0.000000000000000000e+00,1.915647729090570536e-11,0.000000000000000000e+00 +6.907576801520293408e+00,6.845000000000000284e+01,0.000000000000000000e+00,7.128606071269094180e+00,0.000000000000000000e+00,-1.000000009964155501e+00,0.000000000000000000e+00,-7.281195186301177642e-11,0.000000000000000000e+00 +6.908979600314339109e+00,6.846000000000000796e+01,0.000000000000000000e+00,7.127203272461071215e+00,0.000000000000000000e+00,-1.000000009964257641e+00,0.000000000000000000e+00,-3.567083556560935690e-10,0.000000000000000000e+00 +6.910382675211702797e+00,6.846999999999999886e+01,0.000000000000000000e+00,7.125800197549726711e+00,0.000000000000000000e+00,-1.000000009964758130e+00,0.000000000000000000e+00,6.328981958558556348e-10,0.000000000000000000e+00 +6.911786026375469127e+00,6.848000000000000398e+01,0.000000000000000000e+00,7.124396846371976011e+00,0.000000000000000000e+00,-1.000000009963869951e+00,0.000000000000000000e+00,-6.000275218529283718e-10,0.000000000000000000e+00 +6.913189653968883519e+00,6.848999999999999488e+01,0.000000000000000000e+00,7.122993218764576362e+00,0.000000000000000000e+00,-1.000000009964712167e+00,0.000000000000000000e+00,5.668534019077019451e-10,0.000000000000000000e+00 +6.914593558155350372e+00,6.850000000000000000e+01,0.000000000000000000e+00,7.121589314564119810e+00,0.000000000000000000e+00,-1.000000009963916359e+00,0.000000000000000000e+00,-2.615487543497841615e-10,0.000000000000000000e+00 +6.915997739098436625e+00,6.851000000000000512e+01,0.000000000000000000e+00,7.120185133607042083e+00,0.000000000000000000e+00,-1.000000009964283620e+00,0.000000000000000000e+00,-2.682954785389302257e-10,0.000000000000000000e+00 +6.917402196961870864e+00,6.851999999999999602e+01,0.000000000000000000e+00,7.118780675729613705e+00,0.000000000000000000e+00,-1.000000009964660430e+00,0.000000000000000000e+00,2.084925945508544732e-10,0.000000000000000000e+00 +6.918806931909541547e+00,6.853000000000000114e+01,0.000000000000000000e+00,7.117375940767945330e+00,0.000000000000000000e+00,-1.000000009964367553e+00,0.000000000000000000e+00,-6.779808444855481084e-11,0.000000000000000000e+00 +6.920211944105499668e+00,6.854000000000000625e+01,0.000000000000000000e+00,7.115970928557986852e+00,0.000000000000000000e+00,-1.000000009964462810e+00,0.000000000000000000e+00,-8.437536171634818258e-11,0.000000000000000000e+00 +6.921617233713958761e+00,6.854999999999999716e+01,0.000000000000000000e+00,7.114565638935524738e+00,0.000000000000000000e+00,-1.000000009964581382e+00,0.000000000000000000e+00,2.729809583730388310e-10,0.000000000000000000e+00 +6.923022800899294005e+00,6.856000000000000227e+01,0.000000000000000000e+00,7.113160071736183809e+00,0.000000000000000000e+00,-1.000000009964197689e+00,0.000000000000000000e+00,-2.312298429401454232e-10,0.000000000000000000e+00 +6.924428645826042228e+00,6.857000000000000739e+01,0.000000000000000000e+00,7.111754226795427236e+00,0.000000000000000000e+00,-1.000000009964522762e+00,0.000000000000000000e+00,3.145620301964522349e-10,0.000000000000000000e+00 +6.925834768658904572e+00,6.857999999999999829e+01,0.000000000000000000e+00,7.110348103948553877e+00,0.000000000000000000e+00,-1.000000009964080450e+00,0.000000000000000000e+00,-2.215076653175845018e-10,0.000000000000000000e+00 +6.927241169562742940e+00,6.859000000000000341e+01,0.000000000000000000e+00,7.108941703030701831e+00,0.000000000000000000e+00,-1.000000009964391978e+00,0.000000000000000000e+00,-3.775777147307799130e-10,0.000000000000000000e+00 +6.928647848702584433e+00,6.860000000000000853e+01,0.000000000000000000e+00,7.107535023876843994e+00,0.000000000000000000e+00,-1.000000009964923109e+00,0.000000000000000000e+00,4.082777029072868924e-10,0.000000000000000000e+00 +6.930054806243617804e+00,6.860999999999999943e+01,0.000000000000000000e+00,7.106128066321790726e+00,0.000000000000000000e+00,-1.000000009964348680e+00,0.000000000000000000e+00,7.573811515358874007e-12,0.000000000000000000e+00 +6.931462042351195230e+00,6.862000000000000455e+01,0.000000000000000000e+00,7.104720830200190740e+00,0.000000000000000000e+00,-1.000000009964338021e+00,0.000000000000000000e+00,-1.189483957102709093e-10,0.000000000000000000e+00 +6.932869557190834087e+00,6.862999999999999545e+01,0.000000000000000000e+00,7.103313315346526657e+00,0.000000000000000000e+00,-1.000000009964505443e+00,0.000000000000000000e+00,1.433722430477233848e-10,0.000000000000000000e+00 +6.934277350928215178e+00,6.864000000000000057e+01,0.000000000000000000e+00,7.101905521595117676e+00,0.000000000000000000e+00,-1.000000009964303604e+00,0.000000000000000000e+00,-4.352353863890662105e-10,0.000000000000000000e+00 +6.935685423729182730e+00,6.865000000000000568e+01,0.000000000000000000e+00,7.100497448780119569e+00,0.000000000000000000e+00,-1.000000009964916448e+00,0.000000000000000000e+00,5.004214576593412945e-10,0.000000000000000000e+00 +6.937093775759746173e+00,6.865999999999999659e+01,0.000000000000000000e+00,7.099089096735522020e+00,0.000000000000000000e+00,-1.000000009964211678e+00,0.000000000000000000e+00,-6.935783508773839244e-11,0.000000000000000000e+00 +6.938502407186079246e+00,6.867000000000000171e+01,0.000000000000000000e+00,7.097680465295153063e+00,0.000000000000000000e+00,-1.000000009964309378e+00,0.000000000000000000e+00,-2.376610495439266363e-10,0.000000000000000000e+00 +6.939911318174520893e+00,6.868000000000000682e+01,0.000000000000000000e+00,7.096271554292672867e+00,0.000000000000000000e+00,-1.000000009964644221e+00,0.000000000000000000e+00,1.106133547226985413e-10,0.000000000000000000e+00 +6.941320508891574370e+00,6.868999999999999773e+01,0.000000000000000000e+00,7.094862363561577290e+00,0.000000000000000000e+00,-1.000000009964488346e+00,0.000000000000000000e+00,-2.507998449539090668e-10,0.000000000000000000e+00 +6.942729979503909021e+00,6.870000000000000284e+01,0.000000000000000000e+00,7.093452892935197873e+00,0.000000000000000000e+00,-1.000000009964841841e+00,0.000000000000000000e+00,1.357704258733192412e-10,0.000000000000000000e+00 +6.944139730178359393e+00,6.871000000000000796e+01,0.000000000000000000e+00,7.092043142246699183e+00,0.000000000000000000e+00,-1.000000009964650438e+00,0.000000000000000000e+00,4.503784764425935064e-11,0.000000000000000000e+00 +6.945549761081927009e+00,6.871999999999999886e+01,0.000000000000000000e+00,7.090633111329081473e+00,0.000000000000000000e+00,-1.000000009964586933e+00,0.000000000000000000e+00,4.077791384192135637e-11,0.000000000000000000e+00 +6.946960072381777707e+00,6.873000000000000398e+01,0.000000000000000000e+00,7.089222800015178017e+00,0.000000000000000000e+00,-1.000000009964529424e+00,0.000000000000000000e+00,2.389519739947729956e-10,0.000000000000000000e+00 +6.948370664245243411e+00,6.873999999999999488e+01,0.000000000000000000e+00,7.087812208137656000e+00,0.000000000000000000e+00,-1.000000009964192360e+00,0.000000000000000000e+00,-5.827820139077951745e-10,0.000000000000000000e+00 +6.949781536839824803e+00,6.875000000000000000e+01,0.000000000000000000e+00,7.086401335529016521e+00,0.000000000000000000e+00,-1.000000009965014591e+00,0.000000000000000000e+00,3.700865378855998518e-10,0.000000000000000000e+00 +6.951192690333186874e+00,6.876000000000000512e+01,0.000000000000000000e+00,7.084990182021591920e+00,0.000000000000000000e+00,-1.000000009964492342e+00,0.000000000000000000e+00,9.061538952180729589e-11,0.000000000000000000e+00 +6.952604124893163373e+00,6.876999999999999602e+01,0.000000000000000000e+00,7.083578747447551116e+00,0.000000000000000000e+00,-1.000000009964364445e+00,0.000000000000000000e+00,-4.102046119079541744e-10,0.000000000000000000e+00 +6.954015840687754135e+00,6.878000000000000114e+01,0.000000000000000000e+00,7.082167031638893384e+00,0.000000000000000000e+00,-1.000000009964943537e+00,0.000000000000000000e+00,3.203298569387153083e-10,0.000000000000000000e+00 +6.955427837885126863e+00,6.879000000000000625e+01,0.000000000000000000e+00,7.080755034427450134e+00,0.000000000000000000e+00,-1.000000009964491232e+00,0.000000000000000000e+00,-2.727842393020291145e-10,0.000000000000000000e+00 +6.956840116653617123e+00,6.879999999999999716e+01,0.000000000000000000e+00,7.079342755644887575e+00,0.000000000000000000e+00,-1.000000009964876480e+00,0.000000000000000000e+00,1.545207057595848473e-10,0.000000000000000000e+00 +6.958252677161727462e+00,6.881000000000000227e+01,0.000000000000000000e+00,7.077930195122701384e+00,0.000000000000000000e+00,-1.000000009964658210e+00,0.000000000000000000e+00,-6.050722423372434738e-11,0.000000000000000000e+00 +6.959665519578129178e+00,6.882000000000000739e+01,0.000000000000000000e+00,7.076517352692221152e+00,0.000000000000000000e+00,-1.000000009964743697e+00,0.000000000000000000e+00,8.972137273993171327e-11,0.000000000000000000e+00 +6.961078644071662325e+00,6.882999999999999829e+01,0.000000000000000000e+00,7.075104228184606825e+00,0.000000000000000000e+00,-1.000000009964616909e+00,0.000000000000000000e+00,2.788504983592438568e-10,0.000000000000000000e+00 +6.962492050811334821e+00,6.884000000000000341e+01,0.000000000000000000e+00,7.073690821430850484e+00,0.000000000000000000e+00,-1.000000009964222780e+00,0.000000000000000000e+00,-7.086885075734627167e-10,0.000000000000000000e+00 +6.963905739966323338e+00,6.885000000000000853e+01,0.000000000000000000e+00,7.072277132261775456e+00,0.000000000000000000e+00,-1.000000009965224645e+00,0.000000000000000000e+00,3.566289789561969600e-10,0.000000000000000000e+00 +6.965319711705974193e+00,6.885999999999999943e+01,0.000000000000000000e+00,7.070863160508033651e+00,0.000000000000000000e+00,-1.000000009964720382e+00,0.000000000000000000e+00,3.862315661706753226e-11,0.000000000000000000e+00 +6.966733966199803341e+00,6.887000000000000455e+01,0.000000000000000000e+00,7.069448906000111776e+00,0.000000000000000000e+00,-1.000000009964665759e+00,0.000000000000000000e+00,2.324774557257695029e-10,0.000000000000000000e+00 +6.968148503617495493e+00,6.887999999999999545e+01,0.000000000000000000e+00,7.068034368568324233e+00,0.000000000000000000e+00,-1.000000009964336911e+00,0.000000000000000000e+00,-2.737066559795477649e-10,0.000000000000000000e+00 +6.969563324128905002e+00,6.889000000000000057e+01,0.000000000000000000e+00,7.066619548042816668e+00,0.000000000000000000e+00,-1.000000009964724157e+00,0.000000000000000000e+00,-3.012681111745287234e-11,0.000000000000000000e+00 +6.970978427904057639e+00,6.890000000000000568e+01,0.000000000000000000e+00,7.065204444253563310e+00,0.000000000000000000e+00,-1.000000009964766789e+00,0.000000000000000000e+00,-2.484964198789550900e-10,0.000000000000000000e+00 +6.972393815113147042e+00,6.890999999999999659e+01,0.000000000000000000e+00,7.063789057030369634e+00,0.000000000000000000e+00,-1.000000009965118508e+00,0.000000000000000000e+00,5.205772675217223346e-10,0.000000000000000000e+00 +6.973809485926540042e+00,6.892000000000000171e+01,0.000000000000000000e+00,7.062373386202869696e+00,0.000000000000000000e+00,-1.000000009964381542e+00,0.000000000000000000e+00,-2.620398548890400613e-10,0.000000000000000000e+00 +6.975225440514772224e+00,6.893000000000000682e+01,0.000000000000000000e+00,7.060957431600528800e+00,0.000000000000000000e+00,-1.000000009964752579e+00,0.000000000000000000e+00,-2.613601787988102325e-10,0.000000000000000000e+00 +6.976641679048550593e+00,6.893999999999999773e+01,0.000000000000000000e+00,7.059541193052638164e+00,0.000000000000000000e+00,-1.000000009965122727e+00,0.000000000000000000e+00,1.992334487692626861e-10,0.000000000000000000e+00 +6.978058201698753571e+00,6.895000000000000284e+01,0.000000000000000000e+00,7.058124670388319366e+00,0.000000000000000000e+00,-1.000000009964840508e+00,0.000000000000000000e+00,3.541913818922460024e-10,0.000000000000000000e+00 +6.979475008636430999e+00,6.896000000000000796e+01,0.000000000000000000e+00,7.056707863436523454e+00,0.000000000000000000e+00,-1.000000009964338687e+00,0.000000000000000000e+00,-5.603248380758654367e-10,0.000000000000000000e+00 +6.980892100032805025e+00,6.896999999999999886e+01,0.000000000000000000e+00,7.055290772026029167e+00,0.000000000000000000e+00,-1.000000009965132719e+00,0.000000000000000000e+00,2.295053254334907211e-10,0.000000000000000000e+00 +6.982309476059268327e+00,6.898000000000000398e+01,0.000000000000000000e+00,7.053873395985441164e+00,0.000000000000000000e+00,-1.000000009964807424e+00,0.000000000000000000e+00,1.912421202842789829e-10,0.000000000000000000e+00 +6.983727136887387665e+00,6.898999999999999488e+01,0.000000000000000000e+00,7.052455735143195348e+00,0.000000000000000000e+00,-1.000000009964536307e+00,0.000000000000000000e+00,-5.538799626770059418e-10,0.000000000000000000e+00 +6.985145082688900331e+00,6.900000000000000000e+01,0.000000000000000000e+00,7.051037789327553540e+00,0.000000000000000000e+00,-1.000000009965321679e+00,0.000000000000000000e+00,3.239319298602151641e-10,0.000000000000000000e+00 +6.986563313635717698e+00,6.901000000000000512e+01,0.000000000000000000e+00,7.049619558366603478e+00,0.000000000000000000e+00,-1.000000009964862269e+00,0.000000000000000000e+00,2.950647030602004415e-10,0.000000000000000000e+00 +6.987981829899922559e+00,6.901999999999999602e+01,0.000000000000000000e+00,7.048201042088263257e+00,0.000000000000000000e+00,-1.000000009964443715e+00,0.000000000000000000e+00,-5.175504657325611179e-10,0.000000000000000000e+00 +6.989400631653772678e+00,6.903000000000000114e+01,0.000000000000000000e+00,7.046782240320276003e+00,0.000000000000000000e+00,-1.000000009965178016e+00,0.000000000000000000e+00,2.129556670799258810e-10,0.000000000000000000e+00 +6.990819719069697236e+00,6.904000000000000625e+01,0.000000000000000000e+00,7.045363152890209868e+00,0.000000000000000000e+00,-1.000000009964875813e+00,0.000000000000000000e+00,-3.848386799478723959e-11,0.000000000000000000e+00 +6.992239092320300387e+00,6.904999999999999716e+01,0.000000000000000000e+00,7.043943779625462476e+00,0.000000000000000000e+00,-1.000000009964930436e+00,0.000000000000000000e+00,1.729861103309140745e-10,0.000000000000000000e+00 +6.993658751578360366e+00,6.906000000000000227e+01,0.000000000000000000e+00,7.042524120353255590e+00,0.000000000000000000e+00,-1.000000009964684855e+00,0.000000000000000000e+00,-3.529393874854246996e-10,0.000000000000000000e+00 +6.995078697016828606e+00,6.907000000000000739e+01,0.000000000000000000e+00,7.041104174900637780e+00,0.000000000000000000e+00,-1.000000009965186010e+00,0.000000000000000000e+00,2.682861658194089805e-10,0.000000000000000000e+00 +6.996498928808831508e+00,6.907999999999999829e+01,0.000000000000000000e+00,7.039683943094481755e+00,0.000000000000000000e+00,-1.000000009964804981e+00,0.000000000000000000e+00,-4.376746751836202310e-11,0.000000000000000000e+00 +6.997919447127670445e+00,6.909000000000000341e+01,0.000000000000000000e+00,7.038263424761487919e+00,0.000000000000000000e+00,-1.000000009964867154e+00,0.000000000000000000e+00,-2.847436943990240340e-10,0.000000000000000000e+00 +6.999340252146819985e+00,6.910000000000000853e+01,0.000000000000000000e+00,7.036842619728179926e+00,0.000000000000000000e+00,-1.000000009965271719e+00,0.000000000000000000e+00,5.464037809141829322e-10,0.000000000000000000e+00 +7.000761344039931444e+00,6.910999999999999943e+01,0.000000000000000000e+00,7.035421527820906462e+00,0.000000000000000000e+00,-1.000000009964495229e+00,0.000000000000000000e+00,-5.053643868380282967e-10,0.000000000000000000e+00 +7.002182722980831997e+00,6.912000000000000455e+01,0.000000000000000000e+00,7.034000148865843016e+00,0.000000000000000000e+00,-1.000000009965213543e+00,0.000000000000000000e+00,2.003868668997127775e-10,0.000000000000000000e+00 +7.003604389143522013e+00,6.912999999999999545e+01,0.000000000000000000e+00,7.032578482688985666e+00,0.000000000000000000e+00,-1.000000009964928660e+00,0.000000000000000000e+00,1.489714989696476120e-10,0.000000000000000000e+00 +7.005026342702179498e+00,6.914000000000000057e+01,0.000000000000000000e+00,7.031156529116158183e+00,0.000000000000000000e+00,-1.000000009964716829e+00,0.000000000000000000e+00,-5.350336490579604867e-10,0.000000000000000000e+00 +7.006448583831158317e+00,6.915000000000000568e+01,0.000000000000000000e+00,7.029734287973006701e+00,0.000000000000000000e+00,-1.000000009965477776e+00,0.000000000000000000e+00,4.664012743230326522e-10,0.000000000000000000e+00 +7.007871112704989081e+00,6.915999999999999659e+01,0.000000000000000000e+00,7.028311759084999721e+00,0.000000000000000000e+00,-1.000000009964814307e+00,0.000000000000000000e+00,-2.342458660461806893e-10,0.000000000000000000e+00 +7.009293929498378262e+00,6.917000000000000171e+01,0.000000000000000000e+00,7.026888942277432548e+00,0.000000000000000000e+00,-1.000000009965147596e+00,0.000000000000000000e+00,1.198297174302768911e-10,0.000000000000000000e+00 +7.010717034386209079e+00,6.918000000000000682e+01,0.000000000000000000e+00,7.025465837375420186e+00,0.000000000000000000e+00,-1.000000009964977066e+00,0.000000000000000000e+00,-1.020218278223411423e-10,0.000000000000000000e+00 +7.012140427543542387e+00,6.918999999999999773e+01,0.000000000000000000e+00,7.024042444203902669e+00,0.000000000000000000e+00,-1.000000009965122283e+00,0.000000000000000000e+00,1.012213323445439447e-10,0.000000000000000000e+00 +7.013564109145616676e+00,6.920000000000000284e+01,0.000000000000000000e+00,7.022618762587641505e+00,0.000000000000000000e+00,-1.000000009964978176e+00,0.000000000000000000e+00,-2.214255144322596757e-11,0.000000000000000000e+00 +7.014988079367847185e+00,6.921000000000000796e+01,0.000000000000000000e+00,7.021194792351221459e+00,0.000000000000000000e+00,-1.000000009965009706e+00,0.000000000000000000e+00,8.995536305148943144e-11,0.000000000000000000e+00 +7.016412338385826786e+00,6.921999999999999886e+01,0.000000000000000000e+00,7.019770533319048766e+00,0.000000000000000000e+00,-1.000000009964881587e+00,0.000000000000000000e+00,-3.128315264693555751e-10,0.000000000000000000e+00 +7.017836886375327765e+00,6.923000000000000398e+01,0.000000000000000000e+00,7.018345985315352031e+00,0.000000000000000000e+00,-1.000000009965327230e+00,0.000000000000000000e+00,2.069536424120507574e-10,0.000000000000000000e+00 +7.019261723512300044e+00,6.923999999999999488e+01,0.000000000000000000e+00,7.016921148164180444e+00,0.000000000000000000e+00,-1.000000009965032355e+00,0.000000000000000000e+00,2.430588395249371537e-11,0.000000000000000000e+00 +7.020686849972872956e+00,6.925000000000000000e+01,0.000000000000000000e+00,7.015496021689406447e+00,0.000000000000000000e+00,-1.000000009964997716e+00,0.000000000000000000e+00,1.397304479112770391e-10,0.000000000000000000e+00 +7.022112265933352582e+00,6.926000000000000512e+01,0.000000000000000000e+00,7.014070605714722184e+00,0.000000000000000000e+00,-1.000000009964798542e+00,0.000000000000000000e+00,-1.962370036068372436e-10,0.000000000000000000e+00 +7.023537971570226190e+00,6.926999999999999602e+01,0.000000000000000000e+00,7.012644900063641273e+00,0.000000000000000000e+00,-1.000000009965078318e+00,0.000000000000000000e+00,-4.199552549149308046e-10,0.000000000000000000e+00 +7.024963967060160464e+00,6.928000000000000114e+01,0.000000000000000000e+00,7.011218904559497034e+00,0.000000000000000000e+00,-1.000000009965677172e+00,0.000000000000000000e+00,4.667296388454061525e-10,0.000000000000000000e+00 +7.026390252580000606e+00,6.929000000000000625e+01,0.000000000000000000e+00,7.009792619025443372e+00,0.000000000000000000e+00,-1.000000009965011483e+00,0.000000000000000000e+00,-2.972889468452998624e-11,0.000000000000000000e+00 +7.027816828306771235e+00,6.929999999999999716e+01,0.000000000000000000e+00,7.008366043284456559e+00,0.000000000000000000e+00,-1.000000009965053893e+00,0.000000000000000000e+00,-3.688122590125111675e-11,0.000000000000000000e+00 +7.029243694417679045e+00,6.931000000000000227e+01,0.000000000000000000e+00,7.006939177159329901e+00,0.000000000000000000e+00,-1.000000009965106518e+00,0.000000000000000000e+00,1.353592145953678570e-10,0.000000000000000000e+00 +7.030670851090110141e+00,6.932000000000000739e+01,0.000000000000000000e+00,7.005512020472677293e+00,0.000000000000000000e+00,-1.000000009964913339e+00,0.000000000000000000e+00,-2.589967687890883566e-10,0.000000000000000000e+00 +7.032098298501630929e+00,6.932999999999999829e+01,0.000000000000000000e+00,7.004084573046932327e+00,0.000000000000000000e+00,-1.000000009965283043e+00,0.000000000000000000e+00,-2.208411252474871983e-10,0.000000000000000000e+00 +7.033526036829989003e+00,6.934000000000000341e+01,0.000000000000000000e+00,7.002656834704346522e+00,0.000000000000000000e+00,-1.000000009965598347e+00,0.000000000000000000e+00,3.759753447755167508e-10,0.000000000000000000e+00 +7.034954066253113147e+00,6.935000000000000853e+01,0.000000000000000000e+00,7.001228805266991095e+00,0.000000000000000000e+00,-1.000000009965061443e+00,0.000000000000000000e+00,-8.363667752217287963e-11,0.000000000000000000e+00 +7.036382386949114220e+00,6.935999999999999943e+01,0.000000000000000000e+00,6.999800484556756963e+00,0.000000000000000000e+00,-1.000000009965180903e+00,0.000000000000000000e+00,2.695100596077674365e-10,0.000000000000000000e+00 +7.037810999096283382e+00,6.937000000000000455e+01,0.000000000000000000e+00,6.998371872395351190e+00,0.000000000000000000e+00,-1.000000009964795877e+00,0.000000000000000000e+00,-6.130335580634062379e-10,0.000000000000000000e+00 +7.039239902873095645e+00,6.937999999999999545e+01,0.000000000000000000e+00,6.996942968604300539e+00,0.000000000000000000e+00,-1.000000009965671843e+00,0.000000000000000000e+00,4.412318961496677790e-10,0.000000000000000000e+00 +7.040669098458206321e+00,6.939000000000000057e+01,0.000000000000000000e+00,6.995513773004947033e+00,0.000000000000000000e+00,-1.000000009965041237e+00,0.000000000000000000e+00,8.077243678267393352e-11,0.000000000000000000e+00 +7.042098586030454577e+00,6.940000000000000568e+01,0.000000000000000000e+00,6.994084285418454172e+00,0.000000000000000000e+00,-1.000000009964925773e+00,0.000000000000000000e+00,-2.612143783070362109e-10,0.000000000000000000e+00 +7.043528365768861654e+00,6.940999999999999659e+01,0.000000000000000000e+00,6.992654505665799824e+00,0.000000000000000000e+00,-1.000000009965299252e+00,0.000000000000000000e+00,-2.282441374419069947e-11,0.000000000000000000e+00 +7.044958437852631761e+00,6.942000000000000171e+01,0.000000000000000000e+00,6.991224433567778895e+00,0.000000000000000000e+00,-1.000000009965331893e+00,0.000000000000000000e+00,5.572985565584681317e-11,0.000000000000000000e+00 +7.046388802461152068e+00,6.943000000000000682e+01,0.000000000000000000e+00,6.989794068945004213e+00,0.000000000000000000e+00,-1.000000009965252179e+00,0.000000000000000000e+00,-3.308962205348541874e-10,0.000000000000000000e+00 +7.047819459773994488e+00,6.943999999999999773e+01,0.000000000000000000e+00,6.988363411617904752e+00,0.000000000000000000e+00,-1.000000009965725578e+00,0.000000000000000000e+00,6.812087644415010375e-10,0.000000000000000000e+00 +7.049250409970913900e+00,6.945000000000000284e+01,0.000000000000000000e+00,6.986932461406724748e+00,0.000000000000000000e+00,-1.000000009964750802e+00,0.000000000000000000e+00,-6.824655484678073024e-10,0.000000000000000000e+00 +7.050681653231849033e+00,6.946000000000000796e+01,0.000000000000000000e+00,6.985501218131527246e+00,0.000000000000000000e+00,-1.000000009965727576e+00,0.000000000000000000e+00,4.768059446055586772e-10,0.000000000000000000e+00 +7.052113189736924248e+00,6.946999999999999886e+01,0.000000000000000000e+00,6.984069681612186109e+00,0.000000000000000000e+00,-1.000000009965045011e+00,0.000000000000000000e+00,-4.652324979667401014e-11,0.000000000000000000e+00 +7.053545019666445981e+00,6.948000000000000398e+01,0.000000000000000000e+00,6.982637851668395790e+00,0.000000000000000000e+00,-1.000000009965111625e+00,0.000000000000000000e+00,-3.888546314275562149e-10,0.000000000000000000e+00 +7.054977143200908074e+00,6.948999999999999488e+01,0.000000000000000000e+00,6.981205728119662446e+00,0.000000000000000000e+00,-1.000000009965668513e+00,0.000000000000000000e+00,4.441148429248993570e-10,0.000000000000000000e+00 +7.056409560520988222e+00,6.950000000000000000e+01,0.000000000000000000e+00,6.979773310785307494e+00,0.000000000000000000e+00,-1.000000009965032355e+00,0.000000000000000000e+00,-4.469683784936690308e-10,0.000000000000000000e+00 +7.057842271807549750e+00,6.951000000000000512e+01,0.000000000000000000e+00,6.978340599484469386e+00,0.000000000000000000e+00,-1.000000009965672731e+00,0.000000000000000000e+00,9.684393009030220131e-11,0.000000000000000000e+00 +7.059275277241640723e+00,6.951999999999999602e+01,0.000000000000000000e+00,6.976907594036097393e+00,0.000000000000000000e+00,-1.000000009965533954e+00,0.000000000000000000e+00,4.746701891128823913e-10,0.000000000000000000e+00 +7.060708577004496611e+00,6.953000000000000114e+01,0.000000000000000000e+00,6.975474294258957819e+00,0.000000000000000000e+00,-1.000000009964853609e+00,0.000000000000000000e+00,-4.793741612714503162e-10,0.000000000000000000e+00 +7.062142171277538516e+00,6.954000000000000625e+01,0.000000000000000000e+00,6.974040699971630453e+00,0.000000000000000000e+00,-1.000000009965540837e+00,0.000000000000000000e+00,-4.088167015564603912e-11,0.000000000000000000e+00 +7.063576060242373167e+00,6.954999999999999716e+01,0.000000000000000000e+00,6.972606810992505899e+00,0.000000000000000000e+00,-1.000000009965599457e+00,0.000000000000000000e+00,1.912063709935850433e-10,0.000000000000000000e+00 +7.065010244080795587e+00,6.956000000000000227e+01,0.000000000000000000e+00,6.971172627139790912e+00,0.000000000000000000e+00,-1.000000009965325232e+00,0.000000000000000000e+00,-8.296804417155919193e-11,0.000000000000000000e+00 +7.066444722974786430e+00,6.957000000000000739e+01,0.000000000000000000e+00,6.969738148231504837e+00,0.000000000000000000e+00,-1.000000009965444248e+00,0.000000000000000000e+00,1.309263469507516293e-10,0.000000000000000000e+00 +7.067879497106514641e+00,6.957999999999999829e+01,0.000000000000000000e+00,6.968303374085478730e+00,0.000000000000000000e+00,-1.000000009965256398e+00,0.000000000000000000e+00,-3.303430352302182657e-10,0.000000000000000000e+00 +7.069314566658335686e+00,6.959000000000000341e+01,0.000000000000000000e+00,6.966868304519357125e+00,0.000000000000000000e+00,-1.000000009965730463e+00,0.000000000000000000e+00,3.902968777569868016e-10,0.000000000000000000e+00 +7.070749931812793321e+00,6.960000000000000853e+01,0.000000000000000000e+00,6.965432939350595376e+00,0.000000000000000000e+00,-1.000000009965170245e+00,0.000000000000000000e+00,-1.630155192627997278e-10,0.000000000000000000e+00 +7.072185592752618710e+00,6.960999999999999943e+01,0.000000000000000000e+00,6.963997278396463209e+00,0.000000000000000000e+00,-1.000000009965404280e+00,0.000000000000000000e+00,-1.334472455040402521e-10,0.000000000000000000e+00 +7.073621549660732200e+00,6.962000000000000455e+01,0.000000000000000000e+00,6.962561321474039389e+00,0.000000000000000000e+00,-1.000000009965595904e+00,0.000000000000000000e+00,1.794905045533781160e-10,0.000000000000000000e+00 +7.075057802720243316e+00,6.962999999999999545e+01,0.000000000000000000e+00,6.961125068400215277e+00,0.000000000000000000e+00,-1.000000009965338110e+00,0.000000000000000000e+00,4.698868007565837651e-11,0.000000000000000000e+00 +7.076494352114448994e+00,6.964000000000000057e+01,0.000000000000000000e+00,6.959688518991693940e+00,0.000000000000000000e+00,-1.000000009965270609e+00,0.000000000000000000e+00,-3.977759954284425831e-10,0.000000000000000000e+00 +7.077931198026836235e+00,6.965000000000000568e+01,0.000000000000000000e+00,6.958251673064988374e+00,0.000000000000000000e+00,-1.000000009965842152e+00,0.000000000000000000e+00,2.679103250601209432e-10,0.000000000000000000e+00 +7.079368340641080337e+00,6.965999999999999659e+01,0.000000000000000000e+00,6.956814530436421506e+00,0.000000000000000000e+00,-1.000000009965457126e+00,0.000000000000000000e+00,2.626029327710702981e-11,0.000000000000000000e+00 +7.080805780141048444e+00,6.967000000000000171e+01,0.000000000000000000e+00,6.955377090922128858e+00,0.000000000000000000e+00,-1.000000009965419379e+00,0.000000000000000000e+00,-1.289577305145778740e-10,0.000000000000000000e+00 +7.082243516710795994e+00,6.968000000000000682e+01,0.000000000000000000e+00,6.953939354338054102e+00,0.000000000000000000e+00,-1.000000009965604786e+00,0.000000000000000000e+00,3.644039931191624252e-10,0.000000000000000000e+00 +7.083681550534568494e+00,6.968999999999999773e+01,0.000000000000000000e+00,6.952501320499950843e+00,0.000000000000000000e+00,-1.000000009965080761e+00,0.000000000000000000e+00,-5.072813133813544642e-10,0.000000000000000000e+00 +7.085119881796802410e+00,6.970000000000000284e+01,0.000000000000000000e+00,6.951062989223383504e+00,0.000000000000000000e+00,-1.000000009965810399e+00,0.000000000000000000e+00,3.949678404207598694e-10,0.000000000000000000e+00 +7.086558510682126055e+00,6.971000000000000796e+01,0.000000000000000000e+00,6.949624360323722883e+00,0.000000000000000000e+00,-1.000000009965242187e+00,0.000000000000000000e+00,-2.286913614479803576e-10,0.000000000000000000e+00 +7.087997437375356924e+00,6.971999999999999886e+01,0.000000000000000000e+00,6.948185433616152373e+00,0.000000000000000000e+00,-1.000000009965571257e+00,0.000000000000000000e+00,-9.889393444035729246e-11,0.000000000000000000e+00 +7.089436662061506134e+00,6.973000000000000398e+01,0.000000000000000000e+00,6.946746208915660858e+00,0.000000000000000000e+00,-1.000000009965713588e+00,0.000000000000000000e+00,6.061975943669427788e-11,0.000000000000000000e+00 +7.090876184925773984e+00,6.973999999999999488e+01,0.000000000000000000e+00,6.945306686037047150e+00,0.000000000000000000e+00,-1.000000009965626324e+00,0.000000000000000000e+00,-4.441443492050710249e-11,0.000000000000000000e+00 +7.092316006153554397e+00,6.975000000000000000e+01,0.000000000000000000e+00,6.943866864794918214e+00,0.000000000000000000e+00,-1.000000009965690273e+00,0.000000000000000000e+00,1.492509033056750434e-10,0.000000000000000000e+00 +7.093756125930432255e+00,6.976000000000000512e+01,0.000000000000000000e+00,6.942426745003688282e+00,0.000000000000000000e+00,-1.000000009965475334e+00,0.000000000000000000e+00,-8.000532415801485729e-11,0.000000000000000000e+00 +7.095196544442186060e+00,6.976999999999999602e+01,0.000000000000000000e+00,6.940986326477579738e+00,0.000000000000000000e+00,-1.000000009965590575e+00,0.000000000000000000e+00,-1.693788214751381520e-10,0.000000000000000000e+00 +7.096637261874787050e+00,6.978000000000000114e+01,0.000000000000000000e+00,6.939545609030621343e+00,0.000000000000000000e+00,-1.000000009965834602e+00,0.000000000000000000e+00,4.442382015764696629e-10,0.000000000000000000e+00 +7.098078278414398312e+00,6.979000000000000625e+01,0.000000000000000000e+00,6.938104592476649124e+00,0.000000000000000000e+00,-1.000000009965194447e+00,0.000000000000000000e+00,-2.424855123041745787e-10,0.000000000000000000e+00 +7.099519594247377441e+00,6.979999999999999716e+01,0.000000000000000000e+00,6.936663276629307262e+00,0.000000000000000000e+00,-1.000000009965543946e+00,0.000000000000000000e+00,-3.829058160698219415e-10,0.000000000000000000e+00 +7.100961209560274767e+00,6.981000000000000227e+01,0.000000000000000000e+00,6.935221661302043650e+00,0.000000000000000000e+00,-1.000000009966095948e+00,0.000000000000000000e+00,5.851728504635060399e-10,0.000000000000000000e+00 +7.102403124539835133e+00,6.982000000000000739e+01,0.000000000000000000e+00,6.933779746308113445e+00,0.000000000000000000e+00,-1.000000009965252179e+00,0.000000000000000000e+00,-1.932208522429741786e-10,0.000000000000000000e+00 +7.103845339372997003e+00,6.982999999999999829e+01,0.000000000000000000e+00,6.932337531460579960e+00,0.000000000000000000e+00,-1.000000009965530845e+00,0.000000000000000000e+00,-4.447003460670199367e-10,0.000000000000000000e+00 +7.105287854246893353e+00,6.984000000000000341e+01,0.000000000000000000e+00,6.930895016572308442e+00,0.000000000000000000e+00,-1.000000009966172332e+00,0.000000000000000000e+00,3.921290070924286149e-10,0.000000000000000000e+00 +7.106730669348851670e+00,6.985000000000000853e+01,0.000000000000000000e+00,6.929452201455970517e+00,0.000000000000000000e+00,-1.000000009965606562e+00,0.000000000000000000e+00,-1.058589463776395464e-10,0.000000000000000000e+00 +7.108173784866395728e+00,6.985999999999999943e+01,0.000000000000000000e+00,6.928009085924045074e+00,0.000000000000000000e+00,-1.000000009965759329e+00,0.000000000000000000e+00,3.305864809821817252e-10,0.000000000000000000e+00 +7.109617200987242924e+00,6.987000000000000455e+01,0.000000000000000000e+00,6.926565669788812940e+00,0.000000000000000000e+00,-1.000000009965282155e+00,0.000000000000000000e+00,-2.926826441120435968e-10,0.000000000000000000e+00 +7.111060917899307832e+00,6.987999999999999545e+01,0.000000000000000000e+00,6.925121952862361319e+00,0.000000000000000000e+00,-1.000000009965704706e+00,0.000000000000000000e+00,-1.337786792230456291e-10,0.000000000000000000e+00 +7.112504935790699534e+00,6.989000000000000057e+01,0.000000000000000000e+00,6.923677934956579350e+00,0.000000000000000000e+00,-1.000000009965897885e+00,0.000000000000000000e+00,9.208818336856585096e-11,0.000000000000000000e+00 +7.113949254849723403e+00,6.990000000000000568e+01,0.000000000000000000e+00,6.922233615883161661e+00,0.000000000000000000e+00,-1.000000009965764880e+00,0.000000000000000000e+00,9.668010712872174938e-11,0.000000000000000000e+00 +7.115393875264881984e+00,6.990999999999999659e+01,0.000000000000000000e+00,6.920788995453606596e+00,0.000000000000000000e+00,-1.000000009965625214e+00,0.000000000000000000e+00,1.797966914170050289e-11,0.000000000000000000e+00 +7.116838797224874114e+00,6.992000000000000171e+01,0.000000000000000000e+00,6.919344073479215318e+00,0.000000000000000000e+00,-1.000000009965599235e+00,0.000000000000000000e+00,-5.838331480316986788e-12,0.000000000000000000e+00 +7.118284020918594912e+00,6.993000000000000682e+01,0.000000000000000000e+00,6.917898849771091818e+00,0.000000000000000000e+00,-1.000000009965607672e+00,0.000000000000000000e+00,-2.619020009499919753e-10,0.000000000000000000e+00 +7.119729546535138454e+00,6.993999999999999773e+01,0.000000000000000000e+00,6.916453324140142911e+00,0.000000000000000000e+00,-1.000000009965986258e+00,0.000000000000000000e+00,2.385037059491255592e-10,0.000000000000000000e+00 +7.121175374263795099e+00,6.995000000000000284e+01,0.000000000000000000e+00,6.915007496397077347e+00,0.000000000000000000e+00,-1.000000009965641423e+00,0.000000000000000000e+00,-6.663810066945455386e-11,0.000000000000000000e+00 +7.122621504294053274e+00,6.996000000000000796e+01,0.000000000000000000e+00,6.913561366352407589e+00,0.000000000000000000e+00,-1.000000009965737791e+00,0.000000000000000000e+00,-1.878985658713216171e-10,0.000000000000000000e+00 +7.124067936815599467e+00,6.996999999999999886e+01,0.000000000000000000e+00,6.912114933816446261e+00,0.000000000000000000e+00,-1.000000009966009573e+00,0.000000000000000000e+00,1.319926133521086248e-11,0.000000000000000000e+00 +7.125514672018320006e+00,6.998000000000000398e+01,0.000000000000000000e+00,6.910668198599307921e+00,0.000000000000000000e+00,-1.000000009965990477e+00,0.000000000000000000e+00,2.513472654298724595e-10,0.000000000000000000e+00 +7.126961710092297508e+00,6.998999999999999488e+01,0.000000000000000000e+00,6.909221160510909066e+00,0.000000000000000000e+00,-1.000000009965626768e+00,0.000000000000000000e+00,-1.824110631398194696e-10,0.000000000000000000e+00 +7.128409051227815318e+00,7.000000000000000000e+01,0.000000000000000000e+00,6.907773819360967238e+00,0.000000000000000000e+00,-1.000000009965890779e+00,0.000000000000000000e+00,1.239337798174236255e-10,0.000000000000000000e+00 +7.129856695615356621e+00,7.001000000000000512e+01,0.000000000000000000e+00,6.906326174958999253e+00,0.000000000000000000e+00,-1.000000009965711367e+00,0.000000000000000000e+00,3.818446042835412337e-11,0.000000000000000000e+00 +7.131304643445601776e+00,7.001999999999999602e+01,0.000000000000000000e+00,6.904878227114323863e+00,0.000000000000000000e+00,-1.000000009965656078e+00,0.000000000000000000e+00,-2.991255559048343945e-10,0.000000000000000000e+00 +7.132752894909433650e+00,7.003000000000000114e+01,0.000000000000000000e+00,6.903429975636059091e+00,0.000000000000000000e+00,-1.000000009966089287e+00,0.000000000000000000e+00,9.902336204927517472e-11,0.000000000000000000e+00 +7.134201450197934058e+00,7.004000000000000625e+01,0.000000000000000000e+00,6.901981420333122230e+00,0.000000000000000000e+00,-1.000000009965945846e+00,0.000000000000000000e+00,1.025274436506431164e-10,0.000000000000000000e+00 +7.135650309502385547e+00,7.004999999999999716e+01,0.000000000000000000e+00,6.900532561014231625e+00,0.000000000000000000e+00,-1.000000009965797299e+00,0.000000000000000000e+00,2.758006847308895264e-10,0.000000000000000000e+00 +7.137099473014271389e+00,7.006000000000000227e+01,0.000000000000000000e+00,6.899083397487904001e+00,0.000000000000000000e+00,-1.000000009965397618e+00,0.000000000000000000e+00,-5.092049718158307804e-10,0.000000000000000000e+00 +7.138548940925275588e+00,7.007000000000000739e+01,0.000000000000000000e+00,6.897633929562455357e+00,0.000000000000000000e+00,-1.000000009966135694e+00,0.000000000000000000e+00,2.603690081372217180e-12,0.000000000000000000e+00 +7.139998713427283761e+00,7.007999999999999829e+01,0.000000000000000000e+00,6.896184157045998298e+00,0.000000000000000000e+00,-1.000000009966131920e+00,0.000000000000000000e+00,2.615392911183748127e-10,0.000000000000000000e+00 +7.141448790712384032e+00,7.009000000000000341e+01,0.000000000000000000e+00,6.894734079746446476e+00,0.000000000000000000e+00,-1.000000009965752668e+00,0.000000000000000000e+00,-1.377844654320404055e-11,0.000000000000000000e+00 +7.142899172972865252e+00,7.010000000000000853e+01,0.000000000000000000e+00,6.893283697471511040e+00,0.000000000000000000e+00,-1.000000009965772652e+00,0.000000000000000000e+00,-2.577558110626215942e-10,0.000000000000000000e+00 +7.144349860401219665e+00,7.010999999999999943e+01,0.000000000000000000e+00,6.891833010028699746e+00,0.000000000000000000e+00,-1.000000009966146575e+00,0.000000000000000000e+00,5.138728386739093718e-10,0.000000000000000000e+00 +7.145800853190141133e+00,7.012000000000000455e+01,0.000000000000000000e+00,6.890382017225317846e+00,0.000000000000000000e+00,-1.000000009965400949e+00,0.000000000000000000e+00,-5.093277296662330965e-10,0.000000000000000000e+00 +7.147252151532526021e+00,7.012999999999999545e+01,0.000000000000000000e+00,6.888930718868469860e+00,0.000000000000000000e+00,-1.000000009966140135e+00,0.000000000000000000e+00,1.895236225885729127e-10,0.000000000000000000e+00 +7.148703755621475864e+00,7.014000000000000057e+01,0.000000000000000000e+00,6.887479114765053367e+00,0.000000000000000000e+00,-1.000000009965865022e+00,0.000000000000000000e+00,-1.994243162973503419e-10,0.000000000000000000e+00 +7.150155665650293813e+00,7.015000000000000568e+01,0.000000000000000000e+00,6.886027204721766104e+00,0.000000000000000000e+00,-1.000000009966154568e+00,0.000000000000000000e+00,1.529005190175462124e-10,0.000000000000000000e+00 +7.151607881812487300e+00,7.015999999999999659e+01,0.000000000000000000e+00,6.884574988545099750e+00,0.000000000000000000e+00,-1.000000009965932524e+00,0.000000000000000000e+00,1.253519841394763711e-10,0.000000000000000000e+00 +7.153060404301768038e+00,7.017000000000000171e+01,0.000000000000000000e+00,6.883122466041343479e+00,0.000000000000000000e+00,-1.000000009965750447e+00,0.000000000000000000e+00,-1.381637628594972453e-10,0.000000000000000000e+00 +7.154513233312052023e+00,7.018000000000000682e+01,0.000000000000000000e+00,6.881669637016581298e+00,0.000000000000000000e+00,-1.000000009965951175e+00,0.000000000000000000e+00,-7.395702060355502980e-11,0.000000000000000000e+00 +7.155966369037459529e+00,7.018999999999999773e+01,0.000000000000000000e+00,6.880216501276692043e+00,0.000000000000000000e+00,-1.000000009966058645e+00,0.000000000000000000e+00,4.094276078930100077e-11,0.000000000000000000e+00 +7.157419811672316001e+00,7.020000000000000284e+01,0.000000000000000000e+00,6.878763058627350269e+00,0.000000000000000000e+00,-1.000000009965999137e+00,0.000000000000000000e+00,-7.010730316081468187e-11,0.000000000000000000e+00 +7.158873561411152942e+00,7.021000000000000796e+01,0.000000000000000000e+00,6.877309308874025362e+00,0.000000000000000000e+00,-1.000000009966101056e+00,0.000000000000000000e+00,1.569827372432385922e-10,0.000000000000000000e+00 +7.160327618448706133e+00,7.021999999999999886e+01,0.000000000000000000e+00,6.875855251821980652e+00,0.000000000000000000e+00,-1.000000009965872794e+00,0.000000000000000000e+00,2.610736622580397583e-11,0.000000000000000000e+00 +7.161781982979918304e+00,7.023000000000000398e+01,0.000000000000000000e+00,6.874400887276274297e+00,0.000000000000000000e+00,-1.000000009965834824e+00,0.000000000000000000e+00,-3.174961148552013636e-10,0.000000000000000000e+00 +7.163236655199938241e+00,7.023999999999999488e+01,0.000000000000000000e+00,6.872946215041757512e+00,0.000000000000000000e+00,-1.000000009966296677e+00,0.000000000000000000e+00,1.095740250178774213e-10,0.000000000000000000e+00 +7.164691635304120787e+00,7.025000000000000000e+01,0.000000000000000000e+00,6.871491234923074565e+00,0.000000000000000000e+00,-1.000000009966137249e+00,0.000000000000000000e+00,1.930108608977951536e-10,0.000000000000000000e+00 +7.166146923488026843e+00,7.026000000000000512e+01,0.000000000000000000e+00,6.870035946724664555e+00,0.000000000000000000e+00,-1.000000009965856362e+00,0.000000000000000000e+00,-3.404814260108291182e-10,0.000000000000000000e+00 +7.167602519947426032e+00,7.026999999999999602e+01,0.000000000000000000e+00,6.868580350250758748e+00,0.000000000000000000e+00,-1.000000009966351966e+00,0.000000000000000000e+00,3.306484463859426066e-10,0.000000000000000000e+00 +7.169058424878294922e+00,7.028000000000000114e+01,0.000000000000000000e+00,6.867124445305379687e+00,0.000000000000000000e+00,-1.000000009965870573e+00,0.000000000000000000e+00,-1.625445258101162221e-10,0.000000000000000000e+00 +7.170514638476817026e+00,7.029000000000000625e+01,0.000000000000000000e+00,6.865668231692344747e+00,0.000000000000000000e+00,-1.000000009966107273e+00,0.000000000000000000e+00,1.829381508062958050e-12,0.000000000000000000e+00 +7.171971160939385470e+00,7.029999999999999716e+01,0.000000000000000000e+00,6.864211709215260804e+00,0.000000000000000000e+00,-1.000000009966104608e+00,0.000000000000000000e+00,1.315351095832533019e-10,0.000000000000000000e+00 +7.173427992462599434e+00,7.031000000000000227e+01,0.000000000000000000e+00,6.862754877677527787e+00,0.000000000000000000e+00,-1.000000009965912984e+00,0.000000000000000000e+00,-4.541036332623489370e-11,0.000000000000000000e+00 +7.174885133243268598e+00,7.032000000000000739e+01,0.000000000000000000e+00,6.861297736882336906e+00,0.000000000000000000e+00,-1.000000009965979153e+00,0.000000000000000000e+00,-3.825544018745473921e-10,0.000000000000000000e+00 +7.176342583478410475e+00,7.032999999999999829e+01,0.000000000000000000e+00,6.859840286632669759e+00,0.000000000000000000e+00,-1.000000009966536707e+00,0.000000000000000000e+00,5.209311599926042576e-10,0.000000000000000000e+00 +7.177800343365253077e+00,7.034000000000000341e+01,0.000000000000000000e+00,6.858382526731298334e+00,0.000000000000000000e+00,-1.000000009965777314e+00,0.000000000000000000e+00,-5.322419600811898024e-10,0.000000000000000000e+00 +7.179258413101233138e+00,7.035000000000000853e+01,0.000000000000000000e+00,6.856924456980787674e+00,0.000000000000000000e+00,-1.000000009966553360e+00,0.000000000000000000e+00,3.660193569250805493e-10,0.000000000000000000e+00 +7.180716792883997002e+00,7.035999999999999943e+01,0.000000000000000000e+00,6.855466077183488771e+00,0.000000000000000000e+00,-1.000000009966019565e+00,0.000000000000000000e+00,2.054995996524968587e-11,0.000000000000000000e+00 +7.182175482911401510e+00,7.037000000000000455e+01,0.000000000000000000e+00,6.854007387141546559e+00,0.000000000000000000e+00,-1.000000009965989589e+00,0.000000000000000000e+00,-1.675606794036631036e-10,0.000000000000000000e+00 +7.183634483381514890e+00,7.037999999999999545e+01,0.000000000000000000e+00,6.852548386656892809e+00,0.000000000000000000e+00,-1.000000009966234060e+00,0.000000000000000000e+00,-5.112479901462831901e-11,0.000000000000000000e+00 +7.185093794492614983e+00,7.039000000000000057e+01,0.000000000000000000e+00,6.851089075531248795e+00,0.000000000000000000e+00,-1.000000009966308667e+00,0.000000000000000000e+00,1.007065757008637619e-10,0.000000000000000000e+00 +7.186553416443191011e+00,7.040000000000000568e+01,0.000000000000000000e+00,6.849629453566125292e+00,0.000000000000000000e+00,-1.000000009966161674e+00,0.000000000000000000e+00,1.870735617056936435e-11,0.000000000000000000e+00 +7.188013349431944476e+00,7.040999999999999659e+01,0.000000000000000000e+00,6.848169520562821688e+00,0.000000000000000000e+00,-1.000000009966134362e+00,0.000000000000000000e+00,-1.482584118261687452e-10,0.000000000000000000e+00 +7.189473593657788264e+00,7.042000000000000171e+01,0.000000000000000000e+00,6.846709276322425097e+00,0.000000000000000000e+00,-1.000000009966350856e+00,0.000000000000000000e+00,1.649498219082852610e-10,0.000000000000000000e+00 +7.190934149319846647e+00,7.043000000000000682e+01,0.000000000000000000e+00,6.845248720645810359e+00,0.000000000000000000e+00,-1.000000009966109937e+00,0.000000000000000000e+00,-1.427233564374223082e-10,0.000000000000000000e+00 +7.192395016617457060e+00,7.043999999999999773e+01,0.000000000000000000e+00,6.843787853333640925e+00,0.000000000000000000e+00,-1.000000009966318437e+00,0.000000000000000000e+00,3.270235518021190176e-10,0.000000000000000000e+00 +7.193856195750169213e+00,7.045000000000000284e+01,0.000000000000000000e+00,6.842326674186366198e+00,0.000000000000000000e+00,-1.000000009965840597e+00,0.000000000000000000e+00,-3.570359049373630376e-10,0.000000000000000000e+00 +7.195317686917745981e+00,7.046000000000000796e+01,0.000000000000000000e+00,6.840865183004224193e+00,0.000000000000000000e+00,-1.000000009966362402e+00,0.000000000000000000e+00,3.417698715537543253e-11,0.000000000000000000e+00 +7.196779490320164285e+00,7.046999999999999886e+01,0.000000000000000000e+00,6.839403379587237097e+00,0.000000000000000000e+00,-1.000000009966312442e+00,0.000000000000000000e+00,-1.306041254355299827e-11,0.000000000000000000e+00 +7.198241606157613326e+00,7.048000000000000398e+01,0.000000000000000000e+00,6.837941263735215713e+00,0.000000000000000000e+00,-1.000000009966331538e+00,0.000000000000000000e+00,6.726192891181483487e-11,0.000000000000000000e+00 +7.199704034630498128e+00,7.048999999999999488e+01,0.000000000000000000e+00,6.836478835247755903e+00,0.000000000000000000e+00,-1.000000009966233172e+00,0.000000000000000000e+00,9.259819776510648984e-12,0.000000000000000000e+00 +7.201166775939436882e+00,7.050000000000000000e+01,0.000000000000000000e+00,6.835016093924239478e+00,0.000000000000000000e+00,-1.000000009966219627e+00,0.000000000000000000e+00,-3.596897922308983402e-11,0.000000000000000000e+00 +7.202629830285261825e+00,7.051000000000000512e+01,0.000000000000000000e+00,6.833553039563833309e+00,0.000000000000000000e+00,-1.000000009966272252e+00,0.000000000000000000e+00,8.178535822633627895e-11,0.000000000000000000e+00 +7.204093197869021914e+00,7.051999999999999602e+01,0.000000000000000000e+00,6.832089671965489330e+00,0.000000000000000000e+00,-1.000000009966152570e+00,0.000000000000000000e+00,9.830345665115285969e-11,0.000000000000000000e+00 +7.205556878891979267e+00,7.053000000000000114e+01,0.000000000000000000e+00,6.830625990927944535e+00,0.000000000000000000e+00,-1.000000009966008685e+00,0.000000000000000000e+00,-2.496494207153120990e-10,0.000000000000000000e+00 +7.207020873555613605e+00,7.054000000000000625e+01,0.000000000000000000e+00,6.829161996249720090e+00,0.000000000000000000e+00,-1.000000009966374170e+00,0.000000000000000000e+00,1.834818078685831659e-11,0.000000000000000000e+00 +7.208485182061619589e+00,7.054999999999999716e+01,0.000000000000000000e+00,6.827697687729120446e+00,0.000000000000000000e+00,-1.000000009966347303e+00,0.000000000000000000e+00,-1.898098901395441442e-10,0.000000000000000000e+00 +7.209949804611907709e+00,7.056000000000000227e+01,0.000000000000000000e+00,6.826233065164235114e+00,0.000000000000000000e+00,-1.000000009966625303e+00,0.000000000000000000e+00,1.062525485080485086e-10,0.000000000000000000e+00 +7.211414741408606055e+00,7.057000000000000739e+01,0.000000000000000000e+00,6.824768128352936003e+00,0.000000000000000000e+00,-1.000000009966469650e+00,0.000000000000000000e+00,2.298866264174615612e-10,0.000000000000000000e+00 +7.212879992654059436e+00,7.057999999999999829e+01,0.000000000000000000e+00,6.823302877092879193e+00,0.000000000000000000e+00,-1.000000009966132808e+00,0.000000000000000000e+00,-7.954157356046568575e-11,0.000000000000000000e+00 +7.214345558550829374e+00,7.059000000000000341e+01,0.000000000000000000e+00,6.821837311181503161e+00,0.000000000000000000e+00,-1.000000009966249381e+00,0.000000000000000000e+00,-2.561445920525411893e-10,0.000000000000000000e+00 +7.215811439301694996e+00,7.060000000000000853e+01,0.000000000000000000e+00,6.820371430416027891e+00,0.000000000000000000e+00,-1.000000009966624859e+00,0.000000000000000000e+00,2.656304396209055422e-10,0.000000000000000000e+00 +7.217277635109653922e+00,7.060999999999999943e+01,0.000000000000000000e+00,6.818905234593455766e+00,0.000000000000000000e+00,-1.000000009966235393e+00,0.000000000000000000e+00,-1.438396062894705303e-11,0.000000000000000000e+00 +7.218744146177921372e+00,7.062000000000000455e+01,0.000000000000000000e+00,6.817438723510572451e+00,0.000000000000000000e+00,-1.000000009966256487e+00,0.000000000000000000e+00,-1.161065799267248939e-10,0.000000000000000000e+00 +7.220210972709931951e+00,7.062999999999999545e+01,0.000000000000000000e+00,6.815971896963943344e+00,0.000000000000000000e+00,-1.000000009966426795e+00,0.000000000000000000e+00,1.127520091345898867e-10,0.000000000000000000e+00 +7.221678114909337864e+00,7.064000000000000057e+01,0.000000000000000000e+00,6.814504754749915350e+00,0.000000000000000000e+00,-1.000000009966261372e+00,0.000000000000000000e+00,7.565620080140961506e-13,0.000000000000000000e+00 +7.223145572980011586e+00,7.065000000000000568e+01,0.000000000000000000e+00,6.813037296664616882e+00,0.000000000000000000e+00,-1.000000009966260262e+00,0.000000000000000000e+00,-2.977186808158719625e-10,0.000000000000000000e+00 +7.224613347126044083e+00,7.065999999999999659e+01,0.000000000000000000e+00,6.811569522503956087e+00,0.000000000000000000e+00,-1.000000009966697245e+00,0.000000000000000000e+00,1.951089219971469993e-10,0.000000000000000000e+00 +7.226081437551747477e+00,7.067000000000000171e+01,0.000000000000000000e+00,6.810101432063620841e+00,0.000000000000000000e+00,-1.000000009966410808e+00,0.000000000000000000e+00,-1.497024819162137017e-11,0.000000000000000000e+00 +7.227549844461653272e+00,7.068000000000000682e+01,0.000000000000000000e+00,6.808633025139080530e+00,0.000000000000000000e+00,-1.000000009966432790e+00,0.000000000000000000e+00,5.049479568689402518e-11,0.000000000000000000e+00 +7.229018568060513239e+00,7.068999999999999773e+01,0.000000000000000000e+00,6.807164301525582495e+00,0.000000000000000000e+00,-1.000000009966358627e+00,0.000000000000000000e+00,-2.767545711733397133e-10,0.000000000000000000e+00 +7.230487608553301193e+00,7.070000000000000284e+01,0.000000000000000000e+00,6.805695261018153808e+00,0.000000000000000000e+00,-1.000000009966765191e+00,0.000000000000000000e+00,3.921480740652262907e-10,0.000000000000000000e+00 +7.231956966145210330e+00,7.071000000000000796e+01,0.000000000000000000e+00,6.804225903411599496e+00,0.000000000000000000e+00,-1.000000009966188985e+00,0.000000000000000000e+00,-2.559365759409015493e-10,0.000000000000000000e+00 +7.233426641041657668e+00,7.071999999999999886e+01,0.000000000000000000e+00,6.802756228500505209e+00,0.000000000000000000e+00,-1.000000009966565129e+00,0.000000000000000000e+00,-8.609937319204536789e-12,0.000000000000000000e+00 +7.234896633448280490e+00,7.073000000000000398e+01,0.000000000000000000e+00,6.801286236079231884e+00,0.000000000000000000e+00,-1.000000009966577785e+00,0.000000000000000000e+00,5.542393319049216948e-11,0.000000000000000000e+00 +7.236366943570938126e+00,7.073999999999999488e+01,0.000000000000000000e+00,6.799815925941920192e+00,0.000000000000000000e+00,-1.000000009966496295e+00,0.000000000000000000e+00,9.270555386749676941e-11,0.000000000000000000e+00 +7.237837571615713728e+00,7.075000000000000000e+01,0.000000000000000000e+00,6.798345297882487870e+00,0.000000000000000000e+00,-1.000000009966359960e+00,0.000000000000000000e+00,-1.517083575291322516e-10,0.000000000000000000e+00 +7.239308517788911601e+00,7.076000000000000512e+01,0.000000000000000000e+00,6.796874351694629723e+00,0.000000000000000000e+00,-1.000000009966583114e+00,0.000000000000000000e+00,2.998798839652312339e-10,0.000000000000000000e+00 +7.240779782297060763e+00,7.076999999999999602e+01,0.000000000000000000e+00,6.795403087171816736e+00,0.000000000000000000e+00,-1.000000009966141912e+00,0.000000000000000000e+00,-4.476854655796898211e-10,0.000000000000000000e+00 +7.242251365346914049e+00,7.078000000000000114e+01,0.000000000000000000e+00,6.793931504107297847e+00,0.000000000000000000e+00,-1.000000009966800718e+00,0.000000000000000000e+00,2.232662638341498318e-10,0.000000000000000000e+00 +7.243723267145446343e+00,7.079000000000000625e+01,0.000000000000000000e+00,6.792459602294095511e+00,0.000000000000000000e+00,-1.000000009966472092e+00,0.000000000000000000e+00,9.652665656708017359e-12,0.000000000000000000e+00 +7.245195487899858122e+00,7.079999999999999716e+01,0.000000000000000000e+00,6.790987381525011024e+00,0.000000000000000000e+00,-1.000000009966457881e+00,0.000000000000000000e+00,-1.112831757314016214e-10,0.000000000000000000e+00 +7.246668027817573687e+00,7.081000000000000227e+01,0.000000000000000000e+00,6.789514841592619199e+00,0.000000000000000000e+00,-1.000000009966621750e+00,0.000000000000000000e+00,1.809090168760883701e-11,0.000000000000000000e+00 +7.248140887106242936e+00,7.082000000000000739e+01,0.000000000000000000e+00,6.788041982289270138e+00,0.000000000000000000e+00,-1.000000009966595105e+00,0.000000000000000000e+00,1.456001664766101199e-10,0.000000000000000000e+00 +7.249614065973741361e+00,7.082999999999999829e+01,0.000000000000000000e+00,6.786568803407089234e+00,0.000000000000000000e+00,-1.000000009966380610e+00,0.000000000000000000e+00,-3.889363071961348346e-10,0.000000000000000000e+00 +7.251087564628169169e+00,7.084000000000000341e+01,0.000000000000000000e+00,6.785095304737976285e+00,0.000000000000000000e+00,-1.000000009966953707e+00,0.000000000000000000e+00,6.180047793521476254e-10,0.000000000000000000e+00 +7.252561383277852158e+00,7.085000000000000853e+01,0.000000000000000000e+00,6.783621486073603712e+00,0.000000000000000000e+00,-1.000000009966042880e+00,0.000000000000000000e+00,-3.554789064693354279e-10,0.000000000000000000e+00 +7.254035522131343505e+00,7.085999999999999943e+01,0.000000000000000000e+00,6.782147347205421006e+00,0.000000000000000000e+00,-1.000000009966566905e+00,0.000000000000000000e+00,-2.885379561333853059e-10,0.000000000000000000e+00 +7.255509981397422870e+00,7.087000000000000455e+01,0.000000000000000000e+00,6.780672887924646730e+00,0.000000000000000000e+00,-1.000000009966992343e+00,0.000000000000000000e+00,1.597454154309130326e-10,0.000000000000000000e+00 +7.256984761285095509e+00,7.087999999999999545e+01,0.000000000000000000e+00,6.779198108022274738e+00,0.000000000000000000e+00,-1.000000009966756753e+00,0.000000000000000000e+00,3.314636173060725163e-10,0.000000000000000000e+00 +7.258459862003595831e+00,7.089000000000000057e+01,0.000000000000000000e+00,6.777723007289072399e+00,0.000000000000000000e+00,-1.000000009966267811e+00,0.000000000000000000e+00,-4.295146785527450631e-10,0.000000000000000000e+00 +7.259935283762384728e+00,7.090000000000000568e+01,0.000000000000000000e+00,6.776247585515578820e+00,0.000000000000000000e+00,-1.000000009966901526e+00,0.000000000000000000e+00,4.844906081960012613e-10,0.000000000000000000e+00 +7.261411026771152244e+00,7.090999999999999659e+01,0.000000000000000000e+00,6.774771842492103069e+00,0.000000000000000000e+00,-1.000000009966186543e+00,0.000000000000000000e+00,-4.373004568708381549e-10,0.000000000000000000e+00 +7.262887091239814907e+00,7.092000000000000171e+01,0.000000000000000000e+00,6.773295778008729506e+00,0.000000000000000000e+00,-1.000000009966832026e+00,0.000000000000000000e+00,2.267992467883042860e-10,0.000000000000000000e+00 +7.264363477378520173e+00,7.093000000000000682e+01,0.000000000000000000e+00,6.771819391855309789e+00,0.000000000000000000e+00,-1.000000009966497183e+00,0.000000000000000000e+00,-2.157731954735535443e-10,0.000000000000000000e+00 +7.265840185397641982e+00,7.093999999999999773e+01,0.000000000000000000e+00,6.770342683821469976e+00,0.000000000000000000e+00,-1.000000009966815817e+00,0.000000000000000000e+00,2.585707074270288954e-11,0.000000000000000000e+00 +7.267317215507786088e+00,7.095000000000000284e+01,0.000000000000000000e+00,6.768865653696604312e+00,0.000000000000000000e+00,-1.000000009966777625e+00,0.000000000000000000e+00,2.969908437334576133e-10,0.000000000000000000e+00 +7.268794567919787397e+00,7.096000000000000796e+01,0.000000000000000000e+00,6.767388301269878781e+00,0.000000000000000000e+00,-1.000000009966338865e+00,0.000000000000000000e+00,-4.605659219201680790e-10,0.000000000000000000e+00 +7.270272242844709965e+00,7.096999999999999886e+01,0.000000000000000000e+00,6.765910626330229327e+00,0.000000000000000000e+00,-1.000000009967019432e+00,0.000000000000000000e+00,3.542503458772534515e-10,0.000000000000000000e+00 +7.271750240493848771e+00,7.098000000000000398e+01,0.000000000000000000e+00,6.764432628666359193e+00,0.000000000000000000e+00,-1.000000009966495851e+00,0.000000000000000000e+00,-3.495167428126193306e-10,0.000000000000000000e+00 +7.273228561078729726e+00,7.098999999999999488e+01,0.000000000000000000e+00,6.762954308066744247e+00,0.000000000000000000e+00,-1.000000009967012549e+00,0.000000000000000000e+00,4.351861445601162743e-10,0.000000000000000000e+00 +7.274707204811110550e+00,7.100000000000000000e+01,0.000000000000000000e+00,6.761475664319625878e+00,0.000000000000000000e+00,-1.000000009966369063e+00,0.000000000000000000e+00,-3.798413457262983868e-10,0.000000000000000000e+00 +7.276186171902979005e+00,7.101000000000000512e+01,0.000000000000000000e+00,6.759996697213017214e+00,0.000000000000000000e+00,-1.000000009966930836e+00,0.000000000000000000e+00,2.110435239073616078e-10,0.000000000000000000e+00 +7.277665462566556442e+00,7.101999999999999602e+01,0.000000000000000000e+00,6.758517406534696015e+00,0.000000000000000000e+00,-1.000000009966618641e+00,0.000000000000000000e+00,-6.573032394068693184e-11,0.000000000000000000e+00 +7.279145077014295140e+00,7.103000000000000114e+01,0.000000000000000000e+00,6.757037792072210891e+00,0.000000000000000000e+00,-1.000000009966715897e+00,0.000000000000000000e+00,-2.352570418022554005e-10,0.000000000000000000e+00 +7.280625015458880078e+00,7.104000000000000625e+01,0.000000000000000000e+00,6.755557853612875974e+00,0.000000000000000000e+00,-1.000000009967064063e+00,0.000000000000000000e+00,2.712063595773823667e-10,0.000000000000000000e+00 +7.282105278113229829e+00,7.104999999999999716e+01,0.000000000000000000e+00,6.754077590943772691e+00,0.000000000000000000e+00,-1.000000009966662606e+00,0.000000000000000000e+00,-5.398943365130822025e-12,0.000000000000000000e+00 +7.283585865190495667e+00,7.106000000000000227e+01,0.000000000000000000e+00,6.752597003851750657e+00,0.000000000000000000e+00,-1.000000009966670600e+00,0.000000000000000000e+00,-8.996266403629272242e-11,0.000000000000000000e+00 +7.285066776904062458e+00,7.107000000000000739e+01,0.000000000000000000e+00,6.751116092123424117e+00,0.000000000000000000e+00,-1.000000009966803827e+00,0.000000000000000000e+00,1.812350126723587444e-10,0.000000000000000000e+00 +7.286548013467549545e+00,7.107999999999999829e+01,0.000000000000000000e+00,6.749634855545173728e+00,0.000000000000000000e+00,-1.000000009966535375e+00,0.000000000000000000e+00,-2.423430247903490009e-10,0.000000000000000000e+00 +7.288029575094810752e+00,7.109000000000000341e+01,0.000000000000000000e+00,6.748153293903146555e+00,0.000000000000000000e+00,-1.000000009966894421e+00,0.000000000000000000e+00,1.783085328220744800e-11,0.000000000000000000e+00 +7.289511461999934383e+00,7.110000000000000853e+01,0.000000000000000000e+00,6.746671406983253405e+00,0.000000000000000000e+00,-1.000000009966867998e+00,0.000000000000000000e+00,-8.733701384924766536e-11,0.000000000000000000e+00 +7.290993674397243218e+00,7.110999999999999943e+01,0.000000000000000000e+00,6.745189194571171498e+00,0.000000000000000000e+00,-1.000000009966997450e+00,0.000000000000000000e+00,1.168231638485453764e-11,0.000000000000000000e+00 +7.292476212501296295e+00,7.112000000000000455e+01,0.000000000000000000e+00,6.743706656452341797e+00,0.000000000000000000e+00,-1.000000009966980130e+00,0.000000000000000000e+00,4.796183987880032318e-10,0.000000000000000000e+00 +7.293959076526888907e+00,7.112999999999999545e+01,0.000000000000000000e+00,6.742223792411969896e+00,0.000000000000000000e+00,-1.000000009966268921e+00,0.000000000000000000e+00,-5.377491310541724979e-10,0.000000000000000000e+00 +7.295442266689050825e+00,7.114000000000000057e+01,0.000000000000000000e+00,6.740740602235026024e+00,0.000000000000000000e+00,-1.000000009967066505e+00,0.000000000000000000e+00,-4.684812112686483219e-11,0.000000000000000000e+00 +7.296925783203049853e+00,7.115000000000000568e+01,0.000000000000000000e+00,6.739257085706240602e+00,0.000000000000000000e+00,-1.000000009967136005e+00,0.000000000000000000e+00,5.012992518230931294e-10,0.000000000000000000e+00 +7.298409626284390050e+00,7.115999999999999659e+01,0.000000000000000000e+00,6.737773242610110458e+00,0.000000000000000000e+00,-1.000000009966392156e+00,0.000000000000000000e+00,-3.393123496451207136e-10,0.000000000000000000e+00 +7.299893796148813507e+00,7.117000000000000171e+01,0.000000000000000000e+00,6.736289072730895278e+00,0.000000000000000000e+00,-1.000000009966895753e+00,0.000000000000000000e+00,1.764992842062097531e-11,0.000000000000000000e+00 +7.301378293012298570e+00,7.118000000000000682e+01,0.000000000000000000e+00,6.734804575852614050e+00,0.000000000000000000e+00,-1.000000009966869552e+00,0.000000000000000000e+00,-2.774017124497562963e-10,0.000000000000000000e+00 +7.302863117091063394e+00,7.118999999999999773e+01,0.000000000000000000e+00,6.733319751759050398e+00,0.000000000000000000e+00,-1.000000009967281445e+00,0.000000000000000000e+00,5.542325780487810997e-10,0.000000000000000000e+00 +7.304348268601562388e+00,7.120000000000000284e+01,0.000000000000000000e+00,6.731834600233748134e+00,0.000000000000000000e+00,-1.000000009966458325e+00,0.000000000000000000e+00,-5.420027151636379217e-10,0.000000000000000000e+00 +7.305833747760490660e+00,7.121000000000000796e+01,0.000000000000000000e+00,6.730349121060014816e+00,0.000000000000000000e+00,-1.000000009967263459e+00,0.000000000000000000e+00,2.253612069082700546e-10,0.000000000000000000e+00 +7.307319554784781346e+00,7.121999999999999886e+01,0.000000000000000000e+00,6.728863314020914643e+00,0.000000000000000000e+00,-1.000000009966928616e+00,0.000000000000000000e+00,2.054398219714927494e-10,0.000000000000000000e+00 +7.308805689891607393e+00,7.123000000000000398e+01,0.000000000000000000e+00,6.727377178899276444e+00,0.000000000000000000e+00,-1.000000009966623304e+00,0.000000000000000000e+00,-4.320005420361085248e-10,0.000000000000000000e+00 +7.310292153298381557e+00,7.123999999999999488e+01,0.000000000000000000e+00,6.725890715477687465e+00,0.000000000000000000e+00,-1.000000009967265457e+00,0.000000000000000000e+00,4.907469295614070839e-10,0.000000000000000000e+00 +7.311778945222756398e+00,7.125000000000000000e+01,0.000000000000000000e+00,6.724403923538493366e+00,0.000000000000000000e+00,-1.000000009966535819e+00,0.000000000000000000e+00,-4.746620890323265831e-10,0.000000000000000000e+00 +7.313266065882626066e+00,7.126000000000000512e+01,0.000000000000000000e+00,6.722916802863802666e+00,0.000000000000000000e+00,-1.000000009967241699e+00,0.000000000000000000e+00,4.563451098417080434e-10,0.000000000000000000e+00 +7.314753515496124514e+00,7.126999999999999602e+01,0.000000000000000000e+00,6.721429353235478743e+00,0.000000000000000000e+00,-1.000000009966562908e+00,0.000000000000000000e+00,-5.629548276521006819e-10,0.000000000000000000e+00 +7.316241294281627283e+00,7.128000000000000114e+01,0.000000000000000000e+00,6.719941574435147835e+00,0.000000000000000000e+00,-1.000000009967400461e+00,0.000000000000000000e+00,2.493343836036639098e-10,0.000000000000000000e+00 +7.317729402457752386e+00,7.129000000000000625e+01,0.000000000000000000e+00,6.718453466244190153e+00,0.000000000000000000e+00,-1.000000009967029424e+00,0.000000000000000000e+00,2.537545583898596678e-10,0.000000000000000000e+00 +7.319217840243359419e+00,7.129999999999999716e+01,0.000000000000000000e+00,6.716965028443747876e+00,0.000000000000000000e+00,-1.000000009966651726e+00,0.000000000000000000e+00,-3.788323248931550868e-10,0.000000000000000000e+00 +7.320706607857550452e+00,7.131000000000000227e+01,0.000000000000000000e+00,6.715476260814718934e+00,0.000000000000000000e+00,-1.000000009967215719e+00,0.000000000000000000e+00,1.248080223681817761e-10,0.000000000000000000e+00 +7.322195705519670028e+00,7.132000000000000739e+01,0.000000000000000000e+00,6.713987163137757008e+00,0.000000000000000000e+00,-1.000000009967029868e+00,0.000000000000000000e+00,3.315549490694096449e-10,0.000000000000000000e+00 +7.323685133449306939e+00,7.132999999999999829e+01,0.000000000000000000e+00,6.712497735193275084e+00,0.000000000000000000e+00,-1.000000009966536041e+00,0.000000000000000000e+00,-3.876722633852682480e-10,0.000000000000000000e+00 +7.325174891866292448e+00,7.134000000000000341e+01,0.000000000000000000e+00,6.711007976761441896e+00,0.000000000000000000e+00,-1.000000009967113579e+00,0.000000000000000000e+00,-2.607750450985274012e-10,0.000000000000000000e+00 +7.326664980990702070e+00,7.135000000000000853e+01,0.000000000000000000e+00,6.709517887622180154e+00,0.000000000000000000e+00,-1.000000009967502157e+00,0.000000000000000000e+00,4.816562999706009967e-10,0.000000000000000000e+00 +7.328155401042856454e+00,7.135999999999999943e+01,0.000000000000000000e+00,6.708027467555170098e+00,0.000000000000000000e+00,-1.000000009966784287e+00,0.000000000000000000e+00,1.266059112530614177e-11,0.000000000000000000e+00 +7.329646152243319612e+00,7.137000000000000455e+01,0.000000000000000000e+00,6.706536716339848603e+00,0.000000000000000000e+00,-1.000000009966765413e+00,0.000000000000000000e+00,-2.964898238529442738e-10,0.000000000000000000e+00 +7.331137234812902470e+00,7.137999999999999545e+01,0.000000000000000000e+00,6.705045633755404744e+00,0.000000000000000000e+00,-1.000000009967207504e+00,0.000000000000000000e+00,1.252096954560032537e-10,0.000000000000000000e+00 +7.332628648972659313e+00,7.139000000000000057e+01,0.000000000000000000e+00,6.703554219580782458e+00,0.000000000000000000e+00,-1.000000009967020764e+00,0.000000000000000000e+00,-1.476580143894098665e-10,0.000000000000000000e+00 +7.334120394943892229e+00,7.140000000000000568e+01,0.000000000000000000e+00,6.702062473594681435e+00,0.000000000000000000e+00,-1.000000009967241033e+00,0.000000000000000000e+00,2.552188936236738377e-10,0.000000000000000000e+00 +7.335612472948148444e+00,7.140999999999999659e+01,0.000000000000000000e+00,6.700570395575553562e+00,0.000000000000000000e+00,-1.000000009966860226e+00,0.000000000000000000e+00,-8.986466057797924610e-11,0.000000000000000000e+00 +7.337104883207222095e+00,7.142000000000000171e+01,0.000000000000000000e+00,6.699077985301605587e+00,0.000000000000000000e+00,-1.000000009966994341e+00,0.000000000000000000e+00,-2.110754162819134923e-10,0.000000000000000000e+00 +7.338597625943154235e+00,7.143000000000000682e+01,0.000000000000000000e+00,6.697585242550795570e+00,0.000000000000000000e+00,-1.000000009967309422e+00,0.000000000000000000e+00,6.379927850584480236e-11,0.000000000000000000e+00 +7.340090701378232829e+00,7.143999999999999773e+01,0.000000000000000000e+00,6.696092167100834658e+00,0.000000000000000000e+00,-1.000000009967214165e+00,0.000000000000000000e+00,1.113636523699340581e-10,0.000000000000000000e+00 +7.341584109734995423e+00,7.145000000000000284e+01,0.000000000000000000e+00,6.694598758729187082e+00,0.000000000000000000e+00,-1.000000009967047854e+00,0.000000000000000000e+00,1.061360669070729976e-10,0.000000000000000000e+00 +7.343077851236225584e+00,7.146000000000000796e+01,0.000000000000000000e+00,6.693105017213068386e+00,0.000000000000000000e+00,-1.000000009966889314e+00,0.000000000000000000e+00,-1.765567416811358862e-10,0.000000000000000000e+00 +7.344571926104957349e+00,7.146999999999999886e+01,0.000000000000000000e+00,6.691610942329445422e+00,0.000000000000000000e+00,-1.000000009967153103e+00,0.000000000000000000e+00,-1.632933882693712405e-10,0.000000000000000000e+00 +7.346066334564472555e+00,7.148000000000000398e+01,0.000000000000000000e+00,6.690116533855035463e+00,0.000000000000000000e+00,-1.000000009967397130e+00,0.000000000000000000e+00,3.192348703441199295e-10,0.000000000000000000e+00 +7.347561076838302618e+00,7.148999999999999488e+01,0.000000000000000000e+00,6.688621791566307095e+00,0.000000000000000000e+00,-1.000000009966919956e+00,0.000000000000000000e+00,-1.437646866938854267e-10,0.000000000000000000e+00 +7.349056153150228532e+00,7.150000000000000000e+01,0.000000000000000000e+00,6.687126715239480212e+00,0.000000000000000000e+00,-1.000000009967134895e+00,0.000000000000000000e+00,-1.847141469503801985e-10,0.000000000000000000e+00 +7.350551563724281756e+00,7.151000000000000512e+01,0.000000000000000000e+00,6.685631304650522466e+00,0.000000000000000000e+00,-1.000000009967411119e+00,0.000000000000000000e+00,3.717208937735729518e-10,0.000000000000000000e+00 +7.352047308784743329e+00,7.151999999999999602e+01,0.000000000000000000e+00,6.684135559575151930e+00,0.000000000000000000e+00,-1.000000009966855119e+00,0.000000000000000000e+00,-2.842197498817181869e-10,0.000000000000000000e+00 +7.353543388556146532e+00,7.153000000000000114e+01,0.000000000000000000e+00,6.682639479788837100e+00,0.000000000000000000e+00,-1.000000009967280334e+00,0.000000000000000000e+00,8.606295450247548733e-12,0.000000000000000000e+00 +7.355039803263275999e+00,7.154000000000000625e+01,0.000000000000000000e+00,6.681143065066792452e+00,0.000000000000000000e+00,-1.000000009967267456e+00,0.000000000000000000e+00,2.354333182688295090e-10,0.000000000000000000e+00 +7.356536553131166833e+00,7.154999999999999716e+01,0.000000000000000000e+00,6.679646315183982885e+00,0.000000000000000000e+00,-1.000000009966915071e+00,0.000000000000000000e+00,-2.195105552099073592e-10,0.000000000000000000e+00 +7.358033638385107267e+00,7.156000000000000227e+01,0.000000000000000000e+00,6.678149229915121055e+00,0.000000000000000000e+00,-1.000000009967243697e+00,0.000000000000000000e+00,9.490220847276191998e-12,0.000000000000000000e+00 +7.359531059250637774e+00,7.157000000000000739e+01,0.000000000000000000e+00,6.676651809034665597e+00,0.000000000000000000e+00,-1.000000009967229486e+00,0.000000000000000000e+00,-8.895087078954587076e-11,0.000000000000000000e+00 +7.361028815953551074e+00,7.157999999999999829e+01,0.000000000000000000e+00,6.675154052316823794e+00,0.000000000000000000e+00,-1.000000009967362713e+00,0.000000000000000000e+00,5.869440499667227466e-11,0.000000000000000000e+00 +7.362526908719893903e+00,7.159000000000000341e+01,0.000000000000000000e+00,6.673655959535548909e+00,0.000000000000000000e+00,-1.000000009967274783e+00,0.000000000000000000e+00,-1.616697587326251040e-10,0.000000000000000000e+00 +7.364025337775966129e+00,7.160000000000000853e+01,0.000000000000000000e+00,6.672157530464541075e+00,0.000000000000000000e+00,-1.000000009967517034e+00,0.000000000000000000e+00,2.189681509451666818e-10,0.000000000000000000e+00 +7.365524103348322527e+00,7.160999999999999943e+01,0.000000000000000000e+00,6.670658764877245517e+00,0.000000000000000000e+00,-1.000000009967188852e+00,0.000000000000000000e+00,1.928501294627998514e-10,0.000000000000000000e+00 +7.367023205663771890e+00,7.162000000000000455e+01,0.000000000000000000e+00,6.669159662546854328e+00,0.000000000000000000e+00,-1.000000009966899750e+00,0.000000000000000000e+00,-4.566944244842496476e-10,0.000000000000000000e+00 +7.368522644949377920e+00,7.162999999999999545e+01,0.000000000000000000e+00,6.667660223246303808e+00,0.000000000000000000e+00,-1.000000009967584536e+00,0.000000000000000000e+00,4.247606084749310518e-10,0.000000000000000000e+00 +7.370022421432459225e+00,7.164000000000000057e+01,0.000000000000000000e+00,6.666160446748273571e+00,0.000000000000000000e+00,-1.000000009966947490e+00,0.000000000000000000e+00,-1.440219968770433177e-10,0.000000000000000000e+00 +7.371522535340590210e+00,7.165000000000000568e+01,0.000000000000000000e+00,6.664660332825190991e+00,0.000000000000000000e+00,-1.000000009967163539e+00,0.000000000000000000e+00,-4.029636643539501372e-10,0.000000000000000000e+00 +7.373022986901601961e+00,7.165999999999999659e+01,0.000000000000000000e+00,6.663159881249224092e+00,0.000000000000000000e+00,-1.000000009967768166e+00,0.000000000000000000e+00,6.151838768671929708e-10,0.000000000000000000e+00 +7.374523776343581360e+00,7.167000000000000171e+01,0.000000000000000000e+00,6.661659091792285103e+00,0.000000000000000000e+00,-1.000000009966844905e+00,0.000000000000000000e+00,-4.588433300587373056e-10,0.000000000000000000e+00 +7.376024903894872864e+00,7.168000000000000682e+01,0.000000000000000000e+00,6.660157964226032234e+00,0.000000000000000000e+00,-1.000000009967533687e+00,0.000000000000000000e+00,1.038154205021218728e-10,0.000000000000000000e+00 +7.377526369784077609e+00,7.168999999999999773e+01,0.000000000000000000e+00,6.658656498321861683e+00,0.000000000000000000e+00,-1.000000009967377812e+00,0.000000000000000000e+00,1.188729076207101570e-10,0.000000000000000000e+00 +7.379028174240054305e+00,7.170000000000000284e+01,0.000000000000000000e+00,6.657154693850915628e+00,0.000000000000000000e+00,-1.000000009967199288e+00,0.000000000000000000e+00,-2.329620007459408332e-10,0.000000000000000000e+00 +7.380530317491921011e+00,7.171000000000000796e+01,0.000000000000000000e+00,6.655652550584076899e+00,0.000000000000000000e+00,-1.000000009967549230e+00,0.000000000000000000e+00,4.108427840293356546e-10,0.000000000000000000e+00 +7.382032799769052467e+00,7.171999999999999886e+01,0.000000000000000000e+00,6.654150068291968978e+00,0.000000000000000000e+00,-1.000000009966931946e+00,0.000000000000000000e+00,-5.231891673634217203e-10,0.000000000000000000e+00 +7.383535621301084539e+00,7.173000000000000398e+01,0.000000000000000000e+00,6.652647246744958665e+00,0.000000000000000000e+00,-1.000000009967718206e+00,0.000000000000000000e+00,2.939597014922072454e-10,0.000000000000000000e+00 +7.385038782317910666e+00,7.173999999999999488e+01,0.000000000000000000e+00,6.651144085713149856e+00,0.000000000000000000e+00,-1.000000009967276338e+00,0.000000000000000000e+00,-1.023457507942463032e-10,0.000000000000000000e+00 +7.386542283049683633e+00,7.175000000000000000e+01,0.000000000000000000e+00,6.649640584966390655e+00,0.000000000000000000e+00,-1.000000009967430215e+00,0.000000000000000000e+00,4.311429104420363592e-11,0.000000000000000000e+00 +7.388046123726818237e+00,7.176000000000000512e+01,0.000000000000000000e+00,6.648136744274266263e+00,0.000000000000000000e+00,-1.000000009967365378e+00,0.000000000000000000e+00,1.269517291308168510e-10,0.000000000000000000e+00 +7.389550304579989515e+00,7.176999999999999602e+01,0.000000000000000000e+00,6.646632563406102534e+00,0.000000000000000000e+00,-1.000000009967174419e+00,0.000000000000000000e+00,-6.080497474688226284e-11,0.000000000000000000e+00 +7.391054825840131848e+00,7.178000000000000114e+01,0.000000000000000000e+00,6.645128042130964197e+00,0.000000000000000000e+00,-1.000000009967265902e+00,0.000000000000000000e+00,-3.364173814203974020e-10,0.000000000000000000e+00 +7.392559687738442520e+00,7.179000000000000625e+01,0.000000000000000000e+00,6.643623180217653967e+00,0.000000000000000000e+00,-1.000000009967772163e+00,0.000000000000000000e+00,2.675977761360487162e-10,0.000000000000000000e+00 +7.394064890506380827e+00,7.179999999999999716e+01,0.000000000000000000e+00,6.642117977434712550e+00,0.000000000000000000e+00,-1.000000009967369374e+00,0.000000000000000000e+00,-2.610478238031941225e-11,0.000000000000000000e+00 +7.395570434375666302e+00,7.181000000000000227e+01,0.000000000000000000e+00,6.640612433550420413e+00,0.000000000000000000e+00,-1.000000009967408676e+00,0.000000000000000000e+00,1.431751311504183263e-10,0.000000000000000000e+00 +7.397076319578283154e+00,7.182000000000000739e+01,0.000000000000000000e+00,6.639106548332793345e+00,0.000000000000000000e+00,-1.000000009967193071e+00,0.000000000000000000e+00,-2.159670463199324123e-10,0.000000000000000000e+00 +7.398582546346478495e+00,7.182999999999999829e+01,0.000000000000000000e+00,6.637600321549585125e+00,0.000000000000000000e+00,-1.000000009967518366e+00,0.000000000000000000e+00,-1.355935873764839177e-10,0.000000000000000000e+00 +7.400089114912762334e+00,7.184000000000000341e+01,0.000000000000000000e+00,6.636093752968284853e+00,0.000000000000000000e+00,-1.000000009967722647e+00,0.000000000000000000e+00,1.775578122826089792e-10,0.000000000000000000e+00 +7.401596025509907584e+00,7.185000000000000853e+01,0.000000000000000000e+00,6.634586842356118730e+00,0.000000000000000000e+00,-1.000000009967455084e+00,0.000000000000000000e+00,1.258090778971016017e-10,0.000000000000000000e+00 +7.403103278370953610e+00,7.185999999999999943e+01,0.000000000000000000e+00,6.633079589480049165e+00,0.000000000000000000e+00,-1.000000009967265457e+00,0.000000000000000000e+00,-1.047188910723376692e-10,0.000000000000000000e+00 +7.404610873729203568e+00,7.187000000000000455e+01,0.000000000000000000e+00,6.631571994106773005e+00,0.000000000000000000e+00,-1.000000009967423331e+00,0.000000000000000000e+00,6.243420281884563719e-11,0.000000000000000000e+00 +7.406118811818224401e+00,7.187999999999999545e+01,0.000000000000000000e+00,6.630064056002721529e+00,0.000000000000000000e+00,-1.000000009967329184e+00,0.000000000000000000e+00,-3.584733837850656927e-10,0.000000000000000000e+00 +7.407627092871851282e+00,7.189000000000000057e+01,0.000000000000000000e+00,6.628555774934061340e+00,0.000000000000000000e+00,-1.000000009967869863e+00,0.000000000000000000e+00,3.804693599774766712e-10,0.000000000000000000e+00 +7.409135717124183174e+00,7.190000000000000568e+01,0.000000000000000000e+00,6.627047150666691699e+00,0.000000000000000000e+00,-1.000000009967295878e+00,0.000000000000000000e+00,-2.667829620363873383e-10,0.000000000000000000e+00 +7.410644684809586380e+00,7.190999999999999659e+01,0.000000000000000000e+00,6.625538182966248080e+00,0.000000000000000000e+00,-1.000000009967698444e+00,0.000000000000000000e+00,2.284719257816055265e-10,0.000000000000000000e+00 +7.412153996162694547e+00,7.192000000000000171e+01,0.000000000000000000e+00,6.624028871598095947e+00,0.000000000000000000e+00,-1.000000009967353609e+00,0.000000000000000000e+00,1.028110081790394100e-10,0.000000000000000000e+00 +7.413663651418406886e+00,7.193000000000000682e+01,0.000000000000000000e+00,6.622519216327336089e+00,0.000000000000000000e+00,-1.000000009967198400e+00,0.000000000000000000e+00,-4.551180981978287755e-10,0.000000000000000000e+00 +7.415173650811892614e+00,7.193999999999999773e+01,0.000000000000000000e+00,6.621009216918800178e+00,0.000000000000000000e+00,-1.000000009967885628e+00,0.000000000000000000e+00,3.000595285958256733e-10,0.000000000000000000e+00 +7.416683994578587402e+00,7.195000000000000284e+01,0.000000000000000000e+00,6.619498873137050765e+00,0.000000000000000000e+00,-1.000000009967432435e+00,0.000000000000000000e+00,-1.694707085936779484e-10,0.000000000000000000e+00 +7.418194682954196040e+00,7.196000000000000796e+01,0.000000000000000000e+00,6.617988184746384839e+00,0.000000000000000000e+00,-1.000000009967688452e+00,0.000000000000000000e+00,2.711206415119588751e-10,0.000000000000000000e+00 +7.419705716174691545e+00,7.196999999999999886e+01,0.000000000000000000e+00,6.616477151510827603e+00,0.000000000000000000e+00,-1.000000009967278780e+00,0.000000000000000000e+00,-1.350151657639397952e-10,0.000000000000000000e+00 +7.421217094476317833e+00,7.198000000000000398e+01,0.000000000000000000e+00,6.614965773194136922e+00,0.000000000000000000e+00,-1.000000009967482839e+00,0.000000000000000000e+00,-3.157957542658217559e-11,0.000000000000000000e+00 +7.422728818095587933e+00,7.198999999999999488e+01,0.000000000000000000e+00,6.613454049559798875e+00,0.000000000000000000e+00,-1.000000009967530579e+00,0.000000000000000000e+00,-7.195560778959333657e-12,0.000000000000000000e+00 +7.424240887269284883e+00,7.200000000000000000e+01,0.000000000000000000e+00,6.611941980371030425e+00,0.000000000000000000e+00,-1.000000009967541459e+00,0.000000000000000000e+00,-2.603022937463581076e-10,0.000000000000000000e+00 +7.425753302234462616e+00,7.201000000000000512e+01,0.000000000000000000e+00,6.610429565390777640e+00,0.000000000000000000e+00,-1.000000009967935144e+00,0.000000000000000000e+00,1.751097593929706322e-10,0.000000000000000000e+00 +7.427266063228445958e+00,7.201999999999999602e+01,0.000000000000000000e+00,6.608916804381714805e+00,0.000000000000000000e+00,-1.000000009967670245e+00,0.000000000000000000e+00,3.246053197634680306e-10,0.000000000000000000e+00 +7.428779170488832406e+00,7.203000000000000114e+01,0.000000000000000000e+00,6.607403697106246199e+00,0.000000000000000000e+00,-1.000000009967179082e+00,0.000000000000000000e+00,-3.962740665804702985e-10,0.000000000000000000e+00 +7.430292624253490352e+00,7.204000000000000625e+01,0.000000000000000000e+00,6.605890243326503430e+00,0.000000000000000000e+00,-1.000000009967778825e+00,0.000000000000000000e+00,1.421331418290568150e-10,0.000000000000000000e+00 +7.431806424760560859e+00,7.204999999999999716e+01,0.000000000000000000e+00,6.604376442804343661e+00,0.000000000000000000e+00,-1.000000009967563663e+00,0.000000000000000000e+00,-1.954799388638892690e-10,0.000000000000000000e+00 +7.433320572248458546e+00,7.206000000000000227e+01,0.000000000000000000e+00,6.602862295301354045e+00,0.000000000000000000e+00,-1.000000009967859649e+00,0.000000000000000000e+00,3.325182725998015256e-10,0.000000000000000000e+00 +7.434835066955869820e+00,7.207000000000000739e+01,0.000000000000000000e+00,6.601347800578846403e+00,0.000000000000000000e+00,-1.000000009967356052e+00,0.000000000000000000e+00,-4.057316862927039682e-10,0.000000000000000000e+00 +7.436349909121756419e+00,7.207999999999999829e+01,0.000000000000000000e+00,6.599832958397860772e+00,0.000000000000000000e+00,-1.000000009967970671e+00,0.000000000000000000e+00,4.915143790299764231e-10,0.000000000000000000e+00 +7.437865098985353640e+00,7.209000000000000341e+01,0.000000000000000000e+00,6.598317768519160076e+00,0.000000000000000000e+00,-1.000000009967225933e+00,0.000000000000000000e+00,-2.657729243814301040e-10,0.000000000000000000e+00 +7.439380636786171230e+00,7.210000000000000853e+01,0.000000000000000000e+00,6.596802230703236347e+00,0.000000000000000000e+00,-1.000000009967628722e+00,0.000000000000000000e+00,-1.636164113460018200e-10,0.000000000000000000e+00 +7.440896522763995158e+00,7.210999999999999943e+01,0.000000000000000000e+00,6.595286344710302728e+00,0.000000000000000000e+00,-1.000000009967876746e+00,0.000000000000000000e+00,2.165918223401627534e-10,0.000000000000000000e+00 +7.442412757158885839e+00,7.212000000000000455e+01,0.000000000000000000e+00,6.593770110300298803e+00,0.000000000000000000e+00,-1.000000009967548342e+00,0.000000000000000000e+00,-9.048206468888119347e-11,0.000000000000000000e+00 +7.443929340211179024e+00,7.212999999999999545e+01,0.000000000000000000e+00,6.592253527232888821e+00,0.000000000000000000e+00,-1.000000009967685566e+00,0.000000000000000000e+00,-1.185657207316257375e-10,0.000000000000000000e+00 +7.445446272161488466e+00,7.214000000000000057e+01,0.000000000000000000e+00,6.590736595267459030e+00,0.000000000000000000e+00,-1.000000009967865422e+00,0.000000000000000000e+00,-5.970825014121324107e-11,0.000000000000000000e+00 +7.446963553250704138e+00,7.215000000000000568e+01,0.000000000000000000e+00,6.589219314163119456e+00,0.000000000000000000e+00,-1.000000009967956016e+00,0.000000000000000000e+00,2.797448346010230163e-10,0.000000000000000000e+00 +7.448481183719993126e+00,7.215999999999999659e+01,0.000000000000000000e+00,6.587701683678703013e+00,0.000000000000000000e+00,-1.000000009967531467e+00,0.000000000000000000e+00,-6.275255920003361116e-11,0.000000000000000000e+00 +7.449999163810800518e+00,7.217000000000000171e+01,0.000000000000000000e+00,6.586183703572765502e+00,0.000000000000000000e+00,-1.000000009967626724e+00,0.000000000000000000e+00,-1.199189777907265387e-10,0.000000000000000000e+00 +7.451517493764848510e+00,7.218000000000000682e+01,0.000000000000000000e+00,6.584665373603582950e+00,0.000000000000000000e+00,-1.000000009967808801e+00,0.000000000000000000e+00,-8.333909702238444651e-11,0.000000000000000000e+00 +7.453036173824139965e+00,7.218999999999999773e+01,0.000000000000000000e+00,6.583146693529153382e+00,0.000000000000000000e+00,-1.000000009967935366e+00,0.000000000000000000e+00,2.429432167582280114e-10,0.000000000000000000e+00 +7.454555204230955745e+00,7.220000000000000284e+01,0.000000000000000000e+00,6.581627663107195936e+00,0.000000000000000000e+00,-1.000000009967566328e+00,0.000000000000000000e+00,-1.002530631153749905e-10,0.000000000000000000e+00 +7.456074585227856488e+00,7.221000000000000796e+01,0.000000000000000000e+00,6.580108282095150862e+00,0.000000000000000000e+00,-1.000000009967718650e+00,0.000000000000000000e+00,-1.466921854037191213e-10,0.000000000000000000e+00 +7.457594317057682609e+00,7.221999999999999886e+01,0.000000000000000000e+00,6.578588550250176858e+00,0.000000000000000000e+00,-1.000000009967941583e+00,0.000000000000000000e+00,2.994517195989501604e-10,0.000000000000000000e+00 +7.459114399963554298e+00,7.223000000000000398e+01,0.000000000000000000e+00,6.577068467329152845e+00,0.000000000000000000e+00,-1.000000009967486392e+00,0.000000000000000000e+00,-1.029583811422052865e-10,0.000000000000000000e+00 +7.460634834188874187e+00,7.223999999999999488e+01,0.000000000000000000e+00,6.575548033088677968e+00,0.000000000000000000e+00,-1.000000009967642933e+00,0.000000000000000000e+00,-3.869172157707767126e-10,0.000000000000000000e+00 +7.462155619977325571e+00,7.225000000000000000e+01,0.000000000000000000e+00,6.574027247285068043e+00,0.000000000000000000e+00,-1.000000009968231351e+00,0.000000000000000000e+00,4.114971210466357834e-10,0.000000000000000000e+00 +7.463676757572873299e+00,7.226000000000000512e+01,0.000000000000000000e+00,6.572506109674357333e+00,0.000000000000000000e+00,-1.000000009967605408e+00,0.000000000000000000e+00,-1.968716465839006112e-10,0.000000000000000000e+00 +7.465198247219764660e+00,7.226999999999999602e+01,0.000000000000000000e+00,6.570984620012300326e+00,0.000000000000000000e+00,-1.000000009967904946e+00,0.000000000000000000e+00,2.890381385843713748e-10,0.000000000000000000e+00 +7.466720089162530272e+00,7.228000000000000114e+01,0.000000000000000000e+00,6.569462778054365515e+00,0.000000000000000000e+00,-1.000000009967465076e+00,0.000000000000000000e+00,-2.345611737533430468e-10,0.000000000000000000e+00 +7.468242283645982305e+00,7.229000000000000625e+01,0.000000000000000000e+00,6.567940583555740730e+00,0.000000000000000000e+00,-1.000000009967822123e+00,0.000000000000000000e+00,-3.441766822030245068e-11,0.000000000000000000e+00 +7.469764830915218923e+00,7.229999999999999716e+01,0.000000000000000000e+00,6.566418036271327807e+00,0.000000000000000000e+00,-1.000000009967874526e+00,0.000000000000000000e+00,-6.211240596191348854e-11,0.000000000000000000e+00 +7.471287731215620731e+00,7.231000000000000227e+01,0.000000000000000000e+00,6.564895135955746142e+00,0.000000000000000000e+00,-1.000000009967969117e+00,0.000000000000000000e+00,2.648640076603834127e-10,0.000000000000000000e+00 +7.472810984792853439e+00,7.232000000000000739e+01,0.000000000000000000e+00,6.563371882363330023e+00,0.000000000000000000e+00,-1.000000009967565662e+00,0.000000000000000000e+00,-3.847433875811921213e-10,0.000000000000000000e+00 +7.474334591892866975e+00,7.232999999999999829e+01,0.000000000000000000e+00,6.561848275248129525e+00,0.000000000000000000e+00,-1.000000009968151859e+00,0.000000000000000000e+00,1.025744197530250202e-10,0.000000000000000000e+00 +7.475858552761898146e+00,7.234000000000000341e+01,0.000000000000000000e+00,6.560324314363906950e+00,0.000000000000000000e+00,-1.000000009967995540e+00,0.000000000000000000e+00,3.957812114069699761e-10,0.000000000000000000e+00 +7.477382867646469755e+00,7.235000000000000853e+01,0.000000000000000000e+00,6.558799999464141273e+00,0.000000000000000000e+00,-1.000000009967392245e+00,0.000000000000000000e+00,-4.498653271754967231e-10,0.000000000000000000e+00 +7.478907536793389710e+00,7.235999999999999943e+01,0.000000000000000000e+00,6.557275330302024585e+00,0.000000000000000000e+00,-1.000000009968078141e+00,0.000000000000000000e+00,5.911390897012362358e-11,0.000000000000000000e+00 +7.480432560449753687e+00,7.237000000000000455e+01,0.000000000000000000e+00,6.555750306630459434e+00,0.000000000000000000e+00,-1.000000009967987991e+00,0.000000000000000000e+00,2.134010734682390792e-10,0.000000000000000000e+00 +7.481957938862944246e+00,7.237999999999999545e+01,0.000000000000000000e+00,6.554224928202064149e+00,0.000000000000000000e+00,-1.000000009967662473e+00,0.000000000000000000e+00,-1.664897845779647325e-10,0.000000000000000000e+00 +7.483483672280631716e+00,7.239000000000000057e+01,0.000000000000000000e+00,6.552699194769168400e+00,0.000000000000000000e+00,-1.000000009967916492e+00,0.000000000000000000e+00,-1.150898279581016777e-10,0.000000000000000000e+00 +7.485009760950775970e+00,7.240000000000000568e+01,0.000000000000000000e+00,6.551173106083812314e+00,0.000000000000000000e+00,-1.000000009968092129e+00,0.000000000000000000e+00,1.876501910935272761e-10,0.000000000000000000e+00 +7.486536205121624654e+00,7.240999999999999659e+01,0.000000000000000000e+00,6.549646661897748245e+00,0.000000000000000000e+00,-1.000000009967805692e+00,0.000000000000000000e+00,-1.990955462746861218e-10,0.000000000000000000e+00 +7.488063005041714071e+00,7.242000000000000171e+01,0.000000000000000000e+00,6.548119861962439892e+00,0.000000000000000000e+00,-1.000000009968109671e+00,0.000000000000000000e+00,7.124475969980882644e-11,0.000000000000000000e+00 +7.489590160959871845e+00,7.243000000000000682e+01,0.000000000000000000e+00,6.546592706029059627e+00,0.000000000000000000e+00,-1.000000009968000869e+00,0.000000000000000000e+00,5.858151431791716314e-11,0.000000000000000000e+00 +7.491117673125214260e+00,7.243999999999999773e+01,0.000000000000000000e+00,6.545065193848491170e+00,0.000000000000000000e+00,-1.000000009967911385e+00,0.000000000000000000e+00,-3.313515826602788750e-11,0.000000000000000000e+00 +7.492645541787148922e+00,7.245000000000000284e+01,0.000000000000000000e+00,6.543537325171326913e+00,0.000000000000000000e+00,-1.000000009967962011e+00,0.000000000000000000e+00,1.452957160179863171e-13,0.000000000000000000e+00 +7.494173767195374758e+00,7.246000000000000796e+01,0.000000000000000000e+00,6.542009099747867928e+00,0.000000000000000000e+00,-1.000000009967961789e+00,0.000000000000000000e+00,-1.757667569423064719e-11,0.000000000000000000e+00 +7.495702349599882020e+00,7.246999999999999886e+01,0.000000000000000000e+00,6.540480517328123966e+00,0.000000000000000000e+00,-1.000000009967988657e+00,0.000000000000000000e+00,1.177797792529380159e-10,0.000000000000000000e+00 +7.497231289250953168e+00,7.248000000000000398e+01,0.000000000000000000e+00,6.538951577661812564e+00,0.000000000000000000e+00,-1.000000009967808579e+00,0.000000000000000000e+00,-1.485333514838601317e-10,0.000000000000000000e+00 +7.498760586399162875e+00,7.248999999999999488e+01,0.000000000000000000e+00,6.537422280498359051e+00,0.000000000000000000e+00,-1.000000009968035730e+00,0.000000000000000000e+00,1.486437731841387959e-10,0.000000000000000000e+00 +7.500290241295379801e+00,7.250000000000000000e+01,0.000000000000000000e+00,6.535892625586894766e+00,0.000000000000000000e+00,-1.000000009967808356e+00,0.000000000000000000e+00,-3.037486543478656073e-10,0.000000000000000000e+00 +7.501820254190764814e+00,7.251000000000000512e+01,0.000000000000000000e+00,6.534362612676258841e+00,0.000000000000000000e+00,-1.000000009968273096e+00,0.000000000000000000e+00,2.177830867117661511e-10,0.000000000000000000e+00 +7.503350625336773660e+00,7.251999999999999602e+01,0.000000000000000000e+00,6.532832241514994642e+00,0.000000000000000000e+00,-1.000000009967939807e+00,0.000000000000000000e+00,2.291916643491751702e-11,0.000000000000000000e+00 +7.504881354985156960e+00,7.253000000000000114e+01,0.000000000000000000e+00,6.531301511851353325e+00,0.000000000000000000e+00,-1.000000009967904724e+00,0.000000000000000000e+00,7.715278203656960630e-11,0.000000000000000000e+00 +7.506412443387959321e+00,7.254000000000000625e+01,0.000000000000000000e+00,6.529770423433289395e+00,0.000000000000000000e+00,-1.000000009967786596e+00,0.000000000000000000e+00,-1.705082745652741504e-10,0.000000000000000000e+00 +7.507943890797521114e+00,7.254999999999999716e+01,0.000000000000000000e+00,6.528238976008462480e+00,0.000000000000000000e+00,-1.000000009968047721e+00,0.000000000000000000e+00,-1.342292786206974824e-10,0.000000000000000000e+00 +7.509475697466478472e+00,7.256000000000000227e+01,0.000000000000000000e+00,6.526707169324235558e+00,0.000000000000000000e+00,-1.000000009968253334e+00,0.000000000000000000e+00,1.492696718320188204e-11,0.000000000000000000e+00 +7.511007863647765070e+00,7.257000000000000739e+01,0.000000000000000000e+00,6.525175003127675843e+00,0.000000000000000000e+00,-1.000000009968230463e+00,0.000000000000000000e+00,1.067824490453860725e-10,0.000000000000000000e+00 +7.512540389594610346e+00,7.257999999999999829e+01,0.000000000000000000e+00,6.523642477165553899e+00,0.000000000000000000e+00,-1.000000009968066816e+00,0.000000000000000000e+00,-2.897079233028755710e-11,0.000000000000000000e+00 +7.514073275560541276e+00,7.259000000000000341e+01,0.000000000000000000e+00,6.522109591184342747e+00,0.000000000000000000e+00,-1.000000009968111225e+00,0.000000000000000000e+00,1.949276187070775296e-10,0.000000000000000000e+00 +7.515606521799383266e+00,7.260000000000000853e+01,0.000000000000000000e+00,6.520576344930216983e+00,0.000000000000000000e+00,-1.000000009967812353e+00,0.000000000000000000e+00,-1.466680962772650561e-10,0.000000000000000000e+00 +7.517140128565260149e+00,7.260999999999999943e+01,0.000000000000000000e+00,6.519042738149053662e+00,0.000000000000000000e+00,-1.000000009968037284e+00,0.000000000000000000e+00,-8.800911077232741462e-11,0.000000000000000000e+00 +7.518674096112593297e+00,7.262000000000000455e+01,0.000000000000000000e+00,6.517508770586429634e+00,0.000000000000000000e+00,-1.000000009968172288e+00,0.000000000000000000e+00,2.020260013444165370e-10,0.000000000000000000e+00 +7.520208424696105176e+00,7.262999999999999545e+01,0.000000000000000000e+00,6.515974441987623322e+00,0.000000000000000000e+00,-1.000000009967862313e+00,0.000000000000000000e+00,-1.982166649821658007e-10,0.000000000000000000e+00 +7.521743114570816680e+00,7.264000000000000057e+01,0.000000000000000000e+00,6.514439752097613834e+00,0.000000000000000000e+00,-1.000000009968166514e+00,0.000000000000000000e+00,5.352035943931004005e-11,0.000000000000000000e+00 +7.523278165992050681e+00,7.265000000000000568e+01,0.000000000000000000e+00,6.512904700661078294e+00,0.000000000000000000e+00,-1.000000009968084358e+00,0.000000000000000000e+00,3.644311484955124056e-11,0.000000000000000000e+00 +7.524813579215429371e+00,7.265999999999999659e+01,0.000000000000000000e+00,6.511369287422394514e+00,0.000000000000000000e+00,-1.000000009968028403e+00,0.000000000000000000e+00,-4.143704130433208305e-10,0.000000000000000000e+00 +7.526349354496876920e+00,7.267000000000000171e+01,0.000000000000000000e+00,6.509833512125638322e+00,0.000000000000000000e+00,-1.000000009968664783e+00,0.000000000000000000e+00,4.181754576077938626e-10,0.000000000000000000e+00 +7.527885492092619479e+00,7.268000000000000682e+01,0.000000000000000000e+00,6.508297374514582678e+00,0.000000000000000000e+00,-1.000000009968022407e+00,0.000000000000000000e+00,1.105526224232912320e-10,0.000000000000000000e+00 +7.529421992259185181e+00,7.268999999999999773e+01,0.000000000000000000e+00,6.506760874332701228e+00,0.000000000000000000e+00,-1.000000009967852543e+00,0.000000000000000000e+00,-3.713113249544939422e-10,0.000000000000000000e+00 +7.530958855253405027e+00,7.270000000000000284e+01,0.000000000000000000e+00,6.505224011323162081e+00,0.000000000000000000e+00,-1.000000009968423198e+00,0.000000000000000000e+00,3.127234023850765824e-10,0.000000000000000000e+00 +7.532496081332413773e+00,7.271000000000000796e+01,0.000000000000000000e+00,6.503686785228829592e+00,0.000000000000000000e+00,-1.000000009967942471e+00,0.000000000000000000e+00,-2.567625024626897931e-10,0.000000000000000000e+00 +7.534033670753649936e+00,7.271999999999999886e+01,0.000000000000000000e+00,6.502149195792267022e+00,0.000000000000000000e+00,-1.000000009968337267e+00,0.000000000000000000e+00,1.386016463369571845e-11,0.000000000000000000e+00 +7.535571623774855787e+00,7.273000000000000398e+01,0.000000000000000000e+00,6.500611242755730323e+00,0.000000000000000000e+00,-1.000000009968315950e+00,0.000000000000000000e+00,2.097297476960430674e-10,0.000000000000000000e+00 +7.537109940654079132e+00,7.273999999999999488e+01,0.000000000000000000e+00,6.499072925861172578e+00,0.000000000000000000e+00,-1.000000009967993320e+00,0.000000000000000000e+00,-2.052065562046975626e-10,0.000000000000000000e+00 +7.538648621649672421e+00,7.275000000000000000e+01,0.000000000000000000e+00,6.497534244850241336e+00,0.000000000000000000e+00,-1.000000009968309067e+00,0.000000000000000000e+00,1.092156015259167537e-10,0.000000000000000000e+00 +7.540187667020295414e+00,7.276000000000000512e+01,0.000000000000000000e+00,6.495995199464276837e+00,0.000000000000000000e+00,-1.000000009968140979e+00,0.000000000000000000e+00,-1.331335834710129425e-10,0.000000000000000000e+00 +7.541727077024912518e+00,7.276999999999999602e+01,0.000000000000000000e+00,6.494455789444314675e+00,0.000000000000000000e+00,-1.000000009968345926e+00,0.000000000000000000e+00,4.075258366535912687e-10,0.000000000000000000e+00 +7.543266851922796334e+00,7.278000000000000114e+01,0.000000000000000000e+00,6.492916014531082247e+00,0.000000000000000000e+00,-1.000000009967718428e+00,0.000000000000000000e+00,-3.016071903871658659e-10,0.000000000000000000e+00 +7.544806991973525889e+00,7.279000000000000625e+01,0.000000000000000000e+00,6.491375874465001417e+00,0.000000000000000000e+00,-1.000000009968182946e+00,0.000000000000000000e+00,-1.716677614835363953e-10,0.000000000000000000e+00 +7.546347497436988405e+00,7.279999999999999716e+01,0.000000000000000000e+00,6.489835368986183184e+00,0.000000000000000000e+00,-1.000000009968447401e+00,0.000000000000000000e+00,2.635649229948573122e-10,0.000000000000000000e+00 +7.547888368573379303e+00,7.281000000000000227e+01,0.000000000000000000e+00,6.488294497834432129e+00,0.000000000000000000e+00,-1.000000009968041281e+00,0.000000000000000000e+00,-2.753160096649409766e-10,0.000000000000000000e+00 +7.549429605643203978e+00,7.282000000000000739e+01,0.000000000000000000e+00,6.486753260749244632e+00,0.000000000000000000e+00,-1.000000009968465609e+00,0.000000000000000000e+00,-7.561829966403428111e-11,0.000000000000000000e+00 +7.550971208907276022e+00,7.282999999999999829e+01,0.000000000000000000e+00,6.485211657469805324e+00,0.000000000000000000e+00,-1.000000009968582182e+00,0.000000000000000000e+00,3.314894411298284183e-10,0.000000000000000000e+00 +7.552513178626719892e+00,7.284000000000000341e+01,0.000000000000000000e+00,6.483669687734990639e+00,0.000000000000000000e+00,-1.000000009968071035e+00,0.000000000000000000e+00,4.275801706604225710e-11,0.000000000000000000e+00 +7.554055515062969128e+00,7.285000000000000853e+01,0.000000000000000000e+00,6.482127351283367034e+00,0.000000000000000000e+00,-1.000000009968005088e+00,0.000000000000000000e+00,-3.493233054278006780e-10,0.000000000000000000e+00 +7.555598218477769912e+00,7.285999999999999943e+01,0.000000000000000000e+00,6.480584647853188329e+00,0.000000000000000000e+00,-1.000000009968543990e+00,0.000000000000000000e+00,1.190035515413653518e-10,0.000000000000000000e+00 +7.557141289133179285e+00,7.287000000000000455e+01,0.000000000000000000e+00,6.479041577182396594e+00,0.000000000000000000e+00,-1.000000009968360359e+00,0.000000000000000000e+00,1.734995290121770306e-10,0.000000000000000000e+00 +7.558684727291566041e+00,7.287999999999999545e+01,0.000000000000000000e+00,6.477498139008623923e+00,0.000000000000000000e+00,-1.000000009968092574e+00,0.000000000000000000e+00,-3.385742934730884418e-10,0.000000000000000000e+00 +7.560228533215612501e+00,7.289000000000000057e+01,0.000000000000000000e+00,6.475954333069188884e+00,0.000000000000000000e+00,-1.000000009968615267e+00,0.000000000000000000e+00,2.921915865882549976e-10,0.000000000000000000e+00 +7.561772707168312735e+00,7.290000000000000568e+01,0.000000000000000000e+00,6.474410159101095630e+00,0.000000000000000000e+00,-1.000000009968164072e+00,0.000000000000000000e+00,4.974123146814732736e-11,0.000000000000000000e+00 +7.563317249412974341e+00,7.290999999999999659e+01,0.000000000000000000e+00,6.472865616841037451e+00,0.000000000000000000e+00,-1.000000009968087245e+00,0.000000000000000000e+00,-9.988990975938796184e-11,0.000000000000000000e+00 +7.564862160213220221e+00,7.292000000000000171e+01,0.000000000000000000e+00,6.471320706025391445e+00,0.000000000000000000e+00,-1.000000009968241566e+00,0.000000000000000000e+00,-3.087945054602539785e-10,0.000000000000000000e+00 +7.566407439832987691e+00,7.293000000000000682e+01,0.000000000000000000e+00,6.469775426390220296e+00,0.000000000000000000e+00,-1.000000009968718739e+00,0.000000000000000000e+00,3.868706515867983838e-10,0.000000000000000000e+00 +7.567953088536528483e+00,7.293999999999999773e+01,0.000000000000000000e+00,6.468229777671271385e+00,0.000000000000000000e+00,-1.000000009968120773e+00,0.000000000000000000e+00,-2.240527419853850990e-11,0.000000000000000000e+00 +7.569499106588410520e+00,7.295000000000000284e+01,0.000000000000000000e+00,6.466683759603978565e+00,0.000000000000000000e+00,-1.000000009968155412e+00,0.000000000000000000e+00,-1.991582537679441216e-10,0.000000000000000000e+00 +7.571045494253517916e+00,7.296000000000000796e+01,0.000000000000000000e+00,6.465137371923456833e+00,0.000000000000000000e+00,-1.000000009968463388e+00,0.000000000000000000e+00,7.751963917087915117e-11,0.000000000000000000e+00 +7.572592251797050977e+00,7.296999999999999886e+01,0.000000000000000000e+00,6.463590614364504994e+00,0.000000000000000000e+00,-1.000000009968343484e+00,0.000000000000000000e+00,-8.381599678284049087e-11,0.000000000000000000e+00 +7.574139379484527979e+00,7.298000000000000398e+01,0.000000000000000000e+00,6.462043486661605662e+00,0.000000000000000000e+00,-1.000000009968473158e+00,0.000000000000000000e+00,-8.924840974485800301e-11,0.000000000000000000e+00 +7.575686877581785161e+00,7.298999999999999488e+01,0.000000000000000000e+00,6.460495988548922597e+00,0.000000000000000000e+00,-1.000000009968611270e+00,0.000000000000000000e+00,2.837477156647453802e-10,0.000000000000000000e+00 +7.577234746354975847e+00,7.300000000000000000e+01,0.000000000000000000e+00,6.458948119760301587e+00,0.000000000000000000e+00,-1.000000009968172066e+00,0.000000000000000000e+00,-2.240180699401148666e-10,0.000000000000000000e+00 +7.578782986070573990e+00,7.301000000000000512e+01,0.000000000000000000e+00,6.457399880029270456e+00,0.000000000000000000e+00,-1.000000009968518899e+00,0.000000000000000000e+00,9.348576849930365786e-11,0.000000000000000000e+00 +7.580331596995371513e+00,7.301999999999999602e+01,0.000000000000000000e+00,6.455851269089035505e+00,0.000000000000000000e+00,-1.000000009968374126e+00,0.000000000000000000e+00,-2.150230416749455062e-11,0.000000000000000000e+00 +7.581880579396480968e+00,7.303000000000000114e+01,0.000000000000000000e+00,6.454302286672485067e+00,0.000000000000000000e+00,-1.000000009968407433e+00,0.000000000000000000e+00,2.608320262385870893e-11,0.000000000000000000e+00 +7.583429933541335544e+00,7.304000000000000625e+01,0.000000000000000000e+00,6.452752932512185957e+00,0.000000000000000000e+00,-1.000000009968367021e+00,0.000000000000000000e+00,9.055289525656155456e-11,0.000000000000000000e+00 +7.584979659697689058e+00,7.304999999999999716e+01,0.000000000000000000e+00,6.451203206340384355e+00,0.000000000000000000e+00,-1.000000009968226689e+00,0.000000000000000000e+00,-3.416404858374426261e-10,0.000000000000000000e+00 +7.586529758133616852e+00,7.306000000000000227e+01,0.000000000000000000e+00,6.449653107889004922e+00,0.000000000000000000e+00,-1.000000009968756265e+00,0.000000000000000000e+00,6.344250295764084989e-11,0.000000000000000000e+00 +7.588080229117516673e+00,7.307000000000000739e+01,0.000000000000000000e+00,6.448102636889649020e+00,0.000000000000000000e+00,-1.000000009968657899e+00,0.000000000000000000e+00,4.226574420251481267e-10,0.000000000000000000e+00 +7.589631072918108678e+00,7.307999999999999829e+01,0.000000000000000000e+00,6.446551793073597381e+00,0.000000000000000000e+00,-1.000000009968002423e+00,0.000000000000000000e+00,-5.134510879080121678e-10,0.000000000000000000e+00 +7.591182289804436323e+00,7.309000000000000341e+01,0.000000000000000000e+00,6.445000576171807438e+00,0.000000000000000000e+00,-1.000000009968798897e+00,0.000000000000000000e+00,4.341889458660044707e-10,0.000000000000000000e+00 +7.592733880045866357e+00,7.310000000000000853e+01,0.000000000000000000e+00,6.443448985914909777e+00,0.000000000000000000e+00,-1.000000009968125214e+00,0.000000000000000000e+00,-1.971550190347392023e-10,0.000000000000000000e+00 +7.594285843912090606e+00,7.310999999999999943e+01,0.000000000000000000e+00,6.441897022033215237e+00,0.000000000000000000e+00,-1.000000009968431192e+00,0.000000000000000000e+00,-3.345678652907511061e-10,0.000000000000000000e+00 +7.595838181673125078e+00,7.312000000000000455e+01,0.000000000000000000e+00,6.440344684256706032e+00,0.000000000000000000e+00,-1.000000009968950554e+00,0.000000000000000000e+00,2.479695933588461382e-10,0.000000000000000000e+00 +7.597390893599311745e+00,7.312999999999999545e+01,0.000000000000000000e+00,6.438791972315040191e+00,0.000000000000000000e+00,-1.000000009968565529e+00,0.000000000000000000e+00,3.055266805071452866e-10,0.000000000000000000e+00 +7.598943979961318540e+00,7.314000000000000057e+01,0.000000000000000000e+00,6.437238885937551558e+00,0.000000000000000000e+00,-1.000000009968091019e+00,0.000000000000000000e+00,-3.010219871987126176e-10,0.000000000000000000e+00 +7.600497441030138468e+00,7.315000000000000568e+01,0.000000000000000000e+00,6.435685424853246239e+00,0.000000000000000000e+00,-1.000000009968558645e+00,0.000000000000000000e+00,1.301827406328405650e-10,0.000000000000000000e+00 +7.602051277077093161e+00,7.315999999999999659e+01,0.000000000000000000e+00,6.434131588790801715e+00,0.000000000000000000e+00,-1.000000009968356363e+00,0.000000000000000000e+00,-3.798818125532120057e-10,0.000000000000000000e+00 +7.603605488373831989e+00,7.317000000000000171e+01,0.000000000000000000e+00,6.432577377478570391e+00,0.000000000000000000e+00,-1.000000009968946779e+00,0.000000000000000000e+00,2.381007943754015649e-10,0.000000000000000000e+00 +7.605160075192330282e+00,7.318000000000000682e+01,0.000000000000000000e+00,6.431022790644574272e+00,0.000000000000000000e+00,-1.000000009968576631e+00,0.000000000000000000e+00,7.853856531469007817e-12,0.000000000000000000e+00 +7.606715037804894664e+00,7.318999999999999773e+01,0.000000000000000000e+00,6.429467828016509401e+00,0.000000000000000000e+00,-1.000000009968564418e+00,0.000000000000000000e+00,2.632547219075230372e-10,0.000000000000000000e+00 +7.608270376484158604e+00,7.320000000000000284e+01,0.000000000000000000e+00,6.427912489321740530e+00,0.000000000000000000e+00,-1.000000009968154968e+00,0.000000000000000000e+00,-2.339317310972773038e-10,0.000000000000000000e+00 +7.609826091503087753e+00,7.321000000000000796e+01,0.000000000000000000e+00,6.426356774287303786e+00,0.000000000000000000e+00,-1.000000009968518899e+00,0.000000000000000000e+00,-1.502565557159780845e-10,0.000000000000000000e+00 +7.611382183134976387e+00,7.321999999999999886e+01,0.000000000000000000e+00,6.424800682639903116e+00,0.000000000000000000e+00,-1.000000009968752712e+00,0.000000000000000000e+00,1.084210170267125033e-11,0.000000000000000000e+00 +7.612938651653450073e+00,7.323000000000000398e+01,0.000000000000000000e+00,6.423244214105912953e+00,0.000000000000000000e+00,-1.000000009968735837e+00,0.000000000000000000e+00,1.158112339772810194e-10,0.000000000000000000e+00 +7.614495497332466556e+00,7.323999999999999488e+01,0.000000000000000000e+00,6.421687368411376440e+00,0.000000000000000000e+00,-1.000000009968555537e+00,0.000000000000000000e+00,3.022910193502452390e-11,0.000000000000000000e+00 +7.616052720446314872e+00,7.325000000000000000e+01,0.000000000000000000e+00,6.420130145282004541e+00,0.000000000000000000e+00,-1.000000009968508463e+00,0.000000000000000000e+00,-1.254488630275255432e-11,0.000000000000000000e+00 +7.617610321269617124e+00,7.326000000000000512e+01,0.000000000000000000e+00,6.418572544443175154e+00,0.000000000000000000e+00,-1.000000009968528003e+00,0.000000000000000000e+00,-1.449437964695367830e-10,0.000000000000000000e+00 +7.619168300077328482e+00,7.326999999999999602e+01,0.000000000000000000e+00,6.417014565619933109e+00,0.000000000000000000e+00,-1.000000009968753822e+00,0.000000000000000000e+00,2.319677719426594081e-10,0.000000000000000000e+00 +7.620726657144737182e+00,7.328000000000000114e+01,0.000000000000000000e+00,6.415456208536989280e+00,0.000000000000000000e+00,-1.000000009968392334e+00,0.000000000000000000e+00,-1.102576497970548714e-10,0.000000000000000000e+00 +7.622285392747467192e+00,7.329000000000000625e+01,0.000000000000000000e+00,6.413897472918721476e+00,0.000000000000000000e+00,-1.000000009968564196e+00,0.000000000000000000e+00,-2.056503401103223428e-10,0.000000000000000000e+00 +7.623844507161475548e+00,7.329999999999999716e+01,0.000000000000000000e+00,6.412338358489170886e+00,0.000000000000000000e+00,-1.000000009968884829e+00,0.000000000000000000e+00,1.803986449157197614e-10,0.000000000000000000e+00 +7.625404000663055903e+00,7.331000000000000227e+01,0.000000000000000000e+00,6.410778864972043856e+00,0.000000000000000000e+00,-1.000000009968603498e+00,0.000000000000000000e+00,1.870451222479478068e-10,0.000000000000000000e+00 +7.626963873528838533e+00,7.332000000000000739e+01,0.000000000000000000e+00,6.409218992090711886e+00,0.000000000000000000e+00,-1.000000009968311732e+00,0.000000000000000000e+00,-3.139430292742797666e-10,0.000000000000000000e+00 +7.628524126035788555e+00,7.332999999999999829e+01,0.000000000000000000e+00,6.407658739568208972e+00,0.000000000000000000e+00,-1.000000009968801562e+00,0.000000000000000000e+00,8.109880503934528668e-12,0.000000000000000000e+00 +7.630084758461209482e+00,7.334000000000000341e+01,0.000000000000000000e+00,6.406098107127230712e+00,0.000000000000000000e+00,-1.000000009968788905e+00,0.000000000000000000e+00,-6.998402454675639087e-11,0.000000000000000000e+00 +7.631645771082741447e+00,7.335000000000000853e+01,0.000000000000000000e+00,6.404537094490136973e+00,0.000000000000000000e+00,-1.000000009968898151e+00,0.000000000000000000e+00,4.183797337906632007e-10,0.000000000000000000e+00 +7.633207164178364756e+00,7.335999999999999943e+01,0.000000000000000000e+00,6.402975701378948337e+00,0.000000000000000000e+00,-1.000000009968244896e+00,0.000000000000000000e+00,-4.754319326097090235e-10,0.000000000000000000e+00 +7.634768938026397223e+00,7.337000000000000455e+01,0.000000000000000000e+00,6.401413927515347879e+00,0.000000000000000000e+00,-1.000000009968987413e+00,0.000000000000000000e+00,3.999817986161821561e-10,0.000000000000000000e+00 +7.636331092905495943e+00,7.337999999999999545e+01,0.000000000000000000e+00,6.399851772620675838e+00,0.000000000000000000e+00,-1.000000009968362580e+00,0.000000000000000000e+00,-3.579631394685974099e-10,0.000000000000000000e+00 +7.637893629094659076e+00,7.339000000000000057e+01,0.000000000000000000e+00,6.398289236415936720e+00,0.000000000000000000e+00,-1.000000009968921910e+00,0.000000000000000000e+00,3.736455742980629802e-11,0.000000000000000000e+00 +7.639456546873224951e+00,7.340000000000000568e+01,0.000000000000000000e+00,6.396726318621790419e+00,0.000000000000000000e+00,-1.000000009968863512e+00,0.000000000000000000e+00,5.397362559281316039e-12,0.000000000000000000e+00 +7.641019846520872960e+00,7.340999999999999659e+01,0.000000000000000000e+00,6.395163018958558432e+00,0.000000000000000000e+00,-1.000000009968855075e+00,0.000000000000000000e+00,1.495272052612542255e-10,0.000000000000000000e+00 +7.642583528317623554e+00,7.342000000000000171e+01,0.000000000000000000e+00,6.393599337146219419e+00,0.000000000000000000e+00,-1.000000009968621262e+00,0.000000000000000000e+00,-1.703597086638689287e-11,0.000000000000000000e+00 +7.644147592543840908e+00,7.343000000000000682e+01,0.000000000000000000e+00,6.392035272904410093e+00,0.000000000000000000e+00,-1.000000009968647907e+00,0.000000000000000000e+00,1.092874049065971816e-10,0.000000000000000000e+00 +7.645712039480232036e+00,7.343999999999999773e+01,0.000000000000000000e+00,6.390470825952423439e+00,0.000000000000000000e+00,-1.000000009968476933e+00,0.000000000000000000e+00,-3.194100501695308234e-10,0.000000000000000000e+00 +7.647276869407846789e+00,7.345000000000000284e+01,0.000000000000000000e+00,6.388905996009209609e+00,0.000000000000000000e+00,-1.000000009968976755e+00,0.000000000000000000e+00,2.581892236172391936e-11,0.000000000000000000e+00 +7.648842082608079629e+00,7.346000000000000796e+01,0.000000000000000000e+00,6.387340782793373251e+00,0.000000000000000000e+00,-1.000000009968936343e+00,0.000000000000000000e+00,2.982631401019389882e-10,0.000000000000000000e+00 +7.650407679362669633e+00,7.346999999999999886e+01,0.000000000000000000e+00,6.385775186023176175e+00,0.000000000000000000e+00,-1.000000009968469383e+00,0.000000000000000000e+00,-3.466831339743829385e-10,0.000000000000000000e+00 +7.651973659953700491e+00,7.348000000000000398e+01,0.000000000000000000e+00,6.384209205416534694e+00,0.000000000000000000e+00,-1.000000009969012282e+00,0.000000000000000000e+00,1.444513215780196299e-10,0.000000000000000000e+00 +7.653540024663603170e+00,7.348999999999999488e+01,0.000000000000000000e+00,6.382642840691016950e+00,0.000000000000000000e+00,-1.000000009968786019e+00,0.000000000000000000e+00,2.032309838984262581e-10,0.000000000000000000e+00 +7.655106773775154139e+00,7.350000000000000000e+01,0.000000000000000000e+00,6.381076091563847363e+00,0.000000000000000000e+00,-1.000000009968467607e+00,0.000000000000000000e+00,-2.880524195647394012e-10,0.000000000000000000e+00 +7.656673907571477145e+00,7.351000000000000512e+01,0.000000000000000000e+00,6.379508957751902187e+00,0.000000000000000000e+00,-1.000000009968919024e+00,0.000000000000000000e+00,-8.499213276838315574e-13,0.000000000000000000e+00 +7.658241426336044100e+00,7.351999999999999602e+01,0.000000000000000000e+00,6.377941438971708621e+00,0.000000000000000000e+00,-1.000000009968920356e+00,0.000000000000000000e+00,2.234743854567201978e-10,0.000000000000000000e+00 +7.659809330352675083e+00,7.353000000000000114e+01,0.000000000000000000e+00,6.376373534939447474e+00,0.000000000000000000e+00,-1.000000009968569969e+00,0.000000000000000000e+00,-9.273747692851359608e-11,0.000000000000000000e+00 +7.661377619905538339e+00,7.354000000000000625e+01,0.000000000000000000e+00,6.374805245370950502e+00,0.000000000000000000e+00,-1.000000009968715409e+00,0.000000000000000000e+00,-3.429734964817979211e-10,0.000000000000000000e+00 +7.662946295279152942e+00,7.354999999999999716e+01,0.000000000000000000e+00,6.373236569981698629e+00,0.000000000000000000e+00,-1.000000009969253423e+00,0.000000000000000000e+00,4.386942668453578352e-10,0.000000000000000000e+00 +7.664515356758386133e+00,7.356000000000000227e+01,0.000000000000000000e+00,6.371667508486822840e+00,0.000000000000000000e+00,-1.000000009968565085e+00,0.000000000000000000e+00,-3.877951435696220981e-10,0.000000000000000000e+00 +7.666084804628457761e+00,7.357000000000000739e+01,0.000000000000000000e+00,6.370098060601105949e+00,0.000000000000000000e+00,-1.000000009969173709e+00,0.000000000000000000e+00,3.087735415417339788e-10,0.000000000000000000e+00 +7.667654639174938502e+00,7.357999999999999829e+01,0.000000000000000000e+00,6.368528226038975504e+00,0.000000000000000000e+00,-1.000000009968688985e+00,0.000000000000000000e+00,-1.091683141774455237e-10,0.000000000000000000e+00 +7.669224860683749867e+00,7.359000000000000341e+01,0.000000000000000000e+00,6.366958004514510883e+00,0.000000000000000000e+00,-1.000000009968860404e+00,0.000000000000000000e+00,4.693645599959811728e-11,0.000000000000000000e+00 +7.670795469441167747e+00,7.360000000000000853e+01,0.000000000000000000e+00,6.365387395741436194e+00,0.000000000000000000e+00,-1.000000009968786685e+00,0.000000000000000000e+00,-5.597063720749437378e-11,0.000000000000000000e+00 +7.672366465733818863e+00,7.360999999999999943e+01,0.000000000000000000e+00,6.363816399433123827e+00,0.000000000000000000e+00,-1.000000009968874615e+00,0.000000000000000000e+00,1.893488471624934638e-10,0.000000000000000000e+00 +7.673937849848686099e+00,7.362000000000000455e+01,0.000000000000000000e+00,6.362245015302591788e+00,0.000000000000000000e+00,-1.000000009968577075e+00,0.000000000000000000e+00,-4.069994983055106785e-10,0.000000000000000000e+00 +7.675509622073104943e+00,7.362999999999999545e+01,0.000000000000000000e+00,6.360673243062504589e+00,0.000000000000000000e+00,-1.000000009969216785e+00,0.000000000000000000e+00,2.011190924493756827e-10,0.000000000000000000e+00 +7.677081782694767043e+00,7.364000000000000057e+01,0.000000000000000000e+00,6.359101082425169693e+00,0.000000000000000000e+00,-1.000000009968900594e+00,0.000000000000000000e+00,1.057591061556551441e-10,0.000000000000000000e+00 +7.678654332001718430e+00,7.365000000000000568e+01,0.000000000000000000e+00,6.357528533102541957e+00,0.000000000000000000e+00,-1.000000009968734282e+00,0.000000000000000000e+00,-8.371113624793939872e-11,0.000000000000000000e+00 +7.680227270282362184e+00,7.365999999999999659e+01,0.000000000000000000e+00,6.355955594806218301e+00,0.000000000000000000e+00,-1.000000009968865955e+00,0.000000000000000000e+00,-1.168561077346985429e-10,0.000000000000000000e+00 +7.681800597825457544e+00,7.367000000000000171e+01,0.000000000000000000e+00,6.354382267247438598e+00,0.000000000000000000e+00,-1.000000009969049808e+00,0.000000000000000000e+00,2.558063772033404744e-10,0.000000000000000000e+00 +7.683374314920121684e+00,7.368000000000000682e+01,0.000000000000000000e+00,6.352808550137085675e+00,0.000000000000000000e+00,-1.000000009968647241e+00,0.000000000000000000e+00,-5.078184712846379800e-10,0.000000000000000000e+00 +7.684948421855830603e+00,7.368999999999999773e+01,0.000000000000000000e+00,6.351234443185685308e+00,0.000000000000000000e+00,-1.000000009969446602e+00,0.000000000000000000e+00,3.529874128836712253e-10,0.000000000000000000e+00 +7.686522918922417347e+00,7.370000000000000284e+01,0.000000000000000000e+00,6.349659946103401786e+00,0.000000000000000000e+00,-1.000000009968890824e+00,0.000000000000000000e+00,2.224834404474222637e-10,0.000000000000000000e+00 +7.688097806410075563e+00,7.371000000000000796e+01,0.000000000000000000e+00,6.348085058600044128e+00,0.000000000000000000e+00,-1.000000009968540438e+00,0.000000000000000000e+00,-2.878317515367110342e-10,0.000000000000000000e+00 +7.689673084609357723e+00,7.371999999999999886e+01,0.000000000000000000e+00,6.346509780385058974e+00,0.000000000000000000e+00,-1.000000009968993853e+00,0.000000000000000000e+00,-2.092674261405094923e-10,0.000000000000000000e+00 +7.691248753811177785e+00,7.373000000000000398e+01,0.000000000000000000e+00,6.344934111167531476e+00,0.000000000000000000e+00,-1.000000009969323589e+00,0.000000000000000000e+00,3.520737111585883422e-10,0.000000000000000000e+00 +7.692824814306810310e+00,7.373999999999999488e+01,0.000000000000000000e+00,6.343358050656187075e+00,0.000000000000000000e+00,-1.000000009968768699e+00,0.000000000000000000e+00,-1.380338263610850547e-10,0.000000000000000000e+00 +7.694401266387891347e+00,7.375000000000000000e+01,0.000000000000000000e+00,6.341781598559390609e+00,0.000000000000000000e+00,-1.000000009968986303e+00,0.000000000000000000e+00,4.646922685590746069e-12,0.000000000000000000e+00 +7.695978110346420209e+00,7.376000000000000512e+01,0.000000000000000000e+00,6.340204754585141877e+00,0.000000000000000000e+00,-1.000000009968978976e+00,0.000000000000000000e+00,-3.787004219065532701e-11,0.000000000000000000e+00 +7.697555346474759475e+00,7.376999999999999602e+01,0.000000000000000000e+00,6.338627518441079189e+00,0.000000000000000000e+00,-1.000000009969038706e+00,0.000000000000000000e+00,-1.041518951893393954e-11,0.000000000000000000e+00 +7.699132975065634099e+00,7.378000000000000114e+01,0.000000000000000000e+00,6.337049889834476701e+00,0.000000000000000000e+00,-1.000000009969055137e+00,0.000000000000000000e+00,-1.505605280921005214e-11,0.000000000000000000e+00 +7.700710996412134968e+00,7.379000000000000625e+01,0.000000000000000000e+00,6.335471868472244417e+00,0.000000000000000000e+00,-1.000000009969078896e+00,0.000000000000000000e+00,2.038391397322376922e-10,0.000000000000000000e+00 +7.702289410807717118e+00,7.379999999999999716e+01,0.000000000000000000e+00,6.333893454060927297e+00,0.000000000000000000e+00,-1.000000009968757153e+00,0.000000000000000000e+00,-1.670811361137310169e-10,0.000000000000000000e+00 +7.703868218546200630e+00,7.381000000000000227e+01,0.000000000000000000e+00,6.332314646306705264e+00,0.000000000000000000e+00,-1.000000009969020942e+00,0.000000000000000000e+00,-1.581813341887681713e-10,0.000000000000000000e+00 +7.705447419921772401e+00,7.382000000000000739e+01,0.000000000000000000e+00,6.330735444915390531e+00,0.000000000000000000e+00,-1.000000009969270742e+00,0.000000000000000000e+00,1.308711960849302024e-10,0.000000000000000000e+00 +7.707027015228986144e+00,7.382999999999999829e+01,0.000000000000000000e+00,6.329155849592429384e+00,0.000000000000000000e+00,-1.000000009969064019e+00,0.000000000000000000e+00,2.449533608359555955e-10,0.000000000000000000e+00 +7.708607004762763282e+00,7.384000000000000341e+01,0.000000000000000000e+00,6.327575860042901290e+00,0.000000000000000000e+00,-1.000000009968676995e+00,0.000000000000000000e+00,-2.686367804738859745e-10,0.000000000000000000e+00 +7.710187388818392940e+00,7.385000000000000853e+01,0.000000000000000000e+00,6.325995475971517124e+00,0.000000000000000000e+00,-1.000000009969101544e+00,0.000000000000000000e+00,-8.456012060642177964e-11,0.000000000000000000e+00 +7.711768167691533726e+00,7.385999999999999943e+01,0.000000000000000000e+00,6.324414697082617387e+00,0.000000000000000000e+00,-1.000000009969235215e+00,0.000000000000000000e+00,-1.109398708608659431e-11,0.000000000000000000e+00 +7.713349341678212845e+00,7.387000000000000455e+01,0.000000000000000000e+00,6.322833523080174878e+00,0.000000000000000000e+00,-1.000000009969252757e+00,0.000000000000000000e+00,2.105926607458621706e-10,0.000000000000000000e+00 +7.714930911074828757e+00,7.387999999999999545e+01,0.000000000000000000e+00,6.321251953667792023e+00,0.000000000000000000e+00,-1.000000009968919690e+00,0.000000000000000000e+00,-2.241549028615944235e-10,0.000000000000000000e+00 +7.716512876178149405e+00,7.389000000000000057e+01,0.000000000000000000e+00,6.319669988548700879e+00,0.000000000000000000e+00,-1.000000009969274295e+00,0.000000000000000000e+00,3.640026935490887530e-10,0.000000000000000000e+00 +7.718095237285314880e+00,7.390000000000000568e+01,0.000000000000000000e+00,6.318087627425760466e+00,0.000000000000000000e+00,-1.000000009968698311e+00,0.000000000000000000e+00,-2.476113683515294779e-10,0.000000000000000000e+00 +7.719677994693837420e+00,7.390999999999999659e+01,0.000000000000000000e+00,6.316504870001460326e+00,0.000000000000000000e+00,-1.000000009969090220e+00,0.000000000000000000e+00,-2.426404283074062910e-11,0.000000000000000000e+00 +7.721261148701600519e+00,7.392000000000000171e+01,0.000000000000000000e+00,6.314921715977914296e+00,0.000000000000000000e+00,-1.000000009969128634e+00,0.000000000000000000e+00,-1.228322204659771467e-10,0.000000000000000000e+00 +7.722844699606863372e+00,7.393000000000000682e+01,0.000000000000000000e+00,6.313338165056864959e+00,0.000000000000000000e+00,-1.000000009969323145e+00,0.000000000000000000e+00,7.275563502028321493e-11,0.000000000000000000e+00 +7.724428647708257323e+00,7.393999999999999773e+01,0.000000000000000000e+00,6.311754216939680084e+00,0.000000000000000000e+00,-1.000000009969207904e+00,0.000000000000000000e+00,1.171646452160851139e-10,0.000000000000000000e+00 +7.726012993304789411e+00,7.395000000000000284e+01,0.000000000000000000e+00,6.310169871327353519e+00,0.000000000000000000e+00,-1.000000009969022274e+00,0.000000000000000000e+00,-8.056550262510126851e-11,0.000000000000000000e+00 +7.727597736695841490e+00,7.396000000000000796e+01,0.000000000000000000e+00,6.308585127920503410e+00,0.000000000000000000e+00,-1.000000009969149950e+00,0.000000000000000000e+00,9.651424444395099365e-11,0.000000000000000000e+00 +7.729182878181171112e+00,7.396999999999999886e+01,0.000000000000000000e+00,6.306999986419371318e+00,0.000000000000000000e+00,-1.000000009968996961e+00,0.000000000000000000e+00,-1.478859698180480592e-10,0.000000000000000000e+00 +7.730768418060913305e+00,7.398000000000000398e+01,0.000000000000000000e+00,6.305414446523823102e+00,0.000000000000000000e+00,-1.000000009969231440e+00,0.000000000000000000e+00,1.565293084307669339e-10,0.000000000000000000e+00 +7.732354356635579684e+00,7.398999999999999488e+01,0.000000000000000000e+00,6.303828507933346259e+00,0.000000000000000000e+00,-1.000000009968983194e+00,0.000000000000000000e+00,-1.377335412790262131e-10,0.000000000000000000e+00 +7.733940694206060229e+00,7.400000000000000000e+01,0.000000000000000000e+00,6.302242170347051697e+00,0.000000000000000000e+00,-1.000000009969201686e+00,0.000000000000000000e+00,-5.933366420911911598e-11,0.000000000000000000e+00 +7.735527431073623283e+00,7.401000000000000512e+01,0.000000000000000000e+00,6.300655433463670185e+00,0.000000000000000000e+00,-1.000000009969295833e+00,0.000000000000000000e+00,-4.826641585398064096e-11,0.000000000000000000e+00 +7.737114567539916443e+00,7.401999999999999602e+01,0.000000000000000000e+00,6.299068296981554127e+00,0.000000000000000000e+00,-1.000000009969372439e+00,0.000000000000000000e+00,1.609873925240316859e-10,0.000000000000000000e+00 +7.738702103906968333e+00,7.403000000000000114e+01,0.000000000000000000e+00,6.297480760598675786e+00,0.000000000000000000e+00,-1.000000009969116865e+00,0.000000000000000000e+00,-2.214941457976027899e-10,0.000000000000000000e+00 +7.740290040477186828e+00,7.404000000000000625e+01,0.000000000000000000e+00,6.295892824012627287e+00,0.000000000000000000e+00,-1.000000009969468584e+00,0.000000000000000000e+00,4.799227696324980955e-10,0.000000000000000000e+00 +7.741878377553361723e+00,7.404999999999999716e+01,0.000000000000000000e+00,6.294304486920617947e+00,0.000000000000000000e+00,-1.000000009968706305e+00,0.000000000000000000e+00,-6.353563941084134864e-10,0.000000000000000000e+00 +7.743467115438663839e+00,7.406000000000000227e+01,0.000000000000000000e+00,6.292715749019477833e+00,0.000000000000000000e+00,-1.000000009969715720e+00,0.000000000000000000e+00,5.712013524837105693e-10,0.000000000000000000e+00 +7.745056254436648580e+00,7.407000000000000739e+01,0.000000000000000000e+00,6.291126610005649766e+00,0.000000000000000000e+00,-1.000000009968808001e+00,0.000000000000000000e+00,-2.046474208685261975e-10,0.000000000000000000e+00 +7.746645794851253264e+00,7.407999999999999829e+01,0.000000000000000000e+00,6.289537069575199091e+00,0.000000000000000000e+00,-1.000000009969133297e+00,0.000000000000000000e+00,-2.316889346692997464e-10,0.000000000000000000e+00 +7.748235736986799793e+00,7.409000000000000341e+01,0.000000000000000000e+00,6.287947127423802129e+00,0.000000000000000000e+00,-1.000000009969501669e+00,0.000000000000000000e+00,5.542932800722265284e-11,0.000000000000000000e+00 +7.749826081147994650e+00,7.410000000000000853e+01,0.000000000000000000e+00,6.286356783246752400e+00,0.000000000000000000e+00,-1.000000009969413517e+00,0.000000000000000000e+00,2.241737683016228190e-10,0.000000000000000000e+00 +7.751416827639929785e+00,7.410999999999999943e+01,0.000000000000000000e+00,6.284766036738958839e+00,0.000000000000000000e+00,-1.000000009969056913e+00,0.000000000000000000e+00,-1.562958198674831681e-10,0.000000000000000000e+00 +7.753007976768082621e+00,7.412000000000000455e+01,0.000000000000000000e+00,6.283174887594944025e+00,0.000000000000000000e+00,-1.000000009969305603e+00,0.000000000000000000e+00,-1.134252954585399544e-10,0.000000000000000000e+00 +7.754599528838317823e+00,7.412999999999999545e+01,0.000000000000000000e+00,6.281583335508842403e+00,0.000000000000000000e+00,-1.000000009969486126e+00,0.000000000000000000e+00,2.729607337401863216e-10,0.000000000000000000e+00 +7.756191484156887306e+00,7.414000000000000057e+01,0.000000000000000000e+00,6.279991380174402060e+00,0.000000000000000000e+00,-1.000000009969051584e+00,0.000000000000000000e+00,-1.271727642908405595e-10,0.000000000000000000e+00 +7.757783843030431115e+00,7.415000000000000568e+01,0.000000000000000000e+00,6.278399021284983839e+00,0.000000000000000000e+00,-1.000000009969254089e+00,0.000000000000000000e+00,1.031622626379766404e-11,0.000000000000000000e+00 +7.759376605765978319e+00,7.415999999999999659e+01,0.000000000000000000e+00,6.276806258533557781e+00,0.000000000000000000e+00,-1.000000009969237658e+00,0.000000000000000000e+00,-9.310122851991879537e-11,0.000000000000000000e+00 +7.760969772670947897e+00,7.417000000000000171e+01,0.000000000000000000e+00,6.275213091612705796e+00,0.000000000000000000e+00,-1.000000009969385983e+00,0.000000000000000000e+00,1.861551954894696827e-10,0.000000000000000000e+00 +7.762563344053147851e+00,7.418000000000000682e+01,0.000000000000000000e+00,6.273619520214618994e+00,0.000000000000000000e+00,-1.000000009969089332e+00,0.000000000000000000e+00,-2.773509525321695011e-10,0.000000000000000000e+00 +7.764157320220777869e+00,7.418999999999999773e+01,0.000000000000000000e+00,6.272025544031098576e+00,0.000000000000000000e+00,-1.000000009969531423e+00,0.000000000000000000e+00,1.896815769113570350e-10,0.000000000000000000e+00 +7.765751701482429326e+00,7.420000000000000284e+01,0.000000000000000000e+00,6.270431162753552279e+00,0.000000000000000000e+00,-1.000000009969228998e+00,0.000000000000000000e+00,-2.353013043311036821e-10,0.000000000000000000e+00 +7.767346488147085282e+00,7.421000000000000796e+01,0.000000000000000000e+00,6.268836376072997929e+00,0.000000000000000000e+00,-1.000000009969604253e+00,0.000000000000000000e+00,4.693693491679284784e-10,0.000000000000000000e+00 +7.768941680524121374e+00,7.421999999999999886e+01,0.000000000000000000e+00,6.267241183680058114e+00,0.000000000000000000e+00,-1.000000009968855519e+00,0.000000000000000000e+00,-5.619309439919300976e-10,0.000000000000000000e+00 +7.770537278923308477e+00,7.423000000000000398e+01,0.000000000000000000e+00,6.265645585264964623e+00,0.000000000000000000e+00,-1.000000009969752135e+00,0.000000000000000000e+00,4.362968776348214755e-10,0.000000000000000000e+00 +7.772133283654810931e+00,7.423999999999999488e+01,0.000000000000000000e+00,6.264049580517550453e+00,0.000000000000000000e+00,-1.000000009969055803e+00,0.000000000000000000e+00,-4.446702230634837925e-10,0.000000000000000000e+00 +7.773729695029188314e+00,7.425000000000000000e+01,0.000000000000000000e+00,6.262453169127258690e+00,0.000000000000000000e+00,-1.000000009969765680e+00,0.000000000000000000e+00,5.583033918298494848e-10,0.000000000000000000e+00 +7.775326513357395442e+00,7.426000000000000512e+01,0.000000000000000000e+00,6.260856350783131852e+00,0.000000000000000000e+00,-1.000000009968874171e+00,0.000000000000000000e+00,-4.575113232802527464e-10,0.000000000000000000e+00 +7.776923738950784148e+00,7.426999999999999602e+01,0.000000000000000000e+00,6.259259125173820770e+00,0.000000000000000000e+00,-1.000000009969604919e+00,0.000000000000000000e+00,2.683770843494725433e-10,0.000000000000000000e+00 +7.778521372121103283e+00,7.428000000000000114e+01,0.000000000000000000e+00,6.257661491987573932e+00,0.000000000000000000e+00,-1.000000009969176151e+00,0.000000000000000000e+00,-1.179668497707775360e-10,0.000000000000000000e+00 +7.780119413180499599e+00,7.429000000000000625e+01,0.000000000000000000e+00,6.256063450912246360e+00,0.000000000000000000e+00,-1.000000009969364667e+00,0.000000000000000000e+00,-2.932443164932630476e-10,0.000000000000000000e+00 +7.781717862441518641e+00,7.429999999999999716e+01,0.000000000000000000e+00,6.254465001635291621e+00,0.000000000000000000e+00,-1.000000009969833403e+00,0.000000000000000000e+00,3.694128759412745708e-10,0.000000000000000000e+00 +7.783316720217105633e+00,7.431000000000000227e+01,0.000000000000000000e+00,6.252866143843764490e+00,0.000000000000000000e+00,-1.000000009969242765e+00,0.000000000000000000e+00,6.497783101175617499e-11,0.000000000000000000e+00 +7.784915986820604594e+00,7.432000000000000739e+01,0.000000000000000000e+00,6.251266877224321838e+00,0.000000000000000000e+00,-1.000000009969138848e+00,0.000000000000000000e+00,-2.300015559244683811e-10,0.000000000000000000e+00 +7.786515662565761886e+00,7.432999999999999829e+01,0.000000000000000000e+00,6.249667201463217303e+00,0.000000000000000000e+00,-1.000000009969506776e+00,0.000000000000000000e+00,1.121265546806755581e-10,0.000000000000000000e+00 +7.788115747766724439e+00,7.434000000000000341e+01,0.000000000000000000e+00,6.248067116246303065e+00,0.000000000000000000e+00,-1.000000009969327364e+00,0.000000000000000000e+00,-3.614045693339034046e-10,0.000000000000000000e+00 +7.789716242738040641e+00,7.435000000000000853e+01,0.000000000000000000e+00,6.246466621259030738e+00,0.000000000000000000e+00,-1.000000009969905790e+00,0.000000000000000000e+00,3.651955763078757662e-10,0.000000000000000000e+00 +7.791317147794663889e+00,7.435999999999999943e+01,0.000000000000000000e+00,6.244865716186446924e+00,0.000000000000000000e+00,-1.000000009969321146e+00,0.000000000000000000e+00,1.479543536391445352e-10,0.000000000000000000e+00 +7.792918463251949035e+00,7.437000000000000455e+01,0.000000000000000000e+00,6.243264400713197659e+00,0.000000000000000000e+00,-1.000000009969084225e+00,0.000000000000000000e+00,-3.819210153458398542e-10,0.000000000000000000e+00 +7.794520189425656831e+00,7.437999999999999545e+01,0.000000000000000000e+00,6.241662674523522192e+00,0.000000000000000000e+00,-1.000000009969695958e+00,0.000000000000000000e+00,9.743070484158425598e-11,0.000000000000000000e+00 +7.796122326631952149e+00,7.439000000000000057e+01,0.000000000000000000e+00,6.240060537301253873e+00,0.000000000000000000e+00,-1.000000009969539860e+00,0.000000000000000000e+00,1.391114063820188860e-10,0.000000000000000000e+00 +7.797724875187406646e+00,7.440000000000000568e+01,0.000000000000000000e+00,6.238457988729822823e+00,0.000000000000000000e+00,-1.000000009969316928e+00,0.000000000000000000e+00,2.867396994659262214e-11,0.000000000000000000e+00 +7.799327835408997878e+00,7.440999999999999659e+01,0.000000000000000000e+00,6.236855028492251485e+00,0.000000000000000000e+00,-1.000000009969270964e+00,0.000000000000000000e+00,-2.938672942867216776e-10,0.000000000000000000e+00 +7.800931207614110185e+00,7.442000000000000171e+01,0.000000000000000000e+00,6.235251656271154630e+00,0.000000000000000000e+00,-1.000000009969742143e+00,0.000000000000000000e+00,1.475881254006117401e-10,0.000000000000000000e+00 +7.802534992120537360e+00,7.443000000000000682e+01,0.000000000000000000e+00,6.233647871748738467e+00,0.000000000000000000e+00,-1.000000009969505443e+00,0.000000000000000000e+00,-8.720131637222528220e-11,0.000000000000000000e+00 +7.804139189246479980e+00,7.443999999999999773e+01,0.000000000000000000e+00,6.232043674606802419e+00,0.000000000000000000e+00,-1.000000009969645332e+00,0.000000000000000000e+00,3.240840104263649300e-10,0.000000000000000000e+00 +7.805743799310550735e+00,7.445000000000000284e+01,0.000000000000000000e+00,6.230439064526734683e+00,0.000000000000000000e+00,-1.000000009969125303e+00,0.000000000000000000e+00,-4.007812297575952744e-10,0.000000000000000000e+00 +7.807348822631769991e+00,7.446000000000000796e+01,0.000000000000000000e+00,6.228834041189514892e+00,0.000000000000000000e+00,-1.000000009969768566e+00,0.000000000000000000e+00,9.501752687540047815e-11,0.000000000000000000e+00 +7.808954259529570230e+00,7.446999999999999886e+01,0.000000000000000000e+00,6.227228604275708790e+00,0.000000000000000000e+00,-1.000000009969616022e+00,0.000000000000000000e+00,3.124952884384213771e-11,0.000000000000000000e+00 +7.810560110323796046e+00,7.448000000000000398e+01,0.000000000000000000e+00,6.225622753465473558e+00,0.000000000000000000e+00,-1.000000009969565840e+00,0.000000000000000000e+00,4.202392471904801264e-11,0.000000000000000000e+00 +7.812166375334703261e+00,7.448999999999999488e+01,0.000000000000000000e+00,6.224016488438552486e+00,0.000000000000000000e+00,-1.000000009969498338e+00,0.000000000000000000e+00,7.200268360377761266e-11,0.000000000000000000e+00 +7.813773054882962477e+00,7.450000000000000000e+01,0.000000000000000000e+00,6.222409808874275861e+00,0.000000000000000000e+00,-1.000000009969382653e+00,0.000000000000000000e+00,-2.763305055386256267e-10,0.000000000000000000e+00 +7.815380149289656408e+00,7.451000000000000512e+01,0.000000000000000000e+00,6.220802714451560078e+00,0.000000000000000000e+00,-1.000000009969826742e+00,0.000000000000000000e+00,3.189411727537428624e-10,0.000000000000000000e+00 +7.816987658876284328e+00,7.451999999999999602e+01,0.000000000000000000e+00,6.219195204848905867e+00,0.000000000000000000e+00,-1.000000009969314041e+00,0.000000000000000000e+00,-2.580974509194834036e-10,0.000000000000000000e+00 +7.818595583964759399e+00,7.453000000000000114e+01,0.000000000000000000e+00,6.217587279744400952e+00,0.000000000000000000e+00,-1.000000009969729042e+00,0.000000000000000000e+00,3.465260094905541448e-10,0.000000000000000000e+00 +7.820203924877412227e+00,7.454000000000000625e+01,0.000000000000000000e+00,6.215978938815713839e+00,0.000000000000000000e+00,-1.000000009969171710e+00,0.000000000000000000e+00,-3.228345310610770743e-10,0.000000000000000000e+00 +7.821812681936989087e+00,7.454999999999999716e+01,0.000000000000000000e+00,6.214370181740099142e+00,0.000000000000000000e+00,-1.000000009969691073e+00,0.000000000000000000e+00,8.637969747858469435e-11,0.000000000000000000e+00 +7.823421855466654584e+00,7.456000000000000227e+01,0.000000000000000000e+00,6.212761008194390477e+00,0.000000000000000000e+00,-1.000000009969552073e+00,0.000000000000000000e+00,-1.918898498409404059e-10,0.000000000000000000e+00 +7.825031445789992546e+00,7.457000000000000739e+01,0.000000000000000000e+00,6.211151417855005796e+00,0.000000000000000000e+00,-1.000000009969860937e+00,0.000000000000000000e+00,1.653604042585888204e-10,0.000000000000000000e+00 +7.826641453231005130e+00,7.457999999999999829e+01,0.000000000000000000e+00,6.209541410397942052e+00,0.000000000000000000e+00,-1.000000009969594705e+00,0.000000000000000000e+00,8.079739691731355064e-11,0.000000000000000000e+00 +7.828251878114113715e+00,7.459000000000000341e+01,0.000000000000000000e+00,6.207930985498777865e+00,0.000000000000000000e+00,-1.000000009969464587e+00,0.000000000000000000e+00,-1.499740090387706606e-10,0.000000000000000000e+00 +7.829862720764162454e+00,7.460000000000000853e+01,0.000000000000000000e+00,6.206320142832669973e+00,0.000000000000000000e+00,-1.000000009969706172e+00,0.000000000000000000e+00,1.101085843418681686e-10,0.000000000000000000e+00 +7.831473981506415605e+00,7.460999999999999943e+01,0.000000000000000000e+00,6.204708882074353227e+00,0.000000000000000000e+00,-1.000000009969528758e+00,0.000000000000000000e+00,-2.113425751093979810e-10,0.000000000000000000e+00 +7.833085660666559313e+00,7.462000000000000455e+01,0.000000000000000000e+00,6.203097202898141482e+00,0.000000000000000000e+00,-1.000000009969869375e+00,0.000000000000000000e+00,2.075687951467730629e-10,0.000000000000000000e+00 +7.834697758570704273e+00,7.462999999999999545e+01,0.000000000000000000e+00,6.201485104977924045e+00,0.000000000000000000e+00,-1.000000009969534753e+00,0.000000000000000000e+00,-4.544120823274855197e-11,0.000000000000000000e+00 +7.836310275545383952e+00,7.464000000000000057e+01,0.000000000000000000e+00,6.199872587987168338e+00,0.000000000000000000e+00,-1.000000009969608028e+00,0.000000000000000000e+00,1.073785642320410769e-11,0.000000000000000000e+00 +7.837923211917556365e+00,7.465000000000000568e+01,0.000000000000000000e+00,6.198259651598915454e+00,0.000000000000000000e+00,-1.000000009969590709e+00,0.000000000000000000e+00,-8.945885751153282364e-12,0.000000000000000000e+00 +7.839536568014604967e+00,7.465999999999999659e+01,0.000000000000000000e+00,6.196646295485781941e+00,0.000000000000000000e+00,-1.000000009969605141e+00,0.000000000000000000e+00,-1.470871178160648715e-10,0.000000000000000000e+00 +7.841150344164340424e+00,7.467000000000000171e+01,0.000000000000000000e+00,6.195032519319958020e+00,0.000000000000000000e+00,-1.000000009969842507e+00,0.000000000000000000e+00,2.360484208797208188e-10,0.000000000000000000e+00 +7.842764540694998843e+00,7.468000000000000682e+01,0.000000000000000000e+00,6.193418322773206697e+00,0.000000000000000000e+00,-1.000000009969461479e+00,0.000000000000000000e+00,-2.644538684635849849e-10,0.000000000000000000e+00 +7.844379157935244429e+00,7.468999999999999773e+01,0.000000000000000000e+00,6.191803705516864653e+00,0.000000000000000000e+00,-1.000000009969888470e+00,0.000000000000000000e+00,1.512342268321320971e-11,0.000000000000000000e+00 +7.845994196214169492e+00,7.470000000000000284e+01,0.000000000000000000e+00,6.190188667221837804e+00,0.000000000000000000e+00,-1.000000009969864045e+00,0.000000000000000000e+00,3.526961860365326284e-10,0.000000000000000000e+00 +7.847609655861296218e+00,7.471000000000000796e+01,0.000000000000000000e+00,6.188573207558604850e+00,0.000000000000000000e+00,-1.000000009969294279e+00,0.000000000000000000e+00,-3.112425498468294033e-10,0.000000000000000000e+00 +7.849225537206577563e+00,7.471999999999999886e+01,0.000000000000000000e+00,6.186957326197214613e+00,0.000000000000000000e+00,-1.000000009969797210e+00,0.000000000000000000e+00,2.665134160655967991e-11,0.000000000000000000e+00 +7.850841840580395470e+00,7.473000000000000398e+01,0.000000000000000000e+00,6.185341022807282485e+00,0.000000000000000000e+00,-1.000000009969754133e+00,0.000000000000000000e+00,-3.268743416891280552e-11,0.000000000000000000e+00 +7.852458566313564425e+00,7.473999999999999488e+01,0.000000000000000000e+00,6.183724297057994868e+00,0.000000000000000000e+00,-1.000000009969806980e+00,0.000000000000000000e+00,1.540576257963237526e-10,0.000000000000000000e+00 +7.854075714737332348e+00,7.475000000000000000e+01,0.000000000000000000e+00,6.182107148618104731e+00,0.000000000000000000e+00,-1.000000009969557846e+00,0.000000000000000000e+00,-1.284850512896295171e-10,0.000000000000000000e+00 +7.855693286183377921e+00,7.476000000000000512e+01,0.000000000000000000e+00,6.180489577155932501e+00,0.000000000000000000e+00,-1.000000009969765680e+00,0.000000000000000000e+00,1.025141241702938498e-10,0.000000000000000000e+00 +7.857311280983815927e+00,7.476999999999999602e+01,0.000000000000000000e+00,6.178871582339363400e+00,0.000000000000000000e+00,-1.000000009969599812e+00,0.000000000000000000e+00,-2.053861693776421287e-10,0.000000000000000000e+00 +7.858929699471195462e+00,7.478000000000000114e+01,0.000000000000000000e+00,6.177253163835849215e+00,0.000000000000000000e+00,-1.000000009969932213e+00,0.000000000000000000e+00,-6.899277463577728502e-11,0.000000000000000000e+00 +7.860548541978499948e+00,7.479000000000000625e+01,0.000000000000000000e+00,6.175634321312404751e+00,0.000000000000000000e+00,-1.000000009970043902e+00,0.000000000000000000e+00,1.390464010999798576e-10,0.000000000000000000e+00 +7.862167808839150673e+00,7.479999999999999716e+01,0.000000000000000000e+00,6.174015054435609606e+00,0.000000000000000000e+00,-1.000000009969818748e+00,0.000000000000000000e+00,4.798173567471727206e-11,0.000000000000000000e+00 +7.863787500387005913e+00,7.481000000000000227e+01,0.000000000000000000e+00,6.172395362871606395e+00,0.000000000000000000e+00,-1.000000009969741033e+00,0.000000000000000000e+00,-3.577127904351694255e-11,0.000000000000000000e+00 +7.865407616956360926e+00,7.482000000000000739e+01,0.000000000000000000e+00,6.170775246286098970e+00,0.000000000000000000e+00,-1.000000009969798986e+00,0.000000000000000000e+00,1.956627538145860694e-10,0.000000000000000000e+00 +7.867028158881950617e+00,7.482999999999999829e+01,0.000000000000000000e+00,6.169154704344352425e+00,0.000000000000000000e+00,-1.000000009969481907e+00,0.000000000000000000e+00,-3.032798127171253499e-10,0.000000000000000000e+00 +7.868649126498949542e+00,7.484000000000000341e+01,0.000000000000000000e+00,6.167533736711193093e+00,0.000000000000000000e+00,-1.000000009969973513e+00,0.000000000000000000e+00,1.290038471597908198e-10,0.000000000000000000e+00 +7.870270520142972792e+00,7.485000000000000853e+01,0.000000000000000000e+00,6.165912343051004996e+00,0.000000000000000000e+00,-1.000000009969764347e+00,0.000000000000000000e+00,1.106238916733828619e-10,0.000000000000000000e+00 +7.871892340150075107e+00,7.485999999999999943e+01,0.000000000000000000e+00,6.164290523027733393e+00,0.000000000000000000e+00,-1.000000009969584935e+00,0.000000000000000000e+00,-3.846180345258949651e-10,0.000000000000000000e+00 +7.873514586856755315e+00,7.487000000000000455e+01,0.000000000000000000e+00,6.162668276304880344e+00,0.000000000000000000e+00,-1.000000009970208881e+00,0.000000000000000000e+00,3.022767419115775027e-10,0.000000000000000000e+00 +7.875137260599953670e+00,7.487999999999999545e+01,0.000000000000000000e+00,6.161045602545503819e+00,0.000000000000000000e+00,-1.000000009969718384e+00,0.000000000000000000e+00,1.203863704333239621e-10,0.000000000000000000e+00 +7.876760361717054515e+00,7.489000000000000057e+01,0.000000000000000000e+00,6.159422501412221251e+00,0.000000000000000000e+00,-1.000000009969522985e+00,0.000000000000000000e+00,-2.805084065115363167e-10,0.000000000000000000e+00 +7.878383890545886281e+00,7.490000000000000568e+01,0.000000000000000000e+00,6.157798972567203322e+00,0.000000000000000000e+00,-1.000000009969978398e+00,0.000000000000000000e+00,8.477297448442978848e-11,0.000000000000000000e+00 +7.880007847424724154e+00,7.490999999999999659e+01,0.000000000000000000e+00,6.156175015672174844e+00,0.000000000000000000e+00,-1.000000009969840731e+00,0.000000000000000000e+00,-1.550116139397649445e-10,0.000000000000000000e+00 +7.881632232692287410e+00,7.492000000000000171e+01,0.000000000000000000e+00,6.154550630388416543e+00,0.000000000000000000e+00,-1.000000009970092529e+00,0.000000000000000000e+00,3.223773456425832532e-10,0.000000000000000000e+00 +7.883257046687743852e+00,7.493000000000000682e+01,0.000000000000000000e+00,6.152925816376760615e+00,0.000000000000000000e+00,-1.000000009969568726e+00,0.000000000000000000e+00,-1.878557975291804815e-10,0.000000000000000000e+00 +7.884882289750708040e+00,7.493999999999999773e+01,0.000000000000000000e+00,6.151300573297593388e+00,0.000000000000000000e+00,-1.000000009969874037e+00,0.000000000000000000e+00,-2.554164007421477684e-11,0.000000000000000000e+00 +7.886507962221243950e+00,7.495000000000000284e+01,0.000000000000000000e+00,6.149674900810849998e+00,0.000000000000000000e+00,-1.000000009969915560e+00,0.000000000000000000e+00,1.149752796632593892e-10,0.000000000000000000e+00 +7.888134064439864090e+00,7.496000000000000796e+01,0.000000000000000000e+00,6.148048798576017937e+00,0.000000000000000000e+00,-1.000000009969728598e+00,0.000000000000000000e+00,-1.227261818819122955e-10,0.000000000000000000e+00 +7.889760596747531274e+00,7.496999999999999886e+01,0.000000000000000000e+00,6.146422266252134392e+00,0.000000000000000000e+00,-1.000000009969928216e+00,0.000000000000000000e+00,-8.639056791132306205e-11,0.000000000000000000e+00 +7.891387559485660397e+00,7.498000000000000398e+01,0.000000000000000000e+00,6.144795303497784467e+00,0.000000000000000000e+00,-1.000000009970068771e+00,0.000000000000000000e+00,2.042534712328999000e-10,0.000000000000000000e+00 +7.893014952996117550e+00,7.498999999999999488e+01,0.000000000000000000e+00,6.143167909971102070e+00,0.000000000000000000e+00,-1.000000009969736370e+00,0.000000000000000000e+00,-2.745847327905577222e-10,0.000000000000000000e+00 +7.894642777621221796e+00,7.500000000000000000e+01,0.000000000000000000e+00,6.141540085329769028e+00,0.000000000000000000e+00,-1.000000009970183346e+00,0.000000000000000000e+00,1.355513666827021835e-10,0.000000000000000000e+00 +7.896271033703745168e+00,7.501000000000000512e+01,0.000000000000000000e+00,6.139911829231011531e+00,0.000000000000000000e+00,-1.000000009969962633e+00,0.000000000000000000e+00,7.730105460566036009e-11,0.000000000000000000e+00 +7.897899721586915334e+00,7.501999999999999602e+01,0.000000000000000000e+00,6.138283141331603687e+00,0.000000000000000000e+00,-1.000000009969836734e+00,0.000000000000000000e+00,-1.297549967593278202e-10,0.000000000000000000e+00 +7.899528841614413821e+00,7.503000000000000114e+01,0.000000000000000000e+00,6.136654021287863081e+00,0.000000000000000000e+00,-1.000000009970048120e+00,0.000000000000000000e+00,1.682824483382308217e-10,0.000000000000000000e+00 +7.901158394130379570e+00,7.504000000000000625e+01,0.000000000000000000e+00,6.135024468755650773e+00,0.000000000000000000e+00,-1.000000009969773895e+00,0.000000000000000000e+00,-4.672514359389952139e-11,0.000000000000000000e+00 +7.902788379479407155e+00,7.504999999999999716e+01,0.000000000000000000e+00,6.133394483390372187e+00,0.000000000000000000e+00,-1.000000009969850057e+00,0.000000000000000000e+00,-1.188927486239731476e-10,0.000000000000000000e+00 +7.904418798006550340e+00,7.506000000000000227e+01,0.000000000000000000e+00,6.131764064846973561e+00,0.000000000000000000e+00,-1.000000009970043902e+00,0.000000000000000000e+00,-6.181324086896923473e-11,0.000000000000000000e+00 +7.906049650057321188e+00,7.507000000000000739e+01,0.000000000000000000e+00,6.130133212779942831e+00,0.000000000000000000e+00,-1.000000009970144710e+00,0.000000000000000000e+00,1.124320644087236107e-10,0.000000000000000000e+00 +7.907680935977690950e+00,7.507999999999999829e+01,0.000000000000000000e+00,6.128501926843308745e+00,0.000000000000000000e+00,-1.000000009969961301e+00,0.000000000000000000e+00,5.878659409033891149e-11,0.000000000000000000e+00 +7.909312656114091844e+00,7.509000000000000341e+01,0.000000000000000000e+00,6.126870206690639975e+00,0.000000000000000000e+00,-1.000000009969865378e+00,0.000000000000000000e+00,1.005364032634488766e-10,0.000000000000000000e+00 +7.910944810813416161e+00,7.510000000000000853e+01,0.000000000000000000e+00,6.125238051975043341e+00,0.000000000000000000e+00,-1.000000009969701287e+00,0.000000000000000000e+00,-4.384885228151955563e-10,0.000000000000000000e+00 +7.912577400423018936e+00,7.510999999999999943e+01,0.000000000000000000e+00,6.123605462349163808e+00,0.000000000000000000e+00,-1.000000009970417159e+00,0.000000000000000000e+00,4.315730825487362099e-10,0.000000000000000000e+00 +7.914210425290718831e+00,7.512000000000000455e+01,0.000000000000000000e+00,6.121972437465181827e+00,0.000000000000000000e+00,-1.000000009969712389e+00,0.000000000000000000e+00,-2.952510266090863266e-10,0.000000000000000000e+00 +7.915843885764798138e+00,7.512999999999999545e+01,0.000000000000000000e+00,6.120338976974817768e+00,0.000000000000000000e+00,-1.000000009970194670e+00,0.000000000000000000e+00,3.704601969907928692e-10,0.000000000000000000e+00 +7.917477782194002778e+00,7.514000000000000057e+01,0.000000000000000000e+00,6.118705080529323048e+00,0.000000000000000000e+00,-1.000000009969589376e+00,0.000000000000000000e+00,-5.729323532175845486e-10,0.000000000000000000e+00 +7.919112114927544965e+00,7.515000000000000568e+01,0.000000000000000000e+00,6.117070747779487228e+00,0.000000000000000000e+00,-1.000000009970525738e+00,0.000000000000000000e+00,5.274133510730416184e-10,0.000000000000000000e+00 +7.920746884315103209e+00,7.515999999999999659e+01,0.000000000000000000e+00,6.115435978375629134e+00,0.000000000000000000e+00,-1.000000009969663539e+00,0.000000000000000000e+00,-3.233158866081081261e-10,0.000000000000000000e+00 +7.922382090706824087e+00,7.517000000000000171e+01,0.000000000000000000e+00,6.113800771967605741e+00,0.000000000000000000e+00,-1.000000009970192227e+00,0.000000000000000000e+00,1.942634698589716602e-10,0.000000000000000000e+00 +7.924017734453321360e+00,7.518000000000000682e+01,0.000000000000000000e+00,6.112165128204800624e+00,0.000000000000000000e+00,-1.000000009969874482e+00,0.000000000000000000e+00,-2.486341469347940194e-10,0.000000000000000000e+00 +7.925653815905678634e+00,7.518999999999999773e+01,0.000000000000000000e+00,6.110529046736131953e+00,0.000000000000000000e+00,-1.000000009970281267e+00,0.000000000000000000e+00,3.371672870042649707e-10,0.000000000000000000e+00 +7.927290335415448475e+00,7.520000000000000284e+01,0.000000000000000000e+00,6.108892527210045387e+00,0.000000000000000000e+00,-1.000000009969729486e+00,0.000000000000000000e+00,-3.726158886384832984e-10,0.000000000000000000e+00 +7.928927293334655069e+00,7.521000000000000796e+01,0.000000000000000000e+00,6.107255569274518514e+00,0.000000000000000000e+00,-1.000000009970339443e+00,0.000000000000000000e+00,2.737931879962574704e-10,0.000000000000000000e+00 +7.930564690015794227e+00,7.521999999999999886e+01,0.000000000000000000e+00,6.105618172577053748e+00,0.000000000000000000e+00,-1.000000009969891135e+00,0.000000000000000000e+00,-4.419645814346660988e-11,0.000000000000000000e+00 +7.932202525811834271e+00,7.523000000000000398e+01,0.000000000000000000e+00,6.103980336764684544e+00,0.000000000000000000e+00,-1.000000009969963521e+00,0.000000000000000000e+00,-3.312489825336248764e-10,0.000000000000000000e+00 +7.933840801076216920e+00,7.523999999999999488e+01,0.000000000000000000e+00,6.102342061483968294e+00,0.000000000000000000e+00,-1.000000009970506198e+00,0.000000000000000000e+00,4.058201435818028468e-10,0.000000000000000000e+00 +7.935479516162858182e+00,7.525000000000000000e+01,0.000000000000000000e+00,6.100703346380988101e+00,0.000000000000000000e+00,-1.000000009969841175e+00,0.000000000000000000e+00,-1.465707781985565514e-10,0.000000000000000000e+00 +7.937118671426149241e+00,7.526000000000000512e+01,0.000000000000000000e+00,6.099064191101354560e+00,0.000000000000000000e+00,-1.000000009970081427e+00,0.000000000000000000e+00,-4.062792896176517921e-13,0.000000000000000000e+00 +7.938758267220958231e+00,7.526999999999999602e+01,0.000000000000000000e+00,6.097424595290198646e+00,0.000000000000000000e+00,-1.000000009970082093e+00,0.000000000000000000e+00,-1.444611551087913490e-10,0.000000000000000000e+00 +7.940398303902629351e+00,7.528000000000000114e+01,0.000000000000000000e+00,6.095784558592176161e+00,0.000000000000000000e+00,-1.000000009970319015e+00,0.000000000000000000e+00,8.676166234472725779e-11,0.000000000000000000e+00 +7.942038781826985527e+00,7.529000000000000625e+01,0.000000000000000000e+00,6.094144080651464179e+00,0.000000000000000000e+00,-1.000000009970176684e+00,0.000000000000000000e+00,3.829476235726857381e-11,0.000000000000000000e+00 +7.943679701350327527e+00,7.529999999999999716e+01,0.000000000000000000e+00,6.092503161111761933e+00,0.000000000000000000e+00,-1.000000009970113846e+00,0.000000000000000000e+00,4.613073429780258231e-11,0.000000000000000000e+00 +7.945321062829436620e+00,7.531000000000000227e+01,0.000000000000000000e+00,6.090861799616288152e+00,0.000000000000000000e+00,-1.000000009970038128e+00,0.000000000000000000e+00,1.176625411695424512e-10,0.000000000000000000e+00 +7.946962866621574584e+00,7.532000000000000739e+01,0.000000000000000000e+00,6.089219995807781061e+00,0.000000000000000000e+00,-1.000000009969844950e+00,0.000000000000000000e+00,-3.984575187053869156e-10,0.000000000000000000e+00 +7.948605113084485474e+00,7.532999999999999829e+01,0.000000000000000000e+00,6.087577749328497490e+00,0.000000000000000000e+00,-1.000000009970499315e+00,0.000000000000000000e+00,1.534195158800565399e-10,0.000000000000000000e+00 +7.950247802576394740e+00,7.534000000000000341e+01,0.000000000000000000e+00,6.085935059820210213e+00,0.000000000000000000e+00,-1.000000009970247294e+00,0.000000000000000000e+00,1.358105791186961258e-10,0.000000000000000000e+00 +7.951890935456011000e+00,7.535000000000000853e+01,0.000000000000000000e+00,6.084291926924211502e+00,0.000000000000000000e+00,-1.000000009970024140e+00,0.000000000000000000e+00,-1.111859994264691498e-10,0.000000000000000000e+00 +7.953534512082527819e+00,7.535999999999999943e+01,0.000000000000000000e+00,6.082648350281307792e+00,0.000000000000000000e+00,-1.000000009970206882e+00,0.000000000000000000e+00,8.090209306518276241e-11,0.000000000000000000e+00 +7.955178532815624592e+00,7.537000000000000455e+01,0.000000000000000000e+00,6.081004329531819685e+00,0.000000000000000000e+00,-1.000000009970073878e+00,0.000000000000000000e+00,6.683758309296573625e-11,0.000000000000000000e+00 +7.956822998015465664e+00,7.537999999999999545e+01,0.000000000000000000e+00,6.079359864315582840e+00,0.000000000000000000e+00,-1.000000009969963966e+00,0.000000000000000000e+00,-1.406584399758345515e-10,0.000000000000000000e+00 +7.958467908042703876e+00,7.539000000000000057e+01,0.000000000000000000e+00,6.077714954271945302e+00,0.000000000000000000e+00,-1.000000009970195336e+00,0.000000000000000000e+00,-1.995945723669169328e-10,0.000000000000000000e+00 +7.960113263258477900e+00,7.540000000000000568e+01,0.000000000000000000e+00,6.076069599039766622e+00,0.000000000000000000e+00,-1.000000009970523740e+00,0.000000000000000000e+00,2.320552574619138810e-10,0.000000000000000000e+00 +7.961759064024417576e+00,7.540999999999999659e+01,0.000000000000000000e+00,6.074423798257417850e+00,0.000000000000000000e+00,-1.000000009970141823e+00,0.000000000000000000e+00,1.851892833528142338e-10,0.000000000000000000e+00 +7.963405310702640350e+00,7.542000000000000171e+01,0.000000000000000000e+00,6.072777551562781539e+00,0.000000000000000000e+00,-1.000000009969836956e+00,0.000000000000000000e+00,-3.226786988916815479e-10,0.000000000000000000e+00 +7.965052003655756607e+00,7.543000000000000682e+01,0.000000000000000000e+00,6.071130858593248192e+00,0.000000000000000000e+00,-1.000000009970368309e+00,0.000000000000000000e+00,3.477999580596819782e-11,0.000000000000000000e+00 +7.966699143246867010e+00,7.543999999999999773e+01,0.000000000000000000e+00,6.069483718985715370e+00,0.000000000000000000e+00,-1.000000009970311021e+00,0.000000000000000000e+00,-3.450102053071597701e-11,0.000000000000000000e+00 +7.968346729839565157e+00,7.545000000000000284e+01,0.000000000000000000e+00,6.067836132376590363e+00,0.000000000000000000e+00,-1.000000009970367865e+00,0.000000000000000000e+00,1.425475432815666437e-10,0.000000000000000000e+00 +7.969994763797938475e+00,7.546000000000000796e+01,0.000000000000000000e+00,6.066188098401785744e+00,0.000000000000000000e+00,-1.000000009970132941e+00,0.000000000000000000e+00,-6.882987775920917488e-11,0.000000000000000000e+00 +7.971643245486568219e+00,7.546999999999999886e+01,0.000000000000000000e+00,6.064539616696720259e+00,0.000000000000000000e+00,-1.000000009970246406e+00,0.000000000000000000e+00,5.521053043290658414e-12,0.000000000000000000e+00 +7.973292175270532134e+00,7.548000000000000398e+01,0.000000000000000000e+00,6.062890686896316161e+00,0.000000000000000000e+00,-1.000000009970237302e+00,0.000000000000000000e+00,5.990733144376171299e-11,0.000000000000000000e+00 +7.974941553515403569e+00,7.548999999999999488e+01,0.000000000000000000e+00,6.061241308635000102e+00,0.000000000000000000e+00,-1.000000009970138493e+00,0.000000000000000000e+00,-2.106280183159231335e-10,0.000000000000000000e+00 +7.976591380587253255e+00,7.550000000000000000e+01,0.000000000000000000e+00,6.059591481546701353e+00,0.000000000000000000e+00,-1.000000009970485992e+00,0.000000000000000000e+00,1.961738411736544400e-10,0.000000000000000000e+00 +7.978241656852650188e+00,7.551000000000000512e+01,0.000000000000000000e+00,6.057941205264850026e+00,0.000000000000000000e+00,-1.000000009970162251e+00,0.000000000000000000e+00,-1.614159793898521877e-12,0.000000000000000000e+00 +7.979892382678663409e+00,7.551999999999999602e+01,0.000000000000000000e+00,6.056290479422378858e+00,0.000000000000000000e+00,-1.000000009970164916e+00,0.000000000000000000e+00,-1.266770162459325627e-10,0.000000000000000000e+00 +7.981543558432861118e+00,7.553000000000000114e+01,0.000000000000000000e+00,6.054639303651718762e+00,0.000000000000000000e+00,-1.000000009970374082e+00,0.000000000000000000e+00,1.712765589990070598e-10,0.000000000000000000e+00 +7.983195184483312445e+00,7.554000000000000625e+01,0.000000000000000000e+00,6.052987677584799719e+00,0.000000000000000000e+00,-1.000000009970091197e+00,0.000000000000000000e+00,-3.835870916863330780e-10,0.000000000000000000e+00 +7.984847261198590118e+00,7.554999999999999716e+01,0.000000000000000000e+00,6.051335600853050778e+00,0.000000000000000000e+00,-1.000000009970724912e+00,0.000000000000000000e+00,5.135493067789456430e-10,0.000000000000000000e+00 +7.986499788947768685e+00,7.556000000000000227e+01,0.000000000000000000e+00,6.049683073087395613e+00,0.000000000000000000e+00,-1.000000009969876258e+00,0.000000000000000000e+00,-3.628251916778303598e-10,0.000000000000000000e+00 +7.988152768100426293e+00,7.557000000000000739e+01,0.000000000000000000e+00,6.048030093918257855e+00,0.000000000000000000e+00,-1.000000009970476000e+00,0.000000000000000000e+00,-5.653745626198661888e-11,0.000000000000000000e+00 +7.989806199026647349e+00,7.557999999999999829e+01,0.000000000000000000e+00,6.046376662975551319e+00,0.000000000000000000e+00,-1.000000009970569481e+00,0.000000000000000000e+00,1.601680423608494208e-10,0.000000000000000000e+00 +7.991460082097021633e+00,7.559000000000000341e+01,0.000000000000000000e+00,6.044722779888687114e+00,0.000000000000000000e+00,-1.000000009970304582e+00,0.000000000000000000e+00,-5.771451750629398225e-12,0.000000000000000000e+00 +7.993114417682645190e+00,7.560000000000000853e+01,0.000000000000000000e+00,6.043068444286569196e+00,0.000000000000000000e+00,-1.000000009970314130e+00,0.000000000000000000e+00,1.253269916060263503e-10,0.000000000000000000e+00 +7.994769206155122987e+00,7.560999999999999943e+01,0.000000000000000000e+00,6.041413655797592597e+00,0.000000000000000000e+00,-1.000000009970106740e+00,0.000000000000000000e+00,-3.866097254780745534e-10,0.000000000000000000e+00 +7.996424447886568032e+00,7.562000000000000455e+01,0.000000000000000000e+00,6.039758414049644308e+00,0.000000000000000000e+00,-1.000000009970746673e+00,0.000000000000000000e+00,4.355879063851651861e-10,0.000000000000000000e+00 +7.998080143249604035e+00,7.562999999999999545e+01,0.000000000000000000e+00,6.038102718670099733e+00,0.000000000000000000e+00,-1.000000009970025472e+00,0.000000000000000000e+00,-2.905357863482583888e-10,0.000000000000000000e+00 +7.999736292617364519e+00,7.564000000000000057e+01,0.000000000000000000e+00,6.036446569285827124e+00,0.000000000000000000e+00,-1.000000009970506643e+00,0.000000000000000000e+00,6.138850602816845742e-11,0.000000000000000000e+00 +8.001392896363496376e+00,7.565000000000000568e+01,0.000000000000000000e+00,6.034789965523178701e+00,0.000000000000000000e+00,-1.000000009970404946e+00,0.000000000000000000e+00,2.310147162579037164e-10,0.000000000000000000e+00 +8.003049954862156312e+00,7.565999999999999659e+01,0.000000000000000000e+00,6.033132907007996870e+00,0.000000000000000000e+00,-1.000000009970022141e+00,0.000000000000000000e+00,-3.911703869366644885e-10,0.000000000000000000e+00 +8.004707468488017952e+00,7.567000000000000171e+01,0.000000000000000000e+00,6.031475393365609783e+00,0.000000000000000000e+00,-1.000000009970670511e+00,0.000000000000000000e+00,1.715587667239525549e-10,0.000000000000000000e+00 +8.006365437616267400e+00,7.568000000000000682e+01,0.000000000000000000e+00,6.029817424220828670e+00,0.000000000000000000e+00,-1.000000009970386072e+00,0.000000000000000000e+00,1.820888261714409907e-11,0.000000000000000000e+00 +8.008023862622609457e+00,7.568999999999999773e+01,0.000000000000000000e+00,6.028158999197952284e+00,0.000000000000000000e+00,-1.000000009970355874e+00,0.000000000000000000e+00,-1.659765027418704922e-10,0.000000000000000000e+00 +8.009682743883262290e+00,7.570000000000000284e+01,0.000000000000000000e+00,6.026500117920760680e+00,0.000000000000000000e+00,-1.000000009970631210e+00,0.000000000000000000e+00,3.046971734589470313e-10,0.000000000000000000e+00 +8.011342081774962764e+00,7.571000000000000796e+01,0.000000000000000000e+00,6.024840780012516106e+00,0.000000000000000000e+00,-1.000000009970125614e+00,0.000000000000000000e+00,-1.428752661304015043e-10,0.000000000000000000e+00 +8.013001876674966439e+00,7.571999999999999886e+01,0.000000000000000000e+00,6.023180985095963891e+00,0.000000000000000000e+00,-1.000000009970362758e+00,0.000000000000000000e+00,-1.761375347213741407e-10,0.000000000000000000e+00 +8.014662128961049348e+00,7.573000000000000398e+01,0.000000000000000000e+00,6.021520732793327113e+00,0.000000000000000000e+00,-1.000000009970655190e+00,0.000000000000000000e+00,2.466850224537006937e-10,0.000000000000000000e+00 +8.016322839011507995e+00,7.573999999999999488e+01,0.000000000000000000e+00,6.019860022726309268e+00,0.000000000000000000e+00,-1.000000009970245518e+00,0.000000000000000000e+00,-1.194989631762526497e-10,0.000000000000000000e+00 +8.017984007205161134e+00,7.575000000000000000e+01,0.000000000000000000e+00,6.018198854516093377e+00,0.000000000000000000e+00,-1.000000009970444026e+00,0.000000000000000000e+00,5.786216181758937708e-11,0.000000000000000000e+00 +8.019645633921349770e+00,7.576000000000000512e+01,0.000000000000000000e+00,6.016537227783337549e+00,0.000000000000000000e+00,-1.000000009970347881e+00,0.000000000000000000e+00,-1.416096009665487758e-10,0.000000000000000000e+00 +8.021307719539938930e+00,7.576999999999999602e+01,0.000000000000000000e+00,6.014875142148177645e+00,0.000000000000000000e+00,-1.000000009970583248e+00,0.000000000000000000e+00,-2.871476735415119714e-11,0.000000000000000000e+00 +8.022970264441315891e+00,7.578000000000000114e+01,0.000000000000000000e+00,6.013212597230223722e+00,0.000000000000000000e+00,-1.000000009970630988e+00,0.000000000000000000e+00,1.221709295166218972e-10,0.000000000000000000e+00 +8.024633269006397285e+00,7.579000000000000625e+01,0.000000000000000000e+00,6.011549592648560925e+00,0.000000000000000000e+00,-1.000000009970427817e+00,0.000000000000000000e+00,3.737530032003271406e-11,0.000000000000000000e+00 +8.026296733616625545e+00,7.579999999999999716e+01,0.000000000000000000e+00,6.009886128021747709e+00,0.000000000000000000e+00,-1.000000009970365644e+00,0.000000000000000000e+00,-2.336644346937717453e-10,0.000000000000000000e+00 +8.027960658653968906e+00,7.581000000000000227e+01,0.000000000000000000e+00,6.008222202967814063e+00,0.000000000000000000e+00,-1.000000009970754444e+00,0.000000000000000000e+00,3.205826260839574331e-10,0.000000000000000000e+00 +8.029625044500926734e+00,7.582000000000000739e+01,0.000000000000000000e+00,6.006557817104260621e+00,0.000000000000000000e+00,-1.000000009970220871e+00,0.000000000000000000e+00,-1.733840884695756037e-10,0.000000000000000000e+00 +8.031289891540527748e+00,7.582999999999999829e+01,0.000000000000000000e+00,6.004892970048060441e+00,0.000000000000000000e+00,-1.000000009970509529e+00,0.000000000000000000e+00,-6.093428178281985911e-11,0.000000000000000000e+00 +8.032955200156331799e+00,7.584000000000000341e+01,0.000000000000000000e+00,6.003227661415652783e+00,0.000000000000000000e+00,-1.000000009970611003e+00,0.000000000000000000e+00,6.904858748354021622e-11,0.000000000000000000e+00 +8.034620970732429868e+00,7.585000000000000853e+01,0.000000000000000000e+00,6.001561890822946665e+00,0.000000000000000000e+00,-1.000000009970495984e+00,0.000000000000000000e+00,-5.050608723737630312e-11,0.000000000000000000e+00 +8.036287203653445843e+00,7.585999999999999943e+01,0.000000000000000000e+00,5.999895657885318201e+00,0.000000000000000000e+00,-1.000000009970580139e+00,0.000000000000000000e+00,-4.502986277999359982e-11,0.000000000000000000e+00 +8.037953899304536520e+00,7.587000000000000455e+01,0.000000000000000000e+00,5.998228962217608817e+00,0.000000000000000000e+00,-1.000000009970655190e+00,0.000000000000000000e+00,1.401131847934094882e-10,0.000000000000000000e+00 +8.039621058071396931e+00,7.587999999999999545e+01,0.000000000000000000e+00,5.996561803434125260e+00,0.000000000000000000e+00,-1.000000009970421599e+00,0.000000000000000000e+00,-7.815929633760612740e-11,0.000000000000000000e+00 +8.041288680340256789e+00,7.589000000000000057e+01,0.000000000000000000e+00,5.994894181148638701e+00,0.000000000000000000e+00,-1.000000009970551940e+00,0.000000000000000000e+00,-3.860288339059504200e-12,0.000000000000000000e+00 +8.042956766497882271e+00,7.590000000000000568e+01,0.000000000000000000e+00,5.993226094974382079e+00,0.000000000000000000e+00,-1.000000009970558379e+00,0.000000000000000000e+00,1.007387985007125842e-10,0.000000000000000000e+00 +8.044625316931577785e+00,7.590999999999999659e+01,0.000000000000000000e+00,5.991557544524050982e+00,0.000000000000000000e+00,-1.000000009970390291e+00,0.000000000000000000e+00,-2.394707450146980285e-11,0.000000000000000000e+00 +8.046294332029185981e+00,7.592000000000000171e+01,0.000000000000000000e+00,5.989888529409801876e+00,0.000000000000000000e+00,-1.000000009970430259e+00,0.000000000000000000e+00,-3.184073702346316510e-10,0.000000000000000000e+00 +8.047963812179091292e+00,7.593000000000000682e+01,0.000000000000000000e+00,5.988219049243250325e+00,0.000000000000000000e+00,-1.000000009970961834e+00,0.000000000000000000e+00,2.338857398336031098e-10,0.000000000000000000e+00 +8.049633757770219944e+00,7.593999999999999773e+01,0.000000000000000000e+00,5.986549103635470104e+00,0.000000000000000000e+00,-1.000000009970571258e+00,0.000000000000000000e+00,1.007594945380426941e-10,0.000000000000000000e+00 +8.051304169192039950e+00,7.595000000000000284e+01,0.000000000000000000e+00,5.984878692196994976e+00,0.000000000000000000e+00,-1.000000009970402948e+00,0.000000000000000000e+00,-1.754161232647718074e-11,0.000000000000000000e+00 +8.052975046834562889e+00,7.596000000000000796e+01,0.000000000000000000e+00,5.983207814537813363e+00,0.000000000000000000e+00,-1.000000009970432258e+00,0.000000000000000000e+00,-5.792430106984461712e-11,0.000000000000000000e+00 +8.054646391088342128e+00,7.596999999999999886e+01,0.000000000000000000e+00,5.981536470267369232e+00,0.000000000000000000e+00,-1.000000009970529069e+00,0.000000000000000000e+00,-2.741338550523020324e-10,0.000000000000000000e+00 +8.056318202344481705e+00,7.598000000000000398e+01,0.000000000000000000e+00,5.979864658994561211e+00,0.000000000000000000e+00,-1.000000009970987369e+00,0.000000000000000000e+00,3.518661217135751867e-10,0.000000000000000000e+00 +8.057990480994627447e+00,7.598999999999999488e+01,0.000000000000000000e+00,5.978192380327740807e+00,0.000000000000000000e+00,-1.000000009970398951e+00,0.000000000000000000e+00,-1.991138047883558661e-11,0.000000000000000000e+00 +8.059663227430975851e+00,7.600000000000000000e+01,0.000000000000000000e+00,5.976519633874714188e+00,0.000000000000000000e+00,-1.000000009970432258e+00,0.000000000000000000e+00,-3.687882901845592025e-10,0.000000000000000000e+00 +8.061336442046270534e+00,7.601000000000000512e+01,0.000000000000000000e+00,5.974846419242735962e+00,0.000000000000000000e+00,-1.000000009971049320e+00,0.000000000000000000e+00,3.238431769274966969e-10,0.000000000000000000e+00 +8.063010125233807557e+00,7.601999999999999602e+01,0.000000000000000000e+00,5.973172736038510955e+00,0.000000000000000000e+00,-1.000000009970507309e+00,0.000000000000000000e+00,-9.297438570061702338e-11,0.000000000000000000e+00 +8.064684277387430100e+00,7.603000000000000114e+01,0.000000000000000000e+00,5.971498583868195986e+00,0.000000000000000000e+00,-1.000000009970662962e+00,0.000000000000000000e+00,3.580035418436573008e-11,0.000000000000000000e+00 +8.066358898901535568e+00,7.604000000000000625e+01,0.000000000000000000e+00,5.969823962337392764e+00,0.000000000000000000e+00,-1.000000009970603010e+00,0.000000000000000000e+00,1.467402893930434832e-10,0.000000000000000000e+00 +8.068033990171075587e+00,7.604999999999999716e+01,0.000000000000000000e+00,5.968148871051151438e+00,0.000000000000000000e+00,-1.000000009970357207e+00,0.000000000000000000e+00,-3.208297720117511503e-10,0.000000000000000000e+00 +8.069709551591552454e+00,7.606000000000000227e+01,0.000000000000000000e+00,5.966473309613967935e+00,0.000000000000000000e+00,-1.000000009970894777e+00,0.000000000000000000e+00,2.872216716741223234e-10,0.000000000000000000e+00 +8.071385583559028021e+00,7.607000000000000739e+01,0.000000000000000000e+00,5.964797277629781291e+00,0.000000000000000000e+00,-1.000000009970413384e+00,0.000000000000000000e+00,-1.695297350360584998e-10,0.000000000000000000e+00 +8.073062086470116583e+00,7.607999999999999829e+01,0.000000000000000000e+00,5.963120774701977211e+00,0.000000000000000000e+00,-1.000000009970697601e+00,0.000000000000000000e+00,-3.561771962689768158e-11,0.000000000000000000e+00 +8.074739060721991990e+00,7.609000000000000341e+01,0.000000000000000000e+00,5.961443800433380957e+00,0.000000000000000000e+00,-1.000000009970757331e+00,0.000000000000000000e+00,1.321059020583107235e-10,0.000000000000000000e+00 +8.076416506712385868e+00,7.610000000000000853e+01,0.000000000000000000e+00,5.959766354426260904e+00,0.000000000000000000e+00,-1.000000009970535730e+00,0.000000000000000000e+00,-2.212614390506730364e-10,0.000000000000000000e+00 +8.078094424839591170e+00,7.610999999999999943e+01,0.000000000000000000e+00,5.958088436282325873e+00,0.000000000000000000e+00,-1.000000009970906989e+00,0.000000000000000000e+00,2.436894885800465775e-10,0.000000000000000000e+00 +8.079772815502458627e+00,7.612000000000000455e+01,0.000000000000000000e+00,5.956410045602722469e+00,0.000000000000000000e+00,-1.000000009970497983e+00,0.000000000000000000e+00,-2.866049746157694941e-10,0.000000000000000000e+00 +8.081451679100403851e+00,7.612999999999999545e+01,0.000000000000000000e+00,5.954731181988037747e+00,0.000000000000000000e+00,-1.000000009970979153e+00,0.000000000000000000e+00,1.578725823690722447e-10,0.000000000000000000e+00 +8.083131016033403782e+00,7.614000000000000057e+01,0.000000000000000000e+00,5.953051845038292988e+00,0.000000000000000000e+00,-1.000000009970714032e+00,0.000000000000000000e+00,8.195426879184489827e-11,0.000000000000000000e+00 +8.084810826702000242e+00,7.615000000000000568e+01,0.000000000000000000e+00,5.951372034352948148e+00,0.000000000000000000e+00,-1.000000009970576365e+00,0.000000000000000000e+00,-1.174786876343374785e-10,0.000000000000000000e+00 +8.086491111507298157e+00,7.615999999999999659e+01,0.000000000000000000e+00,5.949691749530896523e+00,0.000000000000000000e+00,-1.000000009970773762e+00,0.000000000000000000e+00,-4.425674795733525273e-11,0.000000000000000000e+00 +8.088171870850970890e+00,7.617000000000000171e+01,0.000000000000000000e+00,5.948010990170464751e+00,0.000000000000000000e+00,-1.000000009970848147e+00,0.000000000000000000e+00,7.026250352139412096e-11,0.000000000000000000e+00 +8.089853105135260236e+00,7.618000000000000682e+01,0.000000000000000000e+00,5.946329755869412814e+00,0.000000000000000000e+00,-1.000000009970730019e+00,0.000000000000000000e+00,-4.225121412467141060e-12,0.000000000000000000e+00 +8.091534814762972871e+00,7.618999999999999773e+01,0.000000000000000000e+00,5.944648046224932258e+00,0.000000000000000000e+00,-1.000000009970737125e+00,0.000000000000000000e+00,1.316017095761847153e-10,0.000000000000000000e+00 +8.093217000137487460e+00,7.620000000000000284e+01,0.000000000000000000e+00,5.942965860833644420e+00,0.000000000000000000e+00,-1.000000009970515746e+00,0.000000000000000000e+00,-3.780664046557278737e-10,0.000000000000000000e+00 +8.094899661662754653e+00,7.621000000000000796e+01,0.000000000000000000e+00,5.941283199291600425e+00,0.000000000000000000e+00,-1.000000009971151904e+00,0.000000000000000000e+00,4.360054755827289221e-10,0.000000000000000000e+00 +8.096582799743295311e+00,7.621999999999999886e+01,0.000000000000000000e+00,5.939600061194277636e+00,0.000000000000000000e+00,-1.000000009970418047e+00,0.000000000000000000e+00,-1.606366789482700659e-10,0.000000000000000000e+00 +8.098266414784202283e+00,7.623000000000000398e+01,0.000000000000000000e+00,5.937916446136584092e+00,0.000000000000000000e+00,-1.000000009970688497e+00,0.000000000000000000e+00,-1.976404984729005443e-10,0.000000000000000000e+00 +8.099950507191145732e+00,7.623999999999999488e+01,0.000000000000000000e+00,5.936232353712849630e+00,0.000000000000000000e+00,-1.000000009971021342e+00,0.000000000000000000e+00,1.003080467837475657e-10,0.000000000000000000e+00 +8.101635077370367810e+00,7.625000000000000000e+01,0.000000000000000000e+00,5.934547783516830322e+00,0.000000000000000000e+00,-1.000000009970852366e+00,0.000000000000000000e+00,1.985825617225570244e-10,0.000000000000000000e+00 +8.103320125728689760e+00,7.626000000000000512e+01,0.000000000000000000e+00,5.932862735141706700e+00,0.000000000000000000e+00,-1.000000009970517745e+00,0.000000000000000000e+00,-1.242270632859338856e-10,0.000000000000000000e+00 +8.105005652673510141e+00,7.626999999999999602e+01,0.000000000000000000e+00,5.931177208180081095e+00,0.000000000000000000e+00,-1.000000009970727133e+00,0.000000000000000000e+00,-1.488194066921686736e-10,0.000000000000000000e+00 +8.106691658612804829e+00,7.628000000000000114e+01,0.000000000000000000e+00,5.929491202223975854e+00,0.000000000000000000e+00,-1.000000009970978043e+00,0.000000000000000000e+00,-9.505935256738840469e-11,0.000000000000000000e+00 +8.108378143955130568e+00,7.629000000000000625e+01,0.000000000000000000e+00,5.927804716864834234e+00,0.000000000000000000e+00,-1.000000009971138359e+00,0.000000000000000000e+00,4.439667591334980225e-10,0.000000000000000000e+00 +8.110065109109624970e+00,7.629999999999999716e+01,0.000000000000000000e+00,5.926117751693518620e+00,0.000000000000000000e+00,-1.000000009970389403e+00,0.000000000000000000e+00,-3.080434053773678842e-10,0.000000000000000000e+00 +8.111752554486008293e+00,7.631000000000000227e+01,0.000000000000000000e+00,5.924430306300310534e+00,0.000000000000000000e+00,-1.000000009970909209e+00,0.000000000000000000e+00,-7.037859659210589662e-11,0.000000000000000000e+00 +8.113440480494583440e+00,7.632000000000000739e+01,0.000000000000000000e+00,5.922742380274904406e+00,0.000000000000000000e+00,-1.000000009971028003e+00,0.000000000000000000e+00,3.183888553392032366e-10,0.000000000000000000e+00 +8.115128887546239511e+00,7.632999999999999829e+01,0.000000000000000000e+00,5.921053973206412913e+00,0.000000000000000000e+00,-1.000000009970490433e+00,0.000000000000000000e+00,-2.891109060394670005e-10,0.000000000000000000e+00 +8.116817776052450029e+00,7.634000000000000341e+01,0.000000000000000000e+00,5.919365084683363420e+00,0.000000000000000000e+00,-1.000000009970978709e+00,0.000000000000000000e+00,7.610162242669786858e-11,0.000000000000000000e+00 +8.118507146425274712e+00,7.635000000000000853e+01,0.000000000000000000e+00,5.917675714293693545e+00,0.000000000000000000e+00,-1.000000009970850146e+00,0.000000000000000000e+00,-4.217901371035893724e-11,0.000000000000000000e+00 +8.120196999077363031e+00,7.635999999999999943e+01,0.000000000000000000e+00,5.915985861624755593e+00,0.000000000000000000e+00,-1.000000009970921422e+00,0.000000000000000000e+00,7.999901607224027658e-11,0.000000000000000000e+00 +8.121887334421952431e+00,7.637000000000000455e+01,0.000000000000000000e+00,5.914295526263311231e+00,0.000000000000000000e+00,-1.000000009970786197e+00,0.000000000000000000e+00,-7.629909372661688961e-11,0.000000000000000000e+00 +8.123578152872871883e+00,7.637999999999999545e+01,0.000000000000000000e+00,5.912604707795532377e+00,0.000000000000000000e+00,-1.000000009970915205e+00,0.000000000000000000e+00,-9.636406906925288607e-11,0.000000000000000000e+00 +8.125269454844541883e+00,7.639000000000000057e+01,0.000000000000000000e+00,5.910913405806998533e+00,0.000000000000000000e+00,-1.000000009971078185e+00,0.000000000000000000e+00,1.240299678181869338e-10,0.000000000000000000e+00 +8.126961240751974458e+00,7.640000000000000568e+01,0.000000000000000000e+00,5.909221619882696785e+00,0.000000000000000000e+00,-1.000000009970868353e+00,0.000000000000000000e+00,7.019792673006992415e-11,0.000000000000000000e+00 +8.128653511010776711e+00,7.640999999999999659e+01,0.000000000000000000e+00,5.907529349607020919e+00,0.000000000000000000e+00,-1.000000009970749559e+00,0.000000000000000000e+00,-1.508495273593995778e-10,0.000000000000000000e+00 +8.130346266037150826e+00,7.642000000000000171e+01,0.000000000000000000e+00,5.905836594563768749e+00,0.000000000000000000e+00,-1.000000009971004911e+00,0.000000000000000000e+00,1.883111744270487282e-10,0.000000000000000000e+00 +8.132039506247895844e+00,7.643000000000000682e+01,0.000000000000000000e+00,5.904143354336141236e+00,0.000000000000000000e+00,-1.000000009970686055e+00,0.000000000000000000e+00,-3.523922783900245452e-10,0.000000000000000000e+00 +8.133733232060405882e+00,7.643999999999999773e+01,0.000000000000000000e+00,5.902449628506743373e+00,0.000000000000000000e+00,-1.000000009971282910e+00,0.000000000000000000e+00,1.950183358627296210e-10,0.000000000000000000e+00 +8.135427443892677246e+00,7.645000000000000284e+01,0.000000000000000000e+00,5.900755416657578856e+00,0.000000000000000000e+00,-1.000000009970952508e+00,0.000000000000000000e+00,8.346170866448681901e-11,0.000000000000000000e+00 +8.137122142163303096e+00,7.646000000000000796e+01,0.000000000000000000e+00,5.899060718370054524e+00,0.000000000000000000e+00,-1.000000009970811066e+00,0.000000000000000000e+00,4.427308570440664989e-11,0.000000000000000000e+00 +8.138817327291480552e+00,7.646999999999999886e+01,0.000000000000000000e+00,5.897365533224974143e+00,0.000000000000000000e+00,-1.000000009970736015e+00,0.000000000000000000e+00,-1.186387249130632894e-10,0.000000000000000000e+00 +8.140512999697008922e+00,7.648000000000000398e+01,0.000000000000000000e+00,5.895669860802539297e+00,0.000000000000000000e+00,-1.000000009970937187e+00,0.000000000000000000e+00,1.754196257913821131e-11,0.000000000000000000e+00 +8.142209159800287921e+00,7.648999999999999488e+01,0.000000000000000000e+00,5.893973700682347605e+00,0.000000000000000000e+00,-1.000000009970907433e+00,0.000000000000000000e+00,-5.025504237337100476e-11,0.000000000000000000e+00 +8.143905808022326553e+00,7.650000000000000000e+01,0.000000000000000000e+00,5.892277052443392726e+00,0.000000000000000000e+00,-1.000000009970992698e+00,0.000000000000000000e+00,1.029670135882054796e-10,0.000000000000000000e+00 +8.145602944784736010e+00,7.651000000000000512e+01,0.000000000000000000e+00,5.890579915664061694e+00,0.000000000000000000e+00,-1.000000009970817949e+00,0.000000000000000000e+00,-3.311783813067271043e-10,0.000000000000000000e+00 +8.147300570509736772e+00,7.651999999999999602e+01,0.000000000000000000e+00,5.888882289922134916e+00,0.000000000000000000e+00,-1.000000009971380166e+00,0.000000000000000000e+00,3.065001605312974516e-10,0.000000000000000000e+00 +8.148998685620156834e+00,7.653000000000000114e+01,0.000000000000000000e+00,5.887184174794782621e+00,0.000000000000000000e+00,-1.000000009970859693e+00,0.000000000000000000e+00,-2.143836674109654596e-11,0.000000000000000000e+00 +8.150697290539435258e+00,7.654000000000000625e+01,0.000000000000000000e+00,5.885485569858568411e+00,0.000000000000000000e+00,-1.000000009970896109e+00,0.000000000000000000e+00,3.698358100367948394e-11,0.000000000000000000e+00 +8.152396385691620395e+00,7.654999999999999716e+01,0.000000000000000000e+00,5.883786474689442159e+00,0.000000000000000000e+00,-1.000000009970833270e+00,0.000000000000000000e+00,-3.199527992884131007e-10,0.000000000000000000e+00 +8.154095971501373441e+00,7.656000000000000227e+01,0.000000000000000000e+00,5.882086888862742668e+00,0.000000000000000000e+00,-1.000000009971377057e+00,0.000000000000000000e+00,2.595192205172629088e-10,0.000000000000000000e+00 +8.155796048393970210e+00,7.657000000000000739e+01,0.000000000000000000e+00,5.880386811953194126e+00,0.000000000000000000e+00,-1.000000009970935855e+00,0.000000000000000000e+00,5.444803054165352033e-11,0.000000000000000000e+00 +8.157496616795299360e+00,7.657999999999999829e+01,0.000000000000000000e+00,5.878686243534908762e+00,0.000000000000000000e+00,-1.000000009970843262e+00,0.000000000000000000e+00,-1.957995846635887707e-10,0.000000000000000000e+00 +8.159197677131865944e+00,7.659000000000000341e+01,0.000000000000000000e+00,5.876985183181380634e+00,0.000000000000000000e+00,-1.000000009971176329e+00,0.000000000000000000e+00,2.479410420984567680e-10,0.000000000000000000e+00 +8.160899229830793189e+00,7.660000000000000853e+01,0.000000000000000000e+00,5.875283630465486517e+00,0.000000000000000000e+00,-1.000000009970754444e+00,0.000000000000000000e+00,-3.292747382154212759e-10,0.000000000000000000e+00 +8.162601275319822491e+00,7.660999999999999943e+01,0.000000000000000000e+00,5.873581584959486790e+00,0.000000000000000000e+00,-1.000000009971314885e+00,0.000000000000000000e+00,3.470468489825061542e-10,0.000000000000000000e+00 +8.164303814027313422e+00,7.662000000000000455e+01,0.000000000000000000e+00,5.871879046235019217e+00,0.000000000000000000e+00,-1.000000009970724024e+00,0.000000000000000000e+00,-3.530742022573736652e-10,0.000000000000000000e+00 +8.166006846382247275e+00,7.662999999999999545e+01,0.000000000000000000e+00,5.870176013863104281e+00,0.000000000000000000e+00,-1.000000009971325321e+00,0.000000000000000000e+00,1.508081137311292628e-10,0.000000000000000000e+00 +8.167710372814228847e+00,7.664000000000000057e+01,0.000000000000000000e+00,5.868472487414136296e+00,0.000000000000000000e+00,-1.000000009971068415e+00,0.000000000000000000e+00,1.514158805088256317e-10,0.000000000000000000e+00 +8.169414393753484660e+00,7.665000000000000568e+01,0.000000000000000000e+00,5.866768466457889630e+00,0.000000000000000000e+00,-1.000000009970810400e+00,0.000000000000000000e+00,-2.180693495301812668e-10,0.000000000000000000e+00 +8.171118909630866511e+00,7.665999999999999659e+01,0.000000000000000000e+00,5.865063950563512485e+00,0.000000000000000000e+00,-1.000000009971182102e+00,0.000000000000000000e+00,9.220325118961463595e-11,0.000000000000000000e+00 +8.172823920877851478e+00,7.667000000000000171e+01,0.000000000000000000e+00,5.863358939299526007e+00,0.000000000000000000e+00,-1.000000009971024895e+00,0.000000000000000000e+00,-7.290792427578317994e-12,0.000000000000000000e+00 +8.174529427926545466e+00,7.668000000000000682e+01,0.000000000000000000e+00,5.861653432233826067e+00,0.000000000000000000e+00,-1.000000009971037329e+00,0.000000000000000000e+00,-7.496919478470606490e-11,0.000000000000000000e+00 +8.176235431209681437e+00,7.668999999999999773e+01,0.000000000000000000e+00,5.859947428933678815e+00,0.000000000000000000e+00,-1.000000009971165227e+00,0.000000000000000000e+00,2.459210755186769881e-11,0.000000000000000000e+00 +8.177941931160622957e+00,7.670000000000000284e+01,0.000000000000000000e+00,5.858240928965720684e+00,0.000000000000000000e+00,-1.000000009971123260e+00,0.000000000000000000e+00,1.233149671411194067e-10,0.000000000000000000e+00 +8.179648928213365977e+00,7.671000000000000796e+01,0.000000000000000000e+00,5.856533931895957501e+00,0.000000000000000000e+00,-1.000000009970912762e+00,0.000000000000000000e+00,-2.499391408751001286e-10,0.000000000000000000e+00 +8.181356422802535278e+00,7.671999999999999886e+01,0.000000000000000000e+00,5.854826437289762708e+00,0.000000000000000000e+00,-1.000000009971339532e+00,0.000000000000000000e+00,2.626065898808720793e-10,0.000000000000000000e+00 +8.183064415363391575e+00,7.673000000000000398e+01,0.000000000000000000e+00,5.853118444711874702e+00,0.000000000000000000e+00,-1.000000009970891002e+00,0.000000000000000000e+00,-3.302419219866708629e-10,0.000000000000000000e+00 +8.184772906331831521e+00,7.673999999999999488e+01,0.000000000000000000e+00,5.851409953726399493e+00,0.000000000000000000e+00,-1.000000009971455217e+00,0.000000000000000000e+00,2.436138771430451526e-10,0.000000000000000000e+00 +8.186481896144385928e+00,7.675000000000000000e+01,0.000000000000000000e+00,5.849700963896803607e+00,0.000000000000000000e+00,-1.000000009971038883e+00,0.000000000000000000e+00,-3.507015256536709386e-12,0.000000000000000000e+00 +8.188191385238225095e+00,7.676000000000000512e+01,0.000000000000000000e+00,5.847991474785919408e+00,0.000000000000000000e+00,-1.000000009971044879e+00,0.000000000000000000e+00,-1.480307050551121214e-11,0.000000000000000000e+00 +8.189901374051155258e+00,7.676999999999999602e+01,0.000000000000000000e+00,5.846281485955937995e+00,0.000000000000000000e+00,-1.000000009971070192e+00,0.000000000000000000e+00,4.997820761894002959e-11,0.000000000000000000e+00 +8.191611863021627471e+00,7.678000000000000114e+01,0.000000000000000000e+00,5.844570996968410981e+00,0.000000000000000000e+00,-1.000000009970984705e+00,0.000000000000000000e+00,-2.699331352594546331e-10,0.000000000000000000e+00 +8.193322852588728722e+00,7.679000000000000625e+01,0.000000000000000000e+00,5.842860007384248711e+00,0.000000000000000000e+00,-1.000000009971446557e+00,0.000000000000000000e+00,8.199413425262413976e-11,0.000000000000000000e+00 +8.195034343192194370e+00,7.679999999999999716e+01,0.000000000000000000e+00,5.841148516763717602e+00,0.000000000000000000e+00,-1.000000009971306225e+00,0.000000000000000000e+00,3.435741118475352371e-10,0.000000000000000000e+00 +8.196746335272399264e+00,7.681000000000000227e+01,0.000000000000000000e+00,5.839436524666441919e+00,0.000000000000000000e+00,-1.000000009970718029e+00,0.000000000000000000e+00,-2.445416599332819042e-10,0.000000000000000000e+00 +8.198458829270366621e+00,7.682000000000000739e+01,0.000000000000000000e+00,5.837724030651400220e+00,0.000000000000000000e+00,-1.000000009971136805e+00,0.000000000000000000e+00,-1.723992717642977605e-11,0.000000000000000000e+00 +8.200171825627764477e+00,7.682999999999999829e+01,0.000000000000000000e+00,5.836011034276921805e+00,0.000000000000000000e+00,-1.000000009971166337e+00,0.000000000000000000e+00,-3.511766411643626252e-11,0.000000000000000000e+00 +8.201885324786911013e+00,7.684000000000000341e+01,0.000000000000000000e+00,5.834297535100690268e+00,0.000000000000000000e+00,-1.000000009971226511e+00,0.000000000000000000e+00,-1.448340257557705716e-10,0.000000000000000000e+00 +8.203599327190771007e+00,7.685000000000000853e+01,0.000000000000000000e+00,5.832583532679739058e+00,0.000000000000000000e+00,-1.000000009971474757e+00,0.000000000000000000e+00,1.083993432094519124e-10,0.000000000000000000e+00 +8.205313833282962932e+00,7.685999999999999943e+01,0.000000000000000000e+00,5.830869026570450586e+00,0.000000000000000000e+00,-1.000000009971288906e+00,0.000000000000000000e+00,2.753854570939428760e-10,0.000000000000000000e+00 +8.207028843507757188e+00,7.687000000000000455e+01,0.000000000000000000e+00,5.829154016328556231e+00,0.000000000000000000e+00,-1.000000009970816617e+00,0.000000000000000000e+00,-3.938652886434423175e-10,0.000000000000000000e+00 +8.208744358310074318e+00,7.687999999999999545e+01,0.000000000000000000e+00,5.827438501509133673e+00,0.000000000000000000e+00,-1.000000009971492299e+00,0.000000000000000000e+00,6.909699834092013532e-11,0.000000000000000000e+00 +8.210460378135493897e+00,7.689000000000000057e+01,0.000000000000000000e+00,5.825722481666603336e+00,0.000000000000000000e+00,-1.000000009971373727e+00,0.000000000000000000e+00,3.120091435389015710e-10,0.000000000000000000e+00 +8.212176903430247421e+00,7.690000000000000568e+01,0.000000000000000000e+00,5.824005956354732838e+00,0.000000000000000000e+00,-1.000000009970838155e+00,0.000000000000000000e+00,-4.083891183041698138e-10,0.000000000000000000e+00 +8.213893934641228967e+00,7.690999999999999659e+01,0.000000000000000000e+00,5.822288925126631653e+00,0.000000000000000000e+00,-1.000000009971539372e+00,0.000000000000000000e+00,1.768561130782327219e-10,0.000000000000000000e+00 +8.215611472215986311e+00,7.692000000000000171e+01,0.000000000000000000e+00,5.820571387534747565e+00,0.000000000000000000e+00,-1.000000009971235615e+00,0.000000000000000000e+00,1.200664194516094525e-10,0.000000000000000000e+00 +8.217329516602731587e+00,7.693000000000000682e+01,0.000000000000000000e+00,5.818853343130871991e+00,0.000000000000000000e+00,-1.000000009971029336e+00,0.000000000000000000e+00,-1.139583682672513426e-10,0.000000000000000000e+00 +8.219048068250334182e+00,7.693999999999999773e+01,0.000000000000000000e+00,5.817134791466132882e+00,0.000000000000000000e+00,-1.000000009971225179e+00,0.000000000000000000e+00,-6.109567865760735963e-11,0.000000000000000000e+00 +8.220767127608331393e+00,7.695000000000000284e+01,0.000000000000000000e+00,5.815415732090994716e+00,0.000000000000000000e+00,-1.000000009971330206e+00,0.000000000000000000e+00,1.425574984332480080e-10,0.000000000000000000e+00 +8.222486695126921319e+00,7.696000000000000796e+01,0.000000000000000000e+00,5.813696164555258505e+00,0.000000000000000000e+00,-1.000000009971085069e+00,0.000000000000000000e+00,-2.379128456747668105e-10,0.000000000000000000e+00 +8.224206771256968196e+00,7.696999999999999886e+01,0.000000000000000000e+00,5.811976088408060015e+00,0.000000000000000000e+00,-1.000000009971494297e+00,0.000000000000000000e+00,1.655734509815052351e-10,0.000000000000000000e+00 +8.225927356450005945e+00,7.698000000000000398e+01,0.000000000000000000e+00,5.810255503197866211e+00,0.000000000000000000e+00,-1.000000009971209414e+00,0.000000000000000000e+00,2.012611984844852278e-11,0.000000000000000000e+00 +8.227648451158232845e+00,7.698999999999999488e+01,0.000000000000000000e+00,5.808534408472477928e+00,0.000000000000000000e+00,-1.000000009971174775e+00,0.000000000000000000e+00,-2.039100643845823051e-10,0.000000000000000000e+00 +8.229370055834520414e+00,7.700000000000000000e+01,0.000000000000000000e+00,5.806812803779024534e+00,0.000000000000000000e+00,-1.000000009971525827e+00,0.000000000000000000e+00,2.629028396518113777e-10,0.000000000000000000e+00 +8.231092170932408081e+00,7.701000000000000512e+01,0.000000000000000000e+00,5.805090688663963938e+00,0.000000000000000000e+00,-1.000000009971073078e+00,0.000000000000000000e+00,-2.048203629875686447e-10,0.000000000000000000e+00 +8.232814796906112065e+00,7.701999999999999602e+01,0.000000000000000000e+00,5.803368062673083472e+00,0.000000000000000000e+00,-1.000000009971425907e+00,0.000000000000000000e+00,6.249741858247326428e-11,0.000000000000000000e+00 +8.234537934210520049e+00,7.703000000000000114e+01,0.000000000000000000e+00,5.801644925351493676e+00,0.000000000000000000e+00,-1.000000009971318216e+00,0.000000000000000000e+00,4.212492334043501262e-11,0.000000000000000000e+00 +8.236261583301194733e+00,7.704000000000000625e+01,0.000000000000000000e+00,5.799921276243631851e+00,0.000000000000000000e+00,-1.000000009971245607e+00,0.000000000000000000e+00,-9.053523835509998622e-11,0.000000000000000000e+00 +8.237985744634377383e+00,7.704999999999999716e+01,0.000000000000000000e+00,5.798197114893257620e+00,0.000000000000000000e+00,-1.000000009971401704e+00,0.000000000000000000e+00,1.394317433829205768e-10,0.000000000000000000e+00 +8.239710418666986058e+00,7.706000000000000227e+01,0.000000000000000000e+00,5.796472440843452034e+00,0.000000000000000000e+00,-1.000000009971161230e+00,0.000000000000000000e+00,-2.848297933419132615e-10,0.000000000000000000e+00 +8.241435605856619162e+00,7.707000000000000739e+01,0.000000000000000000e+00,5.794747253636617579e+00,0.000000000000000000e+00,-1.000000009971652615e+00,0.000000000000000000e+00,3.076481443696799728e-10,0.000000000000000000e+00 +8.243161306661555443e+00,7.707999999999999829e+01,0.000000000000000000e+00,5.793021552814473729e+00,0.000000000000000000e+00,-1.000000009971121706e+00,0.000000000000000000e+00,-2.899340896266050070e-10,0.000000000000000000e+00 +8.244887521540755770e+00,7.709000000000000341e+01,0.000000000000000000e+00,5.791295337918060504e+00,0.000000000000000000e+00,-1.000000009971622195e+00,0.000000000000000000e+00,1.909599939688604130e-10,0.000000000000000000e+00 +8.246614250953866687e+00,7.710000000000000853e+01,0.000000000000000000e+00,5.789568608487730472e+00,0.000000000000000000e+00,-1.000000009971292458e+00,0.000000000000000000e+00,1.437236486332268001e-10,0.000000000000000000e+00 +8.248341495361220410e+00,7.710999999999999943e+01,0.000000000000000000e+00,5.787841364063154082e+00,0.000000000000000000e+00,-1.000000009971044213e+00,0.000000000000000000e+00,-2.468790341129194363e-10,0.000000000000000000e+00 +8.250069255223833053e+00,7.712000000000000455e+01,0.000000000000000000e+00,5.786113604183313441e+00,0.000000000000000000e+00,-1.000000009971470760e+00,0.000000000000000000e+00,9.597271560412979908e-11,0.000000000000000000e+00 +8.251797531003411734e+00,7.712999999999999545e+01,0.000000000000000000e+00,5.784385328386501435e+00,0.000000000000000000e+00,-1.000000009971304893e+00,0.000000000000000000e+00,-1.292097904305582433e-10,0.000000000000000000e+00 +8.253526323162351019e+00,7.714000000000000057e+01,0.000000000000000000e+00,5.782656536210323495e+00,0.000000000000000000e+00,-1.000000009971528270e+00,0.000000000000000000e+00,1.561353346175964887e-10,0.000000000000000000e+00 +8.255255632163738255e+00,7.715000000000000568e+01,0.000000000000000000e+00,5.780927227191692275e+00,0.000000000000000000e+00,-1.000000009971258264e+00,0.000000000000000000e+00,-4.787916409437767203e-11,0.000000000000000000e+00 +8.256985458471351791e+00,7.715999999999999659e+01,0.000000000000000000e+00,5.779197400866829426e+00,0.000000000000000000e+00,-1.000000009971341086e+00,0.000000000000000000e+00,4.183361107929131337e-11,0.000000000000000000e+00 +8.258715802549666307e+00,7.717000000000000171e+01,0.000000000000000000e+00,5.777467056771261156e+00,0.000000000000000000e+00,-1.000000009971268700e+00,0.000000000000000000e+00,-2.737613402448129085e-10,0.000000000000000000e+00 +8.260446664863849264e+00,7.718000000000000682e+01,0.000000000000000000e+00,5.775736194439819116e+00,0.000000000000000000e+00,-1.000000009971742543e+00,0.000000000000000000e+00,3.820481292046423000e-10,0.000000000000000000e+00 +8.262178045879766231e+00,7.718999999999999773e+01,0.000000000000000000e+00,5.774004813406636849e+00,0.000000000000000000e+00,-1.000000009971081072e+00,0.000000000000000000e+00,-4.639871469196114405e-10,0.000000000000000000e+00 +8.263909946063980883e+00,7.720000000000000284e+01,0.000000000000000000e+00,5.772272913205152456e+00,0.000000000000000000e+00,-1.000000009971884651e+00,0.000000000000000000e+00,3.437524920983085993e-10,0.000000000000000000e+00 +8.265642365883758558e+00,7.721000000000000796e+01,0.000000000000000000e+00,5.770540493368099710e+00,0.000000000000000000e+00,-1.000000009971289128e+00,0.000000000000000000e+00,3.972083890566826401e-11,0.000000000000000000e+00 +8.267375305807062702e+00,7.721999999999999886e+01,0.000000000000000000e+00,5.768807553427516055e+00,0.000000000000000000e+00,-1.000000009971220294e+00,0.000000000000000000e+00,-2.901312325612375973e-10,0.000000000000000000e+00 +8.269108766302561975e+00,7.723000000000000398e+01,0.000000000000000000e+00,5.767074092914732830e+00,0.000000000000000000e+00,-1.000000009971723225e+00,0.000000000000000000e+00,1.418846838896375577e-10,0.000000000000000000e+00 +8.270842747839626696e+00,7.723999999999999488e+01,0.000000000000000000e+00,5.765340111360377051e+00,0.000000000000000000e+00,-1.000000009971477199e+00,0.000000000000000000e+00,5.735128749438820422e-11,0.000000000000000000e+00 +8.272577250888335954e+00,7.725000000000000000e+01,0.000000000000000000e+00,5.763605608294372296e+00,0.000000000000000000e+00,-1.000000009971377724e+00,0.000000000000000000e+00,-4.773570187785571436e-11,0.000000000000000000e+00 +8.274312275919474047e+00,7.726000000000000512e+01,0.000000000000000000e+00,5.761870583245933375e+00,0.000000000000000000e+00,-1.000000009971460546e+00,0.000000000000000000e+00,2.827456932802066646e-11,0.000000000000000000e+00 +8.276047823404535819e+00,7.726999999999999602e+01,0.000000000000000000e+00,5.760135035743566334e+00,0.000000000000000000e+00,-1.000000009971411474e+00,0.000000000000000000e+00,-1.020647512844556030e-10,0.000000000000000000e+00 +8.277783893815723104e+00,7.728000000000000114e+01,0.000000000000000000e+00,5.758398965315067564e+00,0.000000000000000000e+00,-1.000000009971588666e+00,0.000000000000000000e+00,5.945589618131533106e-11,0.000000000000000000e+00 +8.279520487625953606e+00,7.729000000000000625e+01,0.000000000000000000e+00,5.756662371487521135e+00,0.000000000000000000e+00,-1.000000009971485415e+00,0.000000000000000000e+00,1.292296416005341543e-10,0.000000000000000000e+00 +8.281257605308853798e+00,7.729999999999999716e+01,0.000000000000000000e+00,5.754925253787298800e+00,0.000000000000000000e+00,-1.000000009971260928e+00,0.000000000000000000e+00,-2.751211274666166291e-10,0.000000000000000000e+00 +8.282995247338769573e+00,7.731000000000000227e+01,0.000000000000000000e+00,5.753187611740057328e+00,0.000000000000000000e+00,-1.000000009971738990e+00,0.000000000000000000e+00,2.309655400717596910e-10,0.000000000000000000e+00 +8.284733414190759149e+00,7.732000000000000739e+01,0.000000000000000000e+00,5.751449444870735839e+00,0.000000000000000000e+00,-1.000000009971337533e+00,0.000000000000000000e+00,-2.025446215095924272e-10,0.000000000000000000e+00 +8.286472106340600163e+00,7.732999999999999829e+01,0.000000000000000000e+00,5.749710752703558470e+00,0.000000000000000000e+00,-1.000000009971689696e+00,0.000000000000000000e+00,1.044334262559123577e-10,0.000000000000000000e+00 +8.288211324264787905e+00,7.734000000000000341e+01,0.000000000000000000e+00,5.747971534762027268e+00,0.000000000000000000e+00,-1.000000009971508064e+00,0.000000000000000000e+00,1.874893614709586709e-10,0.000000000000000000e+00 +8.289951068440542414e+00,7.735000000000000853e+01,0.000000000000000000e+00,5.746231790568925746e+00,0.000000000000000000e+00,-1.000000009971181880e+00,0.000000000000000000e+00,-3.263802765890513853e-10,0.000000000000000000e+00 +8.291691339345801381e+00,7.735999999999999943e+01,0.000000000000000000e+00,5.744491519646314437e+00,0.000000000000000000e+00,-1.000000009971749870e+00,0.000000000000000000e+00,2.422237831602636436e-10,0.000000000000000000e+00 +8.293432137459229025e+00,7.737000000000000455e+01,0.000000000000000000e+00,5.742750721515528234e+00,0.000000000000000000e+00,-1.000000009971328208e+00,0.000000000000000000e+00,-2.365397342088138936e-10,0.000000000000000000e+00 +8.295173463260214319e+00,7.737999999999999545e+01,0.000000000000000000e+00,5.741009395697179940e+00,0.000000000000000000e+00,-1.000000009971740100e+00,0.000000000000000000e+00,2.112277590320449600e-10,0.000000000000000000e+00 +8.296915317228872766e+00,7.739000000000000057e+01,0.000000000000000000e+00,5.739267541711152276e+00,0.000000000000000000e+00,-1.000000009971372172e+00,0.000000000000000000e+00,-2.458266276752677206e-10,0.000000000000000000e+00 +8.298657699846048175e+00,7.740000000000000568e+01,0.000000000000000000e+00,5.737525159076602321e+00,0.000000000000000000e+00,-1.000000009971800496e+00,0.000000000000000000e+00,3.660163235170061552e-10,0.000000000000000000e+00 +8.300400611593316214e+00,7.740999999999999659e+01,0.000000000000000000e+00,5.735782247311954407e+00,0.000000000000000000e+00,-1.000000009971162562e+00,0.000000000000000000e+00,-3.645041777701599080e-10,0.000000000000000000e+00 +8.302144052952982634e+00,7.742000000000000171e+01,0.000000000000000000e+00,5.734038805934904559e+00,0.000000000000000000e+00,-1.000000009971798054e+00,0.000000000000000000e+00,1.223557098418357998e-10,0.000000000000000000e+00 +8.303888024408085045e+00,7.743000000000000682e+01,0.000000000000000000e+00,5.732294834462411615e+00,0.000000000000000000e+00,-1.000000009971584669e+00,0.000000000000000000e+00,3.691192911312811454e-12,0.000000000000000000e+00 +8.305632526442398245e+00,7.743999999999999773e+01,0.000000000000000000e+00,5.730550332410703440e+00,0.000000000000000000e+00,-1.000000009971578230e+00,0.000000000000000000e+00,8.792545091331307901e-11,0.000000000000000000e+00 +8.307377559540430667e+00,7.745000000000000284e+01,0.000000000000000000e+00,5.728805299295269826e+00,0.000000000000000000e+00,-1.000000009971424797e+00,0.000000000000000000e+00,-2.748900718558173105e-10,0.000000000000000000e+00 +8.309123124187431486e+00,7.746000000000000796e+01,0.000000000000000000e+00,5.727059734630863375e+00,0.000000000000000000e+00,-1.000000009971904635e+00,0.000000000000000000e+00,3.077423773102758459e-10,0.000000000000000000e+00 +8.310869220869387064e+00,7.746999999999999886e+01,0.000000000000000000e+00,5.725313637931495947e+00,0.000000000000000000e+00,-1.000000009971367287e+00,0.000000000000000000e+00,-2.676033885117456803e-10,0.000000000000000000e+00 +8.312615850073026280e+00,7.748000000000000398e+01,0.000000000000000000e+00,5.723567008710441328e+00,0.000000000000000000e+00,-1.000000009971834691e+00,0.000000000000000000e+00,2.668863067943211944e-10,0.000000000000000000e+00 +8.314363012285818755e+00,7.748999999999999488e+01,0.000000000000000000e+00,5.721819846480227234e+00,0.000000000000000000e+00,-1.000000009971368398e+00,0.000000000000000000e+00,-1.868904363305204929e-10,0.000000000000000000e+00 +8.316110707995978402e+00,7.750000000000000000e+01,0.000000000000000000e+00,5.720072150752640638e+00,0.000000000000000000e+00,-1.000000009971695025e+00,0.000000000000000000e+00,5.740902447071579758e-11,0.000000000000000000e+00 +8.317858937692466981e+00,7.751000000000000512e+01,0.000000000000000000e+00,5.718323921038719782e+00,0.000000000000000000e+00,-1.000000009971594661e+00,0.000000000000000000e+00,6.932687448306975513e-11,0.000000000000000000e+00 +8.319607701864990545e+00,7.751999999999999602e+01,0.000000000000000000e+00,5.716575156848757722e+00,0.000000000000000000e+00,-1.000000009971473425e+00,0.000000000000000000e+00,-2.069015515729571990e-10,0.000000000000000000e+00 +8.321357001004006548e+00,7.753000000000000114e+01,0.000000000000000000e+00,5.714825857692297895e+00,0.000000000000000000e+00,-1.000000009971835357e+00,0.000000000000000000e+00,4.517448649240436808e-11,0.000000000000000000e+00 +8.323106835600723841e+00,7.754000000000000625e+01,0.000000000000000000e+00,5.713076023078132337e+00,0.000000000000000000e+00,-1.000000009971756310e+00,0.000000000000000000e+00,1.907910793510383432e-10,0.000000000000000000e+00 +8.324857206147099120e+00,7.754999999999999716e+01,0.000000000000000000e+00,5.711325652514302575e+00,0.000000000000000000e+00,-1.000000009971422354e+00,0.000000000000000000e+00,-1.105843409952560799e-10,0.000000000000000000e+00 +8.326608113135845812e+00,7.756000000000000227e+01,0.000000000000000000e+00,5.709574745508096072e+00,0.000000000000000000e+00,-1.000000009971615977e+00,0.000000000000000000e+00,-4.031541254326974756e-11,0.000000000000000000e+00 +8.328359557060434071e+00,7.757000000000000739e+01,0.000000000000000000e+00,5.707823301566043561e+00,0.000000000000000000e+00,-1.000000009971686588e+00,0.000000000000000000e+00,6.298935108791256219e-11,0.000000000000000000e+00 +8.330111538415087225e+00,7.757999999999999829e+01,0.000000000000000000e+00,5.706071320193919938e+00,0.000000000000000000e+00,-1.000000009971576231e+00,0.000000000000000000e+00,-1.370896544827764511e-10,0.000000000000000000e+00 +8.331864057694790660e+00,7.759000000000000341e+01,0.000000000000000000e+00,5.704318800896741593e+00,0.000000000000000000e+00,-1.000000009971816484e+00,0.000000000000000000e+00,1.808723670322486647e-10,0.000000000000000000e+00 +8.333617115395286490e+00,7.760000000000000853e+01,0.000000000000000000e+00,5.702565743178763746e+00,0.000000000000000000e+00,-1.000000009971499404e+00,0.000000000000000000e+00,-1.833492290464555809e-10,0.000000000000000000e+00 +8.335370712013082439e+00,7.760999999999999943e+01,0.000000000000000000e+00,5.700812146543481340e+00,0.000000000000000000e+00,-1.000000009971820925e+00,0.000000000000000000e+00,1.719003360768588913e-10,0.000000000000000000e+00 +8.337124848045448289e+00,7.762000000000000455e+01,0.000000000000000000e+00,5.699058010493623705e+00,0.000000000000000000e+00,-1.000000009971519388e+00,0.000000000000000000e+00,-2.385363984065520713e-10,0.000000000000000000e+00 +8.338879523990417653e+00,7.762999999999999545e+01,0.000000000000000000e+00,5.697303334531157226e+00,0.000000000000000000e+00,-1.000000009971937942e+00,0.000000000000000000e+00,2.769206419570280779e-10,0.000000000000000000e+00 +8.340634740346793308e+00,7.764000000000000057e+01,0.000000000000000000e+00,5.695548118157279127e+00,0.000000000000000000e+00,-1.000000009971451886e+00,0.000000000000000000e+00,-3.385510163835156235e-10,0.000000000000000000e+00 +8.342390497614143641e+00,7.765000000000000568e+01,0.000000000000000000e+00,5.693792360872421021e+00,0.000000000000000000e+00,-1.000000009972046300e+00,0.000000000000000000e+00,1.839521398554338412e-10,0.000000000000000000e+00 +8.344146796292809753e+00,7.765999999999999659e+01,0.000000000000000000e+00,5.692036062176240918e+00,0.000000000000000000e+00,-1.000000009971723225e+00,0.000000000000000000e+00,8.025675456395459338e-11,0.000000000000000000e+00 +8.345903636883903687e+00,7.767000000000000171e+01,0.000000000000000000e+00,5.690279221567628554e+00,0.000000000000000000e+00,-1.000000009971582227e+00,0.000000000000000000e+00,-1.066390456606187401e-10,0.000000000000000000e+00 +8.347661019889310197e+00,7.768000000000000682e+01,0.000000000000000000e+00,5.688521838544698284e+00,0.000000000000000000e+00,-1.000000009971769632e+00,0.000000000000000000e+00,1.658457632116403034e-10,0.000000000000000000e+00 +8.349418945811690307e+00,7.768999999999999773e+01,0.000000000000000000e+00,5.686763912604789084e+00,0.000000000000000000e+00,-1.000000009971478088e+00,0.000000000000000000e+00,-2.824694005919984020e-10,0.000000000000000000e+00 +8.351177415154479533e+00,7.770000000000000284e+01,0.000000000000000000e+00,5.685005443244464551e+00,0.000000000000000000e+00,-1.000000009971974801e+00,0.000000000000000000e+00,2.424925917060031609e-10,0.000000000000000000e+00 +8.352936428421894988e+00,7.771000000000000796e+01,0.000000000000000000e+00,5.683246429959507573e+00,0.000000000000000000e+00,-1.000000009971548254e+00,0.000000000000000000e+00,-2.961759586720394876e-10,0.000000000000000000e+00 +8.354695986118933604e+00,7.771999999999999886e+01,0.000000000000000000e+00,5.681486872244923880e+00,0.000000000000000000e+00,-1.000000009972069392e+00,0.000000000000000000e+00,3.703891739295327952e-10,0.000000000000000000e+00 +8.356456088751372135e+00,7.773000000000000398e+01,0.000000000000000000e+00,5.679726769594934055e+00,0.000000000000000000e+00,-1.000000009971417470e+00,0.000000000000000000e+00,-3.628336279454163963e-10,0.000000000000000000e+00 +8.358216736825770710e+00,7.773999999999999488e+01,0.000000000000000000e+00,5.677966121502978858e+00,0.000000000000000000e+00,-1.000000009972056292e+00,0.000000000000000000e+00,3.473398605344947560e-10,0.000000000000000000e+00 +8.359977930849478156e+00,7.775000000000000000e+01,0.000000000000000000e+00,5.676204927461709460e+00,0.000000000000000000e+00,-1.000000009971444559e+00,0.000000000000000000e+00,-3.851692799888391856e-10,0.000000000000000000e+00 +8.361739671330626678e+00,7.776000000000000512e+01,0.000000000000000000e+00,5.674443186962994545e+00,0.000000000000000000e+00,-1.000000009972123127e+00,0.000000000000000000e+00,2.824874029177200910e-10,0.000000000000000000e+00 +8.363501958778137180e+00,7.776999999999999602e+01,0.000000000000000000e+00,5.672680899497909657e+00,0.000000000000000000e+00,-1.000000009971625303e+00,0.000000000000000000e+00,-2.427226440578349862e-10,0.000000000000000000e+00 +8.365264793701724599e+00,7.778000000000000114e+01,0.000000000000000000e+00,5.670918064556744298e+00,0.000000000000000000e+00,-1.000000009972053183e+00,0.000000000000000000e+00,3.096364835807337767e-10,0.000000000000000000e+00 +8.367028176611892576e+00,7.779000000000000625e+01,0.000000000000000000e+00,5.669154681628992165e+00,0.000000000000000000e+00,-1.000000009971507176e+00,0.000000000000000000e+00,-7.615771529824266252e-11,0.000000000000000000e+00 +8.368792108019938780e+00,7.779999999999999716e+01,0.000000000000000000e+00,5.667390750203356475e+00,0.000000000000000000e+00,-1.000000009971641513e+00,0.000000000000000000e+00,-2.701813870561810187e-10,0.000000000000000000e+00 +8.370556588437958467e+00,7.781000000000000227e+01,0.000000000000000000e+00,5.665626269767741974e+00,0.000000000000000000e+00,-1.000000009972118242e+00,0.000000000000000000e+00,2.849419256328630073e-10,0.000000000000000000e+00 +8.372321618378842700e+00,7.782000000000000739e+01,0.000000000000000000e+00,5.663861239809256709e+00,0.000000000000000000e+00,-1.000000009971615311e+00,0.000000000000000000e+00,-1.321768952742170425e-10,0.000000000000000000e+00 +8.374087198356281903e+00,7.782999999999999829e+01,0.000000000000000000e+00,5.662095659814212034e+00,0.000000000000000000e+00,-1.000000009971848680e+00,0.000000000000000000e+00,-1.047279082261373798e-10,0.000000000000000000e+00 +8.375853328884767635e+00,7.784000000000000341e+01,0.000000000000000000e+00,5.660329529268115500e+00,0.000000000000000000e+00,-1.000000009972033643e+00,0.000000000000000000e+00,7.440526153705215928e-11,0.000000000000000000e+00 +8.377620010479592594e+00,7.785000000000000853e+01,0.000000000000000000e+00,5.658562847655673522e+00,0.000000000000000000e+00,-1.000000009971902193e+00,0.000000000000000000e+00,1.149654817035315224e-10,0.000000000000000000e+00 +8.379387243656854167e+00,7.785999999999999943e+01,0.000000000000000000e+00,5.656795614460788713e+00,0.000000000000000000e+00,-1.000000009971699022e+00,0.000000000000000000e+00,1.281182166301687316e-11,0.000000000000000000e+00 +8.381155028933457984e+00,7.787000000000000455e+01,0.000000000000000000e+00,5.655027829166557218e+00,0.000000000000000000e+00,-1.000000009971676374e+00,0.000000000000000000e+00,-2.336798929931430063e-10,0.000000000000000000e+00 +8.382923366827114364e+00,7.787999999999999545e+01,0.000000000000000000e+00,5.653259491255266944e+00,0.000000000000000000e+00,-1.000000009972089599e+00,0.000000000000000000e+00,2.254475283412928616e-10,0.000000000000000000e+00 +8.384692257856345421e+00,7.789000000000000057e+01,0.000000000000000000e+00,5.651490600208395776e+00,0.000000000000000000e+00,-1.000000009971690806e+00,0.000000000000000000e+00,-2.823486744511802786e-11,0.000000000000000000e+00 +8.386461702540485064e+00,7.790000000000000568e+01,0.000000000000000000e+00,5.649721155506612469e+00,0.000000000000000000e+00,-1.000000009971740766e+00,0.000000000000000000e+00,-1.406283404242295111e-10,0.000000000000000000e+00 +8.388231701399677220e+00,7.790999999999999659e+01,0.000000000000000000e+00,5.647951156629770431e+00,0.000000000000000000e+00,-1.000000009971989678e+00,0.000000000000000000e+00,-1.086048074059627004e-10,0.000000000000000000e+00 +8.390002254954882943e+00,7.792000000000000171e+01,0.000000000000000000e+00,5.646180603056908609e+00,0.000000000000000000e+00,-1.000000009972181969e+00,0.000000000000000000e+00,3.564280305232878882e-10,0.000000000000000000e+00 +8.391773363727880408e+00,7.793000000000000682e+01,0.000000000000000000e+00,5.644409494266249716e+00,0.000000000000000000e+00,-1.000000009971550696e+00,0.000000000000000000e+00,-1.542825442389207068e-10,0.000000000000000000e+00 +8.393545028241264916e+00,7.793999999999999773e+01,0.000000000000000000e+00,5.642637829735199340e+00,0.000000000000000000e+00,-1.000000009971824033e+00,0.000000000000000000e+00,-2.157523569313649100e-10,0.000000000000000000e+00 +8.395317249018452443e+00,7.795000000000000284e+01,0.000000000000000000e+00,5.640865608940339726e+00,0.000000000000000000e+00,-1.000000009972206394e+00,0.000000000000000000e+00,1.808644331926479117e-10,0.000000000000000000e+00 +8.397090026583681421e+00,7.796000000000000796e+01,0.000000000000000000e+00,5.639092831357432445e+00,0.000000000000000000e+00,-1.000000009971885762e+00,0.000000000000000000e+00,-8.301622827366856494e-11,0.000000000000000000e+00 +8.398863361462014510e+00,7.796999999999999886e+01,0.000000000000000000e+00,5.637319496461416612e+00,0.000000000000000000e+00,-1.000000009972032977e+00,0.000000000000000000e+00,1.366896127427323261e-10,0.000000000000000000e+00 +8.400637254179338598e+00,7.798000000000000398e+01,0.000000000000000000e+00,5.635545603726403563e+00,0.000000000000000000e+00,-1.000000009971790504e+00,0.000000000000000000e+00,7.758323482121842504e-12,0.000000000000000000e+00 +8.402411705262368358e+00,7.798999999999999488e+01,0.000000000000000000e+00,5.633771152625678624e+00,0.000000000000000000e+00,-1.000000009971776738e+00,0.000000000000000000e+00,-1.703791843138663209e-10,0.000000000000000000e+00 +8.404186715238649796e+00,7.800000000000000000e+01,0.000000000000000000e+00,5.631996142631696678e+00,0.000000000000000000e+00,-1.000000009972079162e+00,0.000000000000000000e+00,1.842066569967324093e-10,0.000000000000000000e+00 +8.405962284636558479e+00,7.801000000000000512e+01,0.000000000000000000e+00,5.630220573216081270e+00,0.000000000000000000e+00,-1.000000009971752091e+00,0.000000000000000000e+00,-3.537953090982151175e-11,0.000000000000000000e+00 +8.407738413985304859e+00,7.801999999999999602e+01,0.000000000000000000e+00,5.628444443849624612e+00,0.000000000000000000e+00,-1.000000009971814929e+00,0.000000000000000000e+00,-2.438292925333178285e-10,0.000000000000000000e+00 +8.409515103814930725e+00,7.803000000000000114e+01,0.000000000000000000e+00,5.626667754002282251e+00,0.000000000000000000e+00,-1.000000009972248138e+00,0.000000000000000000e+00,1.448021242220464169e-10,0.000000000000000000e+00 +8.411292354656316306e+00,7.804000000000000625e+01,0.000000000000000000e+00,5.624890503143173071e+00,0.000000000000000000e+00,-1.000000009971990789e+00,0.000000000000000000e+00,2.985054048945597804e-11,0.000000000000000000e+00 +8.413070167041182046e+00,7.804999999999999716e+01,0.000000000000000000e+00,5.623112690740579289e+00,0.000000000000000000e+00,-1.000000009971937720e+00,0.000000000000000000e+00,1.123723652277979544e-12,0.000000000000000000e+00 +8.414848541502086832e+00,7.806000000000000227e+01,0.000000000000000000e+00,5.621334316261941133e+00,0.000000000000000000e+00,-1.000000009971935722e+00,0.000000000000000000e+00,8.674899353971030610e-11,0.000000000000000000e+00 +8.416627478572431542e+00,7.807000000000000739e+01,0.000000000000000000e+00,5.619555379173856835e+00,0.000000000000000000e+00,-1.000000009971781401e+00,0.000000000000000000e+00,-2.448167813793113316e-10,0.000000000000000000e+00 +8.418406978786462602e+00,7.807999999999999829e+01,0.000000000000000000e+00,5.617775878942080858e+00,0.000000000000000000e+00,-1.000000009972217052e+00,0.000000000000000000e+00,1.605399714543422493e-10,0.000000000000000000e+00 +8.420187042679271983e+00,7.809000000000000341e+01,0.000000000000000000e+00,5.615995815031520344e+00,0.000000000000000000e+00,-1.000000009971931281e+00,0.000000000000000000e+00,-6.634048363089491974e-11,0.000000000000000000e+00 +8.421967670786798976e+00,7.810000000000000853e+01,0.000000000000000000e+00,5.614215186906236887e+00,0.000000000000000000e+00,-1.000000009972049408e+00,0.000000000000000000e+00,-4.911628400974382037e-11,0.000000000000000000e+00 +8.423748863645833751e+00,7.810999999999999943e+01,0.000000000000000000e+00,5.612433994029440321e+00,0.000000000000000000e+00,-1.000000009972136894e+00,0.000000000000000000e+00,2.483697902922060355e-10,0.000000000000000000e+00 +8.425530621794017350e+00,7.812000000000000455e+01,0.000000000000000000e+00,5.610652235863489601e+00,0.000000000000000000e+00,-1.000000009971694359e+00,0.000000000000000000e+00,-2.543954350649634080e-10,0.000000000000000000e+00 +8.427312945769843466e+00,7.812999999999999545e+01,0.000000000000000000e+00,5.608869911869891034e+00,0.000000000000000000e+00,-1.000000009972147774e+00,0.000000000000000000e+00,1.605345482413931217e-10,0.000000000000000000e+00 +8.429095836112661999e+00,7.814000000000000057e+01,0.000000000000000000e+00,5.607087021509292946e+00,0.000000000000000000e+00,-1.000000009971861559e+00,0.000000000000000000e+00,-1.423061771884697495e-10,0.000000000000000000e+00 +8.430879293362680826e+00,7.815000000000000568e+01,0.000000000000000000e+00,5.605303564241489234e+00,0.000000000000000000e+00,-1.000000009972115356e+00,0.000000000000000000e+00,-1.742478381569619819e-12,0.000000000000000000e+00 +8.432663318060967583e+00,7.815999999999999659e+01,0.000000000000000000e+00,5.603519539525412263e+00,0.000000000000000000e+00,-1.000000009972118464e+00,0.000000000000000000e+00,6.855714365713310570e-11,0.000000000000000000e+00 +8.434447910749449662e+00,7.817000000000000171e+01,0.000000000000000000e+00,5.601734946819134642e+00,0.000000000000000000e+00,-1.000000009971996118e+00,0.000000000000000000e+00,1.156766571539912361e-10,0.000000000000000000e+00 +8.436233071970917763e+00,7.818000000000000682e+01,0.000000000000000000e+00,5.599949785579865669e+00,0.000000000000000000e+00,-1.000000009971789616e+00,0.000000000000000000e+00,-3.689282438171894983e-10,0.000000000000000000e+00 +8.438018802269027674e+00,7.818999999999999773e+01,0.000000000000000000e+00,5.598164055263949557e+00,0.000000000000000000e+00,-1.000000009972448423e+00,0.000000000000000000e+00,3.361185908586632605e-10,0.000000000000000000e+00 +8.439805102188302044e+00,7.820000000000000284e+01,0.000000000000000000e+00,5.596377755326861880e+00,0.000000000000000000e+00,-1.000000009971848014e+00,0.000000000000000000e+00,-2.233033941383937288e-10,0.000000000000000000e+00 +8.441591972274132161e+00,7.821000000000000796e+01,0.000000000000000000e+00,5.594590885223213128e+00,0.000000000000000000e+00,-1.000000009972247028e+00,0.000000000000000000e+00,2.332943101468297768e-10,0.000000000000000000e+00 +8.443379413072781503e+00,7.821999999999999886e+01,0.000000000000000000e+00,5.592803444406738933e+00,0.000000000000000000e+00,-1.000000009971830028e+00,0.000000000000000000e+00,-1.860294043192499645e-10,0.000000000000000000e+00 +8.445167425131385741e+00,7.823000000000000398e+01,0.000000000000000000e+00,5.591015432330305401e+00,0.000000000000000000e+00,-1.000000009972162651e+00,0.000000000000000000e+00,-3.339513446436131253e-11,0.000000000000000000e+00 +8.446956008997954513e+00,7.823999999999999488e+01,0.000000000000000000e+00,5.589226848445901119e+00,0.000000000000000000e+00,-1.000000009972222381e+00,0.000000000000000000e+00,1.928603615138897442e-10,0.000000000000000000e+00 +8.448745165221373199e+00,7.825000000000000000e+01,0.000000000000000000e+00,5.587437692204639816e+00,0.000000000000000000e+00,-1.000000009971877324e+00,0.000000000000000000e+00,-2.777838624200820869e-10,0.000000000000000000e+00 +8.450534894351410031e+00,7.826000000000000512e+01,0.000000000000000000e+00,5.585647963056756815e+00,0.000000000000000000e+00,-1.000000009972374482e+00,0.000000000000000000e+00,2.805474895158784474e-10,0.000000000000000000e+00 +8.452325196938708984e+00,7.826999999999999602e+01,0.000000000000000000e+00,5.583857660451604588e+00,0.000000000000000000e+00,-1.000000009971872217e+00,0.000000000000000000e+00,-8.679058277208103100e-12,0.000000000000000000e+00 +8.454116073534798659e+00,7.828000000000000114e+01,0.000000000000000000e+00,5.582066783837656310e+00,0.000000000000000000e+00,-1.000000009971887760e+00,0.000000000000000000e+00,-2.476456691737380366e-10,0.000000000000000000e+00 +8.455907524692092281e+00,7.829000000000000625e+01,0.000000000000000000e+00,5.580275332662497867e+00,0.000000000000000000e+00,-1.000000009972331405e+00,0.000000000000000000e+00,1.843736207041545584e-10,0.000000000000000000e+00 +8.457699550963891255e+00,7.829999999999999716e+01,0.000000000000000000e+00,5.578483306372828743e+00,0.000000000000000000e+00,-1.000000009972001003e+00,0.000000000000000000e+00,-2.725078668057761641e-11,0.000000000000000000e+00 +8.459492152904381612e+00,7.831000000000000227e+01,0.000000000000000000e+00,5.576690704414462019e+00,0.000000000000000000e+00,-1.000000009972049853e+00,0.000000000000000000e+00,-2.569418724820417654e-10,0.000000000000000000e+00 +8.461285331068644666e+00,7.832000000000000739e+01,0.000000000000000000e+00,5.574897526232318157e+00,0.000000000000000000e+00,-1.000000009972510595e+00,0.000000000000000000e+00,3.953775684359067352e-10,0.000000000000000000e+00 +8.463079086012649910e+00,7.832999999999999829e+01,0.000000000000000000e+00,5.573103771270425000e+00,0.000000000000000000e+00,-1.000000009971801385e+00,0.000000000000000000e+00,-2.040600603786508693e-10,0.000000000000000000e+00 +8.464873418293263896e+00,7.834000000000000341e+01,0.000000000000000000e+00,5.571309438971918659e+00,0.000000000000000000e+00,-1.000000009972167536e+00,0.000000000000000000e+00,-4.639047012343565930e-11,0.000000000000000000e+00 +8.466668328468248461e+00,7.835000000000000853e+01,0.000000000000000000e+00,5.569514528779034634e+00,0.000000000000000000e+00,-1.000000009972250803e+00,0.000000000000000000e+00,1.182266704427616242e-10,0.000000000000000000e+00 +8.468463817096266055e+00,7.835999999999999943e+01,0.000000000000000000e+00,5.567719040133112252e+00,0.000000000000000000e+00,-1.000000009972038528e+00,0.000000000000000000e+00,-1.813625656738099358e-10,0.000000000000000000e+00 +8.470259884736877964e+00,7.837000000000000455e+01,0.000000000000000000e+00,5.565922972474590225e+00,0.000000000000000000e+00,-1.000000009972364268e+00,0.000000000000000000e+00,2.385254513209913078e-10,0.000000000000000000e+00 +8.472056531950547864e+00,7.837999999999999545e+01,0.000000000000000000e+00,5.564126325243003102e+00,0.000000000000000000e+00,-1.000000009971935722e+00,0.000000000000000000e+00,-1.903881200959626720e-10,0.000000000000000000e+00 +8.473853759298645372e+00,7.839000000000000057e+01,0.000000000000000000e+00,5.562329097876983042e+00,0.000000000000000000e+00,-1.000000009972277892e+00,0.000000000000000000e+00,-6.792968418506053188e-12,0.000000000000000000e+00 +8.475651567343447823e+00,7.840000000000000568e+01,0.000000000000000000e+00,5.560531289814252709e+00,0.000000000000000000e+00,-1.000000009972290105e+00,0.000000000000000000e+00,5.074559350756530832e-11,0.000000000000000000e+00 +8.477449956648138496e+00,7.840999999999999659e+01,0.000000000000000000e+00,5.558732900491627937e+00,0.000000000000000000e+00,-1.000000009972198844e+00,0.000000000000000000e+00,7.146519707978199614e-11,0.000000000000000000e+00 +8.479248927776813716e+00,7.842000000000000171e+01,0.000000000000000000e+00,5.556933929345013290e+00,0.000000000000000000e+00,-1.000000009972070281e+00,0.000000000000000000e+00,-1.279541025296544068e-10,0.000000000000000000e+00 +8.481048481294481078e+00,7.843000000000000682e+01,0.000000000000000000e+00,5.555134375809400282e+00,0.000000000000000000e+00,-1.000000009972300541e+00,0.000000000000000000e+00,9.288161761898901343e-11,0.000000000000000000e+00 +8.482848617767064781e+00,7.843999999999999773e+01,0.000000000000000000e+00,5.553334239318864718e+00,0.000000000000000000e+00,-1.000000009972133341e+00,0.000000000000000000e+00,6.165439535931033224e-12,0.000000000000000000e+00 +8.484649337761405619e+00,7.845000000000000284e+01,0.000000000000000000e+00,5.551533519306566689e+00,0.000000000000000000e+00,-1.000000009972122239e+00,0.000000000000000000e+00,-1.799724577852842924e-11,0.000000000000000000e+00 +8.486450641845262766e+00,7.846000000000000796e+01,0.000000000000000000e+00,5.549732215204746133e+00,0.000000000000000000e+00,-1.000000009972154658e+00,0.000000000000000000e+00,-1.555147578622049009e-10,0.000000000000000000e+00 +8.488252530587319100e+00,7.846999999999999886e+01,0.000000000000000000e+00,5.547930326444721949e+00,0.000000000000000000e+00,-1.000000009972434878e+00,0.000000000000000000e+00,2.405877259092146907e-10,0.000000000000000000e+00 +8.490055004557175877e+00,7.848000000000000398e+01,0.000000000000000000e+00,5.546127852456889329e+00,0.000000000000000000e+00,-1.000000009972001225e+00,0.000000000000000000e+00,-3.689537352516056924e-10,0.000000000000000000e+00 +8.491858064325365163e+00,7.848999999999999488e+01,0.000000000000000000e+00,5.544324792670719759e+00,0.000000000000000000e+00,-1.000000009972666470e+00,0.000000000000000000e+00,3.056790034472766657e-10,0.000000000000000000e+00 +8.493661710463344505e+00,7.850000000000000000e+01,0.000000000000000000e+00,5.542521146514753916e+00,0.000000000000000000e+00,-1.000000009972115134e+00,0.000000000000000000e+00,-8.885559549884129867e-11,0.000000000000000000e+00 +8.495465943543498710e+00,7.851000000000000512e+01,0.000000000000000000e+00,5.540716913416606992e+00,0.000000000000000000e+00,-1.000000009972275450e+00,0.000000000000000000e+00,1.930319201626375133e-10,0.000000000000000000e+00 +8.497270764139148724e+00,7.851999999999999602e+01,0.000000000000000000e+00,5.538912092802958931e+00,0.000000000000000000e+00,-1.000000009971927062e+00,0.000000000000000000e+00,-3.764679660471749588e-10,0.000000000000000000e+00 +8.499076172824546305e+00,7.853000000000000114e+01,0.000000000000000000e+00,5.537106684099557974e+00,0.000000000000000000e+00,-1.000000009972606740e+00,0.000000000000000000e+00,2.213072398977545754e-10,0.000000000000000000e+00 +8.500882170174879349e+00,7.854000000000000625e+01,0.000000000000000000e+00,5.535300686731213560e+00,0.000000000000000000e+00,-1.000000009972207060e+00,0.000000000000000000e+00,-8.050497934528488973e-11,0.000000000000000000e+00 +8.502688756766277223e+00,7.854999999999999716e+01,0.000000000000000000e+00,5.533494100121800763e+00,0.000000000000000000e+00,-1.000000009972352499e+00,0.000000000000000000e+00,1.937632320346178605e-10,0.000000000000000000e+00 +8.504495933175805433e+00,7.856000000000000227e+01,0.000000000000000000e+00,5.531686923694251412e+00,0.000000000000000000e+00,-1.000000009972002335e+00,0.000000000000000000e+00,-1.992272167290937313e-10,0.000000000000000000e+00 +8.506303699981472732e+00,7.857000000000000739e+01,0.000000000000000000e+00,5.529879156870556756e+00,0.000000000000000000e+00,-1.000000009972362491e+00,0.000000000000000000e+00,-5.378113667096737666e-11,0.000000000000000000e+00 +8.508112057762234670e+00,7.857999999999999829e+01,0.000000000000000000e+00,5.528070799071761243e+00,0.000000000000000000e+00,-1.000000009972459747e+00,0.000000000000000000e+00,2.057253625063875582e-10,0.000000000000000000e+00 +8.509921007097991819e+00,7.859000000000000341e+01,0.000000000000000000e+00,5.526261849717964303e+00,0.000000000000000000e+00,-1.000000009972087600e+00,0.000000000000000000e+00,-1.122775115656601756e-10,0.000000000000000000e+00 +8.511730548569595101e+00,7.860000000000000853e+01,0.000000000000000000e+00,5.524452308228316788e+00,0.000000000000000000e+00,-1.000000009972290771e+00,0.000000000000000000e+00,-6.992046532184083464e-11,0.000000000000000000e+00 +8.513540682758844014e+00,7.860999999999999943e+01,0.000000000000000000e+00,5.522642174021016537e+00,0.000000000000000000e+00,-1.000000009972417336e+00,0.000000000000000000e+00,1.866387353302020619e-10,0.000000000000000000e+00 +8.515351410248493735e+00,7.862000000000000455e+01,0.000000000000000000e+00,5.520831446513309260e+00,0.000000000000000000e+00,-1.000000009972079384e+00,0.000000000000000000e+00,-2.980092005716329242e-10,0.000000000000000000e+00 +8.517162731622255123e+00,7.862999999999999545e+01,0.000000000000000000e+00,5.519020125121485876e+00,0.000000000000000000e+00,-1.000000009972619175e+00,0.000000000000000000e+00,2.297753706104807307e-10,0.000000000000000000e+00 +8.518974647464794714e+00,7.864000000000000057e+01,0.000000000000000000e+00,5.517208209260877183e+00,0.000000000000000000e+00,-1.000000009972202841e+00,0.000000000000000000e+00,6.982878007552484014e-12,0.000000000000000000e+00 +8.520787158361740055e+00,7.865000000000000568e+01,0.000000000000000000e+00,5.515395698345857411e+00,0.000000000000000000e+00,-1.000000009972190185e+00,0.000000000000000000e+00,-2.912250656332037861e-10,0.000000000000000000e+00 +8.522600264899681477e+00,7.865999999999999659e+01,0.000000000000000000e+00,5.513582591789836229e+00,0.000000000000000000e+00,-1.000000009972718207e+00,0.000000000000000000e+00,2.801109781905873876e-10,0.000000000000000000e+00 +8.524413967666172098e+00,7.867000000000000171e+01,0.000000000000000000e+00,5.511768889005258742e+00,0.000000000000000000e+00,-1.000000009972210169e+00,0.000000000000000000e+00,-3.255463730756689150e-11,0.000000000000000000e+00 +8.526228267249731374e+00,7.868000000000000682e+01,0.000000000000000000e+00,5.509954589403606384e+00,0.000000000000000000e+00,-1.000000009972269233e+00,0.000000000000000000e+00,-9.542954381680097719e-12,0.000000000000000000e+00 +8.528043164239850427e+00,7.868999999999999773e+01,0.000000000000000000e+00,5.508139692395388920e+00,0.000000000000000000e+00,-1.000000009972286552e+00,0.000000000000000000e+00,-5.002285550647554081e-11,0.000000000000000000e+00 +8.529858659226988493e+00,7.870000000000000284e+01,0.000000000000000000e+00,5.506324197390146225e+00,0.000000000000000000e+00,-1.000000009972377368e+00,0.000000000000000000e+00,-1.088158127088785222e-11,0.000000000000000000e+00 +8.531674752802580031e+00,7.871000000000000796e+01,0.000000000000000000e+00,5.504508103796444729e+00,0.000000000000000000e+00,-1.000000009972397130e+00,0.000000000000000000e+00,-1.686699931555478439e-11,0.000000000000000000e+00 +8.533491445559032940e+00,7.871999999999999886e+01,0.000000000000000000e+00,5.502691411021875645e+00,0.000000000000000000e+00,-1.000000009972427772e+00,0.000000000000000000e+00,7.868668536077567171e-11,0.000000000000000000e+00 +8.535308738089733893e+00,7.873000000000000398e+01,0.000000000000000000e+00,5.500874118473052299e+00,0.000000000000000000e+00,-1.000000009972284776e+00,0.000000000000000000e+00,-1.132274342691035132e-10,0.000000000000000000e+00 +8.537126630989050113e+00,7.873999999999999488e+01,0.000000000000000000e+00,5.499056225555608357e+00,0.000000000000000000e+00,-1.000000009972490611e+00,0.000000000000000000e+00,9.560710056111345742e-11,0.000000000000000000e+00 +8.538945124852329371e+00,7.875000000000000000e+01,0.000000000000000000e+00,5.497237731674194272e+00,0.000000000000000000e+00,-1.000000009972316750e+00,0.000000000000000000e+00,5.151066956902172784e-11,0.000000000000000000e+00 +8.540764220275905316e+00,7.876000000000000512e+01,0.000000000000000000e+00,5.495418636232477283e+00,0.000000000000000000e+00,-1.000000009972223047e+00,0.000000000000000000e+00,-3.587470496340890743e-10,0.000000000000000000e+00 +8.542583917857099252e+00,7.876999999999999602e+01,0.000000000000000000e+00,5.493598938633136974e+00,0.000000000000000000e+00,-1.000000009972875858e+00,0.000000000000000000e+00,3.620437649645846691e-10,0.000000000000000000e+00 +8.544404218194220135e+00,7.878000000000000114e+01,0.000000000000000000e+00,5.491778638277862612e+00,0.000000000000000000e+00,-1.000000009972216830e+00,0.000000000000000000e+00,-4.085056390541650042e-11,0.000000000000000000e+00 +8.546225121886568132e+00,7.879000000000000625e+01,0.000000000000000000e+00,5.489957734567355807e+00,0.000000000000000000e+00,-1.000000009972291215e+00,0.000000000000000000e+00,-6.631444299475577914e-11,0.000000000000000000e+00 +8.548046629534438168e+00,7.879999999999999716e+01,0.000000000000000000e+00,5.488136226901320747e+00,0.000000000000000000e+00,-1.000000009972412007e+00,0.000000000000000000e+00,-8.798371710800341811e-11,0.000000000000000000e+00 +8.549868741739121702e+00,7.881000000000000227e+01,0.000000000000000000e+00,5.486314114678466858e+00,0.000000000000000000e+00,-1.000000009972572323e+00,0.000000000000000000e+00,5.835208895923450523e-11,0.000000000000000000e+00 +8.551691459102906734e+00,7.882000000000000739e+01,0.000000000000000000e+00,5.484491397296505255e+00,0.000000000000000000e+00,-1.000000009972465964e+00,0.000000000000000000e+00,4.140525866793280599e-12,0.000000000000000000e+00 +8.553514782229081348e+00,7.882999999999999829e+01,0.000000000000000000e+00,5.482668074152146964e+00,0.000000000000000000e+00,-1.000000009972458415e+00,0.000000000000000000e+00,1.850443237019497420e-10,0.000000000000000000e+00 +8.555338711721939049e+00,7.884000000000000341e+01,0.000000000000000000e+00,5.480844144641099369e+00,0.000000000000000000e+00,-1.000000009972120907e+00,0.000000000000000000e+00,-2.963375210152346941e-10,0.000000000000000000e+00 +8.557163248186778759e+00,7.885000000000000853e+01,0.000000000000000000e+00,5.479019608158065324e+00,0.000000000000000000e+00,-1.000000009972661585e+00,0.000000000000000000e+00,6.666895358599366516e-11,0.000000000000000000e+00 +8.558988392229904818e+00,7.885999999999999943e+01,0.000000000000000000e+00,5.477194464096737825e+00,0.000000000000000000e+00,-1.000000009972539905e+00,0.000000000000000000e+00,1.139562047582619201e-10,0.000000000000000000e+00 +8.560814144458632313e+00,7.887000000000000455e+01,0.000000000000000000e+00,5.475368711849802672e+00,0.000000000000000000e+00,-1.000000009972331849e+00,0.000000000000000000e+00,-2.435199493130458752e-10,0.000000000000000000e+00 +8.562640505481288855e+00,7.887999999999999545e+01,0.000000000000000000e+00,5.473542350808932255e+00,0.000000000000000000e+00,-1.000000009972776605e+00,0.000000000000000000e+00,2.372403311307954691e-10,0.000000000000000000e+00 +8.564467475907218130e+00,7.889000000000000057e+01,0.000000000000000000e+00,5.471715380364782888e+00,0.000000000000000000e+00,-1.000000009972343173e+00,0.000000000000000000e+00,-1.263563475091128213e-10,0.000000000000000000e+00 +8.566295056346779901e+00,7.890000000000000568e+01,0.000000000000000000e+00,5.469887799906996584e+00,0.000000000000000000e+00,-1.000000009972574100e+00,0.000000000000000000e+00,1.782972722855429506e-10,0.000000000000000000e+00 +8.568123247411351784e+00,7.890999999999999659e+01,0.000000000000000000e+00,5.468059608824193063e+00,0.000000000000000000e+00,-1.000000009972248138e+00,0.000000000000000000e+00,-2.595859403801386967e-10,0.000000000000000000e+00 +8.569952049713334574e+00,7.892000000000000171e+01,0.000000000000000000e+00,5.466230806503972417e+00,0.000000000000000000e+00,-1.000000009972722870e+00,0.000000000000000000e+00,7.525231771127101002e-11,0.000000000000000000e+00 +8.571781463866154027e+00,7.893000000000000682e+01,0.000000000000000000e+00,5.464401392332908003e+00,0.000000000000000000e+00,-1.000000009972585202e+00,0.000000000000000000e+00,4.295226603025724618e-11,0.000000000000000000e+00 +8.573611490484262632e+00,7.893999999999999773e+01,0.000000000000000000e+00,5.462571365696549108e+00,0.000000000000000000e+00,-1.000000009972506598e+00,0.000000000000000000e+00,1.000670963135975090e-10,0.000000000000000000e+00 +8.575442130183141387e+00,7.895000000000000284e+01,0.000000000000000000e+00,5.460740725979414734e+00,0.000000000000000000e+00,-1.000000009972323411e+00,0.000000000000000000e+00,-9.118210688577921444e-11,0.000000000000000000e+00 +8.577273383579301580e+00,7.896000000000000796e+01,0.000000000000000000e+00,5.458909472564992704e+00,0.000000000000000000e+00,-1.000000009972490389e+00,0.000000000000000000e+00,-7.078788959398076679e-11,0.000000000000000000e+00 +8.579105251290290113e+00,7.896999999999999886e+01,0.000000000000000000e+00,5.457077604835736118e+00,0.000000000000000000e+00,-1.000000009972620063e+00,0.000000000000000000e+00,9.233265562979721779e-11,0.000000000000000000e+00 +8.580937733934689504e+00,7.898000000000000398e+01,0.000000000000000000e+00,5.455245122173062455e+00,0.000000000000000000e+00,-1.000000009972450865e+00,0.000000000000000000e+00,6.831775698280766548e-11,0.000000000000000000e+00 +8.582770832132121441e+00,7.898999999999999488e+01,0.000000000000000000e+00,5.453412023957350918e+00,0.000000000000000000e+00,-1.000000009972325632e+00,0.000000000000000000e+00,-2.060953022636849199e-10,0.000000000000000000e+00 +8.584604546503246780e+00,7.900000000000000000e+01,0.000000000000000000e+00,5.451578309567938874e+00,0.000000000000000000e+00,-1.000000009972703552e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +8.586438877669772651e+00,7.901000000000000512e+01,0.000000000000000000e+00,5.449743978383119192e+00,0.000000000000000000e+00,-1.000000009972703552e+00,0.000000000000000000e+00,9.922707238705713662e-11,0.000000000000000000e+00 +8.588273826254452459e+00,7.901999999999999602e+01,0.000000000000000000e+00,5.447909029780140244e+00,0.000000000000000000e+00,-1.000000009972521475e+00,0.000000000000000000e+00,3.508068543736621507e-11,0.000000000000000000e+00 +8.590109392881085881e+00,7.903000000000000114e+01,0.000000000000000000e+00,5.446073463135201465e+00,0.000000000000000000e+00,-1.000000009972457082e+00,0.000000000000000000e+00,1.680887010415228684e-11,0.000000000000000000e+00 +8.591945578174525977e+00,7.904000000000000625e+01,0.000000000000000000e+00,5.444237277823450682e+00,0.000000000000000000e+00,-1.000000009972426218e+00,0.000000000000000000e+00,-2.710272001689201355e-10,0.000000000000000000e+00 +8.593782382760677407e+00,7.904999999999999716e+01,0.000000000000000000e+00,5.442400473218982349e+00,0.000000000000000000e+00,-1.000000009972924042e+00,0.000000000000000000e+00,1.743801521593144757e-10,0.000000000000000000e+00 +8.595619807266501766e+00,7.906000000000000227e+01,0.000000000000000000e+00,5.440563048694833981e+00,0.000000000000000000e+00,-1.000000009972603632e+00,0.000000000000000000e+00,-1.063081951991108012e-11,0.000000000000000000e+00 +8.597457852320019356e+00,7.907000000000000739e+01,0.000000000000000000e+00,5.438725003622987053e+00,0.000000000000000000e+00,-1.000000009972623172e+00,0.000000000000000000e+00,1.806628758909132099e-10,0.000000000000000000e+00 +8.599296518550310964e+00,7.907999999999999829e+01,0.000000000000000000e+00,5.436886337374359890e+00,0.000000000000000000e+00,-1.000000009972290993e+00,0.000000000000000000e+00,-8.293678885387534056e-11,0.000000000000000000e+00 +8.601135806587519639e+00,7.909000000000000341e+01,0.000000000000000000e+00,5.435047049318808554e+00,0.000000000000000000e+00,-1.000000009972443538e+00,0.000000000000000000e+00,-3.166703223514434210e-10,0.000000000000000000e+00 +8.602975717062857797e+00,7.910000000000000853e+01,0.000000000000000000e+00,5.433207138825121518e+00,0.000000000000000000e+00,-1.000000009973026183e+00,0.000000000000000000e+00,2.274091016981695024e-10,0.000000000000000000e+00 +8.604816250608605444e+00,7.910999999999999943e+01,0.000000000000000000e+00,5.431366605261018776e+00,0.000000000000000000e+00,-1.000000009972607629e+00,0.000000000000000000e+00,2.014029438953879579e-10,0.000000000000000000e+00 +8.606657407858111952e+00,7.912000000000000455e+01,0.000000000000000000e+00,5.429525447993151843e+00,0.000000000000000000e+00,-1.000000009972236814e+00,0.000000000000000000e+00,-4.269018385759382357e-10,0.000000000000000000e+00 +8.608499189445799615e+00,7.912999999999999545e+01,0.000000000000000000e+00,5.427683666387096650e+00,0.000000000000000000e+00,-1.000000009973023074e+00,0.000000000000000000e+00,4.047020885462131294e-10,0.000000000000000000e+00 +8.610341596007170750e+00,7.914000000000000057e+01,0.000000000000000000e+00,5.425841259807350880e+00,0.000000000000000000e+00,-1.000000009972277448e+00,0.000000000000000000e+00,-2.116796314562189426e-10,0.000000000000000000e+00 +8.612184628178804147e+00,7.915000000000000568e+01,0.000000000000000000e+00,5.423998227617338408e+00,0.000000000000000000e+00,-1.000000009972667581e+00,0.000000000000000000e+00,5.166745341895402734e-11,0.000000000000000000e+00 +8.614028286598358619e+00,7.915999999999999659e+01,0.000000000000000000e+00,5.422154569179396866e+00,0.000000000000000000e+00,-1.000000009972572323e+00,0.000000000000000000e+00,-1.374922513176029195e-10,0.000000000000000000e+00 +8.615872571904580113e+00,7.917000000000000171e+01,0.000000000000000000e+00,5.420310283854782973e+00,0.000000000000000000e+00,-1.000000009972825898e+00,0.000000000000000000e+00,-1.733112943991452361e-11,0.000000000000000000e+00 +8.617717484737298150e+00,7.918000000000000682e+01,0.000000000000000000e+00,5.418465371003665432e+00,0.000000000000000000e+00,-1.000000009972857873e+00,0.000000000000000000e+00,1.306611128828456672e-10,0.000000000000000000e+00 +8.619563025737432937e+00,7.918999999999999773e+01,0.000000000000000000e+00,5.416619829985124923e+00,0.000000000000000000e+00,-1.000000009972616732e+00,0.000000000000000000e+00,2.826418343918622666e-11,0.000000000000000000e+00 +8.621409195546995363e+00,7.920000000000000284e+01,0.000000000000000000e+00,5.414773660157150559e+00,0.000000000000000000e+00,-1.000000009972564552e+00,0.000000000000000000e+00,-7.839134733394953368e-11,0.000000000000000000e+00 +8.623255994809092329e+00,7.921000000000000796e+01,0.000000000000000000e+00,5.412926860876636326e+00,0.000000000000000000e+00,-1.000000009972709325e+00,0.000000000000000000e+00,5.793212014421153045e-11,0.000000000000000000e+00 +8.625103424167924970e+00,7.921999999999999886e+01,0.000000000000000000e+00,5.411079431499379311e+00,0.000000000000000000e+00,-1.000000009972602300e+00,0.000000000000000000e+00,-9.395737777656598253e-11,0.000000000000000000e+00 +8.626951484268795767e+00,7.923000000000000398e+01,0.000000000000000000e+00,5.409231371380077924e+00,0.000000000000000000e+00,-1.000000009972775938e+00,0.000000000000000000e+00,2.384164925970256786e-10,0.000000000000000000e+00 +8.628800175758110313e+00,7.923999999999999488e+01,0.000000000000000000e+00,5.407382679872327458e+00,0.000000000000000000e+00,-1.000000009972335180e+00,0.000000000000000000e+00,-2.503418114482026225e-10,0.000000000000000000e+00 +8.630649499283375548e+00,7.925000000000000000e+01,0.000000000000000000e+00,5.405533356328620087e+00,0.000000000000000000e+00,-1.000000009972798143e+00,0.000000000000000000e+00,-4.681051122208760988e-12,0.000000000000000000e+00 +8.632499455493208629e+00,7.926000000000000512e+01,0.000000000000000000e+00,5.403683400100337764e+00,0.000000000000000000e+00,-1.000000009972806803e+00,0.000000000000000000e+00,-6.431242877033629688e-11,0.000000000000000000e+00 +8.634350045037335164e+00,7.926999999999999602e+01,0.000000000000000000e+00,5.401832810537754881e+00,0.000000000000000000e+00,-1.000000009972925819e+00,0.000000000000000000e+00,3.502387670277827635e-10,0.000000000000000000e+00 +8.636201268566596312e+00,7.928000000000000114e+01,0.000000000000000000e+00,5.399981586990032056e+00,0.000000000000000000e+00,-1.000000009972277448e+00,0.000000000000000000e+00,-3.119893696578848824e-10,0.000000000000000000e+00 +8.638053126732945231e+00,7.929000000000000625e+01,0.000000000000000000e+00,5.398129728805216132e+00,0.000000000000000000e+00,-1.000000009972855208e+00,0.000000000000000000e+00,2.840742631630890878e-11,0.000000000000000000e+00 +8.639905620189454183e+00,7.929999999999999716e+01,0.000000000000000000e+00,5.396277235330232180e+00,0.000000000000000000e+00,-1.000000009972802584e+00,0.000000000000000000e+00,8.423446154897436208e-11,0.000000000000000000e+00 +8.641758749590318089e+00,7.931000000000000227e+01,0.000000000000000000e+00,5.394424105910887945e+00,0.000000000000000000e+00,-1.000000009972646486e+00,0.000000000000000000e+00,-1.324769862950923370e-10,0.000000000000000000e+00 +8.643612515590852752e+00,7.932000000000000739e+01,0.000000000000000000e+00,5.392570339891866738e+00,0.000000000000000000e+00,-1.000000009972892068e+00,0.000000000000000000e+00,1.675150219761772137e-10,0.000000000000000000e+00 +8.645466918847500182e+00,7.932999999999999829e+01,0.000000000000000000e+00,5.390715936616724768e+00,0.000000000000000000e+00,-1.000000009972581427e+00,0.000000000000000000e+00,-3.387451674857839952e-11,0.000000000000000000e+00 +8.647321960017833931e+00,7.934000000000000341e+01,0.000000000000000000e+00,5.388860895427891151e+00,0.000000000000000000e+00,-1.000000009972644266e+00,0.000000000000000000e+00,-2.006643678250113595e-10,0.000000000000000000e+00 +8.649177639760557312e+00,7.935000000000000853e+01,0.000000000000000000e+00,5.387005215666661684e+00,0.000000000000000000e+00,-1.000000009973016635e+00,0.000000000000000000e+00,2.028679634451670602e-10,0.000000000000000000e+00 +8.651033958735508733e+00,7.935999999999999943e+01,0.000000000000000000e+00,5.385148896673197960e+00,0.000000000000000000e+00,-1.000000009972640047e+00,0.000000000000000000e+00,-8.872414983444072749e-11,0.000000000000000000e+00 +8.652890917603661691e+00,7.937000000000000455e+01,0.000000000000000000e+00,5.383291937786526482e+00,0.000000000000000000e+00,-1.000000009972804804e+00,0.000000000000000000e+00,-1.852762943858968925e-11,0.000000000000000000e+00 +8.654748517027131882e+00,7.937999999999999545e+01,0.000000000000000000e+00,5.381434338344531554e+00,0.000000000000000000e+00,-1.000000009972839221e+00,0.000000000000000000e+00,-7.384596092612039942e-11,0.000000000000000000e+00 +8.656606757669175423e+00,7.939000000000000057e+01,0.000000000000000000e+00,5.379576097683956171e+00,0.000000000000000000e+00,-1.000000009972976445e+00,0.000000000000000000e+00,2.907427237133830208e-10,0.000000000000000000e+00 +8.658465640194195956e+00,7.940000000000000568e+01,0.000000000000000000e+00,5.377717215140397577e+00,0.000000000000000000e+00,-1.000000009972435988e+00,0.000000000000000000e+00,-1.772034152140633628e-10,0.000000000000000000e+00 +8.660325165267742875e+00,7.940999999999999659e+01,0.000000000000000000e+00,5.375857690048306381e+00,0.000000000000000000e+00,-1.000000009972765502e+00,0.000000000000000000e+00,-1.563721057965157531e-10,0.000000000000000000e+00 +8.662185333556518430e+00,7.942000000000000171e+01,0.000000000000000000e+00,5.373997521740979444e+00,0.000000000000000000e+00,-1.000000009973056381e+00,0.000000000000000000e+00,1.335265948216458840e-10,0.000000000000000000e+00 +8.664046145728377724e+00,7.943000000000000682e+01,0.000000000000000000e+00,5.372136709550561662e+00,0.000000000000000000e+00,-1.000000009972807913e+00,0.000000000000000000e+00,-3.662061697955515135e-11,0.000000000000000000e+00 +8.665907602452332270e+00,7.943999999999999773e+01,0.000000000000000000e+00,5.370275252808042410e+00,0.000000000000000000e+00,-1.000000009972876081e+00,0.000000000000000000e+00,1.463124673683029101e-10,0.000000000000000000e+00 +8.667769704398553543e+00,7.945000000000000284e+01,0.000000000000000000e+00,5.368413150843250214e+00,0.000000000000000000e+00,-1.000000009972603632e+00,0.000000000000000000e+00,-4.124414032950528704e-11,0.000000000000000000e+00 +8.669632452238374754e+00,7.946000000000000796e+01,0.000000000000000000e+00,5.366550402984852752e+00,0.000000000000000000e+00,-1.000000009972680459e+00,0.000000000000000000e+00,-3.848911811852556850e-11,0.000000000000000000e+00 +8.671495846644292627e+00,7.946999999999999886e+01,0.000000000000000000e+00,5.364687008560351522e+00,0.000000000000000000e+00,-1.000000009972752180e+00,0.000000000000000000e+00,-5.086423177436727495e-11,0.000000000000000000e+00 +8.673359888289972730e+00,7.948000000000000398e+01,0.000000000000000000e+00,5.362822966896080956e+00,0.000000000000000000e+00,-1.000000009972846993e+00,0.000000000000000000e+00,-2.512558263701054936e-11,0.000000000000000000e+00 +8.675224577850253027e+00,7.948999999999999488e+01,0.000000000000000000e+00,5.360958277317204868e+00,0.000000000000000000e+00,-1.000000009972893844e+00,0.000000000000000000e+00,-1.610573130241860929e-10,0.000000000000000000e+00 +8.677089916001142100e+00,7.950000000000000000e+01,0.000000000000000000e+00,5.359092939147713786e+00,0.000000000000000000e+00,-1.000000009973194270e+00,0.000000000000000000e+00,3.651980102824377873e-10,0.000000000000000000e+00 +8.678955903419824480e+00,7.951000000000000512e+01,0.000000000000000000e+00,5.357226951710421403e+00,0.000000000000000000e+00,-1.000000009972512816e+00,0.000000000000000000e+00,-1.714131955802215451e-10,0.000000000000000000e+00 +8.680822540784665975e+00,7.951999999999999602e+01,0.000000000000000000e+00,5.355360314326964577e+00,0.000000000000000000e+00,-1.000000009972832782e+00,0.000000000000000000e+00,-1.763478107130042841e-10,0.000000000000000000e+00 +8.682689828775213670e+00,7.953000000000000114e+01,0.000000000000000000e+00,5.353493026317794445e+00,0.000000000000000000e+00,-1.000000009973162074e+00,0.000000000000000000e+00,1.597631943932834567e-10,0.000000000000000000e+00 +8.684557768072199480e+00,7.954000000000000625e+01,0.000000000000000000e+00,5.351625087002179093e+00,0.000000000000000000e+00,-1.000000009972863646e+00,0.000000000000000000e+00,1.417641277433289984e-10,0.000000000000000000e+00 +8.686426359357543703e+00,7.954999999999999716e+01,0.000000000000000000e+00,5.349756495698199998e+00,0.000000000000000000e+00,-1.000000009972598747e+00,0.000000000000000000e+00,-1.581074359385659974e-10,0.000000000000000000e+00 +8.688295603314355020e+00,7.956000000000000227e+01,0.000000000000000000e+00,5.347887251722746704e+00,0.000000000000000000e+00,-1.000000009972894288e+00,0.000000000000000000e+00,-1.582896859485854160e-10,0.000000000000000000e+00 +8.690165500626939377e+00,7.957000000000000739e+01,0.000000000000000000e+00,5.346017354391514154e+00,0.000000000000000000e+00,-1.000000009973190274e+00,0.000000000000000000e+00,2.172309389822151402e-10,0.000000000000000000e+00 +8.692036051980796429e+00,7.957999999999999829e+01,0.000000000000000000e+00,5.344146803019001801e+00,0.000000000000000000e+00,-1.000000009972783932e+00,0.000000000000000000e+00,3.108994089708835092e-11,0.000000000000000000e+00 +8.693907258062626653e+00,7.959000000000000341e+01,0.000000000000000000e+00,5.342275596918510949e+00,0.000000000000000000e+00,-1.000000009972725756e+00,0.000000000000000000e+00,-1.263328000149102979e-10,0.000000000000000000e+00 +8.695779119560331338e+00,7.960000000000000853e+01,0.000000000000000000e+00,5.340403735402138530e+00,0.000000000000000000e+00,-1.000000009972962234e+00,0.000000000000000000e+00,8.134641765713250750e-11,0.000000000000000000e+00 +8.697651637163019700e+00,7.960999999999999943e+01,0.000000000000000000e+00,5.338531217780776217e+00,0.000000000000000000e+00,-1.000000009972809911e+00,0.000000000000000000e+00,-1.920335129313967551e-11,0.000000000000000000e+00 +8.699524811561007098e+00,7.962000000000000455e+01,0.000000000000000000e+00,5.336658043364108650e+00,0.000000000000000000e+00,-1.000000009972845882e+00,0.000000000000000000e+00,-8.519978352114585928e-11,0.000000000000000000e+00 +8.701398643445820369e+00,7.962999999999999545e+01,0.000000000000000000e+00,5.334784211460608105e+00,0.000000000000000000e+00,-1.000000009973005533e+00,0.000000000000000000e+00,-2.475730509921596733e-11,0.000000000000000000e+00 +8.703273133510201376e+00,7.964000000000000057e+01,0.000000000000000000e+00,5.332909721377532719e+00,0.000000000000000000e+00,-1.000000009973051940e+00,0.000000000000000000e+00,2.960359580460332594e-12,0.000000000000000000e+00 +8.705148282448108787e+00,7.965000000000000568e+01,0.000000000000000000e+00,5.331034572420923823e+00,0.000000000000000000e+00,-1.000000009973046389e+00,0.000000000000000000e+00,9.576355195691837480e-11,0.000000000000000000e+00 +8.707024090954723405e+00,7.965999999999999659e+01,0.000000000000000000e+00,5.329158763895602391e+00,0.000000000000000000e+00,-1.000000009972866755e+00,0.000000000000000000e+00,1.004630998512860193e-10,0.000000000000000000e+00 +8.708900559726446389e+00,7.967000000000000171e+01,0.000000000000000000e+00,5.327282295105166376e+00,0.000000000000000000e+00,-1.000000009972678239e+00,0.000000000000000000e+00,-1.322475819060548188e-10,0.000000000000000000e+00 +8.710777689460906359e+00,7.968000000000000682e+01,0.000000000000000000e+00,5.325405165351987158e+00,0.000000000000000000e+00,-1.000000009972926485e+00,0.000000000000000000e+00,-2.452458305977072072e-10,0.000000000000000000e+00 +8.712655480856961177e+00,7.968999999999999773e+01,0.000000000000000000e+00,5.323527373937205986e+00,0.000000000000000000e+00,-1.000000009973387005e+00,0.000000000000000000e+00,3.723490677543450557e-10,0.000000000000000000e+00 +8.714533934614699717e+00,7.970000000000000284e+01,0.000000000000000000e+00,5.321648920160732210e+00,0.000000000000000000e+00,-1.000000009972687565e+00,0.000000000000000000e+00,-1.830365676209527350e-10,0.000000000000000000e+00 +8.716413051435448978e+00,7.971000000000000796e+01,0.000000000000000000e+00,5.319769803321242385e+00,0.000000000000000000e+00,-1.000000009973031512e+00,0.000000000000000000e+00,-3.649988909396081955e-11,0.000000000000000000e+00 +8.718292832021774075e+00,7.971999999999999886e+01,0.000000000000000000e+00,5.317890022716170506e+00,0.000000000000000000e+00,-1.000000009973100124e+00,0.000000000000000000e+00,1.723980832128015496e-10,0.000000000000000000e+00 +8.720173277077480023e+00,7.973000000000000398e+01,0.000000000000000000e+00,5.316009577641711559e+00,0.000000000000000000e+00,-1.000000009972775938e+00,0.000000000000000000e+00,-1.908692645501785283e-10,0.000000000000000000e+00 +8.722054387307615286e+00,7.973999999999999488e+01,0.000000000000000000e+00,5.314128467392816191e+00,0.000000000000000000e+00,-1.000000009973134985e+00,0.000000000000000000e+00,-9.439788448504799171e-13,0.000000000000000000e+00 +8.723936163418478884e+00,7.975000000000000000e+01,0.000000000000000000e+00,5.312246691263185383e+00,0.000000000000000000e+00,-1.000000009973136761e+00,0.000000000000000000e+00,1.126475710523675963e-10,0.000000000000000000e+00 +8.725818606117618614e+00,7.976000000000000512e+01,0.000000000000000000e+00,5.310364248545271337e+00,0.000000000000000000e+00,-1.000000009972924708e+00,0.000000000000000000e+00,2.605894386783502641e-11,0.000000000000000000e+00 +8.727701716113838160e+00,7.976999999999999602e+01,0.000000000000000000e+00,5.308481138530272148e+00,0.000000000000000000e+00,-1.000000009972875636e+00,0.000000000000000000e+00,-1.311914911635668262e-10,0.000000000000000000e+00 +8.729585494117195310e+00,7.978000000000000114e+01,0.000000000000000000e+00,5.306597360508128247e+00,0.000000000000000000e+00,-1.000000009973122772e+00,0.000000000000000000e+00,2.309470576244073040e-11,0.000000000000000000e+00 +8.731469940839010846e+00,7.979000000000000625e+01,0.000000000000000000e+00,5.304712913767519744e+00,0.000000000000000000e+00,-1.000000009973079251e+00,0.000000000000000000e+00,1.227353964271705819e-10,0.000000000000000000e+00 +8.733355056991864984e+00,7.979999999999999716e+01,0.000000000000000000e+00,5.302827797595864645e+00,0.000000000000000000e+00,-1.000000009972847881e+00,0.000000000000000000e+00,5.545856868555469868e-11,0.000000000000000000e+00 +8.735240843289608037e+00,7.981000000000000227e+01,0.000000000000000000e+00,5.300942011279314414e+00,0.000000000000000000e+00,-1.000000009972743298e+00,0.000000000000000000e+00,-2.879053475532789587e-10,0.000000000000000000e+00 +8.737127300447358635e+00,7.982000000000000739e+01,0.000000000000000000e+00,5.299055554102750420e+00,0.000000000000000000e+00,-1.000000009973286419e+00,0.000000000000000000e+00,2.337957246912251005e-10,0.000000000000000000e+00 +8.739014429181507282e+00,7.982999999999999829e+01,0.000000000000000000e+00,5.297168425349780385e+00,0.000000000000000000e+00,-1.000000009972845216e+00,0.000000000000000000e+00,-2.300662202966245919e-10,0.000000000000000000e+00 +8.740902230209721679e+00,7.984000000000000341e+01,0.000000000000000000e+00,5.295280624302739270e+00,0.000000000000000000e+00,-1.000000009973279536e+00,0.000000000000000000e+00,2.146989790391807065e-10,0.000000000000000000e+00 +8.742790704250946732e+00,7.985000000000000853e+01,0.000000000000000000e+00,5.293392150242679506e+00,0.000000000000000000e+00,-1.000000009972874082e+00,0.000000000000000000e+00,-2.515290021047741103e-11,0.000000000000000000e+00 +8.744679852025411648e+00,7.985999999999999943e+01,0.000000000000000000e+00,5.291503002449374549e+00,0.000000000000000000e+00,-1.000000009972921600e+00,0.000000000000000000e+00,-2.966747976437183293e-10,0.000000000000000000e+00 +8.746569674254629945e+00,7.987000000000000455e+01,0.000000000000000000e+00,5.289613180201309994e+00,0.000000000000000000e+00,-1.000000009973482262e+00,0.000000000000000000e+00,3.019716806895182479e-10,0.000000000000000000e+00 +8.748460171661402995e+00,7.987999999999999545e+01,0.000000000000000000e+00,5.287722682775682692e+00,0.000000000000000000e+00,-1.000000009972911386e+00,0.000000000000000000e+00,-5.811845955547762846e-11,0.000000000000000000e+00 +8.750351344969823586e+00,7.989000000000000057e+01,0.000000000000000000e+00,5.285831509448400745e+00,0.000000000000000000e+00,-1.000000009973021298e+00,0.000000000000000000e+00,2.816856886117804780e-11,0.000000000000000000e+00 +8.752243194905283019e+00,7.990000000000000568e+01,0.000000000000000000e+00,5.283939659494073737e+00,0.000000000000000000e+00,-1.000000009972968007e+00,0.000000000000000000e+00,-1.935895985331108813e-11,0.000000000000000000e+00 +8.754135722194467562e+00,7.990999999999999659e+01,0.000000000000000000e+00,5.282047132186014515e+00,0.000000000000000000e+00,-1.000000009973004644e+00,0.000000000000000000e+00,-3.225337688819505291e-11,0.000000000000000000e+00 +8.756028927565367326e+00,7.992000000000000171e+01,0.000000000000000000e+00,5.280153926796233854e+00,0.000000000000000000e+00,-1.000000009973065707e+00,0.000000000000000000e+00,-8.769774100788791642e-11,0.000000000000000000e+00 +8.757922811747276270e+00,7.993000000000000682e+01,0.000000000000000000e+00,5.278260042595437795e+00,0.000000000000000000e+00,-1.000000009973231796e+00,0.000000000000000000e+00,-1.230609624142167105e-11,0.000000000000000000e+00 +8.759817375470795753e+00,7.993999999999999773e+01,0.000000000000000000e+00,5.276365478853024094e+00,0.000000000000000000e+00,-1.000000009973255111e+00,0.000000000000000000e+00,1.230167912601593091e-10,0.000000000000000000e+00 +8.761712619467838081e+00,7.995000000000000284e+01,0.000000000000000000e+00,5.274470234837079552e+00,0.000000000000000000e+00,-1.000000009973021964e+00,0.000000000000000000e+00,2.459452084914796417e-12,0.000000000000000000e+00 +8.763608544471633621e+00,7.996000000000000796e+01,0.000000000000000000e+00,5.272574309814376470e+00,0.000000000000000000e+00,-1.000000009973017301e+00,0.000000000000000000e+00,-1.907146341004221880e-10,0.000000000000000000e+00 +8.765505151216727242e+00,7.996999999999999886e+01,0.000000000000000000e+00,5.270677703050368201e+00,0.000000000000000000e+00,-1.000000009973379012e+00,0.000000000000000000e+00,2.215426262858055021e-10,0.000000000000000000e+00 +8.767402440438987199e+00,7.998000000000000398e+01,0.000000000000000000e+00,5.268780413809186491e+00,0.000000000000000000e+00,-1.000000009972958681e+00,0.000000000000000000e+00,-5.369860578282406869e-11,0.000000000000000000e+00 +8.769300412875605133e+00,7.998999999999999488e+01,0.000000000000000000e+00,5.266882441353640587e+00,0.000000000000000000e+00,-1.000000009973060600e+00,0.000000000000000000e+00,-8.502140180475452655e-11,0.000000000000000000e+00 +8.771199069265101400e+00,8.000000000000000000e+01,0.000000000000000000e+00,5.264983784945209244e+00,0.000000000000000000e+00,-1.000000009973222026e+00,0.000000000000000000e+00,7.423538902351829681e-11,0.000000000000000000e+00 +8.773098410347326848e+00,8.001000000000000512e+01,0.000000000000000000e+00,5.263084443844040727e+00,0.000000000000000000e+00,-1.000000009973081028e+00,0.000000000000000000e+00,-1.182663180092673209e-10,0.000000000000000000e+00 +8.774998436863469919e+00,8.001999999999999602e+01,0.000000000000000000e+00,5.261184417308949257e+00,0.000000000000000000e+00,-1.000000009973305737e+00,0.000000000000000000e+00,2.932226214601532633e-11,0.000000000000000000e+00 +8.776899149556053104e+00,8.003000000000000114e+01,0.000000000000000000e+00,5.259283704597409681e+00,0.000000000000000000e+00,-1.000000009973250004e+00,0.000000000000000000e+00,2.270194592698918306e-10,0.000000000000000000e+00 +8.778800549168943590e+00,8.004000000000000625e+01,0.000000000000000000e+00,5.257382304965556585e+00,0.000000000000000000e+00,-1.000000009972818349e+00,0.000000000000000000e+00,-3.022329672654106317e-10,0.000000000000000000e+00 +8.780702636447351495e+00,8.004999999999999716e+01,0.000000000000000000e+00,5.255480217668179854e+00,0.000000000000000000e+00,-1.000000009973393222e+00,0.000000000000000000e+00,1.231133335197738079e-10,0.000000000000000000e+00 +8.782605412137835188e+00,8.006000000000000227e+01,0.000000000000000000e+00,5.253577441958718452e+00,0.000000000000000000e+00,-1.000000009973158965e+00,0.000000000000000000e+00,-4.082849846399730341e-12,0.000000000000000000e+00 +8.784508876988306625e+00,8.007000000000000739e+01,0.000000000000000000e+00,5.251673977089263090e+00,0.000000000000000000e+00,-1.000000009973166737e+00,0.000000000000000000e+00,2.098990572188136079e-11,0.000000000000000000e+00 +8.786413031748031344e+00,8.007999999999999829e+01,0.000000000000000000e+00,5.249769822310547340e+00,0.000000000000000000e+00,-1.000000009973126769e+00,0.000000000000000000e+00,-7.483685284633548100e-11,0.000000000000000000e+00 +8.788317877167633796e+00,8.009000000000000341e+01,0.000000000000000000e+00,5.247864976871946752e+00,0.000000000000000000e+00,-1.000000009973269322e+00,0.000000000000000000e+00,1.732741776862797145e-10,0.000000000000000000e+00 +8.790223413999100899e+00,8.010000000000000853e+01,0.000000000000000000e+00,5.245959440021474407e+00,0.000000000000000000e+00,-1.000000009972939141e+00,0.000000000000000000e+00,-2.350641048468234681e-10,0.000000000000000000e+00 +8.792129642995785588e+00,8.010999999999999943e+01,0.000000000000000000e+00,5.244053211005779147e+00,0.000000000000000000e+00,-1.000000009973387227e+00,0.000000000000000000e+00,1.483463083667171845e-10,0.000000000000000000e+00 +8.794036564912408593e+00,8.012000000000000455e+01,0.000000000000000000e+00,5.242146289070138465e+00,0.000000000000000000e+00,-1.000000009973104342e+00,0.000000000000000000e+00,-1.577206858824906133e-10,0.000000000000000000e+00 +8.795944180505061993e+00,8.012999999999999545e+01,0.000000000000000000e+00,5.240238673458460283e+00,0.000000000000000000e+00,-1.000000009973405213e+00,0.000000000000000000e+00,2.989202918993690590e-10,0.000000000000000000e+00 +8.797852490531216318e+00,8.014000000000000057e+01,0.000000000000000000e+00,5.238330363413274071e+00,0.000000000000000000e+00,-1.000000009972834780e+00,0.000000000000000000e+00,-1.985485094190599483e-10,0.000000000000000000e+00 +8.799761495749718776e+00,8.015000000000000568e+01,0.000000000000000000e+00,5.236421358175732621e+00,0.000000000000000000e+00,-1.000000009973213810e+00,0.000000000000000000e+00,-1.921974691635350017e-10,0.000000000000000000e+00 +8.801671196920803908e+00,8.015999999999999659e+01,0.000000000000000000e+00,5.234511656985602279e+00,0.000000000000000000e+00,-1.000000009973580850e+00,0.000000000000000000e+00,3.131222926260160312e-10,0.000000000000000000e+00 +8.803581594806088262e+00,8.017000000000000171e+01,0.000000000000000000e+00,5.232601259081264722e+00,0.000000000000000000e+00,-1.000000009972982662e+00,0.000000000000000000e+00,-1.416320601870260339e-10,0.000000000000000000e+00 +8.805492690168581049e+00,8.018000000000000682e+01,0.000000000000000000e+00,5.230690163699713402e+00,0.000000000000000000e+00,-1.000000009973253334e+00,0.000000000000000000e+00,-9.268343316453922076e-11,0.000000000000000000e+00 +8.807404483772682369e+00,8.018999999999999773e+01,0.000000000000000000e+00,5.228778370076544668e+00,0.000000000000000000e+00,-1.000000009973430526e+00,0.000000000000000000e+00,2.222196160489910068e-10,0.000000000000000000e+00 +8.809316976384193865e+00,8.020000000000000284e+01,0.000000000000000000e+00,5.226865877445959541e+00,0.000000000000000000e+00,-1.000000009973005533e+00,0.000000000000000000e+00,-1.576091226767409477e-10,0.000000000000000000e+00 +8.811230168770313398e+00,8.021000000000000796e+01,0.000000000000000000e+00,5.224952685040759270e+00,0.000000000000000000e+00,-1.000000009973307069e+00,0.000000000000000000e+00,-4.872724729747798776e-12,0.000000000000000000e+00 +8.813144061699647480e+00,8.021999999999999886e+01,0.000000000000000000e+00,5.223038792092338234e+00,0.000000000000000000e+00,-1.000000009973316395e+00,0.000000000000000000e+00,-3.154513431467255814e-11,0.000000000000000000e+00 +8.815058655942205945e+00,8.023000000000000398e+01,0.000000000000000000e+00,5.221124197830684821e+00,0.000000000000000000e+00,-1.000000009973376791e+00,0.000000000000000000e+00,2.492543288509446225e-11,0.000000000000000000e+00 +8.816973952269414383e+00,8.023999999999999488e+01,0.000000000000000000e+00,5.219208901484375218e+00,0.000000000000000000e+00,-1.000000009973329052e+00,0.000000000000000000e+00,1.869301149003254498e-10,0.000000000000000000e+00 +8.818889951454110587e+00,8.025000000000000000e+01,0.000000000000000000e+00,5.217292902280570743e+00,0.000000000000000000e+00,-1.000000009972970894e+00,0.000000000000000000e+00,-2.443216902328010096e-10,0.000000000000000000e+00 +8.820806654270551661e+00,8.026000000000000512e+01,0.000000000000000000e+00,5.215376199445014294e+00,0.000000000000000000e+00,-1.000000009973439186e+00,0.000000000000000000e+00,-3.045661368559301862e-11,0.000000000000000000e+00 +8.822724061494419345e+00,8.026999999999999602e+01,0.000000000000000000e+00,5.213458792202024128e+00,0.000000000000000000e+00,-1.000000009973497583e+00,0.000000000000000000e+00,1.359046347025922101e-10,0.000000000000000000e+00 +8.824642173902818243e+00,8.028000000000000114e+01,0.000000000000000000e+00,5.211540679774494755e+00,0.000000000000000000e+00,-1.000000009973236903e+00,0.000000000000000000e+00,4.929648532900754127e-11,0.000000000000000000e+00 +8.826560992274284700e+00,8.029000000000000625e+01,0.000000000000000000e+00,5.209621861383890717e+00,0.000000000000000000e+00,-1.000000009973142312e+00,0.000000000000000000e+00,-8.907116895752399630e-12,0.000000000000000000e+00 +8.828480517388790361e+00,8.029999999999999716e+01,0.000000000000000000e+00,5.207702336250242148e+00,0.000000000000000000e+00,-1.000000009973159409e+00,0.000000000000000000e+00,-2.370501526030687519e-10,0.000000000000000000e+00 +8.830400750027740386e+00,8.031000000000000227e+01,0.000000000000000000e+00,5.205782103592142107e+00,0.000000000000000000e+00,-1.000000009973614601e+00,0.000000000000000000e+00,1.330459120926120857e-10,0.000000000000000000e+00 +8.832321690973982342e+00,8.032000000000000739e+01,0.000000000000000000e+00,5.203861162626742143e+00,0.000000000000000000e+00,-1.000000009973359028e+00,0.000000000000000000e+00,1.873048148719013978e-10,0.000000000000000000e+00 +8.834243341011807971e+00,8.032999999999999829e+01,0.000000000000000000e+00,5.201939512569751400e+00,0.000000000000000000e+00,-1.000000009972999093e+00,0.000000000000000000e+00,-2.611596547446072822e-10,0.000000000000000000e+00 +8.836165700926958522e+00,8.034000000000000341e+01,0.000000000000000000e+00,5.200017152635429518e+00,0.000000000000000000e+00,-1.000000009973501136e+00,0.000000000000000000e+00,4.537718514243058135e-11,0.000000000000000000e+00 +8.838088771506626529e+00,8.035000000000000853e+01,0.000000000000000000e+00,5.198094082036582186e+00,0.000000000000000000e+00,-1.000000009973413873e+00,0.000000000000000000e+00,2.045257899345470365e-10,0.000000000000000000e+00 +8.840012553539459361e+00,8.035999999999999943e+01,0.000000000000000000e+00,5.196170299984562035e+00,0.000000000000000000e+00,-1.000000009973020410e+00,0.000000000000000000e+00,-2.001811043699944933e-10,0.000000000000000000e+00 +8.841937047815566331e+00,8.037000000000000455e+01,0.000000000000000000e+00,5.194245805689261530e+00,0.000000000000000000e+00,-1.000000009973405657e+00,0.000000000000000000e+00,-1.431312633939446244e-10,0.000000000000000000e+00 +8.843862255126518690e+00,8.037999999999999545e+01,0.000000000000000000e+00,5.192320598359107642e+00,0.000000000000000000e+00,-1.000000009973681214e+00,0.000000000000000000e+00,2.045292100458574842e-10,0.000000000000000000e+00 +8.845788176265356739e+00,8.039000000000000057e+01,0.000000000000000000e+00,5.190394677201061846e+00,0.000000000000000000e+00,-1.000000009973287307e+00,0.000000000000000000e+00,-4.229671827300028940e-11,0.000000000000000000e+00 +8.847714812026588049e+00,8.040000000000000568e+01,0.000000000000000000e+00,5.188468041420615684e+00,0.000000000000000000e+00,-1.000000009973368797e+00,0.000000000000000000e+00,1.503453094032525935e-10,0.000000000000000000e+00 +8.849642163206198120e+00,8.040999999999999659e+01,0.000000000000000000e+00,5.186540690221783656e+00,0.000000000000000000e+00,-1.000000009973079029e+00,0.000000000000000000e+00,-3.335159224100944475e-10,0.000000000000000000e+00 +8.851570230601650380e+00,8.042000000000000171e+01,0.000000000000000000e+00,5.184612622807103222e+00,0.000000000000000000e+00,-1.000000009973722070e+00,0.000000000000000000e+00,2.614409858913131378e-10,0.000000000000000000e+00 +8.853499015011889739e+00,8.043000000000000682e+01,0.000000000000000000e+00,5.182683838377626806e+00,0.000000000000000000e+00,-1.000000009973217807e+00,0.000000000000000000e+00,-1.276222766746390627e-10,0.000000000000000000e+00 +8.855428517237347918e+00,8.043999999999999773e+01,0.000000000000000000e+00,5.180754336132924465e+00,0.000000000000000000e+00,-1.000000009973464055e+00,0.000000000000000000e+00,2.128163317093514388e-11,0.000000000000000000e+00 +8.857358738079948779e+00,8.045000000000000284e+01,0.000000000000000000e+00,5.178824115271072337e+00,0.000000000000000000e+00,-1.000000009973422976e+00,0.000000000000000000e+00,8.555478862607829983e-11,0.000000000000000000e+00 +8.859289678343108321e+00,8.046000000000000796e+01,0.000000000000000000e+00,5.176893174988654422e+00,0.000000000000000000e+00,-1.000000009973257775e+00,0.000000000000000000e+00,-7.575212906546553389e-11,0.000000000000000000e+00 +8.861221338831741789e+00,8.046999999999999886e+01,0.000000000000000000e+00,5.174961514480756364e+00,0.000000000000000000e+00,-1.000000009973404103e+00,0.000000000000000000e+00,1.131836200710344448e-10,0.000000000000000000e+00 +8.863153720352265452e+00,8.048000000000000398e+01,0.000000000000000000e+00,5.173029132940961006e+00,0.000000000000000000e+00,-1.000000009973185389e+00,0.000000000000000000e+00,-1.950396170732060896e-10,0.000000000000000000e+00 +8.865086823712600150e+00,8.048999999999999488e+01,0.000000000000000000e+00,5.171096029561346619e+00,0.000000000000000000e+00,-1.000000009973562420e+00,0.000000000000000000e+00,5.718105595068468622e-11,0.000000000000000000e+00 +8.867020649722180181e+00,8.050000000000000000e+01,0.000000000000000000e+00,5.169162203532479793e+00,0.000000000000000000e+00,-1.000000009973451842e+00,0.000000000000000000e+00,2.995717751912379695e-11,0.000000000000000000e+00 +8.868955199191949745e+00,8.051000000000000512e+01,0.000000000000000000e+00,5.167227654043415441e+00,0.000000000000000000e+00,-1.000000009973393889e+00,0.000000000000000000e+00,-1.618917937452670528e-10,0.000000000000000000e+00 +8.870890472934373605e+00,8.051999999999999602e+01,0.000000000000000000e+00,5.165292380281689688e+00,0.000000000000000000e+00,-1.000000009973707193e+00,0.000000000000000000e+00,3.098992176546993841e-10,0.000000000000000000e+00 +8.872826471763437084e+00,8.053000000000000114e+01,0.000000000000000000e+00,5.163356381433316322e+00,0.000000000000000000e+00,-1.000000009973107229e+00,0.000000000000000000e+00,-3.291588373220977179e-10,0.000000000000000000e+00 +8.874763196494653172e+00,8.054000000000000625e+01,0.000000000000000000e+00,5.161419656682785906e+00,0.000000000000000000e+00,-1.000000009973744719e+00,0.000000000000000000e+00,1.775255286818130388e-10,0.000000000000000000e+00 +8.876700647945060751e+00,8.054999999999999716e+01,0.000000000000000000e+00,5.159482205213055117e+00,0.000000000000000000e+00,-1.000000009973400772e+00,0.000000000000000000e+00,6.346818940823411453e-11,0.000000000000000000e+00 +8.878638826933235251e+00,8.056000000000000227e+01,0.000000000000000000e+00,5.157544026205551191e+00,0.000000000000000000e+00,-1.000000009973277759e+00,0.000000000000000000e+00,-6.562023651159388574e-11,0.000000000000000000e+00 +8.880577734279288649e+00,8.057000000000000739e+01,0.000000000000000000e+00,5.155605118840161261e+00,0.000000000000000000e+00,-1.000000009973404991e+00,0.000000000000000000e+00,-7.452480704472786026e-11,0.000000000000000000e+00 +8.882517370804874801e+00,8.057999999999999829e+01,0.000000000000000000e+00,5.153665482295230582e+00,0.000000000000000000e+00,-1.000000009973549542e+00,0.000000000000000000e+00,-6.087908036758321807e-11,0.000000000000000000e+00 +8.884457737333194771e+00,8.059000000000000341e+01,0.000000000000000000e+00,5.151725115747558981e+00,0.000000000000000000e+00,-1.000000009973667670e+00,0.000000000000000000e+00,1.174798412744758170e-10,0.000000000000000000e+00 +8.886398834688996828e+00,8.060000000000000853e+01,0.000000000000000000e+00,5.149784018372396410e+00,0.000000000000000000e+00,-1.000000009973439630e+00,0.000000000000000000e+00,1.345878028940885721e-10,0.000000000000000000e+00 +8.888340663698587107e+00,8.060999999999999943e+01,0.000000000000000000e+00,5.147842189343439401e+00,0.000000000000000000e+00,-1.000000009973178283e+00,0.000000000000000000e+00,-3.299987039325660386e-10,0.000000000000000000e+00 +8.890283225189827832e+00,8.062000000000000455e+01,0.000000000000000000e+00,5.145899627832825729e+00,0.000000000000000000e+00,-1.000000009973819326e+00,0.000000000000000000e+00,2.883970986611317810e-10,0.000000000000000000e+00 +8.892226519992142642e+00,8.062999999999999545e+01,0.000000000000000000e+00,5.143956333011129090e+00,0.000000000000000000e+00,-1.000000009973258885e+00,0.000000000000000000e+00,-2.061648891845699348e-10,0.000000000000000000e+00 +8.894170548936521925e+00,8.064000000000000057e+01,0.000000000000000000e+00,5.142012304047360871e+00,0.000000000000000000e+00,-1.000000009973659676e+00,0.000000000000000000e+00,2.281228668962548690e-10,0.000000000000000000e+00 +8.896115312855528146e+00,8.065000000000000568e+01,0.000000000000000000e+00,5.140067540108957722e+00,0.000000000000000000e+00,-1.000000009973216031e+00,0.000000000000000000e+00,-1.250891395789692290e-10,0.000000000000000000e+00 +8.898060812583297619e+00,8.065999999999999659e+01,0.000000000000000000e+00,5.138122040361785103e+00,0.000000000000000000e+00,-1.000000009973459392e+00,0.000000000000000000e+00,-1.578994913456079917e-10,0.000000000000000000e+00 +8.900007048955545841e+00,8.067000000000000171e+01,0.000000000000000000e+00,5.136175803970126630e+00,0.000000000000000000e+00,-1.000000009973766701e+00,0.000000000000000000e+00,6.523431927687257237e-11,0.000000000000000000e+00 +8.901954022809569267e+00,8.068000000000000682e+01,0.000000000000000000e+00,5.134228830096684071e+00,0.000000000000000000e+00,-1.000000009973639692e+00,0.000000000000000000e+00,2.502361047720885031e-10,0.000000000000000000e+00 +8.903901734984254190e+00,8.068999999999999773e+01,0.000000000000000000e+00,5.132281117902572909e+00,0.000000000000000000e+00,-1.000000009973152304e+00,0.000000000000000000e+00,-3.601121252876844374e-10,0.000000000000000000e+00 +8.905850186320078521e+00,8.070000000000000284e+01,0.000000000000000000e+00,5.130332666547317011e+00,0.000000000000000000e+00,-1.000000009973853965e+00,0.000000000000000000e+00,2.883220768586105570e-10,0.000000000000000000e+00 +8.907799377659113560e+00,8.071000000000000796e+01,0.000000000000000000e+00,5.128383475188841523e+00,0.000000000000000000e+00,-1.000000009973291970e+00,0.000000000000000000e+00,-1.915343662621278589e-10,0.000000000000000000e+00 +8.909749309845031107e+00,8.071999999999999886e+01,0.000000000000000000e+00,5.126433542983476421e+00,0.000000000000000000e+00,-1.000000009973665449e+00,0.000000000000000000e+00,2.674997740206557136e-11,0.000000000000000000e+00 +8.911699983723108787e+00,8.073000000000000398e+01,0.000000000000000000e+00,5.124482869085943193e+00,0.000000000000000000e+00,-1.000000009973613269e+00,0.000000000000000000e+00,-3.197397205252694397e-11,0.000000000000000000e+00 +8.913651400140231829e+00,8.073999999999999488e+01,0.000000000000000000e+00,5.122531452649357497e+00,0.000000000000000000e+00,-1.000000009973675663e+00,0.000000000000000000e+00,6.324113427764827931e-11,0.000000000000000000e+00 +8.915603559944898393e+00,8.075000000000000000e+01,0.000000000000000000e+00,5.120579292825221174e+00,0.000000000000000000e+00,-1.000000009973552206e+00,0.000000000000000000e+00,4.638947784735703670e-11,0.000000000000000000e+00 +8.917556463987223125e+00,8.076000000000000512e+01,0.000000000000000000e+00,5.118626388763419577e+00,0.000000000000000000e+00,-1.000000009973461612e+00,0.000000000000000000e+00,-1.103603036398510560e-10,0.000000000000000000e+00 +8.919510113118942485e+00,8.076999999999999602e+01,0.000000000000000000e+00,5.116672739612216247e+00,0.000000000000000000e+00,-1.000000009973677217e+00,0.000000000000000000e+00,3.374304843683680188e-11,0.000000000000000000e+00 +8.921464508193418297e+00,8.078000000000000114e+01,0.000000000000000000e+00,5.114718344518248472e+00,0.000000000000000000e+00,-1.000000009973611270e+00,0.000000000000000000e+00,2.252084402782836119e-10,0.000000000000000000e+00 +8.923419650065643083e+00,8.079000000000000625e+01,0.000000000000000000e+00,5.112763202626524617e+00,0.000000000000000000e+00,-1.000000009973170956e+00,0.000000000000000000e+00,-2.493034221943768254e-10,0.000000000000000000e+00 +8.925375539592241836e+00,8.079999999999999716e+01,0.000000000000000000e+00,5.110807313080418801e+00,0.000000000000000000e+00,-1.000000009973658566e+00,0.000000000000000000e+00,-8.851652087311039056e-12,0.000000000000000000e+00 +8.927332177631482679e+00,8.081000000000000227e+01,0.000000000000000000e+00,5.108850675021663790e+00,0.000000000000000000e+00,-1.000000009973675885e+00,0.000000000000000000e+00,8.621384746146851828e-12,0.000000000000000000e+00 +8.929289565043271537e+00,8.082000000000000739e+01,0.000000000000000000e+00,5.106893287590351882e+00,0.000000000000000000e+00,-1.000000009973659010e+00,0.000000000000000000e+00,3.095705619653812231e-11,0.000000000000000000e+00 +8.931247702689166346e+00,8.082999999999999829e+01,0.000000000000000000e+00,5.104935149924926918e+00,0.000000000000000000e+00,-1.000000009973598392e+00,0.000000000000000000e+00,5.712957475006248687e-11,0.000000000000000000e+00 +8.933206591432375276e+00,8.084000000000000341e+01,0.000000000000000000e+00,5.102976261162180727e+00,0.000000000000000000e+00,-1.000000009973486481e+00,0.000000000000000000e+00,-1.408428816379501267e-10,0.000000000000000000e+00 +8.935166232137762066e+00,8.085000000000000853e+01,0.000000000000000000e+00,5.101016620437248683e+00,0.000000000000000000e+00,-1.000000009973762483e+00,0.000000000000000000e+00,1.382969581865429720e-10,0.000000000000000000e+00 +8.937126625671853120e+00,8.085999999999999943e+01,0.000000000000000000e+00,5.099056226883604381e+00,0.000000000000000000e+00,-1.000000009973491366e+00,0.000000000000000000e+00,-1.958737010922780803e-11,0.000000000000000000e+00 +8.939087772902839291e+00,8.087000000000000455e+01,0.000000000000000000e+00,5.097095079633057857e+00,0.000000000000000000e+00,-1.000000009973529780e+00,0.000000000000000000e+00,-1.357007173403709677e-10,0.000000000000000000e+00 +8.941049674700582983e+00,8.087999999999999545e+01,0.000000000000000000e+00,5.095133177815747594e+00,0.000000000000000000e+00,-1.000000009973796011e+00,0.000000000000000000e+00,3.891833107269298039e-11,0.000000000000000000e+00 +8.943012331936618153e+00,8.089000000000000057e+01,0.000000000000000000e+00,5.093170520560137859e+00,0.000000000000000000e+00,-1.000000009973719628e+00,0.000000000000000000e+00,6.661066002355656220e-11,0.000000000000000000e+00 +8.944975745484159191e+00,8.090000000000000568e+01,0.000000000000000000e+00,5.091207106993015152e+00,0.000000000000000000e+00,-1.000000009973588844e+00,0.000000000000000000e+00,-2.509654656873581956e-11,0.000000000000000000e+00 +8.946939916218102695e+00,8.090999999999999659e+01,0.000000000000000000e+00,5.089242936239481985e+00,0.000000000000000000e+00,-1.000000009973638138e+00,0.000000000000000000e+00,2.576488776690148661e-11,0.000000000000000000e+00 +8.948904845015034581e+00,8.092000000000000171e+01,0.000000000000000000e+00,5.087278007422952442e+00,0.000000000000000000e+00,-1.000000009973587511e+00,0.000000000000000000e+00,2.462533744958425279e-11,0.000000000000000000e+00 +8.950870532753233633e+00,8.093000000000000682e+01,0.000000000000000000e+00,5.085312319665148628e+00,0.000000000000000000e+00,-1.000000009973539106e+00,0.000000000000000000e+00,-2.180419864499994365e-10,0.000000000000000000e+00 +8.952836980312675053e+00,8.093999999999999773e+01,0.000000000000000000e+00,5.083345872086095341e+00,0.000000000000000000e+00,-1.000000009973967874e+00,0.000000000000000000e+00,2.591562991385226406e-10,0.000000000000000000e+00 +8.954804188575034019e+00,8.095000000000000284e+01,0.000000000000000000e+00,5.081378663804114737e+00,0.000000000000000000e+00,-1.000000009973458059e+00,0.000000000000000000e+00,-1.018848324244617849e-10,0.000000000000000000e+00 +8.956772158423696339e+00,8.096000000000000796e+01,0.000000000000000000e+00,5.079410693935825449e+00,0.000000000000000000e+00,-1.000000009973658566e+00,0.000000000000000000e+00,-1.016198022449050530e-10,0.000000000000000000e+00 +8.958740890743754903e+00,8.096999999999999886e+01,0.000000000000000000e+00,5.077441961596131925e+00,0.000000000000000000e+00,-1.000000009973858628e+00,0.000000000000000000e+00,8.602203875213928268e-11,0.000000000000000000e+00 +8.960710386422018559e+00,8.098000000000000398e+01,0.000000000000000000e+00,5.075472465898224428e+00,0.000000000000000000e+00,-1.000000009973689208e+00,0.000000000000000000e+00,6.333634785160140348e-11,0.000000000000000000e+00 +8.962680646347019220e+00,8.098999999999999488e+01,0.000000000000000000e+00,5.073502205953573707e+00,0.000000000000000000e+00,-1.000000009973564419e+00,0.000000000000000000e+00,-1.042053008439193448e-10,0.000000000000000000e+00 +8.964651671409010092e+00,8.100000000000000000e+01,0.000000000000000000e+00,5.071531180871924782e+00,0.000000000000000000e+00,-1.000000009973769810e+00,0.000000000000000000e+00,1.086692422611925017e-10,0.000000000000000000e+00 +8.966623462499976327e+00,8.101000000000000512e+01,0.000000000000000000e+00,5.069559389761292501e+00,0.000000000000000000e+00,-1.000000009973555537e+00,0.000000000000000000e+00,-1.387949028503071274e-10,0.000000000000000000e+00 +8.968596020513636802e+00,8.101999999999999602e+01,0.000000000000000000e+00,5.067586831727958874e+00,0.000000000000000000e+00,-1.000000009973829318e+00,0.000000000000000000e+00,1.440294804447136775e-10,0.000000000000000000e+00 +8.970569346345449446e+00,8.103000000000000114e+01,0.000000000000000000e+00,5.065613505876465084e+00,0.000000000000000000e+00,-1.000000009973545101e+00,0.000000000000000000e+00,-1.030309609047561988e-10,0.000000000000000000e+00 +8.972543440892614797e+00,8.104000000000000625e+01,0.000000000000000000e+00,5.063639411309610594e+00,0.000000000000000000e+00,-1.000000009973748494e+00,0.000000000000000000e+00,-1.092871905815182827e-10,0.000000000000000000e+00 +8.974518305054084877e+00,8.104999999999999716e+01,0.000000000000000000e+00,5.061664547128444269e+00,0.000000000000000000e+00,-1.000000009973964321e+00,0.000000000000000000e+00,2.137686909406588668e-10,0.000000000000000000e+00 +8.976493939730561422e+00,8.106000000000000227e+01,0.000000000000000000e+00,5.059688912432262597e+00,0.000000000000000000e+00,-1.000000009973541992e+00,0.000000000000000000e+00,-1.771722638578427647e-10,0.000000000000000000e+00 +8.978470345824506538e+00,8.107000000000000739e+01,0.000000000000000000e+00,5.057712506318605250e+00,0.000000000000000000e+00,-1.000000009973892157e+00,0.000000000000000000e+00,1.805844742666166702e-10,0.000000000000000000e+00 +8.980447524240146251e+00,8.107999999999999829e+01,0.000000000000000000e+00,5.055735327883246200e+00,0.000000000000000000e+00,-1.000000009973535109e+00,0.000000000000000000e+00,-2.009451768738792705e-10,0.000000000000000000e+00 +8.982425475883470511e+00,8.109000000000000341e+01,0.000000000000000000e+00,5.053757376220194608e+00,0.000000000000000000e+00,-1.000000009973932569e+00,0.000000000000000000e+00,1.473395502266575858e-10,0.000000000000000000e+00 +8.984404201662245626e+00,8.110000000000000853e+01,0.000000000000000000e+00,5.051778650421684169e+00,0.000000000000000000e+00,-1.000000009973641024e+00,0.000000000000000000e+00,-2.501436033961547549e-11,0.000000000000000000e+00 +8.986383702486012481e+00,8.110999999999999943e+01,0.000000000000000000e+00,5.049799149578173996e+00,0.000000000000000000e+00,-1.000000009973690540e+00,0.000000000000000000e+00,-1.485696870682469152e-10,0.000000000000000000e+00 +8.988363979266097203e+00,8.112000000000000455e+01,0.000000000000000000e+00,5.047818872778338850e+00,0.000000000000000000e+00,-1.000000009973984749e+00,0.000000000000000000e+00,1.226199996389066198e-10,0.000000000000000000e+00 +8.990345032915611156e+00,8.112999999999999545e+01,0.000000000000000000e+00,5.045837819109066480e+00,0.000000000000000000e+00,-1.000000009973741832e+00,0.000000000000000000e+00,6.946486603371095701e-12,0.000000000000000000e+00 +8.992326864349458049e+00,8.114000000000000057e+01,0.000000000000000000e+00,5.043855987655454065e+00,0.000000000000000000e+00,-1.000000009973728066e+00,0.000000000000000000e+00,8.545302506892918762e-11,0.000000000000000000e+00 +8.994309474484337485e+00,8.115000000000000568e+01,0.000000000000000000e+00,5.041873377500800224e+00,0.000000000000000000e+00,-1.000000009973558646e+00,0.000000000000000000e+00,-1.867360664691582934e-10,0.000000000000000000e+00 +8.996292864238753850e+00,8.115999999999999659e+01,0.000000000000000000e+00,5.039889987726602349e+00,0.000000000000000000e+00,-1.000000009973929016e+00,0.000000000000000000e+00,5.035861715356684088e-12,0.000000000000000000e+00 +8.998277034533016305e+00,8.117000000000000171e+01,0.000000000000000000e+00,5.037905817412549503e+00,0.000000000000000000e+00,-1.000000009973919024e+00,0.000000000000000000e+00,1.245046105053974751e-10,0.000000000000000000e+00 +9.000261986289247673e+00,8.118000000000000682e+01,0.000000000000000000e+00,5.035920865636520638e+00,0.000000000000000000e+00,-1.000000009973671888e+00,0.000000000000000000e+00,-1.328420482144251413e-10,0.000000000000000000e+00 +9.002247720431386213e+00,8.118999999999999773e+01,0.000000000000000000e+00,5.033935131474577496e+00,0.000000000000000000e+00,-1.000000009973935677e+00,0.000000000000000000e+00,5.968828454177954006e-11,0.000000000000000000e+00 +9.004234237885192726e+00,8.120000000000000284e+01,0.000000000000000000e+00,5.031948614000958386e+00,0.000000000000000000e+00,-1.000000009973817106e+00,0.000000000000000000e+00,-4.446921827155628356e-11,0.000000000000000000e+00 +9.006221539578254109e+00,8.121000000000000796e+01,0.000000000000000000e+00,5.029961312288076414e+00,0.000000000000000000e+00,-1.000000009973905479e+00,0.000000000000000000e+00,1.640690509619165627e-10,0.000000000000000000e+00 +9.008209626439990458e+00,8.121999999999999886e+01,0.000000000000000000e+00,5.027973225406511482e+00,0.000000000000000000e+00,-1.000000009973579296e+00,0.000000000000000000e+00,-5.001625791272428710e-11,0.000000000000000000e+00 +9.010198499401658623e+00,8.123000000000000398e+01,0.000000000000000000e+00,5.025984352425007629e+00,0.000000000000000000e+00,-1.000000009973678772e+00,0.000000000000000000e+00,-6.919154801340320572e-11,0.000000000000000000e+00 +9.012188159396357534e+00,8.123999999999999488e+01,0.000000000000000000e+00,5.023994692410465035e+00,0.000000000000000000e+00,-1.000000009973816439e+00,0.000000000000000000e+00,-1.698984046014903656e-10,0.000000000000000000e+00 +9.014178607359033535e+00,8.125000000000000000e+01,0.000000000000000000e+00,5.022004244427937358e+00,0.000000000000000000e+00,-1.000000009974154613e+00,0.000000000000000000e+00,2.726441378803358641e-10,0.000000000000000000e+00 +9.016169844226483931e+00,8.126000000000000512e+01,0.000000000000000000e+00,5.020013007540625516e+00,0.000000000000000000e+00,-1.000000009973611714e+00,0.000000000000000000e+00,-1.277408158504646370e-10,0.000000000000000000e+00 +9.018161870937365876e+00,8.126999999999999602e+01,0.000000000000000000e+00,5.018020980809875020e+00,0.000000000000000000e+00,-1.000000009973866177e+00,0.000000000000000000e+00,-6.562782223655841060e-11,0.000000000000000000e+00 +9.020154688432199919e+00,8.128000000000000114e+01,0.000000000000000000e+00,5.016028163295165321e+00,0.000000000000000000e+00,-1.000000009973996962e+00,0.000000000000000000e+00,2.018172969162810157e-10,0.000000000000000000e+00 +9.022148297653371785e+00,8.129000000000000625e+01,0.000000000000000000e+00,5.014034554054109805e+00,0.000000000000000000e+00,-1.000000009973594617e+00,0.000000000000000000e+00,-2.478293329960400875e-10,0.000000000000000000e+00 +9.024142699545141255e+00,8.129999999999999716e+01,0.000000000000000000e+00,5.012040152142449578e+00,0.000000000000000000e+00,-1.000000009974088888e+00,0.000000000000000000e+00,1.254234327833123639e-10,0.000000000000000000e+00 +9.026137895053645721e+00,8.131000000000000227e+01,0.000000000000000000e+00,5.010044956614044587e+00,0.000000000000000000e+00,-1.000000009973838644e+00,0.000000000000000000e+00,-3.693345464119396865e-11,0.000000000000000000e+00 +9.028133885126907288e+00,8.132000000000000739e+01,0.000000000000000000e+00,5.008048966520874501e+00,0.000000000000000000e+00,-1.000000009973912363e+00,0.000000000000000000e+00,1.427821166413779111e-10,0.000000000000000000e+00 +9.030130670714838104e+00,8.132999999999999829e+01,0.000000000000000000e+00,5.006052180913028060e+00,0.000000000000000000e+00,-1.000000009973627257e+00,0.000000000000000000e+00,-2.353187082303005488e-10,0.000000000000000000e+00 +9.032128252769242138e+00,8.134000000000000341e+01,0.000000000000000000e+00,5.004054598838701295e+00,0.000000000000000000e+00,-1.000000009974097326e+00,0.000000000000000000e+00,1.591128603436913249e-10,0.000000000000000000e+00 +9.034126632243822286e+00,8.135000000000000853e+01,0.000000000000000000e+00,5.002056219344188648e+00,0.000000000000000000e+00,-1.000000009973779358e+00,0.000000000000000000e+00,-8.774368816592901407e-12,0.000000000000000000e+00 +9.036125810094189248e+00,8.135999999999999943e+01,0.000000000000000000e+00,5.000057041473882968e+00,0.000000000000000000e+00,-1.000000009973796899e+00,0.000000000000000000e+00,-6.650311785356367971e-11,0.000000000000000000e+00 +9.038125787277859757e+00,8.137000000000000455e+01,0.000000000000000000e+00,4.998057064270264860e+00,0.000000000000000000e+00,-1.000000009973929904e+00,0.000000000000000000e+00,-4.772103906783207030e-12,0.000000000000000000e+00 +9.040126564754269012e+00,8.137999999999999545e+01,0.000000000000000000e+00,4.996056286773900013e+00,0.000000000000000000e+00,-1.000000009973939452e+00,0.000000000000000000e+00,-3.095079090820003664e-11,0.000000000000000000e+00 +9.042128143484770675e+00,8.139000000000000057e+01,0.000000000000000000e+00,4.994054708023433875e+00,0.000000000000000000e+00,-1.000000009974001403e+00,0.000000000000000000e+00,9.592010124937533839e-11,0.000000000000000000e+00 +9.044130524432647533e+00,8.140000000000000568e+01,0.000000000000000000e+00,4.992052327055585437e+00,0.000000000000000000e+00,-1.000000009973809334e+00,0.000000000000000000e+00,-4.311902735364686926e-11,0.000000000000000000e+00 +9.046133708563111497e+00,8.140999999999999659e+01,0.000000000000000000e+00,4.990049142905142787e+00,0.000000000000000000e+00,-1.000000009973895709e+00,0.000000000000000000e+00,-1.967831959115325694e-10,0.000000000000000000e+00 +9.048137696843310707e+00,8.142000000000000171e+01,0.000000000000000000e+00,4.988045154604956011e+00,0.000000000000000000e+00,-1.000000009974290061e+00,0.000000000000000000e+00,3.313844998981802545e-10,0.000000000000000000e+00 +9.050142490242338411e+00,8.143000000000000682e+01,0.000000000000000000e+00,4.986040361185932746e+00,0.000000000000000000e+00,-1.000000009973625703e+00,0.000000000000000000e+00,-1.876574098826945372e-10,0.000000000000000000e+00 +9.052148089731232972e+00,8.143999999999999773e+01,0.000000000000000000e+00,4.984034761677035519e+00,0.000000000000000000e+00,-1.000000009974002069e+00,0.000000000000000000e+00,5.754725753863839590e-11,0.000000000000000000e+00 +9.054154496282986742e+00,8.145000000000000284e+01,0.000000000000000000e+00,4.982028355105269313e+00,0.000000000000000000e+00,-1.000000009973886606e+00,0.000000000000000000e+00,1.128357168191346076e-11,0.000000000000000000e+00 +9.056161710872553172e+00,8.146000000000000796e+01,0.000000000000000000e+00,4.980021140495683341e+00,0.000000000000000000e+00,-1.000000009973863957e+00,0.000000000000000000e+00,-5.175082348767244596e-11,0.000000000000000000e+00 +9.058169734476846813e+00,8.146999999999999886e+01,0.000000000000000000e+00,4.978013116871361277e+00,0.000000000000000000e+00,-1.000000009973967874e+00,0.000000000000000000e+00,-7.295250308592345854e-11,0.000000000000000000e+00 +9.060178568074755745e+00,8.148000000000000398e+01,0.000000000000000000e+00,4.976004283253416816e+00,0.000000000000000000e+00,-1.000000009974114423e+00,0.000000000000000000e+00,1.104894905180268419e-11,0.000000000000000000e+00 +9.062188212647139807e+00,8.148999999999999488e+01,0.000000000000000000e+00,4.973994638660988343e+00,0.000000000000000000e+00,-1.000000009974092219e+00,0.000000000000000000e+00,4.870618654283499679e-11,0.000000000000000000e+00 +9.064198669176841250e+00,8.150000000000000000e+01,0.000000000000000000e+00,4.971984182111233608e+00,0.000000000000000000e+00,-1.000000009973994297e+00,0.000000000000000000e+00,1.134914326785884722e-10,0.000000000000000000e+00 +9.066209938648691846e+00,8.151000000000000512e+01,0.000000000000000000e+00,4.969972912619323502e+00,0.000000000000000000e+00,-1.000000009973766035e+00,0.000000000000000000e+00,-1.546081496290801430e-10,0.000000000000000000e+00 +9.068222022049511111e+00,8.151999999999999602e+01,0.000000000000000000e+00,4.967960829198436734e+00,0.000000000000000000e+00,-1.000000009974077120e+00,0.000000000000000000e+00,-1.389917213499021049e-11,0.000000000000000000e+00 +9.070234920368118736e+00,8.153000000000000114e+01,0.000000000000000000e+00,4.965947930859752724e+00,0.000000000000000000e+00,-1.000000009974105097e+00,0.000000000000000000e+00,1.850266746035758948e-10,0.000000000000000000e+00 +9.072248634595338146e+00,8.154000000000000625e+01,0.000000000000000000e+00,4.963934216612448935e+00,0.000000000000000000e+00,-1.000000009973732507e+00,0.000000000000000000e+00,-1.210231863577708434e-10,0.000000000000000000e+00 +9.074263165724000046e+00,8.154999999999999716e+01,0.000000000000000000e+00,4.961919685463693774e+00,0.000000000000000000e+00,-1.000000009973976312e+00,0.000000000000000000e+00,-1.754013853995806338e-10,0.000000000000000000e+00 +9.076278514748954862e+00,8.156000000000000227e+01,0.000000000000000000e+00,4.959904336418638593e+00,0.000000000000000000e+00,-1.000000009974329807e+00,0.000000000000000000e+00,3.422902556413449365e-10,0.000000000000000000e+00 +9.078294682667069182e+00,8.157000000000000739e+01,0.000000000000000000e+00,4.957888168480415025e+00,0.000000000000000000e+00,-1.000000009973639692e+00,0.000000000000000000e+00,-2.061933854672085899e-10,0.000000000000000000e+00 +9.080311670477236419e+00,8.157999999999999829e+01,0.000000000000000000e+00,4.955871180650130547e+00,0.000000000000000000e+00,-1.000000009974055581e+00,0.000000000000000000e+00,4.038557762206180065e-11,0.000000000000000000e+00 +9.082329479180385690e+00,8.159000000000000341e+01,0.000000000000000000e+00,4.953853371926856042e+00,0.000000000000000000e+00,-1.000000009973974091e+00,0.000000000000000000e+00,-1.084576745018468403e-10,0.000000000000000000e+00 +9.084348109779480041e+00,8.160000000000000853e+01,0.000000000000000000e+00,4.951834741307627574e+00,0.000000000000000000e+00,-1.000000009974193027e+00,0.000000000000000000e+00,1.256760719784337536e-10,0.000000000000000000e+00 +9.086367563279528881e+00,8.160999999999999943e+01,0.000000000000000000e+00,4.949815287787435736e+00,0.000000000000000000e+00,-1.000000009973939230e+00,0.000000000000000000e+00,6.594478680171847856e-13,0.000000000000000000e+00 +9.088387840687591535e+00,8.162000000000000455e+01,0.000000000000000000e+00,4.947795010359222978e+00,0.000000000000000000e+00,-1.000000009973937898e+00,0.000000000000000000e+00,-1.305173851730402790e-10,0.000000000000000000e+00 +9.090408943012780796e+00,8.162999999999999545e+01,0.000000000000000000e+00,4.945773908013874731e+00,0.000000000000000000e+00,-1.000000009974201687e+00,0.000000000000000000e+00,8.895277548973098242e-11,0.000000000000000000e+00 +9.092430871266273584e+00,8.164000000000000057e+01,0.000000000000000000e+00,4.943751979740214963e+00,0.000000000000000000e+00,-1.000000009974021831e+00,0.000000000000000000e+00,-6.520536723821219129e-11,0.000000000000000000e+00 +9.094453626461310947e+00,8.165000000000000568e+01,0.000000000000000000e+00,4.941729224525001740e+00,0.000000000000000000e+00,-1.000000009974153725e+00,0.000000000000000000e+00,-8.119903918465401205e-12,0.000000000000000000e+00 +9.096477209613210491e+00,8.165999999999999659e+01,0.000000000000000000e+00,4.939705641352918342e+00,0.000000000000000000e+00,-1.000000009974170156e+00,0.000000000000000000e+00,1.979787152582183472e-10,0.000000000000000000e+00 +9.098501621739368161e+00,8.167000000000000171e+01,0.000000000000000000e+00,4.937681229206569711e+00,0.000000000000000000e+00,-1.000000009973769366e+00,0.000000000000000000e+00,-1.526168585076602785e-10,0.000000000000000000e+00 +9.100526863859261795e+00,8.168000000000000682e+01,0.000000000000000000e+00,4.935655987066476236e+00,0.000000000000000000e+00,-1.000000009974078452e+00,0.000000000000000000e+00,-2.717920743561222056e-11,0.000000000000000000e+00 +9.102552936994465327e+00,8.168999999999999773e+01,0.000000000000000000e+00,4.933629913911064868e+00,0.000000000000000000e+00,-1.000000009974133519e+00,0.000000000000000000e+00,9.552637092303692910e-11,0.000000000000000000e+00 +9.104579842168647019e+00,8.170000000000000284e+01,0.000000000000000000e+00,4.931603008716667347e+00,0.000000000000000000e+00,-1.000000009973939896e+00,0.000000000000000000e+00,-2.564573941302591234e-10,0.000000000000000000e+00 +9.106607580407578340e+00,8.171000000000000796e+01,0.000000000000000000e+00,4.929575270457512204e+00,0.000000000000000000e+00,-1.000000009974459925e+00,0.000000000000000000e+00,1.791836616358055104e-10,0.000000000000000000e+00 +9.108636152739139291e+00,8.171999999999999886e+01,0.000000000000000000e+00,4.927546698105716771e+00,0.000000000000000000e+00,-1.000000009974096438e+00,0.000000000000000000e+00,7.790242337993348400e-11,0.000000000000000000e+00 +9.110665560193329071e+00,8.173000000000000398e+01,0.000000000000000000e+00,4.925517290631286293e+00,0.000000000000000000e+00,-1.000000009973938342e+00,0.000000000000000000e+00,-1.512565719995044816e-10,0.000000000000000000e+00 +9.112695803802264294e+00,8.173999999999999488e+01,0.000000000000000000e+00,4.923487047002102379e+00,0.000000000000000000e+00,-1.000000009974245430e+00,0.000000000000000000e+00,1.203650343561804914e-10,0.000000000000000000e+00 +9.114726884600189649e+00,8.175000000000000000e+01,0.000000000000000000e+00,4.921455966183918562e+00,0.000000000000000000e+00,-1.000000009974000958e+00,0.000000000000000000e+00,1.879586322547663828e-11,0.000000000000000000e+00 +9.116758803623485008e+00,8.176000000000000512e+01,0.000000000000000000e+00,4.919424047140356748e+00,0.000000000000000000e+00,-1.000000009973962767e+00,0.000000000000000000e+00,-3.156838234427279427e-11,0.000000000000000000e+00 +9.118791561910668975e+00,8.176999999999999602e+01,0.000000000000000000e+00,4.917391288832897445e+00,0.000000000000000000e+00,-1.000000009974026938e+00,0.000000000000000000e+00,-3.144614993253191085e-11,0.000000000000000000e+00 +9.120825160502407769e+00,8.178000000000000114e+01,0.000000000000000000e+00,4.915357690220875320e+00,0.000000000000000000e+00,-1.000000009974090887e+00,0.000000000000000000e+00,-1.914365863308601414e-10,0.000000000000000000e+00 +9.122859600441518779e+00,8.179000000000000625e+01,0.000000000000000000e+00,4.913323250261472985e+00,0.000000000000000000e+00,-1.000000009974480353e+00,0.000000000000000000e+00,1.426997811325049817e-10,0.000000000000000000e+00 +9.124894882772977667e+00,8.179999999999999716e+01,0.000000000000000000e+00,4.911287967909713892e+00,0.000000000000000000e+00,-1.000000009974189918e+00,0.000000000000000000e+00,1.282457395892904984e-10,0.000000000000000000e+00 +9.126931008543923696e+00,8.181000000000000227e+01,0.000000000000000000e+00,4.909251842118458775e+00,0.000000000000000000e+00,-1.000000009973928794e+00,0.000000000000000000e+00,2.180145771521350640e-12,0.000000000000000000e+00 +9.128967978803670391e+00,8.182000000000000739e+01,0.000000000000000000e+00,4.907214871838395887e+00,0.000000000000000000e+00,-1.000000009973924353e+00,0.000000000000000000e+00,-2.082264942711725457e-10,0.000000000000000000e+00 +9.131005794603705539e+00,8.182999999999999829e+01,0.000000000000000000e+00,4.905177056018035664e+00,0.000000000000000000e+00,-1.000000009974348680e+00,0.000000000000000000e+00,1.711083087442129722e-10,0.000000000000000000e+00 +9.133044456997701843e+00,8.184000000000000341e+01,0.000000000000000000e+00,4.903138393603704515e+00,0.000000000000000000e+00,-1.000000009973999848e+00,0.000000000000000000e+00,-1.036457086980463738e-10,0.000000000000000000e+00 +9.135083967041522257e+00,8.185000000000000853e+01,0.000000000000000000e+00,4.901098883539541262e+00,0.000000000000000000e+00,-1.000000009974211235e+00,0.000000000000000000e+00,-1.333121642485210755e-10,0.000000000000000000e+00 +9.137124325793227086e+00,8.185999999999999943e+01,0.000000000000000000e+00,4.899058524767485601e+00,0.000000000000000000e+00,-1.000000009974483239e+00,0.000000000000000000e+00,3.444004923339484981e-10,0.000000000000000000e+00 +9.139165534313077544e+00,8.187000000000000455e+01,0.000000000000000000e+00,4.897017316227275430e+00,0.000000000000000000e+00,-1.000000009973780246e+00,0.000000000000000000e+00,-3.196827449360603889e-10,0.000000000000000000e+00 +9.141207593663544628e+00,8.187999999999999545e+01,0.000000000000000000e+00,4.894975256856441526e+00,0.000000000000000000e+00,-1.000000009974433057e+00,0.000000000000000000e+00,6.684452509212926350e-11,0.000000000000000000e+00 +9.143250504909314458e+00,8.189000000000000057e+01,0.000000000000000000e+00,4.892932345590294219e+00,0.000000000000000000e+00,-1.000000009974296500e+00,0.000000000000000000e+00,8.017995314459097072e-11,0.000000000000000000e+00 +9.145294269117297148e+00,8.190000000000000568e+01,0.000000000000000000e+00,4.890888581361926057e+00,0.000000000000000000e+00,-1.000000009974132631e+00,0.000000000000000000e+00,6.950370705797477076e-12,0.000000000000000000e+00 +9.147338887356630366e+00,8.190999999999999659e+01,0.000000000000000000e+00,4.888843963102199375e+00,0.000000000000000000e+00,-1.000000009974118420e+00,0.000000000000000000e+00,-7.435958770340991646e-11,0.000000000000000000e+00 +9.149384360698686436e+00,8.192000000000000171e+01,0.000000000000000000e+00,4.886798489739740958e+00,0.000000000000000000e+00,-1.000000009974270521e+00,0.000000000000000000e+00,1.337912566923082826e-10,0.000000000000000000e+00 +9.151430690217081221e+00,8.193000000000000682e+01,0.000000000000000000e+00,4.884752160200935833e+00,0.000000000000000000e+00,-1.000000009973996740e+00,0.000000000000000000e+00,-1.269020450375156720e-10,0.000000000000000000e+00 +9.153477876987675899e+00,8.193999999999999773e+01,0.000000000000000000e+00,4.882704973409921934e+00,0.000000000000000000e+00,-1.000000009974256532e+00,0.000000000000000000e+00,8.825211335840412835e-11,0.000000000000000000e+00 +9.155525922088589397e+00,8.195000000000000284e+01,0.000000000000000000e+00,4.880656928288580332e+00,0.000000000000000000e+00,-1.000000009974075788e+00,0.000000000000000000e+00,-1.774055434024736486e-10,0.000000000000000000e+00 +9.157574826600201945e+00,8.196000000000000796e+01,0.000000000000000000e+00,4.878608023756532575e+00,0.000000000000000000e+00,-1.000000009974439275e+00,0.000000000000000000e+00,2.421105301374703742e-10,0.000000000000000000e+00 +9.159624591605158628e+00,8.196999999999999886e+01,0.000000000000000000e+00,4.876558258731130024e+00,0.000000000000000000e+00,-1.000000009973943005e+00,0.000000000000000000e+00,-2.300978585401936110e-10,0.000000000000000000e+00 +9.161675218188383596e+00,8.198000000000000398e+01,0.000000000000000000e+00,4.874507632127452084e+00,0.000000000000000000e+00,-1.000000009974414850e+00,0.000000000000000000e+00,5.303554794760969901e-12,0.000000000000000000e+00 +9.163726707437080066e+00,8.198999999999999488e+01,0.000000000000000000e+00,4.872456142858292871e+00,0.000000000000000000e+00,-1.000000009974403969e+00,0.000000000000000000e+00,2.287142094826151140e-10,0.000000000000000000e+00 +9.165779060440740977e+00,8.200000000000000000e+01,0.000000000000000000e+00,4.870403789834161223e+00,0.000000000000000000e+00,-1.000000009973934567e+00,0.000000000000000000e+00,-2.700372872691736411e-10,0.000000000000000000e+00 +9.167832278291152548e+00,8.201000000000000512e+01,0.000000000000000000e+00,4.868350571963270923e+00,0.000000000000000000e+00,-1.000000009974489013e+00,0.000000000000000000e+00,1.221519806708592113e-10,0.000000000000000000e+00 +9.169886362082404929e+00,8.201999999999999602e+01,0.000000000000000000e+00,4.866296488151530930e+00,0.000000000000000000e+00,-1.000000009974238102e+00,0.000000000000000000e+00,7.444885331190153207e-11,0.000000000000000000e+00 +9.171941312910893984e+00,8.203000000000000114e+01,0.000000000000000000e+00,4.864241537302545382e+00,0.000000000000000000e+00,-1.000000009974085113e+00,0.000000000000000000e+00,-5.184377233969298734e-11,0.000000000000000000e+00 +9.173997131875333721e+00,8.204000000000000625e+01,0.000000000000000000e+00,4.862185718317601157e+00,0.000000000000000000e+00,-1.000000009974191695e+00,0.000000000000000000e+00,-1.004048559413244042e-10,0.000000000000000000e+00 +9.176053820076758072e+00,8.204999999999999716e+01,0.000000000000000000e+00,4.860129030095662550e+00,0.000000000000000000e+00,-1.000000009974398196e+00,0.000000000000000000e+00,9.075781269430765254e-11,0.000000000000000000e+00 +9.178111378618533323e+00,8.206000000000000227e+01,0.000000000000000000e+00,4.858071471533365049e+00,0.000000000000000000e+00,-1.000000009974211457e+00,0.000000000000000000e+00,-1.498326190665331942e-10,0.000000000000000000e+00 +9.180169808606358117e+00,8.207000000000000739e+01,0.000000000000000000e+00,4.856013041525009122e+00,0.000000000000000000e+00,-1.000000009974519877e+00,0.000000000000000000e+00,1.912818156238974664e-10,0.000000000000000000e+00 +9.182229111148275891e+00,8.207999999999999829e+01,0.000000000000000000e+00,4.853953738962550446e+00,0.000000000000000000e+00,-1.000000009974125970e+00,0.000000000000000000e+00,3.729168071411420106e-11,0.000000000000000000e+00 +9.184289287354680198e+00,8.209000000000000341e+01,0.000000000000000000e+00,4.851893562735597243e+00,0.000000000000000000e+00,-1.000000009974049142e+00,0.000000000000000000e+00,-2.150364231394752638e-10,0.000000000000000000e+00 +9.186350338338321819e+00,8.210000000000000853e+01,0.000000000000000000e+00,4.849832511731398732e+00,0.000000000000000000e+00,-1.000000009974492343e+00,0.000000000000000000e+00,4.533661196324076987e-11,0.000000000000000000e+00 +9.188412265214314090e+00,8.210999999999999943e+01,0.000000000000000000e+00,4.847770584834839802e+00,0.000000000000000000e+00,-1.000000009974398862e+00,0.000000000000000000e+00,1.803005684663706642e-10,0.000000000000000000e+00 +9.190475069100141781e+00,8.212000000000000455e+01,0.000000000000000000e+00,4.845707780928436570e+00,0.000000000000000000e+00,-1.000000009974026938e+00,0.000000000000000000e+00,-2.300409470828989539e-10,0.000000000000000000e+00 +9.192538751115668205e+00,8.212999999999999545e+01,0.000000000000000000e+00,4.843644098892326610e+00,0.000000000000000000e+00,-1.000000009974501669e+00,0.000000000000000000e+00,6.893987308553799193e-11,0.000000000000000000e+00 +9.194603312383142324e+00,8.214000000000000057e+01,0.000000000000000000e+00,4.841579537604260075e+00,0.000000000000000000e+00,-1.000000009974359338e+00,0.000000000000000000e+00,4.310936928718219796e-11,0.000000000000000000e+00 +9.196668754027202297e+00,8.215000000000000568e+01,0.000000000000000000e+00,4.839514095939597915e+00,0.000000000000000000e+00,-1.000000009974270299e+00,0.000000000000000000e+00,-8.285073445012236382e-11,0.000000000000000000e+00 +9.198735077174889696e+00,8.215999999999999659e+01,0.000000000000000000e+00,4.837447772771300336e+00,0.000000000000000000e+00,-1.000000009974441495e+00,0.000000000000000000e+00,1.293251532178773258e-10,0.000000000000000000e+00 +9.200802282955649503e+00,8.217000000000000171e+01,0.000000000000000000e+00,4.835380566969920579e+00,0.000000000000000000e+00,-1.000000009974174153e+00,0.000000000000000000e+00,-1.236868033138571246e-10,0.000000000000000000e+00 +9.202870372501342544e+00,8.218000000000000682e+01,0.000000000000000000e+00,4.833312477403599594e+00,0.000000000000000000e+00,-1.000000009974429949e+00,0.000000000000000000e+00,2.446920987715418918e-11,0.000000000000000000e+00 +9.204939346946249046e+00,8.218999999999999773e+01,0.000000000000000000e+00,4.831243502938055379e+00,0.000000000000000000e+00,-1.000000009974379322e+00,0.000000000000000000e+00,-7.509260884345534174e-12,0.000000000000000000e+00 +9.207009207427079289e+00,8.220000000000000284e+01,0.000000000000000000e+00,4.829173642436579428e+00,0.000000000000000000e+00,-1.000000009974394866e+00,0.000000000000000000e+00,3.560009285783359311e-11,0.000000000000000000e+00 +9.209079955082977165e+00,8.221000000000000796e+01,0.000000000000000000e+00,4.827102894760026963e+00,0.000000000000000000e+00,-1.000000009974321147e+00,0.000000000000000000e+00,1.500565017279251150e-12,0.000000000000000000e+00 +9.211151591055530830e+00,8.221999999999999886e+01,0.000000000000000000e+00,4.825031258766810716e+00,0.000000000000000000e+00,-1.000000009974318038e+00,0.000000000000000000e+00,-4.842602161409189273e-11,0.000000000000000000e+00 +9.213224116488776261e+00,8.223000000000000398e+01,0.000000000000000000e+00,4.822958733312892932e+00,0.000000000000000000e+00,-1.000000009974418402e+00,0.000000000000000000e+00,1.598871565996728726e-10,0.000000000000000000e+00 +9.215297532529209690e+00,8.223999999999999488e+01,0.000000000000000000e+00,4.820885317251778268e+00,0.000000000000000000e+00,-1.000000009974086890e+00,0.000000000000000000e+00,-1.251357891944266697e-10,0.000000000000000000e+00 +9.217371840325791155e+00,8.225000000000000000e+01,0.000000000000000000e+00,4.818811009434507575e+00,0.000000000000000000e+00,-1.000000009974346460e+00,0.000000000000000000e+00,3.316972059074656928e-12,0.000000000000000000e+00 +9.219447041029953382e+00,8.226000000000000512e+01,0.000000000000000000e+00,4.816735808709647237e+00,0.000000000000000000e+00,-1.000000009974339577e+00,0.000000000000000000e+00,1.358303353584944525e-11,0.000000000000000000e+00 +9.221523135795607118e+00,8.226999999999999602e+01,0.000000000000000000e+00,4.814659713923285622e+00,0.000000000000000000e+00,-1.000000009974311377e+00,0.000000000000000000e+00,-2.053681960145022111e-10,0.000000000000000000e+00 +9.223600125779153558e+00,8.228000000000000114e+01,0.000000000000000000e+00,4.812582723919023309e+00,0.000000000000000000e+00,-1.000000009974737925e+00,0.000000000000000000e+00,2.703578314892125334e-10,0.000000000000000000e+00 +9.225678012139486128e+00,8.229000000000000625e+01,0.000000000000000000e+00,4.810504837537965095e+00,0.000000000000000000e+00,-1.000000009974176152e+00,0.000000000000000000e+00,-9.741497412806552895e-11,0.000000000000000000e+00 +9.227756796038001141e+00,8.229999999999999716e+01,0.000000000000000000e+00,4.808426053618716445e+00,0.000000000000000000e+00,-1.000000009974378656e+00,0.000000000000000000e+00,3.982465286433492407e-11,0.000000000000000000e+00 +9.229836478638604902e+00,8.231000000000000227e+01,0.000000000000000000e+00,4.806346370997369277e+00,0.000000000000000000e+00,-1.000000009974295834e+00,0.000000000000000000e+00,-2.235832773864629859e-10,0.000000000000000000e+00 +9.231917061107720812e+00,8.232000000000000739e+01,0.000000000000000000e+00,4.804265788507500190e+00,0.000000000000000000e+00,-1.000000009974761017e+00,0.000000000000000000e+00,2.654102111822411400e-10,0.000000000000000000e+00 +9.233998544614300030e+00,8.232999999999999829e+01,0.000000000000000000e+00,4.802184304980158913e+00,0.000000000000000000e+00,-1.000000009974208570e+00,0.000000000000000000e+00,-2.032366116576019203e-10,0.000000000000000000e+00 +9.236080930329823246e+00,8.234000000000000341e+01,0.000000000000000000e+00,4.800101919243865645e+00,0.000000000000000000e+00,-1.000000009974631787e+00,0.000000000000000000e+00,1.513488162646911925e-10,0.000000000000000000e+00 +9.238164219428313118e+00,8.235000000000000853e+01,0.000000000000000000e+00,4.798018630124595951e+00,0.000000000000000000e+00,-1.000000009974316484e+00,0.000000000000000000e+00,4.389341502733697844e-11,0.000000000000000000e+00 +9.240248413086339596e+00,8.235999999999999943e+01,0.000000000000000000e+00,4.795934436445780769e+00,0.000000000000000000e+00,-1.000000009974225001e+00,0.000000000000000000e+00,-1.649547707772594713e-10,0.000000000000000000e+00 +9.242333512483030589e+00,8.237000000000000455e+01,0.000000000000000000e+00,4.793849337028293078e+00,0.000000000000000000e+00,-1.000000009974568949e+00,0.000000000000000000e+00,9.537457503710711594e-11,0.000000000000000000e+00 +9.244419518800075508e+00,8.237999999999999545e+01,0.000000000000000000e+00,4.791763330690441691e+00,0.000000000000000000e+00,-1.000000009974369997e+00,0.000000000000000000e+00,-2.713162248926399101e-11,0.000000000000000000e+00 +9.246506433221735932e+00,8.239000000000000057e+01,0.000000000000000000e+00,4.789676416247965918e+00,0.000000000000000000e+00,-1.000000009974426618e+00,0.000000000000000000e+00,5.147445548612273437e-11,0.000000000000000000e+00 +9.248594256934852709e+00,8.240000000000000568e+01,0.000000000000000000e+00,4.787588592514024022e+00,0.000000000000000000e+00,-1.000000009974319148e+00,0.000000000000000000e+00,-9.705721526399155204e-11,0.000000000000000000e+00 +9.250682991128854837e+00,8.240999999999999659e+01,0.000000000000000000e+00,4.785499858299187892e+00,0.000000000000000000e+00,-1.000000009974521875e+00,0.000000000000000000e+00,-7.905702525011982782e-11,0.000000000000000000e+00 +9.252772636995766575e+00,8.242000000000000171e+01,0.000000000000000000e+00,4.783410212411433271e+00,0.000000000000000000e+00,-1.000000009974687076e+00,0.000000000000000000e+00,9.814085180677533666e-11,0.000000000000000000e+00 +9.254863195730212766e+00,8.243000000000000682e+01,0.000000000000000000e+00,4.781319653656133539e+00,0.000000000000000000e+00,-1.000000009974481907e+00,0.000000000000000000e+00,2.887732155164509550e-11,0.000000000000000000e+00 +9.256954668529433050e+00,8.243999999999999773e+01,0.000000000000000000e+00,4.779228180836051720e+00,0.000000000000000000e+00,-1.000000009974421511e+00,0.000000000000000000e+00,-7.576981089478664688e-11,0.000000000000000000e+00 +9.259047056593283642e+00,8.245000000000000284e+01,0.000000000000000000e+00,4.777135792751330712e+00,0.000000000000000000e+00,-1.000000009974580051e+00,0.000000000000000000e+00,2.049344327924711669e-10,0.000000000000000000e+00 +9.261140361124247988e+00,8.246000000000000796e+01,0.000000000000000000e+00,4.775042488199486179e+00,0.000000000000000000e+00,-1.000000009974151061e+00,0.000000000000000000e+00,-3.230650072248727415e-10,0.000000000000000000e+00 +9.263234583327445648e+00,8.246999999999999886e+01,0.000000000000000000e+00,4.772948265975400339e+00,0.000000000000000000e+00,-1.000000009974827631e+00,0.000000000000000000e+00,1.929909297335986557e-10,0.000000000000000000e+00 +9.265329724410639400e+00,8.248000000000000398e+01,0.000000000000000000e+00,4.770853124871308637e+00,0.000000000000000000e+00,-1.000000009974423287e+00,0.000000000000000000e+00,-3.241587123638246404e-11,0.000000000000000000e+00 +9.267425785584240572e+00,8.248999999999999488e+01,0.000000000000000000e+00,4.768757063676799746e+00,0.000000000000000000e+00,-1.000000009974491233e+00,0.000000000000000000e+00,5.664990763303485153e-11,0.000000000000000000e+00 +9.269522768061325024e+00,8.250000000000000000e+01,0.000000000000000000e+00,4.766660081178799580e+00,0.000000000000000000e+00,-1.000000009974372439e+00,0.000000000000000000e+00,-9.441027498472397480e-11,0.000000000000000000e+00 +9.271620673057631379e+00,8.251000000000000512e+01,0.000000000000000000e+00,4.764562176161567741e+00,0.000000000000000000e+00,-1.000000009974570503e+00,0.000000000000000000e+00,-2.306320810781463328e-11,0.000000000000000000e+00 +9.273719501791577002e+00,8.251999999999999602e+01,0.000000000000000000e+00,4.762463347406686864e+00,0.000000000000000000e+00,-1.000000009974618909e+00,0.000000000000000000e+00,1.346171139282306540e-10,0.000000000000000000e+00 +9.275819255484263337e+00,8.253000000000000114e+01,0.000000000000000000e+00,4.760363593693056394e+00,0.000000000000000000e+00,-1.000000009974336246e+00,0.000000000000000000e+00,-1.515756718663184276e-10,0.000000000000000000e+00 +9.277919935359483006e+00,8.254000000000000625e+01,0.000000000000000000e+00,4.758262913796883709e+00,0.000000000000000000e+00,-1.000000009974654658e+00,0.000000000000000000e+00,2.058152793988094822e-10,0.000000000000000000e+00 +9.280021542643730470e+00,8.254999999999999716e+01,0.000000000000000000e+00,4.756161306491673457e+00,0.000000000000000000e+00,-1.000000009974222115e+00,0.000000000000000000e+00,-3.136557476031202740e-10,0.000000000000000000e+00 +9.282124078566209135e+00,8.256000000000000227e+01,0.000000000000000000e+00,4.754058770548224011e+00,0.000000000000000000e+00,-1.000000009974881587e+00,0.000000000000000000e+00,1.946550559160026188e-10,0.000000000000000000e+00 +9.284227544358838458e+00,8.257000000000000739e+01,0.000000000000000000e+00,4.751955304734612362e+00,0.000000000000000000e+00,-1.000000009974472137e+00,0.000000000000000000e+00,2.637865095653009519e-11,0.000000000000000000e+00 +9.286331941256266376e+00,8.257999999999999829e+01,0.000000000000000000e+00,4.749850907816194123e+00,0.000000000000000000e+00,-1.000000009974416626e+00,0.000000000000000000e+00,-1.044131980596059652e-10,0.000000000000000000e+00 +9.288437270495872866e+00,8.259000000000000341e+01,0.000000000000000000e+00,4.747745578555587542e+00,0.000000000000000000e+00,-1.000000009974636450e+00,0.000000000000000000e+00,1.203909294635981020e-10,0.000000000000000000e+00 +9.290543533317782376e+00,8.260000000000000853e+01,0.000000000000000000e+00,4.745639315712668171e+00,0.000000000000000000e+00,-1.000000009974382875e+00,0.000000000000000000e+00,-1.736569464293342215e-10,0.000000000000000000e+00 +9.292650730964870931e+00,8.260999999999999943e+01,0.000000000000000000e+00,4.743532118044561763e+00,0.000000000000000000e+00,-1.000000009974748805e+00,0.000000000000000000e+00,1.469319622565060312e-10,0.000000000000000000e+00 +9.294758864682773236e+00,8.262000000000000455e+01,0.000000000000000000e+00,4.741423984305631834e+00,0.000000000000000000e+00,-1.000000009974439052e+00,0.000000000000000000e+00,2.410929439213815019e-11,0.000000000000000000e+00 +9.296867935719891562e+00,8.262999999999999545e+01,0.000000000000000000e+00,4.739314913247476113e+00,0.000000000000000000e+00,-1.000000009974388204e+00,0.000000000000000000e+00,-1.926833272082568477e-10,0.000000000000000000e+00 +9.298977945327408179e+00,8.264000000000000057e+01,0.000000000000000000e+00,4.737204903618913221e+00,0.000000000000000000e+00,-1.000000009974794768e+00,0.000000000000000000e+00,5.206760416801264218e-11,0.000000000000000000e+00 +9.301088894759288905e+00,8.265000000000000568e+01,0.000000000000000000e+00,4.735093954165975560e+00,0.000000000000000000e+00,-1.000000009974684856e+00,0.000000000000000000e+00,1.241705840342447835e-10,0.000000000000000000e+00 +9.303200785272295548e+00,8.265999999999999659e+01,0.000000000000000000e+00,4.732982063631903102e+00,0.000000000000000000e+00,-1.000000009974422621e+00,0.000000000000000000e+00,-2.312052891360091723e-12,0.000000000000000000e+00 +9.305313618125993003e+00,8.267000000000000171e+01,0.000000000000000000e+00,4.730869230757131838e+00,0.000000000000000000e+00,-1.000000009974427506e+00,0.000000000000000000e+00,-1.474851440970817562e-10,0.000000000000000000e+00 +9.307427394582756364e+00,8.268000000000000682e+01,0.000000000000000000e+00,4.728755454279284898e+00,0.000000000000000000e+00,-1.000000009974739257e+00,0.000000000000000000e+00,7.454961920090968249e-11,0.000000000000000000e+00 +9.309542115907783355e+00,8.268999999999999773e+01,0.000000000000000000e+00,4.726640732933164557e+00,0.000000000000000000e+00,-1.000000009974581605e+00,0.000000000000000000e+00,6.423093453900234197e-11,0.000000000000000000e+00 +9.311657783369099661e+00,8.270000000000000284e+01,0.000000000000000000e+00,4.724525065450745132e+00,0.000000000000000000e+00,-1.000000009974445714e+00,0.000000000000000000e+00,-1.728843137063857509e-10,0.000000000000000000e+00 +9.313774398237571361e+00,8.271000000000000796e+01,0.000000000000000000e+00,4.722408450561161430e+00,0.000000000000000000e+00,-1.000000009974811643e+00,0.000000000000000000e+00,1.686125192468767455e-10,0.000000000000000000e+00 +9.315891961786910258e+00,8.271999999999999886e+01,0.000000000000000000e+00,4.720290886990699875e+00,0.000000000000000000e+00,-1.000000009974454596e+00,0.000000000000000000e+00,-7.944712648508712239e-11,0.000000000000000000e+00 +9.318010475293686312e+00,8.273000000000000398e+01,0.000000000000000000e+00,4.718172373462793168e+00,0.000000000000000000e+00,-1.000000009974622905e+00,0.000000000000000000e+00,-9.554519852179738487e-11,0.000000000000000000e+00 +9.320129940037332972e+00,8.273999999999999488e+01,0.000000000000000000e+00,4.716052908698006085e+00,0.000000000000000000e+00,-1.000000009974825410e+00,0.000000000000000000e+00,1.561336590431833585e-10,0.000000000000000000e+00 +9.322250357300157830e+00,8.275000000000000000e+01,0.000000000000000000e+00,4.713932491414030146e+00,0.000000000000000000e+00,-1.000000009974494342e+00,0.000000000000000000e+00,-6.929175698369343989e-11,0.000000000000000000e+00 +9.324371728367353285e+00,8.276000000000000512e+01,0.000000000000000000e+00,4.711811120325674729e+00,0.000000000000000000e+00,-1.000000009974641335e+00,0.000000000000000000e+00,-1.256524918671594379e-10,0.000000000000000000e+00 +9.326494054527003641e+00,8.276999999999999602e+01,0.000000000000000000e+00,4.709688794144854640e+00,0.000000000000000000e+00,-1.000000009974908011e+00,0.000000000000000000e+00,2.442897667070371501e-10,0.000000000000000000e+00 +9.328617337070093996e+00,8.278000000000000114e+01,0.000000000000000000e+00,4.707565511580583895e+00,0.000000000000000000e+00,-1.000000009974389314e+00,0.000000000000000000e+00,-7.160233240616653380e-11,0.000000000000000000e+00 +9.330741577290522670e+00,8.279000000000000625e+01,0.000000000000000000e+00,4.705441271338967724e+00,0.000000000000000000e+00,-1.000000009974541415e+00,0.000000000000000000e+00,-2.069784157071040650e-10,0.000000000000000000e+00 +9.332866776485104765e+00,8.279999999999999716e+01,0.000000000000000000e+00,4.703316072123188363e+00,0.000000000000000000e+00,-1.000000009974981285e+00,0.000000000000000000e+00,3.158102180234161674e-10,0.000000000000000000e+00 +9.334992935953584592e+00,8.281000000000000227e+01,0.000000000000000000e+00,4.701189912633499723e+00,0.000000000000000000e+00,-1.000000009974309823e+00,0.000000000000000000e+00,-1.769366187323880257e-10,0.000000000000000000e+00 +9.337120056998648110e+00,8.282000000000000739e+01,0.000000000000000000e+00,4.699062791567220287e+00,0.000000000000000000e+00,-1.000000009974686188e+00,0.000000000000000000e+00,-1.095571618125031071e-11,0.000000000000000000e+00 +9.339248140925924702e+00,8.282999999999999829e+01,0.000000000000000000e+00,4.696934707618716232e+00,0.000000000000000000e+00,-1.000000009974709503e+00,0.000000000000000000e+00,-5.715250983085021700e-11,0.000000000000000000e+00 +9.341377189044004936e+00,8.284000000000000341e+01,0.000000000000000000e+00,4.694805659479399651e+00,0.000000000000000000e+00,-1.000000009974831183e+00,0.000000000000000000e+00,-1.042456267858904236e-13,0.000000000000000000e+00 +9.343507202664442346e+00,8.285000000000000853e+01,0.000000000000000000e+00,4.692675645837715237e+00,0.000000000000000000e+00,-1.000000009974831405e+00,0.000000000000000000e+00,9.211132458820748173e-11,0.000000000000000000e+00 +9.345638183101769414e+00,8.285999999999999943e+01,0.000000000000000000e+00,4.690544665379132283e+00,0.000000000000000000e+00,-1.000000009974635118e+00,0.000000000000000000e+00,-3.572379770278116741e-11,0.000000000000000000e+00 +9.347770131673501126e+00,8.287000000000000455e+01,0.000000000000000000e+00,4.688412716786134915e+00,0.000000000000000000e+00,-1.000000009974711279e+00,0.000000000000000000e+00,1.520954690908858609e-10,0.000000000000000000e+00 +9.349903049700149182e+00,8.287999999999999545e+01,0.000000000000000000e+00,4.686279798738211433e+00,0.000000000000000000e+00,-1.000000009974386872e+00,0.000000000000000000e+00,-1.680509481563554713e-10,0.000000000000000000e+00 +9.352036938505229102e+00,8.289000000000000057e+01,0.000000000000000000e+00,4.684145909911847205e+00,0.000000000000000000e+00,-1.000000009974745474e+00,0.000000000000000000e+00,-5.366860932364298908e-11,0.000000000000000000e+00 +9.354171799415270883e+00,8.290000000000000568e+01,0.000000000000000000e+00,4.682011048980511347e+00,0.000000000000000000e+00,-1.000000009974860049e+00,0.000000000000000000e+00,7.963453149171398560e-11,0.000000000000000000e+00 +9.356307633759826103e+00,8.290999999999999659e+01,0.000000000000000000e+00,4.679875214614651391e+00,0.000000000000000000e+00,-1.000000009974689963e+00,0.000000000000000000e+00,2.099064907117663620e-11,0.000000000000000000e+00 +9.358444442871482138e+00,8.292000000000000171e+01,0.000000000000000000e+00,4.677738405481681738e+00,0.000000000000000000e+00,-1.000000009974645110e+00,0.000000000000000000e+00,-4.206599633560694809e-11,0.000000000000000000e+00 +9.360582228085867484e+00,8.293000000000000682e+01,0.000000000000000000e+00,4.675600620245973005e+00,0.000000000000000000e+00,-1.000000009974735038e+00,0.000000000000000000e+00,8.606610788905814401e-11,0.000000000000000000e+00 +9.362720990741664195e+00,8.293999999999999773e+01,0.000000000000000000e+00,4.673461857568843136e+00,0.000000000000000000e+00,-1.000000009974550963e+00,0.000000000000000000e+00,-1.670724356791683401e-10,0.000000000000000000e+00 +9.364860732180614988e+00,8.295000000000000284e+01,0.000000000000000000e+00,4.671322116108548528e+00,0.000000000000000000e+00,-1.000000009974908455e+00,0.000000000000000000e+00,-6.119727055118415643e-12,0.000000000000000000e+00 +9.367001453747539230e+00,8.296000000000000796e+01,0.000000000000000000e+00,4.669181394520271589e+00,0.000000000000000000e+00,-1.000000009974921555e+00,0.000000000000000000e+00,2.080790441905607879e-10,0.000000000000000000e+00 +9.369143156790332938e+00,8.296999999999999886e+01,0.000000000000000000e+00,4.667039691456114525e+00,0.000000000000000000e+00,-1.000000009974475912e+00,0.000000000000000000e+00,-6.818794677738989990e-11,0.000000000000000000e+00 +9.371285842659988319e+00,8.298000000000000398e+01,0.000000000000000000e+00,4.664897005565087795e+00,0.000000000000000000e+00,-1.000000009974622017e+00,0.000000000000000000e+00,-2.076809501296406500e-10,0.000000000000000000e+00 +9.373429512710595546e+00,8.298999999999999488e+01,0.000000000000000000e+00,4.662753335493097673e+00,0.000000000000000000e+00,-1.000000009975067217e+00,0.000000000000000000e+00,2.294311716489240051e-10,0.000000000000000000e+00 +9.375574168299360522e+00,8.300000000000000000e+01,0.000000000000000000e+00,4.660608679882939143e+00,0.000000000000000000e+00,-1.000000009974575166e+00,0.000000000000000000e+00,-4.543048627222679510e-11,0.000000000000000000e+00 +9.377719810786610211e+00,8.301000000000000512e+01,0.000000000000000000e+00,4.658463037374287907e+00,0.000000000000000000e+00,-1.000000009974672643e+00,0.000000000000000000e+00,-1.862930239029634921e-10,0.000000000000000000e+00 +9.379866441535801513e+00,8.301999999999999602e+01,0.000000000000000000e+00,4.656316406603684399e+00,0.000000000000000000e+00,-1.000000009975072546e+00,0.000000000000000000e+00,2.726420503632346354e-10,0.000000000000000000e+00 +9.382014061913535485e+00,8.303000000000000114e+01,0.000000000000000000e+00,4.654168786204527564e+00,0.000000000000000000e+00,-1.000000009974487014e+00,0.000000000000000000e+00,-1.185347730587114825e-10,0.000000000000000000e+00 +9.384162673289564438e+00,8.304000000000000625e+01,0.000000000000000000e+00,4.652020174807066866e+00,0.000000000000000000e+00,-1.000000009974741699e+00,0.000000000000000000e+00,-1.043285541636493305e-10,0.000000000000000000e+00 +9.386312277036804375e+00,8.304999999999999716e+01,0.000000000000000000e+00,4.649870571038385414e+00,0.000000000000000000e+00,-1.000000009974965964e+00,0.000000000000000000e+00,3.840820666903342273e-11,0.000000000000000000e+00 +9.388462874531342095e+00,8.306000000000000227e+01,0.000000000000000000e+00,4.647719973522395520e+00,0.000000000000000000e+00,-1.000000009974883364e+00,0.000000000000000000e+00,4.386004867622568208e-11,0.000000000000000000e+00 +9.390614467152449407e+00,8.307000000000000739e+01,0.000000000000000000e+00,4.645568380879827153e+00,0.000000000000000000e+00,-1.000000009974788995e+00,0.000000000000000000e+00,3.961049839813166030e-11,0.000000000000000000e+00 +9.392767056282588456e+00,8.307999999999999829e+01,0.000000000000000000e+00,4.643415791728216391e+00,0.000000000000000000e+00,-1.000000009974703730e+00,0.000000000000000000e+00,-2.979721278183366297e-11,0.000000000000000000e+00 +9.394920643307427710e+00,8.309000000000000341e+01,0.000000000000000000e+00,4.641262204681895653e+00,0.000000000000000000e+00,-1.000000009974767901e+00,0.000000000000000000e+00,-1.834409674013886599e-11,0.000000000000000000e+00 +9.397075229615849068e+00,8.310000000000000853e+01,0.000000000000000000e+00,4.639107618351983042e+00,0.000000000000000000e+00,-1.000000009974807424e+00,0.000000000000000000e+00,3.739222410507658264e-11,0.000000000000000000e+00 +9.399230816599958516e+00,8.310999999999999943e+01,0.000000000000000000e+00,4.636952031346372571e+00,0.000000000000000000e+00,-1.000000009974726822e+00,0.000000000000000000e+00,-8.061847723937387633e-11,0.000000000000000000e+00 +9.401387405655096785e+00,8.312000000000000455e+01,0.000000000000000000e+00,4.634795442269723509e+00,0.000000000000000000e+00,-1.000000009974900683e+00,0.000000000000000000e+00,-7.306832392498527276e-12,0.000000000000000000e+00 +9.403544998179850012e+00,8.312999999999999545e+01,0.000000000000000000e+00,4.632637849723448831e+00,0.000000000000000000e+00,-1.000000009974916448e+00,0.000000000000000000e+00,5.770739072585528431e-11,0.000000000000000000e+00 +9.405703595576060394e+00,8.314000000000000057e+01,0.000000000000000000e+00,4.630479252305706339e+00,0.000000000000000000e+00,-1.000000009974791881e+00,0.000000000000000000e+00,-7.341154764409273005e-11,0.000000000000000000e+00 +9.407863199248838626e+00,8.315000000000000568e+01,0.000000000000000000e+00,4.628319648611387116e+00,0.000000000000000000e+00,-1.000000009974950421e+00,0.000000000000000000e+00,1.814906558250164318e-10,0.000000000000000000e+00 +9.410023810606569228e+00,8.315999999999999659e+01,0.000000000000000000e+00,4.626159037232103977e+00,0.000000000000000000e+00,-1.000000009974558290e+00,0.000000000000000000e+00,-1.080628765841178989e-10,0.000000000000000000e+00 +9.412185431060928309e+00,8.317000000000000171e+01,0.000000000000000000e+00,4.623997416756183476e+00,0.000000000000000000e+00,-1.000000009974791881e+00,0.000000000000000000e+00,-1.496977704824712412e-10,0.000000000000000000e+00 +9.414348062026888897e+00,8.318000000000000682e+01,0.000000000000000000e+00,4.621834785768650811e+00,0.000000000000000000e+00,-1.000000009975115622e+00,0.000000000000000000e+00,9.564682424604026157e-11,0.000000000000000000e+00 +9.416511704922735149e+00,8.318999999999999773e+01,0.000000000000000000e+00,4.619671142851222712e+00,0.000000000000000000e+00,-1.000000009974908677e+00,0.000000000000000000e+00,1.087319437025845547e-10,0.000000000000000000e+00 +9.418676361170069455e+00,8.320000000000000284e+01,0.000000000000000000e+00,4.617506486582296787e+00,0.000000000000000000e+00,-1.000000009974673310e+00,0.000000000000000000e+00,-4.982921081262405644e-11,0.000000000000000000e+00 +9.420842032193826654e+00,8.321000000000000796e+01,0.000000000000000000e+00,4.615340815536938202e+00,0.000000000000000000e+00,-1.000000009974781223e+00,0.000000000000000000e+00,-1.206203168432779294e-10,0.000000000000000000e+00 +9.423008719422282908e+00,8.321999999999999886e+01,0.000000000000000000e+00,4.613174128286869013e+00,0.000000000000000000e+00,-1.000000009975042570e+00,0.000000000000000000e+00,1.645074665385928647e-10,0.000000000000000000e+00 +9.425176424287069921e+00,8.323000000000000398e+01,0.000000000000000000e+00,4.611006423400458409e+00,0.000000000000000000e+00,-1.000000009974685966e+00,0.000000000000000000e+00,-5.078291533970052459e-11,0.000000000000000000e+00 +9.427345148223183813e+00,8.323999999999999488e+01,0.000000000000000000e+00,4.608837699442712932e+00,0.000000000000000000e+00,-1.000000009974796100e+00,0.000000000000000000e+00,-9.906197846599842414e-11,0.000000000000000000e+00 +9.429514892668992232e+00,8.325000000000000000e+01,0.000000000000000000e+00,4.606667954975261381e+00,0.000000000000000000e+00,-1.000000009975011039e+00,0.000000000000000000e+00,-6.055483735213040627e-11,0.000000000000000000e+00 +9.431685659066253891e+00,8.326000000000000512e+01,0.000000000000000000e+00,4.604497188556346821e+00,0.000000000000000000e+00,-1.000000009975142490e+00,0.000000000000000000e+00,1.831125132568537697e-10,0.000000000000000000e+00 +9.433857448860122119e+00,8.326999999999999602e+01,0.000000000000000000e+00,4.602325398740815032e+00,0.000000000000000000e+00,-1.000000009974744808e+00,0.000000000000000000e+00,8.379756504178699390e-12,0.000000000000000000e+00 +9.436030263499160853e+00,8.328000000000000114e+01,0.000000000000000000e+00,4.600152584080103857e+00,0.000000000000000000e+00,-1.000000009974726600e+00,0.000000000000000000e+00,-6.833427332319151388e-11,0.000000000000000000e+00 +9.438204104435351738e+00,8.329000000000000625e+01,0.000000000000000000e+00,4.597978743122228984e+00,0.000000000000000000e+00,-1.000000009974875148e+00,0.000000000000000000e+00,-8.647500483293164359e-11,0.000000000000000000e+00 +9.440378973124111894e+00,8.329999999999999716e+01,0.000000000000000000e+00,4.595803874411775070e+00,0.000000000000000000e+00,-1.000000009975063220e+00,0.000000000000000000e+00,1.132725535723426743e-10,0.000000000000000000e+00 +9.442554871024297469e+00,8.331000000000000227e+01,0.000000000000000000e+00,4.593627976489884190e+00,0.000000000000000000e+00,-1.000000009974816750e+00,0.000000000000000000e+00,-5.018352321324354899e-11,0.000000000000000000e+00 +9.444731799598221400e+00,8.332000000000000739e+01,0.000000000000000000e+00,4.591451047894245185e+00,0.000000000000000000e+00,-1.000000009974925996e+00,0.000000000000000000e+00,-2.161354700000073268e-11,0.000000000000000000e+00 +9.446909760311662296e+00,8.332999999999999829e+01,0.000000000000000000e+00,4.589273087159079445e+00,0.000000000000000000e+00,-1.000000009974973070e+00,0.000000000000000000e+00,1.385871728162590551e-11,0.000000000000000000e+00 +9.449088754633875098e+00,8.334000000000000341e+01,0.000000000000000000e+00,4.587094092815132029e+00,0.000000000000000000e+00,-1.000000009974942872e+00,0.000000000000000000e+00,6.915883175077019185e-11,0.000000000000000000e+00 +9.451268784037601733e+00,8.335000000000000853e+01,0.000000000000000000e+00,4.584914063389659233e+00,0.000000000000000000e+00,-1.000000009974792103e+00,0.000000000000000000e+00,-2.055453916845744543e-10,0.000000000000000000e+00 +9.453449849999088883e+00,8.335999999999999943e+01,0.000000000000000000e+00,4.582732997406417041e+00,0.000000000000000000e+00,-1.000000009975240411e+00,0.000000000000000000e+00,1.572147408033889225e-10,0.000000000000000000e+00 +9.455631953998091532e+00,8.337000000000000455e+01,0.000000000000000000e+00,4.580550893385647804e+00,0.000000000000000000e+00,-1.000000009974897353e+00,0.000000000000000000e+00,8.177376372224955948e-11,0.000000000000000000e+00 +9.457815097517888958e+00,8.337999999999999545e+01,0.000000000000000000e+00,4.578367749844073131e+00,0.000000000000000000e+00,-1.000000009974718829e+00,0.000000000000000000e+00,-1.893929261855722066e-10,0.000000000000000000e+00 +9.459999282045298941e+00,8.339000000000000057e+01,0.000000000000000000e+00,4.576183565294877020e+00,0.000000000000000000e+00,-1.000000009975132498e+00,0.000000000000000000e+00,1.541449294551428639e-10,0.000000000000000000e+00 +9.462184509070683092e+00,8.340000000000000568e+01,0.000000000000000000e+00,4.573998338247695195e+00,0.000000000000000000e+00,-1.000000009974795656e+00,0.000000000000000000e+00,-1.142585610686954156e-10,0.000000000000000000e+00 +9.464370780087962842e+00,8.340999999999999659e+01,0.000000000000000000e+00,4.571812067208607111e+00,0.000000000000000000e+00,-1.000000009975045456e+00,0.000000000000000000e+00,2.202867263232971767e-11,0.000000000000000000e+00 +9.466558096594633653e+00,8.342000000000000171e+01,0.000000000000000000e+00,4.569624750680118197e+00,0.000000000000000000e+00,-1.000000009974997273e+00,0.000000000000000000e+00,1.032924411823978809e-10,0.000000000000000000e+00 +9.468746460091770345e+00,8.343000000000000682e+01,0.000000000000000000e+00,4.567436387161152744e+00,0.000000000000000000e+00,-1.000000009974771231e+00,0.000000000000000000e+00,-1.327554562012600252e-10,0.000000000000000000e+00 +9.470935872084044860e+00,8.343999999999999773e+01,0.000000000000000000e+00,4.565246975147039699e+00,0.000000000000000000e+00,-1.000000009975061888e+00,0.000000000000000000e+00,-1.104920422470073210e-11,0.000000000000000000e+00 +9.473126334079735145e+00,8.345000000000000284e+01,0.000000000000000000e+00,4.563056513129499336e+00,0.000000000000000000e+00,-1.000000009975086090e+00,0.000000000000000000e+00,4.245316718168324102e-11,0.000000000000000000e+00 +9.475317847590739362e+00,8.346000000000000796e+01,0.000000000000000000e+00,4.560864999596634384e+00,0.000000000000000000e+00,-1.000000009974993054e+00,0.000000000000000000e+00,-1.610217592453421939e-11,0.000000000000000000e+00 +9.477510414132586547e+00,8.346999999999999886e+01,0.000000000000000000e+00,4.558672433032915805e+00,0.000000000000000000e+00,-1.000000009975028359e+00,0.000000000000000000e+00,-3.512433309232724814e-11,0.000000000000000000e+00 +9.479704035224450820e+00,8.348000000000000398e+01,0.000000000000000000e+00,4.556478811919170369e+00,0.000000000000000000e+00,-1.000000009975105408e+00,0.000000000000000000e+00,1.476130903419485891e-10,0.000000000000000000e+00 +9.481898712389160266e+00,8.348999999999999488e+01,0.000000000000000000e+00,4.554284134732569100e+00,0.000000000000000000e+00,-1.000000009974781445e+00,0.000000000000000000e+00,-2.159027762716821977e-10,0.000000000000000000e+00 +9.484094447153211149e+00,8.350000000000000000e+01,0.000000000000000000e+00,4.552088399946615738e+00,0.000000000000000000e+00,-1.000000009975255510e+00,0.000000000000000000e+00,1.640474305977991840e-10,0.000000000000000000e+00 +9.486291241046782119e+00,8.351000000000000512e+01,0.000000000000000000e+00,4.549891606031130742e+00,0.000000000000000000e+00,-1.000000009974895132e+00,0.000000000000000000e+00,9.597649399072536320e-12,0.000000000000000000e+00 +9.488489095603744872e+00,8.351999999999999602e+01,0.000000000000000000e+00,4.547693751452245081e+00,0.000000000000000000e+00,-1.000000009974874038e+00,0.000000000000000000e+00,-1.035035633920278401e-10,0.000000000000000000e+00 +9.490688012361674808e+00,8.353000000000000114e+01,0.000000000000000000e+00,4.545494834672381579e+00,0.000000000000000000e+00,-1.000000009975101634e+00,0.000000000000000000e+00,4.188605809727438118e-11,0.000000000000000000e+00 +9.492887992861867019e+00,8.354000000000000625e+01,0.000000000000000000e+00,4.543294854150245143e+00,0.000000000000000000e+00,-1.000000009975009485e+00,0.000000000000000000e+00,-6.002443960138926965e-11,0.000000000000000000e+00 +9.495089038649345170e+00,8.354999999999999716e+01,0.000000000000000000e+00,4.541093808340811222e+00,0.000000000000000000e+00,-1.000000009975141602e+00,0.000000000000000000e+00,1.472155055676790163e-11,0.000000000000000000e+00 +9.497291151272879262e+00,8.356000000000000227e+01,0.000000000000000000e+00,4.538891695695310702e+00,0.000000000000000000e+00,-1.000000009975109183e+00,0.000000000000000000e+00,1.503691928745310599e-10,0.000000000000000000e+00 +9.499494332284994513e+00,8.357000000000000739e+01,0.000000000000000000e+00,4.536688514661219251e+00,0.000000000000000000e+00,-1.000000009974777893e+00,0.000000000000000000e+00,-1.220904817193923629e-10,0.000000000000000000e+00 +9.501698583241982021e+00,8.357999999999999829e+01,0.000000000000000000e+00,4.534484263682243999e+00,0.000000000000000000e+00,-1.000000009975047011e+00,0.000000000000000000e+00,1.973441223061466874e-11,0.000000000000000000e+00 +9.503903905703920074e+00,8.359000000000000341e+01,0.000000000000000000e+00,4.532278941198308431e+00,0.000000000000000000e+00,-1.000000009975003490e+00,0.000000000000000000e+00,-5.263305094531024330e-11,0.000000000000000000e+00 +9.506110301234675930e+00,8.360000000000000853e+01,0.000000000000000000e+00,4.530072545645543514e+00,0.000000000000000000e+00,-1.000000009975119619e+00,0.000000000000000000e+00,-4.244805871827892735e-11,0.000000000000000000e+00 +9.508317771401927132e+00,8.360999999999999943e+01,0.000000000000000000e+00,4.527865075456271704e+00,0.000000000000000000e+00,-1.000000009975213322e+00,0.000000000000000000e+00,1.751385916614017753e-10,0.000000000000000000e+00 +9.510526317777172167e+00,8.362000000000000455e+01,0.000000000000000000e+00,4.525656529058995403e+00,0.000000000000000000e+00,-1.000000009974826520e+00,0.000000000000000000e+00,-1.723399411476517727e-10,0.000000000000000000e+00 +9.512735941935742900e+00,8.362999999999999545e+01,0.000000000000000000e+00,4.523446904878384522e+00,0.000000000000000000e+00,-1.000000009975207327e+00,0.000000000000000000e+00,-2.601414080513068319e-11,0.000000000000000000e+00 +9.514946645456815233e+00,8.364000000000000057e+01,0.000000000000000000e+00,4.521236201335259608e+00,0.000000000000000000e+00,-1.000000009975264836e+00,0.000000000000000000e+00,2.283909141373489432e-10,0.000000000000000000e+00 +9.517158429923428642e+00,8.365000000000000568e+01,0.000000000000000000e+00,4.519024416846583847e+00,0.000000000000000000e+00,-1.000000009974759685e+00,0.000000000000000000e+00,-1.444931987450788343e-10,0.000000000000000000e+00 +9.519371296922491510e+00,8.365999999999999659e+01,0.000000000000000000e+00,4.516811549825447969e+00,0.000000000000000000e+00,-1.000000009975079429e+00,0.000000000000000000e+00,-5.195196235007375725e-11,0.000000000000000000e+00 +9.521585248044802441e+00,8.367000000000000171e+01,0.000000000000000000e+00,4.514597598681053370e+00,0.000000000000000000e+00,-1.000000009975194448e+00,0.000000000000000000e+00,-2.435934157672949813e-11,0.000000000000000000e+00 +9.523800284885055589e+00,8.368000000000000682e+01,0.000000000000000000e+00,4.512382561818704119e+00,0.000000000000000000e+00,-1.000000009975248405e+00,0.000000000000000000e+00,1.463849246889276500e-10,0.000000000000000000e+00 +9.526016409041861976e+00,8.368999999999999773e+01,0.000000000000000000e+00,4.510166437639790971e+00,0.000000000000000000e+00,-1.000000009974923998e+00,0.000000000000000000e+00,-4.346328261596686627e-11,0.000000000000000000e+00 +9.528233622117756596e+00,8.370000000000000284e+01,0.000000000000000000e+00,4.507949224541778932e+00,0.000000000000000000e+00,-1.000000009975020365e+00,0.000000000000000000e+00,-1.802739414058450347e-10,0.000000000000000000e+00 +9.530451925719216177e+00,8.371000000000000796e+01,0.000000000000000000e+00,4.505730920918191273e+00,0.000000000000000000e+00,-1.000000009975420268e+00,0.000000000000000000e+00,1.589751981909472097e-10,0.000000000000000000e+00 +9.532671321456669844e+00,8.371999999999999886e+01,0.000000000000000000e+00,4.503511525158597983e+00,0.000000000000000000e+00,-1.000000009975067439e+00,0.000000000000000000e+00,-3.199937399613331826e-11,0.000000000000000000e+00 +9.534891810944513324e+00,8.373000000000000398e+01,0.000000000000000000e+00,4.501291035648604222e+00,0.000000000000000000e+00,-1.000000009975138493e+00,0.000000000000000000e+00,5.537160138734013528e-11,0.000000000000000000e+00 +9.537113395801124938e+00,8.373999999999999488e+01,0.000000000000000000e+00,4.499069450769831668e+00,0.000000000000000000e+00,-1.000000009975015480e+00,0.000000000000000000e+00,-1.868118964618489164e-11,0.000000000000000000e+00 +9.539336077648876255e+00,8.375000000000000000e+01,0.000000000000000000e+00,4.496846768899908753e+00,0.000000000000000000e+00,-1.000000009975057003e+00,0.000000000000000000e+00,-1.413876798919637957e-10,0.000000000000000000e+00 +9.541559858114148085e+00,8.376000000000000512e+01,0.000000000000000000e+00,4.494622988412454667e+00,0.000000000000000000e+00,-1.000000009975371418e+00,0.000000000000000000e+00,1.705593596845052970e-10,0.000000000000000000e+00 +9.543784738827342906e+00,8.376999999999999602e+01,0.000000000000000000e+00,4.492398107677066044e+00,0.000000000000000000e+00,-1.000000009974991944e+00,0.000000000000000000e+00,-2.254378844346353633e-11,0.000000000000000000e+00 +9.546010721422899081e+00,8.378000000000000114e+01,0.000000000000000000e+00,4.490172125059305408e+00,0.000000000000000000e+00,-1.000000009975042126e+00,0.000000000000000000e+00,-3.170518815862297890e-11,0.000000000000000000e+00 +9.548237807539306843e+00,8.379000000000000625e+01,0.000000000000000000e+00,4.487945038920682528e+00,0.000000000000000000e+00,-1.000000009975112736e+00,0.000000000000000000e+00,-5.401159988360792229e-11,0.000000000000000000e+00 +9.550465998819118951e+00,8.379999999999999716e+01,0.000000000000000000e+00,4.485716847618643754e+00,0.000000000000000000e+00,-1.000000009975233084e+00,0.000000000000000000e+00,8.565851337021332251e-11,0.000000000000000000e+00 +9.552695296908968459e+00,8.381000000000000227e+01,0.000000000000000000e+00,4.483487549506556924e+00,0.000000000000000000e+00,-1.000000009975042126e+00,0.000000000000000000e+00,-1.400716649814387769e-10,0.000000000000000000e+00 +9.554925703459579367e+00,8.382000000000000739e+01,0.000000000000000000e+00,4.481257142933698034e+00,0.000000000000000000e+00,-1.000000009975354542e+00,0.000000000000000000e+00,4.577179270602862633e-12,0.000000000000000000e+00 +9.557157220125782615e+00,8.382999999999999829e+01,0.000000000000000000e+00,4.479025626245234371e+00,0.000000000000000000e+00,-1.000000009975344328e+00,0.000000000000000000e+00,1.967206994793596338e-10,0.000000000000000000e+00 +9.559389848566532066e+00,8.384000000000000341e+01,0.000000000000000000e+00,4.476792997782213845e+00,0.000000000000000000e+00,-1.000000009974905124e+00,0.000000000000000000e+00,-2.287303832537029529e-10,0.000000000000000000e+00 +9.561623590444915166e+00,8.385000000000000853e+01,0.000000000000000000e+00,4.474559255881549014e+00,0.000000000000000000e+00,-1.000000009975416049e+00,0.000000000000000000e+00,2.133155590473042831e-10,0.000000000000000000e+00 +9.563858447428170706e+00,8.385999999999999943e+01,0.000000000000000000e+00,4.472324398875999307e+00,0.000000000000000000e+00,-1.000000009974939319e+00,0.000000000000000000e+00,-1.834173516340513628e-10,0.000000000000000000e+00 +9.566094421187703034e+00,8.387000000000000455e+01,0.000000000000000000e+00,4.470088425094163931e+00,0.000000000000000000e+00,-1.000000009975349435e+00,0.000000000000000000e+00,9.012435886436299173e-11,0.000000000000000000e+00 +9.568331513399092714e+00,8.387999999999999545e+01,0.000000000000000000e+00,4.467851332860458768e+00,0.000000000000000000e+00,-1.000000009975147819e+00,0.000000000000000000e+00,6.706341040304919769e-11,0.000000000000000000e+00 +9.570569725742116063e+00,8.389000000000000057e+01,0.000000000000000000e+00,4.465613120495109278e+00,0.000000000000000000e+00,-1.000000009974997717e+00,0.000000000000000000e+00,-1.388191421523721756e-10,0.000000000000000000e+00 +9.572809059900757589e+00,8.390000000000000568e+01,0.000000000000000000e+00,4.463373786314130953e+00,0.000000000000000000e+00,-1.000000009975308579e+00,0.000000000000000000e+00,-4.737305369891041784e-11,0.000000000000000000e+00 +9.575049517563224200e+00,8.390999999999999659e+01,0.000000000000000000e+00,4.461133328629315109e+00,0.000000000000000000e+00,-1.000000009975414716e+00,0.000000000000000000e+00,1.256043504916253637e-10,0.000000000000000000e+00 +9.577291100421962966e+00,8.392000000000000171e+01,0.000000000000000000e+00,4.458891745748216451e+00,0.000000000000000000e+00,-1.000000009975133164e+00,0.000000000000000000e+00,2.673196711437993878e-12,0.000000000000000000e+00 +9.579533810173671782e+00,8.393000000000000682e+01,0.000000000000000000e+00,4.456649035974137085e+00,0.000000000000000000e+00,-1.000000009975127169e+00,0.000000000000000000e+00,-7.342645568659400465e-11,0.000000000000000000e+00 +9.581777648519317125e+00,8.393999999999999773e+01,0.000000000000000000e+00,4.454405197606109645e+00,0.000000000000000000e+00,-1.000000009975291926e+00,0.000000000000000000e+00,7.615890145544100926e-11,0.000000000000000000e+00 +9.584022617164148272e+00,8.395000000000000284e+01,0.000000000000000000e+00,4.452160228938883968e+00,0.000000000000000000e+00,-1.000000009975120951e+00,0.000000000000000000e+00,-6.129184586405562748e-11,0.000000000000000000e+00 +9.586268717817715057e+00,8.396000000000000796e+01,0.000000000000000000e+00,4.449914128262912882e+00,0.000000000000000000e+00,-1.000000009975258619e+00,0.000000000000000000e+00,-1.029578760391992629e-10,0.000000000000000000e+00 +9.588515952193876757e+00,8.396999999999999886e+01,0.000000000000000000e+00,4.447666893864334448e+00,0.000000000000000000e+00,-1.000000009975489990e+00,0.000000000000000000e+00,1.699625934290631506e-10,0.000000000000000000e+00 +9.590764322010823406e+00,8.398000000000000398e+01,0.000000000000000000e+00,4.445418524024958629e+00,0.000000000000000000e+00,-1.000000009975107851e+00,0.000000000000000000e+00,-6.356802927314382658e-11,0.000000000000000000e+00 +9.593013828991090008e+00,8.398999999999999488e+01,0.000000000000000000e+00,4.443169017022253087e+00,0.000000000000000000e+00,-1.000000009975250848e+00,0.000000000000000000e+00,-2.920281858639544302e-11,0.000000000000000000e+00 +9.595264474861568971e+00,8.400000000000000000e+01,0.000000000000000000e+00,4.440918371129323639e+00,0.000000000000000000e+00,-1.000000009975316573e+00,0.000000000000000000e+00,6.508140970463379560e-12,0.000000000000000000e+00 +9.597516261353527867e+00,8.401000000000000512e+01,0.000000000000000000e+00,4.438666584614902710e+00,0.000000000000000000e+00,-1.000000009975301918e+00,0.000000000000000000e+00,1.427122689917043886e-10,0.000000000000000000e+00 +9.599769190202623648e+00,8.401999999999999602e+01,0.000000000000000000e+00,4.436413655743332463e+00,0.000000000000000000e+00,-1.000000009974980397e+00,0.000000000000000000e+00,-2.072611933564332381e-10,0.000000000000000000e+00 +9.602023263148922183e+00,8.403000000000000114e+01,0.000000000000000000e+00,4.434159582774549690e+00,0.000000000000000000e+00,-1.000000009975447579e+00,0.000000000000000000e+00,1.326230893549622223e-10,0.000000000000000000e+00 +9.604278481936907141e+00,8.404000000000000625e+01,0.000000000000000000e+00,4.431904363964067173e+00,0.000000000000000000e+00,-1.000000009975148485e+00,0.000000000000000000e+00,-9.437331549658844606e-11,0.000000000000000000e+00 +9.606534848315503083e+00,8.404999999999999716e+01,0.000000000000000000e+00,4.429647997562963901e+00,0.000000000000000000e+00,-1.000000009975361426e+00,0.000000000000000000e+00,-3.432692244119626980e-11,0.000000000000000000e+00 +9.608792364038084344e+00,8.406000000000000227e+01,0.000000000000000000e+00,4.427390481817862877e+00,0.000000000000000000e+00,-1.000000009975438919e+00,0.000000000000000000e+00,1.324206295507370986e-10,0.000000000000000000e+00 +9.611051030862496347e+00,8.407000000000000739e+01,0.000000000000000000e+00,4.425131814970919564e+00,0.000000000000000000e+00,-1.000000009975139825e+00,0.000000000000000000e+00,-1.063147930535309676e-10,0.000000000000000000e+00 +9.613310850551068043e+00,8.407999999999999829e+01,0.000000000000000000e+00,4.422871995259805011e+00,0.000000000000000000e+00,-1.000000009975380078e+00,0.000000000000000000e+00,1.428918928315207166e-10,0.000000000000000000e+00 +9.615571824870631445e+00,8.409000000000000341e+01,0.000000000000000000e+00,4.420611020917687206e+00,0.000000000000000000e+00,-1.000000009975057003e+00,0.000000000000000000e+00,-1.244634345481638104e-10,0.000000000000000000e+00 +9.617833955592534068e+00,8.410000000000000853e+01,0.000000000000000000e+00,4.418348890173219523e+00,0.000000000000000000e+00,-1.000000009975338555e+00,0.000000000000000000e+00,1.324445220548275084e-11,0.000000000000000000e+00 +9.620097244492656685e+00,8.410999999999999943e+01,0.000000000000000000e+00,4.416085601250519410e+00,0.000000000000000000e+00,-1.000000009975308579e+00,0.000000000000000000e+00,-7.069895154868943194e-11,0.000000000000000000e+00 +9.622361693351431100e+00,8.412000000000000455e+01,0.000000000000000000e+00,4.413821152369156842e+00,0.000000000000000000e+00,-1.000000009975468673e+00,0.000000000000000000e+00,5.194345422134045925e-11,0.000000000000000000e+00 +9.624627303953852575e+00,8.412999999999999545e+01,0.000000000000000000e+00,4.411555541744134779e+00,0.000000000000000000e+00,-1.000000009975350990e+00,0.000000000000000000e+00,1.321429282844030532e-10,0.000000000000000000e+00 +9.626894078089501150e+00,8.414000000000000057e+01,0.000000000000000000e+00,4.409288767585874957e+00,0.000000000000000000e+00,-1.000000009975051452e+00,0.000000000000000000e+00,-2.367364135840742649e-10,0.000000000000000000e+00 +9.629162017552552300e+00,8.415000000000000568e+01,0.000000000000000000e+00,4.407020828100200127e+00,0.000000000000000000e+00,-1.000000009975588355e+00,0.000000000000000000e+00,1.081303494532442012e-10,0.000000000000000000e+00 +9.631431124141801803e+00,8.415999999999999659e+01,0.000000000000000000e+00,4.404751721488315397e+00,0.000000000000000000e+00,-1.000000009975342996e+00,0.000000000000000000e+00,9.897879720602131332e-11,0.000000000000000000e+00 +9.633701399660672848e+00,8.417000000000000171e+01,0.000000000000000000e+00,4.402481445946797578e+00,0.000000000000000000e+00,-1.000000009975118287e+00,0.000000000000000000e+00,-1.065526506156990559e-10,0.000000000000000000e+00 +9.635972845917239127e+00,8.418000000000000682e+01,0.000000000000000000e+00,4.400209999667572980e+00,0.000000000000000000e+00,-1.000000009975360316e+00,0.000000000000000000e+00,6.546187369454500897e-12,0.000000000000000000e+00 +9.638245464724240819e+00,8.418999999999999773e+01,0.000000000000000000e+00,4.397937380837901422e+00,0.000000000000000000e+00,-1.000000009975345439e+00,0.000000000000000000e+00,-6.367029508749924978e-11,0.000000000000000000e+00 +9.640519257899098804e+00,8.420000000000000284e+01,0.000000000000000000e+00,4.395663587640362024e+00,0.000000000000000000e+00,-1.000000009975490212e+00,0.000000000000000000e+00,5.631712629724481431e-11,0.000000000000000000e+00 +9.642794227263932427e+00,8.421000000000000796e+01,0.000000000000000000e+00,4.393388618252833666e+00,0.000000000000000000e+00,-1.000000009975362092e+00,0.000000000000000000e+00,6.692123726551465948e-11,0.000000000000000000e+00 +9.645070374645580813e+00,8.421999999999999886e+01,0.000000000000000000e+00,4.391112470848479887e+00,0.000000000000000000e+00,-1.000000009975209769e+00,0.000000000000000000e+00,-1.417683200302930390e-10,0.000000000000000000e+00 +9.647347701875613524e+00,8.423000000000000398e+01,0.000000000000000000e+00,4.388835143595730237e+00,0.000000000000000000e+00,-1.000000009975532622e+00,0.000000000000000000e+00,1.910053644459981770e-11,0.000000000000000000e+00 +9.649626210790351877e+00,8.423999999999999488e+01,0.000000000000000000e+00,4.386556634658262510e+00,0.000000000000000000e+00,-1.000000009975489101e+00,0.000000000000000000e+00,1.267188616636083458e-10,0.000000000000000000e+00 +9.651905903230884931e+00,8.425000000000000000e+01,0.000000000000000000e+00,4.384276942194988536e+00,0.000000000000000000e+00,-1.000000009975200221e+00,0.000000000000000000e+00,-5.383482879559206321e-11,0.000000000000000000e+00 +9.654186781043087251e+00,8.426000000000000512e+01,0.000000000000000000e+00,4.381996064360034637e+00,0.000000000000000000e+00,-1.000000009975323012e+00,0.000000000000000000e+00,-5.818531537665318756e-11,0.000000000000000000e+00 +9.656468846077634893e+00,8.426999999999999602e+01,0.000000000000000000e+00,4.379713999302722982e+00,0.000000000000000000e+00,-1.000000009975455795e+00,0.000000000000000000e+00,8.003608046150169423e-11,0.000000000000000000e+00 +9.658752100190024947e+00,8.428000000000000114e+01,0.000000000000000000e+00,4.377430745167556481e+00,0.000000000000000000e+00,-1.000000009975273052e+00,0.000000000000000000e+00,-1.666954069881567591e-10,0.000000000000000000e+00 +9.661036545240593298e+00,8.429000000000000625e+01,0.000000000000000000e+00,4.375146300094201024e+00,0.000000000000000000e+00,-1.000000009975653859e+00,0.000000000000000000e+00,2.216911955524862199e-10,0.000000000000000000e+00 +9.663322183094528839e+00,8.429999999999999716e+01,0.000000000000000000e+00,4.372860662217465055e+00,0.000000000000000000e+00,-1.000000009975147153e+00,0.000000000000000000e+00,-1.003012132032719205e-10,0.000000000000000000e+00 +9.665609015621894784e+00,8.431000000000000227e+01,0.000000000000000000e+00,4.370573829667287136e+00,0.000000000000000000e+00,-1.000000009975376525e+00,0.000000000000000000e+00,-8.113065156582725276e-11,0.000000000000000000e+00 +9.667897044697646436e+00,8.432000000000000739e+01,0.000000000000000000e+00,4.368285800568711075e+00,0.000000000000000000e+00,-1.000000009975562154e+00,0.000000000000000000e+00,1.555806688838193414e-10,0.000000000000000000e+00 +9.670186272201647171e+00,8.432999999999999829e+01,0.000000000000000000e+00,4.365996573041873496e+00,0.000000000000000000e+00,-1.000000009975205995e+00,0.000000000000000000e+00,-1.738216649608066304e-10,0.000000000000000000e+00 +9.672476700018687978e+00,8.434000000000000341e+01,0.000000000000000000e+00,4.363706145201985187e+00,0.000000000000000000e+00,-1.000000009975604121e+00,0.000000000000000000e+00,2.703335365586654080e-11,0.000000000000000000e+00 +9.674768330038503450e+00,8.435000000000000853e+01,0.000000000000000000e+00,4.361414515159308891e+00,0.000000000000000000e+00,-1.000000009975542170e+00,0.000000000000000000e+00,1.757697841723114755e-10,0.000000000000000000e+00 +9.677061164155793094e+00,8.435999999999999943e+01,0.000000000000000000e+00,4.359121681019146877e+00,0.000000000000000000e+00,-1.000000009975139159e+00,0.000000000000000000e+00,-1.205059717095133302e-10,0.000000000000000000e+00 +9.679355204270237323e+00,8.437000000000000455e+01,0.000000000000000000e+00,4.356827640881819619e+00,0.000000000000000000e+00,-1.000000009975415605e+00,0.000000000000000000e+00,-5.794786332753898336e-11,0.000000000000000000e+00 +9.681650452286515218e+00,8.437999999999999545e+01,0.000000000000000000e+00,4.354532392842645372e+00,0.000000000000000000e+00,-1.000000009975548609e+00,0.000000000000000000e+00,2.417251062004990799e-12,0.000000000000000000e+00 +9.683946910114325846e+00,8.439000000000000057e+01,0.000000000000000000e+00,4.352235934991925959e+00,0.000000000000000000e+00,-1.000000009975543058e+00,0.000000000000000000e+00,5.363467323428225122e-11,0.000000000000000000e+00 +9.686244579668404242e+00,8.440000000000000568e+01,0.000000000000000000e+00,4.349938265414926342e+00,0.000000000000000000e+00,-1.000000009975419824e+00,0.000000000000000000e+00,-6.171975267755009580e-11,0.000000000000000000e+00 +9.688543462868542733e+00,8.440999999999999659e+01,0.000000000000000000e+00,4.347639382191855972e+00,0.000000000000000000e+00,-1.000000009975561710e+00,0.000000000000000000e+00,1.870886806074127189e-10,0.000000000000000000e+00 +9.690843561639605142e+00,8.442000000000000171e+01,0.000000000000000000e+00,4.345339283397849250e+00,0.000000000000000000e+00,-1.000000009975131388e+00,0.000000000000000000e+00,-1.631576813260374334e-10,0.000000000000000000e+00 +9.693144877911548107e+00,8.443000000000000682e+01,0.000000000000000000e+00,4.343037967102949537e+00,0.000000000000000000e+00,-1.000000009975506865e+00,0.000000000000000000e+00,-4.455288451058609436e-11,0.000000000000000000e+00 +9.695447413619444177e+00,8.443999999999999773e+01,0.000000000000000000e+00,4.340735431372085174e+00,0.000000000000000000e+00,-1.000000009975609450e+00,0.000000000000000000e+00,1.170097977106923575e-10,0.000000000000000000e+00 +9.697751170703492463e+00,8.445000000000000284e+01,0.000000000000000000e+00,4.338431674265056159e+00,0.000000000000000000e+00,-1.000000009975339887e+00,0.000000000000000000e+00,-8.515796068420809658e-11,0.000000000000000000e+00 +9.700056151109043512e+00,8.446000000000000796e+01,0.000000000000000000e+00,4.336126693836512835e+00,0.000000000000000000e+00,-1.000000009975536175e+00,0.000000000000000000e+00,-3.677947717596436405e-11,0.000000000000000000e+00 +9.702362356786615294e+00,8.446999999999999886e+01,0.000000000000000000e+00,4.333820488135934568e+00,0.000000000000000000e+00,-1.000000009975620996e+00,0.000000000000000000e+00,5.696824631976567825e-11,0.000000000000000000e+00 +9.704669789691918069e+00,8.448000000000000398e+01,0.000000000000000000e+00,4.331513055207613760e+00,0.000000000000000000e+00,-1.000000009975489546e+00,0.000000000000000000e+00,9.040817587669185156e-12,0.000000000000000000e+00 +9.706978451785866824e+00,8.448999999999999488e+01,0.000000000000000000e+00,4.329204393090635428e+00,0.000000000000000000e+00,-1.000000009975468673e+00,0.000000000000000000e+00,-1.595718955311843247e-11,0.000000000000000000e+00 +9.709288345034602585e+00,8.450000000000000000e+01,0.000000000000000000e+00,4.326894499818856765e+00,0.000000000000000000e+00,-1.000000009975505533e+00,0.000000000000000000e+00,-3.554825245128904821e-12,0.000000000000000000e+00 +9.711599471409515516e+00,8.451000000000000512e+01,0.000000000000000000e+00,4.324583373420888499e+00,0.000000000000000000e+00,-1.000000009975513748e+00,0.000000000000000000e+00,7.922065854586953115e-11,0.000000000000000000e+00 +9.713911832887260900e+00,8.451999999999999602e+01,0.000000000000000000e+00,4.322271011920075345e+00,0.000000000000000000e+00,-1.000000009975330562e+00,0.000000000000000000e+00,-4.952242709578855470e-11,0.000000000000000000e+00 +9.716225431449780459e+00,8.453000000000000114e+01,0.000000000000000000e+00,4.319957413334476470e+00,0.000000000000000000e+00,-1.000000009975445137e+00,0.000000000000000000e+00,-1.553941644161638903e-10,0.000000000000000000e+00 +9.718540269084321892e+00,8.454000000000000625e+01,0.000000000000000000e+00,4.317642575676844174e+00,0.000000000000000000e+00,-1.000000009975804849e+00,0.000000000000000000e+00,1.788951441697548702e-10,0.000000000000000000e+00 +9.720856347783456641e+00,8.454999999999999716e+01,0.000000000000000000e+00,4.315326496954605240e+00,0.000000000000000000e+00,-1.000000009975390514e+00,0.000000000000000000e+00,-1.023352224904243347e-10,0.000000000000000000e+00 +9.723173669545102982e+00,8.456000000000000227e+01,0.000000000000000000e+00,4.313009175169843168e+00,0.000000000000000000e+00,-1.000000009975627657e+00,0.000000000000000000e+00,1.162624027863088283e-10,0.000000000000000000e+00 +9.725492236372543786e+00,8.457000000000000739e+01,0.000000000000000000e+00,4.310690608319272421e+00,0.000000000000000000e+00,-1.000000009975358095e+00,0.000000000000000000e+00,-1.821486123627996711e-10,0.000000000000000000e+00 +9.727812050274451394e+00,8.457999999999999829e+01,0.000000000000000000e+00,4.308370794394224212e+00,0.000000000000000000e+00,-1.000000009975780646e+00,0.000000000000000000e+00,1.510551125149746178e-10,0.000000000000000000e+00 +9.730133113264900047e+00,8.459000000000000341e+01,0.000000000000000000e+00,4.306049731380620749e+00,0.000000000000000000e+00,-1.000000009975430038e+00,0.000000000000000000e+00,-2.753669120808807404e-11,0.000000000000000000e+00 +9.732455427363394307e+00,8.460000000000000853e+01,0.000000000000000000e+00,4.303727417258961019e+00,0.000000000000000000e+00,-1.000000009975493986e+00,0.000000000000000000e+00,-2.799965000425953602e-11,0.000000000000000000e+00 +9.734778994594883272e+00,8.460999999999999943e+01,0.000000000000000000e+00,4.301403850004294149e+00,0.000000000000000000e+00,-1.000000009975559045e+00,0.000000000000000000e+00,3.295107138815381525e-11,0.000000000000000000e+00 +9.737103816989783667e+00,8.462000000000000455e+01,0.000000000000000000e+00,4.299079027586202528e+00,0.000000000000000000e+00,-1.000000009975482440e+00,0.000000000000000000e+00,-1.059591907686271330e-10,0.000000000000000000e+00 +9.739429896584001156e+00,8.462999999999999545e+01,0.000000000000000000e+00,4.296752947968780489e+00,0.000000000000000000e+00,-1.000000009975728910e+00,0.000000000000000000e+00,1.331882851865899157e-10,0.000000000000000000e+00 +9.741757235418953442e+00,8.464000000000000057e+01,0.000000000000000000e+00,4.294425609110612108e+00,0.000000000000000000e+00,-1.000000009975418935e+00,0.000000000000000000e+00,-1.290158613082383532e-10,0.000000000000000000e+00 +9.744085835541582696e+00,8.465000000000000568e+01,0.000000000000000000e+00,4.292097008964753435e+00,0.000000000000000000e+00,-1.000000009975719362e+00,0.000000000000000000e+00,5.032035278980972671e-11,0.000000000000000000e+00 +9.746415699004387534e+00,8.465999999999999659e+01,0.000000000000000000e+00,4.289767145478706745e+00,0.000000000000000000e+00,-1.000000009975602122e+00,0.000000000000000000e+00,1.575467502817180575e-10,0.000000000000000000e+00 +9.748746827865435449e+00,8.467000000000000171e+01,0.000000000000000000e+00,4.287436016594404542e+00,0.000000000000000000e+00,-1.000000009975234860e+00,0.000000000000000000e+00,-1.351842891753397552e-10,0.000000000000000000e+00 +9.751079224188387684e+00,8.468000000000000682e+01,0.000000000000000000e+00,4.285103620248185585e+00,0.000000000000000000e+00,-1.000000009975550164e+00,0.000000000000000000e+00,-1.579463673098577324e-10,0.000000000000000000e+00 +9.753412890042522321e+00,8.468999999999999773e+01,0.000000000000000000e+00,4.282769954370771792e+00,0.000000000000000000e+00,-1.000000009975918758e+00,0.000000000000000000e+00,1.244814444916495565e-10,0.000000000000000000e+00 +9.755747827502750269e+00,8.470000000000000284e+01,0.000000000000000000e+00,4.280435016887250477e+00,0.000000000000000000e+00,-1.000000009975628101e+00,0.000000000000000000e+00,1.157645057718575120e-10,0.000000000000000000e+00 +9.758084038649641911e+00,8.471000000000000796e+01,0.000000000000000000e+00,4.278098805717053033e+00,0.000000000000000000e+00,-1.000000009975357651e+00,0.000000000000000000e+00,-1.082918785426088007e-10,0.000000000000000000e+00 +9.760421525569448420e+00,8.471999999999999886e+01,0.000000000000000000e+00,4.275761318773930064e+00,0.000000000000000000e+00,-1.000000009975610782e+00,0.000000000000000000e+00,3.417875038011197473e-11,0.000000000000000000e+00 +9.762760290354117743e+00,8.473000000000000398e+01,0.000000000000000000e+00,4.273422553965930071e+00,0.000000000000000000e+00,-1.000000009975530846e+00,0.000000000000000000e+00,-1.547640279379798743e-10,0.000000000000000000e+00 +9.765100335101323026e+00,8.473999999999999488e+01,0.000000000000000000e+00,4.271082509195380794e+00,0.000000000000000000e+00,-1.000000009975893001e+00,0.000000000000000000e+00,2.689579669219033358e-10,0.000000000000000000e+00 +9.767441661914483930e+00,8.475000000000000000e+01,0.000000000000000000e+00,4.268741182358863462e+00,0.000000000000000000e+00,-1.000000009975263282e+00,0.000000000000000000e+00,-1.613242315817672510e-10,0.000000000000000000e+00 +9.769784272902782618e+00,8.476000000000000512e+01,0.000000000000000000e+00,4.266398571347195912e+00,0.000000000000000000e+00,-1.000000009975641202e+00,0.000000000000000000e+00,-1.385944938787841317e-10,0.000000000000000000e+00 +9.772128170181193951e+00,8.476999999999999602e+01,0.000000000000000000e+00,4.264054674045402393e+00,0.000000000000000000e+00,-1.000000009975966053e+00,0.000000000000000000e+00,2.053631617649926164e-10,0.000000000000000000e+00 +9.774473355870503255e+00,8.478000000000000114e+01,0.000000000000000000e+00,4.261709488332698470e+00,0.000000000000000000e+00,-1.000000009975484438e+00,0.000000000000000000e+00,-4.665207726235510940e-11,0.000000000000000000e+00 +9.776819832097325857e+00,8.479000000000000625e+01,0.000000000000000000e+00,4.259363012082467925e+00,0.000000000000000000e+00,-1.000000009975593906e+00,0.000000000000000000e+00,-1.541602780917733104e-11,0.000000000000000000e+00 +9.779167600994137288e+00,8.479999999999999716e+01,0.000000000000000000e+00,4.257015243162235230e+00,0.000000000000000000e+00,-1.000000009975630100e+00,0.000000000000000000e+00,6.767970437647008795e-11,0.000000000000000000e+00 +9.781516664699291042e+00,8.481000000000000227e+01,0.000000000000000000e+00,4.254666179433647777e+00,0.000000000000000000e+00,-1.000000009975471116e+00,0.000000000000000000e+00,-1.673109163164318952e-10,0.000000000000000000e+00 +9.783867025357041669e+00,8.482000000000000739e+01,0.000000000000000000e+00,4.252315818752451904e+00,0.000000000000000000e+00,-1.000000009975864357e+00,0.000000000000000000e+00,5.570802337348960807e-11,0.000000000000000000e+00 +9.786218685117566096e+00,8.482999999999999829e+01,0.000000000000000000e+00,4.249964158968468020e+00,0.000000000000000000e+00,-1.000000009975733350e+00,0.000000000000000000e+00,8.587502674875638404e-11,0.000000000000000000e+00 +9.788571646136990267e+00,8.484000000000000341e+01,0.000000000000000000e+00,4.247611197925571958e+00,0.000000000000000000e+00,-1.000000009975531290e+00,0.000000000000000000e+00,-6.253145166611804623e-11,0.000000000000000000e+00 +9.790925910577408686e+00,8.485000000000000853e+01,0.000000000000000000e+00,4.245256933461668325e+00,0.000000000000000000e+00,-1.000000009975678505e+00,0.000000000000000000e+00,-3.431196490888515645e-11,0.000000000000000000e+00 +9.793281480606911060e+00,8.485999999999999943e+01,0.000000000000000000e+00,4.242901363408667414e+00,0.000000000000000000e+00,-1.000000009975759330e+00,0.000000000000000000e+00,6.481739895980805001e-11,0.000000000000000000e+00 +9.795638358399603618e+00,8.487000000000000455e+01,0.000000000000000000e+00,4.240544485592463886e+00,0.000000000000000000e+00,-1.000000009975606563e+00,0.000000000000000000e+00,-8.191833217242469677e-12,0.000000000000000000e+00 +9.797996546135630425e+00,8.487999999999999545e+01,0.000000000000000000e+00,4.238186297832912786e+00,0.000000000000000000e+00,-1.000000009975625881e+00,0.000000000000000000e+00,3.858372248614059624e-12,0.000000000000000000e+00 +9.800356046001201804e+00,8.489000000000000057e+01,0.000000000000000000e+00,4.235826797943804678e+00,0.000000000000000000e+00,-1.000000009975616777e+00,0.000000000000000000e+00,-9.950939521773495965e-11,0.000000000000000000e+00 +9.802716860188612102e+00,8.490000000000000568e+01,0.000000000000000000e+00,4.233465983732843441e+00,0.000000000000000000e+00,-1.000000009975851700e+00,0.000000000000000000e+00,1.400627239914062149e-10,0.000000000000000000e+00 +9.805078990896269886e+00,8.490999999999999659e+01,0.000000000000000000e+00,4.231103853001621395e+00,0.000000000000000000e+00,-1.000000009975520854e+00,0.000000000000000000e+00,-7.140152754117573254e-11,0.000000000000000000e+00 +9.807442440328717481e+00,8.492000000000000171e+01,0.000000000000000000e+00,4.228740403545597992e+00,0.000000000000000000e+00,-1.000000009975689608e+00,0.000000000000000000e+00,-7.380296278973385898e-11,0.000000000000000000e+00 +9.809807210696654067e+00,8.493000000000000682e+01,0.000000000000000000e+00,4.226375633154071387e+00,0.000000000000000000e+00,-1.000000009975864135e+00,0.000000000000000000e+00,1.780228092960916872e-10,0.000000000000000000e+00 +9.812173304216964098e+00,8.493999999999999773e+01,0.000000000000000000e+00,4.224009539610158015e+00,0.000000000000000000e+00,-1.000000009975442916e+00,0.000000000000000000e+00,-2.012773164140257686e-10,0.000000000000000000e+00 +9.814540723112736842e+00,8.495000000000000284e+01,0.000000000000000000e+00,4.221642120690768607e+00,0.000000000000000000e+00,-1.000000009975919424e+00,0.000000000000000000e+00,1.463270249501722509e-10,0.000000000000000000e+00 +9.816909469613296579e+00,8.496000000000000796e+01,0.000000000000000000e+00,4.219273374166578883e+00,0.000000000000000000e+00,-1.000000009975572812e+00,0.000000000000000000e+00,-9.424880907741469775e-11,0.000000000000000000e+00 +9.819279545954220367e+00,8.496999999999999886e+01,0.000000000000000000e+00,4.216903297802012673e+00,0.000000000000000000e+00,-1.000000009975796189e+00,0.000000000000000000e+00,1.966315316211770007e-12,0.000000000000000000e+00 +9.821650954377366460e+00,8.498000000000000398e+01,0.000000000000000000e+00,4.214531889355209948e+00,0.000000000000000000e+00,-1.000000009975791526e+00,0.000000000000000000e+00,1.150115489960146903e-10,0.000000000000000000e+00 +9.824023697130899180e+00,8.498999999999999488e+01,0.000000000000000000e+00,4.212159146578007274e+00,0.000000000000000000e+00,-1.000000009975518633e+00,0.000000000000000000e+00,-2.079143475795610633e-10,0.000000000000000000e+00 +9.826397776469312006e+00,8.500000000000000000e+01,0.000000000000000000e+00,4.209785067215911170e+00,0.000000000000000000e+00,-1.000000009976012239e+00,0.000000000000000000e+00,1.782587438366066118e-10,0.000000000000000000e+00 +9.828773194653456002e+00,8.501000000000000512e+01,0.000000000000000000e+00,4.207409649008070573e+00,0.000000000000000000e+00,-1.000000009975588799e+00,0.000000000000000000e+00,-7.912950234411821045e-11,0.000000000000000000e+00 +9.831149953950559350e+00,8.501999999999999602e+01,0.000000000000000000e+00,4.205032889687258191e+00,0.000000000000000000e+00,-1.000000009975776871e+00,0.000000000000000000e+00,5.163387912781156388e-11,0.000000000000000000e+00 +9.833528056634255776e+00,8.503000000000000114e+01,0.000000000000000000e+00,4.202654786979837631e+00,0.000000000000000000e+00,-1.000000009975654081e+00,0.000000000000000000e+00,-1.053556631824878134e-10,0.000000000000000000e+00 +9.835907504984612970e+00,8.504000000000000625e+01,0.000000000000000000e+00,4.200275338605743869e+00,0.000000000000000000e+00,-1.000000009975904769e+00,0.000000000000000000e+00,5.418687657976344868e-11,0.000000000000000000e+00 +9.838288301288152127e+00,8.504999999999999716e+01,0.000000000000000000e+00,4.197894542278453933e+00,0.000000000000000000e+00,-1.000000009975775761e+00,0.000000000000000000e+00,5.816427771380705979e-11,0.000000000000000000e+00 +9.840670447837878143e+00,8.506000000000000227e+01,0.000000000000000000e+00,4.195512395704964703e+00,0.000000000000000000e+00,-1.000000009975637205e+00,0.000000000000000000e+00,-7.005563510565100609e-11,0.000000000000000000e+00 +9.843053946933300935e+00,8.507000000000000739e+01,0.000000000000000000e+00,4.193128896585764487e+00,0.000000000000000000e+00,-1.000000009975804183e+00,0.000000000000000000e+00,2.793184947726355680e-11,0.000000000000000000e+00 +9.845438800880467412e+00,8.507999999999999829e+01,0.000000000000000000e+00,4.190744042614807263e+00,0.000000000000000000e+00,-1.000000009975737569e+00,0.000000000000000000e+00,-4.773629700108631064e-11,0.000000000000000000e+00 +9.847825011991981015e+00,8.509000000000000341e+01,0.000000000000000000e+00,4.188357831479488702e+00,0.000000000000000000e+00,-1.000000009975851478e+00,0.000000000000000000e+00,1.076012614791681186e-10,0.000000000000000000e+00 +9.850212582587033694e+00,8.510000000000000853e+01,0.000000000000000000e+00,4.185970260860617742e+00,0.000000000000000000e+00,-1.000000009975594573e+00,0.000000000000000000e+00,-1.688850828958919363e-10,0.000000000000000000e+00 +9.852601514991427223e+00,8.510999999999999943e+01,0.000000000000000000e+00,4.183581328432392610e+00,0.000000000000000000e+00,-1.000000009975998028e+00,0.000000000000000000e+00,1.965640559423263372e-10,0.000000000000000000e+00 +9.854991811537603397e+00,8.512000000000000455e+01,0.000000000000000000e+00,4.181191031862370622e+00,0.000000000000000000e+00,-1.000000009975528181e+00,0.000000000000000000e+00,-1.873533217966075540e-10,0.000000000000000000e+00 +9.857383474564668902e+00,8.512999999999999545e+01,0.000000000000000000e+00,4.178799368811447756e+00,0.000000000000000000e+00,-1.000000009975976267e+00,0.000000000000000000e+00,1.094898228792275425e-10,0.000000000000000000e+00 +9.859776506418420183e+00,8.514000000000000057e+01,0.000000000000000000e+00,4.176406336933824015e+00,0.000000000000000000e+00,-1.000000009975714255e+00,0.000000000000000000e+00,-9.774253138257750586e-11,0.000000000000000000e+00 +9.862170909451373646e+00,8.515000000000000568e+01,0.000000000000000000e+00,4.174011933876984770e+00,0.000000000000000000e+00,-1.000000009975948290e+00,0.000000000000000000e+00,4.634084154050404529e-11,0.000000000000000000e+00 +9.864566686022790520e+00,8.515999999999999659e+01,0.000000000000000000e+00,4.171616157281667014e+00,0.000000000000000000e+00,-1.000000009975837267e+00,0.000000000000000000e+00,2.732540341550330683e-11,0.000000000000000000e+00 +9.866963838498707062e+00,8.517000000000000171e+01,0.000000000000000000e+00,4.169219004781837157e+00,0.000000000000000000e+00,-1.000000009975771764e+00,0.000000000000000000e+00,-2.508789510126958063e-11,0.000000000000000000e+00 +9.869362369251955869e+00,8.518000000000000682e+01,0.000000000000000000e+00,4.166820474004660824e+00,0.000000000000000000e+00,-1.000000009975831938e+00,0.000000000000000000e+00,4.283768627520241416e-11,0.000000000000000000e+00 +9.871762280662199629e+00,8.518999999999999773e+01,0.000000000000000000e+00,4.164420562570476214e+00,0.000000000000000000e+00,-1.000000009975729132e+00,0.000000000000000000e+00,-5.289210318149689078e-11,0.000000000000000000e+00 +9.874163575115954217e+00,8.520000000000000284e+01,0.000000000000000000e+00,4.162019268092767454e+00,0.000000000000000000e+00,-1.000000009975856141e+00,0.000000000000000000e+00,4.482146531759028913e-11,0.000000000000000000e+00 +9.876566255006617112e+00,8.521000000000000796e+01,0.000000000000000000e+00,4.159616588178135288e+00,0.000000000000000000e+00,-1.000000009975748450e+00,0.000000000000000000e+00,-5.135329546106610938e-11,0.000000000000000000e+00 +9.878970322734499376e+00,8.521999999999999886e+01,0.000000000000000000e+00,4.157212520426271318e+00,0.000000000000000000e+00,-1.000000009975871906e+00,0.000000000000000000e+00,6.516991478513362133e-11,0.000000000000000000e+00 +9.881375780706846967e+00,8.523000000000000398e+01,0.000000000000000000e+00,4.154807062429927811e+00,0.000000000000000000e+00,-1.000000009975715143e+00,0.000000000000000000e+00,-9.465388575276247290e-11,0.000000000000000000e+00 +9.883782631337872715e+00,8.523999999999999488e+01,0.000000000000000000e+00,4.152400211774891936e+00,0.000000000000000000e+00,-1.000000009975942961e+00,0.000000000000000000e+00,7.855593909660747026e-11,0.000000000000000000e+00 +9.886190877048784742e+00,8.525000000000000000e+01,0.000000000000000000e+00,4.149991966039954683e+00,0.000000000000000000e+00,-1.000000009975753779e+00,0.000000000000000000e+00,-1.586794288304283508e-10,0.000000000000000000e+00 +9.888600520267814886e+00,8.526000000000000512e+01,0.000000000000000000e+00,4.147582322796885990e+00,0.000000000000000000e+00,-1.000000009976136139e+00,0.000000000000000000e+00,1.596003366223675750e-10,0.000000000000000000e+00 +9.891011563430245346e+00,8.526999999999999602e+01,0.000000000000000000e+00,4.145171279610401882e+00,0.000000000000000000e+00,-1.000000009975751336e+00,0.000000000000000000e+00,3.635631030554328340e-11,0.000000000000000000e+00 +9.893424008978440654e+00,8.528000000000000114e+01,0.000000000000000000e+00,4.142758834038141380e+00,0.000000000000000000e+00,-1.000000009975663628e+00,0.000000000000000000e+00,-1.221596986145690241e-10,0.000000000000000000e+00 +9.895837859361870770e+00,8.529000000000000625e+01,0.000000000000000000e+00,4.140344983630631859e+00,0.000000000000000000e+00,-1.000000009975958504e+00,0.000000000000000000e+00,-3.815266254495935459e-11,0.000000000000000000e+00 +9.898253117037144833e+00,8.529999999999999716e+01,0.000000000000000000e+00,4.137929725931262404e+00,0.000000000000000000e+00,-1.000000009976050652e+00,0.000000000000000000e+00,1.346049282810856985e-10,0.000000000000000000e+00 +9.900669784468041357e+00,8.531000000000000227e+01,0.000000000000000000e+00,4.135513058476256276e+00,0.000000000000000000e+00,-1.000000009975725357e+00,0.000000000000000000e+00,-3.397592943957172381e-11,0.000000000000000000e+00 +9.903087864125534878e+00,8.532000000000000739e+01,0.000000000000000000e+00,4.133094978794640717e+00,0.000000000000000000e+00,-1.000000009975807513e+00,0.000000000000000000e+00,-3.487379478399529402e-11,0.000000000000000000e+00 +9.905507358487824376e+00,8.532999999999999829e+01,0.000000000000000000e+00,4.130675484408214970e+00,0.000000000000000000e+00,-1.000000009975891890e+00,0.000000000000000000e+00,-9.346208959231041010e-11,0.000000000000000000e+00 +9.907928270040365248e+00,8.534000000000000341e+01,0.000000000000000000e+00,4.128254572831523639e+00,0.000000000000000000e+00,-1.000000009976118154e+00,0.000000000000000000e+00,1.992811569392512594e-10,0.000000000000000000e+00 +9.910350601275897731e+00,8.535000000000000853e+01,0.000000000000000000e+00,4.125832241571825598e+00,0.000000000000000000e+00,-1.000000009975635429e+00,0.000000000000000000e+00,-2.350760815311337928e-10,0.000000000000000000e+00 +9.912774354694478873e+00,8.535999999999999943e+01,0.000000000000000000e+00,4.123408488129066463e+00,0.000000000000000000e+00,-1.000000009976205195e+00,0.000000000000000000e+00,1.244274047211258259e-10,0.000000000000000000e+00 +9.915199532803509186e+00,8.537000000000000455e+01,0.000000000000000000e+00,4.120983309995842170e+00,0.000000000000000000e+00,-1.000000009975903437e+00,0.000000000000000000e+00,1.035827669618803577e-10,0.000000000000000000e+00 +9.917626138117766388e+00,8.537999999999999545e+01,0.000000000000000000e+00,4.118556704657377665e+00,0.000000000000000000e+00,-1.000000009975652082e+00,0.000000000000000000e+00,-8.203094568232467532e-11,0.000000000000000000e+00 +9.920054173159433830e+00,8.539000000000000057e+01,0.000000000000000000e+00,4.116128669591489597e+00,0.000000000000000000e+00,-1.000000009975851256e+00,0.000000000000000000e+00,-4.094559455884965925e-11,0.000000000000000000e+00 +9.922483640458130694e+00,8.540000000000000568e+01,0.000000000000000000e+00,4.113699202268557009e+00,0.000000000000000000e+00,-1.000000009975950732e+00,0.000000000000000000e+00,-1.069620340267469847e-10,0.000000000000000000e+00 +9.924914542550943963e+00,8.540999999999999659e+01,0.000000000000000000e+00,4.111268300151492916e+00,0.000000000000000000e+00,-1.000000009976210746e+00,0.000000000000000000e+00,1.660537715769808856e-10,0.000000000000000000e+00 +9.927346881982460403e+00,8.542000000000000171e+01,0.000000000000000000e+00,4.108835960695711442e+00,0.000000000000000000e+00,-1.000000009975806847e+00,0.000000000000000000e+00,-9.944558947779404551e-11,0.000000000000000000e+00 +9.929780661304793199e+00,8.543000000000000682e+01,0.000000000000000000e+00,4.106402181349099401e+00,0.000000000000000000e+00,-1.000000009976048876e+00,0.000000000000000000e+00,4.869035763111860085e-11,0.000000000000000000e+00 +9.932215883077619267e+00,8.543999999999999773e+01,0.000000000000000000e+00,4.103966959551979876e+00,0.000000000000000000e+00,-1.000000009975930304e+00,0.000000000000000000e+00,9.039736123818285855e-11,0.000000000000000000e+00 +9.934652549868204119e+00,8.545000000000000284e+01,0.000000000000000000e+00,4.101530292737086469e+00,0.000000000000000000e+00,-1.000000009975710036e+00,0.000000000000000000e+00,-1.651140206944642715e-10,0.000000000000000000e+00 +9.937090664251439165e+00,8.546000000000000796e+01,0.000000000000000000e+00,4.099092178329528657e+00,0.000000000000000000e+00,-1.000000009976112603e+00,0.000000000000000000e+00,1.661080878501450814e-10,0.000000000000000000e+00 +9.939530228809871915e+00,8.546999999999999886e+01,0.000000000000000000e+00,4.096652613746758931e+00,0.000000000000000000e+00,-1.000000009975707371e+00,0.000000000000000000e+00,-9.487541144132792768e-11,0.000000000000000000e+00 +9.941971246133734397e+00,8.548000000000000398e+01,0.000000000000000000e+00,4.094211596398546149e+00,0.000000000000000000e+00,-1.000000009975938964e+00,0.000000000000000000e+00,-7.636419809775093974e-12,0.000000000000000000e+00 +9.944413718820978687e+00,8.548999999999999488e+01,0.000000000000000000e+00,4.091769123686936460e+00,0.000000000000000000e+00,-1.000000009975957616e+00,0.000000000000000000e+00,-9.467145793710747674e-11,0.000000000000000000e+00 +9.946857649477307106e+00,8.550000000000000000e+01,0.000000000000000000e+00,4.089325193006226655e+00,0.000000000000000000e+00,-1.000000009976188986e+00,0.000000000000000000e+00,4.458341850735030937e-11,0.000000000000000000e+00 +9.949303040716209523e+00,8.551000000000000512e+01,0.000000000000000000e+00,4.086879801742928642e+00,0.000000000000000000e+00,-1.000000009976079962e+00,0.000000000000000000e+00,9.601028483894365947e-11,0.000000000000000000e+00 +9.951749895158988224e+00,8.551999999999999602e+01,0.000000000000000000e+00,4.084432947275739245e+00,0.000000000000000000e+00,-1.000000009975845039e+00,0.000000000000000000e+00,-7.491211238996343729e-11,0.000000000000000000e+00 +9.954198215434796992e+00,8.553000000000000114e+01,0.000000000000000000e+00,4.081984626975505570e+00,0.000000000000000000e+00,-1.000000009976028448e+00,0.000000000000000000e+00,1.966850380460815274e-11,0.000000000000000000e+00 +9.956648004180671307e+00,8.554000000000000625e+01,0.000000000000000000e+00,4.079534838205191249e+00,0.000000000000000000e+00,-1.000000009975980264e+00,0.000000000000000000e+00,7.699628962130972621e-12,0.000000000000000000e+00 +9.959099264041562094e+00,8.554999999999999716e+01,0.000000000000000000e+00,4.077083578319846247e+00,0.000000000000000000e+00,-1.000000009975961390e+00,0.000000000000000000e+00,-8.147649711549267925e-12,0.000000000000000000e+00 +9.961551997670369474e+00,8.556000000000000227e+01,0.000000000000000000e+00,4.074630844666571328e+00,0.000000000000000000e+00,-1.000000009975981374e+00,0.000000000000000000e+00,-4.252324041760876430e-11,0.000000000000000000e+00 +9.964006207727972964e+00,8.557000000000000739e+01,0.000000000000000000e+00,4.072176634584485200e+00,0.000000000000000000e+00,-1.000000009976085735e+00,0.000000000000000000e+00,6.691115904883291285e-11,0.000000000000000000e+00 +9.966461896883268778e+00,8.557999999999999829e+01,0.000000000000000000e+00,4.069720945404690760e+00,0.000000000000000000e+00,-1.000000009975921422e+00,0.000000000000000000e+00,-7.545557488637204931e-11,0.000000000000000000e+00 +9.968919067813205359e+00,8.559000000000000341e+01,0.000000000000000000e+00,4.067263774450242231e+00,0.000000000000000000e+00,-1.000000009976106830e+00,0.000000000000000000e+00,4.804566362554061256e-11,0.000000000000000000e+00 +9.971377723202811794e+00,8.560000000000000853e+01,0.000000000000000000e+00,4.064805119036108749e+00,0.000000000000000000e+00,-1.000000009975988702e+00,0.000000000000000000e+00,1.031635277439384898e-10,0.000000000000000000e+00 +9.973837865745235121e+00,8.560999999999999943e+01,0.000000000000000000e+00,4.062344976469143276e+00,0.000000000000000000e+00,-1.000000009975734905e+00,0.000000000000000000e+00,-2.114339064905584087e-10,0.000000000000000000e+00 +9.976299498141775857e+00,8.562000000000000455e+01,0.000000000000000000e+00,4.059883344048046183e+00,0.000000000000000000e+00,-1.000000009976255377e+00,0.000000000000000000e+00,1.529803402810955276e-10,0.000000000000000000e+00 +9.978762623101919971e+00,8.562999999999999545e+01,0.000000000000000000e+00,4.057420219063328837e+00,0.000000000000000000e+00,-1.000000009975878568e+00,0.000000000000000000e+00,-6.892101262109142790e-11,0.000000000000000000e+00 +9.981227243343376188e+00,8.564000000000000057e+01,0.000000000000000000e+00,4.054955598797285177e+00,0.000000000000000000e+00,-1.000000009976048432e+00,0.000000000000000000e+00,-5.897495641198838931e-11,0.000000000000000000e+00 +9.983693361592109738e+00,8.565000000000000568e+01,0.000000000000000000e+00,4.052489480523949084e+00,0.000000000000000000e+00,-1.000000009976193871e+00,0.000000000000000000e+00,1.521618322800843559e-10,0.000000000000000000e+00 +9.986160980582377888e+00,8.565999999999999659e+01,0.000000000000000000e+00,4.050021861509064180e+00,0.000000000000000000e+00,-1.000000009975818394e+00,0.000000000000000000e+00,-1.615116765501029774e-10,0.000000000000000000e+00 +9.988630103056761911e+00,8.567000000000000171e+01,0.000000000000000000e+00,4.047552739010048306e+00,0.000000000000000000e+00,-1.000000009976217186e+00,0.000000000000000000e+00,5.491284590453425422e-11,0.000000000000000000e+00 +9.991100731766209719e+00,8.568000000000000682e+01,0.000000000000000000e+00,4.045082110275953546e+00,0.000000000000000000e+00,-1.000000009976081516e+00,0.000000000000000000e+00,-5.838226283925983735e-12,0.000000000000000000e+00 +9.993572869470064290e+00,8.568999999999999773e+01,0.000000000000000000e+00,4.042609972547436925e+00,0.000000000000000000e+00,-1.000000009976095949e+00,0.000000000000000000e+00,4.685679412629899372e-11,0.000000000000000000e+00 +9.996046518936104519e+00,8.570000000000000284e+01,0.000000000000000000e+00,4.040136323056719547e+00,0.000000000000000000e+00,-1.000000009975980042e+00,0.000000000000000000e+00,5.382542842178387320e-11,0.000000000000000000e+00 +9.998521682940578970e+00,8.571000000000000796e+01,0.000000000000000000e+00,4.037661159027552848e+00,0.000000000000000000e+00,-1.000000009975846815e+00,0.000000000000000000e+00,-1.100055655928590686e-10,0.000000000000000000e+00 +1.000099836426824318e+01,8.571999999999999886e+01,0.000000000000000000e+00,4.035184477675181292e+00,0.000000000000000000e+00,-1.000000009976119264e+00,0.000000000000000000e+00,4.166357885624270402e-11,0.000000000000000000e+00 +1.000347656571239696e+01,8.573000000000000398e+01,0.000000000000000000e+00,4.032706276206305063e+00,0.000000000000000000e+00,-1.000000009976016013e+00,0.000000000000000000e+00,-1.295702652208801674e-10,0.000000000000000000e+00 +1.000595629007491816e+01,8.573999999999999488e+01,0.000000000000000000e+00,4.030226551819046321e+00,0.000000000000000000e+00,-1.000000009976337312e+00,0.000000000000000000e+00,2.171003291520758191e-10,0.000000000000000000e+00 +1.000843754016630172e+01,8.575000000000000000e+01,0.000000000000000000e+00,4.027745301702908343e+00,0.000000000000000000e+00,-1.000000009975798632e+00,0.000000000000000000e+00,-2.095436544700105223e-10,0.000000000000000000e+00 +1.001092031880569877e+01,8.576000000000000512e+01,0.000000000000000000e+00,4.025262523038743545e+00,0.000000000000000000e+00,-1.000000009976318882e+00,0.000000000000000000e+00,7.346935935043867664e-11,0.000000000000000000e+00 +1.001340462882095039e+01,8.576999999999999602e+01,0.000000000000000000e+00,4.022778212998708192e+00,0.000000000000000000e+00,-1.000000009976136361e+00,0.000000000000000000e+00,1.318416629733330582e-10,0.000000000000000000e+00 +1.001589047304862490e+01,8.578000000000000114e+01,0.000000000000000000e+00,4.020292368746233969e+00,0.000000000000000000e+00,-1.000000009975808624e+00,0.000000000000000000e+00,-2.116554310992961840e-10,0.000000000000000000e+00 +1.001837785433406047e+01,8.579000000000000625e+01,0.000000000000000000e+00,4.017804987435984465e+00,0.000000000000000000e+00,-1.000000009976335091e+00,0.000000000000000000e+00,1.907378047314031054e-10,0.000000000000000000e+00 +1.002086677553139893e+01,8.579999999999999716e+01,0.000000000000000000e+00,4.015316066213816093e+00,0.000000000000000000e+00,-1.000000009975860360e+00,0.000000000000000000e+00,-2.054198637092914828e-10,0.000000000000000000e+00 +1.002335723950362301e+01,8.581000000000000227e+01,0.000000000000000000e+00,4.012825602216747001e+00,0.000000000000000000e+00,-1.000000009976371951e+00,0.000000000000000000e+00,1.016660980319563321e-10,0.000000000000000000e+00 +1.002584924912259901e+01,8.582000000000000739e+01,0.000000000000000000e+00,4.010333592572909112e+00,0.000000000000000000e+00,-1.000000009976118598e+00,0.000000000000000000e+00,6.901165270898355973e-11,0.000000000000000000e+00 +1.002834280726911409e+01,8.582999999999999829e+01,0.000000000000000000e+00,4.007840034401518814e+00,0.000000000000000000e+00,-1.000000009975946513e+00,0.000000000000000000e+00,-2.144705409469795961e-11,0.000000000000000000e+00 +1.003083791683291004e+01,8.584000000000000341e+01,0.000000000000000000e+00,4.005344924812831664e+00,0.000000000000000000e+00,-1.000000009976000026e+00,0.000000000000000000e+00,-1.390077856707184959e-10,0.000000000000000000e+00 +1.003333458071272943e+01,8.585000000000000853e+01,0.000000000000000000e+00,4.002848260908105082e+00,0.000000000000000000e+00,-1.000000009976347082e+00,0.000000000000000000e+00,1.374101590593020144e-10,0.000000000000000000e+00 +1.003583280181635295e+01,8.585999999999999943e+01,0.000000000000000000e+00,4.000350039779559275e+00,0.000000000000000000e+00,-1.000000009976003801e+00,0.000000000000000000e+00,-8.767088142708046279e-11,0.000000000000000000e+00 +1.003833258306063492e+01,8.587000000000000455e+01,0.000000000000000000e+00,3.997850258510340371e+00,0.000000000000000000e+00,-1.000000009976222959e+00,0.000000000000000000e+00,3.435403184245404066e-11,0.000000000000000000e+00 +1.004083392737154590e+01,8.587999999999999545e+01,0.000000000000000000e+00,3.995348914174475130e+00,0.000000000000000000e+00,-1.000000009976137028e+00,0.000000000000000000e+00,3.619554338436938292e-11,0.000000000000000000e+00 +1.004333683768421537e+01,8.589000000000000057e+01,0.000000000000000000e+00,3.992846003836836299e+00,0.000000000000000000e+00,-1.000000009976046433e+00,0.000000000000000000e+00,-8.555592664777449543e-11,0.000000000000000000e+00 +1.004584131694296723e+01,8.590000000000000568e+01,0.000000000000000000e+00,3.990341524553099539e+00,0.000000000000000000e+00,-1.000000009976260706e+00,0.000000000000000000e+00,5.555431971992582507e-11,0.000000000000000000e+00 +1.004834736810136242e+01,8.590999999999999659e+01,0.000000000000000000e+00,3.987835473369703010e+00,0.000000000000000000e+00,-1.000000009976121484e+00,0.000000000000000000e+00,3.249701882538771317e-11,0.000000000000000000e+00 +1.005085499412223982e+01,8.592000000000000171e+01,0.000000000000000000e+00,3.985327847323809181e+00,0.000000000000000000e+00,-1.000000009976039994e+00,0.000000000000000000e+00,-4.822816983088786874e-11,0.000000000000000000e+00 +1.005336419797775527e+01,8.593000000000000682e+01,0.000000000000000000e+00,3.982818643443261308e+00,0.000000000000000000e+00,-1.000000009976161008e+00,0.000000000000000000e+00,-4.412973326935326032e-11,0.000000000000000000e+00 +1.005587498264942603e+01,8.593999999999999773e+01,0.000000000000000000e+00,3.980307858746543026e+00,0.000000000000000000e+00,-1.000000009976271809e+00,0.000000000000000000e+00,8.290099210449003345e-11,0.000000000000000000e+00 +1.005838735112816629e+01,8.595000000000000284e+01,0.000000000000000000e+00,3.977795490242737930e+00,0.000000000000000000e+00,-1.000000009976063531e+00,0.000000000000000000e+00,-8.329028905016193471e-11,0.000000000000000000e+00 +1.006090130641433689e+01,8.596000000000000796e+01,0.000000000000000000e+00,3.975281534931488281e+00,0.000000000000000000e+00,-1.000000009976272919e+00,0.000000000000000000e+00,6.275924605195299375e-11,0.000000000000000000e+00 +1.006341685151777909e+01,8.596999999999999886e+01,0.000000000000000000e+00,3.972765989802950592e+00,0.000000000000000000e+00,-1.000000009976115045e+00,0.000000000000000000e+00,-2.955139703129080405e-11,0.000000000000000000e+00 +1.006593398945786078e+01,8.598000000000000398e+01,0.000000000000000000e+00,3.970248851837757442e+00,0.000000000000000000e+00,-1.000000009976189430e+00,0.000000000000000000e+00,-3.041424565273290285e-11,0.000000000000000000e+00 +1.006845272326351903e+01,8.598999999999999488e+01,0.000000000000000000e+00,3.967730118006971729e+00,0.000000000000000000e+00,-1.000000009976266035e+00,0.000000000000000000e+00,7.700054201227531680e-11,0.000000000000000000e+00 +1.007097305597330106e+01,8.600000000000000000e+01,0.000000000000000000e+00,3.965209785272046261e+00,0.000000000000000000e+00,-1.000000009976071969e+00,0.000000000000000000e+00,-7.078845659333421948e-11,0.000000000000000000e+00 +1.007349499063540677e+01,8.601000000000000512e+01,0.000000000000000000e+00,3.962687850584781124e+00,0.000000000000000000e+00,-1.000000009976250492e+00,0.000000000000000000e+00,3.959520562009435849e-11,0.000000000000000000e+00 +1.007601853030773320e+01,8.601999999999999602e+01,0.000000000000000000e+00,3.960164310887278383e+00,0.000000000000000000e+00,-1.000000009976150572e+00,0.000000000000000000e+00,-1.626766271720973227e-11,0.000000000000000000e+00 +1.007854367805791895e+01,8.603000000000000114e+01,0.000000000000000000e+00,3.957639163111902114e+00,0.000000000000000000e+00,-1.000000009976191651e+00,0.000000000000000000e+00,-6.625944080043964599e-11,0.000000000000000000e+00 +1.008107043696338145e+01,8.604000000000000625e+01,0.000000000000000000e+00,3.955112404181232222e+00,0.000000000000000000e+00,-1.000000009976359072e+00,0.000000000000000000e+00,1.012577711017250888e-10,0.000000000000000000e+00 +1.008359881011136849e+01,8.604999999999999716e+01,0.000000000000000000e+00,3.952584031008021803e+00,0.000000000000000000e+00,-1.000000009976103055e+00,0.000000000000000000e+00,-2.738267873946271449e-11,0.000000000000000000e+00 +1.008612880059899553e+01,8.606000000000000227e+01,0.000000000000000000e+00,3.950054040495154517e+00,0.000000000000000000e+00,-1.000000009976172333e+00,0.000000000000000000e+00,-2.236574881578388988e-11,0.000000000000000000e+00 +1.008866041153329718e+01,8.607000000000000739e+01,0.000000000000000000e+00,3.947522429535597066e+00,0.000000000000000000e+00,-1.000000009976228954e+00,0.000000000000000000e+00,-3.874245177681276408e-11,0.000000000000000000e+00 +1.009119364603126456e+01,8.607999999999999829e+01,0.000000000000000000e+00,3.944989195012357452e+00,0.000000000000000000e+00,-1.000000009976327098e+00,0.000000000000000000e+00,1.673090413428469291e-11,0.000000000000000000e+00 +1.009372850721989501e+01,8.609000000000000341e+01,0.000000000000000000e+00,3.942454333798439237e+00,0.000000000000000000e+00,-1.000000009976284687e+00,0.000000000000000000e+00,6.985697705566350188e-11,0.000000000000000000e+00 +1.009626499823623291e+01,8.610000000000000853e+01,0.000000000000000000e+00,3.939917842756797128e+00,0.000000000000000000e+00,-1.000000009976107496e+00,0.000000000000000000e+00,-4.942831879700882733e-11,0.000000000000000000e+00 +1.009880312222741772e+01,8.610999999999999943e+01,0.000000000000000000e+00,3.937379718740291246e+00,0.000000000000000000e+00,-1.000000009976232951e+00,0.000000000000000000e+00,-5.709008724291497547e-11,0.000000000000000000e+00 +1.010134288235073186e+01,8.612000000000000455e+01,0.000000000000000000e+00,3.934839958591640485e+00,0.000000000000000000e+00,-1.000000009976377946e+00,0.000000000000000000e+00,9.610809824535780162e-11,0.000000000000000000e+00 +1.010388428177363984e+01,8.612999999999999545e+01,0.000000000000000000e+00,3.932298559143378558e+00,0.000000000000000000e+00,-1.000000009976133697e+00,0.000000000000000000e+00,-4.872152894468418811e-11,0.000000000000000000e+00 +1.010642732367383978e+01,8.614000000000000057e+01,0.000000000000000000e+00,3.929755517217808247e+00,0.000000000000000000e+00,-1.000000009976257598e+00,0.000000000000000000e+00,-1.527016769727032906e-11,0.000000000000000000e+00 +1.010897201123930955e+01,8.615000000000000568e+01,0.000000000000000000e+00,3.927210829626952115e+00,0.000000000000000000e+00,-1.000000009976296456e+00,0.000000000000000000e+00,2.773010807247390609e-11,0.000000000000000000e+00 +1.011151834766834945e+01,8.615999999999999659e+01,0.000000000000000000e+00,3.924664493172508983e+00,0.000000000000000000e+00,-1.000000009976225845e+00,0.000000000000000000e+00,-4.548972011155893082e-11,0.000000000000000000e+00 +1.011406633616963369e+01,8.617000000000000171e+01,0.000000000000000000e+00,3.922116504645805968e+00,0.000000000000000000e+00,-1.000000009976341753e+00,0.000000000000000000e+00,2.394933226796062372e-11,0.000000000000000000e+00 +1.011661597996225304e+01,8.618000000000000682e+01,0.000000000000000000e+00,3.919566860827750521e+00,0.000000000000000000e+00,-1.000000009976280690e+00,0.000000000000000000e+00,-9.660537293496147443e-12,0.000000000000000000e+00 +1.011916728227576634e+01,8.618999999999999773e+01,0.000000000000000000e+00,3.917015558488784688e+00,0.000000000000000000e+00,-1.000000009976305337e+00,0.000000000000000000e+00,6.114357770353997330e-11,0.000000000000000000e+00 +1.012172024635024670e+01,8.620000000000000284e+01,0.000000000000000000e+00,3.914462594388835814e+00,0.000000000000000000e+00,-1.000000009976149240e+00,0.000000000000000000e+00,-5.832233364777358525e-11,0.000000000000000000e+00 +1.012427487543632765e+01,8.621000000000000796e+01,0.000000000000000000e+00,3.911907965277269916e+00,0.000000000000000000e+00,-1.000000009976298232e+00,0.000000000000000000e+00,-6.427773634032751560e-12,0.000000000000000000e+00 +1.012683117279525291e+01,8.621999999999999886e+01,0.000000000000000000e+00,3.909351667892841498e+00,0.000000000000000000e+00,-1.000000009976314663e+00,0.000000000000000000e+00,9.635359957374087588e-12,0.000000000000000000e+00 +1.012938914169892790e+01,8.623000000000000398e+01,0.000000000000000000e+00,3.906793698963647365e+00,0.000000000000000000e+00,-1.000000009976290016e+00,0.000000000000000000e+00,-3.678125644858335091e-11,0.000000000000000000e+00 +1.013194878542996236e+01,8.623999999999999488e+01,0.000000000000000000e+00,3.904234055207076448e+00,0.000000000000000000e+00,-1.000000009976384163e+00,0.000000000000000000e+00,7.481468754830148595e-11,0.000000000000000000e+00 +1.013451010728172541e+01,8.625000000000000000e+01,0.000000000000000000e+00,3.901672733329760501e+00,0.000000000000000000e+00,-1.000000009976192539e+00,0.000000000000000000e+00,-6.696849792184665872e-11,0.000000000000000000e+00 +1.013707311055839000e+01,8.626000000000000512e+01,0.000000000000000000e+00,3.899109730027526144e+00,0.000000000000000000e+00,-1.000000009976364179e+00,0.000000000000000000e+00,-1.757525847513514013e-11,0.000000000000000000e+00 +1.013963779857498793e+01,8.626999999999999602e+01,0.000000000000000000e+00,3.896545041985342461e+00,0.000000000000000000e+00,-1.000000009976409254e+00,0.000000000000000000e+00,3.711737190962764732e-11,0.000000000000000000e+00 +1.014220417465745250e+01,8.628000000000000114e+01,0.000000000000000000e+00,3.893978665877273926e+00,0.000000000000000000e+00,-1.000000009976313997e+00,0.000000000000000000e+00,2.351812516107317777e-11,0.000000000000000000e+00 +1.014477224214267714e+01,8.629000000000000625e+01,0.000000000000000000e+00,3.891410598366428886e+00,0.000000000000000000e+00,-1.000000009976253601e+00,0.000000000000000000e+00,-1.745414792409013799e-11,0.000000000000000000e+00 +1.014734200437856160e+01,8.629999999999999716e+01,0.000000000000000000e+00,3.888840836104908494e+00,0.000000000000000000e+00,-1.000000009976298454e+00,0.000000000000000000e+00,-1.726992254138485661e-13,0.000000000000000000e+00 +1.014991346472405986e+01,8.631000000000000227e+01,0.000000000000000000e+00,3.886269375733756082e+00,0.000000000000000000e+00,-1.000000009976298898e+00,0.000000000000000000e+00,-6.135397803467724246e-11,0.000000000000000000e+00 +1.015248662654923884e+01,8.632000000000000739e+01,0.000000000000000000e+00,3.883696213882906534e+00,0.000000000000000000e+00,-1.000000009976456772e+00,0.000000000000000000e+00,4.406627874363000651e-11,0.000000000000000000e+00 +1.015506149323532270e+01,8.632999999999999829e+01,0.000000000000000000e+00,3.881121347171133884e+00,0.000000000000000000e+00,-1.000000009976343307e+00,0.000000000000000000e+00,4.653623103473085710e-12,0.000000000000000000e+00 +1.015763806817474979e+01,8.634000000000000341e+01,0.000000000000000000e+00,3.878544772206001134e+00,0.000000000000000000e+00,-1.000000009976331317e+00,0.000000000000000000e+00,2.531957228387869721e-11,0.000000000000000000e+00 +1.016021635477122231e+01,8.635000000000000853e+01,0.000000000000000000e+00,3.875966485583806076e+00,0.000000000000000000e+00,-1.000000009976266035e+00,0.000000000000000000e+00,-4.363431856260179510e-11,0.000000000000000000e+00 +1.016279635643975965e+01,8.635999999999999943e+01,0.000000000000000000e+00,3.873386483889530219e+00,0.000000000000000000e+00,-1.000000009976378612e+00,0.000000000000000000e+00,2.975823417518735813e-11,0.000000000000000000e+00 +1.016537807660674808e+01,8.637000000000000455e+01,0.000000000000000000e+00,3.870804763696785056e+00,0.000000000000000000e+00,-1.000000009976301785e+00,0.000000000000000000e+00,-8.337065750620722822e-12,0.000000000000000000e+00 +1.016796151870999942e+01,8.637999999999999545e+01,0.000000000000000000e+00,3.868221321567760551e+00,0.000000000000000000e+00,-1.000000009976323323e+00,0.000000000000000000e+00,-3.006211862885335783e-11,0.000000000000000000e+00 +1.017054668619879898e+01,8.639000000000000057e+01,0.000000000000000000e+00,3.865636154053170070e+00,0.000000000000000000e+00,-1.000000009976401039e+00,0.000000000000000000e+00,7.038417951407359198e-12,0.000000000000000000e+00 +1.017313358253396416e+01,8.640000000000000568e+01,0.000000000000000000e+00,3.863049257692197536e+00,0.000000000000000000e+00,-1.000000009976382831e+00,0.000000000000000000e+00,-4.546177005020056352e-12,0.000000000000000000e+00 +1.017572221118789244e+01,8.640999999999999659e+01,0.000000000000000000e+00,3.860460629012443690e+00,0.000000000000000000e+00,-1.000000009976394599e+00,0.000000000000000000e+00,9.429139007174764882e-12,0.000000000000000000e+00 +1.017831257564462177e+01,8.642000000000000171e+01,0.000000000000000000e+00,3.857870264529871029e+00,0.000000000000000000e+00,-1.000000009976370174e+00,0.000000000000000000e+00,-2.664085956880035300e-11,0.000000000000000000e+00 +1.018090467939988386e+01,8.643000000000000682e+01,0.000000000000000000e+00,3.855278160748749627e+00,0.000000000000000000e+00,-1.000000009976439230e+00,0.000000000000000000e+00,6.009426886878493235e-11,0.000000000000000000e+00 +1.018349852596115390e+01,8.643999999999999773e+01,0.000000000000000000e+00,3.852684314161601620e+00,0.000000000000000000e+00,-1.000000009976283355e+00,0.000000000000000000e+00,-1.020573045361581446e-10,0.000000000000000000e+00 +1.018609411884771454e+01,8.645000000000000284e+01,0.000000000000000000e+00,3.850088721249147028e+00,0.000000000000000000e+00,-1.000000009976548254e+00,0.000000000000000000e+00,8.865224119104209945e-11,0.000000000000000000e+00 +1.018869146159070382e+01,8.646000000000000796e+01,0.000000000000000000e+00,3.847491378480245583e+00,0.000000000000000000e+00,-1.000000009976317994e+00,0.000000000000000000e+00,-3.340370489070600415e-11,0.000000000000000000e+00 +1.019129055773317560e+01,8.646999999999999886e+01,0.000000000000000000e+00,3.844892282311844767e+00,0.000000000000000000e+00,-1.000000009976404813e+00,0.000000000000000000e+00,-2.877095670903643538e-11,0.000000000000000000e+00 +1.019389141083015460e+01,8.648000000000000398e+01,0.000000000000000000e+00,3.842291429188918972e+00,0.000000000000000000e+00,-1.000000009976479642e+00,0.000000000000000000e+00,6.518143029544307800e-11,0.000000000000000000e+00 +1.019649402444869324e+01,8.648999999999999488e+01,0.000000000000000000e+00,3.839688815544415768e+00,0.000000000000000000e+00,-1.000000009976310000e+00,0.000000000000000000e+00,-6.360263108176353900e-11,0.000000000000000000e+00 +1.019909840216792851e+01,8.650000000000000000e+01,0.000000000000000000e+00,3.837084437799198611e+00,0.000000000000000000e+00,-1.000000009976475646e+00,0.000000000000000000e+00,4.455980386828219789e-11,0.000000000000000000e+00 +1.020170454757913880e+01,8.651000000000000512e+01,0.000000000000000000e+00,3.834478292361987339e+00,0.000000000000000000e+00,-1.000000009976359516e+00,0.000000000000000000e+00,-1.464451374136337200e-11,0.000000000000000000e+00 +1.020431246428580430e+01,8.651999999999999602e+01,0.000000000000000000e+00,3.831870375629303549e+00,0.000000000000000000e+00,-1.000000009976397708e+00,0.000000000000000000e+00,-4.934907633347132335e-12,0.000000000000000000e+00 +1.020692215590366203e+01,8.653000000000000114e+01,0.000000000000000000e+00,3.829260683985409752e+00,0.000000000000000000e+00,-1.000000009976410587e+00,0.000000000000000000e+00,-2.865398697211769990e-11,0.000000000000000000e+00 +1.020953362606076631e+01,8.654000000000000625e+01,0.000000000000000000e+00,3.826649213802252536e+00,0.000000000000000000e+00,-1.000000009976485416e+00,0.000000000000000000e+00,-5.013152195905877189e-12,0.000000000000000000e+00 +1.021214687839754554e+01,8.654999999999999716e+01,0.000000000000000000e+00,3.824035961439403053e+00,0.000000000000000000e+00,-1.000000009976498516e+00,0.000000000000000000e+00,6.954182679528011482e-11,0.000000000000000000e+00 +1.021476191656686083e+01,8.656000000000000227e+01,0.000000000000000000e+00,3.821420923243998402e+00,0.000000000000000000e+00,-1.000000009976316662e+00,0.000000000000000000e+00,-7.161558588859438968e-11,0.000000000000000000e+00 +1.021737874423407000e+01,8.657000000000000739e+01,0.000000000000000000e+00,3.818804095550682121e+00,0.000000000000000000e+00,-1.000000009976504067e+00,0.000000000000000000e+00,7.801092589480313313e-12,0.000000000000000000e+00 +1.021999736507708434e+01,8.657999999999999829e+01,0.000000000000000000e+00,3.816185474681542455e+00,0.000000000000000000e+00,-1.000000009976483639e+00,0.000000000000000000e+00,1.923514909025114735e-11,0.000000000000000000e+00 +1.022261778278642907e+01,8.659000000000000341e+01,0.000000000000000000e+00,3.813565056946055076e+00,0.000000000000000000e+00,-1.000000009976433235e+00,0.000000000000000000e+00,-1.041541302103354343e-11,0.000000000000000000e+00 +1.022524000106530373e+01,8.660000000000000853e+01,0.000000000000000000e+00,3.810942838641020458e+00,0.000000000000000000e+00,-1.000000009976460547e+00,0.000000000000000000e+00,-4.230996484989613608e-13,0.000000000000000000e+00 +1.022786402362964253e+01,8.660999999999999943e+01,0.000000000000000000e+00,3.808318816050503042e+00,0.000000000000000000e+00,-1.000000009976461657e+00,0.000000000000000000e+00,-7.525988157752622323e-12,0.000000000000000000e+00 +1.023048985420817836e+01,8.662000000000000455e+01,0.000000000000000000e+00,3.805692985445770393e+00,0.000000000000000000e+00,-1.000000009976481419e+00,0.000000000000000000e+00,3.092822959234524713e-11,0.000000000000000000e+00 +1.023311749654250313e+01,8.662999999999999545e+01,0.000000000000000000e+00,3.803065343085231031e+00,0.000000000000000000e+00,-1.000000009976400150e+00,0.000000000000000000e+00,-8.731614464241596651e-11,0.000000000000000000e+00 +1.023574695438712823e+01,8.664000000000000057e+01,0.000000000000000000e+00,3.800435885214372700e+00,0.000000000000000000e+00,-1.000000009976629745e+00,0.000000000000000000e+00,6.978774174265037329e-11,0.000000000000000000e+00 +1.023837823150955195e+01,8.665000000000000568e+01,0.000000000000000000e+00,3.797804608065698417e+00,0.000000000000000000e+00,-1.000000009976446114e+00,0.000000000000000000e+00,2.799696318950965843e-11,0.000000000000000000e+00 +1.024101133169031463e+01,8.665999999999999659e+01,0.000000000000000000e+00,3.795171507858666526e+00,0.000000000000000000e+00,-1.000000009976372395e+00,0.000000000000000000e+00,-5.182588752224059696e-11,0.000000000000000000e+00 +1.024364625872306966e+01,8.667000000000000171e+01,0.000000000000000000e+00,3.792536580799624080e+00,0.000000000000000000e+00,-1.000000009976508952e+00,0.000000000000000000e+00,-1.600013344820025287e-11,0.000000000000000000e+00 +1.024628301641464390e+01,8.668000000000000682e+01,0.000000000000000000e+00,3.789899823081744223e+00,0.000000000000000000e+00,-1.000000009976551141e+00,0.000000000000000000e+00,2.692885788549222224e-11,0.000000000000000000e+00 +1.024892160858510159e+01,8.668999999999999773e+01,0.000000000000000000e+00,3.787261230884963137e+00,0.000000000000000000e+00,-1.000000009976480086e+00,0.000000000000000000e+00,-3.649683609117269280e-11,0.000000000000000000e+00 +1.025156203906780839e+01,8.670000000000000284e+01,0.000000000000000000e+00,3.784620800375914751e+00,0.000000000000000000e+00,-1.000000009976576454e+00,0.000000000000000000e+00,5.731218579399785668e-11,0.000000000000000000e+00 +1.025420431170949698e+01,8.671000000000000796e+01,0.000000000000000000e+00,3.781978527707865023e+00,0.000000000000000000e+00,-1.000000009976425019e+00,0.000000000000000000e+00,-6.961676123284509868e-11,0.000000000000000000e+00 +1.025684843037033467e+01,8.671999999999999886e+01,0.000000000000000000e+00,3.779334409020648433e+00,0.000000000000000000e+00,-1.000000009976609094e+00,0.000000000000000000e+00,9.138679083305870238e-11,0.000000000000000000e+00 +1.025949439892398551e+01,8.673000000000000398e+01,0.000000000000000000e+00,3.776688440440599592e+00,0.000000000000000000e+00,-1.000000009976367288e+00,0.000000000000000000e+00,-9.878628987800622017e-11,0.000000000000000000e+00 +1.026214222125767961e+01,8.673999999999999488e+01,0.000000000000000000e+00,3.774040618080490628e+00,0.000000000000000000e+00,-1.000000009976628856e+00,0.000000000000000000e+00,5.019652094496094011e-11,0.000000000000000000e+00 +1.026479190127227525e+01,8.675000000000000000e+01,0.000000000000000000e+00,3.771390938039460128e+00,0.000000000000000000e+00,-1.000000009976495852e+00,0.000000000000000000e+00,2.101916697245586089e-11,0.000000000000000000e+00 +1.026744344288233179e+01,8.676000000000000512e+01,0.000000000000000000e+00,3.768739396402950970e+00,0.000000000000000000e+00,-1.000000009976440118e+00,0.000000000000000000e+00,-7.163249822907781882e-11,0.000000000000000000e+00 +1.027009685001617179e+01,8.676999999999999602e+01,0.000000000000000000e+00,3.766085989242639265e+00,0.000000000000000000e+00,-1.000000009976630189e+00,0.000000000000000000e+00,9.951244999581422349e-12,0.000000000000000000e+00 +1.027275212661595383e+01,8.678000000000000114e+01,0.000000000000000000e+00,3.763430712616367302e+00,0.000000000000000000e+00,-1.000000009976603765e+00,0.000000000000000000e+00,6.058458771655819891e-11,0.000000000000000000e+00 +1.027540927663773473e+01,8.679000000000000625e+01,0.000000000000000000e+00,3.760773562568076933e+00,0.000000000000000000e+00,-1.000000009976442783e+00,0.000000000000000000e+00,-6.196141340953949290e-11,0.000000000000000000e+00 +1.027806830405154415e+01,8.679999999999999716e+01,0.000000000000000000e+00,3.758114535127739408e+00,0.000000000000000000e+00,-1.000000009976607540e+00,0.000000000000000000e+00,6.467135193419788550e-11,0.000000000000000000e+00 +1.028072921284145202e+01,8.681000000000000227e+01,0.000000000000000000e+00,3.755453626311285209e+00,0.000000000000000000e+00,-1.000000009976435456e+00,0.000000000000000000e+00,-7.846794019792201394e-11,0.000000000000000000e+00 +1.028339200700563438e+01,8.682000000000000739e+01,0.000000000000000000e+00,3.752790832120537434e+00,0.000000000000000000e+00,-1.000000009976644400e+00,0.000000000000000000e+00,5.599688355639733693e-11,0.000000000000000000e+00 +1.028605669055644967e+01,8.682999999999999829e+01,0.000000000000000000e+00,3.750126148543138083e+00,0.000000000000000000e+00,-1.000000009976495186e+00,0.000000000000000000e+00,-4.846286524200730064e-11,0.000000000000000000e+00 +1.028872326752050270e+01,8.684000000000000341e+01,0.000000000000000000e+00,3.747459571552481439e+00,0.000000000000000000e+00,-1.000000009976624415e+00,0.000000000000000000e+00,3.161992084144011623e-11,0.000000000000000000e+00 +1.029139174193872286e+01,8.685000000000000853e+01,0.000000000000000000e+00,3.744791097107639466e+00,0.000000000000000000e+00,-1.000000009976540039e+00,0.000000000000000000e+00,-2.785560709941534995e-11,0.000000000000000000e+00 +1.029406211786642800e+01,8.685999999999999943e+01,0.000000000000000000e+00,3.742120721153293417e+00,0.000000000000000000e+00,-1.000000009976614423e+00,0.000000000000000000e+00,1.279613284349794594e-11,0.000000000000000000e+00 +1.029673439937340085e+01,8.687000000000000455e+01,0.000000000000000000e+00,3.739448439619659670e+00,0.000000000000000000e+00,-1.000000009976580229e+00,0.000000000000000000e+00,2.250178992328883306e-11,0.000000000000000000e+00 +1.029940859054396185e+01,8.687999999999999545e+01,0.000000000000000000e+00,3.736774248422419120e+00,0.000000000000000000e+00,-1.000000009976520055e+00,0.000000000000000000e+00,-6.364033408123849201e-11,0.000000000000000000e+00 +1.030208469547703842e+01,8.689000000000000057e+01,0.000000000000000000e+00,3.734098143462643460e+00,0.000000000000000000e+00,-1.000000009976690363e+00,0.000000000000000000e+00,6.517011687549339708e-11,0.000000000000000000e+00 +1.030476271828624313e+01,8.690000000000000568e+01,0.000000000000000000e+00,3.731420120626721459e+00,0.000000000000000000e+00,-1.000000009976515836e+00,0.000000000000000000e+00,-1.897360507870969296e-11,0.000000000000000000e+00 +1.030744266309994117e+01,8.690999999999999659e+01,0.000000000000000000e+00,3.728740175786287470e+00,0.000000000000000000e+00,-1.000000009976566684e+00,0.000000000000000000e+00,3.808554540322566187e-12,0.000000000000000000e+00 +1.031012453406132856e+01,8.692000000000000171e+01,0.000000000000000000e+00,3.726058304798144150e+00,0.000000000000000000e+00,-1.000000009976556470e+00,0.000000000000000000e+00,-3.541062897246773110e-11,0.000000000000000000e+00 +1.031280833532850671e+01,8.693000000000000682e+01,0.000000000000000000e+00,3.723374503504190081e+00,0.000000000000000000e+00,-1.000000009976651505e+00,0.000000000000000000e+00,8.515578772370781836e-12,0.000000000000000000e+00 +1.031549407107455885e+01,8.693999999999999773e+01,0.000000000000000000e+00,3.720688767731343383e+00,0.000000000000000000e+00,-1.000000009976628634e+00,0.000000000000000000e+00,-2.015827636650974624e-11,0.000000000000000000e+00 +1.031818174548762101e+01,8.695000000000000284e+01,0.000000000000000000e+00,3.718001093291467107e+00,0.000000000000000000e+00,-1.000000009976682813e+00,0.000000000000000000e+00,3.748051860773151978e-11,0.000000000000000000e+00 +1.032087136277096207e+01,8.696000000000000796e+01,0.000000000000000000e+00,3.715311475981291967e+00,0.000000000000000000e+00,-1.000000009976582005e+00,0.000000000000000000e+00,-2.054162523455675170e-11,0.000000000000000000e+00 +1.032356292714306001e+01,8.696999999999999886e+01,0.000000000000000000e+00,3.712619911582340837e+00,0.000000000000000000e+00,-1.000000009976637294e+00,0.000000000000000000e+00,4.138323451950609472e-11,0.000000000000000000e+00 +1.032625644283767841e+01,8.698000000000000398e+01,0.000000000000000000e+00,3.709926395860850157e+00,0.000000000000000000e+00,-1.000000009976525828e+00,0.000000000000000000e+00,-8.320068322785665239e-11,0.000000000000000000e+00 +1.032895191410394276e+01,8.698999999999999488e+01,0.000000000000000000e+00,3.707230924567693986e+00,0.000000000000000000e+00,-1.000000009976750093e+00,0.000000000000000000e+00,4.189938486398494623e-11,0.000000000000000000e+00 +1.033164934520642220e+01,8.700000000000000000e+01,0.000000000000000000e+00,3.704533493438303626e+00,0.000000000000000000e+00,-1.000000009976637072e+00,0.000000000000000000e+00,7.649916586633103238e-12,0.000000000000000000e+00 +1.033434874042520235e+01,8.701000000000000512e+01,0.000000000000000000e+00,3.701834098192592126e+00,0.000000000000000000e+00,-1.000000009976616422e+00,0.000000000000000000e+00,2.605652158764851995e-11,0.000000000000000000e+00 +1.033705010405597235e+01,8.701999999999999602e+01,0.000000000000000000e+00,3.699132734534872124e+00,0.000000000000000000e+00,-1.000000009976546034e+00,0.000000000000000000e+00,-4.550403464991957505e-11,0.000000000000000000e+00 +1.033975344041009770e+01,8.703000000000000114e+01,0.000000000000000000e+00,3.696429398153777690e+00,0.000000000000000000e+00,-1.000000009976669046e+00,0.000000000000000000e+00,-3.414412374240719472e-11,0.000000000000000000e+00 +1.034245875381470192e+01,8.704000000000000625e+01,0.000000000000000000e+00,3.693724084722183054e+00,0.000000000000000000e+00,-1.000000009976761417e+00,0.000000000000000000e+00,6.233303438715995962e-11,0.000000000000000000e+00 +1.034516604861275191e+01,8.704999999999999716e+01,0.000000000000000000e+00,3.691016789897123118e+00,0.000000000000000000e+00,-1.000000009976592663e+00,0.000000000000000000e+00,-4.335527230238285594e-11,0.000000000000000000e+00 +1.034787532916313424e+01,8.706000000000000227e+01,0.000000000000000000e+00,3.688307509319712185e+00,0.000000000000000000e+00,-1.000000009976710125e+00,0.000000000000000000e+00,4.053895479557162456e-11,0.000000000000000000e+00 +1.035058659984073692e+01,8.707000000000000739e+01,0.000000000000000000e+00,3.685596238615060027e+00,0.000000000000000000e+00,-1.000000009976600213e+00,0.000000000000000000e+00,-6.465097409660052787e-12,0.000000000000000000e+00 +1.035329986503653465e+01,8.707999999999999829e+01,0.000000000000000000e+00,3.682882973392192394e+00,0.000000000000000000e+00,-1.000000009976617754e+00,0.000000000000000000e+00,-6.656601359769631035e-11,0.000000000000000000e+00 +1.035601512915767231e+01,8.709000000000000341e+01,0.000000000000000000e+00,3.680167709243965746e+00,0.000000000000000000e+00,-1.000000009976798498e+00,0.000000000000000000e+00,5.180803181260960705e-11,0.000000000000000000e+00 +1.035873239662754308e+01,8.710000000000000853e+01,0.000000000000000000e+00,3.677450441746984655e+00,0.000000000000000000e+00,-1.000000009976657722e+00,0.000000000000000000e+00,1.461638874539672835e-11,0.000000000000000000e+00 +1.036145167188587912e+01,8.710999999999999943e+01,0.000000000000000000e+00,3.674731166461519205e+00,0.000000000000000000e+00,-1.000000009976617976e+00,0.000000000000000000e+00,-1.436079444910259707e-11,0.000000000000000000e+00 +1.036417295938883143e+01,8.712000000000000455e+01,0.000000000000000000e+00,3.672009878931417948e+00,0.000000000000000000e+00,-1.000000009976657056e+00,0.000000000000000000e+00,-3.522311925903959597e-11,0.000000000000000000e+00 +1.036689626360905514e+01,8.712999999999999545e+01,0.000000000000000000e+00,3.669286574684023972e+00,0.000000000000000000e+00,-1.000000009976752979e+00,0.000000000000000000e+00,2.908640677561794674e-11,0.000000000000000000e+00 +1.036962158903580011e+01,8.714000000000000057e+01,0.000000000000000000e+00,3.666561249230089192e+00,0.000000000000000000e+00,-1.000000009976673709e+00,0.000000000000000000e+00,-2.556400052218794298e-11,0.000000000000000000e+00 +1.037234894017499087e+01,8.715000000000000568e+01,0.000000000000000000e+00,3.663833898063688643e+00,0.000000000000000000e+00,-1.000000009976743431e+00,0.000000000000000000e+00,3.400574420699124618e-11,0.000000000000000000e+00 +1.037507832154931720e+01,8.715999999999999659e+01,0.000000000000000000e+00,3.661104516662132102e+00,0.000000000000000000e+00,-1.000000009976650617e+00,0.000000000000000000e+00,-1.731537717761875614e-11,0.000000000000000000e+00 +1.037780973769832116e+01,8.717000000000000171e+01,0.000000000000000000e+00,3.658373100485878382e+00,0.000000000000000000e+00,-1.000000009976697912e+00,0.000000000000000000e+00,-2.729401952812915618e-11,0.000000000000000000e+00 +1.038054319317848240e+01,8.718000000000000682e+01,0.000000000000000000e+00,3.655639644978445624e+00,0.000000000000000000e+00,-1.000000009976772519e+00,0.000000000000000000e+00,5.755059780487221690e-11,0.000000000000000000e+00 +1.038327869256331226e+01,8.718999999999999773e+01,0.000000000000000000e+00,3.652904145566323812e+00,0.000000000000000000e+00,-1.000000009976615090e+00,0.000000000000000000e+00,-4.452981041493746085e-11,0.000000000000000000e+00 +1.038601624044343907e+01,8.720000000000000284e+01,0.000000000000000000e+00,3.650166597658885959e+00,0.000000000000000000e+00,-1.000000009976736992e+00,0.000000000000000000e+00,3.241999200350852374e-13,0.000000000000000000e+00 +1.038875584142669695e+01,8.721000000000000796e+01,0.000000000000000000e+00,3.647426996648296171e+00,0.000000000000000000e+00,-1.000000009976736104e+00,0.000000000000000000e+00,1.401112271582139525e-11,0.000000000000000000e+00 +1.039149750013821816e+01,8.721999999999999886e+01,0.000000000000000000e+00,3.644685337909421730e+00,0.000000000000000000e+00,-1.000000009976697690e+00,0.000000000000000000e+00,-3.933113999430257418e-11,0.000000000000000000e+00 +1.039424122122052552e+01,8.723000000000000398e+01,0.000000000000000000e+00,3.641941616799740711e+00,0.000000000000000000e+00,-1.000000009976805604e+00,0.000000000000000000e+00,5.013775622266434614e-12,0.000000000000000000e+00 +1.039698700933362119e+01,8.723999999999999488e+01,0.000000000000000000e+00,3.639195828659250065e+00,0.000000000000000000e+00,-1.000000009976791837e+00,0.000000000000000000e+00,4.104964104098883109e-11,0.000000000000000000e+00 +1.039973486915508261e+01,8.725000000000000000e+01,0.000000000000000000e+00,3.636447968810374576e+00,0.000000000000000000e+00,-1.000000009976679038e+00,0.000000000000000000e+00,-1.219255015373047538e-11,0.000000000000000000e+00 +1.040248480538014952e+01,8.726000000000000512e+01,0.000000000000000000e+00,3.633698032557873159e+00,0.000000000000000000e+00,-1.000000009976712567e+00,0.000000000000000000e+00,-3.308056480630323269e-11,0.000000000000000000e+00 +1.040523682272182171e+01,8.726999999999999602e+01,0.000000000000000000e+00,3.630946015188744713e+00,0.000000000000000000e+00,-1.000000009976803605e+00,0.000000000000000000e+00,8.223566129156356043e-12,0.000000000000000000e+00 +1.040799092591095487e+01,8.728000000000000114e+01,0.000000000000000000e+00,3.628191911972134864e+00,0.000000000000000000e+00,-1.000000009976780957e+00,0.000000000000000000e+00,5.091521178815814589e-11,0.000000000000000000e+00 +1.041074711969635125e+01,8.729000000000000625e+01,0.000000000000000000e+00,3.625435718159241372e+00,0.000000000000000000e+00,-1.000000009976640625e+00,0.000000000000000000e+00,-5.409656728356826882e-11,0.000000000000000000e+00 +1.041350540884485554e+01,8.729999999999999716e+01,0.000000000000000000e+00,3.622677428983218206e+00,0.000000000000000000e+00,-1.000000009976789839e+00,0.000000000000000000e+00,-1.874242629880317913e-11,0.000000000000000000e+00 +1.041626579814145614e+01,8.731000000000000227e+01,0.000000000000000000e+00,3.619917039659078295e+00,0.000000000000000000e+00,-1.000000009976841575e+00,0.000000000000000000e+00,6.028372866993666479e-12,0.000000000000000000e+00 +1.041902829238937400e+01,8.732000000000000739e+01,0.000000000000000000e+00,3.617154545383598929e+00,0.000000000000000000e+00,-1.000000009976824922e+00,0.000000000000000000e+00,7.469477763437086134e-11,0.000000000000000000e+00 +1.042179289641016737e+01,8.732999999999999829e+01,0.000000000000000000e+00,3.614389941335223178e+00,0.000000000000000000e+00,-1.000000009976618420e+00,0.000000000000000000e+00,-7.632305530269161081e-11,0.000000000000000000e+00 +1.042455961504382600e+01,8.734000000000000341e+01,0.000000000000000000e+00,3.611623222673962186e+00,0.000000000000000000e+00,-1.000000009976829585e+00,0.000000000000000000e+00,1.660018804846586093e-11,0.000000000000000000e+00 +1.042732845314886880e+01,8.735000000000000853e+01,0.000000000000000000e+00,3.608854384541294369e+00,0.000000000000000000e+00,-1.000000009976783621e+00,0.000000000000000000e+00,-2.115502345565237961e-11,0.000000000000000000e+00 +1.043009941560244869e+01,8.735999999999999943e+01,0.000000000000000000e+00,3.606083422060069488e+00,0.000000000000000000e+00,-1.000000009976842241e+00,0.000000000000000000e+00,4.772239757917076391e-11,0.000000000000000000e+00 +1.043287250730044669e+01,8.737000000000000455e+01,0.000000000000000000e+00,3.603310330334405620e+00,0.000000000000000000e+00,-1.000000009976709903e+00,0.000000000000000000e+00,-2.656317454155005156e-11,0.000000000000000000e+00 +1.043564773315757499e+01,8.737999999999999545e+01,0.000000000000000000e+00,3.600535104449590129e+00,0.000000000000000000e+00,-1.000000009976783621e+00,0.000000000000000000e+00,-5.532397411920611856e-11,0.000000000000000000e+00 +1.043842509810747998e+01,8.739000000000000057e+01,0.000000000000000000e+00,3.597757739471976191e+00,0.000000000000000000e+00,-1.000000009976937276e+00,0.000000000000000000e+00,6.806310168872285205e-11,0.000000000000000000e+00 +1.044120460710284348e+01,8.740000000000000568e+01,0.000000000000000000e+00,3.594978230448881984e+00,0.000000000000000000e+00,-1.000000009976748094e+00,0.000000000000000000e+00,-3.113157531487029840e-11,0.000000000000000000e+00 +1.044398626511548578e+01,8.740999999999999659e+01,0.000000000000000000e+00,3.592196572408488553e+00,0.000000000000000000e+00,-1.000000009976834692e+00,0.000000000000000000e+00,-1.914306884960386660e-12,0.000000000000000000e+00 +1.044677007713646688e+01,8.742000000000000171e+01,0.000000000000000000e+00,3.589412760359733223e+00,0.000000000000000000e+00,-1.000000009976840021e+00,0.000000000000000000e+00,2.646072331112650563e-11,0.000000000000000000e+00 +1.044955604817619665e+01,8.743000000000000682e+01,0.000000000000000000e+00,3.586626789292207906e+00,0.000000000000000000e+00,-1.000000009976766302e+00,0.000000000000000000e+00,-3.703218747254936486e-11,0.000000000000000000e+00 +1.045234418326453429e+01,8.743999999999999773e+01,0.000000000000000000e+00,3.583838654176052962e+00,0.000000000000000000e+00,-1.000000009976869553e+00,0.000000000000000000e+00,4.058437394216045726e-11,0.000000000000000000e+00 +1.045513448745089846e+01,8.745000000000000284e+01,0.000000000000000000e+00,3.581048349961850619e+00,0.000000000000000000e+00,-1.000000009976756310e+00,0.000000000000000000e+00,-3.936004707119336250e-11,0.000000000000000000e+00 +1.045792696580436854e+01,8.746000000000000796e+01,0.000000000000000000e+00,3.578255871580520164e+00,0.000000000000000000e+00,-1.000000009976866222e+00,0.000000000000000000e+00,3.424434692814069233e-11,0.000000000000000000e+00 +1.046072162341379830e+01,8.746999999999999886e+01,0.000000000000000000e+00,3.575461213943208261e+00,0.000000000000000000e+00,-1.000000009976770521e+00,0.000000000000000000e+00,-6.970546242084677574e-11,0.000000000000000000e+00 +1.046351846538792074e+01,8.748000000000000398e+01,0.000000000000000000e+00,3.572664371941183248e+00,0.000000000000000000e+00,-1.000000009976965476e+00,0.000000000000000000e+00,4.109246597806610306e-11,0.000000000000000000e+00 +1.046631749685545465e+01,8.748999999999999488e+01,0.000000000000000000e+00,3.569865340445723678e+00,0.000000000000000000e+00,-1.000000009976850457e+00,0.000000000000000000e+00,6.103553911492214937e-12,0.000000000000000000e+00 +1.046911872296522006e+01,8.750000000000000000e+01,0.000000000000000000e+00,3.567064114308011735e+00,0.000000000000000000e+00,-1.000000009976833359e+00,0.000000000000000000e+00,1.869231727128918993e-11,0.000000000000000000e+00 +1.047192214888624306e+01,8.751000000000000512e+01,0.000000000000000000e+00,3.564260688359019991e+00,0.000000000000000000e+00,-1.000000009976780957e+00,0.000000000000000000e+00,-2.350531823497601391e-11,0.000000000000000000e+00 +1.047472777980786951e+01,8.751999999999999602e+01,0.000000000000000000e+00,3.561455057409401714e+00,0.000000000000000000e+00,-1.000000009976846904e+00,0.000000000000000000e+00,-9.410542386050630702e-12,0.000000000000000000e+00 +1.047753562093988045e+01,8.753000000000000114e+01,0.000000000000000000e+00,3.558647216249378076e+00,0.000000000000000000e+00,-1.000000009976873327e+00,0.000000000000000000e+00,-7.901784151996556165e-12,0.000000000000000000e+00 +1.048034567751259694e+01,8.754000000000000625e+01,0.000000000000000000e+00,3.555837159648626233e+00,0.000000000000000000e+00,-1.000000009976895532e+00,0.000000000000000000e+00,1.476466835135899089e-11,0.000000000000000000e+00 +1.048315795477700085e+01,8.754999999999999716e+01,0.000000000000000000e+00,3.553024882356165204e+00,0.000000000000000000e+00,-1.000000009976854010e+00,0.000000000000000000e+00,-2.911151723215932206e-11,0.000000000000000000e+00 +1.048597245800484501e+01,8.756000000000000227e+01,0.000000000000000000e+00,3.550210379100241731e+00,0.000000000000000000e+00,-1.000000009976935944e+00,0.000000000000000000e+00,4.477572746639373750e-11,0.000000000000000000e+00 +1.048878919248877040e+01,8.757000000000000739e+01,0.000000000000000000e+00,3.547393644588214379e+00,0.000000000000000000e+00,-1.000000009976809823e+00,0.000000000000000000e+00,-3.465790329435090679e-11,0.000000000000000000e+00 +1.049160816354242165e+01,8.757999999999999829e+01,0.000000000000000000e+00,3.544574673506438955e+00,0.000000000000000000e+00,-1.000000009976907522e+00,0.000000000000000000e+00,1.487531460881357165e-11,0.000000000000000000e+00 +1.049442937650056429e+01,8.759000000000000341e+01,0.000000000000000000e+00,3.541753460520149499e+00,0.000000000000000000e+00,-1.000000009976865556e+00,0.000000000000000000e+00,-3.326587258545339621e-11,0.000000000000000000e+00 +1.049725283671920195e+01,8.760000000000000853e+01,0.000000000000000000e+00,3.538930000273342813e+00,0.000000000000000000e+00,-1.000000009976959481e+00,0.000000000000000000e+00,3.638255452746003685e-11,0.000000000000000000e+00 +1.050007854957569542e+01,8.760999999999999943e+01,0.000000000000000000e+00,3.536104287388658118e+00,0.000000000000000000e+00,-1.000000009976856674e+00,0.000000000000000000e+00,-1.005021285717662735e-11,0.000000000000000000e+00 +1.050290652046887985e+01,8.762000000000000455e+01,0.000000000000000000e+00,3.533276316467259370e+00,0.000000000000000000e+00,-1.000000009976885096e+00,0.000000000000000000e+00,-1.929980561701118399e-11,0.000000000000000000e+00 +1.050573675481918912e+01,8.762999999999999545e+01,0.000000000000000000e+00,3.530446082088713133e+00,0.000000000000000000e+00,-1.000000009976939719e+00,0.000000000000000000e+00,4.836764838975184904e-11,0.000000000000000000e+00 +1.050856925806877307e+01,8.764000000000000057e+01,0.000000000000000000e+00,3.527613578810868677e+00,0.000000000000000000e+00,-1.000000009976802717e+00,0.000000000000000000e+00,-4.456906235946487609e-11,0.000000000000000000e+00 +1.051140403568162363e+01,8.765000000000000568e+01,0.000000000000000000e+00,3.524778801169736298e+00,0.000000000000000000e+00,-1.000000009976929061e+00,0.000000000000000000e+00,-3.694146309190217177e-11,0.000000000000000000e+00 +1.051424109314369204e+01,8.765999999999999659e+01,0.000000000000000000e+00,3.521941743679362524e+00,0.000000000000000000e+00,-1.000000009977033866e+00,0.000000000000000000e+00,5.583681084136016023e-11,0.000000000000000000e+00 +1.051708043596301856e+01,8.767000000000000171e+01,0.000000000000000000e+00,3.519102400831708444e+00,0.000000000000000000e+00,-1.000000009976875326e+00,0.000000000000000000e+00,1.328376093881789912e-12,0.000000000000000000e+00 +1.051992206966985144e+01,8.768000000000000682e+01,0.000000000000000000e+00,3.516260767096524908e+00,0.000000000000000000e+00,-1.000000009976871551e+00,0.000000000000000000e+00,-4.395716705907978115e-11,0.000000000000000000e+00 +1.052276599981677840e+01,8.768999999999999773e+01,0.000000000000000000e+00,3.513416836921225084e+00,0.000000000000000000e+00,-1.000000009976996562e+00,0.000000000000000000e+00,2.496432811171605152e-11,0.000000000000000000e+00 +1.052561223197884743e+01,8.770000000000000284e+01,0.000000000000000000e+00,3.510570604730759214e+00,0.000000000000000000e+00,-1.000000009976925508e+00,0.000000000000000000e+00,-1.138074763963749710e-11,0.000000000000000000e+00 +1.052846077175369821e+01,8.771000000000000796e+01,0.000000000000000000e+00,3.507722064927488059e+00,0.000000000000000000e+00,-1.000000009976957926e+00,0.000000000000000000e+00,1.861501116623797237e-11,0.000000000000000000e+00 +1.053131162476169003e+01,8.771999999999999886e+01,0.000000000000000000e+00,3.504871211891052774e+00,0.000000000000000000e+00,-1.000000009976904858e+00,0.000000000000000000e+00,-3.509852223444164898e-11,0.000000000000000000e+00 +1.053416479664602967e+01,8.773000000000000398e+01,0.000000000000000000e+00,3.502018039978247010e+00,0.000000000000000000e+00,-1.000000009977005000e+00,0.000000000000000000e+00,1.353031329101506141e-11,0.000000000000000000e+00 +1.053702029307290111e+01,8.773999999999999488e+01,0.000000000000000000e+00,3.499162543522885471e+00,0.000000000000000000e+00,-1.000000009976966364e+00,0.000000000000000000e+00,3.224426182861778146e-11,0.000000000000000000e+00 +1.053987811973160049e+01,8.775000000000000000e+01,0.000000000000000000e+00,3.496304716835674231e+00,0.000000000000000000e+00,-1.000000009976874216e+00,0.000000000000000000e+00,-4.518273189365290377e-11,0.000000000000000000e+00 +1.054273828233466226e+01,8.776000000000000512e+01,0.000000000000000000e+00,3.493444554204077512e+00,0.000000000000000000e+00,-1.000000009977003446e+00,0.000000000000000000e+00,5.173922440824528975e-11,0.000000000000000000e+00 +1.054560078661799594e+01,8.776999999999999602e+01,0.000000000000000000e+00,3.490582049892184013e+00,0.000000000000000000e+00,-1.000000009976855342e+00,0.000000000000000000e+00,-4.510877789159487115e-11,0.000000000000000000e+00 +1.054846563834102291e+01,8.778000000000000114e+01,0.000000000000000000e+00,3.487717198140575015e+00,0.000000000000000000e+00,-1.000000009976984572e+00,0.000000000000000000e+00,-3.926353951871401124e-11,0.000000000000000000e+00 +1.055133284328680610e+01,8.779000000000000625e+01,0.000000000000000000e+00,3.484849993166186266e+00,0.000000000000000000e+00,-1.000000009977097148e+00,0.000000000000000000e+00,5.408807058289530899e-11,0.000000000000000000e+00 +1.055420240726218850e+01,8.779999999999999716e+01,0.000000000000000000e+00,3.481980429162174318e+00,0.000000000000000000e+00,-1.000000009976941939e+00,0.000000000000000000e+00,2.110713064687516198e-11,0.000000000000000000e+00 +1.055707433609793000e+01,8.781000000000000227e+01,0.000000000000000000e+00,3.479108500297779294e+00,0.000000000000000000e+00,-1.000000009976881321e+00,0.000000000000000000e+00,-6.543221297566278739e-11,0.000000000000000000e+00 +1.055994863564884767e+01,8.782000000000000739e+01,0.000000000000000000e+00,3.476234200718185008e+00,0.000000000000000000e+00,-1.000000009977069393e+00,0.000000000000000000e+00,4.554086393379572703e-11,0.000000000000000000e+00 +1.056282531179395079e+01,8.782999999999999829e+01,0.000000000000000000e+00,3.473357524544380404e+00,0.000000000000000000e+00,-1.000000009976938387e+00,0.000000000000000000e+00,-2.020649584168205150e-11,0.000000000000000000e+00 +1.056570437043658472e+01,8.784000000000000341e+01,0.000000000000000000e+00,3.470478465873021445e+00,0.000000000000000000e+00,-1.000000009976996562e+00,0.000000000000000000e+00,-2.581513416516272959e-11,0.000000000000000000e+00 +1.056858581750457127e+01,8.785000000000000853e+01,0.000000000000000000e+00,3.467597018776286788e+00,0.000000000000000000e+00,-1.000000009977070947e+00,0.000000000000000000e+00,1.778610395269547039e-11,0.000000000000000000e+00 +1.057146965895034896e+01,8.785999999999999943e+01,0.000000000000000000e+00,3.464713177301737446e+00,0.000000000000000000e+00,-1.000000009977019655e+00,0.000000000000000000e+00,1.607880615441954687e-11,0.000000000000000000e+00 +1.057435590075111698e+01,8.787000000000000455e+01,0.000000000000000000e+00,3.461826935472173350e+00,0.000000000000000000e+00,-1.000000009976973248e+00,0.000000000000000000e+00,4.996419962337378844e-12,0.000000000000000000e+00 +1.057724454890898258e+01,8.787999999999999545e+01,0.000000000000000000e+00,3.458938287285488133e+00,0.000000000000000000e+00,-1.000000009976958815e+00,0.000000000000000000e+00,-8.141209005879928192e-12,0.000000000000000000e+00 +1.058013560945110321e+01,8.789000000000000057e+01,0.000000000000000000e+00,3.456047226714523912e+00,0.000000000000000000e+00,-1.000000009976982351e+00,0.000000000000000000e+00,-4.328117055567551576e-11,0.000000000000000000e+00 +1.058302908842983392e+01,8.790000000000000568e+01,0.000000000000000000e+00,3.453153747706924737e+00,0.000000000000000000e+00,-1.000000009977107585e+00,0.000000000000000000e+00,6.571083148243138523e-11,0.000000000000000000e+00 +1.058592499192287661e+01,8.790999999999999659e+01,0.000000000000000000e+00,3.450257844184988709e+00,0.000000000000000000e+00,-1.000000009976917292e+00,0.000000000000000000e+00,-6.948628038907022556e-11,0.000000000000000000e+00 +1.058882332603342746e+01,8.792000000000000171e+01,0.000000000000000000e+00,3.447359510045520548e+00,0.000000000000000000e+00,-1.000000009977118687e+00,0.000000000000000000e+00,3.934503363475000059e-11,0.000000000000000000e+00 +1.059172409689032790e+01,8.793000000000000682e+01,0.000000000000000000e+00,3.444458739159678373e+00,0.000000000000000000e+00,-1.000000009977004556e+00,0.000000000000000000e+00,1.208421098269305800e-11,0.000000000000000000e+00 +1.059462731064821384e+01,8.793999999999999773e+01,0.000000000000000000e+00,3.441555525372826718e+00,0.000000000000000000e+00,-1.000000009976969473e+00,0.000000000000000000e+00,-2.353670817833621080e-11,0.000000000000000000e+00 +1.059753297348767020e+01,8.795000000000000284e+01,0.000000000000000000e+00,3.438649862504381094e+00,0.000000000000000000e+00,-1.000000009977037863e+00,0.000000000000000000e+00,-1.275101195826148467e-11,0.000000000000000000e+00 +1.060044109161538195e+01,8.796000000000000796e+01,0.000000000000000000e+00,3.435741744347655668e+00,0.000000000000000000e+00,-1.000000009977074944e+00,0.000000000000000000e+00,-2.410725821664037480e-11,0.000000000000000000e+00 +1.060335167126428857e+01,8.796999999999999886e+01,0.000000000000000000e+00,3.432831164669709167e+00,0.000000000000000000e+00,-1.000000009977145110e+00,0.000000000000000000e+00,6.692481596859433159e-11,0.000000000000000000e+00 +1.060626471869374576e+01,8.798000000000000398e+01,0.000000000000000000e+00,3.429918117211188555e+00,0.000000000000000000e+00,-1.000000009976950155e+00,0.000000000000000000e+00,-4.965598182464103842e-11,0.000000000000000000e+00 +1.060918024018967287e+01,8.798999999999999488e+01,0.000000000000000000e+00,3.427002595686173159e+00,0.000000000000000000e+00,-1.000000009977094928e+00,0.000000000000000000e+00,3.485139263457764612e-11,0.000000000000000000e+00 +1.061209824206471808e+01,8.800000000000000000e+01,0.000000000000000000e+00,3.424084593782013908e+00,0.000000000000000000e+00,-1.000000009976993232e+00,0.000000000000000000e+00,-6.797077627054549221e-11,0.000000000000000000e+00 +1.061501873065841650e+01,8.801000000000000512e+01,0.000000000000000000e+00,3.421164105159177460e+00,0.000000000000000000e+00,-1.000000009977191739e+00,0.000000000000000000e+00,7.672475424349055128e-11,0.000000000000000000e+00 +1.061794171233734829e+01,8.801999999999999602e+01,0.000000000000000000e+00,3.418241123451082331e+00,0.000000000000000000e+00,-1.000000009976967474e+00,0.000000000000000000e+00,-4.364261498822346317e-11,0.000000000000000000e+00 +1.062086719349530206e+01,8.803000000000000114e+01,0.000000000000000000e+00,3.415315642263940799e+00,0.000000000000000000e+00,-1.000000009977095150e+00,0.000000000000000000e+00,-1.357450818340589525e-11,0.000000000000000000e+00 +1.062379518055343830e+01,8.804000000000000625e+01,0.000000000000000000e+00,3.412387655176591483e+00,0.000000000000000000e+00,-1.000000009977134896e+00,0.000000000000000000e+00,5.432725266899786711e-11,0.000000000000000000e+00 +1.062672567996045281e+01,8.804999999999999716e+01,0.000000000000000000e+00,3.409457155740338585e+00,0.000000000000000000e+00,-1.000000009976975690e+00,0.000000000000000000e+00,-6.026130474555266912e-11,0.000000000000000000e+00 +1.062965869819274367e+01,8.806000000000000227e+01,0.000000000000000000e+00,3.406524137478785352e+00,0.000000000000000000e+00,-1.000000009977152438e+00,0.000000000000000000e+00,3.774437528307558667e-11,0.000000000000000000e+00 +1.063259424175457468e+01,8.807000000000000739e+01,0.000000000000000000e+00,3.403588593887665326e+00,0.000000000000000000e+00,-1.000000009977041637e+00,0.000000000000000000e+00,-3.408425665803653796e-11,0.000000000000000000e+00 +1.063553231717824943e+01,8.807999999999999829e+01,0.000000000000000000e+00,3.400650518434677583e+00,0.000000000000000000e+00,-1.000000009977141779e+00,0.000000000000000000e+00,1.072236463212581868e-11,0.000000000000000000e+00 +1.063847293102427471e+01,8.809000000000000341e+01,0.000000000000000000e+00,3.397709904559313987e+00,0.000000000000000000e+00,-1.000000009977110249e+00,0.000000000000000000e+00,-4.903880497150301183e-12,0.000000000000000000e+00 +1.064141608988153287e+01,8.810000000000000853e+01,0.000000000000000000e+00,3.394766745672690877e+00,0.000000000000000000e+00,-1.000000009977124682e+00,0.000000000000000000e+00,5.276527485988688815e-13,0.000000000000000000e+00 +1.064436180036745938e+01,8.810999999999999943e+01,0.000000000000000000e+00,3.391821035157375430e+00,0.000000000000000000e+00,-1.000000009977123128e+00,0.000000000000000000e+00,8.585745403698404504e-12,0.000000000000000000e+00 +1.064731006912820632e+01,8.812000000000000455e+01,0.000000000000000000e+00,3.388872766367212908e+00,0.000000000000000000e+00,-1.000000009977097815e+00,0.000000000000000000e+00,5.342614493299360202e-12,0.000000000000000000e+00 +1.065026090283882709e+01,8.812999999999999545e+01,0.000000000000000000e+00,3.385921932627151687e+00,0.000000000000000000e+00,-1.000000009977082049e+00,0.000000000000000000e+00,-1.721680848047175124e-11,0.000000000000000000e+00 +1.065321430820344517e+01,8.814000000000000057e+01,0.000000000000000000e+00,3.382968527233066958e+00,0.000000000000000000e+00,-1.000000009977132898e+00,0.000000000000000000e+00,-8.713570957198064037e-12,0.000000000000000000e+00 +1.065617029195543708e+01,8.815000000000000568e+01,0.000000000000000000e+00,3.380012543451583085e+00,0.000000000000000000e+00,-1.000000009977158655e+00,0.000000000000000000e+00,3.880155052736685484e-11,0.000000000000000000e+00 +1.065912886085760647e+01,8.815999999999999659e+01,0.000000000000000000e+00,3.377053974519895085e+00,0.000000000000000000e+00,-1.000000009977043858e+00,0.000000000000000000e+00,-5.863878733857314938e-11,0.000000000000000000e+00 +1.066209002170236886e+01,8.817000000000000171e+01,0.000000000000000000e+00,3.374092813645588329e+00,0.000000000000000000e+00,-1.000000009977217497e+00,0.000000000000000000e+00,3.348920002864858860e-11,0.000000000000000000e+00 +1.066505378131193282e+01,8.818000000000000682e+01,0.000000000000000000e+00,3.371129054006455128e+00,0.000000000000000000e+00,-1.000000009977118243e+00,0.000000000000000000e+00,5.090078928847472940e-12,0.000000000000000000e+00 +1.066802014653847763e+01,8.818999999999999773e+01,0.000000000000000000e+00,3.368162688750314437e+00,0.000000000000000000e+00,-1.000000009977103144e+00,0.000000000000000000e+00,-3.365470590960576466e-11,0.000000000000000000e+00 +1.067098912426434509e+01,8.820000000000000284e+01,0.000000000000000000e+00,3.365193710994824450e+00,0.000000000000000000e+00,-1.000000009977203064e+00,0.000000000000000000e+00,4.326421795632925125e-11,0.000000000000000000e+00 +1.067396072140222429e+01,8.821000000000000796e+01,0.000000000000000000e+00,3.362222113827297409e+00,0.000000000000000000e+00,-1.000000009977074500e+00,0.000000000000000000e+00,-2.262086741233007218e-11,0.000000000000000000e+00 +1.067693494489533457e+01,8.821999999999999886e+01,0.000000000000000000e+00,3.359247890304513096e+00,0.000000000000000000e+00,-1.000000009977141779e+00,0.000000000000000000e+00,-1.618609229305965806e-11,0.000000000000000000e+00 +1.067991180171761911e+01,8.823000000000000398e+01,0.000000000000000000e+00,3.356271033452527419e+00,0.000000000000000000e+00,-1.000000009977189963e+00,0.000000000000000000e+00,-3.279064252834889317e-12,0.000000000000000000e+00 +1.068289129887393507e+01,8.823999999999999488e+01,0.000000000000000000e+00,3.353291536266483686e+00,0.000000000000000000e+00,-1.000000009977199733e+00,0.000000000000000000e+00,2.397548547867351543e-11,0.000000000000000000e+00 +1.068587344340024536e+01,8.825000000000000000e+01,0.000000000000000000e+00,3.350309391710419860e+00,0.000000000000000000e+00,-1.000000009977128235e+00,0.000000000000000000e+00,-1.115877187888443167e-12,0.000000000000000000e+00 +1.068885824236381055e+01,8.826000000000000512e+01,0.000000000000000000e+00,3.347324592717074943e+00,0.000000000000000000e+00,-1.000000009977131565e+00,0.000000000000000000e+00,-1.910166292536459610e-11,0.000000000000000000e+00 +1.069184570286338598e+01,8.826999999999999602e+01,0.000000000000000000e+00,3.344337132187693129e+00,0.000000000000000000e+00,-1.000000009977188631e+00,0.000000000000000000e+00,7.722956979428376348e-12,0.000000000000000000e+00 +1.069483583202941901e+01,8.828000000000000114e+01,0.000000000000000000e+00,3.341347002991827519e+00,0.000000000000000000e+00,-1.000000009977165538e+00,0.000000000000000000e+00,-2.299977033109948891e-12,0.000000000000000000e+00 +1.069782863702424436e+01,8.829000000000000625e+01,0.000000000000000000e+00,3.338354197967142056e+00,0.000000000000000000e+00,-1.000000009977172422e+00,0.000000000000000000e+00,5.188844772912037262e-13,0.000000000000000000e+00 +1.070082412504228841e+01,8.829999999999999716e+01,0.000000000000000000e+00,3.335358709919210796e+00,0.000000000000000000e+00,-1.000000009977170867e+00,0.000000000000000000e+00,-2.962393628109092865e-13,0.000000000000000000e+00 +1.070382230331026996e+01,8.831000000000000227e+01,0.000000000000000000e+00,3.332360531621316735e+00,0.000000000000000000e+00,-1.000000009977171755e+00,0.000000000000000000e+00,-3.499881565575974425e-11,0.000000000000000000e+00 +1.070682317908739734e+01,8.832000000000000739e+01,0.000000000000000000e+00,3.329359655814248420e+00,0.000000000000000000e+00,-1.000000009977276783e+00,0.000000000000000000e+00,5.049189166597426943e-11,0.000000000000000000e+00 +1.070982675966558340e+01,8.832999999999999829e+01,0.000000000000000000e+00,3.326356075206094776e+00,0.000000000000000000e+00,-1.000000009977125126e+00,0.000000000000000000e+00,-4.372508569709960486e-11,0.000000000000000000e+00 +1.071283305236964445e+01,8.834000000000000341e+01,0.000000000000000000e+00,3.323349782472039937e+00,0.000000000000000000e+00,-1.000000009977256576e+00,0.000000000000000000e+00,1.394691271110949520e-11,0.000000000000000000e+00 +1.071584206455750987e+01,8.835000000000000853e+01,0.000000000000000000e+00,3.320340770254152307e+00,0.000000000000000000e+00,-1.000000009977214610e+00,0.000000000000000000e+00,6.635373790928016994e-12,0.000000000000000000e+00 +1.071885380362043527e+01,8.835999999999999943e+01,0.000000000000000000e+00,3.317329031161177610e+00,0.000000000000000000e+00,-1.000000009977194626e+00,0.000000000000000000e+00,7.807907149783518159e-12,0.000000000000000000e+00 +1.072186827698321210e+01,8.837000000000000455e+01,0.000000000000000000e+00,3.314314557768325287e+00,0.000000000000000000e+00,-1.000000009977171089e+00,0.000000000000000000e+00,-1.037655189873496027e-11,0.000000000000000000e+00 +1.072488549210437903e+01,8.837999999999999545e+01,0.000000000000000000e+00,3.311297342617055772e+00,0.000000000000000000e+00,-1.000000009977202398e+00,0.000000000000000000e+00,-2.786619141774391759e-11,0.000000000000000000e+00 +1.072790545647643867e+01,8.839000000000000057e+01,0.000000000000000000e+00,3.308277378214865116e+00,0.000000000000000000e+00,-1.000000009977286552e+00,0.000000000000000000e+00,2.424130973312855613e-11,0.000000000000000000e+00 +1.073092817762607609e+01,8.840000000000000568e+01,0.000000000000000000e+00,3.305254657035068266e+00,0.000000000000000000e+00,-1.000000009977213278e+00,0.000000000000000000e+00,-2.480629200003144059e-11,0.000000000000000000e+00 +1.073395366311437726e+01,8.840999999999999659e+01,0.000000000000000000e+00,3.302229171516581019e+00,0.000000000000000000e+00,-1.000000009977288329e+00,0.000000000000000000e+00,4.722079586142853264e-11,0.000000000000000000e+00 +1.073698192053704581e+01,8.842000000000000171e+01,0.000000000000000000e+00,3.299200914063697976e+00,0.000000000000000000e+00,-1.000000009977145332e+00,0.000000000000000000e+00,-6.380682640360026544e-11,0.000000000000000000e+00 +1.074001295752463037e+01,8.843000000000000682e+01,0.000000000000000000e+00,3.296169877045872276e+00,0.000000000000000000e+00,-1.000000009977338733e+00,0.000000000000000000e+00,7.238458739951808163e-11,0.000000000000000000e+00 +1.074304678174274486e+01,8.843999999999999773e+01,0.000000000000000000e+00,3.293136052797488666e+00,0.000000000000000000e+00,-1.000000009977119131e+00,0.000000000000000000e+00,-6.888121543669432264e-11,0.000000000000000000e+00 +1.074608340089229586e+01,8.845000000000000284e+01,0.000000000000000000e+00,3.290099433617641456e+00,0.000000000000000000e+00,-1.000000009977328297e+00,0.000000000000000000e+00,1.322293380312074187e-11,0.000000000000000000e+00 +1.074912282270970998e+01,8.846000000000000796e+01,0.000000000000000000e+00,3.287060011769901813e+00,0.000000000000000000e+00,-1.000000009977288107e+00,0.000000000000000000e+00,1.554631495774814370e-11,0.000000000000000000e+00 +1.075216505496716657e+01,8.846999999999999886e+01,0.000000000000000000e+00,3.284017779482092614e+00,0.000000000000000000e+00,-1.000000009977240811e+00,0.000000000000000000e+00,-1.086505661313701088e-11,0.000000000000000000e+00 +1.075521010547282330e+01,8.848000000000000398e+01,0.000000000000000000e+00,3.280972728946053962e+00,0.000000000000000000e+00,-1.000000009977273896e+00,0.000000000000000000e+00,3.788315925516866944e-12,0.000000000000000000e+00 +1.075825798207105777e+01,8.848999999999999488e+01,0.000000000000000000e+00,3.277924852317410043e+00,0.000000000000000000e+00,-1.000000009977262350e+00,0.000000000000000000e+00,6.987317076544904072e-12,0.000000000000000000e+00 +1.076130869264269663e+01,8.850000000000000000e+01,0.000000000000000000e+00,3.274874141715334197e+00,0.000000000000000000e+00,-1.000000009977241033e+00,0.000000000000000000e+00,1.723388479894026048e-11,0.000000000000000000e+00 +1.076436224510525363e+01,8.851000000000000512e+01,0.000000000000000000e+00,3.271820589222310893e+00,0.000000000000000000e+00,-1.000000009977188409e+00,0.000000000000000000e+00,-6.378583166848780616e-11,0.000000000000000000e+00 +1.076741864741317301e+01,8.851999999999999602e+01,0.000000000000000000e+00,3.268764186883896361e+00,0.000000000000000000e+00,-1.000000009977383364e+00,0.000000000000000000e+00,7.308921326370139986e-11,0.000000000000000000e+00 +1.077047790755806922e+01,8.853000000000000114e+01,0.000000000000000000e+00,3.265704926708476119e+00,0.000000000000000000e+00,-1.000000009977159765e+00,0.000000000000000000e+00,-4.038986132607605098e-11,0.000000000000000000e+00 +1.077354003356897039e+01,8.854000000000000625e+01,0.000000000000000000e+00,3.262642800667024279e+00,0.000000000000000000e+00,-1.000000009977283444e+00,0.000000000000000000e+00,-3.303502176486367964e-11,0.000000000000000000e+00 +1.077660503351256160e+01,8.854999999999999716e+01,0.000000000000000000e+00,3.259577800692853522e+00,0.000000000000000000e+00,-1.000000009977384696e+00,0.000000000000000000e+00,2.533200827420364624e-11,0.000000000000000000e+00 +1.077967291549343543e+01,8.856000000000000227e+01,0.000000000000000000e+00,3.256509918681370852e+00,0.000000000000000000e+00,-1.000000009977306981e+00,0.000000000000000000e+00,8.460158362438193730e-12,0.000000000000000000e+00 +1.078274368765434055e+01,8.857000000000000739e+01,0.000000000000000000e+00,3.253439146489827127e+00,0.000000000000000000e+00,-1.000000009977281001e+00,0.000000000000000000e+00,1.726556577732615698e-11,0.000000000000000000e+00 +1.078581735817643761e+01,8.857999999999999829e+01,0.000000000000000000e+00,3.250365475937063930e+00,0.000000000000000000e+00,-1.000000009977227933e+00,0.000000000000000000e+00,-4.113838872408518270e-11,0.000000000000000000e+00 +1.078889393527954610e+01,8.859000000000000341e+01,0.000000000000000000e+00,3.247288898803260437e+00,0.000000000000000000e+00,-1.000000009977354498e+00,0.000000000000000000e+00,1.802607451530524888e-11,0.000000000000000000e+00 +1.079197342722240549e+01,8.860000000000000853e+01,0.000000000000000000e+00,3.244209406829676290e+00,0.000000000000000000e+00,-1.000000009977298987e+00,0.000000000000000000e+00,3.601795980167828204e-12,0.000000000000000000e+00 +1.079505584230293280e+01,8.860999999999999943e+01,0.000000000000000000e+00,3.241126991718394912e+00,0.000000000000000000e+00,-1.000000009977287885e+00,0.000000000000000000e+00,6.836910242685678798e-12,0.000000000000000000e+00 +1.079814118885848373e+01,8.862000000000000455e+01,0.000000000000000000e+00,3.238041645132061053e+00,0.000000000000000000e+00,-1.000000009977266791e+00,0.000000000000000000e+00,-1.718385329999711175e-11,0.000000000000000000e+00 +1.080122947526611377e+01,8.862999999999999545e+01,0.000000000000000000e+00,3.234953358693618775e+00,0.000000000000000000e+00,-1.000000009977319859e+00,0.000000000000000000e+00,-1.415058762749594483e-11,0.000000000000000000e+00 +1.080432070994284466e+01,8.864000000000000057e+01,0.000000000000000000e+00,3.231862123986045887e+00,0.000000000000000000e+00,-1.000000009977363602e+00,0.000000000000000000e+00,-1.406530395045602018e-11,0.000000000000000000e+00 +1.080741490134593086e+01,8.865000000000000568e+01,0.000000000000000000e+00,3.228767932552087050e+00,0.000000000000000000e+00,-1.000000009977407123e+00,0.000000000000000000e+00,5.735443999825106081e-11,0.000000000000000000e+00 +1.081051205797313308e+01,8.865999999999999659e+01,0.000000000000000000e+00,3.225670775893983766e+00,0.000000000000000000e+00,-1.000000009977229487e+00,0.000000000000000000e+00,-3.588376393188509963e-11,0.000000000000000000e+00 +1.081361218836298299e+01,8.867000000000000171e+01,0.000000000000000000e+00,3.222570645473203044e+00,0.000000000000000000e+00,-1.000000009977340731e+00,0.000000000000000000e+00,-4.150215669739182991e-12,0.000000000000000000e+00 +1.081671530109506385e+01,8.868000000000000682e+01,0.000000000000000000e+00,3.219467532710160729e+00,0.000000000000000000e+00,-1.000000009977353610e+00,0.000000000000000000e+00,-1.358244253102226692e-12,0.000000000000000000e+00 +1.081982140479028587e+01,8.868999999999999773e+01,0.000000000000000000e+00,3.216361428983947501e+00,0.000000000000000000e+00,-1.000000009977357829e+00,0.000000000000000000e+00,-2.099676566216858040e-11,0.000000000000000000e+00 +1.082293050811116508e+01,8.870000000000000284e+01,0.000000000000000000e+00,3.213252325632048212e+00,0.000000000000000000e+00,-1.000000009977423110e+00,0.000000000000000000e+00,5.957602615464541839e-11,0.000000000000000000e+00 +1.082604261976210225e+01,8.871000000000000796e+01,0.000000000000000000e+00,3.210140213950060328e+00,0.000000000000000000e+00,-1.000000009977237703e+00,0.000000000000000000e+00,-6.849953372536373083e-11,0.000000000000000000e+00 +1.082915774848967061e+01,8.871999999999999886e+01,0.000000000000000000e+00,3.207025085191411051e+00,0.000000000000000000e+00,-1.000000009977451088e+00,0.000000000000000000e+00,4.820934724035964009e-11,0.000000000000000000e+00 +1.083227590308290189e+01,8.873000000000000398e+01,0.000000000000000000e+00,3.203906930567067768e+00,0.000000000000000000e+00,-1.000000009977300763e+00,0.000000000000000000e+00,-1.970606388661705938e-11,0.000000000000000000e+00 +1.083539709237357584e+01,8.873999999999999488e+01,0.000000000000000000e+00,3.200785741245253391e+00,0.000000000000000000e+00,-1.000000009977362270e+00,0.000000000000000000e+00,-2.579903455473047223e-11,0.000000000000000000e+00 +1.083852132523650624e+01,8.875000000000000000e+01,0.000000000000000000e+00,3.197661508351150594e+00,0.000000000000000000e+00,-1.000000009977442872e+00,0.000000000000000000e+00,3.890928704955843905e-11,0.000000000000000000e+00 +1.084164861058984464e+01,8.876000000000000512e+01,0.000000000000000000e+00,3.194534222966610049e+00,0.000000000000000000e+00,-1.000000009977321191e+00,0.000000000000000000e+00,-2.198920177320149716e-12,0.000000000000000000e+00 +1.084477895739536812e+01,8.876999999999999602e+01,0.000000000000000000e+00,3.191403876129853767e+00,0.000000000000000000e+00,-1.000000009977328075e+00,0.000000000000000000e+00,-5.484827259315554046e-11,0.000000000000000000e+00 +1.084791237465878488e+01,8.878000000000000114e+01,0.000000000000000000e+00,3.188270458835174015e+00,0.000000000000000000e+00,-1.000000009977499937e+00,0.000000000000000000e+00,6.555508235986653678e-11,0.000000000000000000e+00 +1.085104887143003261e+01,8.879000000000000625e+01,0.000000000000000000e+00,3.185133962032632216e+00,0.000000000000000000e+00,-1.000000009977294324e+00,0.000000000000000000e+00,-3.953481730381550327e-11,0.000000000000000000e+00 +1.085418845680358402e+01,8.879999999999999716e+01,0.000000000000000000e+00,3.181994376627756083e+00,0.000000000000000000e+00,-1.000000009977418447e+00,0.000000000000000000e+00,5.934975347548643351e-12,0.000000000000000000e+00 +1.085733113991875598e+01,8.881000000000000227e+01,0.000000000000000000e+00,3.178851693481228313e+00,0.000000000000000000e+00,-1.000000009977399795e+00,0.000000000000000000e+00,1.411693736788612104e-12,0.000000000000000000e+00 +1.086047692996001679e+01,8.882000000000000739e+01,0.000000000000000000e+00,3.175705903408580166e+00,0.000000000000000000e+00,-1.000000009977395354e+00,0.000000000000000000e+00,-1.509017496136158314e-11,0.000000000000000000e+00 +1.086362583615730237e+01,8.882999999999999829e+01,0.000000000000000000e+00,3.172556997179876603e+00,0.000000000000000000e+00,-1.000000009977442872e+00,0.000000000000000000e+00,1.014406797658967156e-11,0.000000000000000000e+00 +1.086677786778632893e+01,8.884000000000000341e+01,0.000000000000000000e+00,3.169404965519400985e+00,0.000000000000000000e+00,-1.000000009977410897e+00,0.000000000000000000e+00,1.548248401515613347e-11,0.000000000000000000e+00 +1.086993303416891266e+01,8.885000000000000853e+01,0.000000000000000000e+00,3.166249799105337104e+00,0.000000000000000000e+00,-1.000000009977362048e+00,0.000000000000000000e+00,6.608657645921260540e-12,0.000000000000000000e+00 +1.087309134467329130e+01,8.885999999999999943e+01,0.000000000000000000e+00,3.163091488569447218e+00,0.000000000000000000e+00,-1.000000009977341175e+00,0.000000000000000000e+00,-3.006046871662444967e-11,0.000000000000000000e+00 +1.087625280871444744e+01,8.887000000000000455e+01,0.000000000000000000e+00,3.159930024496747869e+00,0.000000000000000000e+00,-1.000000009977436211e+00,0.000000000000000000e+00,9.261719463217647776e-12,0.000000000000000000e+00 +1.087941743575443709e+01,8.887999999999999545e+01,0.000000000000000000e+00,3.156765397425182584e+00,0.000000000000000000e+00,-1.000000009977406901e+00,0.000000000000000000e+00,-6.588861619815470610e-12,0.000000000000000000e+00 +1.088258523530272015e+01,8.889000000000000057e+01,0.000000000000000000e+00,3.153597597845292810e+00,0.000000000000000000e+00,-1.000000009977427773e+00,0.000000000000000000e+00,-4.019373769732932605e-11,0.000000000000000000e+00 +1.088575621691649076e+01,8.890000000000000568e+01,0.000000000000000000e+00,3.150426616199883512e+00,0.000000000000000000e+00,-1.000000009977555226e+00,0.000000000000000000e+00,7.170236141728915546e-11,0.000000000000000000e+00 +1.088893039020101661e+01,8.890999999999999659e+01,0.000000000000000000e+00,3.147252442883687440e+00,0.000000000000000000e+00,-1.000000009977327631e+00,0.000000000000000000e+00,-3.934415294323292408e-11,0.000000000000000000e+00 +1.089210776480997467e+01,8.892000000000000171e+01,0.000000000000000000e+00,3.144075068243027626e+00,0.000000000000000000e+00,-1.000000009977452642e+00,0.000000000000000000e+00,8.447311367230232998e-12,0.000000000000000000e+00 +1.089528835044579758e+01,8.893000000000000682e+01,0.000000000000000000e+00,3.140894482575471436e+00,0.000000000000000000e+00,-1.000000009977425774e+00,0.000000000000000000e+00,-1.583140391102926238e-11,0.000000000000000000e+00 +1.089847215686001292e+01,8.893999999999999773e+01,0.000000000000000000e+00,3.137710676129489062e+00,0.000000000000000000e+00,-1.000000009977476179e+00,0.000000000000000000e+00,1.658173911331536045e-11,0.000000000000000000e+00 +1.090165919385360027e+01,8.895000000000000284e+01,0.000000000000000000e+00,3.134523639104102699e+00,0.000000000000000000e+00,-1.000000009977423332e+00,0.000000000000000000e+00,-1.733050117051874498e-11,0.000000000000000000e+00 +1.090484947127733584e+01,8.896000000000000796e+01,0.000000000000000000e+00,3.131333361648536151e+00,0.000000000000000000e+00,-1.000000009977478621e+00,0.000000000000000000e+00,-7.092015927593357811e-12,0.000000000000000000e+00 +1.090804299903214947e+01,8.896999999999999886e+01,0.000000000000000000e+00,3.128139833861858676e+00,0.000000000000000000e+00,-1.000000009977501270e+00,0.000000000000000000e+00,1.041879860340164092e-12,0.000000000000000000e+00 +1.091123978706948350e+01,8.898000000000000398e+01,0.000000000000000000e+00,3.124943045792627938e+00,0.000000000000000000e+00,-1.000000009977497939e+00,0.000000000000000000e+00,2.664486697022392418e-11,0.000000000000000000e+00 +1.091443984539165513e+01,8.898999999999999488e+01,0.000000000000000000e+00,3.121742987438528072e+00,0.000000000000000000e+00,-1.000000009977412674e+00,0.000000000000000000e+00,-1.531897276194437665e-11,0.000000000000000000e+00 +1.091764318405221701e+01,8.900000000000000000e+01,0.000000000000000000e+00,3.118539648746005088e+00,0.000000000000000000e+00,-1.000000009977461746e+00,0.000000000000000000e+00,-7.478512965887608644e-12,0.000000000000000000e+00 +1.092084981315633030e+01,8.901000000000000512e+01,0.000000000000000000e+00,3.115333019609897836e+00,0.000000000000000000e+00,-1.000000009977485727e+00,0.000000000000000000e+00,-1.591008645963124483e-11,0.000000000000000000e+00 +1.092405974286113413e+01,8.901999999999999602e+01,0.000000000000000000e+00,3.112123089873067627e+00,0.000000000000000000e+00,-1.000000009977536797e+00,0.000000000000000000e+00,1.630831135046681984e-11,0.000000000000000000e+00 +1.092727298337611863e+01,8.903000000000000114e+01,0.000000000000000000e+00,3.108909849326022545e+00,0.000000000000000000e+00,-1.000000009977484394e+00,0.000000000000000000e+00,1.387536485074681760e-11,0.000000000000000000e+00 +1.093048954496350866e+01,8.904000000000000625e+01,0.000000000000000000e+00,3.105693287706539518e+00,0.000000000000000000e+00,-1.000000009977439763e+00,0.000000000000000000e+00,-1.034403658630680092e-11,0.000000000000000000e+00 +1.093370943793864036e+01,8.904999999999999716e+01,0.000000000000000000e+00,3.102473394699281517e+00,0.000000000000000000e+00,-1.000000009977473070e+00,0.000000000000000000e+00,3.788881135690324869e-12,0.000000000000000000e+00 +1.093693267267035019e+01,8.906000000000000227e+01,0.000000000000000000e+00,3.099250159935412086e+00,0.000000000000000000e+00,-1.000000009977460858e+00,0.000000000000000000e+00,-2.683869931574124860e-12,0.000000000000000000e+00 +1.094015925958136215e+01,8.907000000000000739e+01,0.000000000000000000e+00,3.096023572992206763e+00,0.000000000000000000e+00,-1.000000009977469517e+00,0.000000000000000000e+00,-3.265412822742282424e-11,0.000000000000000000e+00 +1.094338920914868218e+01,8.907999999999999829e+01,0.000000000000000000e+00,3.092793623392659619e+00,0.000000000000000000e+00,-1.000000009977574988e+00,0.000000000000000000e+00,1.311669844001879237e-11,0.000000000000000000e+00 +1.094662253190399426e+01,8.909000000000000341e+01,0.000000000000000000e+00,3.089560300605086685e+00,0.000000000000000000e+00,-1.000000009977532578e+00,0.000000000000000000e+00,-1.372040392679834934e-13,0.000000000000000000e+00 +1.094985923843406006e+01,8.910000000000000853e+01,0.000000000000000000e+00,3.086323594042726715e+00,0.000000000000000000e+00,-1.000000009977533022e+00,0.000000000000000000e+00,3.077003748963989866e-11,0.000000000000000000e+00 +1.095309933938112223e+01,8.910999999999999943e+01,0.000000000000000000e+00,3.083083493063335734e+00,0.000000000000000000e+00,-1.000000009977433324e+00,0.000000000000000000e+00,-1.547155446939982489e-11,0.000000000000000000e+00 +1.095634284544331649e+01,8.912000000000000455e+01,0.000000000000000000e+00,3.079839986968780252e+00,0.000000000000000000e+00,-1.000000009977483506e+00,0.000000000000000000e+00,-1.497657458373964187e-11,0.000000000000000000e+00 +1.095958976737507662e+01,8.912999999999999545e+01,0.000000000000000000e+00,3.076593065004624261e+00,0.000000000000000000e+00,-1.000000009977532134e+00,0.000000000000000000e+00,-1.748840682583150027e-11,0.000000000000000000e+00 +1.096284011598755548e+01,8.914000000000000057e+01,0.000000000000000000e+00,3.073342716359714899e+00,0.000000000000000000e+00,-1.000000009977588977e+00,0.000000000000000000e+00,1.221530312963434688e-11,0.000000000000000000e+00 +1.096609390214904245e+01,8.915000000000000568e+01,0.000000000000000000e+00,3.070088930165762342e+00,0.000000000000000000e+00,-1.000000009977549231e+00,0.000000000000000000e+00,2.951746639915986539e-11,0.000000000000000000e+00 +1.096935113678538976e+01,8.915999999999999659e+01,0.000000000000000000e+00,3.066831695496916588e+00,0.000000000000000000e+00,-1.000000009977453086e+00,0.000000000000000000e+00,-4.208415810984731821e-11,0.000000000000000000e+00 +1.097261183088043346e+01,8.917000000000000171e+01,0.000000000000000000e+00,3.063571001369339353e+00,0.000000000000000000e+00,-1.000000009977590310e+00,0.000000000000000000e+00,2.652972709369466253e-11,0.000000000000000000e+00 +1.097587599547643222e+01,8.918000000000000682e+01,0.000000000000000000e+00,3.060306836740771530e+00,0.000000000000000000e+00,-1.000000009977503712e+00,0.000000000000000000e+00,-1.861897465686926691e-11,0.000000000000000000e+00 +1.097914364167450074e+01,8.918999999999999773e+01,0.000000000000000000e+00,3.057039190510099758e+00,0.000000000000000000e+00,-1.000000009977564552e+00,0.000000000000000000e+00,8.756507864933268693e-12,0.000000000000000000e+00 +1.098241478063504850e+01,8.920000000000000284e+01,0.000000000000000000e+00,3.053768051516913662e+00,0.000000000000000000e+00,-1.000000009977535909e+00,0.000000000000000000e+00,-1.132381443288032040e-11,0.000000000000000000e+00 +1.098568942357822564e+01,8.921000000000000796e+01,0.000000000000000000e+00,3.050493408541063545e+00,0.000000000000000000e+00,-1.000000009977572990e+00,0.000000000000000000e+00,-1.354691207451825066e-13,0.000000000000000000e+00 +1.098896758178437061e+01,8.921999999999999886e+01,0.000000000000000000e+00,3.047215250302210521e+00,0.000000000000000000e+00,-1.000000009977573434e+00,0.000000000000000000e+00,-7.984088935223639297e-12,0.000000000000000000e+00 +1.099224926659446311e+01,8.923000000000000398e+01,0.000000000000000000e+00,3.043933565459374435e+00,0.000000000000000000e+00,-1.000000009977599635e+00,0.000000000000000000e+00,3.845808557715066922e-11,0.000000000000000000e+00 +1.099553448941058242e+01,8.923999999999999488e+01,0.000000000000000000e+00,3.040648342610476007e+00,0.000000000000000000e+00,-1.000000009977473292e+00,0.000000000000000000e+00,-2.889682916589828059e-11,0.000000000000000000e+00 +1.099882326169636926e+01,8.925000000000000000e+01,0.000000000000000000e+00,3.037359570291875865e+00,0.000000000000000000e+00,-1.000000009977568327e+00,0.000000000000000000e+00,1.888402056242022722e-12,0.000000000000000000e+00 +1.100211559497748937e+01,8.926000000000000512e+01,0.000000000000000000e+00,3.034067236977906479e+00,0.000000000000000000e+00,-1.000000009977562110e+00,0.000000000000000000e+00,-1.205919887101825657e-11,0.000000000000000000e+00 +1.100541150084210784e+01,8.926999999999999602e+01,0.000000000000000000e+00,3.030771331080403641e+00,0.000000000000000000e+00,-1.000000009977601856e+00,0.000000000000000000e+00,1.191150568405311369e-11,0.000000000000000000e+00 +1.100871099094136163e+01,8.928000000000000114e+01,0.000000000000000000e+00,3.027471840948229520e+00,0.000000000000000000e+00,-1.000000009977562554e+00,0.000000000000000000e+00,-2.319206571515273359e-11,0.000000000000000000e+00 +1.101201407698984092e+01,8.929000000000000625e+01,0.000000000000000000e+00,3.024168754866793485e+00,0.000000000000000000e+00,-1.000000009977639159e+00,0.000000000000000000e+00,2.034646079895093645e-11,0.000000000000000000e+00 +1.101532077076607585e+01,8.929999999999999716e+01,0.000000000000000000e+00,3.020862061057566272e+00,0.000000000000000000e+00,-1.000000009977571880e+00,0.000000000000000000e+00,-9.994415230920092273e-12,0.000000000000000000e+00 +1.101863108411302150e+01,8.931000000000000227e+01,0.000000000000000000e+00,3.017551747677591933e+00,0.000000000000000000e+00,-1.000000009977604964e+00,0.000000000000000000e+00,-2.217802893514437819e-11,0.000000000000000000e+00 +1.102194502893855699e+01,8.932000000000000739e+01,0.000000000000000000e+00,3.014237802818991785e+00,0.000000000000000000e+00,-1.000000009977678461e+00,0.000000000000000000e+00,3.948841928254520900e-11,0.000000000000000000e+00 +1.102526261721598111e+01,8.932999999999999829e+01,0.000000000000000000e+00,3.010920214508466142e+00,0.000000000000000000e+00,-1.000000009977547455e+00,0.000000000000000000e+00,5.348468715930583353e-13,0.000000000000000000e+00 +1.102858386098451859e+01,8.934000000000000341e+01,0.000000000000000000e+00,3.007598970706790720e+00,0.000000000000000000e+00,-1.000000009977545679e+00,0.000000000000000000e+00,-5.456098593076160035e-11,0.000000000000000000e+00 +1.103190877234982992e+01,8.935000000000000853e+01,0.000000000000000000e+00,3.004274059308305489e+00,0.000000000000000000e+00,-1.000000009977727089e+00,0.000000000000000000e+00,5.957049820009700393e-11,0.000000000000000000e+00 +1.103523736348452289e+01,8.935999999999999943e+01,0.000000000000000000e+00,3.000945468140401307e+00,0.000000000000000000e+00,-1.000000009977528803e+00,0.000000000000000000e+00,-4.477830005878645987e-11,0.000000000000000000e+00 +1.103856964662867313e+01,8.937000000000000455e+01,0.000000000000000000e+00,2.997613184963002553e+00,0.000000000000000000e+00,-1.000000009977678017e+00,0.000000000000000000e+00,3.907094513640535617e-11,0.000000000000000000e+00 +1.104190563409035164e+01,8.937999999999999545e+01,0.000000000000000000e+00,2.994277197468038221e+00,0.000000000000000000e+00,-1.000000009977547677e+00,0.000000000000000000e+00,-4.281718346919963901e-11,0.000000000000000000e+00 +1.104524533824615062e+01,8.939000000000000057e+01,0.000000000000000000e+00,2.990937493278916559e+00,0.000000000000000000e+00,-1.000000009977690674e+00,0.000000000000000000e+00,3.898393404876907627e-11,0.000000000000000000e+00 +1.104858877154172170e+01,8.940000000000000568e+01,0.000000000000000000e+00,2.987594059949985947e+00,0.000000000000000000e+00,-1.000000009977560333e+00,0.000000000000000000e+00,-5.167723521772946905e-11,0.000000000000000000e+00 +1.105193594649231237e+01,8.940999999999999659e+01,0.000000000000000000e+00,2.984246884965997992e+00,0.000000000000000000e+00,-1.000000009977733306e+00,0.000000000000000000e+00,4.114969066746098352e-11,0.000000000000000000e+00 +1.105528687568331847e+01,8.942000000000000171e+01,0.000000000000000000e+00,2.980895955741557746e+00,0.000000000000000000e+00,-1.000000009977595417e+00,0.000000000000000000e+00,-1.701062092575212387e-11,0.000000000000000000e+00 +1.105864157177082774e+01,8.943000000000000682e+01,0.000000000000000000e+00,2.977541259620576142e+00,0.000000000000000000e+00,-1.000000009977652482e+00,0.000000000000000000e+00,2.267734116156677775e-11,0.000000000000000000e+00 +1.106200004748218468e+01,8.943999999999999773e+01,0.000000000000000000e+00,2.974182783875709113e+00,0.000000000000000000e+00,-1.000000009977576321e+00,0.000000000000000000e+00,-2.932181511019071607e-11,0.000000000000000000e+00 +1.106536231561654837e+01,8.945000000000000284e+01,0.000000000000000000e+00,2.970820515707797593e+00,0.000000000000000000e+00,-1.000000009977674909e+00,0.000000000000000000e+00,-5.804961075878938117e-12,0.000000000000000000e+00 +1.106872838904546263e+01,8.946000000000000796e+01,0.000000000000000000e+00,2.967454442245296864e+00,0.000000000000000000e+00,-1.000000009977694448e+00,0.000000000000000000e+00,3.268179956336474796e-11,0.000000000000000000e+00 +1.107209828071343161e+01,8.946999999999999886e+01,0.000000000000000000e+00,2.964084550543704122e+00,0.000000000000000000e+00,-1.000000009977584314e+00,0.000000000000000000e+00,-3.652782355593754866e-11,0.000000000000000000e+00 +1.107547200363849704e+01,8.948000000000000398e+01,0.000000000000000000e+00,2.960710827584977611e+00,0.000000000000000000e+00,-1.000000009977707549e+00,0.000000000000000000e+00,-2.037970584625943579e-12,0.000000000000000000e+00 +1.107884957091282452e+01,8.948999999999999488e+01,0.000000000000000000e+00,2.957333260276949094e+00,0.000000000000000000e+00,-1.000000009977714432e+00,0.000000000000000000e+00,2.429641613016444820e-11,0.000000000000000000e+00 +1.108223099570330028e+01,8.950000000000000000e+01,0.000000000000000000e+00,2.953951835452734098e+00,0.000000000000000000e+00,-1.000000009977632276e+00,0.000000000000000000e+00,4.853727105202983118e-12,0.000000000000000000e+00 +1.108561629125212455e+01,8.951000000000000512e+01,0.000000000000000000e+00,2.950566539870132399e+00,0.000000000000000000e+00,-1.000000009977615845e+00,0.000000000000000000e+00,-1.716512339924258025e-11,0.000000000000000000e+00 +1.108900547087741728e+01,8.951999999999999602e+01,0.000000000000000000e+00,2.947177360211023167e+00,0.000000000000000000e+00,-1.000000009977674020e+00,0.000000000000000000e+00,-2.755044345212544408e-11,0.000000000000000000e+00 +1.109239854797383096e+01,8.953000000000000114e+01,0.000000000000000000e+00,2.943784283080754793e+00,0.000000000000000000e+00,-1.000000009977767501e+00,0.000000000000000000e+00,4.209515132700416207e-11,0.000000000000000000e+00 +1.109579553601316348e+01,8.954000000000000625e+01,0.000000000000000000e+00,2.940387295007528046e+00,0.000000000000000000e+00,-1.000000009977624504e+00,0.000000000000000000e+00,-2.311255858772709401e-11,0.000000000000000000e+00 +1.109919644854498522e+01,8.954999999999999716e+01,0.000000000000000000e+00,2.936986382441773458e+00,0.000000000000000000e+00,-1.000000009977703108e+00,0.000000000000000000e+00,1.565140754302753190e-11,0.000000000000000000e+00 +1.110260129919726779e+01,8.956000000000000227e+01,0.000000000000000000e+00,2.933581531755518945e+00,0.000000000000000000e+00,-1.000000009977649817e+00,0.000000000000000000e+00,-2.559946792279708210e-11,0.000000000000000000e+00 +1.110601010167701830e+01,8.957000000000000739e+01,0.000000000000000000e+00,2.930172729241756091e+00,0.000000000000000000e+00,-1.000000009977737081e+00,0.000000000000000000e+00,2.095025528205608219e-11,0.000000000000000000e+00 +1.110942286977092763e+01,8.957999999999999829e+01,0.000000000000000000e+00,2.926759961113794883e+00,0.000000000000000000e+00,-1.000000009977665583e+00,0.000000000000000000e+00,-4.432121988261723724e-11,0.000000000000000000e+00 +1.111283961734601533e+01,8.959000000000000341e+01,0.000000000000000000e+00,2.923343213504615790e+00,0.000000000000000000e+00,-1.000000009977817017e+00,0.000000000000000000e+00,5.822539922459047272e-11,0.000000000000000000e+00 +1.111626035835028858e+01,8.960000000000000853e+01,0.000000000000000000e+00,2.919922472466210728e+00,0.000000000000000000e+00,-1.000000009977617843e+00,0.000000000000000000e+00,-4.674625359353563109e-11,0.000000000000000000e+00 +1.111968510681340661e+01,8.960999999999999943e+01,0.000000000000000000e+00,2.916497723968922706e+00,0.000000000000000000e+00,-1.000000009977777937e+00,0.000000000000000000e+00,2.421996267464037359e-11,0.000000000000000000e+00 +1.112311387684734676e+01,8.962000000000000455e+01,0.000000000000000000e+00,2.913068953900770808e+00,0.000000000000000000e+00,-1.000000009977694893e+00,0.000000000000000000e+00,-2.056923359062701296e-11,0.000000000000000000e+00 +1.112654668264708846e+01,8.962999999999999545e+01,0.000000000000000000e+00,2.909636148066776951e+00,0.000000000000000000e+00,-1.000000009977765503e+00,0.000000000000000000e+00,3.378940916929194268e-11,0.000000000000000000e+00 +1.112998353849129529e+01,8.964000000000000057e+01,0.000000000000000000e+00,2.906199292188277550e+00,0.000000000000000000e+00,-1.000000009977649373e+00,0.000000000000000000e+00,-2.684472434456183317e-11,0.000000000000000000e+00 +1.113342445874300601e+01,8.965000000000000568e+01,0.000000000000000000e+00,2.902758371902233847e+00,0.000000000000000000e+00,-1.000000009977741744e+00,0.000000000000000000e+00,-9.152494069522392051e-12,0.000000000000000000e+00 +1.113686945785033622e+01,8.965999999999999659e+01,0.000000000000000000e+00,2.899313372760529806e+00,0.000000000000000000e+00,-1.000000009977773274e+00,0.000000000000000000e+00,1.860515219060483797e-11,0.000000000000000000e+00 +1.114031855034718355e+01,8.967000000000000171e+01,0.000000000000000000e+00,2.895864280229267340e+00,0.000000000000000000e+00,-1.000000009977709103e+00,0.000000000000000000e+00,-9.002154560280249694e-13,0.000000000000000000e+00 +1.114377175085394533e+01,8.968000000000000682e+01,0.000000000000000000e+00,2.892411079688050890e+00,0.000000000000000000e+00,-1.000000009977712212e+00,0.000000000000000000e+00,-3.121307178784766085e-11,0.000000000000000000e+00 +1.114722907407823627e+01,8.968999999999999773e+01,0.000000000000000000e+00,2.888953756429264441e+00,0.000000000000000000e+00,-1.000000009977820126e+00,0.000000000000000000e+00,2.771178892529851364e-11,0.000000000000000000e+00 +1.115069053481562023e+01,8.970000000000000284e+01,0.000000000000000000e+00,2.885492295657341888e+00,0.000000000000000000e+00,-1.000000009977724202e+00,0.000000000000000000e+00,1.492849632552052678e-11,0.000000000000000000e+00 +1.115415614795035282e+01,8.971000000000000796e+01,0.000000000000000000e+00,2.882026682488030289e+00,0.000000000000000000e+00,-1.000000009977672466e+00,0.000000000000000000e+00,-3.679646237554606427e-11,0.000000000000000000e+00 +1.115762592845612033e+01,8.971999999999999886e+01,0.000000000000000000e+00,2.878556901947642022e+00,0.000000000000000000e+00,-1.000000009977800142e+00,0.000000000000000000e+00,-5.177261043382208450e-12,0.000000000000000000e+00 +1.116109989139679826e+01,8.973000000000000398e+01,0.000000000000000000e+00,2.875082938972301161e+00,0.000000000000000000e+00,-1.000000009977818127e+00,0.000000000000000000e+00,3.587789202846709873e-11,0.000000000000000000e+00 +1.116457805192721153e+01,8.973999999999999488e+01,0.000000000000000000e+00,2.871604778407182756e+00,0.000000000000000000e+00,-1.000000009977693338e+00,0.000000000000000000e+00,-2.512239933177684608e-11,0.000000000000000000e+00 +1.116806042529390730e+01,8.975000000000000000e+01,0.000000000000000000e+00,2.868122405005741449e+00,0.000000000000000000e+00,-1.000000009977780824e+00,0.000000000000000000e+00,4.457957744072913287e-13,0.000000000000000000e+00 +1.117154702683592937e+01,8.976000000000000512e+01,0.000000000000000000e+00,2.864635803428931204e+00,0.000000000000000000e+00,-1.000000009977779269e+00,0.000000000000000000e+00,-1.208546157930305674e-11,0.000000000000000000e+00 +1.117503787198560872e+01,8.976999999999999602e+01,0.000000000000000000e+00,2.861144958244420167e+00,0.000000000000000000e+00,-1.000000009977821458e+00,0.000000000000000000e+00,2.147320090376800877e-11,0.000000000000000000e+00 +1.117853297626936282e+01,8.978000000000000114e+01,0.000000000000000000e+00,2.857649853925793071e+00,0.000000000000000000e+00,-1.000000009977746407e+00,0.000000000000000000e+00,2.474650358033202043e-12,0.000000000000000000e+00 +1.118203235530849327e+01,8.979000000000000625e+01,0.000000000000000000e+00,2.854150474851747443e+00,0.000000000000000000e+00,-1.000000009977737747e+00,0.000000000000000000e+00,-1.299184864899345796e-11,0.000000000000000000e+00 +1.118553602482000286e+01,8.979999999999999716e+01,0.000000000000000000e+00,2.850646805305278697e+00,0.000000000000000000e+00,-1.000000009977783266e+00,0.000000000000000000e+00,-2.272364969756679354e-11,0.000000000000000000e+00 +1.118904400061742166e+01,8.981000000000000227e+01,0.000000000000000000e+00,2.847138829472858124e+00,0.000000000000000000e+00,-1.000000009977862980e+00,0.000000000000000000e+00,4.001774198805916624e-11,0.000000000000000000e+00 +1.119255629861163293e+01,8.982000000000000739e+01,0.000000000000000000e+00,2.843626531443601113e+00,0.000000000000000000e+00,-1.000000009977722426e+00,0.000000000000000000e+00,8.206713415456215437e-09,0.000000000000000000e+00 +1.119607293481171872e+01,8.982999999999999829e+01,0.000000000000000000e+00,2.840109895208426938e+00,0.000000000000000000e+00,-1.000000009948862401e+00,0.000000000000000000e+00,9.999999988303004406e-01,0.000000000000000000e+00 +1.119959392532580722e+01,8.984000000000000341e+01,0.000000000000000000e+00,2.836588904659307797e+00,0.000000000000000000e+00,-9.964790194388916111e-01,0.000000000000000000e+00,1.000000006007865538e+00,0.000000000000000000e+00 +1.120311928636193599e+01,8.985000000000000853e+01,0.000000000000000000e+00,2.833075956350858515e+00,0.000000000000000000e+00,-9.929536583815833373e-01,0.000000000000000000e+00,1.000000007552291015e+00,0.000000000000000000e+00 +1.120664901876377328e+01,8.985999999999999943e+01,0.000000000000000000e+00,2.829571095649345391e+00,0.000000000000000000e+00,-9.894239259530877018e-01,0.000000000000000000e+00,1.000000008223941750e+00,0.000000000000000000e+00 +1.121018312328419952e+01,8.987000000000000455e+01,0.000000000000000000e+00,2.826074368080017329e+00,0.000000000000000000e+00,-9.858898214035978214e-01,0.000000000000000000e+00,1.000000008657073058e+00,0.000000000000000000e+00 +1.121372160058435341e+01,8.987999999999999545e+01,0.000000000000000000e+00,2.822585819326527190e+00,0.000000000000000000e+00,-9.823513440728103285e-01,0.000000000000000000e+00,1.000000008833693776e+00,0.000000000000000000e+00 +1.121726445123269400e+01,8.989000000000000057e+01,0.000000000000000000e+00,2.819105495230279868e+00,0.000000000000000000e+00,-9.788084933931725518e-01,0.000000000000000000e+00,1.000000009065608042e+00,0.000000000000000000e+00 +1.122081167570404503e+01,8.990000000000000568e+01,0.000000000000000000e+00,2.815633441789749725e+00,0.000000000000000000e+00,-9.752612688896641346e-01,0.000000000000000000e+00,1.000000009200558759e+00,0.000000000000000000e+00 +1.122436327437863746e+01,8.990999999999999659e+01,0.000000000000000000e+00,2.812169705159779376e+00,0.000000000000000000e+00,-9.717096701823945137e-01,0.000000000000000000e+00,1.000000009246040378e+00,0.000000000000000000e+00 +1.122791924754115733e+01,8.992000000000000171e+01,0.000000000000000000e+00,2.808714331650849605e+00,0.000000000000000000e+00,-9.681536969869958265e-01,0.000000000000000000e+00,1.000000009317427718e+00,0.000000000000000000e+00 +1.123147959537977947e+01,8.993000000000000682e+01,0.000000000000000000e+00,2.805267367728327965e+00,0.000000000000000000e+00,-9.645933491152004491e-01,0.000000000000000000e+00,1.000000009446500693e+00,0.000000000000000000e+00 +1.123504431798520287e+01,8.993999999999999773e+01,0.000000000000000000e+00,2.801828860011695177e+00,0.000000000000000000e+00,-9.610286264761020991e-01,0.000000000000000000e+00,1.000000009464297124e+00,0.000000000000000000e+00 +1.123861341534968616e+01,8.995000000000000284e+01,0.000000000000000000e+00,2.798398855273746655e+00,0.000000000000000000e+00,-9.574595290778401546e-01,0.000000000000000000e+00,1.000000009509743881e+00,0.000000000000000000e+00 +1.124218688736606886e+01,8.996000000000000796e+01,0.000000000000000000e+00,2.794977400439767390e+00,0.000000000000000000e+00,-9.538860570274739770e-01,0.000000000000000000e+00,1.000000009525883415e+00,0.000000000000000000e+00 +1.124576473382680497e+01,8.996999999999999886e+01,0.000000000000000000e+00,2.791564542586686404e+00,0.000000000000000000e+00,-9.503082105326560169e-01,0.000000000000000000e+00,1.000000009593374095e+00,0.000000000000000000e+00 +1.124934695442297716e+01,8.998000000000000398e+01,0.000000000000000000e+00,2.788160328942204114e+00,0.000000000000000000e+00,-9.467259899021175373e-01,0.000000000000000000e+00,1.000000009569249837e+00,0.000000000000000000e+00 +1.125293354874332330e+01,8.998999999999999488e+01,0.000000000000000000e+00,2.784764806883896604e+00,0.000000000000000000e+00,-9.431393955474498547e-01,0.000000000000000000e+00,1.000000009660102274e+00,0.000000000000000000e+00 +1.125652451627324879e+01,9.000000000000000000e+01,0.000000000000000000e+00,2.781378023938291921e+00,0.000000000000000000e+00,-9.395484279828349994e-01,0.000000000000000000e+00,1.000000009647516341e+00,0.000000000000000000e+00 +1.126011985639384072e+01,9.001000000000000512e+01,0.000000000000000000e+00,2.778000027779925496e+00,0.000000000000000000e+00,-9.359530878275562626e-01,0.000000000000000000e+00,1.000000009632352693e+00,0.000000000000000000e+00 +1.126371956838088195e+01,9.001999999999999602e+01,0.000000000000000000e+00,2.774630866230364479e+00,0.000000000000000000e+00,-9.323533758058414334e-01,0.000000000000000000e+00,1.000000009640159560e+00,0.000000000000000000e+00 +1.126732365140385639e+01,9.003000000000000114e+01,0.000000000000000000e+00,2.771270587257210316e+00,0.000000000000000000e+00,-9.287492927481236782e-01,0.000000000000000000e+00,1.000000009675025670e+00,0.000000000000000000e+00 +1.127093210452495597e+01,9.004000000000000625e+01,0.000000000000000000e+00,2.767919238973074236e+00,0.000000000000000000e+00,-9.251408395921121297e-01,0.000000000000000000e+00,1.000000009637892040e+00,0.000000000000000000e+00 +1.127454492669808772e+01,9.004999999999999716e+01,0.000000000000000000e+00,2.764576869634526091e+00,0.000000000000000000e+00,-9.215280173841603473e-01,0.000000000000000000e+00,1.000000009617266761e+00,0.000000000000000000e+00 +1.127816211676787361e+01,9.006000000000000227e+01,0.000000000000000000e+00,2.761243527641015216e+00,0.000000000000000000e+00,-9.179108272795876156e-01,0.000000000000000000e+00,1.000000009669592460e+00,0.000000000000000000e+00 +1.128178367346864874e+01,9.007000000000000739e+01,0.000000000000000000e+00,2.757919261533766875e+00,0.000000000000000000e+00,-9.142892705437936085e-01,0.000000000000000000e+00,1.000000009635306775e+00,0.000000000000000000e+00 +1.128540959542346300e+01,9.007999999999999829e+01,0.000000000000000000e+00,2.754604119994651157e+00,0.000000000000000000e+00,-9.106633485540426287e-01,0.000000000000000000e+00,1.000000009632248554e+00,0.000000000000000000e+00 +1.128903988114307388e+01,9.009000000000000341e+01,0.000000000000000000e+00,2.751298151845021689e+00,0.000000000000000000e+00,-9.070330627994631634e-01,0.000000000000000000e+00,1.000000009666647038e+00,0.000000000000000000e+00 +1.129267452902494462e+01,9.010000000000000853e+01,0.000000000000000000e+00,2.748001406044530359e+00,0.000000000000000000e+00,-9.033984148824569793e-01,0.000000000000000000e+00,1.000000009620002794e+00,0.000000000000000000e+00 +1.129631353735223520e+01,9.010999999999999943e+01,0.000000000000000000e+00,2.744713931689912734e+00,0.000000000000000000e+00,-8.997594065201599545e-01,0.000000000000000000e+00,1.000000009636096143e+00,0.000000000000000000e+00 +1.129995690429278987e+01,9.012000000000000455e+01,0.000000000000000000e+00,2.741435778013743718e+00,0.000000000000000000e+00,-8.961160395444970339e-01,0.000000000000000000e+00,1.000000009635202858e+00,0.000000000000000000e+00 +1.130360462789813525e+01,9.012999999999999545e+01,0.000000000000000000e+00,2.738166994383168351e+00,0.000000000000000000e+00,-8.924683159040047720e-01,0.000000000000000000e+00,1.000000009634456344e+00,0.000000000000000000e+00 +1.130725670610246425e+01,9.014000000000000057e+01,0.000000000000000000e+00,2.734907630298601067e+00,0.000000000000000000e+00,-8.888162376644899165e-01,0.000000000000000000e+00,1.000000009664109957e+00,0.000000000000000000e+00 +1.131091313672162535e+01,9.015000000000000568e+01,0.000000000000000000e+00,2.731657735392397424e+00,0.000000000000000000e+00,-8.851598070099930826e-01,0.000000000000000000e+00,1.000000009586341276e+00,0.000000000000000000e+00 +1.131457391745210828e+01,9.015999999999999659e+01,0.000000000000000000e+00,2.728417359427496969e+00,0.000000000000000000e+00,-8.814990262444163394e-01,0.000000000000000000e+00,1.000000009675807933e+00,0.000000000000000000e+00 +1.131823904587003327e+01,9.017000000000000171e+01,0.000000000000000000e+00,2.725186552296034570e+00,0.000000000000000000e+00,-8.778338977910273844e-01,0.000000000000000000e+00,1.000000009609668838e+00,0.000000000000000000e+00 +1.132190851943013676e+01,9.018000000000000682e+01,0.000000000000000000e+00,2.721965364017927769e+00,0.000000000000000000e+00,-8.741644241956614270e-01,0.000000000000000000e+00,1.000000009642715293e+00,0.000000000000000000e+00 +1.132558233546475357e+01,9.018999999999999773e+01,0.000000000000000000e+00,2.718753844739426384e+00,0.000000000000000000e+00,-8.704906081256192918e-01,0.000000000000000000e+00,1.000000009632197484e+00,0.000000000000000000e+00 +1.132926049118280432e+01,9.020000000000000284e+01,0.000000000000000000e+00,2.715552044731639914e+00,0.000000000000000000e+00,-8.668124523721401076e-01,0.000000000000000000e+00,1.000000009615261698e+00,0.000000000000000000e+00 +1.133294298366877939e+01,9.021000000000000796e+01,0.000000000000000000e+00,2.712360014389029406e+00,0.000000000000000000e+00,-8.631299598507563564e-01,0.000000000000000000e+00,1.000000009627088904e+00,0.000000000000000000e+00 +1.133662980988172642e+01,9.021999999999999886e+01,0.000000000000000000e+00,2.709177804227871356e+00,0.000000000000000000e+00,-8.594431336023155010e-01,0.000000000000000000e+00,1.000000009650898525e+00,0.000000000000000000e+00 +1.134032096665423239e+01,9.023000000000000398e+01,0.000000000000000000e+00,2.706005464884690959e+00,0.000000000000000000e+00,-8.557519767941860200e-01,0.000000000000000000e+00,1.000000009601789364e+00,0.000000000000000000e+00 +1.134401645069141118e+01,9.023999999999999488e+01,0.000000000000000000e+00,2.702843047114663833e+00,0.000000000000000000e+00,-8.520564927215239504e-01,0.000000000000000000e+00,1.000000009634520515e+00,0.000000000000000000e+00 +1.134771625856988742e+01,9.025000000000000000e+01,0.000000000000000000e+00,2.699690601789985767e+00,0.000000000000000000e+00,-8.483566848074016731e-01,0.000000000000000000e+00,1.000000009637372012e+00,0.000000000000000000e+00 +1.135142038673678577e+01,9.026000000000000512e+01,0.000000000000000000e+00,2.696548179898214492e+00,0.000000000000000000e+00,-8.446525566048056488e-01,0.000000000000000000e+00,1.000000009605479301e+00,0.000000000000000000e+00 +1.135512883150871488e+01,9.026999999999999602e+01,0.000000000000000000e+00,2.693415832540576371e+00,0.000000000000000000e+00,-8.409441117972545898e-01,0.000000000000000000e+00,1.000000009621188735e+00,0.000000000000000000e+00 +1.135884158907076191e+01,9.028000000000000114e+01,0.000000000000000000e+00,2.690293610930242885e+00,0.000000000000000000e+00,-8.372313541994872432e-01,0.000000000000000000e+00,1.000000009642064480e+00,0.000000000000000000e+00 +1.136255865547547472e+01,9.029000000000000625e+01,0.000000000000000000e+00,2.687181566390576481e+00,0.000000000000000000e+00,-8.335142877589351018e-01,0.000000000000000000e+00,1.000000009580273463e+00,0.000000000000000000e+00 +1.136628002664185644e+01,9.029999999999999716e+01,0.000000000000000000e+00,2.684079750353342675e+00,0.000000000000000000e+00,-8.297929165569010168e-01,0.000000000000000000e+00,1.000000009635915621e+00,0.000000000000000000e+00 +1.137000569835436181e+01,9.031000000000000227e+01,0.000000000000000000e+00,2.680988214356889277e+00,0.000000000000000000e+00,-8.260672448084953601e-01,0.000000000000000000e+00,1.000000009636529574e+00,0.000000000000000000e+00 +1.137373566626188470e+01,9.032000000000000739e+01,0.000000000000000000e+00,2.677907010044297209e+00,0.000000000000000000e+00,-8.223372768650278886e-01,0.000000000000000000e+00,1.000000009595519712e+00,0.000000000000000000e+00 +1.137746992587675976e+01,9.032999999999999829e+01,0.000000000000000000e+00,2.674836189161493571e+00,0.000000000000000000e+00,-8.186030172143203831e-01,0.000000000000000000e+00,1.000000009626513586e+00,0.000000000000000000e+00 +1.138120847257375701e+01,9.034000000000000341e+01,0.000000000000000000e+00,2.671775803555334505e+00,0.000000000000000000e+00,-8.148644704813333695e-01,0.000000000000000000e+00,1.000000009605738649e+00,0.000000000000000000e+00 +1.138495130158908530e+01,9.035000000000000853e+01,0.000000000000000000e+00,2.668725905171656532e+00,0.000000000000000000e+00,-8.111216414300520539e-01,0.000000000000000000e+00,1.000000009597236561e+00,0.000000000000000000e+00 +1.138869840801939404e+01,9.035999999999999943e+01,0.000000000000000000e+00,2.665686546053291472e+00,0.000000000000000000e+00,-8.073745349637815316e-01,0.000000000000000000e+00,1.000000009640799714e+00,0.000000000000000000e+00 +1.139244978682077836e+01,9.037000000000000455e+01,0.000000000000000000e+00,2.662657778338050729e+00,0.000000000000000000e+00,-8.036231561262308087e-01,0.000000000000000000e+00,1.000000009574444348e+00,0.000000000000000000e+00 +1.139620543280778975e+01,9.037999999999999545e+01,0.000000000000000000e+00,2.659639654256675811e+00,0.000000000000000000e+00,-7.998675101032611812e-01,0.000000000000000000e+00,1.000000009643538412e+00,0.000000000000000000e+00 +1.139996534065244660e+01,9.039000000000000057e+01,0.000000000000000000e+00,2.656632226130752450e+00,0.000000000000000000e+00,-7.961076022223455562e-01,0.000000000000000000e+00,1.000000009597266537e+00,0.000000000000000000e+00 +1.140372950488325010e+01,9.040000000000000568e+01,0.000000000000000000e+00,2.653635546370596732e+00,0.000000000000000000e+00,-7.923434379554168405e-01,0.000000000000000000e+00,1.000000009610755081e+00,0.000000000000000000e+00 +1.140749791988420192e+01,9.040999999999999659e+01,0.000000000000000000e+00,2.650649667473100379e+00,0.000000000000000000e+00,-7.885750229182484361e-01,0.000000000000000000e+00,1.000000009571493820e+00,0.000000000000000000e+00 +1.141127057989382720e+01,9.042000000000000171e+01,0.000000000000000000e+00,2.647674642019548052e+00,0.000000000000000000e+00,-7.848023628725140366e-01,0.000000000000000000e+00,1.000000009651792476e+00,0.000000000000000000e+00 +1.141504747900419936e+01,9.043000000000000682e+01,0.000000000000000000e+00,2.644710522673396458e+00,0.000000000000000000e+00,-7.810254637256874855e-01,0.000000000000000000e+00,1.000000009568243975e+00,0.000000000000000000e+00 +1.141882861115997549e+01,9.043999999999999773e+01,0.000000000000000000e+00,2.641757362178023261e+00,0.000000000000000000e+00,-7.772443315337325132e-01,0.000000000000000000e+00,1.000000009617211694e+00,0.000000000000000000e+00 +1.142261397015742475e+01,9.045000000000000284e+01,0.000000000000000000e+00,2.638815213354435141e+00,0.000000000000000000e+00,-7.734589724998780502e-01,0.000000000000000000e+00,1.000000009593609906e+00,0.000000000000000000e+00 +1.142640354964347260e+01,9.046000000000000796e+01,0.000000000000000000e+00,2.635884129098949646e+00,0.000000000000000000e+00,-7.696693929774740539e-01,0.000000000000000000e+00,1.000000009605267470e+00,0.000000000000000000e+00 +1.143019734311474345e+01,9.046999999999999886e+01,0.000000000000000000e+00,2.632964162380835305e+00,0.000000000000000000e+00,-7.658755994697635794e-01,0.000000000000000000e+00,1.000000009583325022e+00,0.000000000000000000e+00 +1.143399534391660666e+01,9.048000000000000398e+01,0.000000000000000000e+00,2.630055366239921533e+00,0.000000000000000000e+00,-7.620775986315027062e-01,0.000000000000000000e+00,1.000000009628045694e+00,0.000000000000000000e+00 +1.143779754524223691e+01,9.048999999999999488e+01,0.000000000000000000e+00,2.627157793784171247e+00,0.000000000000000000e+00,-7.582753972692640732e-01,0.000000000000000000e+00,1.000000009552442615e+00,0.000000000000000000e+00 +1.144160394013167270e+01,9.050000000000000000e+01,0.000000000000000000e+00,2.624271498187221052e+00,0.000000000000000000e+00,-7.544690023434684756e-01,0.000000000000000000e+00,1.000000009624398611e+00,0.000000000000000000e+00 +1.144541452147087846e+01,9.051000000000000512e+01,0.000000000000000000e+00,2.621396532685882352e+00,0.000000000000000000e+00,-7.506584209675888353e-01,0.000000000000000000e+00,1.000000009589442573e+00,0.000000000000000000e+00 +1.144922928199081902e+01,9.051999999999999602e+01,0.000000000000000000e+00,2.618532950577614038e+00,0.000000000000000000e+00,-7.468436604110665344e-01,0.000000000000000000e+00,1.000000009563459580e+00,0.000000000000000000e+00 +1.145304821426653952e+01,9.053000000000000114e+01,0.000000000000000000e+00,2.615680805217952543e+00,0.000000000000000000e+00,-7.430247280988232506e-01,0.000000000000000000e+00,1.000000009636733189e+00,0.000000000000000000e+00 +1.145687131071624876e+01,9.054000000000000625e+01,0.000000000000000000e+00,2.612840150017912144e+00,0.000000000000000000e+00,-7.392016316122723696e-01,0.000000000000000000e+00,1.000000009543902557e+00,0.000000000000000000e+00 +1.146069856360040617e+01,9.054999999999999716e+01,0.000000000000000000e+00,2.610011038441349740e+00,0.000000000000000000e+00,-7.353743786915873937e-01,0.000000000000000000e+00,1.000000009607532325e+00,0.000000000000000000e+00 +1.146452996502082833e+01,9.056000000000000227e+01,0.000000000000000000e+00,2.607193524002289209e+00,0.000000000000000000e+00,-7.315429772343555737e-01,0.000000000000000000e+00,1.000000009586285987e+00,0.000000000000000000e+00 +1.146836550691978474e+01,9.057000000000000739e+01,0.000000000000000000e+00,2.604387660262219129e+00,0.000000000000000000e+00,-7.277074352986300232e-01,0.000000000000000000e+00,1.000000009586166527e+00,0.000000000000000000e+00 +1.147220518107912035e+01,9.057999999999999829e+01,0.000000000000000000e+00,2.601593500827346972e+00,0.000000000000000000e+00,-7.238677611024871839e-01,0.000000000000000000e+00,1.000000009576019755e+00,0.000000000000000000e+00 +1.147604897911936739e+01,9.059000000000000341e+01,0.000000000000000000e+00,2.598811099345823106e+00,0.000000000000000000e+00,-7.200239630254317014e-01,0.000000000000000000e+00,1.000000009569036896e+00,0.000000000000000000e+00 +1.147989689249888023e+01,9.060000000000000853e+01,0.000000000000000000e+00,2.596040509504927485e+00,0.000000000000000000e+00,-7.161760496090977535e-01,0.000000000000000000e+00,1.000000009591849315e+00,0.000000000000000000e+00 +1.148374891251297036e+01,9.060999999999999943e+01,0.000000000000000000e+00,2.593281785028221709e+00,0.000000000000000000e+00,-7.123240295580602899e-01,0.000000000000000000e+00,1.000000009563462688e+00,0.000000000000000000e+00 +1.148760503029304836e+01,9.062000000000000455e+01,0.000000000000000000e+00,2.590534979672665994e+00,0.000000000000000000e+00,-7.084679117411043503e-01,0.000000000000000000e+00,1.000000009592845629e+00,0.000000000000000000e+00 +1.149146523680578369e+01,9.062999999999999545e+01,0.000000000000000000e+00,2.587800147225699288e+00,0.000000000000000000e+00,-7.046077051913390843e-01,0.000000000000000000e+00,1.000000009587672878e+00,0.000000000000000000e+00 +1.149532952285226273e+01,9.064000000000000057e+01,0.000000000000000000e+00,2.585077341502286963e+00,0.000000000000000000e+00,-7.007434191078107943e-01,0.000000000000000000e+00,1.000000009550324087e+00,0.000000000000000000e+00 +1.149919787906716451e+01,9.065000000000000568e+01,0.000000000000000000e+00,2.582366616341930321e+00,0.000000000000000000e+00,-6.968750628559657878e-01,0.000000000000000000e+00,1.000000009602582729e+00,0.000000000000000000e+00 +1.150307029591793828e+01,9.065999999999999659e+01,0.000000000000000000e+00,2.579668025605642345e+00,0.000000000000000000e+00,-6.930026459680060924e-01,0.000000000000000000e+00,1.000000009537070023e+00,0.000000000000000000e+00 +1.150694676370400238e+01,9.067000000000000171e+01,0.000000000000000000e+00,2.576981623172890146e+00,0.000000000000000000e+00,-6.891261781449717905e-01,0.000000000000000000e+00,1.000000009582229898e+00,0.000000000000000000e+00 +1.151082727255593952e+01,9.068000000000000682e+01,0.000000000000000000e+00,2.574307462938497437e+00,0.000000000000000000e+00,-6.852456692558513973e-01,0.000000000000000000e+00,1.000000009568185133e+00,0.000000000000000000e+00 +1.151471181243470987e+01,9.068999999999999773e+01,0.000000000000000000e+00,2.571645598809518596e+00,0.000000000000000000e+00,-6.813611293399133295e-01,0.000000000000000000e+00,1.000000009571006432e+00,0.000000000000000000e+00 +1.151860037313087659e+01,9.070000000000000284e+01,0.000000000000000000e+00,2.568996084702071858e+00,0.000000000000000000e+00,-6.774725686065294905e-01,0.000000000000000000e+00,1.000000009551003544e+00,0.000000000000000000e+00 +1.152249294426383663e+01,9.071000000000000796e+01,0.000000000000000000e+00,2.566358974538141435e+00,0.000000000000000000e+00,-6.735799974363909648e-01,0.000000000000000000e+00,1.000000009580809923e+00,0.000000000000000000e+00 +1.152638951528106936e+01,9.071999999999999886e+01,0.000000000000000000e+00,2.563734322242343211e+00,0.000000000000000000e+00,-6.696834263818260968e-01,0.000000000000000000e+00,1.000000009543713153e+00,0.000000000000000000e+00 +1.153029007545738871e+01,9.073000000000000398e+01,0.000000000000000000e+00,2.561122181738657577e+00,0.000000000000000000e+00,-6.657828661682815286e-01,0.000000000000000000e+00,1.000000009563783765e+00,0.000000000000000000e+00 +1.153419461389421308e+01,9.073999999999999488e+01,0.000000000000000000e+00,2.558522606947124967e+00,0.000000000000000000e+00,-6.618783276941158089e-01,0.000000000000000000e+00,1.000000009557450387e+00,0.000000000000000000e+00 +1.153810311951884415e+01,9.075000000000000000e+01,0.000000000000000000e+00,2.555935651780510742e+00,0.000000000000000000e+00,-6.579698220321288371e-01,0.000000000000000000e+00,1.000000009573686732e+00,0.000000000000000000e+00 +1.154201558108376346e+01,9.076000000000000512e+01,0.000000000000000000e+00,2.553361370140932785e+00,0.000000000000000000e+00,-6.540573604297521548e-01,0.000000000000000000e+00,1.000000009520955357e+00,0.000000000000000000e+00 +1.154593198716593427e+01,9.076999999999999602e+01,0.000000000000000000e+00,2.550799815916457103e+00,0.000000000000000000e+00,-6.501409543102933952e-01,0.000000000000000000e+00,1.000000009589959715e+00,0.000000000000000000e+00 +1.154985232616611768e+01,9.078000000000000114e+01,0.000000000000000000e+00,2.548251042977657477e+00,0.000000000000000000e+00,-6.462206152725132879e-01,0.000000000000000000e+00,1.000000009517770794e+00,0.000000000000000000e+00 +1.155377658630820825e+01,9.079000000000000625e+01,0.000000000000000000e+00,2.545715105174145787e+00,0.000000000000000000e+00,-6.422963550930717025e-01,0.000000000000000000e+00,1.000000009586385463e+00,0.000000000000000000e+00 +1.155770475563857680e+01,9.079999999999999716e+01,0.000000000000000000e+00,2.543192056331061934e+00,0.000000000000000000e+00,-6.383681857250466107e-01,0.000000000000000000e+00,1.000000009511792687e+00,0.000000000000000000e+00 +1.156163682202542553e+01,9.081000000000000227e+01,0.000000000000000000e+00,2.540681950245538889e+00,0.000000000000000000e+00,-6.344361193007969080e-01,0.000000000000000000e+00,1.000000009581486271e+00,0.000000000000000000e+00 +1.156557277315816457e+01,9.082000000000000739e+01,0.000000000000000000e+00,2.538184840683125998e+00,0.000000000000000000e+00,-6.305001681303450400e-01,0.000000000000000000e+00,1.000000009517868049e+00,0.000000000000000000e+00 +1.156951259654679909e+01,9.082999999999999829e+01,0.000000000000000000e+00,2.535700781374188306e+00,0.000000000000000000e+00,-6.265603447042121799e-01,0.000000000000000000e+00,1.000000009552637126e+00,0.000000000000000000e+00 +1.157345627952132538e+01,9.084000000000000341e+01,0.000000000000000000e+00,2.533229826010264585e+00,0.000000000000000000e+00,-6.226166616920126851e-01,0.000000000000000000e+00,1.000000009549757651e+00,0.000000000000000000e+00 +1.157740380923115353e+01,9.085000000000000853e+01,0.000000000000000000e+00,2.530772028240400928e+00,0.000000000000000000e+00,-6.186691319444859172e-01,0.000000000000000000e+00,1.000000009532195477e+00,0.000000000000000000e+00 +1.158135517264453540e+01,9.085999999999999943e+01,0.000000000000000000e+00,2.528327441667446607e+00,0.000000000000000000e+00,-6.147177684934386210e-01,0.000000000000000000e+00,1.000000009519613764e+00,0.000000000000000000e+00 +1.158531035654801222e+01,9.087000000000000455e+01,0.000000000000000000e+00,2.525896119844320609e+00,0.000000000000000000e+00,-6.107625845523106944e-01,0.000000000000000000e+00,1.000000009566300863e+00,0.000000000000000000e+00 +1.158926934754587457e+01,9.087999999999999545e+01,0.000000000000000000e+00,2.523478116270246652e+00,0.000000000000000000e+00,-6.068035935165750905e-01,0.000000000000000000e+00,1.000000009514468324e+00,0.000000000000000000e+00 +1.159323213205964720e+01,9.089000000000000057e+01,0.000000000000000000e+00,2.521073484386957553e+00,0.000000000000000000e+00,-6.028408089650986179e-01,0.000000000000000000e+00,1.000000009540209067e+00,0.000000000000000000e+00 +1.159719869632757927e+01,9.090000000000000568e+01,0.000000000000000000e+00,2.518682277574865402e+00,0.000000000000000000e+00,-5.988742446593248170e-01,0.000000000000000000e+00,1.000000009537169054e+00,0.000000000000000000e+00 +1.160116902640415759e+01,9.090999999999999659e+01,0.000000000000000000e+00,2.516304549149206427e+00,0.000000000000000000e+00,-5.949039145448808963e-01,0.000000000000000000e+00,1.000000009518956512e+00,0.000000000000000000e+00 +1.160514310815963590e+01,9.092000000000000171e+01,0.000000000000000000e+00,2.513940352356151209e+00,0.000000000000000000e+00,-5.909298327515738469e-01,0.000000000000000000e+00,1.000000009510693122e+00,0.000000000000000000e+00 +1.160912092727958012e+01,9.093000000000000682e+01,0.000000000000000000e+00,2.511589740368886936e+00,0.000000000000000000e+00,-5.869520135937984495e-01,0.000000000000000000e+00,1.000000009553036806e+00,0.000000000000000000e+00 +1.161310246926443135e+01,9.093999999999999773e+01,0.000000000000000000e+00,2.509252766283670333e+00,0.000000000000000000e+00,-5.829704715709115304e-01,0.000000000000000000e+00,1.000000009510238819e+00,0.000000000000000000e+00 +1.161708771942908847e+01,9.095000000000000284e+01,0.000000000000000000e+00,2.506929483115851731e+00,0.000000000000000000e+00,-5.789852213683530646e-01,0.000000000000000000e+00,1.000000009520314981e+00,0.000000000000000000e+00 +1.162107666290250840e+01,9.096000000000000796e+01,0.000000000000000000e+00,2.504619943795867609e+00,0.000000000000000000e+00,-5.749962778569567279e-01,0.000000000000000000e+00,1.000000009520991107e+00,0.000000000000000000e+00 +1.162506928462732247e+01,9.096999999999999886e+01,0.000000000000000000e+00,2.502324201165209150e+00,0.000000000000000000e+00,-5.710036560941297301e-01,0.000000000000000000e+00,1.000000009502820975e+00,0.000000000000000000e+00 +1.162906556935947044e+01,9.098000000000000398e+01,0.000000000000000000e+00,2.500042307972359712e+00,0.000000000000000000e+00,-5.670073713240061375e-01,0.000000000000000000e+00,1.000000009536453405e+00,0.000000000000000000e+00 +1.163306550166785946e+01,9.098999999999999488e+01,0.000000000000000000e+00,2.497774316868705657e+00,0.000000000000000000e+00,-5.630074389774711863e-01,0.000000000000000000e+00,1.000000009494038444e+00,0.000000000000000000e+00 +1.163706906593404078e+01,9.100000000000000000e+01,0.000000000000000000e+00,2.495520280404421420e+00,0.000000000000000000e+00,-5.590038746732802766e-01,0.000000000000000000e+00,1.000000009519824706e+00,0.000000000000000000e+00 +1.164107624635189708e+01,9.101000000000000512e+01,0.000000000000000000e+00,2.493280251024324823e+00,0.000000000000000000e+00,-5.549966942172762652e-01,0.000000000000000000e+00,1.000000009528202449e+00,0.000000000000000000e+00 +1.164508702692736186e+01,9.101999999999999602e+01,0.000000000000000000e+00,2.491054281063710629e+00,0.000000000000000000e+00,-5.509859136035952787e-01,0.000000000000000000e+00,1.000000009478285712e+00,0.000000000000000000e+00 +1.164910139147815293e+01,9.103000000000000114e+01,0.000000000000000000e+00,2.488842422744154792e+00,0.000000000000000000e+00,-5.469715490147543102e-01,0.000000000000000000e+00,1.000000009506966103e+00,0.000000000000000000e+00 +1.165311932363352554e+01,9.104000000000000625e+01,0.000000000000000000e+00,2.486644728169294272e+00,0.000000000000000000e+00,-5.429536168211830383e-01,0.000000000000000000e+00,1.000000009510403576e+00,0.000000000000000000e+00 +1.165714080683404852e+01,9.104999999999999716e+01,0.000000000000000000e+00,2.484461249320585097e+00,0.000000000000000000e+00,-5.389321335824148740e-01,0.000000000000000000e+00,1.000000009497066689e+00,0.000000000000000000e+00 +1.166116582433139648e+01,9.106000000000000227e+01,0.000000000000000000e+00,2.482292038053032446e+00,0.000000000000000000e+00,-5.349071160468403807e-01,0.000000000000000000e+00,1.000000009498035691e+00,0.000000000000000000e+00 +1.166519435918817571e+01,9.107000000000000739e+01,0.000000000000000000e+00,2.480137146090898970e+00,0.000000000000000000e+00,-5.308785811517988673e-01,0.000000000000000000e+00,1.000000009504887988e+00,0.000000000000000000e+00 +1.166922639427775188e+01,9.107999999999999829e+01,0.000000000000000000e+00,2.477996625023390465e+00,0.000000000000000000e+00,-5.268465460238985765e-01,0.000000000000000000e+00,1.000000009489029340e+00,0.000000000000000000e+00 +1.167326191228411858e+01,9.109000000000000341e+01,0.000000000000000000e+00,2.475870526300318453e+00,0.000000000000000000e+00,-5.228110279792378412e-01,0.000000000000000000e+00,1.000000009474731888e+00,0.000000000000000000e+00 +1.167730089570177832e+01,9.110000000000000853e+01,0.000000000000000000e+00,2.473758901227740559e+00,0.000000000000000000e+00,-5.187720445233096056e-01,0.000000000000000000e+00,1.000000009501683218e+00,0.000000000000000000e+00 +1.168134332683564303e+01,9.110999999999999943e+01,0.000000000000000000e+00,2.471661800963580458e+00,0.000000000000000000e+00,-5.147296133510341765e-01,0.000000000000000000e+00,1.000000009478725138e+00,0.000000000000000000e+00 +1.168538918780096658e+01,9.112000000000000455e+01,0.000000000000000000e+00,2.469579276513227395e+00,0.000000000000000000e+00,-5.106837523473609641e-01,0.000000000000000000e+00,1.000000009498368536e+00,0.000000000000000000e+00 +1.168943846052328972e+01,9.112999999999999545e+01,0.000000000000000000e+00,2.467511378725113502e+00,0.000000000000000000e+00,-5.066344795865761474e-01,0.000000000000000000e+00,1.000000009472044926e+00,0.000000000000000000e+00 +1.169349112673841695e+01,9.114000000000000057e+01,0.000000000000000000e+00,2.465458158286274681e+00,0.000000000000000000e+00,-5.025818133330623994e-01,0.000000000000000000e+00,1.000000009496088138e+00,0.000000000000000000e+00 +1.169754716799240946e+01,9.115000000000000568e+01,0.000000000000000000e+00,2.463419665717889728e+00,0.000000000000000000e+00,-4.985257720405539827e-01,0.000000000000000000e+00,1.000000009459535377e+00,0.000000000000000000e+00 +1.170160656564160639e+01,9.115999999999999659e+01,0.000000000000000000e+00,2.461395951370804358e+00,0.000000000000000000e+00,-4.944663743529573163e-01,0.000000000000000000e+00,1.000000009488693387e+00,0.000000000000000000e+00 +1.170566930085266932e+01,9.117000000000000171e+01,0.000000000000000000e+00,2.459387065421034357e+00,0.000000000000000000e+00,-4.904036391033451125e-01,0.000000000000000000e+00,1.000000009473040130e+00,0.000000000000000000e+00 +1.170973535460264614e+01,9.118000000000000682e+01,0.000000000000000000e+00,2.457393057865255859e+00,0.000000000000000000e+00,-4.863375853148502737e-01,0.000000000000000000e+00,1.000000009453804850e+00,0.000000000000000000e+00 +1.171380470767906701e+01,9.118999999999999773e+01,0.000000000000000000e+00,2.455413978516275630e+00,0.000000000000000000e+00,-4.822682321999582356e-01,0.000000000000000000e+00,1.000000009471774254e+00,0.000000000000000000e+00 +1.171787734068005804e+01,9.120000000000000284e+01,0.000000000000000000e+00,2.453449876998488488e+00,0.000000000000000000e+00,-4.781955991603921707e-01,0.000000000000000000e+00,1.000000009469691697e+00,0.000000000000000000e+00 +1.172195323401448164e+01,9.121000000000000796e+01,0.000000000000000000e+00,2.451500802743320051e+00,0.000000000000000000e+00,-4.741197057873713372e-01,0.000000000000000000e+00,1.000000009461740724e+00,0.000000000000000000e+00 +1.172603236790210168e+01,9.121999999999999886e+01,0.000000000000000000e+00,2.449566804984653956e+00,0.000000000000000000e+00,-4.700405718611547767e-01,0.000000000000000000e+00,1.000000009487088226e+00,0.000000000000000000e+00 +1.173011472237377895e+01,9.123000000000000398e+01,0.000000000000000000e+00,2.447647932754247080e+00,0.000000000000000000e+00,-4.659582173507483827e-01,0.000000000000000000e+00,1.000000009430756620e+00,0.000000000000000000e+00 +1.173420027727167891e+01,9.123999999999999488e+01,0.000000000000000000e+00,2.445744234877132772e+00,0.000000000000000000e+00,-4.618726624143180692e-01,0.000000000000000000e+00,1.000000009455498828e+00,0.000000000000000000e+00 +1.173828901224952226e+01,9.125000000000000000e+01,0.000000000000000000e+00,2.443855759967009877e+00,0.000000000000000000e+00,-4.577839273978140389e-01,0.000000000000000000e+00,1.000000009448608118e+00,0.000000000000000000e+00 +1.174238090677284596e+01,9.126000000000000512e+01,0.000000000000000000e+00,2.441982556421625539e+00,0.000000000000000000e+00,-4.536920328358284848e-01,0.000000000000000000e+00,1.000000009452108873e+00,0.000000000000000000e+00 +1.174647594011929819e+01,9.126999999999999602e+01,0.000000000000000000e+00,2.440124672418143348e+00,0.000000000000000000e+00,-4.495969994506700540e-01,0.000000000000000000e+00,1.000000009454147909e+00,0.000000000000000000e+00 +1.175057409137895981e+01,9.128000000000000114e+01,0.000000000000000000e+00,2.438282155908504834e+00,0.000000000000000000e+00,-4.454988481522646482e-01,0.000000000000000000e+00,1.000000009445502158e+00,0.000000000000000000e+00 +1.175467533945468723e+01,9.129000000000000625e+01,0.000000000000000000e+00,2.436455054614781623e+00,0.000000000000000000e+00,-4.413976000377989872e-01,0.000000000000000000e+00,1.000000009448529736e+00,0.000000000000000000e+00 +1.175877966306248723e+01,9.129999999999999716e+01,0.000000000000000000e+00,2.434643416024520057e+00,0.000000000000000000e+00,-4.372932763912187881e-01,0.000000000000000000e+00,1.000000009413436031e+00,0.000000000000000000e+00 +1.176288704073191482e+01,9.131000000000000227e+01,0.000000000000000000e+00,2.432847287386079582e+00,0.000000000000000000e+00,-4.331858986831258473e-01,0.000000000000000000e+00,1.000000009456756711e+00,0.000000000000000000e+00 +1.176699745080649961e+01,9.132000000000000739e+01,0.000000000000000000e+00,2.431066715703964043e+00,0.000000000000000000e+00,-4.290754885696690946e-01,0.000000000000000000e+00,1.000000009440604298e+00,0.000000000000000000e+00 +1.177111087144419876e+01,9.132999999999999829e+01,0.000000000000000000e+00,2.429301747734150752e+00,0.000000000000000000e+00,-4.249620678931368412e-01,0.000000000000000000e+00,1.000000009420302316e+00,0.000000000000000000e+00 +1.177522728061787483e+01,9.134000000000000341e+01,0.000000000000000000e+00,2.427552429979411119e+00,0.000000000000000000e+00,-4.208456586806830213e-01,0.000000000000000000e+00,1.000000009432741033e+00,0.000000000000000000e+00 +1.177934665611580556e+01,9.135000000000000853e+01,0.000000000000000000e+00,2.425818808684631289e+00,0.000000000000000000e+00,-4.167262831438950377e-01,0.000000000000000000e+00,1.000000009416764701e+00,0.000000000000000000e+00 +1.178346897554221862e+01,9.135999999999999943e+01,0.000000000000000000e+00,2.424100929832130102e+00,0.000000000000000000e+00,-4.126039636786625886e-01,0.000000000000000000e+00,1.000000009421008862e+00,0.000000000000000000e+00 +1.178759421631785465e+01,9.137000000000000455e+01,0.000000000000000000e+00,2.422398839136973958e+00,0.000000000000000000e+00,-4.084787228641629242e-01,0.000000000000000000e+00,1.000000009418089641e+00,0.000000000000000000e+00 +1.179172235568055527e+01,9.137999999999999545e+01,0.000000000000000000e+00,2.420712582042293004e+00,0.000000000000000000e+00,-4.043505834625837903e-01,0.000000000000000000e+00,1.000000009432318038e+00,0.000000000000000000e+00 +1.179585337068588125e+01,9.139000000000000057e+01,0.000000000000000000e+00,2.419042203714596440e+00,0.000000000000000000e+00,-4.002195684182919821e-01,0.000000000000000000e+00,1.000000009405739076e+00,0.000000000000000000e+00 +1.179998723820776441e+01,9.140000000000000568e+01,0.000000000000000000e+00,2.417387749039090039e+00,0.000000000000000000e+00,-3.960857008575269234e-01,0.000000000000000000e+00,1.000000009402456591e+00,0.000000000000000000e+00 +1.180412393493917378e+01,9.140999999999999659e+01,0.000000000000000000e+00,2.415749262614994564e+00,0.000000000000000000e+00,-3.919490040872220527e-01,0.000000000000000000e+00,1.000000009421470271e+00,0.000000000000000000e+00 +1.180826343739282436e+01,9.142000000000000171e+01,0.000000000000000000e+00,2.414126788750869501e+00,0.000000000000000000e+00,-3.878095015945710045e-01,0.000000000000000000e+00,1.000000009392282729e+00,0.000000000000000000e+00 +1.181240572190190541e+01,9.143000000000000682e+01,0.000000000000000000e+00,2.412520371459939916e+00,0.000000000000000000e+00,-3.836672170465845744e-01,0.000000000000000000e+00,1.000000009402340462e+00,0.000000000000000000e+00 +1.181655076462083898e+01,9.143999999999999773e+01,0.000000000000000000e+00,2.410930054455427296e+00,0.000000000000000000e+00,-3.795221742886774607e-01,0.000000000000000000e+00,1.000000009380115573e+00,0.000000000000000000e+00 +1.182069854152607036e+01,9.145000000000000284e+01,0.000000000000000000e+00,2.409355881145889278e+00,0.000000000000000000e+00,-3.753743973445388127e-01,0.000000000000000000e+00,1.000000009425034753e+00,0.000000000000000000e+00 +1.182484902841688346e+01,9.146000000000000796e+01,0.000000000000000000e+00,2.407797894630563817e+00,0.000000000000000000e+00,-3.712239104146070057e-01,0.000000000000000000e+00,1.000000009387276290e+00,0.000000000000000000e+00 +1.182900220091624455e+01,9.146999999999999886e+01,0.000000000000000000e+00,2.406256137694724462e+00,0.000000000000000000e+00,-3.670707378762586015e-01,0.000000000000000000e+00,1.000000009376633026e+00,0.000000000000000000e+00 +1.183315803447167802e+01,9.148000000000000398e+01,0.000000000000000000e+00,2.404730652805040503e+00,0.000000000000000000e+00,-3.629149042818571869e-01,0.000000000000000000e+00,1.000000009393468892e+00,0.000000000000000000e+00 +1.183731650435616878e+01,9.148999999999999488e+01,0.000000000000000000e+00,2.403221482104951789e+00,0.000000000000000000e+00,-3.587564343583046211e-01,0.000000000000000000e+00,1.000000009372713938e+00,0.000000000000000000e+00 +1.184147758566909125e+01,9.150000000000000000e+01,0.000000000000000000e+00,2.401728667410052864e+00,0.000000000000000000e+00,-3.545953530063818415e-01,0.000000000000000000e+00,1.000000009380987764e+00,0.000000000000000000e+00 +1.184564125333717222e+01,9.151000000000000512e+01,0.000000000000000000e+00,2.400252250203488202e+00,0.000000000000000000e+00,-3.504316852992409026e-01,0.000000000000000000e+00,1.000000009376681653e+00,0.000000000000000000e+00 +1.184980748211548196e+01,9.151999999999999602e+01,0.000000000000000000e+00,2.398792271631362993e+00,0.000000000000000000e+00,-3.462654564818659630e-01,0.000000000000000000e+00,1.000000009354997887e+00,0.000000000000000000e+00 +1.185397624658844684e+01,9.153000000000000114e+01,0.000000000000000000e+00,2.397348772498166358e+00,0.000000000000000000e+00,-3.420966919699021114e-01,0.000000000000000000e+00,1.000000009389633959e+00,0.000000000000000000e+00 +1.185814752117090087e+01,9.154000000000000625e+01,0.000000000000000000e+00,2.395921793262210553e+00,0.000000000000000000e+00,-3.379254173482809098e-01,0.000000000000000000e+00,1.000000009367755904e+00,0.000000000000000000e+00 +1.186232128010916043e+01,9.154999999999999716e+01,0.000000000000000000e+00,2.394511374031087936e+00,0.000000000000000000e+00,-3.337516583709221885e-01,0.000000000000000000e+00,1.000000009337992379e+00,0.000000000000000000e+00 +1.186649749748212912e+01,9.156000000000000227e+01,0.000000000000000000e+00,2.393117554557142146e+00,0.000000000000000000e+00,-3.295754409589559120e-01,0.000000000000000000e+00,1.000000009372133292e+00,0.000000000000000000e+00 +1.187067614720243114e+01,9.157000000000000739e+01,0.000000000000000000e+00,2.391740374232960598e+00,0.000000000000000000e+00,-3.253967911994910533e-01,0.000000000000000000e+00,1.000000009351898145e+00,0.000000000000000000e+00 +1.187485720301757475e+01,9.157999999999999829e+01,0.000000000000000000e+00,2.390379872086886959e+00,0.000000000000000000e+00,-3.212157353452468334e-01,0.000000000000000000e+00,1.000000009340290763e+00,0.000000000000000000e+00 +1.187904063851114245e+01,9.159000000000000341e+01,0.000000000000000000e+00,2.389036086778550949e+00,0.000000000000000000e+00,-3.170322998126038350e-01,0.000000000000000000e+00,1.000000009367283393e+00,0.000000000000000000e+00 +1.188322642710401489e+01,9.160000000000000853e+01,0.000000000000000000e+00,2.387709056594423007e+00,0.000000000000000000e+00,-3.128465111805212029e-01,0.000000000000000000e+00,1.000000009318211092e+00,0.000000000000000000e+00 +1.188741454205561787e+01,9.160999999999999943e+01,0.000000000000000000e+00,2.386398819443391162e+00,0.000000000000000000e+00,-3.086583961898928807e-01,0.000000000000000000e+00,1.000000009354033770e+00,0.000000000000000000e+00 +1.189160495646519777e+01,9.162000000000000455e+01,0.000000000000000000e+00,2.385105412852359219e+00,0.000000000000000000e+00,-3.044679817411157230e-01,0.000000000000000000e+00,1.000000009317783212e+00,0.000000000000000000e+00 +1.189579764327313249e+01,9.162999999999999545e+01,0.000000000000000000e+00,2.383828873961874706e+00,0.000000000000000000e+00,-3.002752948941143640e-01,0.000000000000000000e+00,1.000000009356738495e+00,0.000000000000000000e+00 +1.189999257526226550e+01,9.164000000000000057e+01,0.000000000000000000e+00,2.382569239521777238e+00,0.000000000000000000e+00,-2.960803628657311393e-01,0.000000000000000000e+00,1.000000009304762072e+00,0.000000000000000000e+00 +1.190418972505926654e+01,9.165000000000000568e+01,0.000000000000000000e+00,2.381326545886879309e+00,0.000000000000000000e+00,-2.918832130296765137e-01,0.000000000000000000e+00,1.000000009328180228e+00,0.000000000000000000e+00 +1.190838906513602780e+01,9.165999999999999659e+01,0.000000000000000000e+00,2.380100829012669728e+00,0.000000000000000000e+00,-2.876838729137423112e-01,0.000000000000000000e+00,1.000000009309320870e+00,0.000000000000000000e+00 +1.191259056781108328e+01,9.167000000000000171e+01,0.000000000000000000e+00,2.378892124451052137e+00,0.000000000000000000e+00,-2.834823701995730638e-01,0.000000000000000000e+00,1.000000009314948812e+00,0.000000000000000000e+00 +1.191679420525105648e+01,9.168000000000000682e+01,0.000000000000000000e+00,2.377700467346108848e+00,0.000000000000000000e+00,-2.792787327204431236e-01,0.000000000000000000e+00,1.000000009333644968e+00,0.000000000000000000e+00 +1.192099994947213659e+01,9.168999999999999773e+01,0.000000000000000000e+00,2.376525892429899312e+00,0.000000000000000000e+00,-2.750729884601082476e-01,0.000000000000000000e+00,1.000000009290814784e+00,0.000000000000000000e+00 +1.192520777234158302e+01,9.170000000000000284e+01,0.000000000000000000e+00,2.375368434018289676e+00,0.000000000000000000e+00,-2.708651655515669221e-01,0.000000000000000000e+00,1.000000009289160552e+00,0.000000000000000000e+00 +1.192941764557926199e+01,9.171000000000000796e+01,0.000000000000000000e+00,2.374228126006814765e+00,0.000000000000000000e+00,-2.666552922747821852e-01,0.000000000000000000e+00,1.000000009322186578e+00,0.000000000000000000e+00 +1.193362954075919902e+01,9.171999999999999886e+01,0.000000000000000000e+00,2.373105001866577801e+00,0.000000000000000000e+00,-2.624433970555806739e-01,0.000000000000000000e+00,1.000000009264952805e+00,0.000000000000000000e+00 +1.193784342931117415e+01,9.173000000000000398e+01,0.000000000000000000e+00,2.371999094640183881e+00,0.000000000000000000e+00,-2.582295084645642724e-01,0.000000000000000000e+00,1.000000009314346405e+00,0.000000000000000000e+00 +1.194205928252233129e+01,9.173999999999999488e+01,0.000000000000000000e+00,2.370910436937708088e+00,0.000000000000000000e+00,-2.540136552141394888e-01,0.000000000000000000e+00,1.000000009279131907e+00,0.000000000000000000e+00 +1.194627707153882312e+01,9.175000000000000000e+01,0.000000000000000000e+00,2.369839060932707131e+00,0.000000000000000000e+00,-2.497958661585109597e-01,0.000000000000000000e+00,1.000000009270719525e+00,0.000000000000000000e+00 +1.195049676736747735e+01,9.176000000000000512e+01,0.000000000000000000e+00,2.368784998358262950e+00,0.000000000000000000e+00,-2.455761702907369448e-01,0.000000000000000000e+00,1.000000009269272461e+00,0.000000000000000000e+00 +1.195471834087749663e+01,9.176999999999999602e+01,0.000000000000000000e+00,2.367748280503071623e+00,0.000000000000000000e+00,-2.413545967415868798e-01,0.000000000000000000e+00,1.000000009289663039e+00,0.000000000000000000e+00 +1.195894176280217636e+01,9.178000000000000114e+01,0.000000000000000000e+00,2.366728938207570909e+00,0.000000000000000000e+00,-2.371311747776727319e-01,0.000000000000000000e+00,1.000000009248708910e+00,0.000000000000000000e+00 +1.196316700374065611e+01,9.179000000000000625e+01,0.000000000000000000e+00,2.365727001860110423e+00,0.000000000000000000e+00,-2.329059338001146784e-01,0.000000000000000000e+00,1.000000009255889388e+00,0.000000000000000000e+00 +1.196739403415969250e+01,9.179999999999999716e+01,0.000000000000000000e+00,2.364742501393163110e+00,0.000000000000000000e+00,-2.286789033419527051e-01,0.000000000000000000e+00,1.000000009281824642e+00,0.000000000000000000e+00 +1.197162282439546210e+01,9.181000000000000227e+01,0.000000000000000000e+00,2.363775466279584236e+00,0.000000000000000000e+00,-2.244501130669325495e-01,0.000000000000000000e+00,1.000000009226376552e+00,0.000000000000000000e+00 +1.197585334465538232e+01,9.182000000000000739e+01,0.000000000000000000e+00,2.362825925528913018e+00,0.000000000000000000e+00,-2.202195927679791720e-01,0.000000000000000000e+00,1.000000009259088607e+00,0.000000000000000000e+00 +1.198008556501997113e+01,9.182999999999999829e+01,0.000000000000000000e+00,2.361893907683719096e+00,0.000000000000000000e+00,-2.159873723642046495e-01,0.000000000000000000e+00,1.000000009242134169e+00,0.000000000000000000e+00 +1.198431945544471411e+01,9.184000000000000341e+01,0.000000000000000000e+00,2.360979440816000974e+00,0.000000000000000000e+00,-2.117534819003318580e-01,0.000000000000000000e+00,1.000000009245429533e+00,0.000000000000000000e+00 +1.198855498576197220e+01,9.185000000000000853e+01,0.000000000000000000e+00,2.360082552523627086e+00,0.000000000000000000e+00,-2.075179515439141420e-01,0.000000000000000000e+00,1.000000009219173869e+00,0.000000000000000000e+00 +1.199279212568290731e+01,9.185999999999999943e+01,0.000000000000000000e+00,2.359203269926829716e+00,0.000000000000000000e+00,-2.032808115839162266e-01,0.000000000000000000e+00,1.000000009236543752e+00,0.000000000000000000e+00 +1.199703084479942916e+01,9.187000000000000455e+01,0.000000000000000000e+00,2.358341619664746869e+00,0.000000000000000000e+00,-1.990420924282431392e-01,0.000000000000000000e+00,1.000000009192817840e+00,0.000000000000000000e+00 +1.200127111258617241e+01,9.187999999999999545e+01,0.000000000000000000e+00,2.357497627892017444e+00,0.000000000000000000e+00,-1.948018246025200184e-01,0.000000000000000000e+00,1.000000009246675647e+00,0.000000000000000000e+00 +1.200551289840249147e+01,9.189000000000000057e+01,0.000000000000000000e+00,2.356671320275425252e+00,0.000000000000000000e+00,-1.905600387469777723e-01,0.000000000000000000e+00,1.000000009199648376e+00,0.000000000000000000e+00 +1.200975617149448560e+01,9.190000000000000568e+01,0.000000000000000000e+00,2.355862721990600761e+00,0.000000000000000000e+00,-1.863167656159465946e-01,0.000000000000000000e+00,1.000000009209941698e+00,0.000000000000000000e+00 +1.201400090099703988e+01,9.190999999999999659e+01,0.000000000000000000e+00,2.355071857718770367e+00,0.000000000000000000e+00,-1.820720360742991706e-01,0.000000000000000000e+00,1.000000009173724891e+00,0.000000000000000000e+00 +1.201824705593588938e+01,9.192000000000000171e+01,0.000000000000000000e+00,2.354298751643566945e+00,0.000000000000000000e+00,-1.778258810964957748e-01,0.000000000000000000e+00,1.000000009217318686e+00,0.000000000000000000e+00 +1.202249460522971525e+01,9.193000000000000682e+01,0.000000000000000000e+00,2.353543427447891467e+00,0.000000000000000000e+00,-1.735783317635183620e-01,0.000000000000000000e+00,1.000000009204397244e+00,0.000000000000000000e+00 +1.202674351769224970e+01,9.193999999999999773e+01,0.000000000000000000e+00,2.352805908310835470e+00,0.000000000000000000e+00,-1.693294192618749749e-01,0.000000000000000000e+00,1.000000009155137759e+00,0.000000000000000000e+00 +1.203099376203440940e+01,9.195000000000000284e+01,0.000000000000000000e+00,2.352086216904656357e+00,0.000000000000000000e+00,-1.650791748808028703e-01,0.000000000000000000e+00,1.000000009173319215e+00,0.000000000000000000e+00 +1.203524530686645200e+01,9.196000000000000796e+01,0.000000000000000000e+00,2.351384375391813997e+00,0.000000000000000000e+00,-1.608276300097593314e-01,0.000000000000000000e+00,1.000000009178065863e+00,0.000000000000000000e+00 +1.203949812070014680e+01,9.196999999999999886e+01,0.000000000000000000e+00,2.350700405422068151e+00,0.000000000000000000e+00,-1.565748161370319746e-01,0.000000000000000000e+00,1.000000009177258509e+00,0.000000000000000000e+00 +1.204375217195097214e+01,9.198000000000000398e+01,0.000000000000000000e+00,2.350034328129632755e+00,0.000000000000000000e+00,-1.523207648471666953e-01,0.000000000000000000e+00,1.000000009148339419e+00,0.000000000000000000e+00 +1.204800742894032872e+01,9.198999999999999488e+01,0.000000000000000000e+00,2.349386164130392807e+00,0.000000000000000000e+00,-1.480655078188822249e-01,0.000000000000000000e+00,1.000000009165522119e+00,0.000000000000000000e+00 +1.205226385989777427e+01,9.200000000000000000e+01,0.000000000000000000e+00,2.348755933519182548e+00,0.000000000000000000e+00,-1.438090768224237759e-01,0.000000000000000000e+00,1.000000009135510570e+00,0.000000000000000000e+00 +1.205652143296328127e+01,9.201000000000000512e+01,0.000000000000000000e+00,2.348143655867128032e+00,0.000000000000000000e+00,-1.395515037180221074e-01,0.000000000000000000e+00,1.000000009147132385e+00,0.000000000000000000e+00 +1.206078011618950363e+01,9.201999999999999602e+01,0.000000000000000000e+00,2.347549350219050091e+00,0.000000000000000000e+00,-1.352928204528457690e-01,0.000000000000000000e+00,1.000000009111036814e+00,0.000000000000000000e+00 +1.206503987754406992e+01,9.203000000000000114e+01,0.000000000000000000e+00,2.346973035090934800e+00,0.000000000000000000e+00,-1.310330590594687705e-01,0.000000000000000000e+00,1.000000009159744296e+00,0.000000000000000000e+00 +1.206930068491189445e+01,9.204000000000000625e+01,0.000000000000000000e+00,2.346414728467465682e+00,0.000000000000000000e+00,-1.267722516526167409e-01,0.000000000000000000e+00,1.000000009093993780e+00,0.000000000000000000e+00 +1.207356250609750070e+01,9.204999999999999716e+01,0.000000000000000000e+00,2.345874447799625617e+00,0.000000000000000000e+00,-1.225104304282540191e-01,0.000000000000000000e+00,1.000000009126814859e+00,0.000000000000000000e+00 +1.207782530882736616e+01,9.206000000000000227e+01,0.000000000000000000e+00,2.345352210002359161e+00,0.000000000000000000e+00,-1.182476276594835451e-01,0.000000000000000000e+00,1.000000009112138377e+00,0.000000000000000000e+00 +1.208208906075228128e+01,9.207000000000000739e+01,0.000000000000000000e+00,2.344848031452309467e+00,0.000000000000000000e+00,-1.139838756957171628e-01,0.000000000000000000e+00,1.000000009094940134e+00,0.000000000000000000e+00 +1.208635372944972630e+01,9.207999999999999829e+01,0.000000000000000000e+00,2.344361927985616489e+00,0.000000000000000000e+00,-1.097192069594853381e-01,0.000000000000000000e+00,1.000000009104444532e+00,0.000000000000000000e+00 +1.209061928242626394e+01,9.209000000000000341e+01,0.000000000000000000e+00,2.343893914895787134e+00,0.000000000000000000e+00,-1.054536539441124493e-01,0.000000000000000000e+00,1.000000009095292297e+00,0.000000000000000000e+00 +1.209488568711994461e+01,9.210000000000000853e+01,0.000000000000000000e+00,2.343444006931634238e+00,0.000000000000000000e+00,-1.011872492116279859e-01,0.000000000000000000e+00,1.000000009060599382e+00,0.000000000000000000e+00 +1.209915291090272760e+01,9.210999999999999943e+01,0.000000000000000000e+00,2.343012218295283944e+00,0.000000000000000000e+00,-9.692002539018093610e-02,0.000000000000000000e+00,1.000000009072807838e+00,0.000000000000000000e+00 +1.210342092108292000e+01,9.212000000000000455e+01,0.000000000000000000e+00,2.342598562640254123e+00,0.000000000000000000e+00,-9.265201517126546438e-02,0.000000000000000000e+00,1.000000009081768670e+00,0.000000000000000000e+00 +1.210768968490762276e+01,9.212999999999999545e+01,0.000000000000000000e+00,2.342203053069605190e+00,0.000000000000000000e+00,-8.838325130779452199e-02,0.000000000000000000e+00,1.000000009031199344e+00,0.000000000000000000e+00 +1.211195916956519447e+01,9.214000000000000057e+01,0.000000000000000000e+00,2.341825702134160192e+00,0.000000000000000000e+00,-8.411376661166351798e-02,0.000000000000000000e+00,1.000000009073347851e+00,0.000000000000000000e+00 +1.211622934218772940e+01,9.215000000000000568e+01,0.000000000000000000e+00,2.341466521830796843e+00,0.000000000000000000e+00,-7.984359395038465035e-02,0.000000000000000000e+00,1.000000009029798020e+00,0.000000000000000000e+00 +1.212050016985353729e+01,9.215999999999999659e+01,0.000000000000000000e+00,2.341125523600815939e+00,0.000000000000000000e+00,-7.557276624601116932e-02,0.000000000000000000e+00,1.000000009046989158e+00,0.000000000000000000e+00 +1.212477161958965333e+01,9.217000000000000171e+01,0.000000000000000000e+00,2.340802718328376830e+00,0.000000000000000000e+00,-7.130131647125104166e-02,0.000000000000000000e+00,1.000000009035161286e+00,0.000000000000000000e+00 +1.212904365837434106e+01,9.218000000000000682e+01,0.000000000000000000e+00,2.340498116339012391e+00,0.000000000000000000e+00,-6.702927764796530463e-02,0.000000000000000000e+00,1.000000009009613056e+00,0.000000000000000000e+00 +1.213331625313961304e+01,9.218999999999999773e+01,0.000000000000000000e+00,2.340211727398213704e+00,0.000000000000000000e+00,-6.275668284419846921e-02,0.000000000000000000e+00,1.000000008994700540e+00,0.000000000000000000e+00 +1.213758937077376743e+01,9.220000000000000284e+01,0.000000000000000000e+00,2.339943560710091131e+00,0.000000000000000000e+00,-5.848356517160875623e-02,0.000000000000000000e+00,1.000000009026656755e+00,0.000000000000000000e+00 +1.214186297812392290e+01,9.221000000000000796e+01,0.000000000000000000e+00,2.339693624916110437e+00,0.000000000000000000e+00,-5.420995778287673178e-02,0.000000000000000000e+00,1.000000008987367739e+00,0.000000000000000000e+00 +1.214613704199857125e+01,9.221999999999999886e+01,0.000000000000000000e+00,2.339461928093904408e+00,0.000000000000000000e+00,-4.993589386981536760e-02,0.000000000000000000e+00,1.000000008998715106e+00,0.000000000000000000e+00 +1.215041152917013534e+01,9.223000000000000398e+01,0.000000000000000000e+00,2.339248477756157296e+00,0.000000000000000000e+00,-4.566140665978637991e-02,0.000000000000000000e+00,1.000000008967095511e+00,0.000000000000000000e+00 +1.215468640637753239e+01,9.223999999999999488e+01,0.000000000000000000e+00,2.339053280849569649e+00,0.000000000000000000e+00,-4.138652941405526059e-02,0.000000000000000000e+00,1.000000008980212796e+00,0.000000000000000000e+00 +1.215896164032875149e+01,9.225000000000000000e+01,0.000000000000000000e+00,2.338876343753895526e+00,0.000000000000000000e+00,-3.711129542444301099e-02,0.000000000000000000e+00,1.000000008951586139e+00,0.000000000000000000e+00 +1.216323719770343104e+01,9.226000000000000512e+01,0.000000000000000000e+00,2.338717672281059645e+00,0.000000000000000000e+00,-3.283573801149065885e-02,0.000000000000000000e+00,1.000000008946866803e+00,0.000000000000000000e+00 +1.216751304515544341e+01,9.226999999999999602e+01,0.000000000000000000e+00,2.338577271674348257e+00,0.000000000000000000e+00,-2.855989052122253832e-02,0.000000000000000000e+00,1.000000008952520059e+00,0.000000000000000000e+00 +1.217178914931549194e+01,9.228000000000000114e+01,0.000000000000000000e+00,2.338455146607679946e+00,0.000000000000000000e+00,-2.428378632289279401e-02,0.000000000000000000e+00,1.000000008937452112e+00,0.000000000000000000e+00 +1.217606547679370266e+01,9.229000000000000625e+01,0.000000000000000000e+00,2.338351301184952380e+00,0.000000000000000000e+00,-2.000745880646332894e-02,0.000000000000000000e+00,1.000000008940176377e+00,0.000000000000000000e+00 +1.218034199418222840e+01,9.229999999999999716e+01,0.000000000000000000e+00,2.338265738939466321e+00,0.000000000000000000e+00,-1.573094137970444326e-02,0.000000000000000000e+00,1.000000008890169267e+00,0.000000000000000000e+00 +1.218461866805785654e+01,9.231000000000000227e+01,0.000000000000000000e+00,2.338198462833428692e+00,0.000000000000000000e+00,-1.145426746605541189e-02,0.000000000000000000e+00,1.000000008916203109e+00,0.000000000000000000e+00 +1.218889546498461662e+01,9.232000000000000739e+01,0.000000000000000000e+00,2.338149475257531584e+00,0.000000000000000000e+00,-7.177470501163033846e-03,0.000000000000000000e+00,1.000000008903312088e+00,0.000000000000000000e+00 +1.219317235151638990e+01,9.232999999999999829e+01,0.000000000000000000e+00,2.338118778030612965e+00,0.000000000000000000e+00,-2.900583931312024442e-03,0.000000000000000000e+00,1.000000008876623436e+00,0.000000000000000000e+00 +1.219744929419952584e+01,9.234000000000000341e+01,0.000000000000000000e+00,2.338106372399391120e+00,0.000000000000000000e+00,1.376358789788394241e-03,0.000000000000000000e+00,1.000000008876624324e+00,0.000000000000000000e+00 +1.220172625957545876e+01,9.235000000000000853e+01,0.000000000000000000e+00,2.338112259038279905e+00,0.000000000000000000e+00,5.653324203686192415e-03,0.000000000000000000e+00,1.000000008860078893e+00,0.000000000000000000e+00 +1.220600321418332435e+01,9.235999999999999943e+01,0.000000000000000000e+00,2.338136438049282617e+00,0.000000000000000000e+00,9.930278849445597911e-03,0.000000000000000000e+00,1.000000008869337487e+00,0.000000000000000000e+00 +1.221028012456257628e+01,9.237000000000000455e+01,0.000000000000000000e+00,2.338178908961962676e+00,0.000000000000000000e+00,1.420718926663084095e-02,0.000000000000000000e+00,1.000000008838806131e+00,0.000000000000000000e+00 +1.221455695725560631e+01,9.237999999999999545e+01,0.000000000000000000e+00,2.338239670733494258e+00,0.000000000000000000e+00,1.848402199746219249e-02,0.000000000000000000e+00,1.000000008839778909e+00,0.000000000000000000e+00 +1.221883367881035731e+01,9.239000000000000057e+01,0.000000000000000000e+00,2.338318721748789297e+00,0.000000000000000000e+00,2.276074359001854439e-02,0.000000000000000000e+00,1.000000008816746444e+00,0.000000000000000000e+00 +1.222311025578294519e+01,9.240000000000000568e+01,0.000000000000000000e+00,2.338416059820705328e+00,0.000000000000000000e+00,2.703732060031106485e-02,0.000000000000000000e+00,1.000000008810637331e+00,0.000000000000000000e+00 +1.222738665474026654e+01,9.240999999999999659e+01,0.000000000000000000e+00,2.338531682190329253e+00,0.000000000000000000e+00,3.131371959530988847e-02,0.000000000000000000e+00,1.000000008819186048e+00,0.000000000000000000e+00 +1.223166284226261524e+01,9.242000000000000171e+01,0.000000000000000000e+00,2.338665585527341051e+00,0.000000000000000000e+00,3.558990715537133781e-02,0.000000000000000000e+00,1.000000008780024041e+00,0.000000000000000000e+00 +1.223593878494629017e+01,9.243000000000000682e+01,0.000000000000000000e+00,2.338817765930454762e+00,0.000000000000000000e+00,3.986584987659001073e-02,0.000000000000000000e+00,1.000000008773680893e+00,0.000000000000000000e+00 +1.224021444940620285e+01,9.243999999999999773e+01,0.000000000000000000e+00,2.338988218927936291e+00,0.000000000000000000e+00,4.414151437401548500e-02,0.000000000000000000e+00,1.000000008790786099e+00,0.000000000000000000e+00 +1.224448980227847272e+01,9.245000000000000284e+01,0.000000000000000000e+00,2.339176939478201600e+00,0.000000000000000000e+00,4.841686728386952049e-02,0.000000000000000000e+00,1.000000008743342939e+00,0.000000000000000000e+00 +1.224876481022303309e+01,9.246000000000000796e+01,0.000000000000000000e+00,2.339383921970490832e+00,0.000000000000000000e+00,5.269187526580701442e-02,0.000000000000000000e+00,1.000000008720393518e+00,0.000000000000000000e+00 +1.225303943992621392e+01,9.246999999999999886e+01,0.000000000000000000e+00,2.339609160225618378e+00,0.000000000000000000e+00,5.696650500626484342e-02,0.000000000000000000e+00,1.000000008759069692e+00,0.000000000000000000e+00 +1.225731365810333706e+01,9.248000000000000398e+01,0.000000000000000000e+00,2.339852647496803328e+00,0.000000000000000000e+00,6.124072322082609737e-02,0.000000000000000000e+00,1.000000008713955779e+00,0.000000000000000000e+00 +1.226158743150128849e+01,9.248999999999999488e+01,0.000000000000000000e+00,2.340114376470575852e+00,0.000000000000000000e+00,6.551449665601982719e-02,0.000000000000000000e+00,1.000000008686886765e+00,0.000000000000000000e+00 +1.226586072690109752e+01,9.250000000000000000e+01,0.000000000000000000e+00,2.340394339267756862e+00,0.000000000000000000e+00,6.978779209295105090e-02,0.000000000000000000e+00,1.000000008728874068e+00,0.000000000000000000e+00 +1.227013351112049833e+01,9.251000000000000512e+01,0.000000000000000000e+00,2.340692527444518500e+00,0.000000000000000000e+00,7.406057634964920144e-02,0.000000000000000000e+00,1.000000008640200555e+00,0.000000000000000000e+00 +1.227440575101649145e+01,9.251999999999999602e+01,0.000000000000000000e+00,2.341008931993519671e+00,0.000000000000000000e+00,7.833281628255471529e-02,0.000000000000000000e+00,1.000000008696297682e+00,0.000000000000000000e+00 +1.227867741348788755e+01,9.253000000000000114e+01,0.000000000000000000e+00,2.341343543345112632e+00,0.000000000000000000e+00,8.260447879109855673e-02,0.000000000000000000e+00,1.000000008647605299e+00,0.000000000000000000e+00 +1.228294846547785468e+01,9.254000000000000625e+01,0.000000000000000000e+00,2.341696351368633522e+00,0.000000000000000000e+00,8.687553081799970212e-02,0.000000000000000000e+00,1.000000008618322056e+00,0.000000000000000000e+00 +1.228721887397644430e+01,9.254999999999999716e+01,0.000000000000000000e+00,2.342067345373758158e+00,0.000000000000000000e+00,9.114593935339268538e-02,0.000000000000000000e+00,1.000000008644035931e+00,0.000000000000000000e+00 +1.229148860602311366e+01,9.256000000000000227e+01,0.000000000000000000e+00,2.342456514111939114e+00,0.000000000000000000e+00,9.541567143696969011e-02,0.000000000000000000e+00,1.000000008599363888e+00,0.000000000000000000e+00 +1.229575762870923583e+01,9.257000000000000739e+01,0.000000000000000000e+00,2.342863845777915177e+00,0.000000000000000000e+00,9.968469415980336923e-02,0.000000000000000000e+00,1.000000008614337910e+00,0.000000000000000000e+00 +1.230002590918060079e+01,9.257999999999999829e+01,0.000000000000000000e+00,2.343289328011291417e+00,0.000000000000000000e+00,1.039529746679363625e-01,0.000000000000000000e+00,1.000000008566142018e+00,0.000000000000000000e+00 +1.230429341463989701e+01,9.259000000000000341e+01,0.000000000000000000e+00,2.343732947898196972e+00,0.000000000000000000e+00,1.082204801637891706e-01,0.000000000000000000e+00,1.000000008571085397e+00,0.000000000000000000e+00 +1.230856011234919301e+01,9.260000000000000853e+01,0.000000000000000000e+00,2.344194691973010780e+00,0.000000000000000000e+00,1.124871779096559138e-01,0.000000000000000000e+00,1.000000008551507058e+00,0.000000000000000000e+00 +1.231282596963239584e+01,9.260999999999999943e+01,0.000000000000000000e+00,2.344674546220163691e+00,0.000000000000000000e+00,1.167530352293389001e-01,0.000000000000000000e+00,1.000000008535205653e+00,0.000000000000000000e+00 +1.231709095387770247e+01,9.262000000000000455e+01,0.000000000000000000e+00,2.345172496076008528e+00,0.000000000000000000e+00,1.210180195110478474e-01,0.000000000000000000e+00,1.000000008517138328e+00,0.000000000000000000e+00 +1.232135503254003162e+01,9.262999999999999545e+01,0.000000000000000000e+00,2.345688526430762977e+00,0.000000000000000000e+00,1.252820982096952140e-01,0.000000000000000000e+00,1.000000008492800241e+00,0.000000000000000000e+00 +1.232561817314345021e+01,9.264000000000000057e+01,0.000000000000000000e+00,2.346222621630522198e+00,0.000000000000000000e+00,1.295452388493197604e-01,0.000000000000000000e+00,1.000000008492991199e+00,0.000000000000000000e+00 +1.232988034328357507e+01,9.265000000000000568e+01,0.000000000000000000e+00,2.346774765479341163e+00,0.000000000000000000e+00,1.338074090256435866e-01,0.000000000000000000e+00,1.000000008472745838e+00,0.000000000000000000e+00 +1.233414151062996744e+01,9.265999999999999659e+01,0.000000000000000000e+00,2.347344941241386707e+00,0.000000000000000000e+00,1.380685764081405198e-01,0.000000000000000000e+00,1.000000008470389945e+00,0.000000000000000000e+00 +1.233840164292850794e+01,9.267000000000000171e+01,0.000000000000000000e+00,2.347933131643156646e+00,0.000000000000000000e+00,1.423287087427668185e-01,0.000000000000000000e+00,1.000000008400690366e+00,0.000000000000000000e+00 +1.234266070800375559e+01,9.268000000000000682e+01,0.000000000000000000e+00,2.348539318875768167e+00,0.000000000000000000e+00,1.465877738537943176e-01,0.000000000000000000e+00,1.000000008436461751e+00,0.000000000000000000e+00 +1.234691867376129082e+01,9.268999999999999773e+01,0.000000000000000000e+00,2.349163484597311058e+00,0.000000000000000000e+00,1.508457396472525081e-01,0.000000000000000000e+00,1.000000008387346595e+00,0.000000000000000000e+00 +1.235117550819004251e+01,9.270000000000000284e+01,0.000000000000000000e+00,2.349805609935271988e+00,0.000000000000000000e+00,1.551025741117076917e-01,0.000000000000000000e+00,1.000000008401807028e+00,0.000000000000000000e+00 +1.235543117936459367e+01,9.271000000000000796e+01,0.000000000000000000e+00,2.350465675489017858e+00,0.000000000000000000e+00,1.593582453220141193e-01,0.000000000000000000e+00,1.000000008347518676e+00,0.000000000000000000e+00 +1.235968565544747477e+01,9.271999999999999886e+01,0.000000000000000000e+00,2.351143661332350199e+00,0.000000000000000000e+00,1.636127214404091146e-01,0.000000000000000000e+00,1.000000008344402502e+00,0.000000000000000000e+00 +1.236393890469143386e+01,9.273000000000000398e+01,0.000000000000000000e+00,2.351839547016118637e+00,0.000000000000000000e+00,1.678659707198585926e-01,0.000000000000000000e+00,1.000000008317766476e+00,0.000000000000000000e+00 +1.236819089544169081e+01,9.273999999999999488e+01,0.000000000000000000e+00,2.352553311570902306e+00,0.000000000000000000e+00,1.721179615054821699e-01,0.000000000000000000e+00,1.000000008312874389e+00,0.000000000000000000e+00 +1.237244159613817018e+01,9.275000000000000000e+01,0.000000000000000000e+00,2.353284933509750321e+00,0.000000000000000000e+00,1.763686622372973856e-01,0.000000000000000000e+00,1.000000008270231167e+00,0.000000000000000000e+00 +1.237669097531771811e+01,9.276000000000000512e+01,0.000000000000000000e+00,2.354034390830986201e+00,0.000000000000000000e+00,1.806180414519885924e-01,0.000000000000000000e+00,1.000000008268696838e+00,0.000000000000000000e+00 +1.238093900161629257e+01,9.276999999999999602e+01,0.000000000000000000e+00,2.354801661021071357e+00,0.000000000000000000e+00,1.848660677856892309e-01,0.000000000000000000e+00,1.000000008252961203e+00,0.000000000000000000e+00 +1.238518564377114117e+01,9.278000000000000114e+01,0.000000000000000000e+00,2.355586721057531197e+00,0.000000000000000000e+00,1.891127099755853802e-01,0.000000000000000000e+00,1.000000008204520174e+00,0.000000000000000000e+00 +1.238943087062295056e+01,9.279000000000000625e+01,0.000000000000000000e+00,2.356389547411938068e+00,0.000000000000000000e+00,1.933579368622252159e-01,0.000000000000000000e+00,1.000000008190710554e+00,0.000000000000000000e+00 +1.239367465111798161e+01,9.279999999999999716e+01,0.000000000000000000e+00,2.357210116052953275e+00,0.000000000000000000e+00,1.976017173920150694e-01,0.000000000000000000e+00,1.000000008192549972e+00,0.000000000000000000e+00 +1.239791695431017438e+01,9.281000000000000227e+01,0.000000000000000000e+00,2.358048402449428149e+00,0.000000000000000000e+00,2.018440206189628938e-01,0.000000000000000000e+00,1.000000008130287776e+00,0.000000000000000000e+00 +1.240215774936324067e+01,9.282000000000000739e+01,0.000000000000000000e+00,2.358904381573560194e+00,0.000000000000000000e+00,2.060848157065087449e-01,0.000000000000000000e+00,1.000000008136765262e+00,0.000000000000000000e+00 +1.240639700555272995e+01,9.282999999999999829e+01,0.000000000000000000e+00,2.359778027904103848e+00,0.000000000000000000e+00,2.103240719304922401e-01,0.000000000000000000e+00,1.000000008115456529e+00,0.000000000000000000e+00 +1.241063469226807037e+01,9.284000000000000341e+01,0.000000000000000000e+00,2.360669315429639870e+00,0.000000000000000000e+00,2.145617586802228138e-01,0.000000000000000000e+00,1.000000008064445556e+00,0.000000000000000000e+00 +1.241487077901458669e+01,9.285000000000000853e+01,0.000000000000000000e+00,2.361578217651894462e+00,0.000000000000000000e+00,2.187978454609011414e-01,0.000000000000000000e+00,1.000000008055824230e+00,0.000000000000000000e+00 +1.241910523541550226e+01,9.285999999999999943e+01,0.000000000000000000e+00,2.362504707589113018e+00,0.000000000000000000e+00,2.230323018959292358e-01,0.000000000000000000e+00,1.000000008041872501e+00,0.000000000000000000e+00 +1.242333803121390901e+01,9.287000000000000455e+01,0.000000000000000000e+00,2.363448757779487153e+00,0.000000000000000000e+00,2.272650977283758589e-01,0.000000000000000000e+00,1.000000008008457009e+00,0.000000000000000000e+00 +1.242756913627471604e+01,9.287999999999999545e+01,0.000000000000000000e+00,2.364410340284630596e+00,0.000000000000000000e+00,2.314962028230679869e-01,0.000000000000000000e+00,1.000000007955591075e+00,0.000000000000000000e+00 +1.243179852058657708e+01,9.289000000000000057e+01,0.000000000000000000e+00,2.365389426693105701e+00,0.000000000000000000e+00,2.357255871685755011e-01,0.000000000000000000e+00,1.000000007953397274e+00,0.000000000000000000e+00 +1.243602615426378577e+01,9.290000000000000568e+01,0.000000000000000000e+00,2.366385988123999251e+00,0.000000000000000000e+00,2.399532208794077637e-01,0.000000000000000000e+00,1.000000007924849887e+00,0.000000000000000000e+00 +1.244025200754815508e+01,9.290999999999999659e+01,0.000000000000000000e+00,2.367399995230547560e+00,0.000000000000000000e+00,2.441790741972666157e-01,0.000000000000000000e+00,1.000000007901044707e+00,0.000000000000000000e+00 +1.244447605081086827e+01,9.292000000000000171e+01,0.000000000000000000e+00,2.368431418203805983e+00,0.000000000000000000e+00,2.484031174933538089e-01,0.000000000000000000e+00,1.000000007854673356e+00,0.000000000000000000e+00 +1.244869825455429968e+01,9.293000000000000682e+01,0.000000000000000000e+00,2.369480226776366383e+00,0.000000000000000000e+00,2.526253212699489659e-01,0.000000000000000000e+00,1.000000007857180684e+00,0.000000000000000000e+00 +1.245291858941381591e+01,9.293999999999999773e+01,0.000000000000000000e+00,2.370546390226118572e+00,0.000000000000000000e+00,2.568456561626256685e-01,0.000000000000000000e+00,1.000000007787931855e+00,0.000000000000000000e+00 +1.245713702615955043e+01,9.295000000000000284e+01,0.000000000000000000e+00,2.371629877380057483e+00,0.000000000000000000e+00,2.610640929412138544e-01,0.000000000000000000e+00,1.000000007766421950e+00,0.000000000000000000e+00 +1.246135353569814974e+01,9.296000000000000796e+01,0.000000000000000000e+00,2.372730656618129874e+00,0.000000000000000000e+00,2.652806025125603040e-01,0.000000000000000000e+00,1.000000007737431362e+00,0.000000000000000000e+00 +1.246556808907449110e+01,9.296999999999999886e+01,0.000000000000000000e+00,2.373848695877127213e+00,0.000000000000000000e+00,2.694951559215120751e-01,0.000000000000000000e+00,1.000000007729643814e+00,0.000000000000000000e+00 +1.246978065747338249e+01,9.298000000000000398e+01,0.000000000000000000e+00,2.374983962654616310e+00,0.000000000000000000e+00,2.737077243529644766e-01,0.000000000000000000e+00,1.000000007664963109e+00,0.000000000000000000e+00 +1.247399121222122353e+01,9.298999999999999488e+01,0.000000000000000000e+00,2.376136424012911252e+00,0.000000000000000000e+00,2.779182791330785385e-01,0.000000000000000000e+00,1.000000007618714992e+00,0.000000000000000000e+00 +1.247819972478764861e+01,9.300000000000000000e+01,0.000000000000000000e+00,2.377306046583082200e+00,0.000000000000000000e+00,2.821267917315676277e-01,0.000000000000000000e+00,1.000000007629653354e+00,0.000000000000000000e+00 +1.248240616678714332e+01,9.301000000000000512e+01,0.000000000000000000e+00,2.378492796569004586e+00,0.000000000000000000e+00,2.863332337631561142e-01,0.000000000000000000e+00,1.000000007584175066e+00,0.000000000000000000e+00 +1.248661050998062549e+01,9.301999999999999602e+01,0.000000000000000000e+00,2.379696639751444298e+00,0.000000000000000000e+00,2.905375769885242265e-01,0.000000000000000000e+00,1.000000007502660049e+00,0.000000000000000000e+00 +1.249081272627700301e+01,9.303000000000000114e+01,0.000000000000000000e+00,2.380917541492175715e+00,0.000000000000000000e+00,2.947397933164302430e-01,0.000000000000000000e+00,1.000000007525691847e+00,0.000000000000000000e+00 +1.249501278773471036e+01,9.304000000000000625e+01,0.000000000000000000e+00,2.382155466738136607e+00,0.000000000000000000e+00,2.989398548057456972e-01,0.000000000000000000e+00,1.000000007446422146e+00,0.000000000000000000e+00 +1.249921066656320434e+01,9.304999999999999716e+01,0.000000000000000000e+00,2.383410380025618558e+00,0.000000000000000000e+00,3.031377336654983434e-01,0.000000000000000000e+00,1.000000007400625446e+00,0.000000000000000000e+00 +1.250340633512444199e+01,9.306000000000000227e+01,0.000000000000000000e+00,2.384682245484483598e+00,0.000000000000000000e+00,3.073334022577861591e-01,0.000000000000000000e+00,1.000000007399839852e+00,0.000000000000000000e+00 +1.250759976593432654e+01,9.307000000000000739e+01,0.000000000000000000e+00,2.385971026842418130e+00,0.000000000000000000e+00,3.115268330987017165e-01,0.000000000000000000e+00,1.000000007316020012e+00,0.000000000000000000e+00 +1.251179093166412670e+01,9.307999999999999829e+01,0.000000000000000000e+00,2.387276687429214839e+00,0.000000000000000000e+00,3.157179988591653497e-01,0.000000000000000000e+00,1.000000007296991011e+00,0.000000000000000000e+00 +1.251597980514186759e+01,9.309000000000000341e+01,0.000000000000000000e+00,2.388599190181081244e+00,0.000000000000000000e+00,3.199068723674718395e-01,0.000000000000000000e+00,1.000000007272028757e+00,0.000000000000000000e+00 +1.252016635935368605e+01,9.310000000000000853e+01,0.000000000000000000e+00,2.389938497644981119e+00,0.000000000000000000e+00,3.240934266097355576e-01,0.000000000000000000e+00,1.000000007189932871e+00,0.000000000000000000e+00 +1.252435056744517183e+01,9.310999999999999943e+01,0.000000000000000000e+00,2.391294571982998995e+00,0.000000000000000000e+00,3.282776347313057230e-01,0.000000000000000000e+00,1.000000007157092252e+00,0.000000000000000000e+00 +1.252853240272266611e+01,9.312000000000000455e+01,0.000000000000000000e+00,2.392667374976730876e+00,0.000000000000000000e+00,3.324594700387301649e-01,0.000000000000000000e+00,1.000000007118652334e+00,0.000000000000000000e+00 +1.253271183865454041e+01,9.312999999999999545e+01,0.000000000000000000e+00,2.394056868031702479e+00,0.000000000000000000e+00,3.366389060003559530e-01,0.000000000000000000e+00,1.000000007046549566e+00,0.000000000000000000e+00 +1.253688884887244015e+01,9.314000000000000057e+01,0.000000000000000000e+00,2.395463012181808349e+00,0.000000000000000000e+00,3.408159162476885884e-01,0.000000000000000000e+00,1.000000007001308644e+00,0.000000000000000000e+00 +1.254106340717250490e+01,9.315000000000000568e+01,0.000000000000000000e+00,2.396885768093774072e+00,0.000000000000000000e+00,3.449904745769800107e-01,0.000000000000000000e+00,1.000000006989915757e+00,0.000000000000000000e+00 +1.254523548751655682e+01,9.315999999999999659e+01,0.000000000000000000e+00,2.398325096071641571e+00,0.000000000000000000e+00,3.491625549501936598e-01,0.000000000000000000e+00,1.000000006899282701e+00,0.000000000000000000e+00 +1.254940506403326062e+01,9.317000000000000171e+01,0.000000000000000000e+00,2.399780956061273951e+00,0.000000000000000000e+00,3.533321314956638370e-01,0.000000000000000000e+00,1.000000006838082545e+00,0.000000000000000000e+00 +1.255357211101925508e+01,9.318000000000000682e+01,0.000000000000000000e+00,2.401253307654877656e+00,0.000000000000000000e+00,3.574991785101520603e-01,0.000000000000000000e+00,1.000000006815272791e+00,0.000000000000000000e+00 +1.255773660294025440e+01,9.318999999999999773e+01,0.000000000000000000e+00,2.402742110095546835e+00,0.000000000000000000e+00,3.616636704595328489e-01,0.000000000000000000e+00,1.000000006723405388e+00,0.000000000000000000e+00 +1.256189851443212113e+01,9.320000000000000284e+01,0.000000000000000000e+00,2.404247322281823251e+00,0.000000000000000000e+00,3.658255819793823083e-01,0.000000000000000000e+00,1.000000006681161180e+00,0.000000000000000000e+00 +1.256605782030191421e+01,9.321000000000000796e+01,0.000000000000000000e+00,2.405768902772270401e+00,0.000000000000000000e+00,3.699848878769639304e-01,0.000000000000000000e+00,1.000000006632765892e+00,0.000000000000000000e+00 +1.257021449552889791e+01,9.321999999999999886e+01,0.000000000000000000e+00,2.407306809790066726e+00,0.000000000000000000e+00,3.741415631315173629e-01,0.000000000000000000e+00,1.000000006535798347e+00,0.000000000000000000e+00 +1.257436851526553134e+01,9.323000000000000398e+01,0.000000000000000000e+00,2.408861001227609933e+00,0.000000000000000000e+00,3.782955828953006305e-01,0.000000000000000000e+00,1.000000006498660943e+00,0.000000000000000000e+00 +1.257851985483842583e+01,9.323999999999999488e+01,0.000000000000000000e+00,2.410431434651134630e+00,0.000000000000000000e+00,3.824469224951739244e-01,0.000000000000000000e+00,1.000000006428718891e+00,0.000000000000000000e+00 +1.258266848974927399e+01,9.325000000000000000e+01,0.000000000000000000e+00,2.412018067305344626e+00,0.000000000000000000e+00,3.865955574326926936e-01,0.000000000000000000e+00,1.000000006348727544e+00,0.000000000000000000e+00 +1.258681439567574678e+01,9.326000000000000512e+01,0.000000000000000000e+00,2.413620856118052771e+00,0.000000000000000000e+00,3.907414633854864316e-01,0.000000000000000000e+00,1.000000006275695519e+00,0.000000000000000000e+00 +1.259095754847236392e+01,9.326999999999999602e+01,0.000000000000000000e+00,2.415239757704832790e+00,0.000000000000000000e+00,3.948846162081051658e-01,0.000000000000000000e+00,1.000000006202104830e+00,0.000000000000000000e+00 +1.259509792417133944e+01,9.328000000000000114e+01,0.000000000000000000e+00,2.416874728373680004e+00,0.000000000000000000e+00,3.990249919327594763e-01,0.000000000000000000e+00,1.000000006128290098e+00,0.000000000000000000e+00 +1.259923549898338990e+01,9.329000000000000625e+01,0.000000000000000000e+00,2.418525724129679588e+00,0.000000000000000000e+00,4.031625667701660976e-01,0.000000000000000000e+00,1.000000006068751945e+00,0.000000000000000000e+00 +1.260337024929852134e+01,9.329999999999999716e+01,0.000000000000000000e+00,2.420192700679681952e+00,0.000000000000000000e+00,4.072973171103908552e-01,0.000000000000000000e+00,1.000000005953740834e+00,0.000000000000000000e+00 +1.260750215168678601e+01,9.331000000000000227e+01,0.000000000000000000e+00,2.421875613436984320e+00,0.000000000000000000e+00,4.114292195232561733e-01,0.000000000000000000e+00,1.000000005894690513e+00,0.000000000000000000e+00 +1.261163118289900709e+01,9.332000000000000739e+01,0.000000000000000000e+00,2.423574417526015878e+00,0.000000000000000000e+00,4.155582507598172826e-01,0.000000000000000000e+00,1.000000005798810321e+00,0.000000000000000000e+00 +1.261575731986748039e+01,9.332999999999999829e+01,0.000000000000000000e+00,2.425289067787030017e+00,0.000000000000000000e+00,4.196843877522171695e-01,0.000000000000000000e+00,1.000000005685339755e+00,0.000000000000000000e+00 +1.261988053970664225e+01,9.334000000000000341e+01,0.000000000000000000e+00,2.427019518780796137e+00,0.000000000000000000e+00,4.238076076148201699e-01,0.000000000000000000e+00,1.000000005637898370e+00,0.000000000000000000e+00 +1.262400081971371257e+01,9.335000000000000853e+01,0.000000000000000000e+00,2.428765724793295444e+00,0.000000000000000000e+00,4.279278876451194091e-01,0.000000000000000000e+00,1.000000005519712909e+00,0.000000000000000000e+00 +1.262811813736930944e+01,9.335999999999999943e+01,0.000000000000000000e+00,2.430527639840418974e+00,0.000000000000000000e+00,4.320452053234427048e-01,0.000000000000000000e+00,1.000000005394553693e+00,0.000000000000000000e+00 +1.263223247033803709e+01,9.337000000000000455e+01,0.000000000000000000e+00,2.432305217672662057e+00,0.000000000000000000e+00,4.361595383143656579e-01,0.000000000000000000e+00,1.000000005319845675e+00,0.000000000000000000e+00 +1.263634379646904371e+01,9.337999999999999545e+01,0.000000000000000000e+00,2.434098411779821447e+00,0.000000000000000000e+00,4.402708644672433391e-01,0.000000000000000000e+00,1.000000005190433638e+00,0.000000000000000000e+00 +1.264045209379654899e+01,9.339000000000000057e+01,0.000000000000000000e+00,2.435907175395690683e+00,0.000000000000000000e+00,4.443791618160725099e-01,0.000000000000000000e+00,1.000000005106745249e+00,0.000000000000000000e+00 +1.264455734054035219e+01,9.340000000000000568e+01,0.000000000000000000e+00,2.437731461502750108e+00,0.000000000000000000e+00,4.484844085808401548e-01,0.000000000000000000e+00,1.000000004954497479e+00,0.000000000000000000e+00 +1.264865951510630460e+01,9.340999999999999659e+01,0.000000000000000000e+00,2.439571222836856901e+00,0.000000000000000000e+00,4.525865831671173622e-01,0.000000000000000000e+00,1.000000004851723245e+00,0.000000000000000000e+00 +1.265275859608676079e+01,9.342000000000000171e+01,0.000000000000000000e+00,2.441426411891927106e+00,0.000000000000000000e+00,4.566856641674616468e-01,0.000000000000000000e+00,1.000000004726003811e+00,0.000000000000000000e+00 +1.265685456226099781e+01,9.343000000000000682e+01,0.000000000000000000e+00,2.443296980924616335e+00,0.000000000000000000e+00,4.607816303610569597e-01,0.000000000000000000e+00,1.000000004576192092e+00,0.000000000000000000e+00 +1.266094739259561130e+01,9.343999999999999773e+01,0.000000000000000000e+00,2.445182881958991139e+00,0.000000000000000000e+00,4.648744607144009167e-01,0.000000000000000000e+00,1.000000004443999391e+00,0.000000000000000000e+00 +1.266503706624488323e+01,9.345000000000000284e+01,0.000000000000000000e+00,2.447084066791194612e+00,0.000000000000000000e+00,4.689641343818479746e-01,0.000000000000000000e+00,1.000000004331268677e+00,0.000000000000000000e+00 +1.266912356255112293e+01,9.346000000000000796e+01,0.000000000000000000e+00,2.449000486994104886e+00,0.000000000000000000e+00,4.730506307057872895e-01,0.000000000000000000e+00,1.000000004115863428e+00,0.000000000000000000e+00 +1.267320686104498151e+01,9.346999999999999886e+01,0.000000000000000000e+00,2.450932093921984301e+00,0.000000000000000000e+00,4.771339292164513690e-01,0.000000000000000000e+00,1.000000004026157407e+00,0.000000000000000000e+00 +1.267728694144573964e+01,9.348000000000000398e+01,0.000000000000000000e+00,2.452878838715117027e+00,0.000000000000000000e+00,4.812140096336364747e-01,0.000000000000000000e+00,1.000000003810324500e+00,0.000000000000000000e+00 +1.268136378366157402e+01,9.348999999999999488e+01,0.000000000000000000e+00,2.454840672304442251e+00,0.000000000000000000e+00,4.852908518650047021e-01,0.000000000000000000e+00,1.000000003662815384e+00,0.000000000000000000e+00 +1.268543736778979003e+01,9.350000000000000000e+01,0.000000000000000000e+00,2.456817545416168258e+00,0.000000000000000000e+00,4.893644360081421119e-01,0.000000000000000000e+00,1.000000003443836771e+00,0.000000000000000000e+00 +1.268950767411703673e+01,9.351000000000000512e+01,0.000000000000000000e+00,2.458809408576382083e+00,0.000000000000000000e+00,4.934347423494070406e-01,0.000000000000000000e+00,1.000000003313458619e+00,0.000000000000000000e+00 +1.269357468311949155e+01,9.351999999999999602e+01,0.000000000000000000e+00,2.460816212115640944e+00,0.000000000000000000e+00,4.975017513653374190e-01,0.000000000000000000e+00,1.000000003079837718e+00,0.000000000000000000e+00 +1.269763837546301843e+01,9.353000000000000114e+01,0.000000000000000000e+00,2.462837906173555247e+00,0.000000000000000000e+00,5.015654437213793448e-01,0.000000000000000000e+00,1.000000002861003212e+00,0.000000000000000000e+00 +1.270169873200330635e+01,9.354000000000000625e+01,0.000000000000000000e+00,2.464874440703351599e+00,0.000000000000000000e+00,5.056258002732836321e-01,0.000000000000000000e+00,1.000000002645263342e+00,0.000000000000000000e+00 +1.270575573378597944e+01,9.354999999999999716e+01,0.000000000000000000e+00,2.466925765476426058e+00,0.000000000000000000e+00,5.096828020666890335e-01,0.000000000000000000e+00,1.000000002414787259e+00,0.000000000000000000e+00 +1.270980936204668588e+01,9.356000000000000227e+01,0.000000000000000000e+00,2.468991830086879613e+00,0.000000000000000000e+00,5.137364303371840801e-01,0.000000000000000000e+00,1.000000002187850567e+00,0.000000000000000000e+00 +1.271385959821115641e+01,9.357000000000000739e+01,0.000000000000000000e+00,2.471072583956037239e+00,0.000000000000000000e+00,5.177866665105158583e-01,0.000000000000000000e+00,1.000000001870977595e+00,0.000000000000000000e+00 +1.271790642389524528e+01,9.357999999999999829e+01,0.000000000000000000e+00,2.473167976336950513e+00,0.000000000000000000e+00,5.218334922021757860e-01,0.000000000000000000e+00,1.000000001652549653e+00,0.000000000000000000e+00 +1.272194982090494264e+01,9.359000000000000341e+01,0.000000000000000000e+00,2.475277956318880701e+00,0.000000000000000000e+00,5.258768892185550214e-01,0.000000000000000000e+00,1.000000001310440645e+00,0.000000000000000000e+00 +1.272598977123636743e+01,9.360000000000000853e+01,0.000000000000000000e+00,2.477402472831768065e+00,0.000000000000000000e+00,5.299168395552743549e-01,0.000000000000000000e+00,1.000000001038646502e+00,0.000000000000000000e+00 +1.273002625707573543e+01,9.360999999999999943e+01,0.000000000000000000e+00,2.479541474650675426e+00,0.000000000000000000e+00,5.339533253988345551e-01,0.000000000000000000e+00,1.000000000697949920e+00,0.000000000000000000e+00 +1.273405926079930062e+01,9.362000000000000455e+01,0.000000000000000000e+00,2.481694910400218834e+00,0.000000000000000000e+00,5.379863291252143798e-01,0.000000000000000000e+00,1.000000000315697024e+00,0.000000000000000000e+00 +1.273808876497327880e+01,9.362999999999999545e+01,0.000000000000000000e+00,2.483862728558972499e+00,0.000000000000000000e+00,5.420158333004654327e-01,0.000000000000000000e+00,9.999999999604959333e-01,0.000000000000000000e+00 +1.274211475235374991e+01,9.364000000000000057e+01,0.000000000000000000e+00,2.486044877463855496e+00,0.000000000000000000e+00,5.460418206807771124e-01,0.000000000000000000e+00,9.999999995319370782e-01,0.000000000000000000e+00 +1.274613720588652832e+01,9.365000000000000568e+01,0.000000000000000000e+00,2.488241305314497609e+00,0.000000000000000000e+00,5.500642742116726991e-01,0.000000000000000000e+00,9.999999991520805986e-01,0.000000000000000000e+00 +1.275015610870702254e+01,9.365999999999999659e+01,0.000000000000000000e+00,2.490451960177580304e+00,0.000000000000000000e+00,5.540831770287597546e-01,0.000000000000000000e+00,9.999999986240640792e-01,0.000000000000000000e+00 +1.275417144414006820e+01,9.367000000000000171e+01,0.000000000000000000e+00,2.492676789991158603e+00,0.000000000000000000e+00,5.580985124562809485e-01,0.000000000000000000e+00,9.999999981258215209e-01,0.000000000000000000e+00 +1.275818319569973802e+01,9.368000000000000682e+01,0.000000000000000000e+00,2.494915742568954542e+00,0.000000000000000000e+00,5.621102640084321145e-01,0.000000000000000000e+00,9.999999976108022715e-01,0.000000000000000000e+00 +1.276219134708913217e+01,9.368999999999999773e+01,0.000000000000000000e+00,2.497168765604632856e+00,0.000000000000000000e+00,5.661184153882503622e-01,0.000000000000000000e+00,9.999999970048490949e-01,0.000000000000000000e+00 +1.276619588220014911e+01,9.370000000000000284e+01,0.000000000000000000e+00,2.499435806676048699e+00,0.000000000000000000e+00,5.701229504872736831e-01,0.000000000000000000e+00,9.999999963485428633e-01,0.000000000000000000e+00 +1.277019678511323519e+01,9.371000000000000796e+01,0.000000000000000000e+00,2.501716813249470039e+00,0.000000000000000000e+00,5.741238533857498938e-01,0.000000000000000000e+00,9.999999956627562137e-01,0.000000000000000000e+00 +1.277419404009710746e+01,9.371999999999999886e+01,0.000000000000000000e+00,2.504011732683776525e+00,0.000000000000000000e+00,5.781211083522856953e-01,0.000000000000000000e+00,9.999999948951113771e-01,0.000000000000000000e+00 +1.277818763160847126e+01,9.373000000000000398e+01,0.000000000000000000e+00,2.506320512234632147e+00,0.000000000000000000e+00,5.821146998432621400e-01,0.000000000000000000e+00,9.999999940043631241e-01,0.000000000000000000e+00 +1.278217754429169872e+01,9.373999999999999488e+01,0.000000000000000000e+00,2.508643099058630366e+00,0.000000000000000000e+00,5.861046125025682896e-01,0.000000000000000000e+00,9.999999931010742360e-01,0.000000000000000000e+00 +1.278616376297850721e+01,9.375000000000000000e+01,0.000000000000000000e+00,2.510979440217412595e+00,0.000000000000000000e+00,5.900908311618758839e-01,0.000000000000000000e+00,9.999999920570472600e-01,0.000000000000000000e+00 +1.279014627268760051e+01,9.376000000000000512e+01,0.000000000000000000e+00,2.513329482681761817e+00,0.000000000000000000e+00,5.940733408393364945e-01,0.000000000000000000e+00,9.999999908383859770e-01,0.000000000000000000e+00 +1.279412505862430471e+01,9.376999999999999602e+01,0.000000000000000000e+00,2.515693173335664667e+00,0.000000000000000000e+00,5.980521267395892959e-01,0.000000000000000000e+00,9.999999895610228728e-01,0.000000000000000000e+00 +1.279810010618017913e+01,9.378000000000000114e+01,0.000000000000000000e+00,2.518070458980346871e+00,0.000000000000000000e+00,6.020271742539691218e-01,0.000000000000000000e+00,9.999999880670449315e-01,0.000000000000000000e+00 +1.280207140093260954e+01,9.379000000000000625e+01,0.000000000000000000e+00,2.520461286338282481e+00,0.000000000000000000e+00,6.059984689590107720e-01,0.000000000000000000e+00,9.999999863135687894e-01,0.000000000000000000e+00 +1.280603892864438365e+01,9.379999999999999716e+01,0.000000000000000000e+00,2.522865602057169809e+00,0.000000000000000000e+00,6.099659966164832081e-01,0.000000000000000000e+00,9.999999843974454183e-01,0.000000000000000000e+00 +1.281000267526324699e+01,9.381000000000000227e+01,0.000000000000000000e+00,2.525283352713879825e+00,0.000000000000000000e+00,6.139297431735016852e-01,0.000000000000000000e+00,9.999999820138456563e-01,0.000000000000000000e+00 +1.281396262692144461e+01,9.382000000000000739e+01,0.000000000000000000e+00,2.527714484818377016e+00,0.000000000000000000e+00,6.178896947604757273e-01,0.000000000000000000e+00,9.999999793537994730e-01,0.000000000000000000e+00 +1.281791876993524681e+01,9.382999999999999829e+01,0.000000000000000000e+00,2.530158944817603839e+00,0.000000000000000000e+00,6.218458376925982689e-01,0.000000000000000000e+00,9.999999760221144340e-01,0.000000000000000000e+00 +1.282187109080444820e+01,9.384000000000000341e+01,0.000000000000000000e+00,2.532616679099342516e+00,0.000000000000000000e+00,6.257981584670316844e-01,0.000000000000000000e+00,9.999999720205745568e-01,0.000000000000000000e+00 +1.282581957621186319e+01,9.385000000000000853e+01,0.000000000000000000e+00,2.535087633996036871e+00,0.000000000000000000e+00,6.297466437639704928e-01,0.000000000000000000e+00,9.999999670013542952e-01,0.000000000000000000e+00 +1.282976421302279491e+01,9.385999999999999943e+01,0.000000000000000000e+00,2.537571755788589289e+00,0.000000000000000000e+00,6.336912804447351055e-01,0.000000000000000000e+00,9.999999605684978254e-01,0.000000000000000000e+00 +1.283370498828449513e+01,9.387000000000000455e+01,0.000000000000000000e+00,2.540068990710120822e+00,0.000000000000000000e+00,6.376320555510442967e-01,0.000000000000000000e+00,9.999999518940388965e-01,0.000000000000000000e+00 +1.283764188922560123e+01,9.387999999999999545e+01,0.000000000000000000e+00,2.542579284949698870e+00,0.000000000000000000e+00,6.415689563027615616e-01,0.000000000000000000e+00,9.999999399032470926e-01,0.000000000000000000e+00 +1.284157490325556417e+01,9.389000000000000057e+01,0.000000000000000000e+00,2.545102584656026234e+00,0.000000000000000000e+00,6.455019700963630092e-01,0.000000000000000000e+00,9.999999217623388725e-01,0.000000000000000000e+00 +1.284550401796405872e+01,9.390000000000000568e+01,0.000000000000000000e+00,2.547638835941094193e+00,0.000000000000000000e+00,6.494310844974530150e-01,0.000000000000000000e+00,9.999998915465079241e-01,0.000000000000000000e+00 +1.284942922112037955e+01,9.390999999999999659e+01,0.000000000000000000e+00,2.550187984883776071e+00,0.000000000000000000e+00,6.533562872280712641e-01,0.000000000000000000e+00,9.999998312265239164e-01,0.000000000000000000e+00 +1.285335050067281770e+01,9.392000000000000171e+01,0.000000000000000000e+00,2.552749977533340875e+00,0.000000000000000000e+00,6.572775661187021390e-01,0.000000000000000000e+00,9.999996499929686422e-01,0.000000000000000000e+00 +1.285726784474803530e+01,9.393000000000000682e+01,0.000000000000000000e+00,2.555324759912748878e+00,0.000000000000000000e+00,6.611949088228209481e-01,0.000000000000000000e+00,1.056785000206537650e-01,0.000000000000000000e+00 +1.286118124165040832e+01,9.393999999999999773e+01,0.000000000000000000e+00,2.557912278020801011e+00,0.000000000000000000e+00,6.616084707374492169e-01,0.000000000000000000e+00,-9.999996451770121197e-01,0.000000000000000000e+00 +1.286509067986137644e+01,9.395000000000000284e+01,0.000000000000000000e+00,2.560498795457002430e+00,0.000000000000000000e+00,6.576990339136392638e-01,0.000000000000000000e+00,-9.999998263274196830e-01,0.000000000000000000e+00 +1.286899616890817555e+01,9.396000000000000796e+01,0.000000000000000000e+00,2.563067431830042597e+00,0.000000000000000000e+00,6.537935455451163724e-01,0.000000000000000000e+00,-9.999998867854658080e-01,0.000000000000000000e+00 +1.287289774398022146e+01,9.396999999999999886e+01,0.000000000000000000e+00,2.565618256429605726e+00,0.000000000000000000e+00,6.498919709147857882e-01,0.000000000000000000e+00,-9.999999169087602224e-01,0.000000000000000000e+00 +1.287679543997413667e+01,9.398000000000000398e+01,0.000000000000000000e+00,2.568151337761117592e+00,0.000000000000000000e+00,6.459942752447355163e-01,0.000000000000000000e+00,-9.999999350232522399e-01,0.000000000000000000e+00 +1.288068929149797981e+01,9.398999999999999488e+01,0.000000000000000000e+00,2.570666743554173017e+00,0.000000000000000000e+00,6.421004239739025454e-01,0.000000000000000000e+00,-9.999999471273554041e-01,0.000000000000000000e+00 +1.288457933287540591e+01,9.400000000000000000e+01,0.000000000000000000e+00,2.573164540771894604e+00,0.000000000000000000e+00,6.382103828021528091e-01,0.000000000000000000e+00,-9.999999557164065411e-01,0.000000000000000000e+00 +1.288846559814975912e+01,9.401000000000000512e+01,0.000000000000000000e+00,2.575644795620310568e+00,0.000000000000000000e+00,6.343241176998969388e-01,0.000000000000000000e+00,-9.999999621496038493e-01,0.000000000000000000e+00 +1.289234812108809436e+01,9.401999999999999602e+01,0.000000000000000000e+00,2.578107573557619769e+00,0.000000000000000000e+00,6.304415949085165893e-01,0.000000000000000000e+00,-9.999999672120614136e-01,0.000000000000000000e+00 +1.289622693518513330e+01,9.403000000000000114e+01,0.000000000000000000e+00,2.580552939303311089e+00,0.000000000000000000e+00,6.265627809386552505e-01,0.000000000000000000e+00,-9.999999712063922797e-01,0.000000000000000000e+00 +1.290010207366715989e+01,9.404000000000000625e+01,0.000000000000000000e+00,2.582980956847131804e+00,0.000000000000000000e+00,6.226876425682082994e-01,0.000000000000000000e+00,-9.999999745142570395e-01,0.000000000000000000e+00 +1.290397356949584307e+01,9.404999999999999716e+01,0.000000000000000000e+00,2.585391689457906761e+00,0.000000000000000000e+00,6.188161468381937480e-01,0.000000000000000000e+00,-9.999999771802361437e-01,0.000000000000000000e+00 +1.290784145537200445e+01,9.406000000000000227e+01,0.000000000000000000e+00,2.587785199692202998e+00,0.000000000000000000e+00,6.149482610502963187e-01,0.000000000000000000e+00,-9.999999795566617555e-01,0.000000000000000000e+00 +1.291170576373932555e+01,9.407000000000000739e+01,0.000000000000000000e+00,2.590161549402849150e+00,0.000000000000000000e+00,6.110839527619746914e-01,0.000000000000000000e+00,-9.999999815205622422e-01,0.000000000000000000e+00 +1.291556652678798756e+01,9.407999999999999829e+01,0.000000000000000000e+00,2.592520799747302984e+00,0.000000000000000000e+00,6.072231897846572801e-01,0.000000000000000000e+00,-9.999999831994780264e-01,0.000000000000000000e+00 +1.291942377645825957e+01,9.409000000000000341e+01,0.000000000000000000e+00,2.594863011195881697e+00,0.000000000000000000e+00,6.033659401791885424e-01,0.000000000000000000e+00,-9.999999847141723963e-01,0.000000000000000000e+00 +1.292327754444402821e+01,9.410000000000000853e+01,0.000000000000000000e+00,2.597188243539847008e+00,0.000000000000000000e+00,5.995121722523286678e-01,0.000000000000000000e+00,-9.999999860334012336e-01,0.000000000000000000e+00 +1.292712786219626331e+01,9.410999999999999943e+01,0.000000000000000000e+00,2.599496555899351691e+00,0.000000000000000000e+00,5.956618545538685527e-01,0.000000000000000000e+00,-9.999999871831667386e-01,0.000000000000000000e+00 +1.293097476092644449e+01,9.412000000000000455e+01,0.000000000000000000e+00,2.601788006731252434e+00,0.000000000000000000e+00,5.918149558729922655e-01,0.000000000000000000e+00,-9.999999882735249868e-01,0.000000000000000000e+00 +1.293481827160991671e+01,9.412999999999999545e+01,0.000000000000000000e+00,2.604062653836788588e+00,0.000000000000000000e+00,5.879714452345914388e-01,0.000000000000000000e+00,-9.999999891596610402e-01,0.000000000000000000e+00 +1.293865842498920138e+01,9.414000000000000057e+01,0.000000000000000000e+00,2.606320554369129017e+00,0.000000000000000000e+00,5.841312918969354673e-01,0.000000000000000000e+00,-9.999999900614403581e-01,0.000000000000000000e+00 +1.294249525157725778e+01,9.415000000000000568e+01,0.000000000000000000e+00,2.608561764840794606e+00,0.000000000000000000e+00,5.802944653470121228e-01,0.000000000000000000e+00,-9.999999907645157338e-01,0.000000000000000000e+00 +1.294632878166068757e+01,9.415999999999999659e+01,0.000000000000000000e+00,2.610786341130949761e+00,0.000000000000000000e+00,5.764609352989875646e-01,0.000000000000000000e+00,-9.999999915348040114e-01,0.000000000000000000e+00 +1.295015904530289319e+01,9.417000000000000171e+01,0.000000000000000000e+00,2.612994338492577118e+00,0.000000000000000000e+00,5.726306716892062276e-01,0.000000000000000000e+00,-9.999999920983333457e-01,0.000000000000000000e+00 +1.295398607234718824e+01,9.418000000000000682e+01,0.000000000000000000e+00,2.615185811559524343e+00,0.000000000000000000e+00,5.688036446751514319e-01,0.000000000000000000e+00,-9.999999927631998409e-01,0.000000000000000000e+00 +1.295780989241985637e+01,9.418999999999999773e+01,0.000000000000000000e+00,2.617360814353440368e+00,0.000000000000000000e+00,5.649798246301548366e-01,0.000000000000000000e+00,-9.999999932672085645e-01,0.000000000000000000e+00 +1.296163053493316930e+01,9.420000000000000284e+01,0.000000000000000000e+00,2.619519400290586830e+00,0.000000000000000000e+00,5.611591821425647719e-01,0.000000000000000000e+00,-9.999999937443235787e-01,0.000000000000000000e+00 +1.296544802908835337e+01,9.421000000000000796e+01,0.000000000000000000e+00,2.621661622188543816e+00,0.000000000000000000e+00,5.573416880112619376e-01,0.000000000000000000e+00,-9.999999942620285687e-01,0.000000000000000000e+00 +1.296926240387851159e+01,9.421999999999999886e+01,0.000000000000000000e+00,2.623787532272797929e+00,0.000000000000000000e+00,5.535273132429909815e-01,0.000000000000000000e+00,-9.999999946570390374e-01,0.000000000000000000e+00 +1.297307368809150496e+01,9.423000000000000398e+01,0.000000000000000000e+00,2.625897182183221545e+00,0.000000000000000000e+00,5.497160290503612101e-01,0.000000000000000000e+00,-9.999999950392722825e-01,0.000000000000000000e+00 +1.297688191031278926e+01,9.423999999999999488e+01,0.000000000000000000e+00,2.627990622980447721e+00,0.000000000000000000e+00,5.459078068479676915e-01,0.000000000000000000e+00,-9.999999954392774226e-01,0.000000000000000000e+00 +1.298068709892821104e+01,9.425000000000000000e+01,0.000000000000000000e+00,2.630067905152135399e+00,0.000000000000000000e+00,5.421026182499004697e-01,0.000000000000000000e+00,-9.999999957869106781e-01,0.000000000000000000e+00 +1.298448928212675568e+01,9.426000000000000512e+01,0.000000000000000000e+00,2.632129078619132034e+00,0.000000000000000000e+00,5.383004350673751270e-01,0.000000000000000000e+00,-9.999999960709415880e-01,0.000000000000000000e+00 +1.298828848790326163e+01,9.426999999999999602e+01,0.000000000000000000e+00,2.634174192741535858e+00,0.000000000000000000e+00,5.345012293057961328e-01,0.000000000000000000e+00,-9.999999964365038352e-01,0.000000000000000000e+00 +1.299208474406109382e+01,9.428000000000000114e+01,0.000000000000000000e+00,2.636203296324657330e+00,0.000000000000000000e+00,5.307049731614910115e-01,0.000000000000000000e+00,-9.999999966932149320e-01,0.000000000000000000e+00 +1.299587807821477625e+01,9.429000000000000625e+01,0.000000000000000000e+00,2.638216437624880228e+00,0.000000000000000000e+00,5.269116390203517630e-01,0.000000000000000000e+00,-9.999999969602659800e-01,0.000000000000000000e+00 +1.299966851779258548e+01,9.429999999999999716e+01,0.000000000000000000e+00,2.640213664355431256e+00,0.000000000000000000e+00,5.231211994540645449e-01,0.000000000000000000e+00,-9.999999972308135643e-01,0.000000000000000000e+00 +1.300345609003910674e+01,9.431000000000000227e+01,0.000000000000000000e+00,2.642195023692050615e+00,0.000000000000000000e+00,5.193336272180313351e-01,0.000000000000000000e+00,-9.999999974260000979e-01,0.000000000000000000e+00 +1.300724082201775822e+01,9.432000000000000739e+01,0.000000000000000000e+00,2.644160562278571547e+00,0.000000000000000000e+00,5.155488952491221744e-01,0.000000000000000000e+00,-9.999999976951051694e-01,0.000000000000000000e+00 +1.301102274061327080e+01,9.432999999999999829e+01,0.000000000000000000e+00,2.646110326232409715e+00,0.000000000000000000e+00,5.117669766623273997e-01,0.000000000000000000e+00,-9.999999978764667619e-01,0.000000000000000000e+00 +1.301480187253413767e+01,9.434000000000000341e+01,0.000000000000000000e+00,2.648044361149959780e+00,0.000000000000000000e+00,5.079878447494857729e-01,0.000000000000000000e+00,-9.999999981028725449e-01,0.000000000000000000e+00 +1.301857824431503019e+01,9.435000000000000853e+01,0.000000000000000000e+00,2.649962712111908480e+00,0.000000000000000000e+00,5.042114729757568581e-01,0.000000000000000000e+00,-9.999999982876652815e-01,0.000000000000000000e+00 +1.302235188231917817e+01,9.435999999999999943e+01,0.000000000000000000e+00,2.651865423688457124e+00,0.000000000000000000e+00,5.004378349780708168e-01,0.000000000000000000e+00,-9.999999984469415404e-01,0.000000000000000000e+00 +1.302612281274071115e+01,9.437000000000000455e+01,0.000000000000000000e+00,2.653752539944462363e+00,0.000000000000000000e+00,4.966669045623936518e-01,0.000000000000000000e+00,-9.999999986469468860e-01,0.000000000000000000e+00 +1.302989106160697830e+01,9.437999999999999545e+01,0.000000000000000000e+00,2.655624104444492151e+00,0.000000000000000000e+00,4.928986557012248748e-01,0.000000000000000000e+00,-9.999999987608036989e-01,0.000000000000000000e+00 +1.303365665478082569e+01,9.439000000000000057e+01,0.000000000000000000e+00,2.657480160257799096e+00,0.000000000000000000e+00,4.891330625320440828e-01,0.000000000000000000e+00,-9.999999989738607153e-01,0.000000000000000000e+00 +1.303741961796284698e+01,9.440000000000000568e+01,0.000000000000000000e+00,2.659320749963216102e+00,0.000000000000000000e+00,4.853700993538849207e-01,0.000000000000000000e+00,-9.999999990658759996e-01,0.000000000000000000e+00 +1.304117997669360207e+01,9.440999999999999659e+01,0.000000000000000000e+00,2.661145915653968519e+00,0.000000000000000000e+00,4.816097406266433567e-01,0.000000000000000000e+00,-9.999999992580187458e-01,0.000000000000000000e+00 +1.304493775635580555e+01,9.442000000000000171e+01,0.000000000000000000e+00,2.662955698942414351e+00,0.000000000000000000e+00,4.778519609672282065e-01,0.000000000000000000e+00,-9.999999993324957259e-01,0.000000000000000000e+00 +1.304869298217648677e+01,9.443000000000000682e+01,0.000000000000000000e+00,2.664750140964701863e+00,0.000000000000000000e+00,4.740967351490531501e-01,0.000000000000000000e+00,-9.999999995087838212e-01,0.000000000000000000e+00 +1.305244567922911969e+01,9.443999999999999773e+01,0.000000000000000000e+00,2.666529282385358357e+00,0.000000000000000000e+00,4.703440380982641389e-01,0.000000000000000000e+00,-9.999999995886454940e-01,0.000000000000000000e+00 +1.305619587243571900e+01,9.445000000000000284e+01,0.000000000000000000e+00,2.668293163401799006e+00,0.000000000000000000e+00,4.665938448932073768e-01,0.000000000000000000e+00,-9.999999997360042858e-01,0.000000000000000000e+00 +1.305994358656891841e+01,9.446000000000000796e+01,0.000000000000000000e+00,2.670041823748769083e+00,0.000000000000000000e+00,4.628461307609974540e-01,0.000000000000000000e+00,-9.999999998052614414e-01,0.000000000000000000e+00 +1.306368884625401172e+01,9.446999999999999886e+01,0.000000000000000000e+00,2.671775302702709798e+00,0.000000000000000000e+00,4.591008710766332213e-01,0.000000000000000000e+00,-9.999999999301381060e-01,0.000000000000000000e+00 +1.306743167597097255e+01,9.448000000000000398e+01,0.000000000000000000e+00,2.673493639086058415e+00,0.000000000000000000e+00,4.553580413599330190e-01,0.000000000000000000e+00,-1.000000000004720890e+00,0.000000000000000000e+00 +1.307117210005644736e+01,9.448999999999999488e+01,0.000000000000000000e+00,2.675196871271475541e+00,0.000000000000000000e+00,4.516176172744409967e-01,0.000000000000000000e+00,-1.000000000111656684e+00,0.000000000000000000e+00 +1.307491014270571483e+01,9.450000000000000000e+01,0.000000000000000000e+00,2.676885037186008010e+00,0.000000000000000000e+00,4.478795746247560272e-01,0.000000000000000000e+00,-1.000000000220703678e+00,0.000000000000000000e+00 +1.307864582797463093e+01,9.451000000000000512e+01,0.000000000000000000e+00,2.678558174315182505e+00,0.000000000000000000e+00,4.441438893550145872e-01,0.000000000000000000e+00,-1.000000000296836555e+00,0.000000000000000000e+00 +1.308237917978154385e+01,9.451999999999999602e+01,0.000000000000000000e+00,2.680216319707035222e+00,0.000000000000000000e+00,4.404105375469938299e-01,0.000000000000000000e+00,-1.000000000312138093e+00,0.000000000000000000e+00 +1.308611022190917872e+01,9.453000000000000114e+01,0.000000000000000000e+00,2.681859509976077138e+00,0.000000000000000000e+00,4.366794954181948962e-01,0.000000000000000000e+00,-1.000000000479924767e+00,0.000000000000000000e+00 +1.308983897800650631e+01,9.454000000000000625e+01,0.000000000000000000e+00,2.683487781307195785e+00,0.000000000000000000e+00,4.329507393190775155e-01,0.000000000000000000e+00,-1.000000000497328401e+00,0.000000000000000000e+00 +1.309356547159058692e+01,9.454999999999999716e+01,0.000000000000000000e+00,2.685101169459491288e+00,0.000000000000000000e+00,4.292242457331436056e-01,0.000000000000000000e+00,-1.000000000573758152e+00,0.000000000000000000e+00 +1.309728972604838582e+01,9.456000000000000227e+01,0.000000000000000000e+00,2.686699709770058231e+00,0.000000000000000000e+00,4.254999912732080891e-01,0.000000000000000000e+00,-1.000000000638580522e+00,0.000000000000000000e+00 +1.310101176463856909e+01,9.457000000000000739e+01,0.000000000000000000e+00,2.688283437157700018e+00,0.000000000000000000e+00,4.217779526806473833e-01,0.000000000000000000e+00,-1.000000000696556368e+00,0.000000000000000000e+00 +1.310473161049328006e+01,9.457999999999999829e+01,0.000000000000000000e+00,2.689852386126587724e+00,0.000000000000000000e+00,4.180581068233450437e-01,0.000000000000000000e+00,-1.000000000766757102e+00,0.000000000000000000e+00 +1.310844928661988718e+01,9.459000000000000341e+01,0.000000000000000000e+00,2.691406590769859442e+00,0.000000000000000000e+00,4.143404306938873738e-01,0.000000000000000000e+00,-1.000000000819848189e+00,0.000000000000000000e+00 +1.311216481590271421e+01,9.460000000000000853e+01,0.000000000000000000e+00,2.692946084773161886e+00,0.000000000000000000e+00,4.106249014080138315e-01,0.000000000000000000e+00,-1.000000000842028225e+00,0.000000000000000000e+00 +1.311587822110475088e+01,9.460999999999999943e+01,0.000000000000000000e+00,2.694470901418136055e+00,0.000000000000000000e+00,4.069114962028507199e-01,0.000000000000000000e+00,-1.000000000930671762e+00,0.000000000000000000e+00 +1.311958952486933683e+01,9.462000000000000455e+01,0.000000000000000000e+00,2.695981073585846932e+00,0.000000000000000000e+00,4.032001924348109223e-01,0.000000000000000000e+00,-1.000000000937147915e+00,0.000000000000000000e+00 +1.312329874972183141e+01,9.462999999999999545e+01,0.000000000000000000e+00,2.697476633760156783e+00,0.000000000000000000e+00,3.994909675788401171e-01,0.000000000000000000e+00,-1.000000001010700412e+00,0.000000000000000000e+00 +1.312700591807126038e+01,9.464000000000000057e+01,0.000000000000000000e+00,2.698957614031047836e+00,0.000000000000000000e+00,3.957837992256642567e-01,0.000000000000000000e+00,-1.000000001012705697e+00,0.000000000000000000e+00 +1.313071105221194301e+01,9.465000000000000568e+01,0.000000000000000000e+00,2.700424046097887665e+00,0.000000000000000000e+00,3.920786650812300711e-01,0.000000000000000000e+00,-1.000000001091488899e+00,0.000000000000000000e+00 +1.313441417432509795e+01,9.465999999999999659e+01,0.000000000000000000e+00,2.701875961272646176e+00,0.000000000000000000e+00,3.883755429640333712e-01,0.000000000000000000e+00,-1.000000001124922155e+00,0.000000000000000000e+00 +1.313811530648043480e+01,9.467000000000000171e+01,0.000000000000000000e+00,2.703313390483057077e+00,0.000000000000000000e+00,3.846744108045322408e-01,0.000000000000000000e+00,-1.000000001132054006e+00,0.000000000000000000e+00 +1.314181447063772623e+01,9.468000000000000682e+01,0.000000000000000000e+00,2.704736364275732274e+00,0.000000000000000000e+00,3.809752466430534890e-01,0.000000000000000000e+00,-1.000000001166264418e+00,0.000000000000000000e+00 +1.314551168864835340e+01,9.468999999999999773e+01,0.000000000000000000e+00,2.706144912819224313e+00,0.000000000000000000e+00,3.772780286281138262e-01,0.000000000000000000e+00,-1.000000001174077946e+00,0.000000000000000000e+00 +1.314920698225684781e+01,9.470000000000000284e+01,0.000000000000000000e+00,2.707539065907039078e+00,0.000000000000000000e+00,3.735827350152810533e-01,0.000000000000000000e+00,-1.000000001242826952e+00,0.000000000000000000e+00 +1.315290037310240123e+01,9.471000000000000796e+01,0.000000000000000000e+00,2.708918852960601420e+00,0.000000000000000000e+00,3.698893441651371350e-01,0.000000000000000000e+00,-1.000000001261731386e+00,0.000000000000000000e+00 +1.315659188272037028e+01,9.471999999999999886e+01,0.000000000000000000e+00,2.710284303032171049e+00,0.000000000000000000e+00,3.661978345425110359e-01,0.000000000000000000e+00,-1.000000001232739244e+00,0.000000000000000000e+00 +1.316028153254375255e+01,9.473000000000000398e+01,0.000000000000000000e+00,2.711635444807714013e+00,0.000000000000000000e+00,3.625081847145797953e-01,0.000000000000000000e+00,-1.000000001288083640e+00,0.000000000000000000e+00 +1.316396934390465923e+01,9.473999999999999488e+01,0.000000000000000000e+00,2.712972306609726214e+00,0.000000000000000000e+00,3.588203733489225833e-01,0.000000000000000000e+00,-1.000000001314659714e+00,0.000000000000000000e+00 +1.316765533803575927e+01,9.475000000000000000e+01,0.000000000000000000e+00,2.714294916400009416e+00,0.000000000000000000e+00,3.551343792129768584e-01,0.000000000000000000e+00,-1.000000001294985452e+00,0.000000000000000000e+00 +1.317133953607171293e+01,9.476000000000000512e+01,0.000000000000000000e+00,2.715603301782405499e+00,0.000000000000000000e+00,3.514501811722521851e-01,0.000000000000000000e+00,-1.000000001321746934e+00,0.000000000000000000e+00 +1.317502195905059104e+01,9.476999999999999602e+01,0.000000000000000000e+00,2.716897490005484972e+00,0.000000000000000000e+00,3.477677581885071367e-01,0.000000000000000000e+00,-1.000000001349194756e+00,0.000000000000000000e+00 +1.317870262791527480e+01,9.478000000000000114e+01,0.000000000000000000e+00,2.718177507965190198e+00,0.000000000000000000e+00,3.440870893188576751e-01,0.000000000000000000e+00,-1.000000001302971286e+00,0.000000000000000000e+00 +1.318238156351484314e+01,9.479000000000000625e+01,0.000000000000000000e+00,2.719443382207437310e+00,0.000000000000000000e+00,3.404081537144954539e-01,0.000000000000000000e+00,-1.000000001354018897e+00,0.000000000000000000e+00 +1.318605878660594577e+01,9.479999999999999716e+01,0.000000000000000000e+00,2.720695138930675938e+00,0.000000000000000000e+00,3.367309306184135820e-01,0.000000000000000000e+00,-1.000000001371210923e+00,0.000000000000000000e+00 +1.318973431785415862e+01,9.481000000000000227e+01,0.000000000000000000e+00,2.721932803988403649e+00,0.000000000000000000e+00,3.330553993651609868e-01,0.000000000000000000e+00,-1.000000001324127696e+00,0.000000000000000000e+00 +1.319340817783532671e+01,9.482000000000000739e+01,0.000000000000000000e+00,2.723156402891643069e+00,0.000000000000000000e+00,3.293815393791288404e-01,0.000000000000000000e+00,-1.000000001325163312e+00,0.000000000000000000e+00 +1.319708038703689112e+01,9.482999999999999829e+01,0.000000000000000000e+00,2.724365960811376830e+00,0.000000000000000000e+00,3.257093301726973200e-01,0.000000000000000000e+00,-1.000000001341177613e+00,0.000000000000000000e+00 +1.320075096585921059e+01,9.484000000000000341e+01,0.000000000000000000e+00,2.725561502580940321e+00,0.000000000000000000e+00,3.220387513454557871e-01,0.000000000000000000e+00,-1.000000001364615754e+00,0.000000000000000000e+00 +1.320441993461685293e+01,9.485000000000000853e+01,0.000000000000000000e+00,2.726743052698376690e+00,0.000000000000000000e+00,3.183697825828075145e-01,0.000000000000000000e+00,-1.000000001287664642e+00,0.000000000000000000e+00 +1.320808731353988819e+01,9.485999999999999943e+01,0.000000000000000000e+00,2.727910635328752331e+00,0.000000000000000000e+00,3.147024036550494785e-01,0.000000000000000000e+00,-1.000000001336785127e+00,0.000000000000000000e+00 +1.321175312277516589e+01,9.487000000000000455e+01,0.000000000000000000e+00,2.729064274306435056e+00,0.000000000000000000e+00,3.110365944148715256e-01,0.000000000000000000e+00,-1.000000001317705278e+00,0.000000000000000000e+00 +1.321541738238757091e+01,9.487999999999999545e+01,0.000000000000000000e+00,2.730203993137329643e+00,0.000000000000000000e+00,3.073723347976375364e-01,0.000000000000000000e+00,-1.000000001279406359e+00,0.000000000000000000e+00 +1.321908011236127756e+01,9.489000000000000057e+01,0.000000000000000000e+00,2.731329815001081407e+00,0.000000000000000000e+00,3.037096048192439168e-01,0.000000000000000000e+00,-1.000000001253225079e+00,0.000000000000000000e+00 +1.322274133260098594e+01,9.490000000000000568e+01,0.000000000000000000e+00,2.732441762753239356e+00,0.000000000000000000e+00,3.000483845749475353e-01,0.000000000000000000e+00,-1.000000001254746085e+00,0.000000000000000000e+00 +1.322640106293314233e+01,9.490999999999999659e+01,0.000000000000000000e+00,2.733539858927382937e+00,0.000000000000000000e+00,2.963886542381987121e-01,0.000000000000000000e+00,-1.000000001252108417e+00,0.000000000000000000e+00 +1.323005932310715771e+01,9.492000000000000171e+01,0.000000000000000000e+00,2.734624125737212808e+00,0.000000000000000000e+00,2.927303940596019394e-01,0.000000000000000000e+00,-1.000000001199613964e+00,0.000000000000000000e+00 +1.323371613279660863e+01,9.493000000000000682e+01,0.000000000000000000e+00,2.735694585078606522e+00,0.000000000000000000e+00,2.890735843657650239e-01,0.000000000000000000e+00,-1.000000001170844310e+00,0.000000000000000000e+00 +1.323737151160042025e+01,9.493999999999999773e+01,0.000000000000000000e+00,2.736751258531639142e+00,0.000000000000000000e+00,2.854182055576729993e-01,0.000000000000000000e+00,-1.000000001158684704e+00,0.000000000000000000e+00 +1.324102547904405469e+01,9.495000000000000284e+01,0.000000000000000000e+00,2.737794167362567421e+00,0.000000000000000000e+00,2.817642381098048321e-01,0.000000000000000000e+00,-1.000000001106999381e+00,0.000000000000000000e+00 +1.324467805458067104e+01,9.496000000000000796e+01,0.000000000000000000e+00,2.738823332525780696e+00,0.000000000000000000e+00,2.781116625691448796e-01,0.000000000000000000e+00,-1.000000001141613248e+00,0.000000000000000000e+00 +1.324832925759228708e+01,9.496999999999999886e+01,0.000000000000000000e+00,2.739838774665718457e+00,0.000000000000000000e+00,2.744604595533614577e-01,0.000000000000000000e+00,-1.000000001001496441e+00,0.000000000000000000e+00 +1.325197910739091967e+01,9.498000000000000398e+01,0.000000000000000000e+00,2.740840514118751958e+00,0.000000000000000000e+00,2.708106097510733501e-01,0.000000000000000000e+00,-1.000000001068243494e+00,0.000000000000000000e+00 +1.325562762321972698e+01,9.498999999999999488e+01,0.000000000000000000e+00,2.741828570915037844e+00,0.000000000000000000e+00,2.671620939183680377e-01,0.000000000000000000e+00,-1.000000000928811472e+00,0.000000000000000000e+00 +1.325927482425413118e+01,9.500000000000000000e+01,0.000000000000000000e+00,2.742802964780330477e+00,0.000000000000000000e+00,2.635148928805763902e-01,0.000000000000000000e+00,-1.000000000971696723e+00,0.000000000000000000e+00 +1.326292072960293211e+01,9.501000000000000512e+01,0.000000000000000000e+00,2.743763715137772508e+00,0.000000000000000000e+00,2.598689875282326200e-01,0.000000000000000000e+00,-1.000000000880050921e+00,0.000000000000000000e+00 +1.326656535830941586e+01,9.501999999999999602e+01,0.000000000000000000e+00,2.744710841109642807e+00,0.000000000000000000e+00,2.562243588185412757e-01,0.000000000000000000e+00,-1.000000000861316352e+00,0.000000000000000000e+00 +1.327020872935244888e+01,9.503000000000000114e+01,0.000000000000000000e+00,2.745644361519082199e+00,0.000000000000000000e+00,2.525809877723693142e-01,0.000000000000000000e+00,-1.000000000771973596e+00,0.000000000000000000e+00 +1.327385086164756700e+01,9.504000000000000625e+01,0.000000000000000000e+00,2.746564294891781000e+00,0.000000000000000000e+00,2.489388554744386972e-01,0.000000000000000000e+00,-1.000000000712513826e+00,0.000000000000000000e+00 +1.327749177404805181e+01,9.504999999999999716e+01,0.000000000000000000e+00,2.747470659457640352e+00,0.000000000000000000e+00,2.452979430713597975e-01,0.000000000000000000e+00,-1.000000000718846982e+00,0.000000000000000000e+00 +1.328113148534599652e+01,9.506000000000000227e+01,0.000000000000000000e+00,2.748363473152399816e+00,0.000000000000000000e+00,2.416582317707985372e-01,0.000000000000000000e+00,-1.000000000586252158e+00,0.000000000000000000e+00 +1.328477001427337001e+01,9.507000000000000739e+01,0.000000000000000000e+00,2.749242753619235646e+00,0.000000000000000000e+00,2.380197028412925631e-01,0.000000000000000000e+00,-1.000000000564611469e+00,0.000000000000000000e+00 +1.328840737950306305e+01,9.507999999999999829e+01,0.000000000000000000e+00,2.750108518210332420e+00,0.000000000000000000e+00,2.343823376095458821e-01,0.000000000000000000e+00,-1.000000000511101383e+00,0.000000000000000000e+00 +1.329204359964993465e+01,9.509000000000000341e+01,0.000000000000000000e+00,2.750960783988419145e+00,0.000000000000000000e+00,2.307461174608156640e-01,0.000000000000000000e+00,-1.000000000416666479e+00,0.000000000000000000e+00 +1.329567869327184404e+01,9.510000000000000853e+01,0.000000000000000000e+00,2.751799567728281382e+00,0.000000000000000000e+00,2.271110238373913459e-01,0.000000000000000000e+00,-1.000000000328939320e+00,0.000000000000000000e+00 +1.329931267887067747e+01,9.510999999999999943e+01,0.000000000000000000e+00,2.752624885918242725e+00,0.000000000000000000e+00,2.234770382373627851e-01,0.000000000000000000e+00,-1.000000000240502063e+00,0.000000000000000000e+00 +1.330294557489336427e+01,9.512000000000000455e+01,0.000000000000000000e+00,2.753436754761616978e+00,0.000000000000000000e+00,2.198441422138026624e-01,0.000000000000000000e+00,-1.000000000212129869e+00,0.000000000000000000e+00 +1.330657739973288756e+01,9.512999999999999545e+01,0.000000000000000000e+00,2.754235190178132786e+00,0.000000000000000000e+00,2.162123173735088222e-01,0.000000000000000000e+00,-1.000000000125066180e+00,0.000000000000000000e+00 +1.331020817172928794e+01,9.514000000000000057e+01,0.000000000000000000e+00,2.755020207805329413e+00,0.000000000000000000e+00,2.125815453766540797e-01,0.000000000000000000e+00,-9.999999999715640797e-01,0.000000000000000000e+00 +1.331383790917065646e+01,9.515000000000000568e+01,0.000000000000000000e+00,2.755791822999927199e+00,0.000000000000000000e+00,2.089518079353880065e-01,0.000000000000000000e+00,-9.999999999098312387e-01,0.000000000000000000e+00 +1.331746663029412403e+01,9.515999999999999659e+01,0.000000000000000000e+00,2.756550050839169153e+00,0.000000000000000000e+00,2.053230868122472852e-01,0.000000000000000000e+00,-9.999999998459946360e-01,0.000000000000000000e+00 +1.332109435328684022e+01,9.517000000000000171e+01,0.000000000000000000e+00,2.757294906122133238e+00,0.000000000000000000e+00,2.016953638200905952e-01,0.000000000000000000e+00,-9.999999996897678267e-01,0.000000000000000000e+00 +1.332472109628694312e+01,9.518000000000000682e+01,0.000000000000000000e+00,2.758026403371021118e+00,0.000000000000000000e+00,1.980686208211120403e-01,0.000000000000000000e+00,-9.999999996103455802e-01,0.000000000000000000e+00 +1.332834687738453461e+01,9.518999999999999773e+01,0.000000000000000000e+00,2.758744556832420258e+00,0.000000000000000000e+00,1.944428397249336748e-01,0.000000000000000000e+00,-9.999999994814470217e-01,0.000000000000000000e+00 +1.333197171462263064e+01,9.520000000000000284e+01,0.000000000000000000e+00,2.759449380478536273e+00,0.000000000000000000e+00,1.908180024887176363e-01,0.000000000000000000e+00,-9.999999993725934289e-01,0.000000000000000000e+00 +1.333559562599811876e+01,9.521000000000000796e+01,0.000000000000000000e+00,2.760140888008403071e+00,0.000000000000000000e+00,1.871940911155031140e-01,0.000000000000000000e+00,-9.999999992293547857e-01,0.000000000000000000e+00 +1.333921862946270487e+01,9.521999999999999886e+01,0.000000000000000000e+00,2.760819092849064571e+00,0.000000000000000000e+00,1.835710876537091363e-01,0.000000000000000000e+00,-9.999999991277338518e-01,0.000000000000000000e+00 +1.334284074292385114e+01,9.523000000000000398e+01,0.000000000000000000e+00,2.761484008156732450e+00,0.000000000000000000e+00,1.799489741957216726e-01,0.000000000000000000e+00,-9.999999989529811950e-01,0.000000000000000000e+00 +1.334646198424571395e+01,9.523999999999999488e+01,0.000000000000000000e+00,2.762135646817916790e+00,0.000000000000000000e+00,1.763277328776505504e-01,0.000000000000000000e+00,-9.999999988226571102e-01,0.000000000000000000e+00 +1.335008237125006758e+01,9.525000000000000000e+01,0.000000000000000000e+00,2.762774021450534079e+00,0.000000000000000000e+00,1.727073458775598980e-01,0.000000000000000000e+00,-9.999999986629460880e-01,0.000000000000000000e+00 +1.335370192171722792e+01,9.526000000000000512e+01,0.000000000000000000e+00,2.763399144404987240e+00,0.000000000000000000e+00,1.690877954152389950e-01,0.000000000000000000e+00,-9.999999985294310001e-01,0.000000000000000000e+00 +1.335732065338697083e+01,9.526999999999999602e+01,0.000000000000000000e+00,2.764011027765223449e+00,0.000000000000000000e+00,1.654690637508172413e-01,0.000000000000000000e+00,-9.999999983515686086e-01,0.000000000000000000e+00 +1.336093858395944167e+01,9.528000000000000114e+01,0.000000000000000000e+00,2.764609683349765756e+00,0.000000000000000000e+00,1.618511331843097145e-01,0.000000000000000000e+00,-9.999999981174182428e-01,0.000000000000000000e+00 +1.336455573109606121e+01,9.529000000000000625e+01,0.000000000000000000e+00,2.765195122712722053e+00,0.000000000000000000e+00,1.582339860544994814e-01,0.000000000000000000e+00,-9.999999979904239389e-01,0.000000000000000000e+00 +1.336817211242042447e+01,9.529999999999999716e+01,0.000000000000000000e+00,2.765767357144769178e+00,0.000000000000000000e+00,1.546176047374031304e-01,0.000000000000000000e+00,-9.999999977807796370e-01,0.000000000000000000e+00 +1.337178774551919780e+01,9.531000000000000227e+01,0.000000000000000000e+00,2.766326397674110815e+00,0.000000000000000000e+00,1.510019716466534934e-01,0.000000000000000000e+00,-9.999999975704130240e-01,0.000000000000000000e+00 +1.337540264794300704e+01,9.532000000000000739e+01,0.000000000000000000e+00,2.766872255067416297e+00,0.000000000000000000e+00,1.473870692316268383e-01,0.000000000000000000e+00,-9.999999973192776892e-01,0.000000000000000000e+00 +1.337901683720732393e+01,9.532999999999999829e+01,0.000000000000000000e+00,2.767404939830732324e+00,0.000000000000000000e+00,1.437728799769989185e-01,0.000000000000000000e+00,-9.999999971165840496e-01,0.000000000000000000e+00 +1.338263033079334363e+01,9.534000000000000341e+01,0.000000000000000000e+00,2.767924462210372916e+00,0.000000000000000000e+00,1.401593864013975510e-01,0.000000000000000000e+00,-9.999999968877181233e-01,0.000000000000000000e+00 +1.338624314614886579e+01,9.535000000000000853e+01,0.000000000000000000e+00,2.768430832193784497e+00,0.000000000000000000e+00,1.365465710571191482e-01,0.000000000000000000e+00,-9.999999965766984689e-01,0.000000000000000000e+00 +1.338985530068915963e+01,9.535999999999999943e+01,0.000000000000000000e+00,2.768924059510390112e+00,0.000000000000000000e+00,1.329344165291901636e-01,0.000000000000000000e+00,-9.999999962947143661e-01,0.000000000000000000e+00 +1.339346681179783438e+01,9.537000000000000455e+01,0.000000000000000000e+00,2.769404153632410548e+00,0.000000000000000000e+00,1.293229054338965733e-01,0.000000000000000000e+00,-9.999999960597675264e-01,0.000000000000000000e+00 +1.339707769682770078e+01,9.537999999999999545e+01,0.000000000000000000e+00,2.769871123775660582e+00,0.000000000000000000e+00,1.257120204182582968e-01,0.000000000000000000e+00,-9.999999957058050004e-01,0.000000000000000000e+00 +1.340068797310162729e+01,9.539000000000000057e+01,0.000000000000000000e+00,2.770324978900323920e+00,0.000000000000000000e+00,1.221017441598355319e-01,0.000000000000000000e+00,-9.999999954048870432e-01,0.000000000000000000e+00 +1.340429765791339634e+01,9.540000000000000568e+01,0.000000000000000000e+00,2.770765727711708148e+00,0.000000000000000000e+00,1.184920593646537207e-01,0.000000000000000000e+00,-9.999999949966299484e-01,0.000000000000000000e+00 +1.340790676852855334e+01,9.540999999999999659e+01,0.000000000000000000e+00,2.771193378660973039e+00,0.000000000000000000e+00,1.148829487675535471e-01,0.000000000000000000e+00,-9.999999946462184708e-01,0.000000000000000000e+00 +1.341151532218525766e+01,9.542000000000000171e+01,0.000000000000000000e+00,2.771607939945841093e+00,0.000000000000000000e+00,1.112743951301693041e-01,0.000000000000000000e+00,-9.999999942409570908e-01,0.000000000000000000e+00 +1.341512333609511742e+01,9.543000000000000682e+01,0.000000000000000000e+00,2.772009419511281880e+00,0.000000000000000000e+00,1.076663812410890986e-01,0.000000000000000000e+00,-9.999999937750451151e-01,0.000000000000000000e+00 +1.341873082744403334e+01,9.543999999999999773e+01,0.000000000000000000e+00,2.772397825050178177e+00,0.000000000000000000e+00,1.040588899146297902e-01,0.000000000000000000e+00,-9.999999933592343959e-01,0.000000000000000000e+00 +1.342233781339303533e+01,9.545000000000000284e+01,0.000000000000000000e+00,2.772773164003969004e+00,0.000000000000000000e+00,1.004519039895808291e-01,0.000000000000000000e+00,-9.999999928204199584e-01,0.000000000000000000e+00 +1.342594431107911390e+01,9.546000000000000796e+01,0.000000000000000000e+00,2.773135443563269575e+00,0.000000000000000000e+00,9.684540632939578342e-02,0.000000000000000000e+00,-9.999999922565199206e-01,0.000000000000000000e+00 +1.342955033761604788e+01,9.546999999999999886e+01,0.000000000000000000e+00,2.773484670668473484e+00,0.000000000000000000e+00,9.323937982038547900e-02,0.000000000000000000e+00,-9.999999917379095438e-01,0.000000000000000000e+00 +1.343315591009523224e+01,9.548000000000000398e+01,0.000000000000000000e+00,2.773820852010330018e+00,0.000000000000000000e+00,8.963380737099138629e-02,0.000000000000000000e+00,-9.999999910080329402e-01,0.000000000000000000e+00 +1.343676104558649875e+01,9.548999999999999488e+01,0.000000000000000000e+00,2.774143994030500604e+00,0.000000000000000000e+00,8.602867191214125242e-02,0.000000000000000000e+00,-9.999999903452965189e-01,0.000000000000000000e+00 +1.344036576113894199e+01,9.550000000000000000e+01,0.000000000000000000e+00,2.774454102922098375e+00,0.000000000000000000e+00,8.242395639450002254e-02,0.000000000000000000e+00,-9.999999896141403832e-01,0.000000000000000000e+00 +1.344397007378173114e+01,9.551000000000000512e+01,0.000000000000000000e+00,2.774751184630199763e+00,0.000000000000000000e+00,7.881964378914488312e-02,0.000000000000000000e+00,-9.999999887504160689e-01,0.000000000000000000e+00 +1.344757400052492535e+01,9.551999999999999602e+01,0.000000000000000000e+00,2.775035244852340544e+00,0.000000000000000000e+00,7.521571708649284205e-02,0.000000000000000000e+00,-9.999999878026473166e-01,0.000000000000000000e+00 +1.345117755836028905e+01,9.553000000000000114e+01,0.000000000000000000e+00,2.775306289038990126e+00,0.000000000000000000e+00,7.161215929508231437e-02,0.000000000000000000e+00,-9.999999868019392446e-01,0.000000000000000000e+00 +1.345478076426210023e+01,9.554000000000000625e+01,0.000000000000000000e+00,2.775564322394003636e+00,0.000000000000000000e+00,6.800895344082609484e-02,0.000000000000000000e+00,-9.999999856998722514e-01,0.000000000000000000e+00 +1.345838363518795688e+01,9.554999999999999716e+01,0.000000000000000000e+00,2.775809349875053567e+00,0.000000000000000000e+00,6.440608256649037189e-02,0.000000000000000000e+00,-9.999999843743966332e-01,0.000000000000000000e+00 +1.346198618807958525e+01,9.556000000000000227e+01,0.000000000000000000e+00,2.776041376194041899e+00,0.000000000000000000e+00,6.080352973115458332e-02,0.000000000000000000e+00,-9.999999829435283205e-01,0.000000000000000000e+00 +1.346558843986363740e+01,9.557000000000000739e+01,0.000000000000000000e+00,2.776260405817492671e+00,0.000000000000000000e+00,5.720127800854326455e-02,0.000000000000000000e+00,-9.999999813602172827e-01,0.000000000000000000e+00 +1.346919040745250129e+01,9.557999999999999829e+01,0.000000000000000000e+00,2.776466442966921022e+00,0.000000000000000000e+00,5.359931048681952637e-02,0.000000000000000000e+00,-9.999999794515286311e-01,0.000000000000000000e+00 +1.347279210774509117e+01,9.559000000000000341e+01,0.000000000000000000e+00,2.776659491619184017e+00,0.000000000000000000e+00,4.999761026823906079e-02,0.000000000000000000e+00,-9.999999773000265435e-01,0.000000000000000000e+00 +1.347639355762765057e+01,9.560000000000000853e+01,0.000000000000000000e+00,2.776839555506812829e+00,0.000000000000000000e+00,4.639616046743224448e-02,0.000000000000000000e+00,-9.999999748375454356e-01,0.000000000000000000e+00 +1.347999477397454626e+01,9.560999999999999943e+01,0.000000000000000000e+00,2.777006638118321380e+00,0.000000000000000000e+00,4.279494421115116742e-02,0.000000000000000000e+00,-9.999999718150632821e-01,0.000000000000000000e+00 +1.348359577364906414e+01,9.562000000000000455e+01,0.000000000000000000e+00,2.777160742698496776e+00,0.000000000000000000e+00,3.919394463812653912e-02,0.000000000000000000e+00,-9.999999682860506445e-01,0.000000000000000000e+00 +1.348719657350420142e+01,9.562999999999999545e+01,0.000000000000000000e+00,2.777301872248671977e+00,0.000000000000000000e+00,3.559314489718545110e-02,0.000000000000000000e+00,-9.999999638909526922e-01,0.000000000000000000e+00 +1.349079719038345537e+01,9.564000000000000057e+01,0.000000000000000000e+00,2.777430029526974486e+00,0.000000000000000000e+00,3.199252814794712602e-02,0.000000000000000000e+00,-9.999999584769669880e-01,0.000000000000000000e+00 +1.349439764112161555e+01,9.565000000000000568e+01,0.000000000000000000e+00,2.777545217048560389e+00,0.000000000000000000e+00,2.839207755928809321e-02,0.000000000000000000e+00,-9.999999513817622310e-01,0.000000000000000000e+00 +1.349799794254555607e+01,9.565999999999999659e+01,0.000000000000000000e+00,2.777647437085825732e+00,0.000000000000000000e+00,2.479177631038756435e-02,0.000000000000000000e+00,-9.999999420870655520e-01,0.000000000000000000e+00 +1.350159811147501898e+01,9.567000000000000171e+01,0.000000000000000000e+00,2.777736691668604596e+00,0.000000000000000000e+00,2.119160758942052400e-02,0.000000000000000000e+00,-9.999999289534570179e-01,0.000000000000000000e+00 +1.350519816472340473e+01,9.568000000000000682e+01,0.000000000000000000e+00,2.777812982584345392e+00,0.000000000000000000e+00,1.759155459680677644e-02,0.000000000000000000e+00,-9.999999092565710068e-01,0.000000000000000000e+00 +1.350879811909855377e+01,9.568999999999999773e+01,0.000000000000000000e+00,2.777876311378281837e+00,0.000000000000000000e+00,1.399160054833005484e-02,0.000000000000000000e+00,-9.999998764474599122e-01,0.000000000000000000e+00 +1.351239799140353703e+01,9.570000000000000284e+01,0.000000000000000000e+00,2.777926679353598161e+00,0.000000000000000000e+00,1.039172868812006552e-02,0.000000000000000000e+00,-9.999998108324064106e-01,0.000000000000000000e+00 +1.351599779843743931e+01,9.571000000000000796e+01,0.000000000000000000e+00,2.777964087571624052e+00,0.000000000000000000e+00,6.791922335185298504e-03,0.000000000000000000e+00,-9.999996139102954595e-01,0.000000000000000000e+00 +1.351959755699614085e+01,9.571999999999999886e+01,0.000000000000000000e+00,2.777988536852180168e+00,0.000000000000000000e+00,3.192165166314005383e-03,0.000000000000000000e+00,-8.868142753856690375e-01,0.000000000000000000e+00 +1.352319728387310249e+01,9.573000000000000398e+01,0.000000000000000000e+00,2.778000027774925051e+00,0.000000000000000000e+00,-1.240156656443832984e-07,0.000000000000000000e+00,3.448774309774771336e-05,0.000000000000000000e+00 +1.352679699586015083e+01,9.574000000000000909e+01,0.000000000000000000e+00,2.778000027328504373e+00,0.000000000000000000e+00,1.302765907977354877e-10,0.000000000000000000e+00,-3.619083727963735346e-08,0.000000000000000000e+00 +1.353039670784777648e+01,9.575000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.353399641983540214e+01,9.576000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.353759613182302779e+01,9.576999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.354119584381065344e+01,9.578000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.354479555579827910e+01,9.579000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.354839526778590475e+01,9.579999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.355199497977353040e+01,9.581000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.355559469176115606e+01,9.582000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.355919440374878171e+01,9.582999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.356279411573640736e+01,9.584000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.356639382772403302e+01,9.585000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.356999353971165867e+01,9.585999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.357359325169928432e+01,9.587000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.357719296368690998e+01,9.587999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.358079267567453563e+01,9.589000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.358439238766216128e+01,9.590000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.358799209964978694e+01,9.590999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.359159181163741259e+01,9.592000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.359519152362503824e+01,9.593000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.359879123561266390e+01,9.593999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.360239094760028955e+01,9.595000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.360599065958791520e+01,9.596000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.360959037157554086e+01,9.596999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.361319008356316651e+01,9.598000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.361678979555079216e+01,9.599000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.362038950753841782e+01,9.600000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.362398921952604347e+01,9.601000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.362758893151366912e+01,9.601999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.363118864350129478e+01,9.603000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.363478835548892043e+01,9.604000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.363838806747654608e+01,9.604999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.364198777946417174e+01,9.606000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.364558749145179739e+01,9.607000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.364918720343942304e+01,9.607999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.365278691542704870e+01,9.609000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.365638662741467435e+01,9.610000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.365998633940230000e+01,9.610999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.366358605138992566e+01,9.612000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.366718576337755131e+01,9.612999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.367078547536517696e+01,9.614000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.367438518735280262e+01,9.615000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.367798489934042827e+01,9.615999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.368158461132805392e+01,9.617000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.368518432331567958e+01,9.618000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.368878403530330523e+01,9.618999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.369238374729093088e+01,9.620000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.369598345927855654e+01,9.621000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.369958317126618219e+01,9.621999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.370318288325380784e+01,9.623000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.370678259524143350e+01,9.624000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.371038230722905915e+01,9.625000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.371398201921668480e+01,9.626000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.371758173120431046e+01,9.626999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.372118144319193611e+01,9.628000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.372478115517956176e+01,9.629000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.372838086716718742e+01,9.629999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.373198057915481307e+01,9.631000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.373558029114243872e+01,9.632000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.373918000313006438e+01,9.632999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.374277971511769003e+01,9.634000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.374637942710531568e+01,9.635000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.374997913909294134e+01,9.635999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.375357885108056699e+01,9.637000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.375717856306819264e+01,9.637999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.376077827505581830e+01,9.639000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.376437798704344395e+01,9.640000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.376797769903106960e+01,9.640999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.377157741101869526e+01,9.642000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.377517712300632091e+01,9.643000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.377877683499394657e+01,9.643999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.378237654698157222e+01,9.645000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.378597625896919787e+01,9.646000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.378957597095682353e+01,9.646999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.379317568294444918e+01,9.648000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.379677539493207483e+01,9.649000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.380037510691970049e+01,9.650000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.380397481890732614e+01,9.651000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.380757453089495179e+01,9.651999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.381117424288257745e+01,9.653000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.381477395487020310e+01,9.654000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.381837366685782875e+01,9.654999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.382197337884545441e+01,9.656000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.382557309083308006e+01,9.657000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.382917280282070571e+01,9.657999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.383277251480833137e+01,9.659000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.383637222679595702e+01,9.660000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.383997193878358267e+01,9.660999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.384357165077120833e+01,9.662000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.384717136275883398e+01,9.662999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.385077107474645963e+01,9.664000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.385437078673408529e+01,9.665000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.385797049872171094e+01,9.665999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.386157021070933659e+01,9.667000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.386516992269696225e+01,9.668000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.386876963468458790e+01,9.668999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.387236934667221355e+01,9.670000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.387596905865983921e+01,9.671000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.387956877064746486e+01,9.671999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.388316848263509051e+01,9.673000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.388676819462271617e+01,9.674000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.389036790661034182e+01,9.675000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.389396761859796747e+01,9.676000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.389756733058559313e+01,9.676999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.390116704257321878e+01,9.678000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.390476675456084443e+01,9.679000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.390836646654847009e+01,9.679999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.391196617853609574e+01,9.681000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.391556589052372139e+01,9.682000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.391916560251134705e+01,9.682999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.392276531449897270e+01,9.684000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.392636502648659835e+01,9.685000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.392996473847422401e+01,9.685999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.393356445046184966e+01,9.687000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.393716416244947531e+01,9.687999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.394076387443710097e+01,9.689000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.394436358642472662e+01,9.690000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.394796329841235227e+01,9.690999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.395156301039997793e+01,9.692000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.395516272238760358e+01,9.693000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.395876243437522923e+01,9.693999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.396236214636285489e+01,9.695000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.396596185835048054e+01,9.696000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.396956157033810619e+01,9.696999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.397316128232573185e+01,9.698000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.397676099431335750e+01,9.699000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.398036070630098315e+01,9.700000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.398396041828860881e+01,9.701000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.398756013027623446e+01,9.701999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.399115984226386011e+01,9.703000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.399475955425148577e+01,9.704000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.399835926623911142e+01,9.704999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.400195897822673707e+01,9.706000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.400555869021436273e+01,9.707000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.400915840220198838e+01,9.707999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.401275811418961403e+01,9.709000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.401635782617723969e+01,9.710000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.401995753816486534e+01,9.710999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.402355725015249099e+01,9.712000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.402715696214011665e+01,9.712999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.403075667412774230e+01,9.714000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.403435638611536795e+01,9.715000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.403795609810299361e+01,9.715999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.404155581009061926e+01,9.717000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.404515552207824491e+01,9.718000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.404875523406587057e+01,9.718999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.405235494605349622e+01,9.720000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.405595465804112187e+01,9.721000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.405955437002874753e+01,9.721999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.406315408201637318e+01,9.723000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.406675379400399883e+01,9.724000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.407035350599162449e+01,9.725000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.407395321797925014e+01,9.726000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.407755292996687579e+01,9.726999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.408115264195450145e+01,9.728000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.408475235394212710e+01,9.729000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.408835206592975275e+01,9.729999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.409195177791737841e+01,9.731000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.409555148990500406e+01,9.732000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.409915120189262971e+01,9.732999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.410275091388025537e+01,9.734000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.410635062586788102e+01,9.735000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.410995033785550667e+01,9.735999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.411355004984313233e+01,9.737000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.411714976183075798e+01,9.737999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.412074947381838363e+01,9.739000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.412434918580600929e+01,9.740000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.412794889779363494e+01,9.740999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.413154860978126059e+01,9.742000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.413514832176888625e+01,9.743000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.413874803375651190e+01,9.743999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.414234774574413755e+01,9.745000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.414594745773176321e+01,9.746000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.414954716971938886e+01,9.746999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.415314688170701451e+01,9.748000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.415674659369464017e+01,9.749000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.416034630568226582e+01,9.750000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.416394601766989148e+01,9.751000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.416754572965751713e+01,9.751999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.417114544164514278e+01,9.753000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.417474515363276844e+01,9.754000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.417834486562039409e+01,9.754999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.418194457760801974e+01,9.756000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.418554428959564540e+01,9.757000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.418914400158327105e+01,9.757999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.419274371357089670e+01,9.759000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.419634342555852236e+01,9.760000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.419994313754614801e+01,9.760999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.420354284953377366e+01,9.762000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.420714256152139932e+01,9.762999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.421074227350902497e+01,9.764000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.421434198549665062e+01,9.765000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.421794169748427628e+01,9.765999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.422154140947190193e+01,9.767000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.422514112145952758e+01,9.768000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.422874083344715324e+01,9.768999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.423234054543477889e+01,9.770000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.423594025742240454e+01,9.771000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.423953996941003020e+01,9.771999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.424313968139765585e+01,9.773000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.424673939338528150e+01,9.774000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.425033910537290716e+01,9.775000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.425393881736053281e+01,9.776000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.425753852934815846e+01,9.776999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.426113824133578412e+01,9.778000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.426473795332340977e+01,9.779000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.426833766531103542e+01,9.779999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.427193737729866108e+01,9.781000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.427553708928628673e+01,9.782000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.427913680127391238e+01,9.782999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.428273651326153804e+01,9.784000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.428633622524916369e+01,9.785000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.428993593723678934e+01,9.785999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.429353564922441500e+01,9.787000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.429713536121204065e+01,9.787999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.430073507319966630e+01,9.789000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.430433478518729196e+01,9.790000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.430793449717491761e+01,9.790999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.431153420916254326e+01,9.792000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.431513392115016892e+01,9.793000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.431873363313779457e+01,9.793999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.432233334512542022e+01,9.795000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.432593305711304588e+01,9.796000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.432953276910067153e+01,9.796999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.433313248108829718e+01,9.798000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.433673219307592284e+01,9.799000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.434033190506354849e+01,9.800000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.434393161705117414e+01,9.801000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.434753132903879980e+01,9.801999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.435113104102642545e+01,9.803000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.435473075301405110e+01,9.804000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.435833046500167676e+01,9.804999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.436193017698930241e+01,9.806000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.436552988897692806e+01,9.807000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.436912960096455372e+01,9.807999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.437272931295217937e+01,9.809000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.437632902493980502e+01,9.810000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.437992873692743068e+01,9.810999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.438352844891505633e+01,9.812000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.438712816090268198e+01,9.812999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.439072787289030764e+01,9.814000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.439432758487793329e+01,9.815000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.439792729686555894e+01,9.815999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.440152700885318460e+01,9.817000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.440512672084081025e+01,9.818000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.440872643282843590e+01,9.818999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.441232614481606156e+01,9.820000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.441592585680368721e+01,9.821000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.441952556879131286e+01,9.821999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.442312528077893852e+01,9.823000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.442672499276656417e+01,9.824000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.443032470475418982e+01,9.825000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.443392441674181548e+01,9.826000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.443752412872944113e+01,9.826999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.444112384071706678e+01,9.828000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.444472355270469244e+01,9.829000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.444832326469231809e+01,9.829999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.445192297667994374e+01,9.831000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.445552268866756940e+01,9.832000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.445912240065519505e+01,9.832999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.446272211264282070e+01,9.834000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.446632182463044636e+01,9.835000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.446992153661807201e+01,9.835999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.447352124860569766e+01,9.837000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.447712096059332332e+01,9.837999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.448072067258094897e+01,9.839000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.448432038456857462e+01,9.840000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.448792009655620028e+01,9.840999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.449151980854382593e+01,9.842000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.449511952053145158e+01,9.843000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.449871923251907724e+01,9.843999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.450231894450670289e+01,9.845000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.450591865649432854e+01,9.846000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.450951836848195420e+01,9.846999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.451311808046957985e+01,9.848000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.451671779245720550e+01,9.849000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.452031750444483116e+01,9.850000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.452391721643245681e+01,9.851000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.452751692842008246e+01,9.851999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.453111664040770812e+01,9.853000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.453471635239533377e+01,9.854000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.453831606438295942e+01,9.854999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.454191577637058508e+01,9.856000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.454551548835821073e+01,9.857000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.454911520034583639e+01,9.857999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.455271491233346204e+01,9.859000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.455631462432108769e+01,9.860000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.455991433630871335e+01,9.860999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.456351404829633900e+01,9.862000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.456711376028396465e+01,9.862999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.457071347227159031e+01,9.864000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.457431318425921596e+01,9.865000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.457791289624684161e+01,9.865999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.458151260823446727e+01,9.867000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.458511232022209292e+01,9.868000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.458871203220971857e+01,9.868999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.459231174419734423e+01,9.870000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.459591145618496988e+01,9.871000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.459951116817259553e+01,9.871999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.460311088016022119e+01,9.873000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.460671059214784684e+01,9.874000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.461031030413547249e+01,9.875000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.461391001612309815e+01,9.876000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.461750972811072380e+01,9.876999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.462110944009834945e+01,9.878000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.462470915208597511e+01,9.879000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.462830886407360076e+01,9.879999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.463190857606122641e+01,9.881000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.463550828804885207e+01,9.882000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.463910800003647772e+01,9.882999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.464270771202410337e+01,9.884000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.464630742401172903e+01,9.885000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.464990713599935468e+01,9.885999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.465350684798698033e+01,9.887000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.465710655997460599e+01,9.887999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.466070627196223164e+01,9.889000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.466430598394985729e+01,9.890000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.466790569593748295e+01,9.890999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.467150540792510860e+01,9.892000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.467510511991273425e+01,9.893000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.467870483190035991e+01,9.893999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.468230454388798556e+01,9.895000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.468590425587561121e+01,9.896000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.468950396786323687e+01,9.896999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.469310367985086252e+01,9.898000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.469670339183848817e+01,9.899000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.470030310382611383e+01,9.900000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.470390281581373948e+01,9.901000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.470750252780136513e+01,9.901999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.471110223978899079e+01,9.903000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.471470195177661644e+01,9.904000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.471830166376424209e+01,9.904999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.472190137575186775e+01,9.906000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.472550108773949340e+01,9.907000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.472910079972711905e+01,9.907999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.473270051171474471e+01,9.909000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.473630022370237036e+01,9.910000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.473989993568999601e+01,9.910999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.474349964767762167e+01,9.912000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.474709935966524732e+01,9.912999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.475069907165287297e+01,9.914000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.475429878364049863e+01,9.915000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.475789849562812428e+01,9.915999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.476149820761574993e+01,9.917000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.476509791960337559e+01,9.918000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.476869763159100124e+01,9.918999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.477229734357862689e+01,9.920000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.477589705556625255e+01,9.921000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.477949676755387820e+01,9.921999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.478309647954150385e+01,9.923000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.478669619152912951e+01,9.924000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.479029590351675516e+01,9.925000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.479389561550438081e+01,9.926000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.479749532749200647e+01,9.926999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.480109503947963212e+01,9.928000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.480469475146725777e+01,9.929000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.480829446345488343e+01,9.929999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.481189417544250908e+01,9.931000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.481549388743013473e+01,9.932000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.481909359941776039e+01,9.932999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.482269331140538604e+01,9.934000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.482629302339301169e+01,9.935000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.482989273538063735e+01,9.935999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.483349244736826300e+01,9.937000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.483709215935588865e+01,9.937999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.484069187134351431e+01,9.939000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.484429158333113996e+01,9.940000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.484789129531876561e+01,9.940999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.485149100730639127e+01,9.942000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.485509071929401692e+01,9.943000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.485869043128164257e+01,9.943999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.486229014326926823e+01,9.945000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.486588985525689388e+01,9.946000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.486948956724451953e+01,9.946999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.487308927923214519e+01,9.948000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.487668899121977084e+01,9.949000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.488028870320739649e+01,9.950000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.488388841519502215e+01,9.951000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.488748812718264780e+01,9.951999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.489108783917027345e+01,9.953000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.489468755115789911e+01,9.954000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.489828726314552476e+01,9.954999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.490188697513315041e+01,9.956000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.490548668712077607e+01,9.957000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.490908639910840172e+01,9.957999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.491268611109602737e+01,9.959000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.491628582308365303e+01,9.960000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.491988553507127868e+01,9.960999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.492348524705890433e+01,9.962000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.492708495904652999e+01,9.962999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.493068467103415564e+01,9.964000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.493428438302178130e+01,9.965000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.493788409500940695e+01,9.965999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.494148380699703260e+01,9.967000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.494508351898465826e+01,9.968000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.494868323097228391e+01,9.968999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.495228294295990956e+01,9.970000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.495588265494753522e+01,9.971000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.495948236693516087e+01,9.971999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.496308207892278652e+01,9.973000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.496668179091041218e+01,9.974000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.497028150289803783e+01,9.975000000000000000e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.497388121488566348e+01,9.976000000000000512e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.497748092687328914e+01,9.976999999999999602e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.498108063886091479e+01,9.978000000000000114e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.498468035084854044e+01,9.979000000000000625e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.498828006283616610e+01,9.979999999999999716e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.499187977482379175e+01,9.981000000000000227e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.499547948681141740e+01,9.982000000000000739e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.499907919879904306e+01,9.982999999999999829e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.500267891078666871e+01,9.984000000000000341e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.500627862277429436e+01,9.985000000000000853e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.500987833476192002e+01,9.985999999999999943e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.501347804674954567e+01,9.987000000000000455e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.501707775873717132e+01,9.987999999999999545e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.502067747072479698e+01,9.989000000000000057e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.502427718271242263e+01,9.990000000000000568e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.502787689470004828e+01,9.990999999999999659e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.503147660668767394e+01,9.992000000000000171e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.503507631867529959e+01,9.993000000000000682e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.503867603066292524e+01,9.993999999999999773e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.504227574265055090e+01,9.995000000000000284e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.504587545463817655e+01,9.996000000000000796e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.504947516662580220e+01,9.996999999999999886e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.505307487861342786e+01,9.998000000000000398e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.505667459060105351e+01,9.999000000000000909e+01,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.506027430258867916e+01,1.000000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.506387401457630482e+01,1.000100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.506747372656393047e+01,1.000199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.507107343855155612e+01,1.000300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.507467315053918178e+01,1.000400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.507827286252680743e+01,1.000499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.508187257451443308e+01,1.000600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.508547228650205874e+01,1.000700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.508907199848968439e+01,1.000799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.509267171047731004e+01,1.000900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.509627142246493570e+01,1.001000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.509987113445256135e+01,1.001099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.510347084644018700e+01,1.001200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.510707055842781266e+01,1.001299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.511067027041543831e+01,1.001400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.511426998240306396e+01,1.001500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.511786969439068962e+01,1.001599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.512146940637831527e+01,1.001700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.512506911836594092e+01,1.001800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.512866883035356658e+01,1.001899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.513226854234119223e+01,1.002000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.513586825432881788e+01,1.002100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.513946796631644354e+01,1.002199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.514306767830406919e+01,1.002300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.514666739029169484e+01,1.002400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.515026710227932050e+01,1.002500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.515386681426694615e+01,1.002600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.515746652625457180e+01,1.002699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.516106623824219746e+01,1.002800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.516466595022982311e+01,1.002900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.516826566221744876e+01,1.002999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.517186537420507442e+01,1.003100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.517546508619270007e+01,1.003200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.517906479818032572e+01,1.003299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.518266451016795138e+01,1.003400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.518626422215557703e+01,1.003500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.518986393414320268e+01,1.003599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.519346364613082834e+01,1.003700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.519706335811845399e+01,1.003799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.520066307010607964e+01,1.003900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.520426278209370530e+01,1.004000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.520786249408133095e+01,1.004099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.521146220606895660e+01,1.004200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.521506191805658226e+01,1.004300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.521866163004420791e+01,1.004399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.522226134203183356e+01,1.004500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.522586105401945922e+01,1.004600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.522946076600708487e+01,1.004699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.523306047799471052e+01,1.004800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.523666018998233618e+01,1.004900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.524025990196996183e+01,1.005000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.524385961395758748e+01,1.005100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.524745932594521314e+01,1.005199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.525105903793283879e+01,1.005300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.525465874992046444e+01,1.005400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.525825846190809010e+01,1.005499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.526185817389571575e+01,1.005600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.526545788588334140e+01,1.005700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.526905759787096706e+01,1.005799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.527265730985859271e+01,1.005900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.527625702184621836e+01,1.006000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.527985673383384402e+01,1.006099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.528345644582146967e+01,1.006200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.528705615780909532e+01,1.006299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.529065586979672098e+01,1.006400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.529425558178434663e+01,1.006500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.529785529377197228e+01,1.006599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.530145500575959794e+01,1.006700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.530505471774722359e+01,1.006800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.530865442973484924e+01,1.006899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.531225414172247490e+01,1.007000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.531585385371010055e+01,1.007100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.531945356569772621e+01,1.007199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.532305327768535186e+01,1.007300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.532665298967297751e+01,1.007400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.533025270166060317e+01,1.007500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.533385241364822882e+01,1.007600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.533745212563585447e+01,1.007699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.534105183762348013e+01,1.007800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.534465154961110578e+01,1.007900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.534825126159873143e+01,1.007999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.535185097358635709e+01,1.008100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.535545068557398274e+01,1.008200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.535905039756160839e+01,1.008299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.536265010954923405e+01,1.008400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.536624982153685970e+01,1.008500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.536984953352448535e+01,1.008599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.537344924551211101e+01,1.008700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.537704895749973666e+01,1.008799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.538064866948736231e+01,1.008900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.538424838147498797e+01,1.009000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.538784809346261362e+01,1.009099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.539144780545023927e+01,1.009200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.539504751743786493e+01,1.009300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.539864722942549058e+01,1.009399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.540224694141311623e+01,1.009500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.540584665340074189e+01,1.009600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.540944636538836754e+01,1.009699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.541304607737599319e+01,1.009800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.541664578936361885e+01,1.009900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.542024550135124450e+01,1.010000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.542384521333887015e+01,1.010100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.542744492532649581e+01,1.010199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.543104463731412146e+01,1.010300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.543464434930174711e+01,1.010400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.543824406128937277e+01,1.010499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.544184377327699842e+01,1.010600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.544544348526462407e+01,1.010700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.544904319725224973e+01,1.010799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.545264290923987538e+01,1.010900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.545624262122750103e+01,1.011000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.545984233321512669e+01,1.011099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.546344204520275234e+01,1.011200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.546704175719037799e+01,1.011299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.547064146917800365e+01,1.011400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.547424118116562930e+01,1.011500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.547784089315325495e+01,1.011599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.548144060514088061e+01,1.011700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.548504031712850626e+01,1.011800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.548864002911613191e+01,1.011899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.549223974110375757e+01,1.012000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.549583945309138322e+01,1.012100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.549943916507900887e+01,1.012199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.550303887706663453e+01,1.012300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.550663858905426018e+01,1.012400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.551023830104188583e+01,1.012500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.551383801302951149e+01,1.012600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.551743772501713714e+01,1.012699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.552103743700476279e+01,1.012800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.552463714899238845e+01,1.012900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.552823686098001410e+01,1.012999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.553183657296763975e+01,1.013100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.553543628495526541e+01,1.013200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.553903599694289106e+01,1.013299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.554263570893051671e+01,1.013400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.554623542091814237e+01,1.013500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.554983513290576802e+01,1.013599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.555343484489339367e+01,1.013700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.555703455688101933e+01,1.013799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.556063426886864498e+01,1.013900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.556423398085627063e+01,1.014000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.556783369284389629e+01,1.014099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.557143340483152194e+01,1.014200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.557503311681914759e+01,1.014300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.557863282880677325e+01,1.014399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.558223254079439890e+01,1.014500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.558583225278202455e+01,1.014600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.558943196476965021e+01,1.014699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.559303167675727586e+01,1.014800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.559663138874490151e+01,1.014900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.560023110073252717e+01,1.015000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.560383081272015282e+01,1.015100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.560743052470777847e+01,1.015199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.561103023669540413e+01,1.015300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.561462994868302978e+01,1.015400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.561822966067065543e+01,1.015499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.562182937265828109e+01,1.015600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.562542908464590674e+01,1.015700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.562902879663353239e+01,1.015799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.563262850862115805e+01,1.015900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.563622822060878370e+01,1.016000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.563982793259640935e+01,1.016099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.564342764458403501e+01,1.016200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.564702735657166066e+01,1.016299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.565062706855928631e+01,1.016400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.565422678054691197e+01,1.016500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.565782649253453762e+01,1.016599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.566142620452216327e+01,1.016700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.566502591650978893e+01,1.016800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.566862562849741458e+01,1.016899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.567222534048504023e+01,1.017000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.567582505247266589e+01,1.017100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.567942476446029154e+01,1.017199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.568302447644791719e+01,1.017300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.568662418843554285e+01,1.017400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.569022390042316850e+01,1.017500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.569382361241079415e+01,1.017600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.569742332439841981e+01,1.017699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.570102303638604546e+01,1.017800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.570462274837367112e+01,1.017900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.570822246036129677e+01,1.017999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.571182217234892242e+01,1.018100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.571542188433654808e+01,1.018200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.571902159632417373e+01,1.018299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.572262130831179938e+01,1.018400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.572622102029942504e+01,1.018500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.572982073228705069e+01,1.018599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.573342044427467634e+01,1.018700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.573702015626230200e+01,1.018799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.574061986824992765e+01,1.018900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.574421958023755330e+01,1.019000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.574781929222517896e+01,1.019099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.575141900421280461e+01,1.019200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.575501871620043026e+01,1.019300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.575861842818805592e+01,1.019399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.576221814017568157e+01,1.019500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.576581785216330722e+01,1.019600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.576941756415093288e+01,1.019699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.577301727613855853e+01,1.019800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.577661698812618418e+01,1.019900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.578021670011380984e+01,1.020000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.578381641210143549e+01,1.020100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.578741612408906114e+01,1.020199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.579101583607668680e+01,1.020300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.579461554806431245e+01,1.020400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.579821526005193810e+01,1.020499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.580181497203956376e+01,1.020600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.580541468402718941e+01,1.020700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.580901439601481506e+01,1.020799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.581261410800244072e+01,1.020900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.581621381999006637e+01,1.021000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.581981353197769202e+01,1.021099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.582341324396531768e+01,1.021200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.582701295595294333e+01,1.021299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.583061266794056898e+01,1.021400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.583421237992819464e+01,1.021500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.583781209191582029e+01,1.021599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.584141180390344594e+01,1.021700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.584501151589107160e+01,1.021800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.584861122787869725e+01,1.021899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.585221093986632290e+01,1.022000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.585581065185394856e+01,1.022100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.585941036384157421e+01,1.022199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.586301007582919986e+01,1.022300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.586660978781682552e+01,1.022400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.587020949980445117e+01,1.022500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.587380921179207682e+01,1.022600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.587740892377970248e+01,1.022699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.588100863576732813e+01,1.022800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.588460834775495378e+01,1.022900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.588820805974257944e+01,1.022999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.589180777173020509e+01,1.023100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.589540748371783074e+01,1.023200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.589900719570545640e+01,1.023299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.590260690769308205e+01,1.023400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.590620661968070770e+01,1.023500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.590980633166833336e+01,1.023599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.591340604365595901e+01,1.023700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.591700575564358466e+01,1.023799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.592060546763121032e+01,1.023900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.592420517961883597e+01,1.024000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.592780489160646162e+01,1.024099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.593140460359408728e+01,1.024200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.593500431558171293e+01,1.024300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.593860402756933858e+01,1.024399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.594220373955696424e+01,1.024500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.594580345154458989e+01,1.024600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.594940316353221554e+01,1.024699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.595300287551984120e+01,1.024800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.595660258750746685e+01,1.024900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.596020229949509250e+01,1.025000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.596380201148271816e+01,1.025100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.596740172347034381e+01,1.025199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.597100143545796946e+01,1.025300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.597460114744559512e+01,1.025400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.597820085943322077e+01,1.025499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.598180057142084642e+01,1.025600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.598540028340847208e+01,1.025700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.598899999539609773e+01,1.025799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.599259970738372338e+01,1.025900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.599619941937134904e+01,1.026000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.599979913135897469e+01,1.026099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.600339884334659857e+01,1.026200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.600699855533422422e+01,1.026299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.601059826732184987e+01,1.026400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.601419797930947553e+01,1.026500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.601779769129710118e+01,1.026599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.602139740328472683e+01,1.026700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.602499711527235249e+01,1.026800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.602859682725997814e+01,1.026899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.603219653924760379e+01,1.027000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.603579625123522945e+01,1.027100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.603939596322285510e+01,1.027199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.604299567521048075e+01,1.027300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.604659538719810641e+01,1.027400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.605019509918573206e+01,1.027500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.605379481117335772e+01,1.027600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.605739452316098337e+01,1.027699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.606099423514860902e+01,1.027800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.606459394713623468e+01,1.027900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.606819365912386033e+01,1.027999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.607179337111148598e+01,1.028100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.607539308309911164e+01,1.028200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.607899279508673729e+01,1.028299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.608259250707436294e+01,1.028400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.608619221906198860e+01,1.028500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.608979193104961425e+01,1.028599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.609339164303723990e+01,1.028700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.609699135502486556e+01,1.028799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.610059106701249121e+01,1.028900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.610419077900011686e+01,1.029000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.610779049098774252e+01,1.029099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.611139020297536817e+01,1.029200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.611498991496299382e+01,1.029300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.611858962695061948e+01,1.029399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.612218933893824513e+01,1.029500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.612578905092587078e+01,1.029600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.612938876291349644e+01,1.029699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.613298847490112209e+01,1.029800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.613658818688874774e+01,1.029900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.614018789887637340e+01,1.030000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.614378761086399905e+01,1.030100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.614738732285162470e+01,1.030199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.615098703483925036e+01,1.030300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.615458674682687601e+01,1.030400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.615818645881450166e+01,1.030499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.616178617080212732e+01,1.030600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.616538588278975297e+01,1.030700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.616898559477737862e+01,1.030799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.617258530676500428e+01,1.030900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.617618501875262993e+01,1.031000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.617978473074025558e+01,1.031099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.618338444272788124e+01,1.031200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.618698415471550689e+01,1.031299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.619058386670313254e+01,1.031400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.619418357869075820e+01,1.031500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.619778329067838385e+01,1.031599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.620138300266600950e+01,1.031700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.620498271465363516e+01,1.031800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.620858242664126081e+01,1.031899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.621218213862888646e+01,1.032000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.621578185061651212e+01,1.032100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.621938156260413777e+01,1.032199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.622298127459176342e+01,1.032300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.622658098657938908e+01,1.032400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.623018069856701473e+01,1.032500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.623378041055464038e+01,1.032600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.623738012254226604e+01,1.032699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.624097983452989169e+01,1.032800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.624457954651751734e+01,1.032900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.624817925850514300e+01,1.032999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.625177897049276865e+01,1.033100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.625537868248039430e+01,1.033200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.625897839446801996e+01,1.033299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.626257810645564561e+01,1.033400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.626617781844327126e+01,1.033500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.626977753043089692e+01,1.033599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.627337724241852257e+01,1.033700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.627697695440614822e+01,1.033799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.628057666639377388e+01,1.033900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.628417637838139953e+01,1.034000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.628777609036902518e+01,1.034099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.629137580235665084e+01,1.034200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.629497551434427649e+01,1.034300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.629857522633190214e+01,1.034399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.630217493831952780e+01,1.034500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.630577465030715345e+01,1.034600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.630937436229477910e+01,1.034699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.631297407428240476e+01,1.034800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.631657378627003041e+01,1.034900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.632017349825765606e+01,1.035000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.632377321024528172e+01,1.035100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.632737292223290737e+01,1.035199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.633097263422053302e+01,1.035300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.633457234620815868e+01,1.035400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.633817205819578433e+01,1.035499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.634177177018340998e+01,1.035600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.634537148217103564e+01,1.035700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.634897119415866129e+01,1.035799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.635257090614628694e+01,1.035900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.635617061813391260e+01,1.036000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.635977033012153825e+01,1.036099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.636337004210916390e+01,1.036200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.636696975409678956e+01,1.036299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.637056946608441521e+01,1.036400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.637416917807204086e+01,1.036500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.637776889005966652e+01,1.036599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.638136860204729217e+01,1.036700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.638496831403491782e+01,1.036800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.638856802602254348e+01,1.036899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.639216773801016913e+01,1.037000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.639576744999779478e+01,1.037100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.639936716198542044e+01,1.037199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.640296687397304609e+01,1.037300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.640656658596067174e+01,1.037400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.641016629794829740e+01,1.037500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.641376600993592305e+01,1.037600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.641736572192354870e+01,1.037699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.642096543391117436e+01,1.037800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.642456514589880001e+01,1.037900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.642816485788642566e+01,1.037999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.643176456987405132e+01,1.038100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.643536428186167697e+01,1.038200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.643896399384930262e+01,1.038299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.644256370583692828e+01,1.038400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.644616341782455393e+01,1.038500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.644976312981217959e+01,1.038599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.645336284179980524e+01,1.038700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.645696255378743089e+01,1.038799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.646056226577505655e+01,1.038900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.646416197776268220e+01,1.039000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.646776168975030785e+01,1.039099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.647136140173793351e+01,1.039200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.647496111372555916e+01,1.039300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.647856082571318481e+01,1.039399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.648216053770081047e+01,1.039500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.648576024968843612e+01,1.039600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.648935996167606177e+01,1.039699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.649295967366368743e+01,1.039800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.649655938565131308e+01,1.039900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.650015909763893873e+01,1.040000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.650375880962656439e+01,1.040100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.650735852161419004e+01,1.040199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.651095823360181569e+01,1.040300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.651455794558944135e+01,1.040400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.651815765757706700e+01,1.040499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.652175736956469265e+01,1.040600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.652535708155231831e+01,1.040700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.652895679353994396e+01,1.040799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.653255650552756961e+01,1.040900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.653615621751519527e+01,1.041000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.653975592950282092e+01,1.041099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.654335564149044657e+01,1.041200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.654695535347807223e+01,1.041299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.655055506546569788e+01,1.041400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.655415477745332353e+01,1.041500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.655775448944094919e+01,1.041599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.656135420142857484e+01,1.041700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.656495391341620049e+01,1.041800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.656855362540382615e+01,1.041899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.657215333739145180e+01,1.042000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.657575304937907745e+01,1.042100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.657935276136670311e+01,1.042199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.658295247335432876e+01,1.042300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.658655218534195441e+01,1.042400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.659015189732958007e+01,1.042500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.659375160931720572e+01,1.042600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.659735132130483137e+01,1.042699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.660095103329245703e+01,1.042800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.660455074528008268e+01,1.042900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.660815045726770833e+01,1.042999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.661175016925533399e+01,1.043100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.661534988124295964e+01,1.043200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.661894959323058529e+01,1.043299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.662254930521821095e+01,1.043400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.662614901720583660e+01,1.043500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.662974872919346225e+01,1.043599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.663334844118108791e+01,1.043700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.663694815316871356e+01,1.043799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.664054786515633921e+01,1.043900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.664414757714396487e+01,1.044000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.664774728913159052e+01,1.044099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.665134700111921617e+01,1.044200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.665494671310684183e+01,1.044300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.665854642509446748e+01,1.044399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.666214613708209313e+01,1.044500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.666574584906971879e+01,1.044600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.666934556105734444e+01,1.044699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.667294527304497009e+01,1.044800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.667654498503259575e+01,1.044900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.668014469702022140e+01,1.045000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.668374440900784705e+01,1.045100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.668734412099547271e+01,1.045199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.669094383298309836e+01,1.045300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.669454354497072401e+01,1.045400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.669814325695834967e+01,1.045499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.670174296894597532e+01,1.045600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.670534268093360097e+01,1.045700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.670894239292122663e+01,1.045799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.671254210490885228e+01,1.045900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.671614181689647793e+01,1.046000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.671974152888410359e+01,1.046099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.672334124087172924e+01,1.046200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.672694095285935489e+01,1.046299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.673054066484698055e+01,1.046400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.673414037683460620e+01,1.046500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.673774008882223185e+01,1.046599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.674133980080985751e+01,1.046700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.674493951279748316e+01,1.046800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.674853922478510881e+01,1.046899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.675213893677273447e+01,1.047000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.675573864876036012e+01,1.047100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.675933836074798577e+01,1.047199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.676293807273561143e+01,1.047300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.676653778472323708e+01,1.047400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.677013749671086273e+01,1.047500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.677373720869848839e+01,1.047600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.677733692068611404e+01,1.047699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.678093663267373969e+01,1.047800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.678453634466136535e+01,1.047900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.678813605664899100e+01,1.047999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.679173576863661665e+01,1.048100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.679533548062424231e+01,1.048200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.679893519261186796e+01,1.048299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.680253490459949361e+01,1.048400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.680613461658711927e+01,1.048500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.680973432857474492e+01,1.048599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.681333404056237057e+01,1.048700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.681693375254999623e+01,1.048799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.682053346453762188e+01,1.048900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.682413317652524753e+01,1.049000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.682773288851287319e+01,1.049099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.683133260050049884e+01,1.049200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.683493231248812450e+01,1.049300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.683853202447575015e+01,1.049399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.684213173646337580e+01,1.049500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.684573144845100146e+01,1.049600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.684933116043862711e+01,1.049699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.685293087242625276e+01,1.049800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.685653058441387842e+01,1.049900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.686013029640150407e+01,1.050000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.686373000838912972e+01,1.050100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.686732972037675538e+01,1.050199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.687092943236438103e+01,1.050300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.687452914435200668e+01,1.050400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.687812885633963234e+01,1.050499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.688172856832725799e+01,1.050600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.688532828031488364e+01,1.050700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.688892799230250930e+01,1.050799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.689252770429013495e+01,1.050900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.689612741627776060e+01,1.051000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.689972712826538626e+01,1.051099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.690332684025301191e+01,1.051200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.690692655224063756e+01,1.051299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.691052626422826322e+01,1.051400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.691412597621588887e+01,1.051500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.691772568820351452e+01,1.051599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.692132540019114018e+01,1.051700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.692492511217876583e+01,1.051800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.692852482416639148e+01,1.051899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.693212453615401714e+01,1.052000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.693572424814164279e+01,1.052100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.693932396012926844e+01,1.052199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.694292367211689410e+01,1.052300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.694652338410451975e+01,1.052400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.695012309609214540e+01,1.052500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.695372280807977106e+01,1.052600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.695732252006739671e+01,1.052699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.696092223205502236e+01,1.052800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.696452194404264802e+01,1.052900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.696812165603027367e+01,1.052999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.697172136801789932e+01,1.053100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.697532108000552498e+01,1.053200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.697892079199315063e+01,1.053299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.698252050398077628e+01,1.053400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.698612021596840194e+01,1.053500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.698971992795602759e+01,1.053599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.699331963994365324e+01,1.053700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.699691935193127890e+01,1.053799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.700051906391890455e+01,1.053900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.700411877590653020e+01,1.054000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.700771848789415586e+01,1.054099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.701131819988178151e+01,1.054200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.701491791186940716e+01,1.054300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.701851762385703282e+01,1.054399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.702211733584465847e+01,1.054500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.702571704783228412e+01,1.054600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.702931675981990978e+01,1.054699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.703291647180753543e+01,1.054800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.703651618379516108e+01,1.054900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.704011589578278674e+01,1.055000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.704371560777041239e+01,1.055100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.704731531975803804e+01,1.055199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.705091503174566370e+01,1.055300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.705451474373328935e+01,1.055400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.705811445572091500e+01,1.055499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.706171416770854066e+01,1.055600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.706531387969616631e+01,1.055700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.706891359168379196e+01,1.055799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.707251330367141762e+01,1.055900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.707611301565904327e+01,1.056000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.707971272764666892e+01,1.056099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.708331243963429458e+01,1.056200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.708691215162192023e+01,1.056299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.709051186360954588e+01,1.056400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.709411157559717154e+01,1.056500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.709771128758479719e+01,1.056599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.710131099957242284e+01,1.056700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.710491071156004850e+01,1.056800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.710851042354767415e+01,1.056899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.711211013553529980e+01,1.057000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.711570984752292546e+01,1.057100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.711930955951055111e+01,1.057199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.712290927149817676e+01,1.057300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.712650898348580242e+01,1.057400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.713010869547342807e+01,1.057500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.713370840746105372e+01,1.057600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.713730811944867938e+01,1.057699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.714090783143630503e+01,1.057800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.714450754342393068e+01,1.057900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.714810725541155634e+01,1.057999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.715170696739918199e+01,1.058100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.715530667938680764e+01,1.058200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.715890639137443330e+01,1.058299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.716250610336205895e+01,1.058400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.716610581534968460e+01,1.058500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.716970552733731026e+01,1.058599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.717330523932493591e+01,1.058700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.717690495131256156e+01,1.058799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.718050466330018722e+01,1.058900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.718410437528781287e+01,1.059000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.718770408727543852e+01,1.059099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.719130379926306418e+01,1.059200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.719490351125068983e+01,1.059300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.719850322323831548e+01,1.059399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.720210293522594114e+01,1.059500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.720570264721356679e+01,1.059600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.720930235920119244e+01,1.059699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.721290207118881810e+01,1.059800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.721650178317644375e+01,1.059900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.722010149516406941e+01,1.060000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.722370120715169506e+01,1.060100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.722730091913932071e+01,1.060199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.723090063112694637e+01,1.060300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.723450034311457202e+01,1.060400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.723810005510219767e+01,1.060499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.724169976708982333e+01,1.060600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.724529947907744898e+01,1.060700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.724889919106507463e+01,1.060799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.725249890305270029e+01,1.060900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.725609861504032594e+01,1.061000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.725969832702795159e+01,1.061099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.726329803901557725e+01,1.061200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.726689775100320290e+01,1.061299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.727049746299082855e+01,1.061400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.727409717497845421e+01,1.061500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.727769688696607986e+01,1.061599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.728129659895370551e+01,1.061700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.728489631094133117e+01,1.061800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.728849602292895682e+01,1.061899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.729209573491658247e+01,1.062000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.729569544690420813e+01,1.062100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.729929515889183378e+01,1.062199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.730289487087945943e+01,1.062300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.730649458286708509e+01,1.062400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.731009429485471074e+01,1.062500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.731369400684233639e+01,1.062600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.731729371882996205e+01,1.062699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.732089343081758770e+01,1.062800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.732449314280521335e+01,1.062900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.732809285479283901e+01,1.062999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.733169256678046466e+01,1.063100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.733529227876809031e+01,1.063200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.733889199075571597e+01,1.063299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.734249170274334162e+01,1.063400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.734609141473096727e+01,1.063500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.734969112671859293e+01,1.063599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.735329083870621858e+01,1.063700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.735689055069384423e+01,1.063799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.736049026268146989e+01,1.063900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.736408997466909554e+01,1.064000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.736768968665672119e+01,1.064099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.737128939864434685e+01,1.064200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.737488911063197250e+01,1.064300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.737848882261959815e+01,1.064399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.738208853460722381e+01,1.064500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.738568824659484946e+01,1.064600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.738928795858247511e+01,1.064699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.739288767057010077e+01,1.064800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.739648738255772642e+01,1.064900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.740008709454535207e+01,1.065000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.740368680653297773e+01,1.065100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.740728651852060338e+01,1.065199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.741088623050822903e+01,1.065300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.741448594249585469e+01,1.065400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.741808565448348034e+01,1.065499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.742168536647110599e+01,1.065600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.742528507845873165e+01,1.065700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.742888479044635730e+01,1.065799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.743248450243398295e+01,1.065900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.743608421442160861e+01,1.066000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.743968392640923426e+01,1.066099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.744328363839685991e+01,1.066200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.744688335038448557e+01,1.066299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.745048306237211122e+01,1.066400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.745408277435973687e+01,1.066500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.745768248634736253e+01,1.066599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.746128219833498818e+01,1.066700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.746488191032261383e+01,1.066800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.746848162231023949e+01,1.066899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.747208133429786514e+01,1.067000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.747568104628549079e+01,1.067100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.747928075827311645e+01,1.067199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.748288047026074210e+01,1.067300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.748648018224836775e+01,1.067400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.749007989423599341e+01,1.067500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.749367960622361906e+01,1.067600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.749727931821124471e+01,1.067699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.750087903019887037e+01,1.067800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.750447874218649602e+01,1.067900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.750807845417412167e+01,1.067999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.751167816616174733e+01,1.068100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.751527787814937298e+01,1.068200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.751887759013699863e+01,1.068299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.752247730212462429e+01,1.068400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.752607701411224994e+01,1.068500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.752967672609987559e+01,1.068599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.753327643808750125e+01,1.068700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.753687615007512690e+01,1.068799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.754047586206275255e+01,1.068900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.754407557405037821e+01,1.069000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.754767528603800386e+01,1.069099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.755127499802562951e+01,1.069200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.755487471001325517e+01,1.069300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.755847442200088082e+01,1.069399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.756207413398850647e+01,1.069500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.756567384597613213e+01,1.069600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.756927355796375778e+01,1.069699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.757287326995138343e+01,1.069800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.757647298193900909e+01,1.069900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.758007269392663474e+01,1.070000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.758367240591426039e+01,1.070100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.758727211790188605e+01,1.070199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.759087182988951170e+01,1.070300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.759447154187713735e+01,1.070400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.759807125386476301e+01,1.070499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.760167096585238866e+01,1.070600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.760527067784001432e+01,1.070700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.760887038982763997e+01,1.070799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.761247010181526562e+01,1.070900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.761606981380289128e+01,1.071000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.761966952579051693e+01,1.071099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.762326923777814258e+01,1.071200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.762686894976576824e+01,1.071299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.763046866175339389e+01,1.071400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.763406837374101954e+01,1.071500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.763766808572864520e+01,1.071599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.764126779771627085e+01,1.071700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.764486750970389650e+01,1.071800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.764846722169152216e+01,1.071899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.765206693367914781e+01,1.072000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.765566664566677346e+01,1.072100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.765926635765439912e+01,1.072199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.766286606964202477e+01,1.072300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.766646578162965042e+01,1.072400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.767006549361727608e+01,1.072500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.767366520560490173e+01,1.072600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.767726491759252738e+01,1.072699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.768086462958015304e+01,1.072800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.768446434156777869e+01,1.072900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.768806405355540434e+01,1.072999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.769166376554303000e+01,1.073100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.769526347753065565e+01,1.073200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.769886318951828130e+01,1.073299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.770246290150590696e+01,1.073400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.770606261349353261e+01,1.073500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.770966232548115826e+01,1.073599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.771326203746878392e+01,1.073700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.771686174945640957e+01,1.073799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.772046146144403522e+01,1.073900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.772406117343166088e+01,1.074000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.772766088541928653e+01,1.074099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.773126059740691218e+01,1.074200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.773486030939453784e+01,1.074300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.773846002138216349e+01,1.074399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.774205973336978914e+01,1.074500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.774565944535741480e+01,1.074600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.774925915734504045e+01,1.074699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.775285886933266610e+01,1.074800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.775645858132029176e+01,1.074900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.776005829330791741e+01,1.075000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.776365800529554306e+01,1.075100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.776725771728316872e+01,1.075199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.777085742927079437e+01,1.075300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.777445714125842002e+01,1.075400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.777805685324604568e+01,1.075499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.778165656523367133e+01,1.075600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.778525627722129698e+01,1.075700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.778885598920892264e+01,1.075799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.779245570119654829e+01,1.075900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.779605541318417394e+01,1.076000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.779965512517179960e+01,1.076099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.780325483715942525e+01,1.076200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.780685454914705090e+01,1.076299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.781045426113467656e+01,1.076400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.781405397312230221e+01,1.076500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.781765368510992786e+01,1.076599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.782125339709755352e+01,1.076700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.782485310908517917e+01,1.076800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.782845282107280482e+01,1.076899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.783205253306043048e+01,1.077000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.783565224504805613e+01,1.077100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.783925195703568178e+01,1.077199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.784285166902330744e+01,1.077300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.784645138101093309e+01,1.077400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.785005109299855874e+01,1.077500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.785365080498618440e+01,1.077600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.785725051697381005e+01,1.077699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.786085022896143570e+01,1.077800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.786444994094906136e+01,1.077900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.786804965293668701e+01,1.077999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.787164936492431266e+01,1.078100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.787524907691193832e+01,1.078200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.787884878889956397e+01,1.078299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.788244850088718962e+01,1.078400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.788604821287481528e+01,1.078500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.788964792486244093e+01,1.078599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.789324763685006658e+01,1.078700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.789684734883769224e+01,1.078799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.790044706082531789e+01,1.078900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.790404677281294354e+01,1.079000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.790764648480056920e+01,1.079099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.791124619678819485e+01,1.079200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.791484590877582050e+01,1.079300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.791844562076344616e+01,1.079399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.792204533275107181e+01,1.079500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.792564504473869746e+01,1.079600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.792924475672632312e+01,1.079699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.793284446871394877e+01,1.079800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.793644418070157442e+01,1.079900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.794004389268920008e+01,1.080000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.794364360467682573e+01,1.080100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.794724331666445138e+01,1.080199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.795084302865207704e+01,1.080300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.795444274063970269e+01,1.080400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.795804245262732834e+01,1.080499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.796164216461495400e+01,1.080600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.796524187660257965e+01,1.080700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.796884158859020530e+01,1.080799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.797244130057783096e+01,1.080900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.797604101256545661e+01,1.081000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.797964072455308226e+01,1.081099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.798324043654070792e+01,1.081200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.798684014852833357e+01,1.081299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.799043986051595923e+01,1.081400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.799403957250358488e+01,1.081500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.799763928449121053e+01,1.081599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.800123899647883619e+01,1.081700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.800483870846646184e+01,1.081800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.800843842045408749e+01,1.081899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.801203813244171315e+01,1.082000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.801563784442933880e+01,1.082100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.801923755641696445e+01,1.082199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.802283726840459011e+01,1.082300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.802643698039221576e+01,1.082400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.803003669237984141e+01,1.082500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.803363640436746707e+01,1.082600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.803723611635509272e+01,1.082699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.804083582834271837e+01,1.082800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.804443554033034403e+01,1.082900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.804803525231796968e+01,1.082999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.805163496430559533e+01,1.083100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.805523467629322099e+01,1.083200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.805883438828084664e+01,1.083299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.806243410026847229e+01,1.083400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.806603381225609795e+01,1.083500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.806963352424372360e+01,1.083599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.807323323623134925e+01,1.083700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.807683294821897491e+01,1.083799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.808043266020660056e+01,1.083900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.808403237219422621e+01,1.084000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.808763208418185187e+01,1.084099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.809123179616947752e+01,1.084200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.809483150815710317e+01,1.084300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.809843122014472883e+01,1.084399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.810203093213235448e+01,1.084500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.810563064411998013e+01,1.084600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.810923035610760579e+01,1.084699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.811283006809523144e+01,1.084800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.811642978008285709e+01,1.084900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.812002949207048275e+01,1.085000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.812362920405810840e+01,1.085100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.812722891604573405e+01,1.085199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.813082862803335971e+01,1.085300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.813442834002098536e+01,1.085400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.813802805200861101e+01,1.085499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.814162776399623667e+01,1.085600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.814522747598386232e+01,1.085700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.814882718797148797e+01,1.085799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.815242689995911363e+01,1.085900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.815602661194673928e+01,1.086000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.815962632393436493e+01,1.086099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.816322603592199059e+01,1.086200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.816682574790961624e+01,1.086299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.817042545989724189e+01,1.086400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.817402517188486755e+01,1.086500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.817762488387249320e+01,1.086599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818122459586011885e+01,1.086700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818482430784774451e+01,1.086800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.818842401983537016e+01,1.086899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.819202373182299581e+01,1.087000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.819562344381062147e+01,1.087100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.819922315579824712e+01,1.087199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.820282286778587277e+01,1.087300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.820642257977349843e+01,1.087400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.821002229176112408e+01,1.087500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.821362200374874973e+01,1.087600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.821722171573637539e+01,1.087699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.822082142772400104e+01,1.087800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.822442113971162669e+01,1.087900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.822802085169925235e+01,1.087999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.823162056368687800e+01,1.088100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.823522027567450365e+01,1.088200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.823881998766212931e+01,1.088299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.824241969964975496e+01,1.088400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.824601941163738061e+01,1.088500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.824961912362500627e+01,1.088599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.825321883561263192e+01,1.088700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.825681854760025757e+01,1.088799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.826041825958788323e+01,1.088900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.826401797157550888e+01,1.089000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.826761768356313453e+01,1.089099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.827121739555076019e+01,1.089200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.827481710753838584e+01,1.089300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.827841681952601149e+01,1.089399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.828201653151363715e+01,1.089500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.828561624350126280e+01,1.089600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.828921595548888845e+01,1.089699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.829281566747651411e+01,1.089800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.829641537946413976e+01,1.089900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.830001509145176541e+01,1.090000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.830361480343939107e+01,1.090100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.830721451542701672e+01,1.090199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.831081422741464237e+01,1.090300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.831441393940226803e+01,1.090400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.831801365138989368e+01,1.090499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.832161336337751933e+01,1.090600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.832521307536514499e+01,1.090700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.832881278735277064e+01,1.090799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.833241249934039629e+01,1.090900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.833601221132802195e+01,1.091000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.833961192331564760e+01,1.091099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.834321163530327325e+01,1.091200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.834681134729089891e+01,1.091299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.835041105927852456e+01,1.091400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.835401077126615021e+01,1.091500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.835761048325377587e+01,1.091599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.836121019524140152e+01,1.091700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.836480990722902717e+01,1.091800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.836840961921665283e+01,1.091899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.837200933120427848e+01,1.092000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.837560904319190414e+01,1.092100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.837920875517952979e+01,1.092199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.838280846716715544e+01,1.092300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.838640817915478110e+01,1.092400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.839000789114240675e+01,1.092500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.839360760313003240e+01,1.092600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.839720731511765806e+01,1.092699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.840080702710528371e+01,1.092800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.840440673909290936e+01,1.092900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.840800645108053502e+01,1.092999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.841160616306816067e+01,1.093100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.841520587505578632e+01,1.093200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.841880558704341198e+01,1.093299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.842240529903103763e+01,1.093400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.842600501101866328e+01,1.093500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.842960472300628894e+01,1.093599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.843320443499391459e+01,1.093700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.843680414698154024e+01,1.093799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.844040385896916590e+01,1.093900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.844400357095679155e+01,1.094000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.844760328294441720e+01,1.094099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.845120299493204286e+01,1.094200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.845480270691966851e+01,1.094300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.845840241890729416e+01,1.094399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.846200213089491982e+01,1.094500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.846560184288254547e+01,1.094600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.846920155487017112e+01,1.094699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.847280126685779678e+01,1.094800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.847640097884542243e+01,1.094900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.848000069083304808e+01,1.095000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.848360040282067374e+01,1.095100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.848720011480829939e+01,1.095199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.849079982679592504e+01,1.095300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.849439953878355070e+01,1.095400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.849799925077117635e+01,1.095499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.850159896275880200e+01,1.095600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.850519867474642766e+01,1.095700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.850879838673405331e+01,1.095799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.851239809872167896e+01,1.095900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.851599781070930462e+01,1.096000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.851959752269693027e+01,1.096099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.852319723468455592e+01,1.096200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.852679694667218158e+01,1.096299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.853039665865980723e+01,1.096400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.853399637064743288e+01,1.096500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.853759608263505854e+01,1.096599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.854119579462268419e+01,1.096700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.854479550661030984e+01,1.096800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.854839521859793550e+01,1.096899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.855199493058556115e+01,1.097000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.855559464257318680e+01,1.097100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.855919435456081246e+01,1.097199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.856279406654843811e+01,1.097300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.856639377853606376e+01,1.097400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.856999349052368942e+01,1.097500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.857359320251131507e+01,1.097600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.857719291449894072e+01,1.097699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.858079262648656638e+01,1.097800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.858439233847419203e+01,1.097900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.858799205046181768e+01,1.097999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.859159176244944334e+01,1.098100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.859519147443706899e+01,1.098200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.859879118642469464e+01,1.098299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.860239089841232030e+01,1.098400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.860599061039994595e+01,1.098500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.860959032238757160e+01,1.098599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.861319003437519726e+01,1.098700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.861678974636282291e+01,1.098799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.862038945835044856e+01,1.098900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.862398917033807422e+01,1.099000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.862758888232569987e+01,1.099099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.863118859431332552e+01,1.099200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.863478830630095118e+01,1.099300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.863838801828857683e+01,1.099399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.864198773027620248e+01,1.099500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.864558744226382814e+01,1.099600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.864918715425145379e+01,1.099699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.865278686623907944e+01,1.099800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.865638657822670510e+01,1.099900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.865998629021433075e+01,1.100000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.866358600220195640e+01,1.100100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.866718571418958206e+01,1.100199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.867078542617720771e+01,1.100300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.867438513816483336e+01,1.100400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.867798485015245902e+01,1.100499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.868158456214008467e+01,1.100600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.868518427412771032e+01,1.100700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.868878398611533598e+01,1.100799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.869238369810296163e+01,1.100900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.869598341009058728e+01,1.101000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.869958312207821294e+01,1.101099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.870318283406583859e+01,1.101200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.870678254605346424e+01,1.101299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.871038225804108990e+01,1.101400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.871398197002871555e+01,1.101500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.871758168201634120e+01,1.101599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.872118139400396686e+01,1.101700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.872478110599159251e+01,1.101800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.872838081797921816e+01,1.101899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.873198052996684382e+01,1.102000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.873558024195446947e+01,1.102100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.873917995394209512e+01,1.102199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.874277966592972078e+01,1.102300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.874637937791734643e+01,1.102400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.874997908990497208e+01,1.102500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.875357880189259774e+01,1.102600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.875717851388022339e+01,1.102699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.876077822586784905e+01,1.102800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.876437793785547470e+01,1.102900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.876797764984310035e+01,1.102999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.877157736183072601e+01,1.103100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.877517707381835166e+01,1.103200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.877877678580597731e+01,1.103299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.878237649779360297e+01,1.103400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.878597620978122862e+01,1.103500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.878957592176885427e+01,1.103599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.879317563375647993e+01,1.103700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.879677534574410558e+01,1.103799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.880037505773173123e+01,1.103900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.880397476971935689e+01,1.104000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.880757448170698254e+01,1.104099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.881117419369460819e+01,1.104200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.881477390568223385e+01,1.104300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.881837361766985950e+01,1.104399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.882197332965748515e+01,1.104500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.882557304164511081e+01,1.104600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.882917275363273646e+01,1.104699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.883277246562036211e+01,1.104800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.883637217760798777e+01,1.104900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.883997188959561342e+01,1.105000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.884357160158323907e+01,1.105100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.884717131357086473e+01,1.105199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.885077102555849038e+01,1.105300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.885437073754611603e+01,1.105400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.885797044953374169e+01,1.105499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.886157016152136734e+01,1.105600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.886516987350899299e+01,1.105700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.886876958549661865e+01,1.105799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.887236929748424430e+01,1.105900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.887596900947186995e+01,1.106000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.887956872145949561e+01,1.106099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.888316843344712126e+01,1.106200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.888676814543474691e+01,1.106299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.889036785742237257e+01,1.106400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.889396756940999822e+01,1.106500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.889756728139762387e+01,1.106599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.890116699338524953e+01,1.106700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.890476670537287518e+01,1.106800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.890836641736050083e+01,1.106899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.891196612934812649e+01,1.107000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.891556584133575214e+01,1.107100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.891916555332337779e+01,1.107199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.892276526531100345e+01,1.107300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.892636497729862910e+01,1.107400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.892996468928625475e+01,1.107500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.893356440127388041e+01,1.107600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.893716411326150606e+01,1.107699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.894076382524913171e+01,1.107800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.894436353723675737e+01,1.107900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.894796324922438302e+01,1.107999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.895156296121200867e+01,1.108100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.895516267319963433e+01,1.108200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.895876238518725998e+01,1.108299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.896236209717488563e+01,1.108400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.896596180916251129e+01,1.108500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.896956152115013694e+01,1.108599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.897316123313776259e+01,1.108700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.897676094512538825e+01,1.108799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.898036065711301390e+01,1.108900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.898396036910063955e+01,1.109000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.898756008108826521e+01,1.109099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.899115979307589086e+01,1.109200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.899475950506351651e+01,1.109300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.899835921705114217e+01,1.109399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.900195892903876782e+01,1.109500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.900555864102639347e+01,1.109600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.900915835301401913e+01,1.109699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.901275806500164478e+01,1.109800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.901635777698927043e+01,1.109900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.901995748897689609e+01,1.110000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.902355720096452174e+01,1.110100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.902715691295214739e+01,1.110199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.903075662493977305e+01,1.110300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.903435633692739870e+01,1.110400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.903795604891502435e+01,1.110499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.904155576090265001e+01,1.110600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.904515547289027566e+01,1.110700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.904875518487790131e+01,1.110799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.905235489686552697e+01,1.110900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.905595460885315262e+01,1.111000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.905955432084077827e+01,1.111099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.906315403282840393e+01,1.111200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.906675374481602958e+01,1.111299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.907035345680365523e+01,1.111400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.907395316879128089e+01,1.111500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.907755288077890654e+01,1.111599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.908115259276653219e+01,1.111700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.908475230475415785e+01,1.111800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.908835201674178350e+01,1.111899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909195172872940915e+01,1.112000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909555144071703481e+01,1.112100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.909915115270466046e+01,1.112199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.910275086469228611e+01,1.112300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.910635057667991177e+01,1.112400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.910995028866753742e+01,1.112500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.911355000065516307e+01,1.112600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.911714971264278873e+01,1.112699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.912074942463041438e+01,1.112800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.912434913661804003e+01,1.112900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.912794884860566569e+01,1.112999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.913154856059329134e+01,1.113100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.913514827258091699e+01,1.113200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.913874798456854265e+01,1.113299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.914234769655616830e+01,1.113400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.914594740854379396e+01,1.113500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.914954712053141961e+01,1.113599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.915314683251904526e+01,1.113700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.915674654450667092e+01,1.113799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.916034625649429657e+01,1.113900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.916394596848192222e+01,1.114000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.916754568046954788e+01,1.114099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.917114539245717353e+01,1.114200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.917474510444479918e+01,1.114300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.917834481643242484e+01,1.114399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.918194452842005049e+01,1.114500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.918554424040767614e+01,1.114600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.918914395239530180e+01,1.114699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.919274366438292745e+01,1.114800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.919634337637055310e+01,1.114900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.919994308835817876e+01,1.115000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.920354280034580441e+01,1.115100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.920714251233343006e+01,1.115199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.921074222432105572e+01,1.115300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.921434193630868137e+01,1.115400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.921794164829630702e+01,1.115499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.922154136028393268e+01,1.115600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.922514107227155833e+01,1.115700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.922874078425918398e+01,1.115799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.923234049624680964e+01,1.115900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.923594020823443529e+01,1.116000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.923953992022206094e+01,1.116099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.924313963220968660e+01,1.116200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.924673934419731225e+01,1.116299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.925033905618493790e+01,1.116400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.925393876817256356e+01,1.116500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.925753848016018921e+01,1.116599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.926113819214781486e+01,1.116700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.926473790413544052e+01,1.116800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.926833761612306617e+01,1.116899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.927193732811069182e+01,1.117000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.927553704009831748e+01,1.117100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.927913675208594313e+01,1.117199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.928273646407356878e+01,1.117300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.928633617606119444e+01,1.117400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.928993588804882009e+01,1.117500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.929353560003644574e+01,1.117600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.929713531202407140e+01,1.117699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.930073502401169705e+01,1.117800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.930433473599932270e+01,1.117900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.930793444798694836e+01,1.117999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.931153415997457401e+01,1.118100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.931513387196219966e+01,1.118200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.931873358394982532e+01,1.118299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.932233329593745097e+01,1.118400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.932593300792507662e+01,1.118500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.932953271991270228e+01,1.118599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.933313243190032793e+01,1.118700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.933673214388795358e+01,1.118799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.934033185587557924e+01,1.118900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.934393156786320489e+01,1.119000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.934753127985083054e+01,1.119099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.935113099183845620e+01,1.119200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.935473070382608185e+01,1.119300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.935833041581370750e+01,1.119399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.936193012780133316e+01,1.119500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.936552983978895881e+01,1.119600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.936912955177658446e+01,1.119699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.937272926376421012e+01,1.119800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.937632897575183577e+01,1.119900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.937992868773946142e+01,1.120000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.938352839972708708e+01,1.120100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.938712811171471273e+01,1.120199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.939072782370233838e+01,1.120300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.939432753568996404e+01,1.120400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.939792724767758969e+01,1.120499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.940152695966521534e+01,1.120600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.940512667165284100e+01,1.120700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.940872638364046665e+01,1.120799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.941232609562809230e+01,1.120900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.941592580761571796e+01,1.121000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.941952551960334361e+01,1.121099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.942312523159096926e+01,1.121200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.942672494357859492e+01,1.121299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.943032465556622057e+01,1.121400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.943392436755384622e+01,1.121500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.943752407954147188e+01,1.121599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.944112379152909753e+01,1.121700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.944472350351672318e+01,1.121800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.944832321550434884e+01,1.121899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.945192292749197449e+01,1.122000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.945552263947960014e+01,1.122100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.945912235146722580e+01,1.122199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.946272206345485145e+01,1.122300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.946632177544247710e+01,1.122400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.946992148743010276e+01,1.122500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.947352119941772841e+01,1.122600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.947712091140535406e+01,1.122699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.948072062339297972e+01,1.122800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.948432033538060537e+01,1.122900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.948792004736823102e+01,1.122999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.949151975935585668e+01,1.123100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.949511947134348233e+01,1.123200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.949871918333110798e+01,1.123299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.950231889531873364e+01,1.123400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.950591860730635929e+01,1.123500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.950951831929398494e+01,1.123599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.951311803128161060e+01,1.123700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.951671774326923625e+01,1.123799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.952031745525686190e+01,1.123900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.952391716724448756e+01,1.124000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.952751687923211321e+01,1.124099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.953111659121973886e+01,1.124200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.953471630320736452e+01,1.124300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.953831601519499017e+01,1.124399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.954191572718261583e+01,1.124500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.954551543917024148e+01,1.124600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.954911515115786713e+01,1.124699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.955271486314549279e+01,1.124800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.955631457513311844e+01,1.124900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.955991428712074409e+01,1.125000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.956351399910836975e+01,1.125100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.956711371109599540e+01,1.125199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.957071342308362105e+01,1.125300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.957431313507124671e+01,1.125400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.957791284705887236e+01,1.125499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.958151255904649801e+01,1.125600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.958511227103412367e+01,1.125700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.958871198302174932e+01,1.125799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.959231169500937497e+01,1.125900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.959591140699700063e+01,1.126000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.959951111898462628e+01,1.126099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.960311083097225193e+01,1.126200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.960671054295987759e+01,1.126299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.961031025494750324e+01,1.126400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.961390996693512889e+01,1.126500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.961750967892275455e+01,1.126599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.962110939091038020e+01,1.126700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.962470910289800585e+01,1.126800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.962830881488563151e+01,1.126899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.963190852687325716e+01,1.127000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.963550823886088281e+01,1.127100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.963910795084850847e+01,1.127199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.964270766283613412e+01,1.127300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.964630737482375977e+01,1.127400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.964990708681138543e+01,1.127500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.965350679879901108e+01,1.127600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.965710651078663673e+01,1.127699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.966070622277426239e+01,1.127800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.966430593476188804e+01,1.127900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.966790564674951369e+01,1.127999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.967150535873713935e+01,1.128100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.967510507072476500e+01,1.128200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.967870478271239065e+01,1.128299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.968230449470001631e+01,1.128400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.968590420668764196e+01,1.128500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.968950391867526761e+01,1.128599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.969310363066289327e+01,1.128700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.969670334265051892e+01,1.128799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.970030305463814457e+01,1.128900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.970390276662577023e+01,1.129000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.970750247861339588e+01,1.129099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.971110219060102153e+01,1.129200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.971470190258864719e+01,1.129300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.971830161457627284e+01,1.129399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.972190132656389849e+01,1.129500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.972550103855152415e+01,1.129600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.972910075053914980e+01,1.129699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.973270046252677545e+01,1.129800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.973630017451440111e+01,1.129900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.973989988650202676e+01,1.130000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.974349959848965241e+01,1.130100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.974709931047727807e+01,1.130199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.975069902246490372e+01,1.130300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.975429873445252937e+01,1.130400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.975789844644015503e+01,1.130499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.976149815842778068e+01,1.130600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.976509787041540633e+01,1.130700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.976869758240303199e+01,1.130799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.977229729439065764e+01,1.130900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.977589700637828329e+01,1.131000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.977949671836590895e+01,1.131099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.978309643035353460e+01,1.131200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.978669614234116025e+01,1.131299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.979029585432878591e+01,1.131400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.979389556631641156e+01,1.131500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.979749527830403721e+01,1.131599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.980109499029166287e+01,1.131700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.980469470227928852e+01,1.131800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.980829441426691417e+01,1.131899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.981189412625453983e+01,1.132000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.981549383824216548e+01,1.132100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.981909355022979113e+01,1.132199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.982269326221741679e+01,1.132300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.982629297420504244e+01,1.132400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.982989268619266809e+01,1.132500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.983349239818029375e+01,1.132600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.983709211016791940e+01,1.132699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.984069182215554505e+01,1.132800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.984429153414317071e+01,1.132900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.984789124613079636e+01,1.132999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.985149095811842201e+01,1.133100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.985509067010604767e+01,1.133200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.985869038209367332e+01,1.133299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.986229009408129897e+01,1.133400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.986588980606892463e+01,1.133500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.986948951805655028e+01,1.133599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.987308923004417593e+01,1.133700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.987668894203180159e+01,1.133799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.988028865401942724e+01,1.133900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.988388836600705289e+01,1.134000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.988748807799467855e+01,1.134099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.989108778998230420e+01,1.134200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.989468750196992985e+01,1.134300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.989828721395755551e+01,1.134399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.990188692594518116e+01,1.134500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.990548663793280681e+01,1.134600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.990908634992043247e+01,1.134699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.991268606190805812e+01,1.134800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.991628577389568377e+01,1.134900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.991988548588330943e+01,1.135000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.992348519787093508e+01,1.135100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.992708490985856074e+01,1.135199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.993068462184618639e+01,1.135300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.993428433383381204e+01,1.135400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.993788404582143770e+01,1.135499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.994148375780906335e+01,1.135600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.994508346979668900e+01,1.135700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.994868318178431466e+01,1.135799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.995228289377194031e+01,1.135900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.995588260575956596e+01,1.136000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.995948231774719162e+01,1.136099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.996308202973481727e+01,1.136200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.996668174172244292e+01,1.136299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.997028145371006858e+01,1.136400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.997388116569769423e+01,1.136500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.997748087768531988e+01,1.136599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.998108058967294554e+01,1.136700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.998468030166057119e+01,1.136800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.998828001364819684e+01,1.136899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999187972563582250e+01,1.137000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999547943762344815e+01,1.137100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +1.999907914961107380e+01,1.137199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.000267886159869946e+01,1.137300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.000627857358632511e+01,1.137400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.000987828557395076e+01,1.137500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.001347799756157642e+01,1.137600000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.001707770954920207e+01,1.137699999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.002067742153682772e+01,1.137800000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.002427713352445338e+01,1.137900000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.002787684551207903e+01,1.137999999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.003147655749970468e+01,1.138100000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.003507626948733034e+01,1.138200000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.003867598147495599e+01,1.138299999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.004227569346258164e+01,1.138400000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.004587540545020730e+01,1.138500000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.004947511743783295e+01,1.138599999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.005307482942545860e+01,1.138700000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.005667454141308426e+01,1.138799999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.006027425340070991e+01,1.138900000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.006387396538833556e+01,1.139000000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.006747367737596122e+01,1.139099999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.007107338936358687e+01,1.139200000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.007467310135121252e+01,1.139300000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.007827281333883818e+01,1.139399999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.008187252532646383e+01,1.139500000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.008547223731408948e+01,1.139600000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.008907194930171514e+01,1.139699999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.009267166128934079e+01,1.139800000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.009627137327696644e+01,1.139900000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.009987108526459210e+01,1.140000000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.010347079725221775e+01,1.140100000000000051e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.010707050923984340e+01,1.140199999999999960e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.011067022122746906e+01,1.140300000000000011e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.011426993321509471e+01,1.140400000000000063e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.011786964520272036e+01,1.140499999999999972e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.012146935719034602e+01,1.140600000000000023e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.012506906917797167e+01,1.140700000000000074e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.012866878116559732e+01,1.140799999999999983e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.013226849315322298e+01,1.140900000000000034e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.013586820514084863e+01,1.141000000000000085e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.013946791712847428e+01,1.141099999999999994e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.014306762911609994e+01,1.141200000000000045e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.014666734110372559e+01,1.141299999999999955e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.015026705309135124e+01,1.141400000000000006e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.015386676507897690e+01,1.141500000000000057e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.015746647706660255e+01,1.141599999999999966e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.016106618905422820e+01,1.141700000000000017e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.016466590104185386e+01,1.141800000000000068e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.016826561302947951e+01,1.141899999999999977e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.017186532501710516e+01,1.142000000000000028e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.017546503700473082e+01,1.142100000000000080e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.017906474899235647e+01,1.142199999999999989e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.018266446097998212e+01,1.142300000000000040e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +2.018626417296760778e+01,1.142400000000000091e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,4.112595145414723780e-10,0.000000000000000000e+00 +2.018986388495523343e+01,1.142500000000000000e+02,0.000000000000000000e+00,2.778000027328973331e+00,0.000000000000000000e+00,1.480415804519971206e-12,0.000000000000000000e+00,3.441433326333532362e-05,0.000000000000000000e+00 +2.019346359694285908e+01,1.142600000000000051e+02,0.000000000000000000e+00,2.778000027328978661e+00,0.000000000000000000e+00,1.238831684099708011e-07,0.000000000000000000e+00,-5.944211625601464322e-01,0.000000000000000000e+00 +2.019706330893048474e+01,1.142699999999999960e+02,0.000000000000000000e+00,2.778000027774922387e+00,0.000000000000000000e+00,-2.139621101397615969e-03,0.000000000000000000e+00,-9.999996136541885461e-01,0.000000000000000000e+00 +2.020066302091753130e+01,1.142800000000000011e+02,0.000000000000000000e+00,2.777992325755195946e+00,0.000000000000000000e+00,-5.739331697711584114e-03,0.000000000000000000e+00,-9.999998107169645323e-01,0.000000000000000000e+00 +2.020426274288482560e+01,1.142900000000000063e+02,0.000000000000000000e+00,2.777971665756806097e+00,0.000000000000000000e+00,-9.339052983641037142e-03,0.000000000000000000e+00,-9.999998763999631279e-01,0.000000000000000000e+00 +2.020786249162354409e+01,1.142999999999999972e+02,0.000000000000000000e+00,2.777938047512607422e+00,0.000000000000000000e+00,-1.293880127742909510e-02,0.000000000000000000e+00,-9.999999091688275277e-01,0.000000000000000000e+00 +2.021146228392595035e+01,1.143100000000000023e+02,0.000000000000000000e+00,2.777891470515366557e+00,0.000000000000000000e+00,-1.653859325286295007e-02,0.000000000000000000e+00,-9.999999288900709438e-01,0.000000000000000000e+00 +2.021506213658619444e+01,1.143200000000000074e+02,0.000000000000000000e+00,2.777831934016448567e+00,0.000000000000000000e+00,-2.013844565712029355e-02,0.000000000000000000e+00,-9.999999420137737349e-01,0.000000000000000000e+00 +2.021866206640107677e+01,1.143299999999999983e+02,0.000000000000000000e+00,2.777759437025502098e+00,0.000000000000000000e+00,-2.373837526325697778e-02,0.000000000000000000e+00,-9.999999514081863161e-01,0.000000000000000000e+00 +2.022226209017084742e+01,1.143400000000000034e+02,0.000000000000000000e+00,2.777673978310298608e+00,0.000000000000000000e+00,-2.733839885809718692e-02,0.000000000000000000e+00,-9.999999583803419467e-01,0.000000000000000000e+00 +2.022586222469998418e+01,1.143500000000000085e+02,0.000000000000000000e+00,2.777575556396598255e+00,0.000000000000000000e+00,-3.093853323739773065e-02,0.000000000000000000e+00,-9.999999639080573433e-01,0.000000000000000000e+00 +2.022946248679797421e+01,1.143599999999999994e+02,0.000000000000000000e+00,2.777464169568016228e+00,0.000000000000000000e+00,-3.453879520544794052e-02,0.000000000000000000e+00,-9.999999682268747581e-01,0.000000000000000000e+00 +2.023306289328010621e+01,1.143700000000000045e+02,0.000000000000000000e+00,2.777339815865873529e+00,0.000000000000000000e+00,-3.813920157318303333e-02,0.000000000000000000e+00,-9.999999717872442018e-01,0.000000000000000000e+00 +2.023666346096824853e+01,1.143799999999999955e+02,0.000000000000000000e+00,2.777202493089037549e+00,0.000000000000000000e+00,-4.173976915974420693e-02,0.000000000000000000e+00,-9.999999748065780958e-01,0.000000000000000000e+00 +2.024026420669164494e+01,1.143900000000000006e+02,0.000000000000000000e+00,2.777052198793739990e+00,0.000000000000000000e+00,-4.534051479242687949e-02,0.000000000000000000e+00,-9.999999772665509878e-01,0.000000000000000000e+00 +2.024386514728769981e+01,1.144000000000000057e+02,0.000000000000000000e+00,2.776888930293377911e+00,0.000000000000000000e+00,-4.894145530662001586e-02,0.000000000000000000e+00,-9.999999794580287649e-01,0.000000000000000000e+00 +2.024746629960276323e+01,1.144099999999999966e+02,0.000000000000000000e+00,2.776712684658297903e+00,0.000000000000000000e+00,-5.254260754770867514e-02,0.000000000000000000e+00,-9.999999813269465632e-01,0.000000000000000000e+00 +2.025106768049292683e+01,1.144200000000000017e+02,0.000000000000000000e+00,2.776523458715556281e+00,0.000000000000000000e+00,-5.614398837062232334e-02,0.000000000000000000e+00,-9.999999829159029741e-01,0.000000000000000000e+00 +2.025466930682480893e+01,1.144300000000000068e+02,0.000000000000000000e+00,2.776321249048663731e+00,0.000000000000000000e+00,-5.974561464097449814e-02,0.000000000000000000e+00,-9.999999843943699895e-01,0.000000000000000000e+00 +2.025827119547635746e+01,1.144399999999999977e+02,0.000000000000000000e+00,2.776106051997308644e+00,0.000000000000000000e+00,-6.334750323631277436e-02,0.000000000000000000e+00,-9.999999856094087258e-01,0.000000000000000000e+00 +2.026187336333763511e+01,1.144500000000000028e+02,0.000000000000000000e+00,2.775877863657058686e+00,0.000000000000000000e+00,-6.694967104575198780e-02,0.000000000000000000e+00,-9.999999867999979086e-01,0.000000000000000000e+00 +2.026547582731161867e+01,1.144600000000000080e+02,0.000000000000000000e+00,2.775636679879046387e+00,0.000000000000000000e+00,-7.055213497218193464e-02,0.000000000000000000e+00,-9.999999878049278257e-01,0.000000000000000000e+00 +2.026907860431499486e+01,1.144699999999999989e+02,0.000000000000000000e+00,2.775382496269629407e+00,0.000000000000000000e+00,-7.415491193162355998e-02,0.000000000000000000e+00,-9.999999887421905376e-01,0.000000000000000000e+00 +2.027268171127897034e+01,1.144800000000000040e+02,0.000000000000000000e+00,2.775115308190035712e+00,0.000000000000000000e+00,-7.775801885503423605e-02,0.000000000000000000e+00,-9.999999895586452192e-01,0.000000000000000000e+00 +2.027628516515005330e+01,1.144900000000000091e+02,0.000000000000000000e+00,2.774835110755984768e+00,0.000000000000000000e+00,-8.136147268849262815e-02,0.000000000000000000e+00,-9.999999903322259742e-01,0.000000000000000000e+00 +2.027988898289087771e+01,1.145000000000000000e+02,0.000000000000000000e+00,2.774541898837290521e+00,0.000000000000000000e+00,-8.496529039447438258e-02,0.000000000000000000e+00,-9.999999910606144349e-01,0.000000000000000000e+00 +2.028349318148099201e+01,1.145100000000000051e+02,0.000000000000000000e+00,2.774235667057442178e+00,0.000000000000000000e+00,-8.856948895236849140e-02,0.000000000000000000e+00,-9.999999916208300865e-01,0.000000000000000000e+00 +2.028709777791767621e+01,1.145199999999999960e+02,0.000000000000000000e+00,2.773916409793165450e+00,0.000000000000000000e+00,-9.217408535885007748e-02,0.000000000000000000e+00,-9.999999923094486931e-01,0.000000000000000000e+00 +2.029070278921675197e+01,1.145300000000000011e+02,0.000000000000000000e+00,2.773584121173964689e+00,0.000000000000000000e+00,-9.577909663020274522e-02,0.000000000000000000e+00,-9.999999927760859775e-01,0.000000000000000000e+00 +2.029430823241339255e+01,1.145400000000000063e+02,0.000000000000000000e+00,2.773238795081638841e+00,0.000000000000000000e+00,-9.938453980079899053e-02,0.000000000000000000e+00,-9.999999933489982507e-01,0.000000000000000000e+00 +2.029791412456293642e+01,1.145499999999999972e+02,0.000000000000000000e+00,2.772880425149784944e+00,0.000000000000000000e+00,-1.029904319263617307e-01,0.000000000000000000e+00,-9.999999937631870450e-01,0.000000000000000000e+00 +2.030152048274171150e+01,1.145600000000000023e+02,0.000000000000000000e+00,2.772509004763271889e+00,0.000000000000000000e+00,-1.065967900826430975e-01,0.000000000000000000e+00,-9.999999942115762597e-01,0.000000000000000000e+00 +2.030512732404784160e+01,1.145700000000000074e+02,0.000000000000000000e+00,2.772124527057700849e+00,0.000000000000000000e+00,-1.102036313678960572e-01,0.000000000000000000e+00,-9.999999946194833012e-01,0.000000000000000000e+00 +2.030873466560208840e+01,1.145799999999999983e+02,0.000000000000000000e+00,2.771726984918838621e+00,0.000000000000000000e+00,-1.138109729027327738e-01,0.000000000000000000e+00,-9.999999950458769993e-01,0.000000000000000000e+00 +2.031234252454866152e+01,1.145900000000000034e+02,0.000000000000000000e+00,2.771316370982033206e+00,0.000000000000000000e+00,-1.174188318314329932e-01,0.000000000000000000e+00,-9.999999953332767699e-01,0.000000000000000000e+00 +2.031595091805606046e+01,1.146000000000000085e+02,0.000000000000000000e+00,2.770892677631606293e+00,0.000000000000000000e+00,-1.210272253219925737e-01,0.000000000000000000e+00,-9.999999957126403105e-01,0.000000000000000000e+00 +2.031955986331789887e+01,1.146099999999999994e+02,0.000000000000000000e+00,2.770455897000227097e+00,0.000000000000000000e+00,-1.246361705683576571e-01,0.000000000000000000e+00,-9.999999960092668116e-01,0.000000000000000000e+00 +2.032316937755374298e+01,1.146200000000000045e+02,0.000000000000000000e+00,2.770006020968259541e+00,0.000000000000000000e+00,-1.282456847897969487e-01,0.000000000000000000e+00,-9.999999962810499632e-01,0.000000000000000000e+00 +2.032677947800995355e+01,1.146299999999999955e+02,0.000000000000000000e+00,2.769543041163093022e+00,0.000000000000000000e+00,-1.318557852325804580e-01,0.000000000000000000e+00,-9.999999966035658661e-01,0.000000000000000000e+00 +2.033039018196052439e+01,1.146400000000000006e+02,0.000000000000000000e+00,2.769066948958448293e+00,0.000000000000000000e+00,-1.354664891708864949e-01,0.000000000000000000e+00,-9.999999968551526175e-01,0.000000000000000000e+00 +2.033400150670793138e+01,1.146500000000000057e+02,0.000000000000000000e+00,2.768577735473661150e+00,0.000000000000000000e+00,-1.390778139069362707e-01,0.000000000000000000e+00,-9.999999970809919647e-01,0.000000000000000000e+00 +2.033761346958398519e+01,1.146599999999999966e+02,0.000000000000000000e+00,2.768075391572946575e+00,0.000000000000000000e+00,-1.426897767724467359e-01,0.000000000000000000e+00,-9.999999973453250757e-01,0.000000000000000000e+00 +2.034122608795068388e+01,1.146700000000000017e+02,0.000000000000000000e+00,2.767559907864638458e+00,0.000000000000000000e+00,-1.463023951295539804e-01,0.000000000000000000e+00,-9.999999975500122318e-01,0.000000000000000000e+00 +2.034483937920106911e+01,1.146800000000000068e+02,0.000000000000000000e+00,2.767031274700406662e+00,0.000000000000000000e+00,-1.499156863710851550e-01,0.000000000000000000e+00,-9.999999977287989950e-01,0.000000000000000000e+00 +2.034845336076008948e+01,1.146899999999999977e+02,0.000000000000000000e+00,2.766489482174453673e+00,0.000000000000000000e+00,-1.535296679218974836e-01,0.000000000000000000e+00,-9.999999980009240952e-01,0.000000000000000000e+00 +2.035206805008547093e+01,1.147000000000000028e+02,0.000000000000000000e+00,2.765934520122686813e+00,0.000000000000000000e+00,-1.571443572400543220e-01,0.000000000000000000e+00,-9.999999981166758367e-01,0.000000000000000000e+00 +2.035568346466858713e+01,1.147100000000000080e+02,0.000000000000000000e+00,2.765366378121866475e+00,0.000000000000000000e+00,-1.607597718163629452e-01,0.000000000000000000e+00,-9.999999983281311344e-01,0.000000000000000000e+00 +2.035929962203533350e+01,1.147199999999999989e+02,0.000000000000000000e+00,2.764785045488736159e+00,0.000000000000000000e+00,-1.643759291770642561e-01,0.000000000000000000e+00,-9.999999984922078866e-01,0.000000000000000000e+00 +2.036291653974700822e+01,1.147300000000000040e+02,0.000000000000000000e+00,2.764190511279122742e+00,0.000000000000000000e+00,-1.679928468832848354e-01,0.000000000000000000e+00,-9.999999986346299607e-01,0.000000000000000000e+00 +2.036653423540119690e+01,1.147400000000000091e+02,0.000000000000000000e+00,2.763582764287018545e+00,0.000000000000000000e+00,-1.716105425325325506e-01,0.000000000000000000e+00,-9.999999988337301415e-01,0.000000000000000000e+00 +2.037015272663266074e+01,1.147500000000000000e+02,0.000000000000000000e+00,2.762961793043637648e+00,0.000000000000000000e+00,-1.752290337597772751e-01,0.000000000000000000e+00,-9.999999989686163548e-01,0.000000000000000000e+00 +2.037377203111424251e+01,1.147600000000000051e+02,0.000000000000000000e+00,2.762327585816447773e+00,0.000000000000000000e+00,-1.788483382376254149e-01,0.000000000000000000e+00,-9.999999990774685044e-01,0.000000000000000000e+00 +2.037739216655775110e+01,1.147699999999999960e+02,0.000000000000000000e+00,2.761680130608180850e+00,0.000000000000000000e+00,-1.824684736777958949e-01,0.000000000000000000e+00,-9.999999992404297045e-01,0.000000000000000000e+00 +2.038101315071488528e+01,1.147800000000000011e+02,0.000000000000000000e+00,2.761019415155817391e+00,0.000000000000000000e+00,-1.860894578321780624e-01,0.000000000000000000e+00,-9.999999993267733034e-01,0.000000000000000000e+00 +2.038463500137812545e+01,1.147900000000000063e+02,0.000000000000000000e+00,2.760345426929545987e+00,0.000000000000000000e+00,-1.897113084929795135e-01,0.000000000000000000e+00,-9.999999994870902853e-01,0.000000000000000000e+00 +2.038825773638166439e+01,1.147999999999999972e+02,0.000000000000000000e+00,2.759658153131701042e+00,0.000000000000000000e+00,-1.933340434946616559e-01,0.000000000000000000e+00,-9.999999995949653275e-01,0.000000000000000000e+00 +2.039188137360233100e+01,1.148100000000000023e+02,0.000000000000000000e+00,2.758957580695672096e+00,0.000000000000000000e+00,-1.969576807138590790e-01,0.000000000000000000e+00,-9.999999997041266742e-01,0.000000000000000000e+00 +2.039550593096050335e+01,1.148200000000000074e+02,0.000000000000000000e+00,2.758243696284791824e+00,0.000000000000000000e+00,-2.005822380709605113e-01,0.000000000000000000e+00,-9.999999997942090602e-01,0.000000000000000000e+00 +2.039913142642106436e+01,1.148299999999999983e+02,0.000000000000000000e+00,2.757516486291196500e+00,0.000000000000000000e+00,-2.042077335307748709e-01,0.000000000000000000e+00,-9.999999998883964958e-01,0.000000000000000000e+00 +2.040275787799432550e+01,1.148400000000000034e+02,0.000000000000000000e+00,2.756775936834662044e+00,0.000000000000000000e+00,-2.078341851036297483e-01,0.000000000000000000e+00,-1.000000000001404654e+00,0.000000000000000000e+00 +2.040638530373697890e+01,1.148500000000000085e+02,0.000000000000000000e+00,2.756022033761413859e+00,0.000000000000000000e+00,-2.114616108462877009e-01,0.000000000000000000e+00,-1.000000000087306384e+00,0.000000000000000000e+00 +2.041001372175305306e+01,1.148599999999999994e+02,0.000000000000000000e+00,2.755254762642910915e+00,0.000000000000000000e+00,-2.150900288626796386e-01,0.000000000000000000e+00,-1.000000000155522928e+00,0.000000000000000000e+00 +2.041364315019487563e+01,1.148700000000000045e+02,0.000000000000000000e+00,2.754474108774604524e+00,0.000000000000000000e+00,-2.187194573050654789e-01,0.000000000000000000e+00,-1.000000000285031776e+00,0.000000000000000000e+00 +2.041727360726402907e+01,1.148799999999999955e+02,0.000000000000000000e+00,2.753680057174670015e+00,0.000000000000000000e+00,-2.223499143752533935e-01,0.000000000000000000e+00,-1.000000000301179748e+00,0.000000000000000000e+00 +2.042090511121233476e+01,1.148900000000000006e+02,0.000000000000000000e+00,2.752872592582710887e+00,0.000000000000000000e+00,-2.259814183246526553e-01,0.000000000000000000e+00,-1.000000000395534272e+00,0.000000000000000000e+00 +2.042453768034283001e+01,1.149000000000000057e+02,0.000000000000000000e+00,2.752051699458439415e+00,0.000000000000000000e+00,-2.296139874565838457e-01,0.000000000000000000e+00,-1.000000000498652675e+00,0.000000000000000000e+00 +2.042817133301075216e+01,1.149099999999999966e+02,0.000000000000000000e+00,2.751217361980325293e+00,0.000000000000000000e+00,-2.332476401263190724e-01,0.000000000000000000e+00,-1.000000000528497690e+00,0.000000000000000000e+00 +2.043180608762454398e+01,1.149200000000000017e+02,0.000000000000000000e+00,2.750369564044220283e+00,0.000000000000000000e+00,-2.368823947420310716e-01,0.000000000000000000e+00,-1.000000000603851413e+00,0.000000000000000000e+00 +2.043544196264684132e+01,1.149300000000000068e+02,0.000000000000000000e+00,2.749508289261955341e+00,0.000000000000000000e+00,-2.405182697665256830e-01,0.000000000000000000e+00,-1.000000000685856705e+00,0.000000000000000000e+00 +2.043907897659549988e+01,1.149399999999999977e+02,0.000000000000000000e+00,2.748633520959907095e+00,0.000000000000000000e+00,-2.441552837176794166e-01,0.000000000000000000e+00,-1.000000000689894586e+00,0.000000000000000000e+00 +2.044271714804460061e+01,1.149500000000000028e+02,0.000000000000000000e+00,2.747745242177538127e+00,0.000000000000000000e+00,-2.477934551692909937e-01,0.000000000000000000e+00,-1.000000000797892863e+00,0.000000000000000000e+00 +2.044635649562548352e+01,1.149600000000000080e+02,0.000000000000000000e+00,2.746843435665909272e+00,0.000000000000000000e+00,-2.514328027530772225e-01,0.000000000000000000e+00,-1.000000000830540525e+00,0.000000000000000000e+00 +2.044999703802777447e+01,1.149699999999999989e+02,0.000000000000000000e+00,2.745928083886159499e+00,0.000000000000000000e+00,-2.550733451583931388e-01,0.000000000000000000e+00,-1.000000000860540528e+00,0.000000000000000000e+00 +2.045363879400044027e+01,1.149800000000000040e+02,0.000000000000000000e+00,2.744999169007961370e+00,0.000000000000000000e+00,-2.587151011341916607e-01,0.000000000000000000e+00,-1.000000000919203602e+00,0.000000000000000000e+00 +2.045728178235282613e+01,1.149900000000000091e+02,0.000000000000000000e+00,2.744056672907943639e+00,0.000000000000000000e+00,-2.623580894899243954e-01,0.000000000000000000e+00,-1.000000000971400738e+00,0.000000000000000000e+00 +2.046092602195572141e+01,1.150000000000000000e+02,0.000000000000000000e+00,2.743100577168084531e+00,0.000000000000000000e+00,-2.660023290963596243e-01,0.000000000000000000e+00,-1.000000001023451768e+00,0.000000000000000000e+00 +2.046457153174243260e+01,1.150100000000000051e+02,0.000000000000000000e+00,2.742130863074075720e+00,0.000000000000000000e+00,-2.696478388868020493e-01,0.000000000000000000e+00,-1.000000000996664973e+00,0.000000000000000000e+00 +2.046821833070985619e+01,1.150199999999999960e+02,0.000000000000000000e+00,2.741147511613655219e+00,0.000000000000000000e+00,-2.732946378578606783e-01,0.000000000000000000e+00,-1.000000001100848301e+00,0.000000000000000000e+00 +2.047186643791956584e+01,1.150300000000000011e+02,0.000000000000000000e+00,2.740150503474910515e+00,0.000000000000000000e+00,-2.769427450715880035e-01,0.000000000000000000e+00,-1.000000001105663339e+00,0.000000000000000000e+00 +2.047551587249891369e+01,1.150400000000000063e+02,0.000000000000000000e+00,2.739139819044546620e+00,0.000000000000000000e+00,-2.805921796549713521e-01,0.000000000000000000e+00,-1.000000001147089534e+00,0.000000000000000000e+00 +2.047916665364212818e+01,1.150499999999999972e+02,0.000000000000000000e+00,2.738115438406128366e+00,0.000000000000000000e+00,-2.842429608023751553e-01,0.000000000000000000e+00,-1.000000001164662589e+00,0.000000000000000000e+00 +2.048281880061144022e+01,1.150600000000000023e+02,0.000000000000000000e+00,2.737077341338285841e+00,0.000000000000000000e+00,-2.878951077759401844e-01,0.000000000000000000e+00,-1.000000001205621603e+00,0.000000000000000000e+00 +2.048647233273819879e+01,1.150700000000000074e+02,0.000000000000000000e+00,2.736025507312890070e+00,0.000000000000000000e+00,-2.915486399071026691e-01,0.000000000000000000e+00,-1.000000001195114896e+00,0.000000000000000000e+00 +2.049012726942401130e+01,1.150799999999999983e+02,0.000000000000000000e+00,2.734959915493194504e+00,0.000000000000000000e+00,-2.952035765972844672e-01,0.000000000000000000e+00,-1.000000001238326108e+00,0.000000000000000000e+00 +2.049378363014189830e+01,1.150900000000000034e+02,0.000000000000000000e+00,2.733880544731944973e+00,0.000000000000000000e+00,-2.988599373196974551e-01,0.000000000000000000e+00,-1.000000001289921503e+00,0.000000000000000000e+00 +2.049744143443743383e+01,1.151000000000000085e+02,0.000000000000000000e+00,2.732787373569453671e+00,0.000000000000000000e+00,-3.025177416199507086e-01,0.000000000000000000e+00,-1.000000001222327350e+00,0.000000000000000000e+00 +2.050110070192992850e+01,1.151099999999999994e+02,0.000000000000000000e+00,2.731680380231641170e+00,0.000000000000000000e+00,-3.061770091169172536e-01,0.000000000000000000e+00,-1.000000001323872567e+00,0.000000000000000000e+00 +2.050476145231359837e+01,1.151200000000000045e+02,0.000000000000000000e+00,2.730559542628045122e+00,0.000000000000000000e+00,-3.098377595054347955e-01,0.000000000000000000e+00,-1.000000001270462180e+00,0.000000000000000000e+00 +2.050842370535876569e+01,1.151299999999999955e+02,0.000000000000000000e+00,2.729424838349788551e+00,0.000000000000000000e+00,-3.135000125552547812e-01,0.000000000000000000e+00,-1.000000001318709586e+00,0.000000000000000000e+00 +2.051208748091304912e+01,1.151400000000000006e+02,0.000000000000000000e+00,2.728276244667521055e+00,0.000000000000000000e+00,-3.171637881143696824e-01,0.000000000000000000e+00,-1.000000001343145151e+00,0.000000000000000000e+00 +2.051575279890258230e+01,1.151500000000000057e+02,0.000000000000000000e+00,2.727113738529316489e+00,0.000000000000000000e+00,-3.208291061088274221e-01,0.000000000000000000e+00,-1.000000001298328556e+00,0.000000000000000000e+00 +2.051941967933324307e+01,1.151599999999999966e+02,0.000000000000000000e+00,2.725937296558539558e+00,0.000000000000000000e+00,-3.244959865442492708e-01,0.000000000000000000e+00,-1.000000001314447218e+00,0.000000000000000000e+00 +2.052308814229188272e+01,1.151700000000000017e+02,0.000000000000000000e+00,2.724746895051674667e+00,0.000000000000000000e+00,-3.281644495077111756e-01,0.000000000000000000e+00,-1.000000001330243471e+00,0.000000000000000000e+00 +2.052675820794758010e+01,1.151800000000000068e+02,0.000000000000000000e+00,2.723542509976115245e+00,0.000000000000000000e+00,-3.318345151682916550e-01,0.000000000000000000e+00,-1.000000001352929102e+00,0.000000000000000000e+00 +2.053042989655290640e+01,1.151899999999999977e+02,0.000000000000000000e+00,2.722324116967917984e+00,0.000000000000000000e+00,-3.355062037785850881e-01,0.000000000000000000e+00,-1.000000001288268381e+00,0.000000000000000000e+00 +2.053410322844519342e+01,1.152000000000000028e+02,0.000000000000000000e+00,2.721091691329518003e+00,0.000000000000000000e+00,-3.391795356756042157e-01,0.000000000000000000e+00,-1.000000001362260527e+00,0.000000000000000000e+00 +2.053777822404782682e+01,1.152100000000000080e+02,0.000000000000000000e+00,2.719845208027406702e+00,0.000000000000000000e+00,-3.428545312832445568e-01,0.000000000000000000e+00,-1.000000001291690088e+00,0.000000000000000000e+00 +2.054145490387154993e+01,1.152199999999999989e+02,0.000000000000000000e+00,2.718584641689766102e+00,0.000000000000000000e+00,-3.465312111117151983e-01,0.000000000000000000e+00,-1.000000001296273089e+00,0.000000000000000000e+00 +2.054513328851576759e+01,1.152300000000000040e+02,0.000000000000000000e+00,2.717309966604070315e+00,0.000000000000000000e+00,-3.502095957607019305e-01,0.000000000000000000e+00,-1.000000001300736185e+00,0.000000000000000000e+00 +2.054881339866988910e+01,1.152400000000000091e+02,0.000000000000000000e+00,2.716021156714639950e+00,0.000000000000000000e+00,-3.538897059196120520e-01,0.000000000000000000e+00,-1.000000001287341345e+00,0.000000000000000000e+00 +2.055249525511466757e+01,1.152500000000000000e+02,0.000000000000000000e+00,2.714718185620159652e+00,0.000000000000000000e+00,-3.575715623691286815e-01,0.000000000000000000e+00,-1.000000001252463022e+00,0.000000000000000000e+00 +2.055617887872354643e+01,1.152600000000000051e+02,0.000000000000000000e+00,2.713401026571153452e+00,0.000000000000000000e+00,-3.612551859826199641e-01,0.000000000000000000e+00,-1.000000001228298574e+00,0.000000000000000000e+00 +2.055986429046404140e+01,1.152699999999999960e+02,0.000000000000000000e+00,2.712069652467417935e+00,0.000000000000000000e+00,-3.649405977276430346e-01,0.000000000000000000e+00,-1.000000001237729030e+00,0.000000000000000000e+00 +2.056355151139912962e+01,1.152800000000000011e+02,0.000000000000000000e+00,2.710724035855412328e+00,0.000000000000000000e+00,-3.686278186672967694e-01,0.000000000000000000e+00,-1.000000001216267531e+00,0.000000000000000000e+00 +2.056724056268864942e+01,1.152900000000000063e+02,0.000000000000000000e+00,2.709364148925605509e+00,0.000000000000000000e+00,-3.723168699613016996e-01,0.000000000000000000e+00,-1.000000001194236710e+00,0.000000000000000000e+00 +2.057093146559070718e+01,1.152999999999999972e+02,0.000000000000000000e+00,2.707989963509780384e+00,0.000000000000000000e+00,-3.760077728677669873e-01,0.000000000000000000e+00,-1.000000001118341864e+00,0.000000000000000000e+00 +2.057462424146312685e+01,1.153100000000000023e+02,0.000000000000000000e+00,2.706601451078292531e+00,0.000000000000000000e+00,-3.797005487443151361e-01,0.000000000000000000e+00,-1.000000001129221605e+00,0.000000000000000000e+00 +2.057831891176488881e+01,1.153200000000000074e+02,0.000000000000000000e+00,2.705198582737284863e+00,0.000000000000000000e+00,-3.833952190502474267e-01,0.000000000000000000e+00,-1.000000001088420243e+00,0.000000000000000000e+00 +2.058201549805759711e+01,1.153299999999999983e+02,0.000000000000000000e+00,2.703781329225853902e+00,0.000000000000000000e+00,-3.870918053469789566e-01,0.000000000000000000e+00,-1.000000001049086151e+00,0.000000000000000000e+00 +2.058571402200696809e+01,1.153400000000000034e+02,0.000000000000000000e+00,2.702349660913173413e+00,0.000000000000000000e+00,-3.907903293002285561e-01,0.000000000000000000e+00,-1.000000001041188469e+00,0.000000000000000000e+00 +2.058941450538431894e+01,1.153500000000000085e+02,0.000000000000000000e+00,2.700903547795568294e+00,0.000000000000000000e+00,-3.944908126814327121e-01,0.000000000000000000e+00,-1.000000000954774482e+00,0.000000000000000000e+00 +2.059311697006809538e+01,1.153599999999999994e+02,0.000000000000000000e+00,2.699442959493540961e+00,0.000000000000000000e+00,-3.981932773687443250e-01,0.000000000000000000e+00,-1.000000000939961664e+00,0.000000000000000000e+00 +2.059682143804539933e+01,1.153700000000000045e+02,0.000000000000000000e+00,2.697967865248751096e+00,0.000000000000000000e+00,-4.018977453495294339e-01,0.000000000000000000e+00,-1.000000000898625396e+00,0.000000000000000000e+00 +2.060052793141353789e+01,1.153799999999999955e+02,0.000000000000000000e+00,2.696478233920942547e+00,0.000000000000000000e+00,-4.056042387210004319e-01,0.000000000000000000e+00,-1.000000000849944559e+00,0.000000000000000000e+00 +2.060423647238160783e+01,1.153900000000000006e+02,0.000000000000000000e+00,2.694974033984823603e+00,0.000000000000000000e+00,-4.093127796922206851e-01,0.000000000000000000e+00,-1.000000000776045672e+00,0.000000000000000000e+00 +2.060794708327206237e+01,1.154000000000000057e+02,0.000000000000000000e+00,2.693455233526894865e+00,0.000000000000000000e+00,-4.130233905855562049e-01,0.000000000000000000e+00,-1.000000000725683069e+00,0.000000000000000000e+00 +2.061165978652234188e+01,1.154099999999999966e+02,0.000000000000000000e+00,2.691921800242226048e+00,0.000000000000000000e+00,-4.167360938385308300e-01,0.000000000000000000e+00,-1.000000000690157931e+00,0.000000000000000000e+00 +2.061537460468648675e+01,1.154200000000000017e+02,0.000000000000000000e+00,2.690373701431179487e+00,0.000000000000000000e+00,-4.204509120052404847e-01,0.000000000000000000e+00,-1.000000000607967010e+00,0.000000000000000000e+00 +2.061909156043678948e+01,1.154300000000000068e+02,0.000000000000000000e+00,2.688810903996081247e+00,0.000000000000000000e+00,-4.241678677578037959e-01,0.000000000000000000e+00,-1.000000000560291147e+00,0.000000000000000000e+00 +2.062281067656546085e+01,1.154399999999999977e+02,0.000000000000000000e+00,2.687233374437838940e+00,0.000000000000000000e+00,-4.278869838885592247e-01,0.000000000000000000e+00,-1.000000000515200549e+00,0.000000000000000000e+00 +2.062653197598631749e+01,1.154500000000000028e+02,0.000000000000000000e+00,2.685641078852502694e+00,0.000000000000000000e+00,-4.316082833113322748e-01,0.000000000000000000e+00,-1.000000000360502517e+00,0.000000000000000000e+00 +2.063025548173648716e+01,1.154600000000000080e+02,0.000000000000000000e+00,2.684033982927771955e+00,0.000000000000000000e+00,-4.353317890628445874e-01,0.000000000000000000e+00,-1.000000000382570642e+00,0.000000000000000000e+00 +2.063398121697814602e+01,1.154699999999999989e+02,0.000000000000000000e+00,2.682412051939446762e+00,0.000000000000000000e+00,-4.390575243059273158e-01,0.000000000000000000e+00,-1.000000000239140263e+00,0.000000000000000000e+00 +2.063770920500025952e+01,1.154800000000000040e+02,0.000000000000000000e+00,2.680775250747815974e+00,0.000000000000000000e+00,-4.427855123289311523e-01,0.000000000000000000e+00,-1.000000000171573866e+00,0.000000000000000000e+00 +2.064143946922036221e+01,1.154900000000000091e+02,0.000000000000000000e+00,2.679123543793995754e+00,0.000000000000000000e+00,-4.465157765496733377e-01,0.000000000000000000e+00,-1.000000000103221875e+00,0.000000000000000000e+00 +2.064517203318635197e+01,1.155000000000000000e+02,0.000000000000000000e+00,2.677456895096200551e+00,0.000000000000000000e+00,-4.502483405160482843e-01,0.000000000000000000e+00,-9.999999999847486443e-01,0.000000000000000000e+00 +2.064890692057830890e+01,1.155100000000000051e+02,0.000000000000000000e+00,2.675775268245958127e+00,0.000000000000000000e+00,-4.539832279079471511e-01,0.000000000000000000e+00,-9.999999999123873051e-01,0.000000000000000000e+00 +2.065264415521033214e+01,1.155199999999999960e+02,0.000000000000000000e+00,2.674078626404262859e+00,0.000000000000000000e+00,-4.577204625396429361e-01,0.000000000000000000e+00,-9.999999997995466794e-01,0.000000000000000000e+00 +2.065638376103241214e+01,1.155300000000000011e+02,0.000000000000000000e+00,2.672366932297664643e+00,0.000000000000000000e+00,-4.614600683609729193e-01,0.000000000000000000e+00,-9.999999996516792944e-01,0.000000000000000000e+00 +2.066012576213231355e+01,1.155400000000000063e+02,0.000000000000000000e+00,2.670640148214296961e+00,0.000000000000000000e+00,-4.652020694595716543e-01,0.000000000000000000e+00,-9.999999996156941906e-01,0.000000000000000000e+00 +2.066387018273749732e+01,1.155499999999999972e+02,0.000000000000000000e+00,2.668898235999839219e+00,0.000000000000000000e+00,-4.689464900633146804e-01,0.000000000000000000e+00,-9.999999994264422432e-01,0.000000000000000000e+00 +2.066761704721704618e+01,1.155600000000000023e+02,0.000000000000000000e+00,2.667141157053411593e+00,0.000000000000000000e+00,-4.726933545407150938e-01,0.000000000000000000e+00,-9.999999993721094826e-01,0.000000000000000000e+00 +2.067136638008364713e+01,1.155700000000000074e+02,0.000000000000000000e+00,2.665368872323409022e+00,0.000000000000000000e+00,-4.764426874049602079e-01,0.000000000000000000e+00,-9.999999991680077471e-01,0.000000000000000000e+00 +2.067511820599556316e+01,1.155799999999999983e+02,0.000000000000000000e+00,2.663581342303259714e+00,0.000000000000000000e+00,-4.801945133137557331e-01,0.000000000000000000e+00,-9.999999990744523615e-01,0.000000000000000000e+00 +2.067887254975866895e+01,1.155900000000000034e+02,0.000000000000000000e+00,2.661778527027122809e+00,0.000000000000000000e+00,-4.839488570733862516e-01,0.000000000000000000e+00,-9.999999988959858976e-01,0.000000000000000000e+00 +2.068262943632847950e+01,1.156000000000000085e+02,0.000000000000000000e+00,2.659960386065508331e+00,0.000000000000000000e+00,-4.877057436390497824e-01,0.000000000000000000e+00,-9.999999987774714771e-01,0.000000000000000000e+00 +2.068638889081223198e+01,1.156099999999999994e+02,0.000000000000000000e+00,2.658126878520832292e+00,0.000000000000000000e+00,-4.914651981182069918e-01,0.000000000000000000e+00,-9.999999986116349104e-01,0.000000000000000000e+00 +2.069015093847098186e+01,1.156200000000000045e+02,0.000000000000000000e+00,2.656277963022894539e+00,0.000000000000000000e+00,-4.952272457717339926e-01,0.000000000000000000e+00,-9.999999984204253067e-01,0.000000000000000000e+00 +2.069391560472173097e+01,1.156299999999999955e+02,0.000000000000000000e+00,2.654413597724286422e+00,0.000000000000000000e+00,-4.989919120165361988e-01,0.000000000000000000e+00,-9.999999982308931390e-01,0.000000000000000000e+00 +2.069768291513958403e+01,1.156400000000000006e+02,0.000000000000000000e+00,2.652533740295721643e+00,0.000000000000000000e+00,-5.027592224277254163e-01,0.000000000000000000e+00,-9.999999980747927841e-01,0.000000000000000000e+00 +2.070145289545994061e+01,1.156500000000000057e+02,0.000000000000000000e+00,2.650638347921290716e+00,0.000000000000000000e+00,-5.065292027408252462e-01,0.000000000000000000e+00,-9.999999978614959595e-01,0.000000000000000000e+00 +2.070522557158071209e+01,1.156599999999999966e+02,0.000000000000000000e+00,2.648727377293637719e+00,0.000000000000000000e+00,-5.103018788535274020e-01,0.000000000000000000e+00,-9.999999976550388858e-01,0.000000000000000000e+00 +2.070900096956455982e+01,1.156700000000000017e+02,0.000000000000000000e+00,2.646800784609059765e+00,0.000000000000000000e+00,-5.140772768285232219e-01,0.000000000000000000e+00,-9.999999973859690083e-01,0.000000000000000000e+00 +2.071277911564119378e+01,1.156800000000000068e+02,0.000000000000000000e+00,2.644858525562523877e+00,0.000000000000000000e+00,-5.178554228952800820e-01,0.000000000000000000e+00,-9.999999971853851255e-01,0.000000000000000000e+00 +2.071656003620966757e+01,1.156899999999999977e+02,0.000000000000000000e+00,2.642900555342603930e+00,0.000000000000000000e+00,-5.216363434531110510e-01,0.000000000000000000e+00,-9.999999969380334308e-01,0.000000000000000000e+00 +2.072034375784073035e+01,1.157000000000000028e+02,0.000000000000000000e+00,2.640926828626331435e+00,0.000000000000000000e+00,-5.254200650725890931e-01,0.000000000000000000e+00,-9.999999966424341080e-01,0.000000000000000000e+00 +2.072413030727921068e+01,1.157100000000000080e+02,0.000000000000000000e+00,2.638937299573965056e+00,0.000000000000000000e+00,-5.292066144983548215e-01,0.000000000000000000e+00,-9.999999963938706049e-01,0.000000000000000000e+00 +2.072791971144641465e+01,1.157199999999999989e+02,0.000000000000000000e+00,2.636931921823672198e+00,0.000000000000000000e+00,-5.329960186518953869e-01,0.000000000000000000e+00,-9.999999960259690068e-01,0.000000000000000000e+00 +2.073171199744259141e+01,1.157300000000000040e+02,0.000000000000000000e+00,2.634910648486121332e+00,0.000000000000000000e+00,-5.367883046330002017e-01,0.000000000000000000e+00,-9.999999957700576037e-01,0.000000000000000000e+00 +2.073550719254939523e+01,1.157400000000000091e+02,0.000000000000000000e+00,2.632873432138988612e+00,0.000000000000000000e+00,-5.405834997237506379e-01,0.000000000000000000e+00,-9.999999953668781139e-01,0.000000000000000000e+00 +2.073930532423241857e+01,1.157500000000000000e+02,0.000000000000000000e+00,2.630820224821367681e+00,0.000000000000000000e+00,-5.443816313891777225e-01,0.000000000000000000e+00,-9.999999950278136707e-01,0.000000000000000000e+00 +2.074310642014374295e+01,1.157600000000000051e+02,0.000000000000000000e+00,2.628750978028093765e+00,0.000000000000000000e+00,-5.481827272816031105e-01,0.000000000000000000e+00,-9.999999946050613930e-01,0.000000000000000000e+00 +2.074691050812452886e+01,1.157699999999999960e+02,0.000000000000000000e+00,2.626665642703966519e+00,0.000000000000000000e+00,-5.519868152418677676e-01,0.000000000000000000e+00,-9.999999941754815769e-01,0.000000000000000000e+00 +2.075071761620765187e+01,1.157800000000000011e+02,0.000000000000000000e+00,2.624564169237881828e+00,0.000000000000000000e+00,-5.557939233028162951e-01,0.000000000000000000e+00,-9.999999937296725205e-01,0.000000000000000000e+00 +2.075452777262036719e+01,1.157900000000000063e+02,0.000000000000000000e+00,2.622446507456862363e+00,0.000000000000000000e+00,-5.596040796916389448e-01,0.000000000000000000e+00,-9.999999932271034231e-01,0.000000000000000000e+00 +2.075834100578701680e+01,1.157999999999999972e+02,0.000000000000000000e+00,2.620312606619989548e+00,0.000000000000000000e+00,-5.634173128324623248e-01,0.000000000000000000e+00,-9.999999926480744872e-01,0.000000000000000000e+00 +2.076215734433178994e+01,1.158100000000000023e+02,0.000000000000000000e+00,2.618162415412234267e+00,0.000000000000000000e+00,-5.672336513491784693e-01,0.000000000000000000e+00,-9.999999921026502259e-01,0.000000000000000000e+00 +2.076597681708150844e+01,1.158200000000000074e+02,0.000000000000000000e+00,2.615995881938183665e+00,0.000000000000000000e+00,-5.710531240687316545e-01,0.000000000000000000e+00,-9.999999914191588513e-01,0.000000000000000000e+00 +2.076979945306845465e+01,1.158299999999999983e+02,0.000000000000000000e+00,2.613812953715660470e+00,0.000000000000000000e+00,-5.748757600228764364e-01,0.000000000000000000e+00,-9.999999907646945907e-01,0.000000000000000000e+00 +2.077362528153325982e+01,1.158400000000000034e+02,0.000000000000000000e+00,2.611613577669238850e+00,0.000000000000000000e+00,-5.787015884523482034e-01,0.000000000000000000e+00,-9.999999899540230608e-01,0.000000000000000000e+00 +2.077745433192781377e+01,1.158500000000000085e+02,0.000000000000000000e+00,2.609397700123645691e+00,0.000000000000000000e+00,-5.825306388084368070e-01,0.000000000000000000e+00,-9.999999891227495663e-01,0.000000000000000000e+00 +2.078128663391824205e+01,1.158599999999999994e+02,0.000000000000000000e+00,2.607165266797055292e+00,0.000000000000000000e+00,-5.863629407571790964e-01,0.000000000000000000e+00,-9.999999881824058745e-01,0.000000000000000000e+00 +2.078512221738790089e+01,1.158700000000000045e+02,0.000000000000000000e+00,2.604916222794265490e+00,0.000000000000000000e+00,-5.901985241815123073e-01,0.000000000000000000e+00,-9.999999871218584468e-01,0.000000000000000000e+00 +2.078896111244045386e+01,1.158799999999999955e+02,0.000000000000000000e+00,2.602650512599760990e+00,0.000000000000000000e+00,-5.940374191846274909e-01,0.000000000000000000e+00,-9.999999859405596103e-01,0.000000000000000000e+00 +2.079280334940296271e+01,1.158900000000000006e+02,0.000000000000000000e+00,2.600368080070657228e+00,0.000000000000000000e+00,-5.978796560931153303e-01,0.000000000000000000e+00,-9.999999846391089964e-01,0.000000000000000000e+00 +2.079664895882904219e+01,1.159000000000000057e+02,0.000000000000000000e+00,2.598068868429523448e+00,0.000000000000000000e+00,-6.017252654601243922e-01,0.000000000000000000e+00,-9.999999831158304930e-01,0.000000000000000000e+00 +2.080049797150207525e+01,1.159099999999999966e+02,0.000000000000000000e+00,2.595752820257082760e+00,0.000000000000000000e+00,-6.055742780681708792e-01,0.000000000000000000e+00,-9.999999814201833148e-01,0.000000000000000000e+00 +2.080435041843845667e+01,1.159200000000000017e+02,0.000000000000000000e+00,2.593419877484788305e+00,0.000000000000000000e+00,-6.094267249329734515e-01,0.000000000000000000e+00,-9.999999794312837142e-01,0.000000000000000000e+00 +2.080820633089089711e+01,1.159300000000000068e+02,0.000000000000000000e+00,2.591069981387269294e+00,0.000000000000000000e+00,-6.132826373061026626e-01,0.000000000000000000e+00,-9.999999771026557571e-01,0.000000000000000000e+00 +2.081206574035179102e+01,1.159399999999999977e+02,0.000000000000000000e+00,2.588703072574649156e+00,0.000000000000000000e+00,-6.171420466786247117e-01,0.000000000000000000e+00,-9.999999743727369106e-01,0.000000000000000000e+00 +2.081592867855661666e+01,1.159500000000000028e+02,0.000000000000000000e+00,2.586319090984729563e+00,0.000000000000000000e+00,-6.210049847844545390e-01,0.000000000000000000e+00,-9.999999710720188784e-01,0.000000000000000000e+00 +2.081979517748741770e+01,1.159600000000000080e+02,0.000000000000000000e+00,2.583917975875039019e+00,0.000000000000000000e+00,-6.248714836034044984e-01,0.000000000000000000e+00,-9.999999670636966487e-01,0.000000000000000000e+00 +2.082366526937630979e+01,1.159699999999999989e+02,0.000000000000000000e+00,2.581499665814744660e+00,0.000000000000000000e+00,-6.287415753648314398e-01,0.000000000000000000e+00,-9.999999619940294071e-01,0.000000000000000000e+00 +2.082753898670907589e+01,1.159800000000000040e+02,0.000000000000000000e+00,2.579064098676422390e+00,0.000000000000000000e+00,-6.326152925503745195e-01,0.000000000000000000e+00,-9.999999555134735374e-01,0.000000000000000000e+00 +2.083141636222879711e+01,1.159900000000000091e+02,0.000000000000000000e+00,2.576611211627686249e+00,0.000000000000000000e+00,-6.364926678976048358e-01,0.000000000000000000e+00,-9.999999469004295927e-01,0.000000000000000000e+00 +2.083529742893955117e+01,1.160000000000000000e+02,0.000000000000000000e+00,2.574140941122670778e+00,0.000000000000000000e+00,-6.403737344022744082e-01,0.000000000000000000e+00,-9.999999347448409459e-01,0.000000000000000000e+00 +2.083918222011017107e+01,1.160100000000000051e+02,0.000000000000000000e+00,2.571653222893369062e+00,0.000000000000000000e+00,-6.442585253193898742e-01,0.000000000000000000e+00,-9.999999166010270502e-01,0.000000000000000000e+00 +2.084307076927806790e+01,1.160199999999999960e+02,0.000000000000000000e+00,2.569147991940828213e+00,0.000000000000000000e+00,-6.481470741629852261e-01,0.000000000000000000e+00,-9.999998862982861780e-01,0.000000000000000000e+00 +2.084696311025311743e+01,1.160300000000000011e+02,0.000000000000000000e+00,2.566625182526204529e+00,0.000000000000000000e+00,-6.520394146954698877e-01,0.000000000000000000e+00,-9.999998257012444602e-01,0.000000000000000000e+00 +2.085085927712161080e+01,1.160400000000000063e+02,0.000000000000000000e+00,2.564084728161716065e+00,0.000000000000000000e+00,-6.559355808848664759e-01,0.000000000000000000e+00,-9.999996437879156153e-01,0.000000000000000000e+00 +2.085475930425026547e+01,1.160499999999999972e+02,0.000000000000000000e+00,2.561526561601615182e+00,0.000000000000000000e+00,-6.598356066242844209e-01,0.000000000000000000e+00,-4.758162536663134712e-01,0.000000000000000000e+00 +2.085866322629031089e+01,1.160600000000000023e+02,0.000000000000000000e+00,2.558950614834107462e+00,0.000000000000000000e+00,-6.616931561839844989e-01,0.000000000000000000e+00,9.999996486865128098e-01,0.000000000000000000e+00 +2.086257107818164158e+01,1.160700000000000074e+02,0.000000000000000000e+00,2.556364815982233640e+00,0.000000000000000000e+00,-6.577853056655353914e-01,0.000000000000000000e+00,9.999998305158547263e-01,0.000000000000000000e+00 +2.086648288291995001e+01,1.160799999999999983e+02,0.000000000000000000e+00,2.553791688306742635e+00,0.000000000000000000e+00,-6.538735015902175096e-01,0.000000000000000000e+00,9.999998911245128186e-01,0.000000000000000000e+00 +2.087039862908115495e+01,1.160900000000000034e+02,0.000000000000000000e+00,2.551231285652978187e+00,0.000000000000000000e+00,-6.499577558553429890e-01,0.000000000000000000e+00,9.999999214549747384e-01,0.000000000000000000e+00 +2.087431830506515240e+01,1.161000000000000085e+02,0.000000000000000000e+00,2.548683661846738335e+00,0.000000000000000000e+00,-6.460380801792153793e-01,0.000000000000000000e+00,9.999999396122624118e-01,0.000000000000000000e+00 +2.087824189909515837e+01,1.161099999999999994e+02,0.000000000000000000e+00,2.546148870692189536e+00,0.000000000000000000e+00,-6.421144863861446561e-01,0.000000000000000000e+00,9.999999517194992915e-01,0.000000000000000000e+00 +2.088216939921705162e+01,1.161200000000000045e+02,0.000000000000000000e+00,2.543626965968639020e+00,0.000000000000000000e+00,-6.381869864538738391e-01,0.000000000000000000e+00,9.999999603423205263e-01,0.000000000000000000e+00 +2.088610079329872704e+01,1.161299999999999955e+02,0.000000000000000000e+00,2.541118001427091766e+00,0.000000000000000000e+00,-6.342555925281080365e-01,0.000000000000000000e+00,9.999999668662038488e-01,0.000000000000000000e+00 +2.089003606902948107e+01,1.161400000000000006e+02,0.000000000000000000e+00,2.538622030786720440e+00,0.000000000000000000e+00,-6.303203169277439288e-01,0.000000000000000000e+00,9.999999718664728254e-01,0.000000000000000000e+00 +2.089397521391939705e+01,1.161500000000000057e+02,0.000000000000000000e+00,2.536139107731284703e+00,0.000000000000000000e+00,-6.263811721486506334e-01,0.000000000000000000e+00,9.999999759296286372e-01,0.000000000000000000e+00 +2.089791821529874483e+01,1.161599999999999966e+02,0.000000000000000000e+00,2.533669285905505664e+00,0.000000000000000000e+00,-6.224381708642132693e-01,0.000000000000000000e+00,9.999999792085019212e-01,0.000000000000000000e+00 +2.090186506031740166e+01,1.161700000000000017e+02,0.000000000000000000e+00,2.531212618911408363e+00,0.000000000000000000e+00,-6.184913259276172415e-01,0.000000000000000000e+00,9.999999819222116226e-01,0.000000000000000000e+00 +2.090581573594428733e+01,1.161800000000000068e+02,0.000000000000000000e+00,2.528769160304625618e+00,0.000000000000000000e+00,-6.145406503721505542e-01,0.000000000000000000e+00,9.999999842794748961e-01,0.000000000000000000e+00 +2.090977022896681348e+01,1.161899999999999977e+02,0.000000000000000000e+00,2.526338963590671227e+00,0.000000000000000000e+00,-6.105861574117926738e-01,0.000000000000000000e+00,9.999999862620781999e-01,0.000000000000000000e+00 +2.091372852599034005e+01,1.162000000000000028e+02,0.000000000000000000e+00,2.523922082221181640e+00,0.000000000000000000e+00,-6.066278604426449395e-01,0.000000000000000000e+00,9.999999879743949327e-01,0.000000000000000000e+00 +2.091769061343766722e+01,1.162100000000000080e+02,0.000000000000000000e+00,2.521518569590122993e+00,0.000000000000000000e+00,-6.026657730429644255e-01,0.000000000000000000e+00,9.999999894524044253e-01,0.000000000000000000e+00 +2.092165647754852387e+01,1.162199999999999989e+02,0.000000000000000000e+00,2.519128479029969281e+00,0.000000000000000000e+00,-5.986999089739365454e-01,0.000000000000000000e+00,9.999999908119735492e-01,0.000000000000000000e+00 +2.092562610437909143e+01,1.162300000000000040e+02,0.000000000000000000e+00,2.516751863807848988e+00,0.000000000000000000e+00,-5.947302821798436945e-01,0.000000000000000000e+00,9.999999919728246311e-01,0.000000000000000000e+00 +2.092959947980151725e+01,1.162400000000000091e+02,0.000000000000000000e+00,2.514388777121662866e+00,0.000000000000000000e+00,-5.907569067893122527e-01,0.000000000000000000e+00,9.999999930581445762e-01,0.000000000000000000e+00 +2.093357658950348110e+01,1.162500000000000000e+02,0.000000000000000000e+00,2.512039272096168840e+00,0.000000000000000000e+00,-5.867797971149567582e-01,0.000000000000000000e+00,9.999999939213648492e-01,0.000000000000000000e+00 +2.093755741898774758e+01,1.162600000000000051e+02,0.000000000000000000e+00,2.509703401779040721e+00,0.000000000000000000e+00,-5.827989676548865905e-01,0.000000000000000000e+00,9.999999948504861846e-01,0.000000000000000000e+00 +2.094154195357175752e+01,1.162699999999999960e+02,0.000000000000000000e+00,2.507381219136893602e+00,0.000000000000000000e+00,-5.788144330913934654e-01,0.000000000000000000e+00,9.999999956178921012e-01,0.000000000000000000e+00 +2.094553017838722653e+01,1.162800000000000011e+02,0.000000000000000000e+00,2.505072777051287503e+00,0.000000000000000000e+00,-5.748262082934023631e-01,0.000000000000000000e+00,9.999999962950808508e-01,0.000000000000000000e+00 +2.094952207837975777e+01,1.162900000000000063e+02,0.000000000000000000e+00,2.502778128314694595e+00,0.000000000000000000e+00,-5.708343083156612874e-01,0.000000000000000000e+00,9.999999969448833959e-01,0.000000000000000000e+00 +2.095351763830849023e+01,1.162999999999999972e+02,0.000000000000000000e+00,2.500497325626443335e+00,0.000000000000000000e+00,-5.668387483991366160e-01,0.000000000000000000e+00,9.999999975656623796e-01,0.000000000000000000e+00 +2.095751684274575055e+01,1.163100000000000023e+02,0.000000000000000000e+00,2.498230421588635064e+00,0.000000000000000000e+00,-5.628395439716128434e-01,0.000000000000000000e+00,9.999999980642291231e-01,0.000000000000000000e+00 +2.096151967607672972e+01,1.163200000000000074e+02,0.000000000000000000e+00,2.495977468702032631e+00,0.000000000000000000e+00,-5.588367106483826952e-01,0.000000000000000000e+00,9.999999986418063314e-01,0.000000000000000000e+00 +2.096552612249918113e+01,1.163299999999999983e+02,0.000000000000000000e+00,2.493738519361921036e+00,0.000000000000000000e+00,-5.548302642313730493e-01,0.000000000000000000e+00,9.999999990714230069e-01,0.000000000000000000e+00 +2.096953616602313275e+01,1.163400000000000034e+02,0.000000000000000000e+00,2.491513625853946756e+00,0.000000000000000000e+00,-5.508202207111434490e-01,0.000000000000000000e+00,9.999999994977594175e-01,0.000000000000000000e+00 +2.097354979047063139e+01,1.163500000000000085e+02,0.000000000000000000e+00,2.489302840349924661e+00,0.000000000000000000e+00,-5.468065962656619705e-01,0.000000000000000000e+00,9.999999999345123847e-01,0.000000000000000000e+00 +2.097756697947548332e+01,1.163599999999999994e+02,0.000000000000000000e+00,2.487106214903625823e+00,0.000000000000000000e+00,-5.427894072610732756e-01,0.000000000000000000e+00,1.000000000288292501e+00,0.000000000000000000e+00 +2.098158771648304466e+01,1.163700000000000045e+02,0.000000000000000000e+00,2.484923801446538683e+00,0.000000000000000000e+00,-5.387686702523523108e-01,0.000000000000000000e+00,1.000000000655582477e+00,0.000000000000000000e+00 +2.098561198475001532e+01,1.163799999999999955e+02,0.000000000000000000e+00,2.482755651783604467e+00,0.000000000000000000e+00,-5.347444019827439776e-01,0.000000000000000000e+00,1.000000000985743487e+00,0.000000000000000000e+00 +2.098963976734425430e+01,1.163900000000000006e+02,0.000000000000000000e+00,2.480601817588932168e+00,0.000000000000000000e+00,-5.307166193845356261e-01,0.000000000000000000e+00,1.000000001321398102e+00,0.000000000000000000e+00 +2.099367104714461973e+01,1.164000000000000057e+02,0.000000000000000000e+00,2.478462350401488212e+00,0.000000000000000000e+00,-5.266853395788416714e-01,0.000000000000000000e+00,1.000000001571002661e+00,0.000000000000000000e+00 +2.099770580684084109e+01,1.164099999999999966e+02,0.000000000000000000e+00,2.476337301620765263e+00,0.000000000000000000e+00,-5.226505798762824950e-01,0.000000000000000000e+00,1.000000001882455525e+00,0.000000000000000000e+00 +2.100174402893338765e+01,1.164200000000000017e+02,0.000000000000000000e+00,2.474226722502427034e+00,0.000000000000000000e+00,-5.186123577761350134e-01,0.000000000000000000e+00,1.000000002141878896e+00,0.000000000000000000e+00 +2.100578569573338328e+01,1.164300000000000068e+02,0.000000000000000000e+00,2.472130664153935786e+00,0.000000000000000000e+00,-5.145706909674826468e-01,0.000000000000000000e+00,1.000000002399535237e+00,0.000000000000000000e+00 +2.100983078936253534e+01,1.164399999999999977e+02,0.000000000000000000e+00,2.470049177530154960e+00,0.000000000000000000e+00,-5.105255973286244586e-01,0.000000000000000000e+00,1.000000002613555816e+00,0.000000000000000000e+00 +2.101387929175308145e+01,1.164500000000000028e+02,0.000000000000000000e+00,2.467982313428934482e+00,0.000000000000000000e+00,-5.064770949274962630e-01,0.000000000000000000e+00,1.000000002827579282e+00,0.000000000000000000e+00 +2.101793118464777166e+01,1.164600000000000080e+02,0.000000000000000000e+00,2.465930122486675202e+00,0.000000000000000000e+00,-5.024252020213505476e-01,0.000000000000000000e+00,1.000000003076334743e+00,0.000000000000000000e+00 +2.102198644959985074e+01,1.164699999999999989e+02,0.000000000000000000e+00,2.463892655173876012e+00,0.000000000000000000e+00,-4.983699370567946096e-01,0.000000000000000000e+00,1.000000003264035930e+00,0.000000000000000000e+00 +2.102604506797309725e+01,1.164800000000000040e+02,0.000000000000000000e+00,2.461869961790662753e+00,0.000000000000000000e+00,-4.943113186702989270e-01,0.000000000000000000e+00,1.000000003420540740e+00,0.000000000000000000e+00 +2.103010702094185902e+01,1.164900000000000091e+02,0.000000000000000000e+00,2.459862092462297589e+00,0.000000000000000000e+00,-4.902493656876434902e-01,0.000000000000000000e+00,1.000000003657786518e+00,0.000000000000000000e+00 +2.103417228949111717e+01,1.165000000000000000e+02,0.000000000000000000e+00,2.457869097134673719e+00,0.000000000000000000e+00,-4.861840971235151798e-01,0.000000000000000000e+00,1.000000003804651705e+00,0.000000000000000000e+00 +2.103824085441658909e+01,1.165100000000000051e+02,0.000000000000000000e+00,2.455891025569795438e+00,0.000000000000000000e+00,-4.821155321825651985e-01,0.000000000000000000e+00,1.000000003981722951e+00,0.000000000000000000e+00 +2.104231269632483503e+01,1.165199999999999960e+02,0.000000000000000000e+00,2.453927927341238213e+00,0.000000000000000000e+00,-4.780436902581063907e-01,0.000000000000000000e+00,1.000000004100205508e+00,0.000000000000000000e+00 +2.104638779563341089e+01,1.165300000000000011e+02,0.000000000000000000e+00,2.451979851829598989e+00,0.000000000000000000e+00,-4.739685909328231195e-01,0.000000000000000000e+00,1.000000004299151035e+00,0.000000000000000000e+00 +2.105046613257102450e+01,1.165400000000000063e+02,0.000000000000000000e+00,2.450046848217929174e+00,0.000000000000000000e+00,-4.698902539776765308e-01,0.000000000000000000e+00,1.000000004444997259e+00,0.000000000000000000e+00 +2.105454768717773462e+01,1.165499999999999972e+02,0.000000000000000000e+00,2.448128965487158304e+00,0.000000000000000000e+00,-4.658086993528237074e-01,0.000000000000000000e+00,1.000000004540016363e+00,0.000000000000000000e+00 +2.105863243930516759e+01,1.165600000000000023e+02,0.000000000000000000e+00,2.446226252411500823e+00,0.000000000000000000e+00,-4.617239472068475070e-01,0.000000000000000000e+00,1.000000004727233494e+00,0.000000000000000000e+00 +2.106272036861675190e+01,1.165700000000000074e+02,0.000000000000000000e+00,2.444338757553853547e+00,0.000000000000000000e+00,-4.576360178759386055e-01,0.000000000000000000e+00,1.000000004817551247e+00,0.000000000000000000e+00 +2.106681145458799875e+01,1.165799999999999983e+02,0.000000000000000000e+00,2.442466529261184682e+00,0.000000000000000000e+00,-4.535449318849841815e-01,0.000000000000000000e+00,1.000000004959125777e+00,0.000000000000000000e+00 +2.107090567650678281e+01,1.165900000000000034e+02,0.000000000000000000e+00,2.440609615659907305e+00,0.000000000000000000e+00,-4.494507099458953658e-01,0.000000000000000000e+00,1.000000005057053221e+00,0.000000000000000000e+00 +2.107500301347367611e+01,1.166000000000000085e+02,0.000000000000000000e+00,2.438768064651249290e+00,0.000000000000000000e+00,-4.453533729582810352e-01,0.000000000000000000e+00,1.000000005201179043e+00,0.000000000000000000e+00 +2.107910344440228556e+01,1.166099999999999994e+02,0.000000000000000000e+00,2.436941923906610796e+00,0.000000000000000000e+00,-4.412529420083449172e-01,0.000000000000000000e+00,1.000000005298001149e+00,0.000000000000000000e+00 +2.108320694801962603e+01,1.166200000000000045e+02,0.000000000000000000e+00,2.435131240862917323e+00,0.000000000000000000e+00,-4.371494383692638430e-01,0.000000000000000000e+00,1.000000005363948841e+00,0.000000000000000000e+00 +2.108731350286652528e+01,1.166299999999999955e+02,0.000000000000000000e+00,2.433336062717962989e+00,0.000000000000000000e+00,-4.330428835003378163e-01,0.000000000000000000e+00,1.000000005525673030e+00,0.000000000000000000e+00 +2.109142308729804327e+01,1.166400000000000006e+02,0.000000000000000000e+00,2.431556436425749812e+00,0.000000000000000000e+00,-4.289332990461103834e-01,0.000000000000000000e+00,1.000000005599872122e+00,0.000000000000000000e+00 +2.109553567948393393e+01,1.166500000000000057e+02,0.000000000000000000e+00,2.429792408691823891e+00,0.000000000000000000e+00,-4.248207068371883666e-01,0.000000000000000000e+00,1.000000005698759242e+00,0.000000000000000000e+00 +2.109965125740912129e+01,1.166599999999999966e+02,0.000000000000000000e+00,2.428044025968602249e+00,0.000000000000000000e+00,-4.207051288885472751e-01,0.000000000000000000e+00,1.000000005782035073e+00,0.000000000000000000e+00 +2.110376979887420390e+01,1.166700000000000017e+02,0.000000000000000000e+00,2.426311334450701462e+00,0.000000000000000000e+00,-4.165865873996502100e-01,0.000000000000000000e+00,1.000000005866226838e+00,0.000000000000000000e+00 +2.110789128149599847e+01,1.166800000000000068e+02,0.000000000000000000e+00,2.424594380070261401e+00,0.000000000000000000e+00,-4.124651047536788129e-01,0.000000000000000000e+00,1.000000005943852077e+00,0.000000000000000000e+00 +2.111201568270809403e+01,1.166899999999999977e+02,0.000000000000000000e+00,2.422893208492268524e+00,0.000000000000000000e+00,-4.083407035170691923e-01,0.000000000000000000e+00,1.000000006059693636e+00,0.000000000000000000e+00 +2.111614297976144883e+01,1.167000000000000028e+02,0.000000000000000000e+00,2.421207865109878288e+00,0.000000000000000000e+00,-4.042134064387056802e-01,0.000000000000000000e+00,1.000000006099230232e+00,0.000000000000000000e+00 +2.112027314972500491e+01,1.167100000000000080e+02,0.000000000000000000e+00,2.419538395039738887e+00,0.000000000000000000e+00,-4.000832364499598004e-01,0.000000000000000000e+00,1.000000006202120373e+00,0.000000000000000000e+00 +2.112440616948633831e+01,1.167199999999999989e+02,0.000000000000000000e+00,2.417884843117313665e+00,0.000000000000000000e+00,-3.959502166629946251e-01,0.000000000000000000e+00,1.000000006263306318e+00,0.000000000000000000e+00 +2.112854201575232693e+01,1.167300000000000040e+02,0.000000000000000000e+00,2.416247253892210178e+00,0.000000000000000000e+00,-3.918143703711007841e-01,0.000000000000000000e+00,1.000000006370832750e+00,0.000000000000000000e+00 +2.113268066504986464e+01,1.167400000000000091e+02,0.000000000000000000e+00,2.414625671623508385e+00,0.000000000000000000e+00,-3.876757210471957760e-01,0.000000000000000000e+00,1.000000006385429741e+00,0.000000000000000000e+00 +2.113682209372658249e+01,1.167500000000000000e+02,0.000000000000000000e+00,2.413020140275096370e+00,0.000000000000000000e+00,-3.835342923440334117e-01,0.000000000000000000e+00,1.000000006479574433e+00,0.000000000000000000e+00 +2.114096627795160899e+01,1.167600000000000051e+02,0.000000000000000000e+00,2.411430703511007412e+00,0.000000000000000000e+00,-3.793901080921540658e-01,0.000000000000000000e+00,1.000000006535246788e+00,0.000000000000000000e+00 +2.114511319371636233e+01,1.167699999999999960e+02,0.000000000000000000e+00,2.409857404690768590e+00,0.000000000000000000e+00,-3.752431923002996217e-01,0.000000000000000000e+00,1.000000006604174319e+00,0.000000000000000000e+00 +2.114926281683536402e+01,1.167800000000000011e+02,0.000000000000000000e+00,2.408300286864751616e+00,0.000000000000000000e+00,-3.710935691538940207e-01,0.000000000000000000e+00,1.000000006693596788e+00,0.000000000000000000e+00 +2.115341512294708082e+01,1.167900000000000063e+02,0.000000000000000000e+00,2.406759392769534767e+00,0.000000000000000000e+00,-3.669412630143824572e-01,0.000000000000000000e+00,1.000000006708022138e+00,0.000000000000000000e+00 +2.115757008751480583e+01,1.167999999999999972e+02,0.000000000000000000e+00,2.405234764823273252e+00,0.000000000000000000e+00,-3.627862984187845141e-01,0.000000000000000000e+00,1.000000006802044705e+00,0.000000000000000000e+00 +2.116172768582755737e+01,1.168100000000000023e+02,0.000000000000000000e+00,2.403726445121078026e+00,0.000000000000000000e+00,-3.586287000777530487e-01,0.000000000000000000e+00,1.000000006831966326e+00,0.000000000000000000e+00 +2.116588789300100615e+01,1.168200000000000074e+02,0.000000000000000000e+00,2.402234475430410132e+00,0.000000000000000000e+00,-3.544684928758823905e-01,0.000000000000000000e+00,1.000000006887601822e+00,0.000000000000000000e+00 +2.117005068397843814e+01,1.168299999999999983e+02,0.000000000000000000e+00,2.400758897186482166e+00,0.000000000000000000e+00,-3.503057018697778302e-01,0.000000000000000000e+00,1.000000006975097833e+00,0.000000000000000000e+00 +2.117421603353174930e+01,1.168400000000000034e+02,0.000000000000000000e+00,2.399299751487677046e+00,0.000000000000000000e+00,-3.461403522874144101e-01,0.000000000000000000e+00,1.000000006983166267e+00,0.000000000000000000e+00 +2.117838391626245098e+01,1.168500000000000085e+02,0.000000000000000000e+00,2.397857079090979671e+00,0.000000000000000000e+00,-3.419724695276086801e-01,0.000000000000000000e+00,1.000000007057467055e+00,0.000000000000000000e+00 +2.118255430660272509e+01,1.168599999999999994e+02,0.000000000000000000e+00,2.396430920407421894e+00,0.000000000000000000e+00,-3.378020791579017246e-01,0.000000000000000000e+00,1.000000007105301458e+00,0.000000000000000000e+00 +2.118672717881650058e+01,1.168700000000000045e+02,0.000000000000000000e+00,2.395021315497548375e+00,0.000000000000000000e+00,-3.336292069144769501e-01,0.000000000000000000e+00,1.000000007143878600e+00,0.000000000000000000e+00 +2.119090250700055122e+01,1.168799999999999955e+02,0.000000000000000000e+00,2.393628304066895751e+00,0.000000000000000000e+00,-3.294538787005978353e-01,0.000000000000000000e+00,1.000000007213729614e+00,0.000000000000000000e+00 +2.119508026508563603e+01,1.168900000000000006e+02,0.000000000000000000e+00,2.392251925461492235e+00,0.000000000000000000e+00,-3.252761205853771931e-01,0.000000000000000000e+00,1.000000007215879450e+00,0.000000000000000000e+00 +2.119926042683765033e+01,1.169000000000000057e+02,0.000000000000000000e+00,2.390892218663377200e+00,0.000000000000000000e+00,-3.210959588031979672e-01,0.000000000000000000e+00,1.000000007308764260e+00,0.000000000000000000e+00 +2.120344296585883370e+01,1.169099999999999966e+02,0.000000000000000000e+00,2.389549222286138974e+00,0.000000000000000000e+00,-3.169134197514467677e-01,0.000000000000000000e+00,1.000000007313240236e+00,0.000000000000000000e+00 +2.120762785558897079e+01,1.169200000000000017e+02,0.000000000000000000e+00,2.388222974570478829e+00,0.000000000000000000e+00,-3.127285299907055505e-01,0.000000000000000000e+00,1.000000007362603860e+00,0.000000000000000000e+00 +2.121181506930665250e+01,1.169300000000000068e+02,0.000000000000000000e+00,2.386913513379791851e+00,0.000000000000000000e+00,-3.085413162421967725e-01,0.000000000000000000e+00,1.000000007409638458e+00,0.000000000000000000e+00 +2.121600458013054435e+01,1.169399999999999977e+02,0.000000000000000000e+00,2.385620876195777118e+00,0.000000000000000000e+00,-3.043518053872614759e-01,0.000000000000000000e+00,1.000000007469718399e+00,0.000000000000000000e+00 +2.122019636102070095e+01,1.169500000000000028e+02,0.000000000000000000e+00,2.384345100114069638e+00,0.000000000000000000e+00,-3.001600244657918193e-01,0.000000000000000000e+00,1.000000007483770270e+00,0.000000000000000000e+00 +2.122439038477989826e+01,1.169600000000000080e+02,0.000000000000000000e+00,2.383086221839899377e+00,0.000000000000000000e+00,-2.959660006752091177e-01,0.000000000000000000e+00,1.000000007509555200e+00,0.000000000000000000e+00 +2.122858662405498364e+01,1.169699999999999989e+02,0.000000000000000000e+00,2.381844277683776046e+00,0.000000000000000000e+00,-2.917697613686116020e-01,0.000000000000000000e+00,1.000000007584705752e+00,0.000000000000000000e+00 +2.123278505133828276e+01,1.169800000000000040e+02,0.000000000000000000e+00,2.380619303557204081e+00,0.000000000000000000e+00,-2.875713340534675755e-01,0.000000000000000000e+00,1.000000007590258866e+00,0.000000000000000000e+00 +2.123698563896901348e+01,1.169900000000000091e+02,0.000000000000000000e+00,2.379411334968426495e+00,0.000000000000000000e+00,-2.833707463908538005e-01,0.000000000000000000e+00,1.000000007643150557e+00,0.000000000000000000e+00 +2.124118835913472836e+01,1.170000000000000000e+02,0.000000000000000000e+00,2.378220407018196259e+00,0.000000000000000000e+00,-2.791680261930178930e-01,0.000000000000000000e+00,1.000000007657721568e+00,0.000000000000000000e+00 +2.124539318387279252e+01,1.170100000000000051e+02,0.000000000000000000e+00,2.377046554395583211e+00,0.000000000000000000e+00,-2.749632014227539889e-01,0.000000000000000000e+00,1.000000007687571246e+00,0.000000000000000000e+00 +2.124960008507189002e+01,1.170199999999999960e+02,0.000000000000000000e+00,2.375889811373809835e+00,0.000000000000000000e+00,-2.707563001913145251e-01,0.000000000000000000e+00,1.000000007764209498e+00,0.000000000000000000e+00 +2.125380903447355507e+01,1.170300000000000011e+02,0.000000000000000000e+00,2.374750211806123001e+00,0.000000000000000000e+00,-2.665473507569719458e-01,0.000000000000000000e+00,1.000000007761992826e+00,0.000000000000000000e+00 +2.125802000367372102e+01,1.170400000000000063e+02,0.000000000000000000e+00,2.373627789121699916e+00,0.000000000000000000e+00,-2.623363815241218089e-01,0.000000000000000000e+00,1.000000007789256351e+00,0.000000000000000000e+00 +2.126223296412431552e+01,1.170499999999999972e+02,0.000000000000000000e+00,2.372522576321586918e+00,0.000000000000000000e+00,-2.581234210407122309e-01,0.000000000000000000e+00,1.000000007827581028e+00,0.000000000000000000e+00 +2.126644788713486989e+01,1.170600000000000023e+02,0.000000000000000000e+00,2.371434605974679144e+00,0.000000000000000000e+00,-2.539084979971641953e-01,0.000000000000000000e+00,1.000000007847842376e+00,0.000000000000000000e+00 +2.127066474387416406e+01,1.170700000000000074e+02,0.000000000000000000e+00,2.370363910213735714e+00,0.000000000000000000e+00,-2.496916412247766892e-01,0.000000000000000000e+00,1.000000007900816890e+00,0.000000000000000000e+00 +2.127488350537188566e+01,1.170799999999999983e+02,0.000000000000000000e+00,2.369310520731433556e+00,0.000000000000000000e+00,-2.454728796937228064e-01,0.000000000000000000e+00,1.000000007933517177e+00,0.000000000000000000e+00 +2.127910414252033178e+01,1.170900000000000034e+02,0.000000000000000000e+00,2.368274468776462527e+00,0.000000000000000000e+00,-2.412522425117935854e-01,0.000000000000000000e+00,1.000000007905658572e+00,0.000000000000000000e+00 +2.128332662607611780e+01,1.171000000000000085e+02,0.000000000000000000e+00,2.367255785149659619e+00,0.000000000000000000e+00,-2.370297589226245671e-01,0.000000000000000000e+00,1.000000008005156538e+00,0.000000000000000000e+00 +2.128755092666193960e+01,1.171099999999999994e+02,0.000000000000000000e+00,2.366254500200185351e+00,0.000000000000000000e+00,-2.328054583029856295e-01,0.000000000000000000e+00,1.000000007992929207e+00,0.000000000000000000e+00 +2.129177701476833562e+01,1.171200000000000045e+02,0.000000000000000000e+00,2.365270643821747232e+00,0.000000000000000000e+00,-2.285793701628116570e-01,0.000000000000000000e+00,1.000000007992233542e+00,0.000000000000000000e+00 +2.129600486075548460e+01,1.171299999999999955e+02,0.000000000000000000e+00,2.364304245448859643e+00,0.000000000000000000e+00,-2.243515241418740369e-01,0.000000000000000000e+00,1.000000008082833070e+00,0.000000000000000000e+00 +2.130023443485503165e+01,1.171400000000000006e+02,0.000000000000000000e+00,2.363355334053155232e+00,0.000000000000000000e+00,-2.201219500081398883e-01,0.000000000000000000e+00,1.000000008071320945e+00,0.000000000000000000e+00 +2.130446570717194277e+01,1.171500000000000057e+02,0.000000000000000000e+00,2.362423938139741608e+00,0.000000000000000000e+00,-2.158906776570782282e-01,0.000000000000000000e+00,1.000000008081032510e+00,0.000000000000000000e+00 +2.130869864768636646e+01,1.171599999999999966e+02,0.000000000000000000e+00,2.361510085743600218e+00,0.000000000000000000e+00,-2.116577371084463477e-01,0.000000000000000000e+00,1.000000008148655306e+00,0.000000000000000000e+00 +2.131293322625554865e+01,1.171700000000000017e+02,0.000000000000000000e+00,2.360613804426038964e+00,0.000000000000000000e+00,-2.074231585047569548e-01,0.000000000000000000e+00,1.000000008120586870e+00,0.000000000000000000e+00 +2.131716941261574405e+01,1.171800000000000068e+02,0.000000000000000000e+00,2.359735121271192337e+00,0.000000000000000000e+00,-2.031869721101606241e-01,0.000000000000000000e+00,1.000000008193087542e+00,0.000000000000000000e+00 +2.132140717638416660e+01,1.171899999999999977e+02,0.000000000000000000e+00,2.358874062882568179e+00,0.000000000000000000e+00,-1.989492083070165396e-01,0.000000000000000000e+00,1.000000008190203848e+00,0.000000000000000000e+00 +2.132564648706096477e+01,1.172000000000000028e+02,0.000000000000000000e+00,2.358030655379651730e+00,0.000000000000000000e+00,-1.947098975954976996e-01,0.000000000000000000e+00,1.000000008203879798e+00,0.000000000000000000e+00 +2.132988731403121108e+01,1.172100000000000080e+02,0.000000000000000000e+00,2.357204924394554979e+00,0.000000000000000000e+00,-1.904690705904608372e-01,0.000000000000000000e+00,1.000000008244568361e+00,0.000000000000000000e+00 +2.133412962656692358e+01,1.172199999999999989e+02,0.000000000000000000e+00,2.356396895068723740e+00,0.000000000000000000e+00,-1.862267580197732586e-01,0.000000000000000000e+00,1.000000008239467553e+00,0.000000000000000000e+00 +2.133837339382910514e+01,1.172300000000000040e+02,0.000000000000000000e+00,2.355606592049697134e+00,0.000000000000000000e+00,-1.819829907226248600e-01,0.000000000000000000e+00,1.000000008302217136e+00,0.000000000000000000e+00 +2.134261858486981112e+01,1.172400000000000091e+02,0.000000000000000000e+00,2.354834039487920361e+00,0.000000000000000000e+00,-1.777377996466732446e-01,0.000000000000000000e+00,1.000000008288386200e+00,0.000000000000000000e+00 +2.134686516863423478e+01,1.172500000000000000e+02,0.000000000000000000e+00,2.354079261033616532e+00,0.000000000000000000e+00,-1.734912158470529320e-01,0.000000000000000000e+00,1.000000008312879940e+00,0.000000000000000000e+00 +2.135111311396280698e+01,1.172600000000000051e+02,0.000000000000000000e+00,2.353342279833710471e+00,0.000000000000000000e+00,-1.692432704831665635e-01,0.000000000000000000e+00,1.000000008356276116e+00,0.000000000000000000e+00 +2.135536238959333843e+01,1.172699999999999960e+02,0.000000000000000000e+00,2.352623118528814672e+00,0.000000000000000000e+00,-1.649939948171255943e-01,0.000000000000000000e+00,1.000000008340459878e+00,0.000000000000000000e+00 +2.135961296416316202e+01,1.172800000000000011e+02,0.000000000000000000e+00,2.351921799250271228e+00,0.000000000000000000e+00,-1.607434202118492583e-01,0.000000000000000000e+00,1.000000008376576766e+00,0.000000000000000000e+00 +2.136386480621130701e+01,1.172900000000000063e+02,0.000000000000000000e+00,2.351238343617251925e+00,0.000000000000000000e+00,-1.564915781280888651e-01,0.000000000000000000e+00,1.000000008399254847e+00,0.000000000000000000e+00 +2.136811788418068758e+01,1.172999999999999972e+02,0.000000000000000000e+00,2.350572772733921845e+00,0.000000000000000000e+00,-1.522385001229862034e-01,0.000000000000000000e+00,1.000000008416321640e+00,0.000000000000000000e+00 +2.137237216642031612e+01,1.173100000000000023e+02,0.000000000000000000e+00,2.349925107186660700e+00,0.000000000000000000e+00,-1.479842178475506975e-01,0.000000000000000000e+00,1.000000008439771104e+00,0.000000000000000000e+00 +2.137662762118754145e+01,1.173200000000000074e+02,0.000000000000000000e+00,2.349295367041347227e+00,0.000000000000000000e+00,-1.437287630444102904e-01,0.000000000000000000e+00,1.000000008442238242e+00,0.000000000000000000e+00 +2.138088421665028704e+01,1.173299999999999983e+02,0.000000000000000000e+00,2.348683571840706197e+00,0.000000000000000000e+00,-1.394721675457284149e-01,0.000000000000000000e+00,1.000000008461655598e+00,0.000000000000000000e+00 +2.138514192088933186e+01,1.173400000000000034e+02,0.000000000000000000e+00,2.348089740601718045e+00,0.000000000000000000e+00,-1.352144632706568372e-01,0.000000000000000000e+00,1.000000008485989467e+00,0.000000000000000000e+00 +2.138940070190058762e+01,1.173500000000000085e+02,0.000000000000000000e+00,2.347513891813093778e+00,0.000000000000000000e+00,-1.309556822232607054e-01,0.000000000000000000e+00,1.000000008486270575e+00,0.000000000000000000e+00 +2.139366052759741166e+01,1.173599999999999994e+02,0.000000000000000000e+00,2.346956043432813832e+00,0.000000000000000000e+00,-1.266958564902852802e-01,0.000000000000000000e+00,1.000000008523691974e+00,0.000000000000000000e+00 +2.139792136581293036e+01,1.173700000000000045e+02,0.000000000000000000e+00,2.346416212885732211e+00,0.000000000000000000e+00,-1.224350182384489755e-01,0.000000000000000000e+00,1.000000008539738472e+00,0.000000000000000000e+00 +2.140218318430236977e+01,1.173799999999999955e+02,0.000000000000000000e+00,2.345894417061248571e+00,0.000000000000000000e+00,-1.181731997126133915e-01,0.000000000000000000e+00,1.000000008538779905e+00,0.000000000000000000e+00 +2.140644595074542522e+01,1.173900000000000006e+02,0.000000000000000000e+00,2.345390672311045144e+00,0.000000000000000000e+00,-1.139104332331590391e-01,0.000000000000000000e+00,1.000000008575842259e+00,0.000000000000000000e+00 +2.141070963274862393e+01,1.174000000000000057e+02,0.000000000000000000e+00,2.344904994446892488e+00,0.000000000000000000e+00,-1.096467511933968270e-01,0.000000000000000000e+00,1.000000008574481569e+00,0.000000000000000000e+00 +2.141497419784771239e+01,1.174099999999999966e+02,0.000000000000000000e+00,2.344437398738524525e+00,0.000000000000000000e+00,-1.053821860577404124e-01,0.000000000000000000e+00,1.000000008585629097e+00,0.000000000000000000e+00 +2.141923961351007222e+01,1.174200000000000017e+02,0.000000000000000000e+00,2.343987899911580186e+00,0.000000000000000000e+00,-1.011167703587599193e-01,0.000000000000000000e+00,1.000000008607601742e+00,0.000000000000000000e+00 +2.142350584713712180e+01,1.174300000000000068e+02,0.000000000000000000e+00,2.343556512145616999e+00,0.000000000000000000e+00,-9.685053669498834561e-02,0.000000000000000000e+00,1.000000008627171866e+00,0.000000000000000000e+00 +2.142777286606676057e+01,1.174399999999999977e+02,0.000000000000000000e+00,2.343143249072193957e+00,0.000000000000000000e+00,-9.258351772853878892e-02,0.000000000000000000e+00,1.000000008637355053e+00,0.000000000000000000e+00 +2.143204063757580613e+01,1.174500000000000028e+02,0.000000000000000000e+00,2.342748123773024993e+00,0.000000000000000000e+00,-8.831574618263214604e-02,0.000000000000000000e+00,1.000000008631829918e+00,0.000000000000000000e+00 +2.143630912888245632e+01,1.174600000000000080e+02,0.000000000000000000e+00,2.342371148778203960e+00,0.000000000000000000e+00,-8.404725483913544348e-02,0.000000000000000000e+00,1.000000008673633811e+00,0.000000000000000000e+00 +2.144057830714876900e+01,1.174699999999999989e+02,0.000000000000000000e+00,2.342012336064501543e+00,0.000000000000000000e+00,-7.977807653579423175e-02,0.000000000000000000e+00,1.000000008697004450e+00,0.000000000000000000e+00 +2.144484813948313118e+01,1.174800000000000040e+02,0.000000000000000000e+00,2.341671697053735901e+00,0.000000000000000000e+00,-7.550824416429871566e-02,0.000000000000000000e+00,1.000000008675986818e+00,0.000000000000000000e+00 +2.144911859294276013e+01,1.174900000000000091e+02,0.000000000000000000e+00,2.341349242611213910e+00,0.000000000000000000e+00,-7.123779066761865009e-02,0.000000000000000000e+00,1.000000008696557252e+00,0.000000000000000000e+00 +2.145338963453621517e+01,1.175000000000000000e+02,0.000000000000000000e+00,2.341044983044246575e+00,0.000000000000000000e+00,-6.696674903701894943e-02,0.000000000000000000e+00,1.000000008713480160e+00,0.000000000000000000e+00 +2.145766123122590940e+01,1.175100000000000051e+02,0.000000000000000000e+00,2.340758928100740377e+00,0.000000000000000000e+00,-6.269515231010300282e-02,0.000000000000000000e+00,1.000000008746679159e+00,0.000000000000000000e+00 +2.146193334993063928e+01,1.175199999999999960e+02,0.000000000000000000e+00,2.340491086967860568e+00,0.000000000000000000e+00,-5.842303356800739728e-02,0.000000000000000000e+00,1.000000008738094248e+00,0.000000000000000000e+00 +2.146620595752811411e+01,1.175300000000000011e+02,0.000000000000000000e+00,2.340241468270770397e+00,0.000000000000000000e+00,-5.415042593319854825e-02,0.000000000000000000e+00,1.000000008750349778e+00,0.000000000000000000e+00 +2.147047902085751048e+01,1.175400000000000063e+02,0.000000000000000000e+00,2.340010080071444065e+00,0.000000000000000000e+00,-4.987736256641161353e-02,0.000000000000000000e+00,1.000000008753117786e+00,0.000000000000000000e+00 +2.147475250672202307e+01,1.175499999999999972e+02,0.000000000000000000e+00,2.339796929867557385e+00,0.000000000000000000e+00,-4.560387666449367688e-02,0.000000000000000000e+00,1.000000008775659532e+00,0.000000000000000000e+00 +2.147902638189142266e+01,1.175600000000000023e+02,0.000000000000000000e+00,2.339602024591452611e+00,0.000000000000000000e+00,-4.133000145758730648e-02,0.000000000000000000e+00,1.000000008817431674e+00,0.000000000000000000e+00 +2.148330061310463179e+01,1.175700000000000074e+02,0.000000000000000000e+00,2.339425370609180543e+00,0.000000000000000000e+00,-3.705577020668875121e-02,0.000000000000000000e+00,1.000000008784312167e+00,0.000000000000000000e+00 +2.148757516707230053e+01,1.175799999999999983e+02,0.000000000000000000e+00,2.339266973719618559e+00,0.000000000000000000e+00,-3.278121620147201459e-02,0.000000000000000000e+00,1.000000008790747241e+00,0.000000000000000000e+00 +2.149185001047937860e+01,1.175900000000000034e+02,0.000000000000000000e+00,2.339126839153663706e+00,0.000000000000000000e+00,-2.850637275681520977e-02,0.000000000000000000e+00,1.000000008855434608e+00,0.000000000000000000e+00 +2.149612510998771242e+01,1.176000000000000085e+02,0.000000000000000000e+00,2.339004971573506619e+00,0.000000000000000000e+00,-2.423127321062193071e-02,0.000000000000000000e+00,1.000000008817289121e+00,0.000000000000000000e+00 +2.150040043223864217e+01,1.176099999999999994e+02,0.000000000000000000e+00,2.338901375071980926e+00,0.000000000000000000e+00,-1.995595092199693374e-02,0.000000000000000000e+00,1.000000008835738141e+00,0.000000000000000000e+00 +2.150467594385558456e+01,1.176200000000000045e+02,0.000000000000000000e+00,2.338816053171986820e+00,0.000000000000000000e+00,-1.568043926727843290e-02,0.000000000000000000e+00,1.000000008871827717e+00,0.000000000000000000e+00 +2.150895161144664414e+01,1.176299999999999955e+02,0.000000000000000000e+00,2.338749008825998121e+00,0.000000000000000000e+00,-1.140477163828472994e-02,0.000000000000000000e+00,1.000000008851062772e+00,0.000000000000000000e+00 +2.151322740160722091e+01,1.176400000000000006e+02,0.000000000000000000e+00,2.338700244415643503e+00,0.000000000000000000e+00,-7.128981439861336970e-03,0.000000000000000000e+00,1.000000008876036794e+00,0.000000000000000000e+00 +2.151750328092261455e+01,1.176500000000000057e+02,0.000000000000000000e+00,2.338669761751364984e+00,0.000000000000000000e+00,-2.853102086516074408e-03,0.000000000000000000e+00,1.000000008881729574e+00,0.000000000000000000e+00 +2.152177921597062848e+01,1.176599999999999966e+02,0.000000000000000000e+00,2.338657562072157692e+00,0.000000000000000000e+00,1.422832999474251152e-03,0.000000000000000000e+00,1.000000008899407211e+00,0.000000000000000000e+00 +2.152605517332418827e+01,1.176700000000000017e+02,0.000000000000000000e+00,2.338663646045384681e+00,0.000000000000000000e+00,5.698790391087247241e-03,0.000000000000000000e+00,1.000000008908922267e+00,0.000000000000000000e+00 +2.153033111955395640e+01,1.176800000000000068e+02,0.000000000000000000e+00,2.338688013766671681e+00,0.000000000000000000e+00,9.974736658947932350e-03,0.000000000000000000e+00,1.000000008910957972e+00,0.000000000000000000e+00 +2.153460702123093640e+01,1.176899999999999977e+02,0.000000000000000000e+00,2.338730664759879119e+00,0.000000000000000000e+00,1.425063837403119441e-02,0.000000000000000000e+00,1.000000008927743878e+00,0.000000000000000000e+00 +2.153888284492909833e+01,1.177000000000000028e+02,0.000000000000000000e+00,2.338791597977152747e+00,0.000000000000000000e+00,1.852646211036731300e-02,0.000000000000000000e+00,1.000000008932234952e+00,0.000000000000000000e+00 +2.154315855722798290e+01,1.177100000000000080e+02,0.000000000000000000e+00,2.338870811799052873e+00,0.000000000000000000e+00,2.280217444744405894e-02,0.000000000000000000e+00,1.000000008948672248e+00,0.000000000000000000e+00 +2.154743412471531627e+01,1.177199999999999989e+02,0.000000000000000000e+00,2.338968304034760859e+00,0.000000000000000000e+00,2.707774197303763897e-02,0.000000000000000000e+00,1.000000008935832074e+00,0.000000000000000000e+00 +2.155170951398961776e+01,1.177300000000000040e+02,0.000000000000000000e+00,2.339084071922364672e+00,0.000000000000000000e+00,3.135313128554270690e-02,0.000000000000000000e+00,1.000000008963147557e+00,0.000000000000000000e+00 +2.155598469166280751e+01,1.177400000000000091e+02,0.000000000000000000e+00,2.339218112129221261e+00,0.000000000000000000e+00,3.562830899705310417e-02,0.000000000000000000e+00,1.000000008975147736e+00,0.000000000000000000e+00 +2.156025962436281773e+01,1.177500000000000000e+02,0.000000000000000000e+00,2.339370420752398871e+00,0.000000000000000000e+00,3.990324173543259578e-02,0.000000000000000000e+00,1.000000008970232779e+00,0.000000000000000000e+00 +2.156453427873618622e+01,1.177600000000000051e+02,0.000000000000000000e+00,2.339540993319194850e+00,0.000000000000000000e+00,4.417789614714653229e-02,0.000000000000000000e+00,1.000000008986401401e+00,0.000000000000000000e+00 +2.156880862145065691e+01,1.177699999999999960e+02,0.000000000000000000e+00,2.339729824787732060e+00,0.000000000000000000e+00,4.845223890002842843e-02,0.000000000000000000e+00,1.000000009015445945e+00,0.000000000000000000e+00 +2.157308261919777337e+01,1.177800000000000011e+02,0.000000000000000000e+00,2.339936909547633448e+00,0.000000000000000000e+00,5.272623668567519295e-02,0.000000000000000000e+00,1.000000008966887233e+00,0.000000000000000000e+00 +2.157735623869546160e+01,1.177900000000000063e+02,0.000000000000000000e+00,2.340162241420773004e+00,0.000000000000000000e+00,5.699985622168315946e-02,0.000000000000000000e+00,1.000000009046721372e+00,0.000000000000000000e+00 +2.158162944669061645e+01,1.177999999999999972e+02,0.000000000000000000e+00,2.340405813662102208e+00,0.000000000000000000e+00,6.127306425549707003e-02,0.000000000000000000e+00,1.000000008994538669e+00,0.000000000000000000e+00 +2.158590220996168085e+01,1.178100000000000023e+02,0.000000000000000000e+00,2.340667618960558638e+00,0.000000000000000000e+00,6.554582756499256757e-02,0.000000000000000000e+00,1.000000009024156977e+00,0.000000000000000000e+00 +2.159017449532120736e+01,1.178200000000000074e+02,0.000000000000000000e+00,2.340947649440042522e+00,0.000000000000000000e+00,6.981811296307158243e-02,0.000000000000000000e+00,1.000000009038919391e+00,0.000000000000000000e+00 +2.159444626961841962e+01,1.178299999999999983e+02,0.000000000000000000e+00,2.341245896660478110e+00,0.000000000000000000e+00,7.408988729889716407e-02,0.000000000000000000e+00,1.000000009064239137e+00,0.000000000000000000e+00 +2.159871749974177391e+01,1.178400000000000034e+02,0.000000000000000000e+00,2.341562351618945215e+00,0.000000000000000000e+00,7.836111746096867392e-02,0.000000000000000000e+00,1.000000009024627934e+00,0.000000000000000000e+00 +2.160298815262149930e+01,1.178500000000000085e+02,0.000000000000000000e+00,2.341897004750888467e+00,0.000000000000000000e+00,8.263177037923596924e-02,0.000000000000000000e+00,1.000000009057476991e+00,0.000000000000000000e+00 +2.160725819523213076e+01,1.178599999999999994e+02,0.000000000000000000e+00,2.342249845931399843e+00,0.000000000000000000e+00,8.690181302854474432e-02,0.000000000000000000e+00,1.000000009073366725e+00,0.000000000000000000e+00 +2.161152759459504225e+01,1.178700000000000045e+02,0.000000000000000000e+00,2.342620864476579801e+00,0.000000000000000000e+00,9.117121243019446486e-02,0.000000000000000000e+00,1.000000009072200102e+00,0.000000000000000000e+00 +2.161579631778095845e+01,1.178799999999999955e+02,0.000000000000000000e+00,2.343010049144968576e+00,0.000000000000000000e+00,9.543993565483642472e-02,0.000000000000000000e+00,1.000000009095622255e+00,0.000000000000000000e+00 +2.162006433191245947e+01,1.178900000000000006e+02,0.000000000000000000e+00,2.343417388139052981e+00,0.000000000000000000e+00,9.970794982515784888e-02,0.000000000000000000e+00,1.000000009058428230e+00,0.000000000000000000e+00 +2.162433160416648192e+01,1.179000000000000057e+02,0.000000000000000000e+00,2.343842869106847360e+00,0.000000000000000000e+00,1.039752221178352753e-01,0.000000000000000000e+00,1.000000009117717470e+00,0.000000000000000000e+00 +2.162859810177679876e+01,1.179099999999999966e+02,0.000000000000000000e+00,2.344286479143545154e+00,0.000000000000000000e+00,1.082417197670517556e-01,0.000000000000000000e+00,1.000000009067597562e+00,0.000000000000000000e+00 +2.163286379203648480e+01,1.179200000000000017e+02,0.000000000000000000e+00,2.344748204793247304e+00,0.000000000000000000e+00,1.125074100654189363e-01,0.000000000000000000e+00,1.000000009125497025e+00,0.000000000000000000e+00 +2.163712864230038946e+01,1.179300000000000068e+02,0.000000000000000000e+00,2.345228032050755917e+00,0.000000000000000000e+00,1.167722603682414262e-01,0.000000000000000000e+00,1.000000009133767298e+00,0.000000000000000000e+00 +2.164139261998756325e+01,1.179399999999999977e+02,0.000000000000000000e+00,2.345725946363447001e+00,0.000000000000000000e+00,1.210362380943618560e-01,0.000000000000000000e+00,1.000000009079917040e+00,0.000000000000000000e+00 +2.164565569258370559e+01,1.179500000000000028e+02,0.000000000000000000e+00,2.346241932633207128e+00,0.000000000000000000e+00,1.252993107292116604e-01,0.000000000000000000e+00,1.000000009154905944e+00,0.000000000000000000e+00 +2.164991782764356998e+01,1.179600000000000080e+02,0.000000000000000000e+00,2.346775975218442944e+00,0.000000000000000000e+00,1.295614458280955061e-01,0.000000000000000000e+00,1.000000009127834932e+00,0.000000000000000000e+00 +2.165417899279337632e+01,1.179699999999999989e+02,0.000000000000000000e+00,2.347328057936163948e+00,0.000000000000000000e+00,1.338226110167955174e-01,0.000000000000000000e+00,1.000000009139070389e+00,0.000000000000000000e+00 +2.165843915573318768e+01,1.179800000000000040e+02,0.000000000000000000e+00,2.347898164064126547e+00,0.000000000000000000e+00,1.380827739955412248e-01,0.000000000000000000e+00,1.000000009150470826e+00,0.000000000000000000e+00 +2.166269828423929411e+01,1.179900000000000091e+02,0.000000000000000000e+00,2.348486276343053181e+00,0.000000000000000000e+00,1.423419025406204852e-01,0.000000000000000000e+00,1.000000009129552003e+00,0.000000000000000000e+00 +2.166695634616655752e+01,1.180000000000000000e+02,0.000000000000000000e+00,2.349092376978915819e+00,0.000000000000000000e+00,1.465999645067593837e-01,0.000000000000000000e+00,1.000000009186444272e+00,0.000000000000000000e+00 +2.167121330945075997e+01,1.180100000000000051e+02,0.000000000000000000e+00,2.349716447645286532e+00,0.000000000000000000e+00,1.508569278300685712e-01,0.000000000000000000e+00,1.000000009148146018e+00,0.000000000000000000e+00 +2.167546914211092002e+01,1.180199999999999960e+02,0.000000000000000000e+00,2.350358469485756885e+00,0.000000000000000000e+00,1.551127605291598710e-01,0.000000000000000000e+00,1.000000009187412608e+00,0.000000000000000000e+00 +2.167972381225159495e+01,1.180300000000000011e+02,0.000000000000000000e+00,2.351018423116417733e+00,0.000000000000000000e+00,1.593674307089227304e-01,0.000000000000000000e+00,1.000000009153694247e+00,0.000000000000000000e+00 +2.168397728806517222e+01,1.180400000000000063e+02,0.000000000000000000e+00,2.351696288628410070e+00,0.000000000000000000e+00,1.636209065614349090e-01,0.000000000000000000e+00,1.000000009204299545e+00,0.000000000000000000e+00 +2.168822953783413965e+01,1.180499999999999972e+02,0.000000000000000000e+00,2.352392045590534053e+00,0.000000000000000000e+00,1.678731563695405882e-01,0.000000000000000000e+00,1.000000009161023495e+00,0.000000000000000000e+00 +2.169248052993332720e+01,1.180600000000000023e+02,0.000000000000000000e+00,2.353105673051926860e+00,0.000000000000000000e+00,1.721241485076728528e-01,0.000000000000000000e+00,1.000000009217561825e+00,0.000000000000000000e+00 +2.169673023283214874e+01,1.180700000000000074e+02,0.000000000000000000e+00,2.353837149544796947e+00,0.000000000000000000e+00,1.763738514456653639e-01,0.000000000000000000e+00,1.000000009174229376e+00,0.000000000000000000e+00 +2.170097861509679760e+01,1.180799999999999983e+02,0.000000000000000000e+00,2.354586453087226694e+00,0.000000000000000000e+00,1.806222337492908170e-01,0.000000000000000000e+00,1.000000009221628350e+00,0.000000000000000000e+00 +2.170522564539245280e+01,1.180900000000000034e+02,0.000000000000000000e+00,2.355353561186028788e+00,0.000000000000000000e+00,1.848692640841102242e-01,0.000000000000000000e+00,1.000000009200825213e+00,0.000000000000000000e+00 +2.170947129248543561e+01,1.181000000000000085e+02,0.000000000000000000e+00,2.356138450839669662e+00,0.000000000000000000e+00,1.891149112161581158e-01,0.000000000000000000e+00,1.000000009241831300e+00,0.000000000000000000e+00 +2.171371552524537307e+01,1.181099999999999994e+02,0.000000000000000000e+00,2.356941098541245783e+00,0.000000000000000000e+00,1.933591440153192009e-01,0.000000000000000000e+00,1.000000009196656325e+00,0.000000000000000000e+00 +2.171795831264731191e+01,1.181200000000000045e+02,0.000000000000000000e+00,2.357761480281523436e+00,0.000000000000000000e+00,1.976019314562763585e-01,0.000000000000000000e+00,1.000000009231146736e+00,0.000000000000000000e+00 +2.172219962377383240e+01,1.181299999999999955e+02,0.000000000000000000e+00,2.358599571552030927e+00,0.000000000000000000e+00,2.018432426219492482e-01,0.000000000000000000e+00,1.000000009234042864e+00,0.000000000000000000e+00 +2.172643942781713733e+01,1.181400000000000006e+02,0.000000000000000000e+00,2.359455347348212939e+00,0.000000000000000000e+00,2.060830467044031944e-01,0.000000000000000000e+00,1.000000009213309005e+00,0.000000000000000000e+00 +2.173067769408110195e+01,1.181500000000000057e+02,0.000000000000000000e+00,2.360328782172635531e+00,0.000000000000000000e+00,2.103213130074176040e-01,0.000000000000000000e+00,1.000000009274006230e+00,0.000000000000000000e+00 +2.173491439198333097e+01,1.181599999999999966e+02,0.000000000000000000e+00,2.361219850038247969e+00,0.000000000000000000e+00,2.145580109489371168e-01,0.000000000000000000e+00,1.000000009225620268e+00,0.000000000000000000e+00 +2.173914949105715877e+01,1.181700000000000017e+02,0.000000000000000000e+00,2.362128524471700075e+00,0.000000000000000000e+00,2.187931100618359936e-01,0.000000000000000000e+00,1.000000009253496414e+00,0.000000000000000000e+00 +2.174338296095365308e+01,1.181800000000000068e+02,0.000000000000000000e+00,2.363054778516707088e+00,0.000000000000000000e+00,2.230265799975040819e-01,0.000000000000000000e+00,1.000000009254900624e+00,0.000000000000000000e+00 +2.174761477144357968e+01,1.181899999999999977e+02,0.000000000000000000e+00,2.363998584737473152e+00,0.000000000000000000e+00,2.272583905265964377e-01,0.000000000000000000e+00,1.000000009264669698e+00,0.000000000000000000e+00 +2.175184489241935282e+01,1.182000000000000028e+02,0.000000000000000000e+00,2.364959915222160536e+00,0.000000000000000000e+00,2.314885115415619421e-01,0.000000000000000000e+00,1.000000009262250300e+00,0.000000000000000000e+00 +2.175607329389695721e+01,1.182100000000000080e+02,0.000000000000000000e+00,2.365938741586411265e+00,0.000000000000000000e+00,2.357169130583306182e-01,0.000000000000000000e+00,1.000000009276838409e+00,0.000000000000000000e+00 +2.176029994601783812e+01,1.182199999999999989e+02,0.000000000000000000e+00,2.366935034976916707e+00,0.000000000000000000e+00,2.399435652184212786e-01,0.000000000000000000e+00,1.000000009269471413e+00,0.000000000000000000e+00 +2.176452481905078074e+01,1.182300000000000040e+02,0.000000000000000000e+00,2.367948766075036016e+00,0.000000000000000000e+00,2.441684382905257855e-01,0.000000000000000000e+00,1.000000009288984915e+00,0.000000000000000000e+00 +2.176874788339375399e+01,1.182400000000000091e+02,0.000000000000000000e+00,2.368979905100460304e+00,0.000000000000000000e+00,2.483915026727274433e-01,0.000000000000000000e+00,1.000000009280231916e+00,0.000000000000000000e+00 +2.177296910957573672e+01,1.182500000000000000e+02,0.000000000000000000e+00,2.370028421814924346e+00,0.000000000000000000e+00,2.526127288938836979e-01,0.000000000000000000e+00,1.000000009265896939e+00,0.000000000000000000e+00 +2.177718846825850818e+01,1.182600000000000051e+02,0.000000000000000000e+00,2.371094285525961354e+00,0.000000000000000000e+00,2.568320876157513255e-01,0.000000000000000000e+00,1.000000009330053619e+00,0.000000000000000000e+00 +2.178140593023842442e+01,1.182699999999999960e+02,0.000000000000000000e+00,2.372177465090703041e+00,0.000000000000000000e+00,2.610495496350156985e-01,0.000000000000000000e+00,1.000000009276840185e+00,0.000000000000000000e+00 +2.178562146644815556e+01,1.182800000000000011e+02,0.000000000000000000e+00,2.373277928919723667e+00,0.000000000000000000e+00,2.652650858838545012e-01,0.000000000000000000e+00,1.000000009288356972e+00,0.000000000000000000e+00 +2.178983504795841242e+01,1.182900000000000063e+02,0.000000000000000000e+00,2.374395644980920927e+00,0.000000000000000000e+00,2.694786674332499410e-01,0.000000000000000000e+00,1.000000009334770290e+00,0.000000000000000000e+00 +2.179404664597963404e+01,1.182999999999999972e+02,0.000000000000000000e+00,2.375530580803444369e+00,0.000000000000000000e+00,2.736902654937863333e-01,0.000000000000000000e+00,1.000000009282634217e+00,0.000000000000000000e+00 +2.179825623186365036e+01,1.183100000000000023e+02,0.000000000000000000e+00,2.376682703481659775e+00,0.000000000000000000e+00,2.778998514168790068e-01,0.000000000000000000e+00,1.000000009330783923e+00,0.000000000000000000e+00 +2.180246377710532357e+01,1.183200000000000074e+02,0.000000000000000000e+00,2.377851979679150407e+00,0.000000000000000000e+00,2.821073966978113745e-01,0.000000000000000000e+00,1.000000009318563032e+00,0.000000000000000000e+00 +2.180666925334415396e+01,1.183299999999999983e+02,0.000000000000000000e+00,2.379038375632761770e+00,0.000000000000000000e+00,2.863128729758322444e-01,0.000000000000000000e+00,1.000000009312266291e+00,0.000000000000000000e+00 +2.181087263236587503e+01,1.183400000000000034e+02,0.000000000000000000e+00,2.380241857156676577e+00,0.000000000000000000e+00,2.905162520366945667e-01,0.000000000000000000e+00,1.000000009339856666e+00,0.000000000000000000e+00 +2.181507388610399190e+01,1.183500000000000085e+02,0.000000000000000000e+00,2.381462389646529232e+00,0.000000000000000000e+00,2.947175058140498183e-01,0.000000000000000000e+00,1.000000009300329618e+00,0.000000000000000000e+00 +2.181927298664132309e+01,1.183599999999999994e+02,0.000000000000000000e+00,2.382699938083554070e+00,0.000000000000000000e+00,2.989166063904345472e-01,0.000000000000000000e+00,1.000000009377209897e+00,0.000000000000000000e+00 +2.182346990621149985e+01,1.183700000000000045e+02,0.000000000000000000e+00,2.383954467038764680e+00,0.000000000000000000e+00,3.031135259999659382e-01,0.000000000000000000e+00,1.000000009293293024e+00,0.000000000000000000e+00 +2.182766461720042983e+01,1.183799999999999955e+02,0.000000000000000000e+00,2.385225940677170531e+00,0.000000000000000000e+00,3.073082370278801823e-01,0.000000000000000000e+00,1.000000009380275001e+00,0.000000000000000000e+00 +2.183185709214775372e+01,1.183900000000000006e+02,0.000000000000000000e+00,2.386514322762016693e+00,0.000000000000000000e+00,3.115007120145322772e-01,0.000000000000000000e+00,1.000000009328191775e+00,0.000000000000000000e+00 +2.183604730374825564e+01,1.184000000000000057e+02,0.000000000000000000e+00,2.387819576659064413e+00,0.000000000000000000e+00,3.156909236541207142e-01,0.000000000000000000e+00,1.000000009357447928e+00,0.000000000000000000e+00 +2.184023522485324520e+01,1.184099999999999966e+02,0.000000000000000000e+00,2.389141665340889453e+00,0.000000000000000000e+00,3.198788447982994776e-01,0.000000000000000000e+00,1.000000009345365370e+00,0.000000000000000000e+00 +2.184442082847192879e+01,1.184200000000000017e+02,0.000000000000000000e+00,2.390480551391217734e+00,0.000000000000000000e+00,3.240644484560996630e-01,0.000000000000000000e+00,1.000000009342819629e+00,0.000000000000000000e+00 +2.184860408777273477e+01,1.184300000000000068e+02,0.000000000000000000e+00,2.391836197009281850e+00,0.000000000000000000e+00,3.282477077959877754e-01,0.000000000000000000e+00,1.000000009382506772e+00,0.000000000000000000e+00 +2.185278497608461024e+01,1.184399999999999977e+02,0.000000000000000000e+00,2.393208564014206452e+00,0.000000000000000000e+00,3.324285961470918038e-01,0.000000000000000000e+00,1.000000009362548292e+00,0.000000000000000000e+00 +2.185696346689831060e+01,1.184500000000000028e+02,0.000000000000000000e+00,2.394597613849418050e+00,0.000000000000000000e+00,3.366070869999124859e-01,0.000000000000000000e+00,1.000000009361891484e+00,0.000000000000000000e+00 +2.186113953386762532e+01,1.184600000000000080e+02,0.000000000000000000e+00,2.396003307587076137e+00,0.000000000000000000e+00,3.407831540083245958e-01,0.000000000000000000e+00,1.000000009371452947e+00,0.000000000000000000e+00 +2.186531315081061422e+01,1.184699999999999989e+02,0.000000000000000000e+00,2.397425605932530068e+00,0.000000000000000000e+00,3.449567709904251545e-01,0.000000000000000000e+00,1.000000009380410892e+00,0.000000000000000000e+00 +2.186948429171077635e+01,1.184800000000000040e+02,0.000000000000000000e+00,2.398864469228795926e+00,0.000000000000000000e+00,3.491279119297138189e-01,0.000000000000000000e+00,1.000000009361115438e+00,0.000000000000000000e+00 +2.187365293071822236e+01,1.184900000000000091e+02,0.000000000000000000e+00,2.400319857461053807e+00,0.000000000000000000e+00,3.532965509761815115e-01,0.000000000000000000e+00,1.000000009406713408e+00,0.000000000000000000e+00 +2.187781904215079365e+01,1.185000000000000000e+02,0.000000000000000000e+00,2.401791730261164215e+00,0.000000000000000000e+00,3.574626624479437242e-01,0.000000000000000000e+00,1.000000009357431274e+00,0.000000000000000000e+00 +2.188198260049517785e+01,1.185100000000000051e+02,0.000000000000000000e+00,2.403280046912204870e+00,0.000000000000000000e+00,3.616262208312873705e-01,0.000000000000000000e+00,1.000000009398806400e+00,0.000000000000000000e+00 +2.188614358040796404e+01,1.185199999999999960e+02,0.000000000000000000e+00,2.404784766353020409e+00,0.000000000000000000e+00,3.657872007831811656e-01,0.000000000000000000e+00,1.000000009405087376e+00,0.000000000000000000e+00 +2.189030195671669432e+01,1.185300000000000011e+02,0.000000000000000000e+00,2.406305847182794277e+00,0.000000000000000000e+00,3.699455771310222185e-01,0.000000000000000000e+00,1.000000009383769317e+00,0.000000000000000000e+00 +2.189445770442087991e+01,1.185400000000000063e+02,0.000000000000000000e+00,2.407843247665630404e+00,0.000000000000000000e+00,3.741013248742051100e-01,0.000000000000000000e+00,1.000000009407725265e+00,0.000000000000000000e+00 +2.189861079869298166e+01,1.185499999999999972e+02,0.000000000000000000e+00,2.409396925735151296e+00,0.000000000000000000e+00,3.782544191853784432e-01,0.000000000000000000e+00,1.000000009392212785e+00,0.000000000000000000e+00 +2.190276121487936933e+01,1.185600000000000023e+02,0.000000000000000000e+00,2.410966838999110351e+00,0.000000000000000000e+00,3.824048354107461023e-01,0.000000000000000000e+00,1.000000009385794808e+00,0.000000000000000000e+00 +2.190690892850124172e+01,1.185700000000000074e+02,0.000000000000000000e+00,2.412552944744013494e+00,0.000000000000000000e+00,3.865525490715484014e-01,0.000000000000000000e+00,1.000000009423889891e+00,0.000000000000000000e+00 +2.191105391525553614e+01,1.185799999999999983e+02,0.000000000000000000e+00,2.414155199939754137e+00,0.000000000000000000e+00,3.906975358649055763e-01,0.000000000000000000e+00,1.000000009406709411e+00,0.000000000000000000e+00 +2.191519615101579177e+01,1.185900000000000034e+02,0.000000000000000000e+00,2.415773561244257905e+00,0.000000000000000000e+00,3.948397716641270372e-01,0.000000000000000000e+00,1.000000009442049365e+00,0.000000000000000000e+00 +2.191933561183299162e+01,1.186000000000000085e+02,0.000000000000000000e+00,2.417407985008134030e+00,0.000000000000000000e+00,3.989792325204127299e-01,0.000000000000000000e+00,1.000000009386180722e+00,0.000000000000000000e+00 +2.192347227393637610e+01,1.186099999999999994e+02,0.000000000000000000e+00,2.419058427279338286e+00,0.000000000000000000e+00,4.031158946626237638e-01,0.000000000000000000e+00,1.000000009419941716e+00,0.000000000000000000e+00 +2.192760611373422108e+01,1.186200000000000045e+02,0.000000000000000000e+00,2.420724843807838589e+00,0.000000000000000000e+00,4.072497344994094326e-01,0.000000000000000000e+00,1.000000009432152837e+00,0.000000000000000000e+00 +2.193173710781460173e+01,1.186299999999999955e+02,0.000000000000000000e+00,2.422407190050292147e+00,0.000000000000000000e+00,4.113807286187540213e-01,0.000000000000000000e+00,1.000000009413276381e+00,0.000000000000000000e+00 +2.193586523294611368e+01,1.186400000000000006e+02,0.000000000000000000e+00,2.424105421174722608e+00,0.000000000000000000e+00,4.155088537891243883e-01,0.000000000000000000e+00,1.000000009435211723e+00,0.000000000000000000e+00 +2.193999046607857295e+01,1.186500000000000057e+02,0.000000000000000000e+00,2.425819492065202976e+00,0.000000000000000000e+00,4.196340869605044155e-01,0.000000000000000000e+00,1.000000009446319282e+00,0.000000000000000000e+00 +2.194411278434368384e+01,1.186599999999999966e+02,0.000000000000000000e+00,2.427549357326542978e+00,0.000000000000000000e+00,4.237564052645550472e-01,0.000000000000000000e+00,1.000000009405550117e+00,0.000000000000000000e+00 +2.194823216505568553e+01,1.186700000000000017e+02,0.000000000000000000e+00,2.429294971288976424e+00,0.000000000000000000e+00,4.278757860153005188e-01,0.000000000000000000e+00,1.000000009442415516e+00,0.000000000000000000e+00 +2.195234858571195957e+01,1.186800000000000068e+02,0.000000000000000000e+00,2.431056288012849897e+00,0.000000000000000000e+00,4.319922067104449148e-01,0.000000000000000000e+00,1.000000009467346240e+00,0.000000000000000000e+00 +2.195646202399362679e+01,1.186899999999999977e+02,0.000000000000000000e+00,2.432833261293314564e+00,0.000000000000000000e+00,4.361056450310555332e-01,0.000000000000000000e+00,1.000000009408241963e+00,0.000000000000000000e+00 +2.196057245776609435e+01,1.187000000000000028e+02,0.000000000000000000e+00,2.434625844665013528e+00,0.000000000000000000e+00,4.402160788421940474e-01,0.000000000000000000e+00,1.000000009475258578e+00,0.000000000000000000e+00 +2.196467986507958869e+01,1.187100000000000080e+02,0.000000000000000000e+00,2.436433991406767863e+00,0.000000000000000000e+00,4.443234861946073755e-01,0.000000000000000000e+00,1.000000009425627612e+00,0.000000000000000000e+00 +2.196878422416966359e+01,1.187199999999999989e+02,0.000000000000000000e+00,2.438257654546264863e+00,0.000000000000000000e+00,4.484278453233693229e-01,0.000000000000000000e+00,1.000000009457584493e+00,0.000000000000000000e+00 +2.197288551345767260e+01,1.187300000000000040e+02,0.000000000000000000e+00,2.440096786864735190e+00,0.000000000000000000e+00,4.525291346501680301e-01,0.000000000000000000e+00,1.000000009446737170e+00,0.000000000000000000e+00 +2.197698371155122032e+01,1.187400000000000091e+02,0.000000000000000000e+00,2.441951340901633127e+00,0.000000000000000000e+00,4.566273327824299511e-01,0.000000000000000000e+00,1.000000009471675444e+00,0.000000000000000000e+00 +2.198107879724457803e+01,1.187500000000000000e+02,0.000000000000000000e+00,2.443821268959306181e+00,0.000000000000000000e+00,4.607224185145741835e-01,0.000000000000000000e+00,1.000000009442411075e+00,0.000000000000000000e+00 +2.198517074951908157e+01,1.187600000000000051e+02,0.000000000000000000e+00,2.445706523107662012e+00,0.000000000000000000e+00,4.648143708277163721e-01,0.000000000000000000e+00,1.000000009468372975e+00,0.000000000000000000e+00 +2.198925954754350442e+01,1.187699999999999960e+02,0.000000000000000000e+00,2.447607055188825598e+00,0.000000000000000000e+00,4.689031688908532058e-01,0.000000000000000000e+00,1.000000009457704619e+00,0.000000000000000000e+00 +2.199334517067439165e+01,1.187800000000000011e+02,0.000000000000000000e+00,2.449522816821791960e+00,0.000000000000000000e+00,4.729887920603801366e-01,0.000000000000000000e+00,1.000000009457696182e+00,0.000000000000000000e+00 +2.199742759845637607e+01,1.187900000000000063e+02,0.000000000000000000e+00,2.451453759407066890e+00,0.000000000000000000e+00,4.770712198809757276e-01,0.000000000000000000e+00,1.000000009491509134e+00,0.000000000000000000e+00 +2.200150681062247315e+01,1.187999999999999972e+02,0.000000000000000000e+00,2.453399834131300583e+00,0.000000000000000000e+00,4.811504320857916128e-01,0.000000000000000000e+00,1.000000009445136451e+00,0.000000000000000000e+00 +2.200558278709434035e+01,1.188100000000000023e+02,0.000000000000000000e+00,2.455360991971910600e+00,0.000000000000000000e+00,4.852264085961561224e-01,0.000000000000000000e+00,1.000000009488879904e+00,0.000000000000000000e+00 +2.200965550798250803e+01,1.188200000000000074e+02,0.000000000000000000e+00,2.457337183701691519e+00,0.000000000000000000e+00,4.892991295229709436e-01,0.000000000000000000e+00,1.000000009455523031e+00,0.000000000000000000e+00 +2.201372495358660686e+01,1.188299999999999983e+02,0.000000000000000000e+00,2.459328359893417471e+00,0.000000000000000000e+00,4.933685751655471075e-01,0.000000000000000000e+00,1.000000009501541332e+00,0.000000000000000000e+00 +2.201779110439553477e+01,1.188400000000000034e+02,0.000000000000000000e+00,2.461334470924426476e+00,0.000000000000000000e+00,4.974347260131097292e-01,0.000000000000000000e+00,1.000000009482512109e+00,0.000000000000000000e+00 +2.202185394108763461e+01,1.188500000000000085e+02,0.000000000000000000e+00,2.463355466981196784e+00,0.000000000000000000e+00,5.014975627437346928e-01,0.000000000000000000e+00,1.000000009480058960e+00,0.000000000000000000e+00 +2.202591344453081845e+01,1.188599999999999994e+02,0.000000000000000000e+00,2.465391298063904113e+00,0.000000000000000000e+00,5.055570662254045278e-01,0.000000000000000000e+00,1.000000009469883100e+00,0.000000000000000000e+00 +2.202996959578269198e+01,1.188700000000000045e+02,0.000000000000000000e+00,2.467441913990967794e+00,0.000000000000000000e+00,5.096132175156893318e-01,0.000000000000000000e+00,1.000000009499275366e+00,0.000000000000000000e+00 +2.203402237609062908e+01,1.188799999999999955e+02,0.000000000000000000e+00,2.469507264403579594e+00,0.000000000000000000e+00,5.136659978621244127e-01,0.000000000000000000e+00,1.000000009486261776e+00,0.000000000000000000e+00 +2.203807176689183933e+01,1.188900000000000006e+02,0.000000000000000000e+00,2.471587298770217433e+00,0.000000000000000000e+00,5.177153887017491574e-01,0.000000000000000000e+00,1.000000009477428842e+00,0.000000000000000000e+00 +2.204211774981341065e+01,1.189000000000000057e+02,0.000000000000000000e+00,2.473681966391140019e+00,0.000000000000000000e+00,5.217613716616672503e-01,0.000000000000000000e+00,1.000000009526800238e+00,0.000000000000000000e+00 +2.204616030667232351e+01,1.189099999999999966e+02,0.000000000000000000e+00,2.475791216402865924e+00,0.000000000000000000e+00,5.258039285590913048e-01,0.000000000000000000e+00,1.000000009464123263e+00,0.000000000000000000e+00 +2.205019941947543316e+01,1.189200000000000017e+02,0.000000000000000000e+00,2.477914997782634465e+00,0.000000000000000000e+00,5.298430414004279276e-01,0.000000000000000000e+00,1.000000009504795173e+00,0.000000000000000000e+00 +2.205423507041945186e+01,1.189300000000000068e+02,0.000000000000000000e+00,2.480053259352843931e+00,0.000000000000000000e+00,5.338786923828048314e-01,0.000000000000000000e+00,1.000000009527377998e+00,0.000000000000000000e+00 +2.205826724189088495e+01,1.189399999999999977e+02,0.000000000000000000e+00,2.482205949785476484e+00,0.000000000000000000e+00,5.379108638926550778e-01,0.000000000000000000e+00,1.000000009464218520e+00,0.000000000000000000e+00 +2.206229591646595978e+01,1.189500000000000028e+02,0.000000000000000000e+00,2.484373017606497314e+00,0.000000000000000000e+00,5.419395385058580761e-01,0.000000000000000000e+00,1.000000009531123446e+00,0.000000000000000000e+00 +2.206632107691051914e+01,1.189600000000000080e+02,0.000000000000000000e+00,2.486554411200233794e+00,0.000000000000000000e+00,5.459646989887816382e-01,0.000000000000000000e+00,1.000000009497322706e+00,0.000000000000000000e+00 +2.207034270617990401e+01,1.189699999999999989e+02,0.000000000000000000e+00,2.488750078813737776e+00,0.000000000000000000e+00,5.499863282963608491e-01,0.000000000000000000e+00,1.000000009515053412e+00,0.000000000000000000e+00 +2.207436078741880792e+01,1.189800000000000040e+02,0.000000000000000000e+00,2.490959968561118565e+00,0.000000000000000000e+00,5.540044095734961704e-01,0.000000000000000000e+00,1.000000009496398556e+00,0.000000000000000000e+00 +2.207837530396110992e+01,1.189900000000000091e+02,0.000000000000000000e+00,2.493184028427859467e+00,0.000000000000000000e+00,5.580189261539213463e-01,0.000000000000000000e+00,1.000000009531939238e+00,0.000000000000000000e+00 +2.208238623932968991e+01,1.190000000000000000e+02,0.000000000000000000e+00,2.495422206275107246e+00,0.000000000000000000e+00,5.620298615607333126e-01,0.000000000000000000e+00,1.000000009510607857e+00,0.000000000000000000e+00 +2.208639357723621899e+01,1.190100000000000051e+02,0.000000000000000000e+00,2.497674449843940714e+00,0.000000000000000000e+00,5.660371995053743444e-01,0.000000000000000000e+00,1.000000009510889409e+00,0.000000000000000000e+00 +2.209039730158092851e+01,1.190199999999999960e+02,0.000000000000000000e+00,2.499940706759611775e+00,0.000000000000000000e+00,5.700409238881631868e-01,0.000000000000000000e+00,1.000000009501145648e+00,0.000000000000000000e+00 +2.209439739645236500e+01,1.190300000000000011e+02,0.000000000000000000e+00,2.502220924535764723e+00,0.000000000000000000e+00,5.740410187976033862e-01,0.000000000000000000e+00,1.000000009564064207e+00,0.000000000000000000e+00 +2.209839384612710944e+01,1.190400000000000063e+02,0.000000000000000000e+00,2.504515050578628443e+00,0.000000000000000000e+00,5.780374685105702515e-01,0.000000000000000000e+00,1.000000009482705732e+00,0.000000000000000000e+00 +2.210238663506950019e+01,1.190499999999999972e+02,0.000000000000000000e+00,2.506823032191184630e+00,0.000000000000000000e+00,5.820302574908228221e-01,0.000000000000000000e+00,1.000000009547918678e+00,0.000000000000000000e+00 +2.210637574793131321e+01,1.190600000000000023e+02,0.000000000000000000e+00,2.509144816577304926e+00,0.000000000000000000e+00,5.860193703907223828e-01,0.000000000000000000e+00,1.000000009529823375e+00,0.000000000000000000e+00 +2.211036116955143527e+01,1.190700000000000074e+02,0.000000000000000000e+00,2.511480350845869403e+00,0.000000000000000000e+00,5.900047920488230568e-01,0.000000000000000000e+00,1.000000009512822752e+00,0.000000000000000000e+00 +2.211434288495551215e+01,1.190799999999999983e+02,0.000000000000000000e+00,2.513829582014849517e+00,0.000000000000000000e+00,5.939865074907775266e-01,0.000000000000000000e+00,1.000000009532784340e+00,0.000000000000000000e+00 +2.211832087935558633e+01,1.190900000000000034e+02,0.000000000000000000e+00,2.516192457015368422e+00,0.000000000000000000e+00,5.979645019287747054e-01,0.000000000000000000e+00,1.000000009546512025e+00,0.000000000000000000e+00 +2.212229513814970971e+01,1.191000000000000085e+02,0.000000000000000000e+00,2.518568922695732404e+00,0.000000000000000000e+00,6.019387607608382984e-01,0.000000000000000000e+00,1.000000009513178245e+00,0.000000000000000000e+00 +2.212626564692153153e+01,1.191099999999999994e+02,0.000000000000000000e+00,2.520958925825432573e+00,0.000000000000000000e+00,6.059092695704317855e-01,0.000000000000000000e+00,1.000000009559605330e+00,0.000000000000000000e+00 +2.213023239143987908e+01,1.191200000000000045e+02,0.000000000000000000e+00,2.523362413099117685e+00,0.000000000000000000e+00,6.098760141267008938e-01,0.000000000000000000e+00,1.000000009525606304e+00,0.000000000000000000e+00 +2.213419535765832080e+01,1.191299999999999955e+02,0.000000000000000000e+00,2.525779331140540318e+00,0.000000000000000000e+00,6.138389803828933067e-01,0.000000000000000000e+00,1.000000009550618962e+00,0.000000000000000000e+00 +2.213815453171470438e+01,1.191400000000000006e+02,0.000000000000000000e+00,2.528209626506468855e+00,0.000000000000000000e+00,6.177981544770888567e-01,0.000000000000000000e+00,1.000000009531398337e+00,0.000000000000000000e+00 +2.214210989993067713e+01,1.191500000000000057e+02,0.000000000000000000e+00,2.530653245690574149e+00,0.000000000000000000e+00,6.217535227307617873e-01,0.000000000000000000e+00,1.000000009539296908e+00,0.000000000000000000e+00 +2.214606144881119931e+01,1.191599999999999966e+02,0.000000000000000000e+00,2.533110135127282003e+00,0.000000000000000000e+00,6.257050716489795938e-01,0.000000000000000000e+00,1.000000009558099423e+00,0.000000000000000000e+00 +2.215000916504403250e+01,1.191700000000000017e+02,0.000000000000000000e+00,2.535580241195597662e+00,0.000000000000000000e+00,6.296527879195469302e-01,0.000000000000000000e+00,1.000000009531098577e+00,0.000000000000000000e+00 +2.215395303549921735e+01,1.191800000000000068e+02,0.000000000000000000e+00,2.538063510222897889e+00,0.000000000000000000e+00,6.335966584123204903e-01,0.000000000000000000e+00,1.000000009552441282e+00,0.000000000000000000e+00 +2.215789304722852293e+01,1.191899999999999977e+02,0.000000000000000000e+00,2.540559888488691076e+00,0.000000000000000000e+00,6.375366701792625213e-01,0.000000000000000000e+00,1.000000009571062609e+00,0.000000000000000000e+00 +2.216182918746489605e+01,1.192000000000000028e+02,0.000000000000000000e+00,2.543069322228348028e+00,0.000000000000000000e+00,6.414728104533102826e-01,0.000000000000000000e+00,1.000000009522201472e+00,0.000000000000000000e+00 +2.216576144362189282e+01,1.192100000000000080e+02,0.000000000000000000e+00,2.545591757636798569e+00,0.000000000000000000e+00,6.454050666477499920e-01,0.000000000000000000e+00,1.000000009574475879e+00,0.000000000000000000e+00 +2.216968980329307826e+01,1.192199999999999989e+02,0.000000000000000000e+00,2.548127140872195717e+00,0.000000000000000000e+00,6.493334263565464504e-01,0.000000000000000000e+00,1.000000009542759916e+00,0.000000000000000000e+00 +2.217361425425142940e+01,1.192300000000000040e+02,0.000000000000000000e+00,2.550675418059551003e+00,0.000000000000000000e+00,6.532578773523490812e-01,0.000000000000000000e+00,1.000000009564658399e+00,0.000000000000000000e+00 +2.217753478444872428e+01,1.192400000000000091e+02,0.000000000000000000e+00,2.553236535294331588e+00,0.000000000000000000e+00,6.571784075871424102e-01,0.000000000000000000e+00,1.000000009568494441e+00,0.000000000000000000e+00 +2.218145138201489885e+01,1.192500000000000000e+02,0.000000000000000000e+00,2.555810438646029414e+00,0.000000000000000000e+00,6.610950051907922287e-01,0.000000000000000000e+00,1.000000009546004653e+00,0.000000000000000000e+00 +2.218536403525740397e+01,1.192600000000000051e+02,0.000000000000000000e+00,2.558397074161693929e+00,0.000000000000000000e+00,6.650076584706487992e-01,0.000000000000000000e+00,1.000000009566625936e+00,0.000000000000000000e+00 +2.218927273266055167e+01,1.192699999999999960e+02,0.000000000000000000e+00,2.560996387869432400e+00,0.000000000000000000e+00,6.689163559111909185e-01,0.000000000000000000e+00,1.000000009557425518e+00,0.000000000000000000e+00 +2.219317746288483661e+01,1.192800000000000011e+02,0.000000000000000000e+00,2.563608325781877806e+00,0.000000000000000000e+00,6.728210861727956793e-01,0.000000000000000000e+00,1.000000009546966107e+00,0.000000000000000000e+00 +2.219707821476625043e+01,1.192900000000000063e+02,0.000000000000000000e+00,2.566232833899620758e+00,0.000000000000000000e+00,6.767218380914491460e-01,0.000000000000000000e+00,1.000000009590007011e+00,0.000000000000000000e+00 +2.220097497731558178e+01,1.192999999999999972e+02,0.000000000000000000e+00,2.568869858214609003e+00,0.000000000000000000e+00,6.806186006781487219e-01,0.000000000000000000e+00,1.000000009572515891e+00,0.000000000000000000e+00 +2.220486773971770234e+01,1.193100000000000023e+02,0.000000000000000000e+00,2.571519344713513178e+00,0.000000000000000000e+00,6.845113631175333557e-01,0.000000000000000000e+00,1.000000009572262760e+00,0.000000000000000000e+00 +2.220875649133085261e+01,1.193200000000000074e+02,0.000000000000000000e+00,2.574181239381055697e+00,0.000000000000000000e+00,6.884001147679070787e-01,0.000000000000000000e+00,1.000000009575367166e+00,0.000000000000000000e+00 +2.221264122168589239e+01,1.193299999999999983e+02,0.000000000000000000e+00,2.576855488203308120e+00,0.000000000000000000e+00,6.922848451601455455e-01,0.000000000000000000e+00,1.000000009542646895e+00,0.000000000000000000e+00 +2.221652192048556529e+01,1.193400000000000034e+02,0.000000000000000000e+00,2.579542037170952540e+00,0.000000000000000000e+00,6.961655439968501558e-01,0.000000000000000000e+00,1.000000009594268713e+00,0.000000000000000000e+00 +2.222039857760372783e+01,1.193500000000000085e+02,0.000000000000000000e+00,2.582240832282507892e+00,0.000000000000000000e+00,7.000422011522070553e-01,0.000000000000000000e+00,1.000000009574033122e+00,0.000000000000000000e+00 +2.222427118308458915e+01,1.193599999999999994e+02,0.000000000000000000e+00,2.584951819547523844e+00,0.000000000000000000e+00,7.039148066701443884e-01,0.000000000000000000e+00,1.000000009586779592e+00,0.000000000000000000e+00 +2.222813972714192232e+01,1.193700000000000045e+02,0.000000000000000000e+00,2.587674944989735604e+00,0.000000000000000000e+00,7.077833507645632238e-01,0.000000000000000000e+00,1.000000009560681802e+00,0.000000000000000000e+00 +2.223200420015827206e+01,1.193799999999999955e+02,0.000000000000000000e+00,2.590410154650187646e+00,0.000000000000000000e+00,7.116478238178610694e-01,0.000000000000000000e+00,1.000000009578147386e+00,0.000000000000000000e+00 +2.223586459268416249e+01,1.193900000000000006e+02,0.000000000000000000e+00,2.593157394590319687e+00,0.000000000000000000e+00,7.155082163807260365e-01,0.000000000000000000e+00,1.000000009612910690e+00,0.000000000000000000e+00 +2.223972089543726938e+01,1.194000000000000057e+02,0.000000000000000000e+00,2.595916610895019794e+00,0.000000000000000000e+00,7.193645191709039377e-01,0.000000000000000000e+00,1.000000009562377112e+00,0.000000000000000000e+00 +2.224357309930161009e+01,1.194099999999999966e+02,0.000000000000000000e+00,2.598687749675640646e+00,0.000000000000000000e+00,7.232167230720824014e-01,0.000000000000000000e+00,1.000000009579374183e+00,0.000000000000000000e+00 +2.224742119532670870e+01,1.194200000000000017e+02,0.000000000000000000e+00,2.601470757072979367e+00,0.000000000000000000e+00,7.270648191340436384e-01,0.000000000000000000e+00,1.000000009566935022e+00,0.000000000000000000e+00 +2.225126517472675047e+01,1.194300000000000068e+02,0.000000000000000000e+00,2.604265579260225838e+00,0.000000000000000000e+00,7.309087985708606627e-01,0.000000000000000000e+00,1.000000009628613018e+00,0.000000000000000000e+00 +2.225510502887973630e+01,1.194399999999999977e+02,0.000000000000000000e+00,2.607072162445871921e+00,0.000000000000000000e+00,7.347486527608187989e-01,0.000000000000000000e+00,1.000000009558740022e+00,0.000000000000000000e+00 +2.225894074932662292e+01,1.194500000000000028e+02,0.000000000000000000e+00,2.609890452876588274e+00,0.000000000000000000e+00,7.385843732443690968e-01,0.000000000000000000e+00,1.000000009625915398e+00,0.000000000000000000e+00 +2.226277232777045256e+01,1.194600000000000080e+02,0.000000000000000000e+00,2.612720396840061188e+00,0.000000000000000000e+00,7.424159517250816798e-01,0.000000000000000000e+00,1.000000009547821200e+00,0.000000000000000000e+00 +2.226659975607548603e+01,1.194699999999999989e+02,0.000000000000000000e+00,2.615561940667801011e+00,0.000000000000000000e+00,7.462433800666572470e-01,0.000000000000000000e+00,1.000000009608065232e+00,0.000000000000000000e+00 +2.227042302626630743e+01,1.194800000000000040e+02,0.000000000000000000e+00,2.618415030737907045e+00,0.000000000000000000e+00,7.500666502942120450e-01,0.000000000000000000e+00,1.000000009595963357e+00,0.000000000000000000e+00 +2.227424213052694313e+01,1.194900000000000091e+02,0.000000000000000000e+00,2.621279613477805359e+00,0.000000000000000000e+00,7.538857545914943170e-01,0.000000000000000000e+00,1.000000009622658004e+00,0.000000000000000000e+00 +2.227805706119995577e+01,1.195000000000000000e+02,0.000000000000000000e+00,2.624155635366943962e+00,0.000000000000000000e+00,7.577006853012170362e-01,0.000000000000000000e+00,1.000000009572120208e+00,0.000000000000000000e+00 +2.228186781078554546e+01,1.195100000000000051e+02,0.000000000000000000e+00,2.627043042939457340e+00,0.000000000000000000e+00,7.615114349232846580e-01,0.000000000000000000e+00,1.000000009586025751e+00,0.000000000000000000e+00 +2.228567437194063316e+01,1.195199999999999960e+02,0.000000000000000000e+00,2.629941782786792359e+00,0.000000000000000000e+00,7.653179961148633970e-01,0.000000000000000000e+00,1.000000009602504569e+00,0.000000000000000000e+00 +2.228947673747794411e+01,1.195300000000000011e+02,0.000000000000000000e+00,2.632851801560302629e+00,0.000000000000000000e+00,7.691203616886855832e-01,0.000000000000000000e+00,1.000000009626569764e+00,0.000000000000000000e+00 +2.229327490036507342e+01,1.195400000000000063e+02,0.000000000000000000e+00,2.635773045973804685e+00,0.000000000000000000e+00,7.729185246123789765e-01,0.000000000000000000e+00,1.000000009572168613e+00,0.000000000000000000e+00 +2.229706885372356595e+01,1.195499999999999972e+02,0.000000000000000000e+00,2.638705462806099966e+00,0.000000000000000000e+00,7.767124780071892332e-01,0.000000000000000000e+00,1.000000009627508568e+00,0.000000000000000000e+00 +2.230085859082797484e+01,1.195600000000000023e+02,0.000000000000000000e+00,2.641648998903460388e+00,0.000000000000000000e+00,7.805022151480828230e-01,0.000000000000000000e+00,1.000000009570113368e+00,0.000000000000000000e+00 +2.230464410510490936e+01,1.195700000000000074e+02,0.000000000000000000e+00,2.644603601182082819e+00,0.000000000000000000e+00,7.842877294612455863e-01,0.000000000000000000e+00,1.000000009626463848e+00,0.000000000000000000e+00 +2.230842539013209702e+01,1.195799999999999983e+02,0.000000000000000000e+00,2.647569216630502709e+00,0.000000000000000000e+00,7.880690145248350209e-01,0.000000000000000000e+00,1.000000009629443021e+00,0.000000000000000000e+00 +2.231220243963742789e+01,1.195900000000000034e+02,0.000000000000000000e+00,2.650545792311979287e+00,0.000000000000000000e+00,7.918460640665354600e-01,0.000000000000000000e+00,1.000000009568742687e+00,0.000000000000000000e+00 +2.231597524749798467e+01,1.196000000000000085e+02,0.000000000000000000e+00,2.653533275366840360e+00,0.000000000000000000e+00,7.956188719631931416e-01,0.000000000000000000e+00,1.000000009647545873e+00,0.000000000000000000e+00 +2.231974380773909061e+01,1.196099999999999994e+02,0.000000000000000000e+00,2.656531613014794679e+00,0.000000000000000000e+00,7.993874322406567812e-01,0.000000000000000000e+00,1.000000009587455940e+00,0.000000000000000000e+00 +2.232350811453333606e+01,1.196200000000000045e+02,0.000000000000000000e+00,2.659540752557212784e+00,0.000000000000000000e+00,8.031517390709925763e-01,0.000000000000000000e+00,1.000000009619707253e+00,0.000000000000000000e+00 +2.232726816219960497e+01,1.196299999999999955e+02,0.000000000000000000e+00,2.662560641379366544e+00,0.000000000000000000e+00,8.069117867734321159e-01,0.000000000000000000e+00,1.000000009600744866e+00,0.000000000000000000e+00 +2.233102394520209799e+01,1.196400000000000006e+02,0.000000000000000000e+00,2.665591226952641613e+00,0.000000000000000000e+00,8.106675698119836238e-01,0.000000000000000000e+00,1.000000009629296249e+00,0.000000000000000000e+00 +2.233477545814935183e+01,1.196500000000000057e+02,0.000000000000000000e+00,2.668632456836710354e+00,0.000000000000000000e+00,8.144190827953622369e-01,0.000000000000000000e+00,1.000000009597148187e+00,0.000000000000000000e+00 +2.233852269579325522e+01,1.196599999999999966e+02,0.000000000000000000e+00,2.671684278681674130e+00,0.000000000000000000e+00,8.181663204752280816e-01,0.000000000000000000e+00,1.000000009619760988e+00,0.000000000000000000e+00 +2.234226565302805767e+01,1.196700000000000017e+02,0.000000000000000000e+00,2.674746640230168726e+00,0.000000000000000000e+00,8.219092777460370591e-01,0.000000000000000000e+00,1.000000009615852337e+00,0.000000000000000000e+00 +2.234600432488938182e+01,1.196800000000000068e+02,0.000000000000000000e+00,2.677819489319439139e+00,0.000000000000000000e+00,8.256479496433117848e-01,0.000000000000000000e+00,1.000000009643838839e+00,0.000000000000000000e+00 +2.234973870655322514e+01,1.196899999999999977e+02,0.000000000000000000e+00,2.680902773883377943e+00,0.000000000000000000e+00,8.293823313431700761e-01,0.000000000000000000e+00,1.000000009605170437e+00,0.000000000000000000e+00 +2.235346879333496872e+01,1.197000000000000028e+02,0.000000000000000000e+00,2.683996441954532131e+00,0.000000000000000000e+00,8.331124181607409973e-01,0.000000000000000000e+00,1.000000009614442131e+00,0.000000000000000000e+00 +2.235719458068836829e+01,1.197100000000000080e+02,0.000000000000000000e+00,2.687100441666074424e+00,0.000000000000000000e+00,8.368382055499605787e-01,0.000000000000000000e+00,1.000000009637147302e+00,0.000000000000000000e+00 +2.236091606420455591e+01,1.197199999999999989e+02,0.000000000000000000e+00,2.690214721253744390e+00,0.000000000000000000e+00,8.405596891020123973e-01,0.000000000000000000e+00,1.000000009603935203e+00,0.000000000000000000e+00 +2.236463323961103811e+01,1.197300000000000040e+02,0.000000000000000000e+00,2.693339229057754469e+00,0.000000000000000000e+00,8.442768645441938169e-01,0.000000000000000000e+00,1.000000009622583397e+00,0.000000000000000000e+00 +2.236834610277068336e+01,1.197400000000000091e+02,0.000000000000000000e+00,2.696473913524662702e+00,0.000000000000000000e+00,8.479897277395679334e-01,0.000000000000000000e+00,1.000000009644451016e+00,0.000000000000000000e+00 +2.237205464968072022e+01,1.197500000000000000e+02,0.000000000000000000e+00,2.699618723209215254e+00,0.000000000000000000e+00,8.516982746853728470e-01,0.000000000000000000e+00,1.000000009610348295e+00,0.000000000000000000e+00 +2.237575887647172124e+01,1.197600000000000051e+02,0.000000000000000000e+00,2.702773606776154303e+00,0.000000000000000000e+00,8.554025015119729458e-01,0.000000000000000000e+00,1.000000009631581976e+00,0.000000000000000000e+00 +2.237945877940659045e+01,1.197699999999999960e+02,0.000000000000000000e+00,2.705938513001993506e+00,0.000000000000000000e+00,8.591024044824787653e-01,0.000000000000000000e+00,1.000000009652350919e+00,0.000000000000000000e+00 +2.238315435487955440e+01,1.197800000000000011e+02,0.000000000000000000e+00,2.709113390776763719e+00,0.000000000000000000e+00,8.627979799911141834e-01,0.000000000000000000e+00,1.000000009596183626e+00,0.000000000000000000e+00 +2.238684559941514607e+01,1.197900000000000063e+02,0.000000000000000000e+00,2.712298189105724511e+00,0.000000000000000000e+00,8.664892245621266254e-01,0.000000000000000000e+00,1.000000009645135579e+00,0.000000000000000000e+00 +2.239053250966718522e+01,1.197999999999999972e+02,0.000000000000000000e+00,2.715492857111043712e+00,0.000000000000000000e+00,8.701761348497261128e-01,0.000000000000000000e+00,1.000000009637992626e+00,0.000000000000000000e+00 +2.239421508241776948e+01,1.198100000000000023e+02,0.000000000000000000e+00,2.718697344033448982e+00,0.000000000000000000e+00,8.738587076358017569e-01,0.000000000000000000e+00,1.000000009641667909e+00,0.000000000000000000e+00 +2.239789331457625110e+01,1.198200000000000074e+02,0.000000000000000000e+00,2.721911599233843404e+00,0.000000000000000000e+00,8.775369398297467871e-01,0.000000000000000000e+00,1.000000009609260943e+00,0.000000000000000000e+00 +2.240156720317822447e+01,1.198299999999999983e+02,0.000000000000000000e+00,2.725135572194893108e+00,0.000000000000000000e+00,8.812108284670219227e-01,0.000000000000000000e+00,1.000000009626468733e+00,0.000000000000000000e+00 +2.240523674538450294e+01,1.198400000000000034e+02,0.000000000000000000e+00,2.728369212522582465e+00,0.000000000000000000e+00,8.848803707086251302e-01,0.000000000000000000e+00,1.000000009665779288e+00,0.000000000000000000e+00 +2.240890193848010981e+01,1.198500000000000085e+02,0.000000000000000000e+00,2.731612469947740429e+00,0.000000000000000000e+00,8.885455638396574374e-01,0.000000000000000000e+00,1.000000009634408160e+00,0.000000000000000000e+00 +2.241256277987324808e+01,1.198599999999999994e+02,0.000000000000000000e+00,2.734865294327534890e+00,0.000000000000000000e+00,8.922064052680667157e-01,0.000000000000000000e+00,1.000000009622776354e+00,0.000000000000000000e+00 +2.241621926709429857e+01,1.198700000000000045e+02,0.000000000000000000e+00,2.738127635646935953e+00,0.000000000000000000e+00,8.958628925243016239e-01,0.000000000000000000e+00,1.000000009656874189e+00,0.000000000000000000e+00 +2.241987139779478611e+01,1.198799999999999955e+02,0.000000000000000000e+00,2.741399444020151677e+00,0.000000000000000000e+00,8.995150232600575002e-01,0.000000000000000000e+00,1.000000009613074115e+00,0.000000000000000000e+00 +2.242351916974637405e+01,1.198900000000000006e+02,0.000000000000000000e+00,2.744680669692033170e+00,0.000000000000000000e+00,9.031627952467133902e-01,0.000000000000000000e+00,1.000000009667620260e+00,0.000000000000000000e+00 +2.242716258083984826e+01,1.199000000000000057e+02,0.000000000000000000e+00,2.747971263039448164e+00,0.000000000000000000e+00,9.068062063754106505e-01,0.000000000000000000e+00,1.000000009611493823e+00,0.000000000000000000e+00 +2.243080162908409392e+01,1.199099999999999966e+02,0.000000000000000000e+00,2.751271174572629263e+00,0.000000000000000000e+00,9.104452546546325520e-01,0.000000000000000000e+00,1.000000009668812195e+00,0.000000000000000000e+00 +2.243443631260508653e+01,1.199200000000000017e+02,0.000000000000000000e+00,2.754580354936488007e+00,0.000000000000000000e+00,9.140799382107678284e-01,0.000000000000000000e+00,1.000000009641009324e+00,0.000000000000000000e+00 +2.243806662964487941e+01,1.199300000000000068e+02,0.000000000000000000e+00,2.757898754911905836e+00,0.000000000000000000e+00,9.177102552855589401e-01,0.000000000000000000e+00,1.000000009626993869e+00,0.000000000000000000e+00 +2.244169257856058408e+01,1.199399999999999977e+02,0.000000000000000000e+00,2.761226325416990868e+00,0.000000000000000000e+00,9.213362042361720183e-01,0.000000000000000000e+00,1.000000009669673062e+00,0.000000000000000000e+00 +2.244531415782337547e+01,1.199500000000000028e+02,0.000000000000000000e+00,2.764563017508310239e+00,0.000000000000000000e+00,9.249577835339815035e-01,0.000000000000000000e+00,1.000000009634432807e+00,0.000000000000000000e+00 +2.244893136601746164e+01,1.199600000000000080e+02,0.000000000000000000e+00,2.767908782382093591e+00,0.000000000000000000e+00,9.285749917629179118e-01,0.000000000000000000e+00,1.000000009630928499e+00,0.000000000000000000e+00 +2.245254420183909261e+01,1.199699999999999989e+02,0.000000000000000000e+00,2.771263571375406354e+00,0.000000000000000000e+00,9.321878276193449331e-01,0.000000000000000000e+00,1.000000009690139580e+00,0.000000000000000000e+00 +2.245615266409554778e+01,1.199800000000000040e+02,0.000000000000000000e+00,2.774627335967298603e+00,0.000000000000000000e+00,9.357962899107675758e-01,0.000000000000000000e+00,1.000000009607201257e+00,0.000000000000000000e+00 +2.245975675170413410e+01,1.199900000000000091e+02,0.000000000000000000e+00,2.778000027779925496e+00,0.000000000000000000e+00,9.394003775539774281e-01,0.000000000000000000e+00,1.000000009673341905e+00,0.000000000000000000e+00 +2.246335646369117356e+01,1.200000000000000000e+02,0.000000000000000000e+00,2.781381598579637515e+00,0.000000000000000000e+00,9.430000895758398061e-01,0.000000000000000000e+00,1.000000009563537740e+00,0.000000000000000000e+00 +2.246695179919102259e+01,1.200100000000000051e+02,0.000000000000000000e+00,2.784772000278050275e+00,0.000000000000000000e+00,9.465954251100728856e-01,0.000000000000000000e+00,1.000000009583180027e+00,0.000000000000000000e+00 +2.247054275744505603e+01,1.200199999999999960e+02,0.000000000000000000e+00,2.788171184933079694e+00,0.000000000000000000e+00,9.501863833985192409e-01,0.000000000000000000e+00,1.000000009551726965e+00,0.000000000000000000e+00 +2.247412933780067945e+01,1.200300000000000011e+02,0.000000000000000000e+00,2.791579104749958962e+00,0.000000000000000000e+00,9.537729637884020395e-01,0.000000000000000000e+00,1.000000009503586140e+00,0.000000000000000000e+00 +2.247771153971033797e+01,1.200400000000000063e+02,0.000000000000000000e+00,2.794995712082223083e+00,0.000000000000000000e+00,9.573551657321049957e-01,0.000000000000000000e+00,1.000000009462723938e+00,0.000000000000000000e+00 +2.248128936273052147e+01,1.200499999999999972e+02,0.000000000000000000e+00,2.798420959432670330e+00,0.000000000000000000e+00,9.609329887861437491e-01,0.000000000000000000e+00,1.000000009422382208e+00,0.000000000000000000e+00 +2.248486280652077340e+01,1.200600000000000023e+02,0.000000000000000000e+00,2.801854799454297940e+00,0.000000000000000000e+00,9.645064326100676322e-01,0.000000000000000000e+00,1.000000009324834460e+00,0.000000000000000000e+00 +2.248843187084271733e+01,1.200700000000000074e+02,0.000000000000000000e+00,2.805297184951212053e+00,0.000000000000000000e+00,9.680754969652926034e-01,0.000000000000000000e+00,1.000000009284985225e+00,0.000000000000000000e+00 +2.249199655555906219e+01,1.200799999999999983e+02,0.000000000000000000e+00,2.808748068879511894e+00,0.000000000000000000e+00,9.716401817147352071e-01,0.000000000000000000e+00,1.000000009186998495e+00,0.000000000000000000e+00 +2.249555686063262883e+01,1.200900000000000034e+02,0.000000000000000000e+00,2.812207404348151307e+00,0.000000000000000000e+00,9.752004868210095712e-01,0.000000000000000000e+00,1.000000009011879243e+00,0.000000000000000000e+00 +2.249911278612536947e+01,1.201000000000000085e+02,0.000000000000000000e+00,2.815675144619772752e+00,0.000000000000000000e+00,9.787564123457973553e-01,0.000000000000000000e+00,1.000000008889203817e+00,0.000000000000000000e+00 +2.250266433219740492e+01,1.201099999999999994e+02,0.000000000000000000e+00,2.819151243111518212e+00,0.000000000000000000e+00,9.823079584494024408e-01,0.000000000000000000e+00,1.000000008654405415e+00,0.000000000000000000e+00 +2.250621149910604046e+01,1.201200000000000045e+02,0.000000000000000000e+00,2.822635653395817901e+00,0.000000000000000000e+00,9.858551253887352095e-01,0.000000000000000000e+00,1.000000008178290489e+00,0.000000000000000000e+00 +2.250975428720480664e+01,1.201299999999999955e+02,0.000000000000000000e+00,2.826128329201151423e+00,0.000000000000000000e+00,9.893979135164739924e-01,0.000000000000000000e+00,1.000000007524307843e+00,0.000000000000000000e+00 +2.251329269694249291e+01,1.201400000000000006e+02,0.000000000000000000e+00,2.829629224412785859e+00,0.000000000000000000e+00,9.929363232807856265e-01,0.000000000000000000e+00,1.000000005933884495e+00,0.000000000000000000e+00 +2.251682672886219549e+01,1.201500000000000057e+02,0.000000000000000000e+00,2.833138293073492964e+00,0.000000000000000000e+00,9.964703552214594362e-01,0.000000000000000000e+00,9.999999980817710910e-01,0.000000000000000000e+00 +2.252035638360035108e+01,1.201599999999999966e+02,0.000000000000000000e+00,2.836655489384233064e+00,0.000000000000000000e+00,1.000000009952845437e+00,0.000000000000000000e+00,7.113306633457638325e-09,0.000000000000000000e+00 +2.252388166188579177e+01,1.201700000000000017e+02,0.000000000000000000e+00,2.840180767704759468e+00,0.000000000000000000e+00,1.000000009977921822e+00,0.000000000000000000e+00,-5.587530794018784076e-11,0.000000000000000000e+00 +2.252740256453878942e+01,1.201800000000000068e+02,0.000000000000000000e+00,2.843701670392886793e+00,0.000000000000000000e+00,1.000000009977725091e+00,0.000000000000000000e+00,5.518686085722331054e-11,0.000000000000000000e+00 +2.253091910781902030e+01,1.201899999999999977e+02,0.000000000000000000e+00,2.847218213708204271e+00,0.000000000000000000e+00,1.000000009977919158e+00,0.000000000000000000e+00,-4.672027786712635947e-11,0.000000000000000000e+00 +2.253443130788568638e+01,1.202000000000000028e+02,0.000000000000000000e+00,2.850730413809915209e+00,0.000000000000000000e+00,1.000000009977755067e+00,0.000000000000000000e+00,2.392699586062691954e-11,0.000000000000000000e+00 +2.253793918079838221e+01,1.202100000000000080e+02,0.000000000000000000e+00,2.854238286757611043e+00,0.000000000000000000e+00,1.000000009977838999e+00,0.000000000000000000e+00,-1.888629273980075911e-11,0.000000000000000000e+00 +2.254144274251794755e+01,1.202199999999999989e+02,0.000000000000000000e+00,2.857741848512133753e+00,0.000000000000000000e+00,1.000000009977772830e+00,0.000000000000000000e+00,8.693282388309294100e-12,0.000000000000000000e+00 +2.254494200890732003e+01,1.202300000000000040e+02,0.000000000000000000e+00,2.861241114936420527e+00,0.000000000000000000e+00,1.000000009977803250e+00,0.000000000000000000e+00,-6.607360790797661211e-12,0.000000000000000000e+00 +2.254843699573237359e+01,1.202400000000000091e+02,0.000000000000000000e+00,2.864736101796344858e+00,0.000000000000000000e+00,1.000000009977780158e+00,0.000000000000000000e+00,1.990990483285450781e-11,0.000000000000000000e+00 +2.255192771866274271e+01,1.202500000000000000e+02,0.000000000000000000e+00,2.868226824761544780e+00,0.000000000000000000e+00,1.000000009977849658e+00,0.000000000000000000e+00,-3.744820837780579129e-11,0.000000000000000000e+00 +2.255541419327265373e+01,1.202600000000000051e+02,0.000000000000000000e+00,2.871713299406244424e+00,0.000000000000000000e+00,1.000000009977719095e+00,0.000000000000000000e+00,2.180757681984192429e-11,0.000000000000000000e+00 +2.255889643504172781e+01,1.202699999999999960e+02,0.000000000000000000e+00,2.875195541210064043e+00,0.000000000000000000e+00,1.000000009977795035e+00,0.000000000000000000e+00,-1.583285711914896621e-11,0.000000000000000000e+00 +2.256237445935578734e+01,1.202800000000000011e+02,0.000000000000000000e+00,2.878673565558825143e+00,0.000000000000000000e+00,1.000000009977739968e+00,0.000000000000000000e+00,1.732215562691855907e-11,0.000000000000000000e+00 +2.256584828150764466e+01,1.202900000000000063e+02,0.000000000000000000e+00,2.882147387745341849e+00,0.000000000000000000e+00,1.000000009977800142e+00,0.000000000000000000e+00,1.023944444876200666e-12,0.000000000000000000e+00 +2.256931791669789078e+01,1.202999999999999972e+02,0.000000000000000000e+00,2.885617022970208279e+00,0.000000000000000000e+00,1.000000009977803694e+00,0.000000000000000000e+00,-4.741444119544700641e-12,0.000000000000000000e+00 +2.257278338003567697e+01,1.203100000000000023e+02,0.000000000000000000e+00,2.889082486342573919e+00,0.000000000000000000e+00,1.000000009977787263e+00,0.000000000000000000e+00,-2.643001338616147588e-11,0.000000000000000000e+00 +2.257624468653947858e+01,1.203200000000000074e+02,0.000000000000000000e+00,2.892543792880912790e+00,0.000000000000000000e+00,1.000000009977695781e+00,0.000000000000000000e+00,3.603155702261311249e-11,0.000000000000000000e+00 +2.257970185113785533e+01,1.203299999999999983e+02,0.000000000000000000e+00,2.896000957513783280e+00,0.000000000000000000e+00,1.000000009977820348e+00,0.000000000000000000e+00,-8.359538050157585002e-12,0.000000000000000000e+00 +2.258315488867020093e+01,1.203400000000000034e+02,0.000000000000000000e+00,2.899453995080581326e+00,0.000000000000000000e+00,1.000000009977791482e+00,0.000000000000000000e+00,-1.886357782329395921e-11,0.000000000000000000e+00 +2.258660381388748917e+01,1.203500000000000085e+02,0.000000000000000000e+00,2.902902920332282033e+00,0.000000000000000000e+00,1.000000009977726423e+00,0.000000000000000000e+00,-1.463182825823645634e-11,0.000000000000000000e+00 +2.259004864145301283e+01,1.203599999999999994e+02,0.000000000000000000e+00,2.906347747932177317e+00,0.000000000000000000e+00,1.000000009977676019e+00,0.000000000000000000e+00,4.007554180653643020e-11,0.000000000000000000e+00 +2.259348938594310852e+01,1.203700000000000045e+02,0.000000000000000000e+00,2.909788492456603759e+00,0.000000000000000000e+00,1.000000009977813908e+00,0.000000000000000000e+00,-3.547104570863880365e-11,0.000000000000000000e+00 +2.259692606184787778e+01,1.203799999999999955e+02,0.000000000000000000e+00,2.913225168395663367e+00,0.000000000000000000e+00,1.000000009977692006e+00,0.000000000000000000e+00,2.904428032767587324e-11,0.000000000000000000e+00 +2.260035868357189770e+01,1.203900000000000006e+02,0.000000000000000000e+00,2.916657790153934116e+00,0.000000000000000000e+00,1.000000009977791704e+00,0.000000000000000000e+00,-2.992041945429052761e-11,0.000000000000000000e+00 +2.260378726543493144e+01,1.204000000000000057e+02,0.000000000000000000e+00,2.920086372051178270e+00,0.000000000000000000e+00,1.000000009977689119e+00,0.000000000000000000e+00,3.559657942311604187e-11,0.000000000000000000e+00 +2.260721182167262100e+01,1.204099999999999966e+02,0.000000000000000000e+00,2.923510928323036939e+00,0.000000000000000000e+00,1.000000009977811022e+00,0.000000000000000000e+00,-4.180524899233341830e-11,0.000000000000000000e+00 +2.261063236643717644e+01,1.204200000000000017e+02,0.000000000000000000e+00,2.926931473121723304e+00,0.000000000000000000e+00,1.000000009977668025e+00,0.000000000000000000e+00,6.694066228697115062e-12,0.000000000000000000e+00 +2.261404891379806514e+01,1.204300000000000068e+02,0.000000000000000000e+00,2.930348020516702512e+00,0.000000000000000000e+00,1.000000009977690896e+00,0.000000000000000000e+00,3.097179530100358645e-11,0.000000000000000000e+00 +2.261746147774268323e+01,1.204399999999999977e+02,0.000000000000000000e+00,2.933760584495370694e+00,0.000000000000000000e+00,1.000000009977796589e+00,0.000000000000000000e+00,-5.413347649509187706e-11,0.000000000000000000e+00 +2.262087007217702350e+01,1.204500000000000028e+02,0.000000000000000000e+00,2.937169178963721983e+00,0.000000000000000000e+00,1.000000009977612070e+00,0.000000000000000000e+00,3.117432684317876081e-11,0.000000000000000000e+00 +2.262427471092633979e+01,1.204600000000000080e+02,0.000000000000000000e+00,2.940573817747009322e+00,0.000000000000000000e+00,1.000000009977718207e+00,0.000000000000000000e+00,6.790560936791067676e-12,0.000000000000000000e+00 +2.262767540773580066e+01,1.204699999999999989e+02,0.000000000000000000e+00,2.943974514590402602e+00,0.000000000000000000e+00,1.000000009977741300e+00,0.000000000000000000e+00,-1.974154847164791919e-11,0.000000000000000000e+00 +2.263107217627113954e+01,1.204800000000000040e+02,0.000000000000000000e+00,2.947371283159633482e+00,0.000000000000000000e+00,1.000000009977674242e+00,0.000000000000000000e+00,2.015699507780615148e-11,0.000000000000000000e+00 +2.263446503011929067e+01,1.204900000000000091e+02,0.000000000000000000e+00,2.950764137041637980e+00,0.000000000000000000e+00,1.000000009977742632e+00,0.000000000000000000e+00,-6.552012570363615044e-12,0.000000000000000000e+00 +2.263785398278903216e+01,1.205000000000000000e+02,0.000000000000000000e+00,2.954153089745191973e+00,0.000000000000000000e+00,1.000000009977720428e+00,0.000000000000000000e+00,-1.771075140391435461e-11,0.000000000000000000e+00 +2.264123904771160412e+01,1.205100000000000051e+02,0.000000000000000000e+00,2.957538154701537803e+00,0.000000000000000000e+00,1.000000009977660476e+00,0.000000000000000000e+00,7.420770919558922478e-12,0.000000000000000000e+00 +2.264462023824133752e+01,1.205199999999999960e+02,0.000000000000000000e+00,2.960919345265006886e+00,0.000000000000000000e+00,1.000000009977685567e+00,0.000000000000000000e+00,-1.867175512105272281e-11,0.000000000000000000e+00 +2.264799756765626881e+01,1.205300000000000011e+02,0.000000000000000000e+00,2.964296674713635227e+00,0.000000000000000000e+00,1.000000009977622506e+00,0.000000000000000000e+00,1.296665985514225140e-11,0.000000000000000000e+00 +2.265137104915874389e+01,1.205400000000000063e+02,0.000000000000000000e+00,2.967670156249771374e+00,0.000000000000000000e+00,1.000000009977666249e+00,0.000000000000000000e+00,1.080686441723349741e-11,0.000000000000000000e+00 +2.265474069587603267e+01,1.205499999999999972e+02,0.000000000000000000e+00,2.971039803000680379e+00,0.000000000000000000e+00,1.000000009977702664e+00,0.000000000000000000e+00,-1.147883845136462213e-11,0.000000000000000000e+00 +2.265810652086090826e+01,1.205600000000000023e+02,0.000000000000000000e+00,2.974405628019139325e+00,0.000000000000000000e+00,1.000000009977664028e+00,0.000000000000000000e+00,1.948329631552883277e-11,0.000000000000000000e+00 +2.266146853709225084e+01,1.205700000000000074e+02,0.000000000000000000e+00,2.977767644284027959e+00,0.000000000000000000e+00,1.000000009977729531e+00,0.000000000000000000e+00,-4.423409536493704580e-11,0.000000000000000000e+00 +2.266482675747563036e+01,1.205799999999999983e+02,0.000000000000000000e+00,2.981125864700914008e+00,0.000000000000000000e+00,1.000000009977580984e+00,0.000000000000000000e+00,4.991049578039172945e-11,0.000000000000000000e+00 +2.266818119484387850e+01,1.205900000000000034e+02,0.000000000000000000e+00,2.984480302102630045e+00,0.000000000000000000e+00,1.000000009977748405e+00,0.000000000000000000e+00,-3.505618195314788195e-11,0.000000000000000000e+00 +2.267153186195766423e+01,1.206000000000000085e+02,0.000000000000000000e+00,2.987830969249849034e+00,0.000000000000000000e+00,1.000000009977630944e+00,0.000000000000000000e+00,-1.074759430382766752e-11,0.000000000000000000e+00 +2.267487877150606934e+01,1.206099999999999994e+02,0.000000000000000000e+00,2.991177878831647430e+00,0.000000000000000000e+00,1.000000009977594972e+00,0.000000000000000000e+00,5.512651756035030325e-12,0.000000000000000000e+00 +2.267822193610713555e+01,1.206200000000000045e+02,0.000000000000000000e+00,2.994521043466069621e+00,0.000000000000000000e+00,1.000000009977613402e+00,0.000000000000000000e+00,3.650395658778276161e-11,0.000000000000000000e+00 +2.268156136830842939e+01,1.206299999999999955e+02,0.000000000000000000e+00,2.997860475700682148e+00,0.000000000000000000e+00,1.000000009977735305e+00,0.000000000000000000e+00,-3.847507545795534317e-11,0.000000000000000000e+00 +2.268489708058758936e+01,1.206400000000000006e+02,0.000000000000000000e+00,3.001196188013123933e+00,0.000000000000000000e+00,1.000000009977606963e+00,0.000000000000000000e+00,-1.132879017178803015e-11,0.000000000000000000e+00 +2.268822908535286942e+01,1.206500000000000057e+02,0.000000000000000000e+00,3.004528192811649401e+00,0.000000000000000000e+00,1.000000009977569215e+00,0.000000000000000000e+00,1.140808161205857446e-11,0.000000000000000000e+00 +2.269155739494368262e+01,1.206599999999999966e+02,0.000000000000000000e+00,3.007856502435669821e+00,0.000000000000000000e+00,1.000000009977607185e+00,0.000000000000000000e+00,4.033984984877269210e-11,0.000000000000000000e+00 +2.269488202163112689e+01,1.206700000000000017e+02,0.000000000000000000e+00,3.011181129156285774e+00,0.000000000000000000e+00,1.000000009977741300e+00,0.000000000000000000e+00,-4.192225606616231842e-11,0.000000000000000000e+00 +2.269820297761852146e+01,1.206800000000000068e+02,0.000000000000000000e+00,3.014502085176815616e+00,0.000000000000000000e+00,1.000000009977602078e+00,0.000000000000000000e+00,-4.685477471841383871e-12,0.000000000000000000e+00 +2.270152027504192560e+01,1.206899999999999977e+02,0.000000000000000000e+00,3.017819382633317282e+00,0.000000000000000000e+00,1.000000009977586535e+00,0.000000000000000000e+00,1.943262486400558789e-12,0.000000000000000000e+00 +2.270483392597065375e+01,1.207000000000000028e+02,0.000000000000000000e+00,3.021133033595108763e+00,0.000000000000000000e+00,1.000000009977592974e+00,0.000000000000000000e+00,4.024957745223523263e-12,0.000000000000000000e+00 +2.270814394240779777e+01,1.207100000000000080e+02,0.000000000000000000e+00,3.024443050065279248e+00,0.000000000000000000e+00,1.000000009977606297e+00,0.000000000000000000e+00,-2.887713427331006658e-12,0.000000000000000000e+00 +2.271145033629072429e+01,1.207199999999999989e+02,0.000000000000000000e+00,3.027749443981197164e+00,0.000000000000000000e+00,1.000000009977596749e+00,0.000000000000000000e+00,2.225297870323608688e-11,0.000000000000000000e+00 +2.271475311949158638e+01,1.207300000000000040e+02,0.000000000000000000e+00,3.031052227215012884e+00,0.000000000000000000e+00,1.000000009977670246e+00,0.000000000000000000e+00,-4.354496299115136585e-11,0.000000000000000000e+00 +2.271805230381781371e+01,1.207400000000000091e+02,0.000000000000000000e+00,3.034351411574156998e+00,0.000000000000000000e+00,1.000000009977526583e+00,0.000000000000000000e+00,3.786538845373224497e-11,0.000000000000000000e+00 +2.272134790101260648e+01,1.207500000000000000e+02,0.000000000000000000e+00,3.037647008801831916e+00,0.000000000000000000e+00,1.000000009977651372e+00,0.000000000000000000e+00,-3.783906459137903798e-11,0.000000000000000000e+00 +2.272463992275542921e+01,1.207600000000000051e+02,0.000000000000000000e+00,3.040939030577502589e+00,0.000000000000000000e+00,1.000000009977526805e+00,0.000000000000000000e+00,2.160717138066205442e-11,0.000000000000000000e+00 +2.272792838066249388e+01,1.207699999999999960e+02,0.000000000000000000e+00,3.044227488517376568e+00,0.000000000000000000e+00,1.000000009977597859e+00,0.000000000000000000e+00,-4.799275458927303869e-12,0.000000000000000000e+00 +2.273121328628722893e+01,1.207800000000000011e+02,0.000000000000000000e+00,3.047512394174885841e+00,0.000000000000000000e+00,1.000000009977582094e+00,0.000000000000000000e+00,3.992433744855322642e-12,0.000000000000000000e+00 +2.273449465112076240e+01,1.207900000000000063e+02,0.000000000000000000e+00,3.050793759041158459e+00,0.000000000000000000e+00,1.000000009977595194e+00,0.000000000000000000e+00,-2.750293917432223521e-11,0.000000000000000000e+00 +2.273777248659238737e+01,1.207999999999999972e+02,0.000000000000000000e+00,3.054071594545489265e+00,0.000000000000000000e+00,1.000000009977505044e+00,0.000000000000000000e+00,3.587361238098915277e-11,0.000000000000000000e+00 +2.274104680407003087e+01,1.208100000000000023e+02,0.000000000000000000e+00,3.057345912055803971e+00,0.000000000000000000e+00,1.000000009977622506e+00,0.000000000000000000e+00,-2.511808511097884763e-12,0.000000000000000000e+00 +2.274431761486071224e+01,1.208200000000000074e+02,0.000000000000000000e+00,3.060616722879121010e+00,0.000000000000000000e+00,1.000000009977614290e+00,0.000000000000000000e+00,-1.420350270912554311e-11,0.000000000000000000e+00 +2.274758493021099781e+01,1.208299999999999983e+02,0.000000000000000000e+00,3.063884038262005394e+00,0.000000000000000000e+00,1.000000009977567883e+00,0.000000000000000000e+00,-4.898296229846374551e-12,0.000000000000000000e+00 +2.275084876130744860e+01,1.208400000000000034e+02,0.000000000000000000e+00,3.067147869391021686e+00,0.000000000000000000e+00,1.000000009977551896e+00,0.000000000000000000e+00,-3.738929566611639138e-11,0.000000000000000000e+00 +2.275410911927707858e+01,1.208500000000000085e+02,0.000000000000000000e+00,3.070408227393181200e+00,0.000000000000000000e+00,1.000000009977429993e+00,0.000000000000000000e+00,5.576858819206491872e-11,0.000000000000000000e+00 +2.275736601518778457e+01,1.208599999999999994e+02,0.000000000000000000e+00,3.073665123336384308e+00,0.000000000000000000e+00,1.000000009977611626e+00,0.000000000000000000e+00,-4.251917422234558032e-11,0.000000000000000000e+00 +2.276061946004880099e+01,1.208700000000000045e+02,0.000000000000000000e+00,3.076918568229860984e+00,0.000000000000000000e+00,1.000000009977473292e+00,0.000000000000000000e+00,3.320415995843789305e-11,0.000000000000000000e+00 +2.276386946481111551e+01,1.208799999999999955e+02,0.000000000000000000e+00,3.080168573024602008e+00,0.000000000000000000e+00,1.000000009977581206e+00,0.000000000000000000e+00,-1.449941805467459809e-11,0.000000000000000000e+00 +2.276711604036791314e+01,1.208900000000000006e+02,0.000000000000000000e+00,3.083415148613793288e+00,0.000000000000000000e+00,1.000000009977534132e+00,0.000000000000000000e+00,2.457913957592764991e-11,0.000000000000000000e+00 +2.277035919755499904e+01,1.209000000000000057e+02,0.000000000000000000e+00,3.086658305833239080e+00,0.000000000000000000e+00,1.000000009977613846e+00,0.000000000000000000e+00,-6.127259867072334103e-11,0.000000000000000000e+00 +2.277359894715122124e+01,1.209099999999999966e+02,0.000000000000000000e+00,3.089898055461786530e+00,0.000000000000000000e+00,1.000000009977415338e+00,0.000000000000000000e+00,6.051359602115659281e-11,0.000000000000000000e+00 +2.277683529987888633e+01,1.209200000000000017e+02,0.000000000000000000e+00,3.093134408221741793e+00,0.000000000000000000e+00,1.000000009977611182e+00,0.000000000000000000e+00,-4.917586862799898913e-11,0.000000000000000000e+00 +2.278006826640417515e+01,1.209300000000000068e+02,0.000000000000000000e+00,3.096367374779287918e+00,0.000000000000000000e+00,1.000000009977452198e+00,0.000000000000000000e+00,4.723342575892731746e-11,0.000000000000000000e+00 +2.278329785733755486e+01,1.209399999999999977e+02,0.000000000000000000e+00,3.099596965744890742e+00,0.000000000000000000e+00,1.000000009977604742e+00,0.000000000000000000e+00,-3.778485822434218462e-11,0.000000000000000000e+00 +2.278652408323418399e+01,1.209500000000000028e+02,0.000000000000000000e+00,3.102823191673710124e+00,0.000000000000000000e+00,1.000000009977482840e+00,0.000000000000000000e+00,9.507719066514308387e-12,0.000000000000000000e+00 +2.278974695459431743e+01,1.209600000000000080e+02,0.000000000000000000e+00,3.106046063065998730e+00,0.000000000000000000e+00,1.000000009977513482e+00,0.000000000000000000e+00,-3.510475124147912340e-11,0.000000000000000000e+00 +2.279296648186370078e+01,1.209699999999999989e+02,0.000000000000000000e+00,3.109265590367504384e+00,0.000000000000000000e+00,1.000000009977400461e+00,0.000000000000000000e+00,4.390916331584133446e-11,0.000000000000000000e+00 +2.279618267543397181e+01,1.209800000000000040e+02,0.000000000000000000e+00,3.112481783969863081e+00,0.000000000000000000e+00,1.000000009977541682e+00,0.000000000000000000e+00,-1.036664682086917376e-12,0.000000000000000000e+00 +2.279939554564304416e+01,1.209900000000000091e+02,0.000000000000000000e+00,3.115694654210992898e+00,0.000000000000000000e+00,1.000000009977538351e+00,0.000000000000000000e+00,-2.774210986130860984e-11,0.000000000000000000e+00 +2.280260510277550878e+01,1.210000000000000000e+02,0.000000000000000000e+00,3.118904211375479463e+00,0.000000000000000000e+00,1.000000009977449311e+00,0.000000000000000000e+00,2.167637221185458962e-11,0.000000000000000000e+00 +2.280581135706299989e+01,1.210100000000000051e+02,0.000000000000000000e+00,3.122110465694961867e+00,0.000000000000000000e+00,1.000000009977518811e+00,0.000000000000000000e+00,-1.469685303961591959e-11,0.000000000000000000e+00 +2.280901431868459284e+01,1.210199999999999960e+02,0.000000000000000000e+00,3.125313427348514139e+00,0.000000000000000000e+00,1.000000009977471738e+00,0.000000000000000000e+00,-4.094358012930728856e-12,0.000000000000000000e+00 +2.281221399776717362e+01,1.210300000000000011e+02,0.000000000000000000e+00,3.128513106463020943e+00,0.000000000000000000e+00,1.000000009977458637e+00,0.000000000000000000e+00,2.431343098545773458e-12,0.000000000000000000e+00 +2.281541040438581192e+01,1.210400000000000063e+02,0.000000000000000000e+00,3.131709513113552834e+00,0.000000000000000000e+00,1.000000009977466409e+00,0.000000000000000000e+00,2.545087877780095068e-11,0.000000000000000000e+00 +2.281860354856413409e+01,1.210499999999999972e+02,0.000000000000000000e+00,3.134902657323736186e+00,0.000000000000000000e+00,1.000000009977547677e+00,0.000000000000000000e+00,-2.081303783851400378e-11,0.000000000000000000e+00 +2.282179344027469270e+01,1.210600000000000023e+02,0.000000000000000000e+00,3.138092549066120451e+00,0.000000000000000000e+00,1.000000009977481286e+00,0.000000000000000000e+00,-2.647826777047170107e-11,0.000000000000000000e+00 +2.282498008943931822e+01,1.210700000000000074e+02,0.000000000000000000e+00,3.141279198262540984e+00,0.000000000000000000e+00,1.000000009977396909e+00,0.000000000000000000e+00,5.370781558738172360e-12,0.000000000000000000e+00 +2.282816350592949561e+01,1.210799999999999983e+02,0.000000000000000000e+00,3.144462614784480525e+00,0.000000000000000000e+00,1.000000009977414006e+00,0.000000000000000000e+00,4.140390986878010238e-11,0.000000000000000000e+00 +2.283134369956671250e+01,1.210900000000000034e+02,0.000000000000000000e+00,3.147642808453426255e+00,0.000000000000000000e+00,1.000000009977545679e+00,0.000000000000000000e+00,-2.942441007200740986e-11,0.000000000000000000e+00 +2.283452068012281089e+01,1.211000000000000085e+02,0.000000000000000000e+00,3.150819789041223284e+00,0.000000000000000000e+00,1.000000009977452198e+00,0.000000000000000000e+00,-3.917886197386722185e-12,0.000000000000000000e+00 +2.283769445732034598e+01,1.211099999999999994e+02,0.000000000000000000e+00,3.153993566270424154e+00,0.000000000000000000e+00,1.000000009977439763e+00,0.000000000000000000e+00,-2.668246842916292315e-11,0.000000000000000000e+00 +2.284086504083292724e+01,1.211200000000000045e+02,0.000000000000000000e+00,3.157164149814638332e+00,0.000000000000000000e+00,1.000000009977355164e+00,0.000000000000000000e+00,2.180207238283388182e-11,0.000000000000000000e+00 +2.284403244028556301e+01,1.211299999999999955e+02,0.000000000000000000e+00,3.160331549298875053e+00,0.000000000000000000e+00,1.000000009977424220e+00,0.000000000000000000e+00,3.663054456946063857e-11,0.000000000000000000e+00 +2.284719666525500159e+01,1.211400000000000006e+02,0.000000000000000000e+00,3.163495774299885710e+00,0.000000000000000000e+00,1.000000009977540127e+00,0.000000000000000000e+00,-5.036474504500661297e-11,0.000000000000000000e+00 +2.285035772527007580e+01,1.211500000000000057e+02,0.000000000000000000e+00,3.166656834346500915e+00,0.000000000000000000e+00,1.000000009977380921e+00,0.000000000000000000e+00,-6.257937684869010060e-12,0.000000000000000000e+00 +2.285351562981203344e+01,1.211599999999999966e+02,0.000000000000000000e+00,3.169814738919964903e+00,0.000000000000000000e+00,1.000000009977361159e+00,0.000000000000000000e+00,3.343241241597867807e-11,0.000000000000000000e+00 +2.285667038831486053e+01,1.211700000000000017e+02,0.000000000000000000e+00,3.172969497454269927e+00,0.000000000000000000e+00,1.000000009977466631e+00,0.000000000000000000e+00,4.297698626858591803e-12,0.000000000000000000e+00 +2.285982201016562954e+01,1.211800000000000068e+02,0.000000000000000000e+00,3.176121119336484000e+00,0.000000000000000000e+00,1.000000009977480175e+00,0.000000000000000000e+00,-4.421858305789728529e-11,0.000000000000000000e+00 +2.286297050470480841e+01,1.211899999999999977e+02,0.000000000000000000e+00,3.179269613907076408e+00,0.000000000000000000e+00,1.000000009977340953e+00,0.000000000000000000e+00,4.913340070976268714e-11,0.000000000000000000e+00 +2.286611588122659100e+01,1.212000000000000028e+02,0.000000000000000000e+00,3.182414990460241455e+00,0.000000000000000000e+00,1.000000009977495496e+00,0.000000000000000000e+00,-2.932548028946602508e-11,0.000000000000000000e+00 +2.286925814897921683e+01,1.212100000000000080e+02,0.000000000000000000e+00,3.185557258244220424e+00,0.000000000000000000e+00,1.000000009977403348e+00,0.000000000000000000e+00,-4.003520644260635775e-11,0.000000000000000000e+00 +2.287239731716529079e+01,1.212199999999999989e+02,0.000000000000000000e+00,3.188696426461615996e+00,0.000000000000000000e+00,1.000000009977277671e+00,0.000000000000000000e+00,4.538490493115378697e-11,0.000000000000000000e+00 +2.287553339494209581e+01,1.212300000000000040e+02,0.000000000000000000e+00,3.191832504269709325e+00,0.000000000000000000e+00,1.000000009977420001e+00,0.000000000000000000e+00,-6.945546036494920383e-12,0.000000000000000000e+00 +2.287866639142189840e+01,1.212400000000000091e+02,0.000000000000000000e+00,3.194965500780772238e+00,0.000000000000000000e+00,1.000000009977398241e+00,0.000000000000000000e+00,2.674531693434792127e-11,0.000000000000000000e+00 +2.288179631567227190e+01,1.212500000000000000e+02,0.000000000000000000e+00,3.198095425062374098e+00,0.000000000000000000e+00,1.000000009977481952e+00,0.000000000000000000e+00,-3.365968018708288279e-11,0.000000000000000000e+00 +2.288492317671639142e+01,1.212600000000000051e+02,0.000000000000000000e+00,3.201222286137690443e+00,0.000000000000000000e+00,1.000000009977376703e+00,0.000000000000000000e+00,-4.904617550838277632e-12,0.000000000000000000e+00 +2.288804698353333933e+01,1.212699999999999960e+02,0.000000000000000000e+00,3.204346092985804972e+00,0.000000000000000000e+00,1.000000009977361382e+00,0.000000000000000000e+00,-2.476047012665150435e-11,0.000000000000000000e+00 +2.289116774505841079e+01,1.212800000000000011e+02,0.000000000000000000e+00,3.207466854542012413e+00,0.000000000000000000e+00,1.000000009977284110e+00,0.000000000000000000e+00,3.689199680529414705e-11,0.000000000000000000e+00 +2.289428547018340865e+01,1.212900000000000063e+02,0.000000000000000000e+00,3.210584579698115615e+00,0.000000000000000000e+00,1.000000009977399129e+00,0.000000000000000000e+00,-1.782232461443664486e-11,0.000000000000000000e+00 +2.289740016775693832e+01,1.212999999999999972e+02,0.000000000000000000e+00,3.213699277302722646e+00,0.000000000000000000e+00,1.000000009977343618e+00,0.000000000000000000e+00,1.298723947205305800e-11,0.000000000000000000e+00 +2.290051184658470618e+01,1.213100000000000023e+02,0.000000000000000000e+00,3.216810956161538115e+00,0.000000000000000000e+00,1.000000009977384030e+00,0.000000000000000000e+00,-2.785674519729663530e-12,0.000000000000000000e+00 +2.290362051542980737e+01,1.213200000000000074e+02,0.000000000000000000e+00,3.219919625037655830e+00,0.000000000000000000e+00,1.000000009977375370e+00,0.000000000000000000e+00,1.479979166735911301e-11,0.000000000000000000e+00 +2.290672618301301000e+01,1.213299999999999983e+02,0.000000000000000000e+00,3.223025292651845675e+00,0.000000000000000000e+00,1.000000009977421334e+00,0.000000000000000000e+00,-5.803965113716828445e-11,0.000000000000000000e+00 +2.290982885801304647e+01,1.213400000000000034e+02,0.000000000000000000e+00,3.226127967682840048e+00,0.000000000000000000e+00,1.000000009977241255e+00,0.000000000000000000e+00,4.763689661644506948e-11,0.000000000000000000e+00 +2.291292854906689769e+01,1.213500000000000085e+02,0.000000000000000000e+00,3.229227658767615861e+00,0.000000000000000000e+00,1.000000009977388915e+00,0.000000000000000000e+00,-2.437910770993732721e-11,0.000000000000000000e+00 +2.291602526477006307e+01,1.213599999999999994e+02,0.000000000000000000e+00,3.232324374501677866e+00,0.000000000000000000e+00,1.000000009977313420e+00,0.000000000000000000e+00,3.480942915320004085e-11,0.000000000000000000e+00 +2.291911901367685189e+01,1.213700000000000045e+02,0.000000000000000000e+00,3.235418123439333549e+00,0.000000000000000000e+00,1.000000009977421112e+00,0.000000000000000000e+00,-5.222819900430931793e-11,0.000000000000000000e+00 +2.292220980430065325e+01,1.213799999999999955e+02,0.000000000000000000e+00,3.238508914093972013e+00,0.000000000000000000e+00,1.000000009977259685e+00,0.000000000000000000e+00,5.443537283087743666e-11,0.000000000000000000e+00 +2.292529764511420964e+01,1.213900000000000006e+02,0.000000000000000000e+00,3.241596754938334879e+00,0.000000000000000000e+00,1.000000009977427773e+00,0.000000000000000000e+00,-3.937191517147707024e-11,0.000000000000000000e+00 +2.292838254454988700e+01,1.214000000000000057e+02,0.000000000000000000e+00,3.244681654404790727e+00,0.000000000000000000e+00,1.000000009977306314e+00,0.000000000000000000e+00,-2.110959684255239559e-11,0.000000000000000000e+00 +2.293146451099994820e+01,1.214099999999999966e+02,0.000000000000000000e+00,3.247763620885600222e+00,0.000000000000000000e+00,1.000000009977241255e+00,0.000000000000000000e+00,5.545631119787734296e-11,0.000000000000000000e+00 +2.293454355281681245e+01,1.214200000000000017e+02,0.000000000000000000e+00,3.250842662733185673e+00,0.000000000000000000e+00,1.000000009977412008e+00,0.000000000000000000e+00,-4.901239787348983582e-11,0.000000000000000000e+00 +2.293761967831332882e+01,1.214300000000000068e+02,0.000000000000000000e+00,3.253918788260394823e+00,0.000000000000000000e+00,1.000000009977261239e+00,0.000000000000000000e+00,3.670376767930872998e-11,0.000000000000000000e+00 +2.294069289576303206e+01,1.214399999999999977e+02,0.000000000000000000e+00,3.256992005740760643e+00,0.000000000000000000e+00,1.000000009977374038e+00,0.000000000000000000e+00,-2.176824484507664293e-11,0.000000000000000000e+00 +2.294376321340040192e+01,1.214500000000000028e+02,0.000000000000000000e+00,3.260062323408764673e+00,0.000000000000000000e+00,1.000000009977307203e+00,0.000000000000000000e+00,-4.661782374071875112e-11,0.000000000000000000e+00 +2.294683063942112256e+01,1.214600000000000080e+02,0.000000000000000000e+00,3.263129749460091489e+00,0.000000000000000000e+00,1.000000009977164206e+00,0.000000000000000000e+00,8.781671515180345959e-11,0.000000000000000000e+00 +2.294989518198234180e+01,1.214699999999999989e+02,0.000000000000000000e+00,3.266194292051885828e+00,0.000000000000000000e+00,1.000000009977433324e+00,0.000000000000000000e+00,-6.955059475183841933e-11,0.000000000000000000e+00 +2.295295684920291635e+01,1.214800000000000040e+02,0.000000000000000000e+00,3.269255959303007053e+00,0.000000000000000000e+00,1.000000009977220383e+00,0.000000000000000000e+00,1.226805894920986231e-11,0.000000000000000000e+00 +2.295601564916366755e+01,1.214900000000000091e+02,0.000000000000000000e+00,3.272314759294276065e+00,0.000000000000000000e+00,1.000000009977257909e+00,0.000000000000000000e+00,-1.453199675835692860e-12,0.000000000000000000e+00 +2.295907158990763008e+01,1.215000000000000000e+02,0.000000000000000000e+00,3.275370700068729324e+00,0.000000000000000000e+00,1.000000009977253468e+00,0.000000000000000000e+00,1.272737187889622263e-11,0.000000000000000000e+00 +2.296212467944030067e+01,1.215100000000000051e+02,0.000000000000000000e+00,3.278423789631862650e+00,0.000000000000000000e+00,1.000000009977292326e+00,0.000000000000000000e+00,1.732536030046601628e-11,0.000000000000000000e+00 +2.296517492572988317e+01,1.215199999999999960e+02,0.000000000000000000e+00,3.281474035951877255e+00,0.000000000000000000e+00,1.000000009977345172e+00,0.000000000000000000e+00,-4.583105381014653268e-11,0.000000000000000000e+00 +2.296822233670752311e+01,1.215300000000000011e+02,0.000000000000000000e+00,3.284521446959922208e+00,0.000000000000000000e+00,1.000000009977205506e+00,0.000000000000000000e+00,2.909947965561452407e-11,0.000000000000000000e+00 +2.297126692026755990e+01,1.215400000000000063e+02,0.000000000000000000e+00,3.287566030550334695e+00,0.000000000000000000e+00,1.000000009977294102e+00,0.000000000000000000e+00,-7.299863004185023447e-12,0.000000000000000000e+00 +2.297430868426775774e+01,1.215499999999999972e+02,0.000000000000000000e+00,3.290607794580880707e+00,0.000000000000000000e+00,1.000000009977271898e+00,0.000000000000000000e+00,-1.315191073879692496e-12,0.000000000000000000e+00 +2.297734763652954726e+01,1.215600000000000023e+02,0.000000000000000000e+00,3.293646746872989528e+00,0.000000000000000000e+00,1.000000009977267901e+00,0.000000000000000000e+00,-2.003861984441355415e-11,0.000000000000000000e+00 +2.298038378483825639e+01,1.215700000000000074e+02,0.000000000000000000e+00,3.296682895211989983e+00,0.000000000000000000e+00,1.000000009977207061e+00,0.000000000000000000e+00,3.015883882245473303e-11,0.000000000000000000e+00 +2.298341713694334487e+01,1.215799999999999983e+02,0.000000000000000000e+00,3.299716247347342701e+00,0.000000000000000000e+00,1.000000009977298543e+00,0.000000000000000000e+00,-3.238464122040708806e-11,0.000000000000000000e+00 +2.298644770055863873e+01,1.215900000000000034e+02,0.000000000000000000e+00,3.302746810992871929e+00,0.000000000000000000e+00,1.000000009977200399e+00,0.000000000000000000e+00,5.822855459865695731e-11,0.000000000000000000e+00 +2.298947548336255053e+01,1.216000000000000085e+02,0.000000000000000000e+00,3.305774593826992902e+00,0.000000000000000000e+00,1.000000009977376703e+00,0.000000000000000000e+00,-5.145546189739218067e-11,0.000000000000000000e+00 +2.299250049299831744e+01,1.216099999999999994e+02,0.000000000000000000e+00,3.308799603492941444e+00,0.000000000000000000e+00,1.000000009977221049e+00,0.000000000000000000e+00,-2.813905215810034363e-11,0.000000000000000000e+00 +2.299552273707421790e+01,1.216200000000000045e+02,0.000000000000000000e+00,3.311821847598996005e+00,0.000000000000000000e+00,1.000000009977136006e+00,0.000000000000000000e+00,3.176807790523131241e-11,0.000000000000000000e+00 +2.299854222316379904e+01,1.216299999999999955e+02,0.000000000000000000e+00,3.314841333718704153e+00,0.000000000000000000e+00,1.000000009977231930e+00,0.000000000000000000e+00,3.518283792120025940e-11,0.000000000000000000e+00 +2.300155895880610046e+01,1.216400000000000006e+02,0.000000000000000000e+00,3.317858069391103282e+00,0.000000000000000000e+00,1.000000009977338067e+00,0.000000000000000000e+00,-6.063143745091710029e-11,0.000000000000000000e+00 +2.300457295150586390e+01,1.216500000000000057e+02,0.000000000000000000e+00,3.320872062120939550e+00,0.000000000000000000e+00,1.000000009977155324e+00,0.000000000000000000e+00,4.453785619242917011e-11,0.000000000000000000e+00 +2.300758420873376764e+01,1.216599999999999966e+02,0.000000000000000000e+00,3.323883319378885481e+00,0.000000000000000000e+00,1.000000009977289439e+00,0.000000000000000000e+00,-3.535261217063570380e-11,0.000000000000000000e+00 +2.301059273792662552e+01,1.216700000000000017e+02,0.000000000000000000e+00,3.326891848601758905e+00,0.000000000000000000e+00,1.000000009977183080e+00,0.000000000000000000e+00,-4.949413187212266994e-12,0.000000000000000000e+00 +2.301359854648761072e+01,1.216800000000000068e+02,0.000000000000000000e+00,3.329897657192733895e+00,0.000000000000000000e+00,1.000000009977168203e+00,0.000000000000000000e+00,3.364205434281272914e-11,0.000000000000000000e+00 +2.301660164178646895e+01,1.216899999999999977e+02,0.000000000000000000e+00,3.332900752521556154e+00,0.000000000000000000e+00,1.000000009977269233e+00,0.000000000000000000e+00,-2.938008944466514181e-11,0.000000000000000000e+00 +2.301960203115973158e+01,1.217000000000000028e+02,0.000000000000000000e+00,3.335901141924753066e+00,0.000000000000000000e+00,1.000000009977181081e+00,0.000000000000000000e+00,-1.807353996751447846e-11,0.000000000000000000e+00 +2.302259972191091109e+01,1.217100000000000080e+02,0.000000000000000000e+00,3.338898832705841979e+00,0.000000000000000000e+00,1.000000009977126902e+00,0.000000000000000000e+00,3.588300845413233555e-11,0.000000000000000000e+00 +2.302559472131072837e+01,1.217199999999999989e+02,0.000000000000000000e+00,3.341893832135539366e+00,0.000000000000000000e+00,1.000000009977234372e+00,0.000000000000000000e+00,-1.165017708182957580e-11,0.000000000000000000e+00 +2.302858703659730111e+01,1.217300000000000040e+02,0.000000000000000000e+00,3.344886147451966441e+00,0.000000000000000000e+00,1.000000009977199511e+00,0.000000000000000000e+00,-2.309840300934865828e-11,0.000000000000000000e+00 +2.303157667497635686e+01,1.217400000000000091e+02,0.000000000000000000e+00,3.347875785860852105e+00,0.000000000000000000e+00,1.000000009977130455e+00,0.000000000000000000e+00,2.393676374994756251e-11,0.000000000000000000e+00 +2.303456364362143916e+01,1.217500000000000000e+02,0.000000000000000000e+00,3.350862754535736787e+00,0.000000000000000000e+00,1.000000009977201954e+00,0.000000000000000000e+00,-1.584807322521335180e-11,0.000000000000000000e+00 +2.303754794967409936e+01,1.217600000000000051e+02,0.000000000000000000e+00,3.353847060618173614e+00,0.000000000000000000e+00,1.000000009977154658e+00,0.000000000000000000e+00,3.991611540169117998e-11,0.000000000000000000e+00 +2.304052960024410268e+01,1.217699999999999960e+02,0.000000000000000000e+00,3.356828711217926475e+00,0.000000000000000000e+00,1.000000009977273674e+00,0.000000000000000000e+00,-4.733072226644504344e-11,0.000000000000000000e+00 +2.304350860240962362e+01,1.217800000000000011e+02,0.000000000000000000e+00,3.359807713413169417e+00,0.000000000000000000e+00,1.000000009977132676e+00,0.000000000000000000e+00,9.474545139631029984e-12,0.000000000000000000e+00 +2.304648496321743778e+01,1.217900000000000063e+02,0.000000000000000000e+00,3.362784074250680710e+00,0.000000000000000000e+00,1.000000009977160875e+00,0.000000000000000000e+00,-2.829947752005530482e-11,0.000000000000000000e+00 +2.304945868968312794e+01,1.217999999999999972e+02,0.000000000000000000e+00,3.365757800746040029e+00,0.000000000000000000e+00,1.000000009977076720e+00,0.000000000000000000e+00,2.421408690093589357e-11,0.000000000000000000e+00 +2.305242978879126525e+01,1.218100000000000023e+02,0.000000000000000000e+00,3.368728899883819405e+00,0.000000000000000000e+00,1.000000009977148663e+00,0.000000000000000000e+00,2.139303102148320685e-11,0.000000000000000000e+00 +2.305539826749560461e+01,1.218200000000000074e+02,0.000000000000000000e+00,3.371697378617776408e+00,0.000000000000000000e+00,1.000000009977212168e+00,0.000000000000000000e+00,-1.227814228273594468e-11,0.000000000000000000e+00 +2.305836413271928009e+01,1.218299999999999983e+02,0.000000000000000000e+00,3.374663243871042884e+00,0.000000000000000000e+00,1.000000009977175752e+00,0.000000000000000000e+00,-3.416925496336088749e-11,0.000000000000000000e+00 +2.306132739135498610e+01,1.218400000000000034e+02,0.000000000000000000e+00,3.377626502536313691e+00,0.000000000000000000e+00,1.000000009977074500e+00,0.000000000000000000e+00,1.477467972409782429e-11,0.000000000000000000e+00 +2.306428805026516926e+01,1.218500000000000085e+02,0.000000000000000000e+00,3.380587161476034108e+00,0.000000000000000000e+00,1.000000009977118243e+00,0.000000000000000000e+00,5.930065011408174041e-12,0.000000000000000000e+00 +2.306724611628220956e+01,1.218599999999999994e+02,0.000000000000000000e+00,3.383545227522585908e+00,0.000000000000000000e+00,1.000000009977135784e+00,0.000000000000000000e+00,2.637055851152209381e-11,0.000000000000000000e+00 +2.307020159620860511e+01,1.218700000000000045e+02,0.000000000000000000e+00,3.386500707478470318e+00,0.000000000000000000e+00,1.000000009977213722e+00,0.000000000000000000e+00,-2.895023714931024488e-11,0.000000000000000000e+00 +2.307315449681716402e+01,1.218799999999999955e+02,0.000000000000000000e+00,3.389453608116491434e+00,0.000000000000000000e+00,1.000000009977128235e+00,0.000000000000000000e+00,-7.526098873259481247e-14,0.000000000000000000e+00 +2.307610482485117487e+01,1.218900000000000006e+02,0.000000000000000000e+00,3.392403936179936519e+00,0.000000000000000000e+00,1.000000009977128013e+00,0.000000000000000000e+00,-2.448111223204384091e-11,0.000000000000000000e+00 +2.307905258702458440e+01,1.219000000000000057e+02,0.000000000000000000e+00,3.395351698382757188e+00,0.000000000000000000e+00,1.000000009977055848e+00,0.000000000000000000e+00,2.246680188817821240e-11,0.000000000000000000e+00 +2.308199779002218932e+01,1.219099999999999966e+02,0.000000000000000000e+00,3.398296901409746607e+00,0.000000000000000000e+00,1.000000009977122017e+00,0.000000000000000000e+00,1.539329925498630070e-11,0.000000000000000000e+00 +2.308494044049979976e+01,1.219200000000000017e+02,0.000000000000000000e+00,3.401239551916717563e+00,0.000000000000000000e+00,1.000000009977167315e+00,0.000000000000000000e+00,-1.450035633716617055e-11,0.000000000000000000e+00 +2.308788054508442400e+01,1.219300000000000068e+02,0.000000000000000000e+00,3.404179656530677001e+00,0.000000000000000000e+00,1.000000009977124682e+00,0.000000000000000000e+00,-3.265400420329750018e-11,0.000000000000000000e+00 +2.309081811037443899e+01,1.219399999999999977e+02,0.000000000000000000e+00,3.407117221850000544e+00,0.000000000000000000e+00,1.000000009977028759e+00,0.000000000000000000e+00,4.773716903965997143e-11,0.000000000000000000e+00 +2.309375314293976089e+01,1.219500000000000028e+02,0.000000000000000000e+00,3.410052254444605691e+00,0.000000000000000000e+00,1.000000009977168869e+00,0.000000000000000000e+00,-4.770257345354748517e-11,0.000000000000000000e+00 +2.309668564932202273e+01,1.219600000000000080e+02,0.000000000000000000e+00,3.412984760856124122e+00,0.000000000000000000e+00,1.000000009977028981e+00,0.000000000000000000e+00,2.311396301160324202e-11,0.000000000000000000e+00 +2.309961563603473422e+01,1.219699999999999989e+02,0.000000000000000000e+00,3.415914747598069567e+00,0.000000000000000000e+00,1.000000009977096704e+00,0.000000000000000000e+00,-1.994816708746443461e-11,0.000000000000000000e+00 +2.310254310956346657e+01,1.219800000000000040e+02,0.000000000000000000e+00,3.418842221156009664e+00,0.000000000000000000e+00,1.000000009977038307e+00,0.000000000000000000e+00,5.443001322033811031e-11,0.000000000000000000e+00 +2.310546807636600519e+01,1.219900000000000091e+02,0.000000000000000000e+00,3.421767187987731162e+00,0.000000000000000000e+00,1.000000009977197513e+00,0.000000000000000000e+00,-4.649883853621286796e-11,0.000000000000000000e+00 +2.310839054287252381e+01,1.220000000000000000e+02,0.000000000000000000e+00,3.424689654523408233e+00,0.000000000000000000e+00,1.000000009977061621e+00,0.000000000000000000e+00,-7.604338613294921069e-13,0.000000000000000000e+00 +2.311131051548574789e+01,1.220100000000000051e+02,0.000000000000000000e+00,3.427609627165765005e+00,0.000000000000000000e+00,1.000000009977059401e+00,0.000000000000000000e+00,-1.461277872962411646e-11,0.000000000000000000e+00 +2.311422800058111804e+01,1.220199999999999960e+02,0.000000000000000000e+00,3.430527112290242098e+00,0.000000000000000000e+00,1.000000009977016768e+00,0.000000000000000000e+00,7.236435354664405591e-12,0.000000000000000000e+00 +2.311714300450694992e+01,1.220300000000000011e+02,0.000000000000000000e+00,3.433442116245157383e+00,0.000000000000000000e+00,1.000000009977037863e+00,0.000000000000000000e+00,4.398917010813753520e-11,0.000000000000000000e+00 +2.312005553358460119e+01,1.220400000000000063e+02,0.000000000000000000e+00,3.436354645351868076e+00,0.000000000000000000e+00,1.000000009977165982e+00,0.000000000000000000e+00,-4.364497334966063046e-11,0.000000000000000000e+00 +2.312296559410862784e+01,1.220499999999999972e+02,0.000000000000000000e+00,3.439264705904930608e+00,0.000000000000000000e+00,1.000000009977038973e+00,0.000000000000000000e+00,9.927712247118436364e-12,0.000000000000000000e+00 +2.312587319234694760e+01,1.220600000000000023e+02,0.000000000000000000e+00,3.442172304172258279e+00,0.000000000000000000e+00,1.000000009977067839e+00,0.000000000000000000e+00,-1.734996841855857062e-11,0.000000000000000000e+00 +2.312877833454098564e+01,1.220700000000000074e+02,0.000000000000000000e+00,3.445077446395281129e+00,0.000000000000000000e+00,1.000000009977017434e+00,0.000000000000000000e+00,2.065394323406634883e-12,0.000000000000000000e+00 +2.313168102690584504e+01,1.220799999999999983e+02,0.000000000000000000e+00,3.447980138789100479e+00,0.000000000000000000e+00,1.000000009977023430e+00,0.000000000000000000e+00,1.990574008037629230e-11,0.000000000000000000e+00 +2.313458127563045252e+01,1.220900000000000034e+02,0.000000000000000000e+00,3.450880387542645256e+00,0.000000000000000000e+00,1.000000009977081161e+00,0.000000000000000000e+00,-3.256559832255643894e-11,0.000000000000000000e+00 +2.313747908687772181e+01,1.221000000000000085e+02,0.000000000000000000e+00,3.453778198818825640e+00,0.000000000000000000e+00,1.000000009976986792e+00,0.000000000000000000e+00,1.901894182825422706e-11,0.000000000000000000e+00 +2.314037446678469578e+01,1.221099999999999994e+02,0.000000000000000000e+00,3.456673578754685394e+00,0.000000000000000000e+00,1.000000009977041859e+00,0.000000000000000000e+00,8.980167914047724901e-12,0.000000000000000000e+00 +2.314326742146270277e+01,1.221200000000000045e+02,0.000000000000000000e+00,3.459566533461555071e+00,0.000000000000000000e+00,1.000000009977067839e+00,0.000000000000000000e+00,-4.063662065070611552e-11,0.000000000000000000e+00 +2.314615795699750933e+01,1.221299999999999955e+02,0.000000000000000000e+00,3.462457069025201228e+00,0.000000000000000000e+00,1.000000009976950377e+00,0.000000000000000000e+00,2.721622488344002440e-11,0.000000000000000000e+00 +2.314904607944946946e+01,1.221400000000000006e+02,0.000000000000000000e+00,3.465345191505976086e+00,0.000000000000000000e+00,1.000000009977028981e+00,0.000000000000000000e+00,-3.016287919589061554e-11,0.000000000000000000e+00 +2.315193179485367025e+01,1.221500000000000057e+02,0.000000000000000000e+00,3.468230906938967184e+00,0.000000000000000000e+00,1.000000009976941939e+00,0.000000000000000000e+00,5.059569887186701904e-11,0.000000000000000000e+00 +2.315481510922007757e+01,1.221599999999999966e+02,0.000000000000000000e+00,3.471114221334142602e+00,0.000000000000000000e+00,1.000000009977087823e+00,0.000000000000000000e+00,-3.044431634406899140e-11,0.000000000000000000e+00 +2.315769602853369236e+01,1.221700000000000017e+02,0.000000000000000000e+00,3.473995140676499283e+00,0.000000000000000000e+00,1.000000009977000115e+00,0.000000000000000000e+00,-1.558191394616443544e-11,0.000000000000000000e+00 +2.316057455875467852e+01,1.221800000000000068e+02,0.000000000000000000e+00,3.476873670926205584e+00,0.000000000000000000e+00,1.000000009976955262e+00,0.000000000000000000e+00,5.473629178102522783e-11,0.000000000000000000e+00 +2.316345070581852639e+01,1.221899999999999977e+02,0.000000000000000000e+00,3.479749818018747387e+00,0.000000000000000000e+00,1.000000009977112692e+00,0.000000000000000000e+00,-5.439524102002652744e-11,0.000000000000000000e+00 +2.316632447563617703e+01,1.222000000000000028e+02,0.000000000000000000e+00,3.482623587865070647e+00,0.000000000000000000e+00,1.000000009976956372e+00,0.000000000000000000e+00,-2.087904002409255447e-11,0.000000000000000000e+00 +2.316919587409417858e+01,1.222100000000000080e+02,0.000000000000000000e+00,3.485494986351721280e+00,0.000000000000000000e+00,1.000000009976896420e+00,0.000000000000000000e+00,6.679062132745128387e-11,0.000000000000000000e+00 +2.317206490705482125e+01,1.222199999999999989e+02,0.000000000000000000e+00,3.488364019340988609e+00,0.000000000000000000e+00,1.000000009977088045e+00,0.000000000000000000e+00,-7.908384311299585901e-11,0.000000000000000000e+00 +2.317493158035627587e+01,1.222300000000000040e+02,0.000000000000000000e+00,3.491230692671044356e+00,0.000000000000000000e+00,1.000000009976861337e+00,0.000000000000000000e+00,8.015660438113992224e-11,0.000000000000000000e+00 +2.317779589981273247e+01,1.222400000000000091e+02,0.000000000000000000e+00,3.494095012156078983e+00,0.000000000000000000e+00,1.000000009977090931e+00,0.000000000000000000e+00,-3.568886754105707471e-11,0.000000000000000000e+00 +2.318065787121454235e+01,1.222500000000000000e+02,0.000000000000000000e+00,3.496956983586443801e+00,0.000000000000000000e+00,1.000000009976988791e+00,0.000000000000000000e+00,-1.972260296925113846e-11,0.000000000000000000e+00 +2.318351750032834957e+01,1.222600000000000051e+02,0.000000000000000000e+00,3.499816612728782861e+00,0.000000000000000000e+00,1.000000009976932391e+00,0.000000000000000000e+00,7.926577050250923553e-12,0.000000000000000000e+00 +2.318637479289723302e+01,1.222699999999999960e+02,0.000000000000000000e+00,3.502673905326171955e+00,0.000000000000000000e+00,1.000000009976955040e+00,0.000000000000000000e+00,-7.855273419242600257e-12,0.000000000000000000e+00 +2.318922975464083081e+01,1.222800000000000011e+02,0.000000000000000000e+00,3.505528867098252288e+00,0.000000000000000000e+00,1.000000009976932613e+00,0.000000000000000000e+00,-1.478929167461435535e-12,0.000000000000000000e+00 +2.319208239125548232e+01,1.222900000000000063e+02,0.000000000000000000e+00,3.508381503741363705e+00,0.000000000000000000e+00,1.000000009976928395e+00,0.000000000000000000e+00,-6.699547790351029441e-12,0.000000000000000000e+00 +2.319493270841435972e+01,1.222999999999999972e+02,0.000000000000000000e+00,3.511231820928677916e+00,0.000000000000000000e+00,1.000000009976909299e+00,0.000000000000000000e+00,6.471095684569944615e-12,0.000000000000000000e+00 +2.319778071176759582e+01,1.223100000000000023e+02,0.000000000000000000e+00,3.514079824310329947e+00,0.000000000000000000e+00,1.000000009976927728e+00,0.000000000000000000e+00,2.130171132900748819e-11,0.000000000000000000e+00 +2.320062640694242262e+01,1.223200000000000074e+02,0.000000000000000000e+00,3.516925519513549148e+00,0.000000000000000000e+00,1.000000009976988347e+00,0.000000000000000000e+00,-2.678536177731832300e-11,0.000000000000000000e+00 +2.320346979954329214e+01,1.223299999999999983e+02,0.000000000000000000e+00,3.519768912142788864e+00,0.000000000000000000e+00,1.000000009976912185e+00,0.000000000000000000e+00,2.274297979795284590e-11,0.000000000000000000e+00 +2.320631089515201140e+01,1.223400000000000034e+02,0.000000000000000000e+00,3.522610007779854779e+00,0.000000000000000000e+00,1.000000009976976800e+00,0.000000000000000000e+00,6.257412379859514290e-12,0.000000000000000000e+00 +2.320914969932786676e+01,1.223500000000000085e+02,0.000000000000000000e+00,3.525448811984034148e+00,0.000000000000000000e+00,1.000000009976994564e+00,0.000000000000000000e+00,-7.186167237719016549e-11,0.000000000000000000e+00 +2.321198621760775538e+01,1.223599999999999994e+02,0.000000000000000000e+00,3.528285330292221467e+00,0.000000000000000000e+00,1.000000009976790727e+00,0.000000000000000000e+00,7.231120946160008899e-11,0.000000000000000000e+00 +2.321482045550630247e+01,1.223700000000000045e+02,0.000000000000000000e+00,3.531119568219044602e+00,0.000000000000000000e+00,1.000000009976995674e+00,0.000000000000000000e+00,-4.876890827692483056e-11,0.000000000000000000e+00 +2.321765241851599626e+01,1.223799999999999955e+02,0.000000000000000000e+00,3.533951531256992240e+00,0.000000000000000000e+00,1.000000009976857562e+00,0.000000000000000000e+00,1.765563461059878534e-11,0.000000000000000000e+00 +2.322048211210730528e+01,1.223900000000000006e+02,0.000000000000000000e+00,3.536781224876534235e+00,0.000000000000000000e+00,1.000000009976907522e+00,0.000000000000000000e+00,5.497262328487848324e-12,0.000000000000000000e+00 +2.322330954172880979e+01,1.224000000000000057e+02,0.000000000000000000e+00,3.539608654526248621e+00,0.000000000000000000e+00,1.000000009976923065e+00,0.000000000000000000e+00,-2.059191633842776553e-11,0.000000000000000000e+00 +2.322613471280731545e+01,1.224099999999999966e+02,0.000000000000000000e+00,3.542433825632941957e+00,0.000000000000000000e+00,1.000000009976864890e+00,0.000000000000000000e+00,5.812813779521573101e-11,0.000000000000000000e+00 +2.322895763074798126e+01,1.224200000000000017e+02,0.000000000000000000e+00,3.545256743601771454e+00,0.000000000000000000e+00,1.000000009977028981e+00,0.000000000000000000e+00,-8.840313643487339262e-11,0.000000000000000000e+00 +2.323177830093443319e+01,1.224300000000000068e+02,0.000000000000000000e+00,3.548077413816366654e+00,0.000000000000000000e+00,1.000000009976779625e+00,0.000000000000000000e+00,4.277924760436950901e-11,0.000000000000000000e+00 +2.323459672872889570e+01,1.224399999999999977e+02,0.000000000000000000e+00,3.550895841638946671e+00,0.000000000000000000e+00,1.000000009976900195e+00,0.000000000000000000e+00,5.519200850006594257e-13,0.000000000000000000e+00 +2.323741291947229470e+01,1.224500000000000028e+02,0.000000000000000000e+00,3.553712032410443200e+00,0.000000000000000000e+00,1.000000009976901749e+00,0.000000000000000000e+00,-2.130522977485548690e-12,0.000000000000000000e+00 +2.324022687848439261e+01,1.224600000000000080e+02,0.000000000000000000e+00,3.556525991450615098e+00,0.000000000000000000e+00,1.000000009976895754e+00,0.000000000000000000e+00,1.832121188131236421e-11,0.000000000000000000e+00 +2.324303861106389135e+01,1.224699999999999989e+02,0.000000000000000000e+00,3.559337724058167396e+00,0.000000000000000000e+00,1.000000009976947268e+00,0.000000000000000000e+00,-1.904699490347146560e-11,0.000000000000000000e+00 +2.324584812248856025e+01,1.224800000000000040e+02,0.000000000000000000e+00,3.562147235510867649e+00,0.000000000000000000e+00,1.000000009976893756e+00,0.000000000000000000e+00,-3.567209645928051876e-11,0.000000000000000000e+00 +2.324865541801534619e+01,1.224900000000000091e+02,0.000000000000000000e+00,3.564954531065660959e+00,0.000000000000000000e+00,1.000000009976793613e+00,0.000000000000000000e+00,3.918315656109565417e-11,0.000000000000000000e+00 +2.325146050288048372e+01,1.225000000000000000e+02,0.000000000000000000e+00,3.567759615958785435e+00,0.000000000000000000e+00,1.000000009976903526e+00,0.000000000000000000e+00,-1.766609956896501321e-11,0.000000000000000000e+00 +2.325426338229961942e+01,1.225100000000000051e+02,0.000000000000000000e+00,3.570562495405886771e+00,0.000000000000000000e+00,1.000000009976854010e+00,0.000000000000000000e+00,1.149595001046174307e-11,0.000000000000000000e+00 +2.325706406146792204e+01,1.225199999999999960e+02,0.000000000000000000e+00,3.573363174602129710e+00,0.000000000000000000e+00,1.000000009976886206e+00,0.000000000000000000e+00,-6.387240415583393837e-11,0.000000000000000000e+00 +2.325986254556018551e+01,1.225300000000000011e+02,0.000000000000000000e+00,3.576161658722312175e+00,0.000000000000000000e+00,1.000000009976707460e+00,0.000000000000000000e+00,6.296954503086190746e-11,0.000000000000000000e+00 +2.326265883973094972e+01,1.225400000000000063e+02,0.000000000000000000e+00,3.578957952920975405e+00,0.000000000000000000e+00,1.000000009976883542e+00,0.000000000000000000e+00,3.814503862558256619e-12,0.000000000000000000e+00 +2.326545294911461426e+01,1.225499999999999972e+02,0.000000000000000000e+00,3.581752062332517195e+00,0.000000000000000000e+00,1.000000009976894200e+00,0.000000000000000000e+00,-2.020084152914901098e-11,0.000000000000000000e+00 +2.326824487882554138e+01,1.225600000000000023e+02,0.000000000000000000e+00,3.584543992071298923e+00,0.000000000000000000e+00,1.000000009976837800e+00,0.000000000000000000e+00,-3.064325320040084751e-11,0.000000000000000000e+00 +2.327103463395816618e+01,1.225700000000000074e+02,0.000000000000000000e+00,3.587333747231756576e+00,0.000000000000000000e+00,1.000000009976752313e+00,0.000000000000000000e+00,4.866908919340058759e-11,0.000000000000000000e+00 +2.327382221958710673e+01,1.225799999999999983e+02,0.000000000000000000e+00,3.590121332888509098e+00,0.000000000000000000e+00,1.000000009976887982e+00,0.000000000000000000e+00,-9.566004875929869572e-12,0.000000000000000000e+00 +2.327660764076727418e+01,1.225900000000000034e+02,0.000000000000000000e+00,3.592906754096466759e+00,0.000000000000000000e+00,1.000000009976861337e+00,0.000000000000000000e+00,-5.081894021950915255e-11,0.000000000000000000e+00 +2.327939090253397580e+01,1.226000000000000085e+02,0.000000000000000000e+00,3.595690015890936397e+00,0.000000000000000000e+00,1.000000009976719895e+00,0.000000000000000000e+00,6.075851160176621063e-11,0.000000000000000000e+00 +2.328217200990302160e+01,1.226099999999999994e+02,0.000000000000000000e+00,3.598471123287728890e+00,0.000000000000000000e+00,1.000000009976888871e+00,0.000000000000000000e+00,-1.765836628579071799e-11,0.000000000000000000e+00 +2.328495096787083440e+01,1.226200000000000045e+02,0.000000000000000000e+00,3.601250081283265736e+00,0.000000000000000000e+00,1.000000009976839799e+00,0.000000000000000000e+00,-1.887146037622079808e-11,0.000000000000000000e+00 +2.328772778141454580e+01,1.226299999999999955e+02,0.000000000000000000e+00,3.604026894854681196e+00,0.000000000000000000e+00,1.000000009976787396e+00,0.000000000000000000e+00,1.592506908734318061e-11,0.000000000000000000e+00 +2.329050245549210985e+01,1.226400000000000006e+02,0.000000000000000000e+00,3.606801568959928428e+00,0.000000000000000000e+00,1.000000009976831583e+00,0.000000000000000000e+00,-3.475779399694476090e-11,0.000000000000000000e+00 +2.329327499504240251e+01,1.226500000000000057e+02,0.000000000000000000e+00,3.609574108537882520e+00,0.000000000000000000e+00,1.000000009976735216e+00,0.000000000000000000e+00,3.045648536136081453e-11,0.000000000000000000e+00 +2.329604540498532117e+01,1.226599999999999966e+02,0.000000000000000000e+00,3.612344518508442182e+00,0.000000000000000000e+00,1.000000009976819593e+00,0.000000000000000000e+00,-1.572119158472006577e-11,0.000000000000000000e+00 +2.329881369022189475e+01,1.226700000000000017e+02,0.000000000000000000e+00,3.615112803772633221e+00,0.000000000000000000e+00,1.000000009976776072e+00,0.000000000000000000e+00,3.732630768369992115e-11,0.000000000000000000e+00 +2.330157985563437251e+01,1.226800000000000068e+02,0.000000000000000000e+00,3.617878969212708018e+00,0.000000000000000000e+00,1.000000009976879323e+00,0.000000000000000000e+00,-8.900902010750399953e-11,0.000000000000000000e+00 +2.330434390608633421e+01,1.226899999999999977e+02,0.000000000000000000e+00,3.620643019692247666e+00,0.000000000000000000e+00,1.000000009976633297e+00,0.000000000000000000e+00,5.482899777376177550e-11,0.000000000000000000e+00 +2.330710584642278960e+01,1.227000000000000028e+02,0.000000000000000000e+00,3.623404960056259672e+00,0.000000000000000000e+00,1.000000009976784732e+00,0.000000000000000000e+00,1.947029205270600243e-11,0.000000000000000000e+00 +2.330986568147027782e+01,1.227100000000000080e+02,0.000000000000000000e+00,3.626164795131280538e+00,0.000000000000000000e+00,1.000000009976838466e+00,0.000000000000000000e+00,-3.349508570004406428e-11,0.000000000000000000e+00 +2.331262341603695631e+01,1.227199999999999989e+02,0.000000000000000000e+00,3.628922529725470802e+00,0.000000000000000000e+00,1.000000009976746096e+00,0.000000000000000000e+00,3.021685010311639739e-11,0.000000000000000000e+00 +2.331537905491270735e+01,1.227300000000000040e+02,0.000000000000000000e+00,3.631678168628714065e+00,0.000000000000000000e+00,1.000000009976829363e+00,0.000000000000000000e+00,-3.612647557872747702e-11,0.000000000000000000e+00 +2.331813260286923750e+01,1.227400000000000091e+02,0.000000000000000000e+00,3.634431716612715135e+00,0.000000000000000000e+00,1.000000009976729887e+00,0.000000000000000000e+00,1.686642445202352095e-11,0.000000000000000000e+00 +2.332088406466016650e+01,1.227500000000000000e+02,0.000000000000000000e+00,3.637183178431094621e+00,0.000000000000000000e+00,1.000000009976776294e+00,0.000000000000000000e+00,-1.938280564547284959e-12,0.000000000000000000e+00 +2.332363344502113023e+01,1.227600000000000051e+02,0.000000000000000000e+00,3.639932558819486630e+00,0.000000000000000000e+00,1.000000009976770965e+00,0.000000000000000000e+00,-2.343859422232810384e-11,0.000000000000000000e+00 +2.332638074866986599e+01,1.227699999999999960e+02,0.000000000000000000e+00,3.642679862495632470e+00,0.000000000000000000e+00,1.000000009976706572e+00,0.000000000000000000e+00,-1.043400260107710877e-11,0.000000000000000000e+00 +2.332912598030631912e+01,1.227800000000000011e+02,0.000000000000000000e+00,3.645425094159475687e+00,0.000000000000000000e+00,1.000000009976677928e+00,0.000000000000000000e+00,4.079612753074836600e-11,0.000000000000000000e+00 +2.333186914461273176e+01,1.227900000000000063e+02,0.000000000000000000e+00,3.648168258493256211e+00,0.000000000000000000e+00,1.000000009976789839e+00,0.000000000000000000e+00,-1.879330104804644951e-11,0.000000000000000000e+00 +2.333461024625373170e+01,1.227999999999999972e+02,0.000000000000000000e+00,3.650909360161603612e+00,0.000000000000000000e+00,1.000000009976738324e+00,0.000000000000000000e+00,-1.832102281876851507e-11,0.000000000000000000e+00 +2.333734928987642832e+01,1.228100000000000023e+02,0.000000000000000000e+00,3.653648403811628587e+00,0.000000000000000000e+00,1.000000009976688142e+00,0.000000000000000000e+00,5.889841372768694696e-11,0.000000000000000000e+00 +2.334008628011050845e+01,1.228200000000000074e+02,0.000000000000000000e+00,3.656385394073016215e+00,0.000000000000000000e+00,1.000000009976849347e+00,0.000000000000000000e+00,-1.032712187156920475e-10,0.000000000000000000e+00 +2.334282122156832529e+01,1.228299999999999983e+02,0.000000000000000000e+00,3.659120335558117443e+00,0.000000000000000000e+00,1.000000009976566906e+00,0.000000000000000000e+00,9.132364325131368142e-11,0.000000000000000000e+00 +2.334555411884498000e+01,1.228400000000000034e+02,0.000000000000000000e+00,3.661853232862037455e+00,0.000000000000000000e+00,1.000000009976816484e+00,0.000000000000000000e+00,-4.634640099990508453e-11,0.000000000000000000e+00 +2.334828497651842838e+01,1.228500000000000085e+02,0.000000000000000000e+00,3.664584090562730267e+00,0.000000000000000000e+00,1.000000009976689919e+00,0.000000000000000000e+00,4.312615970998849379e-12,0.000000000000000000e+00 +2.335101379914955544e+01,1.228599999999999994e+02,0.000000000000000000e+00,3.667312913221083104e+00,0.000000000000000000e+00,1.000000009976701687e+00,0.000000000000000000e+00,1.074885301977486114e-11,0.000000000000000000e+00 +2.335374059128227842e+01,1.228700000000000045e+02,0.000000000000000000e+00,3.670039705381009210e+00,0.000000000000000000e+00,1.000000009976730997e+00,0.000000000000000000e+00,-1.792807536169109918e-12,0.000000000000000000e+00 +2.335646535744361785e+01,1.228799999999999955e+02,0.000000000000000000e+00,3.672764471569534450e+00,0.000000000000000000e+00,1.000000009976726112e+00,0.000000000000000000e+00,-4.901260391794815324e-11,0.000000000000000000e+00 +2.335918810214380414e+01,1.228900000000000006e+02,0.000000000000000000e+00,3.675487216296885240e+00,0.000000000000000000e+00,1.000000009976592663e+00,0.000000000000000000e+00,5.190536599563742229e-11,0.000000000000000000e+00 +2.336190882987635220e+01,1.229000000000000057e+02,0.000000000000000000e+00,3.678207944056575585e+00,0.000000000000000000e+00,1.000000009976733883e+00,0.000000000000000000e+00,-3.822278755324320711e-11,0.000000000000000000e+00 +2.336462754511814666e+01,1.229099999999999966e+02,0.000000000000000000e+00,3.680926659325495010e+00,0.000000000000000000e+00,1.000000009976629967e+00,0.000000000000000000e+00,1.879858783404272930e-11,0.000000000000000000e+00 +2.336734425232954138e+01,1.229200000000000017e+02,0.000000000000000000e+00,3.683643366563992050e+00,0.000000000000000000e+00,1.000000009976681037e+00,0.000000000000000000e+00,3.697057774780630579e-11,0.000000000000000000e+00 +2.337005895595442695e+01,1.229300000000000068e+02,0.000000000000000000e+00,3.686358070215962179e+00,0.000000000000000000e+00,1.000000009976781401e+00,0.000000000000000000e+00,-3.364182636597679538e-11,0.000000000000000000e+00 +2.337277166042033372e+01,1.229399999999999977e+02,0.000000000000000000e+00,3.689070774708931300e+00,0.000000000000000000e+00,1.000000009976690141e+00,0.000000000000000000e+00,-4.701853627959554929e-11,0.000000000000000000e+00 +2.337548237013849928e+01,1.229500000000000028e+02,0.000000000000000000e+00,3.691781484454139672e+00,0.000000000000000000e+00,1.000000009976562687e+00,0.000000000000000000e+00,3.803594347899165413e-11,0.000000000000000000e+00 +2.337819108950396441e+01,1.229600000000000080e+02,0.000000000000000000e+00,3.694490203846626741e+00,0.000000000000000000e+00,1.000000009976665716e+00,0.000000000000000000e+00,3.470045042923970562e-11,0.000000000000000000e+00 +2.338089782289564766e+01,1.229699999999999989e+02,0.000000000000000000e+00,3.697196937265314620e+00,0.000000000000000000e+00,1.000000009976759641e+00,0.000000000000000000e+00,-4.983121783919233051e-11,0.000000000000000000e+00 +2.338360257467643777e+01,1.229800000000000040e+02,0.000000000000000000e+00,3.699901689073089361e+00,0.000000000000000000e+00,1.000000009976624860e+00,0.000000000000000000e+00,-1.215883949041301430e-11,0.000000000000000000e+00 +2.338630534919326820e+01,1.229900000000000091e+02,0.000000000000000000e+00,3.702604463616883113e+00,0.000000000000000000e+00,1.000000009976591997e+00,0.000000000000000000e+00,6.026310721177042235e-11,0.000000000000000000e+00 +2.338900615077719891e+01,1.230000000000000000e+02,0.000000000000000000e+00,3.705305265227757161e+00,0.000000000000000000e+00,1.000000009976754756e+00,0.000000000000000000e+00,-9.181812368184554262e-11,0.000000000000000000e+00 +2.339170498374349805e+01,1.230100000000000051e+02,0.000000000000000000e+00,3.708004098220982314e+00,0.000000000000000000e+00,1.000000009976506954e+00,0.000000000000000000e+00,7.657083436963836521e-11,0.000000000000000000e+00 +2.339440185239172720e+01,1.230199999999999960e+02,0.000000000000000000e+00,3.710700966896117503e+00,0.000000000000000000e+00,1.000000009976713455e+00,0.000000000000000000e+00,-3.831326255380617397e-11,0.000000000000000000e+00 +2.339709676100581603e+01,1.230300000000000011e+02,0.000000000000000000e+00,3.713395875537093715e+00,0.000000000000000000e+00,1.000000009976610205e+00,0.000000000000000000e+00,8.410303105161521791e-12,0.000000000000000000e+00 +2.339978971385414397e+01,1.230400000000000063e+02,0.000000000000000000e+00,3.716088828412289047e+00,0.000000000000000000e+00,1.000000009976632853e+00,0.000000000000000000e+00,-1.072678718502467915e-12,0.000000000000000000e+00 +2.340248071518961837e+01,1.230499999999999972e+02,0.000000000000000000e+00,3.718779829774610857e+00,0.000000000000000000e+00,1.000000009976629967e+00,0.000000000000000000e+00,3.038704793028161189e-11,0.000000000000000000e+00 +2.340516976924975268e+01,1.230600000000000023e+02,0.000000000000000000e+00,3.721468883861572596e+00,0.000000000000000000e+00,1.000000009976711679e+00,0.000000000000000000e+00,-3.677177791857388329e-11,0.000000000000000000e+00 +2.340785688025674460e+01,1.230700000000000074e+02,0.000000000000000000e+00,3.724155994895372412e+00,0.000000000000000000e+00,1.000000009976612869e+00,0.000000000000000000e+00,-2.737134151132566045e-11,0.000000000000000000e+00 +2.341054205241755426e+01,1.230799999999999983e+02,0.000000000000000000e+00,3.726841167082969530e+00,0.000000000000000000e+00,1.000000009976539372e+00,0.000000000000000000e+00,-3.558357390622106286e-12,0.000000000000000000e+00 +2.341322528992397878e+01,1.230900000000000034e+02,0.000000000000000000e+00,3.729524404616162414e+00,0.000000000000000000e+00,1.000000009976529824e+00,0.000000000000000000e+00,3.999823333499478255e-11,0.000000000000000000e+00 +2.341590659695273047e+01,1.231000000000000085e+02,0.000000000000000000e+00,3.732205711671664705e+00,0.000000000000000000e+00,1.000000009976637072e+00,0.000000000000000000e+00,-8.121418198921385272e-12,0.000000000000000000e+00 +2.341858597766551497e+01,1.231099999999999994e+02,0.000000000000000000e+00,3.734885092411181162e+00,0.000000000000000000e+00,1.000000009976615312e+00,0.000000000000000000e+00,-6.302764244364705783e-12,0.000000000000000000e+00 +2.342126343620910234e+01,1.231200000000000045e+02,0.000000000000000000e+00,3.737562550981482268e+00,0.000000000000000000e+00,1.000000009976598436e+00,0.000000000000000000e+00,7.054197600129840497e-12,0.000000000000000000e+00 +2.342393897671540870e+01,1.231300000000000097e+02,0.000000000000000000e+00,3.740238091514480168e+00,0.000000000000000000e+00,1.000000009976617310e+00,0.000000000000000000e+00,-1.993199254454126068e-12,0.000000000000000000e+00 +2.342661260330155670e+01,1.231400000000000006e+02,0.000000000000000000e+00,3.742911718127302834e+00,0.000000000000000000e+00,1.000000009976611981e+00,0.000000000000000000e+00,-6.648746829766776816e-13,0.000000000000000000e+00 +2.342928432006996786e+01,1.231500000000000057e+02,0.000000000000000000e+00,3.745583434922367783e+00,0.000000000000000000e+00,1.000000009976610205e+00,0.000000000000000000e+00,-1.447134673596677092e-11,0.000000000000000000e+00 +2.343195413110841940e+01,1.231599999999999966e+02,0.000000000000000000e+00,3.748253245987455795e+00,0.000000000000000000e+00,1.000000009976571569e+00,0.000000000000000000e+00,-3.994941173588403977e-12,0.000000000000000000e+00 +2.343462204049012954e+01,1.231700000000000017e+02,0.000000000000000000e+00,3.750921155395783746e+00,0.000000000000000000e+00,1.000000009976560911e+00,0.000000000000000000e+00,1.174349246537266325e-11,0.000000000000000000e+00 +2.343728805227382495e+01,1.231800000000000068e+02,0.000000000000000000e+00,3.753587167206077435e+00,0.000000000000000000e+00,1.000000009976592219e+00,0.000000000000000000e+00,-4.767412819277342090e-11,0.000000000000000000e+00 +2.343995217050381186e+01,1.231899999999999977e+02,0.000000000000000000e+00,3.756251285462643530e+00,0.000000000000000000e+00,1.000000009976465210e+00,0.000000000000000000e+00,5.271229702535663941e-11,0.000000000000000000e+00 +2.344261439921005064e+01,1.232000000000000028e+02,0.000000000000000000e+00,3.758913514195440619e+00,0.000000000000000000e+00,1.000000009976605542e+00,0.000000000000000000e+00,-1.460631315862053504e-11,0.000000000000000000e+00 +2.344527474240821974e+01,1.232100000000000080e+02,0.000000000000000000e+00,3.761573857420152045e+00,0.000000000000000000e+00,1.000000009976566684e+00,0.000000000000000000e+00,-1.261208143411447308e-11,0.000000000000000000e+00 +2.344793320409980097e+01,1.232199999999999989e+02,0.000000000000000000e+00,3.764232319138254290e+00,0.000000000000000000e+00,1.000000009976533155e+00,0.000000000000000000e+00,-1.730162879768612155e-11,0.000000000000000000e+00 +2.345058978827213281e+01,1.232300000000000040e+02,0.000000000000000000e+00,3.766888903337088923e+00,0.000000000000000000e+00,1.000000009976487192e+00,0.000000000000000000e+00,2.082679222261541240e-11,0.000000000000000000e+00 +2.345324449889849205e+01,1.232400000000000091e+02,0.000000000000000000e+00,3.769543613989931874e+00,0.000000000000000000e+00,1.000000009976542481e+00,0.000000000000000000e+00,2.469170126422404172e-11,0.000000000000000000e+00 +2.345589733993815784e+01,1.232500000000000000e+02,0.000000000000000000e+00,3.772196455056063158e+00,0.000000000000000000e+00,1.000000009976607984e+00,0.000000000000000000e+00,-2.127493513768819070e-11,0.000000000000000000e+00 +2.345854831533648266e+01,1.232600000000000051e+02,0.000000000000000000e+00,3.774847430480835264e+00,0.000000000000000000e+00,1.000000009976551585e+00,0.000000000000000000e+00,-7.795115909086496296e-12,0.000000000000000000e+00 +2.346119742902495986e+01,1.232699999999999960e+02,0.000000000000000000e+00,3.777496544195741546e+00,0.000000000000000000e+00,1.000000009976530935e+00,0.000000000000000000e+00,-1.736259546466542047e-11,0.000000000000000000e+00 +2.346384468492129116e+01,1.232800000000000011e+02,0.000000000000000000e+00,3.780143800118485053e+00,0.000000000000000000e+00,1.000000009976484971e+00,0.000000000000000000e+00,-8.057861151908307709e-12,0.000000000000000000e+00 +2.346649008692946126e+01,1.232900000000000063e+02,0.000000000000000000e+00,3.782789202153045593e+00,0.000000000000000000e+00,1.000000009976463655e+00,0.000000000000000000e+00,5.846037619990961918e-11,0.000000000000000000e+00 +2.346913363893979110e+01,1.232999999999999972e+02,0.000000000000000000e+00,3.785432754189747229e+00,0.000000000000000000e+00,1.000000009976618198e+00,0.000000000000000000e+00,-3.673137602035846408e-11,0.000000000000000000e+00 +2.347177534482901251e+01,1.233100000000000023e+02,0.000000000000000000e+00,3.788074460105325336e+00,0.000000000000000000e+00,1.000000009976521165e+00,0.000000000000000000e+00,-8.411214969206881885e-12,0.000000000000000000e+00 +2.347441520846034280e+01,1.233200000000000074e+02,0.000000000000000000e+00,3.790714323762991445e+00,0.000000000000000000e+00,1.000000009976498960e+00,0.000000000000000000e+00,-2.070600854432882075e-11,0.000000000000000000e+00 +2.347705323368353447e+01,1.233299999999999983e+02,0.000000000000000000e+00,3.793352349012501179e+00,0.000000000000000000e+00,1.000000009976444337e+00,0.000000000000000000e+00,1.221325464332984389e-11,0.000000000000000000e+00 +2.347968942433495343e+01,1.233400000000000034e+02,0.000000000000000000e+00,3.795988539690218655e+00,0.000000000000000000e+00,1.000000009976476534e+00,0.000000000000000000e+00,4.281824180024942095e-11,0.000000000000000000e+00 +2.348232378423763578e+01,1.233500000000000085e+02,0.000000000000000000e+00,3.798622899619182203e+00,0.000000000000000000e+00,1.000000009976589332e+00,0.000000000000000000e+00,-4.613746553897996460e-11,0.000000000000000000e+00 +2.348495631720135890e+01,1.233599999999999994e+02,0.000000000000000000e+00,3.801255432609168761e+00,0.000000000000000000e+00,1.000000009976467874e+00,0.000000000000000000e+00,5.570718520968690324e-12,0.000000000000000000e+00 +2.348758702702270185e+01,1.233700000000000045e+02,0.000000000000000000e+00,3.803886142456757380e+00,0.000000000000000000e+00,1.000000009976482529e+00,0.000000000000000000e+00,3.969772259703576242e-12,0.000000000000000000e+00 +2.349021591748511284e+01,1.233800000000000097e+02,0.000000000000000000e+00,3.806515032945394950e+00,0.000000000000000000e+00,1.000000009976492965e+00,0.000000000000000000e+00,-6.110912595546126999e-11,0.000000000000000000e+00 +2.349284299235896611e+01,1.233900000000000006e+02,0.000000000000000000e+00,3.809142107845458369e+00,0.000000000000000000e+00,1.000000009976332427e+00,0.000000000000000000e+00,1.154516255310389548e-10,0.000000000000000000e+00 +2.349546825540163653e+01,1.234000000000000057e+02,0.000000000000000000e+00,3.811767370914317610e+00,0.000000000000000000e+00,1.000000009976635518e+00,0.000000000000000000e+00,-7.126539639101492668e-11,0.000000000000000000e+00 +2.349809171035754574e+01,1.234099999999999966e+02,0.000000000000000000e+00,3.814390825896400550e+00,0.000000000000000000e+00,1.000000009976448556e+00,0.000000000000000000e+00,-1.084115077076262610e-11,0.000000000000000000e+00 +2.350071336095824037e+01,1.234200000000000017e+02,0.000000000000000000e+00,3.817012476523251152e+00,0.000000000000000000e+00,1.000000009976420134e+00,0.000000000000000000e+00,-3.474942812108434733e-12,0.000000000000000000e+00 +2.350333321092244887e+01,1.234300000000000068e+02,0.000000000000000000e+00,3.819632326513595633e+00,0.000000000000000000e+00,1.000000009976411031e+00,0.000000000000000000e+00,2.807306165477641357e-11,0.000000000000000000e+00 +2.350595126395613477e+01,1.234399999999999977e+02,0.000000000000000000e+00,3.822250379573401968e+00,0.000000000000000000e+00,1.000000009976484527e+00,0.000000000000000000e+00,-4.328421384830327081e-11,0.000000000000000000e+00 +2.350856752375257486e+01,1.234500000000000028e+02,0.000000000000000000e+00,3.824866639395941625e+00,0.000000000000000000e+00,1.000000009976371285e+00,0.000000000000000000e+00,3.448121467452552561e-11,0.000000000000000000e+00 +2.351118199399239828e+01,1.234600000000000080e+02,0.000000000000000000e+00,3.827481109661849512e+00,0.000000000000000000e+00,1.000000009976461435e+00,0.000000000000000000e+00,-1.623254623929012081e-11,0.000000000000000000e+00 +2.351379467834366821e+01,1.234699999999999989e+02,0.000000000000000000e+00,3.830093794039186150e+00,0.000000000000000000e+00,1.000000009976419024e+00,0.000000000000000000e+00,3.537878919424700780e-11,0.000000000000000000e+00 +2.351640558046193163e+01,1.234800000000000040e+02,0.000000000000000000e+00,3.832704696183495852e+00,0.000000000000000000e+00,1.000000009976511395e+00,0.000000000000000000e+00,-4.672162386320486572e-11,0.000000000000000000e+00 +2.351901470399027261e+01,1.234900000000000091e+02,0.000000000000000000e+00,3.835313819737868002e+00,0.000000000000000000e+00,1.000000009976389492e+00,0.000000000000000000e+00,1.064513427334009564e-11,0.000000000000000000e+00 +2.352162205255938687e+01,1.235000000000000000e+02,0.000000000000000000e+00,3.837921168332994792e+00,0.000000000000000000e+00,1.000000009976417248e+00,0.000000000000000000e+00,1.218631256064957664e-11,0.000000000000000000e+00 +2.352422762978762805e+01,1.235100000000000051e+02,0.000000000000000000e+00,3.840526745587232060e+00,0.000000000000000000e+00,1.000000009976449000e+00,0.000000000000000000e+00,1.083015669788475184e-11,0.000000000000000000e+00 +2.352683143928107512e+01,1.235199999999999960e+02,0.000000000000000000e+00,3.843130555106656576e+00,0.000000000000000000e+00,1.000000009976477200e+00,0.000000000000000000e+00,-1.945629805187460482e-11,0.000000000000000000e+00 +2.352943348463358220e+01,1.235300000000000011e+02,0.000000000000000000e+00,3.845732600485124664e+00,0.000000000000000000e+00,1.000000009976426574e+00,0.000000000000000000e+00,-5.217476714883620192e-11,0.000000000000000000e+00 +2.353203376942684599e+01,1.235400000000000063e+02,0.000000000000000000e+00,3.848332885304329931e+00,0.000000000000000000e+00,1.000000009976290904e+00,0.000000000000000000e+00,5.665345310560999633e-11,0.000000000000000000e+00 +2.353463229723045202e+01,1.235499999999999972e+02,0.000000000000000000e+00,3.850931413133861003e+00,0.000000000000000000e+00,1.000000009976438120e+00,0.000000000000000000e+00,-2.360016782054653749e-11,0.000000000000000000e+00 +2.353722907160194566e+01,1.235600000000000023e+02,0.000000000000000000e+00,3.853528187531259697e+00,0.000000000000000000e+00,1.000000009976376836e+00,0.000000000000000000e+00,1.925224073927663814e-11,0.000000000000000000e+00 +2.353982409608687121e+01,1.235700000000000074e+02,0.000000000000000000e+00,3.856123212042075643e+00,0.000000000000000000e+00,1.000000009976426796e+00,0.000000000000000000e+00,2.183389955658319873e-11,0.000000000000000000e+00 +2.354241737421885006e+01,1.235799999999999983e+02,0.000000000000000000e+00,3.858716490199924909e+00,0.000000000000000000e+00,1.000000009976483417e+00,0.000000000000000000e+00,-6.357509265094361697e-11,0.000000000000000000e+00 +2.354500890951961622e+01,1.235900000000000034e+02,0.000000000000000000e+00,3.861308025526545062e+00,0.000000000000000000e+00,1.000000009976318660e+00,0.000000000000000000e+00,3.009412978726849061e-11,0.000000000000000000e+00 +2.354759870549908385e+01,1.236000000000000085e+02,0.000000000000000000e+00,3.863897821531850685e+00,0.000000000000000000e+00,1.000000009976396598e+00,0.000000000000000000e+00,-4.152515099823207915e-11,0.000000000000000000e+00 +2.355018676565540403e+01,1.236099999999999994e+02,0.000000000000000000e+00,3.866485881713990658e+00,0.000000000000000000e+00,1.000000009976289128e+00,0.000000000000000000e+00,8.877224292752097738e-11,0.000000000000000000e+00 +2.355277309347501102e+01,1.236200000000000045e+02,0.000000000000000000e+00,3.869072209559401010e+00,0.000000000000000000e+00,1.000000009976518722e+00,0.000000000000000000e+00,-9.132303266405112844e-11,0.000000000000000000e+00 +2.355535769243268618e+01,1.236300000000000097e+02,0.000000000000000000e+00,3.871656808542862205e+00,0.000000000000000000e+00,1.000000009976282689e+00,0.000000000000000000e+00,1.736554623045578999e-11,0.000000000000000000e+00 +2.355794056599160768e+01,1.236400000000000006e+02,0.000000000000000000e+00,3.874239682127550211e+00,0.000000000000000000e+00,1.000000009976327542e+00,0.000000000000000000e+00,6.632558491138288350e-11,0.000000000000000000e+00 +2.356052171760340030e+01,1.236500000000000057e+02,0.000000000000000000e+00,3.876820833765094676e+00,0.000000000000000000e+00,1.000000009976498738e+00,0.000000000000000000e+00,-1.133709357074825715e-10,0.000000000000000000e+00 +2.356310115070820288e+01,1.236599999999999966e+02,0.000000000000000000e+00,3.879400266895630445e+00,0.000000000000000000e+00,1.000000009976206305e+00,0.000000000000000000e+00,9.234206923807421249e-11,0.000000000000000000e+00 +2.356567886873470741e+01,1.236700000000000017e+02,0.000000000000000000e+00,3.881977984947849958e+00,0.000000000000000000e+00,1.000000009976444337e+00,0.000000000000000000e+00,-5.714876136809597348e-11,0.000000000000000000e+00 +2.356825487510021944e+01,1.236800000000000068e+02,0.000000000000000000e+00,3.884553991339060541e+00,0.000000000000000000e+00,1.000000009976297122e+00,0.000000000000000000e+00,1.474950678301788226e-11,0.000000000000000000e+00 +2.357082917321070781e+01,1.236899999999999977e+02,0.000000000000000000e+00,3.887128289475232368e+00,0.000000000000000000e+00,1.000000009976335091e+00,0.000000000000000000e+00,-4.660825672778979635e-12,0.000000000000000000e+00 +2.357340176646086505e+01,1.237000000000000028e+02,0.000000000000000000e+00,3.889700882751054856e+00,0.000000000000000000e+00,1.000000009976323101e+00,0.000000000000000000e+00,2.046938417015198385e-11,0.000000000000000000e+00 +2.357597265823415000e+01,1.237100000000000080e+02,0.000000000000000000e+00,3.892271774549986851e+00,0.000000000000000000e+00,1.000000009976375726e+00,0.000000000000000000e+00,4.580567126736252606e-12,0.000000000000000000e+00 +2.357854185190284113e+01,1.237199999999999989e+02,0.000000000000000000e+00,3.894840968244309476e+00,0.000000000000000000e+00,1.000000009976387494e+00,0.000000000000000000e+00,-2.473409292753353279e-11,0.000000000000000000e+00 +2.358110935082809334e+01,1.237300000000000040e+02,0.000000000000000000e+00,3.897408467195177195e+00,0.000000000000000000e+00,1.000000009976323989e+00,0.000000000000000000e+00,6.230869367974739839e-12,0.000000000000000000e+00 +2.358367515835998773e+01,1.237400000000000091e+02,0.000000000000000000e+00,3.899974274752669334e+00,0.000000000000000000e+00,1.000000009976339976e+00,0.000000000000000000e+00,-5.213128847272557000e-11,0.000000000000000000e+00 +2.358623927783757779e+01,1.237500000000000000e+02,0.000000000000000000e+00,3.902538394255841592e+00,0.000000000000000000e+00,1.000000009976206305e+00,0.000000000000000000e+00,3.336169744435622185e-11,0.000000000000000000e+00 +2.358880171258894975e+01,1.237600000000000051e+02,0.000000000000000000e+00,3.905100829032775778e+00,0.000000000000000000e+00,1.000000009976291793e+00,0.000000000000000000e+00,3.468426283099979715e-13,0.000000000000000000e+00 +2.359136246593125819e+01,1.237699999999999960e+02,0.000000000000000000e+00,3.907661582400631772e+00,0.000000000000000000e+00,1.000000009976292681e+00,0.000000000000000000e+00,3.774386999265188482e-11,0.000000000000000000e+00 +2.359392154117079343e+01,1.237800000000000011e+02,0.000000000000000000e+00,3.910220657665695931e+00,0.000000000000000000e+00,1.000000009976389270e+00,0.000000000000000000e+00,-2.761014015501419824e-11,0.000000000000000000e+00 +2.359647894160301718e+01,1.237900000000000063e+02,0.000000000000000000e+00,3.912778058123432157e+00,0.000000000000000000e+00,1.000000009976318660e+00,0.000000000000000000e+00,-5.334501124582641117e-11,0.000000000000000000e+00 +2.359903467051261927e+01,1.237999999999999972e+02,0.000000000000000000e+00,3.915333787058530302e+00,0.000000000000000000e+00,1.000000009976182325e+00,0.000000000000000000e+00,8.041753381047600650e-11,0.000000000000000000e+00 +2.360158873117356393e+01,1.238100000000000023e+02,0.000000000000000000e+00,3.917887847744956353e+00,0.000000000000000000e+00,1.000000009976387716e+00,0.000000000000000000e+00,-7.559829517257126033e-11,0.000000000000000000e+00 +2.360414112684914656e+01,1.238200000000000074e+02,0.000000000000000000e+00,3.920440243446002171e+00,0.000000000000000000e+00,1.000000009976194759e+00,0.000000000000000000e+00,2.646358319164009797e-11,0.000000000000000000e+00 +2.360669186079202930e+01,1.238299999999999983e+02,0.000000000000000000e+00,3.922990977414331226e+00,0.000000000000000000e+00,1.000000009976262261e+00,0.000000000000000000e+00,2.386756409870131682e-11,0.000000000000000000e+00 +2.360924093624429787e+01,1.238400000000000034e+02,0.000000000000000000e+00,3.925540052892030563e+00,0.000000000000000000e+00,1.000000009976323101e+00,0.000000000000000000e+00,6.101514931132582094e-12,0.000000000000000000e+00 +2.361178835643751128e+01,1.238500000000000085e+02,0.000000000000000000e+00,3.928087473110656536e+00,0.000000000000000000e+00,1.000000009976338644e+00,0.000000000000000000e+00,-3.122514059258596514e-11,0.000000000000000000e+00 +2.361433412459274095e+01,1.238599999999999994e+02,0.000000000000000000e+00,3.930633241291283220e+00,0.000000000000000000e+00,1.000000009976259152e+00,0.000000000000000000e+00,-4.913728346094253806e-11,0.000000000000000000e+00 +2.361687824392062751e+01,1.238700000000000045e+02,0.000000000000000000e+00,3.933177360644549925e+00,0.000000000000000000e+00,1.000000009976134141e+00,0.000000000000000000e+00,1.020935410565799441e-10,0.000000000000000000e+00 +2.361942071762142348e+01,1.238800000000000097e+02,0.000000000000000000e+00,3.935719834370708714e+00,0.000000000000000000e+00,1.000000009976393711e+00,0.000000000000000000e+00,-7.200980131120057189e-11,0.000000000000000000e+00 +2.362196154888503941e+01,1.238900000000000006e+02,0.000000000000000000e+00,3.938260665659672366e+00,0.000000000000000000e+00,1.000000009976210746e+00,0.000000000000000000e+00,6.033839781827530133e-12,0.000000000000000000e+00 +2.362450074089109364e+01,1.239000000000000057e+02,0.000000000000000000e+00,3.940799857691057895e+00,0.000000000000000000e+00,1.000000009976226067e+00,0.000000000000000000e+00,-6.387743436674303271e-12,0.000000000000000000e+00 +2.362703829680895851e+01,1.239099999999999966e+02,0.000000000000000000e+00,3.943337413634236732e+00,0.000000000000000000e+00,1.000000009976209858e+00,0.000000000000000000e+00,1.751193596193017746e-12,0.000000000000000000e+00 +2.362957421979780293e+01,1.239200000000000017e+02,0.000000000000000000e+00,3.945873336648378693e+00,0.000000000000000000e+00,1.000000009976214299e+00,0.000000000000000000e+00,4.556031407825582499e-11,0.000000000000000000e+00 +2.363210851300663862e+01,1.239300000000000068e+02,0.000000000000000000e+00,3.948407629882498604e+00,0.000000000000000000e+00,1.000000009976329762e+00,0.000000000000000000e+00,-2.682771193516330252e-11,0.000000000000000000e+00 +2.363464117957437693e+01,1.239399999999999977e+02,0.000000000000000000e+00,3.950940296475502045e+00,0.000000000000000000e+00,1.000000009976261817e+00,0.000000000000000000e+00,-5.000524370115747246e-11,0.000000000000000000e+00 +2.363717222262985374e+01,1.239500000000000028e+02,0.000000000000000000e+00,3.953471339556229758e+00,0.000000000000000000e+00,1.000000009976135251e+00,0.000000000000000000e+00,4.468241136721664527e-11,0.000000000000000000e+00 +2.363970164529189333e+01,1.239600000000000080e+02,0.000000000000000000e+00,3.956000762243503832e+00,0.000000000000000000e+00,1.000000009976248272e+00,0.000000000000000000e+00,1.853442201567865885e-11,0.000000000000000000e+00 +2.364222945066934400e+01,1.239699999999999989e+02,0.000000000000000000e+00,3.958528567646173002e+00,0.000000000000000000e+00,1.000000009976295123e+00,0.000000000000000000e+00,-4.974969701282936030e-11,0.000000000000000000e+00 +2.364475564186112422e+01,1.239800000000000040e+02,0.000000000000000000e+00,3.961054758863155723e+00,0.000000000000000000e+00,1.000000009976169446e+00,0.000000000000000000e+00,2.867270535199281608e-11,0.000000000000000000e+00 +2.364728022195626878e+01,1.239900000000000091e+02,0.000000000000000000e+00,3.963579338983485023e+00,0.000000000000000000e+00,1.000000009976241833e+00,0.000000000000000000e+00,-7.507179713768048009e-11,0.000000000000000000e+00 +2.364980319403396791e+01,1.240000000000000000e+02,0.000000000000000000e+00,3.966102311086353804e+00,0.000000000000000000e+00,1.000000009976052429e+00,0.000000000000000000e+00,1.165982745882828016e-10,0.000000000000000000e+00 +2.365232456116361703e+01,1.240100000000000051e+02,0.000000000000000000e+00,3.968623678241156583e+00,0.000000000000000000e+00,1.000000009976346416e+00,0.000000000000000000e+00,-6.617898190251178066e-11,0.000000000000000000e+00 +2.365484432640485934e+01,1.240199999999999960e+02,0.000000000000000000e+00,3.971143443507536119e+00,0.000000000000000000e+00,1.000000009976179660e+00,0.000000000000000000e+00,2.468958735639925754e-12,0.000000000000000000e+00 +2.365736249280762493e+01,1.240300000000000011e+02,0.000000000000000000e+00,3.973661609935422501e+00,0.000000000000000000e+00,1.000000009976185877e+00,0.000000000000000000e+00,9.352699296209072775e-12,0.000000000000000000e+00 +2.365987906341217695e+01,1.240400000000000063e+02,0.000000000000000000e+00,3.976178180565080211e+00,0.000000000000000000e+00,1.000000009976209414e+00,0.000000000000000000e+00,-4.149577892110984481e-11,0.000000000000000000e+00 +2.366239404124915424e+01,1.240499999999999972e+02,0.000000000000000000e+00,3.978693158427148990e+00,0.000000000000000000e+00,1.000000009976105053e+00,0.000000000000000000e+00,3.357099931827348464e-11,0.000000000000000000e+00 +2.366490742933961755e+01,1.240600000000000023e+02,0.000000000000000000e+00,3.981206546542686464e+00,0.000000000000000000e+00,1.000000009976189430e+00,0.000000000000000000e+00,-3.624422282483277991e-11,0.000000000000000000e+00 +2.366741923069508502e+01,1.240700000000000074e+02,0.000000000000000000e+00,3.983718347923211667e+00,0.000000000000000000e+00,1.000000009976098392e+00,0.000000000000000000e+00,7.916840341940011140e-11,0.000000000000000000e+00 +2.366992944831757839e+01,1.240799999999999983e+02,0.000000000000000000e+00,3.986228565570745452e+00,0.000000000000000000e+00,1.000000009976297122e+00,0.000000000000000000e+00,-9.780582044162486619e-11,0.000000000000000000e+00 +2.367243808519966208e+01,1.240900000000000034e+02,0.000000000000000000e+00,3.988737202477854460e+00,0.000000000000000000e+00,1.000000009976051762e+00,0.000000000000000000e+00,5.048362184761627709e-11,0.000000000000000000e+00 +2.367494514432448582e+01,1.241000000000000085e+02,0.000000000000000000e+00,3.991244261627689749e+00,0.000000000000000000e+00,1.000000009976178328e+00,0.000000000000000000e+00,-2.109237527453156408e-11,0.000000000000000000e+00 +2.367745062866583439e+01,1.241099999999999994e+02,0.000000000000000000e+00,3.993749745994032097e+00,0.000000000000000000e+00,1.000000009976125481e+00,0.000000000000000000e+00,2.695843376936814527e-11,0.000000000000000000e+00 +2.367995454118815246e+01,1.241200000000000045e+02,0.000000000000000000e+00,3.996253658541329745e+00,0.000000000000000000e+00,1.000000009976192983e+00,0.000000000000000000e+00,5.235344732267021279e-12,0.000000000000000000e+00 +2.368245688484660150e+01,1.241300000000000097e+02,0.000000000000000000e+00,3.998756002224741479e+00,0.000000000000000000e+00,1.000000009976206083e+00,0.000000000000000000e+00,-9.784682207695605443e-11,0.000000000000000000e+00 +2.368495766258708812e+01,1.241400000000000006e+02,0.000000000000000000e+00,4.001256779990176149e+00,0.000000000000000000e+00,1.000000009975961390e+00,0.000000000000000000e+00,1.689846128703223927e-10,0.000000000000000000e+00 +2.368745687734631389e+01,1.241500000000000057e+02,0.000000000000000000e+00,4.003755994774333082e+00,0.000000000000000000e+00,1.000000009976383719e+00,0.000000000000000000e+00,-1.285511956537740714e-10,0.000000000000000000e+00 +2.368995453205180723e+01,1.241599999999999966e+02,0.000000000000000000e+00,4.006253649504745162e+00,0.000000000000000000e+00,1.000000009976062643e+00,0.000000000000000000e+00,3.166858551448135394e-11,0.000000000000000000e+00 +2.369245062962197323e+01,1.241700000000000017e+02,0.000000000000000000e+00,4.008749747099813021e+00,0.000000000000000000e+00,1.000000009976141691e+00,0.000000000000000000e+00,-3.560485015352388108e-13,0.000000000000000000e+00 +2.369494517296612557e+01,1.241800000000000068e+02,0.000000000000000000e+00,4.011244290468851226e+00,0.000000000000000000e+00,1.000000009976140802e+00,0.000000000000000000e+00,-1.279900195917113793e-10,0.000000000000000000e+00 +2.369743816498452915e+01,1.241899999999999977e+02,0.000000000000000000e+00,4.013737282512123805e+00,0.000000000000000000e+00,1.000000009975821724e+00,0.000000000000000000e+00,2.112212040728807566e-10,0.000000000000000000e+00 +2.369992960856843567e+01,1.242000000000000028e+02,0.000000000000000000e+00,4.016228726120884218e+00,0.000000000000000000e+00,1.000000009976347970e+00,0.000000000000000000e+00,-1.021090299293184045e-10,0.000000000000000000e+00 +2.370241950660012975e+01,1.242100000000000080e+02,0.000000000000000000e+00,4.018718624177417986e+00,0.000000000000000000e+00,1.000000009976093729e+00,0.000000000000000000e+00,-5.978643087709278940e-12,0.000000000000000000e+00 +2.370490786195296096e+01,1.242199999999999989e+02,0.000000000000000000e+00,4.021206979555074668e+00,0.000000000000000000e+00,1.000000009976078852e+00,0.000000000000000000e+00,2.196502795138829037e-11,0.000000000000000000e+00 +2.370739467749138996e+01,1.242300000000000040e+02,0.000000000000000000e+00,4.023693795118313155e+00,0.000000000000000000e+00,1.000000009976133475e+00,0.000000000000000000e+00,-3.225316591665607695e-11,0.000000000000000000e+00 +2.370987995607102050e+01,1.242400000000000091e+02,0.000000000000000000e+00,4.026179073722737201e+00,0.000000000000000000e+00,1.000000009976053317e+00,0.000000000000000000e+00,-4.380557574732749455e-12,0.000000000000000000e+00 +2.371236370053863851e+01,1.242500000000000000e+02,0.000000000000000000e+00,4.028662818215133612e+00,0.000000000000000000e+00,1.000000009976042437e+00,0.000000000000000000e+00,1.672795117993408459e-11,0.000000000000000000e+00 +2.371484591373225470e+01,1.242600000000000051e+02,0.000000000000000000e+00,4.031145031433511328e+00,0.000000000000000000e+00,1.000000009976083959e+00,0.000000000000000000e+00,-2.443606636107428517e-11,0.000000000000000000e+00 +2.371732659848113300e+01,1.242699999999999960e+02,0.000000000000000000e+00,4.033625716207138723e+00,0.000000000000000000e+00,1.000000009976023341e+00,0.000000000000000000e+00,-5.015611039995699293e-12,0.000000000000000000e+00 +2.371980575760584387e+01,1.242800000000000011e+02,0.000000000000000000e+00,4.036104875356580912e+00,0.000000000000000000e+00,1.000000009976010906e+00,0.000000000000000000e+00,8.773752109223692870e-11,0.000000000000000000e+00 +2.372228339391828555e+01,1.242900000000000063e+02,0.000000000000000000e+00,4.038582511693737942e+00,0.000000000000000000e+00,1.000000009976228288e+00,0.000000000000000000e+00,-1.354085641981926806e-10,0.000000000000000000e+00 +2.372475951022172680e+01,1.242999999999999972e+02,0.000000000000000000e+00,4.041058628021882093e+00,0.000000000000000000e+00,1.000000009975893001e+00,0.000000000000000000e+00,1.292105183814731198e-10,0.000000000000000000e+00 +2.372723410931084942e+01,1.243100000000000023e+02,0.000000000000000000e+00,4.043533227135692520e+00,0.000000000000000000e+00,1.000000009976212745e+00,0.000000000000000000e+00,-2.100956686734161285e-11,0.000000000000000000e+00 +2.372970719397178030e+01,1.243200000000000074e+02,0.000000000000000000e+00,4.046006311821296997e+00,0.000000000000000000e+00,1.000000009976160786e+00,0.000000000000000000e+00,-1.518285645424997668e-10,0.000000000000000000e+00 +2.373217876698213047e+01,1.243299999999999983e+02,0.000000000000000000e+00,4.048477884856303000e+00,0.000000000000000000e+00,1.000000009975785531e+00,0.000000000000000000e+00,2.070264974745953630e-10,0.000000000000000000e+00 +2.373464883111102353e+01,1.243400000000000034e+02,0.000000000000000000e+00,4.050947949009836790e+00,0.000000000000000000e+00,1.000000009976296900e+00,0.000000000000000000e+00,-1.894328334331944214e-10,0.000000000000000000e+00 +2.373711738911914182e+01,1.243500000000000085e+02,0.000000000000000000e+00,4.053416507042582495e+00,0.000000000000000000e+00,1.000000009975829274e+00,0.000000000000000000e+00,6.714292931095414095e-11,0.000000000000000000e+00 +2.373958444375875843e+01,1.243599999999999994e+02,0.000000000000000000e+00,4.055883561706810525e+00,0.000000000000000000e+00,1.000000009975994919e+00,0.000000000000000000e+00,8.708676899994407073e-11,0.000000000000000000e+00 +2.374204999777377267e+01,1.243700000000000045e+02,0.000000000000000000e+00,4.058349115746421987e+00,0.000000000000000000e+00,1.000000009976209636e+00,0.000000000000000000e+00,-1.147144251666442059e-10,0.000000000000000000e+00 +2.374451405389974923e+01,1.243800000000000097e+02,0.000000000000000000e+00,4.060813171896978879e+00,0.000000000000000000e+00,1.000000009975926973e+00,0.000000000000000000e+00,9.512741475317804163e-11,0.000000000000000000e+00 +2.374697661486394296e+01,1.243900000000000006e+02,0.000000000000000000e+00,4.063275732885739622e+00,0.000000000000000000e+00,1.000000009976161230e+00,0.000000000000000000e+00,-8.219301223319839288e-11,0.000000000000000000e+00 +2.374943768338534866e+01,1.244000000000000057e+02,0.000000000000000000e+00,4.065736801431698133e+00,0.000000000000000000e+00,1.000000009975958948e+00,0.000000000000000000e+00,5.082622809751238772e-11,0.000000000000000000e+00 +2.375189726217472952e+01,1.244099999999999966e+02,0.000000000000000000e+00,4.068196380245614030e+00,0.000000000000000000e+00,1.000000009976083959e+00,0.000000000000000000e+00,-9.656502110117063572e-11,0.000000000000000000e+00 +2.375435535393464548e+01,1.244200000000000017e+02,0.000000000000000000e+00,4.070654472030051707e+00,0.000000000000000000e+00,1.000000009975846593e+00,0.000000000000000000e+00,9.020591303001682438e-11,0.000000000000000000e+00 +2.375681196135949946e+01,1.244300000000000068e+02,0.000000000000000000e+00,4.073111079479411423e+00,0.000000000000000000e+00,1.000000009976068194e+00,0.000000000000000000e+00,-6.602210085349048049e-11,0.000000000000000000e+00 +2.375926708713556224e+01,1.244399999999999977e+02,0.000000000000000000e+00,4.075566205279967491e+00,0.000000000000000000e+00,1.000000009975906101e+00,0.000000000000000000e+00,1.128481987407807673e-10,0.000000000000000000e+00 +2.376172073394101503e+01,1.244500000000000028e+02,0.000000000000000000e+00,4.078019852109898480e+00,0.000000000000000000e+00,1.000000009976182991e+00,0.000000000000000000e+00,-1.385418529615410879e-10,0.000000000000000000e+00 +2.376417290444597796e+01,1.244600000000000080e+02,0.000000000000000000e+00,4.080472022639325402e+00,0.000000000000000000e+00,1.000000009975843263e+00,0.000000000000000000e+00,6.831592858236426225e-11,0.000000000000000000e+00 +2.376662360131254559e+01,1.244699999999999989e+02,0.000000000000000000e+00,4.082922719530341027e+00,0.000000000000000000e+00,1.000000009976010684e+00,0.000000000000000000e+00,2.819497892434377362e-11,0.000000000000000000e+00 +2.376907282719481884e+01,1.244800000000000040e+02,0.000000000000000000e+00,4.085371945437048957e+00,0.000000000000000000e+00,1.000000009976079740e+00,0.000000000000000000e+00,-4.862242525836575427e-11,0.000000000000000000e+00 +2.377152058473894414e+01,1.244900000000000091e+02,0.000000000000000000e+00,4.087819703005592942e+00,0.000000000000000000e+00,1.000000009975960724e+00,0.000000000000000000e+00,7.978492353326406998e-11,0.000000000000000000e+00 +2.377396687658313823e+01,1.245000000000000000e+02,0.000000000000000000e+00,4.090265994874191513e+00,0.000000000000000000e+00,1.000000009976155901e+00,0.000000000000000000e+00,-2.057121690410844435e-10,0.000000000000000000e+00 +2.377641170535773085e+01,1.245100000000000051e+02,0.000000000000000000e+00,4.092710823673172627e+00,0.000000000000000000e+00,1.000000009975652970e+00,0.000000000000000000e+00,1.394953289399385399e-10,0.000000000000000000e+00 +2.377885507368518603e+01,1.245199999999999960e+02,0.000000000000000000e+00,4.095154192025002970e+00,0.000000000000000000e+00,1.000000009975993809e+00,0.000000000000000000e+00,-3.964578060784209940e-11,0.000000000000000000e+00 +2.378129698418014826e+01,1.245300000000000011e+02,0.000000000000000000e+00,4.097596102544327046e+00,0.000000000000000000e+00,1.000000009975896997e+00,0.000000000000000000e+00,6.368943754122621993e-11,0.000000000000000000e+00 +2.378373743944946739e+01,1.245400000000000063e+02,0.000000000000000000e+00,4.100036557837992923e+00,0.000000000000000000e+00,1.000000009976052429e+00,0.000000000000000000e+00,-5.380410796190235259e-11,0.000000000000000000e+00 +2.378617644209223414e+01,1.245499999999999972e+02,0.000000000000000000e+00,4.102475560505089547e+00,0.000000000000000000e+00,1.000000009975921200e+00,0.000000000000000000e+00,2.814781625995072000e-11,0.000000000000000000e+00 +2.378861399469980498e+01,1.245600000000000023e+02,0.000000000000000000e+00,4.104913113136976044e+00,0.000000000000000000e+00,1.000000009975989812e+00,0.000000000000000000e+00,1.203145429804665868e-11,0.000000000000000000e+00 +2.379105009985584118e+01,1.245700000000000074e+02,0.000000000000000000e+00,4.107349218317316364e+00,0.000000000000000000e+00,1.000000009976019122e+00,0.000000000000000000e+00,-7.223156697005604773e-11,0.000000000000000000e+00 +2.379348476013634439e+01,1.245799999999999983e+02,0.000000000000000000e+00,4.109783878622109476e+00,0.000000000000000000e+00,1.000000009975843263e+00,0.000000000000000000e+00,1.340543791016530458e-10,0.000000000000000000e+00 +2.379591797810968146e+01,1.245900000000000034e+02,0.000000000000000000e+00,4.112217096619721346e+00,0.000000000000000000e+00,1.000000009976169446e+00,0.000000000000000000e+00,-1.821625763066846389e-10,0.000000000000000000e+00 +2.379834975633661998e+01,1.246000000000000085e+02,0.000000000000000000e+00,4.114648874870918682e+00,0.000000000000000000e+00,1.000000009975726467e+00,0.000000000000000000e+00,1.457248756202370501e-10,0.000000000000000000e+00 +2.380078009737035316e+01,1.246099999999999994e+02,0.000000000000000000e+00,4.117079215928895586e+00,0.000000000000000000e+00,1.000000009976080628e+00,0.000000000000000000e+00,-9.077760013503673704e-11,0.000000000000000000e+00 +2.380320900375653892e+01,1.246200000000000045e+02,0.000000000000000000e+00,4.119508122339311740e+00,0.000000000000000000e+00,1.000000009975860138e+00,0.000000000000000000e+00,3.183206646215809175e-11,0.000000000000000000e+00 +2.380563647803332827e+01,1.246300000000000097e+02,0.000000000000000000e+00,4.121935596640316390e+00,0.000000000000000000e+00,1.000000009975937409e+00,0.000000000000000000e+00,-3.926437777043591453e-11,0.000000000000000000e+00 +2.380806252273139378e+01,1.246400000000000006e+02,0.000000000000000000e+00,4.124361641362584763e+00,0.000000000000000000e+00,1.000000009975842152e+00,0.000000000000000000e+00,7.454548924965873875e-11,0.000000000000000000e+00 +2.381048714037396863e+01,1.246500000000000057e+02,0.000000000000000000e+00,4.126786259029345594e+00,0.000000000000000000e+00,1.000000009976022897e+00,0.000000000000000000e+00,-1.262703600555789584e-10,0.000000000000000000e+00 +2.381291033347686437e+01,1.246599999999999966e+02,0.000000000000000000e+00,4.129209452156413995e+00,0.000000000000000000e+00,1.000000009975716919e+00,0.000000000000000000e+00,9.507928226706766392e-11,0.000000000000000000e+00 +2.381533210454851002e+01,1.246700000000000017e+02,0.000000000000000000e+00,4.131631223252218987e+00,0.000000000000000000e+00,1.000000009975947179e+00,0.000000000000000000e+00,-9.724508080227405272e-12,0.000000000000000000e+00 +2.381775245608998404e+01,1.246800000000000068e+02,0.000000000000000000e+00,4.134051574817838137e+00,0.000000000000000000e+00,1.000000009975923643e+00,0.000000000000000000e+00,-1.029932998207886220e-10,0.000000000000000000e+00 +2.382017139059503918e+01,1.246899999999999977e+02,0.000000000000000000e+00,4.136470509347023317e+00,0.000000000000000000e+00,1.000000009975674509e+00,0.000000000000000000e+00,1.814918377023237791e-10,0.000000000000000000e+00 +2.382258891055013095e+01,1.247000000000000028e+02,0.000000000000000000e+00,4.138888029326232676e+00,0.000000000000000000e+00,1.000000009976113269e+00,0.000000000000000000e+00,-1.305924233124273011e-10,0.000000000000000000e+00 +2.382500501843445662e+01,1.247100000000000080e+02,0.000000000000000000e+00,4.141304137234662619e+00,0.000000000000000000e+00,1.000000009975797743e+00,0.000000000000000000e+00,-1.140247258873068507e-11,0.000000000000000000e+00 +2.382741971671997661e+01,1.247199999999999989e+02,0.000000000000000000e+00,4.143718835544271784e+00,0.000000000000000000e+00,1.000000009975770210e+00,0.000000000000000000e+00,7.333120581717942829e-11,0.000000000000000000e+00 +2.382983300787144643e+01,1.247300000000000040e+02,0.000000000000000000e+00,4.146132126719816569e+00,0.000000000000000000e+00,1.000000009975947179e+00,0.000000000000000000e+00,-1.270464252661384323e-11,0.000000000000000000e+00 +2.383224489434644511e+01,1.247400000000000091e+02,0.000000000000000000e+00,4.148544013218877780e+00,0.000000000000000000e+00,1.000000009975916537e+00,0.000000000000000000e+00,-7.406141004091487378e-11,0.000000000000000000e+00 +2.383465537859541072e+01,1.247500000000000000e+02,0.000000000000000000e+00,4.150954497491889050e+00,0.000000000000000000e+00,1.000000009975738013e+00,0.000000000000000000e+00,1.114331735211958277e-10,0.000000000000000000e+00 +2.383706446306165461e+01,1.247600000000000051e+02,0.000000000000000000e+00,4.153363581982167041e+00,0.000000000000000000e+00,1.000000009976006465e+00,0.000000000000000000e+00,-1.261613342718260652e-10,0.000000000000000000e+00 +2.383947215018141108e+01,1.247699999999999960e+02,0.000000000000000000e+00,4.155771269125941636e+00,0.000000000000000000e+00,1.000000009975702708e+00,0.000000000000000000e+00,9.993562165496503892e-11,0.000000000000000000e+00 +2.384187844238384457e+01,1.247800000000000011e+02,0.000000000000000000e+00,4.158177561352380813e+00,0.000000000000000000e+00,1.000000009975943183e+00,0.000000000000000000e+00,1.708106653564446229e-11,0.000000000000000000e+00 +2.384428334209109579e+01,1.247900000000000063e+02,0.000000000000000000e+00,4.160582461083624395e+00,0.000000000000000000e+00,1.000000009975984261e+00,0.000000000000000000e+00,-4.924039957460317126e-11,0.000000000000000000e+00 +2.384668685171830305e+01,1.247999999999999972e+02,0.000000000000000000e+00,4.162985970734808028e+00,0.000000000000000000e+00,1.000000009975865911e+00,0.000000000000000000e+00,-5.435287222059919041e-11,0.000000000000000000e+00 +2.384908897367362357e+01,1.248100000000000023e+02,0.000000000000000000e+00,4.165388092714093382e+00,0.000000000000000000e+00,1.000000009975735349e+00,0.000000000000000000e+00,7.223484256101879323e-11,0.000000000000000000e+00 +2.385148971035827614e+01,1.248200000000000074e+02,0.000000000000000000e+00,4.167788829422696573e+00,0.000000000000000000e+00,1.000000009975908766e+00,0.000000000000000000e+00,-3.655468344958479398e-11,0.000000000000000000e+00 +2.385388906416655885e+01,1.248299999999999983e+02,0.000000000000000000e+00,4.170188183254916581e+00,0.000000000000000000e+00,1.000000009975821058e+00,0.000000000000000000e+00,-1.068566826906408207e-10,0.000000000000000000e+00 +2.385628703748588109e+01,1.248400000000000034e+02,0.000000000000000000e+00,4.172586156598161011e+00,0.000000000000000000e+00,1.000000009975564819e+00,0.000000000000000000e+00,1.622301928395270839e-10,0.000000000000000000e+00 +2.385868363269678838e+01,1.248500000000000085e+02,0.000000000000000000e+00,4.174982751832975403e+00,0.000000000000000000e+00,1.000000009975953619e+00,0.000000000000000000e+00,-1.413724403441848754e-10,0.000000000000000000e+00 +2.386107885217299085e+01,1.248599999999999994e+02,0.000000000000000000e+00,4.177377971333072537e+00,0.000000000000000000e+00,1.000000009975615001e+00,0.000000000000000000e+00,1.055568106562051867e-10,0.000000000000000000e+00 +2.386347269828139162e+01,1.248700000000000045e+02,0.000000000000000000e+00,4.179771817465354644e+00,0.000000000000000000e+00,1.000000009975867687e+00,0.000000000000000000e+00,3.953688030833826373e-11,0.000000000000000000e+00 +2.386586517338211877e+01,1.248800000000000097e+02,0.000000000000000000e+00,4.182164292589947152e+00,0.000000000000000000e+00,1.000000009975962278e+00,0.000000000000000000e+00,-9.583430826582584971e-11,0.000000000000000000e+00 +2.386825627982853959e+01,1.248900000000000006e+02,0.000000000000000000e+00,4.184555399060220893e+00,0.000000000000000000e+00,1.000000009975733128e+00,0.000000000000000000e+00,-3.149845451758481688e-11,0.000000000000000000e+00 +2.387064601996729962e+01,1.249000000000000057e+02,0.000000000000000000e+00,4.186945139222820522e+00,0.000000000000000000e+00,1.000000009975657855e+00,0.000000000000000000e+00,6.117350851672344635e-11,0.000000000000000000e+00 +2.387303439613834755e+01,1.249099999999999966e+02,0.000000000000000000e+00,4.189333515417692944e+00,0.000000000000000000e+00,1.000000009975803961e+00,0.000000000000000000e+00,3.227859601495496132e-11,0.000000000000000000e+00 +2.387542141067495649e+01,1.249200000000000017e+02,0.000000000000000000e+00,4.191720529978113063e+00,0.000000000000000000e+00,1.000000009975881010e+00,0.000000000000000000e+00,-8.758347422220600464e-11,0.000000000000000000e+00 +2.387780706590375246e+01,1.249300000000000068e+02,0.000000000000000000e+00,4.194106185230709549e+00,0.000000000000000000e+00,1.000000009975672066e+00,0.000000000000000000e+00,6.835585297702763121e-11,0.000000000000000000e+00 +2.388019136414474985e+01,1.249399999999999977e+02,0.000000000000000000e+00,4.196490483495491475e+00,0.000000000000000000e+00,1.000000009975835047e+00,0.000000000000000000e+00,-4.640404195967461858e-11,0.000000000000000000e+00 +2.388257430771136214e+01,1.249500000000000028e+02,0.000000000000000000e+00,4.198873427085876742e+00,0.000000000000000000e+00,1.000000009975724469e+00,0.000000000000000000e+00,-1.762117291457766706e-11,0.000000000000000000e+00 +2.388495589891044091e+01,1.249600000000000080e+02,0.000000000000000000e+00,4.201255018308715172e+00,0.000000000000000000e+00,1.000000009975682502e+00,0.000000000000000000e+00,1.240711794270452841e-10,0.000000000000000000e+00 +2.388733614004229722e+01,1.249699999999999989e+02,0.000000000000000000e+00,4.203635259464316931e+00,0.000000000000000000e+00,1.000000009975977822e+00,0.000000000000000000e+00,-9.977987530368170906e-11,0.000000000000000000e+00 +2.388971503340072644e+01,1.249800000000000040e+02,0.000000000000000000e+00,4.206014152846478282e+00,0.000000000000000000e+00,1.000000009975740456e+00,0.000000000000000000e+00,-4.678952981898211559e-11,0.000000000000000000e+00 +2.389209258127303670e+01,1.249900000000000091e+02,0.000000000000000000e+00,4.208391700742504682e+00,0.000000000000000000e+00,1.000000009975629212e+00,0.000000000000000000e+00,8.223165918538119640e-12,0.000000000000000000e+00 +2.389446878594006662e+01,1.250000000000000000e+02,0.000000000000000000e+00,4.210767905433240088e+00,0.000000000000000000e+00,1.000000009975648751e+00,0.000000000000000000e+00,1.265025634478428108e-10,0.000000000000000000e+00 +2.389684364967622798e+01,1.250100000000000051e+02,0.000000000000000000e+00,4.213142769193090942e+00,0.000000000000000000e+00,1.000000009975949178e+00,0.000000000000000000e+00,-8.045348346432798008e-11,0.000000000000000000e+00 +2.389921717474950924e+01,1.250199999999999960e+02,0.000000000000000000e+00,4.215516294290051924e+00,0.000000000000000000e+00,1.000000009975758219e+00,0.000000000000000000e+00,-3.304195254925953203e-11,0.000000000000000000e+00 +2.390158936342152174e+01,1.250300000000000011e+02,0.000000000000000000e+00,4.217888482985729048e+00,0.000000000000000000e+00,1.000000009975679838e+00,0.000000000000000000e+00,-7.417550304033453316e-11,0.000000000000000000e+00 +2.390396021794751036e+01,1.250400000000000063e+02,0.000000000000000000e+00,4.220259337535368083e+00,0.000000000000000000e+00,1.000000009975503978e+00,0.000000000000000000e+00,1.064529488434868372e-10,0.000000000000000000e+00 +2.390632974057638194e+01,1.250499999999999972e+02,0.000000000000000000e+00,4.222628860187877642e+00,0.000000000000000000e+00,1.000000009975756221e+00,0.000000000000000000e+00,5.156865763529989057e-11,0.000000000000000000e+00 +2.390869793355073725e+01,1.250600000000000023e+02,0.000000000000000000e+00,4.224997053185855833e+00,0.000000000000000000e+00,1.000000009975878346e+00,0.000000000000000000e+00,-4.221620106678337184e-11,0.000000000000000000e+00 +2.391106479910688165e+01,1.250700000000000074e+02,0.000000000000000000e+00,4.227363918765612461e+00,0.000000000000000000e+00,1.000000009975778426e+00,0.000000000000000000e+00,-1.135782654972137527e-10,0.000000000000000000e+00 +2.391343033947486418e+01,1.250799999999999983e+02,0.000000000000000000e+00,4.229729459157194782e+00,0.000000000000000000e+00,1.000000009975509752e+00,0.000000000000000000e+00,8.030062587270683901e-11,0.000000000000000000e+00 +2.391579455687849887e+01,1.250900000000000034e+02,0.000000000000000000e+00,4.232093676584412378e+00,0.000000000000000000e+00,1.000000009975699600e+00,0.000000000000000000e+00,9.491107041071382023e-12,0.000000000000000000e+00 +2.391815745353537892e+01,1.251000000000000085e+02,0.000000000000000000e+00,4.234456573264862911e+00,0.000000000000000000e+00,1.000000009975722026e+00,0.000000000000000000e+00,-4.043024418596032970e-11,0.000000000000000000e+00 +2.392051903165691229e+01,1.251099999999999994e+02,0.000000000000000000e+00,4.236818151409953437e+00,0.000000000000000000e+00,1.000000009975626547e+00,0.000000000000000000e+00,8.052927963590850788e-11,0.000000000000000000e+00 +2.392287929344833941e+01,1.251200000000000045e+02,0.000000000000000000e+00,4.239178413224926167e+00,0.000000000000000000e+00,1.000000009975816617e+00,0.000000000000000000e+00,-9.469344161470773109e-11,0.000000000000000000e+00 +2.392523824110876518e+01,1.251300000000000097e+02,0.000000000000000000e+00,4.241537360908883336e+00,0.000000000000000000e+00,1.000000009975593240e+00,0.000000000000000000e+00,1.055769556574683464e-10,0.000000000000000000e+00 +2.392759587683117317e+01,1.251400000000000006e+02,0.000000000000000000e+00,4.243894996654808516e+00,0.000000000000000000e+00,1.000000009975842152e+00,0.000000000000000000e+00,-6.285367699129811600e-11,0.000000000000000000e+00 +2.392995220280245405e+01,1.251500000000000057e+02,0.000000000000000000e+00,4.246251322649594151e+00,0.000000000000000000e+00,1.000000009975694049e+00,0.000000000000000000e+00,-4.469143115439572521e-11,0.000000000000000000e+00 +2.393230722120342691e+01,1.251599999999999966e+02,0.000000000000000000e+00,4.248606341074061099e+00,0.000000000000000000e+00,1.000000009975588799e+00,0.000000000000000000e+00,-6.282911575795246225e-11,0.000000000000000000e+00 +2.393466093420887120e+01,1.251700000000000017e+02,0.000000000000000000e+00,4.250960054102985275e+00,0.000000000000000000e+00,1.000000009975440918e+00,0.000000000000000000e+00,1.618793208987638753e-10,0.000000000000000000e+00 +2.393701334398754099e+01,1.251800000000000068e+02,0.000000000000000000e+00,4.253312463905119856e+00,0.000000000000000000e+00,1.000000009975821724e+00,0.000000000000000000e+00,-3.381041806700475708e-11,0.000000000000000000e+00 +2.393936445270218627e+01,1.251899999999999977e+02,0.000000000000000000e+00,4.255663572643220149e+00,0.000000000000000000e+00,1.000000009975742232e+00,0.000000000000000000e+00,-1.690510427523044506e-10,0.000000000000000000e+00 +2.394171426250958845e+01,1.252000000000000028e+02,0.000000000000000000e+00,4.258013382474063135e+00,0.000000000000000000e+00,1.000000009975344994e+00,0.000000000000000000e+00,2.603821348608719253e-10,0.000000000000000000e+00 +2.394406277556057105e+01,1.252100000000000080e+02,0.000000000000000000e+00,4.260361895548473221e+00,0.000000000000000000e+00,1.000000009975956505e+00,0.000000000000000000e+00,-1.536288367269982519e-10,0.000000000000000000e+00 +2.394640999400003167e+01,1.252199999999999989e+02,0.000000000000000000e+00,4.262709114011347999e+00,0.000000000000000000e+00,1.000000009975595905e+00,0.000000000000000000e+00,-6.086069338072201621e-11,0.000000000000000000e+00 +2.394875591996695618e+01,1.252300000000000040e+02,0.000000000000000000e+00,4.265055040001673348e+00,0.000000000000000000e+00,1.000000009975453130e+00,0.000000000000000000e+00,1.385508490941422217e-10,0.000000000000000000e+00 +2.395110055559444717e+01,1.252400000000000091e+02,0.000000000000000000e+00,4.267399675652553626e+00,0.000000000000000000e+00,1.000000009975777981e+00,0.000000000000000000e+00,-9.977733880144643389e-11,0.000000000000000000e+00 +2.395344390300974879e+01,1.252500000000000000e+02,0.000000000000000000e+00,4.269743023091232104e+00,0.000000000000000000e+00,1.000000009975544168e+00,0.000000000000000000e+00,-5.972862436970318298e-12,0.000000000000000000e+00 +2.395578596433426455e+01,1.252600000000000051e+02,0.000000000000000000e+00,4.272085084439110503e+00,0.000000000000000000e+00,1.000000009975530180e+00,0.000000000000000000e+00,7.825895919438311076e-11,0.000000000000000000e+00 +2.395812674168357859e+01,1.252699999999999960e+02,0.000000000000000000e+00,4.274425861811775640e+00,0.000000000000000000e+00,1.000000009975713366e+00,0.000000000000000000e+00,-7.687816934315390287e-12,0.000000000000000000e+00 +2.396046623716748414e+01,1.252800000000000011e+02,0.000000000000000000e+00,4.276765357319019856e+00,0.000000000000000000e+00,1.000000009975695381e+00,0.000000000000000000e+00,-8.081374056786406963e-11,0.000000000000000000e+00 +2.396280445289000127e+01,1.252900000000000063e+02,0.000000000000000000e+00,4.279103573064862331e+00,0.000000000000000000e+00,1.000000009975506421e+00,0.000000000000000000e+00,6.347014440260707388e-11,0.000000000000000000e+00 +2.396514139094939821e+01,1.252999999999999972e+02,0.000000000000000000e+00,4.281440511147572181e+00,0.000000000000000000e+00,1.000000009975654747e+00,0.000000000000000000e+00,-1.616140303573237472e-12,0.000000000000000000e+00 +2.396747705343821622e+01,1.253100000000000023e+02,0.000000000000000000e+00,4.283776173659691544e+00,0.000000000000000000e+00,1.000000009975650972e+00,0.000000000000000000e+00,-3.300627176594323975e-11,0.000000000000000000e+00 +2.396981144244329442e+01,1.253200000000000074e+02,0.000000000000000000e+00,4.286110562688055126e+00,0.000000000000000000e+00,1.000000009975573922e+00,0.000000000000000000e+00,-9.260116179400318677e-11,0.000000000000000000e+00 +2.397214456004577698e+01,1.253299999999999983e+02,0.000000000000000000e+00,4.288443680313813289e+00,0.000000000000000000e+00,1.000000009975357873e+00,0.000000000000000000e+00,1.028403845357610239e-10,0.000000000000000000e+00 +2.397447640832115567e+01,1.253400000000000034e+02,0.000000000000000000e+00,4.290775528612453371e+00,0.000000000000000000e+00,1.000000009975597681e+00,0.000000000000000000e+00,3.982468068564072163e-11,0.000000000000000000e+00 +2.397680698933927701e+01,1.253500000000000085e+02,0.000000000000000000e+00,4.293106109653822777e+00,0.000000000000000000e+00,1.000000009975690496e+00,0.000000000000000000e+00,-1.232566537674982352e-10,0.000000000000000000e+00 +2.397913630516436356e+01,1.253599999999999994e+02,0.000000000000000000e+00,4.295435425502147631e+00,0.000000000000000000e+00,1.000000009975403392e+00,0.000000000000000000e+00,1.197945497117979803e-10,0.000000000000000000e+00 +2.398146435785504593e+01,1.253700000000000045e+02,0.000000000000000000e+00,4.297763478216054978e+00,0.000000000000000000e+00,1.000000009975682280e+00,0.000000000000000000e+00,-1.631844781024728200e-11,0.000000000000000000e+00 +2.398379114946437696e+01,1.253800000000000097e+02,0.000000000000000000e+00,4.300090269848596769e+00,0.000000000000000000e+00,1.000000009975644311e+00,0.000000000000000000e+00,1.279447872448073888e-11,0.000000000000000000e+00 +2.398611668203984948e+01,1.253900000000000006e+02,0.000000000000000000e+00,4.302415802447266735e+00,0.000000000000000000e+00,1.000000009975674065e+00,0.000000000000000000e+00,-4.919940317949716529e-11,0.000000000000000000e+00 +2.398844095762342121e+01,1.254000000000000057e+02,0.000000000000000000e+00,4.304740078054024366e+00,0.000000000000000000e+00,1.000000009975559712e+00,0.000000000000000000e+00,-1.118337842625651596e-10,0.000000000000000000e+00 +2.399076397825153961e+01,1.254099999999999966e+02,0.000000000000000000e+00,4.307063098705314452e+00,0.000000000000000000e+00,1.000000009975299919e+00,0.000000000000000000e+00,9.927018088564923821e-11,0.000000000000000000e+00 +2.399308574595515253e+01,1.254200000000000017e+02,0.000000000000000000e+00,4.309384866432088401e+00,0.000000000000000000e+00,1.000000009975530402e+00,0.000000000000000000e+00,5.396778723171675203e-11,0.000000000000000000e+00 +2.399540626275974375e+01,1.254300000000000068e+02,0.000000000000000000e+00,4.311705383259826441e+00,0.000000000000000000e+00,1.000000009975655635e+00,0.000000000000000000e+00,-1.019621328073697716e-10,0.000000000000000000e+00 +2.399772553068533654e+01,1.254399999999999977e+02,0.000000000000000000e+00,4.314024651208555383e+00,0.000000000000000000e+00,1.000000009975419157e+00,0.000000000000000000e+00,1.276888563786161400e-10,0.000000000000000000e+00 +2.400004355174652915e+01,1.254500000000000028e+02,0.000000000000000000e+00,4.316342672292869942e+00,0.000000000000000000e+00,1.000000009975715143e+00,0.000000000000000000e+00,-6.421418042715171242e-11,0.000000000000000000e+00 +2.400236032795250196e+01,1.254600000000000080e+02,0.000000000000000000e+00,4.318659448521955824e+00,0.000000000000000000e+00,1.000000009975566373e+00,0.000000000000000000e+00,-1.453745507076061886e-10,0.000000000000000000e+00 +2.400467586130705300e+01,1.254699999999999989e+02,0.000000000000000000e+00,4.320974981899605716e+00,0.000000000000000000e+00,1.000000009975229753e+00,0.000000000000000000e+00,1.061150796118007468e-10,0.000000000000000000e+00 +2.400699015380860502e+01,1.254800000000000040e+02,0.000000000000000000e+00,4.323289274424242379e+00,0.000000000000000000e+00,1.000000009975475335e+00,0.000000000000000000e+00,1.008921174920880023e-10,0.000000000000000000e+00 +2.400930320745023039e+01,1.254900000000000091e+02,0.000000000000000000e+00,4.325602328088939963e+00,0.000000000000000000e+00,1.000000009975708704e+00,0.000000000000000000e+00,-7.040293917824220391e-11,0.000000000000000000e+00 +2.401161502421966887e+01,1.255000000000000000e+02,0.000000000000000000e+00,4.327914144881440883e+00,0.000000000000000000e+00,1.000000009975545945e+00,0.000000000000000000e+00,-1.324244201327623450e-10,0.000000000000000000e+00 +2.401392560609935600e+01,1.255100000000000051e+02,0.000000000000000000e+00,4.330224726784176248e+00,0.000000000000000000e+00,1.000000009975239967e+00,0.000000000000000000e+00,2.099922636510740518e-10,0.000000000000000000e+00 +2.401623495506643025e+01,1.255199999999999960e+02,0.000000000000000000e+00,4.332534075774287174e+00,0.000000000000000000e+00,1.000000009975724913e+00,0.000000000000000000e+00,-6.378164867900332252e-11,0.000000000000000000e+00 +2.401854307309276493e+01,1.255300000000000011e+02,0.000000000000000000e+00,4.334842193823646106e+00,0.000000000000000000e+00,1.000000009975577697e+00,0.000000000000000000e+00,-1.246474177430206001e-10,0.000000000000000000e+00 +2.402084996214497892e+01,1.255400000000000063e+02,0.000000000000000000e+00,4.337149082898871022e+00,0.000000000000000000e+00,1.000000009975290149e+00,0.000000000000000000e+00,4.218117629205998427e-11,0.000000000000000000e+00 +2.402315562418445793e+01,1.255499999999999972e+02,0.000000000000000000e+00,4.339454744961349419e+00,0.000000000000000000e+00,1.000000009975387405e+00,0.000000000000000000e+00,1.349937072723428495e-10,0.000000000000000000e+00 +2.402546006116737942e+01,1.255600000000000023e+02,0.000000000000000000e+00,4.341759181967257852e+00,0.000000000000000000e+00,1.000000009975698489e+00,0.000000000000000000e+00,-1.329444534888335115e-10,0.000000000000000000e+00 +2.402776327504472675e+01,1.255700000000000074e+02,0.000000000000000000e+00,4.344062395867579696e+00,0.000000000000000000e+00,1.000000009975392290e+00,0.000000000000000000e+00,-2.507896607996264168e-11,0.000000000000000000e+00 +2.403006526776230700e+01,1.255799999999999983e+02,0.000000000000000000e+00,4.346364388608122908e+00,0.000000000000000000e+00,1.000000009975334558e+00,0.000000000000000000e+00,3.976157465738309389e-11,0.000000000000000000e+00 +2.403236604126077580e+01,1.255900000000000034e+02,0.000000000000000000e+00,4.348665162129543127e+00,0.000000000000000000e+00,1.000000009975426041e+00,0.000000000000000000e+00,1.630894410373073283e-10,0.000000000000000000e+00 +2.403466559747565512e+01,1.256000000000000085e+02,0.000000000000000000e+00,4.350964718367360540e+00,0.000000000000000000e+00,1.000000009975801074e+00,0.000000000000000000e+00,-2.098387101477673776e-10,0.000000000000000000e+00 +2.403696393833734746e+01,1.256099999999999994e+02,0.000000000000000000e+00,4.353263059251979428e+00,0.000000000000000000e+00,1.000000009975318793e+00,0.000000000000000000e+00,6.534341574614051727e-11,0.000000000000000000e+00 +2.403926106577115718e+01,1.256200000000000045e+02,0.000000000000000000e+00,4.355560186708704151e+00,0.000000000000000000e+00,1.000000009975468895e+00,0.000000000000000000e+00,-3.626732403318486502e-11,0.000000000000000000e+00 +2.404155698169731536e+01,1.256300000000000097e+02,0.000000000000000000e+00,4.357856102657764019e+00,0.000000000000000000e+00,1.000000009975385629e+00,0.000000000000000000e+00,-9.095801304366929619e-12,0.000000000000000000e+00 +2.404385168803098694e+01,1.256400000000000006e+02,0.000000000000000000e+00,4.360150809014326612e+00,0.000000000000000000e+00,1.000000009975364756e+00,0.000000000000000000e+00,-3.872591855204567523e-12,0.000000000000000000e+00 +2.404614518668230261e+01,1.256500000000000057e+02,0.000000000000000000e+00,4.362444307688519096e+00,0.000000000000000000e+00,1.000000009975355875e+00,0.000000000000000000e+00,1.404552973071815869e-11,0.000000000000000000e+00 +2.404843747955636246e+01,1.256599999999999966e+02,0.000000000000000000e+00,4.364736600585445991e+00,0.000000000000000000e+00,1.000000009975388071e+00,0.000000000000000000e+00,9.536595546535585106e-11,0.000000000000000000e+00 +2.405072856855327146e+01,1.256700000000000017e+02,0.000000000000000000e+00,4.367027689605207819e+00,0.000000000000000000e+00,1.000000009975606563e+00,0.000000000000000000e+00,-3.054476054810440770e-11,0.000000000000000000e+00 +2.405301845556813944e+01,1.256800000000000068e+02,0.000000000000000000e+00,4.369317576642919754e+00,0.000000000000000000e+00,1.000000009975536619e+00,0.000000000000000000e+00,-1.105038887016248724e-10,0.000000000000000000e+00 +2.405530714249111668e+01,1.256899999999999977e+02,0.000000000000000000e+00,4.371606263588728503e+00,0.000000000000000000e+00,1.000000009975283710e+00,0.000000000000000000e+00,1.257045603463825133e-10,0.000000000000000000e+00 +2.405759463120740094e+01,1.257000000000000028e+02,0.000000000000000000e+00,4.373893752327831841e+00,0.000000000000000000e+00,1.000000009975571258e+00,0.000000000000000000e+00,-2.230845274974642259e-10,0.000000000000000000e+00 +2.405988092359725883e+01,1.257100000000000080e+02,0.000000000000000000e+00,4.376180044740498154e+00,0.000000000000000000e+00,1.000000009975061221e+00,0.000000000000000000e+00,1.655789016172317467e-10,0.000000000000000000e+00 +2.406216602153604711e+01,1.257199999999999989e+02,0.000000000000000000e+00,4.378465142702079760e+00,0.000000000000000000e+00,1.000000009975439585e+00,0.000000000000000000e+00,8.137435890546476063e-11,0.000000000000000000e+00 +2.406444992689422335e+01,1.257300000000000040e+02,0.000000000000000000e+00,4.380749048083037778e+00,0.000000000000000000e+00,1.000000009975625437e+00,0.000000000000000000e+00,-1.406555566136463178e-10,0.000000000000000000e+00 +2.406673264153736724e+01,1.257400000000000091e+02,0.000000000000000000e+00,4.383031762748953675e+00,0.000000000000000000e+00,1.000000009975304360e+00,0.000000000000000000e+00,2.228693393545611676e-11,0.000000000000000000e+00 +2.406901416732620191e+01,1.257500000000000000e+02,0.000000000000000000e+00,4.385313288560548806e+00,0.000000000000000000e+00,1.000000009975355209e+00,0.000000000000000000e+00,8.685717597147778758e-11,0.000000000000000000e+00 +2.407129450611661170e+01,1.257600000000000051e+02,0.000000000000000000e+00,4.387593627373704841e+00,0.000000000000000000e+00,1.000000009975553272e+00,0.000000000000000000e+00,-2.462882495724178250e-10,0.000000000000000000e+00 +2.407357365975964925e+01,1.257699999999999960e+02,0.000000000000000000e+00,4.389872781039478866e+00,0.000000000000000000e+00,1.000000009974991944e+00,0.000000000000000000e+00,2.792651780420675663e-10,0.000000000000000000e+00 +2.407585163010156748e+01,1.257800000000000011e+02,0.000000000000000000e+00,4.392150751404119369e+00,0.000000000000000000e+00,1.000000009975628101e+00,0.000000000000000000e+00,-1.434597719577426115e-10,0.000000000000000000e+00 +2.407812841898382672e+01,1.257900000000000063e+02,0.000000000000000000e+00,4.394427540309090219e+00,0.000000000000000000e+00,1.000000009975301474e+00,0.000000000000000000e+00,-5.503280348616194925e-11,0.000000000000000000e+00 +2.408040402824311599e+01,1.257999999999999972e+02,0.000000000000000000e+00,4.396703149591078663e+00,0.000000000000000000e+00,1.000000009975176241e+00,0.000000000000000000e+00,1.377508805705088272e-10,0.000000000000000000e+00 +2.408267845971137078e+01,1.258100000000000023e+02,0.000000000000000000e+00,4.398977581082020194e+00,0.000000000000000000e+00,1.000000009975489546e+00,0.000000000000000000e+00,-1.303986934152345072e-10,0.000000000000000000e+00 +2.408495171521578726e+01,1.258200000000000074e+02,0.000000000000000000e+00,4.401250836609113648e+00,0.000000000000000000e+00,1.000000009975193116e+00,0.000000000000000000e+00,1.368183604467167789e-10,0.000000000000000000e+00 +2.408722379657884360e+01,1.258299999999999983e+02,0.000000000000000000e+00,4.403522917994835417e+00,0.000000000000000000e+00,1.000000009975503978e+00,0.000000000000000000e+00,-1.116623054542321048e-10,0.000000000000000000e+00 +2.408949470561831774e+01,1.258400000000000034e+02,0.000000000000000000e+00,4.405793827056961653e+00,0.000000000000000000e+00,1.000000009975250403e+00,0.000000000000000000e+00,1.531990786045867451e-10,0.000000000000000000e+00 +2.409176444414729445e+01,1.258500000000000085e+02,0.000000000000000000e+00,4.408063565608579815e+00,0.000000000000000000e+00,1.000000009975598125e+00,0.000000000000000000e+00,-2.641745392124041554e-10,0.000000000000000000e+00 +2.409403301397419384e+01,1.258599999999999994e+02,0.000000000000000000e+00,4.410332135458110869e+00,0.000000000000000000e+00,1.000000009974998827e+00,0.000000000000000000e+00,2.156397585446337005e-10,0.000000000000000000e+00 +2.409630041690278546e+01,1.258700000000000045e+02,0.000000000000000000e+00,4.412599538409319955e+00,0.000000000000000000e+00,1.000000009975487769e+00,0.000000000000000000e+00,-9.259052555325569397e-11,0.000000000000000000e+00 +2.409856665473219905e+01,1.258800000000000097e+02,0.000000000000000000e+00,4.414865776261341246e+00,0.000000000000000000e+00,1.000000009975277937e+00,0.000000000000000000e+00,7.675726505091140896e-11,0.000000000000000000e+00 +2.410083172925694939e+01,1.258900000000000006e+02,0.000000000000000000e+00,4.417130850808685949e+00,0.000000000000000000e+00,1.000000009975451798e+00,0.000000000000000000e+00,-6.953872529410173432e-11,0.000000000000000000e+00 +2.410309564226694690e+01,1.259000000000000057e+02,0.000000000000000000e+00,4.419394763841265394e+00,0.000000000000000000e+00,1.000000009975294368e+00,0.000000000000000000e+00,-9.960223058100591579e-11,0.000000000000000000e+00 +2.410535839554751192e+01,1.259099999999999966e+02,0.000000000000000000e+00,4.421657517144403471e+00,0.000000000000000000e+00,1.000000009975068993e+00,0.000000000000000000e+00,2.627310705855739681e-10,0.000000000000000000e+00 +2.410761999087940310e+01,1.259200000000000017e+02,0.000000000000000000e+00,4.423919112498855277e+00,0.000000000000000000e+00,1.000000009975663184e+00,0.000000000000000000e+00,-2.567751469245040405e-10,0.000000000000000000e+00 +2.410988043003882453e+01,1.259300000000000068e+02,0.000000000000000000e+00,4.426179551680824886e+00,0.000000000000000000e+00,1.000000009975082760e+00,0.000000000000000000e+00,3.646222465455620044e-11,0.000000000000000000e+00 +2.411213971479743989e+01,1.259399999999999977e+02,0.000000000000000000e+00,4.428438836461975114e+00,0.000000000000000000e+00,1.000000009975165138e+00,0.000000000000000000e+00,7.138837510626036863e-11,0.000000000000000000e+00 +2.411439784692239030e+01,1.259500000000000028e+02,0.000000000000000000e+00,4.430696968609452391e+00,0.000000000000000000e+00,1.000000009975326343e+00,0.000000000000000000e+00,7.378592684530648088e-12,0.000000000000000000e+00 +2.411665482817632267e+01,1.259600000000000080e+02,0.000000000000000000e+00,4.432953949885897416e+00,0.000000000000000000e+00,1.000000009975342996e+00,0.000000000000000000e+00,1.889881936230280515e-11,0.000000000000000000e+00 +2.411891066031738617e+01,1.259699999999999989e+02,0.000000000000000000e+00,4.435209782049462035e+00,0.000000000000000000e+00,1.000000009975385629e+00,0.000000000000000000e+00,-5.396782932905142915e-11,0.000000000000000000e+00 +2.412116534509925714e+01,1.259800000000000040e+02,0.000000000000000000e+00,4.437464466853826117e+00,0.000000000000000000e+00,1.000000009975263948e+00,0.000000000000000000e+00,-7.192799824203383577e-12,0.000000000000000000e+00 +2.412341888427116388e+01,1.259900000000000091e+02,0.000000000000000000e+00,4.439718006048212651e+00,0.000000000000000000e+00,1.000000009975247739e+00,0.000000000000000000e+00,2.789857668687210182e-11,0.000000000000000000e+00 +2.412567127957788671e+01,1.260000000000000000e+02,0.000000000000000000e+00,4.441970401377404620e+00,0.000000000000000000e+00,1.000000009975310578e+00,0.000000000000000000e+00,-6.697082671836568900e-11,0.000000000000000000e+00 +2.412792253275978638e+01,1.260100000000000051e+02,0.000000000000000000e+00,4.444221654581760106e+00,0.000000000000000000e+00,1.000000009975159809e+00,0.000000000000000000e+00,-4.450537641123849896e-11,0.000000000000000000e+00 +2.413017264555280761e+01,1.260199999999999960e+02,0.000000000000000000e+00,4.446471767397227381e+00,0.000000000000000000e+00,1.000000009975059667e+00,0.000000000000000000e+00,1.815672408032820295e-10,0.000000000000000000e+00 +2.413242161968850752e+01,1.260300000000000011e+02,0.000000000000000000e+00,4.448720741555361791e+00,0.000000000000000000e+00,1.000000009975468007e+00,0.000000000000000000e+00,-1.673357660479886628e-10,0.000000000000000000e+00 +2.413466945689406273e+01,1.260400000000000063e+02,0.000000000000000000e+00,4.450968578783341734e+00,0.000000000000000000e+00,1.000000009975091864e+00,0.000000000000000000e+00,7.679196358167175520e-11,0.000000000000000000e+00 +2.413691615889229070e+01,1.260499999999999972e+02,0.000000000000000000e+00,4.453215280803980214e+00,0.000000000000000000e+00,1.000000009975264392e+00,0.000000000000000000e+00,-1.295344280250624233e-11,0.000000000000000000e+00 +2.413916172740165678e+01,1.260600000000000023e+02,0.000000000000000000e+00,4.455460849335746154e+00,0.000000000000000000e+00,1.000000009975235304e+00,0.000000000000000000e+00,5.688538503285776120e-11,0.000000000000000000e+00 +2.414140616413629559e+01,1.260700000000000074e+02,0.000000000000000000e+00,4.457705286092775054e+00,0.000000000000000000e+00,1.000000009975362980e+00,0.000000000000000000e+00,-8.670730423914798161e-11,0.000000000000000000e+00 +2.414364947080602875e+01,1.260799999999999983e+02,0.000000000000000000e+00,4.459948592784886756e+00,0.000000000000000000e+00,1.000000009975168469e+00,0.000000000000000000e+00,7.833332509072577961e-11,0.000000000000000000e+00 +2.414589164911637553e+01,1.260900000000000034e+02,0.000000000000000000e+00,4.462190771117598764e+00,0.000000000000000000e+00,1.000000009975344106e+00,0.000000000000000000e+00,-1.476300026440662699e-10,0.000000000000000000e+00 +2.414813270076856710e+01,1.261000000000000085e+02,0.000000000000000000e+00,4.464431822792144011e+00,0.000000000000000000e+00,1.000000009975013260e+00,0.000000000000000000e+00,1.392780715430799647e-10,0.000000000000000000e+00 +2.415037262745956070e+01,1.261099999999999994e+02,0.000000000000000000e+00,4.466671749505482403e+00,0.000000000000000000e+00,1.000000009975325233e+00,0.000000000000000000e+00,-8.866695253701764849e-11,0.000000000000000000e+00 +2.415261143088206452e+01,1.261200000000000045e+02,0.000000000000000000e+00,4.468910552950320358e+00,0.000000000000000000e+00,1.000000009975126725e+00,0.000000000000000000e+00,1.009166535304134756e-10,0.000000000000000000e+00 +2.415484911272454482e+01,1.261300000000000097e+02,0.000000000000000000e+00,4.471148234815120581e+00,0.000000000000000000e+00,1.000000009975352544e+00,0.000000000000000000e+00,-1.182418062942682548e-10,0.000000000000000000e+00 +2.415708567467123657e+01,1.261400000000000006e+02,0.000000000000000000e+00,4.473384796784121598e+00,0.000000000000000000e+00,1.000000009975088089e+00,0.000000000000000000e+00,3.814237285937555102e-11,0.000000000000000000e+00 +2.415932111840216479e+01,1.261500000000000057e+02,0.000000000000000000e+00,4.475620240537348415e+00,0.000000000000000000e+00,1.000000009975173354e+00,0.000000000000000000e+00,-5.386327318326873204e-11,0.000000000000000000e+00 +2.416155544559315871e+01,1.261599999999999966e+02,0.000000000000000000e+00,4.477854567750631176e+00,0.000000000000000000e+00,1.000000009975053006e+00,0.000000000000000000e+00,6.214271552549597983e-11,0.000000000000000000e+00 +2.416378865791586605e+01,1.261700000000000017e+02,0.000000000000000000e+00,4.480087780095616701e+00,0.000000000000000000e+00,1.000000009975191784e+00,0.000000000000000000e+00,-3.431988658004731466e-11,0.000000000000000000e+00 +2.416602075703777075e+01,1.261800000000000068e+02,0.000000000000000000e+00,4.482319879239785365e+00,0.000000000000000000e+00,1.000000009975115178e+00,0.000000000000000000e+00,1.399356575107177542e-10,0.000000000000000000e+00 +2.416825174462219294e+01,1.261899999999999977e+02,0.000000000000000000e+00,4.484550866846463535e+00,0.000000000000000000e+00,1.000000009975427373e+00,0.000000000000000000e+00,-1.671898376506322453e-10,0.000000000000000000e+00 +2.417048162232832453e+01,1.262000000000000028e+02,0.000000000000000000e+00,4.486780744574840440e+00,0.000000000000000000e+00,1.000000009975054560e+00,0.000000000000000000e+00,8.986314429485511388e-11,0.000000000000000000e+00 +2.417271039181122916e+01,1.262100000000000080e+02,0.000000000000000000e+00,4.489009514079978835e+00,0.000000000000000000e+00,1.000000009975254844e+00,0.000000000000000000e+00,-1.735359759006015117e-10,0.000000000000000000e+00 +2.417493805472186352e+01,1.262199999999999989e+02,0.000000000000000000e+00,4.491237177012834536e+00,0.000000000000000000e+00,1.000000009974868265e+00,0.000000000000000000e+00,2.952872009384100464e-10,0.000000000000000000e+00 +2.417716461270708450e+01,1.262300000000000040e+02,0.000000000000000000e+00,4.493463735020265304e+00,0.000000000000000000e+00,1.000000009975525739e+00,0.000000000000000000e+00,-2.821635246039136341e-10,0.000000000000000000e+00 +2.417939006740967045e+01,1.262400000000000091e+02,0.000000000000000000e+00,4.495689189745051273e+00,0.000000000000000000e+00,1.000000009974897797e+00,0.000000000000000000e+00,9.143910734824494226e-11,0.000000000000000000e+00 +2.418161442046833187e+01,1.262500000000000000e+02,0.000000000000000000e+00,4.497913542825900279e+00,0.000000000000000000e+00,1.000000009975101189e+00,0.000000000000000000e+00,1.987487496851412746e-11,0.000000000000000000e+00 +2.418383767351772562e+01,1.262600000000000051e+02,0.000000000000000000e+00,4.500136795897471842e+00,0.000000000000000000e+00,1.000000009975145376e+00,0.000000000000000000e+00,9.242887646821265616e-11,0.000000000000000000e+00 +2.418605982818847266e+01,1.262699999999999960e+02,0.000000000000000000e+00,4.502358950590384268e+00,0.000000000000000000e+00,1.000000009975350768e+00,0.000000000000000000e+00,-1.672539112615492686e-10,0.000000000000000000e+00 +2.418828088610716520e+01,1.262800000000000011e+02,0.000000000000000000e+00,4.504580008531231528e+00,0.000000000000000000e+00,1.000000009974979287e+00,0.000000000000000000e+00,3.720809800652742500e-11,0.000000000000000000e+00 +2.419050084889638441e+01,1.262900000000000063e+02,0.000000000000000000e+00,4.506799971342594802e+00,0.000000000000000000e+00,1.000000009975061888e+00,0.000000000000000000e+00,7.425272793817783939e-11,0.000000000000000000e+00 +2.419271971817471822e+01,1.262999999999999972e+02,0.000000000000000000e+00,4.509018840643060244e+00,0.000000000000000000e+00,1.000000009975226645e+00,0.000000000000000000e+00,-1.359634091001210737e-10,0.000000000000000000e+00 +2.419493749555676487e+01,1.263100000000000023e+02,0.000000000000000000e+00,4.511236618047229641e+00,0.000000000000000000e+00,1.000000009974925108e+00,0.000000000000000000e+00,6.150411920826656577e-11,0.000000000000000000e+00 +2.419715418265315776e+01,1.263200000000000074e+02,0.000000000000000000e+00,4.513453305165733731e+00,0.000000000000000000e+00,1.000000009975061444e+00,0.000000000000000000e+00,7.065425089751369328e-11,0.000000000000000000e+00 +2.419936978107057257e+01,1.263299999999999983e+02,0.000000000000000000e+00,4.515668903605249085e+00,0.000000000000000000e+00,1.000000009975217985e+00,0.000000000000000000e+00,2.897744962075769767e-11,0.000000000000000000e+00 +2.420158429241174147e+01,1.263400000000000034e+02,0.000000000000000000e+00,4.517883414968508760e+00,0.000000000000000000e+00,1.000000009975282156e+00,0.000000000000000000e+00,-9.439845113335658099e-11,0.000000000000000000e+00 +2.420379771827547088e+01,1.263500000000000085e+02,0.000000000000000000e+00,4.520096840854316511e+00,0.000000000000000000e+00,1.000000009975073212e+00,0.000000000000000000e+00,-1.363978176343264921e-10,0.000000000000000000e+00 +2.420601006025664503e+01,1.263599999999999994e+02,0.000000000000000000e+00,4.522309182857560117e+00,0.000000000000000000e+00,1.000000009974771453e+00,0.000000000000000000e+00,2.599755627312344087e-10,0.000000000000000000e+00 +2.420822131994625437e+01,1.263700000000000045e+02,0.000000000000000000e+00,4.524520442569225587e+00,0.000000000000000000e+00,1.000000009975346327e+00,0.000000000000000000e+00,-1.710911038109806139e-10,0.000000000000000000e+00 +2.421043149893139201e+01,1.263800000000000097e+02,0.000000000000000000e+00,4.526730621576412261e+00,0.000000000000000000e+00,1.000000009974968185e+00,0.000000000000000000e+00,4.141160783376300504e-11,0.000000000000000000e+00 +2.421264059879528574e+01,1.263900000000000006e+02,0.000000000000000000e+00,4.528939721462339918e+00,0.000000000000000000e+00,1.000000009975059667e+00,0.000000000000000000e+00,1.790015403502868132e-11,0.000000000000000000e+00 +2.421484862111729086e+01,1.264000000000000057e+02,0.000000000000000000e+00,4.531147743806369199e+00,0.000000000000000000e+00,1.000000009975099191e+00,0.000000000000000000e+00,-1.841193946453691175e-11,0.000000000000000000e+00 +2.421705556747291865e+01,1.264099999999999966e+02,0.000000000000000000e+00,4.533354690184010494e+00,0.000000000000000000e+00,1.000000009975058557e+00,0.000000000000000000e+00,-1.459580079192072271e-11,0.000000000000000000e+00 +2.421926143943384346e+01,1.264200000000000017e+02,0.000000000000000000e+00,4.535560562166938148e+00,0.000000000000000000e+00,1.000000009975026360e+00,0.000000000000000000e+00,9.496922382109357786e-11,0.000000000000000000e+00 +2.422146623856791692e+01,1.264300000000000068e+02,0.000000000000000000e+00,4.537765361323003788e+00,0.000000000000000000e+00,1.000000009975235749e+00,0.000000000000000000e+00,-1.617176038620420660e-10,0.000000000000000000e+00 +2.422366996643917858e+01,1.264399999999999977e+02,0.000000000000000000e+00,4.539969089216249643e+00,0.000000000000000000e+00,1.000000009974879367e+00,0.000000000000000000e+00,3.508103236898329721e-11,0.000000000000000000e+00 +2.422587262460787727e+01,1.264500000000000028e+02,0.000000000000000000e+00,4.542171747406919202e+00,0.000000000000000000e+00,1.000000009974956638e+00,0.000000000000000000e+00,5.415992606300247585e-11,0.000000000000000000e+00 +2.422807421463047106e+01,1.264600000000000080e+02,0.000000000000000000e+00,4.544373337451474093e+00,0.000000000000000000e+00,1.000000009975075876e+00,0.000000000000000000e+00,6.760659001719932475e-12,0.000000000000000000e+00 +2.423027473805965215e+01,1.264699999999999989e+02,0.000000000000000000e+00,4.546573860902603847e+00,0.000000000000000000e+00,1.000000009975090753e+00,0.000000000000000000e+00,1.605172092763482826e-11,0.000000000000000000e+00 +2.423247419644434686e+01,1.264800000000000040e+02,0.000000000000000000e+00,4.548773319309239227e+00,0.000000000000000000e+00,1.000000009975126058e+00,0.000000000000000000e+00,-1.501915464399780927e-10,0.000000000000000000e+00 +2.423467259132974405e+01,1.264900000000000091e+02,0.000000000000000000e+00,4.550971714216565545e+00,0.000000000000000000e+00,1.000000009974795878e+00,0.000000000000000000e+00,2.060447662552439666e-10,0.000000000000000000e+00 +2.423686992425729514e+01,1.265000000000000000e+02,0.000000000000000000e+00,4.553169047166034211e+00,0.000000000000000000e+00,1.000000009975248627e+00,0.000000000000000000e+00,-2.288918992739730643e-10,0.000000000000000000e+00 +2.423906619676473184e+01,1.265100000000000051e+02,0.000000000000000000e+00,4.555365319695378723e+00,0.000000000000000000e+00,1.000000009974745918e+00,0.000000000000000000e+00,1.866206970033251426e-10,0.000000000000000000e+00 +2.424126141038607685e+01,1.265199999999999960e+02,0.000000000000000000e+00,4.557560533338620878e+00,0.000000000000000000e+00,1.000000009975155590e+00,0.000000000000000000e+00,-2.388276878191130296e-11,0.000000000000000000e+00 +2.424345556665166157e+01,1.265300000000000011e+02,0.000000000000000000e+00,4.559754689626091206e+00,0.000000000000000000e+00,1.000000009975103188e+00,0.000000000000000000e+00,-1.166364205762273000e-10,0.000000000000000000e+00 +2.424564866708812971e+01,1.265400000000000063e+02,0.000000000000000000e+00,4.561947790084434295e+00,0.000000000000000000e+00,1.000000009974847393e+00,0.000000000000000000e+00,1.128432866738040645e-10,0.000000000000000000e+00 +2.424784071321845502e+01,1.265499999999999972e+02,0.000000000000000000e+00,4.564139836236624781e+00,0.000000000000000000e+00,1.000000009975094750e+00,0.000000000000000000e+00,-4.459147557742936566e-11,0.000000000000000000e+00 +2.425003170656195550e+01,1.265600000000000023e+02,0.000000000000000000e+00,4.566330829601980668e+00,0.000000000000000000e+00,1.000000009974997051e+00,0.000000000000000000e+00,6.286360575098966236e-12,0.000000000000000000e+00 +2.425222164863430407e+01,1.265700000000000074e+02,0.000000000000000000e+00,4.568520771696172211e+00,0.000000000000000000e+00,1.000000009975010817e+00,0.000000000000000000e+00,-5.234383411590270587e-11,0.000000000000000000e+00 +2.425441054094753568e+01,1.265799999999999983e+02,0.000000000000000000e+00,4.570709664031237018e+00,0.000000000000000000e+00,1.000000009974896242e+00,0.000000000000000000e+00,2.750382852473232741e-11,0.000000000000000000e+00 +2.425659838501006504e+01,1.265900000000000034e+02,0.000000000000000000e+00,4.572897508115590703e+00,0.000000000000000000e+00,1.000000009974956416e+00,0.000000000000000000e+00,-5.066782230555410200e-11,0.000000000000000000e+00 +2.425878518232670089e+01,1.266000000000000085e+02,0.000000000000000000e+00,4.575084305454040212e+00,0.000000000000000000e+00,1.000000009974845616e+00,0.000000000000000000e+00,1.693459936101123633e-10,0.000000000000000000e+00 +2.426097093439865304e+01,1.266099999999999994e+02,0.000000000000000000e+00,4.577270057547794480e+00,0.000000000000000000e+00,1.000000009975215765e+00,0.000000000000000000e+00,-1.463555695051260551e-10,0.000000000000000000e+00 +2.426315564272354308e+01,1.266200000000000045e+02,0.000000000000000000e+00,4.579454765894478641e+00,0.000000000000000000e+00,1.000000009974896020e+00,0.000000000000000000e+00,3.904677981177950352e-11,0.000000000000000000e+00 +2.426533930879542567e+01,1.266300000000000097e+02,0.000000000000000000e+00,4.581638431988142024e+00,0.000000000000000000e+00,1.000000009974981285e+00,0.000000000000000000e+00,-8.749021621645262420e-11,0.000000000000000000e+00 +2.426752193410478853e+01,1.266400000000000006e+02,0.000000000000000000e+00,4.583821057319275027e+00,0.000000000000000000e+00,1.000000009974790327e+00,0.000000000000000000e+00,-2.554709966655939276e-11,0.000000000000000000e+00 +2.426970352013857024e+01,1.266500000000000057e+02,0.000000000000000000e+00,4.586002643374817112e+00,0.000000000000000000e+00,1.000000009974734594e+00,0.000000000000000000e+00,1.783038301128426818e-10,0.000000000000000000e+00 +2.427188406838017443e+01,1.266599999999999966e+02,0.000000000000000000e+00,4.588183191638171010e+00,0.000000000000000000e+00,1.000000009975123394e+00,0.000000000000000000e+00,-7.375976786563400359e-11,0.000000000000000000e+00 +2.427406358030947686e+01,1.266700000000000017e+02,0.000000000000000000e+00,4.590362703589214277e+00,0.000000000000000000e+00,1.000000009974962634e+00,0.000000000000000000e+00,-6.125784290616205197e-11,0.000000000000000000e+00 +2.427624205740283969e+01,1.266800000000000068e+02,0.000000000000000000e+00,4.592541180704308168e+00,0.000000000000000000e+00,1.000000009974829185e+00,0.000000000000000000e+00,1.346068669534281016e-11,0.000000000000000000e+00 +2.427841950113312564e+01,1.266899999999999977e+02,0.000000000000000000e+00,4.594718624456312739e+00,0.000000000000000000e+00,1.000000009974858495e+00,0.000000000000000000e+00,1.453831286435446449e-10,0.000000000000000000e+00 +2.428059591296970154e+01,1.267000000000000028e+02,0.000000000000000000e+00,4.596895036314597505e+00,0.000000000000000000e+00,1.000000009975174908e+00,0.000000000000000000e+00,-2.245574632884687054e-10,0.000000000000000000e+00 +2.428277129437845616e+01,1.267100000000000080e+02,0.000000000000000000e+00,4.599070417745052985e+00,0.000000000000000000e+00,1.000000009974686410e+00,0.000000000000000000e+00,4.534122556251859028e-11,0.000000000000000000e+00 +2.428494564682181434e+01,1.267199999999999989e+02,0.000000000000000000e+00,4.601244770210099588e+00,0.000000000000000000e+00,1.000000009974784998e+00,0.000000000000000000e+00,2.300826911774832370e-10,0.000000000000000000e+00 +2.428711897175874057e+01,1.267300000000000040e+02,0.000000000000000000e+00,4.603418095168704482e+00,0.000000000000000000e+00,1.000000009975285042e+00,0.000000000000000000e+00,-1.997308753489612496e-10,0.000000000000000000e+00 +2.428929127064475679e+01,1.267400000000000091e+02,0.000000000000000000e+00,4.605590394076389593e+00,0.000000000000000000e+00,1.000000009974851167e+00,0.000000000000000000e+00,-6.923316801609659503e-11,0.000000000000000000e+00 +2.429146254493194945e+01,1.267500000000000000e+02,0.000000000000000000e+00,4.607761668385240483e+00,0.000000000000000000e+00,1.000000009974700843e+00,0.000000000000000000e+00,1.139765281839268558e-10,0.000000000000000000e+00 +2.429363279606898374e+01,1.267600000000000051e+02,0.000000000000000000e+00,4.609931919543923229e+00,0.000000000000000000e+00,1.000000009974948201e+00,0.000000000000000000e+00,3.910192155100530752e-11,0.000000000000000000e+00 +2.429580202550111423e+01,1.267699999999999960e+02,0.000000000000000000e+00,4.612101148997693301e+00,0.000000000000000000e+00,1.000000009975033022e+00,0.000000000000000000e+00,-2.184388614614913846e-10,0.000000000000000000e+00 +2.429797023467019912e+01,1.267800000000000011e+02,0.000000000000000000e+00,4.614269358188405334e+00,0.000000000000000000e+00,1.000000009974559401e+00,0.000000000000000000e+00,1.847306230831889815e-10,0.000000000000000000e+00 +2.430013742501470020e+01,1.267900000000000063e+02,0.000000000000000000e+00,4.616436548554524677e+00,0.000000000000000000e+00,1.000000009974959747e+00,0.000000000000000000e+00,2.214118431904171631e-11,0.000000000000000000e+00 +2.430230359796971129e+01,1.267999999999999972e+02,0.000000000000000000e+00,4.618602721531142485e+00,0.000000000000000000e+00,1.000000009975007709e+00,0.000000000000000000e+00,-3.240693180481459885e-11,0.000000000000000000e+00 +2.430446875496695114e+01,1.268100000000000023e+02,0.000000000000000000e+00,4.620767878549981056e+00,0.000000000000000000e+00,1.000000009974937543e+00,0.000000000000000000e+00,-5.099302392873240350e-11,0.000000000000000000e+00 +2.430663289743479183e+01,1.268200000000000074e+02,0.000000000000000000e+00,4.622932021039408035e+00,0.000000000000000000e+00,1.000000009974827186e+00,0.000000000000000000e+00,-9.679867786971745463e-11,0.000000000000000000e+00 +2.430879602679825524e+01,1.268299999999999983e+02,0.000000000000000000e+00,4.625095150424447077e+00,0.000000000000000000e+00,1.000000009974617798e+00,0.000000000000000000e+00,1.578464302865428576e-10,0.000000000000000000e+00 +2.431095814447903081e+01,1.268400000000000034e+02,0.000000000000000000e+00,4.627257268126788503e+00,0.000000000000000000e+00,1.000000009974959081e+00,0.000000000000000000e+00,-9.041626105491692443e-11,0.000000000000000000e+00 +2.431311925189548617e+01,1.268500000000000085e+02,0.000000000000000000e+00,4.629418375564801735e+00,0.000000000000000000e+00,1.000000009974763682e+00,0.000000000000000000e+00,7.514222205657606654e-11,0.000000000000000000e+00 +2.431527935046268141e+01,1.268599999999999994e+02,0.000000000000000000e+00,4.631578474153542402e+00,0.000000000000000000e+00,1.000000009974925996e+00,0.000000000000000000e+00,-1.299919103765496100e-10,0.000000000000000000e+00 +2.431743844159236900e+01,1.268700000000000045e+02,0.000000000000000000e+00,4.633737565304767436e+00,0.000000000000000000e+00,1.000000009974645332e+00,0.000000000000000000e+00,4.156741565138069138e-11,0.000000000000000000e+00 +2.431959652669301875e+01,1.268800000000000097e+02,0.000000000000000000e+00,4.635895650426942183e+00,0.000000000000000000e+00,1.000000009974735038e+00,0.000000000000000000e+00,2.053604358254579068e-10,0.000000000000000000e+00 +2.432175360716981416e+01,1.268900000000000006e+02,0.000000000000000000e+00,4.638052730925254608e+00,0.000000000000000000e+00,1.000000009975178017e+00,0.000000000000000000e+00,-2.074127136727157936e-10,0.000000000000000000e+00 +2.432390968442467738e+01,1.269000000000000057e+02,0.000000000000000000e+00,4.640208808201624180e+00,0.000000000000000000e+00,1.000000009974730819e+00,0.000000000000000000e+00,-3.606166660553730395e-11,0.000000000000000000e+00 +2.432606475985626560e+01,1.269099999999999966e+02,0.000000000000000000e+00,4.642363883654709866e+00,0.000000000000000000e+00,1.000000009974653103e+00,0.000000000000000000e+00,1.716301737683132663e-10,0.000000000000000000e+00 +2.432821883485999592e+01,1.269200000000000017e+02,0.000000000000000000e+00,4.644517958679926117e+00,0.000000000000000000e+00,1.000000009975022808e+00,0.000000000000000000e+00,-1.260236569657207106e-10,0.000000000000000000e+00 +2.433037191082804540e+01,1.269300000000000068e+02,0.000000000000000000e+00,4.646671034669450862e+00,0.000000000000000000e+00,1.000000009974751469e+00,0.000000000000000000e+00,-1.196851151567326896e-10,0.000000000000000000e+00 +2.433252398914936165e+01,1.269399999999999977e+02,0.000000000000000000e+00,4.648823113012233499e+00,0.000000000000000000e+00,1.000000009974493898e+00,0.000000000000000000e+00,2.443326498569033271e-10,0.000000000000000000e+00 +2.433467507120968065e+01,1.269500000000000028e+02,0.000000000000000000e+00,4.650974195094009112e+00,0.000000000000000000e+00,1.000000009975019477e+00,0.000000000000000000e+00,-1.236170302016399180e-10,0.000000000000000000e+00 +2.433682515839153382e+01,1.269600000000000080e+02,0.000000000000000000e+00,4.653124282297309122e+00,0.000000000000000000e+00,1.000000009974753690e+00,0.000000000000000000e+00,-6.199206857578654820e-13,0.000000000000000000e+00 +2.433897425207425513e+01,1.269699999999999989e+02,0.000000000000000000e+00,4.655273376001466623e+00,0.000000000000000000e+00,1.000000009974752357e+00,0.000000000000000000e+00,-7.411473680536520722e-11,0.000000000000000000e+00 +2.434112235363399535e+01,1.269800000000000040e+02,0.000000000000000000e+00,4.657421477582632363e+00,0.000000000000000000e+00,1.000000009974593151e+00,0.000000000000000000e+00,1.312343090876213503e-10,0.000000000000000000e+00 +2.434326946444372908e+01,1.269900000000000091e+02,0.000000000000000000e+00,4.659568588413781853e+00,0.000000000000000000e+00,1.000000009974874926e+00,0.000000000000000000e+00,-5.618052120201352290e-11,0.000000000000000000e+00 +2.434541558587326904e+01,1.270000000000000000e+02,0.000000000000000000e+00,4.661714709864727801e+00,0.000000000000000000e+00,1.000000009974754356e+00,0.000000000000000000e+00,5.072032145023089662e-11,0.000000000000000000e+00 +2.434756071928926957e+01,1.270100000000000051e+02,0.000000000000000000e+00,4.663859843302127217e+00,0.000000000000000000e+00,1.000000009974863158e+00,0.000000000000000000e+00,-8.906030280452957084e-12,0.000000000000000000e+00 +2.434970486605524798e+01,1.270199999999999960e+02,0.000000000000000000e+00,4.666003990089494735e+00,0.000000000000000000e+00,1.000000009974844062e+00,0.000000000000000000e+00,-1.083719819135711451e-10,0.000000000000000000e+00 +2.435184802753158451e+01,1.270300000000000011e+02,0.000000000000000000e+00,4.668147151587210608e+00,0.000000000000000000e+00,1.000000009974611803e+00,0.000000000000000000e+00,8.250833644448494994e-11,0.000000000000000000e+00 +2.435399020507553658e+01,1.270400000000000063e+02,0.000000000000000000e+00,4.670289329152531366e+00,0.000000000000000000e+00,1.000000009974788551e+00,0.000000000000000000e+00,-6.512438807577212569e-11,0.000000000000000000e+00 +2.435613140004124944e+01,1.270499999999999972e+02,0.000000000000000000e+00,4.672430524139601360e+00,0.000000000000000000e+00,1.000000009974649107e+00,0.000000000000000000e+00,-9.648638304881781878e-12,0.000000000000000000e+00 +2.435827161377975969e+01,1.270600000000000023e+02,0.000000000000000000e+00,4.674570737899459871e+00,0.000000000000000000e+00,1.000000009974628457e+00,0.000000000000000000e+00,2.532630238966034191e-11,0.000000000000000000e+00 +2.436041084763901665e+01,1.270700000000000074e+02,0.000000000000000000e+00,4.676709971780053543e+00,0.000000000000000000e+00,1.000000009974682635e+00,0.000000000000000000e+00,1.817266881557498342e-11,0.000000000000000000e+00 +2.436254910296387877e+01,1.270799999999999983e+02,0.000000000000000000e+00,4.678848227126245263e+00,0.000000000000000000e+00,1.000000009974721493e+00,0.000000000000000000e+00,1.507462771845920350e-10,0.000000000000000000e+00 +2.436468638109613849e+01,1.270900000000000034e+02,0.000000000000000000e+00,4.680985505279823933e+00,0.000000000000000000e+00,1.000000009975043680e+00,0.000000000000000000e+00,-1.640153596789497779e-10,0.000000000000000000e+00 +2.436682268337451873e+01,1.271000000000000085e+02,0.000000000000000000e+00,4.683121807579515128e+00,0.000000000000000000e+00,1.000000009974693294e+00,0.000000000000000000e+00,-1.433969603648533094e-10,0.000000000000000000e+00 +2.436895801113469417e+01,1.271099999999999994e+02,0.000000000000000000e+00,4.685257135360988201e+00,0.000000000000000000e+00,1.000000009974387094e+00,0.000000000000000000e+00,2.276255320270391118e-10,0.000000000000000000e+00 +2.437109236570928772e+01,1.271200000000000045e+02,0.000000000000000000e+00,4.687391489956869606e+00,0.000000000000000000e+00,1.000000009974872928e+00,0.000000000000000000e+00,-3.018348975397638172e-12,0.000000000000000000e+00 +2.437322574842789180e+01,1.271300000000000097e+02,0.000000000000000000e+00,4.689524872696752666e+00,0.000000000000000000e+00,1.000000009974866488e+00,0.000000000000000000e+00,-2.197108602028962522e-10,0.000000000000000000e+00 +2.437535816061707195e+01,1.271400000000000006e+02,0.000000000000000000e+00,4.691657284907202907e+00,0.000000000000000000e+00,1.000000009974397974e+00,0.000000000000000000e+00,2.038718817446082737e-10,0.000000000000000000e+00 +2.437748960360038097e+01,1.271500000000000057e+02,0.000000000000000000e+00,4.693788727911770486e+00,0.000000000000000000e+00,1.000000009974832516e+00,0.000000000000000000e+00,-5.106929272084597888e-11,0.000000000000000000e+00 +2.437962007869836256e+01,1.271599999999999966e+02,0.000000000000000000e+00,4.695919203031002631e+00,0.000000000000000000e+00,1.000000009974723714e+00,0.000000000000000000e+00,4.984122845661118529e-11,0.000000000000000000e+00 +2.438174958722856545e+01,1.271700000000000017e+02,0.000000000000000000e+00,4.698048711582447190e+00,0.000000000000000000e+00,1.000000009974829851e+00,0.000000000000000000e+00,-2.107216267565391220e-10,0.000000000000000000e+00 +2.438387813050555408e+01,1.271800000000000068e+02,0.000000000000000000e+00,4.700177254880666844e+00,0.000000000000000000e+00,1.000000009974381321e+00,0.000000000000000000e+00,2.222972373488079234e-10,0.000000000000000000e+00 +2.438600570984091220e+01,1.271899999999999977e+02,0.000000000000000000e+00,4.702304834237245323e+00,0.000000000000000000e+00,1.000000009974854276e+00,0.000000000000000000e+00,-1.376152030446651056e-10,0.000000000000000000e+00 +2.438813232654325702e+01,1.272000000000000028e+02,0.000000000000000000e+00,4.704431450960801619e+00,0.000000000000000000e+00,1.000000009974561621e+00,0.000000000000000000e+00,-2.130970990767985099e-11,0.000000000000000000e+00 +2.439025798191824634e+01,1.272100000000000080e+02,0.000000000000000000e+00,4.706557106356992648e+00,0.000000000000000000e+00,1.000000009974516324e+00,0.000000000000000000e+00,8.214215720051756125e-11,0.000000000000000000e+00 +2.439238267726858922e+01,1.272199999999999989e+02,0.000000000000000000e+00,4.708681801728528349e+00,0.000000000000000000e+00,1.000000009974690851e+00,0.000000000000000000e+00,8.458397488194389841e-11,0.000000000000000000e+00 +2.439450641389405661e+01,1.272300000000000040e+02,0.000000000000000000e+00,4.710805538375178791e+00,0.000000000000000000e+00,1.000000009974870485e+00,0.000000000000000000e+00,-9.445460860463908610e-11,0.000000000000000000e+00 +2.439662919309148492e+01,1.272400000000000091e+02,0.000000000000000000e+00,4.712928317593783056e+00,0.000000000000000000e+00,1.000000009974669979e+00,0.000000000000000000e+00,-1.329029989026532049e-10,0.000000000000000000e+00 +2.439875101615479380e+01,1.272500000000000000e+02,0.000000000000000000e+00,4.715050140678258117e+00,0.000000000000000000e+00,1.000000009974387982e+00,0.000000000000000000e+00,1.039622785568796813e-10,0.000000000000000000e+00 +2.440087188437498966e+01,1.272600000000000051e+02,0.000000000000000000e+00,4.717171008919609498e+00,0.000000000000000000e+00,1.000000009974608473e+00,0.000000000000000000e+00,-3.184164014039672562e-11,0.000000000000000000e+00 +2.440299179904017635e+01,1.272699999999999960e+02,0.000000000000000000e+00,4.719290923605941046e+00,0.000000000000000000e+00,1.000000009974540971e+00,0.000000000000000000e+00,2.031864698908574112e-10,0.000000000000000000e+00 +2.440511076143556224e+01,1.272800000000000011e+02,0.000000000000000000e+00,4.721409886022461144e+00,0.000000000000000000e+00,1.000000009974971515e+00,0.000000000000000000e+00,-2.196321726980933478e-10,0.000000000000000000e+00 +2.440722877284346737e+01,1.272900000000000063e+02,0.000000000000000000e+00,4.723527897451495150e+00,0.000000000000000000e+00,1.000000009974506332e+00,0.000000000000000000e+00,5.443447867519881511e-11,0.000000000000000000e+00 +2.440934583454334472e+01,1.272999999999999972e+02,0.000000000000000000e+00,4.725644959172489834e+00,0.000000000000000000e+00,1.000000009974621573e+00,0.000000000000000000e+00,1.290643880609767962e-11,0.000000000000000000e+00 +2.441146194781177670e+01,1.273100000000000023e+02,0.000000000000000000e+00,4.727761072462028480e+00,0.000000000000000000e+00,1.000000009974648885e+00,0.000000000000000000e+00,-1.618751260531780506e-10,0.000000000000000000e+00 +2.441357711392248575e+01,1.273200000000000074e+02,0.000000000000000000e+00,4.729876238593835325e+00,0.000000000000000000e+00,1.000000009974306492e+00,0.000000000000000000e+00,1.194126860344633338e-10,0.000000000000000000e+00 +2.441569133414634862e+01,1.273299999999999983e+02,0.000000000000000000e+00,4.731990458838785329e+00,0.000000000000000000e+00,1.000000009974558957e+00,0.000000000000000000e+00,6.388334747806603962e-11,0.000000000000000000e+00 +2.441780460975139988e+01,1.273400000000000034e+02,0.000000000000000000e+00,4.734103734464915725e+00,0.000000000000000000e+00,1.000000009974693960e+00,0.000000000000000000e+00,7.736700943375258709e-11,0.000000000000000000e+00 +2.441991694200284613e+01,1.273500000000000085e+02,0.000000000000000000e+00,4.736216066737431341e+00,0.000000000000000000e+00,1.000000009974857385e+00,0.000000000000000000e+00,-2.207415922069049030e-10,0.000000000000000000e+00 +2.442202833216306956e+01,1.273599999999999994e+02,0.000000000000000000e+00,4.738327456918715264e+00,0.000000000000000000e+00,1.000000009974391313e+00,0.000000000000000000e+00,-8.837808404686333768e-12,0.000000000000000000e+00 +2.442413878149163864e+01,1.273700000000000045e+02,0.000000000000000000e+00,4.740437906268335944e+00,0.000000000000000000e+00,1.000000009974372661e+00,0.000000000000000000e+00,1.491518134151766348e-10,0.000000000000000000e+00 +2.442624829124532226e+01,1.273800000000000097e+02,0.000000000000000000e+00,4.742547416043059627e+00,0.000000000000000000e+00,1.000000009974687298e+00,0.000000000000000000e+00,-1.059375409737510327e-10,0.000000000000000000e+00 +2.442835686267808626e+01,1.273900000000000006e+02,0.000000000000000000e+00,4.744655987496856575e+00,0.000000000000000000e+00,1.000000009974463921e+00,0.000000000000000000e+00,7.374676849742465995e-11,0.000000000000000000e+00 +2.443046449704111467e+01,1.274000000000000057e+02,0.000000000000000000e+00,4.746763621880908168e+00,0.000000000000000000e+00,1.000000009974619353e+00,0.000000000000000000e+00,-5.501844781145757274e-11,0.000000000000000000e+00 +2.443257119558281332e+01,1.274099999999999966e+02,0.000000000000000000e+00,4.748870320443619342e+00,0.000000000000000000e+00,1.000000009974503445e+00,0.000000000000000000e+00,1.728261634960557681e-10,0.000000000000000000e+00 +2.443467695954881336e+01,1.274200000000000017e+02,0.000000000000000000e+00,4.750976084430623914e+00,0.000000000000000000e+00,1.000000009974867377e+00,0.000000000000000000e+00,-1.721643487726693383e-10,0.000000000000000000e+00 +2.443678179018198904e+01,1.274300000000000068e+02,0.000000000000000000e+00,4.753080915084796132e+00,0.000000000000000000e+00,1.000000009974505000e+00,0.000000000000000000e+00,-8.232088596940337183e-12,0.000000000000000000e+00 +2.443888568872246125e+01,1.274399999999999977e+02,0.000000000000000000e+00,4.755184813646255115e+00,0.000000000000000000e+00,1.000000009974487680e+00,0.000000000000000000e+00,-4.962556726470479559e-11,0.000000000000000000e+00 +2.444098865640760820e+01,1.274500000000000028e+02,0.000000000000000000e+00,4.757287781352378175e+00,0.000000000000000000e+00,1.000000009974383319e+00,0.000000000000000000e+00,-4.225320343700270522e-13,0.000000000000000000e+00 +2.444309069447206895e+01,1.274600000000000080e+02,0.000000000000000000e+00,4.759389819437806146e+00,0.000000000000000000e+00,1.000000009974382431e+00,0.000000000000000000e+00,2.433803104421376293e-10,0.000000000000000000e+00 +2.444519180414775761e+01,1.274699999999999989e+02,0.000000000000000000e+00,4.761490929134453154e+00,0.000000000000000000e+00,1.000000009974893800e+00,0.000000000000000000e+00,-2.144130118849545505e-10,0.000000000000000000e+00 +2.444729198666387049e+01,1.274800000000000040e+02,0.000000000000000000e+00,4.763591111671515499e+00,0.000000000000000000e+00,1.000000009974443493e+00,0.000000000000000000e+00,-4.802092867126335363e-11,0.000000000000000000e+00 +2.444939124324689317e+01,1.274900000000000091e+02,0.000000000000000000e+00,4.765690368275476096e+00,0.000000000000000000e+00,1.000000009974342685e+00,0.000000000000000000e+00,6.433830676914030755e-11,0.000000000000000000e+00 +2.445148957512060761e+01,1.275000000000000000e+02,0.000000000000000000e+00,4.767788700170118688e+00,0.000000000000000000e+00,1.000000009974477688e+00,0.000000000000000000e+00,5.356828496974231569e-11,0.000000000000000000e+00 +2.445358698350610283e+01,1.275100000000000051e+02,0.000000000000000000e+00,4.769886108576533168e+00,0.000000000000000000e+00,1.000000009974590043e+00,0.000000000000000000e+00,-1.409698671243157202e-10,0.000000000000000000e+00 +2.445568346962178197e+01,1.275199999999999960e+02,0.000000000000000000e+00,4.771982594713123582e+00,0.000000000000000000e+00,1.000000009974294501e+00,0.000000000000000000e+00,2.355475216663743627e-10,0.000000000000000000e+00 +2.445777903468337300e+01,1.275300000000000011e+02,0.000000000000000000e+00,4.774078159795616116e+00,0.000000000000000000e+00,1.000000009974788107e+00,0.000000000000000000e+00,-2.780532917943978474e-10,0.000000000000000000e+00 +2.445987367990393224e+01,1.275400000000000063e+02,0.000000000000000000e+00,4.776172805037070646e+00,0.000000000000000000e+00,1.000000009974205684e+00,0.000000000000000000e+00,3.028854840533472860e-10,0.000000000000000000e+00 +2.446196740649386214e+01,1.275499999999999972e+02,0.000000000000000000e+00,4.778266531647882509e+00,0.000000000000000000e+00,1.000000009974839843e+00,0.000000000000000000e+00,-2.804192088122848033e-10,0.000000000000000000e+00 +2.446406021566090416e+01,1.275600000000000023e+02,0.000000000000000000e+00,4.780359340835799387e+00,0.000000000000000000e+00,1.000000009974252979e+00,0.000000000000000000e+00,1.772626512063398701e-10,0.000000000000000000e+00 +2.446615210861016010e+01,1.275700000000000074e+02,0.000000000000000000e+00,4.782451233805919522e+00,0.000000000000000000e+00,1.000000009974623794e+00,0.000000000000000000e+00,-1.664024714326001576e-10,0.000000000000000000e+00 +2.446824308654409208e+01,1.275799999999999983e+02,0.000000000000000000e+00,4.784542211760709485e+00,0.000000000000000000e+00,1.000000009974275850e+00,0.000000000000000000e+00,9.997012598332472383e-11,0.000000000000000000e+00 +2.447033315066254033e+01,1.275900000000000034e+02,0.000000000000000000e+00,4.786632275900004174e+00,0.000000000000000000e+00,1.000000009974484794e+00,0.000000000000000000e+00,-4.102585068327172464e-11,0.000000000000000000e+00 +2.447242230216271963e+01,1.276000000000000085e+02,0.000000000000000000e+00,4.788721427421021026e+00,0.000000000000000000e+00,1.000000009974399084e+00,0.000000000000000000e+00,2.413713149406353015e-11,0.000000000000000000e+00 +2.447451054223923350e+01,1.276099999999999994e+02,0.000000000000000000e+00,4.790809667518363568e+00,0.000000000000000000e+00,1.000000009974449489e+00,0.000000000000000000e+00,1.053135705496184152e-10,0.000000000000000000e+00 +2.447659787208408133e+01,1.276200000000000045e+02,0.000000000000000000e+00,4.792896997384032076e+00,0.000000000000000000e+00,1.000000009974669313e+00,0.000000000000000000e+00,-1.870928505765229933e-10,0.000000000000000000e+00 +2.447868429288666903e+01,1.276300000000000097e+02,0.000000000000000000e+00,4.794983418207430681e+00,0.000000000000000000e+00,1.000000009974278958e+00,0.000000000000000000e+00,-1.054053196730765737e-11,0.000000000000000000e+00 +2.448076980583380902e+01,1.276400000000000006e+02,0.000000000000000000e+00,4.797068931175373585e+00,0.000000000000000000e+00,1.000000009974256976e+00,0.000000000000000000e+00,2.608584861995775205e-10,0.000000000000000000e+00 +2.448285441210973801e+01,1.276500000000000057e+02,0.000000000000000000e+00,4.799153537472096609e+00,0.000000000000000000e+00,1.000000009974800763e+00,0.000000000000000000e+00,-3.549600709655721002e-10,0.000000000000000000e+00 +2.448493811289612054e+01,1.276599999999999966e+02,0.000000000000000000e+00,4.801237238279263408e+00,0.000000000000000000e+00,1.000000009974061133e+00,0.000000000000000000e+00,2.344329327769423647e-10,0.000000000000000000e+00 +2.448702090937205256e+01,1.276700000000000017e+02,0.000000000000000000e+00,4.803320034775969027e+00,0.000000000000000000e+00,1.000000009974549409e+00,0.000000000000000000e+00,3.796922626043131300e-11,0.000000000000000000e+00 +2.448910280271407558e+01,1.276800000000000068e+02,0.000000000000000000e+00,4.805401928138756773e+00,0.000000000000000000e+00,1.000000009974628457e+00,0.000000000000000000e+00,-2.694209270914873752e-10,0.000000000000000000e+00 +2.449118379409618029e+01,1.276899999999999977e+02,0.000000000000000000e+00,4.807482919541617328e+00,0.000000000000000000e+00,1.000000009974067794e+00,0.000000000000000000e+00,2.012191591868261763e-10,0.000000000000000000e+00 +2.449326388468981364e+01,1.277000000000000028e+02,0.000000000000000000e+00,4.809563010155999407e+00,0.000000000000000000e+00,1.000000009974486348e+00,0.000000000000000000e+00,9.034751406105045577e-11,0.000000000000000000e+00 +2.449534307566389657e+01,1.277100000000000080e+02,0.000000000000000000e+00,4.811642201150821307e+00,0.000000000000000000e+00,1.000000009974674198e+00,0.000000000000000000e+00,-3.161393207930025193e-10,0.000000000000000000e+00 +2.449742136818481697e+01,1.277199999999999989e+02,0.000000000000000000e+00,4.813720493692472679e+00,0.000000000000000000e+00,1.000000009974017168e+00,0.000000000000000000e+00,3.056941502590609587e-10,0.000000000000000000e+00 +2.449949876341644739e+01,1.277300000000000040e+02,0.000000000000000000e+00,4.815797888944823413e+00,0.000000000000000000e+00,1.000000009974652215e+00,0.000000000000000000e+00,-2.106564221109619772e-10,0.000000000000000000e+00 +2.450157526252014861e+01,1.277400000000000091e+02,0.000000000000000000e+00,4.817874388069236957e+00,0.000000000000000000e+00,1.000000009974214787e+00,0.000000000000000000e+00,9.050364307553624692e-11,0.000000000000000000e+00 +2.450365086665477676e+01,1.277500000000000000e+02,0.000000000000000000e+00,4.819949992224568547e+00,0.000000000000000000e+00,1.000000009974402637e+00,0.000000000000000000e+00,8.380009672652370634e-11,0.000000000000000000e+00 +2.450572557697669396e+01,1.277600000000000051e+02,0.000000000000000000e+00,4.822024702567181187e+00,0.000000000000000000e+00,1.000000009974576498e+00,0.000000000000000000e+00,-1.148866003631751266e-10,0.000000000000000000e+00 +2.450779939463977541e+01,1.277699999999999960e+02,0.000000000000000000e+00,4.824098520250948319e+00,0.000000000000000000e+00,1.000000009974338244e+00,0.000000000000000000e+00,3.192071849144678693e-11,0.000000000000000000e+00 +2.450987232079541300e+01,1.277800000000000011e+02,0.000000000000000000e+00,4.826171446427261813e+00,0.000000000000000000e+00,1.000000009974404414e+00,0.000000000000000000e+00,-1.722101908720709924e-10,0.000000000000000000e+00 +2.451194435659252591e+01,1.277900000000000063e+02,0.000000000000000000e+00,4.828243482245041740e+00,0.000000000000000000e+00,1.000000009974047588e+00,0.000000000000000000e+00,2.382173795456239951e-10,0.000000000000000000e+00 +2.451401550317756772e+01,1.277999999999999972e+02,0.000000000000000000e+00,4.830314628850740810e+00,0.000000000000000000e+00,1.000000009974540971e+00,0.000000000000000000e+00,-4.172201230330103949e-11,0.000000000000000000e+00 +2.451608576169453357e+01,1.278100000000000023e+02,0.000000000000000000e+00,4.832384887388355921e+00,0.000000000000000000e+00,1.000000009974454596e+00,0.000000000000000000e+00,-2.405677194677811936e-10,0.000000000000000000e+00 +2.451815513328496721e+01,1.278200000000000074e+02,0.000000000000000000e+00,4.834454258999429932e+00,0.000000000000000000e+00,1.000000009973956772e+00,0.000000000000000000e+00,2.151222829879197338e-10,0.000000000000000000e+00 +2.452022361908796810e+01,1.278299999999999983e+02,0.000000000000000000e+00,4.836522744823062325e+00,0.000000000000000000e+00,1.000000009974401749e+00,0.000000000000000000e+00,3.747993999477225118e-11,0.000000000000000000e+00 +2.452229122024020214e+01,1.278400000000000034e+02,0.000000000000000000e+00,4.838590345995918973e+00,0.000000000000000000e+00,1.000000009974479243e+00,0.000000000000000000e+00,-1.883393191744097335e-10,0.000000000000000000e+00 +2.452435793787590157e+01,1.278500000000000085e+02,0.000000000000000000e+00,4.840657063652233916e+00,0.000000000000000000e+00,1.000000009974089998e+00,0.000000000000000000e+00,1.320980554104477532e-10,0.000000000000000000e+00 +2.452642377312688282e+01,1.278599999999999994e+02,0.000000000000000000e+00,4.842722898923819130e+00,0.000000000000000000e+00,1.000000009974362891e+00,0.000000000000000000e+00,1.431224955987265542e-10,0.000000000000000000e+00 +2.452848872712254291e+01,1.278700000000000045e+02,0.000000000000000000e+00,4.844787852940074302e+00,0.000000000000000000e+00,1.000000009974658433e+00,0.000000000000000000e+00,-1.728744720635932736e-10,0.000000000000000000e+00 +2.453055280098987012e+01,1.278800000000000097e+02,0.000000000000000000e+00,4.846851926827990376e+00,0.000000000000000000e+00,1.000000009974301607e+00,0.000000000000000000e+00,6.564925659458152246e-12,0.000000000000000000e+00 +2.453261599585345820e+01,1.278900000000000006e+02,0.000000000000000000e+00,4.848915121712156662e+00,0.000000000000000000e+00,1.000000009974315152e+00,0.000000000000000000e+00,-1.563332742532630655e-10,0.000000000000000000e+00 +2.453467831283550282e+01,1.279000000000000057e+02,0.000000000000000000e+00,4.850977438714771495e+00,0.000000000000000000e+00,1.000000009973992743e+00,0.000000000000000000e+00,1.753573124536089183e-10,0.000000000000000000e+00 +2.453673975305581578e+01,1.279099999999999966e+02,0.000000000000000000e+00,4.853038878955645785e+00,0.000000000000000000e+00,1.000000009974354231e+00,0.000000000000000000e+00,-3.448291521803274688e-11,0.000000000000000000e+00 +2.453880031763183212e+01,1.279200000000000017e+02,0.000000000000000000e+00,4.855099443552213678e+00,0.000000000000000000e+00,1.000000009974283177e+00,0.000000000000000000e+00,6.522194258782507647e-11,0.000000000000000000e+00 +2.454086000767861009e+01,1.279300000000000068e+02,0.000000000000000000e+00,4.857159133619535218e+00,0.000000000000000000e+00,1.000000009974417514e+00,0.000000000000000000e+00,-1.324405344523780153e-10,0.000000000000000000e+00 +2.454291882430884542e+01,1.279399999999999977e+02,0.000000000000000000e+00,4.859217950270307007e+00,0.000000000000000000e+00,1.000000009974144843e+00,0.000000000000000000e+00,2.870041925832959222e-11,0.000000000000000000e+00 +2.454497676863287836e+01,1.279500000000000028e+02,0.000000000000000000e+00,4.861275894614866644e+00,0.000000000000000000e+00,1.000000009974203907e+00,0.000000000000000000e+00,1.638559689715128137e-10,0.000000000000000000e+00 +2.454703384175869729e+01,1.279600000000000080e+02,0.000000000000000000e+00,4.863332967761202497e+00,0.000000000000000000e+00,1.000000009974540971e+00,0.000000000000000000e+00,-3.179157438879305184e-10,0.000000000000000000e+00 +2.454909004479194579e+01,1.279699999999999989e+02,0.000000000000000000e+00,4.865389170814959030e+00,0.000000000000000000e+00,1.000000009973887272e+00,0.000000000000000000e+00,3.111360238771583572e-10,0.000000000000000000e+00 +2.455114537883592973e+01,1.279800000000000040e+02,0.000000000000000000e+00,4.867444504879441247e+00,0.000000000000000000e+00,1.000000009974526760e+00,0.000000000000000000e+00,-2.087005088507387646e-10,0.000000000000000000e+00 +2.455319984499162445e+01,1.279900000000000091e+02,0.000000000000000000e+00,4.869498971055628900e+00,0.000000000000000000e+00,1.000000009974097992e+00,0.000000000000000000e+00,7.406534930194621022e-11,0.000000000000000000e+00 +2.455525344435768531e+01,1.280000000000000000e+02,0.000000000000000000e+00,4.871552570442173824e+00,0.000000000000000000e+00,1.000000009974250093e+00,0.000000000000000000e+00,-3.807590919881243664e-11,0.000000000000000000e+00 +2.455730617803045135e+01,1.280099999999999909e+02,0.000000000000000000e+00,4.873605304135415039e+00,0.000000000000000000e+00,1.000000009974171933e+00,0.000000000000000000e+00,1.585361124724822901e-10,0.000000000000000000e+00 +2.455935804710395232e+01,1.280200000000000102e+02,0.000000000000000000e+00,4.875657173229380525e+00,0.000000000000000000e+00,1.000000009974497228e+00,0.000000000000000000e+00,-3.142826615373215630e-10,0.000000000000000000e+00 +2.456140905266991226e+01,1.280300000000000011e+02,0.000000000000000000e+00,4.877708178815796991e+00,0.000000000000000000e+00,1.000000009973852633e+00,0.000000000000000000e+00,3.166893128815881953e-10,0.000000000000000000e+00 +2.456345919581776016e+01,1.280399999999999920e+02,0.000000000000000000e+00,4.879758321984092539e+00,0.000000000000000000e+00,1.000000009974501891e+00,0.000000000000000000e+00,-1.826821478726521410e-10,0.000000000000000000e+00 +2.456550847763463707e+01,1.280500000000000114e+02,0.000000000000000000e+00,4.881807603821410879e+00,0.000000000000000000e+00,1.000000009974127524e+00,0.000000000000000000e+00,-2.601549697705293327e-11,0.000000000000000000e+00 +2.456755689920540320e+01,1.280600000000000023e+02,0.000000000000000000e+00,4.883856025412608659e+00,0.000000000000000000e+00,1.000000009974074233e+00,0.000000000000000000e+00,4.348579865510639876e-11,0.000000000000000000e+00 +2.456960446161264144e+01,1.280699999999999932e+02,0.000000000000000000e+00,4.885903587840269680e+00,0.000000000000000000e+00,1.000000009974163273e+00,0.000000000000000000e+00,1.333328005660592683e-10,0.000000000000000000e+00 +2.457165116593666454e+01,1.280800000000000125e+02,0.000000000000000000e+00,4.887950292184708445e+00,0.000000000000000000e+00,1.000000009974436166e+00,0.000000000000000000e+00,-6.653152538025843996e-11,0.000000000000000000e+00 +2.457369701325552569e+01,1.280900000000000034e+02,0.000000000000000000e+00,4.889996139523977270e+00,0.000000000000000000e+00,1.000000009974300053e+00,0.000000000000000000e+00,-2.238913951945962288e-10,0.000000000000000000e+00 +2.457574200464502212e+01,1.280999999999999943e+02,0.000000000000000000e+00,4.892041130933871607e+00,0.000000000000000000e+00,1.000000009973842197e+00,0.000000000000000000e+00,2.126880124102230678e-10,0.000000000000000000e+00 +2.457778614117870220e+01,1.281100000000000136e+02,0.000000000000000000e+00,4.894085267487938040e+00,0.000000000000000000e+00,1.000000009974276960e+00,0.000000000000000000e+00,1.007375747921494889e-10,0.000000000000000000e+00 +2.457982942392786541e+01,1.281200000000000045e+02,0.000000000000000000e+00,4.896128550257483170e+00,0.000000000000000000e+00,1.000000009974482795e+00,0.000000000000000000e+00,-2.100391051995100180e-10,0.000000000000000000e+00 +2.458187185396158370e+01,1.281299999999999955e+02,0.000000000000000000e+00,4.898170980311575384e+00,0.000000000000000000e+00,1.000000009974053805e+00,0.000000000000000000e+00,6.373408899446226907e-11,0.000000000000000000e+00 +2.458391343234669790e+01,1.281400000000000148e+02,0.000000000000000000e+00,4.900212558717052858e+00,0.000000000000000000e+00,1.000000009974183923e+00,0.000000000000000000e+00,7.290040603048332463e-12,0.000000000000000000e+00 +2.458595416014782487e+01,1.281500000000000057e+02,0.000000000000000000e+00,4.902253286538533317e+00,0.000000000000000000e+00,1.000000009974198800e+00,0.000000000000000000e+00,-1.001437382711734009e-11,0.000000000000000000e+00 +2.458799403842736098e+01,1.281599999999999966e+02,0.000000000000000000e+00,4.904293164838416708e+00,0.000000000000000000e+00,1.000000009974178372e+00,0.000000000000000000e+00,-3.985636927896464166e-11,0.000000000000000000e+00 +2.459003306824549995e+01,1.281700000000000159e+02,0.000000000000000000e+00,4.906332194676893188e+00,0.000000000000000000e+00,1.000000009974097104e+00,0.000000000000000000e+00,-1.280073897712641249e-10,0.000000000000000000e+00 +2.459207125066022570e+01,1.281800000000000068e+02,0.000000000000000000e+00,4.908370377111949345e+00,0.000000000000000000e+00,1.000000009973836201e+00,0.000000000000000000e+00,3.281620132407975751e-10,0.000000000000000000e+00 +2.459410858672733013e+01,1.281899999999999977e+02,0.000000000000000000e+00,4.910407713199374413e+00,0.000000000000000000e+00,1.000000009974504778e+00,0.000000000000000000e+00,-2.041096900186995766e-10,0.000000000000000000e+00 +2.459614507750041312e+01,1.281999999999999886e+02,0.000000000000000000e+00,4.912444203992769154e+00,0.000000000000000000e+00,1.000000009974089110e+00,0.000000000000000000e+00,-4.079523679519460482e-11,0.000000000000000000e+00 +2.459818072403088607e+01,1.282100000000000080e+02,0.000000000000000000e+00,4.914479850543545858e+00,0.000000000000000000e+00,1.000000009974006066e+00,0.000000000000000000e+00,1.535365867714137766e-10,0.000000000000000000e+00 +2.460021552736798611e+01,1.282199999999999989e+02,0.000000000000000000e+00,4.916514653900941667e+00,0.000000000000000000e+00,1.000000009974318482e+00,0.000000000000000000e+00,-2.824190528026124059e-10,0.000000000000000000e+00 +2.460224948855877969e+01,1.282299999999999898e+02,0.000000000000000000e+00,4.918548615112022127e+00,0.000000000000000000e+00,1.000000009973744053e+00,0.000000000000000000e+00,3.574565003386186830e-10,0.000000000000000000e+00 +2.460428260864816608e+01,1.282400000000000091e+02,0.000000000000000000e+00,4.920581735221684738e+00,0.000000000000000000e+00,1.000000009974470805e+00,0.000000000000000000e+00,-2.959822591622872402e-10,0.000000000000000000e+00 +2.460631488867888095e+01,1.282500000000000000e+02,0.000000000000000000e+00,4.922614015272672283e+00,0.000000000000000000e+00,1.000000009973869286e+00,0.000000000000000000e+00,1.217646431020681678e-10,0.000000000000000000e+00 +2.460834632969151770e+01,1.282599999999999909e+02,0.000000000000000000e+00,4.924645456305569269e+00,0.000000000000000000e+00,1.000000009974116644e+00,0.000000000000000000e+00,1.105519355243374031e-10,0.000000000000000000e+00 +2.461037693272451321e+01,1.282700000000000102e+02,0.000000000000000000e+00,4.926676059358817916e+00,0.000000000000000000e+00,1.000000009974341131e+00,0.000000000000000000e+00,-3.199779879642271445e-10,0.000000000000000000e+00 +2.461240669881416920e+01,1.282800000000000011e+02,0.000000000000000000e+00,4.928705825468718160e+00,0.000000000000000000e+00,1.000000009973691650e+00,0.000000000000000000e+00,3.562247710564720663e-10,0.000000000000000000e+00 +2.461443562899464865e+01,1.282899999999999920e+02,0.000000000000000000e+00,4.930734755669433866e+00,0.000000000000000000e+00,1.000000009974414406e+00,0.000000000000000000e+00,-2.111952245017775702e-10,0.000000000000000000e+00 +2.461646372429799001e+01,1.283000000000000114e+02,0.000000000000000000e+00,4.932762850993005266e+00,0.000000000000000000e+00,1.000000009973986081e+00,0.000000000000000000e+00,-5.345031686775550999e-11,0.000000000000000000e+00 +2.461849098575411077e+01,1.283100000000000023e+02,0.000000000000000000e+00,4.934790112469345402e+00,0.000000000000000000e+00,1.000000009973877724e+00,0.000000000000000000e+00,2.159710479715988207e-10,0.000000000000000000e+00 +2.462051741439080743e+01,1.283199999999999932e+02,0.000000000000000000e+00,4.936816541126254343e+00,0.000000000000000000e+00,1.000000009974315374e+00,0.000000000000000000e+00,-2.299813917812727852e-10,0.000000000000000000e+00 +2.462254301123377331e+01,1.283300000000000125e+02,0.000000000000000000e+00,4.938842137989422731e+00,0.000000000000000000e+00,1.000000009973849524e+00,0.000000000000000000e+00,1.674574244760995134e-10,0.000000000000000000e+00 +2.462456777730659141e+01,1.283400000000000034e+02,0.000000000000000000e+00,4.940866904082434452e+00,0.000000000000000000e+00,1.000000009974188586e+00,0.000000000000000000e+00,-5.825562978829019065e-11,0.000000000000000000e+00 +2.462659171363074861e+01,1.283499999999999943e+02,0.000000000000000000e+00,4.942890840426779064e+00,0.000000000000000000e+00,1.000000009974070680e+00,0.000000000000000000e+00,1.481682029197662275e-11,0.000000000000000000e+00 +2.462861482122564283e+01,1.283600000000000136e+02,0.000000000000000000e+00,4.944913948041851803e+00,0.000000000000000000e+00,1.000000009974100657e+00,0.000000000000000000e+00,1.328569671417287943e-11,0.000000000000000000e+00 +2.463063710110858295e+01,1.283700000000000045e+02,0.000000000000000000e+00,4.946936227944963349e+00,0.000000000000000000e+00,1.000000009974127524e+00,0.000000000000000000e+00,-2.149648059132823610e-10,0.000000000000000000e+00 +2.463265855429480311e+01,1.283799999999999955e+02,0.000000000000000000e+00,4.948957681151344268e+00,0.000000000000000000e+00,1.000000009973692983e+00,0.000000000000000000e+00,2.715355591514916689e-10,0.000000000000000000e+00 +2.463467918179745553e+01,1.283900000000000148e+02,0.000000000000000000e+00,4.950978308674150341e+00,0.000000000000000000e+00,1.000000009974241655e+00,0.000000000000000000e+00,-1.909550145155369657e-10,0.000000000000000000e+00 +2.463669898462763186e+01,1.284000000000000057e+02,0.000000000000000000e+00,4.952998111524472336e+00,0.000000000000000000e+00,1.000000009973855963e+00,0.000000000000000000e+00,2.206171736788962348e-10,0.000000000000000000e+00 +2.463871796379435608e+01,1.284099999999999966e+02,0.000000000000000000e+00,4.955017090711335115e+00,0.000000000000000000e+00,1.000000009974301385e+00,0.000000000000000000e+00,-1.490818170671617142e-10,0.000000000000000000e+00 +2.464073612030460225e+01,1.284200000000000159e+02,0.000000000000000000e+00,4.957035247241710962e+00,0.000000000000000000e+00,1.000000009974000514e+00,0.000000000000000000e+00,-1.179932104254513810e-10,0.000000000000000000e+00 +2.464275345516328741e+01,1.284300000000000068e+02,0.000000000000000000e+00,4.959052582120518693e+00,0.000000000000000000e+00,1.000000009973762483e+00,0.000000000000000000e+00,1.947900511505550825e-10,0.000000000000000000e+00 +2.464476996937328934e+01,1.284399999999999977e+02,0.000000000000000000e+00,4.961069096350634311e+00,0.000000000000000000e+00,1.000000009974155279e+00,0.000000000000000000e+00,1.861667880483380269e-11,0.000000000000000000e+00 +2.464678566393544656e+01,1.284499999999999886e+02,0.000000000000000000e+00,4.963084790932896340e+00,0.000000000000000000e+00,1.000000009974192805e+00,0.000000000000000000e+00,-1.016068157886380691e-10,0.000000000000000000e+00 +2.464880053984856190e+01,1.284600000000000080e+02,0.000000000000000000e+00,4.965099666866108485e+00,0.000000000000000000e+00,1.000000009973988080e+00,0.000000000000000000e+00,-5.137526947772933894e-11,0.000000000000000000e+00 +2.465081459810941311e+01,1.284699999999999989e+02,0.000000000000000000e+00,4.967113725147047631e+00,0.000000000000000000e+00,1.000000009973884607e+00,0.000000000000000000e+00,6.926342653628894242e-11,0.000000000000000000e+00 +2.465282783971275649e+01,1.284799999999999898e+02,0.000000000000000000e+00,4.969126966770470055e+00,0.000000000000000000e+00,1.000000009974024051e+00,0.000000000000000000e+00,-5.307199282304155936e-11,0.000000000000000000e+00 +2.465484026565133036e+01,1.284900000000000091e+02,0.000000000000000000e+00,4.971139392729116757e+00,0.000000000000000000e+00,1.000000009973917248e+00,0.000000000000000000e+00,-7.031299527434525937e-11,0.000000000000000000e+00 +2.465685187691586933e+01,1.285000000000000000e+02,0.000000000000000000e+00,4.973151004013717902e+00,0.000000000000000000e+00,1.000000009973775805e+00,0.000000000000000000e+00,1.530506230987385675e-10,0.000000000000000000e+00 +2.465886267449509717e+01,1.285099999999999909e+02,0.000000000000000000e+00,4.975161801612999923e+00,0.000000000000000000e+00,1.000000009974083559e+00,0.000000000000000000e+00,-1.216283328181669201e-10,0.000000000000000000e+00 +2.466087265937574102e+01,1.285200000000000102e+02,0.000000000000000000e+00,4.977171786513691742e+00,0.000000000000000000e+00,1.000000009973839088e+00,0.000000000000000000e+00,1.297450963859042132e-10,0.000000000000000000e+00 +2.466288183254253852e+01,1.285300000000000011e+02,0.000000000000000000e+00,4.979180959700527431e+00,0.000000000000000000e+00,1.000000009974099768e+00,0.000000000000000000e+00,-4.201281022378378754e-11,0.000000000000000000e+00 +2.466489019497823421e+01,1.285399999999999920e+02,0.000000000000000000e+00,4.981189322156255983e+00,0.000000000000000000e+00,1.000000009974015391e+00,0.000000000000000000e+00,-4.147673306606138661e-11,0.000000000000000000e+00 +2.466689774766359733e+01,1.285500000000000114e+02,0.000000000000000000e+00,4.983196874861643089e+00,0.000000000000000000e+00,1.000000009973932125e+00,0.000000000000000000e+00,7.225392638165246275e-11,0.000000000000000000e+00 +2.466890449157741827e+01,1.285600000000000023e+02,0.000000000000000000e+00,4.985203618795479130e+00,0.000000000000000000e+00,1.000000009974077120e+00,0.000000000000000000e+00,-1.971455808619182112e-10,0.000000000000000000e+00 +2.467091042769651565e+01,1.285699999999999932e+02,0.000000000000000000e+00,4.987209554934584510e+00,0.000000000000000000e+00,1.000000009973681658e+00,0.000000000000000000e+00,2.048658504312013252e-10,0.000000000000000000e+00 +2.467291555699574701e+01,1.285800000000000125e+02,0.000000000000000000e+00,4.989214684253813203e+00,0.000000000000000000e+00,1.000000009974092441e+00,0.000000000000000000e+00,-9.228208934749352264e-11,0.000000000000000000e+00 +2.467491988044800522e+01,1.285900000000000034e+02,0.000000000000000000e+00,4.991219007726062529e+00,0.000000000000000000e+00,1.000000009973907478e+00,0.000000000000000000e+00,-2.316291098069515958e-11,0.000000000000000000e+00 +2.467692339902423271e+01,1.285999999999999943e+02,0.000000000000000000e+00,4.993222526322273147e+00,0.000000000000000000e+00,1.000000009973861070e+00,0.000000000000000000e+00,-6.541436926643976600e-11,0.000000000000000000e+00 +2.467892611369342504e+01,1.286100000000000136e+02,0.000000000000000000e+00,4.995225241011438833e+00,0.000000000000000000e+00,1.000000009973730064e+00,0.000000000000000000e+00,1.943253252146180056e-10,0.000000000000000000e+00 +2.468092802542263087e+01,1.286200000000000045e+02,0.000000000000000000e+00,4.997227152760610025e+00,0.000000000000000000e+00,1.000000009974119086e+00,0.000000000000000000e+00,-1.557888689712937815e-10,0.000000000000000000e+00 +2.468292913517696263e+01,1.286299999999999955e+02,0.000000000000000000e+00,4.999228262534900935e+00,0.000000000000000000e+00,1.000000009973807336e+00,0.000000000000000000e+00,1.940370309519103120e-10,0.000000000000000000e+00 +2.468492944391960364e+01,1.286400000000000148e+02,0.000000000000000000e+00,5.001228571297491321e+00,0.000000000000000000e+00,1.000000009974195470e+00,0.000000000000000000e+00,-3.251531767558336814e-10,0.000000000000000000e+00 +2.468692895261180453e+01,1.286500000000000057e+02,0.000000000000000000e+00,5.003228080009637146e+00,0.000000000000000000e+00,1.000000009973545323e+00,0.000000000000000000e+00,2.755130709891395669e-10,0.000000000000000000e+00 +2.468892766221290458e+01,1.286599999999999966e+02,0.000000000000000000e+00,5.005226789630669693e+00,0.000000000000000000e+00,1.000000009974095994e+00,0.000000000000000000e+00,-2.330571419818630689e-10,0.000000000000000000e+00 +2.469092557368031748e+01,1.286700000000000159e+02,0.000000000000000000e+00,5.007224701118008880e+00,0.000000000000000000e+00,1.000000009973630366e+00,0.000000000000000000e+00,1.500966761216318404e-10,0.000000000000000000e+00 +2.469292268796954914e+01,1.286800000000000068e+02,0.000000000000000000e+00,5.009221815427159719e+00,0.000000000000000000e+00,1.000000009973930126e+00,0.000000000000000000e+00,9.365319117082090804e-11,0.000000000000000000e+00 +2.469491900603420476e+01,1.286899999999999977e+02,0.000000000000000000e+00,5.011218133511725625e+00,0.000000000000000000e+00,1.000000009974117088e+00,0.000000000000000000e+00,-1.721368481653637725e-10,0.000000000000000000e+00 +2.469691452882598526e+01,1.286999999999999886e+02,0.000000000000000000e+00,5.013213656323408429e+00,0.000000000000000000e+00,1.000000009973773585e+00,0.000000000000000000e+00,3.550970975856697795e-11,0.000000000000000000e+00 +2.469890925729469799e+01,1.287100000000000080e+02,0.000000000000000000e+00,5.015208384812014586e+00,0.000000000000000000e+00,1.000000009973844417e+00,0.000000000000000000e+00,6.547967790803054195e-11,0.000000000000000000e+00 +2.470090319238826027e+01,1.287199999999999989e+02,0.000000000000000000e+00,5.017202319925463172e+00,0.000000000000000000e+00,1.000000009973974979e+00,0.000000000000000000e+00,-5.993549763427584493e-11,0.000000000000000000e+00 +2.470289633505270643e+01,1.287299999999999898e+02,0.000000000000000000e+00,5.019195462609788549e+00,0.000000000000000000e+00,1.000000009973855519e+00,0.000000000000000000e+00,-8.982751304705805354e-11,0.000000000000000000e+00 +2.470488868623219147e+01,1.287400000000000091e+02,0.000000000000000000e+00,5.021187813809145695e+00,0.000000000000000000e+00,1.000000009973676551e+00,0.000000000000000000e+00,8.473450249224413719e-12,0.000000000000000000e+00 +2.470688024686899809e+01,1.287500000000000000e+02,0.000000000000000000e+00,5.023179374465816416e+00,0.000000000000000000e+00,1.000000009973693427e+00,0.000000000000000000e+00,4.829551578974685092e-11,0.000000000000000000e+00 +2.470887101790354023e+01,1.287599999999999909e+02,0.000000000000000000e+00,5.025170145520214682e+00,0.000000000000000000e+00,1.000000009973789572e+00,0.000000000000000000e+00,7.085405689733674230e-11,0.000000000000000000e+00 +2.471086100027437027e+01,1.287700000000000102e+02,0.000000000000000000e+00,5.027160127910891063e+00,0.000000000000000000e+00,1.000000009973930570e+00,0.000000000000000000e+00,-1.021372212814611934e-10,0.000000000000000000e+00 +2.471285019491817891e+01,1.287800000000000011e+02,0.000000000000000000e+00,5.029149322574538061e+00,0.000000000000000000e+00,1.000000009973727400e+00,0.000000000000000000e+00,2.970409962010538693e-11,0.000000000000000000e+00 +2.471483860276980238e+01,1.287899999999999920e+02,0.000000000000000000e+00,5.031137730445994549e+00,0.000000000000000000e+00,1.000000009973786463e+00,0.000000000000000000e+00,7.239047693128341073e-11,0.000000000000000000e+00 +2.471682622476223656e+01,1.288000000000000114e+02,0.000000000000000000e+00,5.033125352458252877e+00,0.000000000000000000e+00,1.000000009973930348e+00,0.000000000000000000e+00,8.694759410704567711e-11,0.000000000000000000e+00 +2.471881306182662996e+01,1.288100000000000023e+02,0.000000000000000000e+00,5.035112189542462424e+00,0.000000000000000000e+00,1.000000009974103099e+00,0.000000000000000000e+00,-3.131572610761343464e-10,0.000000000000000000e+00 +2.472079911489229431e+01,1.288199999999999932e+02,0.000000000000000000e+00,5.037098242627934930e+00,0.000000000000000000e+00,1.000000009973481152e+00,0.000000000000000000e+00,2.937077244778087486e-10,0.000000000000000000e+00 +2.472278438488670815e+01,1.288300000000000125e+02,0.000000000000000000e+00,5.039083512642148044e+00,0.000000000000000000e+00,1.000000009974064241e+00,0.000000000000000000e+00,-2.720049079137490573e-10,0.000000000000000000e+00 +2.472476887273552393e+01,1.288400000000000034e+02,0.000000000000000000e+00,5.041068000510755986e+00,0.000000000000000000e+00,1.000000009973524451e+00,0.000000000000000000e+00,9.760661826442037913e-11,0.000000000000000000e+00 +2.472675257936256799e+01,1.288499999999999943e+02,0.000000000000000000e+00,5.043051707157585994e+00,0.000000000000000000e+00,1.000000009973718074e+00,0.000000000000000000e+00,1.329181737207652907e-10,0.000000000000000000e+00 +2.472873550568985479e+01,1.288600000000000136e+02,0.000000000000000000e+00,5.045034633504651644e+00,0.000000000000000000e+00,1.000000009973981641e+00,0.000000000000000000e+00,-7.987188008071338010e-11,0.000000000000000000e+00 +2.473071765263758692e+01,1.288700000000000045e+02,0.000000000000000000e+00,5.047016780472152853e+00,0.000000000000000000e+00,1.000000009973823323e+00,0.000000000000000000e+00,4.706783957693758462e-12,0.000000000000000000e+00 +2.473269902112415508e+01,1.288799999999999955e+02,0.000000000000000000e+00,5.048998148978481204e+00,0.000000000000000000e+00,1.000000009973832649e+00,0.000000000000000000e+00,-1.958566590302225686e-10,0.000000000000000000e+00 +2.473467961206614518e+01,1.288900000000000148e+02,0.000000000000000000e+00,5.050978739940227058e+00,0.000000000000000000e+00,1.000000009973444737e+00,0.000000000000000000e+00,3.262567361713956963e-10,0.000000000000000000e+00 +2.473665942637835613e+01,1.289000000000000057e+02,0.000000000000000000e+00,5.052958554272182212e+00,0.000000000000000000e+00,1.000000009974090664e+00,0.000000000000000000e+00,-3.622880478225648547e-10,0.000000000000000000e+00 +2.473863846497378205e+01,1.289099999999999966e+02,0.000000000000000000e+00,5.054937592887348785e+00,0.000000000000000000e+00,1.000000009973373682e+00,0.000000000000000000e+00,3.425630786478215254e-10,0.000000000000000000e+00 +2.474061672876364071e+01,1.289200000000000159e+02,0.000000000000000000e+00,5.056915856696936551e+00,0.000000000000000000e+00,1.000000009974051363e+00,0.000000000000000000e+00,-1.664079829405386928e-10,0.000000000000000000e+00 +2.474259421865735931e+01,1.289300000000000068e+02,0.000000000000000000e+00,5.058893346610378039e+00,0.000000000000000000e+00,1.000000009973722293e+00,0.000000000000000000e+00,4.605529895474480095e-11,0.000000000000000000e+00 +2.474457093556258869e+01,1.289399999999999977e+02,0.000000000000000000e+00,5.060870063535323204e+00,0.000000000000000000e+00,1.000000009973813331e+00,0.000000000000000000e+00,-3.213893236367010070e-11,0.000000000000000000e+00 +2.474654688038521044e+01,1.289499999999999886e+02,0.000000000000000000e+00,5.062846008377651863e+00,0.000000000000000000e+00,1.000000009973749826e+00,0.000000000000000000e+00,-4.507952343323215286e-11,0.000000000000000000e+00 +2.474852205402933336e+01,1.289600000000000080e+02,0.000000000000000000e+00,5.064821182041474579e+00,0.000000000000000000e+00,1.000000009973660786e+00,0.000000000000000000e+00,-8.805744989933639002e-11,0.000000000000000000e+00 +2.475049645739730408e+01,1.289699999999999989e+02,0.000000000000000000e+00,5.066795585429138882e+00,0.000000000000000000e+00,1.000000009973486925e+00,0.000000000000000000e+00,2.046474361060558042e-10,0.000000000000000000e+00 +2.475247009138971421e+01,1.289799999999999898e+02,0.000000000000000000e+00,5.068769219441233709e+00,0.000000000000000000e+00,1.000000009973890824e+00,0.000000000000000000e+00,-1.655599995275659210e-10,0.000000000000000000e+00 +2.475444295690540031e+01,1.289900000000000091e+02,0.000000000000000000e+00,5.070742084976595621e+00,0.000000000000000000e+00,1.000000009973564197e+00,0.000000000000000000e+00,8.759742580437082910e-11,0.000000000000000000e+00 +2.475641505484144389e+01,1.290000000000000000e+02,0.000000000000000000e+00,5.072714182932309690e+00,0.000000000000000000e+00,1.000000009973736947e+00,0.000000000000000000e+00,-2.646966719119997952e-11,0.000000000000000000e+00 +2.475838638609319275e+01,1.290099999999999909e+02,0.000000000000000000e+00,5.074685514203719272e+00,0.000000000000000000e+00,1.000000009973684767e+00,0.000000000000000000e+00,1.038915629990772866e-10,0.000000000000000000e+00 +2.476035695155424676e+01,1.290200000000000102e+02,0.000000000000000000e+00,5.076656079684426892e+00,0.000000000000000000e+00,1.000000009973889492e+00,0.000000000000000000e+00,-2.774147714235869612e-10,0.000000000000000000e+00 +2.476232675211647560e+01,1.290300000000000011e+02,0.000000000000000000e+00,5.078625880266301351e+00,0.000000000000000000e+00,1.000000009973343040e+00,0.000000000000000000e+00,3.669475526632336145e-10,0.000000000000000000e+00 +2.476429578867001524e+01,1.290399999999999920e+02,0.000000000000000000e+00,5.080594916839479502e+00,0.000000000000000000e+00,1.000000009974065573e+00,0.000000000000000000e+00,-3.146323029460453560e-10,0.000000000000000000e+00 +2.476626406210328213e+01,1.290500000000000114e+02,0.000000000000000000e+00,5.082563190292376909e+00,0.000000000000000000e+00,1.000000009973446291e+00,0.000000000000000000e+00,1.415208892436101792e-10,0.000000000000000000e+00 +2.476823157330296610e+01,1.290600000000000023e+02,0.000000000000000000e+00,5.084530701511683404e+00,0.000000000000000000e+00,1.000000009973724735e+00,0.000000000000000000e+00,-1.518495061588346366e-10,0.000000000000000000e+00 +2.477019832315404457e+01,1.290699999999999932e+02,0.000000000000000000e+00,5.086497451382377299e+00,0.000000000000000000e+00,1.000000009973426085e+00,0.000000000000000000e+00,1.337244311380544119e-10,0.000000000000000000e+00 +2.477216431253978257e+01,1.290800000000000125e+02,0.000000000000000000e+00,5.088463440787722725e+00,0.000000000000000000e+00,1.000000009973688986e+00,0.000000000000000000e+00,3.479986831506340188e-11,0.000000000000000000e+00 +2.477412954234173981e+01,1.290900000000000034e+02,0.000000000000000000e+00,5.090428670609279393e+00,0.000000000000000000e+00,1.000000009973757376e+00,0.000000000000000000e+00,-2.961391824428962982e-11,0.000000000000000000e+00 +2.477609401343977069e+01,1.290999999999999943e+02,0.000000000000000000e+00,5.092393141726903494e+00,0.000000000000000000e+00,1.000000009973699200e+00,0.000000000000000000e+00,-9.588661829394804356e-11,0.000000000000000000e+00 +2.477805772671203499e+01,1.291100000000000136e+02,0.000000000000000000e+00,5.094356855018753905e+00,0.000000000000000000e+00,1.000000009973510906e+00,0.000000000000000000e+00,3.393523365659292783e-11,0.000000000000000000e+00 +2.478002068303500138e+01,1.291200000000000045e+02,0.000000000000000000e+00,5.096319811361296637e+00,0.000000000000000000e+00,1.000000009973577519e+00,0.000000000000000000e+00,1.017317676857711007e-10,0.000000000000000000e+00 +2.478198288328344390e+01,1.291299999999999955e+02,0.000000000000000000e+00,5.098282011629310162e+00,0.000000000000000000e+00,1.000000009973777138e+00,0.000000000000000000e+00,-1.478452095679622989e-10,0.000000000000000000e+00 +2.478394432833045968e+01,1.291400000000000148e+02,0.000000000000000000e+00,5.100243456695888966e+00,0.000000000000000000e+00,1.000000009973487147e+00,0.000000000000000000e+00,1.884449288156888497e-10,0.000000000000000000e+00 +2.478590501904746191e+01,1.291500000000000057e+02,0.000000000000000000e+00,5.102204147432447101e+00,0.000000000000000000e+00,1.000000009973856629e+00,0.000000000000000000e+00,-6.015788761108152953e-11,0.000000000000000000e+00 +2.478786495630419395e+01,1.291599999999999966e+02,0.000000000000000000e+00,5.104164084708726179e+00,0.000000000000000000e+00,1.000000009973738724e+00,0.000000000000000000e+00,-2.128435239408640863e-10,0.000000000000000000e+00 +2.478982414096872233e+01,1.291700000000000159e+02,0.000000000000000000e+00,5.106123269392795372e+00,0.000000000000000000e+00,1.000000009973321724e+00,0.000000000000000000e+00,1.856009522071212863e-10,0.000000000000000000e+00 +2.479178257390745443e+01,1.291800000000000068e+02,0.000000000000000000e+00,5.108081702351058517e+00,0.000000000000000000e+00,1.000000009973685211e+00,0.000000000000000000e+00,-2.563341682762707739e-11,0.000000000000000000e+00 +2.479374025598513143e+01,1.291899999999999977e+02,0.000000000000000000e+00,5.110039384448260336e+00,0.000000000000000000e+00,1.000000009973635029e+00,0.000000000000000000e+00,7.908557033610012690e-11,0.000000000000000000e+00 +2.479569718806483891e+01,1.291999999999999886e+02,0.000000000000000000e+00,5.111996316547486430e+00,0.000000000000000000e+00,1.000000009973789794e+00,0.000000000000000000e+00,-1.917169040998857370e-10,0.000000000000000000e+00 +2.479765337100801403e+01,1.292100000000000080e+02,0.000000000000000000e+00,5.113952499510171279e+00,0.000000000000000000e+00,1.000000009973414761e+00,0.000000000000000000e+00,9.845006625653504130e-11,0.000000000000000000e+00 +2.479960880567444192e+01,1.292199999999999989e+02,0.000000000000000000e+00,5.115907934196100015e+00,0.000000000000000000e+00,1.000000009973607273e+00,0.000000000000000000e+00,3.294283292636077448e-11,0.000000000000000000e+00 +2.480156349292226281e+01,1.292299999999999898e+02,0.000000000000000000e+00,5.117862621463416417e+00,0.000000000000000000e+00,1.000000009973671666e+00,0.000000000000000000e+00,-1.403446323046635074e-10,0.000000000000000000e+00 +2.480351743360798267e+01,1.292400000000000091e+02,0.000000000000000000e+00,5.119816562168623797e+00,0.000000000000000000e+00,1.000000009973397441e+00,0.000000000000000000e+00,6.343498263761331918e-11,0.000000000000000000e+00 +2.480547062858646967e+01,1.292500000000000000e+02,0.000000000000000000e+00,5.121769757166590331e+00,0.000000000000000000e+00,1.000000009973521342e+00,0.000000000000000000e+00,-2.945506876419805045e-11,0.000000000000000000e+00 +2.480742307871096131e+01,1.292599999999999909e+02,0.000000000000000000e+00,5.123722207310555277e+00,0.000000000000000000e+00,1.000000009973463833e+00,0.000000000000000000e+00,7.429147522439265928e-11,0.000000000000000000e+00 +2.480937478483307146e+01,1.292700000000000102e+02,0.000000000000000000e+00,5.125673913452130748e+00,0.000000000000000000e+00,1.000000009973608828e+00,0.000000000000000000e+00,-5.997935819988581714e-11,0.000000000000000000e+00 +2.481132574780279043e+01,1.292800000000000011e+02,0.000000000000000000e+00,5.127624876441307933e+00,0.000000000000000000e+00,1.000000009973491810e+00,0.000000000000000000e+00,6.979381626545147840e-11,0.000000000000000000e+00 +2.481327596846849204e+01,1.292899999999999920e+02,0.000000000000000000e+00,5.129575097126459760e+00,0.000000000000000000e+00,1.000000009973627924e+00,0.000000000000000000e+00,3.644782322799116298e-11,0.000000000000000000e+00 +2.481522544767693716e+01,1.293000000000000114e+02,0.000000000000000000e+00,5.131524576354347111e+00,0.000000000000000000e+00,1.000000009973698978e+00,0.000000000000000000e+00,-1.171331312941840883e-10,0.000000000000000000e+00 +2.481717418627327376e+01,1.293100000000000023e+02,0.000000000000000000e+00,5.133473314970121493e+00,0.000000000000000000e+00,1.000000009973470716e+00,0.000000000000000000e+00,-1.096545372059333659e-10,0.000000000000000000e+00 +2.481912218510105461e+01,1.293199999999999932e+02,0.000000000000000000e+00,5.135421313817329469e+00,0.000000000000000000e+00,1.000000009973257109e+00,0.000000000000000000e+00,1.102662941057398974e-10,0.000000000000000000e+00 +2.482106944500222312e+01,1.293300000000000125e+02,0.000000000000000000e+00,5.137368573737917998e+00,0.000000000000000000e+00,1.000000009973471826e+00,0.000000000000000000e+00,1.294722846976745211e-10,0.000000000000000000e+00 +2.482301596681713107e+01,1.293400000000000034e+02,0.000000000000000000e+00,5.139315095572238867e+00,0.000000000000000000e+00,1.000000009973723847e+00,0.000000000000000000e+00,6.276364544898730237e-12,0.000000000000000000e+00 +2.482496175138453509e+01,1.293499999999999943e+02,0.000000000000000000e+00,5.141260880159051361e+00,0.000000000000000000e+00,1.000000009973736059e+00,0.000000000000000000e+00,-1.972666208364080140e-10,0.000000000000000000e+00 +2.482690679954161084e+01,1.293600000000000136e+02,0.000000000000000000e+00,5.143205928335526700e+00,0.000000000000000000e+00,1.000000009973352366e+00,0.000000000000000000e+00,5.550222684049957225e-11,0.000000000000000000e+00 +2.482885111212394591e+01,1.293700000000000045e+02,0.000000000000000000e+00,5.145150240937252484e+00,0.000000000000000000e+00,1.000000009973460280e+00,0.000000000000000000e+00,-1.045344360063890283e-10,0.000000000000000000e+00 +2.483079468996554695e+01,1.293799999999999955e+02,0.000000000000000000e+00,5.147093818798238907e+00,0.000000000000000000e+00,1.000000009973257109e+00,0.000000000000000000e+00,1.017167128021341788e-10,0.000000000000000000e+00 +2.483273753389885030e+01,1.293900000000000148e+02,0.000000000000000000e+00,5.149036662750919646e+00,0.000000000000000000e+00,1.000000009973454729e+00,0.000000000000000000e+00,4.653295352906870551e-11,0.000000000000000000e+00 +2.483467964475471845e+01,1.294000000000000057e+02,0.000000000000000000e+00,5.150978773626158969e+00,0.000000000000000000e+00,1.000000009973545101e+00,0.000000000000000000e+00,4.689362891744875156e-11,0.000000000000000000e+00 +2.483662102336245070e+01,1.294099999999999966e+02,0.000000000000000000e+00,5.152920152253253505e+00,0.000000000000000000e+00,1.000000009973636139e+00,0.000000000000000000e+00,-4.759780976775992295e-11,0.000000000000000000e+00 +2.483856167054977959e+01,1.294200000000000159e+02,0.000000000000000000e+00,5.154860799459937581e+00,0.000000000000000000e+00,1.000000009973543769e+00,0.000000000000000000e+00,-1.478834866320219714e-10,0.000000000000000000e+00 +2.484050158714288159e+01,1.294300000000000068e+02,0.000000000000000000e+00,5.156800716072386770e+00,0.000000000000000000e+00,1.000000009973256887e+00,0.000000000000000000e+00,7.580163328224464114e-11,0.000000000000000000e+00 +2.484244077396637707e+01,1.294399999999999977e+02,0.000000000000000000e+00,5.158739902915222331e+00,0.000000000000000000e+00,1.000000009973403881e+00,0.000000000000000000e+00,1.145470363653805007e-11,0.000000000000000000e+00 +2.484437923184333741e+01,1.294499999999999886e+02,0.000000000000000000e+00,5.160678360811516541e+00,0.000000000000000000e+00,1.000000009973426085e+00,0.000000000000000000e+00,-4.469013072309050520e-12,0.000000000000000000e+00 +2.484631696159528857e+01,1.294600000000000080e+02,0.000000000000000000e+00,5.162616090582794470e+00,0.000000000000000000e+00,1.000000009973417425e+00,0.000000000000000000e+00,1.328597687196943750e-10,0.000000000000000000e+00 +2.484825396404221465e+01,1.294699999999999989e+02,0.000000000000000000e+00,5.164553093049039312e+00,0.000000000000000000e+00,1.000000009973674775e+00,0.000000000000000000e+00,-1.794681201566061008e-10,0.000000000000000000e+00 +2.485019024000256138e+01,1.294799999999999898e+02,0.000000000000000000e+00,5.166489369028696821e+00,0.000000000000000000e+00,1.000000009973327275e+00,0.000000000000000000e+00,1.179312441337621047e-10,0.000000000000000000e+00 +2.485212579029323621e+01,1.294900000000000091e+02,0.000000000000000000e+00,5.168424919338677093e+00,0.000000000000000000e+00,1.000000009973555537e+00,0.000000000000000000e+00,-4.429816555495079301e-11,0.000000000000000000e+00 +2.485406061572962599e+01,1.295000000000000000e+02,0.000000000000000000e+00,5.170359744794362555e+00,0.000000000000000000e+00,1.000000009973469828e+00,0.000000000000000000e+00,-7.347523115860158905e-11,0.000000000000000000e+00 +2.485599471712558284e+01,1.295099999999999909e+02,0.000000000000000000e+00,5.172293846209607970e+00,0.000000000000000000e+00,1.000000009973327719e+00,0.000000000000000000e+00,1.536666164587353772e-10,0.000000000000000000e+00 +2.485792809529343828e+01,1.295200000000000102e+02,0.000000000000000000e+00,5.174227224396746649e+00,0.000000000000000000e+00,1.000000009973624815e+00,0.000000000000000000e+00,-1.870424242448965507e-10,0.000000000000000000e+00 +2.485986075104401039e+01,1.295300000000000011e+02,0.000000000000000000e+00,5.176159880166594895e+00,0.000000000000000000e+00,1.000000009973263326e+00,0.000000000000000000e+00,-1.482646504550301837e-11,0.000000000000000000e+00 +2.486179268518660024e+01,1.295399999999999920e+02,0.000000000000000000e+00,5.178091814328452891e+00,0.000000000000000000e+00,1.000000009973234683e+00,0.000000000000000000e+00,9.094659747818769679e-11,0.000000000000000000e+00 +2.486372389852899900e+01,1.295500000000000114e+02,0.000000000000000000e+00,5.180023027690112691e+00,0.000000000000000000e+00,1.000000009973410320e+00,0.000000000000000000e+00,2.933000225049339720e-11,0.000000000000000000e+00 +2.486565439187749149e+01,1.295600000000000023e+02,0.000000000000000000e+00,5.181953521057860002e+00,0.000000000000000000e+00,1.000000009973466941e+00,0.000000000000000000e+00,-5.914211586741080172e-11,0.000000000000000000e+00 +2.486758416603686328e+01,1.295699999999999932e+02,0.000000000000000000e+00,5.183883295236477728e+00,0.000000000000000000e+00,1.000000009973352810e+00,0.000000000000000000e+00,-2.992738627497458161e-11,0.000000000000000000e+00 +2.486951322181039714e+01,1.295800000000000125e+02,0.000000000000000000e+00,5.185812351029250422e+00,0.000000000000000000e+00,1.000000009973295079e+00,0.000000000000000000e+00,2.717496705091144760e-11,0.000000000000000000e+00 +2.487144155999988371e+01,1.295900000000000034e+02,0.000000000000000000e+00,5.187740689237968716e+00,0.000000000000000000e+00,1.000000009973347481e+00,0.000000000000000000e+00,2.488125236677965253e-11,0.000000000000000000e+00 +2.487336918140562148e+01,1.295999999999999943e+02,0.000000000000000000e+00,5.189668310662932882e+00,0.000000000000000000e+00,1.000000009973395443e+00,0.000000000000000000e+00,1.185755647375365591e-10,0.000000000000000000e+00 +2.487529608682642746e+01,1.296100000000000136e+02,0.000000000000000000e+00,5.191595216102956378e+00,0.000000000000000000e+00,1.000000009973623927e+00,0.000000000000000000e+00,-2.504959884983942570e-10,0.000000000000000000e+00 +2.487722227705963007e+01,1.296200000000000045e+02,0.000000000000000000e+00,5.193521406355370296e+00,0.000000000000000000e+00,1.000000009973141424e+00,0.000000000000000000e+00,3.782474381007897283e-11,0.000000000000000000e+00 +2.487914775290108338e+01,1.296299999999999955e+02,0.000000000000000000e+00,5.195446882216025131e+00,0.000000000000000000e+00,1.000000009973214254e+00,0.000000000000000000e+00,1.920778882367120460e-10,0.000000000000000000e+00 +2.488107251514515994e+01,1.296400000000000148e+02,0.000000000000000000e+00,5.197371644479298780e+00,0.000000000000000000e+00,1.000000009973583959e+00,0.000000000000000000e+00,-9.786329867630272917e-11,0.000000000000000000e+00 +2.488299656458476861e+01,1.296500000000000057e+02,0.000000000000000000e+00,5.199295693938097429e+00,0.000000000000000000e+00,1.000000009973395665e+00,0.000000000000000000e+00,-1.794055017518792706e-10,0.000000000000000000e+00 +2.488491990201134740e+01,1.296599999999999966e+02,0.000000000000000000e+00,5.201219031383858216e+00,0.000000000000000000e+00,1.000000009973050608e+00,0.000000000000000000e+00,1.248449737573309745e-10,0.000000000000000000e+00 +2.488684252821487064e+01,1.296700000000000159e+02,0.000000000000000000e+00,5.203141657606555448e+00,0.000000000000000000e+00,1.000000009973290638e+00,0.000000000000000000e+00,3.465988601196660721e-11,0.000000000000000000e+00 +2.488876444398385246e+01,1.296800000000000068e+02,0.000000000000000000e+00,5.205063573394705045e+00,0.000000000000000000e+00,1.000000009973357251e+00,0.000000000000000000e+00,-2.635124329262145704e-11,0.000000000000000000e+00 +2.489068565010535039e+01,1.296899999999999977e+02,0.000000000000000000e+00,5.206984779535365426e+00,0.000000000000000000e+00,1.000000009973306625e+00,0.000000000000000000e+00,1.296081006487513897e-10,0.000000000000000000e+00 +2.489260614736497246e+01,1.296999999999999886e+02,0.000000000000000000e+00,5.208905276814142837e+00,0.000000000000000000e+00,1.000000009973555537e+00,0.000000000000000000e+00,-2.700682748848720172e-10,0.000000000000000000e+00 +2.489452593654687718e+01,1.297100000000000080e+02,0.000000000000000000e+00,5.210825066015195794e+00,0.000000000000000000e+00,1.000000009973037063e+00,0.000000000000000000e+00,1.739024496454541762e-10,0.000000000000000000e+00 +2.489644501843377711e+01,1.297199999999999989e+02,0.000000000000000000e+00,5.212744147921235971e+00,0.000000000000000000e+00,1.000000009973370796e+00,0.000000000000000000e+00,-2.789482732910059993e-11,0.000000000000000000e+00 +2.489836339380694596e+01,1.297299999999999898e+02,0.000000000000000000e+00,5.214662523313537079e+00,0.000000000000000000e+00,1.000000009973317283e+00,0.000000000000000000e+00,4.932601515975780490e-11,0.000000000000000000e+00 +2.490028106344621506e+01,1.297400000000000091e+02,0.000000000000000000e+00,5.216580192971933094e+00,0.000000000000000000e+00,1.000000009973411874e+00,0.000000000000000000e+00,-1.140938785688073553e-10,0.000000000000000000e+00 +2.490219802812998751e+01,1.297500000000000000e+02,0.000000000000000000e+00,5.218497157674825360e+00,0.000000000000000000e+00,1.000000009973193160e+00,0.000000000000000000e+00,1.736949970377779905e-10,0.000000000000000000e+00 +2.490411428863523469e+01,1.297599999999999909e+02,0.000000000000000000e+00,5.220413418199184363e+00,0.000000000000000000e+00,1.000000009973526005e+00,0.000000000000000000e+00,-3.265366776765055332e-10,0.000000000000000000e+00 +2.490602984573749978e+01,1.297700000000000102e+02,0.000000000000000000e+00,5.222328975320555955e+00,0.000000000000000000e+00,1.000000009972900505e+00,0.000000000000000000e+00,2.941879764326194044e-10,0.000000000000000000e+00 +2.490794470021090845e+01,1.297800000000000011e+02,0.000000000000000000e+00,5.224243829813060458e+00,0.000000000000000000e+00,1.000000009973463833e+00,0.000000000000000000e+00,-1.663461735457600489e-10,0.000000000000000000e+00 +2.490985885282816170e+01,1.297899999999999920e+02,0.000000000000000000e+00,5.226157982449403328e+00,0.000000000000000000e+00,1.000000009973145421e+00,0.000000000000000000e+00,-3.318858927637900503e-11,0.000000000000000000e+00 +2.491177230436054657e+01,1.298000000000000114e+02,0.000000000000000000e+00,5.228071434000870710e+00,0.000000000000000000e+00,1.000000009973081916e+00,0.000000000000000000e+00,1.925875128040975583e-10,0.000000000000000000e+00 +2.491368505557793966e+01,1.298100000000000023e+02,0.000000000000000000e+00,5.229984185237339211e+00,0.000000000000000000e+00,1.000000009973450288e+00,0.000000000000000000e+00,1.161289772175186754e-11,0.000000000000000000e+00 +2.491559710724880716e+01,1.298199999999999932e+02,0.000000000000000000e+00,5.231896236927277677e+00,0.000000000000000000e+00,1.000000009973472492e+00,0.000000000000000000e+00,-3.447968140157833528e-10,0.000000000000000000e+00 +2.491750846014021548e+01,1.298300000000000125e+02,0.000000000000000000e+00,5.233807589837748964e+00,0.000000000000000000e+00,1.000000009972813464e+00,0.000000000000000000e+00,3.327203208437595800e-10,0.000000000000000000e+00 +2.491941911501782769e+01,1.298400000000000034e+02,0.000000000000000000e+00,5.235718244734414384e+00,0.000000000000000000e+00,1.000000009973449178e+00,0.000000000000000000e+00,-1.495056004047969133e-10,0.000000000000000000e+00 +2.492132907264590713e+01,1.298499999999999943e+02,0.000000000000000000e+00,5.237628202381541698e+00,0.000000000000000000e+00,1.000000009973163628e+00,0.000000000000000000e+00,1.545609835887932986e-10,0.000000000000000000e+00 +2.492323833378732445e+01,1.298600000000000136e+02,0.000000000000000000e+00,5.239537463542000673e+00,0.000000000000000000e+00,1.000000009973458726e+00,0.000000000000000000e+00,-2.140676287991034833e-10,0.000000000000000000e+00 +2.492514689920356119e+01,1.298700000000000045e+02,0.000000000000000000e+00,5.241446028977273741e+00,0.000000000000000000e+00,1.000000009973050163e+00,0.000000000000000000e+00,-3.165630690653161307e-11,0.000000000000000000e+00 +2.492705476965471334e+01,1.298799999999999955e+02,0.000000000000000000e+00,5.243353899447454225e+00,0.000000000000000000e+00,1.000000009972989767e+00,0.000000000000000000e+00,2.240033248343409802e-10,0.000000000000000000e+00 +2.492896194589949488e+01,1.298900000000000148e+02,0.000000000000000000e+00,5.245261075711254328e+00,0.000000000000000000e+00,1.000000009973416981e+00,0.000000000000000000e+00,-1.689953470686462653e-10,0.000000000000000000e+00 +2.493086842869523423e+01,1.299000000000000057e+02,0.000000000000000000e+00,5.247167558526006914e+00,0.000000000000000000e+00,1.000000009973094794e+00,0.000000000000000000e+00,2.609835754418700044e-11,0.000000000000000000e+00 +2.493277421879788847e+01,1.299099999999999966e+02,0.000000000000000000e+00,5.249073348647666393e+00,0.000000000000000000e+00,1.000000009973144532e+00,0.000000000000000000e+00,9.475746037713844548e-11,0.000000000000000000e+00 +2.493467931696203976e+01,1.299200000000000159e+02,0.000000000000000000e+00,5.250978446830816715e+00,0.000000000000000000e+00,1.000000009973325055e+00,0.000000000000000000e+00,-1.873683955557119869e-10,0.000000000000000000e+00 +2.493658372394090250e+01,1.299300000000000068e+02,0.000000000000000000e+00,5.252882853828672260e+00,0.000000000000000000e+00,1.000000009972968229e+00,0.000000000000000000e+00,1.839372267939468752e-10,0.000000000000000000e+00 +2.493848744048632327e+01,1.299399999999999977e+02,0.000000000000000000e+00,5.254786570393080503e+00,0.000000000000000000e+00,1.000000009973318393e+00,0.000000000000000000e+00,1.166797007988291870e-11,0.000000000000000000e+00 +2.494039046734879150e+01,1.299499999999999886e+02,0.000000000000000000e+00,5.256689597274529113e+00,0.000000000000000000e+00,1.000000009973340598e+00,0.000000000000000000e+00,-1.843039692882904441e-10,0.000000000000000000e+00 +2.494229280527743597e+01,1.299600000000000080e+02,0.000000000000000000e+00,5.258591935222145075e+00,0.000000000000000000e+00,1.000000009972989989e+00,0.000000000000000000e+00,1.213180005498373025e-10,0.000000000000000000e+00 +2.494419445502002475e+01,1.299699999999999989e+02,0.000000000000000000e+00,5.260493584983700011e+00,0.000000000000000000e+00,1.000000009973220694e+00,0.000000000000000000e+00,-1.611928623307946635e-11,0.000000000000000000e+00 +2.494609541732298297e+01,1.299799999999999898e+02,0.000000000000000000e+00,5.262394547305615511e+00,0.000000000000000000e+00,1.000000009973190052e+00,0.000000000000000000e+00,-6.648687150649691066e-11,0.000000000000000000e+00 +2.494799569293137864e+01,1.299900000000000091e+02,0.000000000000000000e+00,5.264294822932963136e+00,0.000000000000000000e+00,1.000000009973063708e+00,0.000000000000000000e+00,1.426068082283785716e-11,0.000000000000000000e+00 +2.494989528258894040e+01,1.300000000000000000e+02,0.000000000000000000e+00,5.266194412609469744e+00,0.000000000000000000e+00,1.000000009973090798e+00,0.000000000000000000e+00,2.607606028907997760e-11,0.000000000000000000e+00 +2.495179418703805396e+01,1.300099999999999909e+02,0.000000000000000000e+00,5.268093317077521043e+00,0.000000000000000000e+00,1.000000009973140314e+00,0.000000000000000000e+00,1.801417616919960810e-11,0.000000000000000000e+00 +2.495369240701976565e+01,1.300200000000000102e+02,0.000000000000000000e+00,5.269991537078164257e+00,0.000000000000000000e+00,1.000000009973174508e+00,0.000000000000000000e+00,4.259430407263957135e-11,0.000000000000000000e+00 +2.495558994327378954e+01,1.300300000000000011e+02,0.000000000000000000e+00,5.271889073351111676e+00,0.000000000000000000e+00,1.000000009973255333e+00,0.000000000000000000e+00,-9.142343251971536539e-11,0.000000000000000000e+00 +2.495748679653850388e+01,1.300399999999999920e+02,0.000000000000000000e+00,5.273785926634744214e+00,0.000000000000000000e+00,1.000000009973081916e+00,0.000000000000000000e+00,-7.904356059636912911e-11,0.000000000000000000e+00 +2.495938296755096175e+01,1.300500000000000114e+02,0.000000000000000000e+00,5.275682097666114068e+00,0.000000000000000000e+00,1.000000009972932036e+00,0.000000000000000000e+00,1.416267027227376371e-10,0.000000000000000000e+00 +2.496127845704689463e+01,1.300600000000000023e+02,0.000000000000000000e+00,5.277577587180949159e+00,0.000000000000000000e+00,1.000000009973200488e+00,0.000000000000000000e+00,-1.062874870688262016e-10,0.000000000000000000e+00 +2.496317326576070528e+01,1.300699999999999932e+02,0.000000000000000000e+00,5.279472395913656690e+00,0.000000000000000000e+00,1.000000009972999093e+00,0.000000000000000000e+00,-1.371565683965009882e-11,0.000000000000000000e+00 +2.496506739442548195e+01,1.300800000000000125e+02,0.000000000000000000e+00,5.281366524597324030e+00,0.000000000000000000e+00,1.000000009972973114e+00,0.000000000000000000e+00,2.433350307593384093e-10,0.000000000000000000e+00 +2.496696084377299840e+01,1.300900000000000034e+02,0.000000000000000000e+00,5.283259973963724931e+00,0.000000000000000000e+00,1.000000009973433857e+00,0.000000000000000000e+00,-2.531591608304343932e-10,0.000000000000000000e+00 +2.496885361453371743e+01,1.300999999999999943e+02,0.000000000000000000e+00,5.285152744743322195e+00,0.000000000000000000e+00,1.000000009972954684e+00,0.000000000000000000e+00,6.055464610382875131e-11,0.000000000000000000e+00 +2.497074570743679445e+01,1.301100000000000136e+02,0.000000000000000000e+00,5.287044837665267671e+00,0.000000000000000000e+00,1.000000009973069259e+00,0.000000000000000000e+00,2.477055140442655416e-11,0.000000000000000000e+00 +2.497263712321007390e+01,1.301200000000000045e+02,0.000000000000000000e+00,5.288936253457411141e+00,0.000000000000000000e+00,1.000000009973116111e+00,0.000000000000000000e+00,-3.018155985442648903e-11,0.000000000000000000e+00 +2.497452786258010704e+01,1.301299999999999955e+02,0.000000000000000000e+00,5.290826992846299426e+00,0.000000000000000000e+00,1.000000009973059045e+00,0.000000000000000000e+00,-1.879679342965196873e-11,0.000000000000000000e+00 +2.497641792627213775e+01,1.301400000000000148e+02,0.000000000000000000e+00,5.292717056557180832e+00,0.000000000000000000e+00,1.000000009973023518e+00,0.000000000000000000e+00,-1.009513351042960621e-10,0.000000000000000000e+00 +2.497830731501012380e+01,1.301500000000000057e+02,0.000000000000000000e+00,5.294606445314008702e+00,0.000000000000000000e+00,1.000000009972832782e+00,0.000000000000000000e+00,6.383718664361174776e-11,0.000000000000000000e+00 +2.498019602951672269e+01,1.301599999999999966e+02,0.000000000000000000e+00,5.296495159839444078e+00,0.000000000000000000e+00,1.000000009972953352e+00,0.000000000000000000e+00,7.244518359563961207e-11,0.000000000000000000e+00 +2.498208407051330937e+01,1.301700000000000159e+02,0.000000000000000000e+00,5.298383200854860142e+00,0.000000000000000000e+00,1.000000009973090132e+00,0.000000000000000000e+00,2.188247972509946737e-11,0.000000000000000000e+00 +2.498397143871996917e+01,1.301800000000000068e+02,0.000000000000000000e+00,5.300270569080343996e+00,0.000000000000000000e+00,1.000000009973131432e+00,0.000000000000000000e+00,1.282817168112865185e-11,0.000000000000000000e+00 +2.498585813485550844e+01,1.301899999999999977e+02,0.000000000000000000e+00,5.302157265234700212e+00,0.000000000000000000e+00,1.000000009973155635e+00,0.000000000000000000e+00,-1.010136626249685209e-10,0.000000000000000000e+00 +2.498774415963745454e+01,1.301999999999999886e+02,0.000000000000000000e+00,5.304043290035454383e+00,0.000000000000000000e+00,1.000000009972965120e+00,0.000000000000000000e+00,3.650976010207675222e-11,0.000000000000000000e+00 +2.498962951378205233e+01,1.302100000000000080e+02,0.000000000000000000e+00,5.305928644198855793e+00,0.000000000000000000e+00,1.000000009973033954e+00,0.000000000000000000e+00,3.522676960389010150e-11,0.000000000000000000e+00 +2.499151419800428187e+01,1.302199999999999989e+02,0.000000000000000000e+00,5.307813328439881850e+00,0.000000000000000000e+00,1.000000009973100346e+00,0.000000000000000000e+00,-2.433749762437899130e-10,0.000000000000000000e+00 +2.499339821301785136e+01,1.302299999999999898e+02,0.000000000000000000e+00,5.309697343472239872e+00,0.000000000000000000e+00,1.000000009972641823e+00,0.000000000000000000e+00,3.173840134846288391e-10,0.000000000000000000e+00 +2.499528155953520070e+01,1.302400000000000091e+02,0.000000000000000000e+00,5.311580690008369743e+00,0.000000000000000000e+00,1.000000009973239568e+00,0.000000000000000000e+00,-1.673579719057433346e-10,0.000000000000000000e+00 +2.499716423826750500e+01,1.302500000000000000e+02,0.000000000000000000e+00,5.313463368759451022e+00,0.000000000000000000e+00,1.000000009972924486e+00,0.000000000000000000e+00,1.760300204753728887e-10,0.000000000000000000e+00 +2.499904624992468527e+01,1.302599999999999909e+02,0.000000000000000000e+00,5.315345380435399392e+00,0.000000000000000000e+00,1.000000009973255777e+00,0.000000000000000000e+00,-2.826683817268089990e-10,0.000000000000000000e+00 +2.500092759521539776e+01,1.302700000000000102e+02,0.000000000000000000e+00,5.317226725744876425e+00,0.000000000000000000e+00,1.000000009972723980e+00,0.000000000000000000e+00,8.760508386502104330e-11,0.000000000000000000e+00 +2.500280827484705171e+01,1.302800000000000011e+02,0.000000000000000000e+00,5.319107405395286925e+00,0.000000000000000000e+00,1.000000009972888737e+00,0.000000000000000000e+00,1.627527003086260898e-10,0.000000000000000000e+00 +2.500468828952580225e+01,1.302899999999999920e+02,0.000000000000000000e+00,5.320987420092787801e+00,0.000000000000000000e+00,1.000000009973194715e+00,0.000000000000000000e+00,-1.774607817357358011e-10,0.000000000000000000e+00 +2.500656763995655751e+01,1.303000000000000114e+02,0.000000000000000000e+00,5.322866770542287185e+00,0.000000000000000000e+00,1.000000009972861204e+00,0.000000000000000000e+00,-4.337623826320456317e-11,0.000000000000000000e+00 +2.500844632684298219e+01,1.303100000000000023e+02,0.000000000000000000e+00,5.324745457447447095e+00,0.000000000000000000e+00,1.000000009972779713e+00,0.000000000000000000e+00,2.007598040420114208e-10,0.000000000000000000e+00 +2.501032435088749395e+01,1.303199999999999932e+02,0.000000000000000000e+00,5.326623481510689651e+00,0.000000000000000000e+00,1.000000009973156745e+00,0.000000000000000000e+00,-5.972877433009000363e-11,0.000000000000000000e+00 +2.501220171279128124e+01,1.303300000000000125e+02,0.000000000000000000e+00,5.328500843433198852e+00,0.000000000000000000e+00,1.000000009973044612e+00,0.000000000000000000e+00,-1.777113626663476699e-10,0.000000000000000000e+00 +2.501407841325428905e+01,1.303400000000000034e+02,0.000000000000000000e+00,5.330377543914921468e+00,0.000000000000000000e+00,1.000000009972711101e+00,0.000000000000000000e+00,2.466584004050241903e-10,0.000000000000000000e+00 +2.501595445297522957e+01,1.303499999999999943e+02,0.000000000000000000e+00,5.332253583654572360e+00,0.000000000000000000e+00,1.000000009973173842e+00,0.000000000000000000e+00,-1.513149623357921865e-10,0.000000000000000000e+00 +2.501782983265159288e+01,1.303600000000000136e+02,0.000000000000000000e+00,5.334128963349638930e+00,0.000000000000000000e+00,1.000000009972890069e+00,0.000000000000000000e+00,4.287580700995817650e-11,0.000000000000000000e+00 +2.501970455297963625e+01,1.303700000000000045e+02,0.000000000000000000e+00,5.336003683696379341e+00,0.000000000000000000e+00,1.000000009972970449e+00,0.000000000000000000e+00,-2.571082900719977161e-11,0.000000000000000000e+00 +2.502157861465439836e+01,1.303799999999999955e+02,0.000000000000000000e+00,5.337877745389830508e+00,0.000000000000000000e+00,1.000000009972922266e+00,0.000000000000000000e+00,-1.998326366320858188e-10,0.000000000000000000e+00 +2.502345201836969224e+01,1.303900000000000148e+02,0.000000000000000000e+00,5.339751149123808105e+00,0.000000000000000000e+00,1.000000009972547899e+00,0.000000000000000000e+00,1.881647076742317210e-10,0.000000000000000000e+00 +2.502532476481811941e+01,1.304000000000000057e+02,0.000000000000000000e+00,5.341623895590910109e+00,0.000000000000000000e+00,1.000000009972900283e+00,0.000000000000000000e+00,3.605679453365954025e-11,0.000000000000000000e+00 +2.502719685469106281e+01,1.304099999999999966e+02,0.000000000000000000e+00,5.343495985482522137e+00,0.000000000000000000e+00,1.000000009972967785e+00,0.000000000000000000e+00,1.613632458820341884e-11,0.000000000000000000e+00 +2.502906828867869393e+01,1.304200000000000159e+02,0.000000000000000000e+00,5.345367419488816552e+00,0.000000000000000000e+00,1.000000009972997983e+00,0.000000000000000000e+00,4.439043388179835888e-11,0.000000000000000000e+00 +2.503093906746997632e+01,1.304300000000000068e+02,0.000000000000000000e+00,5.347238198298757794e+00,0.000000000000000000e+00,1.000000009973081028e+00,0.000000000000000000e+00,-2.146684310871761246e-10,0.000000000000000000e+00 +2.503280919175267272e+01,1.304399999999999977e+02,0.000000000000000000e+00,5.349108322600105048e+00,0.000000000000000000e+00,1.000000009972679571e+00,0.000000000000000000e+00,1.753105190828775350e-10,0.000000000000000000e+00 +2.503467866221333793e+01,1.304499999999999886e+02,0.000000000000000000e+00,5.350977793079414013e+00,0.000000000000000000e+00,1.000000009973007309e+00,0.000000000000000000e+00,-1.321229194029951211e-10,0.000000000000000000e+00 +2.503654747953732951e+01,1.304600000000000080e+02,0.000000000000000000e+00,5.352846610422043128e+00,0.000000000000000000e+00,1.000000009972760395e+00,0.000000000000000000e+00,5.954739261285631680e-11,0.000000000000000000e+00 +2.503841564440880774e+01,1.304699999999999989e+02,0.000000000000000000e+00,5.354714775312151787e+00,0.000000000000000000e+00,1.000000009972871640e+00,0.000000000000000000e+00,-8.370458108463717897e-11,0.000000000000000000e+00 +2.504028315751073919e+01,1.304799999999999898e+02,0.000000000000000000e+00,5.356582288432707450e+00,0.000000000000000000e+00,1.000000009972715320e+00,0.000000000000000000e+00,1.327370620949542038e-10,0.000000000000000000e+00 +2.504215001952490027e+01,1.304900000000000091e+02,0.000000000000000000e+00,5.358449150465485644e+00,0.000000000000000000e+00,1.000000009972963122e+00,0.000000000000000000e+00,-1.217180463292375977e-10,0.000000000000000000e+00 +2.504401623113187725e+01,1.305000000000000000e+02,0.000000000000000000e+00,5.360315362091075286e+00,0.000000000000000000e+00,1.000000009972735970e+00,0.000000000000000000e+00,1.091440090980614520e-10,0.000000000000000000e+00 +2.504588179301107687e+01,1.305099999999999909e+02,0.000000000000000000e+00,5.362180923988878689e+00,0.000000000000000000e+00,1.000000009972939585e+00,0.000000000000000000e+00,-1.190643344803649957e-12,0.000000000000000000e+00 +2.504774670584071572e+01,1.305200000000000102e+02,0.000000000000000000e+00,5.364045836837117776e+00,0.000000000000000000e+00,1.000000009972937365e+00,0.000000000000000000e+00,-1.071951694776231105e-12,0.000000000000000000e+00 +2.504961097029784156e+01,1.305300000000000011e+02,0.000000000000000000e+00,5.365910101312834080e+00,0.000000000000000000e+00,1.000000009972935366e+00,0.000000000000000000e+00,-2.021926946300185394e-10,0.000000000000000000e+00 +2.505147458705831554e+01,1.305399999999999920e+02,0.000000000000000000e+00,5.367773718091893187e+00,0.000000000000000000e+00,1.000000009972558557e+00,0.000000000000000000e+00,1.095342493801265715e-10,0.000000000000000000e+00 +2.505333755679682994e+01,1.305500000000000114e+02,0.000000000000000000e+00,5.369636687848986512e+00,0.000000000000000000e+00,1.000000009972762616e+00,0.000000000000000000e+00,1.155337592379105916e-10,0.000000000000000000e+00 +2.505519988018690825e+01,1.305600000000000023e+02,0.000000000000000000e+00,5.371499011257636624e+00,0.000000000000000000e+00,1.000000009972977777e+00,0.000000000000000000e+00,-2.332945407084160753e-10,0.000000000000000000e+00 +2.505706155790090151e+01,1.305699999999999932e+02,0.000000000000000000e+00,5.373360688990197254e+00,0.000000000000000000e+00,1.000000009972543458e+00,0.000000000000000000e+00,2.985200629768918932e-10,0.000000000000000000e+00 +2.505892259061000260e+01,1.305800000000000125e+02,0.000000000000000000e+00,5.375221721717855949e+00,0.000000000000000000e+00,1.000000009973099013e+00,0.000000000000000000e+00,-1.273506095483368270e-10,0.000000000000000000e+00 +2.506078297898423557e+01,1.305900000000000034e+02,0.000000000000000000e+00,5.377082110110641189e+00,0.000000000000000000e+00,1.000000009972862092e+00,0.000000000000000000e+00,-1.277528717884198997e-11,0.000000000000000000e+00 +2.506264272369246626e+01,1.305999999999999943e+02,0.000000000000000000e+00,5.378941854837418823e+00,0.000000000000000000e+00,1.000000009972838333e+00,0.000000000000000000e+00,-1.663750471567421072e-10,0.000000000000000000e+00 +2.506450182540240590e+01,1.306100000000000136e+02,0.000000000000000000e+00,5.380800956565900073e+00,0.000000000000000000e+00,1.000000009972529025e+00,0.000000000000000000e+00,1.469576721774514146e-10,0.000000000000000000e+00 +2.506636028478061462e+01,1.306200000000000045e+02,0.000000000000000000e+00,5.382659415962641525e+00,0.000000000000000000e+00,1.000000009972802140e+00,0.000000000000000000e+00,-1.348174865346742861e-10,0.000000000000000000e+00 +2.506821810249249438e+01,1.306299999999999955e+02,0.000000000000000000e+00,5.384517233693050464e+00,0.000000000000000000e+00,1.000000009972551673e+00,0.000000000000000000e+00,2.436638917805752590e-10,0.000000000000000000e+00 +2.507007527920230672e+01,1.306400000000000148e+02,0.000000000000000000e+00,5.386374410421383985e+00,0.000000000000000000e+00,1.000000009973004200e+00,0.000000000000000000e+00,-3.336882904453477685e-11,0.000000000000000000e+00 +2.507193181557316208e+01,1.306500000000000057e+02,0.000000000000000000e+00,5.388230946810756095e+00,0.000000000000000000e+00,1.000000009972942250e+00,0.000000000000000000e+00,-2.199033950542477063e-10,0.000000000000000000e+00 +2.507378771226703407e+01,1.306599999999999966e+02,0.000000000000000000e+00,5.390086843523135940e+00,0.000000000000000000e+00,1.000000009972534132e+00,0.000000000000000000e+00,1.765338562930513112e-10,0.000000000000000000e+00 +2.507564296994474873e+01,1.306700000000000159e+02,0.000000000000000000e+00,5.391942101219353134e+00,0.000000000000000000e+00,1.000000009972861648e+00,0.000000000000000000e+00,-1.545651884854267582e-10,0.000000000000000000e+00 +2.507749758926600236e+01,1.306800000000000068e+02,0.000000000000000000e+00,5.393796720559102198e+00,0.000000000000000000e+00,1.000000009972574988e+00,0.000000000000000000e+00,5.784714520795756070e-11,0.000000000000000000e+00 +2.507935157088935085e+01,1.306899999999999977e+02,0.000000000000000000e+00,5.395650702200940785e+00,0.000000000000000000e+00,1.000000009972682236e+00,0.000000000000000000e+00,2.312284997973493829e-11,0.000000000000000000e+00 +2.508120491547222386e+01,1.306999999999999886e+02,0.000000000000000000e+00,5.397504046802296784e+00,0.000000000000000000e+00,1.000000009972725090e+00,0.000000000000000000e+00,-1.426199117847633575e-11,0.000000000000000000e+00 +2.508305762367091774e+01,1.307100000000000080e+02,0.000000000000000000e+00,5.399356755019468324e+00,0.000000000000000000e+00,1.000000009972698667e+00,0.000000000000000000e+00,1.930225840403331085e-10,0.000000000000000000e+00 +2.508490969614060617e+01,1.307199999999999989e+02,0.000000000000000000e+00,5.401208827507627319e+00,0.000000000000000000e+00,1.000000009973056159e+00,0.000000000000000000e+00,-4.002095068099220765e-10,0.000000000000000000e+00 +2.508676113353533665e+01,1.307299999999999898e+02,0.000000000000000000e+00,5.403060264920823030e+00,0.000000000000000000e+00,1.000000009972315196e+00,0.000000000000000000e+00,2.724564987318698022e-10,0.000000000000000000e+00 +2.508861193650803756e+01,1.307400000000000091e+02,0.000000000000000000e+00,5.404911067911981171e+00,0.000000000000000000e+00,1.000000009972819459e+00,0.000000000000000000e+00,-1.258937778523187803e-10,0.000000000000000000e+00 +2.509046210571051816e+01,1.307500000000000000e+02,0.000000000000000000e+00,5.406761237132913678e+00,0.000000000000000000e+00,1.000000009972586534e+00,0.000000000000000000e+00,2.181385109849665956e-10,0.000000000000000000e+00 +2.509231164179347218e+01,1.307599999999999909e+02,0.000000000000000000e+00,5.408610773234313385e+00,0.000000000000000000e+00,1.000000009972989989e+00,0.000000000000000000e+00,-2.522000968905770492e-10,0.000000000000000000e+00 +2.509416054540648133e+01,1.307700000000000102e+02,0.000000000000000000e+00,5.410459676865762901e+00,0.000000000000000000e+00,1.000000009972523696e+00,0.000000000000000000e+00,2.450781298081440404e-11,0.000000000000000000e+00 +2.509600881719801890e+01,1.307800000000000011e+02,0.000000000000000000e+00,5.412307948675731950e+00,0.000000000000000000e+00,1.000000009972568993e+00,0.000000000000000000e+00,1.442128536235571392e-11,0.000000000000000000e+00 +2.509785645781544616e+01,1.307899999999999920e+02,0.000000000000000000e+00,5.414155589311585359e+00,0.000000000000000000e+00,1.000000009972595638e+00,0.000000000000000000e+00,2.454859807293598130e-10,0.000000000000000000e+00 +2.509970346790502305e+01,1.308000000000000114e+02,0.000000000000000000e+00,5.416002599419582175e+00,0.000000000000000000e+00,1.000000009973049053e+00,0.000000000000000000e+00,-3.138770750973376038e-10,0.000000000000000000e+00 +2.510154984811190815e+01,1.308100000000000023e+02,0.000000000000000000e+00,5.417848979644880103e+00,0.000000000000000000e+00,1.000000009972469517e+00,0.000000000000000000e+00,1.723904927215772151e-10,0.000000000000000000e+00 +2.510339559908015516e+01,1.308199999999999932e+02,0.000000000000000000e+00,5.419694730631534618e+00,0.000000000000000000e+00,1.000000009972787707e+00,0.000000000000000000e+00,-1.051783814392406550e-10,0.000000000000000000e+00 +2.510524072145272712e+01,1.308300000000000125e+02,0.000000000000000000e+00,5.421539853022507849e+00,0.000000000000000000e+00,1.000000009972593640e+00,0.000000000000000000e+00,-8.631415747955312560e-11,0.000000000000000000e+00 +2.510708521587148923e+01,1.308400000000000034e+02,0.000000000000000000e+00,5.423384347459665022e+00,0.000000000000000000e+00,1.000000009972434434e+00,0.000000000000000000e+00,2.491558562776951116e-10,0.000000000000000000e+00 +2.510892908297721604e+01,1.308499999999999943e+02,0.000000000000000000e+00,5.425228214583780684e+00,0.000000000000000000e+00,1.000000009972893844e+00,0.000000000000000000e+00,-1.219098367401813274e-10,0.000000000000000000e+00 +2.511077232340959497e+01,1.308600000000000136e+02,0.000000000000000000e+00,5.427071455034541358e+00,0.000000000000000000e+00,1.000000009972669135e+00,0.000000000000000000e+00,-1.302661144040837251e-10,0.000000000000000000e+00 +2.511261493780722276e+01,1.308700000000000045e+02,0.000000000000000000e+00,5.428914069450544666e+00,0.000000000000000000e+00,1.000000009972429105e+00,0.000000000000000000e+00,2.514591812302366139e-10,0.000000000000000000e+00 +2.511445692680761610e+01,1.308799999999999955e+02,0.000000000000000000e+00,5.430756058469305536e+00,0.000000000000000000e+00,1.000000009972892290e+00,0.000000000000000000e+00,-2.564885667491847934e-10,0.000000000000000000e+00 +2.511629829104720457e+01,1.308900000000000148e+02,0.000000000000000000e+00,5.432597422727258873e+00,0.000000000000000000e+00,1.000000009972420001e+00,0.000000000000000000e+00,2.101337928193310762e-10,0.000000000000000000e+00 +2.511813903116134838e+01,1.309000000000000057e+02,0.000000000000000000e+00,5.434438162859757782e+00,0.000000000000000000e+00,1.000000009972806803e+00,0.000000000000000000e+00,-1.492672653803932573e-10,0.000000000000000000e+00 +2.511997914778432062e+01,1.309099999999999966e+02,0.000000000000000000e+00,5.436278279501082444e+00,0.000000000000000000e+00,1.000000009972532133e+00,0.000000000000000000e+00,1.219167225462690218e-11,0.000000000000000000e+00 +2.512181864154933209e+01,1.309200000000000159e+02,0.000000000000000000e+00,5.438117773284436574e+00,0.000000000000000000e+00,1.000000009972554560e+00,0.000000000000000000e+00,-5.421696159146253819e-11,0.000000000000000000e+00 +2.512365751308851003e+01,1.309300000000000068e+02,0.000000000000000000e+00,5.439956644841954514e+00,0.000000000000000000e+00,1.000000009972454862e+00,0.000000000000000000e+00,-4.577990361010144412e-11,0.000000000000000000e+00 +2.512549576303292653e+01,1.309399999999999977e+02,0.000000000000000000e+00,5.441794894804701244e+00,0.000000000000000000e+00,1.000000009972370707e+00,0.000000000000000000e+00,3.443715412874892068e-10,0.000000000000000000e+00 +2.512733339201257721e+01,1.309499999999999886e+02,0.000000000000000000e+00,5.443632523802675927e+00,0.000000000000000000e+00,1.000000009973003534e+00,0.000000000000000000e+00,-4.180994417309559485e-10,0.000000000000000000e+00 +2.512917040065639540e+01,1.309600000000000080e+02,0.000000000000000000e+00,5.445469532464815465e+00,0.000000000000000000e+00,1.000000009972235482e+00,0.000000000000000000e+00,3.465387017352696983e-10,0.000000000000000000e+00 +2.513100678959225931e+01,1.309699999999999989e+02,0.000000000000000000e+00,5.447305921418991836e+00,0.000000000000000000e+00,1.000000009972871862e+00,0.000000000000000000e+00,-2.084045847584575252e-10,0.000000000000000000e+00 +2.513284255944698486e+01,1.309799999999999898e+02,0.000000000000000000e+00,5.449141691292023637e+00,0.000000000000000000e+00,1.000000009972489279e+00,0.000000000000000000e+00,7.658999413768465277e-11,0.000000000000000000e+00 +2.513467771084632929e+01,1.309900000000000091e+02,0.000000000000000000e+00,5.450976842709668979e+00,0.000000000000000000e+00,1.000000009972629833e+00,0.000000000000000000e+00,-6.221250397404109046e-11,0.000000000000000000e+00 +2.513651224441500176e+01,1.310000000000000000e+02,0.000000000000000000e+00,5.452811376296635260e+00,0.000000000000000000e+00,1.000000009972515702e+00,0.000000000000000000e+00,-4.080285962020293675e-11,0.000000000000000000e+00 +2.513834616077665629e+01,1.310099999999999909e+02,0.000000000000000000e+00,5.454645292676577384e+00,0.000000000000000000e+00,1.000000009972440873e+00,0.000000000000000000e+00,-6.443448653978699248e-11,0.000000000000000000e+00 +2.514017946055389885e+01,1.310200000000000102e+02,0.000000000000000000e+00,5.456478592472102207e+00,0.000000000000000000e+00,1.000000009972322745e+00,0.000000000000000000e+00,1.925203215388953178e-10,0.000000000000000000e+00 +2.514201214436829090e+01,1.310300000000000011e+02,0.000000000000000000e+00,5.458311276304770310e+00,0.000000000000000000e+00,1.000000009972675574e+00,0.000000000000000000e+00,3.635965712714807914e-13,0.000000000000000000e+00 +2.514384421284034943e+01,1.310399999999999920e+02,0.000000000000000000e+00,5.460143344795099551e+00,0.000000000000000000e+00,1.000000009972676240e+00,0.000000000000000000e+00,-4.716217996415069673e-11,0.000000000000000000e+00 +2.514567566658955045e+01,1.310500000000000114e+02,0.000000000000000000e+00,5.461974798562565070e+00,0.000000000000000000e+00,1.000000009972589865e+00,0.000000000000000000e+00,-1.466277661835078264e-10,0.000000000000000000e+00 +2.514750650623433259e+01,1.310600000000000023e+02,0.000000000000000000e+00,5.463805638225603722e+00,0.000000000000000000e+00,1.000000009972321413e+00,0.000000000000000000e+00,3.724550292483775148e-11,0.000000000000000000e+00 +2.514933673239209355e+01,1.310699999999999932e+02,0.000000000000000000e+00,5.465635864401615862e+00,0.000000000000000000e+00,1.000000009972389581e+00,0.000000000000000000e+00,4.660281431712532568e-11,0.000000000000000000e+00 +2.515116634567920073e+01,1.310800000000000125e+02,0.000000000000000000e+00,5.467465477706968890e+00,0.000000000000000000e+00,1.000000009972474846e+00,0.000000000000000000e+00,-4.419037211456836599e-11,0.000000000000000000e+00 +2.515299534671099124e+01,1.310900000000000034e+02,0.000000000000000000e+00,5.469294478756998146e+00,0.000000000000000000e+00,1.000000009972394022e+00,0.000000000000000000e+00,1.066267197280233937e-10,0.000000000000000000e+00 +2.515482373610176836e+01,1.310999999999999943e+02,0.000000000000000000e+00,5.471122868166009567e+00,0.000000000000000000e+00,1.000000009972588977e+00,0.000000000000000000e+00,4.737849931457080438e-11,0.000000000000000000e+00 +2.515665151446481573e+01,1.311100000000000136e+02,0.000000000000000000e+00,5.472950646547283249e+00,0.000000000000000000e+00,1.000000009972675574e+00,0.000000000000000000e+00,-1.413323147832932231e-10,0.000000000000000000e+00 +2.515847868241238672e+01,1.311200000000000045e+02,0.000000000000000000e+00,5.474777814513074325e+00,0.000000000000000000e+00,1.000000009972417336e+00,0.000000000000000000e+00,-1.103805548203300781e-10,0.000000000000000000e+00 +2.516030524055571149e+01,1.311299999999999955e+02,0.000000000000000000e+00,5.476604372674615639e+00,0.000000000000000000e+00,1.000000009972215720e+00,0.000000000000000000e+00,2.266718046742940205e-10,0.000000000000000000e+00 +2.516213118950500771e+01,1.311400000000000148e+02,0.000000000000000000e+00,5.478430321642121292e+00,0.000000000000000000e+00,1.000000009972629611e+00,0.000000000000000000e+00,-1.080212835983963262e-10,0.000000000000000000e+00 +2.516395652986947340e+01,1.311500000000000057e+02,0.000000000000000000e+00,5.480255662024789309e+00,0.000000000000000000e+00,1.000000009972432435e+00,0.000000000000000000e+00,4.064316419230617246e-11,0.000000000000000000e+00 +2.516578126225728695e+01,1.311599999999999966e+02,0.000000000000000000e+00,5.482080394430800752e+00,0.000000000000000000e+00,1.000000009972506598e+00,0.000000000000000000e+00,-3.432691178483184716e-11,0.000000000000000000e+00 +2.516760538727562135e+01,1.311700000000000159e+02,0.000000000000000000e+00,5.483904519467325933e+00,0.000000000000000000e+00,1.000000009972443982e+00,0.000000000000000000e+00,2.800644248684946666e-11,0.000000000000000000e+00 +2.516942890553063350e+01,1.311800000000000068e+02,0.000000000000000000e+00,5.485728037740524421e+00,0.000000000000000000e+00,1.000000009972495052e+00,0.000000000000000000e+00,5.700597153574106199e-11,0.000000000000000000e+00 +2.517125181762747843e+01,1.311899999999999977e+02,0.000000000000000000e+00,5.487550949855548588e+00,0.000000000000000000e+00,1.000000009972598969e+00,0.000000000000000000e+00,-1.161212471781322702e-10,0.000000000000000000e+00 +2.517307412417030221e+01,1.311999999999999886e+02,0.000000000000000000e+00,5.489373256416545388e+00,0.000000000000000000e+00,1.000000009972387360e+00,0.000000000000000000e+00,-1.231074573167114825e-10,0.000000000000000000e+00 +2.517489582576224905e+01,1.312100000000000080e+02,0.000000000000000000e+00,5.491194958026658135e+00,0.000000000000000000e+00,1.000000009972163095e+00,0.000000000000000000e+00,1.393648715769406652e-10,0.000000000000000000e+00 +2.517671692300546127e+01,1.312199999999999989e+02,0.000000000000000000e+00,5.493016055288030053e+00,0.000000000000000000e+00,1.000000009972416892e+00,0.000000000000000000e+00,-2.671131129856793221e-11,0.000000000000000000e+00 +2.517853741650108290e+01,1.312299999999999898e+02,0.000000000000000000e+00,5.494836548801806941e+00,0.000000000000000000e+00,1.000000009972368264e+00,0.000000000000000000e+00,2.122971930454996203e-11,0.000000000000000000e+00 +2.518035730684926321e+01,1.312400000000000091e+02,0.000000000000000000e+00,5.496656439168137176e+00,0.000000000000000000e+00,1.000000009972406900e+00,0.000000000000000000e+00,1.251015480129811536e-10,0.000000000000000000e+00 +2.518217659464916025e+01,1.312500000000000000e+02,0.000000000000000000e+00,5.498475726986176149e+00,0.000000000000000000e+00,1.000000009972634496e+00,0.000000000000000000e+00,-1.406484714802774810e-10,0.000000000000000000e+00 +2.518399528049893377e+01,1.312599999999999909e+02,0.000000000000000000e+00,5.500294412854088044e+00,0.000000000000000000e+00,1.000000009972378701e+00,0.000000000000000000e+00,-1.255507399470002208e-10,0.000000000000000000e+00 +2.518581336499576295e+01,1.312700000000000102e+02,0.000000000000000000e+00,5.502112497369046729e+00,0.000000000000000000e+00,1.000000009972150439e+00,0.000000000000000000e+00,2.873472258760223085e-10,0.000000000000000000e+00 +2.518763084873583225e+01,1.312800000000000011e+02,0.000000000000000000e+00,5.503929981127240190e+00,0.000000000000000000e+00,1.000000009972672688e+00,0.000000000000000000e+00,-1.288112327936932452e-10,0.000000000000000000e+00 +2.518944773231434553e+01,1.312899999999999920e+02,0.000000000000000000e+00,5.505746864723873202e+00,0.000000000000000000e+00,1.000000009972438653e+00,0.000000000000000000e+00,-1.784881225596469673e-10,0.000000000000000000e+00 +2.519126401632552614e+01,1.313000000000000114e+02,0.000000000000000000e+00,5.507563148753165549e+00,0.000000000000000000e+00,1.000000009972114468e+00,0.000000000000000000e+00,2.615835897930689899e-10,0.000000000000000000e+00 +2.519307970136261332e+01,1.313100000000000023e+02,0.000000000000000000e+00,5.509378833808358245e+00,0.000000000000000000e+00,1.000000009972589421e+00,0.000000000000000000e+00,-3.008163174630318881e-10,0.000000000000000000e+00 +2.519489478801786930e+01,1.313199999999999932e+02,0.000000000000000000e+00,5.511193920481716191e+00,0.000000000000000000e+00,1.000000009972043413e+00,0.000000000000000000e+00,1.469700782963055213e-10,0.000000000000000000e+00 +2.519670927688258288e+01,1.313300000000000125e+02,0.000000000000000000e+00,5.513008409364525519e+00,0.000000000000000000e+00,1.000000009972310089e+00,0.000000000000000000e+00,1.165375353043846788e-10,0.000000000000000000e+00 +2.519852316854706942e+01,1.313400000000000034e+02,0.000000000000000000e+00,5.514822301047102471e+00,0.000000000000000000e+00,1.000000009972521475e+00,0.000000000000000000e+00,-2.627855412839404559e-10,0.000000000000000000e+00 +2.520033646360067436e+01,1.313499999999999943e+02,0.000000000000000000e+00,5.516635596118790730e+00,0.000000000000000000e+00,1.000000009972044968e+00,0.000000000000000000e+00,2.222039657020388620e-10,0.000000000000000000e+00 +2.520214916263176974e+01,1.313600000000000136e+02,0.000000000000000000e+00,5.518448295167964091e+00,0.000000000000000000e+00,1.000000009972447756e+00,0.000000000000000000e+00,8.614151950643475510e-11,0.000000000000000000e+00 +2.520396126622776833e+01,1.313700000000000045e+02,0.000000000000000000e+00,5.520260398782032674e+00,0.000000000000000000e+00,1.000000009972603854e+00,0.000000000000000000e+00,-2.654961589190625744e-10,0.000000000000000000e+00 +2.520577277497510948e+01,1.313799999999999955e+02,0.000000000000000000e+00,5.522071907547440262e+00,0.000000000000000000e+00,1.000000009972122905e+00,0.000000000000000000e+00,1.190588033101694790e-10,0.000000000000000000e+00 +2.520758368945927685e+01,1.313900000000000148e+02,0.000000000000000000e+00,5.523882822049667851e+00,0.000000000000000000e+00,1.000000009972338511e+00,0.000000000000000000e+00,2.710671917311949955e-11,0.000000000000000000e+00 +2.520939401026479487e+01,1.314000000000000057e+02,0.000000000000000000e+00,5.525693142873238983e+00,0.000000000000000000e+00,1.000000009972387582e+00,0.000000000000000000e+00,-1.274801414529246373e-10,0.000000000000000000e+00 +2.521120373797522518e+01,1.314099999999999966e+02,0.000000000000000000e+00,5.527502870601717966e+00,0.000000000000000000e+00,1.000000009972156878e+00,0.000000000000000000e+00,7.167736796168451340e-11,0.000000000000000000e+00 +2.521301287317318085e+01,1.314200000000000159e+02,0.000000000000000000e+00,5.529312005817713427e+00,0.000000000000000000e+00,1.000000009972286552e+00,0.000000000000000000e+00,-4.211195876447861271e-11,0.000000000000000000e+00 +2.521482141644031572e+01,1.314300000000000068e+02,0.000000000000000000e+00,5.531120549102881867e+00,0.000000000000000000e+00,1.000000009972210391e+00,0.000000000000000000e+00,2.237699279309490857e-10,0.000000000000000000e+00 +2.521662936835733149e+01,1.314399999999999977e+02,0.000000000000000000e+00,5.532928501037927660e+00,0.000000000000000000e+00,1.000000009972614956e+00,0.000000000000000000e+00,-3.380988652347566609e-10,0.000000000000000000e+00 +2.521843672950398840e+01,1.314499999999999886e+02,0.000000000000000000e+00,5.534735862202607493e+00,0.000000000000000000e+00,1.000000009972003889e+00,0.000000000000000000e+00,5.653207894281030502e-11,0.000000000000000000e+00 +2.522024350045909102e+01,1.314600000000000080e+02,0.000000000000000000e+00,5.536542633175728589e+00,0.000000000000000000e+00,1.000000009972106030e+00,0.000000000000000000e+00,2.043195358755869586e-10,0.000000000000000000e+00 +2.522204968180050599e+01,1.314699999999999989e+02,0.000000000000000000e+00,5.538348814535156706e+00,0.000000000000000000e+00,1.000000009972475068e+00,0.000000000000000000e+00,-1.020701193802193688e-11,0.000000000000000000e+00 +2.522385527410515849e+01,1.314799999999999898e+02,0.000000000000000000e+00,5.540154406857814351e+00,0.000000000000000000e+00,1.000000009972456638e+00,0.000000000000000000e+00,-1.556154166565434286e-10,0.000000000000000000e+00 +2.522566027794902510e+01,1.314900000000000091e+02,0.000000000000000000e+00,5.541959410719682566e+00,0.000000000000000000e+00,1.000000009972175752e+00,0.000000000000000000e+00,-7.001898848945086412e-11,0.000000000000000000e+00 +2.522746469390715163e+01,1.315000000000000000e+02,0.000000000000000000e+00,5.543763826695804475e+00,0.000000000000000000e+00,1.000000009972049408e+00,0.000000000000000000e+00,1.383602241934697139e-10,0.000000000000000000e+00 +2.522926852255364594e+01,1.315099999999999909e+02,0.000000000000000000e+00,5.545567655360287951e+00,0.000000000000000000e+00,1.000000009972298987e+00,0.000000000000000000e+00,8.853502695869258145e-11,0.000000000000000000e+00 +2.523107176446168154e+01,1.315200000000000102e+02,0.000000000000000000e+00,5.547370897286307390e+00,0.000000000000000000e+00,1.000000009972458637e+00,0.000000000000000000e+00,-3.249392849689342874e-10,0.000000000000000000e+00 +2.523287442020350113e+01,1.315300000000000011e+02,0.000000000000000000e+00,5.549173553046104601e+00,0.000000000000000000e+00,1.000000009971872883e+00,0.000000000000000000e+00,1.605509756168260541e-10,0.000000000000000000e+00 +2.523467649035041660e+01,1.315399999999999920e+02,0.000000000000000000e+00,5.550975623210990584e+00,0.000000000000000000e+00,1.000000009972162207e+00,0.000000000000000000e+00,7.703526182527274393e-11,0.000000000000000000e+00 +2.523647797547281257e+01,1.315500000000000114e+02,0.000000000000000000e+00,5.552777108351351742e+00,0.000000000000000000e+00,1.000000009972300985e+00,0.000000000000000000e+00,-1.292146480825144005e-10,0.000000000000000000e+00 +2.523827887614014998e+01,1.315600000000000023e+02,0.000000000000000000e+00,5.554578009036647224e+00,0.000000000000000000e+00,1.000000009972068282e+00,0.000000000000000000e+00,2.655432863253515302e-10,0.000000000000000000e+00 +2.524007919292096247e+01,1.315699999999999932e+02,0.000000000000000000e+00,5.556378325835412468e+00,0.000000000000000000e+00,1.000000009972546344e+00,0.000000000000000000e+00,-2.048047958089057261e-10,0.000000000000000000e+00 +2.524187892638286712e+01,1.315800000000000125e+02,0.000000000000000000e+00,5.558178059315263653e+00,0.000000000000000000e+00,1.000000009972177750e+00,0.000000000000000000e+00,9.749891265140716036e-12,0.000000000000000000e+00 +2.524367807709255729e+01,1.315900000000000034e+02,0.000000000000000000e+00,5.559977210042895024e+00,0.000000000000000000e+00,1.000000009972195292e+00,0.000000000000000000e+00,-6.172814714980762037e-12,0.000000000000000000e+00 +2.524547664561581328e+01,1.315999999999999943e+02,0.000000000000000000e+00,5.561775778584086005e+00,0.000000000000000000e+00,1.000000009972184190e+00,0.000000000000000000e+00,-6.878740041285826507e-11,0.000000000000000000e+00 +2.524727463251749882e+01,1.316100000000000136e+02,0.000000000000000000e+00,5.563573765503700308e+00,0.000000000000000000e+00,1.000000009972060511e+00,0.000000000000000000e+00,7.412169232395226783e-12,0.000000000000000000e+00 +2.524907203836156455e+01,1.316200000000000045e+02,0.000000000000000000e+00,5.565371171365688596e+00,0.000000000000000000e+00,1.000000009972073833e+00,0.000000000000000000e+00,1.356865186021744241e-10,0.000000000000000000e+00 +2.525086886371104811e+01,1.316299999999999955e+02,0.000000000000000000e+00,5.567167996733091151e+00,0.000000000000000000e+00,1.000000009972317638e+00,0.000000000000000000e+00,-4.499621010924592705e-11,0.000000000000000000e+00 +2.525266510912808471e+01,1.316400000000000148e+02,0.000000000000000000e+00,5.568964242168039647e+00,0.000000000000000000e+00,1.000000009972236814e+00,0.000000000000000000e+00,-6.825802726765934534e-11,0.000000000000000000e+00 +2.525446077517389654e+01,1.316500000000000057e+02,0.000000000000000000e+00,5.570759908231758040e+00,0.000000000000000000e+00,1.000000009972114245e+00,0.000000000000000000e+00,-1.521457335035294781e-11,0.000000000000000000e+00 +2.525625586240880338e+01,1.316599999999999966e+02,0.000000000000000000e+00,5.572554995484566120e+00,0.000000000000000000e+00,1.000000009972086934e+00,0.000000000000000000e+00,3.390354816363341820e-11,0.000000000000000000e+00 +2.525805037139222264e+01,1.316700000000000159e+02,0.000000000000000000e+00,5.574349504485881290e+00,0.000000000000000000e+00,1.000000009972147774e+00,0.000000000000000000e+00,4.951016933750445910e-13,0.000000000000000000e+00 +2.525984430268267289e+01,1.316800000000000068e+02,0.000000000000000000e+00,5.576143435794220338e+00,0.000000000000000000e+00,1.000000009972148662e+00,0.000000000000000000e+00,8.444200501526517424e-11,0.000000000000000000e+00 +2.526163765683777029e+01,1.316899999999999977e+02,0.000000000000000000e+00,5.577936789967201214e+00,0.000000000000000000e+00,1.000000009972300097e+00,0.000000000000000000e+00,-3.420877229018827976e-10,0.000000000000000000e+00 +2.526343043441423575e+01,1.316999999999999886e+02,0.000000000000000000e+00,5.579729567561545700e+00,0.000000000000000000e+00,1.000000009971686810e+00,0.000000000000000000e+00,3.062681550816601689e-10,0.000000000000000000e+00 +2.526522263596789841e+01,1.317100000000000080e+02,0.000000000000000000e+00,5.581521769133079403e+00,0.000000000000000000e+00,1.000000009972235704e+00,0.000000000000000000e+00,2.354758912604471188e-11,0.000000000000000000e+00 +2.526701426205369216e+01,1.317199999999999989e+02,0.000000000000000000e+00,5.583313395236738863e+00,0.000000000000000000e+00,1.000000009972277892e+00,0.000000000000000000e+00,-1.544721792804399301e-10,0.000000000000000000e+00 +2.526880531322565915e+01,1.317299999999999898e+02,0.000000000000000000e+00,5.585104446426567115e+00,0.000000000000000000e+00,1.000000009972001225e+00,0.000000000000000000e+00,-1.810607772996861164e-11,0.000000000000000000e+00 +2.527059579003695688e+01,1.317400000000000091e+02,0.000000000000000000e+00,5.586894923255719014e+00,0.000000000000000000e+00,1.000000009971968806e+00,0.000000000000000000e+00,8.981508702181929974e-11,0.000000000000000000e+00 +2.527238569303985116e+01,1.317500000000000000e+02,0.000000000000000000e+00,5.588684826276463902e+00,0.000000000000000000e+00,1.000000009972129567e+00,0.000000000000000000e+00,1.054796717155913416e-10,0.000000000000000000e+00 +2.527417502278573025e+01,1.317599999999999909e+02,0.000000000000000000e+00,5.590474156040186493e+00,0.000000000000000000e+00,1.000000009972318304e+00,0.000000000000000000e+00,-3.123197917308997387e-10,0.000000000000000000e+00 +2.527596377982509424e+01,1.317700000000000102e+02,0.000000000000000000e+00,5.592262913097388655e+00,0.000000000000000000e+00,1.000000009971759640e+00,0.000000000000000000e+00,1.642811183539337686e-10,0.000000000000000000e+00 +2.527775196470756569e+01,1.317800000000000011e+02,0.000000000000000000e+00,5.594051097997690292e+00,0.000000000000000000e+00,1.000000009972053405e+00,0.000000000000000000e+00,8.806693659836022593e-11,0.000000000000000000e+00 +2.527953957798188611e+01,1.317899999999999920e+02,0.000000000000000000e+00,5.595838711289835565e+00,0.000000000000000000e+00,1.000000009972210835e+00,0.000000000000000000e+00,-4.311564511677740584e-11,0.000000000000000000e+00 +2.528132662019591947e+01,1.318000000000000114e+02,0.000000000000000000e+00,5.597625753521690228e+00,0.000000000000000000e+00,1.000000009972133785e+00,0.000000000000000000e+00,-6.960366554169864506e-12,0.000000000000000000e+00 +2.528311309189665934e+01,1.318100000000000023e+02,0.000000000000000000e+00,5.599412225240245178e+00,0.000000000000000000e+00,1.000000009972121351e+00,0.000000000000000000e+00,-1.352731371598056430e-10,0.000000000000000000e+00 +2.528489899363022531e+01,1.318199999999999932e+02,0.000000000000000000e+00,5.601198126991619120e+00,0.000000000000000000e+00,1.000000009971879766e+00,0.000000000000000000e+00,7.673726641574571595e-11,0.000000000000000000e+00 +2.528668432594186299e+01,1.318300000000000125e+02,0.000000000000000000e+00,5.602983459321059456e+00,0.000000000000000000e+00,1.000000009972016768e+00,0.000000000000000000e+00,2.164755312609987836e-11,0.000000000000000000e+00 +2.528846908937595117e+01,1.318400000000000034e+02,0.000000000000000000e+00,5.604768222772945840e+00,0.000000000000000000e+00,1.000000009972055404e+00,0.000000000000000000e+00,-7.106143796072554311e-11,0.000000000000000000e+00 +2.529025328447600174e+01,1.318499999999999943e+02,0.000000000000000000e+00,5.606552417890790174e+00,0.000000000000000000e+00,1.000000009971928616e+00,0.000000000000000000e+00,3.099812744388878262e-11,0.000000000000000000e+00 +2.529203691178466329e+01,1.318600000000000136e+02,0.000000000000000000e+00,5.608336045217239274e+00,0.000000000000000000e+00,1.000000009971983905e+00,0.000000000000000000e+00,3.362312055907100733e-12,0.000000000000000000e+00 +2.529381997184372111e+01,1.318700000000000045e+02,0.000000000000000000e+00,5.610119105294077535e+00,0.000000000000000000e+00,1.000000009971989900e+00,0.000000000000000000e+00,8.159313256078927858e-11,0.000000000000000000e+00 +2.529560246519409716e+01,1.318799999999999955e+02,0.000000000000000000e+00,5.611901598662227819e+00,0.000000000000000000e+00,1.000000009972135340e+00,0.000000000000000000e+00,-5.545111506421321392e-11,0.000000000000000000e+00 +2.529738439237585368e+01,1.318900000000000148e+02,0.000000000000000000e+00,5.613683525861754120e+00,0.000000000000000000e+00,1.000000009972036530e+00,0.000000000000000000e+00,1.108127957059301593e-10,0.000000000000000000e+00 +2.529916575392819666e+01,1.319000000000000057e+02,0.000000000000000000e+00,5.615464887431862451e+00,0.000000000000000000e+00,1.000000009972233928e+00,0.000000000000000000e+00,-2.973817582524461187e-10,0.000000000000000000e+00 +2.530094655038947948e+01,1.319099999999999966e+02,0.000000000000000000e+00,5.617245683910904397e+00,0.000000000000000000e+00,1.000000009971704351e+00,0.000000000000000000e+00,8.294406006028046835e-11,0.000000000000000000e+00 +2.530272678229719929e+01,1.319200000000000159e+02,0.000000000000000000e+00,5.619025915836376228e+00,0.000000000000000000e+00,1.000000009971852011e+00,0.000000000000000000e+00,9.694430006767760825e-11,0.000000000000000000e+00 +2.530450645018800060e+01,1.319300000000000068e+02,0.000000000000000000e+00,5.620805583744925116e+00,0.000000000000000000e+00,1.000000009972024539e+00,0.000000000000000000e+00,-9.734942530583804330e-12,0.000000000000000000e+00 +2.530628555459768236e+01,1.319399999999999977e+02,0.000000000000000000e+00,5.622584688172347356e+00,0.000000000000000000e+00,1.000000009972007220e+00,0.000000000000000000e+00,1.211010657870476427e-11,0.000000000000000000e+00 +2.530806409606119090e+01,1.319499999999999886e+02,0.000000000000000000e+00,5.624363229653591034e+00,0.000000000000000000e+00,1.000000009972028758e+00,0.000000000000000000e+00,-1.487391677938416009e-10,0.000000000000000000e+00 +2.530984207511262696e+01,1.319600000000000080e+02,0.000000000000000000e+00,5.626141208722758691e+00,0.000000000000000000e+00,1.000000009971764303e+00,0.000000000000000000e+00,3.225574607617556695e-10,0.000000000000000000e+00 +2.531161949228525287e+01,1.319699999999999989e+02,0.000000000000000000e+00,5.627918625913108208e+00,0.000000000000000000e+00,1.000000009972337622e+00,0.000000000000000000e+00,-2.876691923970214641e-10,0.000000000000000000e+00 +2.531339634811148187e+01,1.319799999999999898e+02,0.000000000000000000e+00,5.629695481757057252e+00,0.000000000000000000e+00,1.000000009971826476e+00,0.000000000000000000e+00,-3.650127046557340521e-11,0.000000000000000000e+00 +2.531517264312289228e+01,1.319900000000000091e+02,0.000000000000000000e+00,5.631471776786179717e+00,0.000000000000000000e+00,1.000000009971761639e+00,0.000000000000000000e+00,2.098234839530912341e-10,0.000000000000000000e+00 +2.531694837785022045e+01,1.320000000000000000e+02,0.000000000000000000e+00,5.633247511531213725e+00,0.000000000000000000e+00,1.000000009972134229e+00,0.000000000000000000e+00,-1.350898795594293150e-10,0.000000000000000000e+00 +2.531872355282336429e+01,1.320099999999999909e+02,0.000000000000000000e+00,5.635022686522060731e+00,0.000000000000000000e+00,1.000000009971894421e+00,0.000000000000000000e+00,3.616044256038176899e-11,0.000000000000000000e+00 +2.532049816857139390e+01,1.320200000000000102e+02,0.000000000000000000e+00,5.636797302287785527e+00,0.000000000000000000e+00,1.000000009971958592e+00,0.000000000000000000e+00,-1.410576224642653156e-10,0.000000000000000000e+00 +2.532227222562253743e+01,1.320300000000000011e+02,0.000000000000000000e+00,5.638571359356621571e+00,0.000000000000000000e+00,1.000000009971708348e+00,0.000000000000000000e+00,1.627618654778919143e-10,0.000000000000000000e+00 +2.532404572450420233e+01,1.320399999999999920e+02,0.000000000000000000e+00,5.640344858255970095e+00,0.000000000000000000e+00,1.000000009971997006e+00,0.000000000000000000e+00,8.578995797992792946e-11,0.000000000000000000e+00 +2.532581866574295759e+01,1.320500000000000114e+02,0.000000000000000000e+00,5.642117799512404552e+00,0.000000000000000000e+00,1.000000009972149106e+00,0.000000000000000000e+00,-3.864893607706979998e-10,0.000000000000000000e+00 +2.532759104986454801e+01,1.320600000000000023e+02,0.000000000000000000e+00,5.643890183651669723e+00,0.000000000000000000e+00,1.000000009971464099e+00,0.000000000000000000e+00,4.304726082447692773e-10,0.000000000000000000e+00 +2.532936287739389414e+01,1.320699999999999932e+02,0.000000000000000000e+00,5.645662011198683494e+00,0.000000000000000000e+00,1.000000009972226822e+00,0.000000000000000000e+00,-3.022402574659471889e-10,0.000000000000000000e+00 +2.533113414885509229e+01,1.320800000000000125e+02,0.000000000000000000e+00,5.647433282677543964e+00,0.000000000000000000e+00,1.000000009971691473e+00,0.000000000000000000e+00,2.366264207778751318e-10,0.000000000000000000e+00 +2.533290486477141457e+01,1.320900000000000034e+02,0.000000000000000000e+00,5.649203998611522337e+00,0.000000000000000000e+00,1.000000009972110471e+00,0.000000000000000000e+00,-2.256621110752671897e-10,0.000000000000000000e+00 +2.533467502566531238e+01,1.320999999999999943e+02,0.000000000000000000e+00,5.650974159523073581e+00,0.000000000000000000e+00,1.000000009971711012e+00,0.000000000000000000e+00,5.144550131240732791e-12,0.000000000000000000e+00 +2.533644463205842357e+01,1.321100000000000136e+02,0.000000000000000000e+00,5.652743765933831099e+00,0.000000000000000000e+00,1.000000009971720116e+00,0.000000000000000000e+00,7.530967537495267017e-11,0.000000000000000000e+00 +2.533821368447156530e+01,1.321200000000000045e+02,0.000000000000000000e+00,5.654512818364613835e+00,0.000000000000000000e+00,1.000000009971853343e+00,0.000000000000000000e+00,-1.807997853308106368e-11,0.000000000000000000e+00 +2.533998218342474118e+01,1.321299999999999955e+02,0.000000000000000000e+00,5.656281317335425385e+00,0.000000000000000000e+00,1.000000009971821369e+00,0.000000000000000000e+00,8.163653877941770177e-12,0.000000000000000000e+00 +2.534175012943714123e+01,1.321400000000000148e+02,0.000000000000000000e+00,5.658049263365455772e+00,0.000000000000000000e+00,1.000000009971835802e+00,0.000000000000000000e+00,1.550322712649648258e-10,0.000000000000000000e+00 +2.534351752302714544e+01,1.321500000000000057e+02,0.000000000000000000e+00,5.659816656973084115e+00,0.000000000000000000e+00,1.000000009972109805e+00,0.000000000000000000e+00,-1.437701126056280645e-10,0.000000000000000000e+00 +2.534528436471232382e+01,1.321599999999999966e+02,0.000000000000000000e+00,5.661583498675880399e+00,0.000000000000000000e+00,1.000000009971855786e+00,0.000000000000000000e+00,-3.130238937321770196e-11,0.000000000000000000e+00 +2.534705065500943633e+01,1.321700000000000159e+02,0.000000000000000000e+00,5.663349788990605482e+00,0.000000000000000000e+00,1.000000009971800496e+00,0.000000000000000000e+00,-7.042091092112599250e-11,0.000000000000000000e+00 +2.534881639443444001e+01,1.321800000000000068e+02,0.000000000000000000e+00,5.665115528433215530e+00,0.000000000000000000e+00,1.000000009971676151e+00,0.000000000000000000e+00,3.044138181264784028e-11,0.000000000000000000e+00 +2.535058158350248547e+01,1.321899999999999977e+02,0.000000000000000000e+00,5.666880717518862021e+00,0.000000000000000000e+00,1.000000009971729886e+00,0.000000000000000000e+00,-4.529881044283513397e-12,0.000000000000000000e+00 +2.535234622272792038e+01,1.321999999999999886e+02,0.000000000000000000e+00,5.668645356761894405e+00,0.000000000000000000e+00,1.000000009971721893e+00,0.000000000000000000e+00,1.199533589123299351e-10,0.000000000000000000e+00 +2.535411031262429660e+01,1.322100000000000080e+02,0.000000000000000000e+00,5.670409446675860998e+00,0.000000000000000000e+00,1.000000009971933501e+00,0.000000000000000000e+00,-1.552450356656928462e-10,0.000000000000000000e+00 +2.535587385370436309e+01,1.322199999999999989e+02,0.000000000000000000e+00,5.672172987773511643e+00,0.000000000000000000e+00,1.000000009971659720e+00,0.000000000000000000e+00,3.263300787663940615e-10,0.000000000000000000e+00 +2.535763684648006944e+01,1.322299999999999898e+02,0.000000000000000000e+00,5.673935980566797710e+00,0.000000000000000000e+00,1.000000009972235038e+00,0.000000000000000000e+00,-4.211734957023606214e-10,0.000000000000000000e+00 +2.535939929146257299e+01,1.322400000000000091e+02,0.000000000000000000e+00,5.675698425566877425e+00,0.000000000000000000e+00,1.000000009971492743e+00,0.000000000000000000e+00,1.920633519017816111e-10,0.000000000000000000e+00 +2.536116118916223883e+01,1.322500000000000000e+02,0.000000000000000000e+00,5.677460323284111432e+00,0.000000000000000000e+00,1.000000009971831139e+00,0.000000000000000000e+00,-1.034993185692613146e-10,0.000000000000000000e+00 +2.536292254008863623e+01,1.322599999999999909e+02,0.000000000000000000e+00,5.679221674228072558e+00,0.000000000000000000e+00,1.000000009971648840e+00,0.000000000000000000e+00,1.423714761684345691e-10,0.000000000000000000e+00 +2.536468334475054576e+01,1.322700000000000102e+02,0.000000000000000000e+00,5.680982478907540489e+00,0.000000000000000000e+00,1.000000009971899528e+00,0.000000000000000000e+00,-1.943865957087291688e-10,0.000000000000000000e+00 +2.536644360365595929e+01,1.322800000000000011e+02,0.000000000000000000e+00,5.682742737830507984e+00,0.000000000000000000e+00,1.000000009971557358e+00,0.000000000000000000e+00,5.501545516249043002e-11,0.000000000000000000e+00 +2.536820331731208356e+01,1.322899999999999920e+02,0.000000000000000000e+00,5.684502451504179099e+00,0.000000000000000000e+00,1.000000009971654169e+00,0.000000000000000000e+00,5.541115513563920305e-11,0.000000000000000000e+00 +2.536996248622533656e+01,1.323000000000000114e+02,0.000000000000000000e+00,5.686261620434974517e+00,0.000000000000000000e+00,1.000000009971751647e+00,0.000000000000000000e+00,1.193160510684310329e-10,0.000000000000000000e+00 +2.537172111090135473e+01,1.323100000000000023e+02,0.000000000000000000e+00,5.688020245128530661e+00,0.000000000000000000e+00,1.000000009971961479e+00,0.000000000000000000e+00,-1.275624150216495606e-11,0.000000000000000000e+00 +2.537347919184499645e+01,1.323199999999999932e+02,0.000000000000000000e+00,5.689778326089702354e+00,0.000000000000000000e+00,1.000000009971939052e+00,0.000000000000000000e+00,-3.126876836805795170e-10,0.000000000000000000e+00 +2.537523672956033138e+01,1.323300000000000125e+02,0.000000000000000000e+00,5.691535863822563712e+00,0.000000000000000000e+00,1.000000009971389492e+00,0.000000000000000000e+00,4.011221317717432030e-10,0.000000000000000000e+00 +2.537699372455065827e+01,1.323400000000000034e+02,0.000000000000000000e+00,5.693292858830409919e+00,0.000000000000000000e+00,1.000000009972094261e+00,0.000000000000000000e+00,-4.281726731582801490e-10,0.000000000000000000e+00 +2.537875017731849425e+01,1.323499999999999943e+02,0.000000000000000000e+00,5.695049311615762555e+00,0.000000000000000000e+00,1.000000009971342196e+00,0.000000000000000000e+00,3.983348169442824496e-10,0.000000000000000000e+00 +2.538050608836558553e+01,1.323600000000000136e+02,0.000000000000000000e+00,5.696805222680363379e+00,0.000000000000000000e+00,1.000000009972041637e+00,0.000000000000000000e+00,-2.512180501899763853e-10,0.000000000000000000e+00 +2.538226145819290380e+01,1.323700000000000045e+02,0.000000000000000000e+00,5.698560592525185875e+00,0.000000000000000000e+00,1.000000009971600656e+00,0.000000000000000000e+00,-3.580897018206358721e-11,0.000000000000000000e+00 +2.538401628730064630e+01,1.323799999999999955e+02,0.000000000000000000e+00,5.700315421650427261e+00,0.000000000000000000e+00,1.000000009971537818e+00,0.000000000000000000e+00,2.187171565773290880e-10,0.000000000000000000e+00 +2.538577057618824284e+01,1.323900000000000148e+02,0.000000000000000000e+00,5.702069710555517368e+00,0.000000000000000000e+00,1.000000009971921511e+00,0.000000000000000000e+00,-3.142494491647783708e-10,0.000000000000000000e+00 +2.538752432535435588e+01,1.324000000000000057e+02,0.000000000000000000e+00,5.703823459739117752e+00,0.000000000000000000e+00,1.000000009971370396e+00,0.000000000000000000e+00,1.389354039667847662e-10,0.000000000000000000e+00 +2.538927753529687692e+01,1.324099999999999966e+02,0.000000000000000000e+00,5.705576669699120806e+00,0.000000000000000000e+00,1.000000009971613979e+00,0.000000000000000000e+00,1.769848846937465514e-10,0.000000000000000000e+00 +2.539103020651293718e+01,1.324200000000000159e+02,0.000000000000000000e+00,5.707329340932656869e+00,0.000000000000000000e+00,1.000000009971924175e+00,0.000000000000000000e+00,-1.561291040459218957e-10,0.000000000000000000e+00 +2.539278233949890051e+01,1.324300000000000068e+02,0.000000000000000000e+00,5.709081473936091555e+00,0.000000000000000000e+00,1.000000009971650616e+00,0.000000000000000000e+00,5.235480157707263908e-11,0.000000000000000000e+00 +2.539453393475037046e+01,1.324399999999999977e+02,0.000000000000000000e+00,5.710833069205027535e+00,0.000000000000000000e+00,1.000000009971742321e+00,0.000000000000000000e+00,-3.075044706162753345e-10,0.000000000000000000e+00 +2.539628499276219031e+01,1.324499999999999886e+02,0.000000000000000000e+00,5.712584127234308973e+00,0.000000000000000000e+00,1.000000009971203863e+00,0.000000000000000000e+00,2.615540777374723958e-10,0.000000000000000000e+00 +2.539803551402844661e+01,1.324600000000000080e+02,0.000000000000000000e+00,5.714334648518019755e+00,0.000000000000000000e+00,1.000000009971661719e+00,0.000000000000000000e+00,7.080111461272976118e-11,0.000000000000000000e+00 +2.539978549904246563e+01,1.324699999999999989e+02,0.000000000000000000e+00,5.716084633549489702e+00,0.000000000000000000e+00,1.000000009971785619e+00,0.000000000000000000e+00,4.163060473692487022e-11,0.000000000000000000e+00 +2.540153494829682046e+01,1.324799999999999898e+02,0.000000000000000000e+00,5.717834082821291020e+00,0.000000000000000000e+00,1.000000009971858450e+00,0.000000000000000000e+00,-3.537145188912153486e-10,0.000000000000000000e+00 +2.540328386228333102e+01,1.324900000000000091e+02,0.000000000000000000e+00,5.719582996825242738e+00,0.000000000000000000e+00,1.000000009971239834e+00,0.000000000000000000e+00,3.920497862175303793e-10,0.000000000000000000e+00 +2.540503224149306405e+01,1.325000000000000000e+02,0.000000000000000000e+00,5.721331376052410711e+00,0.000000000000000000e+00,1.000000009971925286e+00,0.000000000000000000e+00,-2.793589292324594148e-10,0.000000000000000000e+00 +2.540678008641633667e+01,1.325099999999999909e+02,0.000000000000000000e+00,5.723079220993113836e+00,0.000000000000000000e+00,1.000000009971437009e+00,0.000000000000000000e+00,1.410564539683879716e-11,0.000000000000000000e+00 +2.540852739754271639e+01,1.325200000000000102e+02,0.000000000000000000e+00,5.724826532136917834e+00,0.000000000000000000e+00,1.000000009971461656e+00,0.000000000000000000e+00,1.693194238329448203e-10,0.000000000000000000e+00 +2.541027417536102462e+01,1.325300000000000011e+02,0.000000000000000000e+00,5.726573309972644132e+00,0.000000000000000000e+00,1.000000009971757420e+00,0.000000000000000000e+00,-4.475872572818608264e-11,0.000000000000000000e+00 +2.541202042035933673e+01,1.325399999999999920e+02,0.000000000000000000e+00,5.728319554988368090e+00,0.000000000000000000e+00,1.000000009971679260e+00,0.000000000000000000e+00,1.615366914639088546e-11,0.000000000000000000e+00 +2.541376613302498200e+01,1.325500000000000114e+02,0.000000000000000000e+00,5.730065267671419882e+00,0.000000000000000000e+00,1.000000009971707460e+00,0.000000000000000000e+00,-1.671841723220933926e-10,0.000000000000000000e+00 +2.541551131384454720e+01,1.325600000000000023e+02,0.000000000000000000e+00,5.731810448508388056e+00,0.000000000000000000e+00,1.000000009971415693e+00,0.000000000000000000e+00,5.383595391082014811e-11,0.000000000000000000e+00 +2.541725596330388370e+01,1.325699999999999932e+02,0.000000000000000000e+00,5.733555097985119531e+00,0.000000000000000000e+00,1.000000009971509618e+00,0.000000000000000000e+00,1.619389530169062486e-10,0.000000000000000000e+00 +2.541900008188809679e+01,1.325800000000000125e+02,0.000000000000000000e+00,5.735299216586723148e+00,0.000000000000000000e+00,1.000000009971792059e+00,0.000000000000000000e+00,-3.591248141260230309e-10,0.000000000000000000e+00 +2.542074367008155633e+01,1.325900000000000034e+02,0.000000000000000000e+00,5.737042804797569673e+00,0.000000000000000000e+00,1.000000009971165893e+00,0.000000000000000000e+00,3.128647813839886979e-10,0.000000000000000000e+00 +2.542248672836789680e+01,1.325999999999999943e+02,0.000000000000000000e+00,5.738785863101291795e+00,0.000000000000000000e+00,1.000000009971711235e+00,0.000000000000000000e+00,-8.907122413654551290e-11,0.000000000000000000e+00 +2.542422925723002081e+01,1.326100000000000136e+02,0.000000000000000000e+00,5.740528391980791234e+00,0.000000000000000000e+00,1.000000009971556025e+00,0.000000000000000000e+00,-3.161140329968583966e-11,0.000000000000000000e+00 +2.542597125715009199e+01,1.326200000000000045e+02,0.000000000000000000e+00,5.742270391918233408e+00,0.000000000000000000e+00,1.000000009971500958e+00,0.000000000000000000e+00,-2.537329919486915707e-11,0.000000000000000000e+00 +2.542771272860954568e+01,1.326299999999999955e+02,0.000000000000000000e+00,5.744011863395053652e+00,0.000000000000000000e+00,1.000000009971456771e+00,0.000000000000000000e+00,4.591536641612091045e-12,0.000000000000000000e+00 +2.542945367208908891e+01,1.326400000000000148e+02,0.000000000000000000e+00,5.745752806891957221e+00,0.000000000000000000e+00,1.000000009971464765e+00,0.000000000000000000e+00,1.348534776487397525e-10,0.000000000000000000e+00 +2.543119408806869686e+01,1.326500000000000057e+02,0.000000000000000000e+00,5.747493222888921061e+00,0.000000000000000000e+00,1.000000009971699466e+00,0.000000000000000000e+00,-1.430620045285930863e-10,0.000000000000000000e+00 +2.543293397702762348e+01,1.326599999999999966e+02,0.000000000000000000e+00,5.749233111865195589e+00,0.000000000000000000e+00,1.000000009971450554e+00,0.000000000000000000e+00,1.303394505039881885e-10,0.000000000000000000e+00 +2.543467333944438735e+01,1.326700000000000159e+02,0.000000000000000000e+00,5.750972474299304693e+00,0.000000000000000000e+00,1.000000009971677262e+00,0.000000000000000000e+00,-1.382961121102731871e-10,0.000000000000000000e+00 +2.543641217579679292e+01,1.326800000000000068e+02,0.000000000000000000e+00,5.752711310669050171e+00,0.000000000000000000e+00,1.000000009971436787e+00,0.000000000000000000e+00,1.468962286759058400e-11,0.000000000000000000e+00 +2.543815048656191991e+01,1.326899999999999977e+02,0.000000000000000000e+00,5.754449621451509955e+00,0.000000000000000000e+00,1.000000009971462323e+00,0.000000000000000000e+00,8.522555766683830712e-11,0.000000000000000000e+00 +2.543988827221612326e+01,1.326999999999999886e+02,0.000000000000000000e+00,5.756187407123042554e+00,0.000000000000000000e+00,1.000000009971610426e+00,0.000000000000000000e+00,-1.358652571286488033e-10,0.000000000000000000e+00 +2.544162553323504383e+01,1.327100000000000080e+02,0.000000000000000000e+00,5.757924668159287052e+00,0.000000000000000000e+00,1.000000009971374393e+00,0.000000000000000000e+00,2.659313504909403436e-11,0.000000000000000000e+00 +2.544336227009360485e+01,1.327199999999999989e+02,0.000000000000000000e+00,5.759661405035163995e+00,0.000000000000000000e+00,1.000000009971420578e+00,0.000000000000000000e+00,7.213005820272027583e-11,0.000000000000000000e+00 +2.544509848326600832e+01,1.327299999999999898e+02,0.000000000000000000e+00,5.761397618224878947e+00,0.000000000000000000e+00,1.000000009971545811e+00,0.000000000000000000e+00,-2.054535336275343834e-10,0.000000000000000000e+00 +2.544683417322574570e+01,1.327400000000000091e+02,0.000000000000000000e+00,5.763133308201922489e+00,0.000000000000000000e+00,1.000000009971189208e+00,0.000000000000000000e+00,1.699405290554379533e-10,0.000000000000000000e+00 +2.544856934044559438e+01,1.327500000000000000e+02,0.000000000000000000e+00,5.764868475439071105e+00,0.000000000000000000e+00,1.000000009971484083e+00,0.000000000000000000e+00,1.105970062815621621e-10,0.000000000000000000e+00 +2.545030398539761762e+01,1.327599999999999909e+02,0.000000000000000000e+00,5.766603120408391625e+00,0.000000000000000000e+00,1.000000009971675929e+00,0.000000000000000000e+00,-2.906605863401312105e-10,0.000000000000000000e+00 +2.545203810855317172e+01,1.327700000000000102e+02,0.000000000000000000e+00,5.768337243581239449e+00,0.000000000000000000e+00,1.000000009971171888e+00,0.000000000000000000e+00,2.428450199560845042e-10,0.000000000000000000e+00 +2.545377171038290598e+01,1.327800000000000011e+02,0.000000000000000000e+00,5.770070845428260320e+00,0.000000000000000000e+00,1.000000009971592885e+00,0.000000000000000000e+00,3.523336028472038617e-11,0.000000000000000000e+00 +2.545550479135675914e+01,1.327899999999999920e+02,0.000000000000000000e+00,5.771803926419395658e+00,0.000000000000000000e+00,1.000000009971653947e+00,0.000000000000000000e+00,-2.255612343681908821e-10,0.000000000000000000e+00 +2.545723735194396653e+01,1.328000000000000114e+02,0.000000000000000000e+00,5.773536487023879005e+00,0.000000000000000000e+00,1.000000009971263149e+00,0.000000000000000000e+00,1.519149414513542269e-10,0.000000000000000000e+00 +2.545896939261305647e+01,1.328100000000000023e+02,0.000000000000000000e+00,5.775268527710239574e+00,0.000000000000000000e+00,1.000000009971526271e+00,0.000000000000000000e+00,-2.117188277861360349e-10,0.000000000000000000e+00 +2.546070091383185741e+01,1.328199999999999932e+02,0.000000000000000000e+00,5.777000048946305810e+00,0.000000000000000000e+00,1.000000009971159676e+00,0.000000000000000000e+00,2.664275267441390828e-10,0.000000000000000000e+00 +2.546243191606749434e+01,1.328300000000000125e+02,0.000000000000000000e+00,5.778731051199202717e+00,0.000000000000000000e+00,1.000000009971620862e+00,0.000000000000000000e+00,-8.840807406765296451e-11,0.000000000000000000e+00 +2.546416239978639240e+01,1.328400000000000034e+02,0.000000000000000000e+00,5.780461534935358081e+00,0.000000000000000000e+00,1.000000009971467874e+00,0.000000000000000000e+00,-2.830162256668980909e-10,0.000000000000000000e+00 +2.546589236545428392e+01,1.328499999999999943e+02,0.000000000000000000e+00,5.782191500620498914e+00,0.000000000000000000e+00,1.000000009970978265e+00,0.000000000000000000e+00,3.838874237794896409e-10,0.000000000000000000e+00 +2.546762181353619781e+01,1.328600000000000136e+02,0.000000000000000000e+00,5.783920948719655897e+00,0.000000000000000000e+00,1.000000009971642179e+00,0.000000000000000000e+00,-5.920569717509675108e-11,0.000000000000000000e+00 +2.546935074449647018e+01,1.328700000000000045e+02,0.000000000000000000e+00,5.785649879697166931e+00,0.000000000000000000e+00,1.000000009971539816e+00,0.000000000000000000e+00,-3.159009288417132278e-10,0.000000000000000000e+00 +2.547107915879874085e+01,1.328799999999999955e+02,0.000000000000000000e+00,5.787378294016672697e+00,0.000000000000000000e+00,1.000000009970993808e+00,0.000000000000000000e+00,3.193364475213884611e-10,0.000000000000000000e+00 +2.547280705690596037e+01,1.328900000000000148e+02,0.000000000000000000e+00,5.789106192141121987e+00,0.000000000000000000e+00,1.000000009971545589e+00,0.000000000000000000e+00,-1.236593085005512650e-10,0.000000000000000000e+00 +2.547453443928039007e+01,1.329000000000000057e+02,0.000000000000000000e+00,5.790833574532775252e+00,0.000000000000000000e+00,1.000000009971331982e+00,0.000000000000000000e+00,-4.500381736353078909e-11,0.000000000000000000e+00 +2.547626130638359498e+01,1.329099999999999966e+02,0.000000000000000000e+00,5.792560441653200165e+00,0.000000000000000000e+00,1.000000009971254267e+00,0.000000000000000000e+00,7.511447681464097952e-11,0.000000000000000000e+00 +2.547798765867645798e+01,1.329200000000000159e+02,0.000000000000000000e+00,5.794286793963277837e+00,0.000000000000000000e+00,1.000000009971383941e+00,0.000000000000000000e+00,5.403678512349189427e-11,0.000000000000000000e+00 +2.547971349661917273e+01,1.329300000000000068e+02,0.000000000000000000e+00,5.796012631923202818e+00,0.000000000000000000e+00,1.000000009971477199e+00,0.000000000000000000e+00,-2.898263950410718331e-10,0.000000000000000000e+00 +2.548143882067125077e+01,1.329399999999999977e+02,0.000000000000000000e+00,5.797737955992483982e+00,0.000000000000000000e+00,1.000000009970977155e+00,0.000000000000000000e+00,3.556965826857990328e-10,0.000000000000000000e+00 +2.548316363129151441e+01,1.329499999999999886e+02,0.000000000000000000e+00,5.799462766629945421e+00,0.000000000000000000e+00,1.000000009971590664e+00,0.000000000000000000e+00,-2.772502968662998080e-10,0.000000000000000000e+00 +2.548488792893810739e+01,1.329600000000000080e+02,0.000000000000000000e+00,5.801187064293731765e+00,0.000000000000000000e+00,1.000000009971112602e+00,0.000000000000000000e+00,3.207424501570386636e-10,0.000000000000000000e+00 +2.548661171406849135e+01,1.329699999999999989e+02,0.000000000000000000e+00,5.802910849441302865e+00,0.000000000000000000e+00,1.000000009971665493e+00,0.000000000000000000e+00,-4.168313826978268124e-10,0.000000000000000000e+00 +2.548833498713944579e+01,1.329799999999999898e+02,0.000000000000000000e+00,5.804634122529442664e+00,0.000000000000000000e+00,1.000000009970947179e+00,0.000000000000000000e+00,3.246708092297471115e-10,0.000000000000000000e+00 +2.549005774860707874e+01,1.329900000000000091e+02,0.000000000000000000e+00,5.806356884014252984e+00,0.000000000000000000e+00,1.000000009971506509e+00,0.000000000000000000e+00,-2.153081268009016611e-11,0.000000000000000000e+00 +2.549177999892681612e+01,1.330000000000000000e+02,0.000000000000000000e+00,5.808079134351163297e+00,0.000000000000000000e+00,1.000000009971469428e+00,0.000000000000000000e+00,-1.329631868499891772e-10,0.000000000000000000e+00 +2.549350173855340884e+01,1.330099999999999909e+02,0.000000000000000000e+00,5.809800873994924508e+00,0.000000000000000000e+00,1.000000009971240500e+00,0.000000000000000000e+00,-1.809919020482304323e-10,0.000000000000000000e+00 +2.549522296794093634e+01,1.330200000000000102e+02,0.000000000000000000e+00,5.811522103399614281e+00,0.000000000000000000e+00,1.000000009970928971e+00,0.000000000000000000e+00,2.641483864009644274e-10,0.000000000000000000e+00 +2.549694368754280305e+01,1.330300000000000011e+02,0.000000000000000000e+00,5.813242823018637928e+00,0.000000000000000000e+00,1.000000009971383497e+00,0.000000000000000000e+00,-1.671584971731728972e-10,0.000000000000000000e+00 +2.549866389781174192e+01,1.330399999999999920e+02,0.000000000000000000e+00,5.814963033304731077e+00,0.000000000000000000e+00,1.000000009971095949e+00,0.000000000000000000e+00,1.570076301970713586e-10,0.000000000000000000e+00 +2.550038359919982156e+01,1.330500000000000114e+02,0.000000000000000000e+00,5.816682734709957003e+00,0.000000000000000000e+00,1.000000009971365955e+00,0.000000000000000000e+00,-1.313519591139572777e-10,0.000000000000000000e+00 +2.550210279215843556e+01,1.330600000000000023e+02,0.000000000000000000e+00,5.818401927685712849e+00,0.000000000000000000e+00,1.000000009971140136e+00,0.000000000000000000e+00,3.038654069235490190e-10,0.000000000000000000e+00 +2.550382147713831316e+01,1.330699999999999932e+02,0.000000000000000000e+00,5.820120612682726957e+00,0.000000000000000000e+00,1.000000009971662385e+00,0.000000000000000000e+00,-5.060750112143698732e-10,0.000000000000000000e+00 +2.550553965458951566e+01,1.330800000000000125e+02,0.000000000000000000e+00,5.821838790151064202e+00,0.000000000000000000e+00,1.000000009970792858e+00,0.000000000000000000e+00,2.829737580176833808e-10,0.000000000000000000e+00 +2.550725732496144715e+01,1.330900000000000034e+02,0.000000000000000000e+00,5.823556460540121549e+00,0.000000000000000000e+00,1.000000009971278914e+00,0.000000000000000000e+00,1.015075095428307211e-10,0.000000000000000000e+00 +2.550897448870284023e+01,1.330999999999999943e+02,0.000000000000000000e+00,5.825273624298637820e+00,0.000000000000000000e+00,1.000000009971453219e+00,0.000000000000000000e+00,-3.096568569687305388e-10,0.000000000000000000e+00 +2.551069114626177381e+01,1.331100000000000136e+02,0.000000000000000000e+00,5.826990281874687483e+00,0.000000000000000000e+00,1.000000009970921644e+00,0.000000000000000000e+00,3.964361777445200790e-10,0.000000000000000000e+00 +2.551240729808565888e+01,1.331200000000000045e+02,0.000000000000000000e+00,5.828706433715684199e+00,0.000000000000000000e+00,1.000000009971601989e+00,0.000000000000000000e+00,-3.517724797417016876e-10,0.000000000000000000e+00 +2.551412294462125274e+01,1.331299999999999955e+02,0.000000000000000000e+00,5.830422080268386154e+00,0.000000000000000000e+00,1.000000009970998471e+00,0.000000000000000000e+00,2.589227534718746208e-12,0.000000000000000000e+00 +2.551583808631465544e+01,1.331400000000000148e+02,0.000000000000000000e+00,5.832137221978889841e+00,0.000000000000000000e+00,1.000000009971002912e+00,0.000000000000000000e+00,9.582960079389253374e-11,0.000000000000000000e+00 +2.551755272361130622e+01,1.331500000000000057e+02,0.000000000000000000e+00,5.833851859292638942e+00,0.000000000000000000e+00,1.000000009971167225e+00,0.000000000000000000e+00,7.370685635027545068e-11,0.000000000000000000e+00 +2.551926685695599772e+01,1.331599999999999966e+02,0.000000000000000000e+00,5.835565992654421663e+00,0.000000000000000000e+00,1.000000009971293569e+00,0.000000000000000000e+00,8.396498525886786785e-11,0.000000000000000000e+00 +2.552098048679286180e+01,1.331700000000000159e+02,0.000000000000000000e+00,5.837279622508372512e+00,0.000000000000000000e+00,1.000000009971437454e+00,0.000000000000000000e+00,-3.302555668527625089e-10,0.000000000000000000e+00 +2.552269361356538013e+01,1.331800000000000068e+02,0.000000000000000000e+00,5.838992749297974072e+00,0.000000000000000000e+00,1.000000009970871684e+00,0.000000000000000000e+00,1.921437954179782878e-10,0.000000000000000000e+00 +2.552440623771638784e+01,1.331899999999999977e+02,0.000000000000000000e+00,5.840705373466057004e+00,0.000000000000000000e+00,1.000000009971200754e+00,0.000000000000000000e+00,-1.374710944162864752e-11,0.000000000000000000e+00 +2.552611835968806275e+01,1.331999999999999886e+02,0.000000000000000000e+00,5.842417495454805376e+00,0.000000000000000000e+00,1.000000009971177217e+00,0.000000000000000000e+00,1.132523069443013318e-10,0.000000000000000000e+00 +2.552782997992194325e+01,1.332100000000000080e+02,0.000000000000000000e+00,5.844129115705753108e+00,0.000000000000000000e+00,1.000000009971371062e+00,0.000000000000000000e+00,-1.827101535603881232e-10,0.000000000000000000e+00 +2.552954109885891754e+01,1.332199999999999989e+02,0.000000000000000000e+00,5.845840234659788415e+00,0.000000000000000000e+00,1.000000009971058423e+00,0.000000000000000000e+00,1.639421091409534641e-10,0.000000000000000000e+00 +2.553125171693922368e+01,1.332299999999999898e+02,0.000000000000000000e+00,5.847550852757152917e+00,0.000000000000000000e+00,1.000000009971338866e+00,0.000000000000000000e+00,-2.078765807326066753e-10,0.000000000000000000e+00 +2.553296183460246382e+01,1.332400000000000091e+02,0.000000000000000000e+00,5.849260970437446083e+00,0.000000000000000000e+00,1.000000009970983372e+00,0.000000000000000000e+00,7.455093868971238648e-11,0.000000000000000000e+00 +2.553467145228759350e+01,1.332500000000000000e+02,0.000000000000000000e+00,5.850970588139622564e+00,0.000000000000000000e+00,1.000000009971110826e+00,0.000000000000000000e+00,-4.521134055296613215e-11,0.000000000000000000e+00 +2.553638057043292520e+01,1.332599999999999909e+02,0.000000000000000000e+00,5.852679706301997520e+00,0.000000000000000000e+00,1.000000009971033554e+00,0.000000000000000000e+00,2.011712615458514579e-10,0.000000000000000000e+00 +2.553808918947613549e+01,1.332700000000000102e+02,0.000000000000000000e+00,5.854388325362244849e+00,0.000000000000000000e+00,1.000000009971377279e+00,0.000000000000000000e+00,-2.415279866890396464e-10,0.000000000000000000e+00 +2.553979730985425789e+01,1.332800000000000011e+02,0.000000000000000000e+00,5.856096445757400737e+00,0.000000000000000000e+00,1.000000009970964721e+00,0.000000000000000000e+00,6.891667495015734793e-12,0.000000000000000000e+00 +2.554150493200369354e+01,1.332899999999999920e+02,0.000000000000000000e+00,5.857804067923861879e+00,0.000000000000000000e+00,1.000000009970976489e+00,0.000000000000000000e+00,1.975753866995410250e-10,0.000000000000000000e+00 +2.554321205636020053e+01,1.333000000000000114e+02,0.000000000000000000e+00,5.859511192297390814e+00,0.000000000000000000e+00,1.000000009971313775e+00,0.000000000000000000e+00,-1.141040887474534102e-10,0.000000000000000000e+00 +2.554491868335890814e+01,1.333100000000000023e+02,0.000000000000000000e+00,5.861217819313115029e+00,0.000000000000000000e+00,1.000000009971119042e+00,0.000000000000000000e+00,-1.520095696640515003e-10,0.000000000000000000e+00 +2.554662481343430969e+01,1.333199999999999932e+02,0.000000000000000000e+00,5.862923949405526969e+00,0.000000000000000000e+00,1.000000009970859693e+00,0.000000000000000000e+00,-5.259395753487067393e-11,0.000000000000000000e+00 +2.554833044702026257e+01,1.333300000000000125e+02,0.000000000000000000e+00,5.864629583008487579e+00,0.000000000000000000e+00,1.000000009970769987e+00,0.000000000000000000e+00,3.534196199758151709e-10,0.000000000000000000e+00 +2.555003558454999890e+01,1.333400000000000034e+02,0.000000000000000000e+00,5.866334720555227200e+00,0.000000000000000000e+00,1.000000009971372616e+00,0.000000000000000000e+00,-2.911284124982523403e-10,0.000000000000000000e+00 +2.555174022645612197e+01,1.333499999999999943e+02,0.000000000000000000e+00,5.868039362478347343e+00,0.000000000000000000e+00,1.000000009970876347e+00,0.000000000000000000e+00,3.245689506477758634e-10,0.000000000000000000e+00 +2.555344437317059914e+01,1.333600000000000136e+02,0.000000000000000000e+00,5.869743509209818022e+00,0.000000000000000000e+00,1.000000009971429460e+00,0.000000000000000000e+00,-3.783610182325447999e-10,0.000000000000000000e+00 +2.555514802512477956e+01,1.333700000000000045e+02,0.000000000000000000e+00,5.871447161180985752e+00,0.000000000000000000e+00,1.000000009970784864e+00,0.000000000000000000e+00,2.216329380912468534e-10,0.000000000000000000e+00 +2.555685118274938006e+01,1.333799999999999955e+02,0.000000000000000000e+00,5.873150318822567328e+00,0.000000000000000000e+00,1.000000009971162340e+00,0.000000000000000000e+00,-1.486675530117437593e-10,0.000000000000000000e+00 +2.555855384647449213e+01,1.333900000000000148e+02,0.000000000000000000e+00,5.874852982564658710e+00,0.000000000000000000e+00,1.000000009970909209e+00,0.000000000000000000e+00,-8.792191220071865575e-11,0.000000000000000000e+00 +2.556025601672959269e+01,1.334000000000000057e+02,0.000000000000000000e+00,5.876555152836729690e+00,0.000000000000000000e+00,1.000000009970759551e+00,0.000000000000000000e+00,2.761078189062464751e-10,0.000000000000000000e+00 +2.556195769394352624e+01,1.334099999999999966e+02,0.000000000000000000e+00,5.878256830067629224e+00,0.000000000000000000e+00,1.000000009971229398e+00,0.000000000000000000e+00,-1.045493407599667050e-10,0.000000000000000000e+00 +2.556365887854451913e+01,1.334200000000000159e+02,0.000000000000000000e+00,5.879958014685586321e+00,0.000000000000000000e+00,1.000000009971051540e+00,0.000000000000000000e+00,-1.297779276620552664e-10,0.000000000000000000e+00 +2.556535957096018308e+01,1.334300000000000068e+02,0.000000000000000000e+00,5.881658707118208262e+00,0.000000000000000000e+00,1.000000009970830828e+00,0.000000000000000000e+00,7.600865198448929238e-11,0.000000000000000000e+00 +2.556705977161750809e+01,1.334399999999999977e+02,0.000000000000000000e+00,5.883358907792485049e+00,0.000000000000000000e+00,1.000000009970960058e+00,0.000000000000000000e+00,8.125609608826524510e-11,0.000000000000000000e+00 +2.556875948094286599e+01,1.334499999999999886e+02,0.000000000000000000e+00,5.885058617134790282e+00,0.000000000000000000e+00,1.000000009971098169e+00,0.000000000000000000e+00,6.964953598160501882e-11,0.000000000000000000e+00 +2.557045869936201399e+01,1.334600000000000080e+02,0.000000000000000000e+00,5.886757835570881170e+00,0.000000000000000000e+00,1.000000009971216519e+00,0.000000000000000000e+00,-8.130303927267519966e-11,0.000000000000000000e+00 +2.557215742730009467e+01,1.334699999999999989e+02,0.000000000000000000e+00,5.888456563525900300e+00,0.000000000000000000e+00,1.000000009971078407e+00,0.000000000000000000e+00,-1.851420015953103628e-10,0.000000000000000000e+00 +2.557385566518163600e+01,1.334799999999999898e+02,0.000000000000000000e+00,5.890154801424376529e+00,0.000000000000000000e+00,1.000000009970763992e+00,0.000000000000000000e+00,-5.388453634817753577e-11,0.000000000000000000e+00 +2.557555341343055844e+01,1.334900000000000091e+02,0.000000000000000000e+00,5.891852549690226759e+00,0.000000000000000000e+00,1.000000009970672510e+00,0.000000000000000000e+00,1.938832534218652313e-10,0.000000000000000000e+00 +2.557725067247016781e+01,1.335000000000000000e+02,0.000000000000000000e+00,5.893549808746757712e+00,0.000000000000000000e+00,1.000000009971001580e+00,0.000000000000000000e+00,1.312556831705835028e-10,0.000000000000000000e+00 +2.557894744272315890e+01,1.335099999999999909e+02,0.000000000000000000e+00,5.895246579016666821e+00,0.000000000000000000e+00,1.000000009971224291e+00,0.000000000000000000e+00,-3.590608114443830691e-10,0.000000000000000000e+00 +2.558064372461161895e+01,1.335200000000000102e+02,0.000000000000000000e+00,5.896942860922042229e+00,0.000000000000000000e+00,1.000000009970615222e+00,0.000000000000000000e+00,4.588082754757491128e-10,0.000000000000000000e+00 +2.558233951855703125e+01,1.335300000000000011e+02,0.000000000000000000e+00,5.898638654884363675e+00,0.000000000000000000e+00,1.000000009971393267e+00,0.000000000000000000e+00,-3.091035699737587066e-10,0.000000000000000000e+00 +2.558403482498027159e+01,1.335399999999999920e+02,0.000000000000000000e+00,5.900333961324508714e+00,0.000000000000000000e+00,1.000000009970869241e+00,0.000000000000000000e+00,3.406357040756918188e-12,0.000000000000000000e+00 +2.558572964430160823e+01,1.335500000000000114e+02,0.000000000000000000e+00,5.902028780662745611e+00,0.000000000000000000e+00,1.000000009970875015e+00,0.000000000000000000e+00,4.730954272378909435e-11,0.000000000000000000e+00 +2.558742397694071258e+01,1.335600000000000023e+02,0.000000000000000000e+00,5.903723113318742222e+00,0.000000000000000000e+00,1.000000009970955173e+00,0.000000000000000000e+00,2.018770394076799345e-11,0.000000000000000000e+00 +2.558911782331664497e+01,1.335699999999999932e+02,0.000000000000000000e+00,5.905416959711563329e+00,0.000000000000000000e+00,1.000000009970989368e+00,0.000000000000000000e+00,-1.896090600915316758e-10,0.000000000000000000e+00 +2.559081118384786890e+01,1.335800000000000125e+02,0.000000000000000000e+00,5.907110320259672420e+00,0.000000000000000000e+00,1.000000009970668291e+00,0.000000000000000000e+00,2.379318546841490098e-10,0.000000000000000000e+00 +2.559250405895225100e+01,1.335900000000000034e+02,0.000000000000000000e+00,5.908803195380932571e+00,0.000000000000000000e+00,1.000000009971071080e+00,0.000000000000000000e+00,-3.560816502160302457e-10,0.000000000000000000e+00 +2.559419644904705393e+01,1.335999999999999943e+02,0.000000000000000000e+00,5.910495585492610005e+00,0.000000000000000000e+00,1.000000009970468451e+00,0.000000000000000000e+00,4.014612197349863589e-10,0.000000000000000000e+00 +2.559588835454894706e+01,1.336100000000000136e+02,0.000000000000000000e+00,5.912187491011370533e+00,0.000000000000000000e+00,1.000000009971147685e+00,0.000000000000000000e+00,-7.797849853964930740e-11,0.000000000000000000e+00 +2.559757977587399935e+01,1.336200000000000045e+02,0.000000000000000000e+00,5.913878912353287554e+00,0.000000000000000000e+00,1.000000009971015791e+00,0.000000000000000000e+00,-3.860646025603801135e-11,0.000000000000000000e+00 +2.559927071343768645e+01,1.336299999999999955e+02,0.000000000000000000e+00,5.915569849933835833e+00,0.000000000000000000e+00,1.000000009970950510e+00,0.000000000000000000e+00,-2.062226981268926917e-10,0.000000000000000000e+00 +2.560096116765489427e+01,1.336400000000000148e+02,0.000000000000000000e+00,5.917260304167897722e+00,0.000000000000000000e+00,1.000000009970601900e+00,0.000000000000000000e+00,2.483262923042534328e-10,0.000000000000000000e+00 +2.560265113893990829e+01,1.336500000000000057e+02,0.000000000000000000e+00,5.918950275469762268e+00,0.000000000000000000e+00,1.000000009971021564e+00,0.000000000000000000e+00,-3.329048380910061750e-10,0.000000000000000000e+00 +2.560434062770642782e+01,1.336599999999999966e+02,0.000000000000000000e+00,5.920639764253128767e+00,0.000000000000000000e+00,1.000000009970459125e+00,0.000000000000000000e+00,4.373827632446793708e-10,0.000000000000000000e+00 +2.560602963436756241e+01,1.336700000000000159e+02,0.000000000000000000e+00,5.922328770931103215e+00,0.000000000000000000e+00,1.000000009971197867e+00,0.000000000000000000e+00,-3.432205207183387090e-10,0.000000000000000000e+00 +2.560771815933582829e+01,1.336800000000000068e+02,0.000000000000000000e+00,5.924017295916206294e+00,0.000000000000000000e+00,1.000000009970618331e+00,0.000000000000000000e+00,2.814947611287239960e-11,0.000000000000000000e+00 +2.560940620302315907e+01,1.336899999999999977e+02,0.000000000000000000e+00,5.925705339620366274e+00,0.000000000000000000e+00,1.000000009970665849e+00,0.000000000000000000e+00,2.072339169135090620e-10,0.000000000000000000e+00 +2.561109376584089503e+01,1.336999999999999886e+02,0.000000000000000000e+00,5.927392902454927892e+00,0.000000000000000000e+00,1.000000009971015569e+00,0.000000000000000000e+00,-2.165059537104409169e-10,0.000000000000000000e+00 +2.561278084819979384e+01,1.337100000000000080e+02,0.000000000000000000e+00,5.929079984830649686e+00,0.000000000000000000e+00,1.000000009970650305e+00,0.000000000000000000e+00,2.205171373191058850e-10,0.000000000000000000e+00 +2.561446745051003049e+01,1.337199999999999989e+02,0.000000000000000000e+00,5.930766587157703995e+00,0.000000000000000000e+00,1.000000009971022230e+00,0.000000000000000000e+00,-1.385373249382905113e-10,0.000000000000000000e+00 +2.561615357318119734e+01,1.337299999999999898e+02,0.000000000000000000e+00,5.932452709845682293e+00,0.000000000000000000e+00,1.000000009970788639e+00,0.000000000000000000e+00,-1.392353457931180613e-10,0.000000000000000000e+00 +2.561783921662230057e+01,1.337400000000000091e+02,0.000000000000000000e+00,5.934138353303591629e+00,0.000000000000000000e+00,1.000000009970553938e+00,0.000000000000000000e+00,1.247808305699594003e-10,0.000000000000000000e+00 +2.561952438124176723e+01,1.337500000000000000e+02,0.000000000000000000e+00,5.935823517939859073e+00,0.000000000000000000e+00,1.000000009970764214e+00,0.000000000000000000e+00,2.488417206041416497e-10,0.000000000000000000e+00 +2.562120906744744175e+01,1.337599999999999909e+02,0.000000000000000000e+00,5.937508204162332603e+00,0.000000000000000000e+00,1.000000009971183434e+00,0.000000000000000000e+00,-4.863546846401965600e-10,0.000000000000000000e+00 +2.562289327564659658e+01,1.337700000000000102e+02,0.000000000000000000e+00,5.939192412378281105e+00,0.000000000000000000e+00,1.000000009970364312e+00,0.000000000000000000e+00,3.335158285301326078e-10,0.000000000000000000e+00 +2.562457700624592150e+01,1.337800000000000011e+02,0.000000000000000000e+00,5.940876142994393483e+00,0.000000000000000000e+00,1.000000009970925863e+00,0.000000000000000000e+00,1.135779106124650942e-10,0.000000000000000000e+00 +2.562626025965153076e+01,1.337899999999999920e+02,0.000000000000000000e+00,5.942559396416786655e+00,0.000000000000000000e+00,1.000000009971117043e+00,0.000000000000000000e+00,-2.962307253929915891e-10,0.000000000000000000e+00 +2.562794303626896308e+01,1.338000000000000114e+02,0.000000000000000000e+00,5.944242173050999334e+00,0.000000000000000000e+00,1.000000009970618553e+00,0.000000000000000000e+00,-4.289632440904910997e-11,0.000000000000000000e+00 +2.562962533650318520e+01,1.338100000000000023e+02,0.000000000000000000e+00,5.945924473301995583e+00,0.000000000000000000e+00,1.000000009970546389e+00,0.000000000000000000e+00,1.601475926563749151e-10,0.000000000000000000e+00 +2.563130716075858828e+01,1.338199999999999932e+02,0.000000000000000000e+00,5.947606297574168366e+00,0.000000000000000000e+00,1.000000009970815729e+00,0.000000000000000000e+00,-8.795421711359265708e-11,0.000000000000000000e+00 +2.563298850943899510e+01,1.338300000000000125e+02,0.000000000000000000e+00,5.949287646271338659e+00,0.000000000000000000e+00,1.000000009970667847e+00,0.000000000000000000e+00,7.027758437008983733e-11,0.000000000000000000e+00 +2.563466938294765285e+01,1.338400000000000034e+02,0.000000000000000000e+00,5.950968519796755452e+00,0.000000000000000000e+00,1.000000009970785975e+00,0.000000000000000000e+00,-7.769717068929465337e-11,0.000000000000000000e+00 +2.563634978168724032e+01,1.338499999999999943e+02,0.000000000000000000e+00,5.952648918553099300e+00,0.000000000000000000e+00,1.000000009970655412e+00,0.000000000000000000e+00,1.374623720472639390e-11,0.000000000000000000e+00 +2.563802970605987142e+01,1.338600000000000136e+02,0.000000000000000000e+00,5.954328842942481437e+00,0.000000000000000000e+00,1.000000009970678505e+00,0.000000000000000000e+00,-5.195957520412786499e-11,0.000000000000000000e+00 +2.563970915646709159e+01,1.338700000000000045e+02,0.000000000000000000e+00,5.956008293366446438e+00,0.000000000000000000e+00,1.000000009970591242e+00,0.000000000000000000e+00,2.738896481960109159e-10,0.000000000000000000e+00 +2.564138813330987787e+01,1.338799999999999955e+02,0.000000000000000000e+00,5.957687270225972220e+00,0.000000000000000000e+00,1.000000009971051096e+00,0.000000000000000000e+00,-3.495028659358693802e-10,0.000000000000000000e+00 +2.564306663698864241e+01,1.338900000000000148e+02,0.000000000000000000e+00,5.959365773921472709e+00,0.000000000000000000e+00,1.000000009970464454e+00,0.000000000000000000e+00,2.051029779254927611e-10,0.000000000000000000e+00 +2.564474466790323248e+01,1.339000000000000057e+02,0.000000000000000000e+00,5.961043804852795169e+00,0.000000000000000000e+00,1.000000009970808623e+00,0.000000000000000000e+00,-3.256099336809787341e-11,0.000000000000000000e+00 +2.564642222645293756e+01,1.339099999999999966e+02,0.000000000000000000e+00,5.962721363419227316e+00,0.000000000000000000e+00,1.000000009970754000e+00,0.000000000000000000e+00,-1.936997530079216440e-10,0.000000000000000000e+00 +2.564809931303648227e+01,1.339200000000000159e+02,0.000000000000000000e+00,5.964398450019492870e+00,0.000000000000000000e+00,1.000000009970429149e+00,0.000000000000000000e+00,2.773215069660398957e-10,0.000000000000000000e+00 +2.564977592805202633e+01,1.339300000000000068e+02,0.000000000000000000e+00,5.966075065051755111e+00,0.000000000000000000e+00,1.000000009970894110e+00,0.000000000000000000e+00,-2.747499935322159649e-10,0.000000000000000000e+00 +2.565145207189717880e+01,1.339399999999999977e+02,0.000000000000000000e+00,5.967751208913619543e+00,0.000000000000000000e+00,1.000000009970433590e+00,0.000000000000000000e+00,2.880782529896699051e-10,0.000000000000000000e+00 +2.565312774496898385e+01,1.339499999999999886e+02,0.000000000000000000e+00,5.969426882002130341e+00,0.000000000000000000e+00,1.000000009970916315e+00,0.000000000000000000e+00,-3.215612135617977766e-10,0.000000000000000000e+00 +2.565480294766392788e+01,1.339600000000000080e+02,0.000000000000000000e+00,5.971102084713777458e+00,0.000000000000000000e+00,1.000000009970377635e+00,0.000000000000000000e+00,3.553280689024368312e-10,0.000000000000000000e+00 +2.565647768037794307e+01,1.339699999999999989e+02,0.000000000000000000e+00,5.972776817444491293e+00,0.000000000000000000e+00,1.000000009970972714e+00,0.000000000000000000e+00,-2.858010282123597361e-10,0.000000000000000000e+00 +2.565815194350640738e+01,1.339799999999999898e+02,0.000000000000000000e+00,5.974451080589650687e+00,0.000000000000000000e+00,1.000000009970494208e+00,0.000000000000000000e+00,-9.883129992259242247e-11,0.000000000000000000e+00 +2.565982573744414452e+01,1.339900000000000091e+02,0.000000000000000000e+00,5.976124874544076704e+00,0.000000000000000000e+00,1.000000009970328785e+00,0.000000000000000000e+00,2.136415721668774859e-10,0.000000000000000000e+00 +2.566149906258542401e+01,1.340000000000000000e+02,0.000000000000000000e+00,5.977798199702039739e+00,0.000000000000000000e+00,1.000000009970686277e+00,0.000000000000000000e+00,-5.203164331131658900e-11,0.000000000000000000e+00 +2.566317191932396469e+01,1.340099999999999909e+02,0.000000000000000000e+00,5.979471056457258626e+00,0.000000000000000000e+00,1.000000009970599235e+00,0.000000000000000000e+00,-1.234769638204291655e-11,0.000000000000000000e+00 +2.566484430805293115e+01,1.340200000000000102e+02,0.000000000000000000e+00,5.981143445202899755e+00,0.000000000000000000e+00,1.000000009970578585e+00,0.000000000000000000e+00,-5.113110438166570956e-11,0.000000000000000000e+00 +2.566651622916494091e+01,1.340300000000000011e+02,0.000000000000000000e+00,5.982815366331580620e+00,0.000000000000000000e+00,1.000000009970493098e+00,0.000000000000000000e+00,8.289539695984573678e-11,0.000000000000000000e+00 +2.566818768305206433e+01,1.340399999999999920e+02,0.000000000000000000e+00,5.984486820235369819e+00,0.000000000000000000e+00,1.000000009970631654e+00,0.000000000000000000e+00,7.042761961894563663e-12,0.000000000000000000e+00 +2.566985867010582112e+01,1.340500000000000114e+02,0.000000000000000000e+00,5.986157807305788836e+00,0.000000000000000000e+00,1.000000009970643422e+00,0.000000000000000000e+00,-2.525468686150000721e-11,0.000000000000000000e+00 +2.567152919071718742e+01,1.340600000000000023e+02,0.000000000000000000e+00,5.987828327933812034e+00,0.000000000000000000e+00,1.000000009970601234e+00,0.000000000000000000e+00,-7.738068157031550041e-11,0.000000000000000000e+00 +2.567319924527659225e+01,1.340699999999999932e+02,0.000000000000000000e+00,5.989498382509868435e+00,0.000000000000000000e+00,1.000000009970472004e+00,0.000000000000000000e+00,1.073258192249118717e-10,0.000000000000000000e+00 +2.567486883417392107e+01,1.340800000000000125e+02,0.000000000000000000e+00,5.991167971423842609e+00,0.000000000000000000e+00,1.000000009970651194e+00,0.000000000000000000e+00,1.485952388709062458e-10,0.000000000000000000e+00 +2.567653795779851222e+01,1.340900000000000034e+02,0.000000000000000000e+00,5.992837095065076447e+00,0.000000000000000000e+00,1.000000009970899217e+00,0.000000000000000000e+00,-3.333346248610261625e-10,0.000000000000000000e+00 +2.567820661653916758e+01,1.340999999999999943e+02,0.000000000000000000e+00,5.994505753822369165e+00,0.000000000000000000e+00,1.000000009970342996e+00,0.000000000000000000e+00,1.964626348858593007e-10,0.000000000000000000e+00 +2.567987481078414191e+01,1.341100000000000136e+02,0.000000000000000000e+00,5.996173948083977301e+00,0.000000000000000000e+00,1.000000009970670733e+00,0.000000000000000000e+00,-2.343295812640766777e-10,0.000000000000000000e+00 +2.568154254092115707e+01,1.341200000000000045e+02,0.000000000000000000e+00,5.997841678237620044e+00,0.000000000000000000e+00,1.000000009970279935e+00,0.000000000000000000e+00,2.314648214602362414e-10,0.000000000000000000e+00 +2.568320980733738779e+01,1.341299999999999955e+02,0.000000000000000000e+00,5.999508944670474797e+00,0.000000000000000000e+00,1.000000009970665849e+00,0.000000000000000000e+00,-6.008035256069597444e-11,0.000000000000000000e+00 +2.568487661041947590e+01,1.341400000000000148e+02,0.000000000000000000e+00,6.001175747769183388e+00,0.000000000000000000e+00,1.000000009970565706e+00,0.000000000000000000e+00,-2.064086953200586590e-10,0.000000000000000000e+00 +2.568654295055352677e+01,1.341500000000000057e+02,0.000000000000000000e+00,6.002842087919848524e+00,0.000000000000000000e+00,1.000000009970221759e+00,0.000000000000000000e+00,3.774769117945499969e-10,0.000000000000000000e+00 +2.568820882812510575e+01,1.341599999999999966e+02,0.000000000000000000e+00,6.004507965508037337e+00,0.000000000000000000e+00,1.000000009970850590e+00,0.000000000000000000e+00,-2.823862892619382344e-10,0.000000000000000000e+00 +2.568987424351924531e+01,1.341700000000000159e+02,0.000000000000000000e+00,6.006173380918784055e+00,0.000000000000000000e+00,1.000000009970380299e+00,0.000000000000000000e+00,9.335468768341455879e-13,0.000000000000000000e+00 +2.569153919712044498e+01,1.341800000000000068e+02,0.000000000000000000e+00,6.007838334536585556e+00,0.000000000000000000e+00,1.000000009970381853e+00,0.000000000000000000e+00,2.154423064454699323e-10,0.000000000000000000e+00 +2.569320368931267140e+01,1.341899999999999977e+02,0.000000000000000000e+00,6.009502826745408477e+00,0.000000000000000000e+00,1.000000009970740456e+00,0.000000000000000000e+00,-3.326603558634633872e-10,0.000000000000000000e+00 +2.569486772047935830e+01,1.341999999999999886e+02,0.000000000000000000e+00,6.011166857928687435e+00,0.000000000000000000e+00,1.000000009970186898e+00,0.000000000000000000e+00,2.311782098625700004e-10,0.000000000000000000e+00 +2.569653129100341005e+01,1.342100000000000080e+02,0.000000000000000000e+00,6.012830428469324140e+00,0.000000000000000000e+00,1.000000009970571480e+00,0.000000000000000000e+00,-6.795743274980748980e-11,0.000000000000000000e+00 +2.569819440126719812e+01,1.342199999999999989e+02,0.000000000000000000e+00,6.014493538749693613e+00,0.000000000000000000e+00,1.000000009970458459e+00,0.000000000000000000e+00,4.674200445725401884e-12,0.000000000000000000e+00 +2.569985705165256817e+01,1.342299999999999898e+02,0.000000000000000000e+00,6.016156189151639744e+00,0.000000000000000000e+00,1.000000009970466230e+00,0.000000000000000000e+00,8.041847245608495439e-11,0.000000000000000000e+00 +2.570151924254083653e+01,1.342400000000000091e+02,0.000000000000000000e+00,6.017818380056479732e+00,0.000000000000000000e+00,1.000000009970599901e+00,0.000000000000000000e+00,-2.089854499766804253e-10,0.000000000000000000e+00 +2.570318097431279369e+01,1.342500000000000000e+02,0.000000000000000000e+00,6.019480111845004089e+00,0.000000000000000000e+00,1.000000009970252624e+00,0.000000000000000000e+00,5.466665710650812415e-11,0.000000000000000000e+00 +2.570484224734870438e+01,1.342599999999999909e+02,0.000000000000000000e+00,6.021141384897476634e+00,0.000000000000000000e+00,1.000000009970343440e+00,0.000000000000000000e+00,1.835648771090044927e-10,0.000000000000000000e+00 +2.570650306202830748e+01,1.342700000000000102e+02,0.000000000000000000e+00,6.022802199593638051e+00,0.000000000000000000e+00,1.000000009970648307e+00,0.000000000000000000e+00,-1.896334982159637379e-10,0.000000000000000000e+00 +2.570816341873081967e+01,1.342800000000000011e+02,0.000000000000000000e+00,6.024462556312704997e+00,0.000000000000000000e+00,1.000000009970333448e+00,0.000000000000000000e+00,-1.415285973877820507e-10,0.000000000000000000e+00 +2.570982331783493535e+01,1.342899999999999920e+02,0.000000000000000000e+00,6.026122455433370106e+00,0.000000000000000000e+00,1.000000009970098525e+00,0.000000000000000000e+00,2.855437068992563592e-10,0.000000000000000000e+00 +2.571148275971882669e+01,1.343000000000000114e+02,0.000000000000000000e+00,6.027781897333805539e+00,0.000000000000000000e+00,1.000000009970572368e+00,0.000000000000000000e+00,8.271537260800635614e-11,0.000000000000000000e+00 +2.571314174476014358e+01,1.343100000000000023e+02,0.000000000000000000e+00,6.029440882391663870e+00,0.000000000000000000e+00,1.000000009970709591e+00,0.000000000000000000e+00,-4.693849694185108463e-10,0.000000000000000000e+00 +2.571480027333602081e+01,1.343199999999999932e+02,0.000000000000000000e+00,6.031099410984076314e+00,0.000000000000000000e+00,1.000000009969931103e+00,0.000000000000000000e+00,5.276341958743659313e-10,0.000000000000000000e+00 +2.571645834582306733e+01,1.343300000000000125e+02,0.000000000000000000e+00,6.032757483487654504e+00,0.000000000000000000e+00,1.000000009970805959e+00,0.000000000000000000e+00,-5.189382810362446793e-10,0.000000000000000000e+00 +2.571811596259738053e+01,1.343400000000000034e+02,0.000000000000000000e+00,6.034415100278496702e+00,0.000000000000000000e+00,1.000000009969945758e+00,0.000000000000000000e+00,5.543204843994540480e-10,0.000000000000000000e+00 +2.571977312403454263e+01,1.343499999999999943e+02,0.000000000000000000e+00,6.036072261732178923e+00,0.000000000000000000e+00,1.000000009970864356e+00,0.000000000000000000e+00,-4.934900947372674074e-10,0.000000000000000000e+00 +2.572142983050961362e+01,1.343600000000000136e+02,0.000000000000000000e+00,6.037728968223767367e+00,0.000000000000000000e+00,1.000000009970046788e+00,0.000000000000000000e+00,1.828639975588956729e-10,0.000000000000000000e+00 +2.572308608239714189e+01,1.343700000000000045e+02,0.000000000000000000e+00,6.039385220127807763e+00,0.000000000000000000e+00,1.000000009970349657e+00,0.000000000000000000e+00,-4.076679231787791105e-11,0.000000000000000000e+00 +2.572474188007116069e+01,1.343799999999999955e+02,0.000000000000000000e+00,6.041041017818336911e+00,0.000000000000000000e+00,1.000000009970282155e+00,0.000000000000000000e+00,9.617698659205026095e-11,0.000000000000000000e+00 +2.572639722390519523e+01,1.343900000000000148e+02,0.000000000000000000e+00,6.042696361668876470e+00,0.000000000000000000e+00,1.000000009970441361e+00,0.000000000000000000e+00,-8.855537633637352153e-11,0.000000000000000000e+00 +2.572805211427225558e+01,1.344000000000000057e+02,0.000000000000000000e+00,6.044351252052437395e+00,0.000000000000000000e+00,1.000000009970294812e+00,0.000000000000000000e+00,2.053436846258855699e-11,0.000000000000000000e+00 +2.572970655154484376e+01,1.344099999999999966e+02,0.000000000000000000e+00,6.046005689341519052e+00,0.000000000000000000e+00,1.000000009970328785e+00,0.000000000000000000e+00,6.752689211661575554e-11,0.000000000000000000e+00 +2.573136053609494667e+01,1.344200000000000159e+02,0.000000000000000000e+00,6.047659673908111877e+00,0.000000000000000000e+00,1.000000009970440473e+00,0.000000000000000000e+00,2.054560810611374749e-11,0.000000000000000000e+00 +2.573301406829404669e+01,1.344300000000000068e+02,0.000000000000000000e+00,6.049313206123697384e+00,0.000000000000000000e+00,1.000000009970474446e+00,0.000000000000000000e+00,-1.505746661593013588e-10,0.000000000000000000e+00 +2.573466714851311465e+01,1.344399999999999977e+02,0.000000000000000000e+00,6.050966286359249047e+00,0.000000000000000000e+00,1.000000009970225534e+00,0.000000000000000000e+00,-1.504814548685642060e-10,0.000000000000000000e+00 +2.573631977712262042e+01,1.344499999999999886e+02,0.000000000000000000e+00,6.052618914985233189e+00,0.000000000000000000e+00,1.000000009969976844e+00,0.000000000000000000e+00,3.175757100872834993e-10,0.000000000000000000e+00 +2.573797195449252584e+01,1.344600000000000080e+02,0.000000000000000000e+00,6.054271092371610763e+00,0.000000000000000000e+00,1.000000009970501536e+00,0.000000000000000000e+00,-7.514738921434128152e-11,0.000000000000000000e+00 +2.573962368099228470e+01,1.344699999999999989e+02,0.000000000000000000e+00,6.055922818887839121e+00,0.000000000000000000e+00,1.000000009970377413e+00,0.000000000000000000e+00,-5.472867908390078861e-11,0.000000000000000000e+00 +2.574127495699084989e+01,1.344799999999999898e+02,0.000000000000000000e+00,6.057574094902869355e+00,0.000000000000000000e+00,1.000000009970287040e+00,0.000000000000000000e+00,2.797707425150168429e-11,0.000000000000000000e+00 +2.574292578285667332e+01,1.344900000000000091e+02,0.000000000000000000e+00,6.059224920785150736e+00,0.000000000000000000e+00,1.000000009970333226e+00,0.000000000000000000e+00,-1.786715374497189872e-10,0.000000000000000000e+00 +2.574457615895769891e+01,1.345000000000000000e+02,0.000000000000000000e+00,6.060875296902630716e+00,0.000000000000000000e+00,1.000000009970038350e+00,0.000000000000000000e+00,2.793848955822100506e-10,0.000000000000000000e+00 +2.574622608566137316e+01,1.345099999999999909e+02,0.000000000000000000e+00,6.062525223622754922e+00,0.000000000000000000e+00,1.000000009970499315e+00,0.000000000000000000e+00,-2.524033158988784661e-10,0.000000000000000000e+00 +2.574787556333464167e+01,1.345200000000000102e+02,0.000000000000000000e+00,6.064174701312470717e+00,0.000000000000000000e+00,1.000000009970082981e+00,0.000000000000000000e+00,1.613127696347658123e-10,0.000000000000000000e+00 +2.574952459234395263e+01,1.345300000000000011e+02,0.000000000000000000e+00,6.065823730338223641e+00,0.000000000000000000e+00,1.000000009970348991e+00,0.000000000000000000e+00,-1.342842783446587107e-10,0.000000000000000000e+00 +2.575117317305525688e+01,1.345399999999999920e+02,0.000000000000000000e+00,6.067472311065963630e+00,0.000000000000000000e+00,1.000000009970127612e+00,0.000000000000000000e+00,1.469849195994791629e-10,0.000000000000000000e+00 +2.575282130583400431e+01,1.345500000000000114e+02,0.000000000000000000e+00,6.069120443861141467e+00,0.000000000000000000e+00,1.000000009970369863e+00,0.000000000000000000e+00,-3.228886621074188367e-10,0.000000000000000000e+00 +2.575446899104514742e+01,1.345600000000000023e+02,0.000000000000000000e+00,6.070768129088713216e+00,0.000000000000000000e+00,1.000000009969837844e+00,0.000000000000000000e+00,3.995416605255585073e-10,0.000000000000000000e+00 +2.575611622905314846e+01,1.345699999999999932e+02,0.000000000000000000e+00,6.072415367113137563e+00,0.000000000000000000e+00,1.000000009970495984e+00,0.000000000000000000e+00,-3.225246194146131139e-10,0.000000000000000000e+00 +2.575776302022197228e+01,1.345800000000000125e+02,0.000000000000000000e+00,6.074062158298382030e+00,0.000000000000000000e+00,1.000000009969964854e+00,0.000000000000000000e+00,1.122128993214900063e-10,0.000000000000000000e+00 +2.575940936491509348e+01,1.345900000000000034e+02,0.000000000000000000e+00,6.075708503007916761e+00,0.000000000000000000e+00,1.000000009970149595e+00,0.000000000000000000e+00,4.991589688503171487e-11,0.000000000000000000e+00 +2.576105526349548924e+01,1.345999999999999943e+02,0.000000000000000000e+00,6.077354401604722511e+00,0.000000000000000000e+00,1.000000009970231751e+00,0.000000000000000000e+00,1.295466006809971799e-10,0.000000000000000000e+00 +2.576270071632564651e+01,1.346100000000000136e+02,0.000000000000000000e+00,6.078999854451287099e+00,0.000000000000000000e+00,1.000000009970444914e+00,0.000000000000000000e+00,-3.205796662424777027e-10,0.000000000000000000e+00 +2.576434572376756549e+01,1.346200000000000045e+02,0.000000000000000000e+00,6.080644861909608068e+00,0.000000000000000000e+00,1.000000009969917558e+00,0.000000000000000000e+00,3.266071839860127895e-10,0.000000000000000000e+00 +2.576599028618275256e+01,1.346299999999999955e+02,0.000000000000000000e+00,6.082289424341191797e+00,0.000000000000000000e+00,1.000000009970454684e+00,0.000000000000000000e+00,-2.406661482140749440e-10,0.000000000000000000e+00 +2.576763440393222737e+01,1.346400000000000148e+02,0.000000000000000000e+00,6.083933542107058834e+00,0.000000000000000000e+00,1.000000009970059001e+00,0.000000000000000000e+00,-6.484342174787079043e-11,0.000000000000000000e+00 +2.576927807737651932e+01,1.346500000000000057e+02,0.000000000000000000e+00,6.085577215567738563e+00,0.000000000000000000e+00,1.000000009969952419e+00,0.000000000000000000e+00,1.857995684285826998e-10,0.000000000000000000e+00 +2.577092130687567462e+01,1.346599999999999966e+02,0.000000000000000000e+00,6.087220445083275422e+00,0.000000000000000000e+00,1.000000009970257731e+00,0.000000000000000000e+00,1.711169224866232650e-10,0.000000000000000000e+00 +2.577256409278924920e+01,1.346700000000000159e+02,0.000000000000000000e+00,6.088863231013228017e+00,0.000000000000000000e+00,1.000000009970538839e+00,0.000000000000000000e+00,-4.491341443963113745e-10,0.000000000000000000e+00 +2.577420643547631585e+01,1.346800000000000068e+02,0.000000000000000000e+00,6.090505573716669119e+00,0.000000000000000000e+00,1.000000009969801207e+00,0.000000000000000000e+00,2.917048940733047775e-10,0.000000000000000000e+00 +2.577584833529546415e+01,1.346899999999999977e+02,0.000000000000000000e+00,6.092147473552185666e+00,0.000000000000000000e+00,1.000000009970280157e+00,0.000000000000000000e+00,-2.501194957504447059e-10,0.000000000000000000e+00 +2.577748979260479700e+01,1.346999999999999886e+02,0.000000000000000000e+00,6.093788930877884980e+00,0.000000000000000000e+00,1.000000009969869597e+00,0.000000000000000000e+00,2.244781213428839198e-10,0.000000000000000000e+00 +2.577913080776194121e+01,1.347100000000000080e+02,0.000000000000000000e+00,6.095429946051388548e+00,0.000000000000000000e+00,1.000000009970237969e+00,0.000000000000000000e+00,5.995815990590991447e-11,0.000000000000000000e+00 +2.578077138112403333e+01,1.347199999999999989e+02,0.000000000000000000e+00,6.097070519429839131e+00,0.000000000000000000e+00,1.000000009970336334e+00,0.000000000000000000e+00,-9.043528386108184504e-11,0.000000000000000000e+00 +2.578241151304773737e+01,1.347299999999999898e+02,0.000000000000000000e+00,6.098710651369897207e+00,0.000000000000000000e+00,1.000000009970188009e+00,0.000000000000000000e+00,-2.325137013681669407e-10,0.000000000000000000e+00 +2.578405120388923422e+01,1.347400000000000091e+02,0.000000000000000000e+00,6.100350342227743639e+00,0.000000000000000000e+00,1.000000009969806758e+00,0.000000000000000000e+00,2.909573145771824717e-10,0.000000000000000000e+00 +2.578569045400422866e+01,1.347500000000000000e+02,0.000000000000000000e+00,6.101989592359080561e+00,0.000000000000000000e+00,1.000000009970283710e+00,0.000000000000000000e+00,-1.765452770384508262e-10,0.000000000000000000e+00 +2.578732926374794232e+01,1.347599999999999909e+02,0.000000000000000000e+00,6.103628402119134044e+00,0.000000000000000000e+00,1.000000009969994386e+00,0.000000000000000000e+00,1.463699977730362834e-11,0.000000000000000000e+00 +2.578896763347512433e+01,1.347700000000000102e+02,0.000000000000000000e+00,6.105266771862650543e+00,0.000000000000000000e+00,1.000000009970018366e+00,0.000000000000000000e+00,-1.295993320194076209e-10,0.000000000000000000e+00 +2.579060556354004419e+01,1.347800000000000011e+02,0.000000000000000000e+00,6.106904701943902225e+00,0.000000000000000000e+00,1.000000009969806092e+00,0.000000000000000000e+00,3.826646792523134221e-10,0.000000000000000000e+00 +2.579224305429650244e+01,1.347899999999999920e+02,0.000000000000000000e+00,6.108542192716685193e+00,0.000000000000000000e+00,1.000000009970432702e+00,0.000000000000000000e+00,-4.366151289038057832e-10,0.000000000000000000e+00 +2.579388010609781645e+01,1.348000000000000114e+02,0.000000000000000000e+00,6.110179244534323040e+00,0.000000000000000000e+00,1.000000009969717940e+00,0.000000000000000000e+00,3.948091098847612503e-10,0.000000000000000000e+00 +2.579551671929683820e+01,1.348100000000000023e+02,0.000000000000000000e+00,6.111815857749662406e+00,0.000000000000000000e+00,1.000000009970364090e+00,0.000000000000000000e+00,-4.367134083302562407e-10,0.000000000000000000e+00 +2.579715289424594360e+01,1.348199999999999932e+02,0.000000000000000000e+00,6.113452032715081863e+00,0.000000000000000000e+00,1.000000009969649550e+00,0.000000000000000000e+00,3.872830644921194124e-10,0.000000000000000000e+00 +2.579878863129703959e+01,1.348300000000000125e+02,0.000000000000000000e+00,6.115087769782483917e+00,0.000000000000000000e+00,1.000000009970283044e+00,0.000000000000000000e+00,-1.170442777709834845e-10,0.000000000000000000e+00 +2.580042393080155705e+01,1.348400000000000034e+02,0.000000000000000000e+00,6.116723069303304783e+00,0.000000000000000000e+00,1.000000009970091641e+00,0.000000000000000000e+00,4.549920947153578179e-11,0.000000000000000000e+00 +2.580205879311046147e+01,1.348499999999999943e+02,0.000000000000000000e+00,6.118357931628507274e+00,0.000000000000000000e+00,1.000000009970166026e+00,0.000000000000000000e+00,-1.172427243066965177e-10,0.000000000000000000e+00 +2.580369321857424580e+01,1.348600000000000136e+02,0.000000000000000000e+00,6.119992357108587022e+00,0.000000000000000000e+00,1.000000009969974402e+00,0.000000000000000000e+00,6.454828604122340402e-11,0.000000000000000000e+00 +2.580532720754293763e+01,1.348700000000000045e+02,0.000000000000000000e+00,6.121626346093570703e+00,0.000000000000000000e+00,1.000000009970079873e+00,0.000000000000000000e+00,-6.850741481725729943e-11,0.000000000000000000e+00 +2.580696076036609909e+01,1.348799999999999955e+02,0.000000000000000000e+00,6.123259898933018697e+00,0.000000000000000000e+00,1.000000009969967962e+00,0.000000000000000000e+00,-1.770247146295653745e-10,0.000000000000000000e+00 +2.580859387739282340e+01,1.348900000000000148e+02,0.000000000000000000e+00,6.124893015976024202e+00,0.000000000000000000e+00,1.000000009969678860e+00,0.000000000000000000e+00,7.915196798653592108e-11,0.000000000000000000e+00 +2.581022655897173834e+01,1.349000000000000057e+02,0.000000000000000000e+00,6.126525697571215012e+00,0.000000000000000000e+00,1.000000009969808090e+00,0.000000000000000000e+00,3.760040507413817097e-10,0.000000000000000000e+00 +2.581185880545100630e+01,1.349099999999999966e+02,0.000000000000000000e+00,6.128157944066755292e+00,0.000000000000000000e+00,1.000000009970421821e+00,0.000000000000000000e+00,-2.784042142058980296e-10,0.000000000000000000e+00 +2.581349061717832782e+01,1.349200000000000159e+02,0.000000000000000000e+00,6.129789755810345575e+00,0.000000000000000000e+00,1.000000009969967518e+00,0.000000000000000000e+00,-2.075657285518678690e-10,0.000000000000000000e+00 +2.581512199450093803e+01,1.349300000000000068e+02,0.000000000000000000e+00,6.131421133149220992e+00,0.000000000000000000e+00,1.000000009969628900e+00,0.000000000000000000e+00,2.668440006952648615e-10,0.000000000000000000e+00 +2.581675293776561375e+01,1.349399999999999977e+02,0.000000000000000000e+00,6.133052076430156596e+00,0.000000000000000000e+00,1.000000009970064108e+00,0.000000000000000000e+00,-1.794867063139570384e-10,0.000000000000000000e+00 +2.581838344731866997e+01,1.349499999999999886e+02,0.000000000000000000e+00,6.134682585999467364e+00,0.000000000000000000e+00,1.000000009969771453e+00,0.000000000000000000e+00,1.347189266266085087e-10,0.000000000000000000e+00 +2.582001352350595624e+01,1.349600000000000080e+02,0.000000000000000000e+00,6.136312662203005530e+00,0.000000000000000000e+00,1.000000009969991055e+00,0.000000000000000000e+00,-1.136354290726628142e-10,0.000000000000000000e+00 +2.582164316667286741e+01,1.349699999999999989e+02,0.000000000000000000e+00,6.137942305386165920e+00,0.000000000000000000e+00,1.000000009969805870e+00,0.000000000000000000e+00,9.185925606459201717e-11,0.000000000000000000e+00 +2.582327237716434354e+01,1.349799999999999898e+02,0.000000000000000000e+00,6.139571515893883280e+00,0.000000000000000000e+00,1.000000009969955528e+00,0.000000000000000000e+00,9.665504407438437247e-11,0.000000000000000000e+00 +2.582490115532485575e+01,1.349900000000000091e+02,0.000000000000000000e+00,6.141200294070635834e+00,0.000000000000000000e+00,1.000000009970112957e+00,0.000000000000000000e+00,-8.413537825195010324e-11,0.000000000000000000e+00 +2.582652950149843107e+01,1.350000000000000000e+02,0.000000000000000000e+00,6.142828640260444395e+00,0.000000000000000000e+00,1.000000009969975956e+00,0.000000000000000000e+00,-1.001162757574817416e-10,0.000000000000000000e+00 +2.582815741602863113e+01,1.350099999999999909e+02,0.000000000000000000e+00,6.144456554806873250e+00,0.000000000000000000e+00,1.000000009969812975e+00,0.000000000000000000e+00,6.589778758163067320e-11,0.000000000000000000e+00 +2.582978489925856280e+01,1.350200000000000102e+02,0.000000000000000000e+00,6.146084038053031939e+00,0.000000000000000000e+00,1.000000009969920223e+00,0.000000000000000000e+00,9.648462950603273113e-11,0.000000000000000000e+00 +2.583141195153088532e+01,1.350300000000000011e+02,0.000000000000000000e+00,6.147711090341576146e+00,0.000000000000000000e+00,1.000000009970077208e+00,0.000000000000000000e+00,-3.266603130033772291e-10,0.000000000000000000e+00 +2.583303857318779961e+01,1.350399999999999920e+02,0.000000000000000000e+00,6.149337712014707691e+00,0.000000000000000000e+00,1.000000009969545856e+00,0.000000000000000000e+00,1.589357333916545442e-10,0.000000000000000000e+00 +2.583466476457105543e+01,1.350500000000000114e+02,0.000000000000000000e+00,6.150963903414174538e+00,0.000000000000000000e+00,1.000000009969804315e+00,0.000000000000000000e+00,2.302719157833154546e-10,0.000000000000000000e+00 +2.583629052602194776e+01,1.350600000000000023e+02,0.000000000000000000e+00,6.152589664881275233e+00,0.000000000000000000e+00,1.000000009970178683e+00,0.000000000000000000e+00,-9.358122988620096396e-11,0.000000000000000000e+00 +2.583791585788132394e+01,1.350699999999999932e+02,0.000000000000000000e+00,6.154214996756856237e+00,0.000000000000000000e+00,1.000000009970026582e+00,0.000000000000000000e+00,-1.182031355505470622e-10,0.000000000000000000e+00 +2.583954076048958015e+01,1.350800000000000125e+02,0.000000000000000000e+00,6.155839899381312819e+00,0.000000000000000000e+00,1.000000009969834514e+00,0.000000000000000000e+00,-1.582836662513367142e-10,0.000000000000000000e+00 +2.584116523418666489e+01,1.350900000000000034e+02,0.000000000000000000e+00,6.157464373094591714e+00,0.000000000000000000e+00,1.000000009969577386e+00,0.000000000000000000e+00,1.461570734404142479e-10,0.000000000000000000e+00 +2.584278927931207193e+01,1.350999999999999943e+02,0.000000000000000000e+00,6.159088418236191131e+00,0.000000000000000000e+00,1.000000009969814752e+00,0.000000000000000000e+00,1.455118265215228788e-10,0.000000000000000000e+00 +2.584441289620485449e+01,1.351100000000000136e+02,0.000000000000000000e+00,6.160712035145162524e+00,0.000000000000000000e+00,1.000000009970051007e+00,0.000000000000000000e+00,-1.367952869900693174e-10,0.000000000000000000e+00 +2.584603608520361817e+01,1.351200000000000045e+02,0.000000000000000000e+00,6.162335224160109703e+00,0.000000000000000000e+00,1.000000009969828962e+00,0.000000000000000000e+00,-1.505144619290659493e-12,0.000000000000000000e+00 +2.584765884664652091e+01,1.351299999999999955e+02,0.000000000000000000e+00,6.163957985619189728e+00,0.000000000000000000e+00,1.000000009969826520e+00,0.000000000000000000e+00,-9.676522462937524682e-11,0.000000000000000000e+00 +2.584928118087127302e+01,1.351400000000000148e+02,0.000000000000000000e+00,6.165580319860115566e+00,0.000000000000000000e+00,1.000000009969669534e+00,0.000000000000000000e+00,-5.873155200442047060e-11,0.000000000000000000e+00 +2.585090308821514427e+01,1.351500000000000057e+02,0.000000000000000000e+00,6.167202227220155208e+00,0.000000000000000000e+00,1.000000009969574277e+00,0.000000000000000000e+00,1.400890043622697443e-10,0.000000000000000000e+00 +2.585252456901495677e+01,1.351599999999999966e+02,0.000000000000000000e+00,6.168823708036133446e+00,0.000000000000000000e+00,1.000000009969801429e+00,0.000000000000000000e+00,1.901218584067033410e-10,0.000000000000000000e+00 +2.585414562360709567e+01,1.351700000000000159e+02,0.000000000000000000e+00,6.170444762644432757e+00,0.000000000000000000e+00,1.000000009970109627e+00,0.000000000000000000e+00,-2.185331781405313231e-10,0.000000000000000000e+00 +2.585576625232749848e+01,1.351800000000000068e+02,0.000000000000000000e+00,6.172065391380993304e+00,0.000000000000000000e+00,1.000000009969755466e+00,0.000000000000000000e+00,-4.152535678843973659e-11,0.000000000000000000e+00 +2.585738645551166570e+01,1.351899999999999977e+02,0.000000000000000000e+00,6.173685594581312941e+00,0.000000000000000000e+00,1.000000009969688186e+00,0.000000000000000000e+00,7.525876347503104340e-11,0.000000000000000000e+00 +2.585900623349465377e+01,1.351999999999999886e+02,0.000000000000000000e+00,6.175305372580450758e+00,0.000000000000000000e+00,1.000000009969810089e+00,0.000000000000000000e+00,-1.759240929160181384e-10,0.000000000000000000e+00 +2.586062558661108568e+01,1.352100000000000080e+02,0.000000000000000000e+00,6.176924725713026199e+00,0.000000000000000000e+00,1.000000009969525205e+00,0.000000000000000000e+00,2.525028723895968057e-10,0.000000000000000000e+00 +2.586224451519514034e+01,1.352199999999999989e+02,0.000000000000000000e+00,6.178543654313219058e+00,0.000000000000000000e+00,1.000000009969933989e+00,0.000000000000000000e+00,-3.004487903567542803e-10,0.000000000000000000e+00 +2.586386301958055967e+01,1.352299999999999898e+02,0.000000000000000000e+00,6.180162158714773035e+00,0.000000000000000000e+00,1.000000009969447712e+00,0.000000000000000000e+00,2.317766842023616446e-10,0.000000000000000000e+00 +2.586548110010064860e+01,1.352400000000000091e+02,0.000000000000000000e+00,6.181780239250992182e+00,0.000000000000000000e+00,1.000000009969822745e+00,0.000000000000000000e+00,-1.512639307955552844e-10,0.000000000000000000e+00 +2.586709875708827511e+01,1.352500000000000000e+02,0.000000000000000000e+00,6.183397896254747117e+00,0.000000000000000000e+00,1.000000009969578052e+00,0.000000000000000000e+00,2.818748763513622087e-10,0.000000000000000000e+00 +2.586871599087587370e+01,1.352599999999999909e+02,0.000000000000000000e+00,6.185015130058470589e+00,0.000000000000000000e+00,1.000000009970033910e+00,0.000000000000000000e+00,-1.312921874404770581e-10,0.000000000000000000e+00 +2.587033280179544548e+01,1.352700000000000102e+02,0.000000000000000000e+00,6.186631940994162804e+00,0.000000000000000000e+00,1.000000009969821635e+00,0.000000000000000000e+00,-3.355969242912756952e-10,0.000000000000000000e+00 +2.587194919017855455e+01,1.352800000000000011e+02,0.000000000000000000e+00,6.188248329393387870e+00,0.000000000000000000e+00,1.000000009969279180e+00,0.000000000000000000e+00,3.863876841204529329e-10,0.000000000000000000e+00 +2.587356515635633514e+01,1.352899999999999920e+02,0.000000000000000000e+00,6.189864295587277354e+00,0.000000000000000000e+00,1.000000009969903569e+00,0.000000000000000000e+00,3.188668255163503098e-11,0.000000000000000000e+00 +2.587518070065948450e+01,1.353000000000000114e+02,0.000000000000000000e+00,6.191479839906532945e+00,0.000000000000000000e+00,1.000000009969955084e+00,0.000000000000000000e+00,-3.406716474094382205e-10,0.000000000000000000e+00 +2.587679582341827000e+01,1.353100000000000023e+02,0.000000000000000000e+00,6.193094962681422011e+00,0.000000000000000000e+00,1.000000009969404857e+00,0.000000000000000000e+00,3.296218548231559578e-10,0.000000000000000000e+00 +2.587841052496253269e+01,1.353199999999999932e+02,0.000000000000000000e+00,6.194709664241781155e+00,0.000000000000000000e+00,1.000000009969937098e+00,0.000000000000000000e+00,-3.013724575307850797e-10,0.000000000000000000e+00 +2.588002480562167662e+01,1.353300000000000125e+02,0.000000000000000000e+00,6.196323944917019766e+00,0.000000000000000000e+00,1.000000009969450598e+00,0.000000000000000000e+00,1.919325121759572451e-10,0.000000000000000000e+00 +2.588163866572468308e+01,1.353400000000000034e+02,0.000000000000000000e+00,6.197937805036114689e+00,0.000000000000000000e+00,1.000000009969760351e+00,0.000000000000000000e+00,-1.944596954243322852e-10,0.000000000000000000e+00 +2.588325210560009992e+01,1.353499999999999943e+02,0.000000000000000000e+00,6.199551244927617333e+00,0.000000000000000000e+00,1.000000009969446602e+00,0.000000000000000000e+00,2.871539427777627224e-10,0.000000000000000000e+00 +2.588486512557605224e+01,1.353600000000000136e+02,0.000000000000000000e+00,6.201164264919649227e+00,0.000000000000000000e+00,1.000000009969909787e+00,0.000000000000000000e+00,-3.687432115529980890e-10,0.000000000000000000e+00 +2.588647772598023167e+01,1.353700000000000045e+02,0.000000000000000000e+00,6.202776865339907353e+00,0.000000000000000000e+00,1.000000009969315151e+00,0.000000000000000000e+00,2.721531241680987189e-10,0.000000000000000000e+00 +2.588808990713991065e+01,1.353799999999999955e+02,0.000000000000000000e+00,6.204389046515659700e+00,0.000000000000000000e+00,1.000000009969753911e+00,0.000000000000000000e+00,-1.376273463520126552e-10,0.000000000000000000e+00 +2.588970166938193529e+01,1.353900000000000148e+02,0.000000000000000000e+00,6.206000808773752375e+00,0.000000000000000000e+00,1.000000009969532089e+00,0.000000000000000000e+00,1.558528176453658238e-10,0.000000000000000000e+00 +2.589131301303272181e+01,1.354000000000000057e+02,0.000000000000000000e+00,6.207612152440604270e+00,0.000000000000000000e+00,1.000000009969783221e+00,0.000000000000000000e+00,-1.695391149137291493e-10,0.000000000000000000e+00 +2.589292393841827078e+01,1.354099999999999966e+02,0.000000000000000000e+00,6.209223077842212390e+00,0.000000000000000000e+00,1.000000009969510106e+00,0.000000000000000000e+00,-4.149960700484691468e-11,0.000000000000000000e+00 +2.589453444586415287e+01,1.354200000000000159e+02,0.000000000000000000e+00,6.210833585304149196e+00,0.000000000000000000e+00,1.000000009969443271e+00,0.000000000000000000e+00,2.457524283852484461e-10,0.000000000000000000e+00 +2.589614453569551955e+01,1.354300000000000068e+02,0.000000000000000000e+00,6.212443675151566147e+00,0.000000000000000000e+00,1.000000009969838954e+00,0.000000000000000000e+00,-2.884408206669669171e-10,0.000000000000000000e+00 +2.589775420823709950e+01,1.354399999999999977e+02,0.000000000000000000e+00,6.214053347709193709e+00,0.000000000000000000e+00,1.000000009969374659e+00,0.000000000000000000e+00,1.179726452591758510e-10,0.000000000000000000e+00 +2.589936346381320220e+01,1.354499999999999886e+02,0.000000000000000000e+00,6.215662603301339573e+00,0.000000000000000000e+00,1.000000009969564507e+00,0.000000000000000000e+00,1.433980366634133730e-10,0.000000000000000000e+00 +2.590097230274771789e+01,1.354600000000000080e+02,0.000000000000000000e+00,6.217271442251893987e+00,0.000000000000000000e+00,1.000000009969795212e+00,0.000000000000000000e+00,-1.629003665705671554e-10,0.000000000000000000e+00 +2.590258072536411404e+01,1.354699999999999989e+02,0.000000000000000000e+00,6.218879864884327091e+00,0.000000000000000000e+00,1.000000009969533199e+00,0.000000000000000000e+00,-6.407230873209552189e-11,0.000000000000000000e+00 +2.590418873198544603e+01,1.354799999999999898e+02,0.000000000000000000e+00,6.220487871521689804e+00,0.000000000000000000e+00,1.000000009969430170e+00,0.000000000000000000e+00,1.486198930535329151e-10,0.000000000000000000e+00 +2.590579632293434642e+01,1.354900000000000091e+02,0.000000000000000000e+00,6.222095462486616491e+00,0.000000000000000000e+00,1.000000009969669090e+00,0.000000000000000000e+00,-1.604017548106231720e-10,0.000000000000000000e+00 +2.590740349853303215e+01,1.355000000000000000e+02,0.000000000000000000e+00,6.223702638101324958e+00,0.000000000000000000e+00,1.000000009969411296e+00,0.000000000000000000e+00,9.300453463905603294e-11,0.000000000000000000e+00 +2.590901025910330446e+01,1.355099999999999909e+02,0.000000000000000000e+00,6.225309398687615570e+00,0.000000000000000000e+00,1.000000009969560733e+00,0.000000000000000000e+00,-6.980596648136762470e-11,0.000000000000000000e+00 +2.591061660496654895e+01,1.355200000000000102e+02,0.000000000000000000e+00,6.226915744566874800e+00,0.000000000000000000e+00,1.000000009969448600e+00,0.000000000000000000e+00,9.415867246009938626e-11,0.000000000000000000e+00 +2.591222253644373907e+01,1.355300000000000011e+02,0.000000000000000000e+00,6.228521676060073453e+00,0.000000000000000000e+00,1.000000009969599812e+00,0.000000000000000000e+00,-4.951174492683355290e-11,0.000000000000000000e+00 +2.591382805385542909e+01,1.355399999999999920e+02,0.000000000000000000e+00,6.230127193487769333e+00,0.000000000000000000e+00,1.000000009969520320e+00,0.000000000000000000e+00,-1.005707177462868611e-10,0.000000000000000000e+00 +2.591543315752176468e+01,1.355500000000000114e+02,0.000000000000000000e+00,6.231732297170106349e+00,0.000000000000000000e+00,1.000000009969358894e+00,0.000000000000000000e+00,3.424713276411142482e-10,0.000000000000000000e+00 +2.591703784776247588e+01,1.355600000000000023e+02,0.000000000000000000e+00,6.233336987426816300e+00,0.000000000000000000e+00,1.000000009969908454e+00,0.000000000000000000e+00,-3.885109328406926397e-10,0.000000000000000000e+00 +2.591864212489688413e+01,1.355699999999999932e+02,0.000000000000000000e+00,6.234941264577220643e+00,0.000000000000000000e+00,1.000000009969285175e+00,0.000000000000000000e+00,1.794227850491676005e-10,0.000000000000000000e+00 +2.592024598924390233e+01,1.355800000000000125e+02,0.000000000000000000e+00,6.236545128940226945e+00,0.000000000000000000e+00,1.000000009969572945e+00,0.000000000000000000e+00,3.420434262154072819e-11,0.000000000000000000e+00 +2.592184944112202416e+01,1.355900000000000034e+02,0.000000000000000000e+00,6.238148580834335988e+00,0.000000000000000000e+00,1.000000009969627790e+00,0.000000000000000000e+00,-7.535200969796826061e-11,0.000000000000000000e+00 +2.592345248084934539e+01,1.355999999999999943e+02,0.000000000000000000e+00,6.239751620577637325e+00,0.000000000000000000e+00,1.000000009969506998e+00,0.000000000000000000e+00,-8.894930437565935701e-11,0.000000000000000000e+00 +2.592505510874354258e+01,1.356100000000000136e+02,0.000000000000000000e+00,6.241354248487811951e+00,0.000000000000000000e+00,1.000000009969364445e+00,0.000000000000000000e+00,5.363274478231224295e-11,0.000000000000000000e+00 +2.592665732512189081e+01,1.356200000000000045e+02,0.000000000000000000e+00,6.242956464882133183e+00,0.000000000000000000e+00,1.000000009969450376e+00,0.000000000000000000e+00,6.764728232827545533e-11,0.000000000000000000e+00 +2.592825913030125662e+01,1.356299999999999955e+02,0.000000000000000000e+00,6.244558270077467554e+00,0.000000000000000000e+00,1.000000009969558734e+00,0.000000000000000000e+00,-3.312516862411534156e-10,0.000000000000000000e+00 +2.592986052459809798e+01,1.356400000000000148e+02,0.000000000000000000e+00,6.246159664390274813e+00,0.000000000000000000e+00,1.000000009969028270e+00,0.000000000000000000e+00,3.045689616732137395e-10,0.000000000000000000e+00 +2.593146150832847141e+01,1.356500000000000057e+02,0.000000000000000000e+00,6.247760648136607919e+00,0.000000000000000000e+00,1.000000009969515880e+00,0.000000000000000000e+00,-4.009243664418969925e-11,0.000000000000000000e+00 +2.593306208180802486e+01,1.356599999999999966e+02,0.000000000000000000e+00,6.249361221632117491e+00,0.000000000000000000e+00,1.000000009969451709e+00,0.000000000000000000e+00,8.478461724730709887e-11,0.000000000000000000e+00 +2.593466224535200126e+01,1.356700000000000159e+02,0.000000000000000000e+00,6.250961385192047359e+00,0.000000000000000000e+00,1.000000009969587378e+00,0.000000000000000000e+00,-2.971691409769088993e-10,0.000000000000000000e+00 +2.593626199927524567e+01,1.356800000000000068e+02,0.000000000000000000e+00,6.252561139131239010e+00,0.000000000000000000e+00,1.000000009969111980e+00,0.000000000000000000e+00,2.680898960530347300e-10,0.000000000000000000e+00 +2.593786134389219100e+01,1.356899999999999977e+02,0.000000000000000000e+00,6.254160483764129808e+00,0.000000000000000000e+00,1.000000009969540749e+00,0.000000000000000000e+00,-2.369126624946283745e-10,0.000000000000000000e+00 +2.593946027951687938e+01,1.356999999999999886e+02,0.000000000000000000e+00,6.255759419404757438e+00,0.000000000000000000e+00,1.000000009969161940e+00,0.000000000000000000e+00,3.387911556613377256e-10,0.000000000000000000e+00 +2.594105880646294082e+01,1.357100000000000080e+02,0.000000000000000000e+00,6.257357946366755463e+00,0.000000000000000000e+00,1.000000009969703507e+00,0.000000000000000000e+00,-3.708342157538540084e-10,0.000000000000000000e+00 +2.594265692504361098e+01,1.357199999999999989e+02,0.000000000000000000e+00,6.258956064963359545e+00,0.000000000000000000e+00,1.000000009969110870e+00,0.000000000000000000e+00,1.364751613007535084e-10,0.000000000000000000e+00 +2.594425463557172407e+01,1.357299999999999898e+02,0.000000000000000000e+00,6.260553775507402108e+00,0.000000000000000000e+00,1.000000009969328918e+00,0.000000000000000000e+00,1.903077277691707719e-10,0.000000000000000000e+00 +2.594585193835971637e+01,1.357400000000000091e+02,0.000000000000000000e+00,6.262151078311319452e+00,0.000000000000000000e+00,1.000000009969632897e+00,0.000000000000000000e+00,-1.405772107648305032e-10,0.000000000000000000e+00 +2.594744883371962629e+01,1.357500000000000000e+02,0.000000000000000000e+00,6.263747973687148196e+00,0.000000000000000000e+00,1.000000009969408410e+00,0.000000000000000000e+00,-8.970862814879266946e-11,0.000000000000000000e+00 +2.594904532196308722e+01,1.357599999999999909e+02,0.000000000000000000e+00,6.265344461946526167e+00,0.000000000000000000e+00,1.000000009969265191e+00,0.000000000000000000e+00,6.524662038771380391e-11,0.000000000000000000e+00 +2.595064140340134529e+01,1.357700000000000102e+02,0.000000000000000000e+00,6.266940543400695063e+00,0.000000000000000000e+00,1.000000009969369330e+00,0.000000000000000000e+00,4.731237145963432113e-11,0.000000000000000000e+00 +2.595223707834524163e+01,1.357800000000000011e+02,0.000000000000000000e+00,6.268536218360500456e+00,0.000000000000000000e+00,1.000000009969444825e+00,0.000000000000000000e+00,-7.182176384010792730e-11,0.000000000000000000e+00 +2.595383234710523013e+01,1.357899999999999920e+02,0.000000000000000000e+00,6.270131487136391790e+00,0.000000000000000000e+00,1.000000009969330250e+00,0.000000000000000000e+00,-2.195576466238266993e-10,0.000000000000000000e+00 +2.595542720999136321e+01,1.358000000000000114e+02,0.000000000000000000e+00,6.271726350038423270e+00,0.000000000000000000e+00,1.000000009968980086e+00,0.000000000000000000e+00,3.758635495899321671e-10,0.000000000000000000e+00 +2.595702166731329896e+01,1.358100000000000023e+02,0.000000000000000000e+00,6.273320807376254749e+00,0.000000000000000000e+00,1.000000009969579384e+00,0.000000000000000000e+00,-3.068684359652770754e-10,0.000000000000000000e+00 +2.595861571938030821e+01,1.358199999999999932e+02,0.000000000000000000e+00,6.274914859459154393e+00,0.000000000000000000e+00,1.000000009969090220e+00,0.000000000000000000e+00,2.521892893541337338e-10,0.000000000000000000e+00 +2.596020936650126032e+01,1.358300000000000125e+02,0.000000000000000000e+00,6.276508506595994241e+00,0.000000000000000000e+00,1.000000009969492121e+00,0.000000000000000000e+00,-3.184524186033287459e-10,0.000000000000000000e+00 +2.596180260898464098e+01,1.358400000000000034e+02,0.000000000000000000e+00,6.278101749095257311e+00,0.000000000000000000e+00,1.000000009968984749e+00,0.000000000000000000e+00,5.058893581259368540e-10,0.000000000000000000e+00 +2.596339544713853797e+01,1.358499999999999943e+02,0.000000000000000000e+00,6.279694587265032268e+00,0.000000000000000000e+00,1.000000009969790549e+00,0.000000000000000000e+00,-3.478958897679408391e-10,0.000000000000000000e+00 +2.596498788127064827e+01,1.358600000000000136e+02,0.000000000000000000e+00,6.281287021413020533e+00,0.000000000000000000e+00,1.000000009969236547e+00,0.000000000000000000e+00,-2.231561432144609215e-12,0.000000000000000000e+00 +2.596657991168828516e+01,1.358700000000000045e+02,0.000000000000000000e+00,6.282879051846529173e+00,0.000000000000000000e+00,1.000000009969232995e+00,0.000000000000000000e+00,-1.296028759682027666e-10,0.000000000000000000e+00 +2.596817153869836758e+01,1.358799999999999955e+02,0.000000000000000000e+00,6.284470678872478899e+00,0.000000000000000000e+00,1.000000009969026715e+00,0.000000000000000000e+00,4.925877815957735603e-11,0.000000000000000000e+00 +2.596976276260742722e+01,1.358900000000000148e+02,0.000000000000000000e+00,6.286061902797400514e+00,0.000000000000000000e+00,1.000000009969105097e+00,0.000000000000000000e+00,2.633848430595152413e-10,0.000000000000000000e+00 +2.597135358372160496e+01,1.359000000000000057e+02,0.000000000000000000e+00,6.287652723927437570e+00,0.000000000000000000e+00,1.000000009969524095e+00,0.000000000000000000e+00,-1.094573262152367609e-10,0.000000000000000000e+00 +2.597294400234665801e+01,1.359099999999999966e+02,0.000000000000000000e+00,6.289243142568346379e+00,0.000000000000000000e+00,1.000000009969350012e+00,0.000000000000000000e+00,-2.872585090743637800e-10,0.000000000000000000e+00 +2.597453401878795631e+01,1.359200000000000159e+02,0.000000000000000000e+00,6.290833159025495114e+00,0.000000000000000000e+00,1.000000009968893266e+00,0.000000000000000000e+00,1.634309309230770360e-10,0.000000000000000000e+00 +2.597612363335048258e+01,1.359300000000000068e+02,0.000000000000000000e+00,6.292422773603866482e+00,0.000000000000000000e+00,1.000000009969153059e+00,0.000000000000000000e+00,2.710565145845111884e-10,0.000000000000000000e+00 +2.597771284633883226e+01,1.359399999999999977e+02,0.000000000000000000e+00,6.294011986608059495e+00,0.000000000000000000e+00,1.000000009969583825e+00,0.000000000000000000e+00,-2.349283911737420419e-10,0.000000000000000000e+00 +2.597930165805722069e+01,1.359499999999999886e+02,0.000000000000000000e+00,6.295600798342287696e+00,0.000000000000000000e+00,1.000000009969210568e+00,0.000000000000000000e+00,-2.158364072499917153e-10,0.000000000000000000e+00 +2.598089006880947593e+01,1.359600000000000080e+02,0.000000000000000000e+00,6.297189209110379160e+00,0.000000000000000000e+00,1.000000009968867731e+00,0.000000000000000000e+00,4.134645623952024655e-10,0.000000000000000000e+00 +2.598247807889904593e+01,1.359699999999999989e+02,0.000000000000000000e+00,6.298777219215780043e+00,0.000000000000000000e+00,1.000000009969524317e+00,0.000000000000000000e+00,-3.763658162216835026e-10,0.000000000000000000e+00 +2.598406568862899491e+01,1.359799999999999898e+02,0.000000000000000000e+00,6.300364828961555475e+00,0.000000000000000000e+00,1.000000009968926795e+00,0.000000000000000000e+00,3.186835480034493799e-10,0.000000000000000000e+00 +2.598565289830200342e+01,1.359900000000000091e+02,0.000000000000000000e+00,6.301952038650385113e+00,0.000000000000000000e+00,1.000000009969432613e+00,0.000000000000000000e+00,-2.350848277140081962e-10,0.000000000000000000e+00 +2.598723970822036833e+01,1.360000000000000000e+02,0.000000000000000000e+00,6.303538848584571141e+00,0.000000000000000000e+00,1.000000009969059578e+00,0.000000000000000000e+00,1.640409481704878059e-10,0.000000000000000000e+00 +2.598882611868601344e+01,1.360099999999999909e+02,0.000000000000000000e+00,6.305125259066032051e+00,0.000000000000000000e+00,1.000000009969319814e+00,0.000000000000000000e+00,-1.604421828036367226e-10,0.000000000000000000e+00 +2.599041213000047890e+01,1.360200000000000102e+02,0.000000000000000000e+00,6.306711270396308855e+00,0.000000000000000000e+00,1.000000009969065351e+00,0.000000000000000000e+00,-6.203644470982461078e-11,0.000000000000000000e+00 +2.599199774246492467e+01,1.360300000000000011e+02,0.000000000000000000e+00,6.308296882876561540e+00,0.000000000000000000e+00,1.000000009968966985e+00,0.000000000000000000e+00,1.949806818438520571e-10,0.000000000000000000e+00 +2.599358295638013416e+01,1.360399999999999920e+02,0.000000000000000000e+00,6.309882096807572616e+00,0.000000000000000000e+00,1.000000009969276071e+00,0.000000000000000000e+00,-7.005376386545827492e-12,0.000000000000000000e+00 +2.599516777204651063e+01,1.360500000000000114e+02,0.000000000000000000e+00,6.311466912489747116e+00,0.000000000000000000e+00,1.000000009969264969e+00,0.000000000000000000e+00,-2.259100609454883079e-10,0.000000000000000000e+00 +2.599675218976408075e+01,1.360600000000000023e+02,0.000000000000000000e+00,6.313051330223111712e+00,0.000000000000000000e+00,1.000000009968907033e+00,0.000000000000000000e+00,-1.654099206419184180e-11,0.000000000000000000e+00 +2.599833620983249460e+01,1.360699999999999932e+02,0.000000000000000000e+00,6.314635350307316486e+00,0.000000000000000000e+00,1.000000009968880832e+00,0.000000000000000000e+00,3.582443968149816371e-10,0.000000000000000000e+00 +2.599991983255102923e+01,1.360800000000000125e+02,0.000000000000000000e+00,6.316218973041636708e+00,0.000000000000000000e+00,1.000000009969448156e+00,0.000000000000000000e+00,-4.266351298019590086e-10,0.000000000000000000e+00 +2.600150305821858154e+01,1.360900000000000034e+02,0.000000000000000000e+00,6.317802198724972840e+00,0.000000000000000000e+00,1.000000009968772696e+00,0.000000000000000000e+00,2.003246799504423685e-10,0.000000000000000000e+00 +2.600308588713367897e+01,1.360999999999999943e+02,0.000000000000000000e+00,6.319385027655847864e+00,0.000000000000000000e+00,1.000000009969089776e+00,0.000000000000000000e+00,2.071101579308460950e-10,0.000000000000000000e+00 +2.600466831959446878e+01,1.361100000000000136e+02,0.000000000000000000e+00,6.320967460132414395e+00,0.000000000000000000e+00,1.000000009969417514e+00,0.000000000000000000e+00,-3.145325794963569330e-10,0.000000000000000000e+00 +2.600625035589873235e+01,1.361200000000000045e+02,0.000000000000000000e+00,6.322549496452450235e+00,0.000000000000000000e+00,1.000000009968919912e+00,0.000000000000000000e+00,1.493736837382499178e-10,0.000000000000000000e+00 +2.600783199634387444e+01,1.361299999999999955e+02,0.000000000000000000e+00,6.324131136913359263e+00,0.000000000000000000e+00,1.000000009969156167e+00,0.000000000000000000e+00,-8.074375398792592190e-11,0.000000000000000000e+00 +2.600941324122692677e+01,1.361400000000000148e+02,0.000000000000000000e+00,6.325712381812175877e+00,0.000000000000000000e+00,1.000000009969028492e+00,0.000000000000000000e+00,-1.998732006418252727e-10,0.000000000000000000e+00 +2.601099409084455161e+01,1.361500000000000057e+02,0.000000000000000000e+00,6.327293231445561439e+00,0.000000000000000000e+00,1.000000009968712522e+00,0.000000000000000000e+00,2.440383082951345243e-10,0.000000000000000000e+00 +2.601257454549304171e+01,1.361599999999999966e+02,0.000000000000000000e+00,6.328873686109806940e+00,0.000000000000000000e+00,1.000000009969098214e+00,0.000000000000000000e+00,-7.462101886011724121e-11,0.000000000000000000e+00 +2.601415460546831682e+01,1.361700000000000159e+02,0.000000000000000000e+00,6.330453746100834778e+00,0.000000000000000000e+00,1.000000009968980308e+00,0.000000000000000000e+00,3.646238204121480507e-10,0.000000000000000000e+00 +2.601573427106593073e+01,1.361800000000000068e+02,0.000000000000000000e+00,6.332033411714196092e+00,0.000000000000000000e+00,1.000000009969556292e+00,0.000000000000000000e+00,-4.763507188451687173e-10,0.000000000000000000e+00 +2.601731354258106421e+01,1.361899999999999977e+02,0.000000000000000000e+00,6.333612683245075203e+00,0.000000000000000000e+00,1.000000009968804005e+00,0.000000000000000000e+00,-6.469184819596872460e-12,0.000000000000000000e+00 +2.601889242030853566e+01,1.361999999999999886e+02,0.000000000000000000e+00,6.335191560988285175e+00,0.000000000000000000e+00,1.000000009968793790e+00,0.000000000000000000e+00,9.312321610220319806e-11,0.000000000000000000e+00 +2.602047090454279044e+01,1.362100000000000080e+02,0.000000000000000000e+00,6.336770045238274918e+00,0.000000000000000000e+00,1.000000009968940784e+00,0.000000000000000000e+00,2.790171427171083616e-10,0.000000000000000000e+00 +2.602204899557790796e+01,1.362199999999999989e+02,0.000000000000000000e+00,6.338348136289125634e+00,0.000000000000000000e+00,1.000000009969381098e+00,0.000000000000000000e+00,-4.196854895258489007e-10,0.000000000000000000e+00 +2.602362669370760528e+01,1.362299999999999898e+02,0.000000000000000000e+00,6.339925834434552598e+00,0.000000000000000000e+00,1.000000009968718961e+00,0.000000000000000000e+00,2.394576502500894698e-10,0.000000000000000000e+00 +2.602520399922523353e+01,1.362400000000000091e+02,0.000000000000000000e+00,6.341503139967903380e+00,0.000000000000000000e+00,1.000000009969096659e+00,0.000000000000000000e+00,-1.395423690310913487e-10,0.000000000000000000e+00 +2.602678091242377434e+01,1.362500000000000000e+02,0.000000000000000000e+00,6.343080053182164058e+00,0.000000000000000000e+00,1.000000009968876613e+00,0.000000000000000000e+00,-2.746471073612526503e-11,0.000000000000000000e+00 +2.602835743359584697e+01,1.362599999999999909e+02,0.000000000000000000e+00,6.344656574369953894e+00,0.000000000000000000e+00,1.000000009968833314e+00,0.000000000000000000e+00,3.231779773039605224e-10,0.000000000000000000e+00 +2.602993356303371186e+01,1.362700000000000102e+02,0.000000000000000000e+00,6.346232703823529775e+00,0.000000000000000000e+00,1.000000009969342685e+00,0.000000000000000000e+00,-4.155573717040803420e-10,0.000000000000000000e+00 +2.603150930102925997e+01,1.362800000000000011e+02,0.000000000000000000e+00,6.347808441834786208e+00,0.000000000000000000e+00,1.000000009968687875e+00,0.000000000000000000e+00,3.647777246366873902e-10,0.000000000000000000e+00 +2.603308464787402343e+01,1.362899999999999920e+02,0.000000000000000000e+00,6.349383788695252662e+00,0.000000000000000000e+00,1.000000009969262527e+00,0.000000000000000000e+00,-4.511508527610354136e-10,0.000000000000000000e+00 +2.603465960385917199e+01,1.363000000000000114e+02,0.000000000000000000e+00,6.350958744696100666e+00,0.000000000000000000e+00,1.000000009968551984e+00,0.000000000000000000e+00,4.633904467936963940e-10,0.000000000000000000e+00 +2.603623416927551304e+01,1.363100000000000023e+02,0.000000000000000000e+00,6.352533310128136712e+00,0.000000000000000000e+00,1.000000009969281622e+00,0.000000000000000000e+00,-3.666008401964188699e-10,0.000000000000000000e+00 +2.603780834441349512e+01,1.363199999999999932e+02,0.000000000000000000e+00,6.354107485281811130e+00,0.000000000000000000e+00,1.000000009968704529e+00,0.000000000000000000e+00,3.174514393996313588e-11,0.000000000000000000e+00 +2.603938212956320442e+01,1.363300000000000125e+02,0.000000000000000000e+00,6.355681270447210096e+00,0.000000000000000000e+00,1.000000009968754489e+00,0.000000000000000000e+00,3.324892599726154294e-10,0.000000000000000000e+00 +2.604095552501437183e+01,1.363400000000000034e+02,0.000000000000000000e+00,6.357254665914063629e+00,0.000000000000000000e+00,1.000000009969277626e+00,0.000000000000000000e+00,-4.336417077352550467e-10,0.000000000000000000e+00 +2.604252853105636945e+01,1.363499999999999943e+02,0.000000000000000000e+00,6.358827671971742923e+00,0.000000000000000000e+00,1.000000009968595505e+00,0.000000000000000000e+00,3.545389822683608021e-10,0.000000000000000000e+00 +2.604410114797820697e+01,1.363600000000000136e+02,0.000000000000000000e+00,6.360400288909258570e+00,0.000000000000000000e+00,1.000000009969153059e+00,0.000000000000000000e+00,-6.595406298705306144e-11,0.000000000000000000e+00 +2.604567337606854238e+01,1.363700000000000045e+02,0.000000000000000000e+00,6.361972517015267670e+00,0.000000000000000000e+00,1.000000009969049364e+00,0.000000000000000000e+00,-1.494574891181466832e-10,0.000000000000000000e+00 +2.604724521561567130e+01,1.363799999999999955e+02,0.000000000000000000e+00,6.363544356578067607e+00,0.000000000000000000e+00,1.000000009968814441e+00,0.000000000000000000e+00,-1.445489478508613207e-10,0.000000000000000000e+00 +2.604881666690753761e+01,1.363900000000000148e+02,0.000000000000000000e+00,6.365115807885600496e+00,0.000000000000000000e+00,1.000000009968587289e+00,0.000000000000000000e+00,6.020826801920766368e-11,0.000000000000000000e+00 +2.605038773023172993e+01,1.364000000000000057e+02,0.000000000000000000e+00,6.366686871225453181e+00,0.000000000000000000e+00,1.000000009968681880e+00,0.000000000000000000e+00,2.162943360634038131e-10,0.000000000000000000e+00 +2.605195840587547806e+01,1.364099999999999966e+02,0.000000000000000000e+00,6.368257546884858122e+00,0.000000000000000000e+00,1.000000009969021608e+00,0.000000000000000000e+00,7.593379930786278695e-11,0.000000000000000000e+00 +2.605352869412566008e+01,1.364200000000000159e+02,0.000000000000000000e+00,6.369827835150693396e+00,0.000000000000000000e+00,1.000000009969140846e+00,0.000000000000000000e+00,-2.485076035254555716e-10,0.000000000000000000e+00 +2.605509859526879879e+01,1.364300000000000068e+02,0.000000000000000000e+00,6.371397736309482696e+00,0.000000000000000000e+00,1.000000009968750714e+00,0.000000000000000000e+00,7.682008297962393282e-11,0.000000000000000000e+00 +2.605666810959106527e+01,1.364399999999999977e+02,0.000000000000000000e+00,6.372967250647396220e+00,0.000000000000000000e+00,1.000000009968871284e+00,0.000000000000000000e+00,-2.752336425994968852e-10,0.000000000000000000e+00 +2.605823723737827891e+01,1.364499999999999886e+02,0.000000000000000000e+00,6.374536378450253338e+00,0.000000000000000000e+00,1.000000009968439407e+00,0.000000000000000000e+00,2.520883344296876416e-10,0.000000000000000000e+00 +2.605980597891590733e+01,1.364600000000000080e+02,0.000000000000000000e+00,6.376105120003519922e+00,0.000000000000000000e+00,1.000000009968834869e+00,0.000000000000000000e+00,-3.015610851166416588e-11,0.000000000000000000e+00 +2.606137433448906648e+01,1.364699999999999989e+02,0.000000000000000000e+00,6.377673475592312791e+00,0.000000000000000000e+00,1.000000009968787573e+00,0.000000000000000000e+00,7.703736250524379421e-11,0.000000000000000000e+00 +2.606294230438252058e+01,1.364799999999999898e+02,0.000000000000000000e+00,6.379241445501396157e+00,0.000000000000000000e+00,1.000000009968908365e+00,0.000000000000000000e+00,-3.272059898386686438e-11,0.000000000000000000e+00 +2.606450988888068210e+01,1.364900000000000091e+02,0.000000000000000000e+00,6.380809030015185179e+00,0.000000000000000000e+00,1.000000009968857073e+00,0.000000000000000000e+00,1.191549169164478677e-10,0.000000000000000000e+00 +2.606607708826761893e+01,1.365000000000000000e+02,0.000000000000000000e+00,6.382376229417745073e+00,0.000000000000000000e+00,1.000000009969043813e+00,0.000000000000000000e+00,-4.349301507407656875e-10,0.000000000000000000e+00 +2.606764390282704724e+01,1.365099999999999909e+02,0.000000000000000000e+00,6.383943043992792887e+00,0.000000000000000000e+00,1.000000009968362358e+00,0.000000000000000000e+00,2.321897941928207112e-10,0.000000000000000000e+00 +2.606921033284233502e+01,1.365200000000000102e+02,0.000000000000000000e+00,6.385509474023695731e+00,0.000000000000000000e+00,1.000000009968726067e+00,0.000000000000000000e+00,6.876659452762484108e-11,0.000000000000000000e+00 +2.607077637859650565e+01,1.365300000000000011e+02,0.000000000000000000e+00,6.387075519793476097e+00,0.000000000000000000e+00,1.000000009968833758e+00,0.000000000000000000e+00,-8.310743770054644511e-11,0.000000000000000000e+00 +2.607234204037223080e+01,1.365399999999999920e+02,0.000000000000000000e+00,6.388641181584807427e+00,0.000000000000000000e+00,1.000000009968703640e+00,0.000000000000000000e+00,2.598807978740539391e-10,0.000000000000000000e+00 +2.607390731845183751e+01,1.365500000000000114e+02,0.000000000000000000e+00,6.390206459680016771e+00,0.000000000000000000e+00,1.000000009969110426e+00,0.000000000000000000e+00,-2.325594913846884020e-10,0.000000000000000000e+00 +2.607547221311730823e+01,1.365600000000000023e+02,0.000000000000000000e+00,6.391771354361086566e+00,0.000000000000000000e+00,1.000000009968746495e+00,0.000000000000000000e+00,1.177984426474698974e-11,0.000000000000000000e+00 +2.607703672465027722e+01,1.365699999999999932e+02,0.000000000000000000e+00,6.393335865909651972e+00,0.000000000000000000e+00,1.000000009968764925e+00,0.000000000000000000e+00,-3.367304806975489536e-10,0.000000000000000000e+00 +2.607860085333203770e+01,1.365800000000000125e+02,0.000000000000000000e+00,6.394899994607005311e+00,0.000000000000000000e+00,1.000000009968238235e+00,0.000000000000000000e+00,2.964861953444903094e-10,0.000000000000000000e+00 +2.608016459944353826e+01,1.365900000000000034e+02,0.000000000000000000e+00,6.396463740734093406e+00,0.000000000000000000e+00,1.000000009968701864e+00,0.000000000000000000e+00,2.188682707176256707e-10,0.000000000000000000e+00 +2.608172796326538290e+01,1.365999999999999943e+02,0.000000000000000000e+00,6.398027104571522017e+00,0.000000000000000000e+00,1.000000009969044035e+00,0.000000000000000000e+00,-4.472198017511342438e-10,0.000000000000000000e+00 +2.608329094507783097e+01,1.366100000000000136e+02,0.000000000000000000e+00,6.399590086399552291e+00,0.000000000000000000e+00,1.000000009968345038e+00,0.000000000000000000e+00,2.404322613489116553e-10,0.000000000000000000e+00 +2.608485354516080434e+01,1.366200000000000045e+02,0.000000000000000000e+00,6.401152686498101652e+00,0.000000000000000000e+00,1.000000009968720738e+00,0.000000000000000000e+00,2.249983466812487499e-10,0.000000000000000000e+00 +2.608641576379387672e+01,1.366299999999999955e+02,0.000000000000000000e+00,6.402714905146749125e+00,0.000000000000000000e+00,1.000000009969072234e+00,0.000000000000000000e+00,-3.692124519153706902e-10,0.000000000000000000e+00 +2.608797760125628784e+01,1.366400000000000148e+02,0.000000000000000000e+00,6.404276742624730900e+00,0.000000000000000000e+00,1.000000009968495585e+00,0.000000000000000000e+00,3.967477926619222354e-11,0.000000000000000000e+00 +2.608953905782693283e+01,1.366500000000000057e+02,0.000000000000000000e+00,6.405838199210941220e+00,0.000000000000000000e+00,1.000000009968557535e+00,0.000000000000000000e+00,1.224670740267579444e-10,0.000000000000000000e+00 +2.609110013378436577e+01,1.366599999999999966e+02,0.000000000000000000e+00,6.407399275183936815e+00,0.000000000000000000e+00,1.000000009968748715e+00,0.000000000000000000e+00,5.264095230424052110e-12,0.000000000000000000e+00 +2.609266082940680676e+01,1.366700000000000159e+02,0.000000000000000000e+00,6.408959970821934249e+00,0.000000000000000000e+00,1.000000009968756931e+00,0.000000000000000000e+00,-1.844305180173139550e-10,0.000000000000000000e+00 +2.609422114497212775e+01,1.366800000000000068e+02,0.000000000000000000e+00,6.410520286402810797e+00,0.000000000000000000e+00,1.000000009968469161e+00,0.000000000000000000e+00,4.654588123051348824e-11,0.000000000000000000e+00 +2.609578108075787384e+01,1.366899999999999977e+02,0.000000000000000000e+00,6.412080222204105340e+00,0.000000000000000000e+00,1.000000009968541770e+00,0.000000000000000000e+00,9.752809564855384507e-11,0.000000000000000000e+00 +2.609734063704124196e+01,1.367000000000000171e+02,0.000000000000000000e+00,6.413639778503020139e+00,0.000000000000000000e+00,1.000000009968693870e+00,0.000000000000000000e+00,9.726699376416819699e-11,0.000000000000000000e+00 +2.609889981409909865e+01,1.367100000000000080e+02,0.000000000000000000e+00,6.415198955576419948e+00,0.000000000000000000e+00,1.000000009968845527e+00,0.000000000000000000e+00,-1.897381143051777589e-10,0.000000000000000000e+00 +2.610045861220797292e+01,1.367199999999999989e+02,0.000000000000000000e+00,6.416757753700832900e+00,0.000000000000000000e+00,1.000000009968549763e+00,0.000000000000000000e+00,9.831164438208916183e-11,0.000000000000000000e+00 +2.610201703164405629e+01,1.367299999999999898e+02,0.000000000000000000e+00,6.418316173152450510e+00,0.000000000000000000e+00,1.000000009968702974e+00,0.000000000000000000e+00,-4.275457436854724578e-12,0.000000000000000000e+00 +2.610357507268320276e+01,1.367400000000000091e+02,0.000000000000000000e+00,6.419874214207130336e+00,0.000000000000000000e+00,1.000000009968696313e+00,0.000000000000000000e+00,-3.666381971121510082e-10,0.000000000000000000e+00 +2.610513273560093950e+01,1.367500000000000000e+02,0.000000000000000000e+00,6.421431877140394207e+00,0.000000000000000000e+00,1.000000009968125214e+00,0.000000000000000000e+00,6.084077646075339655e-10,0.000000000000000000e+00 +2.610669002067245259e+01,1.367599999999999909e+02,0.000000000000000000e+00,6.422989162227429105e+00,0.000000000000000000e+00,1.000000009969072678e+00,0.000000000000000000e+00,-6.085553118145723678e-10,0.000000000000000000e+00 +2.610824692817259418e+01,1.367700000000000102e+02,0.000000000000000000e+00,6.424546069743091614e+00,0.000000000000000000e+00,1.000000009968125214e+00,0.000000000000000000e+00,5.116983892643139019e-10,0.000000000000000000e+00 +2.610980345837588601e+01,1.367800000000000011e+02,0.000000000000000000e+00,6.426102599961899919e+00,0.000000000000000000e+00,1.000000009968921688e+00,0.000000000000000000e+00,-2.940802592226504557e-10,0.000000000000000000e+00 +2.611135961155651941e+01,1.367899999999999920e+02,0.000000000000000000e+00,6.427658753158045357e+00,0.000000000000000000e+00,1.000000009968464054e+00,0.000000000000000000e+00,4.053324533563628868e-11,0.000000000000000000e+00 +2.611291538798834821e+01,1.368000000000000114e+02,0.000000000000000000e+00,6.429214529605382644e+00,0.000000000000000000e+00,1.000000009968527115e+00,0.000000000000000000e+00,-1.824437527461348648e-10,0.000000000000000000e+00 +2.611447078794489940e+01,1.368100000000000023e+02,0.000000000000000000e+00,6.430769929577437871e+00,0.000000000000000000e+00,1.000000009968243342e+00,0.000000000000000000e+00,2.735890444209936498e-10,0.000000000000000000e+00 +2.611602581169936599e+01,1.368199999999999932e+02,0.000000000000000000e+00,6.432324953347404950e+00,0.000000000000000000e+00,1.000000009968668779e+00,0.000000000000000000e+00,7.584076811512013204e-11,0.000000000000000000e+00 +2.611758045952461416e+01,1.368300000000000125e+02,0.000000000000000000e+00,6.433879601188149167e+00,0.000000000000000000e+00,1.000000009968786685e+00,0.000000000000000000e+00,-2.718641507706520299e-10,0.000000000000000000e+00 +2.611913473169317612e+01,1.368400000000000034e+02,0.000000000000000000e+00,6.435433873372204516e+00,0.000000000000000000e+00,1.000000009968364134e+00,0.000000000000000000e+00,1.031704334536416568e-10,0.000000000000000000e+00 +2.612068862847725725e+01,1.368499999999999943e+02,0.000000000000000000e+00,6.436987770171775480e+00,0.000000000000000000e+00,1.000000009968524450e+00,0.000000000000000000e+00,-1.319242429047251256e-10,0.000000000000000000e+00 +2.612224215014873607e+01,1.368600000000000136e+02,0.000000000000000000e+00,6.438541291858739690e+00,0.000000000000000000e+00,1.000000009968319503e+00,0.000000000000000000e+00,2.651988428059129359e-10,0.000000000000000000e+00 +2.612379529697916070e+01,1.368700000000000045e+02,0.000000000000000000e+00,6.440094438704645263e+00,0.000000000000000000e+00,1.000000009968731396e+00,0.000000000000000000e+00,-4.074036453942561104e-10,0.000000000000000000e+00 +2.612534806923975239e+01,1.368799999999999955e+02,0.000000000000000000e+00,6.441647210980714355e+00,0.000000000000000000e+00,1.000000009968098791e+00,0.000000000000000000e+00,5.682713048843796568e-10,0.000000000000000000e+00 +2.612690046720140202e+01,1.368900000000000148e+02,0.000000000000000000e+00,6.443199608957839608e+00,0.000000000000000000e+00,1.000000009968980974e+00,0.000000000000000000e+00,-3.522328526018680907e-10,0.000000000000000000e+00 +2.612845249113468071e+01,1.369000000000000057e+02,0.000000000000000000e+00,6.444751632906591254e+00,0.000000000000000000e+00,1.000000009968434300e+00,0.000000000000000000e+00,-7.970794379039627548e-11,0.000000000000000000e+00 +2.613000414130983273e+01,1.369099999999999966e+02,0.000000000000000000e+00,6.446303283097209125e+00,0.000000000000000000e+00,1.000000009968310621e+00,0.000000000000000000e+00,5.253116397200664901e-11,0.000000000000000000e+00 +2.613155541799677195e+01,1.369200000000000159e+02,0.000000000000000000e+00,6.447854559799610641e+00,0.000000000000000000e+00,1.000000009968392112e+00,0.000000000000000000e+00,1.866951559121574846e-10,0.000000000000000000e+00 +2.613310632146508894e+01,1.369300000000000068e+02,0.000000000000000000e+00,6.449405463283388151e+00,0.000000000000000000e+00,1.000000009968681658e+00,0.000000000000000000e+00,-2.740954587015932608e-10,0.000000000000000000e+00 +2.613465685198405453e+01,1.369399999999999977e+02,0.000000000000000000e+00,6.450955993817809819e+00,0.000000000000000000e+00,1.000000009968256665e+00,0.000000000000000000e+00,-7.849551863197490401e-11,0.000000000000000000e+00 +2.613620700982261269e+01,1.369500000000000171e+02,0.000000000000000000e+00,6.452506151671818735e+00,0.000000000000000000e+00,1.000000009968134984e+00,0.000000000000000000e+00,1.783766503134257139e-10,0.000000000000000000e+00 +2.613775679524938056e+01,1.369600000000000080e+02,0.000000000000000000e+00,6.454055937114036468e+00,0.000000000000000000e+00,1.000000009968411430e+00,0.000000000000000000e+00,2.711403064963259604e-10,0.000000000000000000e+00 +2.613930620853266262e+01,1.369699999999999989e+02,0.000000000000000000e+00,6.455605350412762178e+00,0.000000000000000000e+00,1.000000009968831538e+00,0.000000000000000000e+00,-3.963440418950644801e-10,0.000000000000000000e+00 +2.614085524994042942e+01,1.369799999999999898e+02,0.000000000000000000e+00,6.457154391835972618e+00,0.000000000000000000e+00,1.000000009968217585e+00,0.000000000000000000e+00,1.716230226162553699e-10,0.000000000000000000e+00 +2.614240391974033884e+01,1.369900000000000091e+02,0.000000000000000000e+00,6.458703061651321242e+00,0.000000000000000000e+00,1.000000009968483372e+00,0.000000000000000000e+00,-9.952793977388056772e-11,0.000000000000000000e+00 +2.614395221819972548e+01,1.370000000000000000e+02,0.000000000000000000e+00,6.460251360126143538e+00,0.000000000000000000e+00,1.000000009968329273e+00,0.000000000000000000e+00,4.647663233560962308e-11,0.000000000000000000e+00 +2.614550014558560420e+01,1.370099999999999909e+02,0.000000000000000000e+00,6.461799287527452584e+00,0.000000000000000000e+00,1.000000009968401216e+00,0.000000000000000000e+00,1.592636513593308984e-11,0.000000000000000000e+00 +2.614704770216466656e+01,1.370200000000000102e+02,0.000000000000000000e+00,6.463346844121942603e+00,0.000000000000000000e+00,1.000000009968425863e+00,0.000000000000000000e+00,-4.348508428384408907e-11,0.000000000000000000e+00 +2.614859488820328792e+01,1.370300000000000011e+02,0.000000000000000000e+00,6.464894030175988071e+00,0.000000000000000000e+00,1.000000009968358583e+00,0.000000000000000000e+00,1.564689376485756687e-11,0.000000000000000000e+00 +2.615014170396752391e+01,1.370399999999999920e+02,0.000000000000000000e+00,6.466440845955644612e+00,0.000000000000000000e+00,1.000000009968382786e+00,0.000000000000000000e+00,-2.914751754909951776e-11,0.000000000000000000e+00 +2.615168814972311395e+01,1.370500000000000114e+02,0.000000000000000000e+00,6.467987291726649879e+00,0.000000000000000000e+00,1.000000009968337711e+00,0.000000000000000000e+00,-2.843639732046102850e-11,0.000000000000000000e+00 +2.615323422573547418e+01,1.370600000000000023e+02,0.000000000000000000e+00,6.469533367754423558e+00,0.000000000000000000e+00,1.000000009968293746e+00,0.000000000000000000e+00,1.670678552545189319e-10,0.000000000000000000e+00 +2.615477993226971165e+01,1.370699999999999932e+02,0.000000000000000000e+00,6.471079074304068257e+00,0.000000000000000000e+00,1.000000009968551984e+00,0.000000000000000000e+00,-4.076395073449177269e-10,0.000000000000000000e+00 +2.615632526959061011e+01,1.370800000000000125e+02,0.000000000000000000e+00,6.472624411640370390e+00,0.000000000000000000e+00,1.000000009967922043e+00,0.000000000000000000e+00,2.578357126577573936e-10,0.000000000000000000e+00 +2.615787023796263711e+01,1.370900000000000034e+02,0.000000000000000000e+00,6.474169380027798404e+00,0.000000000000000000e+00,1.000000009968320391e+00,0.000000000000000000e+00,8.280313241506602188e-11,0.000000000000000000e+00 +2.615941483764995112e+01,1.370999999999999943e+02,0.000000000000000000e+00,6.475713979730508107e+00,0.000000000000000000e+00,1.000000009968448289e+00,0.000000000000000000e+00,-3.724154142293215760e-11,0.000000000000000000e+00 +2.616095906891638734e+01,1.371100000000000136e+02,0.000000000000000000e+00,6.477258211012338229e+00,0.000000000000000000e+00,1.000000009968390779e+00,0.000000000000000000e+00,5.062605646425006703e-11,0.000000000000000000e+00 +2.616250293202547184e+01,1.371200000000000045e+02,0.000000000000000000e+00,6.478802074136813083e+00,0.000000000000000000e+00,1.000000009968468939e+00,0.000000000000000000e+00,-2.462854176359879671e-10,0.000000000000000000e+00 +2.616404642724041452e+01,1.371299999999999955e+02,0.000000000000000000e+00,6.480345569367143455e+00,0.000000000000000000e+00,1.000000009968088799e+00,0.000000000000000000e+00,-2.877851543455608625e-11,0.000000000000000000e+00 +2.616558955482411619e+01,1.371400000000000148e+02,0.000000000000000000e+00,6.481888696966225716e+00,0.000000000000000000e+00,1.000000009968044390e+00,0.000000000000000000e+00,1.116872289951451743e-10,0.000000000000000000e+00 +2.616713231503915793e+01,1.371500000000000057e+02,0.000000000000000000e+00,6.483431457196644487e+00,0.000000000000000000e+00,1.000000009968216697e+00,0.000000000000000000e+00,3.295269525143833462e-10,0.000000000000000000e+00 +2.616867470814781171e+01,1.371599999999999966e+02,0.000000000000000000e+00,6.484973850320671751e+00,0.000000000000000000e+00,1.000000009968724957e+00,0.000000000000000000e+00,-3.406929878182187704e-10,0.000000000000000000e+00 +2.617021673441203689e+01,1.371700000000000159e+02,0.000000000000000000e+00,6.486515876600267738e+00,0.000000000000000000e+00,1.000000009968199599e+00,0.000000000000000000e+00,-2.493152125281353050e-10,0.000000000000000000e+00 +2.617175839409348015e+01,1.371800000000000068e+02,0.000000000000000000e+00,6.488057536297079153e+00,0.000000000000000000e+00,1.000000009967815240e+00,0.000000000000000000e+00,3.868113492834814165e-10,0.000000000000000000e+00 +2.617329968745348268e+01,1.371899999999999977e+02,0.000000000000000000e+00,6.489598829672443614e+00,0.000000000000000000e+00,1.000000009968411430e+00,0.000000000000000000e+00,-1.446744329889589447e-10,0.000000000000000000e+00 +2.617484061475306945e+01,1.372000000000000171e+02,0.000000000000000000e+00,6.491139756987389653e+00,0.000000000000000000e+00,1.000000009968188497e+00,0.000000000000000000e+00,1.826155687135293948e-10,0.000000000000000000e+00 +2.617638117625295635e+01,1.372100000000000080e+02,0.000000000000000000e+00,6.492680318502633163e+00,0.000000000000000000e+00,1.000000009968469827e+00,0.000000000000000000e+00,-3.439811822036294374e-10,0.000000000000000000e+00 +2.617792137221355375e+01,1.372199999999999989e+02,0.000000000000000000e+00,6.494220514478582729e+00,0.000000000000000000e+00,1.000000009967940029e+00,0.000000000000000000e+00,3.055612045650438966e-10,0.000000000000000000e+00 +2.617946120289495937e+01,1.372299999999999898e+02,0.000000000000000000e+00,6.495760345175336070e+00,0.000000000000000000e+00,1.000000009968410541e+00,0.000000000000000000e+00,-3.311632246765798936e-10,0.000000000000000000e+00 +2.618100066855696184e+01,1.372400000000000091e+02,0.000000000000000000e+00,6.497299810852685376e+00,0.000000000000000000e+00,1.000000009967900727e+00,0.000000000000000000e+00,1.526366411015920436e-10,0.000000000000000000e+00 +2.618253976945904782e+01,1.372500000000000000e+02,0.000000000000000000e+00,6.498838911770111970e+00,0.000000000000000000e+00,1.000000009968135650e+00,0.000000000000000000e+00,4.357956998278952858e-11,0.000000000000000000e+00 +2.618407850586039132e+01,1.372599999999999909e+02,0.000000000000000000e+00,6.500377648186792534e+00,0.000000000000000000e+00,1.000000009968202708e+00,0.000000000000000000e+00,2.514357136527454501e-10,0.000000000000000000e+00 +2.618561687801986082e+01,1.372700000000000102e+02,0.000000000000000000e+00,6.501916020361595550e+00,0.000000000000000000e+00,1.000000009968589509e+00,0.000000000000000000e+00,-5.639152250831978059e-10,0.000000000000000000e+00 +2.618715488619601572e+01,1.372800000000000011e+02,0.000000000000000000e+00,6.503454028553083965e+00,0.000000000000000000e+00,1.000000009967722203e+00,0.000000000000000000e+00,3.871516496401121313e-10,0.000000000000000000e+00 +2.618869253064711700e+01,1.372899999999999920e+02,0.000000000000000000e+00,6.504991673019512533e+00,0.000000000000000000e+00,1.000000009968317505e+00,0.000000000000000000e+00,-1.128075077045540317e-10,0.000000000000000000e+00 +2.619022981163111652e+01,1.373000000000000114e+02,0.000000000000000000e+00,6.506528954018834909e+00,0.000000000000000000e+00,1.000000009968144088e+00,0.000000000000000000e+00,-2.340478234665990699e-11,0.000000000000000000e+00 +2.619176672940565709e+01,1.373100000000000023e+02,0.000000000000000000e+00,6.508065871808696556e+00,0.000000000000000000e+00,1.000000009968108117e+00,0.000000000000000000e+00,6.676273828833108402e-11,0.000000000000000000e+00 +2.619330328422808307e+01,1.373199999999999932e+02,0.000000000000000000e+00,6.509602426646440065e+00,0.000000000000000000e+00,1.000000009968210701e+00,0.000000000000000000e+00,-5.434787092404438956e-11,0.000000000000000000e+00 +2.619483947635543331e+01,1.373300000000000125e+02,0.000000000000000000e+00,6.511138618789104271e+00,0.000000000000000000e+00,1.000000009968127213e+00,0.000000000000000000e+00,1.533954757556630293e-10,0.000000000000000000e+00 +2.619637530604444464e+01,1.373400000000000034e+02,0.000000000000000000e+00,6.512674448493424251e+00,0.000000000000000000e+00,1.000000009968362802e+00,0.000000000000000000e+00,-2.747598027350029834e-10,0.000000000000000000e+00 +2.619791077355154840e+01,1.373499999999999943e+02,0.000000000000000000e+00,6.514209916015833102e+00,0.000000000000000000e+00,1.000000009967940917e+00,0.000000000000000000e+00,-4.368264404945379995e-11,0.000000000000000000e+00 +2.619944587913287393e+01,1.373600000000000136e+02,0.000000000000000000e+00,6.515745021612460164e+00,0.000000000000000000e+00,1.000000009967873860e+00,0.000000000000000000e+00,2.592640564176191480e-10,0.000000000000000000e+00 +2.620098062304424857e+01,1.373700000000000045e+02,0.000000000000000000e+00,6.517279765539134573e+00,0.000000000000000000e+00,1.000000009968271764e+00,0.000000000000000000e+00,4.616334526212870625e-11,0.000000000000000000e+00 +2.620251500554120483e+01,1.373799999999999955e+02,0.000000000000000000e+00,6.518814148051384372e+00,0.000000000000000000e+00,1.000000009968342596e+00,0.000000000000000000e+00,-5.171801420675325333e-10,0.000000000000000000e+00 +2.620404902687896609e+01,1.373900000000000148e+02,0.000000000000000000e+00,6.520348169404435623e+00,0.000000000000000000e+00,1.000000009967549230e+00,0.000000000000000000e+00,6.245844286836441228e-10,0.000000000000000000e+00 +2.620558268731245732e+01,1.374000000000000057e+02,0.000000000000000000e+00,6.521881829853213297e+00,0.000000000000000000e+00,1.000000009968507131e+00,0.000000000000000000e+00,-5.139479645010836366e-10,0.000000000000000000e+00 +2.620711598709630508e+01,1.374099999999999966e+02,0.000000000000000000e+00,6.523415129652346600e+00,0.000000000000000000e+00,1.000000009967719095e+00,0.000000000000000000e+00,3.902229730297839318e-10,0.000000000000000000e+00 +2.620864892648483746e+01,1.374200000000000159e+02,0.000000000000000000e+00,6.524948069056160094e+00,0.000000000000000000e+00,1.000000009968317283e+00,0.000000000000000000e+00,-2.725248319878001236e-10,0.000000000000000000e+00 +2.621018150573208416e+01,1.374300000000000068e+02,0.000000000000000000e+00,6.526480648318684352e+00,0.000000000000000000e+00,1.000000009967899617e+00,0.000000000000000000e+00,-6.521264176980530344e-11,0.000000000000000000e+00 +2.621171372509177644e+01,1.374399999999999977e+02,0.000000000000000000e+00,6.528012867693647969e+00,0.000000000000000000e+00,1.000000009967799697e+00,0.000000000000000000e+00,4.268807062359279476e-10,0.000000000000000000e+00 +2.621324558481734357e+01,1.374500000000000171e+02,0.000000000000000000e+00,6.529544727434483775e+00,0.000000000000000000e+00,1.000000009968453618e+00,0.000000000000000000e+00,-5.189013791870426365e-10,0.000000000000000000e+00 +2.621477708516191996e+01,1.374600000000000080e+02,0.000000000000000000e+00,6.531076227794327949e+00,0.000000000000000000e+00,1.000000009967658920e+00,0.000000000000000000e+00,2.972889993508503231e-10,0.000000000000000000e+00 +2.621630822637834513e+01,1.374699999999999989e+02,0.000000000000000000e+00,6.532607369026016464e+00,0.000000000000000000e+00,1.000000009968114112e+00,0.000000000000000000e+00,1.740636266862876017e-11,0.000000000000000000e+00 +2.621783900871916373e+01,1.374799999999999898e+02,0.000000000000000000e+00,6.534138151382093085e+00,0.000000000000000000e+00,1.000000009968140757e+00,0.000000000000000000e+00,-5.034519331491762736e-11,0.000000000000000000e+00 +2.621936943243661844e+01,1.374900000000000091e+02,0.000000000000000000e+00,6.535668575114803147e+00,0.000000000000000000e+00,1.000000009968063708e+00,0.000000000000000000e+00,-1.123236498732106927e-10,0.000000000000000000e+00 +2.622089949778266060e+01,1.375000000000000000e+02,0.000000000000000000e+00,6.537198640476097111e+00,0.000000000000000000e+00,1.000000009967891845e+00,0.000000000000000000e+00,4.064339130434707413e-12,0.000000000000000000e+00 +2.622242920500894670e+01,1.375099999999999909e+02,0.000000000000000000e+00,6.538728347717630562e+00,0.000000000000000000e+00,1.000000009967898063e+00,0.000000000000000000e+00,9.393724111846484376e-11,0.000000000000000000e+00 +2.622395855436683831e+01,1.375200000000000102e+02,0.000000000000000000e+00,6.540257697090765099e+00,0.000000000000000000e+00,1.000000009968041725e+00,0.000000000000000000e+00,-4.923056094594023304e-11,0.000000000000000000e+00 +2.622548754610740218e+01,1.375300000000000011e+02,0.000000000000000000e+00,6.541786688846568332e+00,0.000000000000000000e+00,1.000000009967966452e+00,0.000000000000000000e+00,1.294238480778429711e-10,0.000000000000000000e+00 +2.622701618048141015e+01,1.375399999999999920e+02,0.000000000000000000e+00,6.543315323235813885e+00,0.000000000000000000e+00,1.000000009968164294e+00,0.000000000000000000e+00,-3.354764262242569935e-10,0.000000000000000000e+00 +2.622854445773934629e+01,1.375500000000000114e+02,0.000000000000000000e+00,6.544843600508983172e+00,0.000000000000000000e+00,1.000000009967651593e+00,0.000000000000000000e+00,2.527196900922206567e-10,0.000000000000000000e+00 +2.623007237813139625e+01,1.375600000000000023e+02,0.000000000000000000e+00,6.546371520916263620e+00,0.000000000000000000e+00,1.000000009968037729e+00,0.000000000000000000e+00,-2.116421912047101510e-10,0.000000000000000000e+00 +2.623159994190745792e+01,1.375699999999999932e+02,0.000000000000000000e+00,6.547899084707553108e+00,0.000000000000000000e+00,1.000000009967714432e+00,0.000000000000000000e+00,3.502506927835046145e-10,0.000000000000000000e+00 +2.623312714931713785e+01,1.375800000000000125e+02,0.000000000000000000e+00,6.549426292132455529e+00,0.000000000000000000e+00,1.000000009968249337e+00,0.000000000000000000e+00,-1.688401402059232130e-10,0.000000000000000000e+00 +2.623465400060974773e+01,1.375900000000000034e+02,0.000000000000000000e+00,6.550953143440286119e+00,0.000000000000000000e+00,1.000000009967991543e+00,0.000000000000000000e+00,-6.763907682171794563e-11,0.000000000000000000e+00 +2.623618049603431146e+01,1.375999999999999943e+02,0.000000000000000000e+00,6.552479638880067014e+00,0.000000000000000000e+00,1.000000009967888293e+00,0.000000000000000000e+00,-3.112122548013399292e-10,0.000000000000000000e+00 +2.623770663583956519e+01,1.376100000000000136e+02,0.000000000000000000e+00,6.554005778700531692e+00,0.000000000000000000e+00,1.000000009967413339e+00,0.000000000000000000e+00,4.234869525281080864e-10,0.000000000000000000e+00 +2.623923242027395020e+01,1.376200000000000045e+02,0.000000000000000000e+00,6.555531563150123198e+00,0.000000000000000000e+00,1.000000009968059489e+00,0.000000000000000000e+00,2.663785361304232766e-11,0.000000000000000000e+00 +2.624075784958561997e+01,1.376299999999999955e+02,0.000000000000000000e+00,6.557056992476997692e+00,0.000000000000000000e+00,1.000000009968100123e+00,0.000000000000000000e+00,-1.776270137825871888e-10,0.000000000000000000e+00 +2.624228292402244023e+01,1.376400000000000148e+02,0.000000000000000000e+00,6.558582066929020016e+00,0.000000000000000000e+00,1.000000009967829229e+00,0.000000000000000000e+00,-9.029046136301826434e-12,0.000000000000000000e+00 +2.624380764383198894e+01,1.376500000000000057e+02,0.000000000000000000e+00,6.560106786753767238e+00,0.000000000000000000e+00,1.000000009967815462e+00,0.000000000000000000e+00,-5.039961666268418639e-11,0.000000000000000000e+00 +2.624533200926155629e+01,1.376599999999999966e+02,0.000000000000000000e+00,6.561631152198529549e+00,0.000000000000000000e+00,1.000000009967738634e+00,0.000000000000000000e+00,2.615269760352392251e-10,0.000000000000000000e+00 +2.624685602055814471e+01,1.376700000000000159e+02,0.000000000000000000e+00,6.563155163510309364e+00,0.000000000000000000e+00,1.000000009968137205e+00,0.000000000000000000e+00,-4.210177821346868559e-10,0.000000000000000000e+00 +2.624837967796846883e+01,1.376800000000000068e+02,0.000000000000000000e+00,6.564678820935823111e+00,0.000000000000000000e+00,1.000000009967495718e+00,0.000000000000000000e+00,3.789893939661479441e-10,0.000000000000000000e+00 +2.624990298173895908e+01,1.376899999999999977e+02,0.000000000000000000e+00,6.566202124721498556e+00,0.000000000000000000e+00,1.000000009968073034e+00,0.000000000000000000e+00,-2.165114788612904107e-10,0.000000000000000000e+00 +2.625142593211576170e+01,1.377000000000000171e+02,0.000000000000000000e+00,6.567725075113481026e+00,0.000000000000000000e+00,1.000000009967743297e+00,0.000000000000000000e+00,-1.111245874704563414e-10,0.000000000000000000e+00 +2.625294852934473155e+01,1.377100000000000080e+02,0.000000000000000000e+00,6.569247672357627188e+00,0.000000000000000000e+00,1.000000009967574099e+00,0.000000000000000000e+00,1.142135481181588006e-10,0.000000000000000000e+00 +2.625447077367144288e+01,1.377199999999999989e+02,0.000000000000000000e+00,6.570769916699510382e+00,0.000000000000000000e+00,1.000000009967747960e+00,0.000000000000000000e+00,2.598486142178353010e-10,0.000000000000000000e+00 +2.625599266534118215e+01,1.377299999999999898e+02,0.000000000000000000e+00,6.572291808384419731e+00,0.000000000000000000e+00,1.000000009968143422e+00,0.000000000000000000e+00,-2.566982469020694465e-10,0.000000000000000000e+00 +2.625751420459895513e+01,1.377400000000000091e+02,0.000000000000000000e+00,6.573813347657360140e+00,0.000000000000000000e+00,1.000000009967752845e+00,0.000000000000000000e+00,-9.955016151646667237e-11,0.000000000000000000e+00 +2.625903539168948342e+01,1.377500000000000000e+02,0.000000000000000000e+00,6.575334534763051408e+00,0.000000000000000000e+00,1.000000009967601411e+00,0.000000000000000000e+00,1.505278103351038799e-10,0.000000000000000000e+00 +2.626055622685720436e+01,1.377599999999999909e+02,0.000000000000000000e+00,6.576855369945931784e+00,0.000000000000000000e+00,1.000000009967830339e+00,0.000000000000000000e+00,-8.893563486316474499e-11,0.000000000000000000e+00 +2.626207671034627467e+01,1.377700000000000102e+02,0.000000000000000000e+00,6.578375853450157074e+00,0.000000000000000000e+00,1.000000009967695114e+00,0.000000000000000000e+00,1.373051295382043301e-10,0.000000000000000000e+00 +2.626359684240056680e+01,1.377800000000000011e+02,0.000000000000000000e+00,6.579895985519599755e+00,0.000000000000000000e+00,1.000000009967903836e+00,0.000000000000000000e+00,-1.367524458661139123e-10,0.000000000000000000e+00 +2.626511662326366903e+01,1.377899999999999920e+02,0.000000000000000000e+00,6.581415766397851641e+00,0.000000000000000000e+00,1.000000009967696002e+00,0.000000000000000000e+00,4.603308770646126648e-11,0.000000000000000000e+00 +2.626663605317889605e+01,1.378000000000000114e+02,0.000000000000000000e+00,6.582935196328222105e+00,0.000000000000000000e+00,1.000000009967765946e+00,0.000000000000000000e+00,1.042195839624953551e-10,0.000000000000000000e+00 +2.626815513238927124e+01,1.378100000000000023e+02,0.000000000000000000e+00,6.584454275553740743e+00,0.000000000000000000e+00,1.000000009967924264e+00,0.000000000000000000e+00,-1.581930037219769197e-10,0.000000000000000000e+00 +2.626967386113754799e+01,1.378199999999999932e+02,0.000000000000000000e+00,6.585973004317156487e+00,0.000000000000000000e+00,1.000000009967684012e+00,0.000000000000000000e+00,-1.674424840990150492e-10,0.000000000000000000e+00 +2.627119223966619543e+01,1.378300000000000125e+02,0.000000000000000000e+00,6.587491382860937605e+00,0.000000000000000000e+00,1.000000009967429770e+00,0.000000000000000000e+00,2.670921098758343434e-10,0.000000000000000000e+00 +2.627271026821740207e+01,1.378400000000000034e+02,0.000000000000000000e+00,6.589009411427273477e+00,0.000000000000000000e+00,1.000000009967835224e+00,0.000000000000000000e+00,-2.064369182158439190e-10,0.000000000000000000e+00 +2.627422794703307574e+01,1.378499999999999943e+02,0.000000000000000000e+00,6.590527090258075482e+00,0.000000000000000000e+00,1.000000009967521919e+00,0.000000000000000000e+00,1.447293683180025790e-10,0.000000000000000000e+00 +2.627574527635485069e+01,1.378600000000000136e+02,0.000000000000000000e+00,6.592044419594974336e+00,0.000000000000000000e+00,1.000000009967741521e+00,0.000000000000000000e+00,-3.088465866462141275e-11,0.000000000000000000e+00 +2.627726225642408053e+01,1.378700000000000045e+02,0.000000000000000000e+00,6.593561399679324531e+00,0.000000000000000000e+00,1.000000009967694670e+00,0.000000000000000000e+00,-1.560693008619420444e-10,0.000000000000000000e+00 +2.627877888748184176e+01,1.378799999999999955e+02,0.000000000000000000e+00,6.595078030752201670e+00,0.000000000000000000e+00,1.000000009967457970e+00,0.000000000000000000e+00,3.482346756984163920e-10,0.000000000000000000e+00 +2.628029516976893021e+01,1.378900000000000148e+02,0.000000000000000000e+00,6.596594313054404246e+00,0.000000000000000000e+00,1.000000009967985992e+00,0.000000000000000000e+00,-2.575009717087271736e-10,0.000000000000000000e+00 +2.628181110352587169e+01,1.379000000000000057e+02,0.000000000000000000e+00,6.598110246826455416e+00,0.000000000000000000e+00,1.000000009967595638e+00,0.000000000000000000e+00,1.523677774328716173e-10,0.000000000000000000e+00 +2.628332668899290780e+01,1.379099999999999966e+02,0.000000000000000000e+00,6.599625832308599449e+00,0.000000000000000000e+00,1.000000009967826564e+00,0.000000000000000000e+00,-1.617814086889145243e-10,0.000000000000000000e+00 +2.628484192641001016e+01,1.379200000000000159e+02,0.000000000000000000e+00,6.601141069740807055e+00,0.000000000000000000e+00,1.000000009967581427e+00,0.000000000000000000e+00,-2.324675948763603710e-10,0.000000000000000000e+00 +2.628635681601687679e+01,1.379300000000000068e+02,0.000000000000000000e+00,6.602655959362771831e+00,0.000000000000000000e+00,1.000000009967229264e+00,0.000000000000000000e+00,5.229522105808960222e-10,0.000000000000000000e+00 +2.628787135805292152e+01,1.379399999999999977e+02,0.000000000000000000e+00,6.604170501413912930e+00,0.000000000000000000e+00,1.000000009968021297e+00,0.000000000000000000e+00,-4.110376464852727002e-10,0.000000000000000000e+00 +2.628938555275729172e+01,1.379500000000000171e+02,0.000000000000000000e+00,6.605684696133376832e+00,0.000000000000000000e+00,1.000000009967398906e+00,0.000000000000000000e+00,2.587358728152028545e-10,0.000000000000000000e+00 +2.629089940036885764e+01,1.379600000000000080e+02,0.000000000000000000e+00,6.607198543760032017e+00,0.000000000000000000e+00,1.000000009967790593e+00,0.000000000000000000e+00,-3.702942202743546658e-10,0.000000000000000000e+00 +2.629241290112621598e+01,1.379699999999999989e+02,0.000000000000000000e+00,6.608712044532476959e+00,0.000000000000000000e+00,1.000000009967230152e+00,0.000000000000000000e+00,2.234894146152069272e-10,0.000000000000000000e+00 +2.629392605526768989e+01,1.379799999999999898e+02,0.000000000000000000e+00,6.610225198689033910e+00,0.000000000000000000e+00,1.000000009967568326e+00,0.000000000000000000e+00,2.991304749439705349e-10,0.000000000000000000e+00 +2.629543886303133249e+01,1.379900000000000091e+02,0.000000000000000000e+00,6.611738006467755113e+00,0.000000000000000000e+00,1.000000009968020853e+00,0.000000000000000000e+00,-3.353142121025854710e-10,0.000000000000000000e+00 +2.629695132465491980e+01,1.380000000000000000e+02,0.000000000000000000e+00,6.613250468106419255e+00,0.000000000000000000e+00,1.000000009967513703e+00,0.000000000000000000e+00,7.136601815060305204e-11,0.000000000000000000e+00 +2.629846344037596140e+01,1.380099999999999909e+02,0.000000000000000000e+00,6.614762583842531463e+00,0.000000000000000000e+00,1.000000009967621617e+00,0.000000000000000000e+00,-2.242815370207550491e-10,0.000000000000000000e+00 +2.629997521043168973e+01,1.380200000000000102e+02,0.000000000000000000e+00,6.616274353913327744e+00,0.000000000000000000e+00,1.000000009967282555e+00,0.000000000000000000e+00,1.427973000290573098e-10,0.000000000000000000e+00 +2.630148663505906725e+01,1.380300000000000011e+02,0.000000000000000000e+00,6.617785778555771437e+00,0.000000000000000000e+00,1.000000009967498382e+00,0.000000000000000000e+00,2.058690523777747601e-10,0.000000000000000000e+00 +2.630299771449478996e+01,1.380399999999999920e+02,0.000000000000000000e+00,6.619296858006556761e+00,0.000000000000000000e+00,1.000000009967809467e+00,0.000000000000000000e+00,-2.245822549936442328e-10,0.000000000000000000e+00 +2.630450844897528029e+01,1.380500000000000114e+02,0.000000000000000000e+00,6.620807592502107042e+00,0.000000000000000000e+00,1.000000009967470183e+00,0.000000000000000000e+00,-1.703862828541500658e-10,0.000000000000000000e+00 +2.630601883873669422e+01,1.380600000000000023e+02,0.000000000000000000e+00,6.622317982278574711e+00,0.000000000000000000e+00,1.000000009967212833e+00,0.000000000000000000e+00,1.810123925457524051e-10,0.000000000000000000e+00 +2.630752888401491418e+01,1.380699999999999932e+02,0.000000000000000000e+00,6.623828027571843968e+00,0.000000000000000000e+00,1.000000009967486170e+00,0.000000000000000000e+00,2.523867536144593566e-10,0.000000000000000000e+00 +2.630903858504555259e+01,1.380800000000000125e+02,0.000000000000000000e+00,6.625337728617530786e+00,0.000000000000000000e+00,1.000000009967867198e+00,0.000000000000000000e+00,-1.454938172962880365e-10,0.000000000000000000e+00 +2.631054794206395897e+01,1.380900000000000034e+02,0.000000000000000000e+00,6.626847085650982017e+00,0.000000000000000000e+00,1.000000009967647596e+00,0.000000000000000000e+00,-4.201005860856266781e-10,0.000000000000000000e+00 +2.631205695530520927e+01,1.380999999999999943e+02,0.000000000000000000e+00,6.628356098907275396e+00,0.000000000000000000e+00,1.000000009967013659e+00,0.000000000000000000e+00,4.118070410173436917e-10,0.000000000000000000e+00 +2.631356562500411655e+01,1.381100000000000136e+02,0.000000000000000000e+00,6.629864768621221316e+00,0.000000000000000000e+00,1.000000009967634940e+00,0.000000000000000000e+00,-1.773911472422134152e-10,0.000000000000000000e+00 +2.631507395139522743e+01,1.381200000000000045e+02,0.000000000000000000e+00,6.631373095027365494e+00,0.000000000000000000e+00,1.000000009967367376e+00,0.000000000000000000e+00,-3.327760998930583787e-11,0.000000000000000000e+00 +2.631658193471281493e+01,1.381299999999999955e+02,0.000000000000000000e+00,6.632881078359983640e+00,0.000000000000000000e+00,1.000000009967317194e+00,0.000000000000000000e+00,2.684906120953345167e-10,0.000000000000000000e+00 +2.631808957519088921e+01,1.381400000000000148e+02,0.000000000000000000e+00,6.634388718853086786e+00,0.000000000000000000e+00,1.000000009967721981e+00,0.000000000000000000e+00,-2.405621652520804193e-10,0.000000000000000000e+00 +2.631959687306319751e+01,1.381500000000000057e+02,0.000000000000000000e+00,6.635896016740420400e+00,0.000000000000000000e+00,1.000000009967359382e+00,0.000000000000000000e+00,2.086426311654773423e-10,0.000000000000000000e+00 +2.632110382856322062e+01,1.381599999999999966e+02,0.000000000000000000e+00,6.637402972255462608e+00,0.000000000000000000e+00,1.000000009967673797e+00,0.000000000000000000e+00,-1.333788566235936741e-10,0.000000000000000000e+00 +2.632261044192416932e+01,1.381700000000000159e+02,0.000000000000000000e+00,6.638909585631428634e+00,0.000000000000000000e+00,1.000000009967472847e+00,0.000000000000000000e+00,-2.786113365980869225e-10,0.000000000000000000e+00 +2.632411671337899506e+01,1.381800000000000068e+02,0.000000000000000000e+00,6.640415857101267250e+00,0.000000000000000000e+00,1.000000009967053183e+00,0.000000000000000000e+00,3.714186190614941637e-10,0.000000000000000000e+00 +2.632562264316038281e+01,1.381899999999999977e+02,0.000000000000000000e+00,6.641921786897663438e+00,0.000000000000000000e+00,1.000000009967612513e+00,0.000000000000000000e+00,-3.254889998346031392e-10,0.000000000000000000e+00 +2.632712823150075110e+01,1.382000000000000171e+02,0.000000000000000000e+00,6.643427375253040168e+00,0.000000000000000000e+00,1.000000009967122461e+00,0.000000000000000000e+00,1.880799938779903633e-10,0.000000000000000000e+00 +2.632863347863226267e+01,1.382100000000000080e+02,0.000000000000000000e+00,6.644932622399553956e+00,0.000000000000000000e+00,1.000000009967405568e+00,0.000000000000000000e+00,1.609739339833529873e-10,0.000000000000000000e+00 +2.633013838478681024e+01,1.382199999999999989e+02,0.000000000000000000e+00,6.646437528569101083e+00,0.000000000000000000e+00,1.000000009967647818e+00,0.000000000000000000e+00,-1.987910136720967096e-10,0.000000000000000000e+00 +2.633164295019602719e+01,1.382299999999999898e+02,0.000000000000000000e+00,6.647942093993314039e+00,0.000000000000000000e+00,1.000000009967348724e+00,0.000000000000000000e+00,1.022964795346884895e-10,0.000000000000000000e+00 +2.633314717509128400e+01,1.382400000000000091e+02,0.000000000000000000e+00,6.649446318903562414e+00,0.000000000000000000e+00,1.000000009967502601e+00,0.000000000000000000e+00,-2.963282677468248375e-10,0.000000000000000000e+00 +2.633465105970368825e+01,1.382500000000000000e+02,0.000000000000000000e+00,6.650950203530955562e+00,0.000000000000000000e+00,1.000000009967056958e+00,0.000000000000000000e+00,3.864805516205052529e-10,0.000000000000000000e+00 +2.633615460426408816e+01,1.382599999999999909e+02,0.000000000000000000e+00,6.652453748106339937e+00,0.000000000000000000e+00,1.000000009967638048e+00,0.000000000000000000e+00,-3.896699182771473567e-10,0.000000000000000000e+00 +2.633765780900306908e+01,1.382700000000000102e+02,0.000000000000000000e+00,6.653956952860303531e+00,0.000000000000000000e+00,1.000000009967052295e+00,0.000000000000000000e+00,3.377508405008867253e-10,0.000000000000000000e+00 +2.633916067415095696e+01,1.382800000000000011e+02,0.000000000000000000e+00,6.655459818023170548e+00,0.000000000000000000e+00,1.000000009967559889e+00,0.000000000000000000e+00,-3.659054950017141995e-10,0.000000000000000000e+00 +2.634066319993781846e+01,1.382899999999999920e+02,0.000000000000000000e+00,6.656962343825008510e+00,0.000000000000000000e+00,1.000000009967010106e+00,0.000000000000000000e+00,4.648758394083441041e-10,0.000000000000000000e+00 +2.634216538659346085e+01,1.383000000000000114e+02,0.000000000000000000e+00,6.658464530495622036e+00,0.000000000000000000e+00,1.000000009967708436e+00,0.000000000000000000e+00,-4.997249306154572693e-10,0.000000000000000000e+00 +2.634366723434742852e+01,1.383100000000000023e+02,0.000000000000000000e+00,6.659966378264559950e+00,0.000000000000000000e+00,1.000000009966957926e+00,0.000000000000000000e+00,4.962885028593403356e-10,0.000000000000000000e+00 +2.634516874342901005e+01,1.383199999999999932e+02,0.000000000000000000e+00,6.661467887361108176e+00,0.000000000000000000e+00,1.000000009967703107e+00,0.000000000000000000e+00,-2.726060558712389468e-10,0.000000000000000000e+00 +2.634666991406723824e+01,1.383300000000000125e+02,0.000000000000000000e+00,6.662969058014298618e+00,0.000000000000000000e+00,1.000000009967293879e+00,0.000000000000000000e+00,-2.290229362113234917e-10,0.000000000000000000e+00 +2.634817074649088298e+01,1.383400000000000034e+02,0.000000000000000000e+00,6.664469890452901168e+00,0.000000000000000000e+00,1.000000009966950154e+00,0.000000000000000000e+00,4.476423991177652515e-10,0.000000000000000000e+00 +2.634967124092845481e+01,1.383499999999999943e+02,0.000000000000000000e+00,6.665970384905429924e+00,0.000000000000000000e+00,1.000000009967621839e+00,0.000000000000000000e+00,-3.951981170690620927e-10,0.000000000000000000e+00 +2.635117139760821559e+01,1.383600000000000136e+02,0.000000000000000000e+00,6.667470541600143186e+00,0.000000000000000000e+00,1.000000009967028980e+00,0.000000000000000000e+00,2.198506655454448975e-10,0.000000000000000000e+00 +2.635267121675816426e+01,1.383700000000000045e+02,0.000000000000000000e+00,6.668970360765039018e+00,0.000000000000000000e+00,1.000000009967358716e+00,0.000000000000000000e+00,-2.557356951325134456e-10,0.000000000000000000e+00 +2.635417069860604045e+01,1.383799999999999955e+02,0.000000000000000000e+00,6.670469842627862356e+00,0.000000000000000000e+00,1.000000009966975245e+00,0.000000000000000000e+00,3.695448892972245758e-10,0.000000000000000000e+00 +2.635566984337933505e+01,1.383900000000000148e+02,0.000000000000000000e+00,6.671968987416099672e+00,0.000000000000000000e+00,1.000000009967529246e+00,0.000000000000000000e+00,-4.545164434464642148e-10,0.000000000000000000e+00 +2.635716865130527964e+01,1.384000000000000057e+02,0.000000000000000000e+00,6.673467795356984311e+00,0.000000000000000000e+00,1.000000009966848014e+00,0.000000000000000000e+00,2.559081587212633223e-10,0.000000000000000000e+00 +2.635866712261084999e+01,1.384099999999999966e+02,0.000000000000000000e+00,6.674966266677491156e+00,0.000000000000000000e+00,1.000000009967231485e+00,0.000000000000000000e+00,3.462279618328927166e-10,0.000000000000000000e+00 +2.636016525752276962e+01,1.384200000000000159e+02,0.000000000000000000e+00,6.676464401604343735e+00,0.000000000000000000e+00,1.000000009967750181e+00,0.000000000000000000e+00,-3.629093660057466300e-10,0.000000000000000000e+00 +2.636166305626750628e+01,1.384300000000000068e+02,0.000000000000000000e+00,6.677962200364009782e+00,0.000000000000000000e+00,1.000000009967206616e+00,0.000000000000000000e+00,-6.969185748875361043e-11,0.000000000000000000e+00 +2.636316051907127189e+01,1.384399999999999977e+02,0.000000000000000000e+00,6.679459663182701235e+00,0.000000000000000000e+00,1.000000009967102255e+00,0.000000000000000000e+00,-1.391183427138592398e-10,0.000000000000000000e+00 +2.636465764616002616e+01,1.384500000000000171e+02,0.000000000000000000e+00,6.680956790286378677e+00,0.000000000000000000e+00,1.000000009966893977e+00,0.000000000000000000e+00,4.404423650319402043e-10,0.000000000000000000e+00 +2.636615443775947654e+01,1.384600000000000080e+02,0.000000000000000000e+00,6.682453581900748674e+00,0.000000000000000000e+00,1.000000009967553227e+00,0.000000000000000000e+00,-4.901000534522509099e-10,0.000000000000000000e+00 +2.636765089409507823e+01,1.384699999999999989e+02,0.000000000000000000e+00,6.683950038251266434e+00,0.000000000000000000e+00,1.000000009966819814e+00,0.000000000000000000e+00,4.615659991760487070e-10,0.000000000000000000e+00 +2.636914701539203065e+01,1.384799999999999898e+02,0.000000000000000000e+00,6.685446159563131374e+00,0.000000000000000000e+00,1.000000009967510373e+00,0.000000000000000000e+00,-4.512780443793200582e-10,0.000000000000000000e+00 +2.637064280187528453e+01,1.384900000000000091e+02,0.000000000000000000e+00,6.686941946061295106e+00,0.000000000000000000e+00,1.000000009966835357e+00,0.000000000000000000e+00,1.673368904156164741e-10,0.000000000000000000e+00 +2.637213825376953835e+01,1.385000000000000000e+02,0.000000000000000000e+00,6.688437397970453446e+00,0.000000000000000000e+00,1.000000009967085601e+00,0.000000000000000000e+00,1.569783931655248441e-10,0.000000000000000000e+00 +2.637363337129923835e+01,1.385099999999999909e+02,0.000000000000000000e+00,6.689932515515054412e+00,0.000000000000000000e+00,1.000000009967320302e+00,0.000000000000000000e+00,-2.615901086815866490e-10,0.000000000000000000e+00 +2.637512815468857852e+01,1.385200000000000102e+02,0.000000000000000000e+00,6.691427298919293776e+00,0.000000000000000000e+00,1.000000009966929282e+00,0.000000000000000000e+00,3.270235523471801696e-10,0.000000000000000000e+00 +2.637662260416150417e+01,1.385300000000000011e+02,0.000000000000000000e+00,6.692921748407115956e+00,0.000000000000000000e+00,1.000000009967418002e+00,0.000000000000000000e+00,-2.406039880813697340e-10,0.000000000000000000e+00 +2.637811671994171192e+01,1.385399999999999920e+02,0.000000000000000000e+00,6.694415864202217570e+00,0.000000000000000000e+00,1.000000009967058512e+00,0.000000000000000000e+00,-1.504296432879891068e-10,0.000000000000000000e+00 +2.637961050225264970e+01,1.385500000000000114e+02,0.000000000000000000e+00,6.695909646528042991e+00,0.000000000000000000e+00,1.000000009966833803e+00,0.000000000000000000e+00,4.240326825643675659e-10,0.000000000000000000e+00 +2.638110395131750963e+01,1.385600000000000023e+02,0.000000000000000000e+00,6.697403095607788792e+00,0.000000000000000000e+00,1.000000009967467074e+00,0.000000000000000000e+00,-2.844864815254078018e-10,0.000000000000000000e+00 +2.638259706735924226e+01,1.385699999999999932e+02,0.000000000000000000e+00,6.698896211664403744e+00,0.000000000000000000e+00,1.000000009967042303e+00,0.000000000000000000e+00,-6.009313201521357810e-11,0.000000000000000000e+00 +2.638408985060054590e+01,1.385800000000000125e+02,0.000000000000000000e+00,6.700388994920585262e+00,0.000000000000000000e+00,1.000000009966952597e+00,0.000000000000000000e+00,1.273544154501320705e-10,0.000000000000000000e+00 +2.638558230126387016e+01,1.385900000000000034e+02,0.000000000000000000e+00,6.701881445598784737e+00,0.000000000000000000e+00,1.000000009967142667e+00,0.000000000000000000e+00,-2.947959019945754840e-10,0.000000000000000000e+00 +2.638707441957141953e+01,1.385999999999999943e+02,0.000000000000000000e+00,6.703373563921205758e+00,0.000000000000000000e+00,1.000000009966702796e+00,0.000000000000000000e+00,4.953554726567727268e-10,0.000000000000000000e+00 +2.638856620574514977e+01,1.386100000000000136e+02,0.000000000000000000e+00,6.704865350109803224e+00,0.000000000000000000e+00,1.000000009967441761e+00,0.000000000000000000e+00,-4.685188072349867004e-10,0.000000000000000000e+00 +2.639005766000676800e+01,1.386200000000000045e+02,0.000000000000000000e+00,6.706356804386287784e+00,0.000000000000000000e+00,1.000000009966742986e+00,0.000000000000000000e+00,2.336414134625394318e-10,0.000000000000000000e+00 +2.639154878257773973e+01,1.386299999999999955e+02,0.000000000000000000e+00,6.707847926972119623e+00,0.000000000000000000e+00,1.000000009967091374e+00,0.000000000000000000e+00,3.440609732964360682e-11,0.000000000000000000e+00 +2.639303957367927822e+01,1.386400000000000148e+02,0.000000000000000000e+00,6.709338718088516451e+00,0.000000000000000000e+00,1.000000009967142667e+00,0.000000000000000000e+00,-4.067078829357672893e-11,0.000000000000000000e+00 +2.639453003353235516e+01,1.386500000000000057e+02,0.000000000000000000e+00,6.710829177956448177e+00,0.000000000000000000e+00,1.000000009967082049e+00,0.000000000000000000e+00,-1.627192927584273631e-10,0.000000000000000000e+00 +2.639602016235769355e+01,1.386599999999999966e+02,0.000000000000000000e+00,6.712319306796639573e+00,0.000000000000000000e+00,1.000000009966839576e+00,0.000000000000000000e+00,2.967454668619165012e-10,0.000000000000000000e+00 +2.639750996037577480e+01,1.386700000000000159e+02,0.000000000000000000e+00,6.713809104829570273e+00,0.000000000000000000e+00,1.000000009967281667e+00,0.000000000000000000e+00,-4.338126412551723381e-10,0.000000000000000000e+00 +2.639899942780683517e+01,1.386800000000000068e+02,0.000000000000000000e+00,6.715298572275476552e+00,0.000000000000000000e+00,1.000000009966635517e+00,0.000000000000000000e+00,2.761509455740759018e-10,0.000000000000000000e+00 +2.640048856487086582e+01,1.386899999999999977e+02,0.000000000000000000e+00,6.716787709354347768e+00,0.000000000000000000e+00,1.000000009967046743e+00,0.000000000000000000e+00,-1.455632237929958926e-10,0.000000000000000000e+00 +2.640197737178761273e+01,1.387000000000000171e+02,0.000000000000000000e+00,6.718276516285932587e+00,0.000000000000000000e+00,1.000000009966830028e+00,0.000000000000000000e+00,1.326172021749048884e-10,0.000000000000000000e+00 +2.640346584877657676e+01,1.387100000000000080e+02,0.000000000000000000e+00,6.719764993289733646e+00,0.000000000000000000e+00,1.000000009967027426e+00,0.000000000000000000e+00,1.401070221773505942e-10,0.000000000000000000e+00 +2.640495399605702431e+01,1.387199999999999989e+02,0.000000000000000000e+00,6.721253140585011998e+00,0.000000000000000000e+00,1.000000009967235926e+00,0.000000000000000000e+00,-2.940063456458580255e-10,0.000000000000000000e+00 +2.640644181384796951e+01,1.387299999999999898e+02,0.000000000000000000e+00,6.722740958390785337e+00,0.000000000000000000e+00,1.000000009966798498e+00,0.000000000000000000e+00,2.660077577732429163e-10,0.000000000000000000e+00 +2.640792930236818492e+01,1.387400000000000091e+02,0.000000000000000000e+00,6.724228446925827996e+00,0.000000000000000000e+00,1.000000009967194181e+00,0.000000000000000000e+00,-3.558006420384229506e-10,0.000000000000000000e+00 +2.640941646183620861e+01,1.387500000000000000e+02,0.000000000000000000e+00,6.725715606408674496e+00,0.000000000000000000e+00,1.000000009966665049e+00,0.000000000000000000e+00,8.034539691887646954e-11,0.000000000000000000e+00 +2.641090329247032997e+01,1.387599999999999909e+02,0.000000000000000000e+00,6.727202437057615114e+00,0.000000000000000000e+00,1.000000009966784509e+00,0.000000000000000000e+00,2.010572703943125414e-10,0.000000000000000000e+00 +2.641238979448860036e+01,1.387700000000000102e+02,0.000000000000000000e+00,6.728688939090701204e+00,0.000000000000000000e+00,1.000000009967083381e+00,0.000000000000000000e+00,-1.625547155932479235e-10,0.000000000000000000e+00 +2.641387596810882954e+01,1.387800000000000011e+02,0.000000000000000000e+00,6.730175112725742537e+00,0.000000000000000000e+00,1.000000009966841796e+00,0.000000000000000000e+00,2.734750305386081956e-11,0.000000000000000000e+00 +2.641536181354858570e+01,1.387899999999999920e+02,0.000000000000000000e+00,6.731660958180307297e+00,0.000000000000000000e+00,1.000000009966882430e+00,0.000000000000000000e+00,2.011905231238551783e-10,0.000000000000000000e+00 +2.641684733102519544e+01,1.388000000000000114e+02,0.000000000000000000e+00,6.733146475671724751e+00,0.000000000000000000e+00,1.000000009967181303e+00,0.000000000000000000e+00,-2.121488506862818020e-10,0.000000000000000000e+00 +2.641833252075575089e+01,1.388100000000000023e+02,0.000000000000000000e+00,6.734631665417084356e+00,0.000000000000000000e+00,1.000000009966866221e+00,0.000000000000000000e+00,-1.718201532955150160e-10,0.000000000000000000e+00 +2.641981738295710258e+01,1.388199999999999932e+02,0.000000000000000000e+00,6.736116527633234874e+00,0.000000000000000000e+00,1.000000009966611092e+00,0.000000000000000000e+00,1.549564193099157870e-10,0.000000000000000000e+00 +2.642130191784585946e+01,1.388300000000000125e+02,0.000000000000000000e+00,6.737601062536787033e+00,0.000000000000000000e+00,1.000000009966841130e+00,0.000000000000000000e+00,1.988247746911617673e-10,0.000000000000000000e+00 +2.642278612563839246e+01,1.388400000000000034e+02,0.000000000000000000e+00,6.739085270344113532e+00,0.000000000000000000e+00,1.000000009967136227e+00,0.000000000000000000e+00,-2.079964761709422377e-10,0.000000000000000000e+00 +2.642427000655083802e+01,1.388499999999999943e+02,0.000000000000000000e+00,6.740569151271348147e+00,0.000000000000000000e+00,1.000000009966827585e+00,0.000000000000000000e+00,-2.140291030254376931e-11,0.000000000000000000e+00 +2.642575356079909099e+01,1.388600000000000136e+02,0.000000000000000000e+00,6.742052705534385737e+00,0.000000000000000000e+00,1.000000009966795833e+00,0.000000000000000000e+00,-2.149744312595598031e-10,0.000000000000000000e+00 +2.642723678859880820e+01,1.388700000000000045e+02,0.000000000000000000e+00,6.743535933348884903e+00,0.000000000000000000e+00,1.000000009966476977e+00,0.000000000000000000e+00,2.569479664954840343e-10,0.000000000000000000e+00 +2.642871969016540845e+01,1.388799999999999955e+02,0.000000000000000000e+00,6.745018834930266216e+00,0.000000000000000000e+00,1.000000009966858006e+00,0.000000000000000000e+00,1.737326249200223628e-11,0.000000000000000000e+00 +2.643020226571407960e+01,1.388900000000000148e+02,0.000000000000000000e+00,6.746501410493714879e+00,0.000000000000000000e+00,1.000000009966883763e+00,0.000000000000000000e+00,1.122020155999113346e-10,0.000000000000000000e+00 +2.643168451545976794e+01,1.389000000000000057e+02,0.000000000000000000e+00,6.747983660254178062e+00,0.000000000000000000e+00,1.000000009967050074e+00,0.000000000000000000e+00,-4.322749460568721270e-10,0.000000000000000000e+00 +2.643316643961718526e+01,1.389099999999999966e+02,0.000000000000000000e+00,6.749465584426367570e+00,0.000000000000000000e+00,1.000000009966409475e+00,0.000000000000000000e+00,2.414377377249116991e-10,0.000000000000000000e+00 +2.643464803840080890e+01,1.389200000000000159e+02,0.000000000000000000e+00,6.750947183224758064e+00,0.000000000000000000e+00,1.000000009966767189e+00,0.000000000000000000e+00,-5.396441040608019766e-11,0.000000000000000000e+00 +2.643612931202487815e+01,1.389300000000000068e+02,0.000000000000000000e+00,6.752428456863591499e+00,0.000000000000000000e+00,1.000000009966687253e+00,0.000000000000000000e+00,1.359901660252855082e-10,0.000000000000000000e+00 +2.643761026070339781e+01,1.389399999999999977e+02,0.000000000000000000e+00,6.753909405556872692e+00,0.000000000000000000e+00,1.000000009966888648e+00,0.000000000000000000e+00,-1.633139699619742296e-10,0.000000000000000000e+00 +2.643909088465014179e+01,1.389500000000000171e+02,0.000000000000000000e+00,6.755390029518372863e+00,0.000000000000000000e+00,1.000000009966646841e+00,0.000000000000000000e+00,1.003498601936445884e-10,0.000000000000000000e+00 +2.644057118407864237e+01,1.389600000000000080e+02,0.000000000000000000e+00,6.756870328961627870e+00,0.000000000000000000e+00,1.000000009966795389e+00,0.000000000000000000e+00,-4.786041862689403859e-11,0.000000000000000000e+00 +2.644205115920220450e+01,1.389699999999999989e+02,0.000000000000000000e+00,6.758350304099940864e+00,0.000000000000000000e+00,1.000000009966724557e+00,0.000000000000000000e+00,4.006749445994294027e-11,0.000000000000000000e+00 +2.644353081023389862e+01,1.389799999999999898e+02,0.000000000000000000e+00,6.759829955146380520e+00,0.000000000000000000e+00,1.000000009966783843e+00,0.000000000000000000e+00,2.005314319059162742e-10,0.000000000000000000e+00 +2.644501013738655715e+01,1.389900000000000091e+02,0.000000000000000000e+00,6.761309282313782809e+00,0.000000000000000000e+00,1.000000009967080494e+00,0.000000000000000000e+00,-5.407726718619053780e-10,0.000000000000000000e+00 +2.644648914087278513e+01,1.390000000000000000e+02,0.000000000000000000e+00,6.762788285814750999e+00,0.000000000000000000e+00,1.000000009966280690e+00,0.000000000000000000e+00,4.952410873974477744e-10,0.000000000000000000e+00 +2.644796782090494958e+01,1.390099999999999909e+02,0.000000000000000000e+00,6.764266965861653880e+00,0.000000000000000000e+00,1.000000009967012993e+00,0.000000000000000000e+00,-5.090172893696985998e-10,0.000000000000000000e+00 +2.644944617769519368e+01,1.390200000000000102e+02,0.000000000000000000e+00,6.765745322666631978e+00,0.000000000000000000e+00,1.000000009966260484e+00,0.000000000000000000e+00,3.474813532761782074e-10,0.000000000000000000e+00 +2.645092421145541906e+01,1.390300000000000011e+02,0.000000000000000000e+00,6.767223356441589566e+00,0.000000000000000000e+00,1.000000009966774073e+00,0.000000000000000000e+00,5.770081676622785528e-11,0.000000000000000000e+00 +2.645240192239730348e+01,1.390399999999999920e+02,0.000000000000000000e+00,6.768701067398203541e+00,0.000000000000000000e+00,1.000000009966859338e+00,0.000000000000000000e+00,-3.207302885017197300e-10,0.000000000000000000e+00 +2.645387931073229382e+01,1.390500000000000114e+02,0.000000000000000000e+00,6.770178455747917212e+00,0.000000000000000000e+00,1.000000009966385495e+00,0.000000000000000000e+00,2.717933133665136406e-10,0.000000000000000000e+00 +2.645535637667159889e+01,1.390600000000000023e+02,0.000000000000000000e+00,6.771655521701942959e+00,0.000000000000000000e+00,1.000000009966786951e+00,0.000000000000000000e+00,4.631117491014521114e-11,0.000000000000000000e+00 +2.645683312042620372e+01,1.390699999999999932e+02,0.000000000000000000e+00,6.773132265471264901e+00,0.000000000000000000e+00,1.000000009966855341e+00,0.000000000000000000e+00,-3.447024699556631195e-10,0.000000000000000000e+00 +2.645830954220685882e+01,1.390800000000000125e+02,0.000000000000000000e+00,6.774608687266635343e+00,0.000000000000000000e+00,1.000000009966346415e+00,0.000000000000000000e+00,1.609563881149811439e-10,0.000000000000000000e+00 +2.645978564222408735e+01,1.390900000000000034e+02,0.000000000000000000e+00,6.776084787298576551e+00,0.000000000000000000e+00,1.000000009966584003e+00,0.000000000000000000e+00,1.808520869580141189e-10,0.000000000000000000e+00 +2.646126142068818510e+01,1.390999999999999943e+02,0.000000000000000000e+00,6.777560565777383417e+00,0.000000000000000000e+00,1.000000009966850900e+00,0.000000000000000000e+00,-3.852597140949787770e-11,0.000000000000000000e+00 +2.646273687780921691e+01,1.391100000000000136e+02,0.000000000000000000e+00,6.779036022913120796e+00,0.000000000000000000e+00,1.000000009966794057e+00,0.000000000000000000e+00,-2.494196558170856142e-10,0.000000000000000000e+00 +2.646421201379701671e+01,1.391200000000000045e+02,0.000000000000000000e+00,6.780511158915624392e+00,0.000000000000000000e+00,1.000000009966426129e+00,0.000000000000000000e+00,2.058122284651111003e-10,0.000000000000000000e+00 +2.646568682886119461e+01,1.391299999999999955e+02,0.000000000000000000e+00,6.781985973994501649e+00,0.000000000000000000e+00,1.000000009966729664e+00,0.000000000000000000e+00,-5.752550973494362130e-11,0.000000000000000000e+00 +2.646716132321112980e+01,1.391400000000000148e+02,0.000000000000000000e+00,6.783460468359133522e+00,0.000000000000000000e+00,1.000000009966644843e+00,0.000000000000000000e+00,-3.828838692891726787e-10,0.000000000000000000e+00 +2.646863549705597407e+01,1.391500000000000057e+02,0.000000000000000000e+00,6.784934642218671819e+00,0.000000000000000000e+00,1.000000009966080405e+00,0.000000000000000000e+00,7.076303546349716013e-10,0.000000000000000000e+00 +2.647010935060465542e+01,1.391599999999999966e+02,0.000000000000000000e+00,6.786408495782040973e+00,0.000000000000000000e+00,1.000000009967123349e+00,0.000000000000000000e+00,-6.259601923792290009e-10,0.000000000000000000e+00 +2.647158288406587090e+01,1.391700000000000159e+02,0.000000000000000000e+00,6.787882029257941596e+00,0.000000000000000000e+00,1.000000009966200976e+00,0.000000000000000000e+00,3.661019365234782916e-10,0.000000000000000000e+00 +2.647305609764809020e+01,1.391800000000000068e+02,0.000000000000000000e+00,6.789355242854842487e+00,0.000000000000000000e+00,1.000000009966740322e+00,0.000000000000000000e+00,-1.558796052483636741e-10,0.000000000000000000e+00 +2.647452899155955919e+01,1.391899999999999977e+02,0.000000000000000000e+00,6.790828136780991287e+00,0.000000000000000000e+00,1.000000009966510728e+00,0.000000000000000000e+00,1.046459525017253257e-10,0.000000000000000000e+00 +2.647600156600829635e+01,1.392000000000000171e+02,0.000000000000000000e+00,6.792300711244406486e+00,0.000000000000000000e+00,1.000000009966664827e+00,0.000000000000000000e+00,-2.376913315265390867e-10,0.000000000000000000e+00 +2.647747382120209991e+01,1.392100000000000080e+02,0.000000000000000000e+00,6.793772966452882756e+00,0.000000000000000000e+00,1.000000009966314884e+00,0.000000000000000000e+00,2.983853814618475894e-10,0.000000000000000000e+00 +2.647894575734853717e+01,1.392199999999999989e+02,0.000000000000000000e+00,6.795244902613988280e+00,0.000000000000000000e+00,1.000000009966754089e+00,0.000000000000000000e+00,-4.942984310965720124e-10,0.000000000000000000e+00 +2.648041737465495160e+01,1.392299999999999898e+02,0.000000000000000000e+00,6.796716519935068312e+00,0.000000000000000000e+00,1.000000009966026671e+00,0.000000000000000000e+00,5.079880473180296315e-10,0.000000000000000000e+00 +2.648188867332845930e+01,1.392400000000000091e+02,0.000000000000000000e+00,6.798187818623240730e+00,0.000000000000000000e+00,1.000000009966774073e+00,0.000000000000000000e+00,-1.329870317913667387e-10,0.000000000000000000e+00 +2.648335965357595967e+01,1.392500000000000000e+02,0.000000000000000000e+00,6.799658798885403144e+00,0.000000000000000000e+00,1.000000009966578451e+00,0.000000000000000000e+00,-1.123311698407900577e-10,0.000000000000000000e+00 +2.648483031560412471e+01,1.392599999999999909e+02,0.000000000000000000e+00,6.801129460928225789e+00,0.000000000000000000e+00,1.000000009966413250e+00,0.000000000000000000e+00,3.624369850069917915e-12,0.000000000000000000e+00 +2.648630065961940261e+01,1.392700000000000102e+02,0.000000000000000000e+00,6.802599804958156859e+00,0.000000000000000000e+00,1.000000009966418579e+00,0.000000000000000000e+00,5.890874286004613085e-11,0.000000000000000000e+00 +2.648777068582801775e+01,1.392800000000000011e+02,0.000000000000000000e+00,6.804069831181421613e+00,0.000000000000000000e+00,1.000000009966505177e+00,0.000000000000000000e+00,-1.027348758331962255e-10,0.000000000000000000e+00 +2.648924039443597067e+01,1.392899999999999920e+02,0.000000000000000000e+00,6.805539539804022375e+00,0.000000000000000000e+00,1.000000009966354186e+00,0.000000000000000000e+00,1.858694006253480160e-10,0.000000000000000000e+00 +2.649070978564904166e+01,1.393000000000000114e+02,0.000000000000000000e+00,6.807008931031738541e+00,0.000000000000000000e+00,1.000000009966627301e+00,0.000000000000000000e+00,-5.380796207371083261e-11,0.000000000000000000e+00 +2.649217885967279074e+01,1.393100000000000023e+02,0.000000000000000000e+00,6.808478005070128347e+00,0.000000000000000000e+00,1.000000009966548253e+00,0.000000000000000000e+00,-1.538997953334540027e-10,0.000000000000000000e+00 +2.649364761671255053e+01,1.393199999999999932e+02,0.000000000000000000e+00,6.809946762124527098e+00,0.000000000000000000e+00,1.000000009966322212e+00,0.000000000000000000e+00,-2.694583474151170505e-10,0.000000000000000000e+00 +2.649511605697343697e+01,1.393300000000000125e+02,0.000000000000000000e+00,6.811415202400048940e+00,0.000000000000000000e+00,1.000000009965926528e+00,0.000000000000000000e+00,6.813533179175705673e-10,0.000000000000000000e+00 +2.649658418066034216e+01,1.393400000000000034e+02,0.000000000000000000e+00,6.812883326101586867e+00,0.000000000000000000e+00,1.000000009966926839e+00,0.000000000000000000e+00,-3.408257261684893775e-10,0.000000000000000000e+00 +2.649805198797794148e+01,1.393499999999999943e+02,0.000000000000000000e+00,6.814351133433815377e+00,0.000000000000000000e+00,1.000000009966426573e+00,0.000000000000000000e+00,-1.932215808996269650e-10,0.000000000000000000e+00 +2.649951947913068295e+01,1.393600000000000136e+02,0.000000000000000000e+00,6.815818624601184261e+00,0.000000000000000000e+00,1.000000009966143022e+00,0.000000000000000000e+00,1.461959618113072084e-10,0.000000000000000000e+00 +2.650098665432280143e+01,1.393700000000000045e+02,0.000000000000000000e+00,6.817285799807925706e+00,0.000000000000000000e+00,1.000000009966357517e+00,0.000000000000000000e+00,1.114113767610421450e-10,0.000000000000000000e+00 +2.650245351375830793e+01,1.393799999999999955e+02,0.000000000000000000e+00,6.818752659258052518e+00,0.000000000000000000e+00,1.000000009966520942e+00,0.000000000000000000e+00,-3.906293479990668993e-11,0.000000000000000000e+00 +2.650392005764099679e+01,1.393900000000000148e+02,0.000000000000000000e+00,6.820219203155357235e+00,0.000000000000000000e+00,1.000000009966463654e+00,0.000000000000000000e+00,-4.543178635400229132e-11,0.000000000000000000e+00 +2.650538628617443848e+01,1.394000000000000057e+02,0.000000000000000000e+00,6.821685431703413016e+00,0.000000000000000000e+00,1.000000009966397041e+00,0.000000000000000000e+00,-6.074020970887758987e-11,0.000000000000000000e+00 +2.650685219956199035e+01,1.394099999999999966e+02,0.000000000000000000e+00,6.823151345105574528e+00,0.000000000000000000e+00,1.000000009966308001e+00,0.000000000000000000e+00,-2.380134037229998709e-10,0.000000000000000000e+00 +2.650831779800678589e+01,1.394200000000000159e+02,0.000000000000000000e+00,6.824616943564977944e+00,0.000000000000000000e+00,1.000000009965959169e+00,0.000000000000000000e+00,5.112856264497142090e-10,0.000000000000000000e+00 +2.650978308171174547e+01,1.394300000000000068e+02,0.000000000000000000e+00,6.826082227284540949e+00,0.000000000000000000e+00,1.000000009966708348e+00,0.000000000000000000e+00,-4.477362236387734717e-10,0.000000000000000000e+00 +2.651124805087956915e+01,1.394399999999999977e+02,0.000000000000000000e+00,6.827547196466965396e+00,0.000000000000000000e+00,1.000000009966052428e+00,0.000000000000000000e+00,4.290336656165630124e-11,0.000000000000000000e+00 +2.651271270571274030e+01,1.394500000000000171e+02,0.000000000000000000e+00,6.829011851314731985e+00,0.000000000000000000e+00,1.000000009966115266e+00,0.000000000000000000e+00,1.765025857676316192e-10,0.000000000000000000e+00 +2.651417704641352202e+01,1.394600000000000080e+02,0.000000000000000000e+00,6.830476192030107363e+00,0.000000000000000000e+00,1.000000009966373726e+00,0.000000000000000000e+00,-1.995938229962051239e-10,0.000000000000000000e+00 +2.651564107318396424e+01,1.394699999999999989e+02,0.000000000000000000e+00,6.831940218815140575e+00,0.000000000000000000e+00,1.000000009966081516e+00,0.000000000000000000e+00,4.209662420254115411e-10,0.000000000000000000e+00 +2.651710478622590017e+01,1.394799999999999898e+02,0.000000000000000000e+00,6.833403931871663062e+00,0.000000000000000000e+00,1.000000009966697689e+00,0.000000000000000000e+00,-1.855682942570667408e-10,0.000000000000000000e+00 +2.651856818574094277e+01,1.394900000000000091e+02,0.000000000000000000e+00,6.834867331401292212e+00,0.000000000000000000e+00,1.000000009966426129e+00,0.000000000000000000e+00,-9.758460026911899240e-11,0.000000000000000000e+00 +2.652003127193049536e+01,1.395000000000000000e+02,0.000000000000000000e+00,6.836330417605426923e+00,0.000000000000000000e+00,1.000000009966283354e+00,0.000000000000000000e+00,-2.949416267085634941e-10,0.000000000000000000e+00 +2.652149404499574104e+01,1.395099999999999909e+02,0.000000000000000000e+00,6.837793190685252043e+00,0.000000000000000000e+00,1.000000009965851921e+00,0.000000000000000000e+00,3.168681847789427468e-10,0.000000000000000000e+00 +2.652295650513764969e+01,1.395200000000000102e+02,0.000000000000000000e+00,6.839255650841736589e+00,0.000000000000000000e+00,1.000000009966315329e+00,0.000000000000000000e+00,-7.274188932877992779e-11,0.000000000000000000e+00 +2.652441865255697806e+01,1.395300000000000011e+02,0.000000000000000000e+00,6.840717798275636419e+00,0.000000000000000000e+00,1.000000009966208969e+00,0.000000000000000000e+00,4.678349001238970247e-11,0.000000000000000000e+00 +2.652588048745426264e+01,1.395399999999999920e+02,0.000000000000000000e+00,6.842179633187490673e+00,0.000000000000000000e+00,1.000000009966277359e+00,0.000000000000000000e+00,1.102989347344455895e-10,0.000000000000000000e+00 +2.652734201002983028e+01,1.395500000000000114e+02,0.000000000000000000e+00,6.843641155777625329e+00,0.000000000000000000e+00,1.000000009966438563e+00,0.000000000000000000e+00,-4.481281516619132414e-10,0.000000000000000000e+00 +2.652880322048379469e+01,1.395600000000000023e+02,0.000000000000000000e+00,6.845102366246152314e+00,0.000000000000000000e+00,1.000000009965783754e+00,0.000000000000000000e+00,3.027676756764371440e-10,0.000000000000000000e+00 +2.653026411901605286e+01,1.395699999999999932e+02,0.000000000000000000e+00,6.846563264792968617e+00,0.000000000000000000e+00,1.000000009966226067e+00,0.000000000000000000e+00,1.328691888386813688e-10,0.000000000000000000e+00 +2.653172470582628861e+01,1.395800000000000125e+02,0.000000000000000000e+00,6.848023851617760727e+00,0.000000000000000000e+00,1.000000009966420134e+00,0.000000000000000000e+00,-2.747664118423929819e-10,0.000000000000000000e+00 +2.653318498111397261e+01,1.395900000000000034e+02,0.000000000000000000e+00,6.849484126920000193e+00,0.000000000000000000e+00,1.000000009966018899e+00,0.000000000000000000e+00,1.808339395316744647e-10,0.000000000000000000e+00 +2.653464494507836946e+01,1.395999999999999943e+02,0.000000000000000000e+00,6.850944090898945404e+00,0.000000000000000000e+00,1.000000009966282910e+00,0.000000000000000000e+00,-3.153479055758248530e-10,0.000000000000000000e+00 +2.653610459791851994e+01,1.396100000000000136e+02,0.000000000000000000e+00,6.852403743753644250e+00,0.000000000000000000e+00,1.000000009965822612e+00,0.000000000000000000e+00,5.894443178733692016e-10,0.000000000000000000e+00 +2.653756393983326234e+01,1.396200000000000045e+02,0.000000000000000000e+00,6.853863085682930567e+00,0.000000000000000000e+00,1.000000009966682812e+00,0.000000000000000000e+00,-5.892654779185837255e-10,0.000000000000000000e+00 +2.653902297102121821e+01,1.396299999999999955e+02,0.000000000000000000e+00,6.855322116885429473e+00,0.000000000000000000e+00,1.000000009965823056e+00,0.000000000000000000e+00,1.721593826208827196e-10,0.000000000000000000e+00 +2.654048169168080307e+01,1.396400000000000148e+02,0.000000000000000000e+00,6.856780837559550257e+00,0.000000000000000000e+00,1.000000009966074188e+00,0.000000000000000000e+00,2.227433874091216391e-10,0.000000000000000000e+00 +2.654194010201021214e+01,1.396500000000000057e+02,0.000000000000000000e+00,6.858239247903495261e+00,0.000000000000000000e+00,1.000000009966399039e+00,0.000000000000000000e+00,-1.676641361734564938e-10,0.000000000000000000e+00 +2.654339820220743817e+01,1.396599999999999966e+02,0.000000000000000000e+00,6.859697348115254556e+00,0.000000000000000000e+00,1.000000009966154568e+00,0.000000000000000000e+00,-3.119429196938315458e-10,0.000000000000000000e+00 +2.654485599247026073e+01,1.396700000000000159e+02,0.000000000000000000e+00,6.861155138392606823e+00,0.000000000000000000e+00,1.000000009965699821e+00,0.000000000000000000e+00,4.803540265852365761e-10,0.000000000000000000e+00 +2.654631347299624977e+01,1.396800000000000068e+02,0.000000000000000000e+00,6.862612618933121134e+00,0.000000000000000000e+00,1.000000009966399928e+00,0.000000000000000000e+00,-4.467799507848348759e-10,0.000000000000000000e+00 +2.654777064398276565e+01,1.396899999999999977e+02,0.000000000000000000e+00,6.864069789934158727e+00,0.000000000000000000e+00,1.000000009965748893e+00,0.000000000000000000e+00,5.239957787182811272e-10,0.000000000000000000e+00 +2.654922750562695555e+01,1.397000000000000171e+02,0.000000000000000000e+00,6.865526651592867680e+00,0.000000000000000000e+00,1.000000009966512282e+00,0.000000000000000000e+00,-5.189238532659538933e-10,0.000000000000000000e+00 +2.655068405812576060e+01,1.397100000000000080e+02,0.000000000000000000e+00,6.866983204106190897e+00,0.000000000000000000e+00,1.000000009965756442e+00,0.000000000000000000e+00,4.641419886941387924e-10,0.000000000000000000e+00 +2.655214030167591588e+01,1.397199999999999989e+02,0.000000000000000000e+00,6.868439447670858122e+00,0.000000000000000000e+00,1.000000009966432346e+00,0.000000000000000000e+00,-4.418214478696941232e-10,0.000000000000000000e+00 +2.655359623647394329e+01,1.397299999999999898e+02,0.000000000000000000e+00,6.869895382483394819e+00,0.000000000000000000e+00,1.000000009965789083e+00,0.000000000000000000e+00,3.879151213060987650e-10,0.000000000000000000e+00 +2.655505186271615514e+01,1.397400000000000091e+02,0.000000000000000000e+00,6.871351008740114175e+00,0.000000000000000000e+00,1.000000009966353742e+00,0.000000000000000000e+00,-5.446914719531782993e-10,0.000000000000000000e+00 +2.655650718059866122e+01,1.397500000000000000e+02,0.000000000000000000e+00,6.872806326637125096e+00,0.000000000000000000e+00,1.000000009965561043e+00,0.000000000000000000e+00,3.882320974694063622e-10,0.000000000000000000e+00 +2.655796219031736172e+01,1.397599999999999909e+02,0.000000000000000000e+00,6.874261336370325104e+00,0.000000000000000000e+00,1.000000009966125925e+00,0.000000000000000000e+00,1.062369279239693550e-10,0.000000000000000000e+00 +2.655941689206794720e+01,1.397700000000000102e+02,0.000000000000000000e+00,6.875716038135408326e+00,0.000000000000000000e+00,1.000000009966280468e+00,0.000000000000000000e+00,-2.774042338347556747e-10,0.000000000000000000e+00 +2.656087128604590220e+01,1.397800000000000011e+02,0.000000000000000000e+00,6.877170432127859279e+00,0.000000000000000000e+00,1.000000009965877013e+00,0.000000000000000000e+00,-6.780051346721481623e-11,0.000000000000000000e+00 +2.656232537244650871e+01,1.397899999999999920e+02,0.000000000000000000e+00,6.878624518542955535e+00,0.000000000000000000e+00,1.000000009965778425e+00,0.000000000000000000e+00,1.713699562212499783e-10,0.000000000000000000e+00 +2.656377915146483559e+01,1.398000000000000114e+02,0.000000000000000000e+00,6.880078297575769497e+00,0.000000000000000000e+00,1.000000009966027559e+00,0.000000000000000000e+00,-1.245062677962372223e-10,0.000000000000000000e+00 +2.656523262329574919e+01,1.398100000000000023e+02,0.000000000000000000e+00,6.881531769421167510e+00,0.000000000000000000e+00,1.000000009965846592e+00,0.000000000000000000e+00,1.613575395189304714e-10,0.000000000000000000e+00 +2.656668578813390980e+01,1.398199999999999932e+02,0.000000000000000000e+00,6.882984934273808975e+00,0.000000000000000000e+00,1.000000009966081072e+00,0.000000000000000000e+00,4.478005934376806949e-11,0.000000000000000000e+00 +2.656813864617377163e+01,1.398300000000000125e+02,0.000000000000000000e+00,6.884437792328149008e+00,0.000000000000000000e+00,1.000000009966146131e+00,0.000000000000000000e+00,-1.981133341568082412e-10,0.000000000000000000e+00 +2.656959119760958288e+01,1.398400000000000034e+02,0.000000000000000000e+00,6.885890343778436673e+00,0.000000000000000000e+00,1.000000009965858361e+00,0.000000000000000000e+00,1.319505253212403019e-10,0.000000000000000000e+00 +2.657104344263538920e+01,1.398499999999999943e+02,0.000000000000000000e+00,6.887342588818715861e+00,0.000000000000000000e+00,1.000000009966049985e+00,0.000000000000000000e+00,4.970216108382180505e-11,0.000000000000000000e+00 +2.657249538144503020e+01,1.398600000000000136e+02,0.000000000000000000e+00,6.888794527642827070e+00,0.000000000000000000e+00,1.000000009966122150e+00,0.000000000000000000e+00,-1.670344667955784585e-10,0.000000000000000000e+00 +2.657394701423214300e+01,1.398700000000000045e+02,0.000000000000000000e+00,6.890246160444405632e+00,0.000000000000000000e+00,1.000000009965879677e+00,0.000000000000000000e+00,-2.395889150909255772e-10,0.000000000000000000e+00 +2.657539834119015509e+01,1.398799999999999955e+02,0.000000000000000000e+00,6.891697487416882595e+00,0.000000000000000000e+00,1.000000009965531955e+00,0.000000000000000000e+00,5.336031425300962291e-10,0.000000000000000000e+00 +2.657684936251229857e+01,1.398900000000000148e+02,0.000000000000000000e+00,6.893148508753485615e+00,0.000000000000000000e+00,1.000000009966306225e+00,0.000000000000000000e+00,-5.210116232622766956e-10,0.000000000000000000e+00 +2.657830007839159592e+01,1.399000000000000057e+02,0.000000000000000000e+00,6.894599224647240732e+00,0.000000000000000000e+00,1.000000009965550385e+00,0.000000000000000000e+00,2.519875491329006024e-10,0.000000000000000000e+00 +2.657975048902086712e+01,1.399099999999999966e+02,0.000000000000000000e+00,6.896049635290967039e+00,0.000000000000000000e+00,1.000000009965915870e+00,0.000000000000000000e+00,1.783883668585501101e-10,0.000000000000000000e+00 +2.658120059459273321e+01,1.399200000000000159e+02,0.000000000000000000e+00,6.897499740877284680e+00,0.000000000000000000e+00,1.000000009966174552e+00,0.000000000000000000e+00,-4.619162656479745197e-10,0.000000000000000000e+00 +2.658265039529960916e+01,1.399300000000000068e+02,0.000000000000000000e+00,6.898949541598609514e+00,0.000000000000000000e+00,1.000000009965504866e+00,0.000000000000000000e+00,3.026984062115290267e-10,0.000000000000000000e+00 +2.658409989133370743e+01,1.399399999999999977e+02,0.000000000000000000e+00,6.900399037647154010e+00,0.000000000000000000e+00,1.000000009965943626e+00,0.000000000000000000e+00,-2.050078753950555340e-10,0.000000000000000000e+00 +2.658554908288704155e+01,1.399500000000000171e+02,0.000000000000000000e+00,6.901848229214931685e+00,0.000000000000000000e+00,1.000000009965646530e+00,0.000000000000000000e+00,4.108681195830239909e-10,0.000000000000000000e+00 +2.658699797015142252e+01,1.399600000000000080e+02,0.000000000000000000e+00,6.903297116493751773e+00,0.000000000000000000e+00,1.000000009966241832e+00,0.000000000000000000e+00,-5.288297589146272520e-10,0.000000000000000000e+00 +2.658844655331845885e+01,1.399699999999999989e+02,0.000000000000000000e+00,6.904745699675224557e+00,0.000000000000000000e+00,1.000000009965475778e+00,0.000000000000000000e+00,2.209285766159751507e-10,0.000000000000000000e+00 +2.658989483257955655e+01,1.399799999999999898e+02,0.000000000000000000e+00,6.906193978950756041e+00,0.000000000000000000e+00,1.000000009965795744e+00,0.000000000000000000e+00,-2.008862878805193374e-11,0.000000000000000000e+00 +2.659134280812592621e+01,1.399900000000000091e+02,0.000000000000000000e+00,6.907641954511555049e+00,0.000000000000000000e+00,1.000000009965766656e+00,0.000000000000000000e+00,3.016993704757327028e-10,0.000000000000000000e+00 +2.659279048014857239e+01,1.400000000000000000e+02,0.000000000000000000e+00,6.909089626548627905e+00,0.000000000000000000e+00,1.000000009966203418e+00,0.000000000000000000e+00,-2.245960576023262944e-10,0.000000000000000000e+00 +2.659423784883830066e+01,1.400099999999999909e+02,0.000000000000000000e+00,6.910536995252781978e+00,0.000000000000000000e+00,1.000000009965878345e+00,0.000000000000000000e+00,-4.683133638552548307e-10,0.000000000000000000e+00 +2.659568491438572124e+01,1.400200000000000102e+02,0.000000000000000000e+00,6.911984060814623021e+00,0.000000000000000000e+00,1.000000009965200665e+00,0.000000000000000000e+00,7.052262498295644988e-10,0.000000000000000000e+00 +2.659713167698123826e+01,1.400300000000000011e+02,0.000000000000000000e+00,6.913430823424557836e+00,0.000000000000000000e+00,1.000000009966220960e+00,0.000000000000000000e+00,-2.380924614604815669e-10,0.000000000000000000e+00 +2.659857813681506045e+01,1.400399999999999920e+02,0.000000000000000000e+00,6.914877283272796937e+00,0.000000000000000000e+00,1.000000009965876568e+00,0.000000000000000000e+00,-4.679933320742676764e-10,0.000000000000000000e+00 +2.660002429407719760e+01,1.400500000000000114e+02,0.000000000000000000e+00,6.916323440549347445e+00,0.000000000000000000e+00,1.000000009965199776e+00,0.000000000000000000e+00,7.280906862226922316e-10,0.000000000000000000e+00 +2.660147014895746054e+01,1.400600000000000023e+02,0.000000000000000000e+00,6.917769295444019306e+00,0.000000000000000000e+00,1.000000009966252490e+00,0.000000000000000000e+00,-6.127316813825654445e-10,0.000000000000000000e+00 +2.660291570164546116e+01,1.400699999999999932e+02,0.000000000000000000e+00,6.919214848146427066e+00,0.000000000000000000e+00,1.000000009965366754e+00,0.000000000000000000e+00,4.698232693030441115e-10,0.000000000000000000e+00 +2.660436095233061238e+01,1.400800000000000125e+02,0.000000000000000000e+00,6.920660098845981878e+00,0.000000000000000000e+00,1.000000009966045766e+00,0.000000000000000000e+00,-4.127563407840885983e-10,0.000000000000000000e+00 +2.660580590120213174e+01,1.400900000000000034e+02,0.000000000000000000e+00,6.922105047731902161e+00,0.000000000000000000e+00,1.000000009965449355e+00,0.000000000000000000e+00,4.283663816557494868e-10,0.000000000000000000e+00 +2.660725054844903781e+01,1.400999999999999943e+02,0.000000000000000000e+00,6.923549694993204717e+00,0.000000000000000000e+00,1.000000009966068193e+00,0.000000000000000000e+00,-5.482143231004991945e-10,0.000000000000000000e+00 +2.660869489426015022e+01,1.401100000000000136e+02,0.000000000000000000e+00,6.924994040818712726e+00,0.000000000000000000e+00,1.000000009965276382e+00,0.000000000000000000e+00,3.502783935124271199e-10,0.000000000000000000e+00 +2.661013893882409675e+01,1.401200000000000045e+02,0.000000000000000000e+00,6.926438085397048638e+00,0.000000000000000000e+00,1.000000009965782199e+00,0.000000000000000000e+00,5.998115012017743849e-12,0.000000000000000000e+00 +2.661158268232930268e+01,1.401299999999999955e+02,0.000000000000000000e+00,6.927881828916642171e+00,0.000000000000000000e+00,1.000000009965790859e+00,0.000000000000000000e+00,-1.461383844485644168e-11,0.000000000000000000e+00 +2.661302612496399789e+01,1.401400000000000148e+02,0.000000000000000000e+00,6.929325271565724087e+00,0.000000000000000000e+00,1.000000009965769765e+00,0.000000000000000000e+00,-2.757205771840749016e-10,0.000000000000000000e+00 +2.661446926691622039e+01,1.401500000000000057e+02,0.000000000000000000e+00,6.930768413532329753e+00,0.000000000000000000e+00,1.000000009965371861e+00,0.000000000000000000e+00,3.662676567419019714e-10,0.000000000000000000e+00 +2.661591210837380928e+01,1.401599999999999966e+02,0.000000000000000000e+00,6.932211255004298245e+00,0.000000000000000000e+00,1.000000009965900327e+00,0.000000000000000000e+00,-3.589554575060831883e-10,0.000000000000000000e+00 +2.661735464952440822e+01,1.401700000000000159e+02,0.000000000000000000e+00,6.933653796169275019e+00,0.000000000000000000e+00,1.000000009965382519e+00,0.000000000000000000e+00,3.992132023504109076e-10,0.000000000000000000e+00 +2.661879689055546905e+01,1.401800000000000068e+02,0.000000000000000000e+00,6.935096037214707465e+00,0.000000000000000000e+00,1.000000009965958281e+00,0.000000000000000000e+00,-4.839907773438639728e-10,0.000000000000000000e+00 +2.662023883165424110e+01,1.401899999999999977e+02,0.000000000000000000e+00,6.936537978327851128e+00,0.000000000000000000e+00,1.000000009965260395e+00,0.000000000000000000e+00,2.720029994513369587e-10,0.000000000000000000e+00 +2.662168047300778539e+01,1.402000000000000171e+02,0.000000000000000000e+00,6.937979619695763489e+00,0.000000000000000000e+00,1.000000009965652525e+00,0.000000000000000000e+00,-3.188919753320857897e-11,0.000000000000000000e+00 +2.662312181480296758e+01,1.402100000000000080e+02,0.000000000000000000e+00,6.939420961505311070e+00,0.000000000000000000e+00,1.000000009965606562e+00,0.000000000000000000e+00,1.778153577620040419e-10,0.000000000000000000e+00 +2.662456285722646143e+01,1.402199999999999989e+02,0.000000000000000000e+00,6.940862003943164105e+00,0.000000000000000000e+00,1.000000009965862802e+00,0.000000000000000000e+00,-5.175285668732852119e-10,0.000000000000000000e+00 +2.662600360046473824e+01,1.402299999999999898e+02,0.000000000000000000e+00,6.942302747195800094e+00,0.000000000000000000e+00,1.000000009965117176e+00,0.000000000000000000e+00,3.138495772889859533e-10,0.000000000000000000e+00 +2.662744404470408455e+01,1.402400000000000091e+02,0.000000000000000000e+00,6.943743191449501140e+00,0.000000000000000000e+00,1.000000009965569259e+00,0.000000000000000000e+00,3.976355620493757485e-10,0.000000000000000000e+00 +2.662888419013059149e+01,1.402500000000000000e+02,0.000000000000000000e+00,6.945183336890359271e+00,0.000000000000000000e+00,1.000000009966141912e+00,0.000000000000000000e+00,-4.026528819838388520e-10,0.000000000000000000e+00 +2.663032403693015482e+01,1.402599999999999909e+02,0.000000000000000000e+00,6.946623183704272009e+00,0.000000000000000000e+00,1.000000009965562153e+00,0.000000000000000000e+00,-7.928245429997806170e-11,0.000000000000000000e+00 +2.663176358528847842e+01,1.402700000000000102e+02,0.000000000000000000e+00,6.948062732076942360e+00,0.000000000000000000e+00,1.000000009965448022e+00,0.000000000000000000e+00,-5.276307067637185648e-11,0.000000000000000000e+00 +2.663320283539107791e+01,1.402800000000000011e+02,0.000000000000000000e+00,6.949501982193883265e+00,0.000000000000000000e+00,1.000000009965372083e+00,0.000000000000000000e+00,-2.808440948152772002e-11,0.000000000000000000e+00 +2.663464178742326993e+01,1.402899999999999920e+02,0.000000000000000000e+00,6.950940934240414926e+00,0.000000000000000000e+00,1.000000009965331671e+00,0.000000000000000000e+00,2.890823662634000344e-10,0.000000000000000000e+00 +2.663608044157018284e+01,1.403000000000000114e+02,0.000000000000000000e+00,6.952379588401665700e+00,0.000000000000000000e+00,1.000000009965747561e+00,0.000000000000000000e+00,-9.355054576712727484e-11,0.000000000000000000e+00 +2.663751879801675670e+01,1.403100000000000023e+02,0.000000000000000000e+00,6.953817944862572986e+00,0.000000000000000000e+00,1.000000009965613001e+00,0.000000000000000000e+00,-2.192562016768396364e-11,0.000000000000000000e+00 +2.663895685694773263e+01,1.403199999999999932e+02,0.000000000000000000e+00,6.955256003807881449e+00,0.000000000000000000e+00,1.000000009965581471e+00,0.000000000000000000e+00,-5.961295496059375661e-11,0.000000000000000000e+00 +2.664039461854766699e+01,1.403300000000000125e+02,0.000000000000000000e+00,6.956693765422145681e+00,0.000000000000000000e+00,1.000000009965495762e+00,0.000000000000000000e+00,-3.395242508563239871e-10,0.000000000000000000e+00 +2.664183208300092431e+01,1.403400000000000034e+02,0.000000000000000000e+00,6.958131229889729319e+00,0.000000000000000000e+00,1.000000009965007708e+00,0.000000000000000000e+00,2.944799542918779814e-10,0.000000000000000000e+00 +2.664326925049167727e+01,1.403499999999999943e+02,0.000000000000000000e+00,6.959568397394805039e+00,0.000000000000000000e+00,1.000000009965430925e+00,0.000000000000000000e+00,-1.035374192216336116e-11,0.000000000000000000e+00 +2.664470612120391024e+01,1.403600000000000136e+02,0.000000000000000000e+00,6.961005268121357226e+00,0.000000000000000000e+00,1.000000009965416048e+00,0.000000000000000000e+00,3.337066261960066317e-10,0.000000000000000000e+00 +2.664614269532141577e+01,1.403700000000000045e+02,0.000000000000000000e+00,6.962441842253178415e+00,0.000000000000000000e+00,1.000000009965895442e+00,0.000000000000000000e+00,-5.281042566171313747e-10,0.000000000000000000e+00 +2.664757897302779810e+01,1.403799999999999955e+02,0.000000000000000000e+00,6.963878119973872849e+00,0.000000000000000000e+00,1.000000009965136938e+00,0.000000000000000000e+00,2.856000522209299433e-10,0.000000000000000000e+00 +2.664901495450646962e+01,1.403900000000000148e+02,0.000000000000000000e+00,6.965314101466852925e+00,0.000000000000000000e+00,1.000000009965547054e+00,0.000000000000000000e+00,5.938984004501594372e-11,0.000000000000000000e+00 +2.665045063994065444e+01,1.404000000000000057e+02,0.000000000000000000e+00,6.966749786915345410e+00,0.000000000000000000e+00,1.000000009965632319e+00,0.000000000000000000e+00,-4.786198957321925627e-10,0.000000000000000000e+00 +2.665188602951339192e+01,1.404099999999999966e+02,0.000000000000000000e+00,6.968185176502386113e+00,0.000000000000000000e+00,1.000000009964945313e+00,0.000000000000000000e+00,6.962615660524193861e-10,0.000000000000000000e+00 +2.665332112340752602e+01,1.404200000000000159e+02,0.000000000000000000e+00,6.969620270410821661e+00,0.000000000000000000e+00,1.000000009965944514e+00,0.000000000000000000e+00,-4.292949691313467596e-10,0.000000000000000000e+00 +2.665475592180571951e+01,1.404300000000000068e+02,0.000000000000000000e+00,6.971055068823313938e+00,0.000000000000000000e+00,1.000000009965328562e+00,0.000000000000000000e+00,-1.047918259187904075e-10,0.000000000000000000e+00 +2.665619042489044332e+01,1.404399999999999977e+02,0.000000000000000000e+00,6.972489571922332097e+00,0.000000000000000000e+00,1.000000009965178238e+00,0.000000000000000000e+00,2.446161833899403898e-10,0.000000000000000000e+00 +2.665762463284398009e+01,1.404500000000000171e+02,0.000000000000000000e+00,6.973923779890160546e+00,0.000000000000000000e+00,1.000000009965529069e+00,0.000000000000000000e+00,-3.759811781372703884e-10,0.000000000000000000e+00 +2.665905854584842771e+01,1.404600000000000080e+02,0.000000000000000000e+00,6.975357692908896290e+00,0.000000000000000000e+00,1.000000009964989944e+00,0.000000000000000000e+00,4.940801332593421189e-10,0.000000000000000000e+00 +2.666049216408569222e+01,1.404699999999999989e+02,0.000000000000000000e+00,6.976791311160447151e+00,0.000000000000000000e+00,1.000000009965698267e+00,0.000000000000000000e+00,-3.008466526182826175e-10,0.000000000000000000e+00 +2.666192548773749849e+01,1.404799999999999898e+02,0.000000000000000000e+00,6.978224634826537098e+00,0.000000000000000000e+00,1.000000009965267056e+00,0.000000000000000000e+00,1.346495627810697791e-10,0.000000000000000000e+00 +2.666335851698537951e+01,1.404900000000000091e+02,0.000000000000000000e+00,6.979657664088700031e+00,0.000000000000000000e+00,1.000000009965460013e+00,0.000000000000000000e+00,-5.982209968143333697e-11,0.000000000000000000e+00 +2.666479125201068712e+01,1.405000000000000000e+02,0.000000000000000000e+00,6.981090399128285995e+00,0.000000000000000000e+00,1.000000009965374304e+00,0.000000000000000000e+00,-1.488108921235554501e-10,0.000000000000000000e+00 +2.666622369299458484e+01,1.405099999999999909e+02,0.000000000000000000e+00,6.982522840126457631e+00,0.000000000000000000e+00,1.000000009965161141e+00,0.000000000000000000e+00,1.700823383381227817e-10,0.000000000000000000e+00 +2.666765584011804791e+01,1.405200000000000102e+02,0.000000000000000000e+00,6.983954987264191949e+00,0.000000000000000000e+00,1.000000009965404724e+00,0.000000000000000000e+00,-9.831751994594512274e-11,0.000000000000000000e+00 +2.666908769356186681e+01,1.405300000000000011e+02,0.000000000000000000e+00,6.985386840722281221e+00,0.000000000000000000e+00,1.000000009965263947e+00,0.000000000000000000e+00,-2.185454052967038318e-10,0.000000000000000000e+00 +2.667051925350665087e+01,1.405399999999999920e+02,0.000000000000000000e+00,6.986818400681331198e+00,0.000000000000000000e+00,1.000000009964951087e+00,0.000000000000000000e+00,5.484147146718966232e-10,0.000000000000000000e+00 +2.667195052013282108e+01,1.405500000000000114e+02,0.000000000000000000e+00,6.988249667321762892e+00,0.000000000000000000e+00,1.000000009965736014e+00,0.000000000000000000e+00,-5.294411101730979512e-10,0.000000000000000000e+00 +2.667338149362061017e+01,1.405600000000000023e+02,0.000000000000000000e+00,6.989680640823814350e+00,0.000000000000000000e+00,1.000000009964978398e+00,0.000000000000000000e+00,3.228203423003235668e-10,0.000000000000000000e+00 +2.667481217415007322e+01,1.405699999999999932e+02,0.000000000000000000e+00,6.991111321367535325e+00,0.000000000000000000e+00,1.000000009965440251e+00,0.000000000000000000e+00,-6.085167121252674286e-11,0.000000000000000000e+00 +2.667624256190107701e+01,1.405800000000000125e+02,0.000000000000000000e+00,6.992541709132795269e+00,0.000000000000000000e+00,1.000000009965353209e+00,0.000000000000000000e+00,-7.297483957763114585e-11,0.000000000000000000e+00 +2.667767265705330715e+01,1.405900000000000034e+02,0.000000000000000000e+00,6.993971804299277117e+00,0.000000000000000000e+00,1.000000009965248848e+00,0.000000000000000000e+00,-2.768952118051972567e-10,0.000000000000000000e+00 +2.667910245978626094e+01,1.405999999999999943e+02,0.000000000000000000e+00,6.995401607046480841e+00,0.000000000000000000e+00,1.000000009964852943e+00,0.000000000000000000e+00,5.031110151870421894e-10,0.000000000000000000e+00 +2.668053197027925805e+01,1.406100000000000136e+02,0.000000000000000000e+00,6.996831117553722557e+00,0.000000000000000000e+00,1.000000009965572145e+00,0.000000000000000000e+00,-4.687237149893958712e-10,0.000000000000000000e+00 +2.668196118871142986e+01,1.406200000000000045e+02,0.000000000000000000e+00,6.998260336000137194e+00,0.000000000000000000e+00,1.000000009964902237e+00,0.000000000000000000e+00,1.569465210984363926e-10,0.000000000000000000e+00 +2.668339011526172655e+01,1.406299999999999955e+02,0.000000000000000000e+00,6.999689262564673164e+00,0.000000000000000000e+00,1.000000009965126502e+00,0.000000000000000000e+00,7.864470778735032390e-11,0.000000000000000000e+00 +2.668481875010891713e+01,1.406400000000000148e+02,0.000000000000000000e+00,7.001117897426099468e+00,0.000000000000000000e+00,1.000000009965238856e+00,0.000000000000000000e+00,3.839764330191833952e-11,0.000000000000000000e+00 +2.668624709343158585e+01,1.406500000000000057e+02,0.000000000000000000e+00,7.002546240763001251e+00,0.000000000000000000e+00,1.000000009965293701e+00,0.000000000000000000e+00,-9.142680367376965148e-11,0.000000000000000000e+00 +2.668767514540813579e+01,1.406599999999999966e+02,0.000000000000000000e+00,7.003974292753781583e+00,0.000000000000000000e+00,1.000000009965163139e+00,0.000000000000000000e+00,-2.021753116161465426e-12,0.000000000000000000e+00 +2.668910290621678882e+01,1.406700000000000159e+02,0.000000000000000000e+00,7.005402053576661459e+00,0.000000000000000000e+00,1.000000009965160253e+00,0.000000000000000000e+00,1.793505026220530026e-10,0.000000000000000000e+00 +2.669053037603558209e+01,1.406800000000000068e+02,0.000000000000000000e+00,7.006829523409680682e+00,0.000000000000000000e+00,1.000000009965416270e+00,0.000000000000000000e+00,-5.464070370878548452e-10,0.000000000000000000e+00 +2.669195755504237511e+01,1.406899999999999977e+02,0.000000000000000000e+00,7.008256702430697871e+00,0.000000000000000000e+00,1.000000009964636449e+00,0.000000000000000000e+00,3.102954307864627656e-10,0.000000000000000000e+00 +2.669338444341484617e+01,1.407000000000000171e+02,0.000000000000000000e+00,7.009683590817388676e+00,0.000000000000000000e+00,1.000000009965079206e+00,0.000000000000000000e+00,7.004080906076347908e-12,0.000000000000000000e+00 +2.669481104133049243e+01,1.407100000000000080e+02,0.000000000000000000e+00,7.011110188747251115e+00,0.000000000000000000e+00,1.000000009965089198e+00,0.000000000000000000e+00,1.612823242856309795e-10,0.000000000000000000e+00 +2.669623734896662981e+01,1.407199999999999989e+02,0.000000000000000000e+00,7.012536496397600239e+00,0.000000000000000000e+00,1.000000009965319236e+00,0.000000000000000000e+00,-2.254674857212474044e-10,0.000000000000000000e+00 +2.669766336650038951e+01,1.407299999999999898e+02,0.000000000000000000e+00,7.013962513945571686e+00,0.000000000000000000e+00,1.000000009964997716e+00,0.000000000000000000e+00,3.052528569321326683e-11,0.000000000000000000e+00 +2.669908909410872866e+01,1.407400000000000091e+02,0.000000000000000000e+00,7.015388241568119909e+00,0.000000000000000000e+00,1.000000009965041237e+00,0.000000000000000000e+00,3.674682971657004757e-10,0.000000000000000000e+00 +2.670051453196842672e+01,1.407500000000000000e+02,0.000000000000000000e+00,7.016813679442020835e+00,0.000000000000000000e+00,1.000000009965565040e+00,0.000000000000000000e+00,-6.525095061938475695e-10,0.000000000000000000e+00 +2.670193968025607489e+01,1.407599999999999909e+02,0.000000000000000000e+00,7.018238827743870978e+00,0.000000000000000000e+00,1.000000009964635117e+00,0.000000000000000000e+00,3.431513273242537621e-10,0.000000000000000000e+00 +2.670336453914809027e+01,1.407700000000000102e+02,0.000000000000000000e+00,7.019663686650084777e+00,0.000000000000000000e+00,1.000000009965124059e+00,0.000000000000000000e+00,1.684931404459520234e-10,0.000000000000000000e+00 +2.670478910882071233e+01,1.407800000000000011e+02,0.000000000000000000e+00,7.021088256336901701e+00,0.000000000000000000e+00,1.000000009965364089e+00,0.000000000000000000e+00,-4.277881643452654237e-10,0.000000000000000000e+00 +2.670621338944999579e+01,1.407899999999999920e+02,0.000000000000000000e+00,7.022512536980380027e+00,0.000000000000000000e+00,1.000000009964754799e+00,0.000000000000000000e+00,1.808800785351669924e-10,0.000000000000000000e+00 +2.670763738121182485e+01,1.408000000000000114e+02,0.000000000000000000e+00,7.023936528756398623e+00,0.000000000000000000e+00,1.000000009965012371e+00,0.000000000000000000e+00,1.185316680775119771e-10,0.000000000000000000e+00 +2.670906108428189896e+01,1.408100000000000023e+02,0.000000000000000000e+00,7.025360231840660497e+00,0.000000000000000000e+00,1.000000009965181125e+00,0.000000000000000000e+00,-3.020050300693526445e-10,0.000000000000000000e+00 +2.671048449883574349e+01,1.408199999999999932e+02,0.000000000000000000e+00,7.026783646408689243e+00,0.000000000000000000e+00,1.000000009964751246e+00,0.000000000000000000e+00,5.485872045690276545e-10,0.000000000000000000e+00 +2.671190762504870264e+01,1.408300000000000125e+02,0.000000000000000000e+00,7.028206772635829935e+00,0.000000000000000000e+00,1.000000009965531955e+00,0.000000000000000000e+00,-5.234169878725174896e-10,0.000000000000000000e+00 +2.671333046309594650e+01,1.408400000000000034e+02,0.000000000000000000e+00,7.029629610697252673e+00,0.000000000000000000e+00,1.000000009964787218e+00,0.000000000000000000e+00,3.054664332177053895e-10,0.000000000000000000e+00 +2.671475301315246398e+01,1.408499999999999943e+02,0.000000000000000000e+00,7.031052160767946368e+00,0.000000000000000000e+00,1.000000009965221759e+00,0.000000000000000000e+00,-5.987229609104599458e-10,0.000000000000000000e+00 +2.671617527539306991e+01,1.408600000000000136e+02,0.000000000000000000e+00,7.032474423022726739e+00,0.000000000000000000e+00,1.000000009964370218e+00,0.000000000000000000e+00,5.911926096572105093e-10,0.000000000000000000e+00 +2.671759724999240504e+01,1.408700000000000045e+02,0.000000000000000000e+00,7.033896397636229203e+00,0.000000000000000000e+00,1.000000009965210879e+00,0.000000000000000000e+00,-2.005400950758610664e-10,0.000000000000000000e+00 +2.671901893712492537e+01,1.408799999999999955e+02,0.000000000000000000e+00,7.035318084782916870e+00,0.000000000000000000e+00,1.000000009964925773e+00,0.000000000000000000e+00,-2.233880827260297440e-11,0.000000000000000000e+00 +2.672044033696491638e+01,1.408900000000000148e+02,0.000000000000000000e+00,7.036739484637072550e+00,0.000000000000000000e+00,1.000000009964894021e+00,0.000000000000000000e+00,1.237476270750672797e-10,0.000000000000000000e+00 +2.672186144968648591e+01,1.409000000000000057e+02,0.000000000000000000e+00,7.038160597372804972e+00,0.000000000000000000e+00,1.000000009965069880e+00,0.000000000000000000e+00,1.151772979271771781e-10,0.000000000000000000e+00 +2.672328227546356771e+01,1.409099999999999966e+02,0.000000000000000000e+00,7.039581423164047003e+00,0.000000000000000000e+00,1.000000009965233527e+00,0.000000000000000000e+00,-6.117977611245014257e-10,0.000000000000000000e+00 +2.672470281446992146e+01,1.409200000000000159e+02,0.000000000000000000e+00,7.041001962184555651e+00,0.000000000000000000e+00,1.000000009964364445e+00,0.000000000000000000e+00,4.613642088459407550e-10,0.000000000000000000e+00 +2.672612306687912564e+01,1.409300000000000068e+02,0.000000000000000000e+00,7.042422214607911179e+00,0.000000000000000000e+00,1.000000009965019698e+00,0.000000000000000000e+00,1.311971029162259245e-10,0.000000000000000000e+00 +2.672754303286458821e+01,1.409399999999999977e+02,0.000000000000000000e+00,7.043842180607522430e+00,0.000000000000000000e+00,1.000000009965205994e+00,0.000000000000000000e+00,-4.047754034933130813e-10,0.000000000000000000e+00 +2.672896271259953949e+01,1.409500000000000171e+02,0.000000000000000000e+00,7.045261860356620609e+00,0.000000000000000000e+00,1.000000009964631342e+00,0.000000000000000000e+00,5.381406609134392092e-11,0.000000000000000000e+00 +2.673038210625703570e+01,1.409600000000000080e+02,0.000000000000000000e+00,7.046681254028261954e+00,0.000000000000000000e+00,1.000000009964707726e+00,0.000000000000000000e+00,5.039826404923405111e-10,0.000000000000000000e+00 +2.673180121400996256e+01,1.409699999999999989e+02,0.000000000000000000e+00,7.048100361795330393e+00,0.000000000000000000e+00,1.000000009965422931e+00,0.000000000000000000e+00,-4.998586557019965193e-10,0.000000000000000000e+00 +2.673322003603102814e+01,1.409799999999999898e+02,0.000000000000000000e+00,7.049519183830535773e+00,0.000000000000000000e+00,1.000000009964713721e+00,0.000000000000000000e+00,8.922253901884959332e-12,0.000000000000000000e+00 +2.673463857249276998e+01,1.409900000000000091e+02,0.000000000000000000e+00,7.050937720306411194e+00,0.000000000000000000e+00,1.000000009964726377e+00,0.000000000000000000e+00,1.440372866019922953e-10,0.000000000000000000e+00 +2.673605682356754443e+01,1.410000000000000000e+02,0.000000000000000000e+00,7.052355971395319223e+00,0.000000000000000000e+00,1.000000009964930658e+00,0.000000000000000000e+00,-2.159427944138180427e-10,0.000000000000000000e+00 +2.673747478942754441e+01,1.410099999999999909e+02,0.000000000000000000e+00,7.053773937269448346e+00,0.000000000000000000e+00,1.000000009964624459e+00,0.000000000000000000e+00,1.325049570273229840e-10,0.000000000000000000e+00 +2.673889247024478166e+01,1.410200000000000102e+02,0.000000000000000000e+00,7.055191618100812967e+00,0.000000000000000000e+00,1.000000009964812309e+00,0.000000000000000000e+00,1.857948741316742755e-10,0.000000000000000000e+00 +2.674030986619110095e+01,1.410300000000000011e+02,0.000000000000000000e+00,7.056609014061256069e+00,0.000000000000000000e+00,1.000000009965075654e+00,0.000000000000000000e+00,-1.779977907284366344e-10,0.000000000000000000e+00 +2.674172697743816940e+01,1.410399999999999920e+02,0.000000000000000000e+00,7.058026125322447442e+00,0.000000000000000000e+00,1.000000009964823411e+00,0.000000000000000000e+00,-1.949592598449428784e-10,0.000000000000000000e+00 +2.674314380415748715e+01,1.410500000000000114e+02,0.000000000000000000e+00,7.059442952055883680e+00,0.000000000000000000e+00,1.000000009964547187e+00,0.000000000000000000e+00,1.551836109067244883e-11,0.000000000000000000e+00 +2.674456034652037673e+01,1.410600000000000023e+02,0.000000000000000000e+00,7.060859494432889960e+00,0.000000000000000000e+00,1.000000009964569170e+00,0.000000000000000000e+00,3.325358430326588295e-10,0.000000000000000000e+00 +2.674597660469799365e+01,1.410699999999999932e+02,0.000000000000000000e+00,7.062275752624620040e+00,0.000000000000000000e+00,1.000000009965040126e+00,0.000000000000000000e+00,-2.494911104916790677e-10,0.000000000000000000e+00 +2.674739257886131938e+01,1.410800000000000125e+02,0.000000000000000000e+00,7.063691726802056259e+00,0.000000000000000000e+00,1.000000009964686853e+00,0.000000000000000000e+00,-7.889326833113572587e-11,0.000000000000000000e+00 +2.674880826918116483e+01,1.410900000000000034e+02,0.000000000000000000e+00,7.065107417136007761e+00,0.000000000000000000e+00,1.000000009964575165e+00,0.000000000000000000e+00,2.820646635373189644e-10,0.000000000000000000e+00 +2.675022367582816685e+01,1.410999999999999943e+02,0.000000000000000000e+00,7.066522823797114050e+00,0.000000000000000000e+00,1.000000009964974401e+00,0.000000000000000000e+00,-1.730698845269932664e-10,0.000000000000000000e+00 +2.675163879897279529e+01,1.411100000000000136e+02,0.000000000000000000e+00,7.067937946955844097e+00,0.000000000000000000e+00,1.000000009964729486e+00,0.000000000000000000e+00,-2.339971656198073165e-10,0.000000000000000000e+00 +2.675305363878534592e+01,1.411200000000000045e+02,0.000000000000000000e+00,7.069352786782494569e+00,0.000000000000000000e+00,1.000000009964398417e+00,0.000000000000000000e+00,4.249209427391645166e-10,0.000000000000000000e+00 +2.675446819543594756e+01,1.411299999999999955e+02,0.000000000000000000e+00,7.070767343447192488e+00,0.000000000000000000e+00,1.000000009964999492e+00,0.000000000000000000e+00,-9.106149299496761014e-11,0.000000000000000000e+00 +2.675588246909455847e+01,1.411400000000000148e+02,0.000000000000000000e+00,7.072181617119896124e+00,0.000000000000000000e+00,1.000000009964870706e+00,0.000000000000000000e+00,-1.256271818505165195e-10,0.000000000000000000e+00 +2.675729645993096284e+01,1.411500000000000057e+02,0.000000000000000000e+00,7.073595607970391441e+00,0.000000000000000000e+00,1.000000009964693071e+00,0.000000000000000000e+00,-2.409382840490654736e-10,0.000000000000000000e+00 +2.675871016811478142e+01,1.411599999999999966e+02,0.000000000000000000e+00,7.075009316168295648e+00,0.000000000000000000e+00,1.000000009964352454e+00,0.000000000000000000e+00,3.330451414712951069e-10,0.000000000000000000e+00 +2.676012359381545735e+01,1.411700000000000159e+02,0.000000000000000000e+00,7.076422741883056311e+00,0.000000000000000000e+00,1.000000009964823189e+00,0.000000000000000000e+00,-3.001147649727506438e-10,0.000000000000000000e+00 +2.676153673720227388e+01,1.411800000000000068e+02,0.000000000000000000e+00,7.077835885283953132e+00,0.000000000000000000e+00,1.000000009964399084e+00,0.000000000000000000e+00,4.092434090558908592e-10,0.000000000000000000e+00 +2.676294959844433663e+01,1.411899999999999977e+02,0.000000000000000000e+00,7.079248746540094395e+00,0.000000000000000000e+00,1.000000009964977288e+00,0.000000000000000000e+00,-3.256995429541625860e-10,0.000000000000000000e+00 +2.676436217771058779e+01,1.412000000000000171e+02,0.000000000000000000e+00,7.080661325820422292e+00,0.000000000000000000e+00,1.000000009964517211e+00,0.000000000000000000e+00,4.653779034231242326e-11,0.000000000000000000e+00 +2.676577447516979902e+01,1.412100000000000080e+02,0.000000000000000000e+00,7.082073623293707598e+00,0.000000000000000000e+00,1.000000009964582937e+00,0.000000000000000000e+00,7.375194964353568367e-11,0.000000000000000000e+00 +2.676718649099057501e+01,1.412199999999999989e+02,0.000000000000000000e+00,7.083485639128555000e+00,0.000000000000000000e+00,1.000000009964687075e+00,0.000000000000000000e+00,8.304646786827244722e-11,0.000000000000000000e+00 +2.676859822534135347e+01,1.412299999999999898e+02,0.000000000000000000e+00,7.084897373493400430e+00,0.000000000000000000e+00,1.000000009964804315e+00,0.000000000000000000e+00,-4.294735640372633559e-11,0.000000000000000000e+00 +2.677000967839040158e+01,1.412400000000000091e+02,0.000000000000000000e+00,7.086308826556511953e+00,0.000000000000000000e+00,1.000000009964743697e+00,0.000000000000000000e+00,-4.216917405302267691e-10,0.000000000000000000e+00 +2.677142085030581597e+01,1.412500000000000000e+02,0.000000000000000000e+00,7.087719998485989770e+00,0.000000000000000000e+00,1.000000009964148617e+00,0.000000000000000000e+00,6.139354738830837199e-10,0.000000000000000000e+00 +2.677283174125553344e+01,1.412599999999999909e+02,0.000000000000000000e+00,7.089130889449766215e+00,0.000000000000000000e+00,1.000000009965014813e+00,0.000000000000000000e+00,-6.217707907058350964e-10,0.000000000000000000e+00 +2.677424235140732023e+01,1.412700000000000102e+02,0.000000000000000000e+00,7.090541499615609311e+00,0.000000000000000000e+00,1.000000009964137737e+00,0.000000000000000000e+00,2.163248251745708032e-10,0.000000000000000000e+00 +2.677565268092877560e+01,1.412800000000000011e+02,0.000000000000000000e+00,7.091951829151115660e+00,0.000000000000000000e+00,1.000000009964442826e+00,0.000000000000000000e+00,3.346300489358826794e-10,0.000000000000000000e+00 +2.677706272998732828e+01,1.412899999999999920e+02,0.000000000000000000e+00,7.093361878223719330e+00,0.000000000000000000e+00,1.000000009964914671e+00,0.000000000000000000e+00,-3.847829403658252843e-10,0.000000000000000000e+00 +2.677847249875024715e+01,1.413000000000000114e+02,0.000000000000000000e+00,7.094771647000686521e+00,0.000000000000000000e+00,1.000000009964372216e+00,0.000000000000000000e+00,1.758097036409004705e-10,0.000000000000000000e+00 +2.677988198738463055e+01,1.413100000000000023e+02,0.000000000000000000e+00,7.096181135649115568e+00,0.000000000000000000e+00,1.000000009964620018e+00,0.000000000000000000e+00,1.136057159190742497e-10,0.000000000000000000e+00 +2.678129119605741337e+01,1.413199999999999932e+02,0.000000000000000000e+00,7.097590344335941381e+00,0.000000000000000000e+00,1.000000009964780112e+00,0.000000000000000000e+00,-2.414403878497375621e-10,0.000000000000000000e+00 +2.678270012493536356e+01,1.413300000000000125e+02,0.000000000000000000e+00,7.098999273227931894e+00,0.000000000000000000e+00,1.000000009964439940e+00,0.000000000000000000e+00,-1.098677258823925431e-10,0.000000000000000000e+00 +2.678410877418508562e+01,1.413400000000000034e+02,0.000000000000000000e+00,7.100407922491688950e+00,0.000000000000000000e+00,1.000000009964285175e+00,0.000000000000000000e+00,-5.486593306407678194e-11,0.000000000000000000e+00 +2.678551714397301353e+01,1.413499999999999943e+02,0.000000000000000000e+00,7.101816292293650079e+00,0.000000000000000000e+00,1.000000009964207903e+00,0.000000000000000000e+00,2.559341148432058396e-10,0.000000000000000000e+00 +2.678692523446542140e+01,1.413600000000000136e+02,0.000000000000000000e+00,7.103224382800087611e+00,0.000000000000000000e+00,1.000000009964568282e+00,0.000000000000000000e+00,2.599279410121400854e-10,0.000000000000000000e+00 +2.678833304582841635e+01,1.413700000000000045e+02,0.000000000000000000e+00,7.104632194177109561e+00,0.000000000000000000e+00,1.000000009964934211e+00,0.000000000000000000e+00,-6.078281843216881570e-10,0.000000000000000000e+00 +2.678974057822793853e+01,1.413799999999999955e+02,0.000000000000000000e+00,7.106039726590658745e+00,0.000000000000000000e+00,1.000000009964078673e+00,0.000000000000000000e+00,2.283160212973963136e-10,0.000000000000000000e+00 +2.679114783182976822e+01,1.413900000000000148e+02,0.000000000000000000e+00,7.107446980206511888e+00,0.000000000000000000e+00,1.000000009964399972e+00,0.000000000000000000e+00,-3.677136698217158253e-11,0.000000000000000000e+00 +2.679255480679952228e+01,1.414000000000000057e+02,0.000000000000000000e+00,7.108853955190284957e+00,0.000000000000000000e+00,1.000000009964348235e+00,0.000000000000000000e+00,2.765501634248352721e-10,0.000000000000000000e+00 +2.679396150330264703e+01,1.414099999999999966e+02,0.000000000000000000e+00,7.110260651707427826e+00,0.000000000000000000e+00,1.000000009964737258e+00,0.000000000000000000e+00,-2.933401142184966501e-10,0.000000000000000000e+00 +2.679536792150443247e+01,1.414200000000000159e+02,0.000000000000000000e+00,7.111667069923227835e+00,0.000000000000000000e+00,1.000000009964324699e+00,0.000000000000000000e+00,-6.442757803989788238e-11,0.000000000000000000e+00 +2.679677406157000163e+01,1.414300000000000068e+02,0.000000000000000000e+00,7.113073210002807123e+00,0.000000000000000000e+00,1.000000009964234104e+00,0.000000000000000000e+00,4.002249090839152488e-10,0.000000000000000000e+00 +2.679817992366431412e+01,1.414399999999999977e+02,0.000000000000000000e+00,7.114479072111126179e+00,0.000000000000000000e+00,1.000000009964796766e+00,0.000000000000000000e+00,-3.616005849429974772e-10,0.000000000000000000e+00 +2.679958550795216610e+01,1.414500000000000171e+02,0.000000000000000000e+00,7.115884656412982956e+00,0.000000000000000000e+00,1.000000009964288505e+00,0.000000000000000000e+00,-2.170980177387579949e-10,0.000000000000000000e+00 +2.680099081459819033e+01,1.414600000000000080e+02,0.000000000000000000e+00,7.117289963073010206e+00,0.000000000000000000e+00,1.000000009963983416e+00,0.000000000000000000e+00,2.719792397176379185e-10,0.000000000000000000e+00 +2.680239584376685968e+01,1.414699999999999989e+02,0.000000000000000000e+00,7.118694992255679921e+00,0.000000000000000000e+00,1.000000009964365555e+00,0.000000000000000000e+00,9.120453304881708999e-11,0.000000000000000000e+00 +2.680380059562248363e+01,1.414799999999999898e+02,0.000000000000000000e+00,7.120099744125302443e+00,0.000000000000000000e+00,1.000000009964493675e+00,0.000000000000000000e+00,2.766714535744458820e-11,0.000000000000000000e+00 +2.680520507032921174e+01,1.414900000000000091e+02,0.000000000000000000e+00,7.121504218846024692e+00,0.000000000000000000e+00,1.000000009964532532e+00,0.000000000000000000e+00,-3.210021929213586297e-11,0.000000000000000000e+00 +2.680660926805102662e+01,1.415000000000000000e+02,0.000000000000000000e+00,7.122908416581831936e+00,0.000000000000000000e+00,1.000000009964487457e+00,0.000000000000000000e+00,-2.014962712843016678e-10,0.000000000000000000e+00 +2.680801318895175456e+01,1.415099999999999909e+02,0.000000000000000000e+00,7.124312337496547798e+00,0.000000000000000000e+00,1.000000009964204573e+00,0.000000000000000000e+00,-1.425305521626094459e-10,0.000000000000000000e+00 +2.680941683319505486e+01,1.415200000000000102e+02,0.000000000000000000e+00,7.125715981753834249e+00,0.000000000000000000e+00,1.000000009964004510e+00,0.000000000000000000e+00,4.832120616588266607e-10,0.000000000000000000e+00 +2.681082020094443052e+01,1.415300000000000011e+02,0.000000000000000000e+00,7.127119349517192504e+00,0.000000000000000000e+00,1.000000009964682635e+00,0.000000000000000000e+00,-2.410205983530629753e-10,0.000000000000000000e+00 +2.681222329236322111e+01,1.415399999999999920e+02,0.000000000000000000e+00,7.128522440949963901e+00,0.000000000000000000e+00,1.000000009964344461e+00,0.000000000000000000e+00,-1.725306444518950318e-10,0.000000000000000000e+00 +2.681362610761460630e+01,1.415500000000000114e+02,0.000000000000000000e+00,7.129925256215326357e+00,0.000000000000000000e+00,1.000000009964102432e+00,0.000000000000000000e+00,1.253863857835777188e-10,0.000000000000000000e+00 +2.681502864686160237e+01,1.415600000000000023e+02,0.000000000000000000e+00,7.131327795476298803e+00,0.000000000000000000e+00,1.000000009964278291e+00,0.000000000000000000e+00,8.930786946967101018e-11,0.000000000000000000e+00 +2.681643091026707282e+01,1.415699999999999932e+02,0.000000000000000000e+00,7.132730058895740299e+00,0.000000000000000000e+00,1.000000009964403525e+00,0.000000000000000000e+00,-3.929368669579676152e-10,0.000000000000000000e+00 +2.681783289799371062e+01,1.415800000000000125e+02,0.000000000000000000e+00,7.134132046636349145e+00,0.000000000000000000e+00,1.000000009963852632e+00,0.000000000000000000e+00,3.738465454996960560e-10,0.000000000000000000e+00 +2.681923461020405952e+01,1.415900000000000034e+02,0.000000000000000000e+00,7.135533758860662878e+00,0.000000000000000000e+00,1.000000009964376657e+00,0.000000000000000000e+00,1.869599993810218655e-11,0.000000000000000000e+00 +2.682063604706049276e+01,1.415999999999999943e+02,0.000000000000000000e+00,7.136935195731061832e+00,0.000000000000000000e+00,1.000000009964402858e+00,0.000000000000000000e+00,-2.142538676392556977e-10,0.000000000000000000e+00 +2.682203720872523434e+01,1.416100000000000136e+02,0.000000000000000000e+00,7.138336357409764688e+00,0.000000000000000000e+00,1.000000009964102654e+00,0.000000000000000000e+00,1.600879367066068542e-11,0.000000000000000000e+00 +2.682343809536034129e+01,1.416200000000000045e+02,0.000000000000000000e+00,7.139737244058831145e+00,0.000000000000000000e+00,1.000000009964125081e+00,0.000000000000000000e+00,1.464854285318031273e-10,0.000000000000000000e+00 +2.682483870712771790e+01,1.416299999999999955e+02,0.000000000000000000e+00,7.141137855840162807e+00,0.000000000000000000e+00,1.000000009964330250e+00,0.000000000000000000e+00,6.548739183069833814e-11,0.000000000000000000e+00 +2.682623904418910499e+01,1.416400000000000148e+02,0.000000000000000000e+00,7.142538192915502293e+00,0.000000000000000000e+00,1.000000009964421954e+00,0.000000000000000000e+00,-3.379685173743970548e-10,0.000000000000000000e+00 +2.682763910670608354e+01,1.416500000000000057e+02,0.000000000000000000e+00,7.143938255446433239e+00,0.000000000000000000e+00,1.000000009963948777e+00,0.000000000000000000e+00,1.846421710935885469e-10,0.000000000000000000e+00 +2.682903889484008175e+01,1.416599999999999966e+02,0.000000000000000000e+00,7.145338043594380295e+00,0.000000000000000000e+00,1.000000009964207237e+00,0.000000000000000000e+00,1.631008108308190182e-10,0.000000000000000000e+00 +2.683043840875236796e+01,1.416700000000000159e+02,0.000000000000000000e+00,7.146737557520611794e+00,0.000000000000000000e+00,1.000000009964435499e+00,0.000000000000000000e+00,-5.132016869473877915e-10,0.000000000000000000e+00 +2.683183764860405063e+01,1.416800000000000068e+02,0.000000000000000000e+00,7.148136797386237085e+00,0.000000000000000000e+00,1.000000009963717407e+00,0.000000000000000000e+00,3.131555881551017352e-10,0.000000000000000000e+00 +2.683323661455608189e+01,1.416899999999999977e+02,0.000000000000000000e+00,7.149535763352206530e+00,0.000000000000000000e+00,1.000000009964155501e+00,0.000000000000000000e+00,2.641626364367615403e-10,0.000000000000000000e+00 +2.683463530676925402e+01,1.417000000000000171e+02,0.000000000000000000e+00,7.150934455579315951e+00,0.000000000000000000e+00,1.000000009964524983e+00,0.000000000000000000e+00,-3.174065005651772166e-10,0.000000000000000000e+00 +2.683603372540420651e+01,1.417100000000000080e+02,0.000000000000000000e+00,7.152332874228202186e+00,0.000000000000000000e+00,1.000000009964081116e+00,0.000000000000000000e+00,-1.793006590978505451e-10,0.000000000000000000e+00 +2.683743187062141544e+01,1.417199999999999989e+02,0.000000000000000000e+00,7.153731019459343976e+00,0.000000000000000000e+00,1.000000009963830427e+00,0.000000000000000000e+00,1.154801243773860507e-10,0.000000000000000000e+00 +2.683882974258120768e+01,1.417299999999999898e+02,0.000000000000000000e+00,7.155128891433064631e+00,0.000000000000000000e+00,1.000000009963991854e+00,0.000000000000000000e+00,4.575622371511484257e-10,0.000000000000000000e+00 +2.684022734144375022e+01,1.417400000000000091e+02,0.000000000000000000e+00,7.156526490309531141e+00,0.000000000000000000e+00,1.000000009964631342e+00,0.000000000000000000e+00,-6.275229915749211793e-10,0.000000000000000000e+00 +2.684162466736905017e+01,1.417500000000000000e+02,0.000000000000000000e+00,7.157923816248754179e+00,0.000000000000000000e+00,1.000000009963754488e+00,0.000000000000000000e+00,3.897155753094671478e-10,0.000000000000000000e+00 +2.684302172051696189e+01,1.417599999999999909e+02,0.000000000000000000e+00,7.159320869410585431e+00,0.000000000000000000e+00,1.000000009964298942e+00,0.000000000000000000e+00,-2.390891615265626782e-10,0.000000000000000000e+00 +2.684441850104718341e+01,1.417700000000000102e+02,0.000000000000000000e+00,7.160717649954724706e+00,0.000000000000000000e+00,1.000000009963964986e+00,0.000000000000000000e+00,1.076429134498757187e-10,0.000000000000000000e+00 +2.684581500911925644e+01,1.417800000000000011e+02,0.000000000000000000e+00,7.162114158040712830e+00,0.000000000000000000e+00,1.000000009964115311e+00,0.000000000000000000e+00,-4.500573928479848914e-11,0.000000000000000000e+00 +2.684721124489256994e+01,1.417899999999999920e+02,0.000000000000000000e+00,7.163510393827936973e+00,0.000000000000000000e+00,1.000000009964052472e+00,0.000000000000000000e+00,-3.502542675273083245e-10,0.000000000000000000e+00 +2.684860720852635296e+01,1.418000000000000114e+02,0.000000000000000000e+00,7.164906357475627985e+00,0.000000000000000000e+00,1.000000009963563530e+00,0.000000000000000000e+00,4.510283152168926846e-10,0.000000000000000000e+00 +2.685000290017968183e+01,1.418100000000000023e+02,0.000000000000000000e+00,7.166302049142861286e+00,0.000000000000000000e+00,1.000000009964193026e+00,0.000000000000000000e+00,-2.896054447241171416e-11,0.000000000000000000e+00 +2.685139832001147653e+01,1.418199999999999932e+02,0.000000000000000000e+00,7.167697468988559528e+00,0.000000000000000000e+00,1.000000009964152614e+00,0.000000000000000000e+00,-7.528024654383155834e-11,0.000000000000000000e+00 +2.685279346818050428e+01,1.418300000000000125e+02,0.000000000000000000e+00,7.169092617171488158e+00,0.000000000000000000e+00,1.000000009964047587e+00,0.000000000000000000e+00,-2.515136173804266773e-10,0.000000000000000000e+00 +2.685418834484537598e+01,1.418400000000000034e+02,0.000000000000000000e+00,7.170487493850258964e+00,0.000000000000000000e+00,1.000000009963696757e+00,0.000000000000000000e+00,2.475821337485840270e-10,0.000000000000000000e+00 +2.685558295016454977e+01,1.418499999999999943e+02,0.000000000000000000e+00,7.171882099183329196e+00,0.000000000000000000e+00,1.000000009964042036e+00,0.000000000000000000e+00,-5.605521600032874213e-11,0.000000000000000000e+00 +2.685697728429633102e+01,1.418600000000000136e+02,0.000000000000000000e+00,7.173276433329003332e+00,0.000000000000000000e+00,1.000000009963963876e+00,0.000000000000000000e+00,1.005048806275299619e-10,0.000000000000000000e+00 +2.685837134739886878e+01,1.418700000000000045e+02,0.000000000000000000e+00,7.174670496445430423e+00,0.000000000000000000e+00,1.000000009964103986e+00,0.000000000000000000e+00,-3.046001226626163057e-10,0.000000000000000000e+00 +2.685976513963015577e+01,1.418799999999999955e+02,0.000000000000000000e+00,7.176064288690606752e+00,0.000000000000000000e+00,1.000000009963679437e+00,0.000000000000000000e+00,4.502966373074380397e-10,0.000000000000000000e+00 +2.686115866114803907e+01,1.418900000000000148e+02,0.000000000000000000e+00,7.177457810222374057e+00,0.000000000000000000e+00,1.000000009964306935e+00,0.000000000000000000e+00,-4.859239424918731041e-10,0.000000000000000000e+00 +2.686255191211020588e+01,1.419000000000000057e+02,0.000000000000000000e+00,7.178851061198423089e+00,0.000000000000000000e+00,1.000000009963629921e+00,0.000000000000000000e+00,4.391539281911972889e-10,0.000000000000000000e+00 +2.686394489267419061e+01,1.419099999999999966e+02,0.000000000000000000e+00,7.180244041776288277e+00,0.000000000000000000e+00,1.000000009964241654e+00,0.000000000000000000e+00,-8.418085904033656941e-11,0.000000000000000000e+00 +2.686533760299737850e+01,1.419200000000000159e+02,0.000000000000000000e+00,7.181636752113354838e+00,0.000000000000000000e+00,1.000000009964124414e+00,0.000000000000000000e+00,-3.324832104779927310e-10,0.000000000000000000e+00 +2.686673004323700198e+01,1.419300000000000068e+02,0.000000000000000000e+00,7.183029192366852556e+00,0.000000000000000000e+00,1.000000009963661451e+00,0.000000000000000000e+00,4.625363349633787340e-11,0.000000000000000000e+00 +2.686812221355013719e+01,1.419399999999999977e+02,0.000000000000000000e+00,7.184421362693859336e+00,0.000000000000000000e+00,1.000000009963725844e+00,0.000000000000000000e+00,2.919329465662592851e-11,0.000000000000000000e+00 +2.686951411409371104e+01,1.419500000000000171e+02,0.000000000000000000e+00,7.185813263251302097e+00,0.000000000000000000e+00,1.000000009963766479e+00,0.000000000000000000e+00,4.272939317703669590e-10,0.000000000000000000e+00 +2.687090574502449769e+01,1.419600000000000080e+02,0.000000000000000000e+00,7.187204894195954985e+00,0.000000000000000000e+00,1.000000009964361114e+00,0.000000000000000000e+00,-7.009105272916789414e-10,0.000000000000000000e+00 +2.687229710649911851e+01,1.419699999999999989e+02,0.000000000000000000e+00,7.188596255684441161e+00,0.000000000000000000e+00,1.000000009963385894e+00,0.000000000000000000e+00,6.673666274052225371e-10,0.000000000000000000e+00 +2.687368819867404568e+01,1.419799999999999898e+02,0.000000000000000000e+00,7.189987347873229240e+00,0.000000000000000000e+00,1.000000009964314263e+00,0.000000000000000000e+00,-6.211973329189820173e-10,0.000000000000000000e+00 +2.687507902170559859e+01,1.419900000000000091e+02,0.000000000000000000e+00,7.191378170918641288e+00,0.000000000000000000e+00,1.000000009963450287e+00,0.000000000000000000e+00,3.768463870594372289e-10,0.000000000000000000e+00 +2.687646957574994389e+01,1.420000000000000000e+02,0.000000000000000000e+00,7.192768724976843053e+00,0.000000000000000000e+00,1.000000009963974312e+00,0.000000000000000000e+00,-1.173879885043134044e-10,0.000000000000000000e+00 +2.687785986096310253e+01,1.420099999999999909e+02,0.000000000000000000e+00,7.194159010203853732e+00,0.000000000000000000e+00,1.000000009963811110e+00,0.000000000000000000e+00,8.705961863777700311e-11,0.000000000000000000e+00 +2.687924987750093919e+01,1.420200000000000102e+02,0.000000000000000000e+00,7.195549026755538868e+00,0.000000000000000000e+00,1.000000009963932124e+00,0.000000000000000000e+00,-3.387193622633009088e-11,0.000000000000000000e+00 +2.688063962551916930e+01,1.420300000000000011e+02,0.000000000000000000e+00,7.196938774787614790e+00,0.000000000000000000e+00,1.000000009963885050e+00,0.000000000000000000e+00,-1.260854685837793007e-10,0.000000000000000000e+00 +2.688202910517335553e+01,1.420399999999999920e+02,0.000000000000000000e+00,7.198328254455646835e+00,0.000000000000000000e+00,1.000000009963709857e+00,0.000000000000000000e+00,-2.945758964081725720e-10,0.000000000000000000e+00 +2.688341831661891845e+01,1.420500000000000114e+02,0.000000000000000000e+00,7.199717465915050241e+00,0.000000000000000000e+00,1.000000009963300629e+00,0.000000000000000000e+00,2.765679067103352255e-10,0.000000000000000000e+00 +2.688480726001111876e+01,1.420600000000000023e+02,0.000000000000000000e+00,7.201106409321090140e+00,0.000000000000000000e+00,1.000000009963684766e+00,0.000000000000000000e+00,1.018541869232677368e-10,0.000000000000000000e+00 +2.688619593550507503e+01,1.420699999999999932e+02,0.000000000000000000e+00,7.202495084828883343e+00,0.000000000000000000e+00,1.000000009963826209e+00,0.000000000000000000e+00,-3.358477868729149460e-12,0.000000000000000000e+00 +2.688758434325575308e+01,1.420800000000000125e+02,0.000000000000000000e+00,7.203883492593395665e+00,0.000000000000000000e+00,1.000000009963821546e+00,0.000000000000000000e+00,-1.428428033386697573e-10,0.000000000000000000e+00 +2.688897248341796953e+01,1.420900000000000034e+02,0.000000000000000000e+00,7.205271632769443713e+00,0.000000000000000000e+00,1.000000009963623260e+00,0.000000000000000000e+00,3.935733564966533305e-11,0.000000000000000000e+00 +2.689036035614639175e+01,1.420999999999999943e+02,0.000000000000000000e+00,7.206659505511694874e+00,0.000000000000000000e+00,1.000000009963677883e+00,0.000000000000000000e+00,4.400549622509055965e-10,0.000000000000000000e+00 +2.689174796159553793e+01,1.421100000000000136e+02,0.000000000000000000e+00,7.208047110974668215e+00,0.000000000000000000e+00,1.000000009964288505e+00,0.000000000000000000e+00,-4.297363907605374663e-10,0.000000000000000000e+00 +2.689313529991978058e+01,1.421200000000000045e+02,0.000000000000000000e+00,7.209434449312734472e+00,0.000000000000000000e+00,1.000000009963692316e+00,0.000000000000000000e+00,-3.665868695029974601e-10,0.000000000000000000e+00 +2.689452237127333944e+01,1.421299999999999955e+02,0.000000000000000000e+00,7.210821520680113395e+00,0.000000000000000000e+00,1.000000009963183834e+00,0.000000000000000000e+00,5.262894639751610070e-10,0.000000000000000000e+00 +2.689590917581028862e+01,1.421400000000000148e+02,0.000000000000000000e+00,7.212208325230878181e+00,0.000000000000000000e+00,1.000000009963913694e+00,0.000000000000000000e+00,-1.633460587177170322e-10,0.000000000000000000e+00 +2.689729571368454941e+01,1.421500000000000057e+02,0.000000000000000000e+00,7.213594863118955480e+00,0.000000000000000000e+00,1.000000009963687209e+00,0.000000000000000000e+00,-2.304903603096026120e-10,0.000000000000000000e+00 +2.689868198504990104e+01,1.421599999999999966e+02,0.000000000000000000e+00,7.214981134498120952e+00,0.000000000000000000e+00,1.000000009963367686e+00,0.000000000000000000e+00,2.223642118145050805e-10,0.000000000000000000e+00 +2.690006799005997351e+01,1.421700000000000159e+02,0.000000000000000000e+00,7.216367139522003704e+00,0.000000000000000000e+00,1.000000009963675884e+00,0.000000000000000000e+00,1.676063738451641881e-10,0.000000000000000000e+00 +2.690145372886824759e+01,1.421800000000000068e+02,0.000000000000000000e+00,7.217752878344086298e+00,0.000000000000000000e+00,1.000000009963908143e+00,0.000000000000000000e+00,-3.622018575079629477e-11,0.000000000000000000e+00 +2.690283920162805842e+01,1.421899999999999977e+02,0.000000000000000000e+00,7.219138351117702967e+00,0.000000000000000000e+00,1.000000009963857961e+00,0.000000000000000000e+00,-4.917914178388185262e-10,0.000000000000000000e+00 +2.690422440849259544e+01,1.422000000000000171e+02,0.000000000000000000e+00,7.220523557996040509e+00,0.000000000000000000e+00,1.000000009963176728e+00,0.000000000000000000e+00,5.497641293399007362e-10,0.000000000000000000e+00 +2.690560934961489536e+01,1.422100000000000080e+02,0.000000000000000000e+00,7.221908499132138282e+00,0.000000000000000000e+00,1.000000009963938119e+00,0.000000000000000000e+00,-2.551305038815783506e-10,0.000000000000000000e+00 +2.690699402514785277e+01,1.422199999999999989e+02,0.000000000000000000e+00,7.223293174678891759e+00,0.000000000000000000e+00,1.000000009963584846e+00,0.000000000000000000e+00,-2.311210215369348655e-10,0.000000000000000000e+00 +2.690837843524421302e+01,1.422299999999999898e+02,0.000000000000000000e+00,7.224677584789046314e+00,0.000000000000000000e+00,1.000000009963264880e+00,0.000000000000000000e+00,5.212048009401916813e-10,0.000000000000000000e+00 +2.690976258005657940e+01,1.422400000000000091e+02,0.000000000000000000e+00,7.226061729615202545e+00,0.000000000000000000e+00,1.000000009963986303e+00,0.000000000000000000e+00,-4.192579461267281525e-10,0.000000000000000000e+00 +2.691114645973740593e+01,1.422500000000000000e+02,0.000000000000000000e+00,7.227445609309816277e+00,0.000000000000000000e+00,1.000000009963406100e+00,0.000000000000000000e+00,9.099302778989106169e-11,0.000000000000000000e+00 +2.691253007443899747e+01,1.422599999999999909e+02,0.000000000000000000e+00,7.228829224025194122e+00,0.000000000000000000e+00,1.000000009963531999e+00,0.000000000000000000e+00,9.566530273550401063e-11,0.000000000000000000e+00 +2.691391342431352030e+01,1.422700000000000102e+02,0.000000000000000000e+00,7.230212573913499696e+00,0.000000000000000000e+00,1.000000009963664338e+00,0.000000000000000000e+00,-4.382823065981223303e-11,0.000000000000000000e+00 +2.691529650951299146e+01,1.422800000000000011e+02,0.000000000000000000e+00,7.231595659126750064e+00,0.000000000000000000e+00,1.000000009963603720e+00,0.000000000000000000e+00,-4.293740206163782929e-10,0.000000000000000000e+00 +2.691667933018927883e+01,1.422899999999999920e+02,0.000000000000000000e+00,7.232978479816816630e+00,0.000000000000000000e+00,1.000000009963009973e+00,0.000000000000000000e+00,6.955775909941815622e-10,0.000000000000000000e+00 +2.691806188649411169e+01,1.423000000000000114e+02,0.000000000000000000e+00,7.234361036135425138e+00,0.000000000000000000e+00,1.000000009963971648e+00,0.000000000000000000e+00,-4.868849390443957312e-10,0.000000000000000000e+00 +2.691944417857907368e+01,1.423100000000000023e+02,0.000000000000000000e+00,7.235743328234159222e+00,0.000000000000000000e+00,1.000000009963298631e+00,0.000000000000000000e+00,1.039507576320875233e-10,0.000000000000000000e+00 +2.692082620659559922e+01,1.423199999999999932e+02,0.000000000000000000e+00,7.237125356264453302e+00,0.000000000000000000e+00,1.000000009963442293e+00,0.000000000000000000e+00,4.290595590200860650e-11,0.000000000000000000e+00 +2.692220797069498062e+01,1.423300000000000125e+02,0.000000000000000000e+00,7.238507120377600579e+00,0.000000000000000000e+00,1.000000009963501579e+00,0.000000000000000000e+00,1.591198739253357639e-10,0.000000000000000000e+00 +2.692358947102836453e+01,1.423400000000000034e+02,0.000000000000000000e+00,7.239888620724748591e+00,0.000000000000000000e+00,1.000000009963721403e+00,0.000000000000000000e+00,-5.795319441606654605e-10,0.000000000000000000e+00 +2.692497070774675549e+01,1.423499999999999943e+02,0.000000000000000000e+00,7.241269857456900993e+00,0.000000000000000000e+00,1.000000009962920933e+00,0.000000000000000000e+00,5.198291896748176855e-10,0.000000000000000000e+00 +2.692635168100101239e+01,1.423600000000000136e+02,0.000000000000000000e+00,7.242650830724915778e+00,0.000000000000000000e+00,1.000000009963638803e+00,0.000000000000000000e+00,-3.687583206535778274e-10,0.000000000000000000e+00 +2.692773239094185200e+01,1.423700000000000045e+02,0.000000000000000000e+00,7.244031540679510606e+00,0.000000000000000000e+00,1.000000009963129655e+00,0.000000000000000000e+00,3.805706555503656358e-10,0.000000000000000000e+00 +2.692911283771984188e+01,1.423799999999999955e+02,0.000000000000000000e+00,7.245411987471255699e+00,0.000000000000000000e+00,1.000000009963655012e+00,0.000000000000000000e+00,-1.283826104537158502e-10,0.000000000000000000e+00 +2.693049302148541457e+01,1.423900000000000148e+02,0.000000000000000000e+00,7.246792171250580950e+00,0.000000000000000000e+00,1.000000009963477821e+00,0.000000000000000000e+00,-1.314643772490181391e-10,0.000000000000000000e+00 +2.693187294238885698e+01,1.424000000000000057e+02,0.000000000000000000e+00,7.248172092167770586e+00,0.000000000000000000e+00,1.000000009963296410e+00,0.000000000000000000e+00,2.716696754574242649e-10,0.000000000000000000e+00 +2.693325260058030679e+01,1.424099999999999966e+02,0.000000000000000000e+00,7.249551750372966730e+00,0.000000000000000000e+00,1.000000009963671221e+00,0.000000000000000000e+00,-4.188501468875939814e-10,0.000000000000000000e+00 +2.693463199620976667e+01,1.424200000000000159e+02,0.000000000000000000e+00,7.250931146016169393e+00,0.000000000000000000e+00,1.000000009963093461e+00,0.000000000000000000e+00,4.974993137716313488e-10,0.000000000000000000e+00 +2.693601112942709008e+01,1.424300000000000068e+02,0.000000000000000000e+00,7.252310279247233815e+00,0.000000000000000000e+00,1.000000009963779579e+00,0.000000000000000000e+00,-3.468664542593766934e-10,0.000000000000000000e+00 +2.693739000038199194e+01,1.424399999999999977e+02,0.000000000000000000e+00,7.253689150215875792e+00,0.000000000000000000e+00,1.000000009963301295e+00,0.000000000000000000e+00,-2.499717224576656068e-10,0.000000000000000000e+00 +2.693876860922404504e+01,1.424500000000000171e+02,0.000000000000000000e+00,7.255067759071665456e+00,0.000000000000000000e+00,1.000000009962956682e+00,0.000000000000000000e+00,2.227941988851814254e-10,0.000000000000000000e+00 +2.694014695610268006e+01,1.424600000000000080e+02,0.000000000000000000e+00,7.256446105964032611e+00,0.000000000000000000e+00,1.000000009963263770e+00,0.000000000000000000e+00,3.625323094706772546e-11,0.000000000000000000e+00 +2.694152504116718205e+01,1.424699999999999989e+02,0.000000000000000000e+00,7.257824191042265838e+00,0.000000000000000000e+00,1.000000009963313730e+00,0.000000000000000000e+00,2.691306377542575829e-11,0.000000000000000000e+00 +2.694290286456669747e+01,1.424799999999999898e+02,0.000000000000000000e+00,7.259202014455510721e+00,0.000000000000000000e+00,1.000000009963350811e+00,0.000000000000000000e+00,9.590606528056053992e-11,0.000000000000000000e+00 +2.694428042645023424e+01,1.424900000000000091e+02,0.000000000000000000e+00,7.260579576352771625e+00,0.000000000000000000e+00,1.000000009963482928e+00,0.000000000000000000e+00,-3.245303289922258904e-10,0.000000000000000000e+00 +2.694565772696665107e+01,1.425000000000000000e+02,0.000000000000000000e+00,7.261956876882911693e+00,0.000000000000000000e+00,1.000000009963035952e+00,0.000000000000000000e+00,5.403414936474478826e-10,0.000000000000000000e+00 +2.694703476626467165e+01,1.425099999999999909e+02,0.000000000000000000e+00,7.263333916194651962e+00,0.000000000000000000e+00,1.000000009963780023e+00,0.000000000000000000e+00,-6.864009171564252908e-10,0.000000000000000000e+00 +2.694841154449287757e+01,1.425200000000000102e+02,0.000000000000000000e+00,7.264710694436574911e+00,0.000000000000000000e+00,1.000000009962835001e+00,0.000000000000000000e+00,5.807123337746948910e-10,0.000000000000000000e+00 +2.694978806179970832e+01,1.425300000000000011e+02,0.000000000000000000e+00,7.266087211757118247e+00,0.000000000000000000e+00,1.000000009963634362e+00,0.000000000000000000e+00,-4.417476781213511345e-10,0.000000000000000000e+00 +2.695116431833346127e+01,1.425399999999999920e+02,0.000000000000000000e+00,7.267463468304583785e+00,0.000000000000000000e+00,1.000000009963026404e+00,0.000000000000000000e+00,3.658260290838930909e-10,0.000000000000000000e+00 +2.695254031424229524e+01,1.425500000000000114e+02,0.000000000000000000e+00,7.268839464227128566e+00,0.000000000000000000e+00,1.000000009963529779e+00,0.000000000000000000e+00,-3.765477367699141682e-10,0.000000000000000000e+00 +2.695391604967423405e+01,1.425600000000000023e+02,0.000000000000000000e+00,7.270215199672772854e+00,0.000000000000000000e+00,1.000000009963011749e+00,0.000000000000000000e+00,4.746077461490017054e-11,0.000000000000000000e+00 +2.695529152477715229e+01,1.425699999999999932e+02,0.000000000000000000e+00,7.271590674789393915e+00,0.000000000000000000e+00,1.000000009963077030e+00,0.000000000000000000e+00,1.327215567376445683e-10,0.000000000000000000e+00 +2.695666673969878957e+01,1.425800000000000125e+02,0.000000000000000000e+00,7.272965889724731348e+00,0.000000000000000000e+00,1.000000009963259551e+00,0.000000000000000000e+00,-2.191450290646481524e-10,0.000000000000000000e+00 +2.695804169458674338e+01,1.425900000000000034e+02,0.000000000000000000e+00,7.274340844626384417e+00,0.000000000000000000e+00,1.000000009962958236e+00,0.000000000000000000e+00,3.038244129336892976e-10,0.000000000000000000e+00 +2.695941638958847619e+01,1.425999999999999943e+02,0.000000000000000000e+00,7.275715539641812057e+00,0.000000000000000000e+00,1.000000009963375902e+00,0.000000000000000000e+00,-2.756099950624631181e-10,0.000000000000000000e+00 +2.696079082485130485e+01,1.426100000000000136e+02,0.000000000000000000e+00,7.277089974918335535e+00,0.000000000000000000e+00,1.000000009962997094e+00,0.000000000000000000e+00,2.955368741758420931e-10,0.000000000000000000e+00 +2.696216500052241472e+01,1.426200000000000045e+02,0.000000000000000000e+00,7.278464150603134897e+00,0.000000000000000000e+00,1.000000009963403214e+00,0.000000000000000000e+00,3.943390620147291076e-11,0.000000000000000000e+00 +2.696353891674884551e+01,1.426299999999999955e+02,0.000000000000000000e+00,7.279838066843253408e+00,0.000000000000000000e+00,1.000000009963457392e+00,0.000000000000000000e+00,-2.009245817965724652e-10,0.000000000000000000e+00 +2.696491257367749839e+01,1.426400000000000148e+02,0.000000000000000000e+00,7.281211723785594003e+00,0.000000000000000000e+00,1.000000009963181391e+00,0.000000000000000000e+00,-5.141277022255460751e-11,0.000000000000000000e+00 +2.696628597145514306e+01,1.426500000000000057e+02,0.000000000000000000e+00,7.282585121576921061e+00,0.000000000000000000e+00,1.000000009963110781e+00,0.000000000000000000e+00,-7.939758394513480929e-11,0.000000000000000000e+00 +2.696765911022840356e+01,1.426599999999999966e+02,0.000000000000000000e+00,7.283958260363861292e+00,0.000000000000000000e+00,1.000000009963001757e+00,0.000000000000000000e+00,8.927847260855274182e-11,0.000000000000000000e+00 +2.696903199014376540e+01,1.426700000000000159e+02,0.000000000000000000e+00,7.285331140292902852e+00,0.000000000000000000e+00,1.000000009963124326e+00,0.000000000000000000e+00,-1.137220937780438957e-10,0.000000000000000000e+00 +2.697040461134758260e+01,1.426800000000000068e+02,0.000000000000000000e+00,7.286703761510396227e+00,0.000000000000000000e+00,1.000000009962968228e+00,0.000000000000000000e+00,1.590467712545500087e-10,0.000000000000000000e+00 +2.697177697398606711e+01,1.426899999999999977e+02,0.000000000000000000e+00,7.288076124162553349e+00,0.000000000000000000e+00,1.000000009963186498e+00,0.000000000000000000e+00,-1.328606224579299830e-10,0.000000000000000000e+00 +2.697314907820529228e+01,1.427000000000000171e+02,0.000000000000000000e+00,7.289448228395449370e+00,0.000000000000000000e+00,1.000000009963004199e+00,0.000000000000000000e+00,-1.419496985800085815e-10,0.000000000000000000e+00 +2.697452092415119651e+01,1.427100000000000080e+02,0.000000000000000000e+00,7.290820074355020886e+00,0.000000000000000000e+00,1.000000009962809466e+00,0.000000000000000000e+00,5.080068231261514736e-10,0.000000000000000000e+00 +2.697589251196957960e+01,1.427199999999999989e+02,0.000000000000000000e+00,7.292191662187067713e+00,0.000000000000000000e+00,1.000000009963506242e+00,0.000000000000000000e+00,-6.395807675838342738e-10,0.000000000000000000e+00 +2.697726384180610282e+01,1.427299999999999898e+02,0.000000000000000000e+00,7.293562992037253778e+00,0.000000000000000000e+00,1.000000009962629166e+00,0.000000000000000000e+00,5.694149036728597759e-10,0.000000000000000000e+00 +2.697863491380629242e+01,1.427400000000000091e+02,0.000000000000000000e+00,7.294934064051102673e+00,0.000000000000000000e+00,1.000000009963409875e+00,0.000000000000000000e+00,-2.118699383885945277e-10,0.000000000000000000e+00 +2.698000572811553610e+01,1.427500000000000000e+02,0.000000000000000000e+00,7.296304878374005654e+00,0.000000000000000000e+00,1.000000009963119441e+00,0.000000000000000000e+00,-2.443118542269751079e-10,0.000000000000000000e+00 +2.698137628487909012e+01,1.427599999999999909e+02,0.000000000000000000e+00,7.297675435151213641e+00,0.000000000000000000e+00,1.000000009962784597e+00,0.000000000000000000e+00,-9.528007618151232417e-11,0.000000000000000000e+00 +2.698274658424206862e+01,1.427700000000000102e+02,0.000000000000000000e+00,7.299045734527842555e+00,0.000000000000000000e+00,1.000000009962654035e+00,0.000000000000000000e+00,6.129539313445131914e-10,0.000000000000000000e+00 +2.698411662634945074e+01,1.427800000000000011e+02,0.000000000000000000e+00,7.300415776648872423e+00,0.000000000000000000e+00,1.000000009963493808e+00,0.000000000000000000e+00,-5.809728285901440615e-10,0.000000000000000000e+00 +2.698548641134607706e+01,1.427899999999999920e+02,0.000000000000000000e+00,7.301785561659148271e+00,0.000000000000000000e+00,1.000000009962698000e+00,0.000000000000000000e+00,1.410550218548735858e-11,0.000000000000000000e+00 +2.698685593937666027e+01,1.428000000000000114e+02,0.000000000000000000e+00,7.303155089703375680e+00,0.000000000000000000e+00,1.000000009962717318e+00,0.000000000000000000e+00,4.102714252096526590e-10,0.000000000000000000e+00 +2.698822521058577095e+01,1.428100000000000023e+02,0.000000000000000000e+00,7.304524360926127891e+00,0.000000000000000000e+00,1.000000009963279091e+00,0.000000000000000000e+00,-4.353260726280999961e-10,0.000000000000000000e+00 +2.698959422511784467e+01,1.428199999999999932e+02,0.000000000000000000e+00,7.305893375471842255e+00,0.000000000000000000e+00,1.000000009962683123e+00,0.000000000000000000e+00,2.253283315163476563e-10,0.000000000000000000e+00 +2.699096298311718556e+01,1.428300000000000125e+02,0.000000000000000000e+00,7.307262133484818456e+00,0.000000000000000000e+00,1.000000009962991543e+00,0.000000000000000000e+00,-7.106717024788157726e-11,0.000000000000000000e+00 +2.699233148472795563e+01,1.428400000000000034e+02,0.000000000000000000e+00,7.308630635109223839e+00,0.000000000000000000e+00,1.000000009962894287e+00,0.000000000000000000e+00,2.271978802682131412e-12,0.000000000000000000e+00 +2.699369973009418899e+01,1.428499999999999943e+02,0.000000000000000000e+00,7.309998880489088968e+00,0.000000000000000000e+00,1.000000009962897396e+00,0.000000000000000000e+00,3.518980123495906287e-10,0.000000000000000000e+00 +2.699506771935978122e+01,1.428600000000000136e+02,0.000000000000000000e+00,7.311366869768310295e+00,0.000000000000000000e+00,1.000000009963378789e+00,0.000000000000000000e+00,-5.407710511206751596e-10,0.000000000000000000e+00 +2.699643545266849287e+01,1.428700000000000045e+02,0.000000000000000000e+00,7.312734603090650154e+00,0.000000000000000000e+00,1.000000009962639158e+00,0.000000000000000000e+00,7.891440872103263504e-11,0.000000000000000000e+00 +2.699780293016395305e+01,1.428799999999999955e+02,0.000000000000000000e+00,7.314102080599734101e+00,0.000000000000000000e+00,1.000000009962747072e+00,0.000000000000000000e+00,2.177860312110145446e-10,0.000000000000000000e+00 +2.699917015198965231e+01,1.428900000000000148e+02,0.000000000000000000e+00,7.315469302439056243e+00,0.000000000000000000e+00,1.000000009963044834e+00,0.000000000000000000e+00,-2.186389221022315801e-10,0.000000000000000000e+00 +2.700053711828895331e+01,1.429000000000000057e+02,0.000000000000000000e+00,7.316836268751975680e+00,0.000000000000000000e+00,1.000000009962745962e+00,0.000000000000000000e+00,1.023538331715588714e-10,0.000000000000000000e+00 +2.700190382920507659e+01,1.429099999999999966e+02,0.000000000000000000e+00,7.318202979681716513e+00,0.000000000000000000e+00,1.000000009962885850e+00,0.000000000000000000e+00,1.360097788614921598e-10,0.000000000000000000e+00 +2.700327028488111836e+01,1.429200000000000159e+02,0.000000000000000000e+00,7.319569435371370503e+00,0.000000000000000000e+00,1.000000009963071701e+00,0.000000000000000000e+00,-2.114477445451379964e-10,0.000000000000000000e+00 +2.700463648546003270e+01,1.429300000000000068e+02,0.000000000000000000e+00,7.320935635963895294e+00,0.000000000000000000e+00,1.000000009962782821e+00,0.000000000000000000e+00,-8.127871304845929337e-11,0.000000000000000000e+00 +2.700600243108464227e+01,1.429399999999999977e+02,0.000000000000000000e+00,7.322301581602114418e+00,0.000000000000000000e+00,1.000000009962671799e+00,0.000000000000000000e+00,-4.324834314464537643e-11,0.000000000000000000e+00 +2.700736812189764180e+01,1.429500000000000171e+02,0.000000000000000000e+00,7.323667272428719066e+00,0.000000000000000000e+00,1.000000009962612735e+00,0.000000000000000000e+00,2.868582941975952400e-10,0.000000000000000000e+00 +2.700873355804158749e+01,1.429600000000000080e+02,0.000000000000000000e+00,7.325032708586267205e+00,0.000000000000000000e+00,1.000000009963004421e+00,0.000000000000000000e+00,-1.374378974795619281e-10,0.000000000000000000e+00 +2.701009873965890407e+01,1.429699999999999989e+02,0.000000000000000000e+00,7.326397890217184461e+00,0.000000000000000000e+00,1.000000009962816794e+00,0.000000000000000000e+00,2.017216035070503389e-11,0.000000000000000000e+00 +2.701146366689188483e+01,1.429799999999999898e+02,0.000000000000000000e+00,7.327762817463762346e+00,0.000000000000000000e+00,1.000000009962844327e+00,0.000000000000000000e+00,-2.858797481027648181e-10,0.000000000000000000e+00 +2.701282833988268806e+01,1.429900000000000091e+02,0.000000000000000000e+00,7.329127490468160921e+00,0.000000000000000000e+00,1.000000009962454195e+00,0.000000000000000000e+00,2.826782019780970159e-10,0.000000000000000000e+00 +2.701419275877334059e+01,1.430000000000000000e+02,0.000000000000000000e+00,7.330491909372407022e+00,0.000000000000000000e+00,1.000000009962839886e+00,0.000000000000000000e+00,-2.754061936429267014e-10,0.000000000000000000e+00 +2.701555692370573780e+01,1.430099999999999909e+02,0.000000000000000000e+00,7.331856074318396921e+00,0.000000000000000000e+00,1.000000009962464187e+00,0.000000000000000000e+00,3.342282122304067337e-10,0.000000000000000000e+00 +2.701692083482164719e+01,1.430200000000000102e+02,0.000000000000000000e+00,7.333219985447892775e+00,0.000000000000000000e+00,1.000000009962920045e+00,0.000000000000000000e+00,1.092590598047568437e-10,0.000000000000000000e+00 +2.701828449226269413e+01,1.430300000000000011e+02,0.000000000000000000e+00,7.334583642902527068e+00,0.000000000000000000e+00,1.000000009963069036e+00,0.000000000000000000e+00,-5.649629798926994957e-10,0.000000000000000000e+00 +2.701964789617038321e+01,1.430399999999999920e+02,0.000000000000000000e+00,7.335947046823799056e+00,0.000000000000000000e+00,1.000000009962298764e+00,0.000000000000000000e+00,6.087227192082108906e-10,0.000000000000000000e+00 +2.702101104668608045e+01,1.430500000000000114e+02,0.000000000000000000e+00,7.337310197353075658e+00,0.000000000000000000e+00,1.000000009963128544e+00,0.000000000000000000e+00,-7.631220314419496120e-10,0.000000000000000000e+00 +2.702237394395102044e+01,1.430600000000000023e+02,0.000000000000000000e+00,7.338673094631595895e+00,0.000000000000000000e+00,1.000000009962088487e+00,0.000000000000000000e+00,4.865725125162688648e-10,0.000000000000000000e+00 +2.702373658810631341e+01,1.430699999999999932e+02,0.000000000000000000e+00,7.340035738800462894e+00,0.000000000000000000e+00,1.000000009962751513e+00,0.000000000000000000e+00,-3.715978965527234313e-11,0.000000000000000000e+00 +2.702509897929293103e+01,1.430800000000000125e+02,0.000000000000000000e+00,7.341398130000653666e+00,0.000000000000000000e+00,1.000000009962700886e+00,0.000000000000000000e+00,-3.472151014905254057e-11,0.000000000000000000e+00 +2.702646111765171710e+01,1.430900000000000034e+02,0.000000000000000000e+00,7.342760268373011101e+00,0.000000000000000000e+00,1.000000009962653591e+00,0.000000000000000000e+00,-7.646671220366979071e-11,0.000000000000000000e+00 +2.702782300332338750e+01,1.430999999999999943e+02,0.000000000000000000e+00,7.344122154058248420e+00,0.000000000000000000e+00,1.000000009962549452e+00,0.000000000000000000e+00,2.265073833382237576e-10,0.000000000000000000e+00 +2.702918463644852309e+01,1.431100000000000136e+02,0.000000000000000000e+00,7.345483787196948278e+00,0.000000000000000000e+00,1.000000009962857872e+00,0.000000000000000000e+00,-1.758244999061255792e-10,0.000000000000000000e+00 +2.703054601716757688e+01,1.431200000000000045e+02,0.000000000000000000e+00,7.346845167929563658e+00,0.000000000000000000e+00,1.000000009962618508e+00,0.000000000000000000e+00,6.296923504447019376e-11,0.000000000000000000e+00 +2.703190714562087038e+01,1.431299999999999955e+02,0.000000000000000000e+00,7.348206296396416093e+00,0.000000000000000000e+00,1.000000009962704217e+00,0.000000000000000000e+00,-1.068717364414085152e-10,0.000000000000000000e+00 +2.703326802194859368e+01,1.431400000000000148e+02,0.000000000000000000e+00,7.349567172737698328e+00,0.000000000000000000e+00,1.000000009962558778e+00,0.000000000000000000e+00,1.837555138384827255e-10,0.000000000000000000e+00 +2.703462864629081253e+01,1.431500000000000057e+02,0.000000000000000000e+00,7.350927797093472549e+00,0.000000000000000000e+00,1.000000009962808800e+00,0.000000000000000000e+00,-5.962550285239499165e-10,0.000000000000000000e+00 +2.703598901878745764e+01,1.431599999999999966e+02,0.000000000000000000e+00,7.352288169603672152e+00,0.000000000000000000e+00,1.000000009961997671e+00,0.000000000000000000e+00,8.231246118293558417e-10,0.000000000000000000e+00 +2.703734913957833541e+01,1.431700000000000159e+02,0.000000000000000000e+00,7.353648290408099086e+00,0.000000000000000000e+00,1.000000009963117220e+00,0.000000000000000000e+00,-4.498468495500576716e-10,0.000000000000000000e+00 +2.703870900880311723e+01,1.431800000000000068e+02,0.000000000000000000e+00,7.355008159646430066e+00,0.000000000000000000e+00,1.000000009962505487e+00,0.000000000000000000e+00,-1.843814925681823714e-10,0.000000000000000000e+00 +2.704006862660135013e+01,1.431899999999999977e+02,0.000000000000000000e+00,7.356367777458207691e+00,0.000000000000000000e+00,1.000000009962254799e+00,0.000000000000000000e+00,8.967595354790871234e-11,0.000000000000000000e+00 +2.704142799311244971e+01,1.432000000000000171e+02,0.000000000000000000e+00,7.357727143982848439e+00,0.000000000000000000e+00,1.000000009962376701e+00,0.000000000000000000e+00,2.819841482651773882e-10,0.000000000000000000e+00 +2.704278710847570011e+01,1.432100000000000080e+02,0.000000000000000000e+00,7.359086259359640003e+00,0.000000000000000000e+00,1.000000009962759950e+00,0.000000000000000000e+00,-1.790913759571336572e-10,0.000000000000000000e+00 +2.704414597283026467e+01,1.432199999999999989e+02,0.000000000000000000e+00,7.360445123727741290e+00,0.000000000000000000e+00,1.000000009962516589e+00,0.000000000000000000e+00,5.981710494228027643e-11,0.000000000000000000e+00 +2.704550458631516818e+01,1.432299999999999898e+02,0.000000000000000000e+00,7.361803737226181532e+00,0.000000000000000000e+00,1.000000009962597858e+00,0.000000000000000000e+00,-5.312608607696020966e-11,0.000000000000000000e+00 +2.704686294906931820e+01,1.432400000000000091e+02,0.000000000000000000e+00,7.363162099993862952e+00,0.000000000000000000e+00,1.000000009962525693e+00,0.000000000000000000e+00,-1.267086575106378383e-10,0.000000000000000000e+00 +2.704822106123148373e+01,1.432500000000000000e+02,0.000000000000000000e+00,7.364520212169558988e+00,0.000000000000000000e+00,1.000000009962353609e+00,0.000000000000000000e+00,2.315516805058613778e-10,0.000000000000000000e+00 +2.704957892294031296e+01,1.432599999999999909e+02,0.000000000000000000e+00,7.365878073891915179e+00,0.000000000000000000e+00,1.000000009962668024e+00,0.000000000000000000e+00,-5.130731288227371677e-10,0.000000000000000000e+00 +2.705093653433432266e+01,1.432700000000000102e+02,0.000000000000000000e+00,7.367235685299450054e+00,0.000000000000000000e+00,1.000000009961971470e+00,0.000000000000000000e+00,4.413536620381889519e-10,0.000000000000000000e+00 +2.705229389555190167e+01,1.432800000000000011e+02,0.000000000000000000e+00,7.368593046530552471e+00,0.000000000000000000e+00,1.000000009962570546e+00,0.000000000000000000e+00,1.137128650649795416e-10,0.000000000000000000e+00 +2.705365100673131451e+01,1.432899999999999920e+02,0.000000000000000000e+00,7.369950157723486939e+00,0.000000000000000000e+00,1.000000009962724867e+00,0.000000000000000000e+00,-6.215266234795580574e-10,0.000000000000000000e+00 +2.705500786801069779e+01,1.433000000000000114e+02,0.000000000000000000e+00,7.371307019016388296e+00,0.000000000000000000e+00,1.000000009961881542e+00,0.000000000000000000e+00,5.594442107569989093e-10,0.000000000000000000e+00 +2.705636447952806023e+01,1.433100000000000023e+02,0.000000000000000000e+00,7.372663630547263480e+00,0.000000000000000000e+00,1.000000009962640490e+00,0.000000000000000000e+00,-2.927063607364945099e-10,0.000000000000000000e+00 +2.705772084142127909e+01,1.433199999999999932e+02,0.000000000000000000e+00,7.374019992453995975e+00,0.000000000000000000e+00,1.000000009962243475e+00,0.000000000000000000e+00,1.116680444746803692e-10,0.000000000000000000e+00 +2.705907695382811085e+01,1.433300000000000125e+02,0.000000000000000000e+00,7.375376104874338701e+00,0.000000000000000000e+00,1.000000009962394909e+00,0.000000000000000000e+00,2.363146949087828764e-10,0.000000000000000000e+00 +2.706043281688618407e+01,1.433400000000000034e+02,0.000000000000000000e+00,7.376731967945920232e+00,0.000000000000000000e+00,1.000000009962715319e+00,0.000000000000000000e+00,-4.913890606381201560e-10,0.000000000000000000e+00 +2.706178843073299944e+01,1.433499999999999943e+02,0.000000000000000000e+00,7.378087581806242135e+00,0.000000000000000000e+00,1.000000009962049186e+00,0.000000000000000000e+00,2.568798802176572537e-10,0.000000000000000000e+00 +2.706314379550593330e+01,1.433600000000000136e+02,0.000000000000000000e+00,7.379442946592678076e+00,0.000000000000000000e+00,1.000000009962397352e+00,0.000000000000000000e+00,-2.392305620718751116e-11,0.000000000000000000e+00 +2.706449891134223407e+01,1.433700000000000045e+02,0.000000000000000000e+00,7.380798062442478269e+00,0.000000000000000000e+00,1.000000009962364933e+00,0.000000000000000000e+00,2.818850190467139869e-11,0.000000000000000000e+00 +2.706585377837902229e+01,1.433799999999999955e+02,0.000000000000000000e+00,7.382152929492765026e+00,0.000000000000000000e+00,1.000000009962403125e+00,0.000000000000000000e+00,-1.580157210419269605e-10,0.000000000000000000e+00 +2.706720839675329771e+01,1.433900000000000148e+02,0.000000000000000000e+00,7.383507547880535427e+00,0.000000000000000000e+00,1.000000009962189074e+00,0.000000000000000000e+00,2.970716045771377783e-10,0.000000000000000000e+00 +2.706856276660192862e+01,1.434000000000000057e+02,0.000000000000000000e+00,7.384861917742660431e+00,0.000000000000000000e+00,1.000000009962591418e+00,0.000000000000000000e+00,-6.311469907014699104e-10,0.000000000000000000e+00 +2.706991688806166252e+01,1.434099999999999966e+02,0.000000000000000000e+00,7.386216039215886653e+00,0.000000000000000000e+00,1.000000009961736769e+00,0.000000000000000000e+00,8.451277733207853791e-10,0.000000000000000000e+00 +2.707127076126912257e+01,1.434200000000000159e+02,0.000000000000000000e+00,7.387569912436832809e+00,0.000000000000000000e+00,1.000000009962880965e+00,0.000000000000000000e+00,-6.919080839531091447e-10,0.000000000000000000e+00 +2.707262438636080049e+01,1.434300000000000068e+02,0.000000000000000000e+00,7.388923537541996822e+00,0.000000000000000000e+00,1.000000009961944381e+00,0.000000000000000000e+00,1.312536486171821951e-12,0.000000000000000000e+00 +2.707397776347306717e+01,1.434399999999999977e+02,0.000000000000000000e+00,7.390276914667746055e+00,0.000000000000000000e+00,1.000000009961946157e+00,0.000000000000000000e+00,4.140170130219438964e-10,0.000000000000000000e+00 +2.707533089274216920e+01,1.434500000000000171e+02,0.000000000000000000e+00,7.391630043950327078e+00,0.000000000000000000e+00,1.000000009962506375e+00,0.000000000000000000e+00,-2.593209085120288672e-11,0.000000000000000000e+00 +2.707668377430422524e+01,1.434600000000000080e+02,0.000000000000000000e+00,7.392982925525861226e+00,0.000000000000000000e+00,1.000000009962471292e+00,0.000000000000000000e+00,-4.364939875983356847e-10,0.000000000000000000e+00 +2.707803640829523317e+01,1.434699999999999989e+02,0.000000000000000000e+00,7.394335559530343716e+00,0.000000000000000000e+00,1.000000009961880876e+00,0.000000000000000000e+00,5.523258477748721735e-10,0.000000000000000000e+00 +2.707938879485106298e+01,1.434799999999999898e+02,0.000000000000000000e+00,7.395687946099645416e+00,0.000000000000000000e+00,1.000000009962627834e+00,0.000000000000000000e+00,-5.452013059026499469e-10,0.000000000000000000e+00 +2.708074093410746386e+01,1.434900000000000091e+02,0.000000000000000000e+00,7.397040085369515516e+00,0.000000000000000000e+00,1.000000009961890646e+00,0.000000000000000000e+00,6.931235399023484155e-11,0.000000000000000000e+00 +2.708209282620005709e+01,1.435000000000000000e+02,0.000000000000000000e+00,7.398391977475575310e+00,0.000000000000000000e+00,1.000000009961984349e+00,0.000000000000000000e+00,3.663383842893559946e-10,0.000000000000000000e+00 +2.708344447126434318e+01,1.435099999999999909e+02,0.000000000000000000e+00,7.399743622553325295e+00,0.000000000000000000e+00,1.000000009962479508e+00,0.000000000000000000e+00,-2.269084019067811037e-10,0.000000000000000000e+00 +2.708479586943569473e+01,1.435200000000000102e+02,0.000000000000000000e+00,7.401095020738141628e+00,0.000000000000000000e+00,1.000000009962172864e+00,0.000000000000000000e+00,1.474105778243497953e-10,0.000000000000000000e+00 +2.708614702084936710e+01,1.435300000000000011e+02,0.000000000000000000e+00,7.402446172165275229e+00,0.000000000000000000e+00,1.000000009962372038e+00,0.000000000000000000e+00,-5.424121678064921095e-10,0.000000000000000000e+00 +2.708749792564048775e+01,1.435399999999999920e+02,0.000000000000000000e+00,7.403797076969855340e+00,0.000000000000000000e+00,1.000000009961639291e+00,0.000000000000000000e+00,5.370860434275152977e-10,0.000000000000000000e+00 +2.708884858394406336e+01,1.435500000000000114e+02,0.000000000000000000e+00,7.405147735286885968e+00,0.000000000000000000e+00,1.000000009962364711e+00,0.000000000000000000e+00,-1.070421790243916794e-10,0.000000000000000000e+00 +2.709019899589497626e+01,1.435600000000000023e+02,0.000000000000000000e+00,7.406498147251251218e+00,0.000000000000000000e+00,1.000000009962220160e+00,0.000000000000000000e+00,-1.274544040112894831e-10,0.000000000000000000e+00 +2.709154916162798443e+01,1.435699999999999932e+02,0.000000000000000000e+00,7.407848312997709073e+00,0.000000000000000000e+00,1.000000009962048075e+00,0.000000000000000000e+00,-9.638954326744237218e-11,0.000000000000000000e+00 +2.709289908127772151e+01,1.435800000000000125e+02,0.000000000000000000e+00,7.409198232660895833e+00,0.000000000000000000e+00,1.000000009961917957e+00,0.000000000000000000e+00,3.879316741753767092e-10,0.000000000000000000e+00 +2.709424875497870389e+01,1.435900000000000034e+02,0.000000000000000000e+00,7.410547906375325233e+00,0.000000000000000000e+00,1.000000009962441538e+00,0.000000000000000000e+00,-7.108439826884228573e-10,0.000000000000000000e+00 +2.709559818286532362e+01,1.435999999999999943e+02,0.000000000000000000e+00,7.411897334275389326e+00,0.000000000000000000e+00,1.000000009961482306e+00,0.000000000000000000e+00,4.234570880854565750e-10,0.000000000000000000e+00 +2.709694736507184842e+01,1.436100000000000136e+02,0.000000000000000000e+00,7.413246516495354932e+00,0.000000000000000000e+00,1.000000009962053626e+00,0.000000000000000000e+00,2.908608153139822797e-10,0.000000000000000000e+00 +2.709829630173242521e+01,1.436200000000000045e+02,0.000000000000000000e+00,7.414595453169370742e+00,0.000000000000000000e+00,1.000000009962445979e+00,0.000000000000000000e+00,-2.188026950125564157e-10,0.000000000000000000e+00 +2.709964499298108009e+01,1.436299999999999955e+02,0.000000000000000000e+00,7.415944144431461105e+00,0.000000000000000000e+00,1.000000009962150882e+00,0.000000000000000000e+00,-2.143964844780690516e-10,0.000000000000000000e+00 +2.710099343895171486e+01,1.436400000000000148e+02,0.000000000000000000e+00,7.417292590415527798e+00,0.000000000000000000e+00,1.000000009961861780e+00,0.000000000000000000e+00,2.195410747201953064e-10,0.000000000000000000e+00 +2.710234163977810695e+01,1.436500000000000057e+02,0.000000000000000000e+00,7.418640791255351807e+00,0.000000000000000000e+00,1.000000009962157765e+00,0.000000000000000000e+00,-4.683186232043770761e-10,0.000000000000000000e+00 +2.710368959559392010e+01,1.436599999999999966e+02,0.000000000000000000e+00,7.419988747084593328e+00,0.000000000000000000e+00,1.000000009961526493e+00,0.000000000000000000e+00,5.700586905835234482e-10,0.000000000000000000e+00 +2.710503730653269017e+01,1.436700000000000159e+02,0.000000000000000000e+00,7.421336458036789097e+00,0.000000000000000000e+00,1.000000009962294767e+00,0.000000000000000000e+00,-1.722021769323332852e-10,0.000000000000000000e+00 +2.710638477272783575e+01,1.436800000000000068e+02,0.000000000000000000e+00,7.422683924245357723e+00,0.000000000000000000e+00,1.000000009962062730e+00,0.000000000000000000e+00,-3.362260515662580302e-10,0.000000000000000000e+00 +2.710773199431265112e+01,1.436899999999999977e+02,0.000000000000000000e+00,7.424031145843593471e+00,0.000000000000000000e+00,1.000000009961609759e+00,0.000000000000000000e+00,4.848138690488836162e-10,0.000000000000000000e+00 +2.710907897142030976e+01,1.437000000000000171e+02,0.000000000000000000e+00,7.425378122964670702e+00,0.000000000000000000e+00,1.000000009962262792e+00,0.000000000000000000e+00,-2.418738477591813692e-10,0.000000000000000000e+00 +2.711042570418386788e+01,1.437100000000000080e+02,0.000000000000000000e+00,7.426724855741644760e+00,0.000000000000000000e+00,1.000000009961937053e+00,0.000000000000000000e+00,-1.530331565053499168e-10,0.000000000000000000e+00 +2.711177219273625738e+01,1.437199999999999989e+02,0.000000000000000000e+00,7.428071344307447532e+00,0.000000000000000000e+00,1.000000009961730996e+00,0.000000000000000000e+00,1.784610946695832105e-10,0.000000000000000000e+00 +2.711311843721028936e+01,1.437299999999999898e+02,0.000000000000000000e+00,7.429417588794891891e+00,0.000000000000000000e+00,1.000000009961971248e+00,0.000000000000000000e+00,1.778335736606549470e-10,0.000000000000000000e+00 +2.711446443773866122e+01,1.437400000000000091e+02,0.000000000000000000e+00,7.430763589336670805e+00,0.000000000000000000e+00,1.000000009962210612e+00,0.000000000000000000e+00,-2.394093360919559965e-10,0.000000000000000000e+00 +2.711581019445393892e+01,1.437500000000000000e+02,0.000000000000000000e+00,7.432109346065356448e+00,0.000000000000000000e+00,1.000000009961888425e+00,0.000000000000000000e+00,-1.764127708568678123e-10,0.000000000000000000e+00 +2.711715570748857829e+01,1.437599999999999909e+02,0.000000000000000000e+00,7.433454859113400204e+00,0.000000000000000000e+00,1.000000009961651060e+00,0.000000000000000000e+00,2.837310143014789403e-10,0.000000000000000000e+00 +2.711850097697491080e+01,1.437700000000000102e+02,0.000000000000000000e+00,7.434800128613134440e+00,0.000000000000000000e+00,1.000000009962032754e+00,0.000000000000000000e+00,-4.158509431024023220e-10,0.000000000000000000e+00 +2.711984600304515070e+01,1.437800000000000011e+02,0.000000000000000000e+00,7.436145154696772508e+00,0.000000000000000000e+00,1.000000009961473424e+00,0.000000000000000000e+00,5.873161582682677649e-10,0.000000000000000000e+00 +2.712119078583138787e+01,1.437899999999999920e+02,0.000000000000000000e+00,7.437489937496406078e+00,0.000000000000000000e+00,1.000000009962263237e+00,0.000000000000000000e+00,-2.280658684946098942e-10,0.000000000000000000e+00 +2.712253532546559853e+01,1.438000000000000114e+02,0.000000000000000000e+00,7.438834477144010471e+00,0.000000000000000000e+00,1.000000009961956593e+00,0.000000000000000000e+00,-4.900751336675286319e-10,0.000000000000000000e+00 +2.712387962207963454e+01,1.438100000000000023e+02,0.000000000000000000e+00,7.440178773771438436e+00,0.000000000000000000e+00,1.000000009961297787e+00,0.000000000000000000e+00,7.021219114673152985e-10,0.000000000000000000e+00 +2.712522367580523053e+01,1.438199999999999932e+02,0.000000000000000000e+00,7.441522827510424598e+00,0.000000000000000000e+00,1.000000009962241476e+00,0.000000000000000000e+00,-6.682103384936723368e-10,0.000000000000000000e+00 +2.712656748677400742e+01,1.438300000000000125e+02,0.000000000000000000e+00,7.442866638492587228e+00,0.000000000000000000e+00,1.000000009961343528e+00,0.000000000000000000e+00,7.253473749711850323e-10,0.000000000000000000e+00 +2.712791105511745826e+01,1.438400000000000034e+02,0.000000000000000000e+00,7.444210206849421141e+00,0.000000000000000000e+00,1.000000009962318082e+00,0.000000000000000000e+00,-6.112596949698713963e-10,0.000000000000000000e+00 +2.712925438096696240e+01,1.438499999999999943e+02,0.000000000000000000e+00,7.445553532712307465e+00,0.000000000000000000e+00,1.000000009961496961e+00,0.000000000000000000e+00,1.592074927892362208e-10,0.000000000000000000e+00 +2.713059746445377840e+01,1.438600000000000136e+02,0.000000000000000000e+00,7.446896616212503872e+00,0.000000000000000000e+00,1.000000009961710790e+00,0.000000000000000000e+00,1.488188895358012161e-12,0.000000000000000000e+00 +2.713194030570905113e+01,1.438700000000000045e+02,0.000000000000000000e+00,7.448239457481153458e+00,0.000000000000000000e+00,1.000000009961712788e+00,0.000000000000000000e+00,3.099298760593711880e-10,0.000000000000000000e+00 +2.713328290486380112e+01,1.438799999999999955e+02,0.000000000000000000e+00,7.449582056649279416e+00,0.000000000000000000e+00,1.000000009962128900e+00,0.000000000000000000e+00,-4.768884191834714959e-10,0.000000000000000000e+00 +2.713462526204893521e+01,1.438900000000000148e+02,0.000000000000000000e+00,7.450924413847787697e+00,0.000000000000000000e+00,1.000000009961488745e+00,0.000000000000000000e+00,2.332756970596734350e-11,0.000000000000000000e+00 +2.713596737739524301e+01,1.439000000000000057e+02,0.000000000000000000e+00,7.452266529207464352e+00,0.000000000000000000e+00,1.000000009961520053e+00,0.000000000000000000e+00,2.495341250529049596e-10,0.000000000000000000e+00 +2.713730925103338976e+01,1.439099999999999966e+02,0.000000000000000000e+00,7.453608402858979964e+00,0.000000000000000000e+00,1.000000009961854897e+00,0.000000000000000000e+00,1.189969110283596642e-10,0.000000000000000000e+00 +2.713865088309393059e+01,1.439200000000000159e+02,0.000000000000000000e+00,7.454950034932886993e+00,0.000000000000000000e+00,1.000000009962014547e+00,0.000000000000000000e+00,-4.507467498165385445e-10,0.000000000000000000e+00 +2.713999227370729983e+01,1.439300000000000068e+02,0.000000000000000000e+00,7.456291425559619768e+00,0.000000000000000000e+00,1.000000009961409919e+00,0.000000000000000000e+00,4.326159318554464708e-10,0.000000000000000000e+00 +2.714133342300381457e+01,1.439399999999999977e+02,0.000000000000000000e+00,7.457632574869494491e+00,0.000000000000000000e+00,1.000000009961990122e+00,0.000000000000000000e+00,-2.748838950746482079e-10,0.000000000000000000e+00 +2.714267433111367467e+01,1.439500000000000171e+02,0.000000000000000000e+00,7.458973482992712789e+00,0.000000000000000000e+00,1.000000009961621528e+00,0.000000000000000000e+00,-1.863252922699576961e-10,0.000000000000000000e+00 +2.714401499816696273e+01,1.439600000000000080e+02,0.000000000000000000e+00,7.460314150059356386e+00,0.000000000000000000e+00,1.000000009961371727e+00,0.000000000000000000e+00,1.230796223493447178e-10,0.000000000000000000e+00 +2.714535542429364412e+01,1.439699999999999989e+02,0.000000000000000000e+00,7.461654576199391542e+00,0.000000000000000000e+00,1.000000009961536707e+00,0.000000000000000000e+00,7.737350065284677097e-11,0.000000000000000000e+00 +2.714669560962357053e+01,1.439799999999999898e+02,0.000000000000000000e+00,7.462994761542668165e+00,0.000000000000000000e+00,1.000000009961640401e+00,0.000000000000000000e+00,8.915293351807641737e-11,0.000000000000000000e+00 +2.714803555428647286e+01,1.439900000000000091e+02,0.000000000000000000e+00,7.464334706218918924e+00,0.000000000000000000e+00,1.000000009961759861e+00,0.000000000000000000e+00,7.706980916548195165e-11,0.000000000000000000e+00 +2.714937525841196830e+01,1.440000000000000000e+02,0.000000000000000000e+00,7.465674410357760138e+00,0.000000000000000000e+00,1.000000009961863112e+00,0.000000000000000000e+00,-5.357727527028073260e-10,0.000000000000000000e+00 +2.715071472212955683e+01,1.440099999999999909e+02,0.000000000000000000e+00,7.467013874088691772e+00,0.000000000000000000e+00,1.000000009961145464e+00,0.000000000000000000e+00,6.454633496983337396e-10,0.000000000000000000e+00 +2.715205394556862117e+01,1.440200000000000102e+02,0.000000000000000000e+00,7.468353097541096552e+00,0.000000000000000000e+00,1.000000009962009884e+00,0.000000000000000000e+00,-4.220392620544652659e-10,0.000000000000000000e+00 +2.715339292885843037e+01,1.440300000000000011e+02,0.000000000000000000e+00,7.469692080844244408e+00,0.000000000000000000e+00,1.000000009961444780e+00,0.000000000000000000e+00,1.424741546395315182e-10,0.000000000000000000e+00 +2.715473167212813621e+01,1.440399999999999920e+02,0.000000000000000000e+00,7.471030824127285364e+00,0.000000000000000000e+00,1.000000009961635516e+00,0.000000000000000000e+00,-2.183115147447513424e-10,0.000000000000000000e+00 +2.715607017550677327e+01,1.440500000000000114e+02,0.000000000000000000e+00,7.472369327519256643e+00,0.000000000000000000e+00,1.000000009961343306e+00,0.000000000000000000e+00,3.968804714077581119e-10,0.000000000000000000e+00 +2.715740843912326241e+01,1.440600000000000023e+02,0.000000000000000000e+00,7.473707591149078233e+00,0.000000000000000000e+00,1.000000009961874436e+00,0.000000000000000000e+00,-5.718624764638962625e-10,0.000000000000000000e+00 +2.715874646310641083e+01,1.440699999999999932e+02,0.000000000000000000e+00,7.475045615145556432e+00,0.000000000000000000e+00,1.000000009961109271e+00,0.000000000000000000e+00,2.663968648410590276e-10,0.000000000000000000e+00 +2.716008424758490847e+01,1.440800000000000125e+02,0.000000000000000000e+00,7.476383399637379412e+00,0.000000000000000000e+00,1.000000009961465652e+00,0.000000000000000000e+00,3.516071887073472610e-10,0.000000000000000000e+00 +2.716142179268732804e+01,1.440900000000000034e+02,0.000000000000000000e+00,7.477720944753123433e+00,0.000000000000000000e+00,1.000000009961935943e+00,0.000000000000000000e+00,-3.981609447815779647e-10,0.000000000000000000e+00 +2.716275909854213211e+01,1.440999999999999943e+02,0.000000000000000000e+00,7.479058250621248405e+00,0.000000000000000000e+00,1.000000009961403480e+00,0.000000000000000000e+00,-7.688969394598373274e-11,0.000000000000000000e+00 +2.716409616527766246e+01,1.441100000000000136e+02,0.000000000000000000e+00,7.480395317370097885e+00,0.000000000000000000e+00,1.000000009961300673e+00,0.000000000000000000e+00,2.425032877475606337e-10,0.000000000000000000e+00 +2.716543299302215075e+01,1.441200000000000045e+02,0.000000000000000000e+00,7.481732145127902633e+00,0.000000000000000000e+00,1.000000009961624858e+00,0.000000000000000000e+00,-5.144978766016520115e-10,0.000000000000000000e+00 +2.716676958190371138e+01,1.441299999999999955e+02,0.000000000000000000e+00,7.483068734022778834e+00,0.000000000000000000e+00,1.000000009960937186e+00,0.000000000000000000e+00,5.546337485766280643e-10,0.000000000000000000e+00 +2.716810593205034863e+01,1.441400000000000148e+02,0.000000000000000000e+00,7.484405084182726320e+00,0.000000000000000000e+00,1.000000009961678371e+00,0.000000000000000000e+00,-1.105144727060805676e-10,0.000000000000000000e+00 +2.716944204358994597e+01,1.441500000000000057e+02,0.000000000000000000e+00,7.485741195735633902e+00,0.000000000000000000e+00,1.000000009961530711e+00,0.000000000000000000e+00,-1.033868773647209455e-10,0.000000000000000000e+00 +2.717077791665027675e+01,1.441599999999999966e+02,0.000000000000000000e+00,7.487077068809273150e+00,0.000000000000000000e+00,1.000000009961392600e+00,0.000000000000000000e+00,-6.649860279148065665e-13,0.000000000000000000e+00 +2.717211355135900064e+01,1.441700000000000159e+02,0.000000000000000000e+00,7.488412703531302839e+00,0.000000000000000000e+00,1.000000009961391711e+00,0.000000000000000000e+00,1.177235241312005131e-10,0.000000000000000000e+00 +2.717344894784366360e+01,1.441800000000000068e+02,0.000000000000000000e+00,7.489748100029268052e+00,0.000000000000000000e+00,1.000000009961548919e+00,0.000000000000000000e+00,-3.257930931245786368e-10,0.000000000000000000e+00 +2.717478410623169438e+01,1.441899999999999977e+02,0.000000000000000000e+00,7.491083258430600189e+00,0.000000000000000000e+00,1.000000009961113934e+00,0.000000000000000000e+00,8.350040205345269094e-11,0.000000000000000000e+00 +2.717611902665041157e+01,1.442000000000000171e+02,0.000000000000000000e+00,7.492418178862616074e+00,0.000000000000000000e+00,1.000000009961225400e+00,0.000000000000000000e+00,2.710087535133176571e-10,0.000000000000000000e+00 +2.717745370922702008e+01,1.442100000000000080e+02,0.000000000000000000e+00,7.493752861452520619e+00,0.000000000000000000e+00,1.000000009961587111e+00,0.000000000000000000e+00,-3.431059525452772603e-10,0.000000000000000000e+00 +2.717878815408861115e+01,1.442199999999999989e+02,0.000000000000000000e+00,7.495087306327405052e+00,0.000000000000000000e+00,1.000000009961129255e+00,0.000000000000000000e+00,1.582695758521293687e-10,0.000000000000000000e+00 +2.718012236136216231e+01,1.442299999999999898e+02,0.000000000000000000e+00,7.496421513614246024e+00,0.000000000000000000e+00,1.000000009961340419e+00,0.000000000000000000e+00,1.989125244243666838e-10,0.000000000000000000e+00 +2.718145633117453741e+01,1.442400000000000091e+02,0.000000000000000000e+00,7.497755483439909163e+00,0.000000000000000000e+00,1.000000009961605762e+00,0.000000000000000000e+00,-3.001699585923257844e-10,0.000000000000000000e+00 +2.718279006365249018e+01,1.442500000000000000e+02,0.000000000000000000e+00,7.499089215931146413e+00,0.000000000000000000e+00,1.000000009961205416e+00,0.000000000000000000e+00,7.992635050795172489e-11,0.000000000000000000e+00 +2.718412355892265708e+01,1.442599999999999909e+02,0.000000000000000000e+00,7.500422711214596028e+00,0.000000000000000000e+00,1.000000009961311997e+00,0.000000000000000000e+00,-2.379897180288116595e-10,0.000000000000000000e+00 +2.718545681711156448e+01,1.442700000000000102e+02,0.000000000000000000e+00,7.501755969416785241e+00,0.000000000000000000e+00,1.000000009960994696e+00,0.000000000000000000e+00,6.666229210773527033e-10,0.000000000000000000e+00 +2.718678983834562857e+01,1.442800000000000011e+02,0.000000000000000000e+00,7.503088990664127600e+00,0.000000000000000000e+00,1.000000009961883318e+00,0.000000000000000000e+00,-7.845290207927874319e-10,0.000000000000000000e+00 +2.718812262275115188e+01,1.442899999999999920e+02,0.000000000000000000e+00,7.504421775082926516e+00,0.000000000000000000e+00,1.000000009960837710e+00,0.000000000000000000e+00,3.304305358218116628e-10,0.000000000000000000e+00 +2.718945517045431970e+01,1.443000000000000114e+02,0.000000000000000000e+00,7.505754322799369049e+00,0.000000000000000000e+00,1.000000009961278025e+00,0.000000000000000000e+00,-6.799777993342953412e-11,0.000000000000000000e+00 +2.719078748158121428e+01,1.443100000000000023e+02,0.000000000000000000e+00,7.507086633939534792e+00,0.000000000000000000e+00,1.000000009961187430e+00,0.000000000000000000e+00,-5.684156572479406359e-11,0.000000000000000000e+00 +2.719211955625780064e+01,1.443199999999999932e+02,0.000000000000000000e+00,7.508418708629388760e+00,0.000000000000000000e+00,1.000000009961111713e+00,0.000000000000000000e+00,2.855920222062855939e-10,0.000000000000000000e+00 +2.719345139460993011e+01,1.443300000000000125e+02,0.000000000000000000e+00,7.509750546994784948e+00,0.000000000000000000e+00,1.000000009961492076e+00,0.000000000000000000e+00,-1.200599707170956352e-10,0.000000000000000000e+00 +2.719478299676334743e+01,1.443400000000000034e+02,0.000000000000000000e+00,7.511082149161466326e+00,0.000000000000000000e+00,1.000000009961332204e+00,0.000000000000000000e+00,-3.504037858845396495e-10,0.000000000000000000e+00 +2.719611436284368367e+01,1.443499999999999943e+02,0.000000000000000000e+00,7.512413515255063068e+00,0.000000000000000000e+00,1.000000009960865688e+00,0.000000000000000000e+00,5.191098852879995606e-10,0.000000000000000000e+00 +2.719744549297645619e+01,1.443600000000000136e+02,0.000000000000000000e+00,7.513744645401094324e+00,0.000000000000000000e+00,1.000000009961556691e+00,0.000000000000000000e+00,-5.966149985593264228e-10,0.000000000000000000e+00 +2.719877638728707581e+01,1.443700000000000045e+02,0.000000000000000000e+00,7.515075539724970000e+00,0.000000000000000000e+00,1.000000009960762659e+00,0.000000000000000000e+00,2.354510272651196098e-10,0.000000000000000000e+00 +2.720010704590083606e+01,1.443799999999999955e+02,0.000000000000000000e+00,7.516406198351985424e+00,0.000000000000000000e+00,1.000000009961075964e+00,0.000000000000000000e+00,4.309299762393875855e-10,0.000000000000000000e+00 +2.720143746894292747e+01,1.443900000000000148e+02,0.000000000000000000e+00,7.517736621407328457e+00,0.000000000000000000e+00,1.000000009961649283e+00,0.000000000000000000e+00,-5.905887371713075158e-10,0.000000000000000000e+00 +2.720276765653842332e+01,1.444000000000000057e+02,0.000000000000000000e+00,7.519066809016075048e+00,0.000000000000000000e+00,1.000000009960863689e+00,0.000000000000000000e+00,1.048488841540094953e-10,0.000000000000000000e+00 +2.720409760881229033e+01,1.444099999999999966e+02,0.000000000000000000e+00,7.520396761303188349e+00,0.000000000000000000e+00,1.000000009961003133e+00,0.000000000000000000e+00,4.331625990965475270e-10,0.000000000000000000e+00 +2.720542732588938151e+01,1.444200000000000159e+02,0.000000000000000000e+00,7.521726478393524040e+00,0.000000000000000000e+00,1.000000009961579117e+00,0.000000000000000000e+00,-6.891075143811526885e-10,0.000000000000000000e+00 +2.720675680789443973e+01,1.444300000000000068e+02,0.000000000000000000e+00,7.523055960411826781e+00,0.000000000000000000e+00,1.000000009960662961e+00,0.000000000000000000e+00,1.784044859780527179e-10,0.000000000000000000e+00 +2.720808605495210131e+01,1.444399999999999977e+02,0.000000000000000000e+00,7.524385207482728433e+00,0.000000000000000000e+00,1.000000009960900105e+00,0.000000000000000000e+00,4.465912453089101028e-10,0.000000000000000000e+00 +2.720941506718688885e+01,1.444500000000000171e+02,0.000000000000000000e+00,7.525714219730754273e+00,0.000000000000000000e+00,1.000000009961493630e+00,0.000000000000000000e+00,-4.653858210346173725e-10,0.000000000000000000e+00 +2.721074384472321483e+01,1.444600000000000080e+02,0.000000000000000000e+00,7.527042997280318559e+00,0.000000000000000000e+00,1.000000009960875236e+00,0.000000000000000000e+00,3.835723667302188976e-10,0.000000000000000000e+00 +2.721207238768538517e+01,1.444699999999999989e+02,0.000000000000000000e+00,7.528371540255723637e+00,0.000000000000000000e+00,1.000000009961384828e+00,0.000000000000000000e+00,-6.046301206620296881e-10,0.000000000000000000e+00 +2.721340069619759561e+01,1.444799999999999898e+02,0.000000000000000000e+00,7.529699848781165272e+00,0.000000000000000000e+00,1.000000009960581693e+00,0.000000000000000000e+00,5.191340253333347474e-10,0.000000000000000000e+00 +2.721472877038392824e+01,1.444900000000000091e+02,0.000000000000000000e+00,7.531027922980726430e+00,0.000000000000000000e+00,1.000000009961271141e+00,0.000000000000000000e+00,-3.489931738101143170e-10,0.000000000000000000e+00 +2.721605661036835855e+01,1.445000000000000000e+02,0.000000000000000000e+00,7.532355762978384384e+00,0.000000000000000000e+00,1.000000009960807734e+00,0.000000000000000000e+00,2.396719669028440853e-10,0.000000000000000000e+00 +2.721738421627475546e+01,1.445099999999999909e+02,0.000000000000000000e+00,7.533683368898003607e+00,0.000000000000000000e+00,1.000000009961125924e+00,0.000000000000000000e+00,-3.099723873704718415e-10,0.000000000000000000e+00 +2.721871158822687065e+01,1.445200000000000102e+02,0.000000000000000000e+00,7.535010740863341994e+00,0.000000000000000000e+00,1.000000009960714475e+00,0.000000000000000000e+00,4.455487890391092230e-10,0.000000000000000000e+00 +2.722003872634835631e+01,1.445300000000000011e+02,0.000000000000000000e+00,7.536337878998046413e+00,0.000000000000000000e+00,1.000000009961305780e+00,0.000000000000000000e+00,-5.948948258413645760e-10,0.000000000000000000e+00 +2.722136563076275095e+01,1.445399999999999920e+02,0.000000000000000000e+00,7.537664783425657156e+00,0.000000000000000000e+00,1.000000009960516412e+00,0.000000000000000000e+00,5.273821764312068830e-10,0.000000000000000000e+00 +2.722269230159348297e+01,1.445500000000000114e+02,0.000000000000000000e+00,7.538991454269602599e+00,0.000000000000000000e+00,1.000000009961216074e+00,0.000000000000000000e+00,-2.996446358403701421e-10,0.000000000000000000e+00 +2.722401873896387414e+01,1.445600000000000023e+02,0.000000000000000000e+00,7.540317891653206317e+00,0.000000000000000000e+00,1.000000009960818614e+00,0.000000000000000000e+00,3.810677000926675957e-10,0.000000000000000000e+00 +2.722534494299713614e+01,1.445699999999999932e+02,0.000000000000000000e+00,7.541644095699679973e+00,0.000000000000000000e+00,1.000000009961323988e+00,0.000000000000000000e+00,-5.362009590654886758e-10,0.000000000000000000e+00 +2.722667091381637761e+01,1.445800000000000125e+02,0.000000000000000000e+00,7.542970066532129536e+00,0.000000000000000000e+00,1.000000009960613001e+00,0.000000000000000000e+00,4.088371848266476336e-10,0.000000000000000000e+00 +2.722799665154459348e+01,1.445900000000000034e+02,0.000000000000000000e+00,7.544295804273549955e+00,0.000000000000000000e+00,1.000000009961155012e+00,0.000000000000000000e+00,-3.958427138405972840e-10,0.000000000000000000e+00 +2.722932215630467212e+01,1.445999999999999943e+02,0.000000000000000000e+00,7.545621309046831371e+00,0.000000000000000000e+00,1.000000009960630321e+00,0.000000000000000000e+00,6.031672208932324328e-12,0.000000000000000000e+00 +2.723064742821939177e+01,1.446100000000000136e+02,0.000000000000000000e+00,7.546946580974752905e+00,0.000000000000000000e+00,1.000000009960638314e+00,0.000000000000000000e+00,5.287018925542806751e-10,0.000000000000000000e+00 +2.723197246741142763e+01,1.446200000000000045e+02,0.000000000000000000e+00,7.548271620179987984e+00,0.000000000000000000e+00,1.000000009961338865e+00,0.000000000000000000e+00,-4.210245110301464781e-10,0.000000000000000000e+00 +2.723329727400334477e+01,1.446299999999999955e+02,0.000000000000000000e+00,7.549596426785102565e+00,0.000000000000000000e+00,1.000000009960781089e+00,0.000000000000000000e+00,1.168413967682461510e-10,0.000000000000000000e+00 +2.723462184811760167e+01,1.446400000000000148e+02,0.000000000000000000e+00,7.550921000912552472e+00,0.000000000000000000e+00,1.000000009960935854e+00,0.000000000000000000e+00,-4.625853265220520946e-10,0.000000000000000000e+00 +2.723594618987654670e+01,1.446500000000000057e+02,0.000000000000000000e+00,7.552245342684688723e+00,0.000000000000000000e+00,1.000000009960323233e+00,0.000000000000000000e+00,8.030843311716434731e-10,0.000000000000000000e+00 +2.723727029940242161e+01,1.446599999999999966e+02,0.000000000000000000e+00,7.553569452223753089e+00,0.000000000000000000e+00,1.000000009961386604e+00,0.000000000000000000e+00,-7.191959430471562218e-10,0.000000000000000000e+00 +2.723859417681736517e+01,1.446700000000000159e+02,0.000000000000000000e+00,7.554893329651883427e+00,0.000000000000000000e+00,1.000000009960434477e+00,0.000000000000000000e+00,4.681967543231559647e-10,0.000000000000000000e+00 +2.723991782224340241e+01,1.446800000000000068e+02,0.000000000000000000e+00,7.556216975091105681e+00,0.000000000000000000e+00,1.000000009961054204e+00,0.000000000000000000e+00,-2.697930078442766688e-10,0.000000000000000000e+00 +2.724124123580245893e+01,1.446899999999999977e+02,0.000000000000000000e+00,7.557540388663343656e+00,0.000000000000000000e+00,1.000000009960697156e+00,0.000000000000000000e+00,3.289097696819210478e-11,0.000000000000000000e+00 +2.724256441761634662e+01,1.447000000000000171e+02,0.000000000000000000e+00,7.558863570490411021e+00,0.000000000000000000e+00,1.000000009960740677e+00,0.000000000000000000e+00,-2.191996767000431820e-10,0.000000000000000000e+00 +2.724388736780677434e+01,1.447100000000000080e+02,0.000000000000000000e+00,7.560186520694016643e+00,0.000000000000000000e+00,1.000000009960450686e+00,0.000000000000000000e+00,4.216890956417389404e-10,0.000000000000000000e+00 +2.724521008649534437e+01,1.447199999999999989e+02,0.000000000000000000e+00,7.561509239395761917e+00,0.000000000000000000e+00,1.000000009961008463e+00,0.000000000000000000e+00,-1.492624182880060882e-10,0.000000000000000000e+00 +2.724653257380355242e+01,1.447299999999999898e+02,0.000000000000000000e+00,7.562831726717143432e+00,0.000000000000000000e+00,1.000000009960811065e+00,0.000000000000000000e+00,2.434964675166430667e-11,0.000000000000000000e+00 +2.724785482985278762e+01,1.447400000000000091e+02,0.000000000000000000e+00,7.564153982779549423e+00,0.000000000000000000e+00,1.000000009960843261e+00,0.000000000000000000e+00,-1.472991294026485478e-10,0.000000000000000000e+00 +2.724917685476433249e+01,1.447500000000000000e+02,0.000000000000000000e+00,7.565476007704263317e+00,0.000000000000000000e+00,1.000000009960648528e+00,0.000000000000000000e+00,-2.308145682269481705e-10,0.000000000000000000e+00 +2.725049864865936655e+01,1.447599999999999909e+02,0.000000000000000000e+00,7.566797801612461960e+00,0.000000000000000000e+00,1.000000009960343439e+00,0.000000000000000000e+00,2.090127285737853431e-10,0.000000000000000000e+00 +2.725182021165895918e+01,1.447700000000000102e+02,0.000000000000000000e+00,7.568119364625216505e+00,0.000000000000000000e+00,1.000000009960619662e+00,0.000000000000000000e+00,8.099817558336562890e-11,0.000000000000000000e+00 +2.725314154388407317e+01,1.447800000000000011e+02,0.000000000000000000e+00,7.569440696863493301e+00,0.000000000000000000e+00,1.000000009960726688e+00,0.000000000000000000e+00,-1.805129225747357643e-10,0.000000000000000000e+00 +2.725446264545557185e+01,1.447899999999999920e+02,0.000000000000000000e+00,7.570761798448152113e+00,0.000000000000000000e+00,1.000000009960488212e+00,0.000000000000000000e+00,3.684854613039323383e-10,0.000000000000000000e+00 +2.725578351649421194e+01,1.448000000000000114e+02,0.000000000000000000e+00,7.572082669499947016e+00,0.000000000000000000e+00,1.000000009960974934e+00,0.000000000000000000e+00,-3.813279357706340483e-10,0.000000000000000000e+00 +2.725710415712063650e+01,1.448100000000000023e+02,0.000000000000000000e+00,7.573403310139528166e+00,0.000000000000000000e+00,1.000000009960471337e+00,0.000000000000000000e+00,4.170450697925882041e-11,0.000000000000000000e+00 +2.725842456745539621e+01,1.448199999999999932e+02,0.000000000000000000e+00,7.574723720487438250e+00,0.000000000000000000e+00,1.000000009960526404e+00,0.000000000000000000e+00,3.632961317612896516e-11,0.000000000000000000e+00 +2.725974474761892452e+01,1.448300000000000125e+02,0.000000000000000000e+00,7.576043900664116926e+00,0.000000000000000000e+00,1.000000009960574365e+00,0.000000000000000000e+00,3.902749645576963711e-11,0.000000000000000000e+00 +2.726106469773155894e+01,1.448400000000000034e+02,0.000000000000000000e+00,7.577363850789898159e+00,0.000000000000000000e+00,1.000000009960625880e+00,0.000000000000000000e+00,-2.405993250549255225e-11,0.000000000000000000e+00 +2.726238441791352685e+01,1.448499999999999943e+02,0.000000000000000000e+00,7.578683570985011109e+00,0.000000000000000000e+00,1.000000009960594127e+00,0.000000000000000000e+00,2.840576189338572436e-10,0.000000000000000000e+00 +2.726370390828495260e+01,1.448600000000000136e+02,0.000000000000000000e+00,7.580003061369580131e+00,0.000000000000000000e+00,1.000000009960968939e+00,0.000000000000000000e+00,-6.404190877276339688e-10,0.000000000000000000e+00 +2.726502316896585754e+01,1.448700000000000045e+02,0.000000000000000000e+00,7.581322322063625663e+00,0.000000000000000000e+00,1.000000009960124059e+00,0.000000000000000000e+00,7.014693296456348657e-10,0.000000000000000000e+00 +2.726634220007615639e+01,1.448799999999999955e+02,0.000000000000000000e+00,7.582641353187061561e+00,0.000000000000000000e+00,1.000000009961049319e+00,0.000000000000000000e+00,-8.674343077523736114e-10,0.000000000000000000e+00 +2.726766100173566088e+01,1.448900000000000148e+02,0.000000000000000000e+00,7.583960154859701319e+00,0.000000000000000000e+00,1.000000009959905345e+00,0.000000000000000000e+00,7.069337277809900148e-10,0.000000000000000000e+00 +2.726897957406407613e+01,1.449000000000000057e+02,0.000000000000000000e+00,7.585278727201249183e+00,0.000000000000000000e+00,1.000000009960837488e+00,0.000000000000000000e+00,-2.661146944799679909e-10,0.000000000000000000e+00 +2.727029791718100427e+01,1.449099999999999966e+02,0.000000000000000000e+00,7.586597070331310810e+00,0.000000000000000000e+00,1.000000009960486658e+00,0.000000000000000000e+00,2.274159981429606220e-10,0.000000000000000000e+00 +2.727161603120594791e+01,1.449200000000000159e+02,0.000000000000000000e+00,7.587915184369383503e+00,0.000000000000000000e+00,1.000000009960786418e+00,0.000000000000000000e+00,-4.400842903778474462e-10,0.000000000000000000e+00 +2.727293391625829955e+01,1.449300000000000068e+02,0.000000000000000000e+00,7.589233069434863310e+00,0.000000000000000000e+00,1.000000009960206437e+00,0.000000000000000000e+00,2.148564029697974836e-10,0.000000000000000000e+00 +2.727425157245735221e+01,1.449399999999999977e+02,0.000000000000000000e+00,7.590550725647040586e+00,0.000000000000000000e+00,1.000000009960489544e+00,0.000000000000000000e+00,7.449648499715504931e-11,0.000000000000000000e+00 +2.727556899992229233e+01,1.449500000000000171e+02,0.000000000000000000e+00,7.591868153125104435e+00,0.000000000000000000e+00,1.000000009960587688e+00,0.000000000000000000e+00,-4.224447811947198973e-10,0.000000000000000000e+00 +2.727688619877220688e+01,1.449600000000000080e+02,0.000000000000000000e+00,7.593185351988139153e+00,0.000000000000000000e+00,1.000000009960031244e+00,0.000000000000000000e+00,6.995321216818070740e-10,0.000000000000000000e+00 +2.727820316912607623e+01,1.449699999999999989e+02,0.000000000000000000e+00,7.594502322355125123e+00,0.000000000000000000e+00,1.000000009960952507e+00,0.000000000000000000e+00,-7.279835961961261108e-10,0.000000000000000000e+00 +2.727951991110277774e+01,1.449799999999999898e+02,0.000000000000000000e+00,7.595819064344942362e+00,0.000000000000000000e+00,1.000000009959993941e+00,0.000000000000000000e+00,3.442372322821191471e-10,0.000000000000000000e+00 +2.728083642482108573e+01,1.449900000000000091e+02,0.000000000000000000e+00,7.597135578076363416e+00,0.000000000000000000e+00,1.000000009960447134e+00,0.000000000000000000e+00,2.591082958841649319e-10,0.000000000000000000e+00 +2.728215271039967504e+01,1.450000000000000000e+02,0.000000000000000000e+00,7.598451863668062245e+00,0.000000000000000000e+00,1.000000009960788194e+00,0.000000000000000000e+00,-5.442891851046997428e-10,0.000000000000000000e+00 +2.728346876795711040e+01,1.450099999999999909e+02,0.000000000000000000e+00,7.599767921238608004e+00,0.000000000000000000e+00,1.000000009960071878e+00,0.000000000000000000e+00,4.264280825554403161e-10,0.000000000000000000e+00 +2.728478459761186414e+01,1.450200000000000102e+02,0.000000000000000000e+00,7.601083750906465930e+00,0.000000000000000000e+00,1.000000009960632985e+00,0.000000000000000000e+00,-4.909750968315342775e-10,0.000000000000000000e+00 +2.728610019948229493e+01,1.450300000000000011e+02,0.000000000000000000e+00,7.602399352790001785e+00,0.000000000000000000e+00,1.000000009959987057e+00,0.000000000000000000e+00,2.236695083023654704e-10,0.000000000000000000e+00 +2.728741557368666903e+01,1.450399999999999920e+02,0.000000000000000000e+00,7.603714727007475638e+00,0.000000000000000000e+00,1.000000009960281266e+00,0.000000000000000000e+00,-6.719688053433647747e-11,0.000000000000000000e+00 +2.728873072034314262e+01,1.450500000000000114e+02,0.000000000000000000e+00,7.605029873677048080e+00,0.000000000000000000e+00,1.000000009960192893e+00,0.000000000000000000e+00,1.043589317613594848e-10,0.000000000000000000e+00 +2.729004563956977236e+01,1.450600000000000023e+02,0.000000000000000000e+00,7.606344792916775788e+00,0.000000000000000000e+00,1.000000009960330116e+00,0.000000000000000000e+00,1.543698311562631727e-10,0.000000000000000000e+00 +2.729136033148451546e+01,1.450699999999999932e+02,0.000000000000000000e+00,7.607659484844614184e+00,0.000000000000000000e+00,1.000000009960533065e+00,0.000000000000000000e+00,1.081113436618553179e-11,0.000000000000000000e+00 +2.729267479620522607e+01,1.450800000000000125e+02,0.000000000000000000e+00,7.608973949578416551e+00,0.000000000000000000e+00,1.000000009960547276e+00,0.000000000000000000e+00,-3.978846952192232344e-10,0.000000000000000000e+00 +2.729398903384965180e+01,1.450900000000000034e+02,0.000000000000000000e+00,7.610288187235934032e+00,0.000000000000000000e+00,1.000000009960024361e+00,0.000000000000000000e+00,4.003191714910132096e-10,0.000000000000000000e+00 +2.729530304453544431e+01,1.450999999999999943e+02,0.000000000000000000e+00,7.611602197934815628e+00,0.000000000000000000e+00,1.000000009960550384e+00,0.000000000000000000e+00,-2.371231629650371447e-10,0.000000000000000000e+00 +2.729661682838015224e+01,1.451100000000000136e+02,0.000000000000000000e+00,7.612915981792610864e+00,0.000000000000000000e+00,1.000000009960238856e+00,0.000000000000000000e+00,-3.243890882367322096e-10,0.000000000000000000e+00 +2.729793038550122475e+01,1.451200000000000045e+02,0.000000000000000000e+00,7.614229538926765350e+00,0.000000000000000000e+00,1.000000009959812752e+00,0.000000000000000000e+00,5.841363627688161108e-10,0.000000000000000000e+00 +2.729924371601600441e+01,1.451299999999999955e+02,0.000000000000000000e+00,7.615542869454624331e+00,0.000000000000000000e+00,1.000000009960579916e+00,0.000000000000000000e+00,-1.577693863819265912e-10,0.000000000000000000e+00 +2.730055682004173434e+01,1.451400000000000148e+02,0.000000000000000000e+00,7.616855973493433574e+00,0.000000000000000000e+00,1.000000009960372749e+00,0.000000000000000000e+00,-5.611672930794500715e-10,0.000000000000000000e+00 +2.730186969769555816e+01,1.451500000000000057e+02,0.000000000000000000e+00,7.618168851160334931e+00,0.000000000000000000e+00,1.000000009959636005e+00,0.000000000000000000e+00,8.503538942946198155e-10,0.000000000000000000e+00 +2.730318234909452002e+01,1.451599999999999966e+02,0.000000000000000000e+00,7.619481502572369891e+00,0.000000000000000000e+00,1.000000009960752223e+00,0.000000000000000000e+00,-6.330957931816217833e-10,0.000000000000000000e+00 +2.730449477435556105e+01,1.451700000000000159e+02,0.000000000000000000e+00,7.620793927846482241e+00,0.000000000000000000e+00,1.000000009959921332e+00,0.000000000000000000e+00,7.327036246079836813e-11,0.000000000000000000e+00 +2.730580697359551934e+01,1.451800000000000068e+02,0.000000000000000000e+00,7.622106127099510076e+00,0.000000000000000000e+00,1.000000009960017477e+00,0.000000000000000000e+00,3.215650333008095317e-10,0.000000000000000000e+00 +2.730711894693113706e+01,1.451899999999999977e+02,0.000000000000000000e+00,7.623418100448194679e+00,0.000000000000000000e+00,1.000000009960439362e+00,0.000000000000000000e+00,-4.754903458561216618e-10,0.000000000000000000e+00 +2.730843069447905336e+01,1.452000000000000171e+02,0.000000000000000000e+00,7.624729848009176081e+00,0.000000000000000000e+00,1.000000009959815639e+00,0.000000000000000000e+00,1.930054344507872243e-10,0.000000000000000000e+00 +2.730974221635580790e+01,1.452100000000000080e+02,0.000000000000000000e+00,7.626041369898992173e+00,0.000000000000000000e+00,1.000000009960068770e+00,0.000000000000000000e+00,1.915146439070039210e-10,0.000000000000000000e+00 +2.731105351267783732e+01,1.452199999999999989e+02,0.000000000000000000e+00,7.627352666234083145e+00,0.000000000000000000e+00,1.000000009960319902e+00,0.000000000000000000e+00,-3.302544393325770581e-11,0.000000000000000000e+00 +2.731236458356148233e+01,1.452299999999999898e+02,0.000000000000000000e+00,7.628663737130787936e+00,0.000000000000000000e+00,1.000000009960276603e+00,0.000000000000000000e+00,-5.517044108634955651e-10,0.000000000000000000e+00 +2.731367542912298418e+01,1.452400000000000091e+02,0.000000000000000000e+00,7.629974582705345121e+00,0.000000000000000000e+00,1.000000009959553404e+00,0.000000000000000000e+00,6.339676536733707639e-10,0.000000000000000000e+00 +2.731498604947847753e+01,1.452500000000000000e+02,0.000000000000000000e+00,7.631285203073892909e+00,0.000000000000000000e+00,1.000000009960384295e+00,0.000000000000000000e+00,-1.645345622455163141e-10,0.000000000000000000e+00 +2.731629644474400465e+01,1.452599999999999909e+02,0.000000000000000000e+00,7.632595598352472699e+00,0.000000000000000000e+00,1.000000009960168690e+00,0.000000000000000000e+00,8.507778904427313799e-11,0.000000000000000000e+00 +2.731760661503550480e+01,1.452700000000000102e+02,0.000000000000000000e+00,7.633905768657022861e+00,0.000000000000000000e+00,1.000000009960280156e+00,0.000000000000000000e+00,-2.388350234924840034e-10,0.000000000000000000e+00 +2.731891656046881778e+01,1.452800000000000011e+02,0.000000000000000000e+00,7.635215714103384066e+00,0.000000000000000000e+00,1.000000009959967295e+00,0.000000000000000000e+00,-1.698749173668987447e-10,0.000000000000000000e+00 +2.732022628115968388e+01,1.452899999999999920e+02,0.000000000000000000e+00,7.636525434807296620e+00,0.000000000000000000e+00,1.000000009959744807e+00,0.000000000000000000e+00,2.222996197128149738e-10,0.000000000000000000e+00 +2.732153577722374749e+01,1.453000000000000114e+02,0.000000000000000000e+00,7.637834930884402240e+00,0.000000000000000000e+00,1.000000009960035907e+00,0.000000000000000000e+00,-1.677284699274011567e-10,0.000000000000000000e+00 +2.732284504877654996e+01,1.453100000000000023e+02,0.000000000000000000e+00,7.639144202450244059e+00,0.000000000000000000e+00,1.000000009959816305e+00,0.000000000000000000e+00,1.448581065964240371e-10,0.000000000000000000e+00 +2.732415409593353317e+01,1.453199999999999932e+02,0.000000000000000000e+00,7.640453249620264842e+00,0.000000000000000000e+00,1.000000009960005931e+00,0.000000000000000000e+00,5.479764197130134012e-11,0.000000000000000000e+00 +2.732546291881004308e+01,1.453300000000000125e+02,0.000000000000000000e+00,7.641762072509809656e+00,0.000000000000000000e+00,1.000000009960077652e+00,0.000000000000000000e+00,1.119895946612209210e-11,0.000000000000000000e+00 +2.732677151752132261e+01,1.453400000000000034e+02,0.000000000000000000e+00,7.643070671234124092e+00,0.000000000000000000e+00,1.000000009960092306e+00,0.000000000000000000e+00,-5.515583474726893515e-11,0.000000000000000000e+00 +2.732807989218252231e+01,1.453499999999999943e+02,0.000000000000000000e+00,7.644379045908355153e+00,0.000000000000000000e+00,1.000000009960020142e+00,0.000000000000000000e+00,-2.131925765183260834e-10,0.000000000000000000e+00 +2.732938804290868973e+01,1.453600000000000136e+02,0.000000000000000000e+00,7.645687196647551254e+00,0.000000000000000000e+00,1.000000009959741254e+00,0.000000000000000000e+00,-1.290239530649581557e-11,0.000000000000000000e+00 +2.733069596981477289e+01,1.453700000000000045e+02,0.000000000000000000e+00,7.646995123566662222e+00,0.000000000000000000e+00,1.000000009959724379e+00,0.000000000000000000e+00,4.779796841178940577e-10,0.000000000000000000e+00 +2.733200367301562750e+01,1.453799999999999955e+02,0.000000000000000000e+00,7.648302826780540187e+00,0.000000000000000000e+00,1.000000009960349434e+00,0.000000000000000000e+00,-3.683535439177763378e-10,0.000000000000000000e+00 +2.733331115262600264e+01,1.453900000000000148e+02,0.000000000000000000e+00,7.649610306403939575e+00,0.000000000000000000e+00,1.000000009959867819e+00,0.000000000000000000e+00,-2.327019936692797131e-11,0.000000000000000000e+00 +2.733461840876055859e+01,1.454000000000000057e+02,0.000000000000000000e+00,7.650917562551514450e+00,0.000000000000000000e+00,1.000000009959837399e+00,0.000000000000000000e+00,-1.134828438283810698e-10,0.000000000000000000e+00 +2.733592544153384907e+01,1.454099999999999966e+02,0.000000000000000000e+00,7.652224595337822954e+00,0.000000000000000000e+00,1.000000009959689073e+00,0.000000000000000000e+00,3.321809290720666085e-10,0.000000000000000000e+00 +2.733723225106033539e+01,1.454200000000000159e+02,0.000000000000000000e+00,7.653531404877324640e+00,0.000000000000000000e+00,1.000000009960123171e+00,0.000000000000000000e+00,-3.149035186664246727e-10,0.000000000000000000e+00 +2.733853883745437940e+01,1.454300000000000068e+02,0.000000000000000000e+00,7.654837991284382248e+00,0.000000000000000000e+00,1.000000009959711722e+00,0.000000000000000000e+00,-4.283283003400449768e-11,0.000000000000000000e+00 +2.733984520083024350e+01,1.454399999999999977e+02,0.000000000000000000e+00,7.656144354673259045e+00,0.000000000000000000e+00,1.000000009959655767e+00,0.000000000000000000e+00,4.029013149903365166e-11,0.000000000000000000e+00 +2.734115134130209768e+01,1.454500000000000171e+02,0.000000000000000000e+00,7.657450495158122372e+00,0.000000000000000000e+00,1.000000009959708391e+00,0.000000000000000000e+00,3.868172421591592815e-10,0.000000000000000000e+00 +2.734245725898400892e+01,1.454600000000000080e+02,0.000000000000000000e+00,7.658756412853041873e+00,0.000000000000000000e+00,1.000000009960213543e+00,0.000000000000000000e+00,-6.338082314694856143e-10,0.000000000000000000e+00 +2.734376295398995182e+01,1.454699999999999989e+02,0.000000000000000000e+00,7.660062107871990378e+00,0.000000000000000000e+00,1.000000009959385983e+00,0.000000000000000000e+00,5.566965395124029238e-10,0.000000000000000000e+00 +2.734506842643380153e+01,1.454799999999999898e+02,0.000000000000000000e+00,7.661367580328841242e+00,0.000000000000000000e+00,1.000000009960112735e+00,0.000000000000000000e+00,-2.778002996234762822e-10,0.000000000000000000e+00 +2.734637367642933370e+01,1.454900000000000091e+02,0.000000000000000000e+00,7.662672830337374563e+00,0.000000000000000000e+00,1.000000009959750136e+00,0.000000000000000000e+00,-7.826693741897354681e-11,0.000000000000000000e+00 +2.734767870409023161e+01,1.455000000000000000e+02,0.000000000000000000e+00,7.663977858011270072e+00,0.000000000000000000e+00,1.000000009959647995e+00,0.000000000000000000e+00,4.577693876861646982e-11,0.000000000000000000e+00 +2.734898350953007906e+01,1.455099999999999909e+02,0.000000000000000000e+00,7.665282663464112467e+00,0.000000000000000000e+00,1.000000009959707725e+00,0.000000000000000000e+00,2.570072337577846490e-11,0.000000000000000000e+00 +2.735028809286236395e+01,1.455200000000000102e+02,0.000000000000000000e+00,7.666587246809389633e+00,0.000000000000000000e+00,1.000000009959741254e+00,0.000000000000000000e+00,-2.054705473963676578e-10,0.000000000000000000e+00 +2.735159245420047469e+01,1.455300000000000011e+02,0.000000000000000000e+00,7.667891608160492645e+00,0.000000000000000000e+00,1.000000009959473246e+00,0.000000000000000000e+00,3.287747562054723603e-10,0.000000000000000000e+00 +2.735289659365771087e+01,1.455399999999999920e+02,0.000000000000000000e+00,7.669195747630715765e+00,0.000000000000000000e+00,1.000000009959902014e+00,0.000000000000000000e+00,-5.960162389563873876e-12,0.000000000000000000e+00 +2.735420051134726549e+01,1.455500000000000114e+02,0.000000000000000000e+00,7.670499665333258221e+00,0.000000000000000000e+00,1.000000009959894243e+00,0.000000000000000000e+00,-2.318045765230217473e-10,0.000000000000000000e+00 +2.735550420738224275e+01,1.455600000000000023e+02,0.000000000000000000e+00,7.671803361381221542e+00,0.000000000000000000e+00,1.000000009959592040e+00,0.000000000000000000e+00,1.059566143885941605e-10,0.000000000000000000e+00 +2.735680768187565093e+01,1.455699999999999932e+02,0.000000000000000000e+00,7.673106835887611332e+00,0.000000000000000000e+00,1.000000009959730152e+00,0.000000000000000000e+00,-1.046115993216244176e-10,0.000000000000000000e+00 +2.735811093494039881e+01,1.455800000000000125e+02,0.000000000000000000e+00,7.674410088965338161e+00,0.000000000000000000e+00,1.000000009959593816e+00,0.000000000000000000e+00,1.146833292747489460e-10,0.000000000000000000e+00 +2.735941396668929926e+01,1.455900000000000034e+02,0.000000000000000000e+00,7.675713120727215788e+00,0.000000000000000000e+00,1.000000009959743252e+00,0.000000000000000000e+00,-3.490510207815175479e-10,0.000000000000000000e+00 +2.736071677723506923e+01,1.455999999999999943e+02,0.000000000000000000e+00,7.677015931285962935e+00,0.000000000000000000e+00,1.000000009959288505e+00,0.000000000000000000e+00,5.306544224946296604e-10,0.000000000000000000e+00 +2.736201936669033330e+01,1.456100000000000136e+02,0.000000000000000000e+00,7.678318520754201515e+00,0.000000000000000000e+00,1.000000009959979730e+00,0.000000000000000000e+00,-4.543636324474397242e-10,0.000000000000000000e+00 +2.736332173516762012e+01,1.456200000000000045e+02,0.000000000000000000e+00,7.679620889244460180e+00,0.000000000000000000e+00,1.000000009959387981e+00,0.000000000000000000e+00,2.944912153185527009e-10,0.000000000000000000e+00 +2.736462388277935887e+01,1.456299999999999955e+02,0.000000000000000000e+00,7.680923036869168996e+00,0.000000000000000000e+00,1.000000009959771452e+00,0.000000000000000000e+00,-4.320050551151945014e-10,0.000000000000000000e+00 +2.736592580963788990e+01,1.456400000000000148e+02,0.000000000000000000e+00,7.682224963740665657e+00,0.000000000000000000e+00,1.000000009959209013e+00,0.000000000000000000e+00,4.435071178249423248e-10,0.000000000000000000e+00 +2.736722751585545055e+01,1.456500000000000057e+02,0.000000000000000000e+00,7.683526669971190159e+00,0.000000000000000000e+00,1.000000009959786329e+00,0.000000000000000000e+00,-2.900345594569979861e-10,0.000000000000000000e+00 +2.736852900154418933e+01,1.456599999999999966e+02,0.000000000000000000e+00,7.684828155672890126e+00,0.000000000000000000e+00,1.000000009959408853e+00,0.000000000000000000e+00,4.457050538113091479e-10,0.000000000000000000e+00 +2.736983026681615527e+01,1.456700000000000159e+02,0.000000000000000000e+00,7.686129420957815483e+00,0.000000000000000000e+00,1.000000009959988834e+00,0.000000000000000000e+00,-5.614923147534692259e-10,0.000000000000000000e+00 +2.737113131178330505e+01,1.456800000000000068e+02,0.000000000000000000e+00,7.687430465937923785e+00,0.000000000000000000e+00,1.000000009959258307e+00,0.000000000000000000e+00,2.935958232400277274e-10,0.000000000000000000e+00 +2.737243213655749940e+01,1.456899999999999977e+02,0.000000000000000000e+00,7.688731290725074885e+00,0.000000000000000000e+00,1.000000009959640224e+00,0.000000000000000000e+00,-2.029909907868468767e-10,0.000000000000000000e+00 +2.737373274125050671e+01,1.457000000000000171e+02,0.000000000000000000e+00,7.690031895431037157e+00,0.000000000000000000e+00,1.000000009959376213e+00,0.000000000000000000e+00,-1.827057200667605448e-11,0.000000000000000000e+00 +2.737503312597399940e+01,1.457100000000000080e+02,0.000000000000000000e+00,7.691332280167482160e+00,0.000000000000000000e+00,1.000000009959352454e+00,0.000000000000000000e+00,2.570267350432877821e-10,0.000000000000000000e+00 +2.737633329083955758e+01,1.457199999999999989e+02,0.000000000000000000e+00,7.692632445045988199e+00,0.000000000000000000e+00,1.000000009959686631e+00,0.000000000000000000e+00,-4.939846982815020163e-10,0.000000000000000000e+00 +2.737763323595866183e+01,1.457299999999999898e+02,0.000000000000000000e+00,7.693932390178039427e+00,0.000000000000000000e+00,1.000000009959044478e+00,0.000000000000000000e+00,2.900856710069080102e-10,0.000000000000000000e+00 +2.737893296144270394e+01,1.457400000000000091e+02,0.000000000000000000e+00,7.695232115675024076e+00,0.000000000000000000e+00,1.000000009959421510e+00,0.000000000000000000e+00,4.418658827972789988e-10,0.000000000000000000e+00 +2.738023246740297623e+01,1.457500000000000000e+02,0.000000000000000000e+00,7.696531621648238897e+00,0.000000000000000000e+00,1.000000009959995717e+00,0.000000000000000000e+00,-6.318074375951340659e-10,0.000000000000000000e+00 +2.738153175395068217e+01,1.457599999999999909e+02,0.000000000000000000e+00,7.697830908208885603e+00,0.000000000000000000e+00,1.000000009959174818e+00,0.000000000000000000e+00,1.601578327956982040e-10,0.000000000000000000e+00 +2.738283082119692935e+01,1.457700000000000102e+02,0.000000000000000000e+00,7.699129975468069986e+00,0.000000000000000000e+00,1.000000009959382874e+00,0.000000000000000000e+00,1.218909345126192203e-10,0.000000000000000000e+00 +2.738412966925272940e+01,1.457800000000000011e+02,0.000000000000000000e+00,7.700428823536807243e+00,0.000000000000000000e+00,1.000000009959541192e+00,0.000000000000000000e+00,-2.870819136795055229e-10,0.000000000000000000e+00 +2.738542829822900515e+01,1.457899999999999920e+02,0.000000000000000000e+00,7.701727452526017537e+00,0.000000000000000000e+00,1.000000009959168379e+00,0.000000000000000000e+00,-7.798179254230017728e-11,0.000000000000000000e+00 +2.738672670823658351e+01,1.458000000000000114e+02,0.000000000000000000e+00,7.703025862546526881e+00,0.000000000000000000e+00,1.000000009959067127e+00,0.000000000000000000e+00,6.841661337505768490e-10,0.000000000000000000e+00 +2.738802489938619544e+01,1.458100000000000023e+02,0.000000000000000000e+00,7.704324053709068920e+00,0.000000000000000000e+00,1.000000009959955305e+00,0.000000000000000000e+00,-7.020727536315889146e-10,0.000000000000000000e+00 +2.738932287178848313e+01,1.458199999999999932e+02,0.000000000000000000e+00,7.705622026124284929e+00,0.000000000000000000e+00,1.000000009959044034e+00,0.000000000000000000e+00,4.431468758095279595e-10,0.000000000000000000e+00 +2.739062062555399280e+01,1.458300000000000125e+02,0.000000000000000000e+00,7.706919779902719370e+00,0.000000000000000000e+00,1.000000009959619129e+00,0.000000000000000000e+00,-6.911859749220613136e-10,0.000000000000000000e+00 +2.739191816079317832e+01,1.458400000000000034e+02,0.000000000000000000e+00,7.708217315154827887e+00,0.000000000000000000e+00,1.000000009958722291e+00,0.000000000000000000e+00,5.773119094780117832e-10,0.000000000000000000e+00 +2.739321547761640119e+01,1.458499999999999943e+02,0.000000000000000000e+00,7.709514631990969313e+00,0.000000000000000000e+00,1.000000009959471248e+00,0.000000000000000000e+00,-3.731846364760718963e-11,0.000000000000000000e+00 +2.739451257613392698e+01,1.458600000000000136e+02,0.000000000000000000e+00,7.710811730521413665e+00,0.000000000000000000e+00,1.000000009959422842e+00,0.000000000000000000e+00,3.869445766242129037e-11,0.000000000000000000e+00 +2.739580945645593246e+01,1.458700000000000045e+02,0.000000000000000000e+00,7.712108610856335034e+00,0.000000000000000000e+00,1.000000009959473024e+00,0.000000000000000000e+00,-3.157724810169755714e-10,0.000000000000000000e+00 +2.739710611869249846e+01,1.458799999999999955e+02,0.000000000000000000e+00,7.713405273105816029e+00,0.000000000000000000e+00,1.000000009959063574e+00,0.000000000000000000e+00,-1.085864496796837194e-10,0.000000000000000000e+00 +2.739840256295361698e+01,1.458900000000000148e+02,0.000000000000000000e+00,7.714701717379846002e+00,0.000000000000000000e+00,1.000000009958922798e+00,0.000000000000000000e+00,5.959554466531288845e-10,0.000000000000000000e+00 +2.739969878934918412e+01,1.459000000000000057e+02,0.000000000000000000e+00,7.715997943788322821e+00,0.000000000000000000e+00,1.000000009959695291e+00,0.000000000000000000e+00,-3.812082965943601017e-10,0.000000000000000000e+00 +2.740099479798900717e+01,1.459099999999999966e+02,0.000000000000000000e+00,7.717293952441052873e+00,0.000000000000000000e+00,1.000000009959201241e+00,0.000000000000000000e+00,6.717247268099619264e-11,0.000000000000000000e+00 +2.740229058898279746e+01,1.459200000000000159e+02,0.000000000000000000e+00,7.718589743447747509e+00,0.000000000000000000e+00,1.000000009959288283e+00,0.000000000000000000e+00,-2.385708724545857094e-10,0.000000000000000000e+00 +2.740358616244017398e+01,1.459300000000000068e+02,0.000000000000000000e+00,7.719885316918028373e+00,0.000000000000000000e+00,1.000000009958979197e+00,0.000000000000000000e+00,2.245548139692713933e-10,0.000000000000000000e+00 +2.740488151847067044e+01,1.459399999999999977e+02,0.000000000000000000e+00,7.721180672961423852e+00,0.000000000000000000e+00,1.000000009959270075e+00,0.000000000000000000e+00,-1.951040130749892605e-10,0.000000000000000000e+00 +2.740617665718372109e+01,1.459500000000000171e+02,0.000000000000000000e+00,7.722475811687371738e+00,0.000000000000000000e+00,1.000000009959017389e+00,0.000000000000000000e+00,2.554953795067356880e-11,0.000000000000000000e+00 +2.740747157868867134e+01,1.459600000000000080e+02,0.000000000000000000e+00,7.723770733205216565e+00,0.000000000000000000e+00,1.000000009959050473e+00,0.000000000000000000e+00,2.937832036749140970e-10,0.000000000000000000e+00 +2.740876628309477425e+01,1.459699999999999989e+02,0.000000000000000000e+00,7.725065437624212272e+00,0.000000000000000000e+00,1.000000009959430836e+00,0.000000000000000000e+00,-5.149357927558081946e-10,0.000000000000000000e+00 +2.741006077051119050e+01,1.459799999999999898e+02,0.000000000000000000e+00,7.726359925053521316e+00,0.000000000000000000e+00,1.000000009958764258e+00,0.000000000000000000e+00,1.857991049643673221e-10,0.000000000000000000e+00 +2.741135504104699194e+01,1.459900000000000091e+02,0.000000000000000000e+00,7.727654195602212894e+00,0.000000000000000000e+00,1.000000009959004732e+00,0.000000000000000000e+00,2.117400760808936392e-10,0.000000000000000000e+00 +2.741264909481115808e+01,1.460000000000000000e+02,0.000000000000000000e+00,7.728948249379267388e+00,0.000000000000000000e+00,1.000000009959278735e+00,0.000000000000000000e+00,2.866006005067451266e-11,0.000000000000000000e+00 +2.741394293191257958e+01,1.460099999999999909e+02,0.000000000000000000e+00,7.730242086493572806e+00,0.000000000000000000e+00,1.000000009959315816e+00,0.000000000000000000e+00,-4.268832414024873520e-10,0.000000000000000000e+00 +2.741523655246004765e+01,1.460200000000000102e+02,0.000000000000000000e+00,7.731535707053925677e+00,0.000000000000000000e+00,1.000000009958763592e+00,0.000000000000000000e+00,3.733922096592021163e-10,0.000000000000000000e+00 +2.741652995656227176e+01,1.460300000000000011e+02,0.000000000000000000e+00,7.732829111169031044e+00,0.000000000000000000e+00,1.000000009959246539e+00,0.000000000000000000e+00,-2.879464315748251133e-10,0.000000000000000000e+00 +2.741782314432786549e+01,1.460399999999999920e+02,0.000000000000000000e+00,7.734122298947505136e+00,0.000000000000000000e+00,1.000000009958874170e+00,0.000000000000000000e+00,1.799751496566633970e-10,0.000000000000000000e+00 +2.741911611586535358e+01,1.460500000000000114e+02,0.000000000000000000e+00,7.735415270497870921e+00,0.000000000000000000e+00,1.000000009959106873e+00,0.000000000000000000e+00,1.209195488278802572e-10,0.000000000000000000e+00 +2.742040887128317195e+01,1.460600000000000023e+02,0.000000000000000000e+00,7.736708025928562549e+00,0.000000000000000000e+00,1.000000009959263192e+00,0.000000000000000000e+00,-5.294550161829964609e-10,0.000000000000000000e+00 +2.742170141068966061e+01,1.460699999999999932e+02,0.000000000000000000e+00,7.738000565347922688e+00,0.000000000000000000e+00,1.000000009958578850e+00,0.000000000000000000e+00,2.922626354630434380e-10,0.000000000000000000e+00 +2.742299373419307074e+01,1.460800000000000125e+02,0.000000000000000000e+00,7.739292888864202524e+00,0.000000000000000000e+00,1.000000009958956548e+00,0.000000000000000000e+00,3.966224679241254358e-10,0.000000000000000000e+00 +2.742428584190156471e+01,1.460900000000000034e+02,0.000000000000000000e+00,7.740584996585565314e+00,0.000000000000000000e+00,1.000000009959469027e+00,0.000000000000000000e+00,-8.129711800164356855e-10,0.000000000000000000e+00 +2.742557773392321607e+01,1.460999999999999943e+02,0.000000000000000000e+00,7.741876888620082831e+00,0.000000000000000000e+00,1.000000009958418756e+00,0.000000000000000000e+00,8.583176681593601319e-10,0.000000000000000000e+00 +2.742686941036600601e+01,1.461100000000000136e+02,0.000000000000000000e+00,7.743168565075734477e+00,0.000000000000000000e+00,1.000000009959527425e+00,0.000000000000000000e+00,-5.078897289675081214e-10,0.000000000000000000e+00 +2.742816087133782332e+01,1.461200000000000045e+02,0.000000000000000000e+00,7.744460026060414393e+00,0.000000000000000000e+00,1.000000009958871505e+00,0.000000000000000000e+00,-1.829670963122316458e-10,0.000000000000000000e+00 +2.742945211694647156e+01,1.461299999999999955e+02,0.000000000000000000e+00,7.745751271681921679e+00,0.000000000000000000e+00,1.000000009958635250e+00,0.000000000000000000e+00,1.730221694653980165e-10,0.000000000000000000e+00 +2.743074314729966190e+01,1.461400000000000148e+02,0.000000000000000000e+00,7.747042302047968398e+00,0.000000000000000000e+00,1.000000009958858627e+00,0.000000000000000000e+00,-3.543589231429237528e-11,0.000000000000000000e+00 +2.743203396250501669e+01,1.461500000000000057e+02,0.000000000000000000e+00,7.748333117266176906e+00,0.000000000000000000e+00,1.000000009958812885e+00,0.000000000000000000e+00,1.942416913845671169e-10,0.000000000000000000e+00 +2.743332456267006592e+01,1.461599999999999966e+02,0.000000000000000000e+00,7.749623717444078963e+00,0.000000000000000000e+00,1.000000009959063574e+00,0.000000000000000000e+00,-2.662019025409187818e-10,0.000000000000000000e+00 +2.743461494790225430e+01,1.461700000000000159e+02,0.000000000000000000e+00,7.750914102689117513e+00,0.000000000000000000e+00,1.000000009958720071e+00,0.000000000000000000e+00,1.196128818518923911e-10,0.000000000000000000e+00 +2.743590511830893419e+01,1.461800000000000068e+02,0.000000000000000000e+00,7.752204273108644905e+00,0.000000000000000000e+00,1.000000009958874392e+00,0.000000000000000000e+00,2.236014340521592397e-10,0.000000000000000000e+00 +2.743719507399736912e+01,1.461899999999999977e+02,0.000000000000000000e+00,7.753494228809925559e+00,0.000000000000000000e+00,1.000000009959162828e+00,0.000000000000000000e+00,-5.516075487290051066e-10,0.000000000000000000e+00 +2.743848481507473380e+01,1.462000000000000171e+02,0.000000000000000000e+00,7.754783969900134188e+00,0.000000000000000000e+00,1.000000009958451397e+00,0.000000000000000000e+00,4.012045506899777906e-10,0.000000000000000000e+00 +2.743977434164811413e+01,1.462100000000000080e+02,0.000000000000000000e+00,7.756073496486354912e+00,0.000000000000000000e+00,1.000000009958968761e+00,0.000000000000000000e+00,-1.835859097466408990e-10,0.000000000000000000e+00 +2.744106365382450363e+01,1.462199999999999989e+02,0.000000000000000000e+00,7.757362808675585697e+00,0.000000000000000000e+00,1.000000009958732061e+00,0.000000000000000000e+00,3.019508421877215409e-10,0.000000000000000000e+00 +2.744235275171081412e+01,1.462299999999999898e+02,0.000000000000000000e+00,7.758651906574733026e+00,0.000000000000000000e+00,1.000000009959121305e+00,0.000000000000000000e+00,-3.417969325934915022e-10,0.000000000000000000e+00 +2.744364163541386148e+01,1.462400000000000091e+02,0.000000000000000000e+00,7.759940790290616341e+00,0.000000000000000000e+00,1.000000009958680769e+00,0.000000000000000000e+00,-3.876869220798859383e-11,0.000000000000000000e+00 +2.744493030504037634e+01,1.462500000000000000e+02,0.000000000000000000e+00,7.761229459929964491e+00,0.000000000000000000e+00,1.000000009958630809e+00,0.000000000000000000e+00,8.030760341898009655e-11,0.000000000000000000e+00 +2.744621876069700050e+01,1.462599999999999909e+02,0.000000000000000000e+00,7.762517915599419283e+00,0.000000000000000000e+00,1.000000009958734282e+00,0.000000000000000000e+00,-4.688260608716281531e-11,0.000000000000000000e+00 +2.744750700249028696e+01,1.462700000000000102e+02,0.000000000000000000e+00,7.763806157405533703e+00,0.000000000000000000e+00,1.000000009958673886e+00,0.000000000000000000e+00,5.275168489063049819e-11,0.000000000000000000e+00 +2.744879503052669989e+01,1.462800000000000011e+02,0.000000000000000000e+00,7.765094185454771925e+00,0.000000000000000000e+00,1.000000009958741831e+00,0.000000000000000000e+00,3.175971372472761467e-10,0.000000000000000000e+00 +2.745008284491261463e+01,1.462899999999999920e+02,0.000000000000000000e+00,7.766381999853510187e+00,0.000000000000000000e+00,1.000000009959150837e+00,0.000000000000000000e+00,-3.850771036633757076e-10,0.000000000000000000e+00 +2.745137044575431773e+01,1.463000000000000114e+02,0.000000000000000000e+00,7.767669600708036803e+00,0.000000000000000000e+00,1.000000009958655012e+00,0.000000000000000000e+00,2.518162926408991907e-11,0.000000000000000000e+00 +2.745265783315801045e+01,1.463100000000000023e+02,0.000000000000000000e+00,7.768956988124550378e+00,0.000000000000000000e+00,1.000000009958687430e+00,0.000000000000000000e+00,-1.198913214649835473e-10,0.000000000000000000e+00 +2.745394500722980524e+01,1.463199999999999932e+02,0.000000000000000000e+00,7.770244162209163363e+00,0.000000000000000000e+00,1.000000009958533109e+00,0.000000000000000000e+00,1.903050897071147153e-10,0.000000000000000000e+00 +2.745523196807572575e+01,1.463300000000000125e+02,0.000000000000000000e+00,7.771531123067899394e+00,0.000000000000000000e+00,1.000000009958778024e+00,0.000000000000000000e+00,-1.787749113968027450e-10,0.000000000000000000e+00 +2.745651871580170678e+01,1.463400000000000034e+02,0.000000000000000000e+00,7.772817870806695062e+00,0.000000000000000000e+00,1.000000009958547986e+00,0.000000000000000000e+00,-2.152212604777036907e-10,0.000000000000000000e+00 +2.745780525051359788e+01,1.463499999999999943e+02,0.000000000000000000e+00,7.774104405531398143e+00,0.000000000000000000e+00,1.000000009958271097e+00,0.000000000000000000e+00,5.560083569159742981e-10,0.000000000000000000e+00 +2.745909157231715980e+01,1.463600000000000136e+02,0.000000000000000000e+00,7.775390727347769371e+00,0.000000000000000000e+00,1.000000009958986302e+00,0.000000000000000000e+00,-6.094486974536656207e-10,0.000000000000000000e+00 +2.746037768131806445e+01,1.463700000000000045e+02,0.000000000000000000e+00,7.776676836361483325e+00,0.000000000000000000e+00,1.000000009958202485e+00,0.000000000000000000e+00,5.214842789993773787e-10,0.000000000000000000e+00 +2.746166357762189847e+01,1.463799999999999955e+02,0.000000000000000000e+00,7.777962732678123992e+00,0.000000000000000000e+00,1.000000009958873060e+00,0.000000000000000000e+00,-4.079303111878147045e-10,0.000000000000000000e+00 +2.746294926133416325e+01,1.463900000000000148e+02,0.000000000000000000e+00,7.779248416403191868e+00,0.000000000000000000e+00,1.000000009958348590e+00,0.000000000000000000e+00,3.017663226735661596e-10,0.000000000000000000e+00 +2.746423473256026782e+01,1.464000000000000057e+02,0.000000000000000000e+00,7.780533887642096857e+00,0.000000000000000000e+00,1.000000009958736502e+00,0.000000000000000000e+00,-9.761084488508285033e-11,0.000000000000000000e+00 +2.746551999140553590e+01,1.464099999999999966e+02,0.000000000000000000e+00,7.781819146500164486e+00,0.000000000000000000e+00,1.000000009958611047e+00,0.000000000000000000e+00,-5.408361298485767101e-11,0.000000000000000000e+00 +2.746680503797520601e+01,1.464200000000000159e+02,0.000000000000000000e+00,7.783104193082631461e+00,0.000000000000000000e+00,1.000000009958541547e+00,0.000000000000000000e+00,-1.662524836408938644e-10,0.000000000000000000e+00 +2.746808987237442778e+01,1.464300000000000068e+02,0.000000000000000000e+00,7.784389027494648339e+00,0.000000000000000000e+00,1.000000009958327940e+00,0.000000000000000000e+00,4.321203965481994742e-11,0.000000000000000000e+00 +2.746937449470826564e+01,1.464399999999999977e+02,0.000000000000000000e+00,7.785673649841278632e+00,0.000000000000000000e+00,1.000000009958383451e+00,0.000000000000000000e+00,-2.437561229812468572e-11,0.000000000000000000e+00 +2.747065890508169517e+01,1.464500000000000171e+02,0.000000000000000000e+00,7.786958060227499701e+00,0.000000000000000000e+00,1.000000009958352143e+00,0.000000000000000000e+00,1.085844672360030055e-10,0.000000000000000000e+00 +2.747194310359961023e+01,1.464600000000000080e+02,0.000000000000000000e+00,7.788242258758201864e+00,0.000000000000000000e+00,1.000000009958491587e+00,0.000000000000000000e+00,3.820105820472733664e-10,0.000000000000000000e+00 +2.747322709036681232e+01,1.464699999999999989e+02,0.000000000000000000e+00,7.789526245538189286e+00,0.000000000000000000e+00,1.000000009958982083e+00,0.000000000000000000e+00,-8.817614371937329726e-10,0.000000000000000000e+00 +2.747451086548801769e+01,1.464799999999999898e+02,0.000000000000000000e+00,7.790810020672179981e+00,0.000000000000000000e+00,1.000000009957850100e+00,0.000000000000000000e+00,5.687935311187192466e-10,0.000000000000000000e+00 +2.747579442906786085e+01,1.464900000000000091e+02,0.000000000000000000e+00,7.792093584264803141e+00,0.000000000000000000e+00,1.000000009958580183e+00,0.000000000000000000e+00,-1.776907534676287209e-10,0.000000000000000000e+00 +2.747707778121088396e+01,1.465000000000000000e+02,0.000000000000000000e+00,7.793376936420606249e+00,0.000000000000000000e+00,1.000000009958352143e+00,0.000000000000000000e+00,5.277955773782060805e-11,0.000000000000000000e+00 +2.747836092202154745e+01,1.465099999999999909e+02,0.000000000000000000e+00,7.794660077244047081e+00,0.000000000000000000e+00,1.000000009958419867e+00,0.000000000000000000e+00,1.223648887685233827e-10,0.000000000000000000e+00 +2.747964385160422296e+01,1.465200000000000102e+02,0.000000000000000000e+00,7.795943006839499034e+00,0.000000000000000000e+00,1.000000009958576852e+00,0.000000000000000000e+00,-2.994711457001105060e-11,0.000000000000000000e+00 +2.748092657006320039e+01,1.465300000000000011e+02,0.000000000000000000e+00,7.797225725311249356e+00,0.000000000000000000e+00,1.000000009958538438e+00,0.000000000000000000e+00,-4.639969507243912309e-10,0.000000000000000000e+00 +2.748220907750267727e+01,1.465399999999999920e+02,0.000000000000000000e+00,7.798508232763499137e+00,0.000000000000000000e+00,1.000000009957943359e+00,0.000000000000000000e+00,3.804361844968219960e-10,0.000000000000000000e+00 +2.748349137402677300e+01,1.465500000000000114e+02,0.000000000000000000e+00,7.799790529300363318e+00,0.000000000000000000e+00,1.000000009958431191e+00,0.000000000000000000e+00,2.833390701159154238e-10,0.000000000000000000e+00 +2.748477345973951458e+01,1.465600000000000023e+02,0.000000000000000000e+00,7.801072615025873347e+00,0.000000000000000000e+00,1.000000009958794456e+00,0.000000000000000000e+00,-8.163793027064367486e-10,0.000000000000000000e+00 +2.748605533474484730e+01,1.465699999999999932e+02,0.000000000000000000e+00,7.802354490043973634e+00,0.000000000000000000e+00,1.000000009957747960e+00,0.000000000000000000e+00,8.057721319775118183e-10,0.000000000000000000e+00 +2.748733699914663120e+01,1.465800000000000125e+02,0.000000000000000000e+00,7.803636154458521546e+00,0.000000000000000000e+00,1.000000009958780689e+00,0.000000000000000000e+00,-3.158812924470374012e-10,0.000000000000000000e+00 +2.748861845304864104e+01,1.465900000000000034e+02,0.000000000000000000e+00,7.804917608373293625e+00,0.000000000000000000e+00,1.000000009958375902e+00,0.000000000000000000e+00,-4.570026076074012420e-10,0.000000000000000000e+00 +2.748989969655456633e+01,1.465999999999999943e+02,0.000000000000000000e+00,7.806198851891976709e+00,0.000000000000000000e+00,1.000000009957790370e+00,0.000000000000000000e+00,3.246516488884780882e-10,0.000000000000000000e+00 +2.749118072976800775e+01,1.466100000000000136e+02,0.000000000000000000e+00,7.807479885118174145e+00,0.000000000000000000e+00,1.000000009958206260e+00,0.000000000000000000e+00,3.460283137956182389e-10,0.000000000000000000e+00 +2.749246155279248427e+01,1.466200000000000045e+02,0.000000000000000000e+00,7.808760708155405794e+00,0.000000000000000000e+00,1.000000009958649461e+00,0.000000000000000000e+00,-4.537598468799574437e-10,0.000000000000000000e+00 +2.749374216573142959e+01,1.466299999999999955e+02,0.000000000000000000e+00,7.810041321107105361e+00,0.000000000000000000e+00,1.000000009958068370e+00,0.000000000000000000e+00,3.329620876019321869e-11,0.000000000000000000e+00 +2.749502256868819572e+01,1.466400000000000148e+02,0.000000000000000000e+00,7.811321724076620399e+00,0.000000000000000000e+00,1.000000009958111002e+00,0.000000000000000000e+00,1.224530063392424771e-10,0.000000000000000000e+00 +2.749630276176604227e+01,1.466500000000000057e+02,0.000000000000000000e+00,7.812601917167215859e+00,0.000000000000000000e+00,1.000000009958267766e+00,0.000000000000000000e+00,2.968150587595165592e-10,0.000000000000000000e+00 +2.749758274506815070e+01,1.466599999999999966e+02,0.000000000000000000e+00,7.813881900482071430e+00,0.000000000000000000e+00,1.000000009958647684e+00,0.000000000000000000e+00,-5.876547692225736633e-10,0.000000000000000000e+00 +2.749886251869761722e+01,1.466700000000000159e+02,0.000000000000000000e+00,7.815161674124282420e+00,0.000000000000000000e+00,1.000000009957895619e+00,0.000000000000000000e+00,1.212984825962964606e-10,0.000000000000000000e+00 +2.750014208275745276e+01,1.466800000000000068e+02,0.000000000000000000e+00,7.816441238196857988e+00,0.000000000000000000e+00,1.000000009958050828e+00,0.000000000000000000e+00,1.957755228307002222e-10,0.000000000000000000e+00 +2.750142143735057942e+01,1.466899999999999977e+02,0.000000000000000000e+00,7.817720592802725577e+00,0.000000000000000000e+00,1.000000009958301295e+00,0.000000000000000000e+00,-4.240761388322647014e-10,0.000000000000000000e+00 +2.750270058257984473e+01,1.467000000000000171e+02,0.000000000000000000e+00,7.818999738044727366e+00,0.000000000000000000e+00,1.000000009957758840e+00,0.000000000000000000e+00,3.746647755309533787e-10,0.000000000000000000e+00 +2.750397951854800382e+01,1.467100000000000080e+02,0.000000000000000000e+00,7.820278674025620269e+00,0.000000000000000000e+00,1.000000009958238012e+00,0.000000000000000000e+00,-1.814590969563661468e-10,0.000000000000000000e+00 +2.750525824535773012e+01,1.467199999999999989e+02,0.000000000000000000e+00,7.821557400848079489e+00,0.000000000000000000e+00,1.000000009958005975e+00,0.000000000000000000e+00,5.635703851536892350e-10,0.000000000000000000e+00 +2.750653676311161178e+01,1.467299999999999898e+02,0.000000000000000000e+00,7.822835918614694073e+00,0.000000000000000000e+00,1.000000009958726510e+00,0.000000000000000000e+00,-7.078350432089236664e-10,0.000000000000000000e+00 +2.750781507191215880e+01,1.467400000000000091e+02,0.000000000000000000e+00,7.824114227427971358e+00,0.000000000000000000e+00,1.000000009957821678e+00,0.000000000000000000e+00,2.927354463992089279e-10,0.000000000000000000e+00 +2.750909317186179237e+01,1.467500000000000000e+02,0.000000000000000000e+00,7.825392327390331637e+00,0.000000000000000000e+00,1.000000009958195824e+00,0.000000000000000000e+00,-2.979960243337668963e-10,0.000000000000000000e+00 +2.751037106306285196e+01,1.467599999999999909e+02,0.000000000000000000e+00,7.826670218604115270e+00,0.000000000000000000e+00,1.000000009957815017e+00,0.000000000000000000e+00,1.798695342948355246e-10,0.000000000000000000e+00 +2.751164874561759177e+01,1.467700000000000102e+02,0.000000000000000000e+00,7.827947901171576461e+00,0.000000000000000000e+00,1.000000009958044833e+00,0.000000000000000000e+00,3.719648702051252767e-11,0.000000000000000000e+00 +2.751292621962818075e+01,1.467800000000000011e+02,0.000000000000000000e+00,7.829225375194887704e+00,0.000000000000000000e+00,1.000000009958092351e+00,0.000000000000000000e+00,-2.416427784872808734e-10,0.000000000000000000e+00 +2.751420348519670966e+01,1.467899999999999920e+02,0.000000000000000000e+00,7.830502640776137113e+00,0.000000000000000000e+00,1.000000009957783709e+00,0.000000000000000000e+00,3.743466022852143001e-10,0.000000000000000000e+00 +2.751548054242518404e+01,1.468000000000000114e+02,0.000000000000000000e+00,7.831779698017329316e+00,0.000000000000000000e+00,1.000000009958261771e+00,0.000000000000000000e+00,-3.504093924245869418e-10,0.000000000000000000e+00 +2.751675739141552768e+01,1.468100000000000023e+02,0.000000000000000000e+00,7.833056547020387228e+00,0.000000000000000000e+00,1.000000009957814351e+00,0.000000000000000000e+00,2.481963899425141818e-10,0.000000000000000000e+00 +2.751803403226957556e+01,1.468199999999999932e+02,0.000000000000000000e+00,7.834333187887148497e+00,0.000000000000000000e+00,1.000000009958131209e+00,0.000000000000000000e+00,-6.610371386710758772e-11,0.000000000000000000e+00 +2.751931046508908452e+01,1.468300000000000125e+02,0.000000000000000000e+00,7.835609620719369950e+00,0.000000000000000000e+00,1.000000009958046832e+00,0.000000000000000000e+00,-2.625440957452324989e-10,0.000000000000000000e+00 +2.752058668997572966e+01,1.468400000000000034e+02,0.000000000000000000e+00,7.836885845618724034e+00,0.000000000000000000e+00,1.000000009957711766e+00,0.000000000000000000e+00,1.470416797110867799e-10,0.000000000000000000e+00 +2.752186270703110083e+01,1.468499999999999943e+02,0.000000000000000000e+00,7.838161862686800596e+00,0.000000000000000000e+00,1.000000009957899394e+00,0.000000000000000000e+00,1.427145674393765186e-11,0.000000000000000000e+00 +2.752313851635670261e+01,1.468600000000000136e+02,0.000000000000000000e+00,7.839437672025107773e+00,0.000000000000000000e+00,1.000000009957917602e+00,0.000000000000000000e+00,3.719886244616977932e-10,0.000000000000000000e+00 +2.752441411805396143e+01,1.468700000000000045e+02,0.000000000000000000e+00,7.840713273735070210e+00,0.000000000000000000e+00,1.000000009958392111e+00,0.000000000000000000e+00,-4.749415485505286143e-10,0.000000000000000000e+00 +2.752568951222422200e+01,1.468799999999999955e+02,0.000000000000000000e+00,7.841988667918030842e+00,0.000000000000000000e+00,1.000000009957786373e+00,0.000000000000000000e+00,1.453961515121350383e-10,0.000000000000000000e+00 +2.752696469896874021e+01,1.468900000000000148e+02,0.000000000000000000e+00,7.843263854675248226e+00,0.000000000000000000e+00,1.000000009957971780e+00,0.000000000000000000e+00,-5.545109285806312617e-10,0.000000000000000000e+00 +2.752823967838869734e+01,1.469000000000000057e+02,0.000000000000000000e+00,7.844538834107900982e+00,0.000000000000000000e+00,1.000000009957264790e+00,0.000000000000000000e+00,6.451766197187606361e-10,0.000000000000000000e+00 +2.752951445058518587e+01,1.469099999999999966e+02,0.000000000000000000e+00,7.845813606317083355e+00,0.000000000000000000e+00,1.000000009958087244e+00,0.000000000000000000e+00,-1.379759501363848669e-10,0.000000000000000000e+00 +2.753078901565922010e+01,1.469200000000000159e+02,0.000000000000000000e+00,7.847088171403810541e+00,0.000000000000000000e+00,1.000000009957911384e+00,0.000000000000000000e+00,-2.287775917387425418e-10,0.000000000000000000e+00 +2.753206337371173262e+01,1.469300000000000068e+02,0.000000000000000000e+00,7.848362529469012472e+00,0.000000000000000000e+00,1.000000009957619840e+00,0.000000000000000000e+00,3.161233414696160497e-10,0.000000000000000000e+00 +2.753333752484357078e+01,1.469399999999999977e+02,0.000000000000000000e+00,7.849636680613538253e+00,0.000000000000000000e+00,1.000000009958022629e+00,0.000000000000000000e+00,-2.020101622164614165e-10,0.000000000000000000e+00 +2.753461146915550373e+01,1.469500000000000171e+02,0.000000000000000000e+00,7.850910624938156168e+00,0.000000000000000000e+00,1.000000009957765279e+00,0.000000000000000000e+00,-1.989050929086396776e-10,0.000000000000000000e+00 +2.753588520674821538e+01,1.469600000000000080e+02,0.000000000000000000e+00,7.852184362543551011e+00,0.000000000000000000e+00,1.000000009957511926e+00,0.000000000000000000e+00,2.686787704026996437e-10,0.000000000000000000e+00 +2.753715873772231149e+01,1.469699999999999989e+02,0.000000000000000000e+00,7.853457893530326750e+00,0.000000000000000000e+00,1.000000009957854097e+00,0.000000000000000000e+00,4.882690274740068010e-11,0.000000000000000000e+00 +2.753843206217831252e+01,1.469799999999999898e+02,0.000000000000000000e+00,7.854731217999006532e+00,0.000000000000000000e+00,1.000000009957916269e+00,0.000000000000000000e+00,-3.687028858856389223e-10,0.000000000000000000e+00 +2.753970518021666081e+01,1.469900000000000091e+02,0.000000000000000000e+00,7.856004336050030901e+00,0.000000000000000000e+00,1.000000009957446867e+00,0.000000000000000000e+00,6.037310875022051373e-10,0.000000000000000000e+00 +2.754097809193771340e+01,1.470000000000000000e+02,0.000000000000000000e+00,7.857277247783758689e+00,0.000000000000000000e+00,1.000000009958215363e+00,0.000000000000000000e+00,-3.794648598438516051e-10,0.000000000000000000e+00 +2.754225079744174920e+01,1.470099999999999909e+02,0.000000000000000000e+00,7.858549953300469681e+00,0.000000000000000000e+00,1.000000009957732416e+00,0.000000000000000000e+00,-8.637495667337919839e-11,0.000000000000000000e+00 +2.754352329682896894e+01,1.470200000000000102e+02,0.000000000000000000e+00,7.859822452700359285e+00,0.000000000000000000e+00,1.000000009957622504e+00,0.000000000000000000e+00,-2.179793732942136679e-10,0.000000000000000000e+00 +2.754479559019948454e+01,1.470300000000000011e+02,0.000000000000000000e+00,7.861094746083543860e+00,0.000000000000000000e+00,1.000000009957345171e+00,0.000000000000000000e+00,2.661908357687848516e-10,0.000000000000000000e+00 +2.754606767765333331e+01,1.470399999999999920e+02,0.000000000000000000e+00,7.862366833550058054e+00,0.000000000000000000e+00,1.000000009957683789e+00,0.000000000000000000e+00,2.115904918445525901e-10,0.000000000000000000e+00 +2.754733955929046729e+01,1.470500000000000114e+02,0.000000000000000000e+00,7.863638715199856577e+00,0.000000000000000000e+00,1.000000009957952907e+00,0.000000000000000000e+00,-4.384403243544019596e-10,0.000000000000000000e+00 +2.754861123521076038e+01,1.470600000000000023e+02,0.000000000000000000e+00,7.864910391132812428e+00,0.000000000000000000e+00,1.000000009957395353e+00,0.000000000000000000e+00,-9.308103706637346436e-11,0.000000000000000000e+00 +2.754988270551400475e+01,1.470699999999999932e+02,0.000000000000000000e+00,7.866181861448716894e+00,0.000000000000000000e+00,1.000000009957277003e+00,0.000000000000000000e+00,6.427647136793285780e-10,0.000000000000000000e+00 +2.755115397029991087e+01,1.470800000000000125e+02,0.000000000000000000e+00,7.867453126247282214e+00,0.000000000000000000e+00,1.000000009958094127e+00,0.000000000000000000e+00,-4.859946799933277097e-10,0.000000000000000000e+00 +2.755242502966811102e+01,1.470900000000000034e+02,0.000000000000000000e+00,7.868724185628140688e+00,0.000000000000000000e+00,1.000000009957476399e+00,0.000000000000000000e+00,3.118765839215383054e-10,0.000000000000000000e+00 +2.755369588371815581e+01,1.470999999999999943e+02,0.000000000000000000e+00,7.869995039690841132e+00,0.000000000000000000e+00,1.000000009957872749e+00,0.000000000000000000e+00,-3.183926669495897977e-10,0.000000000000000000e+00 +2.755496653254951767e+01,1.471100000000000136e+02,0.000000000000000000e+00,7.871265688534855087e+00,0.000000000000000000e+00,1.000000009957468183e+00,0.000000000000000000e+00,-2.335023498974423681e-10,0.000000000000000000e+00 +2.755623697626158375e+01,1.471200000000000045e+02,0.000000000000000000e+00,7.872536132259571495e+00,0.000000000000000000e+00,1.000000009957171532e+00,0.000000000000000000e+00,5.113058462593410867e-10,0.000000000000000000e+00 +2.755750721495366307e+01,1.471299999999999955e+02,0.000000000000000000e+00,7.873806370964300250e+00,0.000000000000000000e+00,1.000000009957821012e+00,0.000000000000000000e+00,-3.419745655898458750e-10,0.000000000000000000e+00 +2.755877724872499002e+01,1.471400000000000148e+02,0.000000000000000000e+00,7.875076404748272196e+00,0.000000000000000000e+00,1.000000009957386693e+00,0.000000000000000000e+00,-9.704831171209552107e-11,0.000000000000000000e+00 +2.756004707767471018e+01,1.471500000000000057e+02,0.000000000000000000e+00,7.876346233710635580e+00,0.000000000000000000e+00,1.000000009957263458e+00,0.000000000000000000e+00,8.919390957356886456e-11,0.000000000000000000e+00 +2.756131670190189453e+01,1.471599999999999966e+02,0.000000000000000000e+00,7.877615857950460487e+00,0.000000000000000000e+00,1.000000009957376701e+00,0.000000000000000000e+00,1.616244261259108890e-10,0.000000000000000000e+00 +2.756258612150553233e+01,1.471700000000000159e+02,0.000000000000000000e+00,7.878885277566737066e+00,0.000000000000000000e+00,1.000000009957581870e+00,0.000000000000000000e+00,6.280575647657957362e-11,0.000000000000000000e+00 +2.756385533658453113e+01,1.471800000000000068e+02,0.000000000000000000e+00,7.880154492658375531e+00,0.000000000000000000e+00,1.000000009957661584e+00,0.000000000000000000e+00,-2.615869957650456245e-10,0.000000000000000000e+00 +2.756512434723772387e+01,1.471899999999999977e+02,0.000000000000000000e+00,7.881423503324206159e+00,0.000000000000000000e+00,1.000000009957329627e+00,0.000000000000000000e+00,2.348536996313007456e-10,0.000000000000000000e+00 +2.756639315356386177e+01,1.472000000000000171e+02,0.000000000000000000e+00,7.882692309662979291e+00,0.000000000000000000e+00,1.000000009957627611e+00,0.000000000000000000e+00,-1.580529297579162988e-10,0.000000000000000000e+00 +2.756766175566161792e+01,1.472100000000000080e+02,0.000000000000000000e+00,7.883960911773367108e+00,0.000000000000000000e+00,1.000000009957427105e+00,0.000000000000000000e+00,1.594788388154086332e-10,0.000000000000000000e+00 +2.756893015362958010e+01,1.472199999999999989e+02,0.000000000000000000e+00,7.885229309753960969e+00,0.000000000000000000e+00,1.000000009957629388e+00,0.000000000000000000e+00,-5.238610899468166133e-10,0.000000000000000000e+00 +2.757019834756626508e+01,1.472299999999999898e+02,0.000000000000000000e+00,7.886497503703274070e+00,0.000000000000000000e+00,1.000000009956965030e+00,0.000000000000000000e+00,4.969775683318887636e-10,0.000000000000000000e+00 +2.757146633757010434e+01,1.472400000000000091e+02,0.000000000000000000e+00,7.887765493719738785e+00,0.000000000000000000e+00,1.000000009957595193e+00,0.000000000000000000e+00,-1.465951741828824044e-10,0.000000000000000000e+00 +2.757273412373945121e+01,1.472500000000000000e+02,0.000000000000000000e+00,7.889033279901711104e+00,0.000000000000000000e+00,1.000000009957409342e+00,0.000000000000000000e+00,-3.007698566113433994e-10,0.000000000000000000e+00 +2.757400170617258439e+01,1.472599999999999909e+02,0.000000000000000000e+00,7.890300862347465305e+00,0.000000000000000000e+00,1.000000009957028091e+00,0.000000000000000000e+00,5.326076162667513269e-10,0.000000000000000000e+00 +2.757526908496769735e+01,1.472700000000000102e+02,0.000000000000000000e+00,7.891568241155197505e+00,0.000000000000000000e+00,1.000000009957703107e+00,0.000000000000000000e+00,-4.664569765545664622e-10,0.000000000000000000e+00 +2.757653626022290894e+01,1.472800000000000011e+02,0.000000000000000000e+00,7.892835416423026551e+00,0.000000000000000000e+00,1.000000009957112024e+00,0.000000000000000000e+00,-3.470071813120332520e-11,0.000000000000000000e+00 +2.757780323203625628e+01,1.472899999999999920e+02,0.000000000000000000e+00,7.894102388248989577e+00,0.000000000000000000e+00,1.000000009957068059e+00,0.000000000000000000e+00,1.135842164231647419e-10,0.000000000000000000e+00 +2.757907000050570190e+01,1.473000000000000114e+02,0.000000000000000000e+00,7.895369156731047333e+00,0.000000000000000000e+00,1.000000009957211944e+00,0.000000000000000000e+00,4.766744496265511568e-10,0.000000000000000000e+00 +2.758033656572912307e+01,1.473100000000000023e+02,0.000000000000000000e+00,7.896635721967081523e+00,0.000000000000000000e+00,1.000000009957815683e+00,0.000000000000000000e+00,-6.619105230682039528e-10,0.000000000000000000e+00 +2.758160292780432599e+01,1.473199999999999932e+02,0.000000000000000000e+00,7.897902084054895688e+00,0.000000000000000000e+00,1.000000009956977465e+00,0.000000000000000000e+00,-3.384615037621763222e-11,0.000000000000000000e+00 +2.758286908682903515e+01,1.473300000000000125e+02,0.000000000000000000e+00,7.899168243092212549e+00,0.000000000000000000e+00,1.000000009956934610e+00,0.000000000000000000e+00,6.451093170343903399e-10,0.000000000000000000e+00 +2.758413504290089691e+01,1.473400000000000034e+02,0.000000000000000000e+00,7.900434199176679329e+00,0.000000000000000000e+00,1.000000009957751290e+00,0.000000000000000000e+00,-3.434819131784103456e-10,0.000000000000000000e+00 +2.758540079611747942e+01,1.473499999999999943e+02,0.000000000000000000e+00,7.901699952405865091e+00,0.000000000000000000e+00,1.000000009957316527e+00,0.000000000000000000e+00,-2.826547578954807354e-10,0.000000000000000000e+00 +2.758666634657626915e+01,1.473600000000000136e+02,0.000000000000000000e+00,7.902965502877258075e+00,0.000000000000000000e+00,1.000000009956958813e+00,0.000000000000000000e+00,2.188249133469697607e-10,0.000000000000000000e+00 +2.758793169437468151e+01,1.473700000000000045e+02,0.000000000000000000e+00,7.904230850688270138e+00,0.000000000000000000e+00,1.000000009957235703e+00,0.000000000000000000e+00,-2.457128543068249512e-12,0.000000000000000000e+00 +2.758919683961005020e+01,1.473799999999999955e+02,0.000000000000000000e+00,7.905495995936235865e+00,0.000000000000000000e+00,1.000000009957232594e+00,0.000000000000000000e+00,-4.469178983702283171e-10,0.000000000000000000e+00 +2.759046178237963076e+01,1.473900000000000148e+02,0.000000000000000000e+00,7.906760938718410792e+00,0.000000000000000000e+00,1.000000009956667268e+00,0.000000000000000000e+00,4.966744059505675052e-10,0.000000000000000000e+00 +2.759172652278060056e+01,1.474000000000000057e+02,0.000000000000000000e+00,7.908025679131972296e+00,0.000000000000000000e+00,1.000000009957295433e+00,0.000000000000000000e+00,-2.458308212723805702e-12,0.000000000000000000e+00 +2.759299106091005882e+01,1.474099999999999966e+02,0.000000000000000000e+00,7.909290217274022261e+00,0.000000000000000000e+00,1.000000009957292324e+00,0.000000000000000000e+00,-3.326271629581655633e-10,0.000000000000000000e+00 +2.759425539686503015e+01,1.474200000000000159e+02,0.000000000000000000e+00,7.910554553241582632e+00,0.000000000000000000e+00,1.000000009956871772e+00,0.000000000000000000e+00,5.636595537284402590e-10,0.000000000000000000e+00 +2.759551953074245745e+01,1.474300000000000068e+02,0.000000000000000000e+00,7.911818687131598082e+00,0.000000000000000000e+00,1.000000009957584313e+00,0.000000000000000000e+00,-7.030620171799707403e-10,0.000000000000000000e+00 +2.759678346263921256e+01,1.474399999999999977e+02,0.000000000000000000e+00,7.913082619040937793e+00,0.000000000000000000e+00,1.000000009956695690e+00,0.000000000000000000e+00,2.609230096267853954e-10,0.000000000000000000e+00 +2.759804719265208206e+01,1.474500000000000171e+02,0.000000000000000000e+00,7.914346349066390118e+00,0.000000000000000000e+00,1.000000009957025426e+00,0.000000000000000000e+00,6.519723639860932776e-11,0.000000000000000000e+00 +2.759931072087778148e+01,1.474600000000000080e+02,0.000000000000000000e+00,7.915609877304669695e+00,0.000000000000000000e+00,1.000000009957107805e+00,0.000000000000000000e+00,-2.323571614625657531e-10,0.000000000000000000e+00 +2.760057404741294462e+01,1.474699999999999989e+02,0.000000000000000000e+00,7.916873203852412111e+00,0.000000000000000000e+00,1.000000009956814262e+00,0.000000000000000000e+00,4.282241922078816406e-10,0.000000000000000000e+00 +2.760183717235413070e+01,1.474799999999999898e+02,0.000000000000000000e+00,7.918136328806175683e+00,0.000000000000000000e+00,1.000000009957355163e+00,0.000000000000000000e+00,-2.347169569584527464e-10,0.000000000000000000e+00 +2.760310009579782431e+01,1.474900000000000091e+02,0.000000000000000000e+00,7.919399252262443234e+00,0.000000000000000000e+00,1.000000009957058733e+00,0.000000000000000000e+00,-4.712672473608702977e-11,0.000000000000000000e+00 +2.760436281784042833e+01,1.475000000000000000e+02,0.000000000000000000e+00,7.920661974317618537e+00,0.000000000000000000e+00,1.000000009956999225e+00,0.000000000000000000e+00,-1.767533960126234282e-10,0.000000000000000000e+00 +2.760562533857826750e+01,1.475099999999999909e+02,0.000000000000000000e+00,7.921924495068029870e+00,0.000000000000000000e+00,1.000000009956776070e+00,0.000000000000000000e+00,4.371166177961972611e-10,0.000000000000000000e+00 +2.760688765810759548e+01,1.475200000000000102e+02,0.000000000000000000e+00,7.923186814609928241e+00,0.000000000000000000e+00,1.000000009957327851e+00,0.000000000000000000e+00,-4.885578560414442502e-10,0.000000000000000000e+00 +2.760814977652458779e+01,1.475300000000000011e+02,0.000000000000000000e+00,7.924448933039489162e+00,0.000000000000000000e+00,1.000000009956711233e+00,0.000000000000000000e+00,3.371357450033509647e-10,0.000000000000000000e+00 +2.760941169392534178e+01,1.475399999999999920e+02,0.000000000000000000e+00,7.925710850452809098e+00,0.000000000000000000e+00,1.000000009957136671e+00,0.000000000000000000e+00,-4.848417976654471312e-10,0.000000000000000000e+00 +2.761067341040588019e+01,1.475500000000000114e+02,0.000000000000000000e+00,7.926972566945910792e+00,0.000000000000000000e+00,1.000000009956524938e+00,0.000000000000000000e+00,3.391792654850960322e-10,0.000000000000000000e+00 +2.761193492606214761e+01,1.475600000000000023e+02,0.000000000000000000e+00,7.928234082614737943e+00,0.000000000000000000e+00,1.000000009956952818e+00,0.000000000000000000e+00,-3.432822129023347533e-11,0.000000000000000000e+00 +2.761319624099001047e+01,1.475699999999999932e+02,0.000000000000000000e+00,7.929495397555160530e+00,0.000000000000000000e+00,1.000000009956909519e+00,0.000000000000000000e+00,1.549417472068390879e-11,0.000000000000000000e+00 +2.761445735528526413e+01,1.475800000000000125e+02,0.000000000000000000e+00,7.930756511862970370e+00,0.000000000000000000e+00,1.000000009956929059e+00,0.000000000000000000e+00,-1.229165224110396393e-10,0.000000000000000000e+00 +2.761571826904362226e+01,1.475900000000000034e+02,0.000000000000000000e+00,7.932017425633883789e+00,0.000000000000000000e+00,1.000000009956774072e+00,0.000000000000000000e+00,5.618424744951353497e-11,0.000000000000000000e+00 +2.761697898236072746e+01,1.475999999999999943e+02,0.000000000000000000e+00,7.933278138963540727e+00,0.000000000000000000e+00,1.000000009956844904e+00,0.000000000000000000e+00,-5.971626058328993844e-11,0.000000000000000000e+00 +2.761823949533214062e+01,1.476100000000000136e+02,0.000000000000000000e+00,7.934538651947505628e+00,0.000000000000000000e+00,1.000000009956769631e+00,0.000000000000000000e+00,3.594115860477511728e-11,0.000000000000000000e+00 +2.761949980805335159e+01,1.476200000000000045e+02,0.000000000000000000e+00,7.935798964681266554e+00,0.000000000000000000e+00,1.000000009956814928e+00,0.000000000000000000e+00,2.893370409930238145e-10,0.000000000000000000e+00 +2.762075992061977558e+01,1.476299999999999955e+02,0.000000000000000000e+00,7.937059077260236073e+00,0.000000000000000000e+00,1.000000009957179525e+00,0.000000000000000000e+00,-4.707320043842353007e-10,0.000000000000000000e+00 +2.762201983312674614e+01,1.476400000000000148e+02,0.000000000000000000e+00,7.938318989779751256e+00,0.000000000000000000e+00,1.000000009956586444e+00,0.000000000000000000e+00,-5.957793855028271811e-11,0.000000000000000000e+00 +2.762327954566952570e+01,1.476500000000000057e+02,0.000000000000000000e+00,7.939578702335071902e+00,0.000000000000000000e+00,1.000000009956511393e+00,0.000000000000000000e+00,3.510014766916286921e-10,0.000000000000000000e+00 +2.762453905834329859e+01,1.476599999999999966e+02,0.000000000000000000e+00,7.940838215021384094e+00,0.000000000000000000e+00,1.000000009956953484e+00,0.000000000000000000e+00,-4.117119363672413074e-10,0.000000000000000000e+00 +2.762579837124317450e+01,1.476700000000000159e+02,0.000000000000000000e+00,7.942097527933798418e+00,0.000000000000000000e+00,1.000000009956435010e+00,0.000000000000000000e+00,3.997854291132511987e-10,0.000000000000000000e+00 +2.762705748446418852e+01,1.476800000000000068e+02,0.000000000000000000e+00,7.943356641167348187e+00,0.000000000000000000e+00,1.000000009956938385e+00,0.000000000000000000e+00,-6.808188820463182064e-11,0.000000000000000000e+00 +2.762831639810129758e+01,1.476899999999999977e+02,0.000000000000000000e+00,7.944615554816993885e+00,0.000000000000000000e+00,1.000000009956852676e+00,0.000000000000000000e+00,-1.876958799568236101e-10,0.000000000000000000e+00 +2.762957511224939111e+01,1.477000000000000171e+02,0.000000000000000000e+00,7.945874268977618726e+00,0.000000000000000000e+00,1.000000009956616420e+00,0.000000000000000000e+00,-1.093889877960246511e-11,0.000000000000000000e+00 +2.763083362700327328e+01,1.477100000000000080e+02,0.000000000000000000e+00,7.947132783744031315e+00,0.000000000000000000e+00,1.000000009956602653e+00,0.000000000000000000e+00,4.100972137304454311e-10,0.000000000000000000e+00 +2.763209194245768074e+01,1.477199999999999989e+02,0.000000000000000000e+00,7.948391099210965649e+00,0.000000000000000000e+00,1.000000009957118685e+00,0.000000000000000000e+00,-6.609540618495183288e-10,0.000000000000000000e+00 +2.763335005870726846e+01,1.477299999999999898e+02,0.000000000000000000e+00,7.949649215473081121e+00,0.000000000000000000e+00,1.000000009956287128e+00,0.000000000000000000e+00,9.055356570226025828e-11,0.000000000000000000e+00 +2.763460797584662387e+01,1.477400000000000091e+02,0.000000000000000000e+00,7.950907132624959850e+00,0.000000000000000000e+00,1.000000009956401037e+00,0.000000000000000000e+00,3.677444916862569043e-10,0.000000000000000000e+00 +2.763586569397025272e+01,1.477500000000000000e+02,0.000000000000000000e+00,7.952164850761112014e+00,0.000000000000000000e+00,1.000000009956863556e+00,0.000000000000000000e+00,-4.433761344793374414e-10,0.000000000000000000e+00 +2.763712321317259324e+01,1.477599999999999909e+02,0.000000000000000000e+00,7.953422369975972295e+00,0.000000000000000000e+00,1.000000009956306002e+00,0.000000000000000000e+00,4.121877908219477946e-10,0.000000000000000000e+00 +2.763838053354800195e+01,1.477700000000000102e+02,0.000000000000000000e+00,7.954679690363898992e+00,0.000000000000000000e+00,1.000000009956824254e+00,0.000000000000000000e+00,7.471422389713054127e-11,0.000000000000000000e+00 +2.763963765519076432e+01,1.477800000000000011e+02,0.000000000000000000e+00,7.955936812019178461e+00,0.000000000000000000e+00,1.000000009956918179e+00,0.000000000000000000e+00,-3.854661950481085872e-10,0.000000000000000000e+00 +2.764089457819509121e+01,1.477899999999999920e+02,0.000000000000000000e+00,7.957193735036020676e+00,0.000000000000000000e+00,1.000000009956433678e+00,0.000000000000000000e+00,1.047743199950348385e-10,0.000000000000000000e+00 +2.764215130265511888e+01,1.478000000000000114e+02,0.000000000000000000e+00,7.958450459508561003e+00,0.000000000000000000e+00,1.000000009956565350e+00,0.000000000000000000e+00,-1.936775562954325526e-10,0.000000000000000000e+00 +2.764340782866490898e+01,1.478100000000000023e+02,0.000000000000000000e+00,7.959706985530861978e+00,0.000000000000000000e+00,1.000000009956321989e+00,0.000000000000000000e+00,3.547191855792872803e-10,0.000000000000000000e+00 +2.764466415631844853e+01,1.478199999999999932e+02,0.000000000000000000e+00,7.960963313196910640e+00,0.000000000000000000e+00,1.000000009956767633e+00,0.000000000000000000e+00,-5.527563358224515920e-10,0.000000000000000000e+00 +2.764592028570965354e+01,1.478300000000000125e+02,0.000000000000000000e+00,7.962219442600621200e+00,0.000000000000000000e+00,1.000000009956073299e+00,0.000000000000000000e+00,4.092845620111792855e-10,0.000000000000000000e+00 +2.764717621693235827e+01,1.478400000000000034e+02,0.000000000000000000e+00,7.963475373835831483e+00,0.000000000000000000e+00,1.000000009956587332e+00,0.000000000000000000e+00,-1.890255768495331242e-10,0.000000000000000000e+00 +2.764843195008033305e+01,1.478499999999999943e+02,0.000000000000000000e+00,7.964731106996308263e+00,0.000000000000000000e+00,1.000000009956349967e+00,0.000000000000000000e+00,4.163109196457639830e-10,0.000000000000000000e+00 +2.764968748524726649e+01,1.478600000000000136e+02,0.000000000000000000e+00,7.965986642175741927e+00,0.000000000000000000e+00,1.000000009956872660e+00,0.000000000000000000e+00,-6.429603836967960521e-10,0.000000000000000000e+00 +2.765094282252677615e+01,1.478700000000000045e+02,0.000000000000000000e+00,7.967241979467750923e+00,0.000000000000000000e+00,1.000000009956065528e+00,0.000000000000000000e+00,5.261253132479624318e-10,0.000000000000000000e+00 +2.765219796201240499e+01,1.478799999999999955e+02,0.000000000000000000e+00,7.968497118965877313e+00,0.000000000000000000e+00,1.000000009956725888e+00,0.000000000000000000e+00,-6.375010546041183549e-10,0.000000000000000000e+00 +2.765345290379762488e+01,1.478900000000000148e+02,0.000000000000000000e+00,7.969752060763592993e+00,0.000000000000000000e+00,1.000000009955925862e+00,0.000000000000000000e+00,8.899521811396327911e-10,0.000000000000000000e+00 +2.765470764797583314e+01,1.479000000000000057e+02,0.000000000000000000e+00,7.971006804954292591e+00,0.000000000000000000e+00,1.000000009957042524e+00,0.000000000000000000e+00,-5.842502806697540076e-10,0.000000000000000000e+00 +2.765596219464034888e+01,1.479099999999999966e+02,0.000000000000000000e+00,7.972261351631301451e+00,0.000000000000000000e+00,1.000000009956309555e+00,0.000000000000000000e+00,-3.327971529702288085e-11,0.000000000000000000e+00 +2.765721654388442374e+01,1.479200000000000159e+02,0.000000000000000000e+00,7.973515700887866764e+00,0.000000000000000000e+00,1.000000009956267810e+00,0.000000000000000000e+00,-3.303708484082958758e-10,0.000000000000000000e+00 +2.765847069580123474e+01,1.479300000000000068e+02,0.000000000000000000e+00,7.974769852817165550e+00,0.000000000000000000e+00,1.000000009955853475e+00,0.000000000000000000e+00,7.322070359227823463e-10,0.000000000000000000e+00 +2.765972465048388429e+01,1.479399999999999977e+02,0.000000000000000000e+00,7.976023807512300223e+00,0.000000000000000000e+00,1.000000009956771629e+00,0.000000000000000000e+00,-2.856676318056492466e-10,0.000000000000000000e+00 +2.766097840802540375e+01,1.479500000000000171e+02,0.000000000000000000e+00,7.977277565066302145e+00,0.000000000000000000e+00,1.000000009956413471e+00,0.000000000000000000e+00,-4.640835986718651848e-11,0.000000000000000000e+00 +2.766223196851874633e+01,1.479600000000000080e+02,0.000000000000000000e+00,7.978531125572126292e+00,0.000000000000000000e+00,1.000000009956355296e+00,0.000000000000000000e+00,-2.956783362280086420e-10,0.000000000000000000e+00 +2.766348533205679772e+01,1.479699999999999989e+02,0.000000000000000000e+00,7.979784489122656588e+00,0.000000000000000000e+00,1.000000009955984703e+00,0.000000000000000000e+00,4.606857045112745618e-11,0.000000000000000000e+00 +2.766473849873236901e+01,1.479799999999999898e+02,0.000000000000000000e+00,7.981037655810703235e+00,0.000000000000000000e+00,1.000000009956042435e+00,0.000000000000000000e+00,3.625811438598680477e-10,0.000000000000000000e+00 +2.766599146863819669e+01,1.479900000000000091e+02,0.000000000000000000e+00,7.982290625729004496e+00,0.000000000000000000e+00,1.000000009956496738e+00,0.000000000000000000e+00,3.704367347928364912e-11,0.000000000000000000e+00 +2.766724424186694620e+01,1.480000000000000000e+02,0.000000000000000000e+00,7.983543398970225802e+00,0.000000000000000000e+00,1.000000009956543146e+00,0.000000000000000000e+00,-4.160533330606756677e-10,0.000000000000000000e+00 +2.766849681851120835e+01,1.480099999999999909e+02,0.000000000000000000e+00,7.984795975626958864e+00,0.000000000000000000e+00,1.000000009956022007e+00,0.000000000000000000e+00,8.474848548156025666e-11,0.000000000000000000e+00 +2.766974919866350291e+01,1.480200000000000102e+02,0.000000000000000000e+00,7.986048355791722564e+00,0.000000000000000000e+00,1.000000009956128144e+00,0.000000000000000000e+00,-2.094218822399357047e-10,0.000000000000000000e+00 +2.767100138241627860e+01,1.480300000000000011e+02,0.000000000000000000e+00,7.987300539556964729e+00,0.000000000000000000e+00,1.000000009955865909e+00,0.000000000000000000e+00,3.495641412657851882e-10,0.000000000000000000e+00 +2.767225336986190953e+01,1.480399999999999920e+02,0.000000000000000000e+00,7.988552527015059468e+00,0.000000000000000000e+00,1.000000009956303559e+00,0.000000000000000000e+00,1.188456043155225944e-11,0.000000000000000000e+00 +2.767350516109269520e+01,1.480500000000000114e+02,0.000000000000000000e+00,7.989804318258309834e+00,0.000000000000000000e+00,1.000000009956318436e+00,0.000000000000000000e+00,-1.408629796961124610e-10,0.000000000000000000e+00 +2.767475675620086761e+01,1.480600000000000023e+02,0.000000000000000000e+00,7.991055913378945164e+00,0.000000000000000000e+00,1.000000009956142133e+00,0.000000000000000000e+00,-1.582738801072296237e-10,0.000000000000000000e+00 +2.767600815527858771e+01,1.480699999999999932e+02,0.000000000000000000e+00,7.992307312469122849e+00,0.000000000000000000e+00,1.000000009955944069e+00,0.000000000000000000e+00,4.763157163504755451e-10,0.000000000000000000e+00 +2.767725935841793472e+01,1.480800000000000125e+02,0.000000000000000000e+00,7.993558515620928340e+00,0.000000000000000000e+00,1.000000009956540037e+00,0.000000000000000000e+00,-5.567944563967331256e-10,0.000000000000000000e+00 +2.767851036571092749e+01,1.480900000000000034e+02,0.000000000000000000e+00,7.994809522926376033e+00,0.000000000000000000e+00,1.000000009955843483e+00,0.000000000000000000e+00,9.603855381852642631e-11,0.000000000000000000e+00 +2.767976117724950313e+01,1.480999999999999943e+02,0.000000000000000000e+00,7.996060334477405718e+00,0.000000000000000000e+00,1.000000009955963609e+00,0.000000000000000000e+00,1.152287855593811370e-10,0.000000000000000000e+00 +2.768101179312553484e+01,1.481100000000000136e+02,0.000000000000000000e+00,7.997310950365887905e+00,0.000000000000000000e+00,1.000000009956107716e+00,0.000000000000000000e+00,1.793517347940986604e-11,0.000000000000000000e+00 +2.768226221343081761e+01,1.481200000000000045e+02,0.000000000000000000e+00,7.998561370683620275e+00,0.000000000000000000e+00,1.000000009956130143e+00,0.000000000000000000e+00,3.212851655735409323e-10,0.000000000000000000e+00 +2.768351243825707897e+01,1.481299999999999955e+02,0.000000000000000000e+00,7.999811595522328567e+00,0.000000000000000000e+00,1.000000009956531821e+00,0.000000000000000000e+00,-1.602236134692600545e-10,0.000000000000000000e+00 +2.768476246769597182e+01,1.481400000000000148e+02,0.000000000000000000e+00,8.001061624973667463e+00,0.000000000000000000e+00,1.000000009956331537e+00,0.000000000000000000e+00,-9.103260315860301040e-10,0.000000000000000000e+00 +2.768601230183907802e+01,1.481500000000000057e+02,0.000000000000000000e+00,8.002311459129218818e+00,0.000000000000000000e+00,1.000000009955193780e+00,0.000000000000000000e+00,2.972703654596382833e-10,0.000000000000000000e+00 +2.768726194077791192e+01,1.481599999999999966e+02,0.000000000000000000e+00,8.003561098080492542e+00,0.000000000000000000e+00,1.000000009955565261e+00,0.000000000000000000e+00,5.690426493577257374e-10,0.000000000000000000e+00 +2.768851138460390970e+01,1.481700000000000159e+02,0.000000000000000000e+00,8.004810541918930156e+00,0.000000000000000000e+00,1.000000009956276248e+00,0.000000000000000000e+00,-1.459265920303973923e-10,0.000000000000000000e+00 +2.768976063340844362e+01,1.481800000000000068e+02,0.000000000000000000e+00,8.006059790735900350e+00,0.000000000000000000e+00,1.000000009956093949e+00,0.000000000000000000e+00,3.784728373918240717e-10,0.000000000000000000e+00 +2.769100968728280776e+01,1.481899999999999977e+02,0.000000000000000000e+00,8.007308844622698984e+00,0.000000000000000000e+00,1.000000009956566682e+00,0.000000000000000000e+00,-1.322994716287107108e-09,0.000000000000000000e+00 +2.769225854631822870e+01,1.482000000000000171e+02,0.000000000000000000e+00,8.008557703670552641e+00,0.000000000000000000e+00,1.000000009954914448e+00,0.000000000000000000e+00,1.533746689522852591e-09,0.000000000000000000e+00 +2.769350721060585840e+01,1.482100000000000080e+02,0.000000000000000000e+00,8.009806367970613294e+00,0.000000000000000000e+00,1.000000009956829583e+00,0.000000000000000000e+00,-1.353642448501098734e-09,0.000000000000000000e+00 +2.769475568023678491e+01,1.482199999999999989e+02,0.000000000000000000e+00,8.011054837613968971e+00,0.000000000000000000e+00,1.000000009955139602e+00,0.000000000000000000e+00,1.359545634380311666e-09,0.000000000000000000e+00 +2.769600395530201808e+01,1.482299999999999898e+02,0.000000000000000000e+00,8.012303112691627760e+00,0.000000000000000000e+00,1.000000009956836688e+00,0.000000000000000000e+00,-1.774818866367137738e-09,0.000000000000000000e+00 +2.769725203589250029e+01,1.482400000000000091e+02,0.000000000000000000e+00,8.013551193294535580e+00,0.000000000000000000e+00,1.000000009954621571e+00,0.000000000000000000e+00,1.736661029351319913e-09,0.000000000000000000e+00 +2.769849992209909928e+01,1.482500000000000000e+02,0.000000000000000000e+00,8.014799079513558411e+00,0.000000000000000000e+00,1.000000009956788727e+00,0.000000000000000000e+00,-7.011793006946525642e-10,0.000000000000000000e+00 +2.769974761401261887e+01,1.482599999999999909e+02,0.000000000000000000e+00,8.016046771439501839e+00,0.000000000000000000e+00,1.000000009955913871e+00,0.000000000000000000e+00,-1.263743156281648493e-11,0.000000000000000000e+00 +2.770099511172378826e+01,1.482700000000000102e+02,0.000000000000000000e+00,8.017294269163091514e+00,0.000000000000000000e+00,1.000000009955898106e+00,0.000000000000000000e+00,-8.108797055159185709e-10,0.000000000000000000e+00 +2.770224241532326559e+01,1.482800000000000011e+02,0.000000000000000000e+00,8.018541572774987358e+00,0.000000000000000000e+00,1.000000009954886693e+00,0.000000000000000000e+00,1.422420595196246945e-09,0.000000000000000000e+00 +2.770348952490164152e+01,1.482899999999999920e+02,0.000000000000000000e+00,8.019788682365776467e+00,0.000000000000000000e+00,1.000000009956660607e+00,0.000000000000000000e+00,-1.357822492288086522e-09,0.000000000000000000e+00 +2.770473644054942852e+01,1.483000000000000114e+02,0.000000000000000000e+00,8.021035598025980207e+00,0.000000000000000000e+00,1.000000009954967517e+00,0.000000000000000000e+00,1.081440007571238265e-09,0.000000000000000000e+00 +2.770598316235707870e+01,1.483100000000000023e+02,0.000000000000000000e+00,8.022282319846041787e+00,0.000000000000000000e+00,1.000000009956315772e+00,0.000000000000000000e+00,-4.510263015034027816e-10,0.000000000000000000e+00 +2.770722969041496953e+01,1.483199999999999932e+02,0.000000000000000000e+00,8.023528847916342244e+00,0.000000000000000000e+00,1.000000009955753555e+00,0.000000000000000000e+00,-2.893288020059645320e-10,0.000000000000000000e+00 +2.770847602481340388e+01,1.483300000000000125e+02,0.000000000000000000e+00,8.024775182327186229e+00,0.000000000000000000e+00,1.000000009955392954e+00,0.000000000000000000e+00,3.743683731476248364e-10,0.000000000000000000e+00 +2.770972216564262425e+01,1.483400000000000034e+02,0.000000000000000000e+00,8.026021323168810895e+00,0.000000000000000000e+00,1.000000009955859470e+00,0.000000000000000000e+00,3.480509135156115123e-10,0.000000000000000000e+00 +2.771096811299279139e+01,1.483499999999999943e+02,0.000000000000000000e+00,8.027267270531384113e+00,0.000000000000000000e+00,1.000000009956293123e+00,0.000000000000000000e+00,-4.188666765825022844e-10,0.000000000000000000e+00 +2.771221386695400568e+01,1.483600000000000136e+02,0.000000000000000000e+00,8.028513024505002704e+00,0.000000000000000000e+00,1.000000009955771318e+00,0.000000000000000000e+00,-8.301978028395449958e-10,0.000000000000000000e+00 +2.771345942761629644e+01,1.483700000000000045e+02,0.000000000000000000e+00,8.029758585179692432e+00,0.000000000000000000e+00,1.000000009954737257e+00,0.000000000000000000e+00,1.355944557530442995e-09,0.000000000000000000e+00 +2.771470479506961482e+01,1.483799999999999955e+02,0.000000000000000000e+00,8.031003952645409782e+00,0.000000000000000000e+00,1.000000009956425906e+00,0.000000000000000000e+00,-7.812379258296151531e-10,0.000000000000000000e+00 +2.771594996940385158e+01,1.483900000000000148e+02,0.000000000000000000e+00,8.032249126992045518e+00,0.000000000000000000e+00,1.000000009955453129e+00,0.000000000000000000e+00,-4.184132252210334646e-10,0.000000000000000000e+00 +2.771719495070882644e+01,1.484000000000000057e+02,0.000000000000000000e+00,8.033494108309414017e+00,0.000000000000000000e+00,1.000000009954932212e+00,0.000000000000000000e+00,1.252401785266430251e-09,0.000000000000000000e+00 +2.771843973907428449e+01,1.484099999999999966e+02,0.000000000000000000e+00,8.034738896687263932e+00,0.000000000000000000e+00,1.000000009956491187e+00,0.000000000000000000e+00,-1.550535605490322132e-09,0.000000000000000000e+00 +2.771968433458990688e+01,1.484200000000000159e+02,0.000000000000000000e+00,8.035983492215276414e+00,0.000000000000000000e+00,1.000000009954561397e+00,0.000000000000000000e+00,1.443714979465799964e-09,0.000000000000000000e+00 +2.772092873734530016e+01,1.484300000000000068e+02,0.000000000000000000e+00,8.037227894983056231e+00,0.000000000000000000e+00,1.000000009956357960e+00,0.000000000000000000e+00,-1.282073229748232293e-09,0.000000000000000000e+00 +2.772217294743000338e+01,1.484399999999999977e+02,0.000000000000000000e+00,8.038472105080147756e+00,0.000000000000000000e+00,1.000000009954762792e+00,0.000000000000000000e+00,5.483210842439903168e-10,0.000000000000000000e+00 +2.772341696493348806e+01,1.484500000000000171e+02,0.000000000000000000e+00,8.039716122596017200e+00,0.000000000000000000e+00,1.000000009955444913e+00,0.000000000000000000e+00,1.785175590151237001e-12,0.000000000000000000e+00 +2.772466078994515826e+01,1.484600000000000080e+02,0.000000000000000000e+00,8.040959947620068604e+00,0.000000000000000000e+00,1.000000009955447133e+00,0.000000000000000000e+00,4.729661751411553649e-10,0.000000000000000000e+00 +2.772590442255434340e+01,1.484699999999999989e+02,0.000000000000000000e+00,8.042203580241633176e+00,0.000000000000000000e+00,1.000000009956035329e+00,0.000000000000000000e+00,-3.828600653407856318e-10,0.000000000000000000e+00 +2.772714786285030542e+01,1.484799999999999898e+02,0.000000000000000000e+00,8.043447020549974624e+00,0.000000000000000000e+00,1.000000009955559266e+00,0.000000000000000000e+00,-3.170157128246354432e-10,0.000000000000000000e+00 +2.772839111092223874e+01,1.484900000000000091e+02,0.000000000000000000e+00,8.044690268634285601e+00,0.000000000000000000e+00,1.000000009955165137e+00,0.000000000000000000e+00,6.230544892681685777e-10,0.000000000000000000e+00 +2.772963416685927029e+01,1.485000000000000000e+02,0.000000000000000000e+00,8.045933324583691260e+00,0.000000000000000000e+00,1.000000009955939628e+00,0.000000000000000000e+00,9.022108235867163088e-11,0.000000000000000000e+00 +2.773087703075045596e+01,1.485099999999999909e+02,0.000000000000000000e+00,8.047176188487249249e+00,0.000000000000000000e+00,1.000000009956051761e+00,0.000000000000000000e+00,-8.146167350301017836e-10,0.000000000000000000e+00 +2.773211970268478055e+01,1.485200000000000102e+02,0.000000000000000000e+00,8.048418860433946165e+00,0.000000000000000000e+00,1.000000009955039459e+00,0.000000000000000000e+00,1.610184295508739776e-10,0.000000000000000000e+00 +2.773336218275116494e+01,1.485300000000000011e+02,0.000000000000000000e+00,8.049661340512699326e+00,0.000000000000000000e+00,1.000000009955239522e+00,0.000000000000000000e+00,-4.818786919274450307e-10,0.000000000000000000e+00 +2.773460447103845894e+01,1.485399999999999920e+02,0.000000000000000000e+00,8.050903628812360324e+00,0.000000000000000000e+00,1.000000009954640889e+00,0.000000000000000000e+00,6.612553287816274052e-10,0.000000000000000000e+00 +2.773584656763544487e+01,1.485500000000000114e+02,0.000000000000000000e+00,8.052145725421709699e+00,0.000000000000000000e+00,1.000000009955462232e+00,0.000000000000000000e+00,8.921798226836214294e-11,0.000000000000000000e+00 +2.773708847263083399e+01,1.485600000000000023e+02,0.000000000000000000e+00,8.053387630429462263e+00,0.000000000000000000e+00,1.000000009955573033e+00,0.000000000000000000e+00,5.632865515326558147e-11,0.000000000000000000e+00 +2.773833018611327006e+01,1.485699999999999932e+02,0.000000000000000000e+00,8.054629343924261775e+00,0.000000000000000000e+00,1.000000009955642977e+00,0.000000000000000000e+00,-6.375956121094093451e-10,0.000000000000000000e+00 +2.773957170817133289e+01,1.485800000000000125e+02,0.000000000000000000e+00,8.055870865994684493e+00,0.000000000000000000e+00,1.000000009954851388e+00,0.000000000000000000e+00,2.659890081021319642e-10,0.000000000000000000e+00 +2.774081303889352768e+01,1.485900000000000034e+02,0.000000000000000000e+00,8.057112196729237397e+00,0.000000000000000000e+00,1.000000009955181568e+00,0.000000000000000000e+00,4.130889422137642420e-10,0.000000000000000000e+00 +2.774205417836829568e+01,1.485999999999999943e+02,0.000000000000000000e+00,8.058353336216361740e+00,0.000000000000000000e+00,1.000000009955694269e+00,0.000000000000000000e+00,-2.437045508491371901e-10,0.000000000000000000e+00 +2.774329512668401065e+01,1.486100000000000136e+02,0.000000000000000000e+00,8.059594284544429499e+00,0.000000000000000000e+00,1.000000009955391844e+00,0.000000000000000000e+00,5.544148050322360068e-10,0.000000000000000000e+00 +2.774453588392897174e+01,1.486200000000000045e+02,0.000000000000000000e+00,8.060835041801743373e+00,0.000000000000000000e+00,1.000000009956079738e+00,0.000000000000000000e+00,-7.012690804448602515e-10,0.000000000000000000e+00 +2.774577645019141769e+01,1.486299999999999955e+02,0.000000000000000000e+00,8.062075608076540334e+00,0.000000000000000000e+00,1.000000009955209768e+00,0.000000000000000000e+00,-5.961167509592718470e-10,0.000000000000000000e+00 +2.774701682555951621e+01,1.486400000000000148e+02,0.000000000000000000e+00,8.063315983456986302e+00,0.000000000000000000e+00,1.000000009954470359e+00,0.000000000000000000e+00,8.226960655829364177e-10,0.000000000000000000e+00 +2.774825701012136747e+01,1.486500000000000057e+02,0.000000000000000000e+00,8.064556168031181471e+00,0.000000000000000000e+00,1.000000009955490654e+00,0.000000000000000000e+00,4.458821058683257615e-11,0.000000000000000000e+00 +2.774949700396500063e+01,1.486599999999999966e+02,0.000000000000000000e+00,8.065796161887160309e+00,0.000000000000000000e+00,1.000000009955545943e+00,0.000000000000000000e+00,-6.698214792923535468e-10,0.000000000000000000e+00 +2.775073680717838442e+01,1.486700000000000159e+02,0.000000000000000000e+00,8.067035965112886231e+00,0.000000000000000000e+00,1.000000009954715496e+00,0.000000000000000000e+00,9.447009325925873831e-10,0.000000000000000000e+00 +2.775197641984941299e+01,1.486800000000000068e+02,0.000000000000000000e+00,8.068275577796255149e+00,0.000000000000000000e+00,1.000000009955886560e+00,0.000000000000000000e+00,-9.389340927696871064e-10,0.000000000000000000e+00 +2.775321584206591652e+01,1.486899999999999977e+02,0.000000000000000000e+00,8.069515000025099027e+00,0.000000000000000000e+00,1.000000009954722824e+00,0.000000000000000000e+00,5.694315834432420504e-10,0.000000000000000000e+00 +2.775445507391565769e+01,1.487000000000000171e+02,0.000000000000000000e+00,8.070754231887176999e+00,0.000000000000000000e+00,1.000000009955428482e+00,0.000000000000000000e+00,-3.598471409211756596e-10,0.000000000000000000e+00 +2.775569411548633170e+01,1.487100000000000080e+02,0.000000000000000000e+00,8.071993273470186026e+00,0.000000000000000000e+00,1.000000009954982616e+00,0.000000000000000000e+00,-3.038020634734009792e-10,0.000000000000000000e+00 +2.775693296686556621e+01,1.487199999999999989e+02,0.000000000000000000e+00,8.073232124861752013e+00,0.000000000000000000e+00,1.000000009954606250e+00,0.000000000000000000e+00,6.915918845988108975e-10,0.000000000000000000e+00 +2.775817162814091787e+01,1.487299999999999898e+02,0.000000000000000000e+00,8.074470786149435142e+00,0.000000000000000000e+00,1.000000009955462899e+00,0.000000000000000000e+00,-8.944741559013708704e-10,0.000000000000000000e+00 +2.775941009939988291e+01,1.487400000000000091e+02,0.000000000000000000e+00,8.075709257420729870e+00,0.000000000000000000e+00,1.000000009954355118e+00,0.000000000000000000e+00,6.810450816559828544e-10,0.000000000000000000e+00 +2.776064838072988650e+01,1.487500000000000000e+02,0.000000000000000000e+00,8.076947538763059597e+00,0.000000000000000000e+00,1.000000009955198443e+00,0.000000000000000000e+00,7.392570501259261296e-10,0.000000000000000000e+00 +2.776188647221828631e+01,1.487599999999999909e+02,0.000000000000000000e+00,8.078185630263785555e+00,0.000000000000000000e+00,1.000000009956113711e+00,0.000000000000000000e+00,-1.928066980288033110e-09,0.000000000000000000e+00 +2.776312437395237609e+01,1.487700000000000102e+02,0.000000000000000000e+00,8.079423532010199693e+00,0.000000000000000000e+00,1.000000009953726954e+00,0.000000000000000000e+00,1.907013927776999610e-09,0.000000000000000000e+00 +2.776436208601937849e+01,1.487800000000000011e+02,0.000000000000000000e+00,8.080661244089522910e+00,0.000000000000000000e+00,1.000000009956087288e+00,0.000000000000000000e+00,-1.715857755373930858e-09,0.000000000000000000e+00 +2.776559960850645226e+01,1.487899999999999920e+02,0.000000000000000000e+00,8.081898766588919258e+00,0.000000000000000000e+00,1.000000009953963875e+00,0.000000000000000000e+00,1.073495035569192052e-09,0.000000000000000000e+00 +2.776683694150069215e+01,1.488000000000000114e+02,0.000000000000000000e+00,8.083136099595474633e+00,0.000000000000000000e+00,1.000000009955292146e+00,0.000000000000000000e+00,-2.119678595673914138e-10,0.000000000000000000e+00 +2.776807408508911834e+01,1.488100000000000023e+02,0.000000000000000000e+00,8.084373243196218084e+00,0.000000000000000000e+00,1.000000009955029912e+00,0.000000000000000000e+00,1.830993292109038240e-10,0.000000000000000000e+00 +2.776931103935869061e+01,1.488199999999999932e+02,0.000000000000000000e+00,8.085610197478105832e+00,0.000000000000000000e+00,1.000000009955256397e+00,0.000000000000000000e+00,-1.096968700466743342e-10,0.000000000000000000e+00 +2.777054780439630122e+01,1.488300000000000125e+02,0.000000000000000000e+00,8.086846962528030147e+00,0.000000000000000000e+00,1.000000009955120728e+00,0.000000000000000000e+00,2.460027812270704160e-11,0.000000000000000000e+00 +2.777178438028877494e+01,1.488400000000000034e+02,0.000000000000000000e+00,8.088083538432815800e+00,0.000000000000000000e+00,1.000000009955151148e+00,0.000000000000000000e+00,-6.226438393263438779e-10,0.000000000000000000e+00 +2.777302076712287260e+01,1.488499999999999943e+02,0.000000000000000000e+00,8.089319925279221835e+00,0.000000000000000000e+00,1.000000009954381319e+00,0.000000000000000000e+00,2.270383966507901922e-10,0.000000000000000000e+00 +2.777425696498528396e+01,1.488600000000000136e+02,0.000000000000000000e+00,8.090556123153939794e+00,0.000000000000000000e+00,1.000000009954661984e+00,0.000000000000000000e+00,2.028208237590155993e-10,0.000000000000000000e+00 +2.777549297396263839e+01,1.488700000000000045e+02,0.000000000000000000e+00,8.091792132143597271e+00,0.000000000000000000e+00,1.000000009954912672e+00,0.000000000000000000e+00,4.206165500641603445e-10,0.000000000000000000e+00 +2.777672879414149421e+01,1.488799999999999955e+02,0.000000000000000000e+00,8.093027952334754360e+00,0.000000000000000000e+00,1.000000009955432478e+00,0.000000000000000000e+00,-3.293925185194802868e-10,0.000000000000000000e+00 +2.777796442560834578e+01,1.488900000000000148e+02,0.000000000000000000e+00,8.094263583813905427e+00,0.000000000000000000e+00,1.000000009955025471e+00,0.000000000000000000e+00,-9.304557696189117773e-10,0.000000000000000000e+00 +2.777919986844961997e+01,1.489000000000000057e+02,0.000000000000000000e+00,8.095499026667477338e+00,0.000000000000000000e+00,1.000000009953875946e+00,0.000000000000000000e+00,9.007582595950298496e-10,0.000000000000000000e+00 +2.778043512275167970e+01,1.489099999999999966e+02,0.000000000000000000e+00,8.096734280981831233e+00,0.000000000000000000e+00,1.000000009954988611e+00,0.000000000000000000e+00,4.613247598372755542e-10,0.000000000000000000e+00 +2.778167018860082038e+01,1.489200000000000159e+02,0.000000000000000000e+00,8.097969346843266081e+00,0.000000000000000000e+00,1.000000009955558378e+00,0.000000000000000000e+00,-1.132090310556614902e-09,0.000000000000000000e+00 +2.778290506608327348e+01,1.489300000000000068e+02,0.000000000000000000e+00,8.099204224338011571e+00,0.000000000000000000e+00,1.000000009954160385e+00,0.000000000000000000e+00,7.346401099988136497e-10,0.000000000000000000e+00 +2.778413975528520297e+01,1.489399999999999977e+02,0.000000000000000000e+00,8.100438913552229891e+00,0.000000000000000000e+00,1.000000009955067437e+00,0.000000000000000000e+00,-9.745133152355919576e-10,0.000000000000000000e+00 +2.778537425629270530e+01,1.489500000000000171e+02,0.000000000000000000e+00,8.101673414572022836e+00,0.000000000000000000e+00,1.000000009953864399e+00,0.000000000000000000e+00,6.862928908855595728e-10,0.000000000000000000e+00 +2.778660856919181654e+01,1.489600000000000080e+02,0.000000000000000000e+00,8.102907727483421141e+00,0.000000000000000000e+00,1.000000009954711500e+00,0.000000000000000000e+00,1.009535016891704400e-09,0.000000000000000000e+00 +2.778784269406850527e+01,1.489699999999999989e+02,0.000000000000000000e+00,8.104141852372395149e+00,0.000000000000000000e+00,1.000000009955957392e+00,0.000000000000000000e+00,-1.218428568759166359e-09,0.000000000000000000e+00 +2.778907663100867254e+01,1.489799999999999898e+02,0.000000000000000000e+00,8.105375789324847702e+00,0.000000000000000000e+00,1.000000009954453928e+00,0.000000000000000000e+00,-2.112912328803811102e-10,0.000000000000000000e+00 +2.779031038009815546e+01,1.489900000000000091e+02,0.000000000000000000e+00,8.106609538426612360e+00,0.000000000000000000e+00,1.000000009954193247e+00,0.000000000000000000e+00,4.869078207613061558e-10,0.000000000000000000e+00 +2.779154394142272722e+01,1.490000000000000000e+02,0.000000000000000000e+00,8.107843099763462291e+00,0.000000000000000000e+00,1.000000009954793878e+00,0.000000000000000000e+00,-3.380968691980742102e-10,0.000000000000000000e+00 +2.779277731506809346e+01,1.490099999999999909e+02,0.000000000000000000e+00,8.109076473421104936e+00,0.000000000000000000e+00,1.000000009954376878e+00,0.000000000000000000e+00,7.711869928353508017e-10,0.000000000000000000e+00 +2.779401050111989235e+01,1.490200000000000102e+02,0.000000000000000000e+00,8.110309659485180234e+00,0.000000000000000000e+00,1.000000009955327895e+00,0.000000000000000000e+00,-9.027663577354340412e-10,0.000000000000000000e+00 +2.779524349966370167e+01,1.490300000000000011e+02,0.000000000000000000e+00,8.111542658041265952e+00,0.000000000000000000e+00,1.000000009954214786e+00,0.000000000000000000e+00,4.355118520736618682e-10,0.000000000000000000e+00 +2.779647631078503522e+01,1.490399999999999920e+02,0.000000000000000000e+00,8.112775469174870580e+00,0.000000000000000000e+00,1.000000009954751690e+00,0.000000000000000000e+00,6.737228609380089569e-11,0.000000000000000000e+00 +2.779770893456933578e+01,1.490500000000000114e+02,0.000000000000000000e+00,8.114008092971442210e+00,0.000000000000000000e+00,1.000000009954834734e+00,0.000000000000000000e+00,-8.851613167053228271e-10,0.000000000000000000e+00 +2.779894137110198571e+01,1.490600000000000023e+02,0.000000000000000000e+00,8.115240529516361434e+00,0.000000000000000000e+00,1.000000009953743829e+00,0.000000000000000000e+00,1.041524428049379927e-09,0.000000000000000000e+00 +2.780017362046830343e+01,1.490699999999999932e+02,0.000000000000000000e+00,8.116472778894943119e+00,0.000000000000000000e+00,1.000000009955027247e+00,0.000000000000000000e+00,-4.577636238599226139e-11,0.000000000000000000e+00 +2.780140568275353630e+01,1.490800000000000125e+02,0.000000000000000000e+00,8.117704841192441734e+00,0.000000000000000000e+00,1.000000009954970848e+00,0.000000000000000000e+00,-6.840459281748438617e-10,0.000000000000000000e+00 +2.780263755804287484e+01,1.490900000000000034e+02,0.000000000000000000e+00,8.118936716494042471e+00,0.000000000000000000e+00,1.000000009954128188e+00,0.000000000000000000e+00,2.529280832162226704e-10,0.000000000000000000e+00 +2.780386924642143853e+01,1.490999999999999943e+02,0.000000000000000000e+00,8.120168404884866575e+00,0.000000000000000000e+00,1.000000009954439717e+00,0.000000000000000000e+00,3.791792248069663805e-10,0.000000000000000000e+00 +2.780510074797428643e+01,1.491100000000000136e+02,0.000000000000000000e+00,8.121399906449973116e+00,0.000000000000000000e+00,1.000000009954906677e+00,0.000000000000000000e+00,-1.523078188234194260e-09,0.000000000000000000e+00 +2.780633206278641012e+01,1.491200000000000045e+02,0.000000000000000000e+00,8.122631221274355440e+00,0.000000000000000000e+00,1.000000009953031288e+00,0.000000000000000000e+00,1.531244887967171018e-09,0.000000000000000000e+00 +2.780756319094274076e+01,1.491299999999999955e+02,0.000000000000000000e+00,8.123862349442939390e+00,0.000000000000000000e+00,1.000000009954916447e+00,0.000000000000000000e+00,1.230232387587922668e-10,0.000000000000000000e+00 +2.780879413252814203e+01,1.491400000000000148e+02,0.000000000000000000e+00,8.125093291040593968e+00,0.000000000000000000e+00,1.000000009955067881e+00,0.000000000000000000e+00,-1.106474848499060824e-09,0.000000000000000000e+00 +2.781002488762741365e+01,1.491500000000000057e+02,0.000000000000000000e+00,8.126324046152117120e+00,0.000000000000000000e+00,1.000000009953706082e+00,0.000000000000000000e+00,1.317397121635291209e-09,0.000000000000000000e+00 +2.781125545632529139e+01,1.491599999999999966e+02,0.000000000000000000e+00,8.127554614862242843e+00,0.000000000000000000e+00,1.000000009955327229e+00,0.000000000000000000e+00,-8.606517267368393548e-10,0.000000000000000000e+00 +2.781248583870644708e+01,1.491700000000000159e+02,0.000000000000000000e+00,8.128784997255646516e+00,0.000000000000000000e+00,1.000000009954268299e+00,0.000000000000000000e+00,-6.476170837411312218e-10,0.000000000000000000e+00 +2.781371603485548860e+01,1.491800000000000068e+02,0.000000000000000000e+00,8.130015193416932462e+00,0.000000000000000000e+00,1.000000009953471602e+00,0.000000000000000000e+00,7.405037099816048067e-10,0.000000000000000000e+00 +2.781494604485695632e+01,1.491899999999999977e+02,0.000000000000000000e+00,8.131245203430644608e+00,0.000000000000000000e+00,1.000000009954382429e+00,0.000000000000000000e+00,-2.637834227095441723e-10,0.000000000000000000e+00 +2.781617586879533377e+01,1.492000000000000171e+02,0.000000000000000000e+00,8.132475027381264709e+00,0.000000000000000000e+00,1.000000009954058022e+00,0.000000000000000000e+00,9.919106719414936346e-10,0.000000000000000000e+00 +2.781740550675503698e+01,1.492100000000000080e+02,0.000000000000000000e+00,8.133704665353207020e+00,0.000000000000000000e+00,1.000000009955277713e+00,0.000000000000000000e+00,-1.411063145226978706e-09,0.000000000000000000e+00 +2.781863495882041448e+01,1.492199999999999989e+02,0.000000000000000000e+00,8.134934117430825395e+00,0.000000000000000000e+00,1.000000009953542879e+00,0.000000000000000000e+00,7.082573788440852025e-10,0.000000000000000000e+00 +2.781986422507575796e+01,1.492299999999999898e+02,0.000000000000000000e+00,8.136163383698404417e+00,0.000000000000000000e+00,1.000000009954413516e+00,0.000000000000000000e+00,2.543680387267456232e-10,0.000000000000000000e+00 +2.782109330560529159e+01,1.492400000000000091e+02,0.000000000000000000e+00,8.137392464240171819e+00,0.000000000000000000e+00,1.000000009954726155e+00,0.000000000000000000e+00,-4.677971141546290119e-10,0.000000000000000000e+00 +2.782232220049317561e+01,1.492500000000000000e+02,0.000000000000000000e+00,8.138621359140287836e+00,0.000000000000000000e+00,1.000000009954151281e+00,0.000000000000000000e+00,-3.260075083641806658e-10,0.000000000000000000e+00 +2.782355090982350632e+01,1.492599999999999909e+02,0.000000000000000000e+00,8.139850068482848755e+00,0.000000000000000000e+00,1.000000009953750713e+00,0.000000000000000000e+00,6.365697289555736776e-10,0.000000000000000000e+00 +2.782477943368031958e+01,1.492700000000000102e+02,0.000000000000000000e+00,8.141078592351888688e+00,0.000000000000000000e+00,1.000000009954532754e+00,0.000000000000000000e+00,2.114988618251814026e-11,0.000000000000000000e+00 +2.782600777214758381e+01,1.492800000000000011e+02,0.000000000000000000e+00,8.142306930831379574e+00,0.000000000000000000e+00,1.000000009954558733e+00,0.000000000000000000e+00,-1.040659085435389576e-09,0.000000000000000000e+00 +2.782723592530920698e+01,1.492899999999999920e+02,0.000000000000000000e+00,8.143535084005227631e+00,0.000000000000000000e+00,1.000000009953280644e+00,0.000000000000000000e+00,9.411826898341681129e-10,0.000000000000000000e+00 +2.782846389324903313e+01,1.493000000000000114e+02,0.000000000000000000e+00,8.144763051957275124e+00,0.000000000000000000e+00,1.000000009954436386e+00,0.000000000000000000e+00,3.291471263225318642e-11,0.000000000000000000e+00 +2.782969167605084237e+01,1.493100000000000023e+02,0.000000000000000000e+00,8.145990834771305700e+00,0.000000000000000000e+00,1.000000009954476798e+00,0.000000000000000000e+00,-2.758379307860323916e-10,0.000000000000000000e+00 +2.783091927379835084e+01,1.493199999999999932e+02,0.000000000000000000e+00,8.147218432531035504e+00,0.000000000000000000e+00,1.000000009954138180e+00,0.000000000000000000e+00,-2.912563895923751211e-11,0.000000000000000000e+00 +2.783214668657521429e+01,1.493300000000000125e+02,0.000000000000000000e+00,8.148445845320118508e+00,0.000000000000000000e+00,1.000000009954102431e+00,0.000000000000000000e+00,-4.496156319615639731e-10,0.000000000000000000e+00 +2.783337391446502807e+01,1.493400000000000034e+02,0.000000000000000000e+00,8.149673073222146513e+00,0.000000000000000000e+00,1.000000009953550650e+00,0.000000000000000000e+00,7.777621850715018273e-10,0.000000000000000000e+00 +2.783460095755131647e+01,1.493499999999999943e+02,0.000000000000000000e+00,8.150900116320647371e+00,0.000000000000000000e+00,1.000000009954504998e+00,0.000000000000000000e+00,6.949875441069350400e-11,0.000000000000000000e+00 +2.783582781591754340e+01,1.493600000000000136e+02,0.000000000000000000e+00,8.152126974699088535e+00,0.000000000000000000e+00,1.000000009954590263e+00,0.000000000000000000e+00,-1.439057971649620907e-09,0.000000000000000000e+00 +2.783705448964711593e+01,1.493700000000000045e+02,0.000000000000000000e+00,8.153353648440871737e+00,0.000000000000000000e+00,1.000000009952825009e+00,0.000000000000000000e+00,2.111298030807283663e-09,0.000000000000000000e+00 +2.783828097882337360e+01,1.493799999999999955e+02,0.000000000000000000e+00,8.154580137629334757e+00,0.000000000000000000e+00,1.000000009955414493e+00,0.000000000000000000e+00,-2.311695826253983581e-09,0.000000000000000000e+00 +2.783950728352959203e+01,1.493900000000000148e+02,0.000000000000000000e+00,8.155806442347760310e+00,0.000000000000000000e+00,1.000000009952579649e+00,0.000000000000000000e+00,1.782339764790622758e-09,0.000000000000000000e+00 +2.784073340384898643e+01,1.494000000000000057e+02,0.000000000000000000e+00,8.157032562679356502e+00,0.000000000000000000e+00,1.000000009954765012e+00,0.000000000000000000e+00,-1.006678895429310689e-09,0.000000000000000000e+00 +2.784195933986470806e+01,1.494099999999999966e+02,0.000000000000000000e+00,8.158258498707281703e+00,0.000000000000000000e+00,1.000000009953530888e+00,0.000000000000000000e+00,1.092876312174274180e-09,0.000000000000000000e+00 +2.784318509165984779e+01,1.494200000000000159e+02,0.000000000000000000e+00,8.159484250514621451e+00,0.000000000000000000e+00,1.000000009954870483e+00,0.000000000000000000e+00,-1.418796661618149235e-09,0.000000000000000000e+00 +2.784441065931743253e+01,1.494300000000000068e+02,0.000000000000000000e+00,8.160709818184406217e+00,0.000000000000000000e+00,1.000000009953131652e+00,0.000000000000000000e+00,8.746724742797723960e-10,0.000000000000000000e+00 +2.784563604292042882e+01,1.494399999999999977e+02,0.000000000000000000e+00,8.161935201799597195e+00,0.000000000000000000e+00,1.000000009954203462e+00,0.000000000000000000e+00,-3.495953083525776379e-10,0.000000000000000000e+00 +2.784686124255173567e+01,1.494500000000000171e+02,0.000000000000000000e+00,8.163160401443100511e+00,0.000000000000000000e+00,1.000000009953775137e+00,0.000000000000000000e+00,7.799556380174635305e-10,0.000000000000000000e+00 +2.784808625829419526e+01,1.494600000000000080e+02,0.000000000000000000e+00,8.164385417197754791e+00,0.000000000000000000e+00,1.000000009954730595e+00,0.000000000000000000e+00,-1.698103839828743320e-09,0.000000000000000000e+00 +2.784931109023058937e+01,1.494699999999999989e+02,0.000000000000000000e+00,8.165610249146340038e+00,0.000000000000000000e+00,1.000000009952650704e+00,0.000000000000000000e+00,1.644689952451515821e-09,0.000000000000000000e+00 +2.785053573844362873e+01,1.494799999999999898e+02,0.000000000000000000e+00,8.166834897371568758e+00,0.000000000000000000e+00,1.000000009954664870e+00,0.000000000000000000e+00,-1.077160567195248181e-09,0.000000000000000000e+00 +2.785176020301597077e+01,1.494900000000000091e+02,0.000000000000000000e+00,8.168059361956100162e+00,0.000000000000000000e+00,1.000000009953345925e+00,0.000000000000000000e+00,7.528558756737473480e-10,0.000000000000000000e+00 +2.785298448403020899e+01,1.495000000000000000e+02,0.000000000000000000e+00,8.169283642982522409e+00,0.000000000000000000e+00,1.000000009954267632e+00,0.000000000000000000e+00,-1.614411369533651249e-11,0.000000000000000000e+00 +2.785420858156886936e+01,1.495099999999999909e+02,0.000000000000000000e+00,8.170507740533368590e+00,0.000000000000000000e+00,1.000000009954247870e+00,0.000000000000000000e+00,-1.059684245073975376e-09,0.000000000000000000e+00 +2.785543249571442459e+01,1.495200000000000102e+02,0.000000000000000000e+00,8.171731654691106073e+00,0.000000000000000000e+00,1.000000009952950908e+00,0.000000000000000000e+00,1.138773250471766942e-09,0.000000000000000000e+00 +2.785665622654927986e+01,1.495300000000000011e+02,0.000000000000000000e+00,8.172955385538140050e+00,0.000000000000000000e+00,1.000000009954344460e+00,0.000000000000000000e+00,-5.810863600184818247e-10,0.000000000000000000e+00 +2.785787977415577998e+01,1.495399999999999920e+02,0.000000000000000000e+00,8.174178933156818871e+00,0.000000000000000000e+00,1.000000009953633473e+00,0.000000000000000000e+00,-3.314249037865557799e-10,0.000000000000000000e+00 +2.785910313861620935e+01,1.495500000000000114e+02,0.000000000000000000e+00,8.175402297629423387e+00,0.000000000000000000e+00,1.000000009953228020e+00,0.000000000000000000e+00,6.594999334927397850e-10,0.000000000000000000e+00 +2.786032632001278841e+01,1.495600000000000023e+02,0.000000000000000000e+00,8.176625479038175826e+00,0.000000000000000000e+00,1.000000009954034708e+00,0.000000000000000000e+00,-2.578117315240426578e-11,0.000000000000000000e+00 +2.786154931842767724e+01,1.495699999999999932e+02,0.000000000000000000e+00,8.177848477465238020e+00,0.000000000000000000e+00,1.000000009954003177e+00,0.000000000000000000e+00,-5.647284587721321430e-11,0.000000000000000000e+00 +2.786277213394297547e+01,1.495800000000000125e+02,0.000000000000000000e+00,8.179071292992707853e+00,0.000000000000000000e+00,1.000000009953934121e+00,0.000000000000000000e+00,-6.628833086757742611e-10,0.000000000000000000e+00 +2.786399476664071884e+01,1.495900000000000034e+02,0.000000000000000000e+00,8.180293925702622815e+00,0.000000000000000000e+00,1.000000009953123659e+00,0.000000000000000000e+00,4.887905847642706325e-10,0.000000000000000000e+00 +2.786521721660288620e+01,1.495999999999999943e+02,0.000000000000000000e+00,8.181516375676958219e+00,0.000000000000000000e+00,1.000000009953721181e+00,0.000000000000000000e+00,-2.094610791737568379e-10,0.000000000000000000e+00 +2.786643948391139247e+01,1.496100000000000136e+02,0.000000000000000000e+00,8.182738642997630762e+00,0.000000000000000000e+00,1.000000009953465163e+00,0.000000000000000000e+00,-4.242538483056772091e-10,0.000000000000000000e+00 +2.786766156864809219e+01,1.496200000000000045e+02,0.000000000000000000e+00,8.183960727746493191e+00,0.000000000000000000e+00,1.000000009952946689e+00,0.000000000000000000e+00,9.931021644401422833e-10,0.000000000000000000e+00 +2.786888347089477591e+01,1.496299999999999955e+02,0.000000000000000000e+00,8.185182630005337856e+00,0.000000000000000000e+00,1.000000009954160163e+00,0.000000000000000000e+00,-7.600683140359071233e-10,0.000000000000000000e+00 +2.787010519073317383e+01,1.496400000000000148e+02,0.000000000000000000e+00,8.186404349855898488e+00,0.000000000000000000e+00,1.000000009953231572e+00,0.000000000000000000e+00,2.232193217293741774e-10,0.000000000000000000e+00 +2.787132672824495927e+01,1.496500000000000057e+02,0.000000000000000000e+00,8.187625887379843093e+00,0.000000000000000000e+00,1.000000009953504243e+00,0.000000000000000000e+00,3.305157006584859014e-10,0.000000000000000000e+00 +2.787254808351174162e+01,1.496599999999999966e+02,0.000000000000000000e+00,8.188847242658782832e+00,0.000000000000000000e+00,1.000000009953907920e+00,0.000000000000000000e+00,-4.818466779587143336e-10,0.000000000000000000e+00 +2.787376925661506988e+01,1.496700000000000159e+02,0.000000000000000000e+00,8.190068415774266697e+00,0.000000000000000000e+00,1.000000009953319502e+00,0.000000000000000000e+00,1.263899551454253786e-10,0.000000000000000000e+00 +2.787499024763643263e+01,1.496800000000000068e+02,0.000000000000000000e+00,8.191289406807781504e+00,0.000000000000000000e+00,1.000000009953473823e+00,0.000000000000000000e+00,-2.708240282420068622e-10,0.000000000000000000e+00 +2.787621105665725452e+01,1.496899999999999977e+02,0.000000000000000000e+00,8.192510215840755450e+00,0.000000000000000000e+00,1.000000009953143199e+00,0.000000000000000000e+00,6.687021503955085926e-10,0.000000000000000000e+00 +2.787743168375890335e+01,1.497000000000000171e+02,0.000000000000000000e+00,8.193730842954554561e+00,0.000000000000000000e+00,1.000000009953959434e+00,0.000000000000000000e+00,-6.746237783000871569e-10,0.000000000000000000e+00 +2.787865212902268652e+01,1.497100000000000080e+02,0.000000000000000000e+00,8.194951288230486242e+00,0.000000000000000000e+00,1.000000009953136093e+00,0.000000000000000000e+00,4.267066871155409235e-10,0.000000000000000000e+00 +2.787987239252984750e+01,1.497199999999999989e+02,0.000000000000000000e+00,8.196171551749793949e+00,0.000000000000000000e+00,1.000000009953656788e+00,0.000000000000000000e+00,3.525176660743445875e-10,0.000000000000000000e+00 +2.788109247436157290e+01,1.497299999999999898e+02,0.000000000000000000e+00,8.197391633593664295e+00,0.000000000000000000e+00,1.000000009954086888e+00,0.000000000000000000e+00,-9.403083906877023443e-10,0.000000000000000000e+00 +2.788231237459898892e+01,1.497400000000000091e+02,0.000000000000000000e+00,8.198611533843221721e+00,0.000000000000000000e+00,1.000000009952939806e+00,0.000000000000000000e+00,8.628968355498950171e-11,0.000000000000000000e+00 +2.788353209332315430e+01,1.497500000000000000e+02,0.000000000000000000e+00,8.199831252579528496e+00,0.000000000000000000e+00,1.000000009953045055e+00,0.000000000000000000e+00,1.004859943764789022e-09,0.000000000000000000e+00 +2.788475163061507800e+01,1.497599999999999909e+02,0.000000000000000000e+00,8.201050789883590042e+00,0.000000000000000000e+00,1.000000009954270519e+00,0.000000000000000000e+00,-6.176828888212500827e-10,0.000000000000000000e+00 +2.788597098655570150e+01,1.497700000000000102e+02,0.000000000000000000e+00,8.202270145836351389e+00,0.000000000000000000e+00,1.000000009953517344e+00,0.000000000000000000e+00,-4.534961886711323124e-11,0.000000000000000000e+00 +2.788719016122590943e+01,1.497800000000000011e+02,0.000000000000000000e+00,8.203489320518693617e+00,0.000000000000000000e+00,1.000000009953462055e+00,0.000000000000000000e+00,-9.036662644644363821e-10,0.000000000000000000e+00 +2.788840915470652249e+01,1.497899999999999920e+02,0.000000000000000000e+00,8.204708314011440962e+00,0.000000000000000000e+00,1.000000009952360491e+00,0.000000000000000000e+00,1.546899903598822625e-09,0.000000000000000000e+00 +2.788962796707830805e+01,1.498000000000000114e+02,0.000000000000000000e+00,8.205927126395355486e+00,0.000000000000000000e+00,1.000000009954245872e+00,0.000000000000000000e+00,-1.106185889206883280e-09,0.000000000000000000e+00 +2.789084659842196601e+01,1.498100000000000023e+02,0.000000000000000000e+00,8.207145757751144188e+00,0.000000000000000000e+00,1.000000009952897839e+00,0.000000000000000000e+00,-5.339492641412058215e-10,0.000000000000000000e+00 +2.789206504881814297e+01,1.498199999999999932e+02,0.000000000000000000e+00,8.208364208159446562e+00,0.000000000000000000e+00,1.000000009952247249e+00,0.000000000000000000e+00,8.320273938766191903e-10,0.000000000000000000e+00 +2.789328331834741803e+01,1.498300000000000125e+02,0.000000000000000000e+00,8.209582477700847036e+00,0.000000000000000000e+00,1.000000009953260882e+00,0.000000000000000000e+00,5.552533594483217096e-10,0.000000000000000000e+00 +2.789450140709031700e+01,1.498400000000000034e+02,0.000000000000000000e+00,8.210800566455871419e+00,0.000000000000000000e+00,1.000000009953937230e+00,0.000000000000000000e+00,-2.102108054985145711e-10,0.000000000000000000e+00 +2.789571931512730529e+01,1.498499999999999943e+02,0.000000000000000000e+00,8.212018474504983345e+00,0.000000000000000000e+00,1.000000009953681213e+00,0.000000000000000000e+00,-3.081604132296394499e-10,0.000000000000000000e+00 +2.789693704253878792e+01,1.498600000000000136e+02,0.000000000000000000e+00,8.213236201928586055e+00,0.000000000000000000e+00,1.000000009953305957e+00,0.000000000000000000e+00,-9.784176185544803362e-10,0.000000000000000000e+00 +2.789815458940510595e+01,1.498700000000000045e+02,0.000000000000000000e+00,8.214453748807024169e+00,0.000000000000000000e+00,1.000000009952114688e+00,0.000000000000000000e+00,1.333690620414817061e-09,0.000000000000000000e+00 +2.789937195580654716e+01,1.498799999999999955e+02,0.000000000000000000e+00,8.215671115220581910e+00,0.000000000000000000e+00,1.000000009953738278e+00,0.000000000000000000e+00,-6.060143374844788826e-10,0.000000000000000000e+00 +2.790058914182333893e+01,1.498900000000000148e+02,0.000000000000000000e+00,8.216888301249488435e+00,0.000000000000000000e+00,1.000000009953000646e+00,0.000000000000000000e+00,3.541385005850829075e-10,0.000000000000000000e+00 +2.790180614753564470e+01,1.499000000000000057e+02,0.000000000000000000e+00,8.218105306973907176e+00,0.000000000000000000e+00,1.000000009953431634e+00,0.000000000000000000e+00,-6.244417507620328043e-10,0.000000000000000000e+00 +2.790302297302357104e+01,1.499099999999999966e+02,0.000000000000000000e+00,8.219322132473946496e+00,0.000000000000000000e+00,1.000000009952671798e+00,0.000000000000000000e+00,1.587798838021366826e-11,0.000000000000000000e+00 +2.790423961836716771e+01,1.499200000000000159e+02,0.000000000000000000e+00,8.220538777829652588e+00,0.000000000000000000e+00,1.000000009952691116e+00,0.000000000000000000e+00,1.034412405819487843e-09,0.000000000000000000e+00 +2.790545608364642405e+01,1.499300000000000068e+02,0.000000000000000000e+00,8.221755243121014800e+00,0.000000000000000000e+00,1.000000009953949442e+00,0.000000000000000000e+00,-1.212378565752884100e-09,0.000000000000000000e+00 +2.790667236894126546e+01,1.499399999999999977e+02,0.000000000000000000e+00,8.222971528427963861e+00,0.000000000000000000e+00,1.000000009952474844e+00,0.000000000000000000e+00,4.380253647950623503e-10,0.000000000000000000e+00 +2.790788847433156405e+01,1.499500000000000171e+02,0.000000000000000000e+00,8.224187633830366551e+00,0.000000000000000000e+00,1.000000009953007529e+00,0.000000000000000000e+00,-5.953204970385205490e-11,0.000000000000000000e+00 +2.790910439989713154e+01,1.499600000000000080e+02,0.000000000000000000e+00,8.225403559408036358e+00,0.000000000000000000e+00,1.000000009952935143e+00,0.000000000000000000e+00,8.574978440960719177e-10,0.000000000000000000e+00 +2.791032014571771924e+01,1.499699999999999989e+02,0.000000000000000000e+00,8.226619305240724600e+00,0.000000000000000000e+00,1.000000009953977642e+00,0.000000000000000000e+00,-1.660266210408888165e-09,0.000000000000000000e+00 +2.791153571187302163e+01,1.499799999999999898e+02,0.000000000000000000e+00,8.227834871408125750e+00,0.000000000000000000e+00,1.000000009951959479e+00,0.000000000000000000e+00,7.607404573960127702e-10,0.000000000000000000e+00 +2.791275109844266922e+01,1.499900000000000091e+02,0.000000000000000000e+00,8.229050257989870332e+00,0.000000000000000000e+00,1.000000009952884072e+00,0.000000000000000000e+00,8.673795365216710673e-10,0.000000000000000000e+00 +2.791396630550624280e+01,1.500000000000000000e+02,0.000000000000000000e+00,8.230265465065537356e+00,0.000000000000000000e+00,1.000000009953938118e+00,0.000000000000000000e+00,-1.384868923854179970e-09,0.000000000000000000e+00 +2.791518133314325567e+01,1.500099999999999909e+02,0.000000000000000000e+00,8.231480492714643660e+00,0.000000000000000000e+00,1.000000009952255464e+00,0.000000000000000000e+00,1.183471902484518896e-09,0.000000000000000000e+00 +2.791639618143316426e+01,1.500200000000000102e+02,0.000000000000000000e+00,8.232695341016643908e+00,0.000000000000000000e+00,1.000000009953693203e+00,0.000000000000000000e+00,-1.096632548120065539e-09,0.000000000000000000e+00 +2.791761085045537172e+01,1.500300000000000011e+02,0.000000000000000000e+00,8.233910010050941253e+00,0.000000000000000000e+00,1.000000009952361157e+00,0.000000000000000000e+00,1.597930087978599061e-10,0.000000000000000000e+00 +2.791882534028921725e+01,1.500399999999999920e+02,0.000000000000000000e+00,8.235124499896873118e+00,0.000000000000000000e+00,1.000000009952555224e+00,0.000000000000000000e+00,9.654823020944888230e-11,0.000000000000000000e+00 +2.792003965101398322e+01,1.500500000000000114e+02,0.000000000000000000e+00,8.236338810633723639e+00,0.000000000000000000e+00,1.000000009952672464e+00,0.000000000000000000e+00,1.081572780805291962e-09,0.000000000000000000e+00 +2.792125378270889158e+01,1.500600000000000023e+02,0.000000000000000000e+00,8.237552942340716555e+00,0.000000000000000000e+00,1.000000009953985636e+00,0.000000000000000000e+00,-1.746977410561538322e-09,0.000000000000000000e+00 +2.792246773545311100e+01,1.500699999999999932e+02,0.000000000000000000e+00,8.238766895097018761e+00,0.000000000000000000e+00,1.000000009951864888e+00,0.000000000000000000e+00,1.212874789813095032e-09,0.000000000000000000e+00 +2.792368150932574622e+01,1.500800000000000125e+02,0.000000000000000000e+00,8.239980668981733203e+00,0.000000000000000000e+00,1.000000009953337043e+00,0.000000000000000000e+00,-9.294587721348435747e-10,0.000000000000000000e+00 +2.792489510440584510e+01,1.500900000000000034e+02,0.000000000000000000e+00,8.241194264073913089e+00,0.000000000000000000e+00,1.000000009952209057e+00,0.000000000000000000e+00,2.258112302004280266e-10,0.000000000000000000e+00 +2.792610852077240224e+01,1.500999999999999943e+02,0.000000000000000000e+00,8.242407680452545904e+00,0.000000000000000000e+00,1.000000009952483060e+00,0.000000000000000000e+00,1.021058625411014222e-09,0.000000000000000000e+00 +2.792732175850434828e+01,1.501100000000000136e+02,0.000000000000000000e+00,8.243620918196565839e+00,0.000000000000000000e+00,1.000000009953721847e+00,0.000000000000000000e+00,-9.997926365732298723e-10,0.000000000000000000e+00 +2.792853481768055701e+01,1.501200000000000045e+02,0.000000000000000000e+00,8.244833977384848467e+00,0.000000000000000000e+00,1.000000009952509039e+00,0.000000000000000000e+00,1.581742860348291770e-10,0.000000000000000000e+00 +2.792974769837984539e+01,1.501299999999999955e+02,0.000000000000000000e+00,8.246046858096207188e+00,0.000000000000000000e+00,1.000000009952700886e+00,0.000000000000000000e+00,-3.746205983571302056e-10,0.000000000000000000e+00 +2.793096040068096997e+01,1.501400000000000148e+02,0.000000000000000000e+00,8.247259560409402113e+00,0.000000000000000000e+00,1.000000009952246582e+00,0.000000000000000000e+00,9.850344801041670204e-10,0.000000000000000000e+00 +2.793217292466263402e+01,1.501500000000000057e+02,0.000000000000000000e+00,8.248472084403132953e+00,0.000000000000000000e+00,1.000000009953440960e+00,0.000000000000000000e+00,-6.364562320127139094e-10,0.000000000000000000e+00 +2.793338527040347685e+01,1.501599999999999966e+02,0.000000000000000000e+00,8.249684430156044357e+00,0.000000000000000000e+00,1.000000009952669355e+00,0.000000000000000000e+00,-4.465923329082341098e-10,0.000000000000000000e+00 +2.793459743798208805e+01,1.501700000000000159e+02,0.000000000000000000e+00,8.250896597746718797e+00,0.000000000000000000e+00,1.000000009952128011e+00,0.000000000000000000e+00,3.070544418242948510e-10,0.000000000000000000e+00 +2.793580942747698970e+01,1.501800000000000068e+02,0.000000000000000000e+00,8.252108587253683680e+00,0.000000000000000000e+00,1.000000009952500157e+00,0.000000000000000000e+00,3.745295174516834182e-10,0.000000000000000000e+00 +2.793702123896665412e+01,1.501899999999999977e+02,0.000000000000000000e+00,8.253320398755409570e+00,0.000000000000000000e+00,1.000000009952954017e+00,0.000000000000000000e+00,-2.846035980056871260e-10,0.000000000000000000e+00 +2.793823287252949328e+01,1.502000000000000171e+02,0.000000000000000000e+00,8.254532032330308411e+00,0.000000000000000000e+00,1.000000009952609181e+00,0.000000000000000000e+00,-5.014744095634009679e-10,0.000000000000000000e+00 +2.793944432824386226e+01,1.502100000000000080e+02,0.000000000000000000e+00,8.255743488056733526e+00,0.000000000000000000e+00,1.000000009952001667e+00,0.000000000000000000e+00,8.949405596301968363e-10,0.000000000000000000e+00 +2.794065560618805577e+01,1.502199999999999989e+02,0.000000000000000000e+00,8.256954766012981395e+00,0.000000000000000000e+00,1.000000009953085689e+00,0.000000000000000000e+00,-9.781254401248608108e-10,0.000000000000000000e+00 +2.794186670644031523e+01,1.502299999999999898e+02,0.000000000000000000e+00,8.258165866277293432e+00,0.000000000000000000e+00,1.000000009951901081e+00,0.000000000000000000e+00,1.104609541134991467e-09,0.000000000000000000e+00 +2.794307762907881809e+01,1.502400000000000091e+02,0.000000000000000000e+00,8.259376788927848878e+00,0.000000000000000000e+00,1.000000009953238678e+00,0.000000000000000000e+00,-1.641385300141889709e-10,0.000000000000000000e+00 +2.794428837418169209e+01,1.502500000000000000e+02,0.000000000000000000e+00,8.260587534042775459e+00,0.000000000000000000e+00,1.000000009953039948e+00,0.000000000000000000e+00,-1.191325172591635701e-09,0.000000000000000000e+00 +2.794549894182700811e+01,1.502599999999999909e+02,0.000000000000000000e+00,8.261798101700138730e+00,0.000000000000000000e+00,1.000000009951597768e+00,0.000000000000000000e+00,4.087238585490184383e-10,0.000000000000000000e+00 +2.794670933209277308e+01,1.502700000000000102e+02,0.000000000000000000e+00,8.263008491977947401e+00,0.000000000000000000e+00,1.000000009952092483e+00,0.000000000000000000e+00,9.597611021824690435e-10,0.000000000000000000e+00 +2.794791954505693710e+01,1.502800000000000011e+02,0.000000000000000000e+00,8.264218704954156891e+00,0.000000000000000000e+00,1.000000009953253999e+00,0.000000000000000000e+00,-7.925473740998834698e-10,0.000000000000000000e+00 +2.794912958079740051e+01,1.502899999999999920e+02,0.000000000000000000e+00,8.265428740706664001e+00,0.000000000000000000e+00,1.000000009952294988e+00,0.000000000000000000e+00,-3.597175964161771921e-11,0.000000000000000000e+00 +2.795033943939199972e+01,1.503000000000000114e+02,0.000000000000000000e+00,8.266638599313305136e+00,0.000000000000000000e+00,1.000000009952251467e+00,0.000000000000000000e+00,7.641446695170481485e-10,0.000000000000000000e+00 +2.795154912091851784e+01,1.503100000000000023e+02,0.000000000000000000e+00,8.267848280851863407e+00,0.000000000000000000e+00,1.000000009953175839e+00,0.000000000000000000e+00,-8.604540389612377194e-10,0.000000000000000000e+00 +2.795275862545468115e+01,1.503199999999999932e+02,0.000000000000000000e+00,8.269057785400065086e+00,0.000000000000000000e+00,1.000000009952135116e+00,0.000000000000000000e+00,-9.327386318831971738e-11,0.000000000000000000e+00 +2.795396795307815552e+01,1.503300000000000125e+02,0.000000000000000000e+00,8.270267113035576045e+00,0.000000000000000000e+00,1.000000009952022317e+00,0.000000000000000000e+00,5.977378470618699561e-10,0.000000000000000000e+00 +2.795517710386655352e+01,1.503400000000000034e+02,0.000000000000000000e+00,8.271476263836008869e+00,0.000000000000000000e+00,1.000000009952745073e+00,0.000000000000000000e+00,-1.257177806878339648e-09,0.000000000000000000e+00 +2.795638607789743091e+01,1.503499999999999943e+02,0.000000000000000000e+00,8.272685237878919295e+00,0.000000000000000000e+00,1.000000009951225177e+00,0.000000000000000000e+00,1.593882577234925873e-09,0.000000000000000000e+00 +2.795759487524828657e+01,1.503600000000000136e+02,0.000000000000000000e+00,8.273894035241802669e+00,0.000000000000000000e+00,1.000000009953151858e+00,0.000000000000000000e+00,-6.128810903575455660e-10,0.000000000000000000e+00 +2.795880349599655901e+01,1.503700000000000045e+02,0.000000000000000000e+00,8.275102656002104595e+00,0.000000000000000000e+00,1.000000009952411117e+00,0.000000000000000000e+00,-6.236277808484823557e-10,0.000000000000000000e+00 +2.796001194021963343e+01,1.503799999999999955e+02,0.000000000000000000e+00,8.276311100237206730e+00,0.000000000000000000e+00,1.000000009951657498e+00,0.000000000000000000e+00,3.078164632718776819e-10,0.000000000000000000e+00 +2.796122020799483820e+01,1.503900000000000148e+02,0.000000000000000000e+00,8.277519368024437441e+00,0.000000000000000000e+00,1.000000009952029423e+00,0.000000000000000000e+00,9.259735772839032230e-10,0.000000000000000000e+00 +2.796242829939944841e+01,1.504000000000000057e+02,0.000000000000000000e+00,8.278727459441070025e+00,0.000000000000000000e+00,1.000000009953148083e+00,0.000000000000000000e+00,-1.244493061945207538e-09,0.000000000000000000e+00 +2.796363621451067516e+01,1.504099999999999966e+02,0.000000000000000000e+00,8.279935374564320938e+00,0.000000000000000000e+00,1.000000009951644842e+00,0.000000000000000000e+00,1.061558548903427296e-09,0.000000000000000000e+00 +2.796484395340567985e+01,1.504200000000000159e+02,0.000000000000000000e+00,8.281143113471346240e+00,0.000000000000000000e+00,1.000000009952926927e+00,0.000000000000000000e+00,-7.184125770794425151e-10,0.000000000000000000e+00 +2.796605151616156704e+01,1.504300000000000068e+02,0.000000000000000000e+00,8.282350676239252252e+00,0.000000000000000000e+00,1.000000009952059399e+00,0.000000000000000000e+00,-5.344283030595256673e-10,0.000000000000000000e+00 +2.796725890285538085e+01,1.504399999999999977e+02,0.000000000000000000e+00,8.283558062945083122e+00,0.000000000000000000e+00,1.000000009951414137e+00,0.000000000000000000e+00,3.564600953517864592e-10,0.000000000000000000e+00 +2.796846611356411572e+01,1.504500000000000171e+02,0.000000000000000000e+00,8.284765273665829710e+00,0.000000000000000000e+00,1.000000009951844460e+00,0.000000000000000000e+00,6.972036367612564234e-10,0.000000000000000000e+00 +2.796967314836470209e+01,1.504600000000000080e+02,0.000000000000000000e+00,8.285972308478427806e+00,0.000000000000000000e+00,1.000000009952686009e+00,0.000000000000000000e+00,-7.723713169259225077e-10,0.000000000000000000e+00 +2.797088000733402069e+01,1.504699999999999989e+02,0.000000000000000000e+00,8.287179167459756357e+00,0.000000000000000000e+00,1.000000009951753865e+00,0.000000000000000000e+00,7.872048008648677996e-10,0.000000000000000000e+00 +2.797208669054889185e+01,1.504799999999999898e+02,0.000000000000000000e+00,8.288385850686635692e+00,0.000000000000000000e+00,1.000000009952703772e+00,0.000000000000000000e+00,-7.622901020086568386e-10,0.000000000000000000e+00 +2.797329319808608261e+01,1.504900000000000091e+02,0.000000000000000000e+00,8.289592358235834624e+00,0.000000000000000000e+00,1.000000009951784063e+00,0.000000000000000000e+00,6.409175543925987551e-10,0.000000000000000000e+00 +2.797449953002230316e+01,1.505000000000000000e+02,0.000000000000000000e+00,8.290798690184061570e+00,0.000000000000000000e+00,1.000000009952557223e+00,0.000000000000000000e+00,-1.145056668437779692e-09,0.000000000000000000e+00 +2.797570568643421041e+01,1.505099999999999909e+02,0.000000000000000000e+00,8.292004846607973434e+00,0.000000000000000000e+00,1.000000009951176105e+00,0.000000000000000000e+00,1.166581114111678148e-09,0.000000000000000000e+00 +2.797691166739840440e+01,1.505200000000000102e+02,0.000000000000000000e+00,8.293210827584166722e+00,0.000000000000000000e+00,1.000000009952582980e+00,0.000000000000000000e+00,-1.012252058157473765e-09,0.000000000000000000e+00 +2.797811747299142482e+01,1.505300000000000011e+02,0.000000000000000000e+00,8.294416633189188204e+00,0.000000000000000000e+00,1.000000009951362401e+00,0.000000000000000000e+00,8.308046124908858007e-10,0.000000000000000000e+00 +2.797932310328976158e+01,1.505399999999999920e+02,0.000000000000000000e+00,8.295622263499522475e+00,0.000000000000000000e+00,1.000000009952364044e+00,0.000000000000000000e+00,-6.749081287940550832e-10,0.000000000000000000e+00 +2.798052855836984776e+01,1.505500000000000114e+02,0.000000000000000000e+00,8.296827718591604395e+00,0.000000000000000000e+00,1.000000009951550473e+00,0.000000000000000000e+00,5.436526472904783929e-10,0.000000000000000000e+00 +2.798173383830805605e+01,1.505600000000000023e+02,0.000000000000000000e+00,8.298032998541808425e+00,0.000000000000000000e+00,1.000000009952205726e+00,0.000000000000000000e+00,-4.434978035370325613e-10,0.000000000000000000e+00 +2.798293894318071295e+01,1.505699999999999932e+02,0.000000000000000000e+00,8.299238103426457513e+00,0.000000000000000000e+00,1.000000009951671265e+00,0.000000000000000000e+00,1.217538650995799829e-09,0.000000000000000000e+00 +2.798414387306408102e+01,1.505800000000000125e+02,0.000000000000000000e+00,8.300443033321815989e+00,0.000000000000000000e+00,1.000000009953138314e+00,0.000000000000000000e+00,-1.853021164444469013e-09,0.000000000000000000e+00 +2.798534862803436951e+01,1.505900000000000034e+02,0.000000000000000000e+00,8.301647788304096665e+00,0.000000000000000000e+00,1.000000009950905877e+00,0.000000000000000000e+00,1.319459982799935882e-09,0.000000000000000000e+00 +2.798655320816773795e+01,1.505999999999999943e+02,0.000000000000000000e+00,8.302852368449450182e+00,0.000000000000000000e+00,1.000000009952495272e+00,0.000000000000000000e+00,-3.183903372130858674e-10,0.000000000000000000e+00 +2.798775761354028191e+01,1.506100000000000136e+02,0.000000000000000000e+00,8.304056773833980998e+00,0.000000000000000000e+00,1.000000009952111801e+00,0.000000000000000000e+00,-6.853668527893242777e-10,0.000000000000000000e+00 +2.798896184422804723e+01,1.506200000000000045e+02,0.000000000000000000e+00,8.305261004533731395e+00,0.000000000000000000e+00,1.000000009951286462e+00,0.000000000000000000e+00,1.809099768978492738e-10,0.000000000000000000e+00 +2.799016590030702289e+01,1.506299999999999955e+02,0.000000000000000000e+00,8.306465060624690366e+00,0.000000000000000000e+00,1.000000009951504287e+00,0.000000000000000000e+00,1.017743094345369963e-09,0.000000000000000000e+00 +2.799136978185314462e+01,1.506400000000000148e+02,0.000000000000000000e+00,8.307668942182793614e+00,0.000000000000000000e+00,1.000000009952729529e+00,0.000000000000000000e+00,-1.891896698658673526e-09,0.000000000000000000e+00 +2.799257348894229125e+01,1.506500000000000057e+02,0.000000000000000000e+00,8.308872649283921774e+00,0.000000000000000000e+00,1.000000009950452240e+00,0.000000000000000000e+00,1.221535002280590261e-09,0.000000000000000000e+00 +2.799377702165028836e+01,1.506599999999999966e+02,0.000000000000000000e+00,8.310076182003895084e+00,0.000000000000000000e+00,1.000000009951922397e+00,0.000000000000000000e+00,5.113070211744739712e-10,0.000000000000000000e+00 +2.799498038005290468e+01,1.506700000000000159e+02,0.000000000000000000e+00,8.311279540418487599e+00,0.000000000000000000e+00,1.000000009952537683e+00,0.000000000000000000e+00,-3.838587546505335539e-10,0.000000000000000000e+00 +2.799618356422585563e+01,1.506800000000000068e+02,0.000000000000000000e+00,8.312482724603412976e+00,0.000000000000000000e+00,1.000000009952075830e+00,0.000000000000000000e+00,-2.744618268543169532e-10,0.000000000000000000e+00 +2.799738657424479982e+01,1.506899999999999977e+02,0.000000000000000000e+00,8.313685734634329805e+00,0.000000000000000000e+00,1.000000009951745650e+00,0.000000000000000000e+00,-4.260588920676163607e-10,0.000000000000000000e+00 +2.799858941018534253e+01,1.507000000000000171e+02,0.000000000000000000e+00,8.314888570586843386e+00,0.000000000000000000e+00,1.000000009951233171e+00,0.000000000000000000e+00,3.511617232833369653e-10,0.000000000000000000e+00 +2.799979207212303578e+01,1.507100000000000080e+02,0.000000000000000000e+00,8.316091232536503952e+00,0.000000000000000000e+00,1.000000009951655500e+00,0.000000000000000000e+00,-4.368921192861334239e-10,0.000000000000000000e+00 +2.800099456013337473e+01,1.507199999999999989e+02,0.000000000000000000e+00,8.317293720558808445e+00,0.000000000000000000e+00,1.000000009951130142e+00,0.000000000000000000e+00,8.559965268781795173e-10,0.000000000000000000e+00 +2.800219687429179771e+01,1.507299999999999898e+02,0.000000000000000000e+00,8.318496034729196964e+00,0.000000000000000000e+00,1.000000009952159319e+00,0.000000000000000000e+00,-7.225765871834570551e-10,0.000000000000000000e+00 +2.800339901467369330e+01,1.507400000000000091e+02,0.000000000000000000e+00,8.319698175123058093e+00,0.000000000000000000e+00,1.000000009951290680e+00,0.000000000000000000e+00,-2.955750551025125164e-10,0.000000000000000000e+00 +2.800460098135439679e+01,1.507500000000000000e+02,0.000000000000000000e+00,8.320900141815721796e+00,0.000000000000000000e+00,1.000000009950935409e+00,0.000000000000000000e+00,8.709638181452053819e-10,0.000000000000000000e+00 +2.800580277440918309e+01,1.507599999999999909e+02,0.000000000000000000e+00,8.322101934882466523e+00,0.000000000000000000e+00,1.000000009951982127e+00,0.000000000000000000e+00,2.795839166286822273e-10,0.000000000000000000e+00 +2.800700439391327379e+01,1.507700000000000102e+02,0.000000000000000000e+00,8.323303554398517434e+00,0.000000000000000000e+00,1.000000009952318081e+00,0.000000000000000000e+00,-8.797168531179832520e-10,0.000000000000000000e+00 +2.800820583994184076e+01,1.507800000000000011e+02,0.000000000000000000e+00,8.324505000439042846e+00,0.000000000000000000e+00,1.000000009951261148e+00,0.000000000000000000e+00,-1.826230486930707636e-10,0.000000000000000000e+00 +2.800940711256999904e+01,1.507899999999999920e+02,0.000000000000000000e+00,8.325706273079156006e+00,0.000000000000000000e+00,1.000000009951041768e+00,0.000000000000000000e+00,1.103106258148207943e-09,0.000000000000000000e+00 +2.801060821187281036e+01,1.508000000000000114e+02,0.000000000000000000e+00,8.326907372393918649e+00,0.000000000000000000e+00,1.000000009952366709e+00,0.000000000000000000e+00,-7.551090799053199015e-10,0.000000000000000000e+00 +2.801180913792527960e+01,1.508100000000000023e+02,0.000000000000000000e+00,8.328108298458339220e+00,0.000000000000000000e+00,1.000000009951459878e+00,0.000000000000000000e+00,-8.700540187033587472e-10,0.000000000000000000e+00 +2.801300989080235837e+01,1.508199999999999932e+02,0.000000000000000000e+00,8.329309051347367543e+00,0.000000000000000000e+00,1.000000009950415158e+00,0.000000000000000000e+00,7.227760561760002613e-10,0.000000000000000000e+00 +2.801421047057894498e+01,1.508300000000000125e+02,0.000000000000000000e+00,8.330509631135901927e+00,0.000000000000000000e+00,1.000000009951282909e+00,0.000000000000000000e+00,2.883752018276923844e-10,0.000000000000000000e+00 +2.801541087732988800e+01,1.508400000000000034e+02,0.000000000000000000e+00,8.331710037898789167e+00,0.000000000000000000e+00,1.000000009951629076e+00,0.000000000000000000e+00,2.534515431289761272e-10,0.000000000000000000e+00 +2.801661111112997204e+01,1.508499999999999943e+02,0.000000000000000000e+00,8.332910271710819217e+00,0.000000000000000000e+00,1.000000009951933277e+00,0.000000000000000000e+00,-6.527779969588591841e-10,0.000000000000000000e+00 +2.801781117205393912e+01,1.508600000000000136e+02,0.000000000000000000e+00,8.334110332646728736e+00,0.000000000000000000e+00,1.000000009951149904e+00,0.000000000000000000e+00,-1.295380965349914919e-12,0.000000000000000000e+00 +2.801901106017647081e+01,1.508700000000000045e+02,0.000000000000000000e+00,8.335310220781199320e+00,0.000000000000000000e+00,1.000000009951148350e+00,0.000000000000000000e+00,9.378057639053047781e-10,0.000000000000000000e+00 +2.802021077557219542e+01,1.508799999999999955e+02,0.000000000000000000e+00,8.336509936188861047e+00,0.000000000000000000e+00,1.000000009952273450e+00,0.000000000000000000e+00,-1.576562327943354395e-09,0.000000000000000000e+00 +2.802141031831568796e+01,1.508900000000000148e+02,0.000000000000000000e+00,8.337709478944290709e+00,0.000000000000000000e+00,1.000000009950382296e+00,0.000000000000000000e+00,1.059153563277354878e-09,0.000000000000000000e+00 +2.802260968848147016e+01,1.509000000000000057e+02,0.000000000000000000e+00,8.338908849122006472e+00,0.000000000000000000e+00,1.000000009951652613e+00,0.000000000000000000e+00,1.655339090492774210e-10,0.000000000000000000e+00 +2.802380888614401044e+01,1.509099999999999966e+02,0.000000000000000000e+00,8.340108046796480323e+00,0.000000000000000000e+00,1.000000009951851121e+00,0.000000000000000000e+00,-5.916743808124181841e-10,0.000000000000000000e+00 +2.802500791137772396e+01,1.509200000000000159e+02,0.000000000000000000e+00,8.341307072042125625e+00,0.000000000000000000e+00,1.000000009951141688e+00,0.000000000000000000e+00,-1.370585252693773001e-11,0.000000000000000000e+00 +2.802620676425697255e+01,1.509300000000000068e+02,0.000000000000000000e+00,8.342505924933302452e+00,0.000000000000000000e+00,1.000000009951125257e+00,0.000000000000000000e+00,-6.088866516597182749e-10,0.000000000000000000e+00 +2.802740544485606122e+01,1.509399999999999977e+02,0.000000000000000000e+00,8.343704605544319364e+00,0.000000000000000000e+00,1.000000009950395397e+00,0.000000000000000000e+00,1.293722668116803041e-09,0.000000000000000000e+00 +2.802860395324924525e+01,1.509500000000000171e+02,0.000000000000000000e+00,8.344903113949429851e+00,0.000000000000000000e+00,1.000000009951945934e+00,0.000000000000000000e+00,-5.254939867951465181e-10,0.000000000000000000e+00 +2.802980228951072661e+01,1.509600000000000080e+02,0.000000000000000000e+00,8.346101450222837670e+00,0.000000000000000000e+00,1.000000009951316216e+00,0.000000000000000000e+00,7.894660964502374160e-11,0.000000000000000000e+00 +2.803100045371465399e+01,1.509699999999999989e+02,0.000000000000000000e+00,8.347299614438687954e+00,0.000000000000000000e+00,1.000000009951410807e+00,0.000000000000000000e+00,-6.405602152592694594e-10,0.000000000000000000e+00 +2.803219844593511922e+01,1.509799999999999898e+02,0.000000000000000000e+00,8.348497606671076099e+00,0.000000000000000000e+00,1.000000009950643420e+00,0.000000000000000000e+00,-2.463618935359037879e-10,0.000000000000000000e+00 +2.803339626624616798e+01,1.509900000000000091e+02,0.000000000000000000e+00,8.349695426994042435e+00,0.000000000000000000e+00,1.000000009950348323e+00,0.000000000000000000e+00,1.225126386596478655e-09,0.000000000000000000e+00 +2.803459391472178552e+01,1.510000000000000000e+02,0.000000000000000000e+00,8.350893075481575778e+00,0.000000000000000000e+00,1.000000009951815594e+00,0.000000000000000000e+00,2.169496781848288867e-11,0.000000000000000000e+00 +2.803579139143590737e+01,1.510099999999999909e+02,0.000000000000000000e+00,8.352090552207613428e+00,0.000000000000000000e+00,1.000000009951841573e+00,0.000000000000000000e+00,-1.418349627597322362e-09,0.000000000000000000e+00 +2.803698869646241576e+01,1.510200000000000102e+02,0.000000000000000000e+00,8.353287857246035841e+00,0.000000000000000000e+00,1.000000009950143376e+00,0.000000000000000000e+00,5.863030709097819983e-10,0.000000000000000000e+00 +2.803818582987513963e+01,1.510300000000000011e+02,0.000000000000000000e+00,8.354484990670670186e+00,0.000000000000000000e+00,1.000000009950845259e+00,0.000000000000000000e+00,1.043290422664974135e-09,0.000000000000000000e+00 +2.803938279174785464e+01,1.510399999999999920e+02,0.000000000000000000e+00,8.355681952555295666e+00,0.000000000000000000e+00,1.000000009952094038e+00,0.000000000000000000e+00,-1.327491547143580748e-09,0.000000000000000000e+00 +2.804057958215428314e+01,1.510500000000000114e+02,0.000000000000000000e+00,8.356878742973636420e+00,0.000000000000000000e+00,1.000000009950505309e+00,0.000000000000000000e+00,8.789976436821803280e-10,0.000000000000000000e+00 +2.804177620116809777e+01,1.510600000000000023e+02,0.000000000000000000e+00,8.358075361999359743e+00,0.000000000000000000e+00,1.000000009951557134e+00,0.000000000000000000e+00,-1.057286599100101451e-09,0.000000000000000000e+00 +2.804297264886291785e+01,1.510699999999999932e+02,0.000000000000000000e+00,8.359271809706086742e+00,0.000000000000000000e+00,1.000000009950292146e+00,0.000000000000000000e+00,2.709951561412824130e-10,0.000000000000000000e+00 +2.804416892531230943e+01,1.510800000000000125e+02,0.000000000000000000e+00,8.360468086167379909e+00,0.000000000000000000e+00,1.000000009950616331e+00,0.000000000000000000e+00,1.105669953842822997e-09,0.000000000000000000e+00 +2.804536503058978170e+01,1.510900000000000034e+02,0.000000000000000000e+00,8.361664191456753770e+00,0.000000000000000000e+00,1.000000009951938829e+00,0.000000000000000000e+00,-1.075378874768995458e-09,0.000000000000000000e+00 +2.804656096476879412e+01,1.510999999999999943e+02,0.000000000000000000e+00,8.362860125647669562e+00,0.000000000000000000e+00,1.000000009950652746e+00,0.000000000000000000e+00,-9.953133933365055900e-11,0.000000000000000000e+00 +2.804775672792275643e+01,1.511100000000000136e+02,0.000000000000000000e+00,8.364055888813531681e+00,0.000000000000000000e+00,1.000000009950533730e+00,0.000000000000000000e+00,2.709645295202221439e-10,0.000000000000000000e+00 +2.804895232012502504e+01,1.511200000000000045e+02,0.000000000000000000e+00,8.365251481027696556e+00,0.000000000000000000e+00,1.000000009950857693e+00,0.000000000000000000e+00,-5.572376880609983287e-13,0.000000000000000000e+00 +2.805014774144889955e+01,1.511299999999999955e+02,0.000000000000000000e+00,8.366446902363467331e+00,0.000000000000000000e+00,1.000000009950857027e+00,0.000000000000000000e+00,2.916627303386630617e-10,0.000000000000000000e+00 +2.805134299196763337e+01,1.511400000000000148e+02,0.000000000000000000e+00,8.367642152894093854e+00,0.000000000000000000e+00,1.000000009951205637e+00,0.000000000000000000e+00,-1.324746724543299512e-10,0.000000000000000000e+00 +2.805253807175442304e+01,1.511500000000000057e+02,0.000000000000000000e+00,8.368837232692774464e+00,0.000000000000000000e+00,1.000000009951047319e+00,0.000000000000000000e+00,-6.578223255833665171e-11,0.000000000000000000e+00 +2.805373298088241185e+01,1.511599999999999966e+02,0.000000000000000000e+00,8.370032141832654204e+00,0.000000000000000000e+00,1.000000009950968716e+00,0.000000000000000000e+00,-7.885702397246940586e-10,0.000000000000000000e+00 +2.805492771942469687e+01,1.511700000000000159e+02,0.000000000000000000e+00,8.371226880386826608e+00,0.000000000000000000e+00,1.000000009950026580e+00,0.000000000000000000e+00,1.507475255733962327e-10,0.000000000000000000e+00 +2.805612228745431480e+01,1.511800000000000068e+02,0.000000000000000000e+00,8.372421448428331914e+00,0.000000000000000000e+00,1.000000009950206659e+00,0.000000000000000000e+00,1.473483832731113875e-09,0.000000000000000000e+00 +2.805731668504425969e+01,1.511899999999999977e+02,0.000000000000000000e+00,8.373615846030160625e+00,0.000000000000000000e+00,1.000000009951966584e+00,0.000000000000000000e+00,-1.840351196858026334e-09,0.000000000000000000e+00 +2.805851091226746519e+01,1.512000000000000171e+02,0.000000000000000000e+00,8.374810073265251731e+00,0.000000000000000000e+00,1.000000009949768787e+00,0.000000000000000000e+00,1.382784724608408265e-09,0.000000000000000000e+00 +2.805970496919681878e+01,1.512100000000000080e+02,0.000000000000000000e+00,8.376004130206485598e+00,0.000000000000000000e+00,1.000000009951419910e+00,0.000000000000000000e+00,-1.350248579285986016e-09,0.000000000000000000e+00 +2.806089885590515109e+01,1.512199999999999989e+02,0.000000000000000000e+00,8.377198016926699964e+00,0.000000000000000000e+00,1.000000009949807867e+00,0.000000000000000000e+00,1.138016291592104491e-09,0.000000000000000000e+00 +2.806209257246524658e+01,1.512299999999999898e+02,0.000000000000000000e+00,8.378391733498672167e+00,0.000000000000000000e+00,1.000000009951166335e+00,0.000000000000000000e+00,8.762374173971464905e-11,0.000000000000000000e+00 +2.806328611894983283e+01,1.512400000000000091e+02,0.000000000000000000e+00,8.379585279995135139e+00,0.000000000000000000e+00,1.000000009951270918e+00,0.000000000000000000e+00,-7.991456114093487380e-10,0.000000000000000000e+00 +2.806447949543158771e+01,1.512500000000000000e+02,0.000000000000000000e+00,8.380778656488764966e+00,0.000000000000000000e+00,1.000000009950317237e+00,0.000000000000000000e+00,-3.107714165192784945e-10,0.000000000000000000e+00 +2.806567270198313579e+01,1.512599999999999909e+02,0.000000000000000000e+00,8.381971863052186222e+00,0.000000000000000000e+00,1.000000009949946422e+00,0.000000000000000000e+00,1.517971582100177959e-09,0.000000000000000000e+00 +2.806686573867705192e+01,1.512700000000000102e+02,0.000000000000000000e+00,8.383164899757973743e+00,0.000000000000000000e+00,1.000000009951757418e+00,0.000000000000000000e+00,-1.589666803612679029e-09,0.000000000000000000e+00 +2.806805860558586119e+01,1.512800000000000011e+02,0.000000000000000000e+00,8.384357766678652624e+00,0.000000000000000000e+00,1.000000009949861157e+00,0.000000000000000000e+00,3.153722184901761091e-10,0.000000000000000000e+00 +2.806925130278203184e+01,1.512899999999999920e+02,0.000000000000000000e+00,8.385550463886689343e+00,0.000000000000000000e+00,1.000000009950237301e+00,0.000000000000000000e+00,9.561196641540569247e-10,0.000000000000000000e+00 +2.807044383033798240e+01,1.513000000000000114e+02,0.000000000000000000e+00,8.386742991454505969e+00,0.000000000000000000e+00,1.000000009951377500e+00,0.000000000000000000e+00,-9.538347356892179532e-10,0.000000000000000000e+00 +2.807163618832608165e+01,1.513100000000000023e+02,0.000000000000000000e+00,8.387935349454471279e+00,0.000000000000000000e+00,1.000000009950240187e+00,0.000000000000000000e+00,-4.538902242195007468e-10,0.000000000000000000e+00 +2.807282837681864507e+01,1.513199999999999932e+02,0.000000000000000000e+00,8.389127537958898984e+00,0.000000000000000000e+00,1.000000009949699065e+00,0.000000000000000000e+00,1.172421464888125044e-09,0.000000000000000000e+00 +2.807402039588794196e+01,1.513300000000000125e+02,0.000000000000000000e+00,8.390319557040054832e+00,0.000000000000000000e+00,1.000000009951096613e+00,0.000000000000000000e+00,-1.112412341688044195e-09,0.000000000000000000e+00 +2.807521224560618123e+01,1.513400000000000034e+02,0.000000000000000000e+00,8.391511406770154835e+00,0.000000000000000000e+00,1.000000009949770785e+00,0.000000000000000000e+00,1.408833444273874519e-09,0.000000000000000000e+00 +2.807640392604552915e+01,1.513499999999999943e+02,0.000000000000000000e+00,8.392703087221358160e+00,0.000000000000000000e+00,1.000000009951449664e+00,0.000000000000000000e+00,-1.305792596987488546e-09,0.000000000000000000e+00 +2.807759543727809159e+01,1.513600000000000136e+02,0.000000000000000000e+00,8.393894598465779566e+00,0.000000000000000000e+00,1.000000009949893798e+00,0.000000000000000000e+00,7.162656455040659632e-10,0.000000000000000000e+00 +2.807878677937593181e+01,1.513700000000000045e+02,0.000000000000000000e+00,8.395085940575475192e+00,0.000000000000000000e+00,1.000000009950747115e+00,0.000000000000000000e+00,-6.803904924601697403e-11,0.000000000000000000e+00 +2.807997795241105976e+01,1.513799999999999955e+02,0.000000000000000000e+00,8.396277113622456767e+00,0.000000000000000000e+00,1.000000009950666069e+00,0.000000000000000000e+00,-1.193369176906097236e-09,0.000000000000000000e+00 +2.808116895645543210e+01,1.513900000000000148e+02,0.000000000000000000e+00,8.397468117678680954e+00,0.000000000000000000e+00,1.000000009949244761e+00,0.000000000000000000e+00,1.063761425864770486e-09,0.000000000000000000e+00 +2.808235979158095574e+01,1.514000000000000057e+02,0.000000000000000000e+00,8.398658952816052903e+00,0.000000000000000000e+00,1.000000009950511526e+00,0.000000000000000000e+00,4.044918015790437120e-10,0.000000000000000000e+00 +2.808355045785948789e+01,1.514099999999999966e+02,0.000000000000000000e+00,8.399849619106431575e+00,0.000000000000000000e+00,1.000000009950993141e+00,0.000000000000000000e+00,-7.020391815952065974e-10,0.000000000000000000e+00 +2.808474095536282888e+01,1.514200000000000159e+02,0.000000000000000000e+00,8.401040116621620868e+00,0.000000000000000000e+00,1.000000009950157365e+00,0.000000000000000000e+00,2.148947289970084013e-10,0.000000000000000000e+00 +2.808593128416273643e+01,1.514300000000000068e+02,0.000000000000000000e+00,8.402230445433373163e+00,0.000000000000000000e+00,1.000000009950413160e+00,0.000000000000000000e+00,-6.404844903145694346e-10,0.000000000000000000e+00 +2.808712144433091495e+01,1.514399999999999977e+02,0.000000000000000000e+00,8.403420605613392880e+00,0.000000000000000000e+00,1.000000009949650881e+00,0.000000000000000000e+00,4.584600350019864098e-10,0.000000000000000000e+00 +2.808831143593901203e+01,1.514500000000000171e+02,0.000000000000000000e+00,8.404610597233331148e+00,0.000000000000000000e+00,1.000000009950196445e+00,0.000000000000000000e+00,9.681837504703977792e-10,0.000000000000000000e+00 +2.808950125905863260e+01,1.514600000000000080e+02,0.000000000000000000e+00,8.405800420364791137e+00,0.000000000000000000e+00,1.000000009951348412e+00,0.000000000000000000e+00,-1.657978757265708736e-09,0.000000000000000000e+00 +2.809069091376132832e+01,1.514699999999999989e+02,0.000000000000000000e+00,8.406990075079324498e+00,0.000000000000000000e+00,1.000000009949375990e+00,0.000000000000000000e+00,1.330602855790572841e-09,0.000000000000000000e+00 +2.809188040011859755e+01,1.514799999999999898e+02,0.000000000000000000e+00,8.408179561448427819e+00,0.000000000000000000e+00,1.000000009950958724e+00,0.000000000000000000e+00,-1.399309686190973966e-09,0.000000000000000000e+00 +2.809306971820188892e+01,1.514900000000000091e+02,0.000000000000000000e+00,8.409368879543555053e+00,0.000000000000000000e+00,1.000000009949294499e+00,0.000000000000000000e+00,1.417806714307228208e-09,0.000000000000000000e+00 +2.809425886808260486e+01,1.515000000000000000e+02,0.000000000000000000e+00,8.410558029436101535e+00,0.000000000000000000e+00,1.000000009950980484e+00,0.000000000000000000e+00,-1.557697626964372156e-09,0.000000000000000000e+00 +2.809544784983209098e+01,1.515099999999999909e+02,0.000000000000000000e+00,8.411747011197419965e+00,0.000000000000000000e+00,1.000000009949128410e+00,0.000000000000000000e+00,9.462188889914042899e-10,0.000000000000000000e+00 +2.809663666352164668e+01,1.515200000000000102e+02,0.000000000000000000e+00,8.412935824898804427e+00,0.000000000000000000e+00,1.000000009950253288e+00,0.000000000000000000e+00,9.825927280486304532e-11,0.000000000000000000e+00 +2.809782530922252164e+01,1.515300000000000011e+02,0.000000000000000000e+00,8.414124470611506368e+00,0.000000000000000000e+00,1.000000009950370083e+00,0.000000000000000000e+00,-3.673099315642463542e-10,0.000000000000000000e+00 +2.809901378700591223e+01,1.515399999999999920e+02,0.000000000000000000e+00,8.415312948406722171e+00,0.000000000000000000e+00,1.000000009949933544e+00,0.000000000000000000e+00,7.732162683572911376e-10,0.000000000000000000e+00 +2.810020209694296511e+01,1.515500000000000114e+02,0.000000000000000000e+00,8.416501258355598480e+00,0.000000000000000000e+00,1.000000009950852364e+00,0.000000000000000000e+00,-1.547585324789107188e-09,0.000000000000000000e+00 +2.810139023910477718e+01,1.515600000000000023e+02,0.000000000000000000e+00,8.417689400529233978e+00,0.000000000000000000e+00,1.000000009949013613e+00,0.000000000000000000e+00,1.442760233120957911e-09,0.000000000000000000e+00 +2.810257821356239560e+01,1.515699999999999932e+02,0.000000000000000000e+00,8.418877374998672281e+00,0.000000000000000000e+00,1.000000009950727575e+00,0.000000000000000000e+00,-3.577967099432356825e-10,0.000000000000000000e+00 +2.810376602038681781e+01,1.515800000000000125e+02,0.000000000000000000e+00,8.420065181834914370e+00,0.000000000000000000e+00,1.000000009950302582e+00,0.000000000000000000e+00,-6.925109693138093235e-10,0.000000000000000000e+00 +2.810495365964899150e+01,1.515900000000000034e+02,0.000000000000000000e+00,8.421252821108904385e+00,0.000000000000000000e+00,1.000000009949480129e+00,0.000000000000000000e+00,4.053929662220868808e-10,0.000000000000000000e+00 +2.810614113141981107e+01,1.515999999999999943e+02,0.000000000000000000e+00,8.422440292891538505e+00,0.000000000000000000e+00,1.000000009949961521e+00,0.000000000000000000e+00,3.824471938909822778e-10,0.000000000000000000e+00 +2.810732843577012474e+01,1.516100000000000136e+02,0.000000000000000000e+00,8.423627597253664945e+00,0.000000000000000000e+00,1.000000009950415603e+00,0.000000000000000000e+00,-7.982957092051689129e-10,0.000000000000000000e+00 +2.810851557277072743e+01,1.516200000000000045e+02,0.000000000000000000e+00,8.424814734266080407e+00,0.000000000000000000e+00,1.000000009949467916e+00,0.000000000000000000e+00,6.104044043089333629e-10,0.000000000000000000e+00 +2.810970254249236788e+01,1.516299999999999955e+02,0.000000000000000000e+00,8.426001703999530079e+00,0.000000000000000000e+00,1.000000009950192448e+00,0.000000000000000000e+00,-4.686725289752851372e-10,0.000000000000000000e+00 +2.811088934500574155e+01,1.516400000000000148e+02,0.000000000000000000e+00,8.427188506524712963e+00,0.000000000000000000e+00,1.000000009949636226e+00,0.000000000000000000e+00,-2.887279718770148770e-10,0.000000000000000000e+00 +2.811207598038149769e+01,1.516500000000000057e+02,0.000000000000000000e+00,8.428375141912274771e+00,0.000000000000000000e+00,1.000000009949293611e+00,0.000000000000000000e+00,1.117270711441881964e-09,0.000000000000000000e+00 +2.811326244869023228e+01,1.516599999999999966e+02,0.000000000000000000e+00,8.429561610232813251e+00,0.000000000000000000e+00,1.000000009950619217e+00,0.000000000000000000e+00,-1.333613807672690872e-09,0.000000000000000000e+00 +2.811444875000249155e+01,1.516700000000000159e+02,0.000000000000000000e+00,8.430747911556878194e+00,0.000000000000000000e+00,1.000000009949037150e+00,0.000000000000000000e+00,1.158769293242147090e-09,0.000000000000000000e+00 +2.811563488438877556e+01,1.516800000000000068e+02,0.000000000000000000e+00,8.431934045954964319e+00,0.000000000000000000e+00,1.000000009950411606e+00,0.000000000000000000e+00,-1.539938344130122525e-09,0.000000000000000000e+00 +2.811682085191953462e+01,1.516899999999999977e+02,0.000000000000000000e+00,8.433120013497523715e+00,0.000000000000000000e+00,1.000000009948585289e+00,0.000000000000000000e+00,1.901365745228341542e-09,0.000000000000000000e+00 +2.811800665266516575e+01,1.517000000000000171e+02,0.000000000000000000e+00,8.434305814254951628e+00,0.000000000000000000e+00,1.000000009950839930e+00,0.000000000000000000e+00,-1.183604608680861357e-09,0.000000000000000000e+00 +2.811919228669601978e+01,1.517100000000000080e+02,0.000000000000000000e+00,8.435491448297602446e+00,0.000000000000000000e+00,1.000000009949436608e+00,0.000000000000000000e+00,5.411256952332748843e-10,0.000000000000000000e+00 +2.812037775408239426e+01,1.517199999999999989e+02,0.000000000000000000e+00,8.436676915695771939e+00,0.000000000000000000e+00,1.000000009950078095e+00,0.000000000000000000e+00,-5.413890732688560899e-10,0.000000000000000000e+00 +2.812156305489454056e+01,1.517299999999999898e+02,0.000000000000000000e+00,8.437862216519713243e+00,0.000000000000000000e+00,1.000000009949436386e+00,0.000000000000000000e+00,5.914897686654704342e-10,0.000000000000000000e+00 +2.812274818920266384e+01,1.517400000000000091e+02,0.000000000000000000e+00,8.439047350839626205e+00,0.000000000000000000e+00,1.000000009950137381e+00,0.000000000000000000e+00,-1.153726326455374836e-09,0.000000000000000000e+00 +2.812393315707691244e+01,1.517500000000000000e+02,0.000000000000000000e+00,8.440232318725664484e+00,0.000000000000000000e+00,1.000000009948770252e+00,0.000000000000000000e+00,5.131307842780789965e-10,0.000000000000000000e+00 +2.812511795858738850e+01,1.517599999999999909e+02,0.000000000000000000e+00,8.441417120247928452e+00,0.000000000000000000e+00,1.000000009949378210e+00,0.000000000000000000e+00,4.982078462138826838e-10,0.000000000000000000e+00 +2.812630259380414799e+01,1.517700000000000102e+02,0.000000000000000000e+00,8.442601755476474068e+00,0.000000000000000000e+00,1.000000009949968405e+00,0.000000000000000000e+00,3.074400040988004970e-11,0.000000000000000000e+00 +2.812748706279719357e+01,1.517800000000000011e+02,0.000000000000000000e+00,8.443786224481305780e+00,0.000000000000000000e+00,1.000000009950004820e+00,0.000000000000000000e+00,-9.235743490386675331e-10,0.000000000000000000e+00 +2.812867136563648174e+01,1.517899999999999920e+02,0.000000000000000000e+00,8.444970527332378296e+00,0.000000000000000000e+00,1.000000009948911028e+00,0.000000000000000000e+00,1.342614663351056681e-10,0.000000000000000000e+00 +2.812985550239191923e+01,1.518000000000000114e+02,0.000000000000000000e+00,8.446154664099596587e+00,0.000000000000000000e+00,1.000000009949070012e+00,0.000000000000000000e+00,6.374563033711872509e-10,0.000000000000000000e+00 +2.813103947313336306e+01,1.518100000000000023e+02,0.000000000000000000e+00,8.447338634852819439e+00,0.000000000000000000e+00,1.000000009949824742e+00,0.000000000000000000e+00,5.510765379401223892e-10,0.000000000000000000e+00 +2.813222327793062050e+01,1.518199999999999932e+02,0.000000000000000000e+00,8.448522439661855898e+00,0.000000000000000000e+00,1.000000009950477109e+00,0.000000000000000000e+00,-1.427784652469430093e-09,0.000000000000000000e+00 +2.813340691685345263e+01,1.518300000000000125e+02,0.000000000000000000e+00,8.449706078596465275e+00,0.000000000000000000e+00,1.000000009948787127e+00,0.000000000000000000e+00,1.006399927962840947e-09,0.000000000000000000e+00 +2.813459038997156725e+01,1.518400000000000034e+02,0.000000000000000000e+00,8.450889551726355364e+00,0.000000000000000000e+00,1.000000009949978175e+00,0.000000000000000000e+00,-1.056642752534278356e-09,0.000000000000000000e+00 +2.813577369735462952e+01,1.518499999999999943e+02,0.000000000000000000e+00,8.452072859121191328e+00,0.000000000000000000e+00,1.000000009948727842e+00,0.000000000000000000e+00,1.227573788653828755e-09,0.000000000000000000e+00 +2.813695683907225131e+01,1.518600000000000136e+02,0.000000000000000000e+00,8.453256000850583263e+00,0.000000000000000000e+00,1.000000009950180235e+00,0.000000000000000000e+00,-1.056563237540063167e-09,0.000000000000000000e+00 +2.813813981519399476e+01,1.518700000000000045e+02,0.000000000000000000e+00,8.454438976984098630e+00,0.000000000000000000e+00,1.000000009948930346e+00,0.000000000000000000e+00,9.410717225848692572e-10,0.000000000000000000e+00 +2.813932262578937937e+01,1.518799999999999955e+02,0.000000000000000000e+00,8.455621787591249827e+00,0.000000000000000000e+00,1.000000009950043456e+00,0.000000000000000000e+00,-1.701225583014316757e-09,0.000000000000000000e+00 +2.814050527092786780e+01,1.518900000000000148e+02,0.000000000000000000e+00,8.456804432741506616e+00,0.000000000000000000e+00,1.000000009948031510e+00,0.000000000000000000e+00,1.143197212150732584e-09,0.000000000000000000e+00 +2.814168775067888006e+01,1.519000000000000057e+02,0.000000000000000000e+00,8.457986912504283694e+00,0.000000000000000000e+00,1.000000009949383317e+00,0.000000000000000000e+00,5.489541209435792989e-10,0.000000000000000000e+00 +2.814287006511178646e+01,1.519099999999999966e+02,0.000000000000000000e+00,8.459169226948954901e+00,0.000000000000000000e+00,1.000000009950032354e+00,0.000000000000000000e+00,-9.786010151647607136e-10,0.000000000000000000e+00 +2.814405221429591109e+01,1.519200000000000159e+02,0.000000000000000000e+00,8.460351376144840785e+00,0.000000000000000000e+00,1.000000009948875501e+00,0.000000000000000000e+00,3.403978586463563196e-10,0.000000000000000000e+00 +2.814523419830052475e+01,1.519300000000000068e+02,0.000000000000000000e+00,8.461533360161212158e+00,0.000000000000000000e+00,1.000000009949277846e+00,0.000000000000000000e+00,6.590963114715527910e-10,0.000000000000000000e+00 +2.814641601719484854e+01,1.519399999999999977e+02,0.000000000000000000e+00,8.462715179067295423e+00,0.000000000000000000e+00,1.000000009950056779e+00,0.000000000000000000e+00,-1.329839245884018134e-09,0.000000000000000000e+00 +2.814759767104806443e+01,1.519500000000000171e+02,0.000000000000000000e+00,8.463896832932267245e+00,0.000000000000000000e+00,1.000000009948485369e+00,0.000000000000000000e+00,7.010022603912115506e-10,0.000000000000000000e+00 +2.814877915992929758e+01,1.519600000000000080e+02,0.000000000000000000e+00,8.465078321825252772e+00,0.000000000000000000e+00,1.000000009949313595e+00,0.000000000000000000e+00,3.571287446095356778e-10,0.000000000000000000e+00 +2.814996048390762695e+01,1.519699999999999989e+02,0.000000000000000000e+00,8.466259645815334522e+00,0.000000000000000000e+00,1.000000009949735480e+00,0.000000000000000000e+00,-1.124924547303484345e-09,0.000000000000000000e+00 +2.815114164305208533e+01,1.519799999999999898e+02,0.000000000000000000e+00,8.467440804971543500e+00,0.000000000000000000e+00,1.000000009948406765e+00,0.000000000000000000e+00,1.315540638921716869e-09,0.000000000000000000e+00 +2.815232263743165220e+01,1.519900000000000091e+02,0.000000000000000000e+00,8.468621799362860969e+00,0.000000000000000000e+00,1.000000009949960411e+00,0.000000000000000000e+00,-1.270594240894037404e-09,0.000000000000000000e+00 +2.815350346711526797e+01,1.520000000000000000e+02,0.000000000000000000e+00,8.469802629058225563e+00,0.000000000000000000e+00,1.000000009948460056e+00,0.000000000000000000e+00,1.274532755271619966e-09,0.000000000000000000e+00 +2.815468413217181620e+01,1.520099999999999909e+02,0.000000000000000000e+00,8.470983294126520846e+00,0.000000000000000000e+00,1.000000009949964852e+00,0.000000000000000000e+00,-1.276779451065542260e-09,0.000000000000000000e+00 +2.815586463267013784e+01,1.520200000000000102e+02,0.000000000000000000e+00,8.472163794636589529e+00,0.000000000000000000e+00,1.000000009948457613e+00,0.000000000000000000e+00,-3.687148594774861887e-11,0.000000000000000000e+00 +2.815704496867902407e+01,1.520300000000000011e+02,0.000000000000000000e+00,8.473344130657219253e+00,0.000000000000000000e+00,1.000000009948414093e+00,0.000000000000000000e+00,1.138471657715785665e-09,0.000000000000000000e+00 +2.815822514026721990e+01,1.520399999999999920e+02,0.000000000000000000e+00,8.474524302257155028e+00,0.000000000000000000e+00,1.000000009949757684e+00,0.000000000000000000e+00,-3.368283097113857066e-10,0.000000000000000000e+00 +2.815940514750341706e+01,1.520500000000000114e+02,0.000000000000000000e+00,8.475704309505093903e+00,0.000000000000000000e+00,1.000000009949360225e+00,0.000000000000000000e+00,-6.696100548091248307e-10,0.000000000000000000e+00 +2.816058499045626462e+01,1.520600000000000023e+02,0.000000000000000000e+00,8.476884152469681410e+00,0.000000000000000000e+00,1.000000009948570190e+00,0.000000000000000000e+00,1.070998197406691553e-10,0.000000000000000000e+00 +2.816176466919436550e+01,1.520699999999999932e+02,0.000000000000000000e+00,8.478063831219516899e+00,0.000000000000000000e+00,1.000000009948696533e+00,0.000000000000000000e+00,6.848565318845834783e-10,0.000000000000000000e+00 +2.816294418378626574e+01,1.520800000000000125e+02,0.000000000000000000e+00,8.479243345823153533e+00,0.000000000000000000e+00,1.000000009949504332e+00,0.000000000000000000e+00,-2.475842864004250987e-10,0.000000000000000000e+00 +2.816412353430047588e+01,1.520900000000000034e+02,0.000000000000000000e+00,8.480422696349096512e+00,0.000000000000000000e+00,1.000000009949212343e+00,0.000000000000000000e+00,-1.698494960701709529e-10,0.000000000000000000e+00 +2.816530272080544961e+01,1.520999999999999943e+02,0.000000000000000000e+00,8.481601882865801301e+00,0.000000000000000000e+00,1.000000009949012059e+00,0.000000000000000000e+00,-3.921017981440088223e-10,0.000000000000000000e+00 +2.816648174336959443e+01,1.521100000000000136e+02,0.000000000000000000e+00,8.482780905441677177e+00,0.000000000000000000e+00,1.000000009948549762e+00,0.000000000000000000e+00,3.303756758864451227e-10,0.000000000000000000e+00 +2.816766060206127520e+01,1.521200000000000045e+02,0.000000000000000000e+00,8.483959764145085458e+00,0.000000000000000000e+00,1.000000009948939228e+00,0.000000000000000000e+00,-5.920838383734584413e-10,0.000000000000000000e+00 +2.816883929694880351e+01,1.521299999999999955e+02,0.000000000000000000e+00,8.485138459044341275e+00,0.000000000000000000e+00,1.000000009948241342e+00,0.000000000000000000e+00,6.426594208752744783e-10,0.000000000000000000e+00 +2.817001782810044830e+01,1.521400000000000148e+02,0.000000000000000000e+00,8.486316990207710020e+00,0.000000000000000000e+00,1.000000009948998736e+00,0.000000000000000000e+00,1.654451313149423184e-10,0.000000000000000000e+00 +2.817119619558442878e+01,1.521500000000000057e+02,0.000000000000000000e+00,8.487495357703412679e+00,0.000000000000000000e+00,1.000000009949193691e+00,0.000000000000000000e+00,-7.787177751079732185e-10,0.000000000000000000e+00 +2.817237439946891442e+01,1.521599999999999966e+02,0.000000000000000000e+00,8.488673561599620498e+00,0.000000000000000000e+00,1.000000009948276203e+00,0.000000000000000000e+00,3.366367402838781940e-10,0.000000000000000000e+00 +2.817355243982203206e+01,1.521700000000000159e+02,0.000000000000000000e+00,8.489851601964456762e+00,0.000000000000000000e+00,1.000000009948672774e+00,0.000000000000000000e+00,9.199413634772069286e-10,0.000000000000000000e+00 +2.817473031671185879e+01,1.521800000000000068e+02,0.000000000000000000e+00,8.491029478866000346e+00,0.000000000000000000e+00,1.000000009949756352e+00,0.000000000000000000e+00,-1.624826763110647129e-09,0.000000000000000000e+00 +2.817590803020642198e+01,1.521899999999999977e+02,0.000000000000000000e+00,8.492207192372282165e+00,0.000000000000000000e+00,1.000000009947842772e+00,0.000000000000000000e+00,1.635046066651658827e-09,0.000000000000000000e+00 +2.817708558037370636e+01,1.522000000000000171e+02,0.000000000000000000e+00,8.493384742551281619e+00,0.000000000000000000e+00,1.000000009949768121e+00,0.000000000000000000e+00,-8.611066245498377606e-10,0.000000000000000000e+00 +2.817826296728165048e+01,1.522100000000000080e+02,0.000000000000000000e+00,8.494562129470939027e+00,0.000000000000000000e+00,1.000000009948754265e+00,0.000000000000000000e+00,-1.799407794215230120e-10,0.000000000000000000e+00 +2.817944019099813957e+01,1.522199999999999989e+02,0.000000000000000000e+00,8.495739353199139643e+00,0.000000000000000000e+00,1.000000009948542434e+00,0.000000000000000000e+00,-1.969436144109138336e-10,0.000000000000000000e+00 +2.818061725159101627e+01,1.522299999999999898e+02,0.000000000000000000e+00,8.496916413803726087e+00,0.000000000000000000e+00,1.000000009948310620e+00,0.000000000000000000e+00,3.365862895560366960e-10,0.000000000000000000e+00 +2.818179414912807346e+01,1.522400000000000091e+02,0.000000000000000000e+00,8.498093311352493018e+00,0.000000000000000000e+00,1.000000009948706747e+00,0.000000000000000000e+00,1.052921320739906034e-10,0.000000000000000000e+00 +2.818297088367706138e+01,1.522500000000000000e+02,0.000000000000000000e+00,8.499270045913188909e+00,0.000000000000000000e+00,1.000000009948830648e+00,0.000000000000000000e+00,-9.241701940351651232e-10,0.000000000000000000e+00 +2.818414745530568055e+01,1.522599999999999909e+02,0.000000000000000000e+00,8.500446617553514272e+00,0.000000000000000000e+00,1.000000009947743296e+00,0.000000000000000000e+00,1.065292758661230140e-09,0.000000000000000000e+00 +2.818532386408158530e+01,1.522700000000000102e+02,0.000000000000000000e+00,8.501623026341121658e+00,0.000000000000000000e+00,1.000000009948996516e+00,0.000000000000000000e+00,-3.758489396475977253e-10,0.000000000000000000e+00 +2.818650011007238376e+01,1.522800000000000011e+02,0.000000000000000000e+00,8.502799272343620984e+00,0.000000000000000000e+00,1.000000009948554425e+00,0.000000000000000000e+00,-1.466976547928265587e-10,0.000000000000000000e+00 +2.818767619334563435e+01,1.522899999999999920e+02,0.000000000000000000e+00,8.503975355628570654e+00,0.000000000000000000e+00,1.000000009948381896e+00,0.000000000000000000e+00,4.373214440275445733e-10,0.000000000000000000e+00 +2.818885211396884927e+01,1.523000000000000114e+02,0.000000000000000000e+00,8.505151276263484661e+00,0.000000000000000000e+00,1.000000009948896151e+00,0.000000000000000000e+00,-1.226406806954629072e-09,0.000000000000000000e+00 +2.819002787200949811e+01,1.523100000000000023e+02,0.000000000000000000e+00,8.506327034315830815e+00,0.000000000000000000e+00,1.000000009947454194e+00,0.000000000000000000e+00,1.254530349868459999e-09,0.000000000000000000e+00 +2.819120346753500073e+01,1.523199999999999932e+02,0.000000000000000000e+00,8.507502629853027187e+00,0.000000000000000000e+00,1.000000009948929014e+00,0.000000000000000000e+00,1.369557668749675699e-10,0.000000000000000000e+00 +2.819237890061273077e+01,1.523300000000000125e+02,0.000000000000000000e+00,8.508678062942450993e+00,0.000000000000000000e+00,1.000000009949089996e+00,0.000000000000000000e+00,-7.572338684152711006e-10,0.000000000000000000e+00 +2.819355417131001573e+01,1.523400000000000034e+02,0.000000000000000000e+00,8.509853333651427931e+00,0.000000000000000000e+00,1.000000009948200042e+00,0.000000000000000000e+00,-1.736512092703903845e-10,0.000000000000000000e+00 +2.819472927969413334e+01,1.523499999999999943e+02,0.000000000000000000e+00,8.511028442047237519e+00,0.000000000000000000e+00,1.000000009947995983e+00,0.000000000000000000e+00,5.701610918874891766e-10,0.000000000000000000e+00 +2.819590422583232225e+01,1.523600000000000136e+02,0.000000000000000000e+00,8.512203388197114862e+00,0.000000000000000000e+00,1.000000009948665891e+00,0.000000000000000000e+00,1.540422403274599111e-10,0.000000000000000000e+00 +2.819707900979176785e+01,1.523700000000000045e+02,0.000000000000000000e+00,8.513378172168248881e+00,0.000000000000000000e+00,1.000000009948846857e+00,0.000000000000000000e+00,-1.455191193530129277e-09,0.000000000000000000e+00 +2.819825363163961285e+01,1.523799999999999955e+02,0.000000000000000000e+00,8.514552794027780536e+00,0.000000000000000000e+00,1.000000009947137558e+00,0.000000000000000000e+00,2.148489784999523198e-09,0.000000000000000000e+00 +2.819942809144295381e+01,1.523900000000000148e+02,0.000000000000000000e+00,8.515727253842802824e+00,0.000000000000000000e+00,1.000000009949660873e+00,0.000000000000000000e+00,-1.945328386988237464e-09,0.000000000000000000e+00 +2.820060238926883756e+01,1.524000000000000057e+02,0.000000000000000000e+00,8.516901551680369664e+00,0.000000000000000000e+00,1.000000009947376478e+00,0.000000000000000000e+00,3.986506340801159114e-10,0.000000000000000000e+00 +2.820177652518426470e+01,1.524099999999999966e+02,0.000000000000000000e+00,8.518075687607478130e+00,0.000000000000000000e+00,1.000000009947844548e+00,0.000000000000000000e+00,1.420625095108091467e-09,0.000000000000000000e+00 +2.820295049925619679e+01,1.524200000000000159e+02,0.000000000000000000e+00,8.519249661691087994e+00,0.000000000000000000e+00,1.000000009949512325e+00,0.000000000000000000e+00,-1.491757891260901119e-09,0.000000000000000000e+00 +2.820412431155154209e+01,1.524300000000000068e+02,0.000000000000000000e+00,8.520423473998111064e+00,0.000000000000000000e+00,1.000000009947761281e+00,0.000000000000000000e+00,6.528995435132739872e-10,0.000000000000000000e+00 +2.820529796213716267e+01,1.524399999999999977e+02,0.000000000000000000e+00,8.521597124595407635e+00,0.000000000000000000e+00,1.000000009948527557e+00,0.000000000000000000e+00,-1.202666218256896211e-09,0.000000000000000000e+00 +2.820647145107987797e+01,1.524500000000000171e+02,0.000000000000000000e+00,8.522770613549798924e+00,0.000000000000000000e+00,1.000000009947116242e+00,0.000000000000000000e+00,1.938421409932513112e-09,0.000000000000000000e+00 +2.820764477844646123e+01,1.524600000000000080e+02,0.000000000000000000e+00,8.523943940928054630e+00,0.000000000000000000e+00,1.000000009949390645e+00,0.000000000000000000e+00,-1.568666249838462138e-09,0.000000000000000000e+00 +2.820881794430363954e+01,1.524699999999999989e+02,0.000000000000000000e+00,8.525117106796905375e+00,0.000000000000000000e+00,1.000000009947550339e+00,0.000000000000000000e+00,-1.415931282418921892e-10,0.000000000000000000e+00 +2.820999094871809376e+01,1.524799999999999898e+02,0.000000000000000000e+00,8.526290111223026713e+00,0.000000000000000000e+00,1.000000009947384250e+00,0.000000000000000000e+00,1.025555496802946452e-09,0.000000000000000000e+00 +2.821116379175645505e+01,1.524900000000000091e+02,0.000000000000000000e+00,8.527462954273055118e+00,0.000000000000000000e+00,1.000000009948587065e+00,0.000000000000000000e+00,-6.825985099413314715e-10,0.000000000000000000e+00 +2.821233647348531548e+01,1.525000000000000000e+02,0.000000000000000000e+00,8.528635636013580879e+00,0.000000000000000000e+00,1.000000009947786594e+00,0.000000000000000000e+00,1.159914237338259395e-09,0.000000000000000000e+00 +2.821350899397121381e+01,1.525099999999999909e+02,0.000000000000000000e+00,8.529808156511144546e+00,0.000000000000000000e+00,1.000000009949146618e+00,0.000000000000000000e+00,-1.230909223641017323e-09,0.000000000000000000e+00 +2.821468135328064974e+01,1.525200000000000102e+02,0.000000000000000000e+00,8.530980515832245814e+00,0.000000000000000000e+00,1.000000009947703550e+00,0.000000000000000000e+00,-1.337346287972344215e-10,0.000000000000000000e+00 +2.821585355148007679e+01,1.525300000000000011e+02,0.000000000000000000e+00,8.532152714043332864e+00,0.000000000000000000e+00,1.000000009947546786e+00,0.000000000000000000e+00,5.433478996480784309e-10,0.000000000000000000e+00 +2.821702558863589871e+01,1.525399999999999920e+02,0.000000000000000000e+00,8.533324751210813019e+00,0.000000000000000000e+00,1.000000009948183610e+00,0.000000000000000000e+00,-5.259905735268957995e-10,0.000000000000000000e+00 +2.821819746481447666e+01,1.525500000000000114e+02,0.000000000000000000e+00,8.534496627401047419e+00,0.000000000000000000e+00,1.000000009947567214e+00,0.000000000000000000e+00,5.067334103807752841e-10,0.000000000000000000e+00 +2.821936918008212203e+01,1.525600000000000023e+02,0.000000000000000000e+00,8.535668342680349241e+00,0.000000000000000000e+00,1.000000009948160962e+00,0.000000000000000000e+00,-2.710277720037823608e-10,0.000000000000000000e+00 +2.822054073450510714e+01,1.525699999999999932e+02,0.000000000000000000e+00,8.536839897114989029e+00,0.000000000000000000e+00,1.000000009947843438e+00,0.000000000000000000e+00,-3.038581465347817534e-10,0.000000000000000000e+00 +2.822171212814965457e+01,1.525800000000000125e+02,0.000000000000000000e+00,8.538011290771189366e+00,0.000000000000000000e+00,1.000000009947487500e+00,0.000000000000000000e+00,3.772680494370443255e-10,0.000000000000000000e+00 +2.822288336108194429e+01,1.525900000000000034e+02,0.000000000000000000e+00,8.539182523715128426e+00,0.000000000000000000e+00,1.000000009947929369e+00,0.000000000000000000e+00,4.459578771993207616e-10,0.000000000000000000e+00 +2.822405443336810649e+01,1.525999999999999943e+02,0.000000000000000000e+00,8.540353596012939974e+00,0.000000000000000000e+00,1.000000009948451618e+00,0.000000000000000000e+00,-1.304681534820973558e-10,0.000000000000000000e+00 +2.822522534507422876e+01,1.526100000000000136e+02,0.000000000000000000e+00,8.541524507730711591e+00,0.000000000000000000e+00,1.000000009948298851e+00,0.000000000000000000e+00,-1.383569287669484748e-09,0.000000000000000000e+00 +2.822639609626635604e+01,1.526200000000000045e+02,0.000000000000000000e+00,8.542695258934484670e+00,0.000000000000000000e+00,1.000000009946679036e+00,0.000000000000000000e+00,1.839384554133964683e-09,0.000000000000000000e+00 +2.822756668701048355e+01,1.526299999999999955e+02,0.000000000000000000e+00,8.543865849690254421e+00,0.000000000000000000e+00,1.000000009948832203e+00,0.000000000000000000e+00,-8.629995773610447698e-10,0.000000000000000000e+00 +2.822873711737256031e+01,1.526400000000000148e+02,0.000000000000000000e+00,8.545036280063976974e+00,0.000000000000000000e+00,1.000000009947822122e+00,0.000000000000000000e+00,-4.483507061124031842e-10,0.000000000000000000e+00 +2.822990738741849626e+01,1.526500000000000057e+02,0.000000000000000000e+00,8.546206550121555168e+00,0.000000000000000000e+00,1.000000009947297430e+00,0.000000000000000000e+00,4.601774713296429527e-10,0.000000000000000000e+00 +2.823107749721415161e+01,1.526599999999999966e+02,0.000000000000000000e+00,8.547376659928850984e+00,0.000000000000000000e+00,1.000000009947835888e+00,0.000000000000000000e+00,-7.646634561731722813e-10,0.000000000000000000e+00 +2.823224744682534393e+01,1.526700000000000159e+02,0.000000000000000000e+00,8.548546609551681996e+00,0.000000000000000000e+00,1.000000009946941271e+00,0.000000000000000000e+00,1.037153888874051305e-09,0.000000000000000000e+00 +2.823341723631784461e+01,1.526800000000000068e+02,0.000000000000000000e+00,8.549716399055817817e+00,0.000000000000000000e+00,1.000000009948154522e+00,0.000000000000000000e+00,-6.564730827370860304e-10,0.000000000000000000e+00 +2.823458686575737886e+01,1.526899999999999977e+02,0.000000000000000000e+00,8.550886028506987202e+00,0.000000000000000000e+00,1.000000009947386692e+00,0.000000000000000000e+00,6.144122363826689760e-10,0.000000000000000000e+00 +2.823575633520962924e+01,1.527000000000000171e+02,0.000000000000000000e+00,8.552055497970869169e+00,0.000000000000000000e+00,1.000000009948105228e+00,0.000000000000000000e+00,-3.761795750785233318e-10,0.000000000000000000e+00 +2.823692564474022859e+01,1.527100000000000080e+02,0.000000000000000000e+00,8.553224807513101879e+00,0.000000000000000000e+00,1.000000009947665358e+00,0.000000000000000000e+00,2.377795173870467825e-10,0.000000000000000000e+00 +2.823809479441477066e+01,1.527199999999999989e+02,0.000000000000000000e+00,8.554393957199275533e+00,0.000000000000000000e+00,1.000000009947943358e+00,0.000000000000000000e+00,-1.743701550418238611e-10,0.000000000000000000e+00 +2.823926378429880302e+01,1.527299999999999898e+02,0.000000000000000000e+00,8.555562947094937698e+00,0.000000000000000000e+00,1.000000009947739521e+00,0.000000000000000000e+00,-3.436587319448567772e-10,0.000000000000000000e+00 +2.824043261445782704e+01,1.527400000000000091e+02,0.000000000000000000e+00,8.556731777265589756e+00,0.000000000000000000e+00,1.000000009947337842e+00,0.000000000000000000e+00,-3.020962041822513879e-10,0.000000000000000000e+00 +2.824160128495730149e+01,1.527500000000000000e+02,0.000000000000000000e+00,8.557900447776688679e+00,0.000000000000000000e+00,1.000000009946984791e+00,0.000000000000000000e+00,1.220711364802561290e-09,0.000000000000000000e+00 +2.824276979586263536e+01,1.527599999999999909e+02,0.000000000000000000e+00,8.559068958693647033e+00,0.000000000000000000e+00,1.000000009948411206e+00,0.000000000000000000e+00,-1.010683286447218368e-09,0.000000000000000000e+00 +2.824393814723919860e+01,1.527700000000000102e+02,0.000000000000000000e+00,8.560237310081834750e+00,0.000000000000000000e+00,1.000000009947230373e+00,0.000000000000000000e+00,-5.223273397826328939e-10,0.000000000000000000e+00 +2.824510633915231494e+01,1.527800000000000011e+02,0.000000000000000000e+00,8.561405502006572021e+00,0.000000000000000000e+00,1.000000009946620194e+00,0.000000000000000000e+00,1.355232810946845925e-09,0.000000000000000000e+00 +2.824627437166726196e+01,1.527899999999999920e+02,0.000000000000000000e+00,8.562573534533138186e+00,0.000000000000000000e+00,1.000000009948203150e+00,0.000000000000000000e+00,-6.182940633770287853e-10,0.000000000000000000e+00 +2.824744224484927457e+01,1.528000000000000114e+02,0.000000000000000000e+00,8.563741407726769950e+00,0.000000000000000000e+00,1.000000009947481061e+00,0.000000000000000000e+00,3.688973200464115059e-11,0.000000000000000000e+00 +2.824860995876354153e+01,1.528100000000000023e+02,0.000000000000000000e+00,8.564909121652654278e+00,0.000000000000000000e+00,1.000000009947524138e+00,0.000000000000000000e+00,-6.173216384493976845e-10,0.000000000000000000e+00 +2.824977751347520893e+01,1.528199999999999932e+02,0.000000000000000000e+00,8.566076676375937282e+00,0.000000000000000000e+00,1.000000009946803381e+00,0.000000000000000000e+00,-6.276768667499286718e-12,0.000000000000000000e+00 +2.825094490904938027e+01,1.528300000000000125e+02,0.000000000000000000e+00,8.567244071961718888e+00,0.000000000000000000e+00,1.000000009946796053e+00,0.000000000000000000e+00,5.356905875918238919e-10,0.000000000000000000e+00 +2.825211214555110928e+01,1.528400000000000034e+02,0.000000000000000000e+00,8.568411308475056387e+00,0.000000000000000000e+00,1.000000009947421331e+00,0.000000000000000000e+00,9.788720097182271401e-10,0.000000000000000000e+00 +2.825327922304540706e+01,1.528499999999999943e+02,0.000000000000000000e+00,8.569578385980962665e+00,0.000000000000000000e+00,1.000000009948563751e+00,0.000000000000000000e+00,-1.318660252432836565e-09,0.000000000000000000e+00 +2.825444614159724210e+01,1.528600000000000136e+02,0.000000000000000000e+00,8.570745304544406196e+00,0.000000000000000000e+00,1.000000009947024981e+00,0.000000000000000000e+00,1.356901569358229132e-10,0.000000000000000000e+00 +2.825561290127153669e+01,1.528700000000000045e+02,0.000000000000000000e+00,8.571912064230307493e+00,0.000000000000000000e+00,1.000000009947183299e+00,0.000000000000000000e+00,9.231232114607521505e-11,0.000000000000000000e+00 +2.825677950213317402e+01,1.528799999999999955e+02,0.000000000000000000e+00,8.573078665103547991e+00,0.000000000000000000e+00,1.000000009947290991e+00,0.000000000000000000e+00,-1.747510184239033069e-10,0.000000000000000000e+00 +2.825794594424698758e+01,1.528900000000000148e+02,0.000000000000000000e+00,8.574245107228962937e+00,0.000000000000000000e+00,1.000000009947087154e+00,0.000000000000000000e+00,-6.970049279423402623e-10,0.000000000000000000e+00 +2.825911222767776820e+01,1.529000000000000057e+02,0.000000000000000000e+00,8.575411390671343170e+00,0.000000000000000000e+00,1.000000009946274249e+00,0.000000000000000000e+00,1.107057597268550108e-09,0.000000000000000000e+00 +2.826027835249026054e+01,1.529099999999999966e+02,0.000000000000000000e+00,8.576577515495435122e+00,0.000000000000000000e+00,1.000000009947565216e+00,0.000000000000000000e+00,-1.694900661773010464e-11,0.000000000000000000e+00 +2.826144431874917018e+01,1.529200000000000159e+02,0.000000000000000000e+00,8.577743481765944367e+00,0.000000000000000000e+00,1.000000009947545454e+00,0.000000000000000000e+00,-1.830360637717259372e-10,0.000000000000000000e+00 +2.826261012651915649e+01,1.529300000000000068e+02,0.000000000000000000e+00,8.578909289547528516e+00,0.000000000000000000e+00,1.000000009947332069e+00,0.000000000000000000e+00,-7.272910200193931176e-10,0.000000000000000000e+00 +2.826377577586483625e+01,1.529399999999999977e+02,0.000000000000000000e+00,8.580074938904802551e+00,0.000000000000000000e+00,1.000000009946484303e+00,0.000000000000000000e+00,9.342901452577912633e-10,0.000000000000000000e+00 +2.826494126685077646e+01,1.529500000000000171e+02,0.000000000000000000e+00,8.581240429902337041e+00,0.000000000000000000e+00,1.000000009947573210e+00,0.000000000000000000e+00,-4.590152301727708182e-10,0.000000000000000000e+00 +2.826610659954150861e+01,1.529600000000000080e+02,0.000000000000000000e+00,8.582405762604661703e+00,0.000000000000000000e+00,1.000000009947038304e+00,0.000000000000000000e+00,2.925214036686031135e-10,0.000000000000000000e+00 +2.826727177400151447e+01,1.529699999999999989e+02,0.000000000000000000e+00,8.583570937076258289e+00,0.000000000000000000e+00,1.000000009947379143e+00,0.000000000000000000e+00,-7.658049311392557182e-10,0.000000000000000000e+00 +2.826843679029523670e+01,1.529799999999999898e+02,0.000000000000000000e+00,8.584735953381567697e+00,0.000000000000000000e+00,1.000000009946486967e+00,0.000000000000000000e+00,2.615298583927729969e-10,0.000000000000000000e+00 +2.826960164848706825e+01,1.529900000000000091e+02,0.000000000000000000e+00,8.585900811584984638e+00,0.000000000000000000e+00,1.000000009946791613e+00,0.000000000000000000e+00,7.263585753345135177e-10,0.000000000000000000e+00 +2.827076634864136295e+01,1.530000000000000000e+02,0.000000000000000000e+00,8.587065511750862967e+00,0.000000000000000000e+00,1.000000009947637603e+00,0.000000000000000000e+00,-7.127287845004544033e-10,0.000000000000000000e+00 +2.827193089082242849e+01,1.530099999999999909e+02,0.000000000000000000e+00,8.588230053943512132e+00,0.000000000000000000e+00,1.000000009946807600e+00,0.000000000000000000e+00,-1.559901582154530941e-10,0.000000000000000000e+00 +2.827309527509452991e+01,1.530200000000000102e+02,0.000000000000000000e+00,8.589394438227195394e+00,0.000000000000000000e+00,1.000000009946625967e+00,0.000000000000000000e+00,-2.542335849877030867e-10,0.000000000000000000e+00 +2.827425950152188960e+01,1.530300000000000011e+02,0.000000000000000000e+00,8.590558664666135158e+00,0.000000000000000000e+00,1.000000009946329982e+00,0.000000000000000000e+00,1.583595877409266228e-09,0.000000000000000000e+00 +2.827542357016868735e+01,1.530399999999999920e+02,0.000000000000000000e+00,8.591722733324509420e+00,0.000000000000000000e+00,1.000000009948173396e+00,0.000000000000000000e+00,-1.227443570477546291e-09,0.000000000000000000e+00 +2.827658748109905318e+01,1.530500000000000114e+02,0.000000000000000000e+00,8.592886644266455320e+00,0.000000000000000000e+00,1.000000009946744761e+00,0.000000000000000000e+00,-8.528778416810001111e-10,0.000000000000000000e+00 +2.827775123437708160e+01,1.530600000000000023e+02,0.000000000000000000e+00,8.594050397556060261e+00,0.000000000000000000e+00,1.000000009945752222e+00,0.000000000000000000e+00,1.368987535600822560e-09,0.000000000000000000e+00 +2.827891483006682094e+01,1.530699999999999932e+02,0.000000000000000000e+00,8.595213993257372564e+00,0.000000000000000000e+00,1.000000009947345170e+00,0.000000000000000000e+00,1.591706426746030906e-10,0.000000000000000000e+00 +2.828007826823227333e+01,1.530800000000000125e+02,0.000000000000000000e+00,8.596377431434399696e+00,0.000000000000000000e+00,1.000000009947530355e+00,0.000000000000000000e+00,-5.770239613950554056e-10,0.000000000000000000e+00 +2.828124154893740183e+01,1.530900000000000034e+02,0.000000000000000000e+00,8.597540712151101161e+00,0.000000000000000000e+00,1.000000009946859114e+00,0.000000000000000000e+00,-8.705211140249474241e-10,0.000000000000000000e+00 +2.828240467224612331e+01,1.530999999999999943e+02,0.000000000000000000e+00,8.598703835471393830e+00,0.000000000000000000e+00,1.000000009945846591e+00,0.000000000000000000e+00,5.636241189835089856e-10,0.000000000000000000e+00 +2.828356763822231557e+01,1.531100000000000136e+02,0.000000000000000000e+00,8.599866801459151944e+00,0.000000000000000000e+00,1.000000009946502066e+00,0.000000000000000000e+00,1.068777388541316889e-09,0.000000000000000000e+00 +2.828473044692980665e+01,1.531200000000000045e+02,0.000000000000000000e+00,8.601029610178208884e+00,0.000000000000000000e+00,1.000000009947744850e+00,0.000000000000000000e+00,-2.015233856380592760e-09,0.000000000000000000e+00 +2.828589309843238553e+01,1.531299999999999955e+02,0.000000000000000000e+00,8.602192261692353625e+00,0.000000000000000000e+00,1.000000009945401835e+00,0.000000000000000000e+00,1.795084145225994560e-09,0.000000000000000000e+00 +2.828705559279379855e+01,1.531400000000000148e+02,0.000000000000000000e+00,8.603354756065327180e+00,0.000000000000000000e+00,1.000000009947488611e+00,0.000000000000000000e+00,-6.731997661629621737e-10,0.000000000000000000e+00 +2.828821793007774588e+01,1.531500000000000057e+02,0.000000000000000000e+00,8.604517093360836810e+00,0.000000000000000000e+00,1.000000009946706125e+00,0.000000000000000000e+00,-2.491404924530045625e-10,0.000000000000000000e+00 +2.828938011034788858e+01,1.531599999999999966e+02,0.000000000000000000e+00,8.605679273642538263e+00,0.000000000000000000e+00,1.000000009946416579e+00,0.000000000000000000e+00,4.083475026511541061e-10,0.000000000000000000e+00 +2.829054213366784154e+01,1.531700000000000159e+02,0.000000000000000000e+00,8.606841296974048205e+00,0.000000000000000000e+00,1.000000009946891089e+00,0.000000000000000000e+00,-4.586646421053711781e-11,0.000000000000000000e+00 +2.829170400010117703e+01,1.531800000000000068e+02,0.000000000000000000e+00,8.608003163418940673e+00,0.000000000000000000e+00,1.000000009946837798e+00,0.000000000000000000e+00,-3.276072174007729968e-10,0.000000000000000000e+00 +2.829286570971142467e+01,1.531899999999999977e+02,0.000000000000000000e+00,8.609164873040745292e+00,0.000000000000000000e+00,1.000000009946457213e+00,0.000000000000000000e+00,-4.656702941191970700e-10,0.000000000000000000e+00 +2.829402726256207501e+01,1.532000000000000171e+02,0.000000000000000000e+00,8.610326425902949055e+00,0.000000000000000000e+00,1.000000009945916313e+00,0.000000000000000000e+00,8.265042237094110868e-10,0.000000000000000000e+00 +2.829518865871657241e+01,1.532100000000000080e+02,0.000000000000000000e+00,8.611487822068996323e+00,0.000000000000000000e+00,1.000000009946876212e+00,0.000000000000000000e+00,-4.317599500643208413e-10,0.000000000000000000e+00 +2.829634989823831503e+01,1.532199999999999989e+02,0.000000000000000000e+00,8.612649061602290601e+00,0.000000000000000000e+00,1.000000009946374835e+00,0.000000000000000000e+00,-3.193695071263175213e-10,0.000000000000000000e+00 +2.829751098119066555e+01,1.532299999999999898e+02,0.000000000000000000e+00,8.613810144566189209e+00,0.000000000000000000e+00,1.000000009946004020e+00,0.000000000000000000e+00,1.134966551804689511e-09,0.000000000000000000e+00 +2.829867190763693685e+01,1.532400000000000091e+02,0.000000000000000000e+00,8.614971071024008609e+00,0.000000000000000000e+00,1.000000009947321633e+00,0.000000000000000000e+00,-1.370981054594301618e-09,0.000000000000000000e+00 +2.829983267764040633e+01,1.532500000000000000e+02,0.000000000000000000e+00,8.616131841039024408e+00,0.000000000000000000e+00,1.000000009945730239e+00,0.000000000000000000e+00,4.132437675751064547e-11,0.000000000000000000e+00 +2.830099329126430163e+01,1.532599999999999909e+02,0.000000000000000000e+00,8.617292454674464253e+00,0.000000000000000000e+00,1.000000009945778201e+00,0.000000000000000000e+00,1.389527999459038398e-09,0.000000000000000000e+00 +2.830215374857181487e+01,1.532700000000000102e+02,0.000000000000000000e+00,8.618452911993518484e+00,0.000000000000000000e+00,1.000000009947390689e+00,0.000000000000000000e+00,-1.315847036284343988e-09,0.000000000000000000e+00 +2.830331404962608843e+01,1.532800000000000011e+02,0.000000000000000000e+00,8.619613213059334811e+00,0.000000000000000000e+00,1.000000009945863910e+00,0.000000000000000000e+00,1.131329112666750706e-09,0.000000000000000000e+00 +2.830447419449022917e+01,1.532899999999999920e+02,0.000000000000000000e+00,8.620773357935012982e+00,0.000000000000000000e+00,1.000000009947176416e+00,0.000000000000000000e+00,-1.856196069114264853e-09,0.000000000000000000e+00 +2.830563418322729419e+01,1.533000000000000114e+02,0.000000000000000000e+00,8.621933346683617216e+00,0.000000000000000000e+00,1.000000009945023249e+00,0.000000000000000000e+00,1.572532337893655737e-09,0.000000000000000000e+00 +2.830679401590030508e+01,1.533100000000000023e+02,0.000000000000000000e+00,8.623093179368161998e+00,0.000000000000000000e+00,1.000000009946847124e+00,0.000000000000000000e+00,-4.943784623707391005e-10,0.000000000000000000e+00 +2.830795369257223726e+01,1.533199999999999932e+02,0.000000000000000000e+00,8.624252856051628058e+00,0.000000000000000000e+00,1.000000009946273805e+00,0.000000000000000000e+00,-1.648788152466374427e-10,0.000000000000000000e+00 +2.830911321330602348e+01,1.533300000000000125e+02,0.000000000000000000e+00,8.625412376796946390e+00,0.000000000000000000e+00,1.000000009946082624e+00,0.000000000000000000e+00,-1.085933302756607241e-10,0.000000000000000000e+00 +2.831027257816455389e+01,1.533400000000000034e+02,0.000000000000000000e+00,8.626571741667008908e+00,0.000000000000000000e+00,1.000000009945956725e+00,0.000000000000000000e+00,9.657868887177358743e-10,0.000000000000000000e+00 +2.831143178721067954e+01,1.533499999999999943e+02,0.000000000000000000e+00,8.627730950724664893e+00,0.000000000000000000e+00,1.000000009947076274e+00,0.000000000000000000e+00,-9.367974029626771379e-10,0.000000000000000000e+00 +2.831259084050720887e+01,1.533600000000000136e+02,0.000000000000000000e+00,8.628890004032722771e+00,0.000000000000000000e+00,1.000000009945990476e+00,0.000000000000000000e+00,-5.581303548606824615e-10,0.000000000000000000e+00 +2.831374973811690410e+01,1.533700000000000045e+02,0.000000000000000000e+00,8.630048901653944782e+00,0.000000000000000000e+00,1.000000009945343660e+00,0.000000000000000000e+00,7.513638987296537357e-10,0.000000000000000000e+00 +2.831490848010248840e+01,1.533799999999999955e+02,0.000000000000000000e+00,8.631207643651054084e+00,0.000000000000000000e+00,1.000000009946214297e+00,0.000000000000000000e+00,3.162246600579674696e-10,0.000000000000000000e+00 +2.831606706652664229e+01,1.533900000000000148e+02,0.000000000000000000e+00,8.632366230086732983e+00,0.000000000000000000e+00,1.000000009946580670e+00,0.000000000000000000e+00,-5.704308559004304000e-10,0.000000000000000000e+00 +2.831722549745200723e+01,1.534000000000000057e+02,0.000000000000000000e+00,8.633524661023619373e+00,0.000000000000000000e+00,1.000000009945919865e+00,0.000000000000000000e+00,7.091084990557298855e-10,0.000000000000000000e+00 +2.831838377294117493e+01,1.534099999999999966e+02,0.000000000000000000e+00,8.634682936524308516e+00,0.000000000000000000e+00,1.000000009946741208e+00,0.000000000000000000e+00,-1.169927161341262689e-09,0.000000000000000000e+00 +2.831954189305670511e+01,1.534200000000000159e+02,0.000000000000000000e+00,8.635841056651356595e+00,0.000000000000000000e+00,1.000000009945386292e+00,0.000000000000000000e+00,3.838918915070269655e-10,0.000000000000000000e+00 +2.832069985786110422e+01,1.534300000000000068e+02,0.000000000000000000e+00,8.636999021467273607e+00,0.000000000000000000e+00,1.000000009945830826e+00,0.000000000000000000e+00,4.430115771911636136e-11,0.000000000000000000e+00 +2.832185766741684674e+01,1.534399999999999977e+02,0.000000000000000000e+00,8.638156831034532246e+00,0.000000000000000000e+00,1.000000009945882118e+00,0.000000000000000000e+00,4.309872103499444527e-10,0.000000000000000000e+00 +2.832301532178636094e+01,1.534500000000000171e+02,0.000000000000000000e+00,8.639314485415560796e+00,0.000000000000000000e+00,1.000000009946381052e+00,0.000000000000000000e+00,-1.136792385571463864e-09,0.000000000000000000e+00 +2.832417282103203249e+01,1.534600000000000080e+02,0.000000000000000000e+00,8.640471984672746686e+00,0.000000000000000000e+00,1.000000009945065216e+00,0.000000000000000000e+00,1.941784887479710910e-09,0.000000000000000000e+00 +2.832533016521620794e+01,1.534699999999999989e+02,0.000000000000000000e+00,8.641629328868432935e+00,0.000000000000000000e+00,1.000000009947312529e+00,0.000000000000000000e+00,-2.298371184510063819e-09,0.000000000000000000e+00 +2.832648735440119125e+01,1.534799999999999898e+02,0.000000000000000000e+00,8.642786518064927037e+00,0.000000000000000000e+00,1.000000009944652879e+00,0.000000000000000000e+00,2.030966721926066416e-09,0.000000000000000000e+00 +2.832764438864924372e+01,1.534900000000000091e+02,0.000000000000000000e+00,8.643943552324484969e+00,0.000000000000000000e+00,1.000000009947002777e+00,0.000000000000000000e+00,-1.019362021601362922e-09,0.000000000000000000e+00 +2.832880126802258403e+01,1.535000000000000000e+02,0.000000000000000000e+00,8.645100431709332511e+00,0.000000000000000000e+00,1.000000009945823498e+00,0.000000000000000000e+00,-8.643949388262211291e-10,0.000000000000000000e+00 +2.832995799258339176e+01,1.535099999999999909e+02,0.000000000000000000e+00,8.646257156281643930e+00,0.000000000000000000e+00,1.000000009944823631e+00,0.000000000000000000e+00,1.141929607885466128e-09,0.000000000000000000e+00 +2.833111456239380388e+01,1.535200000000000102e+02,0.000000000000000000e+00,8.647413726103556186e+00,0.000000000000000000e+00,1.000000009946144353e+00,0.000000000000000000e+00,-3.410118138438259422e-10,0.000000000000000000e+00 +2.833227097751591472e+01,1.535300000000000011e+02,0.000000000000000000e+00,8.648570141237167164e+00,0.000000000000000000e+00,1.000000009945750001e+00,0.000000000000000000e+00,-3.091793027685660998e-11,0.000000000000000000e+00 +2.833342723801177598e+01,1.535399999999999920e+02,0.000000000000000000e+00,8.649726401744528559e+00,0.000000000000000000e+00,1.000000009945714252e+00,0.000000000000000000e+00,-6.132555885500829880e-10,0.000000000000000000e+00 +2.833458334394340383e+01,1.535500000000000114e+02,0.000000000000000000e+00,8.650882507687652989e+00,0.000000000000000000e+00,1.000000009945005264e+00,0.000000000000000000e+00,5.411123998690063813e-10,0.000000000000000000e+00 +2.833573929537276470e+01,1.535600000000000023e+02,0.000000000000000000e+00,8.652038459128510439e+00,0.000000000000000000e+00,1.000000009945630763e+00,0.000000000000000000e+00,7.454017230439062028e-10,0.000000000000000000e+00 +2.833689509236178949e+01,1.535699999999999932e+02,0.000000000000000000e+00,8.653194256129031814e+00,0.000000000000000000e+00,1.000000009946492296e+00,0.000000000000000000e+00,-1.360924149288721009e-09,0.000000000000000000e+00 +2.833805073497237004e+01,1.535800000000000125e+02,0.000000000000000000e+00,8.654349898751105385e+00,0.000000000000000000e+00,1.000000009944919555e+00,0.000000000000000000e+00,8.437972632927804228e-10,0.000000000000000000e+00 +2.833920622326634842e+01,1.535900000000000034e+02,0.000000000000000000e+00,8.655505387056575017e+00,0.000000000000000000e+00,1.000000009945894552e+00,0.000000000000000000e+00,6.811242923394300410e-10,0.000000000000000000e+00 +2.834036155730553119e+01,1.535999999999999943e+02,0.000000000000000000e+00,8.656660721107249046e+00,0.000000000000000000e+00,1.000000009946681478e+00,0.000000000000000000e+00,-1.881414915820784123e-09,0.000000000000000000e+00 +2.834151673715168229e+01,1.536100000000000136e+02,0.000000000000000000e+00,8.657815900964891398e+00,0.000000000000000000e+00,1.000000009944508106e+00,0.000000000000000000e+00,1.115581086914546919e-09,0.000000000000000000e+00 +2.834267176286652656e+01,1.536200000000000045e+02,0.000000000000000000e+00,8.658970926691221592e+00,0.000000000000000000e+00,1.000000009945796631e+00,0.000000000000000000e+00,3.247402767843404494e-10,0.000000000000000000e+00 +2.834382663451174267e+01,1.536299999999999955e+02,0.000000000000000000e+00,8.660125798347925397e+00,0.000000000000000000e+00,1.000000009946171664e+00,0.000000000000000000e+00,-1.621802713975082400e-09,0.000000000000000000e+00 +2.834498135214897374e+01,1.536400000000000148e+02,0.000000000000000000e+00,8.661280515996642393e+00,0.000000000000000000e+00,1.000000009944298940e+00,0.000000000000000000e+00,1.909343637925046413e-09,0.000000000000000000e+00 +2.834613591583982029e+01,1.536500000000000057e+02,0.000000000000000000e+00,8.662435079698969531e+00,0.000000000000000000e+00,1.000000009946503399e+00,0.000000000000000000e+00,-1.102135116652360622e-09,0.000000000000000000e+00 +2.834729032564584017e+01,1.536599999999999966e+02,0.000000000000000000e+00,8.663589489516470010e+00,0.000000000000000000e+00,1.000000009945231083e+00,0.000000000000000000e+00,-2.481577264007716288e-11,0.000000000000000000e+00 +2.834844458162854863e+01,1.536700000000000159e+02,0.000000000000000000e+00,8.664743745510657291e+00,0.000000000000000000e+00,1.000000009945202439e+00,0.000000000000000000e+00,-2.179846228781106905e-10,0.000000000000000000e+00 +2.834959868384942183e+01,1.536800000000000068e+02,0.000000000000000000e+00,8.665897847743009308e+00,0.000000000000000000e+00,1.000000009944950863e+00,0.000000000000000000e+00,9.565277059560117357e-10,0.000000000000000000e+00 +2.835075263236989684e+01,1.536899999999999977e+02,0.000000000000000000e+00,8.667051796274961362e+00,0.000000000000000000e+00,1.000000009946054647e+00,0.000000000000000000e+00,-5.319240862201367526e-10,0.000000000000000000e+00 +2.835190642725136811e+01,1.537000000000000171e+02,0.000000000000000000e+00,8.668205591167909674e+00,0.000000000000000000e+00,1.000000009945440915e+00,0.000000000000000000e+00,-7.098397918398558535e-10,0.000000000000000000e+00 +2.835306006855519101e+01,1.537100000000000080e+02,0.000000000000000000e+00,8.669359232483206057e+00,0.000000000000000000e+00,1.000000009944622015e+00,0.000000000000000000e+00,3.950068082637767115e-10,0.000000000000000000e+00 +2.835421355634267826e+01,1.537199999999999989e+02,0.000000000000000000e+00,8.670512720282163244e+00,0.000000000000000000e+00,1.000000009945077650e+00,0.000000000000000000e+00,1.420057445518124478e-09,0.000000000000000000e+00 +2.835536689067509997e+01,1.537299999999999898e+02,0.000000000000000000e+00,8.671666054626054887e+00,0.000000000000000000e+00,1.000000009946715451e+00,0.000000000000000000e+00,-1.670946004273974263e-09,0.000000000000000000e+00 +2.835652007161368715e+01,1.537400000000000091e+02,0.000000000000000000e+00,8.672819235576113783e+00,0.000000000000000000e+00,1.000000009944788548e+00,0.000000000000000000e+00,4.433082763165832737e-10,0.000000000000000000e+00 +2.835767309921963175e+01,1.537500000000000000e+02,0.000000000000000000e+00,8.673972263193526544e+00,0.000000000000000000e+00,1.000000009945299695e+00,0.000000000000000000e+00,-2.804268731717524017e-10,0.000000000000000000e+00 +2.835882597355408663e+01,1.537599999999999909e+02,0.000000000000000000e+00,8.675125137539446030e+00,0.000000000000000000e+00,1.000000009944976398e+00,0.000000000000000000e+00,1.373426755228030019e-10,0.000000000000000000e+00 +2.835997869467815846e+01,1.537700000000000102e+02,0.000000000000000000e+00,8.676277858674980692e+00,0.000000000000000000e+00,1.000000009945134716e+00,0.000000000000000000e+00,3.327101230506211082e-10,0.000000000000000000e+00 +2.836113126265291484e+01,1.537800000000000011e+02,0.000000000000000000e+00,8.677430426661199903e+00,0.000000000000000000e+00,1.000000009945518187e+00,0.000000000000000000e+00,-1.061653912579690121e-09,0.000000000000000000e+00 +2.836228367753938429e+01,1.537899999999999920e+02,0.000000000000000000e+00,8.678582841559132177e+00,0.000000000000000000e+00,1.000000009944294721e+00,0.000000000000000000e+00,1.277622546414770474e-09,0.000000000000000000e+00 +2.836343593939855623e+01,1.538000000000000114e+02,0.000000000000000000e+00,8.679735103429763399e+00,0.000000000000000000e+00,1.000000009945766877e+00,0.000000000000000000e+00,-7.053875367935654457e-10,0.000000000000000000e+00 +2.836458804829137748e+01,1.538100000000000023e+02,0.000000000000000000e+00,8.680887212334043923e+00,0.000000000000000000e+00,1.000000009944954193e+00,0.000000000000000000e+00,-3.490782494516720621e-10,0.000000000000000000e+00 +2.836574000427875575e+01,1.538199999999999932e+02,0.000000000000000000e+00,8.682039168332877921e+00,0.000000000000000000e+00,1.000000009944552071e+00,0.000000000000000000e+00,9.812501781517456472e-10,0.000000000000000000e+00 +2.836689180742155614e+01,1.538300000000000125e+02,0.000000000000000000e+00,8.683190971487132259e+00,0.000000000000000000e+00,1.000000009945682278e+00,0.000000000000000000e+00,-7.596539492484688551e-10,0.000000000000000000e+00 +2.836804345778060465e+01,1.538400000000000034e+02,0.000000000000000000e+00,8.684342621857634725e+00,0.000000000000000000e+00,1.000000009944807422e+00,0.000000000000000000e+00,-2.445098888807058196e-10,0.000000000000000000e+00 +2.836919495541668823e+01,1.538499999999999943e+02,0.000000000000000000e+00,8.685494119505168698e+00,0.000000000000000000e+00,1.000000009944525869e+00,0.000000000000000000e+00,1.161190257138247612e-09,0.000000000000000000e+00 +2.837034630039055116e+01,1.538600000000000136e+02,0.000000000000000000e+00,8.686645464490480251e+00,0.000000000000000000e+00,1.000000009945862800e+00,0.000000000000000000e+00,-5.917628228559299672e-10,0.000000000000000000e+00 +2.837149749276289867e+01,1.538700000000000045e+02,0.000000000000000000e+00,8.687796656874276380e+00,0.000000000000000000e+00,1.000000009945181567e+00,0.000000000000000000e+00,-1.711092519817710320e-10,0.000000000000000000e+00 +2.837264853259439334e+01,1.538799999999999955e+02,0.000000000000000000e+00,8.688947696717219671e+00,0.000000000000000000e+00,1.000000009944984614e+00,0.000000000000000000e+00,-2.851555590710052898e-10,0.000000000000000000e+00 +2.837379941994566224e+01,1.538900000000000148e+02,0.000000000000000000e+00,8.690098584079935407e+00,0.000000000000000000e+00,1.000000009944656432e+00,0.000000000000000000e+00,3.787784201969327323e-10,0.000000000000000000e+00 +2.837495015487728978e+01,1.539000000000000057e+02,0.000000000000000000e+00,8.691249319023008013e+00,0.000000000000000000e+00,1.000000009945092305e+00,0.000000000000000000e+00,-8.902375083475607199e-10,0.000000000000000000e+00 +2.837610073744982131e+01,1.539099999999999966e+02,0.000000000000000000e+00,8.692399901606982837e+00,0.000000000000000000e+00,1.000000009944068013e+00,0.000000000000000000e+00,1.246844924293746499e-09,0.000000000000000000e+00 +2.837725116772375955e+01,1.539200000000000159e+02,0.000000000000000000e+00,8.693550331892362593e+00,0.000000000000000000e+00,1.000000009945502422e+00,0.000000000000000000e+00,-1.290056880610383137e-09,0.000000000000000000e+00 +2.837840144575957169e+01,1.539300000000000068e+02,0.000000000000000000e+00,8.694700609939614466e+00,0.000000000000000000e+00,1.000000009944018498e+00,0.000000000000000000e+00,8.664583792097111721e-10,0.000000000000000000e+00 +2.837955157161767872e+01,1.539399999999999977e+02,0.000000000000000000e+00,8.695850735809159460e+00,0.000000000000000000e+00,1.000000009945015034e+00,0.000000000000000000e+00,-3.658992474421997786e-10,0.000000000000000000e+00 +2.838070154535846612e+01,1.539500000000000171e+02,0.000000000000000000e+00,8.697000709561384824e+00,0.000000000000000000e+00,1.000000009944594259e+00,0.000000000000000000e+00,3.555195761407172691e-10,0.000000000000000000e+00 +2.838185136704228029e+01,1.539600000000000080e+02,0.000000000000000000e+00,8.698150531256633400e+00,0.000000000000000000e+00,1.000000009945003043e+00,0.000000000000000000e+00,3.169390310596073161e-10,0.000000000000000000e+00 +2.838300103672942498e+01,1.539699999999999989e+02,0.000000000000000000e+00,8.699300200955210727e+00,0.000000000000000000e+00,1.000000009945367418e+00,0.000000000000000000e+00,-5.101441897963956030e-10,0.000000000000000000e+00 +2.838415055448016489e+01,1.539799999999999898e+02,0.000000000000000000e+00,8.700449718717381486e+00,0.000000000000000000e+00,1.000000009944780999e+00,0.000000000000000000e+00,-8.100406050500104436e-10,0.000000000000000000e+00 +2.838529992035472205e+01,1.539900000000000091e+02,0.000000000000000000e+00,8.701599084603369505e+00,0.000000000000000000e+00,1.000000009943849966e+00,0.000000000000000000e+00,7.355668899552420590e-10,0.000000000000000000e+00 +2.838644913441328299e+01,1.540000000000000000e+02,0.000000000000000000e+00,8.702748298673359528e+00,0.000000000000000000e+00,1.000000009944695289e+00,0.000000000000000000e+00,6.376914415545017856e-11,0.000000000000000000e+00 +2.838759819671599516e+01,1.540099999999999909e+02,0.000000000000000000e+00,8.703897360987498999e+00,0.000000000000000000e+00,1.000000009944768564e+00,0.000000000000000000e+00,-1.633092165950075736e-10,0.000000000000000000e+00 +2.838874710732296336e+01,1.540200000000000102e+02,0.000000000000000000e+00,8.705046271605892727e+00,0.000000000000000000e+00,1.000000009944580937e+00,0.000000000000000000e+00,2.667413813121328983e-11,0.000000000000000000e+00 +2.838989586629425332e+01,1.540300000000000011e+02,0.000000000000000000e+00,8.706195030588606443e+00,0.000000000000000000e+00,1.000000009944611579e+00,0.000000000000000000e+00,-7.402083562118860652e-10,0.000000000000000000e+00 +2.839104447368989170e+01,1.540399999999999920e+02,0.000000000000000000e+00,8.707343637995666796e+00,0.000000000000000000e+00,1.000000009943761370e+00,0.000000000000000000e+00,1.548475019246426837e-09,0.000000000000000000e+00 +2.839219292956986607e+01,1.540500000000000114e+02,0.000000000000000000e+00,8.708492093887059582e+00,0.000000000000000000e+00,1.000000009945539725e+00,0.000000000000000000e+00,-1.215507279321271791e-09,0.000000000000000000e+00 +2.839334123399412135e+01,1.540600000000000023e+02,0.000000000000000000e+00,8.709640398322735066e+00,0.000000000000000000e+00,1.000000009944143953e+00,0.000000000000000000e+00,3.676398385102146242e-10,0.000000000000000000e+00 +2.839448938702256697e+01,1.540699999999999932e+02,0.000000000000000000e+00,8.710788551362597332e+00,0.000000000000000000e+00,1.000000009944566060e+00,0.000000000000000000e+00,-4.640106462332231668e-10,0.000000000000000000e+00 +2.839563738871506970e+01,1.540800000000000125e+02,0.000000000000000000e+00,8.711936553066516709e+00,0.000000000000000000e+00,1.000000009944033375e+00,0.000000000000000000e+00,3.033199583770306624e-10,0.000000000000000000e+00 +2.839678523913146080e+01,1.540900000000000034e+02,0.000000000000000000e+00,8.713084403494320895e+00,0.000000000000000000e+00,1.000000009944381540e+00,0.000000000000000000e+00,-5.262366004622387485e-11,0.000000000000000000e+00 +2.839793293833152532e+01,1.540999999999999943e+02,0.000000000000000000e+00,8.714232102705800287e+00,0.000000000000000000e+00,1.000000009944321144e+00,0.000000000000000000e+00,-2.124573150468427114e-10,0.000000000000000000e+00 +2.839908048637501636e+01,1.541100000000000136e+02,0.000000000000000000e+00,8.715379650760704422e+00,0.000000000000000000e+00,1.000000009944077339e+00,0.000000000000000000e+00,1.146414275756822173e-09,0.000000000000000000e+00 +2.840022788332164438e+01,1.541200000000000045e+02,0.000000000000000000e+00,8.716527047718743759e+00,0.000000000000000000e+00,1.000000009945392732e+00,0.000000000000000000e+00,-1.400884358990512099e-09,0.000000000000000000e+00 +2.840137512923108076e+01,1.541299999999999955e+02,0.000000000000000000e+00,8.717674293639591454e+00,0.000000000000000000e+00,1.000000009943785573e+00,0.000000000000000000e+00,2.142833786646709070e-10,0.000000000000000000e+00 +2.840252222416295780e+01,1.541400000000000148e+02,0.000000000000000000e+00,8.718821388582876253e+00,0.000000000000000000e+00,1.000000009944031376e+00,0.000000000000000000e+00,5.672384044374607551e-10,0.000000000000000000e+00 +2.840366916817686871e+01,1.541500000000000057e+02,0.000000000000000000e+00,8.719968332608193151e+00,0.000000000000000000e+00,1.000000009944681967e+00,0.000000000000000000e+00,-3.707864983258855360e-10,0.000000000000000000e+00 +2.840481596133236764e+01,1.541599999999999966e+02,0.000000000000000000e+00,8.721115125775096288e+00,0.000000000000000000e+00,1.000000009944256751e+00,0.000000000000000000e+00,7.377975703538178286e-11,0.000000000000000000e+00 +2.840596260368896608e+01,1.541700000000000159e+02,0.000000000000000000e+00,8.722261768143098948e+00,0.000000000000000000e+00,1.000000009944341350e+00,0.000000000000000000e+00,-8.279525744739168669e-10,0.000000000000000000e+00 +2.840710909530614359e+01,1.541800000000000068e+02,0.000000000000000000e+00,8.723408259771677109e+00,0.000000000000000000e+00,1.000000009943392110e+00,0.000000000000000000e+00,9.504789029324194509e-10,0.000000000000000000e+00 +2.840825543624333349e+01,1.541899999999999977e+02,0.000000000000000000e+00,8.724554600720265896e+00,0.000000000000000000e+00,1.000000009944481683e+00,0.000000000000000000e+00,-2.382805543740468595e-11,0.000000000000000000e+00 +2.840940162655993362e+01,1.542000000000000171e+02,0.000000000000000000e+00,8.725700791048264904e+00,0.000000000000000000e+00,1.000000009944454371e+00,0.000000000000000000e+00,2.764805057970026198e-10,0.000000000000000000e+00 +2.841054766631530271e+01,1.542100000000000080e+02,0.000000000000000000e+00,8.726846830815031097e+00,0.000000000000000000e+00,1.000000009944771229e+00,0.000000000000000000e+00,-8.807070372108663977e-10,0.000000000000000000e+00 +2.841169355556876042e+01,1.542199999999999989e+02,0.000000000000000000e+00,8.727992720079884137e+00,0.000000000000000000e+00,1.000000009943762036e+00,0.000000000000000000e+00,5.360518221251488640e-10,0.000000000000000000e+00 +2.841283929437958733e+01,1.542299999999999898e+02,0.000000000000000000e+00,8.729138458902102826e+00,0.000000000000000000e+00,1.000000009944376211e+00,0.000000000000000000e+00,-9.125319136884769131e-10,0.000000000000000000e+00 +2.841398488280702139e+01,1.542400000000000091e+02,0.000000000000000000e+00,8.730284047340930442e+00,0.000000000000000000e+00,1.000000009943330825e+00,0.000000000000000000e+00,1.593457252127948801e-10,0.000000000000000000e+00 +2.841513032091026858e+01,1.542500000000000000e+02,0.000000000000000000e+00,8.731429485455567630e+00,0.000000000000000000e+00,1.000000009943513346e+00,0.000000000000000000e+00,1.018434205570752952e-09,0.000000000000000000e+00 +2.841627560874849223e+01,1.542599999999999909e+02,0.000000000000000000e+00,8.732574773305179505e+00,0.000000000000000000e+00,1.000000009944679746e+00,0.000000000000000000e+00,-1.072084774769262679e-09,0.000000000000000000e+00 +2.841742074638081661e+01,1.542700000000000102e+02,0.000000000000000000e+00,8.733719910948892107e+00,0.000000000000000000e+00,1.000000009943452062e+00,0.000000000000000000e+00,6.333673414440150845e-10,0.000000000000000000e+00 +2.841856573386632689e+01,1.542800000000000011e+02,0.000000000000000000e+00,8.734864898445788839e+00,0.000000000000000000e+00,1.000000009944177259e+00,0.000000000000000000e+00,-6.666163322667934548e-10,0.000000000000000000e+00 +2.841971057126407274e+01,1.542899999999999920e+02,0.000000000000000000e+00,8.736009735854919356e+00,0.000000000000000000e+00,1.000000009943414092e+00,0.000000000000000000e+00,4.222909398822451493e-10,0.000000000000000000e+00 +2.842085525863306117e+01,1.543000000000000114e+02,0.000000000000000000e+00,8.737154423235290679e+00,0.000000000000000000e+00,1.000000009943897483e+00,0.000000000000000000e+00,1.161888759443478120e-09,0.000000000000000000e+00 +2.842199979603226367e+01,1.543100000000000023e+02,0.000000000000000000e+00,8.738298960645874303e+00,0.000000000000000000e+00,1.000000009945227308e+00,0.000000000000000000e+00,-1.187264760731212773e-09,0.000000000000000000e+00 +2.842314418352060912e+01,1.543199999999999932e+02,0.000000000000000000e+00,8.739443348145602641e+00,0.000000000000000000e+00,1.000000009943868617e+00,0.000000000000000000e+00,-1.228365773403831413e-09,0.000000000000000000e+00 +2.842428842115699439e+01,1.543300000000000125e+02,0.000000000000000000e+00,8.740587585793365477e+00,0.000000000000000000e+00,1.000000009942463075e+00,0.000000000000000000e+00,1.014262245821043287e-09,0.000000000000000000e+00 +2.842543250900027019e+01,1.543400000000000034e+02,0.000000000000000000e+00,8.741731673648017065e+00,0.000000000000000000e+00,1.000000009943623480e+00,0.000000000000000000e+00,1.442785702692755182e-09,0.000000000000000000e+00 +2.842657644710925524e+01,1.543499999999999943e+02,0.000000000000000000e+00,8.742875611768376132e+00,0.000000000000000000e+00,1.000000009945273938e+00,0.000000000000000000e+00,-1.328825573189241345e-09,0.000000000000000000e+00 +2.842772023554272565e+01,1.543600000000000136e+02,0.000000000000000000e+00,8.744019400213220550e+00,0.000000000000000000e+00,1.000000009943754042e+00,0.000000000000000000e+00,-5.401426410898841092e-10,0.000000000000000000e+00 +2.842886387435941842e+01,1.543700000000000045e+02,0.000000000000000000e+00,8.745163039041285558e+00,0.000000000000000000e+00,1.000000009943136314e+00,0.000000000000000000e+00,-2.895248061565282608e-10,0.000000000000000000e+00 +2.843000736361803504e+01,1.543799999999999955e+02,0.000000000000000000e+00,8.746306528311272643e+00,0.000000000000000000e+00,1.000000009942805246e+00,0.000000000000000000e+00,7.541058499745439458e-10,0.000000000000000000e+00 +2.843115070337723793e+01,1.543900000000000148e+02,0.000000000000000000e+00,8.747449868081844215e+00,0.000000000000000000e+00,1.000000009943667445e+00,0.000000000000000000e+00,1.205212073062075117e-09,0.000000000000000000e+00 +2.843229389369565041e+01,1.544000000000000057e+02,0.000000000000000000e+00,8.748593058411625378e+00,0.000000000000000000e+00,1.000000009945045232e+00,0.000000000000000000e+00,-1.682272452138026528e-09,0.000000000000000000e+00 +2.843343693463186028e+01,1.544099999999999966e+02,0.000000000000000000e+00,8.749736099359202157e+00,0.000000000000000000e+00,1.000000009943122325e+00,0.000000000000000000e+00,2.208999637647626676e-10,0.000000000000000000e+00 +2.843457982624441271e+01,1.544200000000000159e+02,0.000000000000000000e+00,8.750878990983117944e+00,0.000000000000000000e+00,1.000000009943374790e+00,0.000000000000000000e+00,9.151932555691129214e-11,0.000000000000000000e+00 +2.843572256859181735e+01,1.544300000000000068e+02,0.000000000000000000e+00,8.752021733341884158e+00,0.000000000000000000e+00,1.000000009943479373e+00,0.000000000000000000e+00,6.218685465840596365e-10,0.000000000000000000e+00 +2.843686516173254475e+01,1.544399999999999977e+02,0.000000000000000000e+00,8.753164326493971359e+00,0.000000000000000000e+00,1.000000009944189916e+00,0.000000000000000000e+00,-9.362287070207355481e-10,0.000000000000000000e+00 +2.843800760572502639e+01,1.544500000000000171e+02,0.000000000000000000e+00,8.754306770497812806e+00,0.000000000000000000e+00,1.000000009943120327e+00,0.000000000000000000e+00,8.342989556759186449e-10,0.000000000000000000e+00 +2.843914990062765824e+01,1.544600000000000080e+02,0.000000000000000000e+00,8.755449065411800902e+00,0.000000000000000000e+00,1.000000009944073343e+00,0.000000000000000000e+00,-8.991463557601516222e-10,0.000000000000000000e+00 +2.844029204649879361e+01,1.544699999999999989e+02,0.000000000000000000e+00,8.756591211294294297e+00,0.000000000000000000e+00,1.000000009943046386e+00,0.000000000000000000e+00,6.447477320182110848e-10,0.000000000000000000e+00 +2.844143404339675385e+01,1.544799999999999898e+02,0.000000000000000000e+00,8.757733208203609010e+00,0.000000000000000000e+00,1.000000009943782686e+00,0.000000000000000000e+00,-1.370559302747299102e-09,0.000000000000000000e+00 +2.844257589137981768e+01,1.544900000000000091e+02,0.000000000000000000e+00,8.758875056198027309e+00,0.000000000000000000e+00,1.000000009942217716e+00,0.000000000000000000e+00,1.202118554085807282e-09,0.000000000000000000e+00 +2.844371759050622828e+01,1.545000000000000000e+02,0.000000000000000000e+00,8.760016755335788829e+00,0.000000000000000000e+00,1.000000009943590173e+00,0.000000000000000000e+00,1.616390115906982587e-10,0.000000000000000000e+00 +2.844485914083418976e+01,1.545099999999999909e+02,0.000000000000000000e+00,8.761158305675101232e+00,0.000000000000000000e+00,1.000000009943774693e+00,0.000000000000000000e+00,-4.312880711161803562e-10,0.000000000000000000e+00 +2.844600054242186715e+01,1.545200000000000102e+02,0.000000000000000000e+00,8.762299707274129545e+00,0.000000000000000000e+00,1.000000009943282420e+00,0.000000000000000000e+00,-6.035317510636317653e-10,0.000000000000000000e+00 +2.844714179532738996e+01,1.545300000000000011e+02,0.000000000000000000e+00,8.763440960191001494e+00,0.000000000000000000e+00,1.000000009942593637e+00,0.000000000000000000e+00,9.838342916951449370e-10,0.000000000000000000e+00 +2.844828289960885215e+01,1.545399999999999920e+02,0.000000000000000000e+00,8.764582064483807500e+00,0.000000000000000000e+00,1.000000009943716295e+00,0.000000000000000000e+00,2.123225824568882751e-10,0.000000000000000000e+00 +2.844942385532430151e+01,1.545500000000000114e+02,0.000000000000000000e+00,8.765723020210602456e+00,0.000000000000000000e+00,1.000000009943958545e+00,0.000000000000000000e+00,-1.582602801638186698e-09,0.000000000000000000e+00 +2.845056466253175387e+01,1.545600000000000023e+02,0.000000000000000000e+00,8.766863827429400402e+00,0.000000000000000000e+00,1.000000009942153101e+00,0.000000000000000000e+00,1.033857750242840057e-09,0.000000000000000000e+00 +2.845170532128918950e+01,1.545699999999999932e+02,0.000000000000000000e+00,8.768004486198176295e+00,0.000000000000000000e+00,1.000000009943332380e+00,0.000000000000000000e+00,-1.553616697510783363e-10,0.000000000000000000e+00 +2.845284583165454606e+01,1.545800000000000125e+02,0.000000000000000000e+00,8.769144996574873119e+00,0.000000000000000000e+00,1.000000009943155188e+00,0.000000000000000000e+00,2.842826350990382592e-10,0.000000000000000000e+00 +2.845398619368572568e+01,1.545900000000000034e+02,0.000000000000000000e+00,8.770285358617391225e+00,0.000000000000000000e+00,1.000000009943479373e+00,0.000000000000000000e+00,-4.044738475228087054e-10,0.000000000000000000e+00 +2.845512640744059141e+01,1.545999999999999943e+02,0.000000000000000000e+00,8.771425572383595437e+00,0.000000000000000000e+00,1.000000009943018187e+00,0.000000000000000000e+00,4.836009303283643074e-10,0.000000000000000000e+00 +2.845626647297697076e+01,1.546100000000000136e+02,0.000000000000000000e+00,8.772565637931311500e+00,0.000000000000000000e+00,1.000000009943569523e+00,0.000000000000000000e+00,-1.176921706411282157e-09,0.000000000000000000e+00 +2.845740639035265573e+01,1.546200000000000045e+02,0.000000000000000000e+00,8.773705555318329630e+00,0.000000000000000000e+00,1.000000009942227930e+00,0.000000000000000000e+00,1.422542038940975675e-09,0.000000000000000000e+00 +2.845854615962539214e+01,1.546299999999999955e+02,0.000000000000000000e+00,8.774845324602399188e+00,0.000000000000000000e+00,1.000000009943849300e+00,0.000000000000000000e+00,-1.315564449193904352e-09,0.000000000000000000e+00 +2.845968578085289735e+01,1.546400000000000148e+02,0.000000000000000000e+00,8.775984945841237561e+00,0.000000000000000000e+00,1.000000009942350054e+00,0.000000000000000000e+00,1.523852206119579928e-09,0.000000000000000000e+00 +2.846082525409284969e+01,1.546500000000000057e+02,0.000000000000000000e+00,8.777124419092517726e+00,0.000000000000000000e+00,1.000000009944086443e+00,0.000000000000000000e+00,-1.029610803417252859e-09,0.000000000000000000e+00 +2.846196457940288482e+01,1.546599999999999966e+02,0.000000000000000000e+00,8.778263744413882463e+00,0.000000000000000000e+00,1.000000009942913382e+00,0.000000000000000000e+00,-7.927258549263185287e-10,0.000000000000000000e+00 +2.846310375684060645e+01,1.546700000000000159e+02,0.000000000000000000e+00,8.779402921862930143e+00,0.000000000000000000e+00,1.000000009942010326e+00,0.000000000000000000e+00,8.411743214828635371e-10,0.000000000000000000e+00 +2.846424278646357919e+01,1.546800000000000068e+02,0.000000000000000000e+00,8.780541951497225384e+00,0.000000000000000000e+00,1.000000009942968449e+00,0.000000000000000000e+00,-2.614510109956786611e-10,0.000000000000000000e+00 +2.846538166832932859e+01,1.546899999999999977e+02,0.000000000000000000e+00,8.781680833374297279e+00,0.000000000000000000e+00,1.000000009942670687e+00,0.000000000000000000e+00,1.350322959472838518e-09,0.000000000000000000e+00 +2.846652040249534465e+01,1.547000000000000171e+02,0.000000000000000000e+00,8.782819567551634066e+00,0.000000000000000000e+00,1.000000009944208346e+00,0.000000000000000000e+00,-1.198384197267472174e-09,0.000000000000000000e+00 +2.846765898901907832e+01,1.547100000000000080e+02,0.000000000000000000e+00,8.783958154086690229e+00,0.000000000000000000e+00,1.000000009942843882e+00,0.000000000000000000e+00,-1.084244324957415402e-09,0.000000000000000000e+00 +2.846879742795794499e+01,1.547199999999999989e+02,0.000000000000000000e+00,8.785096593036877621e+00,0.000000000000000000e+00,1.000000009941609536e+00,0.000000000000000000e+00,1.669199701717451214e-09,0.000000000000000000e+00 +2.846993571936932454e+01,1.547299999999999898e+02,0.000000000000000000e+00,8.786234884459574346e+00,0.000000000000000000e+00,1.000000009943509571e+00,0.000000000000000000e+00,-1.189875899150626303e-09,0.000000000000000000e+00 +2.847107386331055778e+01,1.547400000000000091e+02,0.000000000000000000e+00,8.787373028412124754e+00,0.000000000000000000e+00,1.000000009942155321e+00,0.000000000000000000e+00,1.281345666849951751e-09,0.000000000000000000e+00 +2.847221185983894642e+01,1.547500000000000000e+02,0.000000000000000000e+00,8.788511024951828787e+00,0.000000000000000000e+00,1.000000009943613488e+00,0.000000000000000000e+00,-1.915339791434038588e-09,0.000000000000000000e+00 +2.847334970901176021e+01,1.547599999999999909e+02,0.000000000000000000e+00,8.789648874135956191e+00,0.000000000000000000e+00,1.000000009941434120e+00,0.000000000000000000e+00,1.541057670588264188e-09,0.000000000000000000e+00 +2.847448741088622626e+01,1.547700000000000102e+02,0.000000000000000000e+00,8.790786576021732301e+00,0.000000000000000000e+00,1.000000009943187385e+00,0.000000000000000000e+00,-7.237818483194175911e-10,0.000000000000000000e+00 +2.847562496551953615e+01,1.547800000000000011e+02,0.000000000000000000e+00,8.791924130666354031e+00,0.000000000000000000e+00,1.000000009942364043e+00,0.000000000000000000e+00,8.702904569115733061e-10,0.000000000000000000e+00 +2.847676237296884594e+01,1.547899999999999920e+02,0.000000000000000000e+00,8.793061538126973886e+00,0.000000000000000000e+00,1.000000009943353918e+00,0.000000000000000000e+00,-5.666015342163816146e-10,0.000000000000000000e+00 +2.847789963329127616e+01,1.548000000000000114e+02,0.000000000000000000e+00,8.794198798460712396e+00,0.000000000000000000e+00,1.000000009942709545e+00,0.000000000000000000e+00,-9.412035197571418213e-10,0.000000000000000000e+00 +2.847903674654390827e+01,1.548100000000000023e+02,0.000000000000000000e+00,8.795335911724649236e+00,0.000000000000000000e+00,1.000000009941639290e+00,0.000000000000000000e+00,1.095413518311961988e-09,0.000000000000000000e+00 +2.848017371278378462e+01,1.548199999999999932e+02,0.000000000000000000e+00,8.796472877975828553e+00,0.000000000000000000e+00,1.000000009942884738e+00,0.000000000000000000e+00,2.246190746662480207e-11,0.000000000000000000e+00 +2.848131053206791208e+01,1.548300000000000125e+02,0.000000000000000000e+00,8.797609697271260742e+00,0.000000000000000000e+00,1.000000009942910273e+00,0.000000000000000000e+00,-6.524562310180838908e-11,0.000000000000000000e+00 +2.848244720445326550e+01,1.548400000000000034e+02,0.000000000000000000e+00,8.798746369667915346e+00,0.000000000000000000e+00,1.000000009942836110e+00,0.000000000000000000e+00,-5.671632210801016382e-10,0.000000000000000000e+00 +2.848358372999677712e+01,1.548499999999999943e+02,0.000000000000000000e+00,8.799882895222726376e+00,0.000000000000000000e+00,1.000000009942191515e+00,0.000000000000000000e+00,-1.336513100265689301e-10,0.000000000000000000e+00 +2.848472010875534366e+01,1.548600000000000136e+02,0.000000000000000000e+00,8.801019273992590541e+00,0.000000000000000000e+00,1.000000009942039636e+00,0.000000000000000000e+00,1.209856888568519694e-09,0.000000000000000000e+00 +2.848585634078582629e+01,1.548700000000000045e+02,0.000000000000000000e+00,8.802155506034369026e+00,0.000000000000000000e+00,1.000000009943414314e+00,0.000000000000000000e+00,-2.066462338252725710e-09,0.000000000000000000e+00 +2.848699242614504712e+01,1.548799999999999955e+02,0.000000000000000000e+00,8.803291591404887484e+00,0.000000000000000000e+00,1.000000009941066637e+00,0.000000000000000000e+00,1.020952033623683898e-09,0.000000000000000000e+00 +2.848812836488979627e+01,1.548900000000000148e+02,0.000000000000000000e+00,8.804427530160928939e+00,0.000000000000000000e+00,1.000000009942226376e+00,0.000000000000000000e+00,8.132698631306714322e-10,0.000000000000000000e+00 +2.848926415707682125e+01,1.549000000000000057e+02,0.000000000000000000e+00,8.805563322359247991e+00,0.000000000000000000e+00,1.000000009943150081e+00,0.000000000000000000e+00,-1.341090767949239438e-09,0.000000000000000000e+00 +2.849039980276284112e+01,1.549099999999999966e+02,0.000000000000000000e+00,8.806698968056558385e+00,0.000000000000000000e+00,1.000000009941627077e+00,0.000000000000000000e+00,1.419091830960593463e-09,0.000000000000000000e+00 +2.849153530200452877e+01,1.549200000000000159e+02,0.000000000000000000e+00,8.807834467309534787e+00,0.000000000000000000e+00,1.000000009943238455e+00,0.000000000000000000e+00,-5.734206589147817544e-10,0.000000000000000000e+00 +2.849267065485852513e+01,1.549300000000000068e+02,0.000000000000000000e+00,8.808969820174821663e+00,0.000000000000000000e+00,1.000000009942587420e+00,0.000000000000000000e+00,-4.571135130359795560e-10,0.000000000000000000e+00 +2.849380586138143912e+01,1.549399999999999977e+02,0.000000000000000000e+00,8.810105026709020848e+00,0.000000000000000000e+00,1.000000009942068502e+00,0.000000000000000000e+00,3.664030571176811730e-10,0.000000000000000000e+00 +2.849494092162983350e+01,1.549500000000000171e+02,0.000000000000000000e+00,8.811240086968700425e+00,0.000000000000000000e+00,1.000000009942484391e+00,0.000000000000000000e+00,-8.862892107767852990e-10,0.000000000000000000e+00 +2.849607583566024260e+01,1.549600000000000080e+02,0.000000000000000000e+00,8.812375001010392950e+00,0.000000000000000000e+00,1.000000009941478529e+00,0.000000000000000000e+00,-1.040985853192905905e-10,0.000000000000000000e+00 +2.849721060352916169e+01,1.549699999999999989e+02,0.000000000000000000e+00,8.813509768890591900e+00,0.000000000000000000e+00,1.000000009941360402e+00,0.000000000000000000e+00,1.309423544341091691e-09,0.000000000000000000e+00 +2.849834522529304692e+01,1.549799999999999898e+02,0.000000000000000000e+00,8.814644390665757001e+00,0.000000000000000000e+00,1.000000009942846102e+00,0.000000000000000000e+00,-8.108862850193128821e-10,0.000000000000000000e+00 +2.849947970100832251e+01,1.549900000000000091e+02,0.000000000000000000e+00,8.815778866392312452e+00,0.000000000000000000e+00,1.000000009941926171e+00,0.000000000000000000e+00,4.085294434777066316e-10,0.000000000000000000e+00 +2.850061403073137356e+01,1.550000000000000000e+02,0.000000000000000000e+00,8.816913196126641594e+00,0.000000000000000000e+00,1.000000009942389578e+00,0.000000000000000000e+00,-5.773398873504801344e-10,0.000000000000000000e+00 +2.850174821451854967e+01,1.550099999999999909e+02,0.000000000000000000e+00,8.818047379925095797e+00,0.000000000000000000e+00,1.000000009941734769e+00,0.000000000000000000e+00,3.465659728633645425e-10,0.000000000000000000e+00 +2.850288225242616846e+01,1.550200000000000102e+02,0.000000000000000000e+00,8.819181417843987347e+00,0.000000000000000000e+00,1.000000009942127788e+00,0.000000000000000000e+00,3.947835333833688456e-10,0.000000000000000000e+00 +2.850401614451050136e+01,1.550300000000000011e+02,0.000000000000000000e+00,8.820315309939594783e+00,0.000000000000000000e+00,1.000000009942575430e+00,0.000000000000000000e+00,-4.596607546242965258e-10,0.000000000000000000e+00 +2.850514989082779493e+01,1.550399999999999920e+02,0.000000000000000000e+00,8.821449056268159339e+00,0.000000000000000000e+00,1.000000009942054291e+00,0.000000000000000000e+00,-8.604811464293599747e-10,0.000000000000000000e+00 +2.850628349143424956e+01,1.550500000000000114e+02,0.000000000000000000e+00,8.822582656885884944e+00,0.000000000000000000e+00,1.000000009941078849e+00,0.000000000000000000e+00,5.504809334111312898e-10,0.000000000000000000e+00 +2.850741694638603718e+01,1.550600000000000023e+02,0.000000000000000000e+00,8.823716111848940002e+00,0.000000000000000000e+00,1.000000009941702794e+00,0.000000000000000000e+00,9.837437219849203651e-10,0.000000000000000000e+00 +2.850855025573929069e+01,1.550699999999999932e+02,0.000000000000000000e+00,8.824849421213459166e+00,0.000000000000000000e+00,1.000000009942817680e+00,0.000000000000000000e+00,-9.713292077541150858e-10,0.000000000000000000e+00 +2.850968341955010388e+01,1.550800000000000125e+02,0.000000000000000000e+00,8.825982585035539785e+00,0.000000000000000000e+00,1.000000009941717005e+00,0.000000000000000000e+00,1.940164198007728974e-10,0.000000000000000000e+00 +2.851081643787453856e+01,1.550900000000000034e+02,0.000000000000000000e+00,8.827115603371240127e+00,0.000000000000000000e+00,1.000000009941936829e+00,0.000000000000000000e+00,-1.079575378945403039e-09,0.000000000000000000e+00 +2.851194931076862105e+01,1.550999999999999943e+02,0.000000000000000000e+00,8.828248476276586487e+00,0.000000000000000000e+00,1.000000009940713808e+00,0.000000000000000000e+00,2.103364286086767698e-09,0.000000000000000000e+00 +2.851308203828834209e+01,1.551100000000000136e+02,0.000000000000000000e+00,8.829381203807566081e+00,0.000000000000000000e+00,1.000000009943096346e+00,0.000000000000000000e+00,-1.357657649333874264e-09,0.000000000000000000e+00 +2.851421462048964983e+01,1.551200000000000045e+02,0.000000000000000000e+00,8.830513786020135925e+00,0.000000000000000000e+00,1.000000009941558687e+00,0.000000000000000000e+00,-4.115651916349053514e-10,0.000000000000000000e+00 +2.851534705742846398e+01,1.551299999999999955e+02,0.000000000000000000e+00,8.831646222970208626e+00,0.000000000000000000e+00,1.000000009941092616e+00,0.000000000000000000e+00,7.638170549044467499e-10,0.000000000000000000e+00 +2.851647934916066518e+01,1.551400000000000148e+02,0.000000000000000000e+00,8.832778514713666596e+00,0.000000000000000000e+00,1.000000009941957479e+00,0.000000000000000000e+00,-6.289795505917511494e-10,0.000000000000000000e+00 +2.851761149574209853e+01,1.551500000000000057e+02,0.000000000000000000e+00,8.833910661306356715e+00,0.000000000000000000e+00,1.000000009941245382e+00,0.000000000000000000e+00,9.291730674345235606e-10,0.000000000000000000e+00 +2.851874349722857360e+01,1.551599999999999966e+02,0.000000000000000000e+00,8.835042662804086788e+00,0.000000000000000000e+00,1.000000009942297208e+00,0.000000000000000000e+00,-1.519197442973016014e-09,0.000000000000000000e+00 +2.851987535367586446e+01,1.551700000000000159e+02,0.000000000000000000e+00,8.836174519262632643e+00,0.000000000000000000e+00,1.000000009940577694e+00,0.000000000000000000e+00,1.708531265659263199e-09,0.000000000000000000e+00 +2.852100706513970962e+01,1.551800000000000068e+02,0.000000000000000000e+00,8.837306230737729251e+00,0.000000000000000000e+00,1.000000009942511259e+00,0.000000000000000000e+00,-5.082295281868702314e-10,0.000000000000000000e+00 +2.852213863167581209e+01,1.551899999999999977e+02,0.000000000000000000e+00,8.838437797285083164e+00,0.000000000000000000e+00,1.000000009941936163e+00,0.000000000000000000e+00,-1.259942609323388736e-09,0.000000000000000000e+00 +2.852327005333983934e+01,1.552000000000000171e+02,0.000000000000000000e+00,8.839569218960358299e+00,0.000000000000000000e+00,1.000000009940510637e+00,0.000000000000000000e+00,8.178898655099645754e-10,0.000000000000000000e+00 +2.852440133018741975e+01,1.552100000000000080e+02,0.000000000000000000e+00,8.840700495819184823e+00,0.000000000000000000e+00,1.000000009941435897e+00,0.000000000000000000e+00,1.487976625431862182e-10,0.000000000000000000e+00 +2.852553246227414974e+01,1.552199999999999989e+02,0.000000000000000000e+00,8.841831627917160930e+00,0.000000000000000000e+00,1.000000009941604207e+00,0.000000000000000000e+00,8.720894249238503289e-10,0.000000000000000000e+00 +2.852666344965559020e+01,1.552299999999999898e+02,0.000000000000000000e+00,8.842962615309845731e+00,0.000000000000000000e+00,1.000000009942590529e+00,0.000000000000000000e+00,-1.203056142351575582e-09,0.000000000000000000e+00 +2.852779429238726649e+01,1.552400000000000091e+02,0.000000000000000000e+00,8.844093458052764589e+00,0.000000000000000000e+00,1.000000009941230061e+00,0.000000000000000000e+00,-5.471100100548076731e-10,0.000000000000000000e+00 +2.852892499052466491e+01,1.552500000000000000e+02,0.000000000000000000e+00,8.845224156201403787e+00,0.000000000000000000e+00,1.000000009940611445e+00,0.000000000000000000e+00,1.429227762465626040e-09,0.000000000000000000e+00 +2.853005554412323974e+01,1.552599999999999909e+02,0.000000000000000000e+00,8.846354709811217631e+00,0.000000000000000000e+00,1.000000009942227264e+00,0.000000000000000000e+00,-8.597676918152540244e-10,0.000000000000000000e+00 +2.853118595323840978e+01,1.552700000000000102e+02,0.000000000000000000e+00,8.847485118937626680e+00,0.000000000000000000e+00,1.000000009941255374e+00,0.000000000000000000e+00,-4.889730944820536755e-10,0.000000000000000000e+00 +2.853231621792555828e+01,1.552800000000000011e+02,0.000000000000000000e+00,8.848615383636010634e+00,0.000000000000000000e+00,1.000000009940702705e+00,0.000000000000000000e+00,1.127591435483289696e-09,0.000000000000000000e+00 +2.853344633824002941e+01,1.552899999999999920e+02,0.000000000000000000e+00,8.849745503961717219e+00,0.000000000000000000e+00,1.000000009941977019e+00,0.000000000000000000e+00,-1.598165603938120784e-09,0.000000000000000000e+00 +2.853457631423713892e+01,1.553000000000000114e+02,0.000000000000000000e+00,8.850875479970060411e+00,0.000000000000000000e+00,1.000000009940171131e+00,0.000000000000000000e+00,1.045730356284317735e-09,0.000000000000000000e+00 +2.853570614597215993e+01,1.553100000000000023e+02,0.000000000000000000e+00,8.852005311716313329e+00,0.000000000000000000e+00,1.000000009941352630e+00,0.000000000000000000e+00,6.887252237909082237e-10,0.000000000000000000e+00 +2.853683583350033715e+01,1.553199999999999932e+02,0.000000000000000000e+00,8.853134999255720672e+00,0.000000000000000000e+00,1.000000009942130674e+00,0.000000000000000000e+00,-1.305481712289441229e-09,0.000000000000000000e+00 +2.853796537687687618e+01,1.553300000000000125e+02,0.000000000000000000e+00,8.854264542643488056e+00,0.000000000000000000e+00,1.000000009940656076e+00,0.000000000000000000e+00,6.084898975684892552e-10,0.000000000000000000e+00 +2.853909477615694357e+01,1.553400000000000034e+02,0.000000000000000000e+00,8.855393941934783797e+00,0.000000000000000000e+00,1.000000009941343304e+00,0.000000000000000000e+00,-5.558708754149684246e-10,0.000000000000000000e+00 +2.854022403139568098e+01,1.553499999999999943e+02,0.000000000000000000e+00,8.856523197184746010e+00,0.000000000000000000e+00,1.000000009940715584e+00,0.000000000000000000e+00,7.476797224836052817e-10,0.000000000000000000e+00 +2.854135314264818390e+01,1.553600000000000136e+02,0.000000000000000000e+00,8.857652308448473732e+00,0.000000000000000000e+00,1.000000009941559798e+00,0.000000000000000000e+00,-1.078393099423435458e-09,0.000000000000000000e+00 +2.854248210996951940e+01,1.553700000000000045e+02,0.000000000000000000e+00,8.858781275781034026e+00,0.000000000000000000e+00,1.000000009940342327e+00,0.000000000000000000e+00,9.093647132626551520e-10,0.000000000000000000e+00 +2.854361093341471900e+01,1.553799999999999955e+02,0.000000000000000000e+00,8.859910099237454872e+00,0.000000000000000000e+00,1.000000009941368839e+00,0.000000000000000000e+00,-2.827003256512354871e-10,0.000000000000000000e+00 +2.854473961303877871e+01,1.553900000000000148e+02,0.000000000000000000e+00,8.861038778872734056e+00,0.000000000000000000e+00,1.000000009941049761e+00,0.000000000000000000e+00,-4.975923466991970387e-10,0.000000000000000000e+00 +2.854586814889665547e+01,1.554000000000000057e+02,0.000000000000000000e+00,8.862167314741830282e+00,0.000000000000000000e+00,1.000000009940488210e+00,0.000000000000000000e+00,1.636813078942867857e-09,0.000000000000000000e+00 +2.854699654104327777e+01,1.554099999999999966e+02,0.000000000000000000e+00,8.863295706899668502e+00,0.000000000000000000e+00,1.000000009942335177e+00,0.000000000000000000e+00,-2.276046348066322100e-09,0.000000000000000000e+00 +2.854812478953353505e+01,1.554200000000000159e+02,0.000000000000000000e+00,8.864423955401141697e+00,0.000000000000000000e+00,1.000000009939767232e+00,0.000000000000000000e+00,1.693720011713458175e-09,0.000000000000000000e+00 +2.854925289442228120e+01,1.554300000000000068e+02,0.000000000000000000e+00,8.865552060301100212e+00,0.000000000000000000e+00,1.000000009941677925e+00,0.000000000000000000e+00,-4.340648350301440424e-10,0.000000000000000000e+00 +2.855038085576433815e+01,1.554399999999999977e+02,0.000000000000000000e+00,8.866680021654369526e+00,0.000000000000000000e+00,1.000000009941188317e+00,0.000000000000000000e+00,-3.096919981362927615e-10,0.000000000000000000e+00 +2.855150867361448874e+01,1.554500000000000171e+02,0.000000000000000000e+00,8.867807839515732482e+00,0.000000000000000000e+00,1.000000009940839041e+00,0.000000000000000000e+00,-7.490261971003297115e-10,0.000000000000000000e+00 +2.855263634802748740e+01,1.554600000000000080e+02,0.000000000000000000e+00,8.868935513939939952e+00,0.000000000000000000e+00,1.000000009939994383e+00,0.000000000000000000e+00,1.016749219450650194e-09,0.000000000000000000e+00 +2.855376387905804592e+01,1.554699999999999989e+02,0.000000000000000000e+00,8.870063044981707279e+00,0.000000000000000000e+00,1.000000009941140799e+00,0.000000000000000000e+00,-6.241502823366891398e-10,0.000000000000000000e+00 +2.855489126676084766e+01,1.554799999999999898e+02,0.000000000000000000e+00,8.871190432695717831e+00,0.000000000000000000e+00,1.000000009940437140e+00,0.000000000000000000e+00,-1.083389986163451094e-10,0.000000000000000000e+00 +2.855601851119054047e+01,1.554900000000000091e+02,0.000000000000000000e+00,8.872317677136615899e+00,0.000000000000000000e+00,1.000000009940315016e+00,0.000000000000000000e+00,1.144796213866447415e-09,0.000000000000000000e+00 +2.855714561240173310e+01,1.555000000000000000e+02,0.000000000000000000e+00,8.873444778359013796e+00,0.000000000000000000e+00,1.000000009941605317e+00,0.000000000000000000e+00,-1.085635597614279829e-09,0.000000000000000000e+00 +2.855827257044900591e+01,1.555099999999999909e+02,0.000000000000000000e+00,8.874571736417490087e+00,0.000000000000000000e+00,1.000000009940381851e+00,0.000000000000000000e+00,1.684820912703378443e-10,0.000000000000000000e+00 +2.855939938538690015e+01,1.555200000000000102e+02,0.000000000000000000e+00,8.875698551366584255e+00,0.000000000000000000e+00,1.000000009940571699e+00,0.000000000000000000e+00,6.887949419060170087e-10,0.000000000000000000e+00 +2.856052605726992155e+01,1.555300000000000011e+02,0.000000000000000000e+00,8.876825223260805586e+00,0.000000000000000000e+00,1.000000009941347745e+00,0.000000000000000000e+00,-9.506379694942803760e-10,0.000000000000000000e+00 +2.856165258615254388e+01,1.555399999999999920e+02,0.000000000000000000e+00,8.877951752154627840e+00,0.000000000000000000e+00,1.000000009940276824e+00,0.000000000000000000e+00,-5.750285861035886311e-10,0.000000000000000000e+00 +2.856277897208920535e+01,1.555500000000000114e+02,0.000000000000000000e+00,8.879078138102487472e+00,0.000000000000000000e+00,1.000000009939629120e+00,0.000000000000000000e+00,1.793520306099657050e-09,0.000000000000000000e+00 +2.856390521513431224e+01,1.555600000000000023e+02,0.000000000000000000e+00,8.880204381158788962e+00,0.000000000000000000e+00,1.000000009941649060e+00,0.000000000000000000e+00,-8.719306115675211523e-10,0.000000000000000000e+00 +2.856503131534223172e+01,1.555699999999999932e+02,0.000000000000000000e+00,8.881330481377904817e+00,0.000000000000000000e+00,1.000000009940667178e+00,0.000000000000000000e+00,-1.926694333033432552e-10,0.000000000000000000e+00 +2.856615727276730254e+01,1.555800000000000125e+02,0.000000000000000000e+00,8.882456438814166688e+00,0.000000000000000000e+00,1.000000009940450241e+00,0.000000000000000000e+00,-3.948547664502025192e-10,0.000000000000000000e+00 +2.856728308746382083e+01,1.555900000000000034e+02,0.000000000000000000e+00,8.883582253521876027e+00,0.000000000000000000e+00,1.000000009940005707e+00,0.000000000000000000e+00,-1.007973822530967215e-10,0.000000000000000000e+00 +2.856840875948605429e+01,1.555999999999999943e+02,0.000000000000000000e+00,8.884707925555298758e+00,0.000000000000000000e+00,1.000000009939892243e+00,0.000000000000000000e+00,6.656232130103040705e-10,0.000000000000000000e+00 +2.856953428888823510e+01,1.556100000000000136e+02,0.000000000000000000e+00,8.885833454968667056e+00,0.000000000000000000e+00,1.000000009940641421e+00,0.000000000000000000e+00,-9.245718761704140598e-10,0.000000000000000000e+00 +2.857065967572455989e+01,1.556200000000000045e+02,0.000000000000000000e+00,8.886958841816179344e+00,0.000000000000000000e+00,1.000000009939600920e+00,0.000000000000000000e+00,7.143350579358236726e-10,0.000000000000000000e+00 +2.857178492004919335e+01,1.556299999999999955e+02,0.000000000000000000e+00,8.888084086151996743e+00,0.000000000000000000e+00,1.000000009940404722e+00,0.000000000000000000e+00,-5.190439444153704899e-11,0.000000000000000000e+00 +2.857291002191626106e+01,1.556400000000000148e+02,0.000000000000000000e+00,8.889209188030250175e+00,0.000000000000000000e+00,1.000000009940346324e+00,0.000000000000000000e+00,9.616358190652401975e-10,0.000000000000000000e+00 +2.857403498137986020e+01,1.556500000000000057e+02,0.000000000000000000e+00,8.890334147505033258e+00,0.000000000000000000e+00,1.000000009941428125e+00,0.000000000000000000e+00,-1.884034019989667559e-09,0.000000000000000000e+00 +2.857515979849405241e+01,1.556599999999999966e+02,0.000000000000000000e+00,8.891458964630407635e+00,0.000000000000000000e+00,1.000000009939308931e+00,0.000000000000000000e+00,1.215181953446723615e-09,0.000000000000000000e+00 +2.857628447331286381e+01,1.556700000000000159e+02,0.000000000000000000e+00,8.892583639460395872e+00,0.000000000000000000e+00,1.000000009940675616e+00,0.000000000000000000e+00,-9.977402266646201043e-10,0.000000000000000000e+00 +2.857740900589028143e+01,1.556800000000000068e+02,0.000000000000000000e+00,8.893708172048993887e+00,0.000000000000000000e+00,1.000000009939553625e+00,0.000000000000000000e+00,1.284607346256432378e-09,0.000000000000000000e+00 +2.857853339628026745e+01,1.556899999999999977e+02,0.000000000000000000e+00,8.894832562450156743e+00,0.000000000000000000e+00,1.000000009940998025e+00,0.000000000000000000e+00,-3.910598172763026577e-10,0.000000000000000000e+00 +2.857965764453674495e+01,1.557000000000000171e+02,0.000000000000000000e+00,8.895956810717811081e+00,0.000000000000000000e+00,1.000000009940558376e+00,0.000000000000000000e+00,-4.280473399914773776e-10,0.000000000000000000e+00 +2.858078175071360505e+01,1.557100000000000080e+02,0.000000000000000000e+00,8.897080916905844461e+00,0.000000000000000000e+00,1.000000009940077206e+00,0.000000000000000000e+00,-2.554384620614248841e-10,0.000000000000000000e+00 +2.858190571486469977e+01,1.557199999999999989e+02,0.000000000000000000e+00,8.898204881068112471e+00,0.000000000000000000e+00,1.000000009939790102e+00,0.000000000000000000e+00,1.029390959813910894e-10,0.000000000000000000e+00 +2.858302953704385274e+01,1.557299999999999898e+02,0.000000000000000000e+00,8.899328703258436946e+00,0.000000000000000000e+00,1.000000009939905787e+00,0.000000000000000000e+00,6.246287494127126813e-10,0.000000000000000000e+00 +2.858415321730485203e+01,1.557400000000000091e+02,0.000000000000000000e+00,8.900452383530605971e+00,0.000000000000000000e+00,1.000000009940607670e+00,0.000000000000000000e+00,-1.530049472748683354e-09,0.000000000000000000e+00 +2.858527675570145021e+01,1.557500000000000000e+02,0.000000000000000000e+00,8.901575921938373881e+00,0.000000000000000000e+00,1.000000009938888601e+00,0.000000000000000000e+00,6.520628252121228076e-10,0.000000000000000000e+00 +2.858640015228736786e+01,1.557599999999999909e+02,0.000000000000000000e+00,8.902699318535457707e+00,0.000000000000000000e+00,1.000000009939621126e+00,0.000000000000000000e+00,1.518377278701318543e-09,0.000000000000000000e+00 +2.858752340711629003e+01,1.557700000000000102e+02,0.000000000000000000e+00,8.903822573375546057e+00,0.000000000000000000e+00,1.000000009941326651e+00,0.000000000000000000e+00,-1.772026119732151281e-09,0.000000000000000000e+00 +2.858864652024186981e+01,1.557800000000000011e+02,0.000000000000000000e+00,8.904945686512292014e+00,0.000000000000000000e+00,1.000000009939336465e+00,0.000000000000000000e+00,6.139501430939701688e-10,0.000000000000000000e+00 +2.858976949171772475e+01,1.557899999999999920e+02,0.000000000000000000e+00,8.906068657999309579e+00,0.000000000000000000e+00,1.000000009940025913e+00,0.000000000000000000e+00,2.032915742505479093e-10,0.000000000000000000e+00 +2.859089232159744043e+01,1.558000000000000114e+02,0.000000000000000000e+00,8.907191487890186110e+00,0.000000000000000000e+00,1.000000009940254175e+00,0.000000000000000000e+00,-1.620208693182609965e-09,0.000000000000000000e+00 +2.859201500993456690e+01,1.558100000000000023e+02,0.000000000000000000e+00,8.908314176238471660e+00,0.000000000000000000e+00,1.000000009938435186e+00,0.000000000000000000e+00,2.166748413723689535e-09,0.000000000000000000e+00 +2.859313755678261870e+01,1.558199999999999932e+02,0.000000000000000000e+00,8.909436723097680755e+00,0.000000000000000000e+00,1.000000009940867463e+00,0.000000000000000000e+00,-1.145035616396436607e-09,0.000000000000000000e+00 +2.859425996219508193e+01,1.558300000000000125e+02,0.000000000000000000e+00,8.910559128521301275e+00,0.000000000000000000e+00,1.000000009939582268e+00,0.000000000000000000e+00,-3.017275911564306202e-10,0.000000000000000000e+00 +2.859538222622540360e+01,1.558400000000000034e+02,0.000000000000000000e+00,8.911681392562778470e+00,0.000000000000000000e+00,1.000000009939243650e+00,0.000000000000000000e+00,4.438427706147843338e-10,0.000000000000000000e+00 +2.859650434892700233e+01,1.558499999999999943e+02,0.000000000000000000e+00,8.912803515275529165e+00,0.000000000000000000e+00,1.000000009939741696e+00,0.000000000000000000e+00,-3.423739088110148506e-10,0.000000000000000000e+00 +2.859762633035325763e+01,1.558600000000000136e+02,0.000000000000000000e+00,8.913925496712936436e+00,0.000000000000000000e+00,1.000000009939357559e+00,0.000000000000000000e+00,1.371647322217409748e-10,0.000000000000000000e+00 +2.859874817055751706e+01,1.558700000000000045e+02,0.000000000000000000e+00,8.915047336928347832e+00,0.000000000000000000e+00,1.000000009939511436e+00,0.000000000000000000e+00,4.485633479207526274e-10,0.000000000000000000e+00 +2.859986986959309974e+01,1.558799999999999955e+02,0.000000000000000000e+00,8.916169035975078927e+00,0.000000000000000000e+00,1.000000009940014589e+00,0.000000000000000000e+00,5.683969140309763488e-10,0.000000000000000000e+00 +2.860099142751328571e+01,1.558900000000000148e+02,0.000000000000000000e+00,8.917290593906411544e+00,0.000000000000000000e+00,1.000000009940652079e+00,0.000000000000000000e+00,-9.405172267896823065e-10,0.000000000000000000e+00 +2.860211284437131951e+01,1.559000000000000057e+02,0.000000000000000000e+00,8.918412010775593757e+00,0.000000000000000000e+00,1.000000009939597367e+00,0.000000000000000000e+00,-1.276491886003305382e-09,0.000000000000000000e+00 +2.860323412022041722e+01,1.559099999999999966e+02,0.000000000000000000e+00,8.919533286635838110e+00,0.000000000000000000e+00,1.000000009938166068e+00,0.000000000000000000e+00,2.365550101925482901e-09,0.000000000000000000e+00 +2.860435525511376298e+01,1.559200000000000159e+02,0.000000000000000000e+00,8.920654421540325174e+00,0.000000000000000000e+00,1.000000009940818169e+00,0.000000000000000000e+00,-1.345347940409122535e-09,0.000000000000000000e+00 +2.860547624910450182e+01,1.559300000000000068e+02,0.000000000000000000e+00,8.921775415542207099e+00,0.000000000000000000e+00,1.000000009939310042e+00,0.000000000000000000e+00,2.886363765873810820e-10,0.000000000000000000e+00 +2.860659710224574681e+01,1.559399999999999977e+02,0.000000000000000000e+00,8.922896268694593402e+00,0.000000000000000000e+00,1.000000009939633561e+00,0.000000000000000000e+00,-1.238498738578506232e-09,0.000000000000000000e+00 +2.860771781459058261e+01,1.559500000000000171e+02,0.000000000000000000e+00,8.924016981050566955e+00,0.000000000000000000e+00,1.000000009938245560e+00,0.000000000000000000e+00,1.121744033876820436e-09,0.000000000000000000e+00 +2.860883838619205122e+01,1.559600000000000080e+02,0.000000000000000000e+00,8.925137552663173324e+00,0.000000000000000000e+00,1.000000009939502554e+00,0.000000000000000000e+00,2.734854525660064400e-10,0.000000000000000000e+00 +2.860995881710316979e+01,1.559699999999999989e+02,0.000000000000000000e+00,8.926257983585429656e+00,0.000000000000000000e+00,1.000000009939808976e+00,0.000000000000000000e+00,-9.787251436620369861e-10,0.000000000000000000e+00 +2.861107910737691995e+01,1.559799999999999898e+02,0.000000000000000000e+00,8.927378273870315795e+00,0.000000000000000000e+00,1.000000009938712520e+00,0.000000000000000000e+00,1.589785497833949356e-09,0.000000000000000000e+00 +2.861219925706624778e+01,1.559900000000000091e+02,0.000000000000000000e+00,8.928498423570777831e+00,0.000000000000000000e+00,1.000000009940493317e+00,0.000000000000000000e+00,-1.954967808855544220e-09,0.000000000000000000e+00 +2.861331926622407096e+01,1.560000000000000000e+02,0.000000000000000000e+00,8.929618432739733436e+00,0.000000000000000000e+00,1.000000009938303736e+00,0.000000000000000000e+00,1.107379053940680438e-09,0.000000000000000000e+00 +2.861443913490326807e+01,1.560099999999999909e+02,0.000000000000000000e+00,8.930738301430059423e+00,0.000000000000000000e+00,1.000000009939543855e+00,0.000000000000000000e+00,-5.750764547706659024e-10,0.000000000000000000e+00 +2.861555886315668573e+01,1.560200000000000102e+02,0.000000000000000000e+00,8.931858029694607737e+00,0.000000000000000000e+00,1.000000009938899925e+00,0.000000000000000000e+00,5.592823902609021904e-11,0.000000000000000000e+00 +2.861667845103714214e+01,1.560300000000000011e+02,0.000000000000000000e+00,8.932977617586191244e+00,0.000000000000000000e+00,1.000000009938962542e+00,0.000000000000000000e+00,1.440035146764179177e-10,0.000000000000000000e+00 +2.861779789859741641e+01,1.560399999999999920e+02,0.000000000000000000e+00,8.934097065157592610e+00,0.000000000000000000e+00,1.000000009939123746e+00,0.000000000000000000e+00,1.083930864265638384e-09,0.000000000000000000e+00 +2.861891720589025923e+01,1.560500000000000114e+02,0.000000000000000000e+00,8.935216372461560752e+00,0.000000000000000000e+00,1.000000009940336998e+00,0.000000000000000000e+00,-1.402104523688626468e-09,0.000000000000000000e+00 +2.862003637296838576e+01,1.560600000000000023e+02,0.000000000000000000e+00,8.936335539550812612e+00,0.000000000000000000e+00,1.000000009938767809e+00,0.000000000000000000e+00,-2.462472982097131688e-10,0.000000000000000000e+00 +2.862115539988447921e+01,1.560699999999999932e+02,0.000000000000000000e+00,8.937454566478027829e+00,0.000000000000000000e+00,1.000000009938492251e+00,0.000000000000000000e+00,2.734659697047164514e-10,0.000000000000000000e+00 +2.862227428669118723e+01,1.560800000000000125e+02,0.000000000000000000e+00,8.938573453295857618e+00,0.000000000000000000e+00,1.000000009938798229e+00,0.000000000000000000e+00,1.349638167500707043e-10,0.000000000000000000e+00 +2.862339303344112906e+01,1.560900000000000034e+02,0.000000000000000000e+00,8.939692200056919447e+00,0.000000000000000000e+00,1.000000009938949219e+00,0.000000000000000000e+00,7.330643491079192007e-10,0.000000000000000000e+00 +2.862451164018688843e+01,1.560999999999999943e+02,0.000000000000000000e+00,8.940810806813797029e+00,0.000000000000000000e+00,1.000000009939769230e+00,0.000000000000000000e+00,-7.946990989643605450e-10,0.000000000000000000e+00 +2.862563010698101706e+01,1.561100000000000136e+02,0.000000000000000000e+00,8.941929273619042107e+00,0.000000000000000000e+00,1.000000009938880385e+00,0.000000000000000000e+00,-2.108608596303667579e-10,0.000000000000000000e+00 +2.862674843387603119e+01,1.561200000000000045e+02,0.000000000000000000e+00,8.943047600525170893e+00,0.000000000000000000e+00,1.000000009938644574e+00,0.000000000000000000e+00,-3.792792950153128915e-10,0.000000000000000000e+00 +2.862786662092441503e+01,1.561299999999999955e+02,0.000000000000000000e+00,8.944165787584669403e+00,0.000000000000000000e+00,1.000000009938220469e+00,0.000000000000000000e+00,1.519292875396487850e-09,0.000000000000000000e+00 +2.862898466817862442e+01,1.561400000000000148e+02,0.000000000000000000e+00,8.945283834849989901e+00,0.000000000000000000e+00,1.000000009939919110e+00,0.000000000000000000e+00,-1.644020792858155598e-09,0.000000000000000000e+00 +2.863010257569107608e+01,1.561500000000000057e+02,0.000000000000000000e+00,8.946401742373554455e+00,0.000000000000000000e+00,1.000000009938081247e+00,0.000000000000000000e+00,1.478552128919260823e-09,0.000000000000000000e+00 +2.863122034351415834e+01,1.561599999999999966e+02,0.000000000000000000e+00,8.947519510207746052e+00,0.000000000000000000e+00,1.000000009939733925e+00,0.000000000000000000e+00,-1.930722128844461259e-09,0.000000000000000000e+00 +2.863233797170022754e+01,1.561700000000000159e+02,0.000000000000000000e+00,8.948637138404922808e+00,0.000000000000000000e+00,1.000000009937576095e+00,0.000000000000000000e+00,9.032886534574297486e-10,0.000000000000000000e+00 +2.863345546030160094e+01,1.561800000000000068e+02,0.000000000000000000e+00,8.949754627017401987e+00,0.000000000000000000e+00,1.000000009938585510e+00,0.000000000000000000e+00,1.424854471648079982e-09,0.000000000000000000e+00 +2.863457280937057092e+01,1.561899999999999977e+02,0.000000000000000000e+00,8.950871976097475979e+00,0.000000000000000000e+00,1.000000009940177570e+00,0.000000000000000000e+00,-1.813587208896227272e-09,0.000000000000000000e+00 +2.863569001895939081e+01,1.562000000000000171e+02,0.000000000000000000e+00,8.951989185697401652e+00,0.000000000000000000e+00,1.000000009938151413e+00,0.000000000000000000e+00,-2.963721684928716302e-10,0.000000000000000000e+00 +2.863680708912028550e+01,1.562100000000000080e+02,0.000000000000000000e+00,8.953106255869398566e+00,0.000000000000000000e+00,1.000000009937820344e+00,0.000000000000000000e+00,1.685218225655591249e-09,0.000000000000000000e+00 +2.863792401990544789e+01,1.562199999999999989e+02,0.000000000000000000e+00,8.954223186665659640e+00,0.000000000000000000e+00,1.000000009939702617e+00,0.000000000000000000e+00,-1.587408380795155097e-09,0.000000000000000000e+00 +2.863904081136703184e+01,1.562299999999999898e+02,0.000000000000000000e+00,8.955339978138345813e+00,0.000000000000000000e+00,1.000000009937929812e+00,0.000000000000000000e+00,1.254733989198907691e-09,0.000000000000000000e+00 +2.864015746355716630e+01,1.562400000000000091e+02,0.000000000000000000e+00,8.956456630339578950e+00,0.000000000000000000e+00,1.000000009939330914e+00,0.000000000000000000e+00,-1.205172121651228919e-09,0.000000000000000000e+00 +2.864127397652794471e+01,1.562500000000000000e+02,0.000000000000000000e+00,8.957573143321456044e+00,0.000000000000000000e+00,1.000000009937985324e+00,0.000000000000000000e+00,9.825565101097665887e-10,0.000000000000000000e+00 +2.864239035033142855e+01,1.562599999999999909e+02,0.000000000000000000e+00,8.958689517136035008e+00,0.000000000000000000e+00,1.000000009939082224e+00,0.000000000000000000e+00,-7.547133590971392356e-10,0.000000000000000000e+00 +2.864350658501964730e+01,1.562700000000000102e+02,0.000000000000000000e+00,8.959805751835347110e+00,0.000000000000000000e+00,1.000000009938239787e+00,0.000000000000000000e+00,-7.388915826371017611e-10,0.000000000000000000e+00 +2.864462268064459494e+01,1.562800000000000011e+02,0.000000000000000000e+00,8.960921847471386315e+00,0.000000000000000000e+00,1.000000009937415113e+00,0.000000000000000000e+00,1.008989218587772414e-09,0.000000000000000000e+00 +2.864573863725823699e+01,1.562899999999999920e+02,0.000000000000000000e+00,8.962037804096116389e+00,0.000000000000000000e+00,1.000000009938541101e+00,0.000000000000000000e+00,1.874553759208761785e-10,0.000000000000000000e+00 +2.864685445491250348e+01,1.563000000000000114e+02,0.000000000000000000e+00,8.963153621761470902e+00,0.000000000000000000e+00,1.000000009938750267e+00,0.000000000000000000e+00,-3.747584080788091341e-10,0.000000000000000000e+00 +2.864797013365929246e+01,1.563100000000000023e+02,0.000000000000000000e+00,8.964269300519347894e+00,0.000000000000000000e+00,1.000000009938332157e+00,0.000000000000000000e+00,-6.988531867451946963e-10,0.000000000000000000e+00 +2.864908567355046998e+01,1.563199999999999932e+02,0.000000000000000000e+00,8.965384840421613433e+00,0.000000000000000000e+00,1.000000009937552559e+00,0.000000000000000000e+00,2.047450721936712192e-09,0.000000000000000000e+00 +2.865020107463787369e+01,1.563300000000000125e+02,0.000000000000000000e+00,8.966500241520101611e+00,0.000000000000000000e+00,1.000000009939836287e+00,0.000000000000000000e+00,-2.152629199588037164e-09,0.000000000000000000e+00 +2.865131633697330571e+01,1.563400000000000034e+02,0.000000000000000000e+00,8.967615503866618099e+00,0.000000000000000000e+00,1.000000009937435541e+00,0.000000000000000000e+00,9.577723186459869050e-10,0.000000000000000000e+00 +2.865243146060853263e+01,1.563499999999999943e+02,0.000000000000000000e+00,8.968730627512927711e+00,0.000000000000000000e+00,1.000000009938503576e+00,0.000000000000000000e+00,-6.850616376096067457e-11,0.000000000000000000e+00 +2.865354644559529618e+01,1.563600000000000136e+02,0.000000000000000000e+00,8.969845612510772170e+00,0.000000000000000000e+00,1.000000009938427192e+00,0.000000000000000000e+00,-9.709565898183840530e-10,0.000000000000000000e+00 +2.865466129198529899e+01,1.563700000000000045e+02,0.000000000000000000e+00,8.970960458911855895e+00,0.000000000000000000e+00,1.000000009937344725e+00,0.000000000000000000e+00,1.088801712532387979e-09,0.000000000000000000e+00 +2.865577599983021884e+01,1.563799999999999955e+02,0.000000000000000000e+00,8.972075166767851329e+00,0.000000000000000000e+00,1.000000009938558421e+00,0.000000000000000000e+00,-1.059651651137154620e-09,0.000000000000000000e+00 +2.865689056918169442e+01,1.563900000000000148e+02,0.000000000000000000e+00,8.973189736130402494e+00,0.000000000000000000e+00,1.000000009937377365e+00,0.000000000000000000e+00,1.139281977895337520e-09,0.000000000000000000e+00 +2.865800500009133245e+01,1.564000000000000057e+02,0.000000000000000000e+00,8.974304167051116110e+00,0.000000000000000000e+00,1.000000009938647016e+00,0.000000000000000000e+00,-9.166400786949664485e-10,0.000000000000000000e+00 +2.865911929261071478e+01,1.564099999999999966e+02,0.000000000000000000e+00,8.975418459581572250e+00,0.000000000000000000e+00,1.000000009937625611e+00,0.000000000000000000e+00,1.332481854205145012e-09,0.000000000000000000e+00 +2.866023344679138418e+01,1.564200000000000159e+02,0.000000000000000000e+00,8.976532613773313685e+00,0.000000000000000000e+00,1.000000009939110202e+00,0.000000000000000000e+00,-2.152446569783928191e-09,0.000000000000000000e+00 +2.866134746268485500e+01,1.564300000000000068e+02,0.000000000000000000e+00,8.977646629677856538e+00,0.000000000000000000e+00,1.000000009936712342e+00,0.000000000000000000e+00,1.488500153885675783e-09,0.000000000000000000e+00 +2.866246134034260962e+01,1.564399999999999977e+02,0.000000000000000000e+00,8.978760507346677855e+00,0.000000000000000000e+00,1.000000009938370349e+00,0.000000000000000000e+00,-6.513369971706061966e-10,0.000000000000000000e+00 +2.866357507981609487e+01,1.564500000000000171e+02,0.000000000000000000e+00,8.979874246831231588e+00,0.000000000000000000e+00,1.000000009937644929e+00,0.000000000000000000e+00,-3.389685470003976605e-12,0.000000000000000000e+00 +2.866468868115672919e+01,1.564600000000000080e+02,0.000000000000000000e+00,8.980987848182932609e+00,0.000000000000000000e+00,1.000000009937641154e+00,0.000000000000000000e+00,5.458070382430665670e-10,0.000000000000000000e+00 +2.866580214441589902e+01,1.564699999999999989e+02,0.000000000000000000e+00,8.982101311453167369e+00,0.000000000000000000e+00,1.000000009938248891e+00,0.000000000000000000e+00,-4.583193561051718694e-10,0.000000000000000000e+00 +2.866691546964495885e+01,1.564799999999999898e+02,0.000000000000000000e+00,8.983214636693290345e+00,0.000000000000000000e+00,1.000000009937738632e+00,0.000000000000000000e+00,-1.729382657081464785e-10,0.000000000000000000e+00 +2.866802865689522761e+01,1.564900000000000091e+02,0.000000000000000000e+00,8.984327823954622261e+00,0.000000000000000000e+00,1.000000009937546119e+00,0.000000000000000000e+00,1.380685185505602229e-09,0.000000000000000000e+00 +2.866914170621799940e+01,1.565000000000000000e+02,0.000000000000000000e+00,8.985440873288453645e+00,0.000000000000000000e+00,1.000000009939082890e+00,0.000000000000000000e+00,-1.554834943585368435e-09,0.000000000000000000e+00 +2.867025461766452921e+01,1.565099999999999909e+02,0.000000000000000000e+00,8.986553784746044826e+00,0.000000000000000000e+00,1.000000009937352496e+00,0.000000000000000000e+00,-3.990831569542960610e-10,0.000000000000000000e+00 +2.867136739128604361e+01,1.565200000000000102e+02,0.000000000000000000e+00,8.987666558378618831e+00,0.000000000000000000e+00,1.000000009936908407e+00,0.000000000000000000e+00,5.256575999983254582e-10,0.000000000000000000e+00 +2.867248002713374078e+01,1.565300000000000011e+02,0.000000000000000000e+00,8.988779194237372039e+00,0.000000000000000000e+00,1.000000009937493273e+00,0.000000000000000000e+00,1.195949227025712951e-09,0.000000000000000000e+00 +2.867359252525878333e+01,1.565399999999999920e+02,0.000000000000000000e+00,8.989891692373468857e+00,0.000000000000000000e+00,1.000000009938823764e+00,0.000000000000000000e+00,-1.281333145660596787e-09,0.000000000000000000e+00 +2.867470488571230192e+01,1.565500000000000114e+02,0.000000000000000000e+00,8.991004052838041716e+00,0.000000000000000000e+00,1.000000009937398460e+00,0.000000000000000000e+00,2.489515716661347634e-10,0.000000000000000000e+00 +2.867581710854539523e+01,1.565600000000000023e+02,0.000000000000000000e+00,8.992116275682187521e+00,0.000000000000000000e+00,1.000000009937675349e+00,0.000000000000000000e+00,2.236249014578650882e-11,0.000000000000000000e+00 +2.867692919380913352e+01,1.565699999999999932e+02,0.000000000000000000e+00,8.993228360956976530e+00,0.000000000000000000e+00,1.000000009937700218e+00,0.000000000000000000e+00,-5.477490770756652082e-10,0.000000000000000000e+00 +2.867804114155455153e+01,1.565800000000000125e+02,0.000000000000000000e+00,8.994340308713445253e+00,0.000000000000000000e+00,1.000000009937091150e+00,0.000000000000000000e+00,-4.673318692558373117e-11,0.000000000000000000e+00 +2.867915295183265556e+01,1.565900000000000034e+02,0.000000000000000000e+00,8.995452119002598224e+00,0.000000000000000000e+00,1.000000009937039191e+00,0.000000000000000000e+00,6.711235815936851266e-11,0.000000000000000000e+00 +2.868026462469441995e+01,1.565999999999999943e+02,0.000000000000000000e+00,8.996563791875409777e+00,0.000000000000000000e+00,1.000000009937113798e+00,0.000000000000000000e+00,1.208970791664709065e-09,0.000000000000000000e+00 +2.868137616019078706e+01,1.566100000000000136e+02,0.000000000000000000e+00,8.997675327382822275e+00,0.000000000000000000e+00,1.000000009938457612e+00,0.000000000000000000e+00,-9.571868296529807995e-10,0.000000000000000000e+00 +2.868248755837266728e+01,1.566200000000000045e+02,0.000000000000000000e+00,8.998786725575747880e+00,0.000000000000000000e+00,1.000000009937393797e+00,0.000000000000000000e+00,-7.015441603973926225e-10,0.000000000000000000e+00 +2.868359881929093902e+01,1.566299999999999955e+02,0.000000000000000000e+00,8.999897986505063230e+00,0.000000000000000000e+00,1.000000009936614198e+00,0.000000000000000000e+00,5.167807558126756912e-10,0.000000000000000000e+00 +2.868470994299645227e+01,1.566400000000000148e+02,0.000000000000000000e+00,9.001009110221616538e+00,0.000000000000000000e+00,1.000000009937188405e+00,0.000000000000000000e+00,-2.014614515900212478e-10,0.000000000000000000e+00 +2.868582092954002150e+01,1.566500000000000057e+02,0.000000000000000000e+00,9.002120096776225822e+00,0.000000000000000000e+00,1.000000009936964585e+00,0.000000000000000000e+00,1.438788209830905092e-09,0.000000000000000000e+00 +2.868693177897243274e+01,1.566599999999999966e+02,0.000000000000000000e+00,9.003230946219675346e+00,0.000000000000000000e+00,1.000000009938562862e+00,0.000000000000000000e+00,-1.782814198012229426e-09,0.000000000000000000e+00 +2.868804249134444007e+01,1.566700000000000159e+02,0.000000000000000000e+00,9.004341658602720955e+00,0.000000000000000000e+00,1.000000009936582668e+00,0.000000000000000000e+00,1.905395308343303438e-10,0.000000000000000000e+00 +2.868915306670676557e+01,1.566800000000000068e+02,0.000000000000000000e+00,9.005452233976081189e+00,0.000000000000000000e+00,1.000000009936794276e+00,0.000000000000000000e+00,1.381731949673941580e-10,0.000000000000000000e+00 +2.869026350511009937e+01,1.566899999999999977e+02,0.000000000000000000e+00,9.006562672390449720e+00,0.000000000000000000e+00,1.000000009936947709e+00,0.000000000000000000e+00,9.179351204984734216e-10,0.000000000000000000e+00 +2.869137380660510317e+01,1.567000000000000171e+02,0.000000000000000000e+00,9.007672973896486468e+00,0.000000000000000000e+00,1.000000009937966894e+00,0.000000000000000000e+00,-3.736196488910134184e-10,0.000000000000000000e+00 +2.869248397124240668e+01,1.567100000000000080e+02,0.000000000000000000e+00,9.008783138544821156e+00,0.000000000000000000e+00,1.000000009937552115e+00,0.000000000000000000e+00,-8.767541469776751639e-10,0.000000000000000000e+00 +2.869359399907260411e+01,1.567199999999999989e+02,0.000000000000000000e+00,9.009893166386049757e+00,0.000000000000000000e+00,1.000000009936578893e+00,0.000000000000000000e+00,8.290478810458477850e-10,0.000000000000000000e+00 +2.869470389014626477e+01,1.567299999999999898e+02,0.000000000000000000e+00,9.011003057470738042e+00,0.000000000000000000e+00,1.000000009937499046e+00,0.000000000000000000e+00,-1.045041141826567256e-09,0.000000000000000000e+00 +2.869581364451392247e+01,1.567400000000000091e+02,0.000000000000000000e+00,9.012112811849423366e+00,0.000000000000000000e+00,1.000000009936339307e+00,0.000000000000000000e+00,6.893758594377633889e-10,0.000000000000000000e+00 +2.869692326222608258e+01,1.567500000000000000e+02,0.000000000000000000e+00,9.013222429572607552e+00,0.000000000000000000e+00,1.000000009937104251e+00,0.000000000000000000e+00,2.415614258065387656e-10,0.000000000000000000e+00 +2.869803274333321497e+01,1.567599999999999909e+02,0.000000000000000000e+00,9.014331910690765781e+00,0.000000000000000000e+00,1.000000009937372258e+00,0.000000000000000000e+00,-9.689667019786350478e-10,0.000000000000000000e+00 +2.869914208788576460e+01,1.567700000000000102e+02,0.000000000000000000e+00,9.015441255254339481e+00,0.000000000000000000e+00,1.000000009936297340e+00,0.000000000000000000e+00,1.366849586645383009e-09,0.000000000000000000e+00 +2.870025129593414093e+01,1.567800000000000011e+02,0.000000000000000000e+00,9.016550463313738106e+00,0.000000000000000000e+00,1.000000009937813461e+00,0.000000000000000000e+00,-1.434287522509949838e-09,0.000000000000000000e+00 +2.870136036752872499e+01,1.567899999999999920e+02,0.000000000000000000e+00,9.017659534919344466e+00,0.000000000000000000e+00,1.000000009936222733e+00,0.000000000000000000e+00,7.128268629655401863e-10,0.000000000000000000e+00 +2.870246930271986585e+01,1.568000000000000114e+02,0.000000000000000000e+00,9.018768470121504066e+00,0.000000000000000000e+00,1.000000009937013212e+00,0.000000000000000000e+00,-8.785269684713056157e-10,0.000000000000000000e+00 +2.870357810155788059e+01,1.568100000000000023e+02,0.000000000000000000e+00,9.019877268970537543e+00,0.000000000000000000e+00,1.000000009936039103e+00,0.000000000000000000e+00,9.935965635002393097e-10,0.000000000000000000e+00 +2.870468676409305786e+01,1.568199999999999932e+02,0.000000000000000000e+00,9.020985931516730005e+00,0.000000000000000000e+00,1.000000009937140666e+00,0.000000000000000000e+00,-9.184035864252362259e-10,0.000000000000000000e+00 +2.870579529037565081e+01,1.568300000000000125e+02,0.000000000000000000e+00,9.022094457810339918e+00,0.000000000000000000e+00,1.000000009936122591e+00,0.000000000000000000e+00,5.911760135867874120e-10,0.000000000000000000e+00 +2.870690368045588770e+01,1.568400000000000034e+02,0.000000000000000000e+00,9.023202847901590218e+00,0.000000000000000000e+00,1.000000009936777845e+00,0.000000000000000000e+00,-2.821003344221182146e-10,0.000000000000000000e+00 +2.870801193438396126e+01,1.568499999999999943e+02,0.000000000000000000e+00,9.024311101840677196e+00,0.000000000000000000e+00,1.000000009936465206e+00,0.000000000000000000e+00,7.786765219675667022e-10,0.000000000000000000e+00 +2.870912005221003582e+01,1.568600000000000136e+02,0.000000000000000000e+00,9.025419219677763394e+00,0.000000000000000000e+00,1.000000009937328072e+00,0.000000000000000000e+00,-5.879869922183934391e-10,0.000000000000000000e+00 +2.871022803398424372e+01,1.568700000000000045e+02,0.000000000000000000e+00,9.026527201462982930e+00,0.000000000000000000e+00,1.000000009936676593e+00,0.000000000000000000e+00,-6.333561665488712439e-11,0.000000000000000000e+00 +2.871133587975668888e+01,1.568799999999999955e+02,0.000000000000000000e+00,9.027635047246436173e+00,0.000000000000000000e+00,1.000000009936606427e+00,0.000000000000000000e+00,-5.624732666869802541e-10,0.000000000000000000e+00 +2.871244358957743970e+01,1.568900000000000148e+02,0.000000000000000000e+00,9.028742757078195069e+00,0.000000000000000000e+00,1.000000009935983369e+00,0.000000000000000000e+00,7.874790053331171793e-10,0.000000000000000000e+00 +2.871355116349653969e+01,1.569000000000000057e+02,0.000000000000000000e+00,9.029850331008299591e+00,0.000000000000000000e+00,1.000000009936855561e+00,0.000000000000000000e+00,-3.773465611746655644e-10,0.000000000000000000e+00 +2.871465860156399685e+01,1.569099999999999966e+02,0.000000000000000000e+00,9.030957769086761289e+00,0.000000000000000000e+00,1.000000009936437673e+00,0.000000000000000000e+00,2.646963593909595747e-10,0.000000000000000000e+00 +2.871576590382979077e+01,1.569200000000000159e+02,0.000000000000000000e+00,9.032065071363557962e+00,0.000000000000000000e+00,1.000000009936730772e+00,0.000000000000000000e+00,-2.039615182875373610e-10,0.000000000000000000e+00 +2.871687307034386905e+01,1.569300000000000068e+02,0.000000000000000000e+00,9.033172237888638989e+00,0.000000000000000000e+00,1.000000009936504952e+00,0.000000000000000000e+00,-3.566254011869940148e-10,0.000000000000000000e+00 +2.871798010115615085e+01,1.569399999999999977e+02,0.000000000000000000e+00,9.034279268711921773e+00,0.000000000000000000e+00,1.000000009936110157e+00,0.000000000000000000e+00,-2.142421853031780211e-10,0.000000000000000000e+00 +2.871908699631652340e+01,1.569500000000000171e+02,0.000000000000000000e+00,9.035386163883293520e+00,0.000000000000000000e+00,1.000000009935873013e+00,0.000000000000000000e+00,2.024315079864500938e-10,0.000000000000000000e+00 +2.872019375587484546e+01,1.569600000000000080e+02,0.000000000000000000e+00,9.036492923452611237e+00,0.000000000000000000e+00,1.000000009936097056e+00,0.000000000000000000e+00,8.716255552760486451e-10,0.000000000000000000e+00 +2.872130037988094031e+01,1.569699999999999989e+02,0.000000000000000000e+00,9.037599547469701733e+00,0.000000000000000000e+00,1.000000009937061618e+00,0.000000000000000000e+00,-1.129599699394455831e-09,0.000000000000000000e+00 +2.872240686838460633e+01,1.569799999999999898e+02,0.000000000000000000e+00,9.038706035984361620e+00,0.000000000000000000e+00,1.000000009935811729e+00,0.000000000000000000e+00,-1.906646115253961188e-11,0.000000000000000000e+00 +2.872351322143560637e+01,1.569900000000000091e+02,0.000000000000000000e+00,9.039812389046353758e+00,0.000000000000000000e+00,1.000000009935790635e+00,0.000000000000000000e+00,1.280620121993164257e-09,0.000000000000000000e+00 +2.872461943908367488e+01,1.570000000000000000e+02,0.000000000000000000e+00,9.040918606705414362e+00,0.000000000000000000e+00,1.000000009937207279e+00,0.000000000000000000e+00,-1.607395001188344326e-09,0.000000000000000000e+00 +2.872572552137851787e+01,1.570099999999999909e+02,0.000000000000000000e+00,9.042024689011249450e+00,0.000000000000000000e+00,1.000000009935429368e+00,0.000000000000000000e+00,1.458216332490296453e-09,0.000000000000000000e+00 +2.872683146836980939e+01,1.570200000000000102e+02,0.000000000000000000e+00,9.043130636013529511e+00,0.000000000000000000e+00,1.000000009937042078e+00,0.000000000000000000e+00,-1.160009103978735573e-09,0.000000000000000000e+00 +2.872793728010719505e+01,1.570300000000000011e+02,0.000000000000000000e+00,9.044236447761901942e+00,0.000000000000000000e+00,1.000000009935759326e+00,0.000000000000000000e+00,6.833985961958999734e-10,0.000000000000000000e+00 +2.872904295664028496e+01,1.570399999999999920e+02,0.000000000000000000e+00,9.045342124305976839e+00,0.000000000000000000e+00,1.000000009936514944e+00,0.000000000000000000e+00,-1.750381098138444556e-09,0.000000000000000000e+00 +2.873014849801866077e+01,1.570500000000000114e+02,0.000000000000000000e+00,9.046447665695339424e+00,0.000000000000000000e+00,1.000000009934579825e+00,0.000000000000000000e+00,1.691337944035415092e-09,0.000000000000000000e+00 +2.873125390429187931e+01,1.570600000000000023e+02,0.000000000000000000e+00,9.047553071979539396e+00,0.000000000000000000e+00,1.000000009936449441e+00,0.000000000000000000e+00,-6.412601428919792618e-10,0.000000000000000000e+00 +2.873235917550946183e+01,1.570699999999999932e+02,0.000000000000000000e+00,9.048658343208103361e+00,0.000000000000000000e+00,1.000000009935740675e+00,0.000000000000000000e+00,-4.761817667598579357e-11,0.000000000000000000e+00 +2.873346431172089765e+01,1.570800000000000125e+02,0.000000000000000000e+00,9.049763479430520619e+00,0.000000000000000000e+00,1.000000009935688050e+00,0.000000000000000000e+00,5.447622085149847837e-10,0.000000000000000000e+00 +2.873456931297565120e+01,1.570900000000000034e+02,0.000000000000000000e+00,9.050868480696253826e+00,0.000000000000000000e+00,1.000000009936290013e+00,0.000000000000000000e+00,-3.412464684209801191e-10,0.000000000000000000e+00 +2.873567417932315493e+01,1.570999999999999943e+02,0.000000000000000000e+00,9.051973347054735441e+00,0.000000000000000000e+00,1.000000009935912981e+00,0.000000000000000000e+00,1.835076905068116412e-10,0.000000000000000000e+00 +2.873677891081280933e+01,1.571100000000000136e+02,0.000000000000000000e+00,9.053078078555365948e+00,0.000000000000000000e+00,1.000000009936115708e+00,0.000000000000000000e+00,-8.131207002772024882e-10,0.000000000000000000e+00 +2.873788350749398646e+01,1.571200000000000045e+02,0.000000000000000000e+00,9.054182675247517409e+00,0.000000000000000000e+00,1.000000009935217538e+00,0.000000000000000000e+00,1.016072542563438644e-09,0.000000000000000000e+00 +2.873898796941602640e+01,1.571299999999999955e+02,0.000000000000000000e+00,9.055287137180529911e+00,0.000000000000000000e+00,1.000000009936339751e+00,0.000000000000000000e+00,-1.749289559726432780e-10,0.000000000000000000e+00 +2.874009229662824083e+01,1.571400000000000148e+02,0.000000000000000000e+00,9.056391464403716896e+00,0.000000000000000000e+00,1.000000009936146572e+00,0.000000000000000000e+00,-1.495523334521974278e-09,0.000000000000000000e+00 +2.874119648917990943e+01,1.571500000000000057e+02,0.000000000000000000e+00,9.057495656966358055e+00,0.000000000000000000e+00,1.000000009934495226e+00,0.000000000000000000e+00,1.405806463288136072e-09,0.000000000000000000e+00 +2.874230054712028704e+01,1.571599999999999966e+02,0.000000000000000000e+00,9.058599714917702883e+00,0.000000000000000000e+00,1.000000009936047318e+00,0.000000000000000000e+00,-2.355364851196168841e-10,0.000000000000000000e+00 +2.874340447049859293e+01,1.571700000000000159e+02,0.000000000000000000e+00,9.059703638306976003e+00,0.000000000000000000e+00,1.000000009935787304e+00,0.000000000000000000e+00,-6.113429619606347036e-10,0.000000000000000000e+00 +2.874450825936401799e+01,1.571800000000000068e+02,0.000000000000000000e+00,9.060807427183366514e+00,0.000000000000000000e+00,1.000000009935112510e+00,0.000000000000000000e+00,2.577248262407992010e-10,0.000000000000000000e+00 +2.874561191376572111e+01,1.571899999999999977e+02,0.000000000000000000e+00,9.061911081596035089e+00,0.000000000000000000e+00,1.000000009935396950e+00,0.000000000000000000e+00,8.937963485877627392e-10,0.000000000000000000e+00 +2.874671543375283633e+01,1.572000000000000171e+02,0.000000000000000000e+00,9.063014601594113984e+00,0.000000000000000000e+00,1.000000009936383272e+00,0.000000000000000000e+00,-1.643320529356840553e-09,0.000000000000000000e+00 +2.874781881937446570e+01,1.572100000000000080e+02,0.000000000000000000e+00,9.064117987226705253e+00,0.000000000000000000e+00,1.000000009934570055e+00,0.000000000000000000e+00,1.380468745413043109e-09,0.000000000000000000e+00 +2.874892207067967576e+01,1.572199999999999989e+02,0.000000000000000000e+00,9.065221238542877202e+00,0.000000000000000000e+00,1.000000009936093059e+00,0.000000000000000000e+00,-2.705315381624023773e-10,0.000000000000000000e+00 +2.875002518771751170e+01,1.572299999999999898e+02,0.000000000000000000e+00,9.066324355591675044e+00,0.000000000000000000e+00,1.000000009935794631e+00,0.000000000000000000e+00,-7.800872587430726277e-10,0.000000000000000000e+00 +2.875112817053698677e+01,1.572400000000000091e+02,0.000000000000000000e+00,9.067427338422108463e+00,0.000000000000000000e+00,1.000000009934934209e+00,0.000000000000000000e+00,-1.683180096394761428e-10,0.000000000000000000e+00 +2.875223101918707869e+01,1.572500000000000000e+02,0.000000000000000000e+00,9.068530187083158722e+00,0.000000000000000000e+00,1.000000009934748579e+00,0.000000000000000000e+00,1.545049246886899895e-09,0.000000000000000000e+00 +2.875333373371674384e+01,1.572599999999999909e+02,0.000000000000000000e+00,9.069632901623778665e+00,0.000000000000000000e+00,1.000000009936452328e+00,0.000000000000000000e+00,-1.504959860595056505e-09,0.000000000000000000e+00 +2.875443631417490309e+01,1.572700000000000102e+02,0.000000000000000000e+00,9.070735482092892710e+00,0.000000000000000000e+00,1.000000009934792988e+00,0.000000000000000000e+00,8.882215735368437915e-10,0.000000000000000000e+00 +2.875553876061044889e+01,1.572800000000000011e+02,0.000000000000000000e+00,9.071837928539389750e+00,0.000000000000000000e+00,1.000000009935772205e+00,0.000000000000000000e+00,-1.525670711338852024e-09,0.000000000000000000e+00 +2.875664107307224171e+01,1.572899999999999920e+02,0.000000000000000000e+00,9.072940241012135587e+00,0.000000000000000000e+00,1.000000009934090439e+00,0.000000000000000000e+00,1.465216711801914383e-09,0.000000000000000000e+00 +2.875774325160911715e+01,1.573000000000000114e+02,0.000000000000000000e+00,9.074042419559960493e+00,0.000000000000000000e+00,1.000000009935705370e+00,0.000000000000000000e+00,-3.945060957355117762e-10,0.000000000000000000e+00 +2.875884529626987884e+01,1.573100000000000023e+02,0.000000000000000000e+00,9.075144464231671648e+00,0.000000000000000000e+00,1.000000009935270606e+00,0.000000000000000000e+00,1.859925178423667644e-10,0.000000000000000000e+00 +2.875994720710329844e+01,1.573199999999999932e+02,0.000000000000000000e+00,9.076246375076040707e+00,0.000000000000000000e+00,1.000000009935475553e+00,0.000000000000000000e+00,-1.203152929711936161e-09,0.000000000000000000e+00 +2.876104898415812272e+01,1.573300000000000125e+02,0.000000000000000000e+00,9.077348152141812676e+00,0.000000000000000000e+00,1.000000009934149947e+00,0.000000000000000000e+00,1.272030129854484000e-09,0.000000000000000000e+00 +2.876215062748306650e+01,1.573400000000000034e+02,0.000000000000000000e+00,9.078449795477700590e+00,0.000000000000000000e+00,1.000000009935551271e+00,0.000000000000000000e+00,2.727405539922085045e-10,0.000000000000000000e+00 +2.876325213712681617e+01,1.573499999999999943e+02,0.000000000000000000e+00,9.079551305132392613e+00,0.000000000000000000e+00,1.000000009935851697e+00,0.000000000000000000e+00,-1.295523614758947745e-09,0.000000000000000000e+00 +2.876435351313802258e+01,1.573600000000000136e+02,0.000000000000000000e+00,9.080652681154543160e+00,0.000000000000000000e+00,1.000000009934424838e+00,0.000000000000000000e+00,9.406085856330724717e-10,0.000000000000000000e+00 +2.876545475556531528e+01,1.573700000000000045e+02,0.000000000000000000e+00,9.081753923592776445e+00,0.000000000000000000e+00,1.000000009935460676e+00,0.000000000000000000e+00,-1.827199998009601880e-09,0.000000000000000000e+00 +2.876655586445729185e+01,1.573799999999999955e+02,0.000000000000000000e+00,9.082855032495691816e+00,0.000000000000000000e+00,1.000000009933448730e+00,0.000000000000000000e+00,2.099891074321850249e-09,0.000000000000000000e+00 +2.876765683986251787e+01,1.573900000000000148e+02,0.000000000000000000e+00,9.083956007911853092e+00,0.000000000000000000e+00,1.000000009935760659e+00,0.000000000000000000e+00,-4.853006475577164330e-10,0.000000000000000000e+00 +2.876875768182953053e+01,1.574000000000000057e+02,0.000000000000000000e+00,9.085056849889802777e+00,0.000000000000000000e+00,1.000000009935226419e+00,0.000000000000000000e+00,-8.117566344435847595e-10,0.000000000000000000e+00 +2.876985839040683857e+01,1.574099999999999966e+02,0.000000000000000000e+00,9.086157558478046070e+00,0.000000000000000000e+00,1.000000009934332912e+00,0.000000000000000000e+00,-3.647698335768791437e-10,0.000000000000000000e+00 +2.877095896564291877e+01,1.574200000000000159e+02,0.000000000000000000e+00,9.087258133725061526e+00,0.000000000000000000e+00,1.000000009933931455e+00,0.000000000000000000e+00,8.353595298520700935e-10,0.000000000000000000e+00 +2.877205940758622305e+01,1.574300000000000068e+02,0.000000000000000000e+00,9.088358575679299278e+00,0.000000000000000000e+00,1.000000009934850720e+00,0.000000000000000000e+00,-1.646705127312643644e-10,0.000000000000000000e+00 +2.877315971628517488e+01,1.574399999999999977e+02,0.000000000000000000e+00,9.089458884389181037e+00,0.000000000000000000e+00,1.000000009934669531e+00,0.000000000000000000e+00,1.014581969812065302e-09,0.000000000000000000e+00 +2.877425989178816224e+01,1.574500000000000171e+02,0.000000000000000000e+00,9.090559059903096539e+00,0.000000000000000000e+00,1.000000009935785750e+00,0.000000000000000000e+00,-1.517313662564391807e-09,0.000000000000000000e+00 +2.877535993414354465e+01,1.574600000000000080e+02,0.000000000000000000e+00,9.091659102269408876e+00,0.000000000000000000e+00,1.000000009934116640e+00,0.000000000000000000e+00,1.026334459107440196e-09,0.000000000000000000e+00 +2.877645984339965679e+01,1.574699999999999989e+02,0.000000000000000000e+00,9.092759011536447389e+00,0.000000000000000000e+00,1.000000009935245515e+00,0.000000000000000000e+00,-1.651540431399215213e-09,0.000000000000000000e+00 +2.877755961960480136e+01,1.574799999999999898e+02,0.000000000000000000e+00,9.093858787752518325e+00,0.000000000000000000e+00,1.000000009933429190e+00,0.000000000000000000e+00,2.176743179748633225e-09,0.000000000000000000e+00 +2.877865926280725262e+01,1.574900000000000091e+02,0.000000000000000000e+00,9.094958430965892404e+00,0.000000000000000000e+00,1.000000009935822831e+00,0.000000000000000000e+00,-2.198412951226352096e-09,0.000000000000000000e+00 +2.877975877305525643e+01,1.575000000000000000e+02,0.000000000000000000e+00,9.096057941224819032e+00,0.000000000000000000e+00,1.000000009933405654e+00,0.000000000000000000e+00,1.363722095674146458e-09,0.000000000000000000e+00 +2.878085815039702666e+01,1.575099999999999909e+02,0.000000000000000000e+00,9.097157318577508534e+00,0.000000000000000000e+00,1.000000009934904899e+00,0.000000000000000000e+00,-3.819772162889660902e-10,0.000000000000000000e+00 +2.878195739488074878e+01,1.575200000000000102e+02,0.000000000000000000e+00,9.098256563072151692e+00,0.000000000000000000e+00,1.000000009934485012e+00,0.000000000000000000e+00,-1.078796830684798251e-10,0.000000000000000000e+00 +2.878305650655458336e+01,1.575300000000000011e+02,0.000000000000000000e+00,9.099355674756903767e+00,0.000000000000000000e+00,1.000000009934366441e+00,0.000000000000000000e+00,6.964535395256775352e-10,0.000000000000000000e+00 +2.878415548546665548e+01,1.575399999999999920e+02,0.000000000000000000e+00,9.100454653679893369e+00,0.000000000000000000e+00,1.000000009935131828e+00,0.000000000000000000e+00,-9.311417202652482459e-10,0.000000000000000000e+00 +2.878525433166506531e+01,1.575500000000000114e+02,0.000000000000000000e+00,9.101553499889220689e+00,0.000000000000000000e+00,1.000000009934108647e+00,0.000000000000000000e+00,-5.986056420919510184e-10,0.000000000000000000e+00 +2.878635304519788463e+01,1.575600000000000023e+02,0.000000000000000000e+00,9.102652213432953943e+00,0.000000000000000000e+00,1.000000009933450951e+00,0.000000000000000000e+00,1.675772620703344418e-09,0.000000000000000000e+00 +2.878745162611315322e+01,1.575699999999999932e+02,0.000000000000000000e+00,9.103750794359134701e+00,0.000000000000000000e+00,1.000000009935291923e+00,0.000000000000000000e+00,-1.488385350498029557e-09,0.000000000000000000e+00 +2.878855007445888248e+01,1.575800000000000125e+02,0.000000000000000000e+00,9.104849242715777891e+00,0.000000000000000000e+00,1.000000009933657008e+00,0.000000000000000000e+00,1.924641885656757475e-10,0.000000000000000000e+00 +2.878964839028305889e+01,1.575900000000000034e+02,0.000000000000000000e+00,9.105947558550862908e+00,0.000000000000000000e+00,1.000000009933868395e+00,0.000000000000000000e+00,8.105903451178877917e-10,0.000000000000000000e+00 +2.879074657363363343e+01,1.575999999999999943e+02,0.000000000000000000e+00,9.107045741912346060e+00,0.000000000000000000e+00,1.000000009934758571e+00,0.000000000000000000e+00,-1.128573285616170162e-09,0.000000000000000000e+00 +2.879184462455853222e+01,1.576100000000000136e+02,0.000000000000000000e+00,9.108143792848153453e+00,0.000000000000000000e+00,1.000000009933519340e+00,0.000000000000000000e+00,2.465322897711596994e-10,0.000000000000000000e+00 +2.879294254310565293e+01,1.576200000000000045e+02,0.000000000000000000e+00,9.109241711406179220e+00,0.000000000000000000e+00,1.000000009933790013e+00,0.000000000000000000e+00,4.979783939314421456e-10,0.000000000000000000e+00 +2.879404032932286128e+01,1.576299999999999955e+02,0.000000000000000000e+00,9.110339497634292627e+00,0.000000000000000000e+00,1.000000009934336687e+00,0.000000000000000000e+00,-3.968933203059795008e-10,0.000000000000000000e+00 +2.879513798325799812e+01,1.576400000000000148e+02,0.000000000000000000e+00,9.111437151580332738e+00,0.000000000000000000e+00,1.000000009933901035e+00,0.000000000000000000e+00,4.910174037783370010e-10,0.000000000000000000e+00 +2.879623550495887230e+01,1.576500000000000057e+02,0.000000000000000000e+00,9.112534673292108423e+00,0.000000000000000000e+00,1.000000009934439937e+00,0.000000000000000000e+00,1.928289870811145827e-10,0.000000000000000000e+00 +2.879733289447326428e+01,1.576599999999999966e+02,0.000000000000000000e+00,9.113632062817401902e+00,0.000000000000000000e+00,1.000000009934651546e+00,0.000000000000000000e+00,-1.313135343919349866e-09,0.000000000000000000e+00 +2.879843015184892607e+01,1.576700000000000159e+02,0.000000000000000000e+00,9.114729320203965202e+00,0.000000000000000000e+00,1.000000009933210698e+00,0.000000000000000000e+00,3.802863888827279055e-10,0.000000000000000000e+00 +2.879952727713358129e+01,1.576800000000000068e+02,0.000000000000000000e+00,9.115826445499520148e+00,0.000000000000000000e+00,1.000000009933627920e+00,0.000000000000000000e+00,8.264482293401829950e-10,0.000000000000000000e+00 +2.880062427037492867e+01,1.576899999999999977e+02,0.000000000000000000e+00,9.116923438751763697e+00,0.000000000000000000e+00,1.000000009934534528e+00,0.000000000000000000e+00,-1.471914819432297574e-09,0.000000000000000000e+00 +2.880172113162063141e+01,1.577000000000000171e+02,0.000000000000000000e+00,9.118020300008362611e+00,0.000000000000000000e+00,1.000000009932920042e+00,0.000000000000000000e+00,8.470956588454423971e-10,0.000000000000000000e+00 +2.880281786091832785e+01,1.577100000000000080e+02,0.000000000000000000e+00,9.119117029316951673e+00,0.000000000000000000e+00,1.000000009933849077e+00,0.000000000000000000e+00,3.810769088990918073e-10,0.000000000000000000e+00 +2.880391445831562436e+01,1.577199999999999989e+02,0.000000000000000000e+00,9.120213626725142575e+00,0.000000000000000000e+00,1.000000009934266965e+00,0.000000000000000000e+00,-1.414325811334124831e-09,0.000000000000000000e+00 +2.880501092386010598e+01,1.577299999999999898e+02,0.000000000000000000e+00,9.121310092280515036e+00,0.000000000000000000e+00,1.000000009932716205e+00,0.000000000000000000e+00,1.350495175585530500e-09,0.000000000000000000e+00 +2.880610725759931867e+01,1.577400000000000091e+02,0.000000000000000000e+00,9.122406426030618576e+00,0.000000000000000000e+00,1.000000009934196799e+00,0.000000000000000000e+00,-2.092425308151042080e-10,0.000000000000000000e+00 +2.880720345958079065e+01,1.577500000000000000e+02,0.000000000000000000e+00,9.123502628022979621e+00,0.000000000000000000e+00,1.000000009933967426e+00,0.000000000000000000e+00,-2.029876185644990917e-10,0.000000000000000000e+00 +2.880829952985201459e+01,1.577599999999999909e+02,0.000000000000000000e+00,9.124598698305090849e+00,0.000000000000000000e+00,1.000000009933744938e+00,0.000000000000000000e+00,-1.290605260622155865e-10,0.000000000000000000e+00 +2.880939546846045474e+01,1.577700000000000102e+02,0.000000000000000000e+00,9.125694636924418290e+00,0.000000000000000000e+00,1.000000009933603495e+00,0.000000000000000000e+00,-6.281564906999314108e-12,0.000000000000000000e+00 +2.881049127545355049e+01,1.577800000000000011e+02,0.000000000000000000e+00,9.126790443928399554e+00,0.000000000000000000e+00,1.000000009933596612e+00,0.000000000000000000e+00,1.446959968945921787e-10,0.000000000000000000e+00 +2.881158695087870925e+01,1.577899999999999920e+02,0.000000000000000000e+00,9.127886119364443829e+00,0.000000000000000000e+00,1.000000009933755152e+00,0.000000000000000000e+00,-1.175542762961473835e-09,0.000000000000000000e+00 +2.881268249478331356e+01,1.578000000000000114e+02,0.000000000000000000e+00,9.128981663279931880e+00,0.000000000000000000e+00,1.000000009932467293e+00,0.000000000000000000e+00,1.933189122620431490e-09,0.000000000000000000e+00 +2.881377790721471754e+01,1.578100000000000023e+02,0.000000000000000000e+00,9.130077075722214275e+00,0.000000000000000000e+00,1.000000009934584932e+00,0.000000000000000000e+00,-2.391992813076591204e-09,0.000000000000000000e+00 +2.881487318822023980e+01,1.578199999999999932e+02,0.000000000000000000e+00,9.131172356738618490e+00,0.000000000000000000e+00,1.000000009931965028e+00,0.000000000000000000e+00,2.116941523782232149e-09,0.000000000000000000e+00 +2.881596833784717759e+01,1.578300000000000125e+02,0.000000000000000000e+00,9.132267506376434696e+00,0.000000000000000000e+00,1.000000009934283396e+00,0.000000000000000000e+00,-8.508525985274744923e-10,0.000000000000000000e+00 +2.881706335614279979e+01,1.578400000000000034e+02,0.000000000000000000e+00,9.133362524682935302e+00,0.000000000000000000e+00,1.000000009933351697e+00,0.000000000000000000e+00,-9.470824788919542280e-10,0.000000000000000000e+00 +2.881815824315434327e+01,1.578499999999999943e+02,0.000000000000000000e+00,9.134457411705355412e+00,0.000000000000000000e+00,1.000000009932314748e+00,0.000000000000000000e+00,1.810219361064076065e-09,0.000000000000000000e+00 +2.881925299892902004e+01,1.578600000000000136e+02,0.000000000000000000e+00,9.135552167490905262e+00,0.000000000000000000e+00,1.000000009934296497e+00,0.000000000000000000e+00,-1.492164652817942315e-09,0.000000000000000000e+00 +2.882034762351401014e+01,1.578700000000000045e+02,0.000000000000000000e+00,9.136646792086770219e+00,0.000000000000000000e+00,1.000000009932663136e+00,0.000000000000000000e+00,9.853605369240057701e-10,0.000000000000000000e+00 +2.882144211695646874e+01,1.578799999999999955e+02,0.000000000000000000e+00,9.137741285540100122e+00,0.000000000000000000e+00,1.000000009933741607e+00,0.000000000000000000e+00,-1.155710513121830431e-09,0.000000000000000000e+00 +2.882253647930352258e+01,1.578900000000000148e+02,0.000000000000000000e+00,9.138835647898023495e+00,0.000000000000000000e+00,1.000000009932476841e+00,0.000000000000000000e+00,9.626663091927995715e-10,0.000000000000000000e+00 +2.882363071060226645e+01,1.579000000000000057e+02,0.000000000000000000e+00,9.139929879207635111e+00,0.000000000000000000e+00,1.000000009933530221e+00,0.000000000000000000e+00,-9.558813680825110080e-11,0.000000000000000000e+00 +2.882472481089977023e+01,1.579099999999999966e+02,0.000000000000000000e+00,9.141023979516006648e+00,0.000000000000000000e+00,1.000000009933425638e+00,0.000000000000000000e+00,-1.383859726641126471e-09,0.000000000000000000e+00 +2.882581878024307542e+01,1.579200000000000159e+02,0.000000000000000000e+00,9.142117948870177813e+00,0.000000000000000000e+00,1.000000009931911737e+00,0.000000000000000000e+00,1.532212274348234542e-09,0.000000000000000000e+00 +2.882691261867919508e+01,1.579300000000000068e+02,0.000000000000000000e+00,9.143211787317159889e+00,0.000000000000000000e+00,1.000000009933587730e+00,0.000000000000000000e+00,-2.744831547930104697e-10,0.000000000000000000e+00 +2.882800632625511028e+01,1.579399999999999977e+02,0.000000000000000000e+00,9.144305494903941067e+00,0.000000000000000000e+00,1.000000009933287526e+00,0.000000000000000000e+00,-8.858825867156449505e-10,0.000000000000000000e+00 +2.882909990301778080e+01,1.579500000000000171e+02,0.000000000000000000e+00,9.145399071677475789e+00,0.000000000000000000e+00,1.000000009932318745e+00,0.000000000000000000e+00,1.166020201938612675e-09,0.000000000000000000e+00 +2.883019334901413799e+01,1.579600000000000080e+02,0.000000000000000000e+00,9.146492517684691848e+00,0.000000000000000000e+00,1.000000009933593725e+00,0.000000000000000000e+00,-1.567877433140148310e-09,0.000000000000000000e+00 +2.883128666429107767e+01,1.579699999999999989e+02,0.000000000000000000e+00,9.147585832972492170e+00,0.000000000000000000e+00,1.000000009931879541e+00,0.000000000000000000e+00,1.294465968049911382e-09,0.000000000000000000e+00 +2.883237984889547434e+01,1.579799999999999898e+02,0.000000000000000000e+00,9.148679017587745932e+00,0.000000000000000000e+00,1.000000009933294631e+00,0.000000000000000000e+00,-6.689448995826117752e-10,0.000000000000000000e+00 +2.883347290287417053e+01,1.579900000000000091e+02,0.000000000000000000e+00,9.149772071577300991e+00,0.000000000000000000e+00,1.000000009932563438e+00,0.000000000000000000e+00,-4.713445457506923112e-11,0.000000000000000000e+00 +2.883456582627398390e+01,1.580000000000000000e+02,0.000000000000000000e+00,9.150864994987971457e+00,0.000000000000000000e+00,1.000000009932511924e+00,0.000000000000000000e+00,1.686477168103554038e-10,0.000000000000000000e+00 +2.883565861914170370e+01,1.580099999999999909e+02,0.000000000000000000e+00,9.151957787866546568e+00,0.000000000000000000e+00,1.000000009932696221e+00,0.000000000000000000e+00,-4.226857130698572671e-11,0.000000000000000000e+00 +2.883675128152409073e+01,1.580200000000000102e+02,0.000000000000000000e+00,9.153050450259787141e+00,0.000000000000000000e+00,1.000000009932650036e+00,0.000000000000000000e+00,7.887688013287926417e-10,0.000000000000000000e+00 +2.883784381346787740e+01,1.580300000000000011e+02,0.000000000000000000e+00,9.154142982214425572e+00,0.000000000000000000e+00,1.000000009933511791e+00,0.000000000000000000e+00,-1.822860845923623245e-09,0.000000000000000000e+00 +2.883893621501976767e+01,1.580399999999999920e+02,0.000000000000000000e+00,9.155235383777167613e+00,0.000000000000000000e+00,1.000000009931520495e+00,0.000000000000000000e+00,1.034527860444933756e-09,0.000000000000000000e+00 +2.884002848622644066e+01,1.580500000000000114e+02,0.000000000000000000e+00,9.156327654994687038e+00,0.000000000000000000e+00,1.000000009932650480e+00,0.000000000000000000e+00,4.096723010785628706e-10,0.000000000000000000e+00 +2.884112062713454350e+01,1.580600000000000023e+02,0.000000000000000000e+00,9.157419795913636307e+00,0.000000000000000000e+00,1.000000009933097900e+00,0.000000000000000000e+00,-7.401414605007346939e-10,0.000000000000000000e+00 +2.884221263779069488e+01,1.580699999999999932e+02,0.000000000000000000e+00,9.158511806580635906e+00,0.000000000000000000e+00,1.000000009932289657e+00,0.000000000000000000e+00,5.454110200197984397e-10,0.000000000000000000e+00 +2.884330451824149222e+01,1.580800000000000125e+02,0.000000000000000000e+00,9.159603687042277897e+00,0.000000000000000000e+00,1.000000009932885181e+00,0.000000000000000000e+00,-2.229089277827242204e-10,0.000000000000000000e+00 +2.884439626853350092e+01,1.580900000000000034e+02,0.000000000000000000e+00,9.160695437345129477e+00,0.000000000000000000e+00,1.000000009932641820e+00,0.000000000000000000e+00,-8.400762786794443125e-11,0.000000000000000000e+00 +2.884548788871325797e+01,1.580999999999999943e+02,0.000000000000000000e+00,9.161787057535727641e+00,0.000000000000000000e+00,1.000000009932550116e+00,0.000000000000000000e+00,-5.480472594188434570e-10,0.000000000000000000e+00 +2.884657937882727197e+01,1.581100000000000136e+02,0.000000000000000000e+00,9.162878547660582740e+00,0.000000000000000000e+00,1.000000009931951928e+00,0.000000000000000000e+00,-1.436404829446485198e-10,0.000000000000000000e+00 +2.884767073892202660e+01,1.581200000000000045e+02,0.000000000000000000e+00,9.163969907766176703e+00,0.000000000000000000e+00,1.000000009931795164e+00,0.000000000000000000e+00,1.111209783440061137e-09,0.000000000000000000e+00 +2.884876196904397716e+01,1.581299999999999955e+02,0.000000000000000000e+00,9.165061137898964816e+00,0.000000000000000000e+00,1.000000009933007750e+00,0.000000000000000000e+00,-1.279233925740206238e-09,0.000000000000000000e+00 +2.884985306923955051e+01,1.581400000000000148e+02,0.000000000000000000e+00,9.166152238105375716e+00,0.000000000000000000e+00,1.000000009931611977e+00,0.000000000000000000e+00,1.255776800526357506e-10,0.000000000000000000e+00 +2.885094403955514508e+01,1.581500000000000057e+02,0.000000000000000000e+00,9.167243208431806067e+00,0.000000000000000000e+00,1.000000009931748979e+00,0.000000000000000000e+00,8.304990537589100014e-10,0.000000000000000000e+00 +2.885203488003713446e+01,1.581599999999999966e+02,0.000000000000000000e+00,9.168334048924629442e+00,0.000000000000000000e+00,1.000000009932654921e+00,0.000000000000000000e+00,-6.771001325561369116e-10,0.000000000000000000e+00 +2.885312559073186378e+01,1.581700000000000159e+02,0.000000000000000000e+00,9.169424759630190991e+00,0.000000000000000000e+00,1.000000009931916400e+00,0.000000000000000000e+00,6.209864959332751520e-11,0.000000000000000000e+00 +2.885421617168564623e+01,1.581800000000000068e+02,0.000000000000000000e+00,9.170515340594805664e+00,0.000000000000000000e+00,1.000000009931984124e+00,0.000000000000000000e+00,4.276153257098756629e-11,0.000000000000000000e+00 +2.885530662294477366e+01,1.581899999999999977e+02,0.000000000000000000e+00,9.171605791864763546e+00,0.000000000000000000e+00,1.000000009932030753e+00,0.000000000000000000e+00,7.392515272035347844e-10,0.000000000000000000e+00 +2.885639694455550597e+01,1.582000000000000171e+02,0.000000000000000000e+00,9.172696113486326297e+00,0.000000000000000000e+00,1.000000009932836775e+00,0.000000000000000000e+00,-8.560450518442902999e-10,0.000000000000000000e+00 +2.885748713656407816e+01,1.582100000000000080e+02,0.000000000000000000e+00,9.173786305505728933e+00,0.000000000000000000e+00,1.000000009931903522e+00,0.000000000000000000e+00,-2.796786934813192334e-10,0.000000000000000000e+00 +2.885857719901670038e+01,1.582199999999999989e+02,0.000000000000000000e+00,9.174876367969176272e+00,0.000000000000000000e+00,1.000000009931598655e+00,0.000000000000000000e+00,9.560728829711560350e-10,0.000000000000000000e+00 +2.885966713195954725e+01,1.582299999999999898e+02,0.000000000000000000e+00,9.175966300922848262e+00,0.000000000000000000e+00,1.000000009932640710e+00,0.000000000000000000e+00,-1.655243724945014939e-09,0.000000000000000000e+00 +2.886075693543877208e+01,1.582400000000000091e+02,0.000000000000000000e+00,9.177056104412898208e+00,0.000000000000000000e+00,1.000000009930836820e+00,0.000000000000000000e+00,8.409653094545895052e-10,0.000000000000000000e+00 +2.886184660950049974e+01,1.582500000000000000e+02,0.000000000000000000e+00,9.178145778485447437e+00,0.000000000000000000e+00,1.000000009931753198e+00,0.000000000000000000e+00,9.474465595222546513e-10,0.000000000000000000e+00 +2.886293615419082670e+01,1.582599999999999909e+02,0.000000000000000000e+00,9.179235323186595963e+00,0.000000000000000000e+00,1.000000009932785483e+00,0.000000000000000000e+00,-1.356625707574332161e-09,0.000000000000000000e+00 +2.886402556955582455e+01,1.582700000000000102e+02,0.000000000000000000e+00,9.180324738562413600e+00,0.000000000000000000e+00,1.000000009931307554e+00,0.000000000000000000e+00,-1.047758971943997375e-10,0.000000000000000000e+00 +2.886511485564153290e+01,1.582800000000000011e+02,0.000000000000000000e+00,9.181414024658939965e+00,0.000000000000000000e+00,1.000000009931193423e+00,0.000000000000000000e+00,1.693126605024464071e-09,0.000000000000000000e+00 +2.886620401249396650e+01,1.582899999999999920e+02,0.000000000000000000e+00,9.182503181522191582e+00,0.000000000000000000e+00,1.000000009933037504e+00,0.000000000000000000e+00,-1.974087466904924916e-09,0.000000000000000000e+00 +2.886729304015911524e+01,1.583000000000000114e+02,0.000000000000000000e+00,9.183592209198158329e+00,0.000000000000000000e+00,1.000000009930887668e+00,0.000000000000000000e+00,8.562462669208917678e-10,0.000000000000000000e+00 +2.886838193868294056e+01,1.583100000000000023e+02,0.000000000000000000e+00,9.184681107732796335e+00,0.000000000000000000e+00,1.000000009931820033e+00,0.000000000000000000e+00,-3.193714318496700606e-10,0.000000000000000000e+00 +2.886947070811137195e+01,1.583199999999999932e+02,0.000000000000000000e+00,9.185769877172042186e+00,0.000000000000000000e+00,1.000000009931472311e+00,0.000000000000000000e+00,4.715672287330221610e-10,0.000000000000000000e+00 +2.887055934849031757e+01,1.583300000000000125e+02,0.000000000000000000e+00,9.186858517561800497e+00,0.000000000000000000e+00,1.000000009931985678e+00,0.000000000000000000e+00,-1.285336182358529711e-09,0.000000000000000000e+00 +2.887164785986565718e+01,1.583400000000000034e+02,0.000000000000000000e+00,9.187947028947951011e+00,0.000000000000000000e+00,1.000000009930586575e+00,0.000000000000000000e+00,3.868094193145780153e-10,0.000000000000000000e+00 +2.887273624228324209e+01,1.583499999999999943e+02,0.000000000000000000e+00,9.189035411376343276e+00,0.000000000000000000e+00,1.000000009931007572e+00,0.000000000000000000e+00,9.724430765216594852e-10,0.000000000000000000e+00 +2.887382449578889521e+01,1.583600000000000136e+02,0.000000000000000000e+00,9.190123664892803745e+00,0.000000000000000000e+00,1.000000009932065836e+00,0.000000000000000000e+00,-1.049489517702532933e-09,0.000000000000000000e+00 +2.887491262042841456e+01,1.583700000000000045e+02,0.000000000000000000e+00,9.191211789543130450e+00,0.000000000000000000e+00,1.000000009930923861e+00,0.000000000000000000e+00,3.030675601028220725e-10,0.000000000000000000e+00 +2.887600061624756975e+01,1.583799999999999955e+02,0.000000000000000000e+00,9.192299785373091225e+00,0.000000000000000000e+00,1.000000009931253597e+00,0.000000000000000000e+00,5.110915837785828004e-10,0.000000000000000000e+00 +2.887708848329210554e+01,1.583900000000000148e+02,0.000000000000000000e+00,9.193387652428430812e+00,0.000000000000000000e+00,1.000000009931809597e+00,0.000000000000000000e+00,-4.456249868056986068e-10,0.000000000000000000e+00 +2.887817622160773823e+01,1.584000000000000057e+02,0.000000000000000000e+00,9.194475390754865529e+00,0.000000000000000000e+00,1.000000009931324874e+00,0.000000000000000000e+00,4.162789073835864541e-10,0.000000000000000000e+00 +2.887926383124015572e+01,1.584099999999999966e+02,0.000000000000000000e+00,9.195563000398083275e+00,0.000000000000000000e+00,1.000000009931777623e+00,0.000000000000000000e+00,-1.426827417256455743e-09,0.000000000000000000e+00 +2.888035131223501750e+01,1.584200000000000159e+02,0.000000000000000000e+00,9.196650481403747079e+00,0.000000000000000000e+00,1.000000009930225975e+00,0.000000000000000000e+00,1.517051294060954509e-09,0.000000000000000000e+00 +2.888143866463796172e+01,1.584300000000000068e+02,0.000000000000000000e+00,9.197737833817489772e+00,0.000000000000000000e+00,1.000000009931875544e+00,0.000000000000000000e+00,-1.287675234045588064e-09,0.000000000000000000e+00 +2.888252588849459812e+01,1.584399999999999977e+02,0.000000000000000000e+00,9.198825057684922868e+00,0.000000000000000000e+00,1.000000009930475553e+00,0.000000000000000000e+00,6.579051861255876846e-10,0.000000000000000000e+00 +2.888361298385050446e+01,1.584500000000000171e+02,0.000000000000000000e+00,9.199912153051624131e+00,0.000000000000000000e+00,1.000000009931190759e+00,0.000000000000000000e+00,-1.787442001948174123e-10,0.000000000000000000e+00 +2.888469995075123720e+01,1.584600000000000080e+02,0.000000000000000000e+00,9.200999119963150008e+00,0.000000000000000000e+00,1.000000009930996470e+00,0.000000000000000000e+00,6.925879207181368279e-10,0.000000000000000000e+00 +2.888578678924232079e+01,1.584699999999999989e+02,0.000000000000000000e+00,9.202085958465026749e+00,0.000000000000000000e+00,1.000000009931749201e+00,0.000000000000000000e+00,-1.257634864567696789e-09,0.000000000000000000e+00 +2.888687349936925841e+01,1.584799999999999898e+02,0.000000000000000000e+00,9.203172668602755735e+00,0.000000000000000000e+00,1.000000009930382516e+00,0.000000000000000000e+00,1.472148090200558935e-09,0.000000000000000000e+00 +2.888796008117752123e+01,1.584900000000000091e+02,0.000000000000000000e+00,9.204259250421808147e+00,0.000000000000000000e+00,1.000000009931982126e+00,0.000000000000000000e+00,-1.668318111684846079e-09,0.000000000000000000e+00 +2.888904653471255557e+01,1.585000000000000000e+02,0.000000000000000000e+00,9.205345703967633852e+00,0.000000000000000000e+00,1.000000009930169576e+00,0.000000000000000000e+00,-1.641329872078769293e-10,0.000000000000000000e+00 +2.889013286001978287e+01,1.585099999999999909e+02,0.000000000000000000e+00,9.206432029285648966e+00,0.000000000000000000e+00,1.000000009929991274e+00,0.000000000000000000e+00,1.451409379525439229e-09,0.000000000000000000e+00 +2.889121905714459615e+01,1.585200000000000102e+02,0.000000000000000000e+00,9.207518226421248286e+00,0.000000000000000000e+00,1.000000009931567790e+00,0.000000000000000000e+00,-1.357330103983992932e-09,0.000000000000000000e+00 +2.889230512613236002e+01,1.585300000000000011e+02,0.000000000000000000e+00,9.208604295419799968e+00,0.000000000000000000e+00,1.000000009930093636e+00,0.000000000000000000e+00,1.931238892588283147e-09,0.000000000000000000e+00 +2.889339106702841775e+01,1.585399999999999920e+02,0.000000000000000000e+00,9.209690236326640189e+00,0.000000000000000000e+00,1.000000009932190848e+00,0.000000000000000000e+00,-2.256820096315798866e-09,0.000000000000000000e+00 +2.889447687987807711e+01,1.585500000000000114e+02,0.000000000000000000e+00,9.210776049187085590e+00,0.000000000000000000e+00,1.000000009929740363e+00,0.000000000000000000e+00,1.124248159953409458e-09,0.000000000000000000e+00 +2.889556256472662810e+01,1.585600000000000023e+02,0.000000000000000000e+00,9.211861734046417283e+00,0.000000000000000000e+00,1.000000009930960942e+00,0.000000000000000000e+00,2.863621879104490941e-12,0.000000000000000000e+00 +2.889664812161932872e+01,1.585699999999999932e+02,0.000000000000000000e+00,9.212947290949898616e+00,0.000000000000000000e+00,1.000000009930964051e+00,0.000000000000000000e+00,-1.120830943770789672e-09,0.000000000000000000e+00 +2.889773355060141213e+01,1.585800000000000125e+02,0.000000000000000000e+00,9.214032719942760963e+00,0.000000000000000000e+00,1.000000009929747469e+00,0.000000000000000000e+00,7.520824913622622233e-10,0.000000000000000000e+00 +2.889881885171808307e+01,1.585900000000000034e+02,0.000000000000000000e+00,9.215118021070209053e+00,0.000000000000000000e+00,1.000000009930563705e+00,0.000000000000000000e+00,-4.296951204684749294e-10,0.000000000000000000e+00 +2.889990402501452138e+01,1.585999999999999943e+02,0.000000000000000000e+00,9.216203194377424524e+00,0.000000000000000000e+00,1.000000009930097411e+00,0.000000000000000000e+00,1.349196924416825784e-09,0.000000000000000000e+00 +2.890098907053588206e+01,1.586100000000000136e+02,0.000000000000000000e+00,9.217288239909558811e+00,0.000000000000000000e+00,1.000000009931561351e+00,0.000000000000000000e+00,-1.474815359987242280e-09,0.000000000000000000e+00 +2.890207398832728813e+01,1.586200000000000045e+02,0.000000000000000000e+00,9.218373157711740262e+00,0.000000000000000000e+00,1.000000009929961298e+00,0.000000000000000000e+00,1.342759856961284522e-10,0.000000000000000000e+00 +2.890315877843384129e+01,1.586299999999999955e+02,0.000000000000000000e+00,9.219457947829065247e+00,0.000000000000000000e+00,1.000000009930106959e+00,0.000000000000000000e+00,1.220090014998592073e-10,0.000000000000000000e+00 +2.890424344090061481e+01,1.586400000000000148e+02,0.000000000000000000e+00,9.220542610306608822e+00,0.000000000000000000e+00,1.000000009930239298e+00,0.000000000000000000e+00,-2.231635197798943260e-11,0.000000000000000000e+00 +2.890532797577265356e+01,1.586500000000000057e+02,0.000000000000000000e+00,9.221627145189417618e+00,0.000000000000000000e+00,1.000000009930215095e+00,0.000000000000000000e+00,1.194372404042850850e-09,0.000000000000000000e+00 +2.890641238309497751e+01,1.586599999999999966e+02,0.000000000000000000e+00,9.222711552522511624e+00,0.000000000000000000e+00,1.000000009931510281e+00,0.000000000000000000e+00,-2.289500037493434063e-09,0.000000000000000000e+00 +2.890749666291258180e+01,1.586700000000000159e+02,0.000000000000000000e+00,9.223795832350885959e+00,0.000000000000000000e+00,1.000000009929027822e+00,0.000000000000000000e+00,1.593826829790026001e-09,0.000000000000000000e+00 +2.890858081527043666e+01,1.586800000000000068e+02,0.000000000000000000e+00,9.224879984719503767e+00,0.000000000000000000e+00,1.000000009930755773e+00,0.000000000000000000e+00,-7.728367319958337925e-10,0.000000000000000000e+00 +2.890966484021347682e+01,1.586899999999999977e+02,0.000000000000000000e+00,9.225964009673310429e+00,0.000000000000000000e+00,1.000000009929917999e+00,0.000000000000000000e+00,1.171170632547953598e-09,0.000000000000000000e+00 +2.891074873778661924e+01,1.587000000000000171e+02,0.000000000000000000e+00,9.227047907257217574e+00,0.000000000000000000e+00,1.000000009931187428e+00,0.000000000000000000e+00,-1.663638760239307811e-09,0.000000000000000000e+00 +2.891183250803475246e+01,1.587100000000000080e+02,0.000000000000000000e+00,9.228131677516115516e+00,0.000000000000000000e+00,1.000000009929384426e+00,0.000000000000000000e+00,1.289881288667781218e-09,0.000000000000000000e+00 +2.891291615100274015e+01,1.587199999999999989e+02,0.000000000000000000e+00,9.229215320494862596e+00,0.000000000000000000e+00,1.000000009930782197e+00,0.000000000000000000e+00,-2.087209472795063751e-09,0.000000000000000000e+00 +2.891399966673541400e+01,1.587299999999999898e+02,0.000000000000000000e+00,9.230298836238297611e+00,0.000000000000000000e+00,1.000000009928520672e+00,0.000000000000000000e+00,1.803593491420607852e-09,0.000000000000000000e+00 +2.891508305527758438e+01,1.587400000000000091e+02,0.000000000000000000e+00,9.231382224791225610e+00,0.000000000000000000e+00,1.000000009930474665e+00,0.000000000000000000e+00,-6.762219664132874317e-10,0.000000000000000000e+00 +2.891616631667403681e+01,1.587500000000000000e+02,0.000000000000000000e+00,9.232465486198433879e+00,0.000000000000000000e+00,1.000000009929742140e+00,0.000000000000000000e+00,1.050839816990682280e-09,0.000000000000000000e+00 +2.891724945096952482e+01,1.587599999999999909e+02,0.000000000000000000e+00,9.233548620504675952e+00,0.000000000000000000e+00,1.000000009930880340e+00,0.000000000000000000e+00,-2.118738327989595704e-09,0.000000000000000000e+00 +2.891833245820877707e+01,1.587700000000000102e+02,0.000000000000000000e+00,9.234631627754684047e+00,0.000000000000000000e+00,1.000000009928585731e+00,0.000000000000000000e+00,1.912296422555752222e-09,0.000000000000000000e+00 +2.891941533843650092e+01,1.587800000000000011e+02,0.000000000000000000e+00,9.235714507993158406e+00,0.000000000000000000e+00,1.000000009930656519e+00,0.000000000000000000e+00,-5.053024786970703738e-10,0.000000000000000000e+00 +2.892049809169737173e+01,1.587899999999999920e+02,0.000000000000000000e+00,9.236797261264781511e+00,0.000000000000000000e+00,1.000000009930109401e+00,0.000000000000000000e+00,-3.025196973008971120e-10,0.000000000000000000e+00 +2.892158071803604003e+01,1.588000000000000114e+02,0.000000000000000000e+00,9.237879887614202090e+00,0.000000000000000000e+00,1.000000009929781886e+00,0.000000000000000000e+00,-5.267536529494803825e-10,0.000000000000000000e+00 +2.892266321749713498e+01,1.588100000000000023e+02,0.000000000000000000e+00,9.238962387086045780e+00,0.000000000000000000e+00,1.000000009929211675e+00,0.000000000000000000e+00,3.198228873172924787e-10,0.000000000000000000e+00 +2.892374559012525381e+01,1.588199999999999932e+02,0.000000000000000000e+00,9.240044759724911572e+00,0.000000000000000000e+00,1.000000009929557843e+00,0.000000000000000000e+00,7.029131354045491311e-10,0.000000000000000000e+00 +2.892482783596496887e+01,1.588300000000000125e+02,0.000000000000000000e+00,9.241127005575373587e+00,0.000000000000000000e+00,1.000000009930318567e+00,0.000000000000000000e+00,-9.135247542606875279e-10,0.000000000000000000e+00 +2.892590995506082763e+01,1.588400000000000034e+02,0.000000000000000000e+00,9.242209124681979304e+00,0.000000000000000000e+00,1.000000009929330025e+00,0.000000000000000000e+00,3.078274010586794113e-12,0.000000000000000000e+00 +2.892699194745735269e+01,1.588499999999999943e+02,0.000000000000000000e+00,9.243291117089247777e+00,0.000000000000000000e+00,1.000000009929333356e+00,0.000000000000000000e+00,4.010434394084414366e-10,0.000000000000000000e+00 +2.892807381319903826e+01,1.588600000000000136e+02,0.000000000000000000e+00,9.244372982841674968e+00,0.000000000000000000e+00,1.000000009929767231e+00,0.000000000000000000e+00,-1.256229845813884248e-09,0.000000000000000000e+00 +2.892915555233035363e+01,1.588700000000000045e+02,0.000000000000000000e+00,9.245454721983730195e+00,0.000000000000000000e+00,1.000000009928408318e+00,0.000000000000000000e+00,1.084959415768782824e-09,0.000000000000000000e+00 +2.893023716489573971e+01,1.588799999999999955e+02,0.000000000000000000e+00,9.246536334559854353e+00,0.000000000000000000e+00,1.000000009929581823e+00,0.000000000000000000e+00,-1.841669726077064147e-10,0.000000000000000000e+00 +2.893131865093961252e+01,1.588900000000000148e+02,0.000000000000000000e+00,9.247617820614467021e+00,0.000000000000000000e+00,1.000000009929382649e+00,0.000000000000000000e+00,-5.273089201582414699e-10,0.000000000000000000e+00 +2.893240001050636678e+01,1.589000000000000057e+02,0.000000000000000000e+00,9.248699180191957581e+00,0.000000000000000000e+00,1.000000009928812439e+00,0.000000000000000000e+00,1.557262893823088489e-09,0.000000000000000000e+00 +2.893348124364036522e+01,1.589099999999999966e+02,0.000000000000000000e+00,9.249780413336690543e+00,0.000000000000000000e+00,1.000000009930496203e+00,0.000000000000000000e+00,-1.545121764968280560e-09,0.000000000000000000e+00 +2.893456235038594571e+01,1.589200000000000159e+02,0.000000000000000000e+00,9.250861520093007329e+00,0.000000000000000000e+00,1.000000009928825762e+00,0.000000000000000000e+00,7.836406345863538907e-10,0.000000000000000000e+00 +2.893564333078742123e+01,1.589300000000000068e+02,0.000000000000000000e+00,9.251942500505217382e+00,0.000000000000000000e+00,1.000000009929672862e+00,0.000000000000000000e+00,-5.926782201450276079e-10,0.000000000000000000e+00 +2.893672418488908349e+01,1.589399999999999977e+02,0.000000000000000000e+00,9.253023354617610607e+00,0.000000000000000000e+00,1.000000009929032263e+00,0.000000000000000000e+00,3.881109015695974886e-10,0.000000000000000000e+00 +2.893780491273518862e+01,1.589500000000000171e+02,0.000000000000000000e+00,9.254104082474446713e+00,0.000000000000000000e+00,1.000000009929451705e+00,0.000000000000000000e+00,-8.541902889646351640e-10,0.000000000000000000e+00 +2.893888551436997503e+01,1.589600000000000080e+02,0.000000000000000000e+00,9.255184684119962313e+00,0.000000000000000000e+00,1.000000009928528666e+00,0.000000000000000000e+00,2.258515145536285806e-10,0.000000000000000000e+00 +2.893996598983764912e+01,1.589699999999999989e+02,0.000000000000000000e+00,9.256265159598365599e+00,0.000000000000000000e+00,1.000000009928772693e+00,0.000000000000000000e+00,5.682914842328629876e-10,0.000000000000000000e+00 +2.894104633918239955e+01,1.589799999999999898e+02,0.000000000000000000e+00,9.257345508953841673e+00,0.000000000000000000e+00,1.000000009929386646e+00,0.000000000000000000e+00,1.533435545137865973e-10,0.000000000000000000e+00 +2.894212656244837945e+01,1.589900000000000091e+02,0.000000000000000000e+00,9.258425732230548988e+00,0.000000000000000000e+00,1.000000009929552292e+00,0.000000000000000000e+00,-1.036526032602989564e-09,0.000000000000000000e+00 +2.894320665967972417e+01,1.590000000000000000e+02,0.000000000000000000e+00,9.259505829472619354e+00,0.000000000000000000e+00,1.000000009928432743e+00,0.000000000000000000e+00,2.590589375269902626e-11,0.000000000000000000e+00 +2.894428663092054066e+01,1.590099999999999909e+02,0.000000000000000000e+00,9.260585800724157934e+00,0.000000000000000000e+00,1.000000009928460720e+00,0.000000000000000000e+00,2.771842679688810787e-10,0.000000000000000000e+00 +2.894536647621490744e+01,1.590200000000000102e+02,0.000000000000000000e+00,9.261665646029246801e+00,0.000000000000000000e+00,1.000000009928760036e+00,0.000000000000000000e+00,-3.008663727075597656e-10,0.000000000000000000e+00 +2.894644619560688170e+01,1.590300000000000011e+02,0.000000000000000000e+00,9.262745365431941380e+00,0.000000000000000000e+00,1.000000009928435185e+00,0.000000000000000000e+00,1.321457143108611519e-09,0.000000000000000000e+00 +2.894752578914049224e+01,1.590399999999999920e+02,0.000000000000000000e+00,9.263824958976270452e+00,0.000000000000000000e+00,1.000000009929861822e+00,0.000000000000000000e+00,-9.706899724328593179e-10,0.000000000000000000e+00 +2.894860525685974295e+01,1.590500000000000114e+02,0.000000000000000000e+00,9.264904426706239704e+00,0.000000000000000000e+00,1.000000009928813993e+00,0.000000000000000000e+00,-1.098350848809040139e-09,0.000000000000000000e+00 +2.894968459880861289e+01,1.590600000000000023e+02,0.000000000000000000e+00,9.265983768665824627e+00,0.000000000000000000e+00,1.000000009927628497e+00,0.000000000000000000e+00,9.221543362505406888e-10,0.000000000000000000e+00 +2.895076381503105267e+01,1.590699999999999932e+02,0.000000000000000000e+00,9.267062984898977618e+00,0.000000000000000000e+00,1.000000009928623701e+00,0.000000000000000000e+00,4.979637241099404812e-10,0.000000000000000000e+00 +2.895184290557098805e+01,1.590800000000000125e+02,0.000000000000000000e+00,9.268142075449627981e+00,0.000000000000000000e+00,1.000000009929161049e+00,0.000000000000000000e+00,-8.649525794072139508e-10,0.000000000000000000e+00 +2.895292187047232346e+01,1.590900000000000034e+02,0.000000000000000000e+00,9.269221040361676600e+00,0.000000000000000000e+00,1.000000009928227795e+00,0.000000000000000000e+00,-1.329584618419952710e-10,0.000000000000000000e+00 +2.895400070977893492e+01,1.590999999999999943e+02,0.000000000000000000e+00,9.270299879678997712e+00,0.000000000000000000e+00,1.000000009928084355e+00,0.000000000000000000e+00,1.151480189574545501e-09,0.000000000000000000e+00 +2.895507942353467001e+01,1.591100000000000136e+02,0.000000000000000000e+00,9.271378593445442462e+00,0.000000000000000000e+00,1.000000009929326472e+00,0.000000000000000000e+00,-8.275811579505781391e-11,0.000000000000000000e+00 +2.895615801178335502e+01,1.591200000000000045e+02,0.000000000000000000e+00,9.272457181704837126e+00,0.000000000000000000e+00,1.000000009929237210e+00,0.000000000000000000e+00,-8.015294163582915722e-10,0.000000000000000000e+00 +2.895723647456878780e+01,1.591299999999999955e+02,0.000000000000000000e+00,9.273535644500979558e+00,0.000000000000000000e+00,1.000000009928372791e+00,0.000000000000000000e+00,-1.022156380410318722e-09,0.000000000000000000e+00 +2.895831481193474488e+01,1.591400000000000148e+02,0.000000000000000000e+00,9.274613981877642743e+00,0.000000000000000000e+00,1.000000009927270561e+00,0.000000000000000000e+00,7.667064284462390869e-10,0.000000000000000000e+00 +2.895939302392497439e+01,1.591500000000000057e+02,0.000000000000000000e+00,9.275692193878574798e+00,0.000000000000000000e+00,1.000000009928097233e+00,0.000000000000000000e+00,-3.686715161386776839e-11,0.000000000000000000e+00 +2.896047111058319601e+01,1.591599999999999966e+02,0.000000000000000000e+00,9.276770280547500747e+00,0.000000000000000000e+00,1.000000009928057487e+00,0.000000000000000000e+00,1.133333206916827869e-09,0.000000000000000000e+00 +2.896154907195311168e+01,1.591700000000000159e+02,0.000000000000000000e+00,9.277848241928117190e+00,0.000000000000000000e+00,1.000000009929279177e+00,0.000000000000000000e+00,-1.854910571148965672e-09,0.000000000000000000e+00 +2.896262690807839135e+01,1.591800000000000068e+02,0.000000000000000000e+00,9.278926078064097638e+00,0.000000000000000000e+00,1.000000009927279887e+00,0.000000000000000000e+00,1.683294083183099423e-09,0.000000000000000000e+00 +2.896370461900268012e+01,1.591899999999999977e+02,0.000000000000000000e+00,9.280003788999085401e+00,0.000000000000000000e+00,1.000000009929093991e+00,0.000000000000000000e+00,-5.029863025850904744e-10,0.000000000000000000e+00 +2.896478220476960175e+01,1.592000000000000171e+02,0.000000000000000000e+00,9.281081374776706028e+00,0.000000000000000000e+00,1.000000009928551981e+00,0.000000000000000000e+00,-7.851701519600961078e-10,0.000000000000000000e+00 +2.896585966542275159e+01,1.592100000000000080e+02,0.000000000000000000e+00,9.282158835440553091e+00,0.000000000000000000e+00,1.000000009927705991e+00,0.000000000000000000e+00,-7.100328589103078292e-10,0.000000000000000000e+00 +2.896693700100570013e+01,1.592199999999999989e+02,0.000000000000000000e+00,9.283236171034197071e+00,0.000000000000000000e+00,1.000000009926941047e+00,0.000000000000000000e+00,1.235950987810620136e-09,0.000000000000000000e+00 +2.896801421156199297e+01,1.592299999999999898e+02,0.000000000000000000e+00,9.284313381601183579e+00,0.000000000000000000e+00,1.000000009928272426e+00,0.000000000000000000e+00,4.428170084764669482e-10,0.000000000000000000e+00 +2.896909129713515085e+01,1.592400000000000091e+02,0.000000000000000000e+00,9.285390467185035135e+00,0.000000000000000000e+00,1.000000009928749378e+00,0.000000000000000000e+00,-1.578079414606620377e-09,0.000000000000000000e+00 +2.897016825776866966e+01,1.592500000000000000e+02,0.000000000000000000e+00,9.286467427829245835e+00,0.000000000000000000e+00,1.000000009927049849e+00,0.000000000000000000e+00,1.283395018498927831e-09,0.000000000000000000e+00 +2.897124509350601684e+01,1.592599999999999909e+02,0.000000000000000000e+00,9.287544263577283132e+00,0.000000000000000000e+00,1.000000009928431854e+00,0.000000000000000000e+00,-1.810654706928728058e-10,0.000000000000000000e+00 +2.897232180439063853e+01,1.592700000000000102e+02,0.000000000000000000e+00,9.288620974472594938e+00,0.000000000000000000e+00,1.000000009928236899e+00,0.000000000000000000e+00,-1.394654503647700574e-09,0.000000000000000000e+00 +2.897339839046595245e+01,1.592800000000000011e+02,0.000000000000000000e+00,9.289697560558598965e+00,0.000000000000000000e+00,1.000000009926735434e+00,0.000000000000000000e+00,6.916324384443446155e-10,0.000000000000000000e+00 +2.897447485177535498e+01,1.592899999999999920e+02,0.000000000000000000e+00,9.290774021878688060e+00,0.000000000000000000e+00,1.000000009927479949e+00,0.000000000000000000e+00,1.462643069219280317e-09,0.000000000000000000e+00 +2.897555118836221411e+01,1.593000000000000114e+02,0.000000000000000000e+00,9.291850358476233751e+00,0.000000000000000000e+00,1.000000009929054245e+00,0.000000000000000000e+00,-2.167809747633193186e-09,0.000000000000000000e+00 +2.897662740026987649e+01,1.593100000000000023e+02,0.000000000000000000e+00,9.292926570394580921e+00,0.000000000000000000e+00,1.000000009926721223e+00,0.000000000000000000e+00,5.179244964390682099e-10,0.000000000000000000e+00 +2.897770348754165681e+01,1.593199999999999932e+02,0.000000000000000000e+00,9.294002657677044255e+00,0.000000000000000000e+00,1.000000009927278555e+00,0.000000000000000000e+00,3.004722663919107297e-10,0.000000000000000000e+00 +2.897877945022085200e+01,1.593300000000000125e+02,0.000000000000000000e+00,9.295078620366920674e+00,0.000000000000000000e+00,1.000000009927601852e+00,0.000000000000000000e+00,2.295081330727203613e-10,0.000000000000000000e+00 +2.897985528835073055e+01,1.593400000000000034e+02,0.000000000000000000e+00,9.296154458507478680e+00,0.000000000000000000e+00,1.000000009927848765e+00,0.000000000000000000e+00,2.881568677909660743e-10,0.000000000000000000e+00 +2.898093100197453253e+01,1.593499999999999943e+02,0.000000000000000000e+00,9.297230172141961901e+00,0.000000000000000000e+00,1.000000009928158740e+00,0.000000000000000000e+00,-1.077410255865471944e-09,0.000000000000000000e+00 +2.898200659113548028e+01,1.593600000000000136e+02,0.000000000000000000e+00,9.298305761313589102e+00,0.000000000000000000e+00,1.000000009926999889e+00,0.000000000000000000e+00,7.228299840979806458e-10,0.000000000000000000e+00 +2.898308205587676767e+01,1.593700000000000045e+02,0.000000000000000000e+00,9.299381226065552397e+00,0.000000000000000000e+00,1.000000009927777267e+00,0.000000000000000000e+00,-4.716180051008427009e-10,0.000000000000000000e+00 +2.898415739624156373e+01,1.593799999999999955e+02,0.000000000000000000e+00,9.300456566441022588e+00,0.000000000000000000e+00,1.000000009927270117e+00,0.000000000000000000e+00,-7.083348579438088952e-11,0.000000000000000000e+00 +2.898523261227300907e+01,1.593900000000000148e+02,0.000000000000000000e+00,9.301531782483142052e+00,0.000000000000000000e+00,1.000000009927193956e+00,0.000000000000000000e+00,3.719704264660204091e-10,0.000000000000000000e+00 +2.898630770401422296e+01,1.594000000000000057e+02,0.000000000000000000e+00,9.302606874235030077e+00,0.000000000000000000e+00,1.000000009927593858e+00,0.000000000000000000e+00,-6.973444223716254944e-10,0.000000000000000000e+00 +2.898738267150830339e+01,1.594099999999999966e+02,0.000000000000000000e+00,9.303681841739781078e+00,0.000000000000000000e+00,1.000000009926844236e+00,0.000000000000000000e+00,-2.229033115250183645e-10,0.000000000000000000e+00 +2.898845751479831634e+01,1.594200000000000159e+02,0.000000000000000000e+00,9.304756685040462827e+00,0.000000000000000000e+00,1.000000009926604649e+00,0.000000000000000000e+00,1.779920185498963916e-09,0.000000000000000000e+00 +2.898953223392730649e+01,1.594300000000000068e+02,0.000000000000000000e+00,9.305831404180120003e+00,0.000000000000000000e+00,1.000000009928517564e+00,0.000000000000000000e+00,-2.397332464794071890e-09,0.000000000000000000e+00 +2.899060682893829011e+01,1.594399999999999977e+02,0.000000000000000000e+00,9.306905999201774193e+00,0.000000000000000000e+00,1.000000009925941402e+00,0.000000000000000000e+00,1.071091966095289945e-09,0.000000000000000000e+00 +2.899168129987426568e+01,1.594500000000000171e+02,0.000000000000000000e+00,9.307980470148415009e+00,0.000000000000000000e+00,1.000000009927092259e+00,0.000000000000000000e+00,-1.376480039531911891e-10,0.000000000000000000e+00 +2.899275564677820327e+01,1.594600000000000080e+02,0.000000000000000000e+00,9.309054817063016074e+00,0.000000000000000000e+00,1.000000009926944378e+00,0.000000000000000000e+00,1.122394791700557789e-10,0.000000000000000000e+00 +2.899382986969304454e+01,1.594699999999999989e+02,0.000000000000000000e+00,9.310129039988520816e+00,0.000000000000000000e+00,1.000000009927064948e+00,0.000000000000000000e+00,2.650232351190170401e-10,0.000000000000000000e+00 +2.899490396866170983e+01,1.594799999999999898e+02,0.000000000000000000e+00,9.311203138967849569e+00,0.000000000000000000e+00,1.000000009927349609e+00,0.000000000000000000e+00,3.035093556037438681e-10,0.000000000000000000e+00 +2.899597794372709458e+01,1.594900000000000091e+02,0.000000000000000000e+00,9.312277114043897797e+00,0.000000000000000000e+00,1.000000009927675571e+00,0.000000000000000000e+00,-1.330591264478375359e-09,0.000000000000000000e+00 +2.899705179493207297e+01,1.595000000000000000e+02,0.000000000000000000e+00,9.313350965259536096e+00,0.000000000000000000e+00,1.000000009926246713e+00,0.000000000000000000e+00,-3.308766936974740488e-11,0.000000000000000000e+00 +2.899812552231948715e+01,1.595099999999999909e+02,0.000000000000000000e+00,9.314424692657608418e+00,0.000000000000000000e+00,1.000000009926211186e+00,0.000000000000000000e+00,1.098637269323292931e-09,0.000000000000000000e+00 +2.899919912593215798e+01,1.595200000000000102e+02,0.000000000000000000e+00,9.315498296280937396e+00,0.000000000000000000e+00,1.000000009927390687e+00,0.000000000000000000e+00,-1.035882834349853470e-09,0.000000000000000000e+00 +2.900027260581288502e+01,1.595300000000000011e+02,0.000000000000000000e+00,9.316571776172320796e+00,0.000000000000000000e+00,1.000000009926278688e+00,0.000000000000000000e+00,1.252594519323655552e-09,0.000000000000000000e+00 +2.900134596200443937e+01,1.595399999999999920e+02,0.000000000000000000e+00,9.317645132374527961e+00,0.000000000000000000e+00,1.000000009927623168e+00,0.000000000000000000e+00,-1.302393217901213202e-09,0.000000000000000000e+00 +2.900241919454956374e+01,1.595500000000000114e+02,0.000000000000000000e+00,9.318718364930308695e+00,0.000000000000000000e+00,1.000000009926225397e+00,0.000000000000000000e+00,5.330184850840352004e-10,0.000000000000000000e+00 +2.900349230349098661e+01,1.595600000000000023e+02,0.000000000000000000e+00,9.319791473882382604e+00,0.000000000000000000e+00,1.000000009926797384e+00,0.000000000000000000e+00,-9.697252522447651674e-10,0.000000000000000000e+00 +2.900456528887140095e+01,1.595699999999999932e+02,0.000000000000000000e+00,9.320864459273449754e+00,0.000000000000000000e+00,1.000000009925756883e+00,0.000000000000000000e+00,3.433545478589351231e-10,0.000000000000000000e+00 +2.900563815073348550e+01,1.595800000000000125e+02,0.000000000000000000e+00,9.321937321146181787e+00,0.000000000000000000e+00,1.000000009926125255e+00,0.000000000000000000e+00,1.369643493154810271e-09,0.000000000000000000e+00 +2.900671088911988349e+01,1.595900000000000034e+02,0.000000000000000000e+00,9.323010059543229033e+00,0.000000000000000000e+00,1.000000009927594524e+00,0.000000000000000000e+00,-9.963507222950153800e-10,0.000000000000000000e+00 +2.900778350407322392e+01,1.595999999999999943e+02,0.000000000000000000e+00,9.324082674507216950e+00,0.000000000000000000e+00,1.000000009926525824e+00,0.000000000000000000e+00,-5.968854377559186045e-10,0.000000000000000000e+00 +2.900885599563610384e+01,1.596100000000000136e+02,0.000000000000000000e+00,9.325155166080742575e+00,0.000000000000000000e+00,1.000000009925885669e+00,0.000000000000000000e+00,1.008175332187713643e-09,0.000000000000000000e+00 +2.900992836385109896e+01,1.596200000000000045e+02,0.000000000000000000e+00,9.326227534306381628e+00,0.000000000000000000e+00,1.000000009926966804e+00,0.000000000000000000e+00,-8.324770803349958681e-10,0.000000000000000000e+00 +2.901100060876076014e+01,1.596299999999999955e+02,0.000000000000000000e+00,9.327299779226686738e+00,0.000000000000000000e+00,1.000000009926074185e+00,0.000000000000000000e+00,4.307839316551100608e-11,0.000000000000000000e+00 +2.901207273040761336e+01,1.596400000000000148e+02,0.000000000000000000e+00,9.328371900884182111e+00,0.000000000000000000e+00,1.000000009926120370e+00,0.000000000000000000e+00,5.281852365980258661e-10,0.000000000000000000e+00 +2.901314472883415974e+01,1.596500000000000057e+02,0.000000000000000000e+00,9.329443899321370637e+00,0.000000000000000000e+00,1.000000009926686584e+00,0.000000000000000000e+00,-9.400706083599968410e-10,0.000000000000000000e+00 +2.901421660408287906e+01,1.596599999999999966e+02,0.000000000000000000e+00,9.330515774580730337e+00,0.000000000000000000e+00,1.000000009925678945e+00,0.000000000000000000e+00,2.579379407697370709e-10,0.000000000000000000e+00 +2.901528835619622271e+01,1.596700000000000159e+02,0.000000000000000000e+00,9.331587526704712587e+00,0.000000000000000000e+00,1.000000009925955391e+00,0.000000000000000000e+00,-5.323041642158888790e-10,0.000000000000000000e+00 +2.901635998521662074e+01,1.596800000000000068e+02,0.000000000000000000e+00,9.332659155735747447e+00,0.000000000000000000e+00,1.000000009925384958e+00,0.000000000000000000e+00,1.312366447365198132e-09,0.000000000000000000e+00 +2.901743149118647480e+01,1.596899999999999977e+02,0.000000000000000000e+00,9.333730661716238330e+00,0.000000000000000000e+00,1.000000009926791167e+00,0.000000000000000000e+00,-4.142936569977608829e-10,0.000000000000000000e+00 +2.901850287414816876e+01,1.597000000000000171e+02,0.000000000000000000e+00,9.334802044688567335e+00,0.000000000000000000e+00,1.000000009926347300e+00,0.000000000000000000e+00,-1.087982502591573373e-09,0.000000000000000000e+00 +2.901957413414405451e+01,1.597100000000000080e+02,0.000000000000000000e+00,9.335873304695088137e+00,0.000000000000000000e+00,1.000000009925181788e+00,0.000000000000000000e+00,8.244242651394531465e-10,0.000000000000000000e+00 +2.902064527121646620e+01,1.597199999999999989e+02,0.000000000000000000e+00,9.336944441778131321e+00,0.000000000000000000e+00,1.000000009926064859e+00,0.000000000000000000e+00,6.607346211483934111e-10,0.000000000000000000e+00 +2.902171628540770953e+01,1.597299999999999898e+02,0.000000000000000000e+00,9.338015455980006152e+00,0.000000000000000000e+00,1.000000009926772515e+00,0.000000000000000000e+00,-1.597390465965408392e-09,0.000000000000000000e+00 +2.902278717676006892e+01,1.597400000000000091e+02,0.000000000000000000e+00,9.339086347342995253e+00,0.000000000000000000e+00,1.000000009925061883e+00,0.000000000000000000e+00,2.293505274622321344e-10,0.000000000000000000e+00 +2.902385794531580032e+01,1.597500000000000000e+02,0.000000000000000000e+00,9.340157115909354602e+00,0.000000000000000000e+00,1.000000009925307465e+00,0.000000000000000000e+00,1.477883584576790424e-09,0.000000000000000000e+00 +2.902492859111713841e+01,1.597599999999999909e+02,0.000000000000000000e+00,9.341227761721320633e+00,0.000000000000000000e+00,1.000000009926889755e+00,0.000000000000000000e+00,-9.696741140274228022e-10,0.000000000000000000e+00 +2.902599911420629653e+01,1.597700000000000102e+02,0.000000000000000000e+00,9.342298284821104914e+00,0.000000000000000000e+00,1.000000009925851696e+00,0.000000000000000000e+00,-9.312012716602855149e-10,0.000000000000000000e+00 +2.902706951462545604e+01,1.597800000000000011e+02,0.000000000000000000e+00,9.343368685250890593e+00,0.000000000000000000e+00,1.000000009924854938e+00,0.000000000000000000e+00,2.759277329152639417e-11,0.000000000000000000e+00 +2.902813979241678410e+01,1.597899999999999920e+02,0.000000000000000000e+00,9.344438963052839497e+00,0.000000000000000000e+00,1.000000009924884470e+00,0.000000000000000000e+00,1.890632713304751146e-09,0.000000000000000000e+00 +2.902920994762241236e+01,1.598000000000000114e+02,0.000000000000000000e+00,9.345509118269090365e+00,0.000000000000000000e+00,1.000000009926907740e+00,0.000000000000000000e+00,-1.564432877523961759e-09,0.000000000000000000e+00 +2.903027998028445822e+01,1.598100000000000023e+02,0.000000000000000000e+00,9.346579150941758840e+00,0.000000000000000000e+00,1.000000009925233746e+00,0.000000000000000000e+00,5.043118664180495005e-10,0.000000000000000000e+00 +2.903134989044501069e+01,1.598199999999999932e+02,0.000000000000000000e+00,9.347649061112930369e+00,0.000000000000000000e+00,1.000000009925773314e+00,0.000000000000000000e+00,-1.228959824813850251e-09,0.000000000000000000e+00 +2.903241967814613389e+01,1.598300000000000125e+02,0.000000000000000000e+00,9.348718848824672634e+00,0.000000000000000000e+00,1.000000009924458588e+00,0.000000000000000000e+00,9.787550630459736532e-10,0.000000000000000000e+00 +2.903348934342987064e+01,1.598400000000000034e+02,0.000000000000000000e+00,9.349788514119024896e+00,0.000000000000000000e+00,1.000000009925505529e+00,0.000000000000000000e+00,-6.504327613118233425e-10,0.000000000000000000e+00 +2.903455888633823534e+01,1.598499999999999943e+02,0.000000000000000000e+00,9.350858057038006876e+00,0.000000000000000000e+00,1.000000009924809863e+00,0.000000000000000000e+00,1.629486191126667258e-09,0.000000000000000000e+00 +2.903562830691322461e+01,1.598600000000000136e+02,0.000000000000000000e+00,9.351927477623609875e+00,0.000000000000000000e+00,1.000000009926552469e+00,0.000000000000000000e+00,-1.517123807726463733e-09,0.000000000000000000e+00 +2.903669760519680665e+01,1.598700000000000045e+02,0.000000000000000000e+00,9.352996775917805650e+00,0.000000000000000000e+00,1.000000009924930211e+00,0.000000000000000000e+00,-7.866852011412604912e-10,0.000000000000000000e+00 +2.903776678123092481e+01,1.598799999999999955e+02,0.000000000000000000e+00,9.354065951962535763e+00,0.000000000000000000e+00,1.000000009924089106e+00,0.000000000000000000e+00,2.251904952536639072e-09,0.000000000000000000e+00 +2.903883583505750110e+01,1.598900000000000148e+02,0.000000000000000000e+00,9.355135005799722236e+00,0.000000000000000000e+00,1.000000009926496514e+00,0.000000000000000000e+00,-1.743857466733637587e-09,0.000000000000000000e+00 +2.903990476671843268e+01,1.599000000000000057e+02,0.000000000000000000e+00,9.356203937471265775e+00,0.000000000000000000e+00,1.000000009924632449e+00,0.000000000000000000e+00,-3.564980745429811770e-10,0.000000000000000000e+00 +2.904097357625559539e+01,1.599099999999999966e+02,0.000000000000000000e+00,9.357272747019035108e+00,0.000000000000000000e+00,1.000000009924251421e+00,0.000000000000000000e+00,1.736152800948321947e-09,0.000000000000000000e+00 +2.904204226371083664e+01,1.599200000000000159e+02,0.000000000000000000e+00,9.358341434484881205e+00,0.000000000000000000e+00,1.000000009926106825e+00,0.000000000000000000e+00,-1.705804938094388171e-09,0.000000000000000000e+00 +2.904311082912597897e+01,1.599300000000000068e+02,0.000000000000000000e+00,9.359409999910631939e+00,0.000000000000000000e+00,1.000000009924284061e+00,0.000000000000000000e+00,1.895324324134527604e-10,0.000000000000000000e+00 +2.904417927254282716e+01,1.599399999999999977e+02,0.000000000000000000e+00,9.360478443338084986e+00,0.000000000000000000e+00,1.000000009924486566e+00,0.000000000000000000e+00,1.183881553085213832e-09,0.000000000000000000e+00 +2.904524759400316114e+01,1.599500000000000171e+02,0.000000000000000000e+00,9.361546764809020260e+00,0.000000000000000000e+00,1.000000009925751332e+00,0.000000000000000000e+00,-2.970435081664410678e-10,0.000000000000000000e+00 +2.904631579354873239e+01,1.599600000000000080e+02,0.000000000000000000e+00,9.362614964365192805e+00,0.000000000000000000e+00,1.000000009925434030e+00,0.000000000000000000e+00,-1.157749512626921257e-09,0.000000000000000000e+00 +2.904738387122127108e+01,1.599699999999999989e+02,0.000000000000000000e+00,9.363683042048331018e+00,0.000000000000000000e+00,1.000000009924197464e+00,0.000000000000000000e+00,1.434617158183237598e-10,0.000000000000000000e+00 +2.904845182706248252e+01,1.599799999999999898e+02,0.000000000000000000e+00,9.364750997900140206e+00,0.000000000000000000e+00,1.000000009924350675e+00,0.000000000000000000e+00,4.757649892538467096e-10,0.000000000000000000e+00 +2.904951966111405071e+01,1.599900000000000091e+02,0.000000000000000000e+00,9.365818831962304358e+00,0.000000000000000000e+00,1.000000009924858713e+00,0.000000000000000000e+00,-1.780162888245169608e-10,0.000000000000000000e+00 +2.905058737341763120e+01,1.600000000000000000e+02,0.000000000000000000e+00,9.366886544276482596e+00,0.000000000000000000e+00,1.000000009924668642e+00,0.000000000000000000e+00,-2.770382340639149103e-10,0.000000000000000000e+00 +2.905165496401486180e+01,1.600099999999999909e+02,0.000000000000000000e+00,9.367954134884309170e+00,0.000000000000000000e+00,1.000000009924372879e+00,0.000000000000000000e+00,1.624560970047072162e-10,0.000000000000000000e+00 +2.905272243294735546e+01,1.600200000000000102e+02,0.000000000000000000e+00,9.369021603827395239e+00,0.000000000000000000e+00,1.000000009924546296e+00,0.000000000000000000e+00,-4.345831723461352354e-10,0.000000000000000000e+00 +2.905378978025669667e+01,1.600300000000000011e+02,0.000000000000000000e+00,9.370088951147328871e+00,0.000000000000000000e+00,1.000000009924082445e+00,0.000000000000000000e+00,1.033422943227364068e-09,0.000000000000000000e+00 +2.905485700598444865e+01,1.600399999999999920e+02,0.000000000000000000e+00,9.371156176885673261e+00,0.000000000000000000e+00,1.000000009925185340e+00,0.000000000000000000e+00,-1.279701022657217867e-10,0.000000000000000000e+00 +2.905592411017215326e+01,1.600500000000000114e+02,0.000000000000000000e+00,9.372223281083970292e+00,0.000000000000000000e+00,1.000000009925048783e+00,0.000000000000000000e+00,-8.178532849769659940e-10,0.000000000000000000e+00 +2.905699109286132753e+01,1.600600000000000023e+02,0.000000000000000000e+00,9.373290263783735199e+00,0.000000000000000000e+00,1.000000009924176148e+00,0.000000000000000000e+00,5.099156907000279228e-10,0.000000000000000000e+00 +2.905805795409346359e+01,1.600699999999999932e+02,0.000000000000000000e+00,9.374357125026460125e+00,0.000000000000000000e+00,1.000000009924720157e+00,0.000000000000000000e+00,-8.442667120768759283e-10,0.000000000000000000e+00 +2.905912469391003228e+01,1.600800000000000125e+02,0.000000000000000000e+00,9.375423864853615896e+00,0.000000000000000000e+00,1.000000009923819544e+00,0.000000000000000000e+00,-2.137969869854186670e-10,0.000000000000000000e+00 +2.906019131235247954e+01,1.600900000000000034e+02,0.000000000000000000e+00,9.376490483306646695e+00,0.000000000000000000e+00,1.000000009923591504e+00,0.000000000000000000e+00,8.242634535673645281e-10,0.000000000000000000e+00 +2.906125780946222648e+01,1.600999999999999943e+02,0.000000000000000000e+00,9.377556980426975386e+00,0.000000000000000000e+00,1.000000009924470579e+00,0.000000000000000000e+00,-8.703746207802067508e-10,0.000000000000000000e+00 +2.906232418528066930e+01,1.601100000000000136e+02,0.000000000000000000e+00,9.378623356256001742e+00,0.000000000000000000e+00,1.000000009923542432e+00,0.000000000000000000e+00,9.331560248822678859e-10,0.000000000000000000e+00 +2.906339043984918646e+01,1.601200000000000045e+02,0.000000000000000000e+00,9.379689610835098890e+00,0.000000000000000000e+00,1.000000009924537414e+00,0.000000000000000000e+00,-2.957447453019365854e-11,0.000000000000000000e+00 +2.906445657320912801e+01,1.601299999999999955e+02,0.000000000000000000e+00,9.380755744205620417e+00,0.000000000000000000e+00,1.000000009924505884e+00,0.000000000000000000e+00,-6.513372777157350806e-10,0.000000000000000000e+00 +2.906552258540182265e+01,1.601400000000000148e+02,0.000000000000000000e+00,9.381821756408893265e+00,0.000000000000000000e+00,1.000000009923811550e+00,0.000000000000000000e+00,6.159971851205335689e-10,0.000000000000000000e+00 +2.906658847646857424e+01,1.601500000000000057e+02,0.000000000000000000e+00,9.382887647486221283e+00,0.000000000000000000e+00,1.000000009924468136e+00,0.000000000000000000e+00,-9.356637337112476887e-10,0.000000000000000000e+00 +2.906765424645066176e+01,1.601599999999999966e+02,0.000000000000000000e+00,9.383953417478887005e+00,0.000000000000000000e+00,1.000000009923470934e+00,0.000000000000000000e+00,9.338947219359542918e-10,0.000000000000000000e+00 +2.906871989538934642e+01,1.601700000000000159e+02,0.000000000000000000e+00,9.385019066428146317e+00,0.000000000000000000e+00,1.000000009924466138e+00,0.000000000000000000e+00,-1.613558234389092640e-09,0.000000000000000000e+00 +2.906978542332586102e+01,1.601800000000000068e+02,0.000000000000000000e+00,9.386084594375235568e+00,0.000000000000000000e+00,1.000000009922746846e+00,0.000000000000000000e+00,7.928028410875898160e-10,0.000000000000000000e+00 +2.907085083030141703e+01,1.601899999999999977e+02,0.000000000000000000e+00,9.387150001361362683e+00,0.000000000000000000e+00,1.000000009923591504e+00,0.000000000000000000e+00,3.132802118176709583e-10,0.000000000000000000e+00 +2.907191611635720108e+01,1.602000000000000171e+02,0.000000000000000000e+00,9.388215287427717826e+00,0.000000000000000000e+00,1.000000009923925237e+00,0.000000000000000000e+00,6.149577535621679228e-11,0.000000000000000000e+00 +2.907298128153437844e+01,1.602100000000000080e+02,0.000000000000000000e+00,9.389280452615464512e+00,0.000000000000000000e+00,1.000000009923990740e+00,0.000000000000000000e+00,2.022293896572380281e-11,0.000000000000000000e+00 +2.907404632587408599e+01,1.602199999999999989e+02,0.000000000000000000e+00,9.390345496965743166e+00,0.000000000000000000e+00,1.000000009924012279e+00,0.000000000000000000e+00,1.738953013690076334e-10,0.000000000000000000e+00 +2.907511124941744640e+01,1.602299999999999898e+02,0.000000000000000000e+00,9.391410420519671121e+00,0.000000000000000000e+00,1.000000009924197464e+00,0.000000000000000000e+00,-1.060589691598568947e-09,0.000000000000000000e+00 +2.907617605220555035e+01,1.602400000000000091e+02,0.000000000000000000e+00,9.392475223318342614e+00,0.000000000000000000e+00,1.000000009923068145e+00,0.000000000000000000e+00,1.000646146420289941e-09,0.000000000000000000e+00 +2.907724073427947076e+01,1.602500000000000000e+02,0.000000000000000000e+00,9.393539905402827017e+00,0.000000000000000000e+00,1.000000009924133515e+00,0.000000000000000000e+00,-1.493004800742734978e-09,0.000000000000000000e+00 +2.907830529568025213e+01,1.602599999999999909e+02,0.000000000000000000e+00,9.394604466814174160e+00,0.000000000000000000e+00,1.000000009922544120e+00,0.000000000000000000e+00,8.450472032143044667e-10,0.000000000000000000e+00 +2.907936973644892120e+01,1.602700000000000102e+02,0.000000000000000000e+00,9.395668907593405450e+00,0.000000000000000000e+00,1.000000009923443622e+00,0.000000000000000000e+00,1.614763375118965018e-10,0.000000000000000000e+00 +2.908043405662647984e+01,1.602800000000000011e+02,0.000000000000000000e+00,9.396733227781524533e+00,0.000000000000000000e+00,1.000000009923615485e+00,0.000000000000000000e+00,-4.248101615314677186e-10,0.000000000000000000e+00 +2.908149825625390150e+01,1.602899999999999920e+02,0.000000000000000000e+00,9.397797427419508409e+00,0.000000000000000000e+00,1.000000009923163402e+00,0.000000000000000000e+00,6.383307733609794040e-10,0.000000000000000000e+00 +2.908256233537214541e+01,1.603000000000000114e+02,0.000000000000000000e+00,9.398861506548310984e+00,0.000000000000000000e+00,1.000000009923842637e+00,0.000000000000000000e+00,-1.371554377206052264e-09,0.000000000000000000e+00 +2.908362629402214239e+01,1.603100000000000023e+02,0.000000000000000000e+00,9.399925465208864850e+00,0.000000000000000000e+00,1.000000009922383359e+00,0.000000000000000000e+00,1.374840442365927502e-09,0.000000000000000000e+00 +2.908469013224479838e+01,1.603199999999999932e+02,0.000000000000000000e+00,9.400989303442075951e+00,0.000000000000000000e+00,1.000000009923845967e+00,0.000000000000000000e+00,-5.540062988659337176e-10,0.000000000000000000e+00 +2.908575385008099801e+01,1.603300000000000125e+02,0.000000000000000000e+00,9.402053021288832468e+00,0.000000000000000000e+00,1.000000009923256661e+00,0.000000000000000000e+00,-8.979090814112582100e-10,0.000000000000000000e+00 +2.908681744757160459e+01,1.603400000000000034e+02,0.000000000000000000e+00,9.403116618789994163e+00,0.000000000000000000e+00,1.000000009922301647e+00,0.000000000000000000e+00,3.288460320626072237e-10,0.000000000000000000e+00 +2.908788092475745657e+01,1.603499999999999943e+02,0.000000000000000000e+00,9.404180095986399479e+00,0.000000000000000000e+00,1.000000009922651367e+00,0.000000000000000000e+00,1.540844006348765738e-09,0.000000000000000000e+00 +2.908894428167937107e+01,1.603600000000000136e+02,0.000000000000000000e+00,9.405243452918865543e+00,0.000000000000000000e+00,1.000000009924289834e+00,0.000000000000000000e+00,-1.993570952797696126e-09,0.000000000000000000e+00 +2.909000751837814036e+01,1.603700000000000045e+02,0.000000000000000000e+00,9.406306689628186390e+00,0.000000000000000000e+00,1.000000009922170197e+00,0.000000000000000000e+00,7.092952340576568128e-10,0.000000000000000000e+00 +2.909107063489453182e+01,1.603799999999999955e+02,0.000000000000000000e+00,9.407369806155127634e+00,0.000000000000000000e+00,1.000000009922924260e+00,0.000000000000000000e+00,2.047078597751556000e-10,0.000000000000000000e+00 +2.909213363126929508e+01,1.603900000000000148e+02,0.000000000000000000e+00,9.408432802540438900e+00,0.000000000000000000e+00,1.000000009923141864e+00,0.000000000000000000e+00,-3.808414250412722174e-10,0.000000000000000000e+00 +2.909319650754315134e+01,1.604000000000000057e+02,0.000000000000000000e+00,9.409495678824843168e+00,0.000000000000000000e+00,1.000000009922737076e+00,0.000000000000000000e+00,5.097959711338221266e-10,0.000000000000000000e+00 +2.909425926375680405e+01,1.604099999999999966e+02,0.000000000000000000e+00,9.410558435049040327e+00,0.000000000000000000e+00,1.000000009923278865e+00,0.000000000000000000e+00,-1.858457981314701953e-09,0.000000000000000000e+00 +2.909532189995092821e+01,1.604200000000000159e+02,0.000000000000000000e+00,9.411621071253708948e+00,0.000000000000000000e+00,1.000000009921304001e+00,0.000000000000000000e+00,1.937244305650273428e-09,0.000000000000000000e+00 +2.909638441616617754e+01,1.604300000000000068e+02,0.000000000000000000e+00,9.412683587479500957e+00,0.000000000000000000e+00,1.000000009923362354e+00,0.000000000000000000e+00,-7.058050249790398967e-10,0.000000000000000000e+00 +2.909744681244318798e+01,1.604399999999999977e+02,0.000000000000000000e+00,9.413745983767052294e+00,0.000000000000000000e+00,1.000000009922612509e+00,0.000000000000000000e+00,-3.624530794577488777e-10,0.000000000000000000e+00 +2.909850908882256348e+01,1.604500000000000171e+02,0.000000000000000000e+00,9.414808260156968700e+00,0.000000000000000000e+00,1.000000009922227484e+00,0.000000000000000000e+00,-1.962986430356615223e-10,0.000000000000000000e+00 +2.909957124534489381e+01,1.604600000000000080e+02,0.000000000000000000e+00,9.415870416689836375e+00,0.000000000000000000e+00,1.000000009922018984e+00,0.000000000000000000e+00,1.351456421738352918e-09,0.000000000000000000e+00 +2.910063328205073674e+01,1.604699999999999989e+02,0.000000000000000000e+00,9.416932453406218428e+00,0.000000000000000000e+00,1.000000009923454281e+00,0.000000000000000000e+00,-4.593880964550370074e-10,0.000000000000000000e+00 +2.910169519898063584e+01,1.604799999999999898e+02,0.000000000000000000e+00,9.417994370346656652e+00,0.000000000000000000e+00,1.000000009922966449e+00,0.000000000000000000e+00,-9.211801366454835082e-10,0.000000000000000000e+00 +2.910275699617510980e+01,1.604900000000000091e+02,0.000000000000000000e+00,9.419056167551666192e+00,0.000000000000000000e+00,1.000000009921988342e+00,0.000000000000000000e+00,-4.852165404738398402e-11,0.000000000000000000e+00 +2.910381867367464892e+01,1.605000000000000000e+02,0.000000000000000000e+00,9.420117845061740880e+00,0.000000000000000000e+00,1.000000009921936828e+00,0.000000000000000000e+00,5.672653368328770875e-10,0.000000000000000000e+00 +2.910488023151972925e+01,1.605099999999999909e+02,0.000000000000000000e+00,9.421179402917353229e+00,0.000000000000000000e+00,1.000000009922539013e+00,0.000000000000000000e+00,-6.669047522334219893e-10,0.000000000000000000e+00 +2.910594166975079489e+01,1.605200000000000102e+02,0.000000000000000000e+00,9.422240841158952662e+00,0.000000000000000000e+00,1.000000009921831134e+00,0.000000000000000000e+00,9.630202100619969331e-10,0.000000000000000000e+00 +2.910700298840827571e+01,1.605300000000000011e+02,0.000000000000000000e+00,9.423302159826963731e+00,0.000000000000000000e+00,1.000000009922853206e+00,0.000000000000000000e+00,-8.662508697395406052e-10,0.000000000000000000e+00 +2.910806418753257319e+01,1.605399999999999920e+02,0.000000000000000000e+00,9.424363358961791448e+00,0.000000000000000000e+00,1.000000009921933941e+00,0.000000000000000000e+00,1.374857278432871927e-10,0.000000000000000000e+00 +2.910912526716406745e+01,1.605500000000000114e+02,0.000000000000000000e+00,9.425424438603814181e+00,0.000000000000000000e+00,1.000000009922079824e+00,0.000000000000000000e+00,-7.739413459874479025e-10,0.000000000000000000e+00 +2.911018622734311734e+01,1.605600000000000023e+02,0.000000000000000000e+00,9.426485398793390758e+00,0.000000000000000000e+00,1.000000009921258703e+00,0.000000000000000000e+00,1.118134140839594713e-09,0.000000000000000000e+00 +2.911124706811005680e+01,1.605699999999999932e+02,0.000000000000000000e+00,9.427546239570855136e+00,0.000000000000000000e+00,1.000000009922444866e+00,0.000000000000000000e+00,-5.160072698138709184e-10,0.000000000000000000e+00 +2.911230778950519849e+01,1.605800000000000125e+02,0.000000000000000000e+00,9.428606960976521734e+00,0.000000000000000000e+00,1.000000009921897526e+00,0.000000000000000000e+00,6.220000355008636237e-10,0.000000000000000000e+00 +2.911336839156883016e+01,1.605900000000000034e+02,0.000000000000000000e+00,9.429667563050678325e+00,0.000000000000000000e+00,1.000000009922557220e+00,0.000000000000000000e+00,-1.799836332682850146e-09,0.000000000000000000e+00 +2.911442887434122184e+01,1.605999999999999943e+02,0.000000000000000000e+00,9.430728045833593143e+00,0.000000000000000000e+00,1.000000009920648525e+00,0.000000000000000000e+00,1.679631315268520492e-09,0.000000000000000000e+00 +2.911548923786261867e+01,1.606100000000000136e+02,0.000000000000000000e+00,9.431788409365507775e+00,0.000000000000000000e+00,1.000000009922429545e+00,0.000000000000000000e+00,-1.256566638656432105e-11,0.000000000000000000e+00 +2.911654948217323735e+01,1.606200000000000045e+02,0.000000000000000000e+00,9.432848653686647822e+00,0.000000000000000000e+00,1.000000009922416222e+00,0.000000000000000000e+00,-2.155672936682128651e-09,0.000000000000000000e+00 +2.911760960731328041e+01,1.606299999999999955e+02,0.000000000000000000e+00,9.433908778837210463e+00,0.000000000000000000e+00,1.000000009920130939e+00,0.000000000000000000e+00,1.559959243468982473e-09,0.000000000000000000e+00 +2.911866961332292547e+01,1.606400000000000148e+02,0.000000000000000000e+00,9.434968784857369783e+00,0.000000000000000000e+00,1.000000009921784505e+00,0.000000000000000000e+00,5.237459790784143694e-11,0.000000000000000000e+00 +2.911972950024232532e+01,1.606500000000000057e+02,0.000000000000000000e+00,9.436028671787283884e+00,0.000000000000000000e+00,1.000000009921840016e+00,0.000000000000000000e+00,-3.712728526041223837e-10,0.000000000000000000e+00 +2.912078926811160784e+01,1.606599999999999966e+02,0.000000000000000000e+00,9.437088439667082440e+00,0.000000000000000000e+00,1.000000009921446553e+00,0.000000000000000000e+00,2.747140946813507630e-10,0.000000000000000000e+00 +2.912184891697088673e+01,1.606700000000000159e+02,0.000000000000000000e+00,9.438148088536873814e+00,0.000000000000000000e+00,1.000000009921737654e+00,0.000000000000000000e+00,3.923131424552701066e-10,0.000000000000000000e+00 +2.912290844686024727e+01,1.606800000000000068e+02,0.000000000000000000e+00,9.439207618436745051e+00,0.000000000000000000e+00,1.000000009922153321e+00,0.000000000000000000e+00,-1.617425420074622171e-09,0.000000000000000000e+00 +2.912396785781974984e+01,1.606899999999999977e+02,0.000000000000000000e+00,9.440267029406760102e+00,0.000000000000000000e+00,1.000000009920439803e+00,0.000000000000000000e+00,5.611421291567419583e-10,0.000000000000000000e+00 +2.912502714988944064e+01,1.607000000000000171e+02,0.000000000000000000e+00,9.441326321486958051e+00,0.000000000000000000e+00,1.000000009921034216e+00,0.000000000000000000e+00,5.813304923992420285e-10,0.000000000000000000e+00 +2.912608632310933388e+01,1.607100000000000080e+02,0.000000000000000000e+00,9.442385494717360217e+00,0.000000000000000000e+00,1.000000009921649946e+00,0.000000000000000000e+00,9.434838405259630852e-12,0.000000000000000000e+00 +2.912714537751942956e+01,1.607199999999999989e+02,0.000000000000000000e+00,9.443444549137963051e+00,0.000000000000000000e+00,1.000000009921659938e+00,0.000000000000000000e+00,-1.170470553219795945e-09,0.000000000000000000e+00 +2.912820431315969927e+01,1.607299999999999898e+02,0.000000000000000000e+00,9.444503484788739911e+00,0.000000000000000000e+00,1.000000009920420485e+00,0.000000000000000000e+00,1.778970816467559359e-09,0.000000000000000000e+00 +2.912926313007009682e+01,1.607400000000000091e+02,0.000000000000000000e+00,9.445562301709641062e+00,0.000000000000000000e+00,1.000000009922304089e+00,0.000000000000000000e+00,-6.638068913414010667e-10,0.000000000000000000e+00 +2.913032182829055117e+01,1.607500000000000000e+02,0.000000000000000000e+00,9.446620999940599006e+00,0.000000000000000000e+00,1.000000009921601318e+00,0.000000000000000000e+00,-5.925638718558488174e-10,0.000000000000000000e+00 +2.913138040786096639e+01,1.607599999999999909e+02,0.000000000000000000e+00,9.447679579521517823e+00,0.000000000000000000e+00,1.000000009920974042e+00,0.000000000000000000e+00,-1.193232211889458927e-09,0.000000000000000000e+00 +2.913243886882122879e+01,1.607700000000000102e+02,0.000000000000000000e+00,9.448738040492282053e+00,0.000000000000000000e+00,1.000000009919711053e+00,0.000000000000000000e+00,2.277843445100395745e-09,0.000000000000000000e+00 +2.913349721121119984e+01,1.607800000000000011e+02,0.000000000000000000e+00,9.449796382892753144e+00,0.000000000000000000e+00,1.000000009922121791e+00,0.000000000000000000e+00,-1.297364239048490649e-09,0.000000000000000000e+00 +2.913455543507072321e+01,1.607899999999999920e+02,0.000000000000000000e+00,9.450854606762774779e+00,0.000000000000000000e+00,1.000000009920748889e+00,0.000000000000000000e+00,-8.328991259851970475e-10,0.000000000000000000e+00 +2.913561354043961060e+01,1.608000000000000114e+02,0.000000000000000000e+00,9.451912712142160444e+00,0.000000000000000000e+00,1.000000009919867594e+00,0.000000000000000000e+00,2.071882272286882318e-09,0.000000000000000000e+00 +2.913667152735765953e+01,1.608100000000000023e+02,0.000000000000000000e+00,9.452970699070705862e+00,0.000000000000000000e+00,1.000000009922059618e+00,0.000000000000000000e+00,-2.121440242486452293e-09,0.000000000000000000e+00 +2.913772939586464616e+01,1.608199999999999932e+02,0.000000000000000000e+00,9.454028567588187215e+00,0.000000000000000000e+00,1.000000009919815414e+00,0.000000000000000000e+00,8.564801436019520079e-10,0.000000000000000000e+00 +2.913878714600031827e+01,1.608300000000000125e+02,0.000000000000000000e+00,9.455086317734350487e+00,0.000000000000000000e+00,1.000000009920721356e+00,0.000000000000000000e+00,-1.219780976358921314e-10,0.000000000000000000e+00 +2.913984477780440230e+01,1.608400000000000034e+02,0.000000000000000000e+00,9.456143949548927452e+00,0.000000000000000000e+00,1.000000009920592348e+00,0.000000000000000000e+00,-3.092837105908146054e-10,0.000000000000000000e+00 +2.914090229131660692e+01,1.608499999999999943e+02,0.000000000000000000e+00,9.457201463071623238e+00,0.000000000000000000e+00,1.000000009920265276e+00,0.000000000000000000e+00,2.792894348210341392e-10,0.000000000000000000e+00 +2.914195968657661595e+01,1.608600000000000136e+02,0.000000000000000000e+00,9.458258858342121655e+00,0.000000000000000000e+00,1.000000009920560595e+00,0.000000000000000000e+00,3.948292060780998236e-11,0.000000000000000000e+00 +2.914301696362409189e+01,1.608700000000000045e+02,0.000000000000000000e+00,9.459316135400085201e+00,0.000000000000000000e+00,1.000000009920602340e+00,0.000000000000000000e+00,5.450512346208574395e-10,0.000000000000000000e+00 +2.914407412249867235e+01,1.608799999999999955e+02,0.000000000000000000e+00,9.460373294285153278e+00,0.000000000000000000e+00,1.000000009921178545e+00,0.000000000000000000e+00,-1.399016150481527277e-09,0.000000000000000000e+00 +2.914513116323997721e+01,1.608900000000000148e+02,0.000000000000000000e+00,9.461430335036943973e+00,0.000000000000000000e+00,1.000000009919699728e+00,0.000000000000000000e+00,5.510554627897046640e-10,0.000000000000000000e+00 +2.914618808588759791e+01,1.609000000000000057e+02,0.000000000000000000e+00,9.462487257695050502e+00,0.000000000000000000e+00,1.000000009920282151e+00,0.000000000000000000e+00,2.017050474953318786e-11,0.000000000000000000e+00 +2.914724489048111167e+01,1.609099999999999966e+02,0.000000000000000000e+00,9.463544062299048321e+00,0.000000000000000000e+00,1.000000009920303468e+00,0.000000000000000000e+00,1.731495015663146086e-10,0.000000000000000000e+00 +2.914830157706006730e+01,1.609200000000000159e+02,0.000000000000000000e+00,9.464600748888488013e+00,0.000000000000000000e+00,1.000000009920486432e+00,0.000000000000000000e+00,-5.962135746128502676e-10,0.000000000000000000e+00 +2.914935814566399586e+01,1.609300000000000068e+02,0.000000000000000000e+00,9.465657317502898849e+00,0.000000000000000000e+00,1.000000009919856492e+00,0.000000000000000000e+00,8.787618020917791183e-10,0.000000000000000000e+00 +2.915041459633240351e+01,1.609399999999999977e+02,0.000000000000000000e+00,9.466713768181787003e+00,0.000000000000000000e+00,1.000000009920784860e+00,0.000000000000000000e+00,-1.912849773920794306e-10,0.000000000000000000e+00 +2.915147092910477511e+01,1.609500000000000171e+02,0.000000000000000000e+00,9.467770100964639113e+00,0.000000000000000000e+00,1.000000009920582800e+00,0.000000000000000000e+00,-6.390892505632739955e-10,0.000000000000000000e+00 +2.915252714402057421e+01,1.609600000000000080e+02,0.000000000000000000e+00,9.468826315890916945e+00,0.000000000000000000e+00,1.000000009919907784e+00,0.000000000000000000e+00,-4.795806602186298906e-10,0.000000000000000000e+00 +2.915358324111924304e+01,1.609699999999999989e+02,0.000000000000000000e+00,9.469882413000060950e+00,0.000000000000000000e+00,1.000000009919401300e+00,0.000000000000000000e+00,2.725146243609106415e-10,0.000000000000000000e+00 +2.915463922044019895e+01,1.609799999999999898e+02,0.000000000000000000e+00,9.470938392331490263e+00,0.000000000000000000e+00,1.000000009919689070e+00,0.000000000000000000e+00,8.622180171737682888e-12,0.000000000000000000e+00 +2.915569508202283799e+01,1.609900000000000091e+02,0.000000000000000000e+00,9.471994253924602702e+00,0.000000000000000000e+00,1.000000009919698174e+00,0.000000000000000000e+00,3.064370008402793832e-10,0.000000000000000000e+00 +2.915675082590653489e+01,1.610000000000000000e+02,0.000000000000000000e+00,9.473049997818772994e+00,0.000000000000000000e+00,1.000000009920021693e+00,0.000000000000000000e+00,-4.434050769975156068e-10,0.000000000000000000e+00 +2.915780645213064304e+01,1.610099999999999909e+02,0.000000000000000000e+00,9.474105624053354546e+00,0.000000000000000000e+00,1.000000009919553623e+00,0.000000000000000000e+00,9.323483346658106758e-10,0.000000000000000000e+00 +2.915886196073449455e+01,1.610200000000000102e+02,0.000000000000000000e+00,9.475161132667677677e+00,0.000000000000000000e+00,1.000000009920537725e+00,0.000000000000000000e+00,-3.646073275057190041e-10,0.000000000000000000e+00 +2.915991735175740018e+01,1.610300000000000011e+02,0.000000000000000000e+00,9.476216523701053163e+00,0.000000000000000000e+00,1.000000009920152921e+00,0.000000000000000000e+00,-1.161486800312468202e-09,0.000000000000000000e+00 +2.916097262523864586e+01,1.610399999999999920e+02,0.000000000000000000e+00,9.477271797192766911e+00,0.000000000000000000e+00,1.000000009918927235e+00,0.000000000000000000e+00,1.226851832961313667e-10,0.000000000000000000e+00 +2.916202778121749617e+01,1.610500000000000114e+02,0.000000000000000000e+00,9.478326953182083514e+00,0.000000000000000000e+00,1.000000009919056687e+00,0.000000000000000000e+00,2.818074615953582653e-10,0.000000000000000000e+00 +2.916308281973319438e+01,1.610600000000000023e+02,0.000000000000000000e+00,9.479381991708248023e+00,0.000000000000000000e+00,1.000000009919354005e+00,0.000000000000000000e+00,8.970852072001223712e-10,0.000000000000000000e+00 +2.916413774082496602e+01,1.610699999999999932e+02,0.000000000000000000e+00,9.480436912810482397e+00,0.000000000000000000e+00,1.000000009920300359e+00,0.000000000000000000e+00,-1.241155090657266681e-09,0.000000000000000000e+00 +2.916519254453200816e+01,1.610800000000000125e+02,0.000000000000000000e+00,9.481491716527987279e+00,0.000000000000000000e+00,1.000000009918991184e+00,0.000000000000000000e+00,2.387426169324133464e-10,0.000000000000000000e+00 +2.916624723089349658e+01,1.610900000000000034e+02,0.000000000000000000e+00,9.482546402899938442e+00,0.000000000000000000e+00,1.000000009919242983e+00,0.000000000000000000e+00,5.320720477570293926e-10,0.000000000000000000e+00 +2.916730179994859284e+01,1.610999999999999943e+02,0.000000000000000000e+00,9.483600971965493898e+00,0.000000000000000000e+00,1.000000009919804089e+00,0.000000000000000000e+00,-3.773562116507403446e-10,0.000000000000000000e+00 +2.916835625173642654e+01,1.611100000000000136e+02,0.000000000000000000e+00,9.484655423763788562e+00,0.000000000000000000e+00,1.000000009919406185e+00,0.000000000000000000e+00,-9.081143434401684580e-10,0.000000000000000000e+00 +2.916941058629611305e+01,1.611200000000000045e+02,0.000000000000000000e+00,9.485709758333934261e+00,0.000000000000000000e+00,1.000000009918448729e+00,0.000000000000000000e+00,5.240351681198257807e-10,0.000000000000000000e+00 +2.917046480366674288e+01,1.611299999999999955e+02,0.000000000000000000e+00,9.486763975715021502e+00,0.000000000000000000e+00,1.000000009919001176e+00,0.000000000000000000e+00,7.075682305496656966e-10,0.000000000000000000e+00 +2.917151890388738877e+01,1.611400000000000148e+02,0.000000000000000000e+00,9.487818075946121255e+00,0.000000000000000000e+00,1.000000009919747024e+00,0.000000000000000000e+00,-3.739425898886397881e-10,0.000000000000000000e+00 +2.917257288699709505e+01,1.611500000000000057e+02,0.000000000000000000e+00,9.488872059066281395e+00,0.000000000000000000e+00,1.000000009919352895e+00,0.000000000000000000e+00,-1.136911756532336179e-09,0.000000000000000000e+00 +2.917362675303488828e+01,1.611599999999999966e+02,0.000000000000000000e+00,9.489925925114526706e+00,0.000000000000000000e+00,1.000000009918154742e+00,0.000000000000000000e+00,1.603358476303028112e-09,0.000000000000000000e+00 +2.917468050203977015e+01,1.611700000000000159e+02,0.000000000000000000e+00,9.490979674129860655e+00,0.000000000000000000e+00,1.000000009919844279e+00,0.000000000000000000e+00,-1.766440141460911758e-09,0.000000000000000000e+00 +2.917573413405072813e+01,1.611800000000000068e+02,0.000000000000000000e+00,9.492033306151268945e+00,0.000000000000000000e+00,1.000000009917983101e+00,0.000000000000000000e+00,1.537534165949006334e-09,0.000000000000000000e+00 +2.917678764910671774e+01,1.611899999999999977e+02,0.000000000000000000e+00,9.493086821217708859e+00,0.000000000000000000e+00,1.000000009919602917e+00,0.000000000000000000e+00,-1.301621280114669788e-09,0.000000000000000000e+00 +2.917784104724668381e+01,1.612000000000000171e+02,0.000000000000000000e+00,9.494140219368123468e+00,0.000000000000000000e+00,1.000000009918231791e+00,0.000000000000000000e+00,9.056494750227063234e-10,0.000000000000000000e+00 +2.917889432850954279e+01,1.612100000000000080e+02,0.000000000000000000e+00,9.495193500641427420e+00,0.000000000000000000e+00,1.000000009919185695e+00,0.000000000000000000e+00,1.393623639583726189e-10,0.000000000000000000e+00 +2.917994749293418977e+01,1.612199999999999989e+02,0.000000000000000000e+00,9.496246665076519378e+00,0.000000000000000000e+00,1.000000009919332467e+00,0.000000000000000000e+00,-4.141271425830491247e-10,0.000000000000000000e+00 +2.918100054055949855e+01,1.612299999999999898e+02,0.000000000000000000e+00,9.497299712712273134e+00,0.000000000000000000e+00,1.000000009918896371e+00,0.000000000000000000e+00,-7.690881720870215541e-10,0.000000000000000000e+00 +2.918205347142432160e+01,1.612400000000000091e+02,0.000000000000000000e+00,9.498352643587541166e+00,0.000000000000000000e+00,1.000000009918086574e+00,0.000000000000000000e+00,6.620332937017645688e-10,0.000000000000000000e+00 +2.918310628556749364e+01,1.612500000000000000e+02,0.000000000000000000e+00,9.499405457741154635e+00,0.000000000000000000e+00,1.000000009918783572e+00,0.000000000000000000e+00,-9.439080500193524068e-10,0.000000000000000000e+00 +2.918415898302782097e+01,1.612599999999999909e+02,0.000000000000000000e+00,9.500458155211925160e+00,0.000000000000000000e+00,1.000000009917789923e+00,0.000000000000000000e+00,8.096358783339002112e-10,0.000000000000000000e+00 +2.918521156384409565e+01,1.612700000000000102e+02,0.000000000000000000e+00,9.501510736038639493e+00,0.000000000000000000e+00,1.000000009918642130e+00,0.000000000000000000e+00,-5.050763518993695912e-10,0.000000000000000000e+00 +2.918626402805508491e+01,1.612800000000000011e+02,0.000000000000000000e+00,9.502563200260066623e+00,0.000000000000000000e+00,1.000000009918110555e+00,0.000000000000000000e+00,-9.262868794022536949e-11,0.000000000000000000e+00 +2.918731637569953108e+01,1.612899999999999920e+02,0.000000000000000000e+00,9.503615547914950668e+00,0.000000000000000000e+00,1.000000009918013077e+00,0.000000000000000000e+00,4.285870142742901040e-10,0.000000000000000000e+00 +2.918836860681616230e+01,1.613000000000000114e+02,0.000000000000000000e+00,9.504667779042016207e+00,0.000000000000000000e+00,1.000000009918464050e+00,0.000000000000000000e+00,-5.615934597365159138e-10,0.000000000000000000e+00 +2.918942072144367827e+01,1.613100000000000023e+02,0.000000000000000000e+00,9.505719893679966503e+00,0.000000000000000000e+00,1.000000009917873189e+00,0.000000000000000000e+00,1.317072942631791491e-10,0.000000000000000000e+00 +2.919047271962076096e+01,1.613199999999999932e+02,0.000000000000000000e+00,9.506771891867481727e+00,0.000000000000000000e+00,1.000000009918011745e+00,0.000000000000000000e+00,8.887004391225271553e-10,0.000000000000000000e+00 +2.919152460138606742e+01,1.613300000000000125e+02,0.000000000000000000e+00,9.507823773643222509e+00,0.000000000000000000e+00,1.000000009918946553e+00,0.000000000000000000e+00,-1.516869159470836159e-09,0.000000000000000000e+00 +2.919257636677824053e+01,1.613400000000000034e+02,0.000000000000000000e+00,9.508875539045828162e+00,0.000000000000000000e+00,1.000000009917351163e+00,0.000000000000000000e+00,9.283801670797343721e-10,0.000000000000000000e+00 +2.919362801583589473e+01,1.613499999999999943e+02,0.000000000000000000e+00,9.509927188113913132e+00,0.000000000000000000e+00,1.000000009918327493e+00,0.000000000000000000e+00,1.807553589700085967e-10,0.000000000000000000e+00 +2.919467954859762671e+01,1.613600000000000136e+02,0.000000000000000000e+00,9.510978720886075877e+00,0.000000000000000000e+00,1.000000009918517563e+00,0.000000000000000000e+00,-5.636558376941311340e-10,0.000000000000000000e+00 +2.919573096510201182e+01,1.613700000000000045e+02,0.000000000000000000e+00,9.512030137400889984e+00,0.000000000000000000e+00,1.000000009917924926e+00,0.000000000000000000e+00,2.876673354443862081e-10,0.000000000000000000e+00 +2.919678226538760413e+01,1.613799999999999955e+02,0.000000000000000000e+00,9.513081437696907727e+00,0.000000000000000000e+00,1.000000009918227351e+00,0.000000000000000000e+00,-4.942848478120157403e-10,0.000000000000000000e+00 +2.919783344949293280e+01,1.613900000000000148e+02,0.000000000000000000e+00,9.514132621812661839e+00,0.000000000000000000e+00,1.000000009917707766e+00,0.000000000000000000e+00,-1.317393550462314793e-09,0.000000000000000000e+00 +2.919888451745650926e+01,1.614000000000000057e+02,0.000000000000000000e+00,9.515183689786661958e+00,0.000000000000000000e+00,1.000000009916323096e+00,0.000000000000000000e+00,2.627894673724961834e-09,0.000000000000000000e+00 +2.919993546931682360e+01,1.614099999999999966e+02,0.000000000000000000e+00,9.516234641657396409e+00,0.000000000000000000e+00,1.000000009919084887e+00,0.000000000000000000e+00,-1.538496095541297571e-09,0.000000000000000000e+00 +2.920098630511234106e+01,1.614200000000000159e+02,0.000000000000000000e+00,9.517285477463337529e+00,0.000000000000000000e+00,1.000000009917468180e+00,0.000000000000000000e+00,-9.663946640356933226e-10,0.000000000000000000e+00 +2.920203702488150910e+01,1.614300000000000068e+02,0.000000000000000000e+00,9.518336197242927454e+00,0.000000000000000000e+00,1.000000009916452770e+00,0.000000000000000000e+00,1.115714116323061220e-09,0.000000000000000000e+00 +2.920308762866275742e+01,1.614399999999999977e+02,0.000000000000000000e+00,9.519386801034592338e+00,0.000000000000000000e+00,1.000000009917624944e+00,0.000000000000000000e+00,-1.361241141998598648e-10,0.000000000000000000e+00 +2.920413811649448377e+01,1.614500000000000171e+02,0.000000000000000000e+00,9.520437288876738791e+00,0.000000000000000000e+00,1.000000009917481947e+00,0.000000000000000000e+00,9.090035467045338518e-11,0.000000000000000000e+00 +2.920518848841507520e+01,1.614600000000000080e+02,0.000000000000000000e+00,9.521487660807748554e+00,0.000000000000000000e+00,1.000000009917577426e+00,0.000000000000000000e+00,1.733639872072945802e-10,0.000000000000000000e+00 +2.920623874446289392e+01,1.614699999999999989e+02,0.000000000000000000e+00,9.522537916865983831e+00,0.000000000000000000e+00,1.000000009917759503e+00,0.000000000000000000e+00,9.578359608442645987e-11,0.000000000000000000e+00 +2.920728888467628082e+01,1.614799999999999898e+02,0.000000000000000000e+00,9.523588057089785508e+00,0.000000000000000000e+00,1.000000009917860089e+00,0.000000000000000000e+00,-1.768068352732747664e-09,0.000000000000000000e+00 +2.920833890909355546e+01,1.614900000000000091e+02,0.000000000000000000e+00,9.524638081517473154e+00,0.000000000000000000e+00,1.000000009916003574e+00,0.000000000000000000e+00,1.012399997085114720e-09,0.000000000000000000e+00 +2.920938881775301610e+01,1.615000000000000000e+02,0.000000000000000000e+00,9.525687990187343246e+00,0.000000000000000000e+00,1.000000009917066501e+00,0.000000000000000000e+00,3.663401048959896903e-10,0.000000000000000000e+00 +2.921043861069293968e+01,1.615099999999999909e+02,0.000000000000000000e+00,9.526737783137676274e+00,0.000000000000000000e+00,1.000000009917451083e+00,0.000000000000000000e+00,-4.994366677110850944e-10,0.000000000000000000e+00 +2.921148828795158181e+01,1.615200000000000102e+02,0.000000000000000000e+00,9.527787460406727860e+00,0.000000000000000000e+00,1.000000009916926835e+00,0.000000000000000000e+00,1.248200343448850710e-11,0.000000000000000000e+00 +2.921253784956717681e+01,1.615300000000000011e+02,0.000000000000000000e+00,9.528837022032732307e+00,0.000000000000000000e+00,1.000000009916939936e+00,0.000000000000000000e+00,2.767501522353568576e-10,0.000000000000000000e+00 +2.921358729557794121e+01,1.615399999999999920e+02,0.000000000000000000e+00,9.529886468053904380e+00,0.000000000000000000e+00,1.000000009917230370e+00,0.000000000000000000e+00,2.767806317519496299e-10,0.000000000000000000e+00 +2.921463662602206668e+01,1.615500000000000114e+02,0.000000000000000000e+00,9.530935798508437529e+00,0.000000000000000000e+00,1.000000009917520805e+00,0.000000000000000000e+00,-1.614943092107920817e-09,0.000000000000000000e+00 +2.921568584093772714e+01,1.615600000000000023e+02,0.000000000000000000e+00,9.531985013434503884e+00,0.000000000000000000e+00,1.000000009915826382e+00,0.000000000000000000e+00,1.041542369042662636e-09,0.000000000000000000e+00 +2.921673494036307162e+01,1.615699999999999932e+02,0.000000000000000000e+00,9.533034112870252486e+00,0.000000000000000000e+00,1.000000009916919064e+00,0.000000000000000000e+00,1.623553994483436362e-10,0.000000000000000000e+00 +2.921778392433623139e+01,1.615800000000000125e+02,0.000000000000000000e+00,9.534083096853816386e+00,0.000000000000000000e+00,1.000000009917089372e+00,0.000000000000000000e+00,5.749749496753989801e-10,0.000000000000000000e+00 +2.921883279289531643e+01,1.615900000000000034e+02,0.000000000000000000e+00,9.535131965423303768e+00,0.000000000000000000e+00,1.000000009917692445e+00,0.000000000000000000e+00,-9.643958099326421113e-10,0.000000000000000000e+00 +2.921988154607841537e+01,1.615999999999999943e+02,0.000000000000000000e+00,9.536180718616803276e+00,0.000000000000000000e+00,1.000000009916681032e+00,0.000000000000000000e+00,-1.241888812113235340e-09,0.000000000000000000e+00 +2.922093018392359198e+01,1.616100000000000136e+02,0.000000000000000000e+00,9.537229356472380459e+00,0.000000000000000000e+00,1.000000009915378740e+00,0.000000000000000000e+00,1.345792201243466949e-09,0.000000000000000000e+00 +2.922197870646889584e+01,1.616200000000000045e+02,0.000000000000000000e+00,9.538277879028081330e+00,0.000000000000000000e+00,1.000000009916789834e+00,0.000000000000000000e+00,3.206535638977329093e-10,0.000000000000000000e+00 +2.922302711375235162e+01,1.616299999999999955e+02,0.000000000000000000e+00,9.539326286321934134e+00,0.000000000000000000e+00,1.000000009917126009e+00,0.000000000000000000e+00,-1.101229271384956757e-09,0.000000000000000000e+00 +2.922407540581196272e+01,1.616400000000000148e+02,0.000000000000000000e+00,9.540374578391942251e+00,0.000000000000000000e+00,1.000000009915971599e+00,0.000000000000000000e+00,2.991164850183341515e-10,0.000000000000000000e+00 +2.922512358268571475e+01,1.616500000000000057e+02,0.000000000000000000e+00,9.541422755276087742e+00,0.000000000000000000e+00,1.000000009916285126e+00,0.000000000000000000e+00,-3.432166742711132127e-10,0.000000000000000000e+00 +2.922617164441156845e+01,1.616599999999999966e+02,0.000000000000000000e+00,9.542470817012334905e+00,0.000000000000000000e+00,1.000000009915925414e+00,0.000000000000000000e+00,1.915444162965218979e-10,0.000000000000000000e+00 +2.922721959102746681e+01,1.616700000000000159e+02,0.000000000000000000e+00,9.543518763638624947e+00,0.000000000000000000e+00,1.000000009916126142e+00,0.000000000000000000e+00,2.718788432997854858e-10,0.000000000000000000e+00 +2.922826742257133148e+01,1.616800000000000068e+02,0.000000000000000000e+00,9.544566595192879532e+00,0.000000000000000000e+00,1.000000009916411026e+00,0.000000000000000000e+00,-1.176222332939691005e-10,0.000000000000000000e+00 +2.922931513908106282e+01,1.616899999999999977e+02,0.000000000000000000e+00,9.545614311712999012e+00,0.000000000000000000e+00,1.000000009916287791e+00,0.000000000000000000e+00,6.265396180854226976e-10,0.000000000000000000e+00 +2.923036274059453632e+01,1.617000000000000171e+02,0.000000000000000000e+00,9.546661913236862418e+00,0.000000000000000000e+00,1.000000009916944155e+00,0.000000000000000000e+00,-7.463762185301756102e-10,0.000000000000000000e+00 +2.923141022714961679e+01,1.617100000000000080e+02,0.000000000000000000e+00,9.547709399802329244e+00,0.000000000000000000e+00,1.000000009916162336e+00,0.000000000000000000e+00,-1.015064312742754077e-09,0.000000000000000000e+00 +2.923245759878413708e+01,1.617199999999999989e+02,0.000000000000000000e+00,9.548756771447235892e+00,0.000000000000000000e+00,1.000000009915099186e+00,0.000000000000000000e+00,1.427988324380560868e-09,0.000000000000000000e+00 +2.923350485553591582e+01,1.617299999999999898e+02,0.000000000000000000e+00,9.549804028209399220e+00,0.000000000000000000e+00,1.000000009916594657e+00,0.000000000000000000e+00,-1.531412434457385833e-09,0.000000000000000000e+00 +2.923455199744275035e+01,1.617400000000000091e+02,0.000000000000000000e+00,9.550851170126618328e+00,0.000000000000000000e+00,1.000000009914991050e+00,0.000000000000000000e+00,1.432330893958670300e-09,0.000000000000000000e+00 +2.923559902454241666e+01,1.617500000000000000e+02,0.000000000000000000e+00,9.551898197236665666e+00,0.000000000000000000e+00,1.000000009916490740e+00,0.000000000000000000e+00,-1.037779592906829038e-09,0.000000000000000000e+00 +2.923664593687266944e+01,1.617599999999999909e+02,0.000000000000000000e+00,9.552945109577299476e+00,0.000000000000000000e+00,1.000000009915404275e+00,0.000000000000000000e+00,7.682913680115748984e-10,0.000000000000000000e+00 +2.923769273447124206e+01,1.617700000000000102e+02,0.000000000000000000e+00,9.553991907186251353e+00,0.000000000000000000e+00,1.000000009916208521e+00,0.000000000000000000e+00,-1.269665296555138274e-09,0.000000000000000000e+00 +2.923873941737585014e+01,1.617800000000000011e+02,0.000000000000000000e+00,9.555038590101236906e+00,0.000000000000000000e+00,1.000000009914879584e+00,0.000000000000000000e+00,9.413737839087761332e-10,0.000000000000000000e+00 +2.923978598562418441e+01,1.617899999999999920e+02,0.000000000000000000e+00,9.556085158359946874e+00,0.000000000000000000e+00,1.000000009915864796e+00,0.000000000000000000e+00,-7.220747953762018747e-10,0.000000000000000000e+00 +2.924083243925391784e+01,1.618000000000000114e+02,0.000000000000000000e+00,9.557131612000056009e+00,0.000000000000000000e+00,1.000000009915109178e+00,0.000000000000000000e+00,2.139086389107104903e-10,0.000000000000000000e+00 +2.924187877830270210e+01,1.618100000000000023e+02,0.000000000000000000e+00,9.558177951059214195e+00,0.000000000000000000e+00,1.000000009915332999e+00,0.000000000000000000e+00,4.908976691986302062e-10,0.000000000000000000e+00 +2.924292500280816753e+01,1.618199999999999932e+02,0.000000000000000000e+00,9.559224175575053550e+00,0.000000000000000000e+00,1.000000009915846588e+00,0.000000000000000000e+00,9.339326284003632665e-11,0.000000000000000000e+00 +2.924397111280792672e+01,1.618300000000000125e+02,0.000000000000000000e+00,9.560270285585184880e+00,0.000000000000000000e+00,1.000000009915944288e+00,0.000000000000000000e+00,-9.930488519486746140e-10,0.000000000000000000e+00 +2.924501710833956736e+01,1.618400000000000034e+02,0.000000000000000000e+00,9.561316281127197669e+00,0.000000000000000000e+00,1.000000009914905563e+00,0.000000000000000000e+00,4.645208667299074146e-10,0.000000000000000000e+00 +2.924606298944065941e+01,1.618499999999999943e+02,0.000000000000000000e+00,9.562362162238660090e+00,0.000000000000000000e+00,1.000000009915391397e+00,0.000000000000000000e+00,-4.193460083717093513e-10,0.000000000000000000e+00 +2.924710875614875150e+01,1.618600000000000136e+02,0.000000000000000000e+00,9.563407928957122550e+00,0.000000000000000000e+00,1.000000009914952859e+00,0.000000000000000000e+00,-4.117472579389738265e-10,0.000000000000000000e+00 +2.924815440850137449e+01,1.618700000000000045e+02,0.000000000000000000e+00,9.564453581320112363e+00,0.000000000000000000e+00,1.000000009914522314e+00,0.000000000000000000e+00,4.744424697704447748e-10,0.000000000000000000e+00 +2.924919994653603439e+01,1.618799999999999955e+02,0.000000000000000000e+00,9.565499119365137304e+00,0.000000000000000000e+00,1.000000009915018362e+00,0.000000000000000000e+00,5.991712240966740905e-10,0.000000000000000000e+00 +2.925024537029021587e+01,1.618900000000000148e+02,0.000000000000000000e+00,9.566544543129685607e+00,0.000000000000000000e+00,1.000000009915644750e+00,0.000000000000000000e+00,-1.677692846905071377e-09,0.000000000000000000e+00 +2.925129067980138942e+01,1.619000000000000057e+02,0.000000000000000000e+00,9.567589852651224192e+00,0.000000000000000000e+00,1.000000009913891041e+00,0.000000000000000000e+00,1.758392125470335744e-09,0.000000000000000000e+00 +2.925233587510700062e+01,1.619099999999999966e+02,0.000000000000000000e+00,9.568635047967196883e+00,0.000000000000000000e+00,1.000000009915728905e+00,0.000000000000000000e+00,-4.880352723097980740e-10,0.000000000000000000e+00 +2.925338095624447377e+01,1.619200000000000159e+02,0.000000000000000000e+00,9.569680129115033296e+00,0.000000000000000000e+00,1.000000009915218868e+00,0.000000000000000000e+00,-3.019476993653671998e-10,0.000000000000000000e+00 +2.925442592325121538e+01,1.619300000000000068e+02,0.000000000000000000e+00,9.570725096132136400e+00,0.000000000000000000e+00,1.000000009914903343e+00,0.000000000000000000e+00,-9.492946207872387914e-10,0.000000000000000000e+00 +2.925547077616461067e+01,1.619399999999999977e+02,0.000000000000000000e+00,9.571769949055891402e+00,0.000000000000000000e+00,1.000000009913911470e+00,0.000000000000000000e+00,8.097621130499042479e-10,0.000000000000000000e+00 +2.925651551502202352e+01,1.619500000000000171e+02,0.000000000000000000e+00,9.572814687923662191e+00,0.000000000000000000e+00,1.000000009914757459e+00,0.000000000000000000e+00,7.885945783536026840e-11,0.000000000000000000e+00 +2.925756013986080006e+01,1.619600000000000080e+02,0.000000000000000000e+00,9.573859312772794894e+00,0.000000000000000000e+00,1.000000009914839838e+00,0.000000000000000000e+00,9.821305996251597283e-11,0.000000000000000000e+00 +2.925860465071826155e+01,1.619699999999999989e+02,0.000000000000000000e+00,9.574903823640612543e+00,0.000000000000000000e+00,1.000000009914942423e+00,0.000000000000000000e+00,-7.736716825907527517e-10,0.000000000000000000e+00 +2.925964904763171148e+01,1.619799999999999898e+02,0.000000000000000000e+00,9.575948220564418634e+00,0.000000000000000000e+00,1.000000009914134402e+00,0.000000000000000000e+00,7.057148675227621046e-10,0.000000000000000000e+00 +2.926069333063843558e+01,1.619900000000000091e+02,0.000000000000000000e+00,9.576992503581495342e+00,0.000000000000000000e+00,1.000000009914871368e+00,0.000000000000000000e+00,-1.994037350929371597e-09,0.000000000000000000e+00 +2.926173749977569472e+01,1.620000000000000000e+02,0.000000000000000000e+00,9.578036672729107082e+00,0.000000000000000000e+00,1.000000009912789256e+00,0.000000000000000000e+00,2.518711646251743540e-09,0.000000000000000000e+00 +2.926278155508073198e+01,1.620099999999999909e+02,0.000000000000000000e+00,9.579080728044493398e+00,0.000000000000000000e+00,1.000000009915418930e+00,0.000000000000000000e+00,-2.066151476403637404e-09,0.000000000000000000e+00 +2.926382549659076915e+01,1.620200000000000102e+02,0.000000000000000000e+00,9.580124669564881401e+00,0.000000000000000000e+00,1.000000009913261989e+00,0.000000000000000000e+00,2.165504867339029452e-09,0.000000000000000000e+00 +2.926486932434300670e+01,1.620300000000000011e+02,0.000000000000000000e+00,9.581168497327468003e+00,0.000000000000000000e+00,1.000000009915522403e+00,0.000000000000000000e+00,-2.732705380829510224e-09,0.000000000000000000e+00 +2.926591303837463087e+01,1.620399999999999920e+02,0.000000000000000000e+00,9.582212211369439459e+00,0.000000000000000000e+00,1.000000009912670240e+00,0.000000000000000000e+00,2.791301456660636668e-09,0.000000000000000000e+00 +2.926695663872279951e+01,1.620500000000000114e+02,0.000000000000000000e+00,9.583255811727951823e+00,0.000000000000000000e+00,1.000000009915583243e+00,0.000000000000000000e+00,-2.477525904785971651e-09,0.000000000000000000e+00 +2.926800012542465268e+01,1.620600000000000023e+02,0.000000000000000000e+00,9.584299298440152270e+00,0.000000000000000000e+00,1.000000009912997978e+00,0.000000000000000000e+00,1.020656879798109022e-09,0.000000000000000000e+00 +2.926904349851731268e+01,1.620699999999999932e+02,0.000000000000000000e+00,9.585342671543156001e+00,0.000000000000000000e+00,1.000000009914062904e+00,0.000000000000000000e+00,2.202866703503928541e-10,0.000000000000000000e+00 +2.927008675803788051e+01,1.620800000000000125e+02,0.000000000000000000e+00,9.586385931074067557e+00,0.000000000000000000e+00,1.000000009914292720e+00,0.000000000000000000e+00,2.341465804396641577e-12,0.000000000000000000e+00 +2.927112990402343584e+01,1.620900000000000034e+02,0.000000000000000000e+00,9.587429077069966610e+00,0.000000000000000000e+00,1.000000009914295163e+00,0.000000000000000000e+00,-1.280921163731685081e-09,0.000000000000000000e+00 +2.927217293651104058e+01,1.620999999999999943e+02,0.000000000000000000e+00,9.588472109567913293e+00,0.000000000000000000e+00,1.000000009912959120e+00,0.000000000000000000e+00,1.256363322678316830e-09,0.000000000000000000e+00 +2.927321585553773531e+01,1.621100000000000136e+02,0.000000000000000000e+00,9.589515028604946423e+00,0.000000000000000000e+00,1.000000009914269405e+00,0.000000000000000000e+00,-5.649033101493320987e-10,0.000000000000000000e+00 +2.927425866114053932e+01,1.621200000000000045e+02,0.000000000000000000e+00,9.590557834218088828e+00,0.000000000000000000e+00,1.000000009913680321e+00,0.000000000000000000e+00,-2.274339775830673597e-10,0.000000000000000000e+00 +2.927530135335645056e+01,1.621299999999999955e+02,0.000000000000000000e+00,9.591600526444338470e+00,0.000000000000000000e+00,1.000000009913443177e+00,0.000000000000000000e+00,-1.011211543379302774e-09,0.000000000000000000e+00 +2.927634393222245279e+01,1.621400000000000148e+02,0.000000000000000000e+00,9.592643105320675545e+00,0.000000000000000000e+00,1.000000009912388910e+00,0.000000000000000000e+00,1.972588043983031881e-09,0.000000000000000000e+00 +2.927738639777550134e+01,1.621500000000000057e+02,0.000000000000000000e+00,9.593685570884058933e+00,0.000000000000000000e+00,1.000000009914445265e+00,0.000000000000000000e+00,-1.097705520853099516e-09,0.000000000000000000e+00 +2.927842875005254086e+01,1.621599999999999966e+02,0.000000000000000000e+00,9.594727923171431527e+00,0.000000000000000000e+00,1.000000009913301069e+00,0.000000000000000000e+00,-4.282219717838170932e-10,0.000000000000000000e+00 +2.927947098909048762e+01,1.621700000000000159e+02,0.000000000000000000e+00,9.595770162219709576e+00,0.000000000000000000e+00,1.000000009912854759e+00,0.000000000000000000e+00,6.984398524369207925e-10,0.000000000000000000e+00 +2.928051311492624009e+01,1.621800000000000068e+02,0.000000000000000000e+00,9.596812288065793339e+00,0.000000000000000000e+00,1.000000009913582621e+00,0.000000000000000000e+00,-1.003876597162677444e-09,0.000000000000000000e+00 +2.928155512759667900e+01,1.621899999999999977e+02,0.000000000000000000e+00,9.597854300746563538e+00,0.000000000000000000e+00,1.000000009912536569e+00,0.000000000000000000e+00,9.948216445262437510e-10,0.000000000000000000e+00 +2.928259702713866375e+01,1.622000000000000171e+02,0.000000000000000000e+00,9.598896200298877801e+00,0.000000000000000000e+00,1.000000009913573074e+00,0.000000000000000000e+00,1.361953810173007101e-10,0.000000000000000000e+00 +2.928363881358903598e+01,1.622100000000000080e+02,0.000000000000000000e+00,9.599937986759577768e+00,0.000000000000000000e+00,1.000000009913714960e+00,0.000000000000000000e+00,-3.223001029613144454e-10,0.000000000000000000e+00 +2.928468048698461246e+01,1.622199999999999989e+02,0.000000000000000000e+00,9.600979660165481988e+00,0.000000000000000000e+00,1.000000009913379229e+00,0.000000000000000000e+00,-3.935387227797066923e-10,0.000000000000000000e+00 +2.928572204736219575e+01,1.622299999999999898e+02,0.000000000000000000e+00,9.602021220553389469e+00,0.000000000000000000e+00,1.000000009912969334e+00,0.000000000000000000e+00,-9.167931136118039795e-11,0.000000000000000000e+00 +2.928676349475856355e+01,1.622400000000000091e+02,0.000000000000000000e+00,9.603062667960079679e+00,0.000000000000000000e+00,1.000000009912873855e+00,0.000000000000000000e+00,-1.068286436344933824e-09,0.000000000000000000e+00 +2.928780482921047223e+01,1.622500000000000000e+02,0.000000000000000000e+00,9.604104002422312547e+00,0.000000000000000000e+00,1.000000009911761412e+00,0.000000000000000000e+00,1.577012944629374596e-09,0.000000000000000000e+00 +2.928884605075466752e+01,1.622599999999999909e+02,0.000000000000000000e+00,9.605145223976826685e+00,0.000000000000000000e+00,1.000000009913403431e+00,0.000000000000000000e+00,-3.612913526000293254e-10,0.000000000000000000e+00 +2.928988715942786314e+01,1.622700000000000102e+02,0.000000000000000000e+00,9.606186332660344718e+00,0.000000000000000000e+00,1.000000009913027288e+00,0.000000000000000000e+00,-3.434132977005600856e-10,0.000000000000000000e+00 +2.929092815526676219e+01,1.622800000000000011e+02,0.000000000000000000e+00,9.607227328509564401e+00,0.000000000000000000e+00,1.000000009912669796e+00,0.000000000000000000e+00,-2.175897656515547704e-11,0.000000000000000000e+00 +2.929196903830804644e+01,1.622899999999999920e+02,0.000000000000000000e+00,9.608268211561165728e+00,0.000000000000000000e+00,1.000000009912647148e+00,0.000000000000000000e+00,-1.049877692984424374e-09,0.000000000000000000e+00 +2.929300980858837278e+01,1.623000000000000114e+02,0.000000000000000000e+00,9.609308981851809150e+00,0.000000000000000000e+00,1.000000009911554466e+00,0.000000000000000000e+00,1.478650785019142757e-09,0.000000000000000000e+00 +2.929405046614438390e+01,1.623100000000000023e+02,0.000000000000000000e+00,9.610349639418133805e+00,0.000000000000000000e+00,1.000000009913093235e+00,0.000000000000000000e+00,-6.512743033649602800e-10,0.000000000000000000e+00 +2.929509101101269763e+01,1.623199999999999932e+02,0.000000000000000000e+00,9.611390184296762840e+00,0.000000000000000000e+00,1.000000009912415555e+00,0.000000000000000000e+00,7.486623935573764315e-10,0.000000000000000000e+00 +2.929613144322991758e+01,1.623300000000000125e+02,0.000000000000000000e+00,9.612430616524294535e+00,0.000000000000000000e+00,1.000000009913194488e+00,0.000000000000000000e+00,-8.990043766488115115e-10,0.000000000000000000e+00 +2.929717176283262248e+01,1.623400000000000034e+02,0.000000000000000000e+00,9.613470936137311185e+00,0.000000000000000000e+00,1.000000009912259236e+00,0.000000000000000000e+00,-6.847858893960999016e-10,0.000000000000000000e+00 +2.929821196985737330e+01,1.623499999999999943e+02,0.000000000000000000e+00,9.614511143172371987e+00,0.000000000000000000e+00,1.000000009911546917e+00,0.000000000000000000e+00,1.379326797135964311e-09,0.000000000000000000e+00 +2.929925206434070972e+01,1.623600000000000136e+02,0.000000000000000000e+00,9.615551237666018380e+00,0.000000000000000000e+00,1.000000009912981547e+00,0.000000000000000000e+00,-1.290016106780324678e-09,0.000000000000000000e+00 +2.930029204631915718e+01,1.623700000000000045e+02,0.000000000000000000e+00,9.616591219654774036e+00,0.000000000000000000e+00,1.000000009911639953e+00,0.000000000000000000e+00,-4.949653675181357175e-10,0.000000000000000000e+00 +2.930133191582921270e+01,1.623799999999999955e+02,0.000000000000000000e+00,9.617631089175137760e+00,0.000000000000000000e+00,1.000000009911125254e+00,0.000000000000000000e+00,2.109275915435811769e-09,0.000000000000000000e+00 +2.930237167290736267e+01,1.623900000000000148e+02,0.000000000000000000e+00,9.618670846263592367e+00,0.000000000000000000e+00,1.000000009913318388e+00,0.000000000000000000e+00,-1.707337709989235437e-09,0.000000000000000000e+00 +2.930341131759006856e+01,1.624000000000000057e+02,0.000000000000000000e+00,9.619710490956602911e+00,0.000000000000000000e+00,1.000000009911543364e+00,0.000000000000000000e+00,-4.558234276186598864e-10,0.000000000000000000e+00 +2.930445084991377058e+01,1.624099999999999966e+02,0.000000000000000000e+00,9.620750023290607800e+00,0.000000000000000000e+00,1.000000009911069521e+00,0.000000000000000000e+00,9.213584306711461699e-10,0.000000000000000000e+00 +2.930549026991489114e+01,1.624200000000000159e+02,0.000000000000000000e+00,9.621789443302031231e+00,0.000000000000000000e+00,1.000000009912027199e+00,0.000000000000000000e+00,7.648549839483215119e-10,0.000000000000000000e+00 +2.930652957762983490e+01,1.624300000000000068e+02,0.000000000000000000e+00,9.622828751027277860e+00,0.000000000000000000e+00,1.000000009912822119e+00,0.000000000000000000e+00,-9.390784230404154797e-10,0.000000000000000000e+00 +2.930756877309498520e+01,1.624399999999999977e+02,0.000000000000000000e+00,9.623867946502731030e+00,0.000000000000000000e+00,1.000000009911846233e+00,0.000000000000000000e+00,-9.154599363640536904e-10,0.000000000000000000e+00 +2.930860785634670762e+01,1.624500000000000171e+02,0.000000000000000000e+00,9.624907029764752764e+00,0.000000000000000000e+00,1.000000009910894994e+00,0.000000000000000000e+00,8.232335230985172707e-10,0.000000000000000000e+00 +2.930964682742134642e+01,1.624600000000000080e+02,0.000000000000000000e+00,9.625946000849687323e+00,0.000000000000000000e+00,1.000000009911750309e+00,0.000000000000000000e+00,-6.728501758129738494e-10,0.000000000000000000e+00 +2.931068568635522453e+01,1.624699999999999989e+02,0.000000000000000000e+00,9.626984859793861204e+00,0.000000000000000000e+00,1.000000009911051313e+00,0.000000000000000000e+00,1.165216689152622505e-09,0.000000000000000000e+00 +2.931172443318464715e+01,1.624799999999999898e+02,0.000000000000000000e+00,9.628023606633577813e+00,0.000000000000000000e+00,1.000000009912261678e+00,0.000000000000000000e+00,-1.907604177775277392e-09,0.000000000000000000e+00 +2.931276306794589814e+01,1.624900000000000091e+02,0.000000000000000000e+00,9.629062241405124567e+00,0.000000000000000000e+00,1.000000009910280374e+00,0.000000000000000000e+00,1.621307065859391143e-09,0.000000000000000000e+00 +2.931380159067524716e+01,1.625000000000000000e+02,0.000000000000000000e+00,9.630100764144764014e+00,0.000000000000000000e+00,1.000000009911964138e+00,0.000000000000000000e+00,-1.436945609946179051e-09,0.000000000000000000e+00 +2.931484000140893542e+01,1.625099999999999909e+02,0.000000000000000000e+00,9.631139174888746268e+00,0.000000000000000000e+00,1.000000009910471999e+00,0.000000000000000000e+00,2.082298825498523736e-09,0.000000000000000000e+00 +2.931587830018319352e+01,1.625200000000000102e+02,0.000000000000000000e+00,9.632177473673294799e+00,0.000000000000000000e+00,1.000000009912634047e+00,0.000000000000000000e+00,-2.663841823449272861e-09,0.000000000000000000e+00 +2.931691648703422715e+01,1.625300000000000011e+02,0.000000000000000000e+00,9.633215660534620639e+00,0.000000000000000000e+00,1.000000009909868481e+00,0.000000000000000000e+00,2.439105765740829079e-09,0.000000000000000000e+00 +2.931795456199822425e+01,1.625399999999999920e+02,0.000000000000000000e+00,9.634253735508906402e+00,0.000000000000000000e+00,1.000000009912400456e+00,0.000000000000000000e+00,-2.402573777782202832e-09,0.000000000000000000e+00 +2.931899252511135501e+01,1.625500000000000114e+02,0.000000000000000000e+00,9.635291698632325819e+00,0.000000000000000000e+00,1.000000009909906673e+00,0.000000000000000000e+00,9.325925923584124268e-10,0.000000000000000000e+00 +2.932003037640976828e+01,1.625600000000000023e+02,0.000000000000000000e+00,9.636329549941022421e+00,0.000000000000000000e+00,1.000000009910874565e+00,0.000000000000000000e+00,8.892572369479908786e-10,0.000000000000000000e+00 +2.932106811592959161e+01,1.625699999999999932e+02,0.000000000000000000e+00,9.637367289471129084e+00,0.000000000000000000e+00,1.000000009911797383e+00,0.000000000000000000e+00,-8.983406880869137342e-10,0.000000000000000000e+00 +2.932210574370693479e+01,1.625800000000000125e+02,0.000000000000000000e+00,9.638404917258755589e+00,0.000000000000000000e+00,1.000000009910865240e+00,0.000000000000000000e+00,-1.144555328236314559e-09,0.000000000000000000e+00 +2.932314325977788627e+01,1.625900000000000034e+02,0.000000000000000000e+00,9.639442433339990401e+00,0.000000000000000000e+00,1.000000009909677745e+00,0.000000000000000000e+00,1.788292659078552328e-09,0.000000000000000000e+00 +2.932418066417852032e+01,1.625999999999999943e+02,0.000000000000000000e+00,9.640479837750904224e+00,0.000000000000000000e+00,1.000000009911532928e+00,0.000000000000000000e+00,-2.016460777723183755e-09,0.000000000000000000e+00 +2.932521795694488631e+01,1.626100000000000136e+02,0.000000000000000000e+00,9.641517130527551771e+00,0.000000000000000000e+00,1.000000009909441268e+00,0.000000000000000000e+00,2.284925855946985451e-09,0.000000000000000000e+00 +2.932625513811301943e+01,1.626200000000000045e+02,0.000000000000000000e+00,9.642554311705961112e+00,0.000000000000000000e+00,1.000000009911811150e+00,0.000000000000000000e+00,-1.832547943478675568e-09,0.000000000000000000e+00 +2.932729220771892997e+01,1.626299999999999955e+02,0.000000000000000000e+00,9.643591381322149658e+00,0.000000000000000000e+00,1.000000009909910670e+00,0.000000000000000000e+00,4.794387354407690839e-10,0.000000000000000000e+00 +2.932832916579861049e+01,1.626400000000000148e+02,0.000000000000000000e+00,9.644628339412106399e+00,0.000000000000000000e+00,1.000000009910407828e+00,0.000000000000000000e+00,9.510568878063710127e-10,0.000000000000000000e+00 +2.932936601238803576e+01,1.626500000000000057e+02,0.000000000000000000e+00,9.645665186011807890e+00,0.000000000000000000e+00,1.000000009911393928e+00,0.000000000000000000e+00,-2.085867772873428318e-09,0.000000000000000000e+00 +2.933040274752316279e+01,1.626599999999999966e+02,0.000000000000000000e+00,9.646701921157209370e+00,0.000000000000000000e+00,1.000000009909231435e+00,0.000000000000000000e+00,1.270633282952728230e-09,0.000000000000000000e+00 +2.933143937123992373e+01,1.626700000000000159e+02,0.000000000000000000e+00,9.647738544884242984e+00,0.000000000000000000e+00,1.000000009910548604e+00,0.000000000000000000e+00,-5.610495900987684410e-10,0.000000000000000000e+00 +2.933247588357423652e+01,1.626800000000000068e+02,0.000000000000000000e+00,9.648775057228828445e+00,0.000000000000000000e+00,1.000000009909967069e+00,0.000000000000000000e+00,6.695182642477722959e-10,0.000000000000000000e+00 +2.933351228456199777e+01,1.626899999999999977e+02,0.000000000000000000e+00,9.649811458226860594e+00,0.000000000000000000e+00,1.000000009910660959e+00,0.000000000000000000e+00,-1.665083289956313466e-09,0.000000000000000000e+00 +2.933454857423908635e+01,1.627000000000000171e+02,0.000000000000000000e+00,9.650847747914218289e+00,0.000000000000000000e+00,1.000000009908935450e+00,0.000000000000000000e+00,2.346067365803003461e-09,0.000000000000000000e+00 +2.933558475264135623e+01,1.627100000000000080e+02,0.000000000000000000e+00,9.651883926326757290e+00,0.000000000000000000e+00,1.000000009911366394e+00,0.000000000000000000e+00,-2.199299250537415743e-09,0.000000000000000000e+00 +2.933662081980465075e+01,1.627199999999999989e+02,0.000000000000000000e+00,9.652919993500320928e+00,0.000000000000000000e+00,1.000000009909087773e+00,0.000000000000000000e+00,1.230942448475155041e-09,0.000000000000000000e+00 +2.933765677576478836e+01,1.627299999999999898e+02,0.000000000000000000e+00,9.653955949470724107e+00,0.000000000000000000e+00,1.000000009910362975e+00,0.000000000000000000e+00,-6.158588182276634815e-10,0.000000000000000000e+00 +2.933869262055756977e+01,1.627400000000000091e+02,0.000000000000000000e+00,9.654991794273771077e+00,0.000000000000000000e+00,1.000000009909725041e+00,0.000000000000000000e+00,5.237398282489551756e-10,0.000000000000000000e+00 +2.933972835421877434e+01,1.627500000000000000e+02,0.000000000000000000e+00,9.656027527945241218e+00,0.000000000000000000e+00,1.000000009910267496e+00,0.000000000000000000e+00,-1.987551793903916268e-09,0.000000000000000000e+00 +2.934076397678416726e+01,1.627599999999999909e+02,0.000000000000000000e+00,9.657063150520897921e+00,0.000000000000000000e+00,1.000000009908209142e+00,0.000000000000000000e+00,1.773978374070215086e-09,0.000000000000000000e+00 +2.934179948828949236e+01,1.627700000000000102e+02,0.000000000000000000e+00,9.658098662036481485e+00,0.000000000000000000e+00,1.000000009910046117e+00,0.000000000000000000e+00,2.018001508336270764e-10,0.000000000000000000e+00 +2.934283488877046864e+01,1.627800000000000011e+02,0.000000000000000000e+00,9.659134062527719777e+00,0.000000000000000000e+00,1.000000009910255061e+00,0.000000000000000000e+00,-1.751409878338913524e-09,0.000000000000000000e+00 +2.934387017826280442e+01,1.627899999999999920e+02,0.000000000000000000e+00,9.660169352030315792e+00,0.000000000000000000e+00,1.000000009908441845e+00,0.000000000000000000e+00,8.757987993566146235e-10,0.000000000000000000e+00 +2.934490535680218315e+01,1.628000000000000114e+02,0.000000000000000000e+00,9.661204530579952987e+00,0.000000000000000000e+00,1.000000009909348453e+00,0.000000000000000000e+00,-2.181687054925121287e-10,0.000000000000000000e+00 +2.934594042442427408e+01,1.628100000000000023e+02,0.000000000000000000e+00,9.662239598212300606e+00,0.000000000000000000e+00,1.000000009909122634e+00,0.000000000000000000e+00,1.584628021520285594e-09,0.000000000000000000e+00 +2.934697538116472160e+01,1.628199999999999932e+02,0.000000000000000000e+00,9.663274554963004803e+00,0.000000000000000000e+00,1.000000009910762655e+00,0.000000000000000000e+00,-2.020584954555961913e-09,0.000000000000000000e+00 +2.934801022705915585e+01,1.628300000000000125e+02,0.000000000000000000e+00,9.664309400867695743e+00,0.000000000000000000e+00,1.000000009908671661e+00,0.000000000000000000e+00,5.620132430744216443e-10,0.000000000000000000e+00 +2.934904496214318570e+01,1.628400000000000034e+02,0.000000000000000000e+00,9.665344135961978722e+00,0.000000000000000000e+00,1.000000009909253196e+00,0.000000000000000000e+00,-6.326813409355461367e-10,0.000000000000000000e+00 +2.935007958645240222e+01,1.628499999999999943e+02,0.000000000000000000e+00,9.666378760281446603e+00,0.000000000000000000e+00,1.000000009908598608e+00,0.000000000000000000e+00,1.018451261492702384e-09,0.000000000000000000e+00 +2.935111410002237520e+01,1.628600000000000136e+02,0.000000000000000000e+00,9.667413273861669154e+00,0.000000000000000000e+00,1.000000009909652210e+00,0.000000000000000000e+00,-1.136408431175432381e-09,0.000000000000000000e+00 +2.935214850288865662e+01,1.628700000000000045e+02,0.000000000000000000e+00,9.668447676738200158e+00,0.000000000000000000e+00,1.000000009908476706e+00,0.000000000000000000e+00,1.188912595790373415e-09,0.000000000000000000e+00 +2.935318279508677719e+01,1.628799999999999955e+02,0.000000000000000000e+00,9.669481968946570305e+00,0.000000000000000000e+00,1.000000009909706389e+00,0.000000000000000000e+00,-1.981088851354284786e-09,0.000000000000000000e+00 +2.935421697665225338e+01,1.628900000000000148e+02,0.000000000000000000e+00,9.670516150522296073e+00,0.000000000000000000e+00,1.000000009907657583e+00,0.000000000000000000e+00,9.660639435349295122e-10,0.000000000000000000e+00 +2.935525104762058035e+01,1.629000000000000057e+02,0.000000000000000000e+00,9.671550221500869071e+00,0.000000000000000000e+00,1.000000009908656562e+00,0.000000000000000000e+00,5.068136693151992119e-11,0.000000000000000000e+00 +2.935628500802723551e+01,1.629099999999999966e+02,0.000000000000000000e+00,9.672584181917768476e+00,0.000000000000000000e+00,1.000000009908708964e+00,0.000000000000000000e+00,2.433395236004017315e-10,0.000000000000000000e+00 +2.935731885790767492e+01,1.629200000000000159e+02,0.000000000000000000e+00,9.673618031808450368e+00,0.000000000000000000e+00,1.000000009908960541e+00,0.000000000000000000e+00,-1.310264563381825393e-10,0.000000000000000000e+00 +2.935835259729733338e+01,1.629300000000000068e+02,0.000000000000000000e+00,9.674651771208353068e+00,0.000000000000000000e+00,1.000000009908825094e+00,0.000000000000000000e+00,-1.085917238429395174e-09,0.000000000000000000e+00 +2.935938622623163496e+01,1.629399999999999977e+02,0.000000000000000000e+00,9.675685400152895355e+00,0.000000000000000000e+00,1.000000009907702658e+00,0.000000000000000000e+00,6.905066046967480396e-10,0.000000000000000000e+00 +2.936041974474597538e+01,1.629500000000000171e+02,0.000000000000000000e+00,9.676718918677476466e+00,0.000000000000000000e+00,1.000000009908416310e+00,0.000000000000000000e+00,1.976770170926851349e-10,0.000000000000000000e+00 +2.936145315287573965e+01,1.629600000000000080e+02,0.000000000000000000e+00,9.677752326817479656e+00,0.000000000000000000e+00,1.000000009908620591e+00,0.000000000000000000e+00,-9.160729545870197938e-10,0.000000000000000000e+00 +2.936248645065628793e+01,1.629699999999999989e+02,0.000000000000000000e+00,9.678785624608266858e+00,0.000000000000000000e+00,1.000000009907674015e+00,0.000000000000000000e+00,6.640787382225964008e-10,0.000000000000000000e+00 +2.936351963812296617e+01,1.629799999999999898e+02,0.000000000000000000e+00,9.679818812085180468e+00,0.000000000000000000e+00,1.000000009908360132e+00,0.000000000000000000e+00,-6.705976816891059852e-11,0.000000000000000000e+00 +2.936455271531109545e+01,1.629900000000000091e+02,0.000000000000000000e+00,9.680851889283546896e+00,0.000000000000000000e+00,1.000000009908290854e+00,0.000000000000000000e+00,2.063597695769959471e-10,0.000000000000000000e+00 +2.936558568225598620e+01,1.630000000000000000e+02,0.000000000000000000e+00,9.681884856238671233e+00,0.000000000000000000e+00,1.000000009908504017e+00,0.000000000000000000e+00,-1.945578319539009017e-10,0.000000000000000000e+00 +2.936661853899292041e+01,1.630099999999999909e+02,0.000000000000000000e+00,9.682917712985840808e+00,0.000000000000000000e+00,1.000000009908303067e+00,0.000000000000000000e+00,-1.282713648091371865e-09,0.000000000000000000e+00 +2.936765128555716942e+01,1.630200000000000102e+02,0.000000000000000000e+00,9.683950459560323409e+00,0.000000000000000000e+00,1.000000009906978349e+00,0.000000000000000000e+00,1.926210928909574448e-09,0.000000000000000000e+00 +2.936868392198398325e+01,1.630300000000000011e+02,0.000000000000000000e+00,9.684983095997367286e+00,0.000000000000000000e+00,1.000000009908967424e+00,0.000000000000000000e+00,-2.242969669802364774e-09,0.000000000000000000e+00 +2.936971644830859063e+01,1.630399999999999920e+02,0.000000000000000000e+00,9.686015622332206476e+00,0.000000000000000000e+00,1.000000009906651499e+00,0.000000000000000000e+00,1.191933187238205216e-09,0.000000000000000000e+00 +2.937074886456620604e+01,1.630500000000000114e+02,0.000000000000000000e+00,9.687048038600048372e+00,0.000000000000000000e+00,1.000000009907882070e+00,0.000000000000000000e+00,5.547317470166906570e-10,0.000000000000000000e+00 +2.937178117079201911e+01,1.630600000000000023e+02,0.000000000000000000e+00,9.688080344836089708e+00,0.000000000000000000e+00,1.000000009908454723e+00,0.000000000000000000e+00,-8.365962247640090130e-10,0.000000000000000000e+00 +2.937281336702120527e+01,1.630699999999999932e+02,0.000000000000000000e+00,9.689112541075504126e+00,0.000000000000000000e+00,1.000000009907591192e+00,0.000000000000000000e+00,3.392781717187724939e-10,0.000000000000000000e+00 +2.937384545328892216e+01,1.630800000000000125e+02,0.000000000000000000e+00,9.690144627353445728e+00,0.000000000000000000e+00,1.000000009907941356e+00,0.000000000000000000e+00,-9.320923261156881313e-10,0.000000000000000000e+00 +2.937487742963030257e+01,1.630900000000000034e+02,0.000000000000000000e+00,9.691176603705052628e+00,0.000000000000000000e+00,1.000000009906979459e+00,0.000000000000000000e+00,3.389200731359721958e-10,0.000000000000000000e+00 +2.937590929608046864e+01,1.630999999999999943e+02,0.000000000000000000e+00,9.692208470165441625e+00,0.000000000000000000e+00,1.000000009907329179e+00,0.000000000000000000e+00,8.040255315874952589e-10,0.000000000000000000e+00 +2.937694105267451761e+01,1.631100000000000136e+02,0.000000000000000000e+00,9.693240226769713530e+00,0.000000000000000000e+00,1.000000009908158738e+00,0.000000000000000000e+00,-1.220156838800556926e-09,0.000000000000000000e+00 +2.937797269944753253e+01,1.631200000000000045e+02,0.000000000000000000e+00,9.694271873552949614e+00,0.000000000000000000e+00,1.000000009906899967e+00,0.000000000000000000e+00,-7.391893677995048668e-10,0.000000000000000000e+00 +2.937900423643457515e+01,1.631299999999999955e+02,0.000000000000000000e+00,9.695303410550209833e+00,0.000000000000000000e+00,1.000000009906137466e+00,0.000000000000000000e+00,2.235026386373123756e-09,0.000000000000000000e+00 +2.938003566367068586e+01,1.631400000000000148e+02,0.000000000000000000e+00,9.696334837796538153e+00,0.000000000000000000e+00,1.000000009908442733e+00,0.000000000000000000e+00,-2.329996986785912441e-09,0.000000000000000000e+00 +2.938106698119089089e+01,1.631500000000000057e+02,0.000000000000000000e+00,9.697366155326962556e+00,0.000000000000000000e+00,1.000000009906039766e+00,0.000000000000000000e+00,5.826688646307589048e-10,0.000000000000000000e+00 +2.938209818903019865e+01,1.631599999999999966e+02,0.000000000000000000e+00,9.698397363176484376e+00,0.000000000000000000e+00,1.000000009906640619e+00,0.000000000000000000e+00,9.399926279633009119e-10,0.000000000000000000e+00 +2.938312928722359274e+01,1.631700000000000159e+02,0.000000000000000000e+00,9.699428461380094291e+00,0.000000000000000000e+00,1.000000009907609844e+00,0.000000000000000000e+00,-1.273486216305308281e-09,0.000000000000000000e+00 +2.938416027580604606e+01,1.631800000000000068e+02,0.000000000000000000e+00,9.700459449972761661e+00,0.000000000000000000e+00,1.000000009906296894e+00,0.000000000000000000e+00,6.140867790243552775e-10,0.000000000000000000e+00 +2.938519115481250665e+01,1.631899999999999977e+02,0.000000000000000000e+00,9.701490328989434531e+00,0.000000000000000000e+00,1.000000009906929943e+00,0.000000000000000000e+00,-9.456778148178826658e-11,0.000000000000000000e+00 +2.938622192427790836e+01,1.632000000000000171e+02,0.000000000000000000e+00,9.702521098465046734e+00,0.000000000000000000e+00,1.000000009906832465e+00,0.000000000000000000e+00,-7.087951206841137268e-11,0.000000000000000000e+00 +2.938725258423716014e+01,1.632100000000000080e+02,0.000000000000000000e+00,9.703551758434510788e+00,0.000000000000000000e+00,1.000000009906759413e+00,0.000000000000000000e+00,-9.986669802307437014e-10,0.000000000000000000e+00 +2.938828313472516029e+01,1.632199999999999989e+02,0.000000000000000000e+00,9.704582308932721446e+00,0.000000000000000000e+00,1.000000009905730236e+00,0.000000000000000000e+00,2.126190637824247017e-09,0.000000000000000000e+00 +2.938931357577678583e+01,1.632299999999999898e+02,0.000000000000000000e+00,9.705612749994553923e+00,0.000000000000000000e+00,1.000000009907921150e+00,0.000000000000000000e+00,-2.418645104045077604e-09,0.000000000000000000e+00 +2.939034390742689240e+01,1.632400000000000091e+02,0.000000000000000000e+00,9.706643081654869221e+00,0.000000000000000000e+00,1.000000009905429144e+00,0.000000000000000000e+00,2.084613634728913125e-09,0.000000000000000000e+00 +2.939137412971032148e+01,1.632500000000000000e+02,0.000000000000000000e+00,9.707673303948501697e+00,0.000000000000000000e+00,1.000000009907576759e+00,0.000000000000000000e+00,-2.785168690351693586e-09,0.000000000000000000e+00 +2.939240424266188967e+01,1.632599999999999909e+02,0.000000000000000000e+00,9.708703416910276829e+00,0.000000000000000000e+00,1.000000009904707721e+00,0.000000000000000000e+00,1.371282252970257864e-09,0.000000000000000000e+00 +2.939343424631640289e+01,1.632700000000000102e+02,0.000000000000000000e+00,9.709733420574991669e+00,0.000000000000000000e+00,1.000000009906120146e+00,0.000000000000000000e+00,1.150007157620858166e-09,0.000000000000000000e+00 +2.939446414070864222e+01,1.632800000000000011e+02,0.000000000000000000e+00,9.710763314977434391e+00,0.000000000000000000e+00,1.000000009907304532e+00,0.000000000000000000e+00,-1.791820983753355753e-09,0.000000000000000000e+00 +2.939549392587337451e+01,1.632899999999999920e+02,0.000000000000000000e+00,9.711793100152370073e+00,0.000000000000000000e+00,1.000000009905459342e+00,0.000000000000000000e+00,9.102380777058083466e-10,0.000000000000000000e+00 +2.939652360184534885e+01,1.633000000000000114e+02,0.000000000000000000e+00,9.712822776134542480e+00,0.000000000000000000e+00,1.000000009906396592e+00,0.000000000000000000e+00,-8.087549610126150600e-10,0.000000000000000000e+00 +2.939755316865928947e+01,1.633100000000000023e+02,0.000000000000000000e+00,9.713852342958682939e+00,0.000000000000000000e+00,1.000000009905563925e+00,0.000000000000000000e+00,-2.594760932468197397e-10,0.000000000000000000e+00 +2.939858262634990993e+01,1.633199999999999932e+02,0.000000000000000000e+00,9.714881800659499689e+00,0.000000000000000000e+00,1.000000009905296805e+00,0.000000000000000000e+00,8.697576752205527036e-10,0.000000000000000000e+00 +2.939961197495189893e+01,1.633300000000000125e+02,0.000000000000000000e+00,9.715911149271684977e+00,0.000000000000000000e+00,1.000000009906192089e+00,0.000000000000000000e+00,-7.867912535129713498e-10,0.000000000000000000e+00 +2.940064121449993095e+01,1.633400000000000034e+02,0.000000000000000000e+00,9.716940388829913289e+00,0.000000000000000000e+00,1.000000009905382292e+00,0.000000000000000000e+00,1.464359176561483362e-09,0.000000000000000000e+00 +2.940167034502866272e+01,1.633499999999999943e+02,0.000000000000000000e+00,9.717969519368837794e+00,0.000000000000000000e+00,1.000000009906889309e+00,0.000000000000000000e+00,-2.451718154696108359e-09,0.000000000000000000e+00 +2.940269936657272964e+01,1.633600000000000136e+02,0.000000000000000000e+00,9.718998540923097451e+00,0.000000000000000000e+00,1.000000009904366438e+00,0.000000000000000000e+00,2.549090067147288609e-09,0.000000000000000000e+00 +2.940372827916674936e+01,1.633700000000000045e+02,0.000000000000000000e+00,9.720027453527306349e+00,0.000000000000000000e+00,1.000000009906989229e+00,0.000000000000000000e+00,-2.001372724803800748e-09,0.000000000000000000e+00 +2.940475708284532175e+01,1.633799999999999955e+02,0.000000000000000000e+00,9.721056257216069696e+00,0.000000000000000000e+00,1.000000009904930209e+00,0.000000000000000000e+00,6.641729411661377821e-10,0.000000000000000000e+00 +2.940578577764302892e+01,1.633900000000000148e+02,0.000000000000000000e+00,9.722084952023964277e+00,0.000000000000000000e+00,1.000000009905613441e+00,0.000000000000000000e+00,-1.215368656379721150e-09,0.000000000000000000e+00 +2.940681436359443168e+01,1.634000000000000057e+02,0.000000000000000000e+00,9.723113537985556221e+00,0.000000000000000000e+00,1.000000009904363329e+00,0.000000000000000000e+00,7.413885480965199061e-10,0.000000000000000000e+00 +2.940784284073407662e+01,1.634099999999999966e+02,0.000000000000000000e+00,9.724142015135388561e+00,0.000000000000000000e+00,1.000000009905125831e+00,0.000000000000000000e+00,-1.949751524603028769e-10,0.000000000000000000e+00 +2.940887120909649255e+01,1.634200000000000159e+02,0.000000000000000000e+00,9.725170383507990124e+00,0.000000000000000000e+00,1.000000009904925324e+00,0.000000000000000000e+00,1.001323803169785869e-09,0.000000000000000000e+00 +2.940989946871618699e+01,1.634300000000000068e+02,0.000000000000000000e+00,9.726198643137868416e+00,0.000000000000000000e+00,1.000000009905954945e+00,0.000000000000000000e+00,-7.228348332906630129e-10,0.000000000000000000e+00 +2.941092761962764968e+01,1.634399999999999977e+02,0.000000000000000000e+00,9.727226794059514958e+00,0.000000000000000000e+00,1.000000009905211762e+00,0.000000000000000000e+00,-3.395328578350910481e-10,0.000000000000000000e+00 +2.941195566186535260e+01,1.634500000000000171e+02,0.000000000000000000e+00,9.728254836307399955e+00,0.000000000000000000e+00,1.000000009904862708e+00,0.000000000000000000e+00,4.588066209691303154e-10,0.000000000000000000e+00 +2.941298359546374996e+01,1.634600000000000080e+02,0.000000000000000000e+00,9.729282769915977624e+00,0.000000000000000000e+00,1.000000009905334331e+00,0.000000000000000000e+00,-1.703207915993266973e-09,0.000000000000000000e+00 +2.941401142045727468e+01,1.634699999999999989e+02,0.000000000000000000e+00,9.730310594919684419e+00,0.000000000000000000e+00,1.000000009903583731e+00,0.000000000000000000e+00,1.568784773857952370e-09,0.000000000000000000e+00 +2.941503913688034899e+01,1.634799999999999898e+02,0.000000000000000000e+00,9.731338311352935477e+00,0.000000000000000000e+00,1.000000009905195997e+00,0.000000000000000000e+00,1.726472145418211119e-10,0.000000000000000000e+00 +2.941606674476736671e+01,1.634900000000000091e+02,0.000000000000000000e+00,9.732365919250133501e+00,0.000000000000000000e+00,1.000000009905373410e+00,0.000000000000000000e+00,-8.603018014537951263e-10,0.000000000000000000e+00 +2.941709424415271457e+01,1.635000000000000000e+02,0.000000000000000000e+00,9.733393418645658102e+00,0.000000000000000000e+00,1.000000009904489451e+00,0.000000000000000000e+00,1.411294615033667778e-10,0.000000000000000000e+00 +2.941812163507075084e+01,1.635099999999999909e+02,0.000000000000000000e+00,9.734420809573871125e+00,0.000000000000000000e+00,1.000000009904634446e+00,0.000000000000000000e+00,-2.012333804860160942e-10,0.000000000000000000e+00 +2.941914891755582318e+01,1.635200000000000102e+02,0.000000000000000000e+00,9.735448092069118431e+00,0.000000000000000000e+00,1.000000009904427722e+00,0.000000000000000000e+00,-2.176835651449238539e-10,0.000000000000000000e+00 +2.942017609164225789e+01,1.635300000000000011e+02,0.000000000000000000e+00,9.736475266165726339e+00,0.000000000000000000e+00,1.000000009904204124e+00,0.000000000000000000e+00,7.999147674200998549e-11,0.000000000000000000e+00 +2.942120315736436353e+01,1.635399999999999920e+02,0.000000000000000000e+00,9.737502331898003405e+00,0.000000000000000000e+00,1.000000009904286280e+00,0.000000000000000000e+00,-1.005620550068755725e-09,0.000000000000000000e+00 +2.942223011475643091e+01,1.635500000000000114e+02,0.000000000000000000e+00,9.738529289300240421e+00,0.000000000000000000e+00,1.000000009903253551e+00,0.000000000000000000e+00,1.566433786497144325e-09,0.000000000000000000e+00 +2.942325696385272948e+01,1.635600000000000023e+02,0.000000000000000000e+00,9.739556138406708641e+00,0.000000000000000000e+00,1.000000009904862042e+00,0.000000000000000000e+00,-6.394855201212443396e-10,0.000000000000000000e+00 +2.942428370468751453e+01,1.635699999999999932e+02,0.000000000000000000e+00,9.740582879251665105e+00,0.000000000000000000e+00,1.000000009904205456e+00,0.000000000000000000e+00,-8.977964934103446071e-10,0.000000000000000000e+00 +2.942531033729502354e+01,1.635800000000000125e+02,0.000000000000000000e+00,9.741609511869343763e+00,0.000000000000000000e+00,1.000000009903283749e+00,0.000000000000000000e+00,7.802200110276819173e-10,0.000000000000000000e+00 +2.942633686170947627e+01,1.635900000000000034e+02,0.000000000000000000e+00,9.742636036293962576e+00,0.000000000000000000e+00,1.000000009904084664e+00,0.000000000000000000e+00,-6.745168681635455905e-10,0.000000000000000000e+00 +2.942736327796507112e+01,1.635999999999999943e+02,0.000000000000000000e+00,9.743662452559723519e+00,0.000000000000000000e+00,1.000000009903392328e+00,0.000000000000000000e+00,1.468386236281268040e-09,0.000000000000000000e+00 +2.942838958609599231e+01,1.636100000000000136e+02,0.000000000000000000e+00,9.744688760700807251e+00,0.000000000000000000e+00,1.000000009904899345e+00,0.000000000000000000e+00,-1.234638925952298357e-09,0.000000000000000000e+00 +2.942941578613639919e+01,1.636200000000000045e+02,0.000000000000000000e+00,9.745714960751380218e+00,0.000000000000000000e+00,1.000000009903632359e+00,0.000000000000000000e+00,-3.644148093041660102e-10,0.000000000000000000e+00 +2.943044187812044399e+01,1.636299999999999955e+02,0.000000000000000000e+00,9.746741052745585776e+00,0.000000000000000000e+00,1.000000009903258436e+00,0.000000000000000000e+00,6.947118165026761452e-10,0.000000000000000000e+00 +2.943146786208225052e+01,1.636400000000000148e+02,0.000000000000000000e+00,9.747767036717553069e+00,0.000000000000000000e+00,1.000000009903971199e+00,0.000000000000000000e+00,-1.446278193636334048e-09,0.000000000000000000e+00 +2.943249373805593194e+01,1.636500000000000057e+02,0.000000000000000000e+00,9.748792912701393476e+00,0.000000000000000000e+00,1.000000009902487497e+00,0.000000000000000000e+00,1.639735154628520003e-09,0.000000000000000000e+00 +2.943351950607557654e+01,1.636599999999999966e+02,0.000000000000000000e+00,9.749818680731197063e+00,0.000000000000000000e+00,1.000000009904169485e+00,0.000000000000000000e+00,-1.876747160861807966e-09,0.000000000000000000e+00 +2.943454516617526195e+01,1.636700000000000159e+02,0.000000000000000000e+00,9.750844340841041458e+00,0.000000000000000000e+00,1.000000009902244580e+00,0.000000000000000000e+00,1.498481198746423032e-09,0.000000000000000000e+00 +2.943557071838904449e+01,1.636800000000000068e+02,0.000000000000000000e+00,9.751869893064979422e+00,0.000000000000000000e+00,1.000000009903781351e+00,0.000000000000000000e+00,-6.625971298918917097e-11,0.000000000000000000e+00 +2.943659616275096269e+01,1.636899999999999977e+02,0.000000000000000000e+00,9.752895337437053058e+00,0.000000000000000000e+00,1.000000009903713405e+00,0.000000000000000000e+00,-1.519585936700003096e-09,0.000000000000000000e+00 +2.943762149929503735e+01,1.637000000000000171e+02,0.000000000000000000e+00,9.753920673991281376e+00,0.000000000000000000e+00,1.000000009902155318e+00,0.000000000000000000e+00,5.072316393237037285e-10,0.000000000000000000e+00 +2.943864672805526794e+01,1.637100000000000080e+02,0.000000000000000000e+00,9.754945902761665621e+00,0.000000000000000000e+00,1.000000009902675346e+00,0.000000000000000000e+00,9.324772534433415681e-10,0.000000000000000000e+00 +2.943967184906564327e+01,1.637199999999999989e+02,0.000000000000000000e+00,9.755971023782192830e+00,0.000000000000000000e+00,1.000000009903631248e+00,0.000000000000000000e+00,-2.569185227720023307e-10,0.000000000000000000e+00 +2.944069686236013084e+01,1.637299999999999898e+02,0.000000000000000000e+00,9.756996037086830498e+00,0.000000000000000000e+00,1.000000009903367904e+00,0.000000000000000000e+00,-1.384169394235085286e-09,0.000000000000000000e+00 +2.944172176797267682e+01,1.637400000000000091e+02,0.000000000000000000e+00,9.758020942709526580e+00,0.000000000000000000e+00,1.000000009901949261e+00,0.000000000000000000e+00,9.215042744280224842e-10,0.000000000000000000e+00 +2.944274656593721318e+01,1.637500000000000000e+02,0.000000000000000000e+00,9.759045740684211268e+00,0.000000000000000000e+00,1.000000009902893616e+00,0.000000000000000000e+00,-1.170149466205189106e-10,0.000000000000000000e+00 +2.944377125628765413e+01,1.637599999999999909e+02,0.000000000000000000e+00,9.760070431044800543e+00,0.000000000000000000e+00,1.000000009902773712e+00,0.000000000000000000e+00,5.615140016698622702e-10,0.000000000000000000e+00 +2.944479583905789610e+01,1.637700000000000102e+02,0.000000000000000000e+00,9.761095013825189071e+00,0.000000000000000000e+00,1.000000009903349030e+00,0.000000000000000000e+00,-2.131202931264632459e-09,0.000000000000000000e+00 +2.944582031428181779e+01,1.637800000000000011e+02,0.000000000000000000e+00,9.762119489059255528e+00,0.000000000000000000e+00,1.000000009901165665e+00,0.000000000000000000e+00,1.946961641923877277e-09,0.000000000000000000e+00 +2.944684468199327654e+01,1.637899999999999920e+02,0.000000000000000000e+00,9.763143856780857277e+00,0.000000000000000000e+00,1.000000009903160070e+00,0.000000000000000000e+00,-7.574479851245000129e-10,0.000000000000000000e+00 +2.944786894222611551e+01,1.638000000000000114e+02,0.000000000000000000e+00,9.764168117023841020e+00,0.000000000000000000e+00,1.000000009902384246e+00,0.000000000000000000e+00,-1.001653353608359355e-10,0.000000000000000000e+00 +2.944889309501416008e+01,1.638100000000000023e+02,0.000000000000000000e+00,9.765192269822028592e+00,0.000000000000000000e+00,1.000000009902281661e+00,0.000000000000000000e+00,5.208276439486183933e-10,0.000000000000000000e+00 +2.944991714039121788e+01,1.638199999999999932e+02,0.000000000000000000e+00,9.766216315209227616e+00,0.000000000000000000e+00,1.000000009902815012e+00,0.000000000000000000e+00,-2.295611832021757403e-09,0.000000000000000000e+00 +2.945094107839107878e+01,1.638300000000000125e+02,0.000000000000000000e+00,9.767240253219227952e+00,0.000000000000000000e+00,1.000000009900464448e+00,0.000000000000000000e+00,1.604667746092781883e-09,0.000000000000000000e+00 +2.945196490904751130e+01,1.638400000000000034e+02,0.000000000000000000e+00,9.768264083885798144e+00,0.000000000000000000e+00,1.000000009902107356e+00,0.000000000000000000e+00,3.472553533234981859e-10,0.000000000000000000e+00 +2.945298863239427334e+01,1.638499999999999943e+02,0.000000000000000000e+00,9.769287807242696076e+00,0.000000000000000000e+00,1.000000009902462850e+00,0.000000000000000000e+00,-9.965385891258050048e-10,0.000000000000000000e+00 +2.945401224846509791e+01,1.638600000000000136e+02,0.000000000000000000e+00,9.770311423323656541e+00,0.000000000000000000e+00,1.000000009901442777e+00,0.000000000000000000e+00,9.517354951720431806e-10,0.000000000000000000e+00 +2.945503575729370382e+01,1.638700000000000045e+02,0.000000000000000000e+00,9.771334932162396569e+00,0.000000000000000000e+00,1.000000009902416886e+00,0.000000000000000000e+00,-6.016501023361780969e-10,0.000000000000000000e+00 +2.945605915891379212e+01,1.638799999999999955e+02,0.000000000000000000e+00,9.772358333792618978e+00,0.000000000000000000e+00,1.000000009901801157e+00,0.000000000000000000e+00,-5.832689709269657419e-10,0.000000000000000000e+00 +2.945708245335904607e+01,1.638900000000000148e+02,0.000000000000000000e+00,9.773381628248005271e+00,0.000000000000000000e+00,1.000000009901204301e+00,0.000000000000000000e+00,9.967391760522100925e-10,0.000000000000000000e+00 +2.945810564066313120e+01,1.639000000000000057e+02,0.000000000000000000e+00,9.774404815562220961e+00,0.000000000000000000e+00,1.000000009902224152e+00,0.000000000000000000e+00,-9.651563596070378436e-10,0.000000000000000000e+00 +2.945912872085969525e+01,1.639099999999999966e+02,0.000000000000000000e+00,9.775427895768915576e+00,0.000000000000000000e+00,1.000000009901236719e+00,0.000000000000000000e+00,3.069201569476042783e-10,0.000000000000000000e+00 +2.946015169398236822e+01,1.639200000000000159e+02,0.000000000000000000e+00,9.776450868901717328e+00,0.000000000000000000e+00,1.000000009901550690e+00,0.000000000000000000e+00,-2.913224565152218049e-10,0.000000000000000000e+00 +2.946117456006476232e+01,1.639300000000000068e+02,0.000000000000000000e+00,9.777473734994240218e+00,0.000000000000000000e+00,1.000000009901252707e+00,0.000000000000000000e+00,6.237384395788237629e-10,0.000000000000000000e+00 +2.946219731914047557e+01,1.639399999999999977e+02,0.000000000000000000e+00,9.778496494080078705e+00,0.000000000000000000e+00,1.000000009901890641e+00,0.000000000000000000e+00,-2.055534105359771268e-09,0.000000000000000000e+00 +2.946321997124308112e+01,1.639500000000000171e+02,0.000000000000000000e+00,9.779519146192811263e+00,0.000000000000000000e+00,1.000000009899788544e+00,0.000000000000000000e+00,1.849457577487982466e-09,0.000000000000000000e+00 +2.946424251640614145e+01,1.639600000000000080e+02,0.000000000000000000e+00,9.780541691365995050e+00,0.000000000000000000e+00,1.000000009901679698e+00,0.000000000000000000e+00,-1.262201638990027268e-09,0.000000000000000000e+00 +2.946526495466319773e+01,1.639699999999999989e+02,0.000000000000000000e+00,9.781564129633176563e+00,0.000000000000000000e+00,1.000000009900389175e+00,0.000000000000000000e+00,4.889044914647539353e-10,0.000000000000000000e+00 +2.946628728604777692e+01,1.639799999999999898e+02,0.000000000000000000e+00,9.782586461027877434e+00,0.000000000000000000e+00,1.000000009900888998e+00,0.000000000000000000e+00,2.941118919126793632e-10,0.000000000000000000e+00 +2.946730951059338466e+01,1.639900000000000091e+02,0.000000000000000000e+00,9.783608685583606857e+00,0.000000000000000000e+00,1.000000009901189646e+00,0.000000000000000000e+00,-1.594539783593333181e-10,0.000000000000000000e+00 +2.946833162833351238e+01,1.640000000000000000e+02,0.000000000000000000e+00,9.784630803333854487e+00,0.000000000000000000e+00,1.000000009901026665e+00,0.000000000000000000e+00,-8.853444760333996807e-10,0.000000000000000000e+00 +2.946935363930163021e+01,1.640099999999999909e+02,0.000000000000000000e+00,9.785652814312092218e+00,0.000000000000000000e+00,1.000000009900121833e+00,0.000000000000000000e+00,1.507958880682689744e-09,0.000000000000000000e+00 +2.947037554353119404e+01,1.640200000000000102e+02,0.000000000000000000e+00,9.786674718551774177e+00,0.000000000000000000e+00,1.000000009901662823e+00,0.000000000000000000e+00,-1.498554810444763934e-09,0.000000000000000000e+00 +2.947139734105564202e+01,1.640300000000000011e+02,0.000000000000000000e+00,9.787696516086340282e+00,0.000000000000000000e+00,1.000000009900131603e+00,0.000000000000000000e+00,2.912228976094265204e-10,0.000000000000000000e+00 +2.947241903190839452e+01,1.640399999999999920e+02,0.000000000000000000e+00,9.788718206949207357e+00,0.000000000000000000e+00,1.000000009900429143e+00,0.000000000000000000e+00,5.912007222197833892e-11,0.000000000000000000e+00 +2.947344061612285415e+01,1.640500000000000114e+02,0.000000000000000000e+00,9.789739791173779793e+00,0.000000000000000000e+00,1.000000009900489539e+00,0.000000000000000000e+00,-5.060510729094094207e-10,0.000000000000000000e+00 +2.947446209373240222e+01,1.640600000000000023e+02,0.000000000000000000e+00,9.790761268793442440e+00,0.000000000000000000e+00,1.000000009899972619e+00,0.000000000000000000e+00,2.867487161836945582e-10,0.000000000000000000e+00 +2.947548346477040937e+01,1.640699999999999932e+02,0.000000000000000000e+00,9.791782639841562386e+00,0.000000000000000000e+00,1.000000009900265496e+00,0.000000000000000000e+00,7.224908163337653192e-10,0.000000000000000000e+00 +2.947650472927022847e+01,1.640800000000000125e+02,0.000000000000000000e+00,9.792803904351490729e+00,0.000000000000000000e+00,1.000000009901003351e+00,0.000000000000000000e+00,-9.143517147380380418e-10,0.000000000000000000e+00 +2.947752588726518752e+01,1.640900000000000034e+02,0.000000000000000000e+00,9.793825062356560807e+00,0.000000000000000000e+00,1.000000009900069653e+00,0.000000000000000000e+00,4.738597250336639458e-10,0.000000000000000000e+00 +2.947854693878860388e+01,1.640999999999999943e+02,0.000000000000000000e+00,9.794846113890086414e+00,0.000000000000000000e+00,1.000000009900553488e+00,0.000000000000000000e+00,-1.939786830935334603e-09,0.000000000000000000e+00 +2.947956788387377713e+01,1.641100000000000136e+02,0.000000000000000000e+00,9.795867058985367137e+00,0.000000000000000000e+00,1.000000009898573072e+00,0.000000000000000000e+00,2.058098005622167477e-09,0.000000000000000000e+00 +2.948058872255398555e+01,1.641200000000000045e+02,0.000000000000000000e+00,9.796887897675681245e+00,0.000000000000000000e+00,1.000000009900674058e+00,0.000000000000000000e+00,-1.180777864564133133e-09,0.000000000000000000e+00 +2.948160945486249318e+01,1.641299999999999955e+02,0.000000000000000000e+00,9.797908629994296348e+00,0.000000000000000000e+00,1.000000009899468800e+00,0.000000000000000000e+00,2.643320892268945214e-10,0.000000000000000000e+00 +2.948263008083254988e+01,1.641400000000000148e+02,0.000000000000000000e+00,9.798929255974455188e+00,0.000000000000000000e+00,1.000000009899738584e+00,0.000000000000000000e+00,-4.384235741292325257e-10,0.000000000000000000e+00 +2.948365060049738062e+01,1.641500000000000057e+02,0.000000000000000000e+00,9.799949775649388073e+00,0.000000000000000000e+00,1.000000009899291165e+00,0.000000000000000000e+00,1.098893117990704863e-10,0.000000000000000000e+00 +2.948467101389019618e+01,1.641599999999999966e+02,0.000000000000000000e+00,9.800970189052305770e+00,0.000000000000000000e+00,1.000000009899403297e+00,0.000000000000000000e+00,1.906397236874872833e-10,0.000000000000000000e+00 +2.948569132104419310e+01,1.641700000000000159e+02,0.000000000000000000e+00,9.801990496216403059e+00,0.000000000000000000e+00,1.000000009899597808e+00,0.000000000000000000e+00,-2.076361068279563860e-10,0.000000000000000000e+00 +2.948671152199254664e+01,1.641800000000000068e+02,0.000000000000000000e+00,9.803010697174856958e+00,0.000000000000000000e+00,1.000000009899385978e+00,0.000000000000000000e+00,6.092599078886801496e-10,0.000000000000000000e+00 +2.948773161676841781e+01,1.641899999999999977e+02,0.000000000000000000e+00,9.804030791960826718e+00,0.000000000000000000e+00,1.000000009900007480e+00,0.000000000000000000e+00,-7.845663446521114751e-10,0.000000000000000000e+00 +2.948875160540494988e+01,1.642000000000000171e+02,0.000000000000000000e+00,9.805050780607455607e+00,0.000000000000000000e+00,1.000000009899207232e+00,0.000000000000000000e+00,-9.871237214137228314e-10,0.000000000000000000e+00 +2.948977148793526482e+01,1.642100000000000080e+02,0.000000000000000000e+00,9.806070663147867350e+00,0.000000000000000000e+00,1.000000009898200481e+00,0.000000000000000000e+00,1.698360367287174027e-09,0.000000000000000000e+00 +2.949079126439247389e+01,1.642199999999999989e+02,0.000000000000000000e+00,9.807090439615169686e+00,0.000000000000000000e+00,1.000000009899932429e+00,0.000000000000000000e+00,-1.281088858468138906e-09,0.000000000000000000e+00 +2.949181093480966709e+01,1.642299999999999898e+02,0.000000000000000000e+00,9.808110110042456142e+00,0.000000000000000000e+00,1.000000009898626141e+00,0.000000000000000000e+00,3.127375273863856523e-10,0.000000000000000000e+00 +2.949283049921991662e+01,1.642400000000000091e+02,0.000000000000000000e+00,9.809129674462797155e+00,0.000000000000000000e+00,1.000000009898944997e+00,0.000000000000000000e+00,-3.665682255986821111e-10,0.000000000000000000e+00 +2.949384995765627693e+01,1.642500000000000000e+02,0.000000000000000000e+00,9.810149132909250724e+00,0.000000000000000000e+00,1.000000009898571296e+00,0.000000000000000000e+00,8.647814033235718337e-11,0.000000000000000000e+00 +2.949486931015179181e+01,1.642599999999999909e+02,0.000000000000000000e+00,9.811168485414855311e+00,0.000000000000000000e+00,1.000000009898659448e+00,0.000000000000000000e+00,-4.901663317942934048e-11,0.000000000000000000e+00 +2.949588855673948018e+01,1.642700000000000102e+02,0.000000000000000000e+00,9.812187732012633390e+00,0.000000000000000000e+00,1.000000009898609488e+00,0.000000000000000000e+00,-7.854369770999968146e-10,0.000000000000000000e+00 +2.949690769745234675e+01,1.642800000000000011e+02,0.000000000000000000e+00,9.813206872735589670e+00,0.000000000000000000e+00,1.000000009897809017e+00,0.000000000000000000e+00,1.285809986395774189e-09,0.000000000000000000e+00 +2.949792673232338203e+01,1.642899999999999920e+02,0.000000000000000000e+00,9.814225907616711098e+00,0.000000000000000000e+00,1.000000009899119302e+00,0.000000000000000000e+00,-6.888438285107861826e-10,0.000000000000000000e+00 +2.949894566138555518e+01,1.643000000000000114e+02,0.000000000000000000e+00,9.815244836688970409e+00,0.000000000000000000e+00,1.000000009898417419e+00,0.000000000000000000e+00,1.205220455588795909e-10,0.000000000000000000e+00 +2.949996448467181764e+01,1.643100000000000023e+02,0.000000000000000000e+00,9.816263659985319023e+00,0.000000000000000000e+00,1.000000009898540210e+00,0.000000000000000000e+00,-1.430721200715715096e-09,0.000000000000000000e+00 +2.950098320221511017e+01,1.643199999999999932e+02,0.000000000000000000e+00,9.817282377538694149e+00,0.000000000000000000e+00,1.000000009897082709e+00,0.000000000000000000e+00,1.492124154772786321e-09,0.000000000000000000e+00 +2.950200181404834865e+01,1.643300000000000125e+02,0.000000000000000000e+00,9.818300989382013455e+00,0.000000000000000000e+00,1.000000009898602604e+00,0.000000000000000000e+00,3.178586914236220186e-10,0.000000000000000000e+00 +2.950302032020443477e+01,1.643400000000000034e+02,0.000000000000000000e+00,9.819319495548182175e+00,0.000000000000000000e+00,1.000000009898926345e+00,0.000000000000000000e+00,-1.543017359883924576e-09,0.000000000000000000e+00 +2.950403872071625599e+01,1.643499999999999943e+02,0.000000000000000000e+00,9.820337896070084227e+00,0.000000000000000000e+00,1.000000009897354936e+00,0.000000000000000000e+00,1.037507140411208177e-09,0.000000000000000000e+00 +2.950505701561667848e+01,1.643600000000000136e+02,0.000000000000000000e+00,9.821356190980585765e+00,0.000000000000000000e+00,1.000000009898411424e+00,0.000000000000000000e+00,-5.181531272884203708e-10,0.000000000000000000e+00 +2.950607520493855418e+01,1.643700000000000045e+02,0.000000000000000000e+00,9.822374380312540509e+00,0.000000000000000000e+00,1.000000009897883846e+00,0.000000000000000000e+00,-1.082651000491795567e-09,0.000000000000000000e+00 +2.950709328871471726e+01,1.643799999999999955e+02,0.000000000000000000e+00,9.823392464098780863e+00,0.000000000000000000e+00,1.000000009896781616e+00,0.000000000000000000e+00,1.047427269642627793e-09,0.000000000000000000e+00 +2.950811126697798414e+01,1.643900000000000148e+02,0.000000000000000000e+00,9.824410442372123242e+00,0.000000000000000000e+00,1.000000009897847875e+00,0.000000000000000000e+00,7.179176090465291133e-10,0.000000000000000000e+00 +2.950912913976115703e+01,1.644000000000000057e+02,0.000000000000000000e+00,9.825428315165369852e+00,0.000000000000000000e+00,1.000000009898578623e+00,0.000000000000000000e+00,-2.085252944458173743e-09,0.000000000000000000e+00 +2.951014690709701682e+01,1.644099999999999966e+02,0.000000000000000000e+00,9.826446082511303359e+00,0.000000000000000000e+00,1.000000009896456321e+00,0.000000000000000000e+00,1.201795663485155761e-09,0.000000000000000000e+00 +2.951116456901833018e+01,1.644200000000000159e+02,0.000000000000000000e+00,9.827463744442686888e+00,0.000000000000000000e+00,1.000000009897679343e+00,0.000000000000000000e+00,2.764765430864653826e-10,0.000000000000000000e+00 +2.951218212555784604e+01,1.644300000000000068e+02,0.000000000000000000e+00,9.828481300992272907e+00,0.000000000000000000e+00,1.000000009897960673e+00,0.000000000000000000e+00,-1.442977256841635524e-09,0.000000000000000000e+00 +2.951319957674829553e+01,1.644399999999999977e+02,0.000000000000000000e+00,9.829498752192792566e+00,0.000000000000000000e+00,1.000000009896492514e+00,0.000000000000000000e+00,1.179251846352650287e-09,0.000000000000000000e+00 +2.951421692262239560e+01,1.644500000000000171e+02,0.000000000000000000e+00,9.830516098076959253e+00,0.000000000000000000e+00,1.000000009897692221e+00,0.000000000000000000e+00,-4.492229284079303854e-10,0.000000000000000000e+00 +2.951523416321284188e+01,1.644600000000000080e+02,0.000000000000000000e+00,9.831533338677473921e+00,0.000000000000000000e+00,1.000000009897235254e+00,0.000000000000000000e+00,-1.190847739584679791e-09,0.000000000000000000e+00 +2.951625129855231577e+01,1.644699999999999989e+02,0.000000000000000000e+00,9.832550474027016207e+00,0.000000000000000000e+00,1.000000009896024000e+00,0.000000000000000000e+00,6.589093122369668434e-10,0.000000000000000000e+00 +2.951726832867348449e+01,1.644799999999999898e+02,0.000000000000000000e+00,9.833567504158249761e+00,0.000000000000000000e+00,1.000000009896694131e+00,0.000000000000000000e+00,-6.201113336559023253e-11,0.000000000000000000e+00 +2.951828525360899391e+01,1.644900000000000091e+02,0.000000000000000000e+00,9.834584429103824021e+00,0.000000000000000000e+00,1.000000009896631070e+00,0.000000000000000000e+00,6.878706704611002884e-11,0.000000000000000000e+00 +2.951930207339147572e+01,1.645000000000000000e+02,0.000000000000000000e+00,9.835601248896368887e+00,0.000000000000000000e+00,1.000000009896701014e+00,0.000000000000000000e+00,1.039556484111397331e-09,0.000000000000000000e+00 +2.952031878805354381e+01,1.645099999999999909e+02,0.000000000000000000e+00,9.836617963568498269e+00,0.000000000000000000e+00,1.000000009897757947e+00,0.000000000000000000e+00,-2.317183777644742524e-09,0.000000000000000000e+00 +2.952133539762779435e+01,1.645200000000000102e+02,0.000000000000000000e+00,9.837634573152810091e+00,0.000000000000000000e+00,1.000000009895402275e+00,0.000000000000000000e+00,2.018816641082349482e-09,0.000000000000000000e+00 +2.952235190214680571e+01,1.645300000000000011e+02,0.000000000000000000e+00,9.838651077681880963e+00,0.000000000000000000e+00,1.000000009897454412e+00,0.000000000000000000e+00,-1.436168787997808915e-09,0.000000000000000000e+00 +2.952336830164314208e+01,1.645399999999999920e+02,0.000000000000000000e+00,9.839667477188278610e+00,0.000000000000000000e+00,1.000000009895994690e+00,0.000000000000000000e+00,-6.589492753938906492e-10,0.000000000000000000e+00 +2.952438459614935340e+01,1.645500000000000114e+02,0.000000000000000000e+00,9.840683771704545890e+00,0.000000000000000000e+00,1.000000009895325004e+00,0.000000000000000000e+00,9.009046662175687709e-10,0.000000000000000000e+00 +2.952540078569796478e+01,1.645600000000000023e+02,0.000000000000000000e+00,9.841699961263213225e+00,0.000000000000000000e+00,1.000000009896240494e+00,0.000000000000000000e+00,-2.089143338983052910e-10,0.000000000000000000e+00 +2.952641687032149065e+01,1.645699999999999932e+02,0.000000000000000000e+00,9.842716045896795052e+00,0.000000000000000000e+00,1.000000009896028219e+00,0.000000000000000000e+00,1.160512179770023058e-09,0.000000000000000000e+00 +2.952743285005242768e+01,1.645800000000000125e+02,0.000000000000000000e+00,9.843732025637786265e+00,0.000000000000000000e+00,1.000000009897207276e+00,0.000000000000000000e+00,-1.886300168979595500e-09,0.000000000000000000e+00 +2.952844872492325479e+01,1.645900000000000034e+02,0.000000000000000000e+00,9.844747900518667549e+00,0.000000000000000000e+00,1.000000009895291031e+00,0.000000000000000000e+00,9.666373305371133738e-10,0.000000000000000000e+00 +2.952946449496643311e+01,1.645999999999999943e+02,0.000000000000000000e+00,9.845763670571898274e+00,0.000000000000000000e+00,1.000000009896272912e+00,0.000000000000000000e+00,-6.206618121840893470e-10,0.000000000000000000e+00 +2.953048016021440958e+01,1.646100000000000136e+02,0.000000000000000000e+00,9.846779335829927149e+00,0.000000000000000000e+00,1.000000009895642528e+00,0.000000000000000000e+00,2.258576226912792773e-10,0.000000000000000000e+00 +2.953149572069961337e+01,1.646200000000000045e+02,0.000000000000000000e+00,9.847794896325181568e+00,0.000000000000000000e+00,1.000000009895871900e+00,0.000000000000000000e+00,5.160493356043944054e-11,0.000000000000000000e+00 +2.953251117645445945e+01,1.646299999999999955e+02,0.000000000000000000e+00,9.848810352090074716e+00,0.000000000000000000e+00,1.000000009895924302e+00,0.000000000000000000e+00,-1.156638295190068944e-09,0.000000000000000000e+00 +2.953352652751133789e+01,1.646400000000000148e+02,0.000000000000000000e+00,9.849825703157002010e+00,0.000000000000000000e+00,1.000000009894749908e+00,0.000000000000000000e+00,3.630587090350939088e-11,0.000000000000000000e+00 +2.953454177390263169e+01,1.646500000000000057e+02,0.000000000000000000e+00,9.850840949558341109e+00,0.000000000000000000e+00,1.000000009894786768e+00,0.000000000000000000e+00,1.896411717276409688e-09,0.000000000000000000e+00 +2.953555691566070251e+01,1.646599999999999966e+02,0.000000000000000000e+00,9.851856091326455456e+00,0.000000000000000000e+00,1.000000009896711894e+00,0.000000000000000000e+00,-2.484402231255223863e-09,0.000000000000000000e+00 +2.953657195281789427e+01,1.646700000000000159e+02,0.000000000000000000e+00,9.852871128493692510e+00,0.000000000000000000e+00,1.000000009894190134e+00,0.000000000000000000e+00,6.742728335233384736e-10,0.000000000000000000e+00 +2.953758688540653665e+01,1.646800000000000068e+02,0.000000000000000000e+00,9.853886061092376636e+00,0.000000000000000000e+00,1.000000009894874475e+00,0.000000000000000000e+00,1.016545839501396669e-09,0.000000000000000000e+00 +2.953860171345894159e+01,1.646899999999999977e+02,0.000000000000000000e+00,9.854900889154823318e+00,0.000000000000000000e+00,1.000000009895906095e+00,0.000000000000000000e+00,-1.470926575584091205e-09,0.000000000000000000e+00 +2.953961643700740680e+01,1.647000000000000171e+02,0.000000000000000000e+00,9.855915612713328500e+00,0.000000000000000000e+00,1.000000009894413511e+00,0.000000000000000000e+00,1.002311422886915649e-10,0.000000000000000000e+00 +2.954063105608420869e+01,1.647100000000000080e+02,0.000000000000000000e+00,9.856930231800168585e+00,0.000000000000000000e+00,1.000000009894515207e+00,0.000000000000000000e+00,5.436676596868666058e-10,0.000000000000000000e+00 +2.954164557072160946e+01,1.647199999999999989e+02,0.000000000000000000e+00,9.857944746447607542e+00,0.000000000000000000e+00,1.000000009895066766e+00,0.000000000000000000e+00,-1.527854605725227078e-10,0.000000000000000000e+00 +2.954265998095185708e+01,1.647299999999999898e+02,0.000000000000000000e+00,9.858959156687891578e+00,0.000000000000000000e+00,1.000000009894911779e+00,0.000000000000000000e+00,-2.753923893175828335e-10,0.000000000000000000e+00 +2.954367428680717822e+01,1.647400000000000091e+02,0.000000000000000000e+00,9.859973462553249135e+00,0.000000000000000000e+00,1.000000009894632447e+00,0.000000000000000000e+00,1.644204787960010901e-10,0.000000000000000000e+00 +2.954468848831978534e+01,1.647500000000000000e+02,0.000000000000000000e+00,9.860987664075892667e+00,0.000000000000000000e+00,1.000000009894799202e+00,0.000000000000000000e+00,-5.706043160765122513e-10,0.000000000000000000e+00 +2.954570258552187667e+01,1.647599999999999909e+02,0.000000000000000000e+00,9.862001761288018642e+00,0.000000000000000000e+00,1.000000009894220554e+00,0.000000000000000000e+00,9.611051006229301694e-10,0.000000000000000000e+00 +2.954671657844563271e+01,1.647700000000000102e+02,0.000000000000000000e+00,9.863015754221805764e+00,0.000000000000000000e+00,1.000000009895195108e+00,0.000000000000000000e+00,-2.161997059728141625e-09,0.000000000000000000e+00 +2.954773046712321261e+01,1.647800000000000011e+02,0.000000000000000000e+00,9.864029642909418527e+00,0.000000000000000000e+00,1.000000009893003083e+00,0.000000000000000000e+00,2.143821168250012753e-09,0.000000000000000000e+00 +2.954874425158676488e+01,1.647899999999999920e+02,0.000000000000000000e+00,9.865043427383000108e+00,0.000000000000000000e+00,1.000000009895176456e+00,0.000000000000000000e+00,-1.686231250275101518e-09,0.000000000000000000e+00 +2.954975793186842026e+01,1.648000000000000114e+02,0.000000000000000000e+00,9.866057107674684801e+00,0.000000000000000000e+00,1.000000009893467157e+00,0.000000000000000000e+00,1.632075040717859693e-10,0.000000000000000000e+00 +2.955077150800028818e+01,1.648100000000000023e+02,0.000000000000000000e+00,9.867070683816582033e+00,0.000000000000000000e+00,1.000000009893632580e+00,0.000000000000000000e+00,7.672636200767449813e-10,0.000000000000000000e+00 +2.955178498001447096e+01,1.648199999999999932e+02,0.000000000000000000e+00,9.868084155840790572e+00,0.000000000000000000e+00,1.000000009894410180e+00,0.000000000000000000e+00,1.119680127200571737e-10,0.000000000000000000e+00 +2.955279834794304605e+01,1.648300000000000125e+02,0.000000000000000000e+00,9.869097523779391423e+00,0.000000000000000000e+00,1.000000009894523645e+00,0.000000000000000000e+00,-1.813147696688736637e-09,0.000000000000000000e+00 +2.955381161181807670e+01,1.648400000000000034e+02,0.000000000000000000e+00,9.870110787664447827e+00,0.000000000000000000e+00,1.000000009892686448e+00,0.000000000000000000e+00,1.900340565793322052e-09,0.000000000000000000e+00 +2.955482477167161193e+01,1.648499999999999943e+02,0.000000000000000000e+00,9.871123947528005260e+00,0.000000000000000000e+00,1.000000009894611797e+00,0.000000000000000000e+00,-8.705948033500828966e-10,0.000000000000000000e+00 +2.955583782753568300e+01,1.648600000000000136e+02,0.000000000000000000e+00,9.872137003402098543e+00,0.000000000000000000e+00,1.000000009893729835e+00,0.000000000000000000e+00,-1.486651538697381888e-09,0.000000000000000000e+00 +2.955685077944230343e+01,1.648700000000000045e+02,0.000000000000000000e+00,9.873149955318739401e+00,0.000000000000000000e+00,1.000000009892223929e+00,0.000000000000000000e+00,1.774431173958698935e-09,0.000000000000000000e+00 +2.955786362742346896e+01,1.648799999999999955e+02,0.000000000000000000e+00,9.874162803309925351e+00,0.000000000000000000e+00,1.000000009894021158e+00,0.000000000000000000e+00,-1.487614356598006917e-09,0.000000000000000000e+00 +2.955887637151116465e+01,1.648900000000000148e+02,0.000000000000000000e+00,9.875175547407641474e+00,0.000000000000000000e+00,1.000000009892514585e+00,0.000000000000000000e+00,8.369648322060766128e-10,0.000000000000000000e+00 +2.955988901173735428e+01,1.649000000000000057e+02,0.000000000000000000e+00,9.876188187643849759e+00,0.000000000000000000e+00,1.000000009893362130e+00,0.000000000000000000e+00,7.697269608060144732e-11,0.000000000000000000e+00 +2.956090154813398740e+01,1.649099999999999966e+02,0.000000000000000000e+00,9.877200724050501535e+00,0.000000000000000000e+00,1.000000009893440067e+00,0.000000000000000000e+00,-3.145018876058096162e-10,0.000000000000000000e+00 +2.956191398073299936e+01,1.649200000000000159e+02,0.000000000000000000e+00,9.878213156659528593e+00,0.000000000000000000e+00,1.000000009893121655e+00,0.000000000000000000e+00,-3.494092472812988683e-10,0.000000000000000000e+00 +2.956292630956630418e+01,1.649300000000000068e+02,0.000000000000000000e+00,9.879225485502846738e+00,0.000000000000000000e+00,1.000000009892767938e+00,0.000000000000000000e+00,-3.838850259814115486e-11,0.000000000000000000e+00 +2.956393853466579813e+01,1.649399999999999977e+02,0.000000000000000000e+00,9.880237710612355784e+00,0.000000000000000000e+00,1.000000009892729080e+00,0.000000000000000000e+00,6.074780283401718015e-10,0.000000000000000000e+00 +2.956495065606337036e+01,1.649500000000000171e+02,0.000000000000000000e+00,9.881249832019939561e+00,0.000000000000000000e+00,1.000000009893343922e+00,0.000000000000000000e+00,-1.892392460537894578e-09,0.000000000000000000e+00 +2.956596267379088516e+01,1.649600000000000080e+02,0.000000000000000000e+00,9.882261849757465910e+00,0.000000000000000000e+00,1.000000009891428787e+00,0.000000000000000000e+00,1.122605378064616166e-09,0.000000000000000000e+00 +2.956697458788019262e+01,1.649699999999999989e+02,0.000000000000000000e+00,9.883273763856783134e+00,0.000000000000000000e+00,1.000000009892564767e+00,0.000000000000000000e+00,9.693228489861073497e-10,0.000000000000000000e+00 +2.956798639836312859e+01,1.649799999999999898e+02,0.000000000000000000e+00,9.884285574349728876e+00,0.000000000000000000e+00,1.000000009893545538e+00,0.000000000000000000e+00,-2.366381914034904599e-09,0.000000000000000000e+00 +2.956899810527151118e+01,1.649900000000000091e+02,0.000000000000000000e+00,9.885297281268121239e+00,0.000000000000000000e+00,1.000000009891151453e+00,0.000000000000000000e+00,1.517607048977249680e-09,0.000000000000000000e+00 +2.957000970863714429e+01,1.650000000000000000e+02,0.000000000000000000e+00,9.886308884643758788e+00,0.000000000000000000e+00,1.000000009892686670e+00,0.000000000000000000e+00,4.612118457511313863e-10,0.000000000000000000e+00 +2.957102120849181048e+01,1.650099999999999909e+02,0.000000000000000000e+00,9.887320384508431204e+00,0.000000000000000000e+00,1.000000009893153186e+00,0.000000000000000000e+00,-2.077312221753641613e-09,0.000000000000000000e+00 +2.957203260486728169e+01,1.650200000000000102e+02,0.000000000000000000e+00,9.888331780893906853e+00,0.000000000000000000e+00,1.000000009891052200e+00,0.000000000000000000e+00,8.374211860024818922e-10,0.000000000000000000e+00 +2.957304389779530851e+01,1.650300000000000011e+02,0.000000000000000000e+00,9.889343073831936337e+00,0.000000000000000000e+00,1.000000009891899078e+00,0.000000000000000000e+00,5.114193517331462262e-10,0.000000000000000000e+00 +2.957405508730763088e+01,1.650399999999999920e+02,0.000000000000000000e+00,9.890354263354259601e+00,0.000000000000000000e+00,1.000000009892416220e+00,0.000000000000000000e+00,-1.331275701775902856e-09,0.000000000000000000e+00 +2.957506617343596744e+01,1.650500000000000114e+02,0.000000000000000000e+00,9.891365349492597048e+00,0.000000000000000000e+00,1.000000009891070185e+00,0.000000000000000000e+00,5.106454023533554897e-10,0.000000000000000000e+00 +2.957607715621202260e+01,1.650600000000000023e+02,0.000000000000000000e+00,9.892376332278651319e+00,0.000000000000000000e+00,1.000000009891586439e+00,0.000000000000000000e+00,8.140409832307833582e-10,0.000000000000000000e+00 +2.957708803566748301e+01,1.650699999999999932e+02,0.000000000000000000e+00,9.893387211744112619e+00,0.000000000000000000e+00,1.000000009892409336e+00,0.000000000000000000e+00,-4.343020724743709652e-10,0.000000000000000000e+00 +2.957809881183402467e+01,1.650800000000000125e+02,0.000000000000000000e+00,9.894397987920653392e+00,0.000000000000000000e+00,1.000000009891970354e+00,0.000000000000000000e+00,-1.507579816386861957e-09,0.000000000000000000e+00 +2.957910948474330226e+01,1.650900000000000034e+02,0.000000000000000000e+00,9.895408660839928316e+00,0.000000000000000000e+00,1.000000009890446684e+00,0.000000000000000000e+00,1.062576610784613340e-09,0.000000000000000000e+00 +2.958012005442695624e+01,1.650999999999999943e+02,0.000000000000000000e+00,9.896419230533576084e+00,0.000000000000000000e+00,1.000000009891520492e+00,0.000000000000000000e+00,3.074227651004617799e-10,0.000000000000000000e+00 +2.958113052091660933e+01,1.651100000000000136e+02,0.000000000000000000e+00,9.897429697033222951e+00,0.000000000000000000e+00,1.000000009891831132e+00,0.000000000000000000e+00,-3.056960175789760836e-10,0.000000000000000000e+00 +2.958214088424386645e+01,1.651200000000000045e+02,0.000000000000000000e+00,9.898440060370475635e+00,0.000000000000000000e+00,1.000000009891522268e+00,0.000000000000000000e+00,-7.890443813158844679e-10,0.000000000000000000e+00 +2.958315114444032190e+01,1.651299999999999955e+02,0.000000000000000000e+00,9.899450320576924867e+00,0.000000000000000000e+00,1.000000009890725128e+00,0.000000000000000000e+00,5.888762235356632273e-10,0.000000000000000000e+00 +2.958416130153755219e+01,1.651400000000000148e+02,0.000000000000000000e+00,9.900460477684145388e+00,0.000000000000000000e+00,1.000000009891319985e+00,0.000000000000000000e+00,-1.407599557770291318e-09,0.000000000000000000e+00 +2.958517135556711253e+01,1.651500000000000057e+02,0.000000000000000000e+00,9.901470531723697732e+00,0.000000000000000000e+00,1.000000009889898234e+00,0.000000000000000000e+00,1.752258785577562393e-10,0.000000000000000000e+00 +2.958618130656055101e+01,1.651599999999999966e+02,0.000000000000000000e+00,9.902480482727122890e+00,0.000000000000000000e+00,1.000000009890075203e+00,0.000000000000000000e+00,1.845226554021329018e-09,0.000000000000000000e+00 +2.958719115454939086e+01,1.651700000000000159e+02,0.000000000000000000e+00,9.903490330725949420e+00,0.000000000000000000e+00,1.000000009891938602e+00,0.000000000000000000e+00,-1.636728053790853347e-09,0.000000000000000000e+00 +2.958820089956514465e+01,1.651800000000000068e+02,0.000000000000000000e+00,9.904500075751689891e+00,0.000000000000000000e+00,1.000000009890285924e+00,0.000000000000000000e+00,1.711009347301576181e-10,0.000000000000000000e+00 +2.958921054163930364e+01,1.651899999999999977e+02,0.000000000000000000e+00,9.905509717835835559e+00,0.000000000000000000e+00,1.000000009890458674e+00,0.000000000000000000e+00,2.887897534335704387e-10,0.000000000000000000e+00 +2.959022008080335198e+01,1.652000000000000171e+02,0.000000000000000000e+00,9.906519257009867019e+00,0.000000000000000000e+00,1.000000009890750219e+00,0.000000000000000000e+00,-1.295836880977788181e-09,0.000000000000000000e+00 +2.959122951708874893e+01,1.652100000000000080e+02,0.000000000000000000e+00,9.907528693305247103e+00,0.000000000000000000e+00,1.000000009889442154e+00,0.000000000000000000e+00,6.355549507776917081e-10,0.000000000000000000e+00 +2.959223885052693959e+01,1.652199999999999989e+02,0.000000000000000000e+00,9.908538026753420880e+00,0.000000000000000000e+00,1.000000009890083641e+00,0.000000000000000000e+00,8.428726423591016120e-10,0.000000000000000000e+00 +2.959324808114935834e+01,1.652299999999999898e+02,0.000000000000000000e+00,9.909547257385820984e+00,0.000000000000000000e+00,1.000000009890934294e+00,0.000000000000000000e+00,-6.871728982464002729e-10,0.000000000000000000e+00 +2.959425720898741830e+01,1.652400000000000091e+02,0.000000000000000000e+00,9.910556385233862287e+00,0.000000000000000000e+00,1.000000009890240849e+00,0.000000000000000000e+00,-4.770869531253610274e-10,0.000000000000000000e+00 +2.959526623407251833e+01,1.652500000000000000e+02,0.000000000000000000e+00,9.911565410328941894e+00,0.000000000000000000e+00,1.000000009889759456e+00,0.000000000000000000e+00,-2.819237130553847166e-10,0.000000000000000000e+00 +2.959627515643603957e+01,1.652599999999999909e+02,0.000000000000000000e+00,9.912574332702442703e+00,0.000000000000000000e+00,1.000000009889475017e+00,0.000000000000000000e+00,-1.129130263216893670e-10,0.000000000000000000e+00 +2.959728397610935247e+01,1.652700000000000102e+02,0.000000000000000000e+00,9.913583152385731623e+00,0.000000000000000000e+00,1.000000009889361108e+00,0.000000000000000000e+00,1.849056429748866510e-11,0.000000000000000000e+00 +2.959829269312380617e+01,1.652800000000000011e+02,0.000000000000000000e+00,9.914591869410159575e+00,0.000000000000000000e+00,1.000000009889379760e+00,0.000000000000000000e+00,1.014883033567244949e-10,0.000000000000000000e+00 +2.959930130751073207e+01,1.652899999999999920e+02,0.000000000000000000e+00,9.915600483807061494e+00,0.000000000000000000e+00,1.000000009889482122e+00,0.000000000000000000e+00,1.248367070676127071e-10,0.000000000000000000e+00 +2.960030981930145444e+01,1.653000000000000114e+02,0.000000000000000000e+00,9.916608995607756327e+00,0.000000000000000000e+00,1.000000009889608021e+00,0.000000000000000000e+00,7.706753343190075309e-11,0.000000000000000000e+00 +2.960131822852727268e+01,1.653100000000000023e+02,0.000000000000000000e+00,9.917617404843547035e+00,0.000000000000000000e+00,1.000000009889685737e+00,0.000000000000000000e+00,-5.285168252294639314e-11,0.000000000000000000e+00 +2.960232653521947555e+01,1.653199999999999932e+02,0.000000000000000000e+00,9.918625711545720591e+00,0.000000000000000000e+00,1.000000009889632446e+00,0.000000000000000000e+00,-2.023764526257601402e-09,0.000000000000000000e+00 +2.960333473940933047e+01,1.653300000000000125e+02,0.000000000000000000e+00,9.919633915745547981e+00,0.000000000000000000e+00,1.000000009887592078e+00,0.000000000000000000e+00,2.892015367489154421e-09,0.000000000000000000e+00 +2.960434284112809777e+01,1.653400000000000034e+02,0.000000000000000000e+00,9.920642017474282426e+00,0.000000000000000000e+00,1.000000009890507524e+00,0.000000000000000000e+00,-2.795384972426010650e-09,0.000000000000000000e+00 +2.960535084040701292e+01,1.653499999999999943e+02,0.000000000000000000e+00,9.921650016763168267e+00,0.000000000000000000e+00,1.000000009887689778e+00,0.000000000000000000e+00,1.879861590682099347e-09,0.000000000000000000e+00 +2.960635873727730072e+01,1.653600000000000136e+02,0.000000000000000000e+00,9.922657913643423200e+00,0.000000000000000000e+00,1.000000009889584485e+00,0.000000000000000000e+00,-5.768167814039433653e-10,0.000000000000000000e+00 +2.960736653177017175e+01,1.653700000000000045e+02,0.000000000000000000e+00,9.923665708146259590e+00,0.000000000000000000e+00,1.000000009889003172e+00,0.000000000000000000e+00,-1.433815128024822498e-09,0.000000000000000000e+00 +2.960837422391681528e+01,1.653799999999999955e+02,0.000000000000000000e+00,9.924673400302866710e+00,0.000000000000000000e+00,1.000000009887558328e+00,0.000000000000000000e+00,1.048089319596111196e-09,0.000000000000000000e+00 +2.960938181374840639e+01,1.653900000000000148e+02,0.000000000000000000e+00,9.925680990144419624e+00,0.000000000000000000e+00,1.000000009888614372e+00,0.000000000000000000e+00,-1.403912273261641753e-10,0.000000000000000000e+00 +2.961038930129610591e+01,1.654000000000000057e+02,0.000000000000000000e+00,9.926688477702080959e+00,0.000000000000000000e+00,1.000000009888472929e+00,0.000000000000000000e+00,2.393726036672307717e-10,0.000000000000000000e+00 +2.961139668659105695e+01,1.654099999999999966e+02,0.000000000000000000e+00,9.927695863006993804e+00,0.000000000000000000e+00,1.000000009888714070e+00,0.000000000000000000e+00,-1.325720931258357663e-09,0.000000000000000000e+00 +2.961240396966438837e+01,1.654200000000000159e+02,0.000000000000000000e+00,9.928703146090287035e+00,0.000000000000000000e+00,1.000000009887378694e+00,0.000000000000000000e+00,2.158097591677461525e-09,0.000000000000000000e+00 +2.961341115054721485e+01,1.654300000000000068e+02,0.000000000000000000e+00,9.929710326983071766e+00,0.000000000000000000e+00,1.000000009889552288e+00,0.000000000000000000e+00,-1.578002990725698592e-09,0.000000000000000000e+00 +2.961441822927063328e+01,1.654399999999999977e+02,0.000000000000000000e+00,9.930717405716448454e+00,0.000000000000000000e+00,1.000000009887963115e+00,0.000000000000000000e+00,-2.875401138758670970e-10,0.000000000000000000e+00 +2.961542520586572280e+01,1.654500000000000171e+02,0.000000000000000000e+00,9.931724382321494460e+00,0.000000000000000000e+00,1.000000009887673569e+00,0.000000000000000000e+00,-9.857627600635039033e-10,0.000000000000000000e+00 +2.961643208036354835e+01,1.654600000000000080e+02,0.000000000000000000e+00,9.932731256829276489e+00,0.000000000000000000e+00,1.000000009886681029e+00,0.000000000000000000e+00,1.572087091587605847e-09,0.000000000000000000e+00 +2.961743885279516064e+01,1.654699999999999989e+02,0.000000000000000000e+00,9.933738029270843484e+00,0.000000000000000000e+00,1.000000009888263763e+00,0.000000000000000000e+00,3.650488009308726922e-10,0.000000000000000000e+00 +2.961844552319159618e+01,1.654799999999999898e+02,0.000000000000000000e+00,9.934744699677231949e+00,0.000000000000000000e+00,1.000000009888631247e+00,0.000000000000000000e+00,-1.112905035013858734e-09,0.000000000000000000e+00 +2.961945209158387016e+01,1.654900000000000091e+02,0.000000000000000000e+00,9.935751268079458853e+00,0.000000000000000000e+00,1.000000009887511032e+00,0.000000000000000000e+00,-1.120298186203683065e-09,0.000000000000000000e+00 +2.962045855800298355e+01,1.655000000000000000e+02,0.000000000000000000e+00,9.936757734508525175e+00,0.000000000000000000e+00,1.000000009886383490e+00,0.000000000000000000e+00,2.087257659343381140e-09,0.000000000000000000e+00 +2.962146492247992668e+01,1.655099999999999909e+02,0.000000000000000000e+00,9.937764098995417683e+00,0.000000000000000000e+00,1.000000009888484032e+00,0.000000000000000000e+00,-2.024800846375950654e-09,0.000000000000000000e+00 +2.962247118504566856e+01,1.655200000000000102e+02,0.000000000000000000e+00,9.938770361571110712e+00,0.000000000000000000e+00,1.000000009886446550e+00,0.000000000000000000e+00,5.649536866241709673e-10,0.000000000000000000e+00 +2.962347734573116753e+01,1.655300000000000011e+02,0.000000000000000000e+00,9.939776522266555503e+00,0.000000000000000000e+00,1.000000009887014984e+00,0.000000000000000000e+00,-6.806615447867439056e-10,0.000000000000000000e+00 +2.962448340456736062e+01,1.655399999999999920e+02,0.000000000000000000e+00,9.940782581112694416e+00,0.000000000000000000e+00,1.000000009886330199e+00,0.000000000000000000e+00,1.247122884590872602e-09,0.000000000000000000e+00 +2.962548936158517066e+01,1.655500000000000114e+02,0.000000000000000000e+00,9.941788538140450271e+00,0.000000000000000000e+00,1.000000009887584751e+00,0.000000000000000000e+00,-6.834483493385963536e-10,0.000000000000000000e+00 +2.962649521681550979e+01,1.655600000000000023e+02,0.000000000000000000e+00,9.942794393380733453e+00,0.000000000000000000e+00,1.000000009886897301e+00,0.000000000000000000e+00,5.373648538029286298e-10,0.000000000000000000e+00 +2.962750097028926888e+01,1.655699999999999932e+02,0.000000000000000000e+00,9.943800146864434808e+00,0.000000000000000000e+00,1.000000009887437757e+00,0.000000000000000000e+00,-2.124064422411550412e-09,0.000000000000000000e+00 +2.962850662203732455e+01,1.655800000000000125e+02,0.000000000000000000e+00,9.944805798622432746e+00,0.000000000000000000e+00,1.000000009885301688e+00,0.000000000000000000e+00,1.859738017717618749e-09,0.000000000000000000e+00 +2.962951217209053922e+01,1.655900000000000034e+02,0.000000000000000000e+00,9.945811348685586140e+00,0.000000000000000000e+00,1.000000009887171748e+00,0.000000000000000000e+00,-1.576144894501064390e-09,0.000000000000000000e+00 +2.963051762047975757e+01,1.655999999999999943e+02,0.000000000000000000e+00,9.946816797084744977e+00,0.000000000000000000e+00,1.000000009885587016e+00,0.000000000000000000e+00,1.613851060262532994e-09,0.000000000000000000e+00 +2.963152296723581003e+01,1.656100000000000136e+02,0.000000000000000000e+00,9.947822143850736154e+00,0.000000000000000000e+00,1.000000009887209496e+00,0.000000000000000000e+00,-8.824396649994279649e-10,0.000000000000000000e+00 +2.963252821238951284e+01,1.656200000000000045e+02,0.000000000000000000e+00,9.948827389014377687e+00,0.000000000000000000e+00,1.000000009886322427e+00,0.000000000000000000e+00,-2.889481148755824704e-10,0.000000000000000000e+00 +2.963353335597166449e+01,1.656299999999999955e+02,0.000000000000000000e+00,9.949832532606466273e+00,0.000000000000000000e+00,1.000000009886031993e+00,0.000000000000000000e+00,-1.307909527193513142e-10,0.000000000000000000e+00 +2.963453839801304923e+01,1.656400000000000148e+02,0.000000000000000000e+00,9.950837574657786178e+00,0.000000000000000000e+00,1.000000009885900543e+00,0.000000000000000000e+00,-4.200316145880222866e-10,0.000000000000000000e+00 +2.963554333854443357e+01,1.656500000000000057e+02,0.000000000000000000e+00,9.951842515199105677e+00,0.000000000000000000e+00,1.000000009885478436e+00,0.000000000000000000e+00,5.919928125090658033e-10,0.000000000000000000e+00 +2.963654817759657334e+01,1.656599999999999966e+02,0.000000000000000000e+00,9.952847354261177060e+00,0.000000000000000000e+00,1.000000009886073293e+00,0.000000000000000000e+00,-6.240972389644730171e-10,0.000000000000000000e+00 +2.963755291520020307e+01,1.656700000000000159e+02,0.000000000000000000e+00,9.953852091874738406e+00,0.000000000000000000e+00,1.000000009885446239e+00,0.000000000000000000e+00,-5.609485455954762005e-10,0.000000000000000000e+00 +2.963855755138604309e+01,1.656800000000000068e+02,0.000000000000000000e+00,9.954856728070510030e+00,0.000000000000000000e+00,1.000000009884882690e+00,0.000000000000000000e+00,7.721004846839084808e-10,0.000000000000000000e+00 +2.963956208618480304e+01,1.656899999999999977e+02,0.000000000000000000e+00,9.955861262879198037e+00,0.000000000000000000e+00,1.000000009885658292e+00,0.000000000000000000e+00,-1.569558149371148746e-10,0.000000000000000000e+00 +2.964056651962717126e+01,1.657000000000000171e+02,0.000000000000000000e+00,9.956865696331494320e+00,0.000000000000000000e+00,1.000000009885500640e+00,0.000000000000000000e+00,1.616144734488305674e-10,0.000000000000000000e+00 +2.964157085174382189e+01,1.657100000000000080e+02,0.000000000000000000e+00,9.957870028458073008e+00,0.000000000000000000e+00,1.000000009885662955e+00,0.000000000000000000e+00,-4.311628066909377020e-11,0.000000000000000000e+00 +2.964257508256541485e+01,1.657199999999999989e+02,0.000000000000000000e+00,9.958874259289594022e+00,0.000000000000000000e+00,1.000000009885619656e+00,0.000000000000000000e+00,-7.825841309122754673e-10,0.000000000000000000e+00 +2.964357921212259583e+01,1.657299999999999898e+02,0.000000000000000000e+00,9.959878388856701292e+00,0.000000000000000000e+00,1.000000009884833840e+00,0.000000000000000000e+00,-3.060767570545779972e-10,0.000000000000000000e+00 +2.964458324044599280e+01,1.657400000000000091e+02,0.000000000000000000e+00,9.960882417190022764e+00,0.000000000000000000e+00,1.000000009884526531e+00,0.000000000000000000e+00,-3.855098030394679063e-10,0.000000000000000000e+00 +2.964558716756621948e+01,1.657500000000000000e+02,0.000000000000000000e+00,9.961886344320172171e+00,0.000000000000000000e+00,1.000000009884139507e+00,0.000000000000000000e+00,7.301756271305334384e-10,0.000000000000000000e+00 +2.964659099351387184e+01,1.657599999999999909e+02,0.000000000000000000e+00,9.962890170277747259e+00,0.000000000000000000e+00,1.000000009884872476e+00,0.000000000000000000e+00,1.268700147750553895e-09,0.000000000000000000e+00 +2.964759471831953519e+01,1.657700000000000102e+02,0.000000000000000000e+00,9.963893895093331565e+00,0.000000000000000000e+00,1.000000009886145902e+00,0.000000000000000000e+00,-2.309554511434426083e-09,0.000000000000000000e+00 +2.964859834201377353e+01,1.657800000000000011e+02,0.000000000000000000e+00,9.964897518797492637e+00,0.000000000000000000e+00,1.000000009883827978e+00,0.000000000000000000e+00,5.666601087393002937e-10,0.000000000000000000e+00 +2.964960186462714020e+01,1.657899999999999920e+02,0.000000000000000000e+00,9.965901041420778483e+00,0.000000000000000000e+00,1.000000009884396635e+00,0.000000000000000000e+00,-6.959490489515019080e-10,0.000000000000000000e+00 +2.965060528619017077e+01,1.658000000000000114e+02,0.000000000000000000e+00,9.966904462993728231e+00,0.000000000000000000e+00,1.000000009883698304e+00,0.000000000000000000e+00,9.487548398657644153e-10,0.000000000000000000e+00 +2.965160860673338661e+01,1.658100000000000023e+02,0.000000000000000000e+00,9.967907783546861467e+00,0.000000000000000000e+00,1.000000009884650209e+00,0.000000000000000000e+00,1.965428289405404727e-10,0.000000000000000000e+00 +2.965261182628729486e+01,1.658199999999999932e+02,0.000000000000000000e+00,9.968911003110685343e+00,0.000000000000000000e+00,1.000000009884847385e+00,0.000000000000000000e+00,-1.199740254628432158e-09,0.000000000000000000e+00 +2.965361494488238137e+01,1.658300000000000125e+02,0.000000000000000000e+00,9.969914121715689248e+00,0.000000000000000000e+00,1.000000009883643903e+00,0.000000000000000000e+00,2.798199771858163560e-10,0.000000000000000000e+00 +2.965461796254912485e+01,1.658400000000000034e+02,0.000000000000000000e+00,9.970917139392346584e+00,0.000000000000000000e+00,1.000000009883924568e+00,0.000000000000000000e+00,-6.706170733221532608e-10,0.000000000000000000e+00 +2.965562087931798274e+01,1.658499999999999943e+02,0.000000000000000000e+00,9.971920056171118318e+00,0.000000000000000000e+00,1.000000009883251995e+00,0.000000000000000000e+00,1.234644081043127037e-09,0.000000000000000000e+00 +2.965662369521940178e+01,1.658600000000000136e+02,0.000000000000000000e+00,9.972922872082447654e+00,0.000000000000000000e+00,1.000000009884490115e+00,0.000000000000000000e+00,-1.079536438051185885e-09,0.000000000000000000e+00 +2.965762641028380742e+01,1.658700000000000045e+02,0.000000000000000000e+00,9.973925587156765360e+00,0.000000000000000000e+00,1.000000009883407648e+00,0.000000000000000000e+00,-5.585363356443854087e-10,0.000000000000000000e+00 +2.965862902454161443e+01,1.658799999999999955e+02,0.000000000000000000e+00,9.974928201424482666e+00,0.000000000000000000e+00,1.000000009882847651e+00,0.000000000000000000e+00,1.021502190944761104e-09,0.000000000000000000e+00 +2.965963153802322338e+01,1.658900000000000148e+02,0.000000000000000000e+00,9.975930714915998365e+00,0.000000000000000000e+00,1.000000009883871721e+00,0.000000000000000000e+00,-1.653130319865649983e-09,0.000000000000000000e+00 +2.966063395075901354e+01,1.659000000000000057e+02,0.000000000000000000e+00,9.976933127661697043e+00,0.000000000000000000e+00,1.000000009882214602e+00,0.000000000000000000e+00,2.013729674797844227e-09,0.000000000000000000e+00 +2.966163626277935350e+01,1.659099999999999966e+02,0.000000000000000000e+00,9.977935439691943742e+00,0.000000000000000000e+00,1.000000009884232988e+00,0.000000000000000000e+00,-2.133571503564933133e-09,0.000000000000000000e+00 +2.966263847411459764e+01,1.659200000000000159e+02,0.000000000000000000e+00,9.978937651037094625e+00,0.000000000000000000e+00,1.000000009882094698e+00,0.000000000000000000e+00,1.810061915271044343e-09,0.000000000000000000e+00 +2.966364058479508259e+01,1.659300000000000068e+02,0.000000000000000000e+00,9.979939761727482761e+00,0.000000000000000000e+00,1.000000009883908580e+00,0.000000000000000000e+00,-2.084583468921384400e-09,0.000000000000000000e+00 +2.966464259485113075e+01,1.659399999999999977e+02,0.000000000000000000e+00,9.980941771793434114e+00,0.000000000000000000e+00,1.000000009881819807e+00,0.000000000000000000e+00,3.237889052119015542e-10,0.000000000000000000e+00 +2.966564450431304678e+01,1.659500000000000171e+02,0.000000000000000000e+00,9.981943681265251556e+00,0.000000000000000000e+00,1.000000009882144214e+00,0.000000000000000000e+00,1.948912826440837490e-09,0.000000000000000000e+00 +2.966664631321112466e+01,1.659600000000000080e+02,0.000000000000000000e+00,9.982945490173229075e+00,0.000000000000000000e+00,1.000000009884096652e+00,0.000000000000000000e+00,-2.531646457876589719e-09,0.000000000000000000e+00 +2.966764802157564063e+01,1.659699999999999989e+02,0.000000000000000000e+00,9.983947198547644675e+00,0.000000000000000000e+00,1.000000009881560681e+00,0.000000000000000000e+00,1.033510207185208999e-09,0.000000000000000000e+00 +2.966864962943685313e+01,1.659799999999999898e+02,0.000000000000000000e+00,9.984948806418755041e+00,0.000000000000000000e+00,1.000000009882595853e+00,0.000000000000000000e+00,2.409992062041773998e-10,0.000000000000000000e+00 +2.966965113682500998e+01,1.659900000000000091e+02,0.000000000000000000e+00,9.985950313816809754e+00,0.000000000000000000e+00,1.000000009882837215e+00,0.000000000000000000e+00,-1.379620481247027823e-09,0.000000000000000000e+00 +2.967065254377034123e+01,1.660000000000000000e+02,0.000000000000000000e+00,9.986951720772038854e+00,0.000000000000000000e+00,1.000000009881455654e+00,0.000000000000000000e+00,-2.955992482742503599e-10,0.000000000000000000e+00 +2.967165385030306268e+01,1.660099999999999909e+02,0.000000000000000000e+00,9.987953027314656396e+00,0.000000000000000000e+00,1.000000009881159668e+00,0.000000000000000000e+00,1.711897499708610618e-09,0.000000000000000000e+00 +2.967265505645337598e+01,1.660200000000000102e+02,0.000000000000000000e+00,9.988954233474863997e+00,0.000000000000000000e+00,1.000000009882873631e+00,0.000000000000000000e+00,-6.842509627851257311e-10,0.000000000000000000e+00 +2.967365616225146852e+01,1.660300000000000011e+02,0.000000000000000000e+00,9.989955339282849067e+00,0.000000000000000000e+00,1.000000009882188623e+00,0.000000000000000000e+00,-4.074862216155182925e-10,0.000000000000000000e+00 +2.967465716772750639e+01,1.660399999999999920e+02,0.000000000000000000e+00,9.990956344768779473e+00,0.000000000000000000e+00,1.000000009881780727e+00,0.000000000000000000e+00,-1.011385863409783162e-09,0.000000000000000000e+00 +2.967565807291164859e+01,1.660500000000000114e+02,0.000000000000000000e+00,9.991957249962810650e+00,0.000000000000000000e+00,1.000000009880768426e+00,0.000000000000000000e+00,1.039220437678030144e-09,0.000000000000000000e+00 +2.967665887783403278e+01,1.660600000000000023e+02,0.000000000000000000e+00,9.992958054895082043e+00,0.000000000000000000e+00,1.000000009881808483e+00,0.000000000000000000e+00,-1.359953037259930038e-09,0.000000000000000000e+00 +2.967765958252478242e+01,1.660699999999999932e+02,0.000000000000000000e+00,9.993958759595720664e+00,0.000000000000000000e+00,1.000000009880447571e+00,0.000000000000000000e+00,6.486442817154778630e-10,0.000000000000000000e+00 +2.967866018701401032e+01,1.660800000000000125e+02,0.000000000000000000e+00,9.994959364094833987e+00,0.000000000000000000e+00,1.000000009881096608e+00,0.000000000000000000e+00,-4.039174781900766351e-11,0.000000000000000000e+00 +2.967966069133180795e+01,1.660900000000000034e+02,0.000000000000000000e+00,9.995959868422518824e+00,0.000000000000000000e+00,1.000000009881056195e+00,0.000000000000000000e+00,1.094237637196360722e-10,0.000000000000000000e+00 +2.968066109550825971e+01,1.660999999999999943e+02,0.000000000000000000e+00,9.996960272608854225e+00,0.000000000000000000e+00,1.000000009881165663e+00,0.000000000000000000e+00,1.089241675915434343e-09,0.000000000000000000e+00 +2.968166139957342509e+01,1.661100000000000136e+02,0.000000000000000000e+00,9.997960576683905032e+00,0.000000000000000000e+00,1.000000009882255236e+00,0.000000000000000000e+00,-2.438440537806308366e-09,0.000000000000000000e+00 +2.968266160355735650e+01,1.661200000000000045e+02,0.000000000000000000e+00,9.998960780677721871e+00,0.000000000000000000e+00,1.000000009879816298e+00,0.000000000000000000e+00,1.685143409820708732e-10,0.000000000000000000e+00 +2.968366170749008859e+01,1.661299999999999955e+02,0.000000000000000000e+00,9.999960884620335833e+00,0.000000000000000000e+00,1.000000009879984830e+00,0.000000000000000000e+00,1.799220395961111410e-09,0.000000000000000000e+00 +2.968466171140164178e+01,1.661400000000000148e+02,0.000000000000000000e+00,1.000096088854176912e+01,0.000000000000000000e+00,1.000000009881784058e+00,0.000000000000000000e+00,-1.111440034388156929e-09,0.000000000000000000e+00 +2.968566161532201875e+01,1.661500000000000057e+02,0.000000000000000000e+00,1.000196079247202796e+01,0.000000000000000000e+00,1.000000009880672724e+00,0.000000000000000000e+00,-1.469113067691429004e-09,0.000000000000000000e+00 +2.968666141928121149e+01,1.661599999999999966e+02,0.000000000000000000e+00,1.000296059644109903e+01,0.000000000000000000e+00,1.000000009879203899e+00,0.000000000000000000e+00,7.180827401208416478e-10,0.000000000000000000e+00 +2.968766112330919427e+01,1.661700000000000159e+02,0.000000000000000000e+00,1.000396030047895657e+01,0.000000000000000000e+00,1.000000009879921770e+00,0.000000000000000000e+00,1.075121499701084966e-10,0.000000000000000000e+00 +2.968866072743592355e+01,1.661800000000000068e+02,0.000000000000000000e+00,1.000495990461556239e+01,0.000000000000000000e+00,1.000000009880029239e+00,0.000000000000000000e+00,2.439259011503633249e-10,0.000000000000000000e+00 +2.968966023169134516e+01,1.661899999999999977e+02,0.000000000000000000e+00,1.000595940888086055e+01,0.000000000000000000e+00,1.000000009880273044e+00,0.000000000000000000e+00,-6.623094294749574514e-10,0.000000000000000000e+00 +2.969065963610539072e+01,1.662000000000000171e+02,0.000000000000000000e+00,1.000695881330478088e+01,0.000000000000000000e+00,1.000000009879611129e+00,0.000000000000000000e+00,9.359027002639962194e-10,0.000000000000000000e+00 +2.969165894070797407e+01,1.662100000000000080e+02,0.000000000000000000e+00,1.000795811791723722e+01,0.000000000000000000e+00,1.000000009880546381e+00,0.000000000000000000e+00,-3.071098513043684325e-10,0.000000000000000000e+00 +2.969265814552899485e+01,1.662199999999999989e+02,0.000000000000000000e+00,1.000895732274813099e+01,0.000000000000000000e+00,1.000000009880239515e+00,0.000000000000000000e+00,-8.460809947697296938e-10,0.000000000000000000e+00 +2.969365725059833849e+01,1.662299999999999898e+02,0.000000000000000000e+00,1.000995642782734585e+01,0.000000000000000000e+00,1.000000009879394192e+00,0.000000000000000000e+00,-6.899126770315806827e-10,0.000000000000000000e+00 +2.969465625594587266e+01,1.662400000000000091e+02,0.000000000000000000e+00,1.001095543318475123e+01,0.000000000000000000e+00,1.000000009878704965e+00,0.000000000000000000e+00,1.511557477976850631e-10,0.000000000000000000e+00 +2.969565516160145435e+01,1.662500000000000000e+02,0.000000000000000000e+00,1.001195433885020236e+01,0.000000000000000000e+00,1.000000009878855955e+00,0.000000000000000000e+00,1.667547644317654215e-09,0.000000000000000000e+00 +2.969665396759492637e+01,1.662599999999999909e+02,0.000000000000000000e+00,1.001295314485354027e+01,0.000000000000000000e+00,1.000000009880521512e+00,0.000000000000000000e+00,-1.494517199767242192e-09,0.000000000000000000e+00 +2.969765267395611019e+01,1.662700000000000102e+02,0.000000000000000000e+00,1.001395185122459175e+01,0.000000000000000000e+00,1.000000009879028928e+00,0.000000000000000000e+00,-4.411511261366205236e-10,0.000000000000000000e+00 +2.969865128071481664e+01,1.662800000000000011e+02,0.000000000000000000e+00,1.001495045799316408e+01,0.000000000000000000e+00,1.000000009878588392e+00,0.000000000000000000e+00,-5.254758391135060982e-10,0.000000000000000000e+00 +2.969964978790084231e+01,1.662899999999999920e+02,0.000000000000000000e+00,1.001594896518905387e+01,0.000000000000000000e+00,1.000000009878063700e+00,0.000000000000000000e+00,1.806100192653932085e-09,0.000000000000000000e+00 +2.970064819554396607e+01,1.663000000000000114e+02,0.000000000000000000e+00,1.001694737284204173e+01,0.000000000000000000e+00,1.000000009879866925e+00,0.000000000000000000e+00,-2.368337873060390356e-09,0.000000000000000000e+00 +2.970164650367395609e+01,1.663100000000000023e+02,0.000000000000000000e+00,1.001794568098189586e+01,0.000000000000000000e+00,1.000000009877502594e+00,0.000000000000000000e+00,1.199857968608249682e-09,0.000000000000000000e+00 +2.970264471232056280e+01,1.663199999999999932e+02,0.000000000000000000e+00,1.001894388963836313e+01,0.000000000000000000e+00,1.000000009878700302e+00,0.000000000000000000e+00,2.291392010873030917e-11,0.000000000000000000e+00 +2.970364282151352242e+01,1.663300000000000125e+02,0.000000000000000000e+00,1.001994199884118331e+01,0.000000000000000000e+00,1.000000009878723173e+00,0.000000000000000000e+00,-5.624481630011171717e-10,0.000000000000000000e+00 +2.970464083128255695e+01,1.663400000000000034e+02,0.000000000000000000e+00,1.002094000862007661e+01,0.000000000000000000e+00,1.000000009878161844e+00,0.000000000000000000e+00,-5.658418276581945757e-10,0.000000000000000000e+00 +2.970563874165737062e+01,1.663499999999999943e+02,0.000000000000000000e+00,1.002193791900474906e+01,0.000000000000000000e+00,1.000000009877597185e+00,0.000000000000000000e+00,2.892912419551179779e-12,0.000000000000000000e+00 +2.970663655266765701e+01,1.663600000000000136e+02,0.000000000000000000e+00,1.002293573002489246e+01,0.000000000000000000e+00,1.000000009877600071e+00,0.000000000000000000e+00,1.133689466942184960e-09,0.000000000000000000e+00 +2.970763426434309551e+01,1.663700000000000045e+02,0.000000000000000000e+00,1.002393344171018441e+01,0.000000000000000000e+00,1.000000009878731166e+00,0.000000000000000000e+00,-7.531972993468030899e-10,0.000000000000000000e+00 +2.970863187671334416e+01,1.663799999999999955e+02,0.000000000000000000e+00,1.002493105409028828e+01,0.000000000000000000e+00,1.000000009877979767e+00,0.000000000000000000e+00,-3.149764325258210241e-10,0.000000000000000000e+00 +2.970962938980805390e+01,1.663900000000000148e+02,0.000000000000000000e+00,1.002592856719484971e+01,0.000000000000000000e+00,1.000000009877665574e+00,0.000000000000000000e+00,-1.130911300636357673e-09,0.000000000000000000e+00 +2.971062680365685438e+01,1.664000000000000057e+02,0.000000000000000000e+00,1.002692598105350186e+01,0.000000000000000000e+00,1.000000009876537588e+00,0.000000000000000000e+00,2.145828239661221811e-09,0.000000000000000000e+00 +2.971162411828936456e+01,1.664099999999999966e+02,0.000000000000000000e+00,1.002792329569586194e+01,0.000000000000000000e+00,1.000000009878677654e+00,0.000000000000000000e+00,-2.997065874589616880e-09,0.000000000000000000e+00 +2.971262133373518921e+01,1.664200000000000159e+02,0.000000000000000000e+00,1.002892051115153649e+01,0.000000000000000000e+00,1.000000009875688933e+00,0.000000000000000000e+00,3.078199211651259687e-09,0.000000000000000000e+00 +2.971361845002391533e+01,1.664300000000000068e+02,0.000000000000000000e+00,1.002991762745010895e+01,0.000000000000000000e+00,1.000000009878758256e+00,0.000000000000000000e+00,-2.862700325306637248e-09,0.000000000000000000e+00 +2.971461546718511570e+01,1.664399999999999977e+02,0.000000000000000000e+00,1.003091464462115923e+01,0.000000000000000000e+00,1.000000009875904095e+00,0.000000000000000000e+00,6.105058023765729273e-10,0.000000000000000000e+00 +2.971561238524835247e+01,1.664500000000000171e+02,0.000000000000000000e+00,1.003191156269424056e+01,0.000000000000000000e+00,1.000000009876512719e+00,0.000000000000000000e+00,9.796685030478540110e-10,0.000000000000000000e+00 +2.971660920424316643e+01,1.664600000000000080e+02,0.000000000000000000e+00,1.003290838169890087e+01,0.000000000000000000e+00,1.000000009877489271e+00,0.000000000000000000e+00,2.094087987191565580e-11,0.000000000000000000e+00 +2.971760592419909131e+01,1.664699999999999989e+02,0.000000000000000000e+00,1.003390510166467031e+01,0.000000000000000000e+00,1.000000009877510143e+00,0.000000000000000000e+00,-2.277658325374030864e-09,0.000000000000000000e+00 +2.971860254514563948e+01,1.664799999999999898e+02,0.000000000000000000e+00,1.003490172262106306e+01,0.000000000000000000e+00,1.000000009875240181e+00,0.000000000000000000e+00,1.228627157757345742e-09,0.000000000000000000e+00 +2.971959906711231270e+01,1.664900000000000091e+02,0.000000000000000000e+00,1.003589824459757729e+01,0.000000000000000000e+00,1.000000009876464535e+00,0.000000000000000000e+00,-2.016717440014483272e-10,0.000000000000000000e+00 +2.972059549012859492e+01,1.665000000000000000e+02,0.000000000000000000e+00,1.003689466762370230e+01,0.000000000000000000e+00,1.000000009876263585e+00,0.000000000000000000e+00,5.758801396002965920e-10,0.000000000000000000e+00 +2.972159181422395946e+01,1.665099999999999909e+02,0.000000000000000000e+00,1.003789099172890786e+01,0.000000000000000000e+00,1.000000009876837348e+00,0.000000000000000000e+00,-1.817412068540081176e-09,0.000000000000000000e+00 +2.972258803942786187e+01,1.665200000000000102e+02,0.000000000000000000e+00,1.003888721694265129e+01,0.000000000000000000e+00,1.000000009875026796e+00,0.000000000000000000e+00,1.557904533360514590e-09,0.000000000000000000e+00 +2.972358416576974705e+01,1.665300000000000011e+02,0.000000000000000000e+00,1.003988334329437215e+01,0.000000000000000000e+00,1.000000009876578666e+00,0.000000000000000000e+00,-4.815292169783234709e-11,0.000000000000000000e+00 +2.972458019327903855e+01,1.665399999999999920e+02,0.000000000000000000e+00,1.004087937081350113e+01,0.000000000000000000e+00,1.000000009876530704e+00,0.000000000000000000e+00,-1.277516732284519680e-09,0.000000000000000000e+00 +2.972557612198514931e+01,1.665500000000000114e+02,0.000000000000000000e+00,1.004187529952944935e+01,0.000000000000000000e+00,1.000000009875258389e+00,0.000000000000000000e+00,-3.469482027466735120e-10,0.000000000000000000e+00 +2.972657195191747803e+01,1.665600000000000023e+02,0.000000000000000000e+00,1.004287112947161376e+01,0.000000000000000000e+00,1.000000009874912887e+00,0.000000000000000000e+00,9.419373647931571845e-10,0.000000000000000000e+00 +2.972756768310540920e+01,1.665699999999999932e+02,0.000000000000000000e+00,1.004386686066937884e+01,0.000000000000000000e+00,1.000000009875850804e+00,0.000000000000000000e+00,-1.004698995273124517e-09,0.000000000000000000e+00 +2.972856331557831311e+01,1.665800000000000125e+02,0.000000000000000000e+00,1.004486249315211488e+01,0.000000000000000000e+00,1.000000009874850493e+00,0.000000000000000000e+00,9.706733543656921329e-10,0.000000000000000000e+00 +2.972955884936554227e+01,1.665900000000000034e+02,0.000000000000000000e+00,1.004585802694917440e+01,0.000000000000000000e+00,1.000000009875816831e+00,0.000000000000000000e+00,-3.111726864534003211e-10,0.000000000000000000e+00 +2.973055428449643500e+01,1.665999999999999943e+02,0.000000000000000000e+00,1.004685346208989927e+01,0.000000000000000000e+00,1.000000009875507079e+00,0.000000000000000000e+00,-1.275376720738917818e-09,0.000000000000000000e+00 +2.973154962100031895e+01,1.666100000000000136e+02,0.000000000000000000e+00,1.004784879860361357e+01,0.000000000000000000e+00,1.000000009874237650e+00,0.000000000000000000e+00,1.654115755319533959e-09,0.000000000000000000e+00 +2.973254485890650400e+01,1.666200000000000045e+02,0.000000000000000000e+00,1.004884403651962721e+01,0.000000000000000000e+00,1.000000009875883888e+00,0.000000000000000000e+00,-2.292875252313823712e-09,0.000000000000000000e+00 +2.973353999824428939e+01,1.666299999999999955e+02,0.000000000000000000e+00,1.004983917586723940e+01,0.000000000000000000e+00,1.000000009873602158e+00,0.000000000000000000e+00,1.222422585498444603e-09,0.000000000000000000e+00 +2.973453503904295303e+01,1.666400000000000148e+02,0.000000000000000000e+00,1.005083421667572807e+01,0.000000000000000000e+00,1.000000009874818518e+00,0.000000000000000000e+00,-3.664506428031965180e-10,0.000000000000000000e+00 +2.973552998133176573e+01,1.666500000000000057e+02,0.000000000000000000e+00,1.005182915897436402e+01,0.000000000000000000e+00,1.000000009874453921e+00,0.000000000000000000e+00,1.051250538592213473e-10,0.000000000000000000e+00 +2.973652482513997697e+01,1.666599999999999966e+02,0.000000000000000000e+00,1.005282400279239852e+01,0.000000000000000000e+00,1.000000009874558504e+00,0.000000000000000000e+00,-9.602818287216074605e-10,0.000000000000000000e+00 +2.973751957049682559e+01,1.666700000000000159e+02,0.000000000000000000e+00,1.005381874815907040e+01,0.000000000000000000e+00,1.000000009873603268e+00,0.000000000000000000e+00,1.585001310465226087e-11,0.000000000000000000e+00 +2.973851421743153622e+01,1.666800000000000068e+02,0.000000000000000000e+00,1.005481339510360250e+01,0.000000000000000000e+00,1.000000009873619033e+00,0.000000000000000000e+00,1.229948742712000197e-09,0.000000000000000000e+00 +2.973950876597331927e+01,1.666899999999999977e+02,0.000000000000000000e+00,1.005580794365520525e+01,0.000000000000000000e+00,1.000000009874842277e+00,0.000000000000000000e+00,-9.214922021764112131e-10,0.000000000000000000e+00 +2.974050321615136738e+01,1.667000000000000171e+02,0.000000000000000000e+00,1.005680239384307484e+01,0.000000000000000000e+00,1.000000009873925899e+00,0.000000000000000000e+00,-1.060256277573377568e-09,0.000000000000000000e+00 +2.974149756799486255e+01,1.667100000000000080e+02,0.000000000000000000e+00,1.005779674569638971e+01,0.000000000000000000e+00,1.000000009872871631e+00,0.000000000000000000e+00,8.042039496836728905e-10,0.000000000000000000e+00 +2.974249182153297255e+01,1.667199999999999989e+02,0.000000000000000000e+00,1.005879099924431586e+01,0.000000000000000000e+00,1.000000009873671214e+00,0.000000000000000000e+00,1.070069981010213473e-09,0.000000000000000000e+00 +2.974348597679484740e+01,1.667299999999999898e+02,0.000000000000000000e+00,1.005978515451600686e+01,0.000000000000000000e+00,1.000000009874735030e+00,0.000000000000000000e+00,-2.073563223112186710e-09,0.000000000000000000e+00 +2.974448003380962646e+01,1.667400000000000091e+02,0.000000000000000000e+00,1.006077921154060029e+01,0.000000000000000000e+00,1.000000009872673790e+00,0.000000000000000000e+00,3.525160074027381781e-10,0.000000000000000000e+00 +2.974547399260642777e+01,1.667500000000000000e+02,0.000000000000000000e+00,1.006177317034721597e+01,0.000000000000000000e+00,1.000000009873024176e+00,0.000000000000000000e+00,-6.505881049901039833e-10,0.000000000000000000e+00 +2.974646785321436582e+01,1.667599999999999909e+02,0.000000000000000000e+00,1.006276703096496483e+01,0.000000000000000000e+00,1.000000009872377582e+00,0.000000000000000000e+00,3.011948459028695461e-10,0.000000000000000000e+00 +2.974746161566253022e+01,1.667700000000000102e+02,0.000000000000000000e+00,1.006376079342294005e+01,0.000000000000000000e+00,1.000000009872676898e+00,0.000000000000000000e+00,1.400202734460357157e-09,0.000000000000000000e+00 +2.974845527998000350e+01,1.667800000000000011e+02,0.000000000000000000e+00,1.006475445775022237e+01,0.000000000000000000e+00,1.000000009874068230e+00,0.000000000000000000e+00,-9.629858456971110106e-10,0.000000000000000000e+00 +2.974944884619585039e+01,1.667899999999999920e+02,0.000000000000000000e+00,1.006574802397587831e+01,0.000000000000000000e+00,1.000000009873111440e+00,0.000000000000000000e+00,-1.400479224105862702e-09,0.000000000000000000e+00 +2.975044231433912145e+01,1.668000000000000114e+02,0.000000000000000000e+00,1.006674149212895664e+01,0.000000000000000000e+00,1.000000009871720108e+00,0.000000000000000000e+00,7.845782387632701543e-11,0.000000000000000000e+00 +2.975143568443885300e+01,1.668100000000000023e+02,0.000000000000000000e+00,1.006773486223849368e+01,0.000000000000000000e+00,1.000000009871798046e+00,0.000000000000000000e+00,1.664319483326916761e-09,0.000000000000000000e+00 +2.975242895652406716e+01,1.668199999999999932e+02,0.000000000000000000e+00,1.006872813433351332e+01,0.000000000000000000e+00,1.000000009873451168e+00,0.000000000000000000e+00,-2.055285225098302114e-09,0.000000000000000000e+00 +2.975342213062377184e+01,1.668300000000000125e+02,0.000000000000000000e+00,1.006972130844302526e+01,0.000000000000000000e+00,1.000000009871409912e+00,0.000000000000000000e+00,1.515511516916908247e-09,0.000000000000000000e+00 +2.975441520676696427e+01,1.668400000000000034e+02,0.000000000000000000e+00,1.007071438459601964e+01,0.000000000000000000e+00,1.000000009872914930e+00,0.000000000000000000e+00,-2.042497397634069812e-09,0.000000000000000000e+00 +2.975540818498262041e+01,1.668499999999999943e+02,0.000000000000000000e+00,1.007170736282147949e+01,0.000000000000000000e+00,1.000000009870886775e+00,0.000000000000000000e+00,1.672356201502612286e-09,0.000000000000000000e+00 +2.975640106529970552e+01,1.668600000000000136e+02,0.000000000000000000e+00,1.007270024314836654e+01,0.000000000000000000e+00,1.000000009872547224e+00,0.000000000000000000e+00,-1.763773885109909802e-09,0.000000000000000000e+00 +2.975739384774717422e+01,1.668700000000000045e+02,0.000000000000000000e+00,1.007369302560563540e+01,0.000000000000000000e+00,1.000000009870796180e+00,0.000000000000000000e+00,2.534304810011530742e-10,0.000000000000000000e+00 +2.975838653235395981e+01,1.668799999999999955e+02,0.000000000000000000e+00,1.007468571022221937e+01,0.000000000000000000e+00,1.000000009871047757e+00,0.000000000000000000e+00,5.051212855474001554e-10,0.000000000000000000e+00 +2.975937911914898493e+01,1.668900000000000148e+02,0.000000000000000000e+00,1.007567829702704287e+01,0.000000000000000000e+00,1.000000009871549134e+00,0.000000000000000000e+00,7.832612273859602077e-10,0.000000000000000000e+00 +2.976037160816115801e+01,1.669000000000000057e+02,0.000000000000000000e+00,1.007667078604901434e+01,0.000000000000000000e+00,1.000000009872326512e+00,0.000000000000000000e+00,-2.529012774637173967e-09,0.000000000000000000e+00 +2.976136399941937327e+01,1.669099999999999966e+02,0.000000000000000000e+00,1.007766317731702799e+01,0.000000000000000000e+00,1.000000009869816742e+00,0.000000000000000000e+00,1.380431416750232859e-09,0.000000000000000000e+00 +2.976235629295251073e+01,1.669200000000000159e+02,0.000000000000000000e+00,1.007865547085996027e+01,0.000000000000000000e+00,1.000000009871186535e+00,0.000000000000000000e+00,-1.248754378289053701e-10,0.000000000000000000e+00 +2.976334848878943617e+01,1.669300000000000068e+02,0.000000000000000000e+00,1.007964766670668055e+01,0.000000000000000000e+00,1.000000009871062634e+00,0.000000000000000000e+00,1.602502070899177499e-10,0.000000000000000000e+00 +2.976434058695900120e+01,1.669399999999999977e+02,0.000000000000000000e+00,1.008063976488603863e+01,0.000000000000000000e+00,1.000000009871221618e+00,0.000000000000000000e+00,-1.382182158686157790e-09,0.000000000000000000e+00 +2.976533258749004318e+01,1.669500000000000171e+02,0.000000000000000000e+00,1.008163176542687189e+01,0.000000000000000000e+00,1.000000009869850492e+00,0.000000000000000000e+00,6.525437211961490014e-10,0.000000000000000000e+00 +2.976632449041138173e+01,1.669600000000000080e+02,0.000000000000000000e+00,1.008262366835800172e+01,0.000000000000000000e+00,1.000000009870497752e+00,0.000000000000000000e+00,8.395470708931209051e-10,0.000000000000000000e+00 +2.976731629575182936e+01,1.669699999999999989e+02,0.000000000000000000e+00,1.008361547370823885e+01,0.000000000000000000e+00,1.000000009871330420e+00,0.000000000000000000e+00,-2.639123932470766377e-09,0.000000000000000000e+00 +2.976830800354018081e+01,1.669799999999999898e+02,0.000000000000000000e+00,1.008460718150637803e+01,0.000000000000000000e+00,1.000000009868713180e+00,0.000000000000000000e+00,1.044378092774816901e-09,0.000000000000000000e+00 +2.976929961380521306e+01,1.669900000000000091e+02,0.000000000000000000e+00,1.008559879178119623e+01,0.000000000000000000e+00,1.000000009869748796e+00,0.000000000000000000e+00,1.042913168565751874e-09,0.000000000000000000e+00 +2.977029112657569243e+01,1.670000000000000000e+02,0.000000000000000000e+00,1.008659030456146333e+01,0.000000000000000000e+00,1.000000009870782858e+00,0.000000000000000000e+00,-8.479401823595566293e-10,0.000000000000000000e+00 +2.977128254188037459e+01,1.670099999999999909e+02,0.000000000000000000e+00,1.008758171987593144e+01,0.000000000000000000e+00,1.000000009869942197e+00,0.000000000000000000e+00,-1.025647049408815216e-09,0.000000000000000000e+00 +2.977227385974799390e+01,1.670200000000000102e+02,0.000000000000000000e+00,1.008857303775333669e+01,0.000000000000000000e+00,1.000000009868925455e+00,0.000000000000000000e+00,5.033534392813564899e-10,0.000000000000000000e+00 +2.977326508020727758e+01,1.670300000000000011e+02,0.000000000000000000e+00,1.008956425822240277e+01,0.000000000000000000e+00,1.000000009869424389e+00,0.000000000000000000e+00,1.113445654862607003e-10,0.000000000000000000e+00 +2.977425620328693512e+01,1.670399999999999920e+02,0.000000000000000000e+00,1.009055538131184093e+01,0.000000000000000000e+00,1.000000009869534745e+00,0.000000000000000000e+00,-4.026274429462213054e-10,0.000000000000000000e+00 +2.977524722901565823e+01,1.670500000000000114e+02,0.000000000000000000e+00,1.009154640705034645e+01,0.000000000000000000e+00,1.000000009869135731e+00,0.000000000000000000e+00,7.605185038512567864e-10,0.000000000000000000e+00 +2.977623815742213154e+01,1.670600000000000023e+02,0.000000000000000000e+00,1.009253733546660037e+01,0.000000000000000000e+00,1.000000009869889350e+00,0.000000000000000000e+00,-1.837390542236209298e-09,0.000000000000000000e+00 +2.977722898853502187e+01,1.670699999999999932e+02,0.000000000000000000e+00,1.009352816658927132e+01,0.000000000000000000e+00,1.000000009868068807e+00,0.000000000000000000e+00,8.413515381583663559e-10,0.000000000000000000e+00 +2.977821972238298542e+01,1.670800000000000125e+02,0.000000000000000000e+00,1.009451890044701017e+01,0.000000000000000000e+00,1.000000009868902362e+00,0.000000000000000000e+00,-2.606787115326774931e-10,0.000000000000000000e+00 +2.977921035899465707e+01,1.670900000000000034e+02,0.000000000000000000e+00,1.009550953706845888e+01,0.000000000000000000e+00,1.000000009868644124e+00,0.000000000000000000e+00,2.754992061383884529e-10,0.000000000000000000e+00 +2.978020089839866458e+01,1.670999999999999943e+02,0.000000000000000000e+00,1.009650007648224168e+01,0.000000000000000000e+00,1.000000009868917017e+00,0.000000000000000000e+00,-1.180346329625137206e-09,0.000000000000000000e+00 +2.978119134062361795e+01,1.671100000000000136e+02,0.000000000000000000e+00,1.009749051871697034e+01,0.000000000000000000e+00,1.000000009867747952e+00,0.000000000000000000e+00,7.943736536967054608e-10,0.000000000000000000e+00 +2.978218168569811652e+01,1.671200000000000045e+02,0.000000000000000000e+00,1.009848086380124066e+01,0.000000000000000000e+00,1.000000009868534656e+00,0.000000000000000000e+00,-1.054559895018619395e-09,0.000000000000000000e+00 +2.978317193365074189e+01,1.671299999999999955e+02,0.000000000000000000e+00,1.009947111176363777e+01,0.000000000000000000e+00,1.000000009867490380e+00,0.000000000000000000e+00,5.086065009480818327e-10,0.000000000000000000e+00 +2.978416208451006142e+01,1.671400000000000148e+02,0.000000000000000000e+00,1.010046126263272903e+01,0.000000000000000000e+00,1.000000009867993978e+00,0.000000000000000000e+00,3.924817628588267405e-11,0.000000000000000000e+00 +2.978515213830463537e+01,1.671500000000000057e+02,0.000000000000000000e+00,1.010145131643707117e+01,0.000000000000000000e+00,1.000000009868032835e+00,0.000000000000000000e+00,-6.610040743546552432e-10,0.000000000000000000e+00 +2.978614209506299915e+01,1.671599999999999966e+02,0.000000000000000000e+00,1.010244127320520491e+01,0.000000000000000000e+00,1.000000009867378470e+00,0.000000000000000000e+00,2.110844218991236082e-10,0.000000000000000000e+00 +2.978713195481368459e+01,1.671700000000000159e+02,0.000000000000000000e+00,1.010343113296565676e+01,0.000000000000000000e+00,1.000000009867587414e+00,0.000000000000000000e+00,8.329790145800481665e-10,0.000000000000000000e+00 +2.978812171758520222e+01,1.671800000000000068e+02,0.000000000000000000e+00,1.010442089574694080e+01,0.000000000000000000e+00,1.000000009868411865e+00,0.000000000000000000e+00,-6.190181090241122235e-10,0.000000000000000000e+00 +2.978911138340605191e+01,1.671899999999999977e+02,0.000000000000000000e+00,1.010541056157755690e+01,0.000000000000000000e+00,1.000000009867799244e+00,0.000000000000000000e+00,-2.341459453215884381e-09,0.000000000000000000e+00 +2.979010095230471933e+01,1.672000000000000171e+02,0.000000000000000000e+00,1.010640013048598895e+01,0.000000000000000000e+00,1.000000009865482209e+00,0.000000000000000000e+00,2.913029375358503001e-09,0.000000000000000000e+00 +2.979109042430967591e+01,1.672100000000000080e+02,0.000000000000000000e+00,1.010738960250070662e+01,0.000000000000000000e+00,1.000000009868364570e+00,0.000000000000000000e+00,-1.193289700751526704e-09,0.000000000000000000e+00 +2.979207979944937890e+01,1.672199999999999989e+02,0.000000000000000000e+00,1.010837897765017246e+01,0.000000000000000000e+00,1.000000009867183959e+00,0.000000000000000000e+00,-1.971354025813753261e-09,0.000000000000000000e+00 +2.979306907775227131e+01,1.672299999999999898e+02,0.000000000000000000e+00,1.010936825596282596e+01,0.000000000000000000e+00,1.000000009865233741e+00,0.000000000000000000e+00,2.388168970916837683e-09,0.000000000000000000e+00 +2.979405825924678197e+01,1.672400000000000091e+02,0.000000000000000000e+00,1.011035743746709592e+01,0.000000000000000000e+00,1.000000009867596074e+00,0.000000000000000000e+00,-8.331010648108348946e-10,0.000000000000000000e+00 +2.979504734396132903e+01,1.672500000000000000e+02,0.000000000000000000e+00,1.011134652219140229e+01,0.000000000000000000e+00,1.000000009866772066e+00,0.000000000000000000e+00,-7.525809651550825696e-10,0.000000000000000000e+00 +2.979603633192431289e+01,1.672599999999999909e+02,0.000000000000000000e+00,1.011233551016414367e+01,0.000000000000000000e+00,1.000000009866027773e+00,0.000000000000000000e+00,-1.010200755496370653e-09,0.000000000000000000e+00 +2.979702522316411972e+01,1.672700000000000102e+02,0.000000000000000000e+00,1.011332440141370803e+01,0.000000000000000000e+00,1.000000009865028794e+00,0.000000000000000000e+00,2.017230673565502844e-09,0.000000000000000000e+00 +2.979801401770912506e+01,1.672800000000000011e+02,0.000000000000000000e+00,1.011431319596846912e+01,0.000000000000000000e+00,1.000000009867023421e+00,0.000000000000000000e+00,-2.581130899265495913e-09,0.000000000000000000e+00 +2.979900271558769020e+01,1.672899999999999920e+02,0.000000000000000000e+00,1.011530189385679002e+01,0.000000000000000000e+00,1.000000009864471462e+00,0.000000000000000000e+00,1.538543025712413517e-09,0.000000000000000000e+00 +2.979999131682816227e+01,1.673000000000000114e+02,0.000000000000000000e+00,1.011629049510701250e+01,0.000000000000000000e+00,1.000000009865992467e+00,0.000000000000000000e+00,-1.718394810614057808e-10,0.000000000000000000e+00 +2.980097982145887059e+01,1.673100000000000023e+02,0.000000000000000000e+00,1.011727899974747302e+01,0.000000000000000000e+00,1.000000009865822603e+00,0.000000000000000000e+00,-4.517685796233054278e-10,0.000000000000000000e+00 +2.980196822950813385e+01,1.673199999999999932e+02,0.000000000000000000e+00,1.011826740780648848e+01,0.000000000000000000e+00,1.000000009865376072e+00,0.000000000000000000e+00,6.895142828823999418e-10,0.000000000000000000e+00 +2.980295654100426006e+01,1.673300000000000125e+02,0.000000000000000000e+00,1.011925571931236334e+01,0.000000000000000000e+00,1.000000009866057527e+00,0.000000000000000000e+00,-2.214121016710458416e-09,0.000000000000000000e+00 +2.980394475597553594e+01,1.673400000000000034e+02,0.000000000000000000e+00,1.012024393429338964e+01,0.000000000000000000e+00,1.000000009863869499e+00,0.000000000000000000e+00,1.741987242867945207e-09,0.000000000000000000e+00 +2.980493287445024109e+01,1.673499999999999943e+02,0.000000000000000000e+00,1.012123205277784166e+01,0.000000000000000000e+00,1.000000009865590789e+00,0.000000000000000000e+00,-1.858570832268763273e-10,0.000000000000000000e+00 +2.980592089645663734e+01,1.673600000000000136e+02,0.000000000000000000e+00,1.012222007479398656e+01,0.000000000000000000e+00,1.000000009865407158e+00,0.000000000000000000e+00,-7.306896746140989304e-10,0.000000000000000000e+00 +2.980690882202297587e+01,1.673700000000000045e+02,0.000000000000000000e+00,1.012320800037007196e+01,0.000000000000000000e+00,1.000000009864685291e+00,0.000000000000000000e+00,9.867858335260630402e-11,0.000000000000000000e+00 +2.980789665117749365e+01,1.673799999999999955e+02,0.000000000000000000e+00,1.012419582953433306e+01,0.000000000000000000e+00,1.000000009864782768e+00,0.000000000000000000e+00,-1.348589035585245106e-09,0.000000000000000000e+00 +2.980888438394840989e+01,1.673900000000000148e+02,0.000000000000000000e+00,1.012518356231499261e+01,0.000000000000000000e+00,1.000000009863450723e+00,0.000000000000000000e+00,3.810770840689572793e-10,0.000000000000000000e+00 +2.980987202036393313e+01,1.674000000000000057e+02,0.000000000000000000e+00,1.012617119874025740e+01,0.000000000000000000e+00,1.000000009863827088e+00,0.000000000000000000e+00,1.636205566884659755e-09,0.000000000000000000e+00 +2.981085956045225771e+01,1.674099999999999966e+02,0.000000000000000000e+00,1.012715873883832352e+01,0.000000000000000000e+00,1.000000009865442907e+00,0.000000000000000000e+00,-3.058655843394905923e-09,0.000000000000000000e+00 +2.981184700424156375e+01,1.674200000000000159e+02,0.000000000000000000e+00,1.012814618263737287e+01,0.000000000000000000e+00,1.000000009862422656e+00,0.000000000000000000e+00,2.682713069750013983e-09,0.000000000000000000e+00 +2.981283435176002072e+01,1.674300000000000068e+02,0.000000000000000000e+00,1.012913353016556783e+01,0.000000000000000000e+00,1.000000009865071426e+00,0.000000000000000000e+00,-1.189784190604467043e-09,0.000000000000000000e+00 +2.981382160303578033e+01,1.674399999999999977e+02,0.000000000000000000e+00,1.013012078145106720e+01,0.000000000000000000e+00,1.000000009863896810e+00,0.000000000000000000e+00,-1.932631782480321998e-09,0.000000000000000000e+00 +2.981480875809698361e+01,1.674500000000000171e+02,0.000000000000000000e+00,1.013110793652200670e+01,0.000000000000000000e+00,1.000000009861989003e+00,0.000000000000000000e+00,2.270478747308604318e-09,0.000000000000000000e+00 +2.981579581697175385e+01,1.674600000000000080e+02,0.000000000000000000e+00,1.013209499540651137e+01,0.000000000000000000e+00,1.000000009864230099e+00,0.000000000000000000e+00,-1.352340972924105059e-09,0.000000000000000000e+00 +2.981678277968820368e+01,1.674699999999999989e+02,0.000000000000000000e+00,1.013308195813269741e+01,0.000000000000000000e+00,1.000000009862895389e+00,0.000000000000000000e+00,-4.837491787143056017e-11,0.000000000000000000e+00 +2.981776964627443149e+01,1.674799999999999898e+02,0.000000000000000000e+00,1.013406882472865966e+01,0.000000000000000000e+00,1.000000009862847650e+00,0.000000000000000000e+00,7.043173915510948178e-10,0.000000000000000000e+00 +2.981875641675852506e+01,1.674900000000000091e+02,0.000000000000000000e+00,1.013505559522248411e+01,0.000000000000000000e+00,1.000000009863542649e+00,0.000000000000000000e+00,-9.305546308234762957e-10,0.000000000000000000e+00 +2.981974309116855082e+01,1.675000000000000000e+02,0.000000000000000000e+00,1.013604226964224253e+01,0.000000000000000000e+00,1.000000009862624495e+00,0.000000000000000000e+00,5.120236715380445013e-10,0.000000000000000000e+00 +2.982072966953256810e+01,1.675099999999999909e+02,0.000000000000000000e+00,1.013702884801599069e+01,0.000000000000000000e+00,1.000000009863129646e+00,0.000000000000000000e+00,-4.515250366736739799e-10,0.000000000000000000e+00 +2.982171615187862201e+01,1.675200000000000102e+02,0.000000000000000000e+00,1.013801533037177371e+01,0.000000000000000000e+00,1.000000009862684225e+00,0.000000000000000000e+00,-2.007748605849754071e-09,0.000000000000000000e+00 +2.982270253823473993e+01,1.675300000000000011e+02,0.000000000000000000e+00,1.013900171673762074e+01,0.000000000000000000e+00,1.000000009860703809e+00,0.000000000000000000e+00,1.313189490786526851e-09,0.000000000000000000e+00 +2.982368882862894210e+01,1.675399999999999920e+02,0.000000000000000000e+00,1.013998800714154669e+01,0.000000000000000000e+00,1.000000009861998995e+00,0.000000000000000000e+00,3.719526950395976050e-10,0.000000000000000000e+00 +2.982467502308922747e+01,1.675500000000000114e+02,0.000000000000000000e+00,1.014097420161155760e+01,0.000000000000000000e+00,1.000000009862365813e+00,0.000000000000000000e+00,6.365693320899062681e-10,0.000000000000000000e+00 +2.982566112164358785e+01,1.675600000000000023e+02,0.000000000000000000e+00,1.014196030017564176e+01,0.000000000000000000e+00,1.000000009862993533e+00,0.000000000000000000e+00,-1.555884392743534051e-09,0.000000000000000000e+00 +2.982664712431999732e+01,1.675699999999999932e+02,0.000000000000000000e+00,1.014294630286177501e+01,0.000000000000000000e+00,1.000000009861459427e+00,0.000000000000000000e+00,-7.339875818474289433e-10,0.000000000000000000e+00 +2.982763303114641573e+01,1.675800000000000125e+02,0.000000000000000000e+00,1.014393220969791720e+01,0.000000000000000000e+00,1.000000009860735783e+00,0.000000000000000000e+00,1.266527567603401443e-09,0.000000000000000000e+00 +2.982861884215079584e+01,1.675900000000000034e+02,0.000000000000000000e+00,1.014491802071201754e+01,0.000000000000000000e+00,1.000000009861984340e+00,0.000000000000000000e+00,-1.046794518672039421e-09,0.000000000000000000e+00 +2.982960455736106908e+01,1.675999999999999943e+02,0.000000000000000000e+00,1.014590373593201278e+01,0.000000000000000000e+00,1.000000009860952499e+00,0.000000000000000000e+00,-3.730708317096411997e-10,0.000000000000000000e+00 +2.983059017680515979e+01,1.676100000000000136e+02,0.000000000000000000e+00,1.014688935538582193e+01,0.000000000000000000e+00,1.000000009860584793e+00,0.000000000000000000e+00,1.452098483577782209e-09,0.000000000000000000e+00 +2.983157570051097451e+01,1.676200000000000045e+02,0.000000000000000000e+00,1.014787487910135333e+01,0.000000000000000000e+00,1.000000009862015871e+00,0.000000000000000000e+00,-1.068956443949372036e-09,0.000000000000000000e+00 +2.983256112850640562e+01,1.676299999999999955e+02,0.000000000000000000e+00,1.014886030710650289e+01,0.000000000000000000e+00,1.000000009860962491e+00,0.000000000000000000e+00,-6.287264099752919005e-10,0.000000000000000000e+00 +2.983354646081933481e+01,1.676400000000000148e+02,0.000000000000000000e+00,1.014984563942914875e+01,0.000000000000000000e+00,1.000000009860342987e+00,0.000000000000000000e+00,-8.956277180136902799e-10,0.000000000000000000e+00 +2.983453169747762956e+01,1.676500000000000057e+02,0.000000000000000000e+00,1.015083087609715840e+01,0.000000000000000000e+00,1.000000009859460581e+00,0.000000000000000000e+00,1.781737381535376261e-09,0.000000000000000000e+00 +2.983551683850914316e+01,1.676599999999999966e+02,0.000000000000000000e+00,1.015181601713838511e+01,0.000000000000000000e+00,1.000000009861215844e+00,0.000000000000000000e+00,-1.758467077499415894e-09,0.000000000000000000e+00 +2.983650188394171465e+01,1.676700000000000159e+02,0.000000000000000000e+00,1.015280106258067150e+01,0.000000000000000000e+00,1.000000009859483674e+00,0.000000000000000000e+00,1.288600578990520129e-09,0.000000000000000000e+00 +2.983748683380317246e+01,1.676800000000000068e+02,0.000000000000000000e+00,1.015378601245184065e+01,0.000000000000000000e+00,1.000000009860752881e+00,0.000000000000000000e+00,-1.903327751342907860e-09,0.000000000000000000e+00 +2.983847168812132722e+01,1.676899999999999977e+02,0.000000000000000000e+00,1.015477086677970853e+01,0.000000000000000000e+00,1.000000009858878380e+00,0.000000000000000000e+00,1.476450953400954429e-09,0.000000000000000000e+00 +2.983945644692398247e+01,1.677000000000000171e+02,0.000000000000000000e+00,1.015575562559207157e+01,0.000000000000000000e+00,1.000000009860332328e+00,0.000000000000000000e+00,-1.404433148359527809e-09,0.000000000000000000e+00 +2.984044111023892043e+01,1.677100000000000080e+02,0.000000000000000000e+00,1.015674028891671909e+01,0.000000000000000000e+00,1.000000009858949435e+00,0.000000000000000000e+00,4.377439055855381021e-10,0.000000000000000000e+00 +2.984142567809391622e+01,1.677199999999999989e+02,0.000000000000000000e+00,1.015772485678142090e+01,0.000000000000000000e+00,1.000000009859380423e+00,0.000000000000000000e+00,-3.362902792116950049e-10,0.000000000000000000e+00 +2.984241015051672719e+01,1.677299999999999898e+02,0.000000000000000000e+00,1.015870932921393788e+01,0.000000000000000000e+00,1.000000009859049355e+00,0.000000000000000000e+00,-7.105412788593646695e-11,0.000000000000000000e+00 +2.984339452753510002e+01,1.677400000000000091e+02,0.000000000000000000e+00,1.015969370624201495e+01,0.000000000000000000e+00,1.000000009858979411e+00,0.000000000000000000e+00,1.225182100630392845e-09,0.000000000000000000e+00 +2.984437880917676722e+01,1.677500000000000000e+02,0.000000000000000000e+00,1.016067798789338461e+01,0.000000000000000000e+00,1.000000009860185335e+00,0.000000000000000000e+00,-1.957864172540153235e-09,0.000000000000000000e+00 +2.984536299546944349e+01,1.677599999999999909e+02,0.000000000000000000e+00,1.016166217419576689e+01,0.000000000000000000e+00,1.000000009858258432e+00,0.000000000000000000e+00,-4.623245296581563193e-10,0.000000000000000000e+00 +2.984634708644084000e+01,1.677700000000000102e+02,0.000000000000000000e+00,1.016264626517686409e+01,0.000000000000000000e+00,1.000000009857803462e+00,0.000000000000000000e+00,2.037900035851963786e-09,0.000000000000000000e+00 +2.984733108211864661e+01,1.677800000000000011e+02,0.000000000000000000e+00,1.016363026086436960e+01,0.000000000000000000e+00,1.000000009859808747e+00,0.000000000000000000e+00,-1.807454514041467604e-09,0.000000000000000000e+00 +2.984831498253053894e+01,1.677899999999999920e+02,0.000000000000000000e+00,1.016461416128596440e+01,0.000000000000000000e+00,1.000000009858030392e+00,0.000000000000000000e+00,-9.993985973494157915e-10,0.000000000000000000e+00 +2.984929878770418554e+01,1.678000000000000114e+02,0.000000000000000000e+00,1.016559796646930991e+01,0.000000000000000000e+00,1.000000009857047178e+00,0.000000000000000000e+00,7.855112321334000351e-10,0.000000000000000000e+00 +2.985028249766723718e+01,1.678100000000000023e+02,0.000000000000000000e+00,1.016658167644205868e+01,0.000000000000000000e+00,1.000000009857819894e+00,0.000000000000000000e+00,-1.352203332458399951e-10,0.000000000000000000e+00 +2.985126611244733397e+01,1.678199999999999932e+02,0.000000000000000000e+00,1.016756529123185082e+01,0.000000000000000000e+00,1.000000009857686889e+00,0.000000000000000000e+00,-9.865943689276331321e-11,0.000000000000000000e+00 +2.985224963207209825e+01,1.678300000000000125e+02,0.000000000000000000e+00,1.016854881086631046e+01,0.000000000000000000e+00,1.000000009857589855e+00,0.000000000000000000e+00,8.855371644015990476e-10,0.000000000000000000e+00 +2.985323305656914172e+01,1.678400000000000034e+02,0.000000000000000000e+00,1.016953223537304929e+01,0.000000000000000000e+00,1.000000009858460714e+00,0.000000000000000000e+00,-8.650741899199710446e-10,0.000000000000000000e+00 +2.985421638596606542e+01,1.678499999999999943e+02,0.000000000000000000e+00,1.017051556477966656e+01,0.000000000000000000e+00,1.000000009857610062e+00,0.000000000000000000e+00,-1.686956158517640840e-09,0.000000000000000000e+00 +2.985519962029045260e+01,1.678600000000000136e+02,0.000000000000000000e+00,1.017149879911374555e+01,0.000000000000000000e+00,1.000000009855951388e+00,0.000000000000000000e+00,2.086878423486449367e-09,0.000000000000000000e+00 +2.985618275956987588e+01,1.678700000000000045e+02,0.000000000000000000e+00,1.017248193840285708e+01,0.000000000000000000e+00,1.000000009858003081e+00,0.000000000000000000e+00,-2.416630989964744139e-09,0.000000000000000000e+00 +2.985716580383189012e+01,1.678799999999999955e+02,0.000000000000000000e+00,1.017346498267456312e+01,0.000000000000000000e+00,1.000000009855627425e+00,0.000000000000000000e+00,1.334369451658959775e-09,0.000000000000000000e+00 +2.985814875310404304e+01,1.678900000000000148e+02,0.000000000000000000e+00,1.017444793195640429e+01,0.000000000000000000e+00,1.000000009856939043e+00,0.000000000000000000e+00,4.629062425060820197e-10,0.000000000000000000e+00 +2.985913160741386818e+01,1.679000000000000057e+02,0.000000000000000000e+00,1.017543078627591591e+01,0.000000000000000000e+00,1.000000009857394012e+00,0.000000000000000000e+00,-1.364225423462128286e-09,0.000000000000000000e+00 +2.986011436678888131e+01,1.679099999999999966e+02,0.000000000000000000e+00,1.017641354566061551e+01,0.000000000000000000e+00,1.000000009856053307e+00,0.000000000000000000e+00,-4.770053018108190681e-10,0.000000000000000000e+00 +2.986109703125658754e+01,1.679200000000000159e+02,0.000000000000000000e+00,1.017739621013800644e+01,0.000000000000000000e+00,1.000000009855584571e+00,0.000000000000000000e+00,1.275677377204443854e-09,0.000000000000000000e+00 +2.986207960084447777e+01,1.679300000000000068e+02,0.000000000000000000e+00,1.017837877973558136e+01,0.000000000000000000e+00,1.000000009856838012e+00,0.000000000000000000e+00,-1.635375143086796358e-09,0.000000000000000000e+00 +2.986306207558003223e+01,1.679399999999999977e+02,0.000000000000000000e+00,1.017936125448082052e+01,0.000000000000000000e+00,1.000000009855231298e+00,0.000000000000000000e+00,-1.830820520993695347e-11,0.000000000000000000e+00 +2.986404445549071696e+01,1.679500000000000171e+02,0.000000000000000000e+00,1.018034363440118639e+01,0.000000000000000000e+00,1.000000009855213312e+00,0.000000000000000000e+00,5.967694603996404961e-10,0.000000000000000000e+00 +2.986502674060398377e+01,1.679600000000000080e+02,0.000000000000000000e+00,1.018132591952413257e+01,0.000000000000000000e+00,1.000000009855799510e+00,0.000000000000000000e+00,1.998466306409725824e-10,0.000000000000000000e+00 +2.986600893094727027e+01,1.679699999999999989e+02,0.000000000000000000e+00,1.018230810987709845e+01,0.000000000000000000e+00,1.000000009855995797e+00,0.000000000000000000e+00,-1.219091612735419400e-09,0.000000000000000000e+00 +2.986699102654799987e+01,1.679799999999999898e+02,0.000000000000000000e+00,1.018329020548750918e+01,0.000000000000000000e+00,1.000000009854798533e+00,0.000000000000000000e+00,1.492355469339513613e-11,0.000000000000000000e+00 +2.986797302743358884e+01,1.679900000000000091e+02,0.000000000000000000e+00,1.018427220638277575e+01,0.000000000000000000e+00,1.000000009854813188e+00,0.000000000000000000e+00,2.087237770729566904e-10,0.000000000000000000e+00 +2.986895493363143572e+01,1.680000000000000000e+02,0.000000000000000000e+00,1.018525411259029845e+01,0.000000000000000000e+00,1.000000009855018135e+00,0.000000000000000000e+00,-6.472644036355709297e-10,0.000000000000000000e+00 +2.986993674516892483e+01,1.680099999999999909e+02,0.000000000000000000e+00,1.018623592413746337e+01,0.000000000000000000e+00,1.000000009854382643e+00,0.000000000000000000e+00,-7.199305362199825461e-10,0.000000000000000000e+00 +2.987091846207342982e+01,1.680200000000000102e+02,0.000000000000000000e+00,1.018721764105164240e+01,0.000000000000000000e+00,1.000000009853675875e+00,0.000000000000000000e+00,1.825899893472123913e-09,0.000000000000000000e+00 +2.987190008437231015e+01,1.680300000000000011e+02,0.000000000000000000e+00,1.018819926336019499e+01,0.000000000000000000e+00,1.000000009855468219e+00,0.000000000000000000e+00,-2.237123875378642979e-09,0.000000000000000000e+00 +2.987288161209291104e+01,1.680399999999999920e+02,0.000000000000000000e+00,1.018918079109046992e+01,0.000000000000000000e+00,1.000000009853272420e+00,0.000000000000000000e+00,-1.312222521495092684e-11,0.000000000000000000e+00 +2.987386304526256708e+01,1.680500000000000114e+02,0.000000000000000000e+00,1.019016222426979645e+01,0.000000000000000000e+00,1.000000009853259542e+00,0.000000000000000000e+00,1.115496578788512712e-09,0.000000000000000000e+00 +2.987484438390859864e+01,1.680600000000000023e+02,0.000000000000000000e+00,1.019114356292549672e+01,0.000000000000000000e+00,1.000000009854354222e+00,0.000000000000000000e+00,-7.073789282708875813e-10,0.000000000000000000e+00 +2.987582562805831188e+01,1.680699999999999932e+02,0.000000000000000000e+00,1.019212480708487867e+01,0.000000000000000000e+00,1.000000009853660110e+00,0.000000000000000000e+00,4.367795209442041645e-11,0.000000000000000000e+00 +2.987680677773899873e+01,1.680800000000000125e+02,0.000000000000000000e+00,1.019310595677523423e+01,0.000000000000000000e+00,1.000000009853702965e+00,0.000000000000000000e+00,-3.299926661921201841e-10,0.000000000000000000e+00 +2.987778783297794050e+01,1.680900000000000034e+02,0.000000000000000000e+00,1.019408701202384471e+01,0.000000000000000000e+00,1.000000009853379224e+00,0.000000000000000000e+00,7.243334474099927886e-12,0.000000000000000000e+00 +2.987876879380240780e+01,1.680999999999999943e+02,0.000000000000000000e+00,1.019506797285797717e+01,0.000000000000000000e+00,1.000000009853386329e+00,0.000000000000000000e+00,-7.997863515486977533e-10,0.000000000000000000e+00 +2.987974966023965351e+01,1.681100000000000136e+02,0.000000000000000000e+00,1.019604883930488626e+01,0.000000000000000000e+00,1.000000009852601845e+00,0.000000000000000000e+00,-9.137413740186621975e-10,0.000000000000000000e+00 +2.988073043231691628e+01,1.681200000000000045e+02,0.000000000000000000e+00,1.019702961139181241e+01,0.000000000000000000e+00,1.000000009851705673e+00,0.000000000000000000e+00,1.503425753216306045e-09,0.000000000000000000e+00 +2.988171111006142766e+01,1.681299999999999955e+02,0.000000000000000000e+00,1.019801028914598362e+01,0.000000000000000000e+00,1.000000009853180050e+00,0.000000000000000000e+00,-9.451660553526716162e-10,0.000000000000000000e+00 +2.988269169350039789e+01,1.681400000000000148e+02,0.000000000000000000e+00,1.019899087259461723e+01,0.000000000000000000e+00,1.000000009852253235e+00,0.000000000000000000e+00,9.665444676672813053e-10,0.000000000000000000e+00 +2.988367218266103364e+01,1.681500000000000057e+02,0.000000000000000000e+00,1.019997136176491281e+01,0.000000000000000000e+00,1.000000009853200922e+00,0.000000000000000000e+00,-2.008694233335117828e-09,0.000000000000000000e+00 +2.988465257757052029e+01,1.681599999999999966e+02,0.000000000000000000e+00,1.020095175668406107e+01,0.000000000000000000e+00,1.000000009851231608e+00,0.000000000000000000e+00,1.208865885736161954e-09,0.000000000000000000e+00 +2.988563287825603609e+01,1.681700000000000159e+02,0.000000000000000000e+00,1.020193205737923492e+01,0.000000000000000000e+00,1.000000009852416660e+00,0.000000000000000000e+00,-4.802402023083902394e-10,0.000000000000000000e+00 +2.988661308474474509e+01,1.681800000000000068e+02,0.000000000000000000e+00,1.020291226387760020e+01,0.000000000000000000e+00,1.000000009851945926e+00,0.000000000000000000e+00,-1.539408352636512939e-09,0.000000000000000000e+00 +2.988759319706379358e+01,1.681899999999999977e+02,0.000000000000000000e+00,1.020389237620630496e+01,0.000000000000000000e+00,1.000000009850437133e+00,0.000000000000000000e+00,1.720360627566962955e-09,0.000000000000000000e+00 +2.988857321524032074e+01,1.682000000000000171e+02,0.000000000000000000e+00,1.020487239439248484e+01,0.000000000000000000e+00,1.000000009852123117e+00,0.000000000000000000e+00,-1.805725083035307754e-09,0.000000000000000000e+00 +2.988955313930144797e+01,1.682100000000000080e+02,0.000000000000000000e+00,1.020585231846326657e+01,0.000000000000000000e+00,1.000000009850353644e+00,0.000000000000000000e+00,8.205745248880510153e-10,0.000000000000000000e+00 +2.989053296927428605e+01,1.682199999999999989e+02,0.000000000000000000e+00,1.020683214844575737e+01,0.000000000000000000e+00,1.000000009851157667e+00,0.000000000000000000e+00,3.408623505954370967e-10,0.000000000000000000e+00 +2.989151270518593506e+01,1.682299999999999898e+02,0.000000000000000000e+00,1.020781188436705733e+01,0.000000000000000000e+00,1.000000009851491622e+00,0.000000000000000000e+00,-1.405512184303961380e-09,0.000000000000000000e+00 +2.989249234706347735e+01,1.682400000000000091e+02,0.000000000000000000e+00,1.020879152625425057e+01,0.000000000000000000e+00,1.000000009850114724e+00,0.000000000000000000e+00,1.126149757944696939e-09,0.000000000000000000e+00 +2.989347189493398460e+01,1.682500000000000000e+02,0.000000000000000000e+00,1.020977107413440699e+01,0.000000000000000000e+00,1.000000009851217841e+00,0.000000000000000000e+00,-1.328703108993728551e-09,0.000000000000000000e+00 +2.989445134882451782e+01,1.682599999999999909e+02,0.000000000000000000e+00,1.021075052803458760e+01,0.000000000000000000e+00,1.000000009849916438e+00,0.000000000000000000e+00,4.770277308937481543e-10,0.000000000000000000e+00 +2.989543070876212028e+01,1.682700000000000102e+02,0.000000000000000000e+00,1.021172988798183567e+01,0.000000000000000000e+00,1.000000009850383620e+00,0.000000000000000000e+00,-8.716114427854064868e-10,0.000000000000000000e+00 +2.989640997477382456e+01,1.682800000000000011e+02,0.000000000000000000e+00,1.021270915400318557e+01,0.000000000000000000e+00,1.000000009849530080e+00,0.000000000000000000e+00,1.714363788802055469e-10,0.000000000000000000e+00 +2.989738914688664906e+01,1.682899999999999920e+02,0.000000000000000000e+00,1.021368832612565569e+01,0.000000000000000000e+00,1.000000009849697946e+00,0.000000000000000000e+00,-1.063642468535726406e-10,0.000000000000000000e+00 +2.989836822512760506e+01,1.683000000000000114e+02,0.000000000000000000e+00,1.021466740437625376e+01,0.000000000000000000e+00,1.000000009849593807e+00,0.000000000000000000e+00,1.374475743676664112e-10,0.000000000000000000e+00 +2.989934720952368252e+01,1.683100000000000023e+02,0.000000000000000000e+00,1.021564638878197329e+01,0.000000000000000000e+00,1.000000009849728366e+00,0.000000000000000000e+00,-9.590495715754474289e-10,0.000000000000000000e+00 +2.990032610010186431e+01,1.683199999999999932e+02,0.000000000000000000e+00,1.021662527936979536e+01,0.000000000000000000e+00,1.000000009848789562e+00,0.000000000000000000e+00,3.023972516258396883e-10,0.000000000000000000e+00 +2.990130489688911553e+01,1.683300000000000125e+02,0.000000000000000000e+00,1.021760407616668687e+01,0.000000000000000000e+00,1.000000009849085547e+00,0.000000000000000000e+00,2.053231293637403297e-10,0.000000000000000000e+00 +2.990228359991239415e+01,1.683400000000000034e+02,0.000000000000000000e+00,1.021858277919960400e+01,0.000000000000000000e+00,1.000000009849286497e+00,0.000000000000000000e+00,-1.260192145206553316e-09,0.000000000000000000e+00 +2.990326220919864042e+01,1.683499999999999943e+02,0.000000000000000000e+00,1.021956138849548879e+01,0.000000000000000000e+00,1.000000009848053262e+00,0.000000000000000000e+00,1.461590735181138267e-09,0.000000000000000000e+00 +2.990424072477478390e+01,1.683600000000000136e+02,0.000000000000000000e+00,1.022053990408126900e+01,0.000000000000000000e+00,1.000000009849483451e+00,0.000000000000000000e+00,-2.769594975347185158e-09,0.000000000000000000e+00 +2.990521914666773995e+01,1.683700000000000045e+02,0.000000000000000000e+00,1.022151832598386356e+01,0.000000000000000000e+00,1.000000009846773619e+00,0.000000000000000000e+00,2.737404359402869960e-09,0.000000000000000000e+00 +2.990619747490441327e+01,1.683799999999999955e+02,0.000000000000000000e+00,1.022249665423017184e+01,0.000000000000000000e+00,1.000000009849451699e+00,0.000000000000000000e+00,-2.440769953325472882e-09,0.000000000000000000e+00 +2.990717570951169435e+01,1.683900000000000148e+02,0.000000000000000000e+00,1.022347488884708966e+01,0.000000000000000000e+00,1.000000009847064053e+00,0.000000000000000000e+00,2.467563310166018424e-10,0.000000000000000000e+00 +2.990815385051646302e+01,1.684000000000000057e+02,0.000000000000000000e+00,1.022445302986148974e+01,0.000000000000000000e+00,1.000000009847305416e+00,0.000000000000000000e+00,1.512463622897747030e-09,0.000000000000000000e+00 +2.990913189794558136e+01,1.684099999999999966e+02,0.000000000000000000e+00,1.022543107730023948e+01,0.000000000000000000e+00,1.000000009848784677e+00,0.000000000000000000e+00,-2.370403883112149098e-09,0.000000000000000000e+00 +2.991010985182590076e+01,1.684200000000000159e+02,0.000000000000000000e+00,1.022640903119019207e+01,0.000000000000000000e+00,1.000000009846466531e+00,0.000000000000000000e+00,1.591546914250498015e-09,0.000000000000000000e+00 +2.991108771218426199e+01,1.684300000000000068e+02,0.000000000000000000e+00,1.022738689155818292e+01,0.000000000000000000e+00,1.000000009848022842e+00,0.000000000000000000e+00,-1.471566580974959719e-09,0.000000000000000000e+00 +2.991206547904749158e+01,1.684399999999999977e+02,0.000000000000000000e+00,1.022836465843104214e+01,0.000000000000000000e+00,1.000000009846583993e+00,0.000000000000000000e+00,-4.212989166727428414e-10,0.000000000000000000e+00 +2.991304315244240186e+01,1.684500000000000171e+02,0.000000000000000000e+00,1.022934233183558028e+01,0.000000000000000000e+00,1.000000009846172100e+00,0.000000000000000000e+00,1.017573883968467799e-09,0.000000000000000000e+00 +2.991402073239579451e+01,1.684600000000000080e+02,0.000000000000000000e+00,1.023031991179859901e+01,0.000000000000000000e+00,1.000000009847166860e+00,0.000000000000000000e+00,-8.818302065805507897e-10,0.000000000000000000e+00 +2.991499821893445699e+01,1.684699999999999989e+02,0.000000000000000000e+00,1.023129739834688756e+01,0.000000000000000000e+00,1.000000009846304883e+00,0.000000000000000000e+00,-5.520484664508038203e-10,0.000000000000000000e+00 +2.991597561208516609e+01,1.684799999999999898e+02,0.000000000000000000e+00,1.023227479150721919e+01,0.000000000000000000e+00,1.000000009845765314e+00,0.000000000000000000e+00,1.395021147928650784e-10,0.000000000000000000e+00 +2.991695291187468086e+01,1.684900000000000091e+02,0.000000000000000000e+00,1.023325209130635649e+01,0.000000000000000000e+00,1.000000009845901650e+00,0.000000000000000000e+00,1.184745110995229799e-09,0.000000000000000000e+00 +2.991793011832975324e+01,1.685000000000000000e+02,0.000000000000000000e+00,1.023422929777104962e+01,0.000000000000000000e+00,1.000000009847059390e+00,0.000000000000000000e+00,-1.146908240953214545e-09,0.000000000000000000e+00 +2.991890723147711739e+01,1.685099999999999909e+02,0.000000000000000000e+00,1.023520641092803629e+01,0.000000000000000000e+00,1.000000009845938731e+00,0.000000000000000000e+00,-1.284287152806358954e-09,0.000000000000000000e+00 +2.991988425134350038e+01,1.685200000000000102e+02,0.000000000000000000e+00,1.023618343080403825e+01,0.000000000000000000e+00,1.000000009844683957e+00,0.000000000000000000e+00,7.664182739268991027e-10,0.000000000000000000e+00 +2.992086117795561151e+01,1.685300000000000011e+02,0.000000000000000000e+00,1.023716035742576658e+01,0.000000000000000000e+00,1.000000009845432691e+00,0.000000000000000000e+00,-5.880525809556326280e-10,0.000000000000000000e+00 +2.992183801134014942e+01,1.685399999999999920e+02,0.000000000000000000e+00,1.023813719081992168e+01,0.000000000000000000e+00,1.000000009844858262e+00,0.000000000000000000e+00,2.273323127703879381e-10,0.000000000000000000e+00 +2.992281475152379855e+01,1.685500000000000114e+02,0.000000000000000000e+00,1.023911393101318801e+01,0.000000000000000000e+00,1.000000009845080307e+00,0.000000000000000000e+00,-5.195038917352764196e-10,0.000000000000000000e+00 +2.992379139853323622e+01,1.685600000000000023e+02,0.000000000000000000e+00,1.024009057803223932e+01,0.000000000000000000e+00,1.000000009844572935e+00,0.000000000000000000e+00,8.867651780503246084e-10,0.000000000000000000e+00 +2.992476795239511844e+01,1.685699999999999932e+02,0.000000000000000000e+00,1.024106713190373519e+01,0.000000000000000000e+00,1.000000009845438909e+00,0.000000000000000000e+00,-1.150403297518498586e-09,0.000000000000000000e+00 +2.992574441313609412e+01,1.685800000000000125e+02,0.000000000000000000e+00,1.024204359265432451e+01,0.000000000000000000e+00,1.000000009844315585e+00,0.000000000000000000e+00,-1.052495374116540303e-09,0.000000000000000000e+00 +2.992672078078279796e+01,1.685900000000000034e+02,0.000000000000000000e+00,1.024301996031064022e+01,0.000000000000000000e+00,1.000000009843287962e+00,0.000000000000000000e+00,1.174276499484512957e-09,0.000000000000000000e+00 +2.992769705536185398e+01,1.685999999999999943e+02,0.000000000000000000e+00,1.024399623489930455e+01,0.000000000000000000e+00,1.000000009844434379e+00,0.000000000000000000e+00,-7.096827182114979890e-11,0.000000000000000000e+00 +2.992867323689986847e+01,1.686100000000000136e+02,0.000000000000000000e+00,1.024497241644692913e+01,0.000000000000000000e+00,1.000000009844365101e+00,0.000000000000000000e+00,-1.070312621184905711e-09,0.000000000000000000e+00 +2.992964932542344059e+01,1.686200000000000045e+02,0.000000000000000000e+00,1.024594850498010956e+01,0.000000000000000000e+00,1.000000009843320381e+00,0.000000000000000000e+00,3.253332350654848413e-11,0.000000000000000000e+00 +2.993062532095915174e+01,1.686299999999999955e+02,0.000000000000000000e+00,1.024692450052542902e+01,0.000000000000000000e+00,1.000000009843352133e+00,0.000000000000000000e+00,-5.003328191012328171e-10,0.000000000000000000e+00 +2.993160122353357622e+01,1.686400000000000148e+02,0.000000000000000000e+00,1.024790040310946004e+01,0.000000000000000000e+00,1.000000009842863857e+00,0.000000000000000000e+00,-8.130329329849606053e-10,0.000000000000000000e+00 +2.993257703317327056e+01,1.686500000000000057e+02,0.000000000000000000e+00,1.024887621275876093e+01,0.000000000000000000e+00,1.000000009842070492e+00,0.000000000000000000e+00,9.512458058876043207e-10,0.000000000000000000e+00 +2.993355274990478421e+01,1.686599999999999966e+02,0.000000000000000000e+00,1.024985192949987756e+01,0.000000000000000000e+00,1.000000009842998638e+00,0.000000000000000000e+00,-8.136429451957485516e-10,0.000000000000000000e+00 +2.993452837375464881e+01,1.686700000000000159e+02,0.000000000000000000e+00,1.025082755335934515e+01,0.000000000000000000e+00,1.000000009842204829e+00,0.000000000000000000e+00,1.347930673101106324e-09,0.000000000000000000e+00 +2.993550390474938538e+01,1.686800000000000068e+02,0.000000000000000000e+00,1.025180308436368293e+01,0.000000000000000000e+00,1.000000009843519777e+00,0.000000000000000000e+00,-1.905994189707651834e-09,0.000000000000000000e+00 +2.993647934291550072e+01,1.686899999999999977e+02,0.000000000000000000e+00,1.025277852253940125e+01,0.000000000000000000e+00,1.000000009841660598e+00,0.000000000000000000e+00,6.171792538057622538e-10,0.000000000000000000e+00 +2.993745468827949452e+01,1.687000000000000171e+02,0.000000000000000000e+00,1.025375386791299270e+01,0.000000000000000000e+00,1.000000009842262561e+00,0.000000000000000000e+00,-4.264429030920399264e-10,0.000000000000000000e+00 +2.993842994086784515e+01,1.687100000000000080e+02,0.000000000000000000e+00,1.025472912051094276e+01,0.000000000000000000e+00,1.000000009841846671e+00,0.000000000000000000e+00,-1.312466993988460962e-09,0.000000000000000000e+00 +2.993940510070702743e+01,1.687199999999999989e+02,0.000000000000000000e+00,1.025570428035972093e+01,0.000000000000000000e+00,1.000000009840566806e+00,0.000000000000000000e+00,1.688561451526456412e-09,0.000000000000000000e+00 +2.994038016782349487e+01,1.687299999999999898e+02,0.000000000000000000e+00,1.025667934748578425e+01,0.000000000000000000e+00,1.000000009842213267e+00,0.000000000000000000e+00,-7.750129387028375536e-10,0.000000000000000000e+00 +2.994135514224369388e+01,1.687400000000000091e+02,0.000000000000000000e+00,1.025765432191558091e+01,0.000000000000000000e+00,1.000000009841457649e+00,0.000000000000000000e+00,-1.237906471543119402e-09,0.000000000000000000e+00 +2.994233002399406018e+01,1.687500000000000000e+02,0.000000000000000000e+00,1.025862920367554132e+01,0.000000000000000000e+00,1.000000009840250836e+00,0.000000000000000000e+00,2.917955657079833260e-10,0.000000000000000000e+00 +2.994330481310101177e+01,1.687599999999999909e+02,0.000000000000000000e+00,1.025960399279208524e+01,0.000000000000000000e+00,1.000000009840535276e+00,0.000000000000000000e+00,6.720364660037037291e-11,0.000000000000000000e+00 +2.994427950959095597e+01,1.687700000000000102e+02,0.000000000000000000e+00,1.026057868929162176e+01,0.000000000000000000e+00,1.000000009840600779e+00,0.000000000000000000e+00,-5.126188818073395254e-11,0.000000000000000000e+00 +2.994525411349028943e+01,1.687800000000000011e+02,0.000000000000000000e+00,1.026155329320054577e+01,0.000000000000000000e+00,1.000000009840550819e+00,0.000000000000000000e+00,-7.291272150098781601e-11,0.000000000000000000e+00 +2.994622862482539460e+01,1.687899999999999920e+02,0.000000000000000000e+00,1.026252780454523972e+01,0.000000000000000000e+00,1.000000009840479764e+00,0.000000000000000000e+00,-5.924721222920230976e-12,0.000000000000000000e+00 +2.994720304362263974e+01,1.688000000000000114e+02,0.000000000000000000e+00,1.026350222335207363e+01,0.000000000000000000e+00,1.000000009840473991e+00,0.000000000000000000e+00,-1.730638652034058753e-09,0.000000000000000000e+00 +2.994817736990838242e+01,1.688100000000000023e+02,0.000000000000000000e+00,1.026447654964740508e+01,0.000000000000000000e+00,1.000000009838787784e+00,0.000000000000000000e+00,3.585136990079755018e-10,0.000000000000000000e+00 +2.994915160370896956e+01,1.688199999999999932e+02,0.000000000000000000e+00,1.026545078345757744e+01,0.000000000000000000e+00,1.000000009839137061e+00,0.000000000000000000e+00,6.384565686016125123e-10,0.000000000000000000e+00 +2.995012574505073388e+01,1.688300000000000125e+02,0.000000000000000000e+00,1.026642492480892521e+01,0.000000000000000000e+00,1.000000009839759008e+00,0.000000000000000000e+00,-8.999877643832839988e-10,0.000000000000000000e+00 +2.995109979395999389e+01,1.688400000000000034e+02,0.000000000000000000e+00,1.026739897372776866e+01,0.000000000000000000e+00,1.000000009838882375e+00,0.000000000000000000e+00,1.351249639231710419e-09,0.000000000000000000e+00 +2.995207375046305742e+01,1.688499999999999943e+02,0.000000000000000000e+00,1.026837293024041387e+01,0.000000000000000000e+00,1.000000009840198434e+00,0.000000000000000000e+00,-1.979983966253934055e-09,0.000000000000000000e+00 +2.995304761458621812e+01,1.688600000000000136e+02,0.000000000000000000e+00,1.026934679437315800e+01,0.000000000000000000e+00,1.000000009838270199e+00,0.000000000000000000e+00,3.349691733086450637e-10,0.000000000000000000e+00 +2.995402138635575895e+01,1.688700000000000045e+02,0.000000000000000000e+00,1.027032056615228051e+01,0.000000000000000000e+00,1.000000009838596382e+00,0.000000000000000000e+00,-1.077977825141337005e-09,0.000000000000000000e+00 +2.995499506579795224e+01,1.688799999999999955e+02,0.000000000000000000e+00,1.027129424560405369e+01,0.000000000000000000e+00,1.000000009837546777e+00,0.000000000000000000e+00,1.266692711611947717e-09,0.000000000000000000e+00 +2.995596865293905608e+01,1.688900000000000148e+02,0.000000000000000000e+00,1.027226783275473387e+01,0.000000000000000000e+00,1.000000009838780013e+00,0.000000000000000000e+00,-1.352574679996622442e-10,0.000000000000000000e+00 +2.995694214780531439e+01,1.689000000000000057e+02,0.000000000000000000e+00,1.027324132763056852e+01,0.000000000000000000e+00,1.000000009838648340e+00,0.000000000000000000e+00,-1.545229205776476430e-09,0.000000000000000000e+00 +2.995791555042295684e+01,1.689099999999999966e+02,0.000000000000000000e+00,1.027421473025778909e+01,0.000000000000000000e+00,1.000000009837144210e+00,0.000000000000000000e+00,7.779348771870045597e-10,0.000000000000000000e+00 +2.995888886081820601e+01,1.689200000000000159e+02,0.000000000000000000e+00,1.027518804066261460e+01,0.000000000000000000e+00,1.000000009837901382e+00,0.000000000000000000e+00,-6.735135803745082013e-10,0.000000000000000000e+00 +2.995986207901727383e+01,1.689300000000000068e+02,0.000000000000000000e+00,1.027616125887125520e+01,0.000000000000000000e+00,1.000000009837245907e+00,0.000000000000000000e+00,-2.831671813088127445e-10,0.000000000000000000e+00 +2.996083520504635089e+01,1.689399999999999977e+02,0.000000000000000000e+00,1.027713438490990505e+01,0.000000000000000000e+00,1.000000009836970349e+00,0.000000000000000000e+00,6.458009751252331376e-11,0.000000000000000000e+00 +2.996180823893162071e+01,1.689500000000000171e+02,0.000000000000000000e+00,1.027810741880474765e+01,0.000000000000000000e+00,1.000000009837033188e+00,0.000000000000000000e+00,-1.514466792666719880e-09,0.000000000000000000e+00 +2.996278118069925611e+01,1.689600000000000080e+02,0.000000000000000000e+00,1.027908036058195407e+01,0.000000000000000000e+00,1.000000009835559700e+00,0.000000000000000000e+00,5.993620050690088086e-10,0.000000000000000000e+00 +2.996375403037541574e+01,1.689699999999999989e+02,0.000000000000000000e+00,1.028005321026768115e+01,0.000000000000000000e+00,1.000000009836142789e+00,0.000000000000000000e+00,7.692464291908970323e-10,0.000000000000000000e+00 +2.996472678798624401e+01,1.689799999999999898e+02,0.000000000000000000e+00,1.028102596788807688e+01,0.000000000000000000e+00,1.000000009836891079e+00,0.000000000000000000e+00,-1.015638340787418111e-09,0.000000000000000000e+00 +2.996569945355787468e+01,1.689900000000000091e+02,0.000000000000000000e+00,1.028199863346927501e+01,0.000000000000000000e+00,1.000000009835903203e+00,0.000000000000000000e+00,-1.009341853620952238e-09,0.000000000000000000e+00 +2.996667202711642730e+01,1.690000000000000000e+02,0.000000000000000000e+00,1.028297120703739509e+01,0.000000000000000000e+00,1.000000009834921544e+00,0.000000000000000000e+00,7.813378271155793937e-10,0.000000000000000000e+00 +2.996764450868801433e+01,1.690099999999999909e+02,0.000000000000000000e+00,1.028394368861854602e+01,0.000000000000000000e+00,1.000000009835681380e+00,0.000000000000000000e+00,5.911966518519976822e-10,0.000000000000000000e+00 +2.996861689829873043e+01,1.690200000000000102e+02,0.000000000000000000e+00,1.028491607823882603e+01,0.000000000000000000e+00,1.000000009836256254e+00,0.000000000000000000e+00,-1.589918990612087054e-09,0.000000000000000000e+00 +2.996958919597465965e+01,1.690300000000000011e+02,0.000000000000000000e+00,1.028588837592431915e+01,0.000000000000000000e+00,1.000000009834710379e+00,0.000000000000000000e+00,-1.336096722130026097e-10,0.000000000000000000e+00 +2.997056140174187533e+01,1.690399999999999920e+02,0.000000000000000000e+00,1.028686058170109519e+01,0.000000000000000000e+00,1.000000009834580483e+00,0.000000000000000000e+00,1.195063038827107216e-09,0.000000000000000000e+00 +2.997153351562643664e+01,1.690500000000000114e+02,0.000000000000000000e+00,1.028783269559521507e+01,0.000000000000000000e+00,1.000000009835742221e+00,0.000000000000000000e+00,-1.374041184476598105e-09,0.000000000000000000e+00 +2.997250553765438852e+01,1.690600000000000023e+02,0.000000000000000000e+00,1.028880471763272730e+01,0.000000000000000000e+00,1.000000009834406622e+00,0.000000000000000000e+00,-3.294355100453037593e-10,0.000000000000000000e+00 +2.997347746785176881e+01,1.690699999999999932e+02,0.000000000000000000e+00,1.028977664783966439e+01,0.000000000000000000e+00,1.000000009834086434e+00,0.000000000000000000e+00,-1.319922830912861552e-09,0.000000000000000000e+00 +2.997444930624459758e+01,1.690800000000000125e+02,0.000000000000000000e+00,1.029074848624204996e+01,0.000000000000000000e+00,1.000000009832803682e+00,0.000000000000000000e+00,1.287828920581106411e-09,0.000000000000000000e+00 +2.997542105285888780e+01,1.690900000000000034e+02,0.000000000000000000e+00,1.029172023286589344e+01,0.000000000000000000e+00,1.000000009834055126e+00,0.000000000000000000e+00,-3.793466782155392752e-11,0.000000000000000000e+00 +2.997639270772063469e+01,1.690999999999999943e+02,0.000000000000000000e+00,1.029269188773719534e+01,0.000000000000000000e+00,1.000000009834018266e+00,0.000000000000000000e+00,-1.545640842798660208e-09,0.000000000000000000e+00 +2.997736427085582633e+01,1.691100000000000136e+02,0.000000000000000000e+00,1.029366345088194024e+01,0.000000000000000000e+00,1.000000009832516579e+00,0.000000000000000000e+00,2.403820665029540318e-09,0.000000000000000000e+00 +2.997833574229043307e+01,1.691200000000000045e+02,0.000000000000000000e+00,1.029463492232610022e+01,0.000000000000000000e+00,1.000000009834851822e+00,0.000000000000000000e+00,-3.256219171377756552e-09,0.000000000000000000e+00 +2.997930712205041814e+01,1.691299999999999955e+02,0.000000000000000000e+00,1.029560630209564032e+01,0.000000000000000000e+00,1.000000009831688796e+00,0.000000000000000000e+00,2.172694075655389600e-09,0.000000000000000000e+00 +2.998027841016173412e+01,1.691400000000000148e+02,0.000000000000000000e+00,1.029657759021650421e+01,0.000000000000000000e+00,1.000000009833799108e+00,0.000000000000000000e+00,-2.027947659249304778e-09,0.000000000000000000e+00 +2.998124960665031224e+01,1.691500000000000057e+02,0.000000000000000000e+00,1.029754878671463381e+01,0.000000000000000000e+00,1.000000009831829573e+00,0.000000000000000000e+00,1.080607060855184593e-09,0.000000000000000000e+00 +2.998222071154208024e+01,1.691599999999999966e+02,0.000000000000000000e+00,1.029851989161594972e+01,0.000000000000000000e+00,1.000000009832878956e+00,0.000000000000000000e+00,-1.694238835380947293e-09,0.000000000000000000e+00 +2.998319172486295159e+01,1.691700000000000159e+02,0.000000000000000000e+00,1.029949090494636721e+01,0.000000000000000000e+00,1.000000009831233827e+00,0.000000000000000000e+00,9.424506068730126619e-10,0.000000000000000000e+00 +2.998416264663882203e+01,1.691800000000000068e+02,0.000000000000000000e+00,1.030046182673178379e+01,0.000000000000000000e+00,1.000000009832148873e+00,0.000000000000000000e+00,-4.391350995575088145e-10,0.000000000000000000e+00 +2.998513347689558373e+01,1.691899999999999977e+02,0.000000000000000000e+00,1.030143265699808985e+01,0.000000000000000000e+00,1.000000009831722547e+00,0.000000000000000000e+00,-1.941983535267727943e-10,0.000000000000000000e+00 +2.998610421565911111e+01,1.692000000000000171e+02,0.000000000000000000e+00,1.030240339577115982e+01,0.000000000000000000e+00,1.000000009831534031e+00,0.000000000000000000e+00,-2.161775471743731202e-10,0.000000000000000000e+00 +2.998707486295526436e+01,1.692100000000000080e+02,0.000000000000000000e+00,1.030337404307685745e+01,0.000000000000000000e+00,1.000000009831324199e+00,0.000000000000000000e+00,-5.133842540564362863e-10,0.000000000000000000e+00 +2.998804541880990016e+01,1.692199999999999989e+02,0.000000000000000000e+00,1.030434459894103405e+01,0.000000000000000000e+00,1.000000009830825931e+00,0.000000000000000000e+00,-1.094361939218634534e-09,0.000000000000000000e+00 +2.998901588324885381e+01,1.692299999999999898e+02,0.000000000000000000e+00,1.030531506338952852e+01,0.000000000000000000e+00,1.000000009829763892e+00,0.000000000000000000e+00,-8.169015414405536757e-11,0.000000000000000000e+00 +2.998998625629795356e+01,1.692400000000000091e+02,0.000000000000000000e+00,1.030628543644816730e+01,0.000000000000000000e+00,1.000000009829684622e+00,0.000000000000000000e+00,6.304693739836931252e-10,0.000000000000000000e+00 +2.999095653798301342e+01,1.692500000000000000e+02,0.000000000000000000e+00,1.030725571814276620e+01,0.000000000000000000e+00,1.000000009830296355e+00,0.000000000000000000e+00,1.033563608546400110e-09,0.000000000000000000e+00 +2.999192672832984030e+01,1.692599999999999909e+02,0.000000000000000000e+00,1.030822590849912856e+01,0.000000000000000000e+00,1.000000009831299108e+00,0.000000000000000000e+00,-2.656938809983031219e-09,0.000000000000000000e+00 +2.999289682736421980e+01,1.692700000000000102e+02,0.000000000000000000e+00,1.030919600754304533e+01,0.000000000000000000e+00,1.000000009828721614e+00,0.000000000000000000e+00,8.762679985369009215e-10,0.000000000000000000e+00 +2.999386683511193041e+01,1.692800000000000011e+02,0.000000000000000000e+00,1.031016601530029142e+01,0.000000000000000000e+00,1.000000009829571601e+00,0.000000000000000000e+00,2.994426295369119635e-10,0.000000000000000000e+00 +2.999483675159873997e+01,1.692899999999999920e+02,0.000000000000000000e+00,1.031113593179663646e+01,0.000000000000000000e+00,1.000000009829862035e+00,0.000000000000000000e+00,-6.220658727394181959e-10,0.000000000000000000e+00 +2.999580657685040563e+01,1.693000000000000114e+02,0.000000000000000000e+00,1.031210575705783405e+01,0.000000000000000000e+00,1.000000009829258740e+00,0.000000000000000000e+00,-6.640267601436038217e-12,0.000000000000000000e+00 +2.999677631089266683e+01,1.693100000000000023e+02,0.000000000000000000e+00,1.031307549110962540e+01,0.000000000000000000e+00,1.000000009829252301e+00,0.000000000000000000e+00,-1.641674311953276120e-09,0.000000000000000000e+00 +2.999774595375125230e+01,1.693199999999999932e+02,0.000000000000000000e+00,1.031404513397774103e+01,0.000000000000000000e+00,1.000000009827660463e+00,0.000000000000000000e+00,1.328303284632756889e-10,0.000000000000000000e+00 +2.999871550545188015e+01,1.693300000000000125e+02,0.000000000000000000e+00,1.031501468568789726e+01,0.000000000000000000e+00,1.000000009827789249e+00,0.000000000000000000e+00,1.530211804269950770e-09,0.000000000000000000e+00 +2.999968496602025780e+01,1.693400000000000034e+02,0.000000000000000000e+00,1.031598414626580151e+01,0.000000000000000000e+00,1.000000009829272729e+00,0.000000000000000000e+00,-1.238990204813810601e-09,0.000000000000000000e+00 +3.000065433548207849e+01,1.693499999999999943e+02,0.000000000000000000e+00,1.031695351573714881e+01,0.000000000000000000e+00,1.000000009828071690e+00,0.000000000000000000e+00,-6.231040919414408430e-10,0.000000000000000000e+00 +3.000162361386302123e+01,1.693600000000000136e+02,0.000000000000000000e+00,1.031792279412761815e+01,0.000000000000000000e+00,1.000000009827467728e+00,0.000000000000000000e+00,-4.105542050120523423e-10,0.000000000000000000e+00 +3.000259280118875793e+01,1.693700000000000045e+02,0.000000000000000000e+00,1.031889198146287967e+01,0.000000000000000000e+00,1.000000009827069825e+00,0.000000000000000000e+00,-6.097027674439364350e-10,0.000000000000000000e+00 +3.000356189748494629e+01,1.693799999999999955e+02,0.000000000000000000e+00,1.031986107776859107e+01,0.000000000000000000e+00,1.000000009826478964e+00,0.000000000000000000e+00,6.626929724286414759e-10,0.000000000000000000e+00 +3.000453090277722978e+01,1.693900000000000148e+02,0.000000000000000000e+00,1.032083008307039762e+01,0.000000000000000000e+00,1.000000009827121117e+00,0.000000000000000000e+00,-3.861488615524959426e-10,0.000000000000000000e+00 +3.000549981709124481e+01,1.694000000000000057e+02,0.000000000000000000e+00,1.032179899739393392e+01,0.000000000000000000e+00,1.000000009826746972e+00,0.000000000000000000e+00,1.993952809027970376e-11,0.000000000000000000e+00 +3.000646864045260998e+01,1.694099999999999966e+02,0.000000000000000000e+00,1.032276782076482036e+01,0.000000000000000000e+00,1.000000009826766290e+00,0.000000000000000000e+00,-1.994139965170259259e-11,0.000000000000000000e+00 +3.000743737288693680e+01,1.694200000000000159e+02,0.000000000000000000e+00,1.032373655320866668e+01,0.000000000000000000e+00,1.000000009826746972e+00,0.000000000000000000e+00,-2.407863436524411663e-09,0.000000000000000000e+00 +3.000840601441982258e+01,1.694300000000000068e+02,0.000000000000000000e+00,1.032470519475107018e+01,0.000000000000000000e+00,1.000000009824414615e+00,0.000000000000000000e+00,2.315012027778091542e-09,0.000000000000000000e+00 +3.000937456507685042e+01,1.694399999999999977e+02,0.000000000000000000e+00,1.032567374541761396e+01,0.000000000000000000e+00,1.000000009826656822e+00,0.000000000000000000e+00,-1.007438808761418070e-09,0.000000000000000000e+00 +3.001034302488359629e+01,1.694500000000000171e+02,0.000000000000000000e+00,1.032664220523387577e+01,0.000000000000000000e+00,1.000000009825681158e+00,0.000000000000000000e+00,-1.023125529181568791e-09,0.000000000000000000e+00 +3.001131139386561841e+01,1.694600000000000080e+02,0.000000000000000000e+00,1.032761057422541384e+01,0.000000000000000000e+00,1.000000009824690395e+00,0.000000000000000000e+00,3.678277096476626192e-10,0.000000000000000000e+00 +3.001227967204846792e+01,1.694699999999999989e+02,0.000000000000000000e+00,1.032857885241777751e+01,0.000000000000000000e+00,1.000000009825046554e+00,0.000000000000000000e+00,-6.329798381593102732e-10,0.000000000000000000e+00 +3.001324785945768170e+01,1.694799999999999898e+02,0.000000000000000000e+00,1.032954703983650546e+01,0.000000000000000000e+00,1.000000009824433711e+00,0.000000000000000000e+00,-2.438118263580470055e-10,0.000000000000000000e+00 +3.001421595611878601e+01,1.694900000000000091e+02,0.000000000000000000e+00,1.033051513650712216e+01,0.000000000000000000e+00,1.000000009824197678e+00,0.000000000000000000e+00,1.527235444306649835e-09,0.000000000000000000e+00 +3.001518396205729644e+01,1.695000000000000000e+02,0.000000000000000000e+00,1.033148314245514143e+01,0.000000000000000000e+00,1.000000009825676051e+00,0.000000000000000000e+00,-2.911608377599087861e-09,0.000000000000000000e+00 +3.001615187729871082e+01,1.695099999999999909e+02,0.000000000000000000e+00,1.033245105770606642e+01,0.000000000000000000e+00,1.000000009822857860e+00,0.000000000000000000e+00,1.598873287570547644e-09,0.000000000000000000e+00 +3.001711970186851985e+01,1.695200000000000102e+02,0.000000000000000000e+00,1.033341888228538252e+01,0.000000000000000000e+00,1.000000009824405289e+00,0.000000000000000000e+00,-2.015012259809050929e-09,0.000000000000000000e+00 +3.001808743579220007e+01,1.695300000000000011e+02,0.000000000000000000e+00,1.033438661621857158e+01,0.000000000000000000e+00,1.000000009822455294e+00,0.000000000000000000e+00,1.410778358945913919e-09,0.000000000000000000e+00 +3.001905507909522086e+01,1.695399999999999920e+02,0.000000000000000000e+00,1.033535425953109588e+01,0.000000000000000000e+00,1.000000009823820424e+00,0.000000000000000000e+00,-1.411139945825128597e-09,0.000000000000000000e+00 +3.002002263180303387e+01,1.695500000000000114e+02,0.000000000000000000e+00,1.033632181224841240e+01,0.000000000000000000e+00,1.000000009822455072e+00,0.000000000000000000e+00,8.950985523396861462e-10,0.000000000000000000e+00 +3.002099009394108009e+01,1.695600000000000023e+02,0.000000000000000000e+00,1.033728927439596035e+01,0.000000000000000000e+00,1.000000009823321045e+00,0.000000000000000000e+00,-1.167639108486989753e-09,0.000000000000000000e+00 +3.002195746553478983e+01,1.695699999999999932e+02,0.000000000000000000e+00,1.033825664599917182e+01,0.000000000000000000e+00,1.000000009822191505e+00,0.000000000000000000e+00,-1.492110173173402293e-11,0.000000000000000000e+00 +3.002292474660957922e+01,1.695800000000000125e+02,0.000000000000000000e+00,1.033922392708346294e+01,0.000000000000000000e+00,1.000000009822177072e+00,0.000000000000000000e+00,5.480000345492059228e-10,0.000000000000000000e+00 +3.002389193719085725e+01,1.695900000000000034e+02,0.000000000000000000e+00,1.034019111767424093e+01,0.000000000000000000e+00,1.000000009822707092e+00,0.000000000000000000e+00,-1.386314928819955287e-09,0.000000000000000000e+00 +3.002485903730401873e+01,1.695999999999999943e+02,0.000000000000000000e+00,1.034115821779690059e+01,0.000000000000000000e+00,1.000000009821366387e+00,0.000000000000000000e+00,-1.290463495707129942e-10,0.000000000000000000e+00 +3.002582604697444424e+01,1.696100000000000136e+02,0.000000000000000000e+00,1.034212522747682250e+01,0.000000000000000000e+00,1.000000009821241598e+00,0.000000000000000000e+00,5.134779714452569179e-10,0.000000000000000000e+00 +3.002679296622750371e+01,1.696200000000000045e+02,0.000000000000000000e+00,1.034309214673937838e+01,0.000000000000000000e+00,1.000000009821738089e+00,0.000000000000000000e+00,-1.367412197732204129e-09,0.000000000000000000e+00 +3.002775979508855642e+01,1.696299999999999955e+02,0.000000000000000000e+00,1.034405897560992749e+01,0.000000000000000000e+00,1.000000009820416036e+00,0.000000000000000000e+00,-7.993011860190645694e-11,0.000000000000000000e+00 +3.002872653358295096e+01,1.696400000000000148e+02,0.000000000000000000e+00,1.034502571411381489e+01,0.000000000000000000e+00,1.000000009820338764e+00,0.000000000000000000e+00,5.678325268940598353e-10,0.000000000000000000e+00 +3.002969318173602176e+01,1.696500000000000057e+02,0.000000000000000000e+00,1.034599236227637675e+01,0.000000000000000000e+00,1.000000009820887659e+00,0.000000000000000000e+00,5.674261312998451605e-10,0.000000000000000000e+00 +3.003065973957308898e+01,1.696599999999999966e+02,0.000000000000000000e+00,1.034695892012293683e+01,0.000000000000000000e+00,1.000000009821436109e+00,0.000000000000000000e+00,-1.992839708212431746e-09,0.000000000000000000e+00 +3.003162620711946573e+01,1.696700000000000159e+02,0.000000000000000000e+00,1.034792538767880643e+01,0.000000000000000000e+00,1.000000009819510094e+00,0.000000000000000000e+00,4.871126129541784993e-10,0.000000000000000000e+00 +3.003259258440045087e+01,1.696800000000000068e+02,0.000000000000000000e+00,1.034889176496928265e+01,0.000000000000000000e+00,1.000000009819980828e+00,0.000000000000000000e+00,-1.510879496062168131e-09,0.000000000000000000e+00 +3.003355887144133618e+01,1.696899999999999977e+02,0.000000000000000000e+00,1.034985805201965547e+01,0.000000000000000000e+00,1.000000009818520885e+00,0.000000000000000000e+00,1.516306267817528455e-09,0.000000000000000000e+00 +3.003452506826739210e+01,1.697000000000000171e+02,0.000000000000000000e+00,1.035082424885519892e+01,0.000000000000000000e+00,1.000000009819985936e+00,0.000000000000000000e+00,-1.855453660959583284e-09,0.000000000000000000e+00 +3.003549117490388554e+01,1.697100000000000080e+02,0.000000000000000000e+00,1.035179035550117987e+01,0.000000000000000000e+00,1.000000009818193369e+00,0.000000000000000000e+00,-2.174437002967292449e-10,0.000000000000000000e+00 +3.003645719137606918e+01,1.697199999999999989e+02,0.000000000000000000e+00,1.035275637198284748e+01,0.000000000000000000e+00,1.000000009817983315e+00,0.000000000000000000e+00,7.139991107547310484e-10,0.000000000000000000e+00 +3.003742311770918150e+01,1.697299999999999898e+02,0.000000000000000000e+00,1.035372229832544377e+01,0.000000000000000000e+00,1.000000009818672986e+00,0.000000000000000000e+00,-9.743111895122608575e-10,0.000000000000000000e+00 +3.003838895392845387e+01,1.697400000000000091e+02,0.000000000000000000e+00,1.035468813455419834e+01,0.000000000000000000e+00,1.000000009817731961e+00,0.000000000000000000e+00,4.212139229076881509e-10,0.000000000000000000e+00 +3.003935470005909991e+01,1.697500000000000000e+02,0.000000000000000000e+00,1.035565388069432657e+01,0.000000000000000000e+00,1.000000009818138746e+00,0.000000000000000000e+00,-8.197421871231130196e-10,0.000000000000000000e+00 +3.004032035612632612e+01,1.697599999999999909e+02,0.000000000000000000e+00,1.035661953677103497e+01,0.000000000000000000e+00,1.000000009817347157e+00,0.000000000000000000e+00,1.008158446707079681e-09,0.000000000000000000e+00 +3.004128592215532834e+01,1.697700000000000102e+02,0.000000000000000000e+00,1.035758510280951583e+01,0.000000000000000000e+00,1.000000009818320601e+00,0.000000000000000000e+00,-1.724194465330407323e-09,0.000000000000000000e+00 +3.004225139817128465e+01,1.697800000000000011e+02,0.000000000000000000e+00,1.035855057883495256e+01,0.000000000000000000e+00,1.000000009816655933e+00,0.000000000000000000e+00,5.030231812400041084e-10,0.000000000000000000e+00 +3.004321678419936958e+01,1.697899999999999920e+02,0.000000000000000000e+00,1.035951596487251258e+01,0.000000000000000000e+00,1.000000009817141544e+00,0.000000000000000000e+00,5.865700305568412134e-11,0.000000000000000000e+00 +3.004418208026473636e+01,1.698000000000000114e+02,0.000000000000000000e+00,1.036048126094735622e+01,0.000000000000000000e+00,1.000000009817198166e+00,0.000000000000000000e+00,-1.160366635671172072e-09,0.000000000000000000e+00 +3.004514728639253462e+01,1.698100000000000023e+02,0.000000000000000000e+00,1.036144646708462957e+01,0.000000000000000000e+00,1.000000009816078173e+00,0.000000000000000000e+00,-1.255723854173227591e-09,0.000000000000000000e+00 +3.004611240260789629e+01,1.698199999999999932e+02,0.000000000000000000e+00,1.036241158330946632e+01,0.000000000000000000e+00,1.000000009814866253e+00,0.000000000000000000e+00,1.672997176843507696e-09,0.000000000000000000e+00 +3.004707742893594613e+01,1.698300000000000125e+02,0.000000000000000000e+00,1.036337660964698948e+01,0.000000000000000000e+00,1.000000009816480739e+00,0.000000000000000000e+00,-1.920064428137957061e-09,0.000000000000000000e+00 +3.004804236540179829e+01,1.698400000000000034e+02,0.000000000000000000e+00,1.036434154612231318e+01,0.000000000000000000e+00,1.000000009814627999e+00,0.000000000000000000e+00,1.309926213733452311e-09,0.000000000000000000e+00 +3.004900721203054914e+01,1.698499999999999943e+02,0.000000000000000000e+00,1.036530639276053378e+01,0.000000000000000000e+00,1.000000009815891877e+00,0.000000000000000000e+00,-1.999825799330252140e-09,0.000000000000000000e+00 +3.004997196884728794e+01,1.698600000000000136e+02,0.000000000000000000e+00,1.036627114958674234e+01,0.000000000000000000e+00,1.000000009813962532e+00,0.000000000000000000e+00,1.499836317602359101e-09,0.000000000000000000e+00 +3.005093663587708974e+01,1.698700000000000045e+02,0.000000000000000000e+00,1.036723581662601212e+01,0.000000000000000000e+00,1.000000009815409374e+00,0.000000000000000000e+00,-1.559597399173134615e-09,0.000000000000000000e+00 +3.005190121314502250e+01,1.698799999999999955e+02,0.000000000000000000e+00,1.036820039390341108e+01,0.000000000000000000e+00,1.000000009813905022e+00,0.000000000000000000e+00,2.675159839807986362e-10,0.000000000000000000e+00 +3.005286570067613638e+01,1.698900000000000148e+02,0.000000000000000000e+00,1.036916488144398940e+01,0.000000000000000000e+00,1.000000009814163038e+00,0.000000000000000000e+00,-6.637868555526398744e-10,0.000000000000000000e+00 +3.005383009849547093e+01,1.699000000000000057e+02,0.000000000000000000e+00,1.037012927927279016e+01,0.000000000000000000e+00,1.000000009813522883e+00,0.000000000000000000e+00,1.367302441497782486e-09,0.000000000000000000e+00 +3.005479440662805857e+01,1.699099999999999966e+02,0.000000000000000000e+00,1.037109358741484222e+01,0.000000000000000000e+00,1.000000009814841384e+00,0.000000000000000000e+00,-3.198882514938263123e-09,0.000000000000000000e+00 +3.005575862509891749e+01,1.699200000000000159e+02,0.000000000000000000e+00,1.037205780589516557e+01,0.000000000000000000e+00,1.000000009811756962e+00,0.000000000000000000e+00,2.824932755432165530e-09,0.000000000000000000e+00 +3.005672275393305526e+01,1.699300000000000068e+02,0.000000000000000000e+00,1.037302193473876244e+01,0.000000000000000000e+00,1.000000009814480562e+00,0.000000000000000000e+00,-3.499593843079756844e-09,0.000000000000000000e+00 +3.005768679315546521e+01,1.699399999999999977e+02,0.000000000000000000e+00,1.037398597397063327e+01,0.000000000000000000e+00,1.000000009811106816e+00,0.000000000000000000e+00,2.664674475447543425e-09,0.000000000000000000e+00 +3.005865074279113003e+01,1.699500000000000171e+02,0.000000000000000000e+00,1.037494992361575541e+01,0.000000000000000000e+00,1.000000009813675428e+00,0.000000000000000000e+00,-1.628256331101333402e-09,0.000000000000000000e+00 +3.005961460286502174e+01,1.699600000000000080e+02,0.000000000000000000e+00,1.037591378369910622e+01,0.000000000000000000e+00,1.000000009812106017e+00,0.000000000000000000e+00,-1.093207988659467100e-09,0.000000000000000000e+00 +3.006057837340210170e+01,1.699699999999999989e+02,0.000000000000000000e+00,1.037687755424564173e+01,0.000000000000000000e+00,1.000000009811052415e+00,0.000000000000000000e+00,4.389367034471446827e-10,0.000000000000000000e+00 +3.006154205442731708e+01,1.699799999999999898e+02,0.000000000000000000e+00,1.037784123528031088e+01,0.000000000000000000e+00,1.000000009811475410e+00,0.000000000000000000e+00,1.048245929597738386e-09,0.000000000000000000e+00 +3.006250564596560437e+01,1.699900000000000091e+02,0.000000000000000000e+00,1.037880482682805194e+01,0.000000000000000000e+00,1.000000009812485491e+00,0.000000000000000000e+00,-3.101934552976039571e-09,0.000000000000000000e+00 +3.006346914804188941e+01,1.700000000000000000e+02,0.000000000000000000e+00,1.037976832891379075e+01,0.000000000000000000e+00,1.000000009809496770e+00,0.000000000000000000e+00,1.375026711387665149e-09,0.000000000000000000e+00 +3.006443256068108383e+01,1.700099999999999909e+02,0.000000000000000000e+00,1.038073174156243716e+01,0.000000000000000000e+00,1.000000009810821489e+00,0.000000000000000000e+00,-8.376317228461859457e-10,0.000000000000000000e+00 +3.006539588390809215e+01,1.700200000000000102e+02,0.000000000000000000e+00,1.038169506479889748e+01,0.000000000000000000e+00,1.000000009810014578e+00,0.000000000000000000e+00,1.735354092598087068e-09,0.000000000000000000e+00 +3.006635911774780467e+01,1.700300000000000011e+02,0.000000000000000000e+00,1.038265829864806022e+01,0.000000000000000000e+00,1.000000009811686130e+00,0.000000000000000000e+00,-2.400626827632695893e-09,0.000000000000000000e+00 +3.006732226222510107e+01,1.700399999999999920e+02,0.000000000000000000e+00,1.038362144313480684e+01,0.000000000000000000e+00,1.000000009809373980e+00,0.000000000000000000e+00,1.489435120186640797e-10,0.000000000000000000e+00 +3.006828531736484678e+01,1.700500000000000114e+02,0.000000000000000000e+00,1.038458449828400099e+01,0.000000000000000000e+00,1.000000009809517421e+00,0.000000000000000000e+00,-1.976105704632888775e-10,0.000000000000000000e+00 +3.006924828319190013e+01,1.700600000000000023e+02,0.000000000000000000e+00,1.038554746412050100e+01,0.000000000000000000e+00,1.000000009809327128e+00,0.000000000000000000e+00,-1.534910063964690619e-09,0.000000000000000000e+00 +3.007021115973110525e+01,1.700699999999999932e+02,0.000000000000000000e+00,1.038651034066915102e+01,0.000000000000000000e+00,1.000000009807849199e+00,0.000000000000000000e+00,1.878455762599489808e-09,0.000000000000000000e+00 +3.007117394700729562e+01,1.700800000000000125e+02,0.000000000000000000e+00,1.038747312795478273e+01,0.000000000000000000e+00,1.000000009809657753e+00,0.000000000000000000e+00,-1.463924358249912917e-09,0.000000000000000000e+00 +3.007213664504529049e+01,1.700900000000000034e+02,0.000000000000000000e+00,1.038843582600222071e+01,0.000000000000000000e+00,1.000000009808248436e+00,0.000000000000000000e+00,-7.104624076623009709e-11,0.000000000000000000e+00 +3.007309925386989846e+01,1.700999999999999943e+02,0.000000000000000000e+00,1.038939843483627179e+01,0.000000000000000000e+00,1.000000009808180046e+00,0.000000000000000000e+00,2.994369012391801949e-10,0.000000000000000000e+00 +3.007406177350592102e+01,1.701100000000000136e+02,0.000000000000000000e+00,1.039036095448173569e+01,0.000000000000000000e+00,1.000000009808468260e+00,0.000000000000000000e+00,-2.279668822407688633e-09,0.000000000000000000e+00 +3.007502420397814547e+01,1.701200000000000045e+02,0.000000000000000000e+00,1.039132338496339969e+01,0.000000000000000000e+00,1.000000009806274237e+00,0.000000000000000000e+00,1.773650179175715292e-09,0.000000000000000000e+00 +3.007598654531134486e+01,1.701299999999999955e+02,0.000000000000000000e+00,1.039228572630603686e+01,0.000000000000000000e+00,1.000000009807981094e+00,0.000000000000000000e+00,-9.744787781638206230e-10,0.000000000000000000e+00 +3.007694879753028516e+01,1.701400000000000148e+02,0.000000000000000000e+00,1.039324797853441495e+01,0.000000000000000000e+00,1.000000009807043400e+00,0.000000000000000000e+00,-9.424910794993867491e-10,0.000000000000000000e+00 +3.007791096065971814e+01,1.701500000000000057e+02,0.000000000000000000e+00,1.039421014167328394e+01,0.000000000000000000e+00,1.000000009806136569e+00,0.000000000000000000e+00,-5.492988316909122837e-11,0.000000000000000000e+00 +3.007887303472438489e+01,1.701599999999999966e+02,0.000000000000000000e+00,1.039517221574738493e+01,0.000000000000000000e+00,1.000000009806083723e+00,0.000000000000000000e+00,-2.400519584084222048e-10,0.000000000000000000e+00 +3.007983501974901586e+01,1.701700000000000159e+02,0.000000000000000000e+00,1.039613420078144834e+01,0.000000000000000000e+00,1.000000009805852796e+00,0.000000000000000000e+00,4.148204703914140547e-10,0.000000000000000000e+00 +3.008079691575832726e+01,1.701800000000000068e+02,0.000000000000000000e+00,1.039709609680019220e+01,0.000000000000000000e+00,1.000000009806251811e+00,0.000000000000000000e+00,-1.939932625681084748e-09,0.000000000000000000e+00 +3.008175872277702823e+01,1.701899999999999977e+02,0.000000000000000000e+00,1.039805790382832384e+01,0.000000000000000000e+00,1.000000009804385970e+00,0.000000000000000000e+00,2.290361997969213854e-09,0.000000000000000000e+00 +3.008272044082981012e+01,1.702000000000000171e+02,0.000000000000000000e+00,1.039901962189053641e+01,0.000000000000000000e+00,1.000000009806588652e+00,0.000000000000000000e+00,-2.267021562645716733e-09,0.000000000000000000e+00 +3.008368206994136074e+01,1.702100000000000080e+02,0.000000000000000000e+00,1.039998125101151771e+01,0.000000000000000000e+00,1.000000009804408618e+00,0.000000000000000000e+00,-2.542494960647552599e-10,0.000000000000000000e+00 +3.008464361013635013e+01,1.702199999999999989e+02,0.000000000000000000e+00,1.040094279121593601e+01,0.000000000000000000e+00,1.000000009804164147e+00,0.000000000000000000e+00,6.378765069334416407e-10,0.000000000000000000e+00 +3.008560506143944124e+01,1.702299999999999898e+02,0.000000000000000000e+00,1.040190424252845425e+01,0.000000000000000000e+00,1.000000009804777434e+00,0.000000000000000000e+00,-1.521621609818556589e-09,0.000000000000000000e+00 +3.008656642387528279e+01,1.702400000000000091e+02,0.000000000000000000e+00,1.040286560497372292e+01,0.000000000000000000e+00,1.000000009803314605e+00,0.000000000000000000e+00,9.470590751712807221e-10,0.000000000000000000e+00 +3.008752769746851286e+01,1.702500000000000000e+02,0.000000000000000000e+00,1.040382687857637833e+01,0.000000000000000000e+00,1.000000009804224987e+00,0.000000000000000000e+00,-1.574804460863336466e-09,0.000000000000000000e+00 +3.008848888224375884e+01,1.702599999999999909e+02,0.000000000000000000e+00,1.040478806336104967e+01,0.000000000000000000e+00,1.000000009802711309e+00,0.000000000000000000e+00,5.175132602881216378e-10,0.000000000000000000e+00 +3.008944997822563749e+01,1.702700000000000102e+02,0.000000000000000000e+00,1.040574915935235012e+01,0.000000000000000000e+00,1.000000009803208689e+00,0.000000000000000000e+00,-4.752781728353868037e-10,0.000000000000000000e+00 +3.009041098543875137e+01,1.702800000000000011e+02,0.000000000000000000e+00,1.040671016657488579e+01,0.000000000000000000e+00,1.000000009802751944e+00,0.000000000000000000e+00,-7.156404665727405485e-10,0.000000000000000000e+00 +3.009137190390769589e+01,1.702899999999999920e+02,0.000000000000000000e+00,1.040767108505324856e+01,0.000000000000000000e+00,1.000000009802064271e+00,0.000000000000000000e+00,-2.105291132200262115e-10,0.000000000000000000e+00 +3.009233273365704875e+01,1.703000000000000114e+02,0.000000000000000000e+00,1.040863191481201966e+01,0.000000000000000000e+00,1.000000009801861989e+00,0.000000000000000000e+00,-8.921156966751196010e-10,0.000000000000000000e+00 +3.009329347471138050e+01,1.703100000000000023e+02,0.000000000000000000e+00,1.040959265587576965e+01,0.000000000000000000e+00,1.000000009801004897e+00,0.000000000000000000e+00,1.080345503580456565e-09,0.000000000000000000e+00 +3.009425412709525105e+01,1.703199999999999932e+02,0.000000000000000000e+00,1.041055330826905667e+01,0.000000000000000000e+00,1.000000009802042733e+00,0.000000000000000000e+00,-7.443375172361568271e-11,0.000000000000000000e+00 +3.009521469083320966e+01,1.703300000000000125e+02,0.000000000000000000e+00,1.041151387201642997e+01,0.000000000000000000e+00,1.000000009801971235e+00,0.000000000000000000e+00,-2.441744795605716492e-09,0.000000000000000000e+00 +3.009617516594979136e+01,1.703400000000000034e+02,0.000000000000000000e+00,1.041247434714242459e+01,0.000000000000000000e+00,1.000000009799626000e+00,0.000000000000000000e+00,1.674837250458243512e-09,0.000000000000000000e+00 +3.009713555246951699e+01,1.703499999999999943e+02,0.000000000000000000e+00,1.041343473367156314e+01,0.000000000000000000e+00,1.000000009801234491e+00,0.000000000000000000e+00,-1.214160900409252934e-09,0.000000000000000000e+00 +3.009809585041690383e+01,1.703600000000000136e+02,0.000000000000000000e+00,1.041439503162836289e+01,0.000000000000000000e+00,1.000000009800068534e+00,0.000000000000000000e+00,-1.486449436056849415e-09,0.000000000000000000e+00 +3.009905605981645493e+01,1.703700000000000045e+02,0.000000000000000000e+00,1.041535524103732335e+01,0.000000000000000000e+00,1.000000009798641232e+00,0.000000000000000000e+00,8.508325584472300751e-10,0.000000000000000000e+00 +3.010001618069265916e+01,1.703799999999999955e+02,0.000000000000000000e+00,1.041631536192293517e+01,0.000000000000000000e+00,1.000000009799458134e+00,0.000000000000000000e+00,9.945412506044664288e-12,0.000000000000000000e+00 +3.010097621306999471e+01,1.703900000000000148e+02,0.000000000000000000e+00,1.041727539430968008e+01,0.000000000000000000e+00,1.000000009799467682e+00,0.000000000000000000e+00,-1.639987757721242461e-10,0.000000000000000000e+00 +3.010193615697293268e+01,1.704000000000000057e+02,0.000000000000000000e+00,1.041823533822202563e+01,0.000000000000000000e+00,1.000000009799310252e+00,0.000000000000000000e+00,-1.606133180970814958e-09,0.000000000000000000e+00 +3.010289601242592994e+01,1.704099999999999966e+02,0.000000000000000000e+00,1.041919519368442870e+01,0.000000000000000000e+00,1.000000009797768596e+00,0.000000000000000000e+00,1.459372251527954576e-09,0.000000000000000000e+00 +3.010385577945343272e+01,1.704200000000000159e+02,0.000000000000000000e+00,1.042015496072133374e+01,0.000000000000000000e+00,1.000000009799169254e+00,0.000000000000000000e+00,-6.156859988610701495e-10,0.000000000000000000e+00 +3.010481545807987303e+01,1.704300000000000068e+02,0.000000000000000000e+00,1.042111463935717808e+01,0.000000000000000000e+00,1.000000009798578393e+00,0.000000000000000000e+00,-2.055252417737972807e-09,0.000000000000000000e+00 +3.010577504832967577e+01,1.704399999999999977e+02,0.000000000000000000e+00,1.042207422961638308e+01,0.000000000000000000e+00,1.000000009796606193e+00,0.000000000000000000e+00,9.923141041444661636e-10,0.000000000000000000e+00 +3.010673455022725165e+01,1.704500000000000171e+02,0.000000000000000000e+00,1.042303373152335944e+01,0.000000000000000000e+00,1.000000009797558320e+00,0.000000000000000000e+00,-1.127796597748827472e-09,0.000000000000000000e+00 +3.010769396379700424e+01,1.704600000000000080e+02,0.000000000000000000e+00,1.042399314510251074e+01,0.000000000000000000e+00,1.000000009796476297e+00,0.000000000000000000e+00,1.225344708148339161e-09,0.000000000000000000e+00 +3.010865328906331939e+01,1.704699999999999989e+02,0.000000000000000000e+00,1.042495247037822459e+01,0.000000000000000000e+00,1.000000009797651801e+00,0.000000000000000000e+00,-1.607168731473063368e-09,0.000000000000000000e+00 +3.010961252605057936e+01,1.704799999999999898e+02,0.000000000000000000e+00,1.042591170737488149e+01,0.000000000000000000e+00,1.000000009796110145e+00,0.000000000000000000e+00,-1.912435912179686100e-09,0.000000000000000000e+00 +3.011057167478314867e+01,1.704900000000000091e+02,0.000000000000000000e+00,1.042687085611684594e+01,0.000000000000000000e+00,1.000000009794275835e+00,0.000000000000000000e+00,2.234891924281965576e-09,0.000000000000000000e+00 +3.011153073528538471e+01,1.705000000000000000e+02,0.000000000000000000e+00,1.042782991662847358e+01,0.000000000000000000e+00,1.000000009796419231e+00,0.000000000000000000e+00,-7.601600597049457588e-10,0.000000000000000000e+00 +3.011248970758163068e+01,1.705099999999999909e+02,0.000000000000000000e+00,1.042878888893411293e+01,0.000000000000000000e+00,1.000000009795690259e+00,0.000000000000000000e+00,-1.250222841061693850e-09,0.000000000000000000e+00 +3.011344859169621913e+01,1.705200000000000102e+02,0.000000000000000000e+00,1.042974777305809475e+01,0.000000000000000000e+00,1.000000009794491440e+00,0.000000000000000000e+00,7.586787576960478096e-10,0.000000000000000000e+00 +3.011440738765347547e+01,1.705300000000000011e+02,0.000000000000000000e+00,1.043070656902474092e+01,0.000000000000000000e+00,1.000000009795218858e+00,0.000000000000000000e+00,-2.470796404771123881e-09,0.000000000000000000e+00 +3.011536609547770738e+01,1.705399999999999920e+02,0.000000000000000000e+00,1.043166527685836442e+01,0.000000000000000000e+00,1.000000009792850086e+00,0.000000000000000000e+00,2.582205660548831877e-09,0.000000000000000000e+00 +3.011632471519321896e+01,1.705500000000000114e+02,0.000000000000000000e+00,1.043262389658326228e+01,0.000000000000000000e+00,1.000000009795325440e+00,0.000000000000000000e+00,-3.419860541093082518e-09,0.000000000000000000e+00 +3.011728324682429658e+01,1.705600000000000023e+02,0.000000000000000000e+00,1.043358242822372794e+01,0.000000000000000000e+00,1.000000009792047395e+00,0.000000000000000000e+00,2.714501630396380097e-09,0.000000000000000000e+00 +3.011824169039521593e+01,1.705699999999999932e+02,0.000000000000000000e+00,1.043454087180403356e+01,0.000000000000000000e+00,1.000000009794649092e+00,0.000000000000000000e+00,-2.225414631988392698e-09,0.000000000000000000e+00 +3.011920004593024558e+01,1.705800000000000125e+02,0.000000000000000000e+00,1.043549922734845126e+01,0.000000000000000000e+00,1.000000009792516353e+00,0.000000000000000000e+00,-8.436729689703817587e-10,0.000000000000000000e+00 +3.012015831345364347e+01,1.705900000000000034e+02,0.000000000000000000e+00,1.043645749488123187e+01,0.000000000000000000e+00,1.000000009791707889e+00,0.000000000000000000e+00,1.051849286987447690e-09,0.000000000000000000e+00 +3.012111649298964977e+01,1.705999999999999943e+02,0.000000000000000000e+00,1.043741567442662088e+01,0.000000000000000000e+00,1.000000009792715749e+00,0.000000000000000000e+00,-4.173946883599364873e-10,0.000000000000000000e+00 +3.012207458456250109e+01,1.706100000000000136e+02,0.000000000000000000e+00,1.043837376600885314e+01,0.000000000000000000e+00,1.000000009792315847e+00,0.000000000000000000e+00,-1.389511855070481562e-09,0.000000000000000000e+00 +3.012303258819641627e+01,1.706200000000000045e+02,0.000000000000000000e+00,1.043933176965214926e+01,0.000000000000000000e+00,1.000000009790984690e+00,0.000000000000000000e+00,6.328132624833309048e-11,0.000000000000000000e+00 +3.012399050391560706e+01,1.706299999999999955e+02,0.000000000000000000e+00,1.044028968538071922e+01,0.000000000000000000e+00,1.000000009791045308e+00,0.000000000000000000e+00,6.259166995931750780e-11,0.000000000000000000e+00 +3.012494833174427455e+01,1.706400000000000148e+02,0.000000000000000000e+00,1.044124751321876410e+01,0.000000000000000000e+00,1.000000009791105260e+00,0.000000000000000000e+00,-1.400559140382163714e-09,0.000000000000000000e+00 +3.012590607170660562e+01,1.706500000000000057e+02,0.000000000000000000e+00,1.044220525319047255e+01,0.000000000000000000e+00,1.000000009789763888e+00,0.000000000000000000e+00,1.476506984506119213e-09,0.000000000000000000e+00 +3.012686372382678002e+01,1.706599999999999966e+02,0.000000000000000000e+00,1.044316290532002078e+01,0.000000000000000000e+00,1.000000009791177868e+00,0.000000000000000000e+00,-2.935661544553080033e-09,0.000000000000000000e+00 +3.012782128812895976e+01,1.706700000000000159e+02,0.000000000000000000e+00,1.044412046963157792e+01,0.000000000000000000e+00,1.000000009788366784e+00,0.000000000000000000e+00,8.524866778351221497e-10,0.000000000000000000e+00 +3.012877876463730331e+01,1.706800000000000068e+02,0.000000000000000000e+00,1.044507794614929530e+01,0.000000000000000000e+00,1.000000009789183020e+00,0.000000000000000000e+00,1.209732904230758565e-09,0.000000000000000000e+00 +3.012973615337595845e+01,1.706899999999999977e+02,0.000000000000000000e+00,1.044603533489732072e+01,0.000000000000000000e+00,1.000000009790341204e+00,0.000000000000000000e+00,-1.873680620330121535e-09,0.000000000000000000e+00 +3.013069345436905166e+01,1.707000000000000171e+02,0.000000000000000000e+00,1.044699263589978777e+01,0.000000000000000000e+00,1.000000009788547528e+00,0.000000000000000000e+00,-6.525311465563033607e-10,0.000000000000000000e+00 +3.013165066764070943e+01,1.707100000000000080e+02,0.000000000000000000e+00,1.044794984918081582e+01,0.000000000000000000e+00,1.000000009787922917e+00,0.000000000000000000e+00,-9.493075388633065011e-10,0.000000000000000000e+00 +3.013260779321504401e+01,1.707199999999999989e+02,0.000000000000000000e+00,1.044890697476451713e+01,0.000000000000000000e+00,1.000000009787014310e+00,0.000000000000000000e+00,1.106234847185243869e-09,0.000000000000000000e+00 +3.013356483111615347e+01,1.707299999999999898e+02,0.000000000000000000e+00,1.044986401267499154e+01,0.000000000000000000e+00,1.000000009788073019e+00,0.000000000000000000e+00,-3.113890812980155224e-10,0.000000000000000000e+00 +3.013452178136812520e+01,1.707400000000000091e+02,0.000000000000000000e+00,1.045082096293633001e+01,0.000000000000000000e+00,1.000000009787775035e+00,0.000000000000000000e+00,-1.331994788406166171e-09,0.000000000000000000e+00 +3.013547864399503950e+01,1.707500000000000000e+02,0.000000000000000000e+00,1.045177782557260926e+01,0.000000000000000000e+00,1.000000009786500499e+00,0.000000000000000000e+00,-2.251138051702168754e-11,0.000000000000000000e+00 +3.013643541902096246e+01,1.707599999999999909e+02,0.000000000000000000e+00,1.045273460060789539e+01,0.000000000000000000e+00,1.000000009786478961e+00,0.000000000000000000e+00,-2.710896843340919837e-10,0.000000000000000000e+00 +3.013739210646994948e+01,1.707700000000000102e+02,0.000000000000000000e+00,1.045369128806624559e+01,0.000000000000000000e+00,1.000000009786219612e+00,0.000000000000000000e+00,-1.443777537785618686e-10,0.000000000000000000e+00 +3.013834870636604535e+01,1.707800000000000011e+02,0.000000000000000000e+00,1.045464788797170463e+01,0.000000000000000000e+00,1.000000009786081501e+00,0.000000000000000000e+00,-1.592711277517674707e-09,0.000000000000000000e+00 +3.013930521873328772e+01,1.707899999999999920e+02,0.000000000000000000e+00,1.045560440034830663e+01,0.000000000000000000e+00,1.000000009784558053e+00,0.000000000000000000e+00,1.202362102978946033e-09,0.000000000000000000e+00 +3.014026164359569648e+01,1.708000000000000114e+02,0.000000000000000000e+00,1.045656082522007324e+01,0.000000000000000000e+00,1.000000009785708022e+00,0.000000000000000000e+00,-1.476911557701241236e-09,0.000000000000000000e+00 +3.014121798097728444e+01,1.708100000000000023e+02,0.000000000000000000e+00,1.045751716261101905e+01,0.000000000000000000e+00,1.000000009784295596e+00,0.000000000000000000e+00,7.267970385299024175e-11,0.000000000000000000e+00 +3.014217423090205017e+01,1.708199999999999932e+02,0.000000000000000000e+00,1.045847341254514262e+01,0.000000000000000000e+00,1.000000009784365096e+00,0.000000000000000000e+00,1.672018269845421622e-11,0.000000000000000000e+00 +3.014313039339398870e+01,1.708300000000000125e+02,0.000000000000000000e+00,1.045942957504643545e+01,0.000000000000000000e+00,1.000000009784381083e+00,0.000000000000000000e+00,-1.653823700296223224e-09,0.000000000000000000e+00 +3.014408646847707374e+01,1.708400000000000034e+02,0.000000000000000000e+00,1.046038565013887656e+01,0.000000000000000000e+00,1.000000009782799903e+00,0.000000000000000000e+00,8.837767717379747162e-10,0.000000000000000000e+00 +3.014504245617527900e+01,1.708499999999999943e+02,0.000000000000000000e+00,1.046134163784643256e+01,0.000000000000000000e+00,1.000000009783644783e+00,0.000000000000000000e+00,-1.516843559537788218e-10,0.000000000000000000e+00 +3.014599835651255688e+01,1.708600000000000136e+02,0.000000000000000000e+00,1.046229753819306296e+01,0.000000000000000000e+00,1.000000009783499788e+00,0.000000000000000000e+00,-8.813828968868726820e-10,0.000000000000000000e+00 +3.014695416951285623e+01,1.708700000000000045e+02,0.000000000000000000e+00,1.046325335120271305e+01,0.000000000000000000e+00,1.000000009782657351e+00,0.000000000000000000e+00,-1.312901891373708591e-09,0.000000000000000000e+00 +3.014790989520011166e+01,1.708799999999999955e+02,0.000000000000000000e+00,1.046420907689931745e+01,0.000000000000000000e+00,1.000000009781402577e+00,0.000000000000000000e+00,4.918894317595036239e-10,0.000000000000000000e+00 +3.014886553359824717e+01,1.708900000000000148e+02,0.000000000000000000e+00,1.046516471530680015e+01,0.000000000000000000e+00,1.000000009781872645e+00,0.000000000000000000e+00,-1.310353244346252702e-09,0.000000000000000000e+00 +3.014982108473117606e+01,1.709000000000000057e+02,0.000000000000000000e+00,1.046612026644907623e+01,0.000000000000000000e+00,1.000000009780620536e+00,0.000000000000000000e+00,1.054606485898410683e-09,0.000000000000000000e+00 +3.015077654862280099e+01,1.709099999999999966e+02,0.000000000000000000e+00,1.046707573035004657e+01,0.000000000000000000e+00,1.000000009781628174e+00,0.000000000000000000e+00,-2.150310699660065999e-09,0.000000000000000000e+00 +3.015173192529701396e+01,1.709200000000000159e+02,0.000000000000000000e+00,1.046803110703360495e+01,0.000000000000000000e+00,1.000000009779573817e+00,0.000000000000000000e+00,7.440307830644991575e-10,0.000000000000000000e+00 +3.015268721477769631e+01,1.709300000000000068e+02,0.000000000000000000e+00,1.046898639652362917e+01,0.000000000000000000e+00,1.000000009780284582e+00,0.000000000000000000e+00,-1.162290974190808188e-12,0.000000000000000000e+00 +3.015364241708871518e+01,1.709399999999999977e+02,0.000000000000000000e+00,1.046994159884399167e+01,0.000000000000000000e+00,1.000000009780283472e+00,0.000000000000000000e+00,-5.007606374876062827e-10,0.000000000000000000e+00 +3.015459753225393413e+01,1.709500000000000171e+02,0.000000000000000000e+00,1.047089671401855071e+01,0.000000000000000000e+00,1.000000009779805188e+00,0.000000000000000000e+00,-7.630670099214338175e-10,0.000000000000000000e+00 +3.015555256029719899e+01,1.709600000000000080e+02,0.000000000000000000e+00,1.047185174207115388e+01,0.000000000000000000e+00,1.000000009779076438e+00,0.000000000000000000e+00,-7.949920967340878785e-10,0.000000000000000000e+00 +3.015650750124234492e+01,1.709699999999999989e+02,0.000000000000000000e+00,1.047280668302563811e+01,0.000000000000000000e+00,1.000000009778317267e+00,0.000000000000000000e+00,-6.039142287543337851e-10,0.000000000000000000e+00 +3.015746235511319995e+01,1.709799999999999898e+02,0.000000000000000000e+00,1.047376153690582967e+01,0.000000000000000000e+00,1.000000009777740617e+00,0.000000000000000000e+00,-1.976795906160057112e-10,0.000000000000000000e+00 +3.015841712193357793e+01,1.709900000000000091e+02,0.000000000000000000e+00,1.047471630373554419e+01,0.000000000000000000e+00,1.000000009777551879e+00,0.000000000000000000e+00,4.165604949866254608e-10,0.000000000000000000e+00 +3.015937180172728560e+01,1.710000000000000000e+02,0.000000000000000000e+00,1.047567098353858661e+01,0.000000000000000000e+00,1.000000009777949561e+00,0.000000000000000000e+00,-7.182892502381389672e-10,0.000000000000000000e+00 +3.016032639451811548e+01,1.710099999999999909e+02,0.000000000000000000e+00,1.047662557633875124e+01,0.000000000000000000e+00,1.000000009777263887e+00,0.000000000000000000e+00,-1.660962625550570206e-09,0.000000000000000000e+00 +3.016128090032985298e+01,1.710200000000000102e+02,0.000000000000000000e+00,1.047758008215981995e+01,0.000000000000000000e+00,1.000000009775678489e+00,0.000000000000000000e+00,1.481508914728951329e-09,0.000000000000000000e+00 +3.016223531918626577e+01,1.710300000000000011e+02,0.000000000000000000e+00,1.047853450102556394e+01,0.000000000000000000e+00,1.000000009777092469e+00,0.000000000000000000e+00,-1.049109955911215354e-09,0.000000000000000000e+00 +3.016318965111111794e+01,1.710399999999999920e+02,0.000000000000000000e+00,1.047948883295974731e+01,0.000000000000000000e+00,1.000000009776091270e+00,0.000000000000000000e+00,-1.459673125684546292e-09,0.000000000000000000e+00 +3.016414389612815938e+01,1.710500000000000114e+02,0.000000000000000000e+00,1.048044307798611818e+01,0.000000000000000000e+00,1.000000009774698384e+00,0.000000000000000000e+00,2.431846505611788339e-10,0.000000000000000000e+00 +3.016509805426112933e+01,1.710600000000000023e+02,0.000000000000000000e+00,1.048139723612841578e+01,0.000000000000000000e+00,1.000000009774930421e+00,0.000000000000000000e+00,1.501132821891199645e-10,0.000000000000000000e+00 +3.016605212553375637e+01,1.710699999999999932e+02,0.000000000000000000e+00,1.048235130741037047e+01,0.000000000000000000e+00,1.000000009775073639e+00,0.000000000000000000e+00,-1.747524205698282294e-09,0.000000000000000000e+00 +3.016700610996976195e+01,1.710800000000000125e+02,0.000000000000000000e+00,1.048330529185570015e+01,0.000000000000000000e+00,1.000000009773406529e+00,0.000000000000000000e+00,3.982799724325825833e-10,0.000000000000000000e+00 +3.016796000759284979e+01,1.710900000000000034e+02,0.000000000000000000e+00,1.048425918948811031e+01,0.000000000000000000e+00,1.000000009773786447e+00,0.000000000000000000e+00,7.249308512605962254e-10,0.000000000000000000e+00 +3.016891381842671649e+01,1.710999999999999943e+02,0.000000000000000000e+00,1.048521300033129933e+01,0.000000000000000000e+00,1.000000009774477894e+00,0.000000000000000000e+00,-2.729796886955171145e-09,0.000000000000000000e+00 +3.016986754249504799e+01,1.711100000000000136e+02,0.000000000000000000e+00,1.048616672440895314e+01,0.000000000000000000e+00,1.000000009771874421e+00,0.000000000000000000e+00,1.745133362250796938e-09,0.000000000000000000e+00 +3.017082117982151956e+01,1.711200000000000045e+02,0.000000000000000000e+00,1.048712036174474349e+01,0.000000000000000000e+00,1.000000009773538645e+00,0.000000000000000000e+00,-1.483556473773090257e-09,0.000000000000000000e+00 +3.017177473042979585e+01,1.711299999999999955e+02,0.000000000000000000e+00,1.048807391236233855e+01,0.000000000000000000e+00,1.000000009772123999e+00,0.000000000000000000e+00,-7.030708269222674347e-10,0.000000000000000000e+00 +3.017272819434352726e+01,1.711400000000000148e+02,0.000000000000000000e+00,1.048902737628538873e+01,0.000000000000000000e+00,1.000000009771453646e+00,0.000000000000000000e+00,1.728141699342823992e-10,0.000000000000000000e+00 +3.017368157158636066e+01,1.711500000000000057e+02,0.000000000000000000e+00,1.048998075353753734e+01,0.000000000000000000e+00,1.000000009771618403e+00,0.000000000000000000e+00,-8.189620610429933868e-10,0.000000000000000000e+00 +3.017463486218192514e+01,1.711599999999999966e+02,0.000000000000000000e+00,1.049093404414241704e+01,0.000000000000000000e+00,1.000000009770837694e+00,0.000000000000000000e+00,-1.731484128300277735e-09,0.000000000000000000e+00 +3.017558806615384270e+01,1.711700000000000159e+02,0.000000000000000000e+00,1.049188724812364804e+01,0.000000000000000000e+00,1.000000009769187237e+00,0.000000000000000000e+00,1.339325534687471136e-09,0.000000000000000000e+00 +3.017654118352572468e+01,1.711800000000000068e+02,0.000000000000000000e+00,1.049284036550483989e+01,0.000000000000000000e+00,1.000000009770463771e+00,0.000000000000000000e+00,-1.391403496038166191e-09,0.000000000000000000e+00 +3.017749421432116819e+01,1.711899999999999977e+02,0.000000000000000000e+00,1.049379339630959507e+01,0.000000000000000000e+00,1.000000009769137721e+00,0.000000000000000000e+00,-1.537859537839987888e-10,0.000000000000000000e+00 +3.017844715856376325e+01,1.712000000000000171e+02,0.000000000000000000e+00,1.049474634056150002e+01,0.000000000000000000e+00,1.000000009768991172e+00,0.000000000000000000e+00,1.133924858302487748e-09,0.000000000000000000e+00 +3.017940001627708924e+01,1.712100000000000080e+02,0.000000000000000000e+00,1.049569919828413411e+01,0.000000000000000000e+00,1.000000009770071641e+00,0.000000000000000000e+00,-1.448647118185912421e-09,0.000000000000000000e+00 +3.018035278748471129e+01,1.712199999999999989e+02,0.000000000000000000e+00,1.049665196950106605e+01,0.000000000000000000e+00,1.000000009768691411e+00,0.000000000000000000e+00,-2.041248902104671959e-09,0.000000000000000000e+00 +3.018130547221018745e+01,1.712299999999999898e+02,0.000000000000000000e+00,1.049760465423585032e+01,0.000000000000000000e+00,1.000000009766746745e+00,0.000000000000000000e+00,1.309053926105997092e-09,0.000000000000000000e+00 +3.018225807047706510e+01,1.712400000000000091e+02,0.000000000000000000e+00,1.049855725251203253e+01,0.000000000000000000e+00,1.000000009767993747e+00,0.000000000000000000e+00,-1.193081545077947024e-09,0.000000000000000000e+00 +3.018321058230888099e+01,1.712500000000000000e+02,0.000000000000000000e+00,1.049950976435315120e+01,0.000000000000000000e+00,1.000000009766857323e+00,0.000000000000000000e+00,-9.699544260888757208e-01,0.000000000000000000e+00 +3.018416300772915761e+01,1.712599999999999909e+02,0.000000000000000000e+00,1.050046218978272883e+01,0.000000000000000000e+00,9.990762005149416147e-01,0.000000000000000000e+00,-9.999997637742162881e-01,0.000000000000000000e+00 +3.018511534676140684e+01,1.712700000000000102e+02,0.000000000000000000e+00,1.050141364904467167e+01,0.000000000000000000e+00,9.981238617076582109e-01,0.000000000000000000e+00,-9.999998868351940295e-01,0.000000000000000000e+00 +3.018606759950891316e+01,1.712800000000000011e+02,0.000000000000000000e+00,1.050236411523433411e+01,0.000000000000000000e+00,9.971716090679136890e-01,0.000000000000000000e+00,-9.999999299878884473e-01,0.000000000000000000e+00 +3.018701976607734139e+01,1.712899999999999920e+02,0.000000000000000000e+00,1.050331358870347565e+01,0.000000000000000000e+00,9.962194425661473618e-01,0.000000000000000000e+00,-9.999999467995938085e-01,0.000000000000000000e+00 +3.018797184657227817e+01,1.713000000000000114e+02,0.000000000000000000e+00,1.050426206980341881e+01,0.000000000000000000e+00,9.952673621218625089e-01,0.000000000000000000e+00,-9.999999614826605709e-01,0.000000000000000000e+00 +3.018892384109921778e+01,1.713100000000000023e+02,0.000000000000000000e+00,1.050520955888500119e+01,0.000000000000000000e+00,9.943153676315904521e-01,0.000000000000000000e+00,-9.999999688606644455e-01,0.000000000000000000e+00 +3.018987574976357635e+01,1.713199999999999932e+02,0.000000000000000000e+00,1.050615605629855409e+01,0.000000000000000000e+00,9.933634589968741713e-01,0.000000000000000000e+00,-9.999999755169676208e-01,0.000000000000000000e+00 +3.019082757267068118e+01,1.713300000000000125e+02,0.000000000000000000e+00,1.050710156239390791e+01,0.000000000000000000e+00,9.924116361130731478e-01,0.000000000000000000e+00,-9.999999782336969067e-01,0.000000000000000000e+00 +3.019177930992577785e+01,1.713400000000000034e+02,0.000000000000000000e+00,1.050804607752038677e+01,0.000000000000000000e+00,9.914598988786936795e-01,0.000000000000000000e+00,-9.999999835951877136e-01,0.000000000000000000e+00 +3.019273096163402315e+01,1.713499999999999943e+02,0.000000000000000000e+00,1.050898960202681209e+01,0.000000000000000000e+00,9.905082471860593429e-01,0.000000000000000000e+00,-9.999999844580012009e-01,0.000000000000000000e+00 +3.019368252790049567e+01,1.713600000000000136e+02,0.000000000000000000e+00,1.050993213626149725e+01,0.000000000000000000e+00,9.895566809343759873e-01,0.000000000000000000e+00,-9.999999874061489269e-01,0.000000000000000000e+00 +3.019463400883018522e+01,1.713700000000000045e+02,0.000000000000000000e+00,1.051087368057225468e+01,0.000000000000000000e+00,9.886052000166677400e-01,0.000000000000000000e+00,-9.999999892153744740e-01,0.000000000000000000e+00 +3.019558540452800344e+01,1.713799999999999955e+02,0.000000000000000000e+00,1.051181423530639059e+01,0.000000000000000000e+00,9.876538043291106517e-01,0.000000000000000000e+00,-9.999999905823198088e-01,0.000000000000000000e+00 +3.019653671509877313e+01,1.713900000000000148e+02,0.000000000000000000e+00,1.051275380081070843e+01,0.000000000000000000e+00,9.867024937673014584e-01,0.000000000000000000e+00,-9.999999922037232647e-01,0.000000000000000000e+00 +3.019748794064723185e+01,1.714000000000000057e+02,0.000000000000000000e+00,1.051369237743150897e+01,0.000000000000000000e+00,9.857512682262575821e-01,0.000000000000000000e+00,-9.999999947746686102e-01,0.000000000000000000e+00 +3.019843908127803900e+01,1.714099999999999966e+02,0.000000000000000000e+00,1.051462996551459028e+01,0.000000000000000000e+00,9.848001276004187954e-01,0.000000000000000000e+00,-9.999999930982088614e-01,0.000000000000000000e+00 +3.019939013709577225e+01,1.714200000000000159e+02,0.000000000000000000e+00,1.051556656540524770e+01,0.000000000000000000e+00,9.838490717892509618e-01,0.000000000000000000e+00,-9.999999976855835637e-01,0.000000000000000000e+00 +3.020034110820491691e+01,1.714300000000000068e+02,0.000000000000000000e+00,1.051650217744827920e+01,0.000000000000000000e+00,9.828981006823060973e-01,0.000000000000000000e+00,-9.999999935148476959e-01,0.000000000000000000e+00 +3.020129199470988368e+01,1.714399999999999977e+02,0.000000000000000000e+00,1.051743680198797648e+01,0.000000000000000000e+00,9.819472141835049461e-01,0.000000000000000000e+00,-9.999999969906020469e-01,0.000000000000000000e+00 +3.020224279671499801e+01,1.714500000000000171e+02,0.000000000000000000e+00,1.051837043936813920e+01,0.000000000000000000e+00,9.809964121812513316e-01,0.000000000000000000e+00,-9.999999989797121458e-01,0.000000000000000000e+00 +3.020319351432450361e+01,1.714600000000000080e+02,0.000000000000000000e+00,1.051930308993206076e+01,0.000000000000000000e+00,9.800456945727167302e-01,0.000000000000000000e+00,-9.999999982028913159e-01,0.000000000000000000e+00 +3.020414414764255895e+01,1.714699999999999989e+02,0.000000000000000000e+00,1.052023475402253716e+01,0.000000000000000000e+00,9.790950612563709132e-01,0.000000000000000000e+00,-9.999999973108549822e-01,0.000000000000000000e+00 +3.020509469677324077e+01,1.714799999999999898e+02,0.000000000000000000e+00,1.052116543198186882e+01,0.000000000000000000e+00,9.781445121282457134e-01,0.000000000000000000e+00,-9.999999989542890377e-01,0.000000000000000000e+00 +3.020604516182054411e+01,1.714900000000000091e+02,0.000000000000000000e+00,1.052209512415185877e+01,0.000000000000000000e+00,9.771940470819358016e-01,0.000000000000000000e+00,-1.000000001852197284e+00,0.000000000000000000e+00 +3.020699554288838229e+01,1.715000000000000000e+02,0.000000000000000000e+00,1.052302383087381088e+01,0.000000000000000000e+00,9.762436660123360310e-01,0.000000000000000000e+00,-9.999999968517395699e-01,0.000000000000000000e+00 +3.020794584008058692e+01,1.715099999999999909e+02,0.000000000000000000e+00,1.052395155248853165e+01,0.000000000000000000e+00,9.752933688231214537e-01,0.000000000000000000e+00,-1.000000002336311145e+00,0.000000000000000000e+00 +3.020889605350090790e+01,1.715200000000000102e+02,0.000000000000000000e+00,1.052487828933633907e+01,0.000000000000000000e+00,9.743431554005788087e-01,0.000000000000000000e+00,-9.999999993140419319e-01,0.000000000000000000e+00 +3.020984618325301341e+01,1.715300000000000011e+02,0.000000000000000000e+00,1.052580404175704665e+01,0.000000000000000000e+00,9.733930256491238886e-01,0.000000000000000000e+00,-1.000000002235265750e+00,0.000000000000000000e+00 +3.021079622944048992e+01,1.715399999999999920e+02,0.000000000000000000e+00,1.052672881008998118e+01,0.000000000000000000e+00,9.724429794595234045e-01,0.000000000000000000e+00,-1.000000001938126992e+00,0.000000000000000000e+00 +3.021174619216684221e+01,1.715500000000000114e+02,0.000000000000000000e+00,1.052765259467397030e+01,0.000000000000000000e+00,9.714930167313303722e-01,0.000000000000000000e+00,-9.999999990965118268e-01,0.000000000000000000e+00 +3.021269607153549330e+01,1.715600000000000023e+02,0.000000000000000000e+00,1.052857539584735136e+01,0.000000000000000000e+00,9.705431373635381442e-01,0.000000000000000000e+00,-1.000000004230096273e+00,0.000000000000000000e+00 +3.021364586764978455e+01,1.715699999999999932e+02,0.000000000000000000e+00,1.052949721394797145e+01,0.000000000000000000e+00,9.695933412452290012e-01,0.000000000000000000e+00,-1.000000000290431235e+00,0.000000000000000000e+00 +3.021459558061297912e+01,1.715800000000000125e+02,0.000000000000000000e+00,1.053041804931317849e+01,0.000000000000000000e+00,9.686436282817593169e-01,0.000000000000000000e+00,-1.000000003703606977e+00,0.000000000000000000e+00 +3.021554521052825493e+01,1.715900000000000034e+02,0.000000000000000000e+00,1.053133790227983724e+01,0.000000000000000000e+00,9.676939983629653241e-01,0.000000000000000000e+00,-1.000000003323542330e+00,0.000000000000000000e+00 +3.021649475749871527e+01,1.715999999999999943e+02,0.000000000000000000e+00,1.053225677318431508e+01,0.000000000000000000e+00,9.667444513893495017e-01,0.000000000000000000e+00,-9.999999998173314530e-01,0.000000000000000000e+00 +3.021744422162737820e+01,1.716100000000000136e+02,0.000000000000000000e+00,1.053317466236249267e+01,0.000000000000000000e+00,9.657949872608605490e-01,0.000000000000000000e+00,-1.000000005677069481e+00,0.000000000000000000e+00 +3.021839360301718358e+01,1.716200000000000045e+02,0.000000000000000000e+00,1.053409157014976394e+01,0.000000000000000000e+00,9.648456058656670331e-01,0.000000000000000000e+00,-1.000000001862856092e+00,0.000000000000000000e+00 +3.021934290177098603e+01,1.716299999999999955e+02,0.000000000000000000e+00,1.053500749688102545e+01,0.000000000000000000e+00,9.638963071100946634e-01,0.000000000000000000e+00,-1.000000002835545354e+00,0.000000000000000000e+00 +3.022029211799156911e+01,1.716400000000000148e+02,0.000000000000000000e+00,1.053592244289069413e+01,0.000000000000000000e+00,9.629470908868204004e-01,0.000000000000000000e+00,-1.000000005319110041e+00,0.000000000000000000e+00 +3.022124125178162757e+01,1.716500000000000057e+02,0.000000000000000000e+00,1.053683640851269487e+01,0.000000000000000000e+00,9.619979570917117639e-01,0.000000000000000000e+00,-1.000000002088548667e+00,0.000000000000000000e+00 +3.022219030324378508e+01,1.716599999999999966e+02,0.000000000000000000e+00,1.053774939408046407e+01,0.000000000000000000e+00,9.610489056275733910e-01,0.000000000000000000e+00,-1.000000003665259873e+00,0.000000000000000000e+00 +3.022313927248057652e+01,1.716700000000000159e+02,0.000000000000000000e+00,1.053866139992695672e+01,0.000000000000000000e+00,9.600999363873037318e-01,0.000000000000000000e+00,-1.000000004794346253e+00,0.000000000000000000e+00 +3.022408815959446216e+01,1.716800000000000068e+02,0.000000000000000000e+00,1.053957242638463754e+01,0.000000000000000000e+00,9.591510492688682943e-01,0.000000000000000000e+00,-1.000000002188502490e+00,0.000000000000000000e+00 +3.022503696468782408e+01,1.716899999999999977e+02,0.000000000000000000e+00,1.054048247378548631e+01,0.000000000000000000e+00,9.582022441734309171e-01,0.000000000000000000e+00,-1.000000006371935646e+00,0.000000000000000000e+00 +3.022598568786295914e+01,1.717000000000000171e+02,0.000000000000000000e+00,1.054139154246100141e+01,0.000000000000000000e+00,9.572535209922492516e-01,0.000000000000000000e+00,-1.000000004187795888e+00,0.000000000000000000e+00 +3.022693432922209311e+01,1.717100000000000080e+02,0.000000000000000000e+00,1.054229963274219095e+01,0.000000000000000000e+00,9.563048796291429010e-01,0.000000000000000000e+00,-1.000000002211048900e+00,0.000000000000000000e+00 +3.022788288886736652e+01,1.717199999999999989e+02,0.000000000000000000e+00,1.054320674495958521e+01,0.000000000000000000e+00,9.553563199817721729e-01,0.000000000000000000e+00,-1.000000007020771742e+00,0.000000000000000000e+00 +3.022883136690084172e+01,1.717299999999999898e+02,0.000000000000000000e+00,1.054411287944323128e+01,0.000000000000000000e+00,9.544078419416361925e-01,0.000000000000000000e+00,-1.000000003474160959e+00,0.000000000000000000e+00 +3.022977976342450646e+01,1.717400000000000091e+02,0.000000000000000000e+00,1.054501803652268777e+01,0.000000000000000000e+00,9.534594454146758657e-01,0.000000000000000000e+00,-1.000000004070255244e+00,0.000000000000000000e+00 +3.023072807854026678e+01,1.717500000000000000e+02,0.000000000000000000e+00,1.054592221652703898e+01,0.000000000000000000e+00,9.525111302950556302e-01,0.000000000000000000e+00,-1.000000007486933518e+00,0.000000000000000000e+00 +3.023167631234995056e+01,1.717599999999999909e+02,0.000000000000000000e+00,1.054682541978488430e+01,0.000000000000000000e+00,9.515628964782730792e-01,0.000000000000000000e+00,-1.000000002519503273e+00,0.000000000000000000e+00 +3.023262446495530753e+01,1.717700000000000102e+02,0.000000000000000000e+00,1.054772764662433993e+01,0.000000000000000000e+00,9.506147438705285779e-01,0.000000000000000000e+00,-1.000000005622136534e+00,0.000000000000000000e+00 +3.023357253645800569e+01,1.717800000000000011e+02,0.000000000000000000e+00,1.054862889737304954e+01,0.000000000000000000e+00,9.496666723624989093e-01,0.000000000000000000e+00,-1.000000005586941132e+00,0.000000000000000000e+00 +3.023452052695964198e+01,1.717899999999999920e+02,0.000000000000000000e+00,1.054952917235817011e+01,0.000000000000000000e+00,9.487186818555658485e-01,0.000000000000000000e+00,-1.000000005035013073e+00,0.000000000000000000e+00 +3.023546843656173166e+01,1.718000000000000114e+02,0.000000000000000000e+00,1.055042847190638255e+01,0.000000000000000000e+00,9.477707722487037634e-01,0.000000000000000000e+00,-1.000000004610640536e+00,0.000000000000000000e+00 +3.023641626536571181e+01,1.718100000000000023e+02,0.000000000000000000e+00,1.055132679634388992e+01,0.000000000000000000e+00,9.468229434403540035e-01,0.000000000000000000e+00,-1.000000004957835920e+00,0.000000000000000000e+00 +3.023736401347294134e+01,1.718199999999999932e+02,0.000000000000000000e+00,1.055222414599641745e+01,0.000000000000000000e+00,9.458751953284252334e-01,0.000000000000000000e+00,-1.000000006719399703e+00,0.000000000000000000e+00 +3.023831168098470457e+01,1.718300000000000125e+02,0.000000000000000000e+00,1.055312052118921251e+01,0.000000000000000000e+00,9.449275278102946540e-01,0.000000000000000000e+00,-1.000000004602017434e+00,0.000000000000000000e+00 +3.023925926800220410e+01,1.718400000000000034e+02,0.000000000000000000e+00,1.055401592224704466e+01,0.000000000000000000e+00,9.439799407884330584e-01,0.000000000000000000e+00,-1.000000007158422521e+00,0.000000000000000000e+00 +3.024020677462657147e+01,1.718499999999999943e+02,0.000000000000000000e+00,1.055491034949421092e+01,0.000000000000000000e+00,9.430324341572837721e-01,0.000000000000000000e+00,-1.000000003155758321e+00,0.000000000000000000e+00 +3.024115420095885298e+01,1.718600000000000136e+02,0.000000000000000000e+00,1.055580380325452872e+01,0.000000000000000000e+00,9.420850078220106560e-01,0.000000000000000000e+00,-1.000000007083536646e+00,0.000000000000000000e+00 +3.024210154710002740e+01,1.718700000000000045e+02,0.000000000000000000e+00,1.055669628385134651e+01,0.000000000000000000e+00,9.411376616741263801e-01,0.000000000000000000e+00,-1.000000005724702046e+00,0.000000000000000000e+00 +3.024304881315098825e+01,1.718799999999999955e+02,0.000000000000000000e+00,1.055758779160753136e+01,0.000000000000000000e+00,9.401903956177424249e-01,0.000000000000000000e+00,-1.000000005651307422e+00,0.000000000000000000e+00 +3.024399599921255799e+01,1.718900000000000148e+02,0.000000000000000000e+00,1.055847832684548138e+01,0.000000000000000000e+00,9.392432095508207457e-01,0.000000000000000000e+00,-1.000000007498634380e+00,0.000000000000000000e+00 +3.024494310538547737e+01,1.719000000000000057e+02,0.000000000000000000e+00,1.055936788988712038e+01,0.000000000000000000e+00,9.382961033707984955e-01,0.000000000000000000e+00,-1.000000003977117080e+00,0.000000000000000000e+00 +3.024589013177041608e+01,1.719099999999999966e+02,0.000000000000000000e+00,1.056025648105389791e+01,0.000000000000000000e+00,9.373490769820931323e-01,0.000000000000000000e+00,-1.000000007601641538e+00,0.000000000000000000e+00 +3.024683707846796565e+01,1.719200000000000159e+02,0.000000000000000000e+00,1.056114410066679632e+01,0.000000000000000000e+00,9.364021302773462008e-01,0.000000000000000000e+00,-1.000000005137528181e+00,0.000000000000000000e+00 +3.024778394557863948e+01,1.719300000000000068e+02,0.000000000000000000e+00,1.056203074904632011e+01,0.000000000000000000e+00,9.354552631618086034e-01,0.000000000000000000e+00,-1.000000005136791881e+00,0.000000000000000000e+00 +3.024873073320287631e+01,1.719399999999999977e+02,0.000000000000000000e+00,1.056291642651250839e+01,0.000000000000000000e+00,9.345084755327088821e-01,0.000000000000000000e+00,-1.000000008229294357e+00,0.000000000000000000e+00 +3.024967744144104032e+01,1.719500000000000171e+02,0.000000000000000000e+00,1.056380113338492777e+01,0.000000000000000000e+00,9.335617672867557726e-01,0.000000000000000000e+00,-1.000000005131610026e+00,0.000000000000000000e+00 +3.025062407039341750e+01,1.719600000000000080e+02,0.000000000000000000e+00,1.056468486998267231e+01,0.000000000000000000e+00,9.326151383295224750e-01,0.000000000000000000e+00,-1.000000006379338391e+00,0.000000000000000000e+00 +3.025157062016021925e+01,1.719699999999999989e+02,0.000000000000000000e+00,1.056556763662437248e+01,0.000000000000000000e+00,9.316685885566838854e-01,0.000000000000000000e+00,-1.000000006650678452e+00,0.000000000000000000e+00 +3.025251709084157881e+01,1.719799999999999898e+02,0.000000000000000000e+00,1.056644943362818623e+01,0.000000000000000000e+00,9.307221178690283647e-01,0.000000000000000000e+00,-1.000000004584563840e+00,0.000000000000000000e+00 +3.025346348253756190e+01,1.719900000000000091e+02,0.000000000000000000e+00,1.056733026131180431e+01,0.000000000000000000e+00,9.297757261687075170e-01,0.000000000000000000e+00,-1.000000008737060853e+00,0.000000000000000000e+00 +3.025440979534814900e+01,1.720000000000000000e+02,0.000000000000000000e+00,1.056821011999245208e+01,0.000000000000000000e+00,9.288294133498509186e-01,0.000000000000000000e+00,-1.000000005844376094e+00,0.000000000000000000e+00 +3.025535602937325308e+01,1.720099999999999909e+02,0.000000000000000000e+00,1.056908900998688239e+01,0.000000000000000000e+00,9.278831793192153787e-01,0.000000000000000000e+00,-1.000000006443958700e+00,0.000000000000000000e+00 +3.025630218471270894e+01,1.720200000000000102e+02,0.000000000000000000e+00,1.056996693161138801e+01,0.000000000000000000e+00,9.269370239736609562e-01,0.000000000000000000e+00,-1.000000005202193787e+00,0.000000000000000000e+00 +3.025724826146628033e+01,1.720300000000000011e+02,0.000000000000000000e+00,1.057084388518179274e+01,0.000000000000000000e+00,9.259909472151693910e-01,0.000000000000000000e+00,-1.000000008691247055e+00,0.000000000000000000e+00 +3.025819425973364929e+01,1.720399999999999920e+02,0.000000000000000000e+00,1.057171987101345678e+01,0.000000000000000000e+00,9.250449489395794478e-01,0.000000000000000000e+00,-1.000000005617672549e+00,0.000000000000000000e+00 +3.025914017961442681e+01,1.720500000000000114e+02,0.000000000000000000e+00,1.057259488942127135e+01,0.000000000000000000e+00,9.240990290534882856e-01,0.000000000000000000e+00,-1.000000006520934015e+00,0.000000000000000000e+00 +3.026008602120814928e+01,1.720600000000000023e+02,0.000000000000000000e+00,1.057346894071966936e+01,0.000000000000000000e+00,9.231531874535973126e-01,0.000000000000000000e+00,-1.000000008046154631e+00,0.000000000000000000e+00 +3.026103178461428200e+01,1.720699999999999932e+02,0.000000000000000000e+00,1.057434202522261657e+01,0.000000000000000000e+00,9.222074240398561162e-01,0.000000000000000000e+00,-1.000000004846476997e+00,0.000000000000000000e+00 +3.026197746993220861e+01,1.720800000000000125e+02,0.000000000000000000e+00,1.057521414324361508e+01,0.000000000000000000e+00,9.212617387173450689e-01,0.000000000000000000e+00,-1.000000007465200680e+00,0.000000000000000000e+00 +3.026292307726124520e+01,1.720900000000000034e+02,0.000000000000000000e+00,1.057608529509570872e+01,0.000000000000000000e+00,9.203161313812476818e-01,0.000000000000000000e+00,-1.000000006580759493e+00,0.000000000000000000e+00 +3.026386860670063328e+01,1.720999999999999943e+02,0.000000000000000000e+00,1.057695548109147410e+01,0.000000000000000000e+00,9.193706019356365777e-01,0.000000000000000000e+00,-1.000000008762466086e+00,0.000000000000000000e+00 +3.026481405834953975e+01,1.721100000000000136e+02,0.000000000000000000e+00,1.057782470154302956e+01,0.000000000000000000e+00,9.184251502784464005e-01,0.000000000000000000e+00,-1.000000004682507493e+00,0.000000000000000000e+00 +3.026575943230705334e+01,1.721200000000000045e+02,0.000000000000000000e+00,1.057869295676202981e+01,0.000000000000000000e+00,9.174797763165044584e-01,0.000000000000000000e+00,-1.000000006871587077e+00,0.000000000000000000e+00 +3.026670472867219885e+01,1.721299999999999955e+02,0.000000000000000000e+00,1.057956024705967479e+01,0.000000000000000000e+00,9.165344799448649216e-01,0.000000000000000000e+00,-1.000000007986951545e+00,0.000000000000000000e+00 +3.026764994754391580e+01,1.721400000000000148e+02,0.000000000000000000e+00,1.058042657274669907e+01,0.000000000000000000e+00,9.155892610655973485e-01,0.000000000000000000e+00,-1.000000006643308570e+00,0.000000000000000000e+00 +3.026859508902107976e+01,1.721500000000000057e+02,0.000000000000000000e+00,1.058129193413337887e+01,0.000000000000000000e+00,9.146441195821536363e-01,0.000000000000000000e+00,-1.000000007421498971e+00,0.000000000000000000e+00 +3.026954015320249169e+01,1.721599999999999966e+02,0.000000000000000000e+00,1.058215633152953394e+01,0.000000000000000000e+00,9.136990553937290871e-01,0.000000000000000000e+00,-1.000000006946548003e+00,0.000000000000000000e+00 +3.027048514018687442e+01,1.721700000000000159e+02,0.000000000000000000e+00,1.058301976524452392e+01,0.000000000000000000e+00,9.127540684027818374e-01,0.000000000000000000e+00,-1.000000005818865390e+00,0.000000000000000000e+00 +3.027143005007288323e+01,1.721800000000000068e+02,0.000000000000000000e+00,1.058388223558725194e+01,0.000000000000000000e+00,9.118091585112753084e-01,0.000000000000000000e+00,-1.000000008618571856e+00,0.000000000000000000e+00 +3.027237488295909884e+01,1.721899999999999977e+02,0.000000000000000000e+00,1.058474374286616460e+01,0.000000000000000000e+00,9.108643256169181024e-01,0.000000000000000000e+00,-1.000000005995946184e+00,0.000000000000000000e+00 +3.027331963894402733e+01,1.722000000000000171e+02,0.000000000000000000e+00,1.058560428738924841e+01,0.000000000000000000e+00,9.099195696263255861e-01,0.000000000000000000e+00,-1.000000008498514781e+00,0.000000000000000000e+00 +3.027426431812610375e+01,1.722100000000000080e+02,0.000000000000000000e+00,1.058646386946403872e+01,0.000000000000000000e+00,9.089748904362203730e-01,0.000000000000000000e+00,-1.000000006771649907e+00,0.000000000000000000e+00 +3.027520892060369206e+01,1.722199999999999989e+02,0.000000000000000000e+00,1.058732248939761078e+01,0.000000000000000000e+00,9.080302879522350601e-01,0.000000000000000000e+00,-1.000000007382614520e+00,0.000000000000000000e+00 +3.027615344647508522e+01,1.722299999999999898e+02,0.000000000000000000e+00,1.058818014749658865e+01,0.000000000000000000e+00,9.070857620738705940e-01,0.000000000000000000e+00,-1.000000004952406263e+00,0.000000000000000000e+00 +3.027709789583849798e+01,1.722400000000000091e+02,0.000000000000000000e+00,1.058903684406713985e+01,0.000000000000000000e+00,9.061413127057807992e-01,0.000000000000000000e+00,-1.000000010032609188e+00,0.000000000000000000e+00 +3.027804226879207761e+01,1.722500000000000000e+02,0.000000000000000000e+00,1.058989257941498074e+01,0.000000000000000000e+00,9.051969397427261921e-01,0.000000000000000000e+00,-1.000000005289908733e+00,0.000000000000000000e+00 +3.027898656543390032e+01,1.722599999999999909e+02,0.000000000000000000e+00,1.059074735384536758e+01,0.000000000000000000e+00,9.042526430959086925e-01,0.000000000000000000e+00,-1.000000009242849819e+00,0.000000000000000000e+00 +3.027993078586196773e+01,1.722700000000000102e+02,0.000000000000000000e+00,1.059160116766311255e+01,0.000000000000000000e+00,9.033084226591141519e-01,0.000000000000000000e+00,-1.000000006543791509e+00,0.000000000000000000e+00 +3.028087493017421039e+01,1.722800000000000011e+02,0.000000000000000000e+00,1.059245402117256774e+01,0.000000000000000000e+00,9.023642783406924384e-01,0.000000000000000000e+00,-1.000000005750532495e+00,0.000000000000000000e+00 +3.028181899846849134e+01,1.722899999999999920e+02,0.000000000000000000e+00,1.059330591467763938e+01,0.000000000000000000e+00,9.014202100409842711e-01,0.000000000000000000e+00,-1.000000009446120774e+00,0.000000000000000000e+00 +3.028276299084259549e+01,1.723000000000000114e+02,0.000000000000000000e+00,1.059415684848178074e+01,0.000000000000000000e+00,9.004762176579638178e-01,0.000000000000000000e+00,-1.000000006256715812e+00,0.000000000000000000e+00 +3.028370690739424020e+01,1.723100000000000023e+02,0.000000000000000000e+00,1.059500682288799034e+01,0.000000000000000000e+00,8.995323011004134894e-01,0.000000000000000000e+00,-1.000000008729210021e+00,0.000000000000000000e+00 +3.028465074822107184e+01,1.723199999999999932e+02,0.000000000000000000e+00,1.059585583819882260e+01,0.000000000000000000e+00,8.985884602653430031e-01,0.000000000000000000e+00,-1.000000005484426024e+00,0.000000000000000000e+00 +3.028559451342066566e+01,1.723300000000000125e+02,0.000000000000000000e+00,1.059670389471637719e+01,0.000000000000000000e+00,8.976446950605736497e-01,0.000000000000000000e+00,-1.000000009071757567e+00,0.000000000000000000e+00 +3.028653820309052591e+01,1.723400000000000034e+02,0.000000000000000000e+00,1.059755099274230972e+01,0.000000000000000000e+00,8.967010053821535820e-01,0.000000000000000000e+00,-1.000000006111590123e+00,0.000000000000000000e+00 +3.028748181732808575e+01,1.723499999999999943e+02,0.000000000000000000e+00,1.059839713257782101e+01,0.000000000000000000e+00,8.957573911388284627e-01,0.000000000000000000e+00,-1.000000009154393243e+00,0.000000000000000000e+00 +3.028842535623070376e+01,1.723600000000000136e+02,0.000000000000000000e+00,1.059924231452366961e+01,0.000000000000000000e+00,8.948138522275712603e-01,0.000000000000000000e+00,-1.000000006809133923e+00,0.000000000000000000e+00 +3.028936881989567809e+01,1.723700000000000045e+02,0.000000000000000000e+00,1.060008653888016106e+01,0.000000000000000000e+00,8.938703885561738449e-01,0.000000000000000000e+00,-1.000000007636439925e+00,0.000000000000000000e+00 +3.029031220842022520e+01,1.723799999999999955e+02,0.000000000000000000e+00,1.060092980594715861e+01,0.000000000000000000e+00,8.929270000244212691e-01,0.000000000000000000e+00,-1.000000006226908100e+00,0.000000000000000000e+00 +3.029125552190150117e+01,1.723900000000000148e+02,0.000000000000000000e+00,1.060177211602407610e+01,0.000000000000000000e+00,8.919836865372723356e-01,0.000000000000000000e+00,-1.000000009146537527e+00,0.000000000000000000e+00 +3.029219876043658388e+01,1.724000000000000057e+02,0.000000000000000000e+00,1.060261346940988325e+01,0.000000000000000000e+00,8.910404479935621902e-01,0.000000000000000000e+00,-1.000000006988498225e+00,0.000000000000000000e+00 +3.029314192412248730e+01,1.724099999999999966e+02,0.000000000000000000e+00,1.060345386640310039e+01,0.000000000000000000e+00,8.900972843010691582e-01,0.000000000000000000e+00,-1.000000008314047006e+00,0.000000000000000000e+00 +3.029408501305615076e+01,1.724200000000000159e+02,0.000000000000000000e+00,1.060429330730180730e+01,0.000000000000000000e+00,8.891541953595663017e-01,0.000000000000000000e+00,-1.000000007706315586e+00,0.000000000000000000e+00 +3.029502802733444611e+01,1.724300000000000068e+02,0.000000000000000000e+00,1.060513179240363613e+01,0.000000000000000000e+00,8.882111810740054292e-01,0.000000000000000000e+00,-1.000000005736289888e+00,0.000000000000000000e+00 +3.029597096705417414e+01,1.724399999999999977e+02,0.000000000000000000e+00,1.060596932200577669e+01,0.000000000000000000e+00,8.872682413488691688e-01,0.000000000000000000e+00,-1.000000008970481469e+00,0.000000000000000000e+00 +3.029691383231206814e+01,1.724500000000000171e+02,0.000000000000000000e+00,1.060680589640497651e+01,0.000000000000000000e+00,8.863253760825180461e-01,0.000000000000000000e+00,-1.000000007988470330e+00,0.000000000000000000e+00 +3.029785662320479034e+01,1.724600000000000080e+02,0.000000000000000000e+00,1.060764151589753546e+01,0.000000000000000000e+00,8.853825851822646475e-01,0.000000000000000000e+00,-1.000000007355982712e+00,0.000000000000000000e+00 +3.029879933982893547e+01,1.724699999999999989e+02,0.000000000000000000e+00,1.060847618077931465e+01,0.000000000000000000e+00,8.844398685511857261e-01,0.000000000000000000e+00,-1.000000007641030031e+00,0.000000000000000000e+00 +3.029974198228102722e+01,1.724799999999999898e+02,0.000000000000000000e+00,1.060930989134573288e+01,0.000000000000000000e+00,8.834972260918918519e-01,0.000000000000000000e+00,-1.000000007412120251e+00,0.000000000000000000e+00 +3.030068455065752175e+01,1.724900000000000091e+02,0.000000000000000000e+00,1.061014264789176664e+01,0.000000000000000000e+00,8.825546577084121269e-01,0.000000000000000000e+00,-1.000000009235070708e+00,0.000000000000000000e+00 +3.030162704505480420e+01,1.725000000000000000e+02,0.000000000000000000e+00,1.061097445071195189e+01,0.000000000000000000e+00,8.816121633024261994e-01,0.000000000000000000e+00,-1.000000005675513171e+00,0.000000000000000000e+00 +3.030256946556919218e+01,1.725099999999999909e+02,0.000000000000000000e+00,1.061180530010038225e+01,0.000000000000000000e+00,8.806697427826892799e-01,0.000000000000000000e+00,-1.000000009297318027e+00,0.000000000000000000e+00 +3.030351181229693580e+01,1.725200000000000102e+02,0.000000000000000000e+00,1.061263519635071617e+01,0.000000000000000000e+00,8.797273960461845510e-01,0.000000000000000000e+00,-1.000000006662301155e+00,0.000000000000000000e+00 +3.030445408533421414e+01,1.725300000000000011e+02,0.000000000000000000e+00,1.061346413975616620e+01,0.000000000000000000e+00,8.787851230026277882e-01,0.000000000000000000e+00,-1.000000008333971513e+00,0.000000000000000000e+00 +3.030539628477714231e+01,1.725399999999999920e+02,0.000000000000000000e+00,1.061429213060951149e+01,0.000000000000000000e+00,8.778429235518488971e-01,0.000000000000000000e+00,-1.000000008872018009e+00,0.000000000000000000e+00 +3.030633841072176082e+01,1.725500000000000114e+02,0.000000000000000000e+00,1.061511916920308884e+01,0.000000000000000000e+00,8.769007975988725168e-01,0.000000000000000000e+00,-1.000000006833594135e+00,0.000000000000000000e+00 +3.030728046326404623e+01,1.725600000000000023e+02,0.000000000000000000e+00,1.061594525582879811e+01,0.000000000000000000e+00,8.759587450501504780e-01,0.000000000000000000e+00,-1.000000006780160655e+00,0.000000000000000000e+00 +3.030822244249990405e+01,1.725699999999999932e+02,0.000000000000000000e+00,1.061677039077810392e+01,0.000000000000000000e+00,8.750167658079053279e-01,0.000000000000000000e+00,-1.000000009270433754e+00,0.000000000000000000e+00 +3.030916434852517582e+01,1.725800000000000125e+02,0.000000000000000000e+00,1.061759457434203213e+01,0.000000000000000000e+00,8.740748597739017578e-01,0.000000000000000000e+00,-1.000000006852472367e+00,0.000000000000000000e+00 +3.031010618143563207e+01,1.725900000000000034e+02,0.000000000000000000e+00,1.061841780681116987e+01,0.000000000000000000e+00,8.731330268569913455e-01,0.000000000000000000e+00,-1.000000010093453184e+00,0.000000000000000000e+00 +3.031104794132697577e+01,1.725999999999999943e+02,0.000000000000000000e+00,1.061924008847567258e+01,0.000000000000000000e+00,8.721912669561405762e-01,0.000000000000000000e+00,-1.000000005528462133e+00,0.000000000000000000e+00 +3.031198962829484600e+01,1.726100000000000136e+02,0.000000000000000000e+00,1.062006141962525518e+01,0.000000000000000000e+00,8.712495799830645149e-01,0.000000000000000000e+00,-1.000000009735430462e+00,0.000000000000000000e+00 +3.031293124243481074e+01,1.726200000000000045e+02,0.000000000000000000e+00,1.062088180054920450e+01,0.000000000000000000e+00,8.703079658339339941e-01,0.000000000000000000e+00,-1.000000005236462597e+00,0.000000000000000000e+00 +3.031387278384237050e+01,1.726299999999999955e+02,0.000000000000000000e+00,1.062170123153636503e+01,0.000000000000000000e+00,8.693664244214452941e-01,0.000000000000000000e+00,-1.000000010616310941e+00,0.000000000000000000e+00 +3.031481425261295826e+01,1.726400000000000148e+02,0.000000000000000000e+00,1.062251971287515495e+01,0.000000000000000000e+00,8.684249556408630832e-01,0.000000000000000000e+00,-1.000000006385619145e+00,0.000000000000000000e+00 +3.031575564884194307e+01,1.726500000000000057e+02,0.000000000000000000e+00,1.062333724485355013e+01,0.000000000000000000e+00,8.674835594058685206e-01,0.000000000000000000e+00,-1.000000009126992939e+00,0.000000000000000000e+00 +3.031669697262462293e+01,1.726599999999999966e+02,0.000000000000000000e+00,1.062415382775910189e+01,0.000000000000000000e+00,8.665422356145980887e-01,0.000000000000000000e+00,-1.000000007362093157e+00,0.000000000000000000e+00 +3.031763822405623188e+01,1.726700000000000159e+02,0.000000000000000000e+00,1.062496946187892277e+01,0.000000000000000000e+00,8.656009841760606838e-01,0.000000000000000000e+00,-1.000000007651865364e+00,0.000000000000000000e+00 +3.031857940323193645e+01,1.726800000000000068e+02,0.000000000000000000e+00,1.062578414749969724e+01,0.000000000000000000e+00,8.646598049931559782e-01,0.000000000000000000e+00,-1.000000008538018070e+00,0.000000000000000000e+00 +3.031952051024683570e+01,1.726899999999999977e+02,0.000000000000000000e+00,1.062659788490767632e+01,0.000000000000000000e+00,8.637186979702231593e-01,0.000000000000000000e+00,-1.000000008560270937e+00,0.000000000000000000e+00 +3.032046154519596115e+01,1.727000000000000171e+02,0.000000000000000000e+00,1.062741067438867937e+01,0.000000000000000000e+00,8.627776630130422619e-01,0.000000000000000000e+00,-1.000000006255530094e+00,0.000000000000000000e+00 +3.032140250817428040e+01,1.727100000000000080e+02,0.000000000000000000e+00,1.062822251622809588e+01,0.000000000000000000e+00,8.618367000288362778e-01,0.000000000000000000e+00,-1.000000010192941824e+00,0.000000000000000000e+00 +3.032234339927669353e+01,1.727199999999999989e+02,0.000000000000000000e+00,1.062903341071088725e+01,0.000000000000000000e+00,8.608958089168313732e-01,0.000000000000000000e+00,-1.000000006869120606e+00,0.000000000000000000e+00 +3.032328421859803669e+01,1.727299999999999898e+02,0.000000000000000000e+00,1.062984335812157966e+01,0.000000000000000000e+00,8.599549895890254980e-01,0.000000000000000000e+00,-1.000000008864707635e+00,0.000000000000000000e+00 +3.032422496623307850e+01,1.727400000000000091e+02,0.000000000000000000e+00,1.063065235874427650e+01,0.000000000000000000e+00,8.590142419456459066e-01,0.000000000000000000e+00,-1.000000006685079601e+00,0.000000000000000000e+00 +3.032516564227651656e+01,1.727500000000000000e+02,0.000000000000000000e+00,1.063146041286264776e+01,0.000000000000000000e+00,8.580735658959183221e-01,0.000000000000000000e+00,-1.000000008898598747e+00,0.000000000000000000e+00 +3.032610624682299161e+01,1.727599999999999909e+02,0.000000000000000000e+00,1.063226752075993886e+01,0.000000000000000000e+00,8.571329613410739734e-01,0.000000000000000000e+00,-1.000000008012970065e+00,0.000000000000000000e+00 +3.032704677996707332e+01,1.727700000000000102e+02,0.000000000000000000e+00,1.063307368271896358e+01,0.000000000000000000e+00,8.561924281894575106e-01,0.000000000000000000e+00,-1.000000008580233413e+00,0.000000000000000000e+00 +3.032798724180326388e+01,1.727800000000000011e+02,0.000000000000000000e+00,1.063387889902211114e+01,0.000000000000000000e+00,8.552519663451975118e-01,0.000000000000000000e+00,-1.000000007120190881e+00,0.000000000000000000e+00 +3.032892763242600509e+01,1.727899999999999920e+02,0.000000000000000000e+00,1.063468316995134266e+01,0.000000000000000000e+00,8.543115757157611068e-01,0.000000000000000000e+00,-1.000000008184626532e+00,0.000000000000000000e+00 +3.032986795192967122e+01,1.728000000000000114e+02,0.000000000000000000e+00,1.063548649578819472e+01,0.000000000000000000e+00,8.533712562044002414e-01,0.000000000000000000e+00,-1.000000008290333309e+00,0.000000000000000000e+00 +3.033080820040856906e+01,1.728100000000000023e+02,0.000000000000000000e+00,1.063628887681377577e+01,0.000000000000000000e+00,8.524310077177077449e-01,0.000000000000000000e+00,-1.000000007969760407e+00,0.000000000000000000e+00 +3.033174837795694145e+01,1.728199999999999932e+02,0.000000000000000000e+00,1.063709031330876975e+01,0.000000000000000000e+00,8.514908301618407949e-01,0.000000000000000000e+00,-1.000000009764553166e+00,0.000000000000000000e+00 +3.033268848466897083e+01,1.728300000000000125e+02,0.000000000000000000e+00,1.063789080555343602e+01,0.000000000000000000e+00,8.505507234406320949e-01,0.000000000000000000e+00,-1.000000006165968847e+00,0.000000000000000000e+00 +3.033362852063876858e+01,1.728400000000000034e+02,0.000000000000000000e+00,1.063869035382760764e+01,0.000000000000000000e+00,8.496106874650382057e-01,0.000000000000000000e+00,-1.000000009764331566e+00,0.000000000000000000e+00 +3.033456848596038213e+01,1.728499999999999943e+02,0.000000000000000000e+00,1.063948895841069842e+01,0.000000000000000000e+00,8.486707221342448815e-01,0.000000000000000000e+00,-1.000000007016523806e+00,0.000000000000000000e+00 +3.033550838072779854e+01,1.728600000000000136e+02,0.000000000000000000e+00,1.064028661958169231e+01,0.000000000000000000e+00,8.477308273602331967e-01,0.000000000000000000e+00,-1.000000008503006965e+00,0.000000000000000000e+00 +3.033644820503493733e+01,1.728700000000000045e+02,0.000000000000000000e+00,1.064108333761915581e+01,0.000000000000000000e+00,8.467910030451036851e-01,0.000000000000000000e+00,-1.000000008718667344e+00,0.000000000000000000e+00 +3.033738795897565055e+01,1.728799999999999955e+02,0.000000000000000000e+00,1.064187911280122911e+01,0.000000000000000000e+00,8.458512490961956898e-01,0.000000000000000000e+00,-1.000000008188696610e+00,0.000000000000000000e+00 +3.033832764264373338e+01,1.728900000000000148e+02,0.000000000000000000e+00,1.064267394540563139e+01,0.000000000000000000e+00,8.449115654204191195e-01,0.000000000000000000e+00,-1.000000007437614524e+00,0.000000000000000000e+00 +3.033926725613290998e+01,1.729000000000000057e+02,0.000000000000000000e+00,1.064346783570966082e+01,0.000000000000000000e+00,8.439719519242551149e-01,0.000000000000000000e+00,-1.000000006989504309e+00,0.000000000000000000e+00 +3.034020679953684052e+01,1.729099999999999966e+02,0.000000000000000000e+00,1.064426078399019460e+01,0.000000000000000000e+00,8.430324085137564927e-01,0.000000000000000000e+00,-1.000000011393053834e+00,0.000000000000000000e+00 +3.034114627294912836e+01,1.729200000000000159e+02,0.000000000000000000e+00,1.064505279052368891e+01,0.000000000000000000e+00,8.420929350907667699e-01,0.000000000000000000e+00,-1.000000005068877984e+00,0.000000000000000000e+00 +3.034208567646330224e+01,1.729300000000000068e+02,0.000000000000000000e+00,1.064584385558617541e+01,0.000000000000000000e+00,8.411535315718297046e-01,0.000000000000000000e+00,-1.000000010678074647e+00,0.000000000000000000e+00 +3.034302501017283760e+01,1.729399999999999977e+02,0.000000000000000000e+00,1.064663397945327539e+01,0.000000000000000000e+00,8.402141978522642551e-01,0.000000000000000000e+00,-1.000000006598180669e+00,0.000000000000000000e+00 +3.034396427417113884e+01,1.729500000000000171e+02,0.000000000000000000e+00,1.064742316240018027e+01,0.000000000000000000e+00,8.392749338477647481e-01,0.000000000000000000e+00,-1.000000009453941408e+00,0.000000000000000000e+00 +3.034490346855154996e+01,1.729600000000000080e+02,0.000000000000000000e+00,1.064821140470167116e+01,0.000000000000000000e+00,8.383357394584731725e-01,0.000000000000000000e+00,-1.000000007682070091e+00,0.000000000000000000e+00 +3.034584259340735457e+01,1.729699999999999989e+02,0.000000000000000000e+00,1.064899870663210457e+01,0.000000000000000000e+00,8.373966145954557794e-01,0.000000000000000000e+00,-1.000000009855104510e+00,0.000000000000000000e+00 +3.034678164883176521e+01,1.729799999999999898e+02,0.000000000000000000e+00,1.064978506846542317e+01,0.000000000000000000e+00,8.364575591617910977e-01,0.000000000000000000e+00,-1.000000006417160803e+00,0.000000000000000000e+00 +3.034772063491793759e+01,1.729900000000000091e+02,0.000000000000000000e+00,1.065057049047514859e+01,0.000000000000000000e+00,8.355185730695945390e-01,0.000000000000000000e+00,-1.000000007956484804e+00,0.000000000000000000e+00 +3.034865955175895991e+01,1.730000000000000000e+02,0.000000000000000000e+00,1.065135497293439037e+01,0.000000000000000000e+00,8.345796562211019731e-01,0.000000000000000000e+00,-1.000000008942904861e+00,0.000000000000000000e+00 +3.034959839944785998e+01,1.730099999999999909e+02,0.000000000000000000e+00,1.065213851611583706e+01,0.000000000000000000e+00,8.336408085238052879e-01,0.000000000000000000e+00,-1.000000009890079200e+00,0.000000000000000000e+00 +3.035053717807760520e+01,1.730200000000000102e+02,0.000000000000000000e+00,1.065292112029176153e+01,0.000000000000000000e+00,8.327020298847769286e-01,0.000000000000000000e+00,-1.000000007277703995e+00,0.000000000000000000e+00 +3.035147588774109551e+01,1.730300000000000011e+02,0.000000000000000000e+00,1.065370278573402096e+01,0.000000000000000000e+00,8.317633202144566473e-01,0.000000000000000000e+00,-1.000000007664371360e+00,0.000000000000000000e+00 +3.035241452853116684e+01,1.730399999999999920e+02,0.000000000000000000e+00,1.065448351271406047e+01,0.000000000000000000e+00,8.308246794171899596e-01,0.000000000000000000e+00,-1.000000007528629054e+00,0.000000000000000000e+00 +3.035335310054059832e+01,1.730500000000000114e+02,0.000000000000000000e+00,1.065526330150290768e+01,0.000000000000000000e+00,8.298861074006906868e-01,0.000000000000000000e+00,-1.000000009396409872e+00,0.000000000000000000e+00 +3.035429160386210512e+01,1.730600000000000023e+02,0.000000000000000000e+00,1.065604215237117636e+01,0.000000000000000000e+00,8.289476040703643855e-01,0.000000000000000000e+00,-1.000000009742923579e+00,0.000000000000000000e+00 +3.035523003858833846e+01,1.730699999999999932e+02,0.000000000000000000e+00,1.065682006558906458e+01,0.000000000000000000e+00,8.280091693349871385e-01,0.000000000000000000e+00,-1.000000007057126883e+00,0.000000000000000000e+00 +3.035616840481188916e+01,1.730800000000000125e+02,0.000000000000000000e+00,1.065759704142635833e+01,0.000000000000000000e+00,8.270708031048148445e-01,0.000000000000000000e+00,-1.000000007897291265e+00,0.000000000000000000e+00 +3.035710670262528410e+01,1.730900000000000034e+02,0.000000000000000000e+00,1.065837308015243323e+01,0.000000000000000000e+00,8.261325052840112759e-01,0.000000000000000000e+00,-1.000000008734402535e+00,0.000000000000000000e+00 +3.035804493212098620e+01,1.730999999999999943e+02,0.000000000000000000e+00,1.065914818203624925e+01,0.000000000000000000e+00,8.251942757801139505e-01,0.000000000000000000e+00,-1.000000008055056178e+00,0.000000000000000000e+00 +3.035898309339140155e+01,1.731100000000000136e+02,0.000000000000000000e+00,1.065992234734635424e+01,0.000000000000000000e+00,8.242561145021420899e-01,0.000000000000000000e+00,-1.000000008380160565e+00,0.000000000000000000e+00 +3.035992118652887228e+01,1.731200000000000045e+02,0.000000000000000000e+00,1.066069557635088572e+01,0.000000000000000000e+00,8.233180213568115358e-01,0.000000000000000000e+00,-1.000000010213361712e+00,0.000000000000000000e+00 +3.036085921162567658e+01,1.731299999999999955e+02,0.000000000000000000e+00,1.066146786931756907e+01,0.000000000000000000e+00,8.223799962504275696e-01,0.000000000000000000e+00,-1.000000005979732265e+00,0.000000000000000000e+00 +3.036179716877403223e+01,1.731400000000000148e+02,0.000000000000000000e+00,1.066223922651371758e+01,0.000000000000000000e+00,8.214420390964622953e-01,0.000000000000000000e+00,-1.000000010313614629e+00,0.000000000000000000e+00 +3.036273505806610018e+01,1.731500000000000057e+02,0.000000000000000000e+00,1.066300964820623953e+01,0.000000000000000000e+00,8.205041497947226370e-01,0.000000000000000000e+00,-1.000000007560748916e+00,0.000000000000000000e+00 +3.036367287959397387e+01,1.731599999999999966e+02,0.000000000000000000e+00,1.066377913466162575e+01,0.000000000000000000e+00,8.195663282597595023e-01,0.000000000000000000e+00,-1.000000008316904498e+00,0.000000000000000000e+00 +3.036461063344968636e+01,1.731700000000000159e+02,0.000000000000000000e+00,1.066454768614596382e+01,0.000000000000000000e+00,8.186285743962473660e-01,0.000000000000000000e+00,-1.000000009040722837e+00,0.000000000000000000e+00 +3.036554831972521384e+01,1.731800000000000068e+02,0.000000000000000000e+00,1.066531530292492924e+01,0.000000000000000000e+00,8.176908881122432193e-01,0.000000000000000000e+00,-1.000000006187695467e+00,0.000000000000000000e+00 +3.036648593851246858e+01,1.731899999999999977e+02,0.000000000000000000e+00,1.066608198526378892e+01,0.000000000000000000e+00,8.167532693191884574e-01,0.000000000000000000e+00,-1.000000010357124491e+00,0.000000000000000000e+00 +3.036742348990329887e+01,1.732000000000000171e+02,0.000000000000000000e+00,1.066684773342740478e+01,0.000000000000000000e+00,8.158157179186472652e-01,0.000000000000000000e+00,-1.000000009919641553e+00,0.000000000000000000e+00 +3.036836097398949974e+01,1.732100000000000080e+02,0.000000000000000000e+00,1.066761254768022482e+01,0.000000000000000000e+00,8.148782338231483902e-01,0.000000000000000000e+00,-1.000000005367606803e+00,0.000000000000000000e+00 +3.036929839086279870e+01,1.732199999999999989e+02,0.000000000000000000e+00,1.066837642828629384e+01,0.000000000000000000e+00,8.139408169448187902e-01,0.000000000000000000e+00,-1.000000009322185690e+00,0.000000000000000000e+00 +3.037023574061486286e+01,1.732299999999999898e+02,0.000000000000000000e+00,1.066913937550925340e+01,0.000000000000000000e+00,8.130034671840147276e-01,0.000000000000000000e+00,-1.000000010147925167e+00,0.000000000000000000e+00 +3.037117302333730606e+01,1.732400000000000091e+02,0.000000000000000000e+00,1.066990138961233114e+01,0.000000000000000000e+00,8.120661844520603578e-01,0.000000000000000000e+00,-1.000000006311605238e+00,0.000000000000000000e+00 +3.037211023912167462e+01,1.732500000000000000e+02,0.000000000000000000e+00,1.067066247085835151e+01,0.000000000000000000e+00,8.111289686617765282e-01,0.000000000000000000e+00,-1.000000010437940734e+00,0.000000000000000000e+00 +3.037304738805945803e+01,1.732599999999999909e+02,0.000000000000000000e+00,1.067142261950973747e+01,0.000000000000000000e+00,8.101918197142121691e-01,0.000000000000000000e+00,-1.000000006835672473e+00,0.000000000000000000e+00 +3.037398447024208181e+01,1.732700000000000102e+02,0.000000000000000000e+00,1.067218183582849989e+01,0.000000000000000000e+00,8.092547375251819552e-01,0.000000000000000000e+00,-1.000000010152969576e+00,0.000000000000000000e+00 +3.037492148576091822e+01,1.732800000000000011e+02,0.000000000000000000e+00,1.067294012007625170e+01,0.000000000000000000e+00,8.083177219968334937e-01,0.000000000000000000e+00,-1.000000006715606737e+00,0.000000000000000000e+00 +3.037585843470727198e+01,1.732899999999999920e+02,0.000000000000000000e+00,1.067369747251419554e+01,0.000000000000000000e+00,8.073807730441877606e-01,0.000000000000000000e+00,-1.000000009149806024e+00,0.000000000000000000e+00 +3.037679531717239101e+01,1.733000000000000114e+02,0.000000000000000000e+00,1.067445389340313611e+01,0.000000000000000000e+00,8.064438905704949256e-01,0.000000000000000000e+00,-1.000000009847856530e+00,0.000000000000000000e+00 +3.037773213324746635e+01,1.733100000000000023e+02,0.000000000000000000e+00,1.067520938300346955e+01,0.000000000000000000e+00,8.055070744861930754e-01,0.000000000000000000e+00,-1.000000007269353119e+00,0.000000000000000000e+00 +3.037866888302362867e+01,1.733199999999999932e+02,0.000000000000000000e+00,1.067596394157519057e+01,0.000000000000000000e+00,8.045703247032225391e-01,0.000000000000000000e+00,-1.000000007970040850e+00,0.000000000000000000e+00 +3.037960556659194467e+01,1.733300000000000125e+02,0.000000000000000000e+00,1.067671756937789418e+01,0.000000000000000000e+00,8.036336411274418445e-01,0.000000000000000000e+00,-1.000000008384957173e+00,0.000000000000000000e+00 +3.038054218404342421e+01,1.733400000000000034e+02,0.000000000000000000e+00,1.067747026667077037e+01,0.000000000000000000e+00,8.026970236681085780e-01,0.000000000000000000e+00,-1.000000008995932443e+00,0.000000000000000000e+00 +3.038147873546902034e+01,1.733499999999999943e+02,0.000000000000000000e+00,1.067822203371260770e+01,0.000000000000000000e+00,8.017604722340883061e-01,0.000000000000000000e+00,-1.000000008258408402e+00,0.000000000000000000e+00 +3.038241522095962210e+01,1.733600000000000136e+02,0.000000000000000000e+00,1.067897287076179325e+01,0.000000000000000000e+00,8.008239867357522801e-01,0.000000000000000000e+00,-1.000000010703619546e+00,0.000000000000000000e+00 +3.038335164060606530e+01,1.733700000000000045e+02,0.000000000000000000e+00,1.067972277807631443e+01,0.000000000000000000e+00,7.998875670792874315e-01,0.000000000000000000e+00,-1.000000006681835529e+00,0.000000000000000000e+00 +3.038428799449912177e+01,1.733799999999999955e+02,0.000000000000000000e+00,1.068047175591375542e+01,0.000000000000000000e+00,7.989512131799758610e-01,0.000000000000000000e+00,-1.000000008826350317e+00,0.000000000000000000e+00 +3.038522428272950648e+01,1.733900000000000148e+02,0.000000000000000000e+00,1.068121980453130604e+01,0.000000000000000000e+00,7.980149249413288626e-01,0.000000000000000000e+00,-1.000000007484347808e+00,0.000000000000000000e+00 +3.038616050538787405e+01,1.734000000000000057e+02,0.000000000000000000e+00,1.068196692418575111e+01,0.000000000000000000e+00,7.970787022759548979e-01,0.000000000000000000e+00,-1.000000009211591045e+00,0.000000000000000000e+00 +3.038709666256482222e+01,1.734099999999999966e+02,0.000000000000000000e+00,1.068271311513347932e+01,0.000000000000000000e+00,7.961425450903831802e-01,0.000000000000000000e+00,-1.000000008403529650e+00,0.000000000000000000e+00 +3.038803275435089191e+01,1.734200000000000159e+02,0.000000000000000000e+00,1.068345837763047790e+01,0.000000000000000000e+00,7.952064532964484567e-01,0.000000000000000000e+00,-1.000000009588110528e+00,0.000000000000000000e+00 +3.038896878083656006e+01,1.734300000000000068e+02,0.000000000000000000e+00,1.068420271193233795e+01,0.000000000000000000e+00,7.942704268018051517e-01,0.000000000000000000e+00,-1.000000009185198824e+00,0.000000000000000000e+00 +3.038990474211225035e+01,1.734399999999999977e+02,0.000000000000000000e+00,1.068494611829425089e+01,0.000000000000000000e+00,7.933344655175172955e-01,0.000000000000000000e+00,-1.000000005638151723e+00,0.000000000000000000e+00 +3.039084063826832605e+01,1.734500000000000171e+02,0.000000000000000000e+00,1.068568859697101203e+01,0.000000000000000000e+00,7.923985693561637067e-01,0.000000000000000000e+00,-1.000000011587899973e+00,0.000000000000000000e+00 +3.039177646939509359e+01,1.734600000000000080e+02,0.000000000000000000e+00,1.068643014821702231e+01,0.000000000000000000e+00,7.914627382185509541e-01,0.000000000000000000e+00,-1.000000007223923459e+00,0.000000000000000000e+00 +3.039271223558280255e+01,1.734699999999999989e+02,0.000000000000000000e+00,1.068717077228627765e+01,0.000000000000000000e+00,7.905269720240835074e-01,0.000000000000000000e+00,-1.000000009242104637e+00,0.000000000000000000e+00 +3.039364793692163857e+01,1.734799999999999898e+02,0.000000000000000000e+00,1.068791046943238676e+01,0.000000000000000000e+00,7.895912706765993994e-01,0.000000000000000000e+00,-1.000000007969432669e+00,0.000000000000000000e+00 +3.039458357350173401e+01,1.734900000000000091e+02,0.000000000000000000e+00,1.068864923990855686e+01,0.000000000000000000e+00,7.886556340890461536e-01,0.000000000000000000e+00,-1.000000007931088897e+00,0.000000000000000000e+00 +3.039551914541316435e+01,1.735000000000000000e+02,0.000000000000000000e+00,1.068938708396760262e+01,0.000000000000000000e+00,7.877200621701947458e-01,0.000000000000000000e+00,-1.000000009595861661e+00,0.000000000000000000e+00 +3.039645465274594827e+01,1.735099999999999909e+02,0.000000000000000000e+00,1.069012400186194256e+01,0.000000000000000000e+00,7.867845548284354562e-01,0.000000000000000000e+00,-1.000000007340139829e+00,0.000000000000000000e+00 +3.039739009559004046e+01,1.735200000000000102e+02,0.000000000000000000e+00,1.069085999384359909e+01,0.000000000000000000e+00,7.858491119774769773e-01,0.000000000000000000e+00,-1.000000009749692609e+00,0.000000000000000000e+00 +3.039832547403534235e+01,1.735300000000000011e+02,0.000000000000000000e+00,1.069159506016420380e+01,0.000000000000000000e+00,7.849137335230537138e-01,0.000000000000000000e+00,-1.000000009168846571e+00,0.000000000000000000e+00 +3.039926078817170207e+01,1.735399999999999920e+02,0.000000000000000000e+00,1.069232920107499041e+01,0.000000000000000000e+00,7.839784193781187405e-01,0.000000000000000000e+00,-1.000000008091087800e+00,0.000000000000000000e+00 +3.040019603808890380e+01,1.735500000000000114e+02,0.000000000000000000e+00,1.069306241682680181e+01,0.000000000000000000e+00,7.830431694533497300e-01,0.000000000000000000e+00,-1.000000006978757572e+00,0.000000000000000000e+00 +3.040113122387667843e+01,1.735600000000000023e+02,0.000000000000000000e+00,1.069379470767008833e+01,0.000000000000000000e+00,7.821079836590489887e-01,0.000000000000000000e+00,-1.000000010357577462e+00,0.000000000000000000e+00 +3.040206634562469645e+01,1.735699999999999932e+02,0.000000000000000000e+00,1.069452607385490772e+01,0.000000000000000000e+00,7.811728619013437180e-01,0.000000000000000000e+00,-1.000000008531834128e+00,0.000000000000000000e+00 +3.040300140342257862e+01,1.735800000000000125e+02,0.000000000000000000e+00,1.069525651563092161e+01,0.000000000000000000e+00,7.802378040954849325e-01,0.000000000000000000e+00,-1.000000008055518697e+00,0.000000000000000000e+00 +3.040393639735988174e+01,1.735900000000000034e+02,0.000000000000000000e+00,1.069598603324740438e+01,0.000000000000000000e+00,7.793028101506515037e-01,0.000000000000000000e+00,-1.000000009388664957e+00,0.000000000000000000e+00 +3.040487132752610577e+01,1.735999999999999943e+02,0.000000000000000000e+00,1.069671462695323783e+01,0.000000000000000000e+00,7.783678799756491573e-01,0.000000000000000000e+00,-1.000000008925781225e+00,0.000000000000000000e+00 +3.040580619401070095e+01,1.736100000000000136e+02,0.000000000000000000e+00,1.069744229699691118e+01,0.000000000000000000e+00,7.774330134827112104e-01,0.000000000000000000e+00,-1.000000007123726720e+00,0.000000000000000000e+00 +3.040674099690305354e+01,1.736200000000000045e+02,0.000000000000000000e+00,1.069816904362652465e+01,0.000000000000000000e+00,7.764982105837000548e-01,0.000000000000000000e+00,-1.000000010537685835e+00,0.000000000000000000e+00 +3.040767573629249654e+01,1.736299999999999955e+02,0.000000000000000000e+00,1.069889486708978943e+01,0.000000000000000000e+00,7.755634711844068274e-01,0.000000000000000000e+00,-1.000000007426446347e+00,0.000000000000000000e+00 +3.040861041226830963e+01,1.736400000000000148e+02,0.000000000000000000e+00,1.069961976763402234e+01,0.000000000000000000e+00,7.746287952016541745e-01,0.000000000000000000e+00,-1.000000008409672070e+00,0.000000000000000000e+00 +3.040954502491970857e+01,1.736500000000000057e+02,0.000000000000000000e+00,1.070034374550615652e+01,0.000000000000000000e+00,7.736941825423944152e-01,0.000000000000000000e+00,-1.000000009875934071e+00,0.000000000000000000e+00 +3.041047957433586291e+01,1.736599999999999966e+02,0.000000000000000000e+00,1.070106680095273255e+01,0.000000000000000000e+00,7.727596331170117905e-01,0.000000000000000000e+00,-1.000000008210459201e+00,0.000000000000000000e+00 +3.041141406060587826e+01,1.736700000000000159e+02,0.000000000000000000e+00,1.070178893421990196e+01,0.000000000000000000e+00,7.718251468393245718e-01,0.000000000000000000e+00,-1.000000007932922097e+00,0.000000000000000000e+00 +3.041234848381880695e+01,1.736800000000000068e+02,0.000000000000000000e+00,1.070251014555343083e+01,0.000000000000000000e+00,7.708907236189830314e-01,0.000000000000000000e+00,-1.000000009496010644e+00,0.000000000000000000e+00 +3.041328284406364801e+01,1.736899999999999977e+02,0.000000000000000000e+00,1.070323043519869621e+01,0.000000000000000000e+00,7.699563633652705130e-01,0.000000000000000000e+00,-1.000000007245884337e+00,0.000000000000000000e+00 +3.041421714142934007e+01,1.737000000000000171e+02,0.000000000000000000e+00,1.070394980340068614e+01,0.000000000000000000e+00,7.690220659928087565e-01,0.000000000000000000e+00,-1.000000009771795151e+00,0.000000000000000000e+00 +3.041515137600476848e+01,1.737100000000000080e+02,0.000000000000000000e+00,1.070466825040400494e+01,0.000000000000000000e+00,7.680878314082499880e-01,0.000000000000000000e+00,-1.000000009383216870e+00,0.000000000000000000e+00 +3.041608554787876528e+01,1.737199999999999989e+02,0.000000000000000000e+00,1.070538577645286615e+01,0.000000000000000000e+00,7.671536595254870861e-01,0.000000000000000000e+00,-1.000000006526193141e+00,0.000000000000000000e+00 +3.041701965714010569e+01,1.737299999999999898e+02,0.000000000000000000e+00,1.070610238179109963e+01,0.000000000000000000e+00,7.662195502580511075e-01,0.000000000000000000e+00,-1.000000011827991919e+00,0.000000000000000000e+00 +3.041795370387750808e+01,1.737400000000000091e+02,0.000000000000000000e+00,1.070681806666215152e+01,0.000000000000000000e+00,7.652855035096015612e-01,0.000000000000000000e+00,-1.000000005374727774e+00,0.000000000000000000e+00 +3.041888768817963751e+01,1.737500000000000000e+02,0.000000000000000000e+00,1.070753283130907541e+01,0.000000000000000000e+00,7.643515192024539218e-01,0.000000000000000000e+00,-1.000000012046426079e+00,0.000000000000000000e+00 +3.041982161013510222e+01,1.737599999999999909e+02,0.000000000000000000e+00,1.070824667597455004e+01,0.000000000000000000e+00,7.634175972357405415e-01,0.000000000000000000e+00,-1.000000005813756365e+00,0.000000000000000000e+00 +3.042075546983245360e+01,1.737700000000000102e+02,0.000000000000000000e+00,1.070895960090085808e+01,0.000000000000000000e+00,7.624837375329589495e-01,0.000000000000000000e+00,-1.000000009524049993e+00,0.000000000000000000e+00 +3.042168926736019330e+01,1.737800000000000011e+02,0.000000000000000000e+00,1.070967160632990911e+01,0.000000000000000000e+00,7.615499399963243654e-01,0.000000000000000000e+00,-1.000000009362187026e+00,0.000000000000000000e+00 +3.042262300280676612e+01,1.737899999999999920e+02,0.000000000000000000e+00,1.071038269250322017e+01,0.000000000000000000e+00,7.606162045410083117e-01,0.000000000000000000e+00,-1.000000007806713942e+00,0.000000000000000000e+00 +3.042355667626056359e+01,1.738000000000000114e+02,0.000000000000000000e+00,1.071109285966192814e+01,0.000000000000000000e+00,7.596825310799221187e-01,0.000000000000000000e+00,-1.000000009373898768e+00,0.000000000000000000e+00 +3.042449028780992037e+01,1.738100000000000023e+02,0.000000000000000000e+00,1.071180210804678801e+01,0.000000000000000000e+00,7.587489195218150018e-01,0.000000000000000000e+00,-1.000000010429274333e+00,0.000000000000000000e+00 +3.042542383754311430e+01,1.738199999999999932e+02,0.000000000000000000e+00,1.071251043789816926e+01,0.000000000000000000e+00,7.578153697788841958e-01,0.000000000000000000e+00,-1.000000005296537875e+00,0.000000000000000000e+00 +3.042635732554837347e+01,1.738300000000000125e+02,0.000000000000000000e+00,1.071321784945605948e+01,0.000000000000000000e+00,7.568818817686799871e-01,0.000000000000000000e+00,-1.000000010722011279e+00,0.000000000000000000e+00 +3.042729075191387267e+01,1.738400000000000034e+02,0.000000000000000000e+00,1.071392434296006968e+01,0.000000000000000000e+00,7.559484553931743456e-01,0.000000000000000000e+00,-1.000000008796775530e+00,0.000000000000000000e+00 +3.042822411672772631e+01,1.738499999999999943e+02,0.000000000000000000e+00,1.071462991864942005e+01,0.000000000000000000e+00,7.550150905711109361e-01,0.000000000000000000e+00,-1.000000008112088778e+00,0.000000000000000000e+00 +3.042915742007799906e+01,1.738600000000000136e+02,0.000000000000000000e+00,1.071533457676295598e+01,0.000000000000000000e+00,7.540817872132679067e-01,0.000000000000000000e+00,-1.000000009104118792e+00,0.000000000000000000e+00 +3.043009066205269875e+01,1.738700000000000045e+02,0.000000000000000000e+00,1.071603831753914093e+01,0.000000000000000000e+00,7.531485452300705763e-01,0.000000000000000000e+00,-1.000000008130208284e+00,0.000000000000000000e+00 +3.043102384273978345e+01,1.738799999999999955e+02,0.000000000000000000e+00,1.071674114121605648e+01,0.000000000000000000e+00,7.522153645353977236e-01,0.000000000000000000e+00,-1.000000009703293724e+00,0.000000000000000000e+00 +3.043195696222715796e+01,1.738900000000000148e+02,0.000000000000000000e+00,1.071744304803140579e+01,0.000000000000000000e+00,7.512822450389704532e-01,0.000000000000000000e+00,-1.000000008137542418e+00,0.000000000000000000e+00 +3.043289002060266668e+01,1.739000000000000057e+02,0.000000000000000000e+00,1.071814403822251016e+01,0.000000000000000000e+00,7.503491866558692491e-01,0.000000000000000000e+00,-1.000000009986454996e+00,0.000000000000000000e+00 +3.043382301795410427e+01,1.739099999999999966e+02,0.000000000000000000e+00,1.071884411202631426e+01,0.000000000000000000e+00,7.494161892951132220e-01,0.000000000000000000e+00,-1.000000007519298961e+00,0.000000000000000000e+00 +3.043475595436921566e+01,1.739200000000000159e+02,0.000000000000000000e+00,1.071954326967938087e+01,0.000000000000000000e+00,7.484832528729878920e-01,0.000000000000000000e+00,-1.000000007289398418e+00,0.000000000000000000e+00 +3.043568882993568536e+01,1.739300000000000068e+02,0.000000000000000000e+00,1.072024151141789794e+01,0.000000000000000000e+00,7.475503772997179608e-01,0.000000000000000000e+00,-1.000000011769702768e+00,0.000000000000000000e+00 +3.043662164474114817e+01,1.739399999999999977e+02,0.000000000000000000e+00,1.072093883747767329e+01,0.000000000000000000e+00,7.466175624832750435e-01,0.000000000000000000e+00,-1.000000007099001609e+00,0.000000000000000000e+00 +3.043755439887318914e+01,1.739500000000000171e+02,0.000000000000000000e+00,1.072163524809413282e+01,0.000000000000000000e+00,7.456848083446139253e-01,0.000000000000000000e+00,-1.000000007996501905e+00,0.000000000000000000e+00 +3.043848709241933292e+01,1.739600000000000080e+02,0.000000000000000000e+00,1.072233074350233295e+01,0.000000000000000000e+00,7.447521147910123318e-01,0.000000000000000000e+00,-1.000000010807817752e+00,0.000000000000000000e+00 +3.043941972546705443e+01,1.739699999999999989e+02,0.000000000000000000e+00,1.072302532393694818e+01,0.000000000000000000e+00,7.438194817332102193e-01,0.000000000000000000e+00,-1.000000007790660117e+00,0.000000000000000000e+00 +3.044035229810377885e+01,1.739799999999999898e+02,0.000000000000000000e+00,1.072371898963227466e+01,0.000000000000000000e+00,7.428869090892210592e-01,0.000000000000000000e+00,-1.000000007539802116e+00,0.000000000000000000e+00 +3.044128481041687451e+01,1.739900000000000091e+02,0.000000000000000000e+00,1.072441174082223725e+01,0.000000000000000000e+00,7.419543967690953590e-01,0.000000000000000000e+00,-1.000000010482025692e+00,0.000000000000000000e+00 +3.044221726249365645e+01,1.740000000000000000e+02,0.000000000000000000e+00,1.072510357774038248e+01,0.000000000000000000e+00,7.410219446825389022e-01,0.000000000000000000e+00,-1.000000008869547319e+00,0.000000000000000000e+00 +3.044314965442138998e+01,1.740099999999999909e+02,0.000000000000000000e+00,1.072579450061987849e+01,0.000000000000000000e+00,7.400895527465346513e-01,0.000000000000000000e+00,-1.000000007211673703e+00,0.000000000000000000e+00 +3.044408198628728712e+01,1.740200000000000102e+02,0.000000000000000000e+00,1.072648450969352218e+01,0.000000000000000000e+00,7.391572208739131122e-01,0.000000000000000000e+00,-1.000000010019009844e+00,0.000000000000000000e+00 +3.044501425817850659e+01,1.740300000000000011e+02,0.000000000000000000e+00,1.072717360519373564e+01,0.000000000000000000e+00,7.382249489733521131e-01,0.000000000000000000e+00,-1.000000009538876355e+00,0.000000000000000000e+00 +3.044594647018215738e+01,1.740399999999999920e+02,0.000000000000000000e+00,1.072786178735256257e+01,0.000000000000000000e+00,7.372927369608097692e-01,0.000000000000000000e+00,-1.000000006191027468e+00,0.000000000000000000e+00 +3.044687862238529164e+01,1.740500000000000114e+02,0.000000000000000000e+00,1.072854905640167544e+01,0.000000000000000000e+00,7.363605847519045788e-01,0.000000000000000000e+00,-1.000000010618149027e+00,0.000000000000000000e+00 +3.044781071487491175e+01,1.740600000000000023e+02,0.000000000000000000e+00,1.072923541257237545e+01,0.000000000000000000e+00,7.354284922523867118e-01,0.000000000000000000e+00,-1.000000008928937589e+00,0.000000000000000000e+00 +3.044874274773797040e+01,1.740699999999999932e+02,0.000000000000000000e+00,1.072992085609558366e+01,0.000000000000000000e+00,7.344964593810069386e-01,0.000000000000000000e+00,-1.000000007674751723e+00,0.000000000000000000e+00 +3.044967472106136341e+01,1.740800000000000125e+02,0.000000000000000000e+00,1.073060538720185342e+01,0.000000000000000000e+00,7.335644860504612064e-01,0.000000000000000000e+00,-1.000000011365023367e+00,0.000000000000000000e+00 +3.045060663493193687e+01,1.740900000000000034e+02,0.000000000000000000e+00,1.073128900612136505e+01,0.000000000000000000e+00,7.326325721692950044e-01,0.000000000000000000e+00,-1.000000006098741068e+00,0.000000000000000000e+00 +3.045153848943648711e+01,1.740999999999999943e+02,0.000000000000000000e+00,1.073197171308392228e+01,0.000000000000000000e+00,7.317007176590601958e-01,0.000000000000000000e+00,-1.000000008656360295e+00,0.000000000000000000e+00 +3.045247028466175720e+01,1.741100000000000136e+02,0.000000000000000000e+00,1.073265350831896470e+01,0.000000000000000000e+00,7.307689224257227778e-01,0.000000000000000000e+00,-1.000000011272118572e+00,0.000000000000000000e+00 +3.045340202069444047e+01,1.741200000000000045e+02,0.000000000000000000e+00,1.073333439205555351e+01,0.000000000000000000e+00,7.298371863825373618e-01,0.000000000000000000e+00,-1.000000006174601275e+00,0.000000000000000000e+00 +3.045433369762117337e+01,1.741299999999999955e+02,0.000000000000000000e+00,1.073401436452237867e+01,0.000000000000000000e+00,7.289055094500505039e-01,0.000000000000000000e+00,-1.000000010148350826e+00,0.000000000000000000e+00 +3.045526531552854621e+01,1.741400000000000148e+02,0.000000000000000000e+00,1.073469342594776599e+01,0.000000000000000000e+00,7.279738915332220062e-01,0.000000000000000000e+00,-1.000000009281779567e+00,0.000000000000000000e+00 +3.045619687450309598e+01,1.741500000000000057e+02,0.000000000000000000e+00,1.073537157655966290e+01,0.000000000000000000e+00,7.270423325500240397e-01,0.000000000000000000e+00,-1.000000008079007241e+00,0.000000000000000000e+00 +3.045712837463130995e+01,1.741599999999999966e+02,0.000000000000000000e+00,1.073604881658565091e+01,0.000000000000000000e+00,7.261108324142835357e-01,0.000000000000000000e+00,-1.000000008999703205e+00,0.000000000000000000e+00 +3.045805981599962209e+01,1.741700000000000159e+02,0.000000000000000000e+00,1.073672514625294205e+01,0.000000000000000000e+00,7.251793910375874397e-01,0.000000000000000000e+00,-1.000000008359332115e+00,0.000000000000000000e+00 +3.045899119869441662e+01,1.741800000000000068e+02,0.000000000000000000e+00,1.073740056578837709e+01,0.000000000000000000e+00,7.242480083350057996e-01,0.000000000000000000e+00,-1.000000010663901984e+00,0.000000000000000000e+00 +3.045992252280202806e+01,1.741899999999999977e+02,0.000000000000000000e+00,1.073807507541842909e+01,0.000000000000000000e+00,7.233166842174627575e-01,0.000000000000000000e+00,-1.000000006081440684e+00,0.000000000000000000e+00 +3.046085378840873759e+01,1.742000000000000171e+02,0.000000000000000000e+00,1.073874867536919986e+01,0.000000000000000000e+00,7.223854186050899795e-01,0.000000000000000000e+00,-1.000000011406577460e+00,0.000000000000000000e+00 +3.046178499560077668e+01,1.742100000000000080e+02,0.000000000000000000e+00,1.073942136586642881e+01,0.000000000000000000e+00,7.214542114024293795e-01,0.000000000000000000e+00,-1.000000006562722810e+00,0.000000000000000000e+00 +3.046271614446432707e+01,1.742199999999999989e+02,0.000000000000000000e+00,1.074009314713547880e+01,0.000000000000000000e+00,7.205230625327695426e-01,0.000000000000000000e+00,-1.000000010393723660e+00,0.000000000000000000e+00 +3.046364723508551720e+01,1.742299999999999898e+02,0.000000000000000000e+00,1.074076401940135383e+01,0.000000000000000000e+00,7.195919719019024940e-01,0.000000000000000000e+00,-1.000000008964217146e+00,0.000000000000000000e+00 +3.046457826755042575e+01,1.742400000000000091e+02,0.000000000000000000e+00,1.074143398288868312e+01,0.000000000000000000e+00,7.186609394286465058e-01,0.000000000000000000e+00,-1.000000006775960015e+00,0.000000000000000000e+00 +3.046550924194508525e+01,1.742500000000000000e+02,0.000000000000000000e+00,1.074210303782173348e+01,0.000000000000000000e+00,7.177299650276782739e-01,0.000000000000000000e+00,-1.000000010382910309e+00,0.000000000000000000e+00 +3.046644015835547492e+01,1.742599999999999909e+02,0.000000000000000000e+00,1.074277118442440582e+01,0.000000000000000000e+00,7.167990486076234458e-01,0.000000000000000000e+00,-1.000000009940391843e+00,0.000000000000000000e+00 +3.046737101686752069e+01,1.742700000000000102e+02,0.000000000000000000e+00,1.074343842292022977e+01,0.000000000000000000e+00,7.158681900863228531e-01,0.000000000000000000e+00,-1.000000005849624118e+00,0.000000000000000000e+00 +3.046830181756710587e+01,1.742800000000000011e+02,0.000000000000000000e+00,1.074410475353237260e+01,0.000000000000000000e+00,7.149373893812932534e-01,0.000000000000000000e+00,-1.000000010814373175e+00,0.000000000000000000e+00 +3.046923256054005691e+01,1.742899999999999920e+02,0.000000000000000000e+00,1.074477017648363919e+01,0.000000000000000000e+00,7.140066463982768230e-01,0.000000000000000000e+00,-1.000000008833381804e+00,0.000000000000000000e+00 +3.047016324587215408e+01,1.743000000000000114e+02,0.000000000000000000e+00,1.074543469199646140e+01,0.000000000000000000e+00,7.130759610579593399e-01,0.000000000000000000e+00,-1.000000008508033833e+00,0.000000000000000000e+00 +3.047109387364912436e+01,1.743100000000000023e+02,0.000000000000000000e+00,1.074609830029291224e+01,0.000000000000000000e+00,7.121453332730705021e-01,0.000000000000000000e+00,-1.000000010239001424e+00,0.000000000000000000e+00 +3.047202444395664855e+01,1.743199999999999932e+02,0.000000000000000000e+00,1.074676100159469883e+01,0.000000000000000000e+00,7.112147629560171547e-01,0.000000000000000000e+00,-1.000000006219533111e+00,0.000000000000000000e+00 +3.047295495688035771e+01,1.743300000000000125e+02,0.000000000000000000e+00,1.074742279612316231e+01,0.000000000000000000e+00,7.102842500265204029e-01,0.000000000000000000e+00,-1.000000011208033390e+00,0.000000000000000000e+00 +3.047388541250583316e+01,1.743400000000000034e+02,0.000000000000000000e+00,1.074808368409928505e+01,0.000000000000000000e+00,7.093537943906178533e-01,0.000000000000000000e+00,-1.000000007137005875e+00,0.000000000000000000e+00 +3.047481581091860292e+01,1.743499999999999943e+02,0.000000000000000000e+00,1.074874366574367812e+01,0.000000000000000000e+00,7.084233959712080697e-01,0.000000000000000000e+00,-1.000000010817949647e+00,0.000000000000000000e+00 +3.047574615220414884e+01,1.743600000000000136e+02,0.000000000000000000e+00,1.074940274127659734e+01,0.000000000000000000e+00,7.074930546755969774e-01,0.000000000000000000e+00,-1.000000008281320296e+00,0.000000000000000000e+00 +3.047667643644790658e+01,1.743700000000000045e+02,0.000000000000000000e+00,1.075006091091792904e+01,0.000000000000000000e+00,7.065627704241367324e-01,0.000000000000000000e+00,-1.000000008131304297e+00,0.000000000000000000e+00 +3.047760666373525495e+01,1.743799999999999955e+02,0.000000000000000000e+00,1.075071817488720249e+01,0.000000000000000000e+00,7.056325431292237438e-01,0.000000000000000000e+00,-1.000000008709399424e+00,0.000000000000000000e+00 +3.047853683415153014e+01,1.743900000000000148e+02,0.000000000000000000e+00,1.075137453340358284e+01,0.000000000000000000e+00,7.047023727048465913e-01,0.000000000000000000e+00,-1.000000008356719094e+00,0.000000000000000000e+00 +3.047946694778201859e+01,1.744000000000000057e+02,0.000000000000000000e+00,1.075202998668587284e+01,0.000000000000000000e+00,7.037722590665859146e-01,0.000000000000000000e+00,-1.000000009518582589e+00,0.000000000000000000e+00 +3.048039700471195346e+01,1.744099999999999966e+02,0.000000000000000000e+00,1.075268453495251464e+01,0.000000000000000000e+00,7.028422021277968001e-01,0.000000000000000000e+00,-1.000000010534057848e+00,0.000000000000000000e+00 +3.048132700502652526e+01,1.744200000000000159e+02,0.000000000000000000e+00,1.075333817842158801e+01,0.000000000000000000e+00,7.019122018034280597e-01,0.000000000000000000e+00,-1.000000007685405423e+00,0.000000000000000000e+00 +3.048225694881087122e+01,1.744300000000000068e+02,0.000000000000000000e+00,1.075399091731081214e+01,0.000000000000000000e+00,7.009822580119344781e-01,0.000000000000000000e+00,-1.000000007524693535e+00,0.000000000000000000e+00 +3.048318683615008240e+01,1.744399999999999977e+02,0.000000000000000000e+00,1.075464275183754914e+01,0.000000000000000000e+00,7.000523706657261203e-01,0.000000000000000000e+00,-1.000000010442864351e+00,0.000000000000000000e+00 +3.048411666712920010e+01,1.744500000000000171e+02,0.000000000000000000e+00,1.075529368221879878e+01,0.000000000000000000e+00,6.991225396768985245e-01,0.000000000000000000e+00,-1.000000008610349322e+00,0.000000000000000000e+00 +3.048504644183321588e+01,1.744600000000000080e+02,0.000000000000000000e+00,1.075594370867119842e+01,0.000000000000000000e+00,6.981927649648759227e-01,0.000000000000000000e+00,-1.000000008578403543e+00,0.000000000000000000e+00 +3.048597616034707869e+01,1.744699999999999989e+02,0.000000000000000000e+00,1.075659283141103018e+01,0.000000000000000000e+00,6.972630464430392694e-01,0.000000000000000000e+00,-1.000000008679703623e+00,0.000000000000000000e+00 +3.048690582275568062e+01,1.744799999999999898e+02,0.000000000000000000e+00,1.075724105065421554e+01,0.000000000000000000e+00,6.963333840263681296e-01,0.000000000000000000e+00,-1.000000009301088122e+00,0.000000000000000000e+00 +3.048783542914387112e+01,1.744900000000000091e+02,0.000000000000000000e+00,1.075788836661631720e+01,0.000000000000000000e+00,6.954037776295306506e-01,0.000000000000000000e+00,-1.000000008772337079e+00,0.000000000000000000e+00 +3.048876497959645349e+01,1.745000000000000000e+02,0.000000000000000000e+00,1.075853477951253900e+01,0.000000000000000000e+00,6.944742271687956991e-01,0.000000000000000000e+00,-1.000000009534104173e+00,0.000000000000000000e+00 +3.048969447419817769e+01,1.745099999999999909e+02,0.000000000000000000e+00,1.075918028955772776e+01,0.000000000000000000e+00,6.935447325582113631e-01,0.000000000000000000e+00,-1.000000007858850459e+00,0.000000000000000000e+00 +3.049062391303374753e+01,1.745200000000000102e+02,0.000000000000000000e+00,1.075982489696637145e+01,0.000000000000000000e+00,6.926152937153383649e-01,0.000000000000000000e+00,-1.000000010298247810e+00,0.000000000000000000e+00 +3.049155329618782062e+01,1.745300000000000011e+02,0.000000000000000000e+00,1.076046860195260280e+01,0.000000000000000000e+00,6.916859105516958151e-01,0.000000000000000000e+00,-1.000000006952574738e+00,0.000000000000000000e+00 +3.049248262374500484e+01,1.745399999999999920e+02,0.000000000000000000e+00,1.076111140473019390e+01,0.000000000000000000e+00,6.907565829880513153e-01,0.000000000000000000e+00,-1.000000010544361162e+00,0.000000000000000000e+00 +3.049341189578986189e+01,1.745500000000000114e+02,0.000000000000000000e+00,1.076175330551256515e+01,0.000000000000000000e+00,6.898273109333964426e-01,0.000000000000000000e+00,-1.000000007055871665e+00,0.000000000000000000e+00 +3.049434111240690370e+01,1.745600000000000023e+02,0.000000000000000000e+00,1.076239430451277457e+01,0.000000000000000000e+00,6.888980943097969822e-01,0.000000000000000000e+00,-1.000000011267933031e+00,0.000000000000000000e+00 +3.049527027368059962e+01,1.745699999999999932e+02,0.000000000000000000e+00,1.076303440194353023e+01,0.000000000000000000e+00,6.879689330256312241e-01,0.000000000000000000e+00,-1.000000007100772637e+00,0.000000000000000000e+00 +3.049619937969536920e+01,1.745800000000000125e+02,0.000000000000000000e+00,1.076367359801717782e+01,0.000000000000000000e+00,6.870398270042659128e-01,0.000000000000000000e+00,-1.000000009335956896e+00,0.000000000000000000e+00 +3.049712843053558231e+01,1.745900000000000034e+02,0.000000000000000000e+00,1.076431189294571489e+01,0.000000000000000000e+00,6.861107761553808526e-01,0.000000000000000000e+00,-1.000000010121885774e+00,0.000000000000000000e+00 +3.049805742628556260e+01,1.745999999999999943e+02,0.000000000000000000e+00,1.076494928694077835e+01,0.000000000000000000e+00,6.851817803959981967e-01,0.000000000000000000e+00,-1.000000007775915245e+00,0.000000000000000000e+00 +3.049898636702958754e+01,1.746100000000000136e+02,0.000000000000000000e+00,1.076558578021365165e+01,0.000000000000000000e+00,6.842528396447500327e-01,0.000000000000000000e+00,-1.000000008850573607e+00,0.000000000000000000e+00 +3.049991525285188843e+01,1.746200000000000045e+02,0.000000000000000000e+00,1.076622137297526649e+01,0.000000000000000000e+00,6.833239538142283909e-01,0.000000000000000000e+00,-1.000000009604803841e+00,0.000000000000000000e+00 +3.050084408383664680e+01,1.746299999999999955e+02,0.000000000000000000e+00,1.076685606543619755e+01,0.000000000000000000e+00,6.823951228205475950e-01,0.000000000000000000e+00,-1.000000008354146042e+00,0.000000000000000000e+00 +3.050177286006800159e+01,1.746400000000000148e+02,0.000000000000000000e+00,1.076748985780666601e+01,0.000000000000000000e+00,6.814663465814332355e-01,0.000000000000000000e+00,-1.000000009591638372e+00,0.000000000000000000e+00 +3.050270158163004197e+01,1.746500000000000057e+02,0.000000000000000000e+00,1.076812275029654131e+01,0.000000000000000000e+00,6.805376250104845370e-01,0.000000000000000000e+00,-1.000000007512632072e+00,0.000000000000000000e+00 +3.050363024860681094e+01,1.746599999999999966e+02,0.000000000000000000e+00,1.076875474311533765e+01,0.000000000000000000e+00,6.796089580267383745e-01,0.000000000000000000e+00,-1.000000010728660627e+00,0.000000000000000000e+00 +3.050455886108230530e+01,1.746700000000000159e+02,0.000000000000000000e+00,1.076938583647221925e+01,0.000000000000000000e+00,6.786803455412808717e-01,0.000000000000000000e+00,-1.000000007252750400e+00,0.000000000000000000e+00 +3.050548741914047568e+01,1.746800000000000068e+02,0.000000000000000000e+00,1.077001603057599333e+01,0.000000000000000000e+00,6.777517874763760997e-01,0.000000000000000000e+00,-1.000000009816488733e+00,0.000000000000000000e+00 +3.050641592286522652e+01,1.746899999999999977e+02,0.000000000000000000e+00,1.077064532563512067e+01,0.000000000000000000e+00,6.768232837425121051e-01,0.000000000000000000e+00,-1.000000008489380310e+00,0.000000000000000000e+00 +3.050734437234041252e+01,1.747000000000000171e+02,0.000000000000000000e+00,1.077127372185770504e+01,0.000000000000000000e+00,6.758948342594441883e-01,0.000000000000000000e+00,-1.000000009822850311e+00,0.000000000000000000e+00 +3.050827276764984575e+01,1.747100000000000080e+02,0.000000000000000000e+00,1.077190121945150203e+01,0.000000000000000000e+00,6.749664389408909226e-01,0.000000000000000000e+00,-1.000000008003574248e+00,0.000000000000000000e+00 +3.050920110887729209e+01,1.747199999999999989e+02,0.000000000000000000e+00,1.077252781862391373e+01,0.000000000000000000e+00,6.740380977060141943e-01,0.000000000000000000e+00,-1.000000009583085880e+00,0.000000000000000000e+00 +3.051012939610647123e+01,1.747299999999999898e+02,0.000000000000000000e+00,1.077315351958199408e+01,0.000000000000000000e+00,6.731098104679397176e-01,0.000000000000000000e+00,-1.000000008745769886e+00,0.000000000000000000e+00 +3.051105762942105315e+01,1.747400000000000091e+02,0.000000000000000000e+00,1.077377832253244350e+01,0.000000000000000000e+00,6.721815771452379629e-01,0.000000000000000000e+00,-1.000000007919128686e+00,0.000000000000000000e+00 +3.051198580890466872e+01,1.747500000000000000e+02,0.000000000000000000e+00,1.077440222768161426e+01,0.000000000000000000e+00,6.712533976542717218e-01,0.000000000000000000e+00,-1.000000009532092449e+00,0.000000000000000000e+00 +3.051291393464089907e+01,1.747599999999999909e+02,0.000000000000000000e+00,1.077502523523550870e+01,0.000000000000000000e+00,6.703252719091952194e-01,0.000000000000000000e+00,-1.000000009826363057e+00,0.000000000000000000e+00 +3.051384200671327918e+01,1.747700000000000102e+02,0.000000000000000000e+00,1.077564734539977742e+01,0.000000000000000000e+00,6.693971998276967428e-01,0.000000000000000000e+00,-1.000000007103370336e+00,0.000000000000000000e+00 +3.051477002520529780e+01,1.747800000000000011e+02,0.000000000000000000e+00,1.077626855837972286e+01,0.000000000000000000e+00,6.684691813290862816e-01,0.000000000000000000e+00,-1.000000012040881181e+00,0.000000000000000000e+00 +3.051569799020040108e+01,1.747899999999999920e+02,0.000000000000000000e+00,1.077688887438030108e+01,0.000000000000000000e+00,6.675412163228102713e-01,0.000000000000000000e+00,-1.000000006436841726e+00,0.000000000000000000e+00 +3.051662590178198542e+01,1.748000000000000114e+02,0.000000000000000000e+00,1.077750829360611284e+01,0.000000000000000000e+00,6.666133047352517105e-01,0.000000000000000000e+00,-1.000000009220249675e+00,0.000000000000000000e+00 +3.051755376003340814e+01,1.748100000000000023e+02,0.000000000000000000e+00,1.077812681626141966e+01,0.000000000000000000e+00,6.656854464752738343e-01,0.000000000000000000e+00,-1.000000008374579474e+00,0.000000000000000000e+00 +3.051848156503797682e+01,1.748199999999999932e+02,0.000000000000000000e+00,1.077874444255012776e+01,0.000000000000000000e+00,6.647576414629354780e-01,0.000000000000000000e+00,-1.000000010451626453e+00,0.000000000000000000e+00 +3.051940931687895286e+01,1.748300000000000125e+02,0.000000000000000000e+00,1.077936117267579874e+01,0.000000000000000000e+00,6.638298896122616366e-01,0.000000000000000000e+00,-1.000000009620271690e+00,0.000000000000000000e+00 +3.052033701563955859e+01,1.748400000000000034e+02,0.000000000000000000e+00,1.077997700684164428e+01,0.000000000000000000e+00,6.629021908427323861e-01,0.000000000000000000e+00,-1.000000006239348593e+00,0.000000000000000000e+00 +3.052126466140296301e+01,1.748499999999999943e+02,0.000000000000000000e+00,1.078059194525053144e+01,0.000000000000000000e+00,6.619745450735394776e-01,0.000000000000000000e+00,-1.000000010989746890e+00,0.000000000000000000e+00 +3.052219225425229610e+01,1.748600000000000136e+02,0.000000000000000000e+00,1.078120598810498265e+01,0.000000000000000000e+00,6.610469522140116627e-01,0.000000000000000000e+00,-1.000000007714675121e+00,0.000000000000000000e+00 +3.052311979427064159e+01,1.748700000000000045e+02,0.000000000000000000e+00,1.078181913560716687e+01,0.000000000000000000e+00,6.601194121885098909e-01,0.000000000000000000e+00,-1.000000011223650009e+00,0.000000000000000000e+00 +3.052404728154103708e+01,1.748799999999999955e+02,0.000000000000000000e+00,1.078243138795891376e+01,0.000000000000000000e+00,6.591919249077029530e-01,0.000000000000000000e+00,-1.000000007419733494e+00,0.000000000000000000e+00 +3.052497471614648106e+01,1.748900000000000148e+02,0.000000000000000000e+00,1.078304274536170126e+01,0.000000000000000000e+00,6.582644902953793675e-01,0.000000000000000000e+00,-1.000000006983270628e+00,0.000000000000000000e+00 +3.052590209816991873e+01,1.749000000000000057e+02,0.000000000000000000e+00,1.078365320801666805e+01,0.000000000000000000e+00,6.573371082654663189e-01,0.000000000000000000e+00,-1.000000012337156408e+00,0.000000000000000000e+00 +3.052682942769425622e+01,1.749099999999999966e+02,0.000000000000000000e+00,1.078426277612460460e+01,0.000000000000000000e+00,6.564097787296891973e-01,0.000000000000000000e+00,-1.000000007310768879e+00,0.000000000000000000e+00 +3.052775670480235348e+01,1.749200000000000159e+02,0.000000000000000000e+00,1.078487144988595148e+01,0.000000000000000000e+00,6.554825016148133621e-01,0.000000000000000000e+00,-1.000000008783256567e+00,0.000000000000000000e+00 +3.052868392957702781e+01,1.749300000000000068e+02,0.000000000000000000e+00,1.078547922950081350e+01,0.000000000000000000e+00,6.545552768319961023e-01,0.000000000000000000e+00,-1.000000008845205679e+00,0.000000000000000000e+00 +3.052961110210105034e+01,1.749399999999999977e+02,0.000000000000000000e+00,1.078608611516894555e+01,0.000000000000000000e+00,6.536281042997733604e-01,0.000000000000000000e+00,-1.000000009915047672e+00,0.000000000000000000e+00 +3.053053822245714954e+01,1.749500000000000171e+02,0.000000000000000000e+00,1.078669210708975967e+01,0.000000000000000000e+00,6.527009839344828368e-01,0.000000000000000000e+00,-1.000000008211522351e+00,0.000000000000000000e+00 +3.053146529072800774e+01,1.749600000000000080e+02,0.000000000000000000e+00,1.078729720546232329e+01,0.000000000000000000e+00,6.517739156560119484e-01,0.000000000000000000e+00,-1.000000010286064889e+00,0.000000000000000000e+00 +3.053239230699626461e+01,1.749699999999999989e+02,0.000000000000000000e+00,1.078790141048536277e+01,0.000000000000000000e+00,6.508468993782183798e-01,0.000000000000000000e+00,-1.000000006153679788e+00,0.000000000000000000e+00 +3.053331927134451718e+01,1.749799999999999898e+02,0.000000000000000000e+00,1.078850472235725810e+01,0.000000000000000000e+00,6.499199350242600426e-01,0.000000000000000000e+00,-1.000000012702727981e+00,0.000000000000000000e+00 +3.053424618385531986e+01,1.749900000000000091e+02,0.000000000000000000e+00,1.078910714127605175e+01,0.000000000000000000e+00,6.489930225016836696e-01,0.000000000000000000e+00,-1.000000005472396980e+00,0.000000000000000000e+00 +3.053517304461117732e+01,1.750000000000000000e+02,0.000000000000000000e+00,1.078970866743943446e+01,0.000000000000000000e+00,6.480661617407531550e-01,0.000000000000000000e+00,-1.000000011690426627e+00,0.000000000000000000e+00 +3.053609985369455515e+01,1.750099999999999909e+02,0.000000000000000000e+00,1.079030930104476660e+01,0.000000000000000000e+00,6.471393526465389900e-01,0.000000000000000000e+00,-1.000000006890441107e+00,0.000000000000000000e+00 +3.053702661118787631e+01,1.750200000000000102e+02,0.000000000000000000e+00,1.079090904228905501e+01,0.000000000000000000e+00,6.462125951468317142e-01,0.000000000000000000e+00,-1.000000010031686815e+00,0.000000000000000000e+00 +3.053795331717351758e+01,1.750300000000000011e+02,0.000000000000000000e+00,1.079150789136897437e+01,0.000000000000000000e+00,6.452858891518939988e-01,0.000000000000000000e+00,-1.000000009050749705e+00,0.000000000000000000e+00 +3.053887997173381308e+01,1.750399999999999920e+02,0.000000000000000000e+00,1.079210584848085119e+01,0.000000000000000000e+00,6.443592345832117596e-01,0.000000000000000000e+00,-1.000000008430254272e+00,0.000000000000000000e+00 +3.053980657495105433e+01,1.750500000000000114e+02,0.000000000000000000e+00,1.079270291382067448e+01,0.000000000000000000e+00,6.434326313581599788e-01,0.000000000000000000e+00,-1.000000010583546262e+00,0.000000000000000000e+00 +3.054073312690748665e+01,1.750600000000000023e+02,0.000000000000000000e+00,1.079329908758409218e+01,0.000000000000000000e+00,6.425060793919208368e-01,0.000000000000000000e+00,-1.000000007578918160e+00,0.000000000000000000e+00 +3.054165962768531628e+01,1.750699999999999932e+02,0.000000000000000000e+00,1.079389436996640939e+01,0.000000000000000000e+00,6.415795786070688234e-01,0.000000000000000000e+00,-1.000000008035809573e+00,0.000000000000000000e+00 +3.054258607736670683e+01,1.750800000000000125e+02,0.000000000000000000e+00,1.079448876116259548e+01,0.000000000000000000e+00,6.406531289182352262e-01,0.000000000000000000e+00,-1.000000010229074698e+00,0.000000000000000000e+00 +3.054351247603377217e+01,1.750900000000000034e+02,0.000000000000000000e+00,1.079508226136727700e+01,0.000000000000000000e+00,6.397267302416930201e-01,0.000000000000000000e+00,-1.000000008290498954e+00,0.000000000000000000e+00 +3.054443882376859065e+01,1.750999999999999943e+02,0.000000000000000000e+00,1.079567487077473942e+01,0.000000000000000000e+00,6.388003824991943524e-01,0.000000000000000000e+00,-1.000000010841926690e+00,0.000000000000000000e+00 +3.054536512065319442e+01,1.751100000000000136e+02,0.000000000000000000e+00,1.079626658957893248e+01,0.000000000000000000e+00,6.378740856045471697e-01,0.000000000000000000e+00,-1.000000005801573888e+00,0.000000000000000000e+00 +3.054629136676957302e+01,1.751200000000000045e+02,0.000000000000000000e+00,1.079685741797346310e+01,0.000000000000000000e+00,6.369478394827935430e-01,0.000000000000000000e+00,-1.000000012144347306e+00,0.000000000000000000e+00 +3.054721756219967688e+01,1.751299999999999955e+02,0.000000000000000000e+00,1.079744735615160600e+01,0.000000000000000000e+00,6.360216440414425687e-01,0.000000000000000000e+00,-1.000000007432385374e+00,0.000000000000000000e+00 +3.054814370702540671e+01,1.751400000000000148e+02,0.000000000000000000e+00,1.079803640430628775e+01,0.000000000000000000e+00,6.350954992088283513e-01,0.000000000000000000e+00,-1.000000008569999155e+00,0.000000000000000000e+00 +3.054906980132862770e+01,1.751500000000000057e+02,0.000000000000000000e+00,1.079862456263010628e+01,0.000000000000000000e+00,6.341694048976708187e-01,0.000000000000000000e+00,-1.000000009682988411e+00,0.000000000000000000e+00 +3.054999584519115885e+01,1.751599999999999966e+02,0.000000000000000000e+00,1.079921183131531670e+01,0.000000000000000000e+00,6.332433610261729573e-01,0.000000000000000000e+00,-1.000000009036967397e+00,0.000000000000000000e+00 +3.055092183869477651e+01,1.751700000000000159e+02,0.000000000000000000e+00,1.079979821055383660e+01,0.000000000000000000e+00,6.323173675141861017e-01,0.000000000000000000e+00,-1.000000009039693660e+00,0.000000000000000000e+00 +3.055184778192121797e+01,1.751800000000000068e+02,0.000000000000000000e+00,1.080038370053724783e+01,0.000000000000000000e+00,6.313914242793741138e-01,0.000000000000000000e+00,-1.000000010027103814e+00,0.000000000000000000e+00 +3.055277367495217433e+01,1.751899999999999977e+02,0.000000000000000000e+00,1.080096830145679476e+01,0.000000000000000000e+00,6.304655312391320710e-01,0.000000000000000000e+00,-1.000000006117773177e+00,0.000000000000000000e+00 +3.055369951786930116e+01,1.752000000000000171e+02,0.000000000000000000e+00,1.080155201350338423e+01,0.000000000000000000e+00,6.295396883163425494e-01,0.000000000000000000e+00,-1.000000012152520101e+00,0.000000000000000000e+00 +3.055462531075420429e+01,1.752100000000000080e+02,0.000000000000000000e+00,1.080213483686759091e+01,0.000000000000000000e+00,6.286138954201898610e-01,0.000000000000000000e+00,-1.000000007740975860e+00,0.000000000000000000e+00 +3.055555105368845048e+01,1.752199999999999989e+02,0.000000000000000000e+00,1.080271677173964484e+01,0.000000000000000000e+00,6.276881524787779609e-01,0.000000000000000000e+00,-1.000000007722807283e+00,0.000000000000000000e+00 +3.055647674675356384e+01,1.752299999999999898e+02,0.000000000000000000e+00,1.080329781830944924e+01,0.000000000000000000e+00,6.267624594065140942e-01,0.000000000000000000e+00,-1.000000010359709979e+00,0.000000000000000000e+00 +3.055740239003103298e+01,1.752400000000000091e+02,0.000000000000000000e+00,1.080387797676656803e+01,0.000000000000000000e+00,6.258368161194569623e-01,0.000000000000000000e+00,-1.000000007689938020e+00,0.000000000000000000e+00 +3.055832798360229674e+01,1.752500000000000000e+02,0.000000000000000000e+00,1.080445724730022761e+01,0.000000000000000000e+00,6.249112225410766719e-01,0.000000000000000000e+00,-1.000000010411485452e+00,0.000000000000000000e+00 +3.055925352754875490e+01,1.752599999999999909e+02,0.000000000000000000e+00,1.080503563009932400e+01,0.000000000000000000e+00,6.239856785849826615e-01,0.000000000000000000e+00,-1.000000008486948477e+00,0.000000000000000000e+00 +3.056017902195176816e+01,1.752700000000000102e+02,0.000000000000000000e+00,1.080561312535241392e+01,0.000000000000000000e+00,6.230601841741162383e-01,0.000000000000000000e+00,-1.000000010540939899e+00,0.000000000000000000e+00 +3.056110446689265103e+01,1.752800000000000011e+02,0.000000000000000000e+00,1.080618973324772369e+01,0.000000000000000000e+00,6.221347392234778395e-01,0.000000000000000000e+00,-1.000000006531939878e+00,0.000000000000000000e+00 +3.056202986245268249e+01,1.752899999999999920e+02,0.000000000000000000e+00,1.080676545397314214e+01,0.000000000000000000e+00,6.212093436574022132e-01,0.000000000000000000e+00,-1.000000011308523007e+00,0.000000000000000000e+00 +3.056295520871309535e+01,1.753000000000000114e+02,0.000000000000000000e+00,1.080734028771622945e+01,0.000000000000000000e+00,6.202839973865243994e-01,0.000000000000000000e+00,-1.000000006528209084e+00,0.000000000000000000e+00 +3.056388050575508331e+01,1.753100000000000023e+02,0.000000000000000000e+00,1.080791423466420476e+01,0.000000000000000000e+00,6.193587003384941614e-01,0.000000000000000000e+00,-1.000000011189623672e+00,0.000000000000000000e+00 +3.056480575365980101e+01,1.753199999999999932e+02,0.000000000000000000e+00,1.080848729500396210e+01,0.000000000000000000e+00,6.184334524234225139e-01,0.000000000000000000e+00,-1.000000006945625186e+00,0.000000000000000000e+00 +3.056573095250836047e+01,1.753300000000000125e+02,0.000000000000000000e+00,1.080905946892205449e+01,0.000000000000000000e+00,6.175082535684376372e-01,0.000000000000000000e+00,-1.000000010722026600e+00,0.000000000000000000e+00 +3.056665610238183106e+01,1.753400000000000034e+02,0.000000000000000000e+00,1.080963075660470984e+01,0.000000000000000000e+00,6.165831036850484281e-01,0.000000000000000000e+00,-1.000000008317281086e+00,0.000000000000000000e+00 +3.056758120336124307e+01,1.753499999999999943e+02,0.000000000000000000e+00,1.081020115823781680e+01,0.000000000000000000e+00,6.156580026979436848e-01,0.000000000000000000e+00,-1.000000008356691783e+00,0.000000000000000000e+00 +3.056850625552758416e+01,1.753600000000000136e+02,0.000000000000000000e+00,1.081077067400693714e+01,0.000000000000000000e+00,6.147329505238732228e-01,0.000000000000000000e+00,-1.000000011165260050e+00,0.000000000000000000e+00 +3.056943125896180291e+01,1.753700000000000045e+02,0.000000000000000000e+00,1.081133930409729871e+01,0.000000000000000000e+00,6.138079470793272874e-01,0.000000000000000000e+00,-1.000000006685133558e+00,0.000000000000000000e+00 +3.057035621374480527e+01,1.753799999999999955e+02,0.000000000000000000e+00,1.081190704869379537e+01,0.000000000000000000e+00,6.128829922901402050e-01,0.000000000000000000e+00,-1.000000009771470078e+00,0.000000000000000000e+00 +3.057128111995746167e+01,1.753900000000000148e+02,0.000000000000000000e+00,1.081247390798099595e+01,0.000000000000000000e+00,6.119580860684461499e-01,0.000000000000000000e+00,-1.000000008288727260e+00,0.000000000000000000e+00 +3.057220597768059633e+01,1.754000000000000057e+02,0.000000000000000000e+00,1.081303988214313172e+01,0.000000000000000000e+00,6.110332283376445073e-01,0.000000000000000000e+00,-1.000000010863821842e+00,0.000000000000000000e+00 +3.057313078699499798e+01,1.754099999999999966e+02,0.000000000000000000e+00,1.081360497136410714e+01,0.000000000000000000e+00,6.101084190131961238e-01,0.000000000000000000e+00,-1.000000007432446214e+00,0.000000000000000000e+00 +3.057405554798141267e+01,1.754200000000000159e+02,0.000000000000000000e+00,1.081416917582749271e+01,0.000000000000000000e+00,6.091836580199098128e-01,0.000000000000000000e+00,-1.000000010776868287e+00,0.000000000000000000e+00 +3.057498026072054387e+01,1.754300000000000068e+02,0.000000000000000000e+00,1.081473249571653383e+01,0.000000000000000000e+00,6.082589452708138111e-01,0.000000000000000000e+00,-1.000000006674759856e+00,0.000000000000000000e+00 +3.057590492529305592e+01,1.754399999999999977e+02,0.000000000000000000e+00,1.081529493121414021e+01,0.000000000000000000e+00,6.073342806921283588e-01,0.000000000000000000e+00,-1.000000009987084493e+00,0.000000000000000000e+00 +3.057682954177957768e+01,1.754500000000000171e+02,0.000000000000000000e+00,1.081585648250289822e+01,0.000000000000000000e+00,6.064096641963719891e-01,0.000000000000000000e+00,-1.000000010643531612e+00,0.000000000000000000e+00 +3.057775411026069534e+01,1.754600000000000080e+02,0.000000000000000000e+00,1.081641714976505853e+01,0.000000000000000000e+00,6.054850957054149774e-01,0.000000000000000000e+00,-1.000000006882309611e+00,0.000000000000000000e+00 +3.057867863081695248e+01,1.754699999999999989e+02,0.000000000000000000e+00,1.081697693318254494e+01,0.000000000000000000e+00,6.045605751427959307e-01,0.000000000000000000e+00,-1.000000009410268786e+00,0.000000000000000000e+00 +3.057960310352885358e+01,1.754799999999999898e+02,0.000000000000000000e+00,1.081753583293695620e+01,0.000000000000000000e+00,6.036361024221944538e-01,0.000000000000000000e+00,-1.000000010230644776e+00,0.000000000000000000e+00 +3.058052752847686762e+01,1.754900000000000091e+02,0.000000000000000000e+00,1.081809384920955708e+01,0.000000000000000000e+00,6.027116774647232056e-01,0.000000000000000000e+00,-1.000000007579103789e+00,0.000000000000000000e+00 +3.058145190574142092e+01,1.755000000000000000e+02,0.000000000000000000e+00,1.081865098218128551e+01,0.000000000000000000e+00,6.017873001931651755e-01,0.000000000000000000e+00,-1.000000010085041913e+00,0.000000000000000000e+00 +3.058237623540289718e+01,1.755099999999999909e+02,0.000000000000000000e+00,1.081920723203275436e+01,0.000000000000000000e+00,6.008629705223660356e-01,0.000000000000000000e+00,-1.000000007667550372e+00,0.000000000000000000e+00 +3.058330051754164813e+01,1.755200000000000102e+02,0.000000000000000000e+00,1.081976259894424430e+01,0.000000000000000000e+00,5.999386883765293055e-01,0.000000000000000000e+00,-1.000000011035736991e+00,0.000000000000000000e+00 +3.058422475223797932e+01,1.755300000000000011e+02,0.000000000000000000e+00,1.082031708309571272e+01,0.000000000000000000e+00,5.990144536699995026e-01,0.000000000000000000e+00,-1.000000008025255349e+00,0.000000000000000000e+00 +3.058514893957215719e+01,1.755399999999999920e+02,0.000000000000000000e+00,1.082087068466678481e+01,0.000000000000000000e+00,5.980902663284034526e-01,0.000000000000000000e+00,-1.000000007265767543e+00,0.000000000000000000e+00 +3.058607307962441624e+01,1.755500000000000114e+02,0.000000000000000000e+00,1.082142340383676427e+01,0.000000000000000000e+00,5.971661262694313299e-01,0.000000000000000000e+00,-1.000000011149288159e+00,0.000000000000000000e+00 +3.058699717247494121e+01,1.755600000000000023e+02,0.000000000000000000e+00,1.082197524078462614e+01,0.000000000000000000e+00,5.962420334086023788e-01,0.000000000000000000e+00,-1.000000007505446709e+00,0.000000000000000000e+00 +3.058792121820388488e+01,1.755699999999999932e+02,0.000000000000000000e+00,1.082252619568901508e+01,0.000000000000000000e+00,5.953179876727215936e-01,0.000000000000000000e+00,-1.000000011205970152e+00,0.000000000000000000e+00 +3.058884521689136093e+01,1.755800000000000125e+02,0.000000000000000000e+00,1.082307626872825601e+01,0.000000000000000000e+00,5.943939889748904859e-01,0.000000000000000000e+00,-1.000000007996392659e+00,0.000000000000000000e+00 +3.058976916861744044e+01,1.755900000000000034e+02,0.000000000000000000e+00,1.082362546008034165e+01,0.000000000000000000e+00,5.934700372414210001e-01,0.000000000000000000e+00,-1.000000008588398659e+00,0.000000000000000000e+00 +3.059069307346215894e+01,1.755999999999999943e+02,0.000000000000000000e+00,1.082417376992294500e+01,0.000000000000000000e+00,5.925461323887664111e-01,0.000000000000000000e+00,-1.000000009128455991e+00,0.000000000000000000e+00 +3.059161693150551287e+01,1.756100000000000136e+02,0.000000000000000000e+00,1.082472119843341041e+01,0.000000000000000000e+00,5.916222743369794479e-01,0.000000000000000000e+00,-1.000000009923950106e+00,0.000000000000000000e+00 +3.059254074282745606e+01,1.756200000000000045e+02,0.000000000000000000e+00,1.082526774578875717e+01,0.000000000000000000e+00,5.906984630058675911e-01,0.000000000000000000e+00,-1.000000007118087453e+00,0.000000000000000000e+00 +3.059346450750790680e+01,1.756299999999999955e+02,0.000000000000000000e+00,1.082581341216567949e+01,0.000000000000000000e+00,5.897746983188397740e-01,0.000000000000000000e+00,-1.000000011425129731e+00,0.000000000000000000e+00 +3.059438822562674787e+01,1.756400000000000148e+02,0.000000000000000000e+00,1.082635819774055008e+01,0.000000000000000000e+00,5.888509801894460383e-01,0.000000000000000000e+00,-1.000000006495876725e+00,0.000000000000000000e+00 +3.059531189726381584e+01,1.756500000000000057e+02,0.000000000000000000e+00,1.082690210268941122e+01,0.000000000000000000e+00,5.879273085463772031e-01,0.000000000000000000e+00,-1.000000011372659259e+00,0.000000000000000000e+00 +3.059623552249891532e+01,1.756599999999999966e+02,0.000000000000000000e+00,1.082744512718798902e+01,0.000000000000000000e+00,5.870036833007732380e-01,0.000000000000000000e+00,-1.000000007620209574e+00,0.000000000000000000e+00 +3.059715910141181183e+01,1.756700000000000159e+02,0.000000000000000000e+00,1.082798727141167738e+01,0.000000000000000000e+00,5.860801043808402389e-01,0.000000000000000000e+00,-1.000000010118094140e+00,0.000000000000000000e+00 +3.059808263408222828e+01,1.756800000000000068e+02,0.000000000000000000e+00,1.082852853553555406e+01,0.000000000000000000e+00,5.851565717010795975e-01,0.000000000000000000e+00,-1.000000008756430692e+00,0.000000000000000000e+00 +3.059900612058985203e+01,1.756899999999999977e+02,0.000000000000000000e+00,1.082906891973436814e+01,0.000000000000000000e+00,5.842330851853680951e-01,0.000000000000000000e+00,-1.000000008002296603e+00,0.000000000000000000e+00 +3.059992956101433492e+01,1.757000000000000171e+02,0.000000000000000000e+00,1.082960842418254899e+01,0.000000000000000000e+00,5.833096447534950046e-01,0.000000000000000000e+00,-1.000000010240665205e+00,0.000000000000000000e+00 +3.060085295543528972e+01,1.757100000000000080e+02,0.000000000000000000e+00,1.083014704905420267e+01,0.000000000000000000e+00,5.823862503230854415e-01,0.000000000000000000e+00,-1.000000007439291849e+00,0.000000000000000000e+00 +3.060177630393228654e+01,1.757199999999999989e+02,0.000000000000000000e+00,1.083068479452311017e+01,0.000000000000000000e+00,5.814629018192194465e-01,0.000000000000000000e+00,-1.000000010315339471e+00,0.000000000000000000e+00 +3.060269960658486355e+01,1.757299999999999898e+02,0.000000000000000000e+00,1.083122166076273452e+01,0.000000000000000000e+00,5.805395991571190573e-01,0.000000000000000000e+00,-1.000000008750370206e+00,0.000000000000000000e+00 +3.060362286347251626e+01,1.757400000000000091e+02,0.000000000000000000e+00,1.083175764794621188e+01,0.000000000000000000e+00,5.796163422613868077e-01,0.000000000000000000e+00,-1.000000009294678360e+00,0.000000000000000000e+00 +3.060454607467470822e+01,1.757500000000000000e+02,0.000000000000000000e+00,1.083229275624636045e+01,0.000000000000000000e+00,5.786931310506150394e-01,0.000000000000000000e+00,-1.000000008078054670e+00,0.000000000000000000e+00 +3.060546924027086035e+01,1.757599999999999909e+02,0.000000000000000000e+00,1.083282698583567516e+01,0.000000000000000000e+00,5.777699654470068724e-01,0.000000000000000000e+00,-1.000000009566939241e+00,0.000000000000000000e+00 +3.060639236034035449e+01,1.757700000000000102e+02,0.000000000000000000e+00,1.083336033688633115e+01,0.000000000000000000e+00,5.768468453686796948e-01,0.000000000000000000e+00,-1.000000009889820962e+00,0.000000000000000000e+00 +3.060731543496254403e+01,1.757800000000000011e+02,0.000000000000000000e+00,1.083389280957018030e+01,0.000000000000000000e+00,5.759237707373624504e-01,0.000000000000000000e+00,-1.000000007257359158e+00,0.000000000000000000e+00 +3.060823846421673622e+01,1.757899999999999920e+02,0.000000000000000000e+00,1.083442440405875473e+01,0.000000000000000000e+00,5.750007414764729541e-01,0.000000000000000000e+00,-1.000000010305352571e+00,0.000000000000000000e+00 +3.060916144818220275e+01,1.758000000000000114e+02,0.000000000000000000e+00,1.083495512052326859e+01,0.000000000000000000e+00,5.740777575014952561e-01,0.000000000000000000e+00,-1.000000008903708437e+00,0.000000000000000000e+00 +3.061008438693817979e+01,1.758100000000000023e+02,0.000000000000000000e+00,1.083548495913461096e+01,0.000000000000000000e+00,5.731548187373008973e-01,0.000000000000000000e+00,-1.000000009602478368e+00,0.000000000000000000e+00 +3.061100728056386444e+01,1.758199999999999932e+02,0.000000000000000000e+00,1.083601392006335473e+01,0.000000000000000000e+00,5.722319251027530029e-01,0.000000000000000000e+00,-1.000000008524368322e+00,0.000000000000000000e+00 +3.061193012913842182e+01,1.758300000000000125e+02,0.000000000000000000e+00,1.083654200347975127e+01,0.000000000000000000e+00,5.713090765203302501e-01,0.000000000000000000e+00,-1.000000010134126871e+00,0.000000000000000000e+00 +3.061285293274097086e+01,1.758400000000000034e+02,0.000000000000000000e+00,1.083706920955373398e+01,0.000000000000000000e+00,5.703862729084280270e-01,0.000000000000000000e+00,-1.000000006380373119e+00,0.000000000000000000e+00 +3.061377569145060207e+01,1.758499999999999943e+02,0.000000000000000000e+00,1.083759553845491475e+01,0.000000000000000000e+00,5.694635141929085265e-01,0.000000000000000000e+00,-1.000000012158393847e+00,0.000000000000000000e+00 +3.061469840534636688e+01,1.758600000000000136e+02,0.000000000000000000e+00,1.083812099035259102e+01,0.000000000000000000e+00,5.685408002859260179e-01,0.000000000000000000e+00,-1.000000006896319293e+00,0.000000000000000000e+00 +3.061562107450727765e+01,1.758700000000000045e+02,0.000000000000000000e+00,1.083864556541573343e+01,0.000000000000000000e+00,5.676181311186538903e-01,0.000000000000000000e+00,-1.000000009662684652e+00,0.000000000000000000e+00 +3.061654369901230766e+01,1.758799999999999955e+02,0.000000000000000000e+00,1.083916926381300350e+01,0.000000000000000000e+00,5.666955066047076883e-01,0.000000000000000000e+00,-1.000000008228270731e+00,0.000000000000000000e+00 +3.061746627894040174e+01,1.758900000000000148e+02,0.000000000000000000e+00,1.083969208571273768e+01,0.000000000000000000e+00,5.657729266690231240e-01,0.000000000000000000e+00,-1.000000009142775426e+00,0.000000000000000000e+00 +3.061838881437046211e+01,1.759000000000000057e+02,0.000000000000000000e+00,1.084021403128295802e+01,0.000000000000000000e+00,5.648503912305296026e-01,0.000000000000000000e+00,-1.000000010608482315e+00,0.000000000000000000e+00 +3.061931130538135548e+01,1.759099999999999966e+02,0.000000000000000000e+00,1.084073510069136681e+01,0.000000000000000000e+00,5.639279002098517291e-01,0.000000000000000000e+00,-1.000000008738462176e+00,0.000000000000000000e+00 +3.062023375205190945e+01,1.759200000000000159e+02,0.000000000000000000e+00,1.084125529410534838e+01,0.000000000000000000e+00,5.630054535312360997e-01,0.000000000000000000e+00,-1.000000007994839013e+00,0.000000000000000000e+00 +3.062115615446092320e+01,1.759300000000000068e+02,0.000000000000000000e+00,1.084177461169197265e+01,0.000000000000000000e+00,5.620830511148493525e-01,0.000000000000000000e+00,-1.000000008665311801e+00,0.000000000000000000e+00 +3.062207851268714975e+01,1.759399999999999977e+02,0.000000000000000000e+00,1.084229305361799156e+01,0.000000000000000000e+00,5.611606928806291972e-01,0.000000000000000000e+00,-1.000000011036589864e+00,0.000000000000000000e+00 +3.062300082680931368e+01,1.759500000000000171e+02,0.000000000000000000e+00,1.084281062004983909e+01,0.000000000000000000e+00,5.602383787482853039e-01,0.000000000000000000e+00,-1.000000007041267347e+00,0.000000000000000000e+00 +3.062392309690610048e+01,1.759600000000000080e+02,0.000000000000000000e+00,1.084332731115363124e+01,0.000000000000000000e+00,5.593161086450040287e-01,0.000000000000000000e+00,-1.000000009494126374e+00,0.000000000000000000e+00 +3.062484532305616014e+01,1.759699999999999989e+02,0.000000000000000000e+00,1.084384312709517317e+01,0.000000000000000000e+00,5.583938824861888195e-01,0.000000000000000000e+00,-1.000000010326907329e+00,0.000000000000000000e+00 +3.062576750533810355e+01,1.759799999999999898e+02,0.000000000000000000e+00,1.084435806803994851e+01,0.000000000000000000e+00,5.574717001947203654e-01,0.000000000000000000e+00,-1.000000007733605090e+00,0.000000000000000000e+00 +3.062668964383051318e+01,1.759900000000000091e+02,0.000000000000000000e+00,1.084487213415312645e+01,0.000000000000000000e+00,5.565495616951804392e-01,0.000000000000000000e+00,-1.000000010353291113e+00,0.000000000000000000e+00 +3.062761173861192532e+01,1.760000000000000000e+02,0.000000000000000000e+00,1.084538532559956359e+01,0.000000000000000000e+00,5.556274669042201575e-01,0.000000000000000000e+00,-1.000000008023685716e+00,0.000000000000000000e+00 +3.062853378976085139e+01,1.760099999999999909e+02,0.000000000000000000e+00,1.084589764254379674e+01,0.000000000000000000e+00,5.547054157478972236e-01,0.000000000000000000e+00,-1.000000009383337884e+00,0.000000000000000000e+00 +3.062945579735575663e+01,1.760200000000000102e+02,0.000000000000000000e+00,1.084640908515005187e+01,0.000000000000000000e+00,5.537834081443395728e-01,0.000000000000000000e+00,-1.000000008445735666e+00,0.000000000000000000e+00 +3.063037776147507785e+01,1.760300000000000011e+02,0.000000000000000000e+00,1.084691965358223698e+01,0.000000000000000000e+00,5.528614440172305855e-01,0.000000000000000000e+00,-1.000000009671109247e+00,0.000000000000000000e+00 +3.063129968219721633e+01,1.760399999999999920e+02,0.000000000000000000e+00,1.084742934800394742e+01,0.000000000000000000e+00,5.519395232861769029e-01,0.000000000000000000e+00,-1.000000009159790926e+00,0.000000000000000000e+00 +3.063222155960053428e+01,1.760500000000000114e+02,0.000000000000000000e+00,1.084793816857846238e+01,0.000000000000000000e+00,5.510176458744159289e-01,0.000000000000000000e+00,-1.000000009281454938e+00,0.000000000000000000e+00 +3.063314339376335838e+01,1.760600000000000023e+02,0.000000000000000000e+00,1.084844611546874837e+01,0.000000000000000000e+00,5.500958117030357863e-01,0.000000000000000000e+00,-1.000000008224515957e+00,0.000000000000000000e+00 +3.063406518476398332e+01,1.760699999999999932e+02,0.000000000000000000e+00,1.084895318883745752e+01,0.000000000000000000e+00,5.491740206948299008e-01,0.000000000000000000e+00,-1.000000008358308268e+00,0.000000000000000000e+00 +3.063498693268066475e+01,1.760800000000000125e+02,0.000000000000000000e+00,1.084945938884692929e+01,0.000000000000000000e+00,5.482522727704428611e-01,0.000000000000000000e+00,-1.000000009960617220e+00,0.000000000000000000e+00 +3.063590863759162986e+01,1.760900000000000034e+02,0.000000000000000000e+00,1.084996471565918874e+01,0.000000000000000000e+00,5.473305678502985439e-01,0.000000000000000000e+00,-1.000000009127232081e+00,0.000000000000000000e+00 +3.063683029957506321e+01,1.760999999999999943e+02,0.000000000000000000e+00,1.085046916943594653e+01,0.000000000000000000e+00,5.464089058584544745e-01,0.000000000000000000e+00,-1.000000010316255628e+00,0.000000000000000000e+00 +3.063775191870911740e+01,1.761100000000000136e+02,0.000000000000000000e+00,1.085097275033860242e+01,0.000000000000000000e+00,5.454872867148942150e-01,0.000000000000000000e+00,-1.000000007529865398e+00,0.000000000000000000e+00 +3.063867349507190951e+01,1.761200000000000045e+02,0.000000000000000000e+00,1.085147545852824180e+01,0.000000000000000000e+00,5.445657103451639891e-01,0.000000000000000000e+00,-1.000000009409479862e+00,0.000000000000000000e+00 +3.063959502874152108e+01,1.761299999999999955e+02,0.000000000000000000e+00,1.085197729416564094e+01,0.000000000000000000e+00,5.436441766668810294e-01,0.000000000000000000e+00,-1.000000007863327101e+00,0.000000000000000000e+00 +3.064051651979600166e+01,1.761400000000000148e+02,0.000000000000000000e+00,1.085247825741125993e+01,0.000000000000000000e+00,5.427226856051544646e-01,0.000000000000000000e+00,-1.000000011533422661e+00,0.000000000000000000e+00 +3.064143796831336530e+01,1.761500000000000057e+02,0.000000000000000000e+00,1.085297834842524978e+01,0.000000000000000000e+00,5.418012370771645436e-01,0.000000000000000000e+00,-1.000000006048311629e+00,0.000000000000000000e+00 +3.064235937437158697e+01,1.761599999999999966e+02,0.000000000000000000e+00,1.085347756736744529e+01,0.000000000000000000e+00,5.408798310133687837e-01,0.000000000000000000e+00,-1.000000012603680100e+00,0.000000000000000000e+00 +3.064328073804861319e+01,1.761700000000000159e+02,0.000000000000000000e+00,1.085397591439737752e+01,0.000000000000000000e+00,5.399584673247291855e-01,0.000000000000000000e+00,-1.000000006362901761e+00,0.000000000000000000e+00 +3.064420205942235498e+01,1.761800000000000068e+02,0.000000000000000000e+00,1.085447338967425601e+01,0.000000000000000000e+00,5.390371459451263059e-01,0.000000000000000000e+00,-1.000000010616191704e+00,0.000000000000000000e+00 +3.064512333857068427e+01,1.761899999999999977e+02,0.000000000000000000e+00,1.085496999335699009e+01,0.000000000000000000e+00,5.381158667870167278e-01,0.000000000000000000e+00,-1.000000006799576457e+00,0.000000000000000000e+00 +3.064604457557144102e+01,1.762000000000000171e+02,0.000000000000000000e+00,1.085546572560416934e+01,0.000000000000000000e+00,5.371946297799945480e-01,0.000000000000000000e+00,-1.000000011928257937e+00,0.000000000000000000e+00 +3.064696577050243320e+01,1.762100000000000080e+02,0.000000000000000000e+00,1.085596058657407958e+01,0.000000000000000000e+00,5.362734348380128191e-01,0.000000000000000000e+00,-1.000000007432939153e+00,0.000000000000000000e+00 +3.064788692344143328e+01,1.762199999999999989e+02,0.000000000000000000e+00,1.085645457642468870e+01,0.000000000000000000e+00,5.353522818921651050e-01,0.000000000000000000e+00,-1.000000008236384907e+00,0.000000000000000000e+00 +3.064880803446617819e+01,1.762299999999999898e+02,0.000000000000000000e+00,1.085694769531366255e+01,0.000000000000000000e+00,5.344311708598323829e-01,0.000000000000000000e+00,-1.000000010420915020e+00,0.000000000000000000e+00 +3.064972910365437286e+01,1.762400000000000091e+02,0.000000000000000000e+00,1.085743994339835261e+01,0.000000000000000000e+00,5.335101016620388270e-01,0.000000000000000000e+00,-1.000000007973402161e+00,0.000000000000000000e+00 +3.065065013108368674e+01,1.762500000000000000e+02,0.000000000000000000e+00,1.085793132083579948e+01,0.000000000000000000e+00,5.325890742253810428e-01,0.000000000000000000e+00,-1.000000011631038799e+00,0.000000000000000000e+00 +3.065157111683175728e+01,1.762599999999999909e+02,0.000000000000000000e+00,1.085842182778273823e+01,0.000000000000000000e+00,5.316680884666001861e-01,0.000000000000000000e+00,-1.000000007002104896e+00,0.000000000000000000e+00 +3.065249206097618284e+01,1.762700000000000102e+02,0.000000000000000000e+00,1.085891146439558952e+01,0.000000000000000000e+00,5.307471443157260049e-01,0.000000000000000000e+00,-1.000000009012302016e+00,0.000000000000000000e+00 +3.065341296359453338e+01,1.762800000000000011e+02,0.000000000000000000e+00,1.085940023083047201e+01,0.000000000000000000e+00,5.298262416890758830e-01,0.000000000000000000e+00,-1.000000009550973346e+00,0.000000000000000000e+00 +3.065433382476434332e+01,1.762899999999999920e+02,0.000000000000000000e+00,1.085988812724318997e+01,0.000000000000000000e+00,5.289053805104705352e-01,0.000000000000000000e+00,-1.000000008882452107e+00,0.000000000000000000e+00 +3.065525464456311511e+01,1.763000000000000114e+02,0.000000000000000000e+00,1.086037515378924034e+01,0.000000000000000000e+00,5.279845607035207333e-01,0.000000000000000000e+00,-1.000000009366623921e+00,0.000000000000000000e+00 +3.065617542306831211e+01,1.763100000000000023e+02,0.000000000000000000e+00,1.086086131062381277e+01,0.000000000000000000e+00,5.270637821896977382e-01,0.000000000000000000e+00,-1.000000007076931707e+00,0.000000000000000000e+00 +3.065709616035737284e+01,1.763199999999999932e+02,0.000000000000000000e+00,1.086134659790178780e+01,0.000000000000000000e+00,5.261430448941217808e-01,0.000000000000000000e+00,-1.000000012754259204e+00,0.000000000000000000e+00 +3.065801685650769315e+01,1.763300000000000125e+02,0.000000000000000000e+00,1.086183101577774046e+01,0.000000000000000000e+00,5.252223487320570872e-01,0.000000000000000000e+00,-1.000000005705786066e+00,0.000000000000000000e+00 +3.065893751159664404e+01,1.763400000000000034e+02,0.000000000000000000e+00,1.086231456440593135e+01,0.000000000000000000e+00,5.243016936378531723e-01,0.000000000000000000e+00,-1.000000011342240702e+00,0.000000000000000000e+00 +3.065985812570155744e+01,1.763499999999999943e+02,0.000000000000000000e+00,1.086279724394032442e+01,0.000000000000000000e+00,5.233810795224977941e-01,0.000000000000000000e+00,-1.000000006870970903e+00,0.000000000000000000e+00 +3.066077869889973329e+01,1.763600000000000136e+02,0.000000000000000000e+00,1.086327905453456566e+01,0.000000000000000000e+00,5.224605063179957876e-01,0.000000000000000000e+00,-1.000000011417455648e+00,0.000000000000000000e+00 +3.066169923126843955e+01,1.763700000000000045e+02,0.000000000000000000e+00,1.086375999634200262e+01,0.000000000000000000e+00,5.215399739387782674e-01,0.000000000000000000e+00,-1.000000008472910151e+00,0.000000000000000000e+00 +3.066261972288491222e+01,1.763799999999999955e+02,0.000000000000000000e+00,1.086424006951566845e+01,0.000000000000000000e+00,5.206194823145067208e-01,0.000000000000000000e+00,-1.000000006681612374e+00,0.000000000000000000e+00 +3.066354017382635178e+01,1.763900000000000148e+02,0.000000000000000000e+00,1.086471927420829608e+01,0.000000000000000000e+00,5.196990313669180850e-01,0.000000000000000000e+00,-1.000000012594318921e+00,0.000000000000000000e+00 +3.066446058416992670e+01,1.764000000000000057e+02,0.000000000000000000e+00,1.086519761057231115e+01,0.000000000000000000e+00,5.187786210117529828e-01,0.000000000000000000e+00,-1.000000005501554323e+00,0.000000000000000000e+00 +3.066538095399276997e+01,1.764099999999999966e+02,0.000000000000000000e+00,1.086567507875982663e+01,0.000000000000000000e+00,5.178582511838462077e-01,0.000000000000000000e+00,-1.000000012921818060e+00,0.000000000000000000e+00 +3.066630128337198613e+01,1.764200000000000159e+02,0.000000000000000000e+00,1.086615167892266065e+01,0.000000000000000000e+00,5.169379217927376757e-01,0.000000000000000000e+00,-1.000000005752940790e+00,0.000000000000000000e+00 +3.066722157238464419e+01,1.764300000000000068e+02,0.000000000000000000e+00,1.086662741121231335e+01,0.000000000000000000e+00,5.160176327747841851e-01,0.000000000000000000e+00,-1.000000011516925857e+00,0.000000000000000000e+00 +3.066814182110778475e+01,1.764399999999999977e+02,0.000000000000000000e+00,1.086710227577999177e+01,0.000000000000000000e+00,5.150973840410463245e-01,0.000000000000000000e+00,-1.000000007398487156e+00,0.000000000000000000e+00 +3.066906202961840933e+01,1.764500000000000171e+02,0.000000000000000000e+00,1.086757627277658678e+01,0.000000000000000000e+00,5.141771755236136388e-01,0.000000000000000000e+00,-1.000000008336203283e+00,0.000000000000000000e+00 +3.066998219799349101e+01,1.764600000000000080e+02,0.000000000000000000e+00,1.086804940235269257e+01,0.000000000000000000e+00,5.132570071408609769e-01,0.000000000000000000e+00,-1.000000010390974525e+00,0.000000000000000000e+00 +3.067090232630997093e+01,1.764699999999999989e+02,0.000000000000000000e+00,1.086852166465859426e+01,0.000000000000000000e+00,5.123368788148207065e-01,0.000000000000000000e+00,-1.000000009621005548e+00,0.000000000000000000e+00 +3.067182241464475467e+01,1.764799999999999898e+02,0.000000000000000000e+00,1.086899305984427144e+01,0.000000000000000000e+00,5.114167904711844903e-01,0.000000000000000000e+00,-1.000000008378374439e+00,0.000000000000000000e+00 +3.067274246307471941e+01,1.764900000000000091e+02,0.000000000000000000e+00,1.086946358805940172e+01,0.000000000000000000e+00,5.104967420335119188e-01,0.000000000000000000e+00,-1.000000009015128422e+00,0.000000000000000000e+00 +3.067366247167670679e+01,1.765000000000000000e+02,0.000000000000000000e+00,1.086993324945335893e+01,0.000000000000000000e+00,5.095767334232308432e-01,0.000000000000000000e+00,-1.000000009686377700e+00,0.000000000000000000e+00 +3.067458244052752647e+01,1.765099999999999909e+02,0.000000000000000000e+00,1.087040204417521139e+01,0.000000000000000000e+00,5.086567645634987311e-01,0.000000000000000000e+00,-1.000000008545026908e+00,0.000000000000000000e+00 +3.067550236970395972e+01,1.765200000000000102e+02,0.000000000000000000e+00,1.087086997237372366e+01,0.000000000000000000e+00,5.077368353792043321e-01,0.000000000000000000e+00,-1.000000007942301705e+00,0.000000000000000000e+00 +3.067642225928275224e+01,1.765300000000000011e+02,0.000000000000000000e+00,1.087133703419735831e+01,0.000000000000000000e+00,5.068169457931053223e-01,0.000000000000000000e+00,-1.000000010229032510e+00,0.000000000000000000e+00 +3.067734210934061778e+01,1.765399999999999920e+02,0.000000000000000000e+00,1.087180322979427416e+01,0.000000000000000000e+00,5.058970957258289713e-01,0.000000000000000000e+00,-1.000000009357620900e+00,0.000000000000000000e+00 +3.067826191995424168e+01,1.765500000000000114e+02,0.000000000000000000e+00,1.087226855931232450e+01,0.000000000000000000e+00,5.049772851035974064e-01,0.000000000000000000e+00,-1.000000009777555210e+00,0.000000000000000000e+00 +3.067918169120027372e+01,1.765600000000000023e+02,0.000000000000000000e+00,1.087273302289906241e+01,0.000000000000000000e+00,5.040575138485716700e-01,0.000000000000000000e+00,-1.000000007538449642e+00,0.000000000000000000e+00 +3.068010142315533528e+01,1.765699999999999932e+02,0.000000000000000000e+00,1.087319662070173720e+01,0.000000000000000000e+00,5.031377818865779838e-01,0.000000000000000000e+00,-1.000000009189350836e+00,0.000000000000000000e+00 +3.068102111589601222e+01,1.765800000000000125e+02,0.000000000000000000e+00,1.087365935286729801e+01,0.000000000000000000e+00,5.022180891374508072e-01,0.000000000000000000e+00,-1.000000008678672669e+00,0.000000000000000000e+00 +3.068194076949885840e+01,1.765900000000000034e+02,0.000000000000000000e+00,1.087412121954238842e+01,0.000000000000000000e+00,5.012984355266220104e-01,0.000000000000000000e+00,-1.000000010455161181e+00,0.000000000000000000e+00 +3.068286038404040283e+01,1.765999999999999943e+02,0.000000000000000000e+00,1.087458222087335180e+01,0.000000000000000000e+00,5.003788209754636007e-01,0.000000000000000000e+00,-1.000000008464548173e+00,0.000000000000000000e+00 +3.068377995959713544e+01,1.766100000000000136e+02,0.000000000000000000e+00,1.087504235700622779e+01,0.000000000000000000e+00,4.994592454109466617e-01,0.000000000000000000e+00,-1.000000009255040956e+00,0.000000000000000000e+00 +3.068469949624552129e+01,1.766200000000000045e+02,0.000000000000000000e+00,1.087550162808675758e+01,0.000000000000000000e+00,4.985397087540519023e-01,0.000000000000000000e+00,-1.000000008871842372e+00,0.000000000000000000e+00 +3.068561899406198634e+01,1.766299999999999955e+02,0.000000000000000000e+00,1.087596003426037861e+01,0.000000000000000000e+00,4.976202109294280973e-01,0.000000000000000000e+00,-1.000000009661398570e+00,0.000000000000000000e+00 +3.068653845312293527e+01,1.766400000000000148e+02,0.000000000000000000e+00,1.087641757567222811e+01,0.000000000000000000e+00,4.967007518595976667e-01,0.000000000000000000e+00,-1.000000007666411728e+00,0.000000000000000000e+00 +3.068745787350473009e+01,1.766500000000000057e+02,0.000000000000000000e+00,1.087687425246714135e+01,0.000000000000000000e+00,4.957813314707527619e-01,0.000000000000000000e+00,-1.000000009435415338e+00,0.000000000000000000e+00 +3.068837725528371152e+01,1.766599999999999966e+02,0.000000000000000000e+00,1.087733006478965514e+01,0.000000000000000000e+00,4.948619496830957143e-01,0.000000000000000000e+00,-1.000000008908175531e+00,0.000000000000000000e+00 +3.068929659853618475e+01,1.766700000000000159e+02,0.000000000000000000e+00,1.087778501278400256e+01,0.000000000000000000e+00,4.939426064224317625e-01,0.000000000000000000e+00,-1.000000010531362449e+00,0.000000000000000000e+00 +3.069021590333842653e+01,1.766800000000000068e+02,0.000000000000000000e+00,1.087823909659411825e+01,0.000000000000000000e+00,4.930233016105090016e-01,0.000000000000000000e+00,-1.000000008242130090e+00,0.000000000000000000e+00 +3.069113516976667810e+01,1.766899999999999977e+02,0.000000000000000000e+00,1.087869231636363487e+01,0.000000000000000000e+00,4.921040351746800434e-01,0.000000000000000000e+00,-1.000000008588399325e+00,0.000000000000000000e+00 +3.069205439789715584e+01,1.767000000000000171e+02,0.000000000000000000e+00,1.087914467223588844e+01,0.000000000000000000e+00,4.911848070363088459e-01,0.000000000000000000e+00,-1.000000009710513948e+00,0.000000000000000000e+00 +3.069297358780604057e+01,1.767100000000000080e+02,0.000000000000000000e+00,1.087959616435391297e+01,0.000000000000000000e+00,4.902656171184998080e-01,0.000000000000000000e+00,-1.000000007644429090e+00,0.000000000000000000e+00 +3.069389273956948117e+01,1.767199999999999989e+02,0.000000000000000000e+00,1.088004679286044230e+01,0.000000000000000000e+00,4.893464653480316673e-01,0.000000000000000000e+00,-1.000000011041088266e+00,0.000000000000000000e+00 +3.069481185326360162e+01,1.767299999999999898e+02,0.000000000000000000e+00,1.088049655789791359e+01,0.000000000000000000e+00,4.884273516437622198e-01,0.000000000000000000e+00,-1.000000007524314949e+00,0.000000000000000000e+00 +3.069573092896449396e+01,1.767400000000000091e+02,0.000000000000000000e+00,1.088094545960846027e+01,0.000000000000000000e+00,4.875082759359550821e-01,0.000000000000000000e+00,-1.000000009950543056e+00,0.000000000000000000e+00 +3.069664996674821467e+01,1.767500000000000000e+02,0.000000000000000000e+00,1.088139349813392265e+01,0.000000000000000000e+00,4.865892381430880209e-01,0.000000000000000000e+00,-1.000000008043813615e+00,0.000000000000000000e+00 +3.069756896669079538e+01,1.767599999999999909e+02,0.000000000000000000e+00,1.088184067361583729e+01,0.000000000000000000e+00,4.856702381931135015e-01,0.000000000000000000e+00,-1.000000010455274202e+00,0.000000000000000000e+00 +3.069848792886823574e+01,1.767700000000000102e+02,0.000000000000000000e+00,1.088228698619544588e+01,0.000000000000000000e+00,4.847512760060637693e-01,0.000000000000000000e+00,-1.000000009009392787e+00,0.000000000000000000e+00 +3.069940685335650699e+01,1.767800000000000011e+02,0.000000000000000000e+00,1.088273243601368812e+01,0.000000000000000000e+00,4.838323515095145355e-01,0.000000000000000000e+00,-1.000000008149989128e+00,0.000000000000000000e+00 +3.070032574023154481e+01,1.767899999999999920e+02,0.000000000000000000e+00,1.088317702321120883e+01,0.000000000000000000e+00,4.829134646269879205e-01,0.000000000000000000e+00,-1.000000008113838490e+00,0.000000000000000000e+00 +3.070124458956926006e+01,1.768000000000000114e+02,0.000000000000000000e+00,1.088362074792835443e+01,0.000000000000000000e+00,4.819946152818186946e-01,0.000000000000000000e+00,-1.000000011241856335e+00,0.000000000000000000e+00 +3.070216340144552802e+01,1.768100000000000023e+02,0.000000000000000000e+00,1.088406361030517289e+01,0.000000000000000000e+00,4.810758033952209356e-01,0.000000000000000000e+00,-1.000000007248605272e+00,0.000000000000000000e+00 +3.070308217593619915e+01,1.768199999999999932e+02,0.000000000000000000e+00,1.088450561048141196e+01,0.000000000000000000e+00,4.801570288978890821e-01,0.000000000000000000e+00,-1.000000011098890473e+00,0.000000000000000000e+00 +3.070400091311709190e+01,1.768300000000000125e+02,0.000000000000000000e+00,1.088494674859652811e+01,0.000000000000000000e+00,4.792382917067979919e-01,0.000000000000000000e+00,-1.000000008296544118e+00,0.000000000000000000e+00 +3.070491961306399631e+01,1.768400000000000034e+02,0.000000000000000000e+00,1.088538702478967402e+01,0.000000000000000000e+00,4.783195917522709006e-01,0.000000000000000000e+00,-1.000000007493156318e+00,0.000000000000000000e+00 +3.070583827585267045e+01,1.768499999999999943e+02,0.000000000000000000e+00,1.088582643919971105e+01,0.000000000000000000e+00,4.774009289567122116e-01,0.000000000000000000e+00,-1.000000011027714297e+00,0.000000000000000000e+00 +3.070675690155884396e+01,1.768600000000000136e+02,0.000000000000000000e+00,1.088626499196520214e+01,0.000000000000000000e+00,4.764823032404076342e-01,0.000000000000000000e+00,-1.000000008608419977e+00,0.000000000000000000e+00 +3.070767549025821808e+01,1.768700000000000045e+02,0.000000000000000000e+00,1.088670268322441004e+01,0.000000000000000000e+00,4.755637145331269577e-01,0.000000000000000000e+00,-1.000000008887293346e+00,0.000000000000000000e+00 +3.070859404202645848e+01,1.768799999999999955e+02,0.000000000000000000e+00,1.088713951311530614e+01,0.000000000000000000e+00,4.746451627567215836e-01,0.000000000000000000e+00,-1.000000007885813558e+00,0.000000000000000000e+00 +3.070951255693920956e+01,1.768900000000000148e+02,0.000000000000000000e+00,1.088757548177556345e+01,0.000000000000000000e+00,4.737266478367270772e-01,0.000000000000000000e+00,-1.000000010046383947e+00,0.000000000000000000e+00 +3.071043103507208016e+01,1.769000000000000057e+02,0.000000000000000000e+00,1.088801058934256005e+01,0.000000000000000000e+00,4.728081696946280776e-01,0.000000000000000000e+00,-1.000000009282870694e+00,0.000000000000000000e+00 +3.071134947650065428e+01,1.769099999999999966e+02,0.000000000000000000e+00,1.088844483595337564e+01,0.000000000000000000e+00,4.718897282575287289e-01,0.000000000000000000e+00,-1.000000007930585522e+00,0.000000000000000000e+00 +3.071226788130048035e+01,1.769200000000000159e+02,0.000000000000000000e+00,1.088887822174479680e+01,0.000000000000000000e+00,4.709713234504174229e-01,0.000000000000000000e+00,-1.000000010431541853e+00,0.000000000000000000e+00 +3.071318624954708554e+01,1.769300000000000068e+02,0.000000000000000000e+00,1.088931074685331524e+01,0.000000000000000000e+00,4.700529551942323470e-01,0.000000000000000000e+00,-1.000000008590198330e+00,0.000000000000000000e+00 +3.071410458131596144e+01,1.769399999999999977e+02,0.000000000000000000e+00,1.088974241141512422e+01,0.000000000000000000e+00,4.691346234174675334e-01,0.000000000000000000e+00,-1.000000008953566777e+00,0.000000000000000000e+00 +3.071502287668257480e+01,1.769500000000000171e+02,0.000000000000000000e+00,1.089017321556612572e+01,0.000000000000000000e+00,4.682163280426335783e-01,0.000000000000000000e+00,-1.000000009643377652e+00,0.000000000000000000e+00 +3.071594113572235685e+01,1.769600000000000080e+02,0.000000000000000000e+00,1.089060315944192503e+01,0.000000000000000000e+00,4.672980689939951193e-01,0.000000000000000000e+00,-1.000000008780628002e+00,0.000000000000000000e+00 +3.071685935851071747e+01,1.769699999999999989e+02,0.000000000000000000e+00,1.089103224317783258e+01,0.000000000000000000e+00,4.663798461975711684e-01,0.000000000000000000e+00,-1.000000008698372689e+00,0.000000000000000000e+00 +3.071777754512303460e+01,1.769799999999999898e+02,0.000000000000000000e+00,1.089146046690886571e+01,0.000000000000000000e+00,4.654616595772673171e-01,0.000000000000000000e+00,-1.000000009623424058e+00,0.000000000000000000e+00 +3.071869569563465774e+01,1.769900000000000091e+02,0.000000000000000000e+00,1.089188783076974687e+01,0.000000000000000000e+00,4.645435090568098557e-01,0.000000000000000000e+00,-1.000000007566955507e+00,0.000000000000000000e+00 +3.071961381012090442e+01,1.770000000000000000e+02,0.000000000000000000e+00,1.089231433489490364e+01,0.000000000000000000e+00,4.636253945636161777e-01,0.000000000000000000e+00,-1.000000011183716397e+00,0.000000000000000000e+00 +3.072053188865706730e+01,1.770099999999999909e+02,0.000000000000000000e+00,1.089273997941847227e+01,0.000000000000000000e+00,4.627073160171863431e-01,0.000000000000000000e+00,-1.000000008053713918e+00,0.000000000000000000e+00 +3.072144993131840707e+01,1.770200000000000102e+02,0.000000000000000000e+00,1.089316476447429061e+01,0.000000000000000000e+00,4.617892733484517676e-01,0.000000000000000000e+00,-1.000000008938414231e+00,0.000000000000000000e+00 +3.072236793818015954e+01,1.770300000000000011e+02,0.000000000000000000e+00,1.089358869019590870e+01,0.000000000000000000e+00,4.608712664784926361e-01,0.000000000000000000e+00,-1.000000009846856663e+00,0.000000000000000000e+00 +3.072328590931753212e+01,1.770399999999999920e+02,0.000000000000000000e+00,1.089401175671657995e+01,0.000000000000000000e+00,4.599532953320816797e-01,0.000000000000000000e+00,-1.000000006785389584e+00,0.000000000000000000e+00 +3.072420384480570021e+01,1.770500000000000114e+02,0.000000000000000000e+00,1.089443396416926468e+01,0.000000000000000000e+00,4.590353598376860078e-01,0.000000000000000000e+00,-1.000000010517570370e+00,0.000000000000000000e+00 +3.072512174471981083e+01,1.770600000000000023e+02,0.000000000000000000e+00,1.089485531268663365e+01,0.000000000000000000e+00,4.581174599139208325e-01,0.000000000000000000e+00,-1.000000010724503285e+00,0.000000000000000000e+00 +3.072603960913498611e+01,1.770699999999999932e+02,0.000000000000000000e+00,1.089527580240105920e+01,0.000000000000000000e+00,4.571995954889017666e-01,0.000000000000000000e+00,-1.000000007626723697e+00,0.000000000000000000e+00 +3.072695743812631619e+01,1.770800000000000125e+02,0.000000000000000000e+00,1.089569543344462410e+01,0.000000000000000000e+00,4.562817664905698956e-01,0.000000000000000000e+00,-1.000000007770735388e+00,0.000000000000000000e+00 +3.072787523176886992e+01,1.770900000000000034e+02,0.000000000000000000e+00,1.089611420594912161e+01,0.000000000000000000e+00,4.553639728408858112e-01,0.000000000000000000e+00,-1.000000011378274989e+00,0.000000000000000000e+00 +3.072879299013767707e+01,1.770999999999999943e+02,0.000000000000000000e+00,1.089653212004605010e+01,0.000000000000000000e+00,4.544462144616350785e-01,0.000000000000000000e+00,-1.000000008123642425e+00,0.000000000000000000e+00 +3.072971071330774961e+01,1.771100000000000136e+02,0.000000000000000000e+00,1.089694917586661305e+01,0.000000000000000000e+00,4.535284912841078264e-01,0.000000000000000000e+00,-1.000000008771515292e+00,0.000000000000000000e+00 +3.073062840135406404e+01,1.771200000000000045e+02,0.000000000000000000e+00,1.089736537354172796e+01,0.000000000000000000e+00,4.526108032297428418e-01,0.000000000000000000e+00,-1.000000007213030395e+00,0.000000000000000000e+00 +3.073154605435157549e+01,1.771299999999999955e+02,0.000000000000000000e+00,1.089778071320201747e+01,0.000000000000000000e+00,4.516931502256130715e-01,0.000000000000000000e+00,-1.000000012104624192e+00,0.000000000000000000e+00 +3.073246367237520360e+01,1.771400000000000148e+02,0.000000000000000000e+00,1.089819519497781464e+01,0.000000000000000000e+00,4.507755321908757939e-01,0.000000000000000000e+00,-1.000000006787199025e+00,0.000000000000000000e+00 +3.073338125549985023e+01,1.771500000000000057e+02,0.000000000000000000e+00,1.089860881899915590e+01,0.000000000000000000e+00,4.498579490600028707e-01,0.000000000000000000e+00,-1.000000010464931144e+00,0.000000000000000000e+00 +3.073429880380037815e+01,1.771599999999999966e+02,0.000000000000000000e+00,1.089902158539579524e+01,0.000000000000000000e+00,4.489404007498720706e-01,0.000000000000000000e+00,-1.000000008586209299e+00,0.000000000000000000e+00 +3.073521631735163240e+01,1.771700000000000159e+02,0.000000000000000000e+00,1.089943349429718822e+01,0.000000000000000000e+00,4.480228871907410704e-01,0.000000000000000000e+00,-1.000000009806605084e+00,0.000000000000000000e+00 +3.073613379622842245e+01,1.771800000000000068e+02,0.000000000000000000e+00,1.089984454583250439e+01,0.000000000000000000e+00,4.471054083049532668e-01,0.000000000000000000e+00,-1.000000008011345143e+00,0.000000000000000000e+00 +3.073705124050553650e+01,1.771899999999999977e+02,0.000000000000000000e+00,1.090025474013062023e+01,0.000000000000000000e+00,4.461879640204898800e-01,0.000000000000000000e+00,-1.000000009746564222e+00,0.000000000000000000e+00 +3.073796865025773073e+01,1.772000000000000171e+02,0.000000000000000000e+00,1.090066407732012443e+01,0.000000000000000000e+00,4.452705542593538013e-01,0.000000000000000000e+00,-1.000000008895481241e+00,0.000000000000000000e+00 +3.073888602555973648e+01,1.772100000000000080e+02,0.000000000000000000e+00,1.090107255752931259e+01,0.000000000000000000e+00,4.443531789491870776e-01,0.000000000000000000e+00,-1.000000009893326602e+00,0.000000000000000000e+00 +3.073980336648625666e+01,1.772199999999999989e+02,0.000000000000000000e+00,1.090148018088619253e+01,0.000000000000000000e+00,4.434358380135902111e-01,0.000000000000000000e+00,-1.000000006620591408e+00,0.000000000000000000e+00 +3.074072067311196932e+01,1.772299999999999898e+02,0.000000000000000000e+00,1.090188694751848075e+01,0.000000000000000000e+00,4.425185313818046362e-01,0.000000000000000000e+00,-1.000000011957077550e+00,0.000000000000000000e+00 +3.074163794551152051e+01,1.772400000000000091e+02,0.000000000000000000e+00,1.090229285755360777e+01,0.000000000000000000e+00,4.416012589712842717e-01,0.000000000000000000e+00,-1.000000007114442369e+00,0.000000000000000000e+00 +3.074255518375953500e+01,1.772500000000000000e+02,0.000000000000000000e+00,1.090269791111870745e+01,0.000000000000000000e+00,4.406840207167444512e-01,0.000000000000000000e+00,-1.000000009194669914e+00,0.000000000000000000e+00 +3.074347238793060555e+01,1.772599999999999909e+02,0.000000000000000000e+00,1.090310210834063298e+01,0.000000000000000000e+00,4.397668165372405347e-01,0.000000000000000000e+00,-1.000000009964048253e+00,0.000000000000000000e+00 +3.074438955809930007e+01,1.772700000000000102e+02,0.000000000000000000e+00,1.090350544934594268e+01,0.000000000000000000e+00,4.388496463594073194e-01,0.000000000000000000e+00,-1.000000007521259171e+00,0.000000000000000000e+00 +3.074530669434015806e+01,1.772800000000000011e+02,0.000000000000000000e+00,1.090390793426090710e+01,0.000000000000000000e+00,4.379325101116501862e-01,0.000000000000000000e+00,-1.000000010524012106e+00,0.000000000000000000e+00 +3.074622379672769412e+01,1.772899999999999920e+02,0.000000000000000000e+00,1.090430956321151079e+01,0.000000000000000000e+00,4.370154077144610683e-01,0.000000000000000000e+00,-1.000000008622527359e+00,0.000000000000000000e+00 +3.074714086533639801e+01,1.773000000000000114e+02,0.000000000000000000e+00,1.090471033632344522e+01,0.000000000000000000e+00,4.360983390978507290e-01,0.000000000000000000e+00,-1.000000008361909165e+00,0.000000000000000000e+00 +3.074805790024072749e+01,1.773100000000000023e+02,0.000000000000000000e+00,1.090511025372211762e+01,0.000000000000000000e+00,4.351813041858541009e-01,0.000000000000000000e+00,-1.000000009951416802e+00,0.000000000000000000e+00 +3.074897490151511548e+01,1.773199999999999932e+02,0.000000000000000000e+00,1.090550931553264569e+01,0.000000000000000000e+00,4.342643029023410817e-01,0.000000000000000000e+00,-1.000000009374492294e+00,0.000000000000000000e+00 +3.074989186923397000e+01,1.773300000000000125e+02,0.000000000000000000e+00,1.090590752187985757e+01,0.000000000000000000e+00,4.333473351748914348e-01,0.000000000000000000e+00,-1.000000008951120067e+00,0.000000000000000000e+00 +3.075080880347167067e+01,1.773400000000000034e+02,0.000000000000000000e+00,1.090630487288829542e+01,0.000000000000000000e+00,4.324304009289839934e-01,0.000000000000000000e+00,-1.000000006775589867e+00,0.000000000000000000e+00 +3.075172570430257224e+01,1.773499999999999943e+02,0.000000000000000000e+00,1.090670136868221363e+01,0.000000000000000000e+00,4.315135000918714492e-01,0.000000000000000000e+00,-1.000000011506712694e+00,0.000000000000000000e+00 +3.075264257180100103e+01,1.773600000000000136e+02,0.000000000000000000e+00,1.090709700938558058e+01,0.000000000000000000e+00,4.305966325828937680e-01,0.000000000000000000e+00,-1.000000008559394304e+00,0.000000000000000000e+00 +3.075355940604125848e+01,1.773700000000000045e+02,0.000000000000000000e+00,1.090749179512207157e+01,0.000000000000000000e+00,4.296797983347900862e-01,0.000000000000000000e+00,-1.000000008704713172e+00,0.000000000000000000e+00 +3.075447620709761765e+01,1.773799999999999955e+02,0.000000000000000000e+00,1.090788572601508122e+01,0.000000000000000000e+00,4.287629972704501413e-01,0.000000000000000000e+00,-1.000000010034903575e+00,0.000000000000000000e+00 +3.075539297504433023e+01,1.773900000000000148e+02,0.000000000000000000e+00,1.090827880218771462e+01,0.000000000000000000e+00,4.278462293145391948e-01,0.000000000000000000e+00,-1.000000006413611864e+00,0.000000000000000000e+00 +3.075630970995561597e+01,1.774000000000000057e+02,0.000000000000000000e+00,1.090867102376278908e+01,0.000000000000000000e+00,4.269294943973742096e-01,0.000000000000000000e+00,-1.000000010727155830e+00,0.000000000000000000e+00 +3.075722641190567330e+01,1.774099999999999966e+02,0.000000000000000000e+00,1.090906239086283946e+01,0.000000000000000000e+00,4.260127924374848551e-01,0.000000000000000000e+00,-1.000000010497023917e+00,0.000000000000000000e+00 +3.075814308096866867e+01,1.774200000000000159e+02,0.000000000000000000e+00,1.090945290361010755e+01,0.000000000000000000e+00,4.250961233648662962e-01,0.000000000000000000e+00,-1.000000005924936985e+00,0.000000000000000000e+00 +3.075905971721875076e+01,1.774300000000000068e+02,0.000000000000000000e+00,1.090984256212655268e+01,0.000000000000000000e+00,4.241794871093543251e-01,0.000000000000000000e+00,-1.000000012012790318e+00,0.000000000000000000e+00 +3.075997632073003629e+01,1.774399999999999977e+02,0.000000000000000000e+00,1.091023136653385173e+01,0.000000000000000000e+00,4.232628835870594353e-01,0.000000000000000000e+00,-1.000000007820632586e+00,0.000000000000000000e+00 +3.076089289157661710e+01,1.774500000000000171e+02,0.000000000000000000e+00,1.091061931695338671e+01,0.000000000000000000e+00,4.223463127333119682e-01,0.000000000000000000e+00,-1.000000008349745340e+00,0.000000000000000000e+00 +3.076180942983256017e+01,1.774600000000000080e+02,0.000000000000000000e+00,1.091100641350626255e+01,0.000000000000000000e+00,4.214297744697177994e-01,0.000000000000000000e+00,-1.000000009572747928e+00,0.000000000000000000e+00 +3.076272593557190405e+01,1.774699999999999989e+02,0.000000000000000000e+00,1.091139265631329458e+01,0.000000000000000000e+00,4.205132687216001086e-01,0.000000000000000000e+00,-1.000000009575403359e+00,0.000000000000000000e+00 +3.076364240886866597e+01,1.774799999999999898e+02,0.000000000000000000e+00,1.091177804549501218e+01,0.000000000000000000e+00,4.195967954160621516e-01,0.000000000000000000e+00,-1.000000008557660802e+00,0.000000000000000000e+00 +3.076455884979683475e+01,1.774900000000000091e+02,0.000000000000000000e+00,1.091216258117166049e+01,0.000000000000000000e+00,4.186803544800494215e-01,0.000000000000000000e+00,-1.000000008833605403e+00,0.000000000000000000e+00 +3.076547525843037789e+01,1.775000000000000000e+02,0.000000000000000000e+00,1.091254626346320045e+01,0.000000000000000000e+00,4.177639458384121984e-01,0.000000000000000000e+00,-1.000000008487380354e+00,0.000000000000000000e+00 +3.076639163484323092e+01,1.775099999999999909e+02,0.000000000000000000e+00,1.091292909248930698e+01,0.000000000000000000e+00,4.168475694177820046e-01,0.000000000000000000e+00,-1.000000009832894721e+00,0.000000000000000000e+00 +3.076730797910930804e+01,1.775200000000000102e+02,0.000000000000000000e+00,1.091331106836937082e+01,0.000000000000000000e+00,4.159312251426953710e-01,0.000000000000000000e+00,-1.000000010952787122e+00,0.000000000000000000e+00 +3.076822429130249503e+01,1.775300000000000011e+02,0.000000000000000000e+00,1.091369219122249667e+01,0.000000000000000000e+00,4.150149129394712366e-01,0.000000000000000000e+00,-1.000000005696896954e+00,0.000000000000000000e+00 +3.076914057149665638e+01,1.775399999999999920e+02,0.000000000000000000e+00,1.091407246116750507e+01,0.000000000000000000e+00,4.140986327400890676e-01,0.000000000000000000e+00,-1.000000011188455051e+00,0.000000000000000000e+00 +3.077005681976563167e+01,1.775500000000000114e+02,0.000000000000000000e+00,1.091445187832293762e+01,0.000000000000000000e+00,4.131823844608638052e-01,0.000000000000000000e+00,-1.000000008581492850e+00,0.000000000000000000e+00 +3.077097303618322854e+01,1.775600000000000023e+02,0.000000000000000000e+00,1.091483044280704284e+01,0.000000000000000000e+00,4.122661680354035574e-01,0.000000000000000000e+00,-1.000000008651306338e+00,0.000000000000000000e+00 +3.077188922082323685e+01,1.775699999999999932e+02,0.000000000000000000e+00,1.091520815473779216e+01,0.000000000000000000e+00,4.113499833874685874e-01,0.000000000000000000e+00,-1.000000009477471252e+00,0.000000000000000000e+00 +3.077280537375941805e+01,1.775800000000000125e+02,0.000000000000000000e+00,1.091558501423287098e+01,0.000000000000000000e+00,4.104338304426038420e-01,0.000000000000000000e+00,-1.000000007021903281e+00,0.000000000000000000e+00 +3.077372149506550869e+01,1.775900000000000034e+02,0.000000000000000000e+00,1.091596102140968050e+01,0.000000000000000000e+00,4.095177091300786776e-01,0.000000000000000000e+00,-1.000000012061978971e+00,0.000000000000000000e+00 +3.077463758481522405e+01,1.775999999999999943e+02,0.000000000000000000e+00,1.091633617638534126e+01,0.000000000000000000e+00,4.086016193693139953e-01,0.000000000000000000e+00,-1.000000007858465656e+00,0.000000000000000000e+00 +3.077555364308224739e+01,1.776100000000000136e+02,0.000000000000000000e+00,1.091671047927668425e+01,0.000000000000000000e+00,4.076855610950903541e-01,0.000000000000000000e+00,-1.000000007304453709e+00,0.000000000000000000e+00 +3.077646966994024424e+01,1.776200000000000045e+02,0.000000000000000000e+00,1.091708393020026513e+01,0.000000000000000000e+00,4.067695342304017969e-01,0.000000000000000000e+00,-1.000000010593769417e+00,0.000000000000000000e+00 +3.077738566546285170e+01,1.776299999999999955e+02,0.000000000000000000e+00,1.091745652927235355e+01,0.000000000000000000e+00,4.058535386980898774e-01,0.000000000000000000e+00,-1.000000009450717098e+00,0.000000000000000000e+00 +3.077830162972368200e+01,1.776400000000000148e+02,0.000000000000000000e+00,1.091782827660893318e+01,0.000000000000000000e+00,4.049375744286013989e-01,0.000000000000000000e+00,-1.000000008300779175e+00,0.000000000000000000e+00 +3.077921756279632604e+01,1.776500000000000057e+02,0.000000000000000000e+00,1.091819917232570880e+01,0.000000000000000000e+00,4.040216413483538882e-01,0.000000000000000000e+00,-1.000000009452869376e+00,0.000000000000000000e+00 +3.078013346475434631e+01,1.776599999999999966e+02,0.000000000000000000e+00,1.091856921653810275e+01,0.000000000000000000e+00,4.031057393816746548e-01,0.000000000000000000e+00,-1.000000008863284329e+00,0.000000000000000000e+00 +3.078104933567128398e+01,1.776700000000000159e+02,0.000000000000000000e+00,1.091893840936125315e+01,0.000000000000000000e+00,4.021898684566191928e-01,0.000000000000000000e+00,-1.000000008839506904e+00,0.000000000000000000e+00 +3.078196517562065537e+01,1.776800000000000068e+02,0.000000000000000000e+00,1.091930675091001746e+01,0.000000000000000000e+00,4.012740284991539452e-01,0.000000000000000000e+00,-1.000000009571702764e+00,0.000000000000000000e+00 +3.078288098467594835e+01,1.776899999999999977e+02,0.000000000000000000e+00,1.091967424129897068e+01,0.000000000000000000e+00,4.003582194350955858e-01,0.000000000000000000e+00,-1.000000009131331469e+00,0.000000000000000000e+00 +3.078379676291062950e+01,1.777000000000000171e+02,0.000000000000000000e+00,1.092004088064240541e+01,0.000000000000000000e+00,3.994424411920512452e-01,0.000000000000000000e+00,-1.000000007706925098e+00,0.000000000000000000e+00 +3.078471251039814405e+01,1.777100000000000080e+02,0.000000000000000000e+00,1.092040666905433355e+01,0.000000000000000000e+00,3.985266936974795060e-01,0.000000000000000000e+00,-1.000000009723432948e+00,0.000000000000000000e+00 +3.078562822721190884e+01,1.777199999999999989e+02,0.000000000000000000e+00,1.092077160664848634e+01,0.000000000000000000e+00,3.976109768748110063e-01,0.000000000000000000e+00,-1.000000009013886304e+00,0.000000000000000000e+00 +3.078654391342531937e+01,1.777299999999999898e+02,0.000000000000000000e+00,1.092113569353831082e+01,0.000000000000000000e+00,3.966952906531477918e-01,0.000000000000000000e+00,-1.000000010002431106e+00,0.000000000000000000e+00 +3.078745956911174275e+01,1.777400000000000091e+02,0.000000000000000000e+00,1.092149892983697512e+01,0.000000000000000000e+00,3.957796349575646855e-01,0.000000000000000000e+00,-1.000000008638635363e+00,0.000000000000000000e+00 +3.078837519434452830e+01,1.777500000000000000e+02,0.000000000000000000e+00,1.092186131565736495e+01,0.000000000000000000e+00,3.948640097168693019e-01,0.000000000000000000e+00,-1.000000007227207721e+00,0.000000000000000000e+00 +3.078929078919699691e+01,1.777599999999999909e+02,0.000000000000000000e+00,1.092222285111208713e+01,0.000000000000000000e+00,3.939484148577827582e-01,0.000000000000000000e+00,-1.000000010192556577e+00,0.000000000000000000e+00 +3.079020635374244819e+01,1.777700000000000102e+02,0.000000000000000000e+00,1.092258353631346779e+01,0.000000000000000000e+00,3.930328503029991705e-01,0.000000000000000000e+00,-1.000000009243755095e+00,0.000000000000000000e+00 +3.079112188805415684e+01,1.777800000000000011e+02,0.000000000000000000e+00,1.092294337137354887e+01,0.000000000000000000e+00,3.921173159828274524e-01,0.000000000000000000e+00,-1.000000008803710649e+00,0.000000000000000000e+00 +3.079203739220537273e+01,1.777899999999999920e+02,0.000000000000000000e+00,1.092330235640409519e+01,0.000000000000000000e+00,3.912018118235506825e-01,0.000000000000000000e+00,-1.000000009056809080e+00,0.000000000000000000e+00 +3.079295286626932437e+01,1.778000000000000114e+02,0.000000000000000000e+00,1.092366049151659091e+01,0.000000000000000000e+00,3.902863377513068333e-01,0.000000000000000000e+00,-1.000000010187149568e+00,0.000000000000000000e+00 +3.079386831031921545e+01,1.778100000000000023e+02,0.000000000000000000e+00,1.092401777682223951e+01,0.000000000000000000e+00,3.893708936920889929e-01,0.000000000000000000e+00,-1.000000008138926644e+00,0.000000000000000000e+00 +3.079478372442822831e+01,1.778199999999999932e+02,0.000000000000000000e+00,1.092437421243196383e+01,0.000000000000000000e+00,3.884554795756265944e-01,0.000000000000000000e+00,-1.000000009453733796e+00,0.000000000000000000e+00 +3.079569910866951687e+01,1.778300000000000125e+02,0.000000000000000000e+00,1.092472979845640957e+01,0.000000000000000000e+00,3.875400953256841752e-01,0.000000000000000000e+00,-1.000000007954752190e+00,0.000000000000000000e+00 +3.079661446311621731e+01,1.778400000000000034e+02,0.000000000000000000e+00,1.092508453500594001e+01,0.000000000000000000e+00,3.866247408717039535e-01,0.000000000000000000e+00,-1.000000008063704815e+00,0.000000000000000000e+00 +3.079752978784143735e+01,1.778499999999999943e+02,0.000000000000000000e+00,1.092543842219064132e+01,0.000000000000000000e+00,3.857094161391039222e-01,0.000000000000000000e+00,-1.000000012082858269e+00,0.000000000000000000e+00 +3.079844508291826344e+01,1.778600000000000136e+02,0.000000000000000000e+00,1.092579146012031899e+01,0.000000000000000000e+00,3.847941210512182408e-01,0.000000000000000000e+00,-1.000000005350144772e+00,0.000000000000000000e+00 +3.079936034841976067e+01,1.778700000000000045e+02,0.000000000000000000e+00,1.092614364890449608e+01,0.000000000000000000e+00,3.838788555448243156e-01,0.000000000000000000e+00,-1.000000011370927089e+00,0.000000000000000000e+00 +3.080027558441896929e+01,1.778799999999999955e+02,0.000000000000000000e+00,1.092649498865242563e+01,0.000000000000000000e+00,3.829636195352087991e-01,0.000000000000000000e+00,-1.000000009120161959e+00,0.000000000000000000e+00 +3.080119079098890467e+01,1.778900000000000148e+02,0.000000000000000000e+00,1.092684547947307117e+01,0.000000000000000000e+00,3.820484129569248211e-01,0.000000000000000000e+00,-1.000000009379953259e+00,0.000000000000000000e+00 +3.080210596820256441e+01,1.779000000000000057e+02,0.000000000000000000e+00,1.092719512147512440e+01,0.000000000000000000e+00,3.811332357346802757e-01,0.000000000000000000e+00,-1.000000008087769121e+00,0.000000000000000000e+00 +3.080302111613291771e+01,1.779099999999999966e+02,0.000000000000000000e+00,1.092754391476699638e+01,0.000000000000000000e+00,3.802180877969240647e-01,0.000000000000000000e+00,-1.000000007542880542e+00,0.000000000000000000e+00 +3.080393623485291599e+01,1.779200000000000159e+02,0.000000000000000000e+00,1.092789185945682107e+01,0.000000000000000000e+00,3.793029690700237544e-01,0.000000000000000000e+00,-1.000000012166317731e+00,0.000000000000000000e+00 +3.080485132443548224e+01,1.779300000000000068e+02,0.000000000000000000e+00,1.092823895565245351e+01,0.000000000000000000e+00,3.783878794763241848e-01,0.000000000000000000e+00,-1.000000007286061754e+00,0.000000000000000000e+00 +3.080576638495352171e+01,1.779399999999999977e+02,0.000000000000000000e+00,1.092858520346146634e+01,0.000000000000000000e+00,3.774728189516192156e-01,0.000000000000000000e+00,-1.000000007928642187e+00,0.000000000000000000e+00 +3.080668141647991121e+01,1.779500000000000171e+02,0.000000000000000000e+00,1.092893060299116215e+01,0.000000000000000000e+00,3.765577874179748541e-01,0.000000000000000000e+00,-1.000000010027978226e+00,0.000000000000000000e+00 +3.080759641908750979e+01,1.779600000000000080e+02,0.000000000000000000e+00,1.092927515434856112e+01,0.000000000000000000e+00,3.756427848012007242e-01,0.000000000000000000e+00,-1.000000009516860855e+00,0.000000000000000000e+00 +3.080851139284915163e+01,1.779699999999999989e+02,0.000000000000000000e+00,1.092961885764040453e+01,0.000000000000000000e+00,3.747278110308505661e-01,0.000000000000000000e+00,-1.000000008692313980e+00,0.000000000000000000e+00 +3.080942633783764961e+01,1.779799999999999898e+02,0.000000000000000000e+00,1.092996171297315833e+01,0.000000000000000000e+00,3.738128660343987830e-01,0.000000000000000000e+00,-1.000000007729104912e+00,0.000000000000000000e+00 +3.081034125412579527e+01,1.779900000000000091e+02,0.000000000000000000e+00,1.093030372045301135e+01,0.000000000000000000e+00,3.728979497391823328e-01,0.000000000000000000e+00,-1.000000011046622728e+00,0.000000000000000000e+00 +3.081125614178635530e+01,1.780000000000000000e+02,0.000000000000000000e+00,1.093064488018587532e+01,0.000000000000000000e+00,3.719830620685173339e-01,0.000000000000000000e+00,-1.000000008207488467e+00,0.000000000000000000e+00 +3.081217100089207150e+01,1.780099999999999909e+02,0.000000000000000000e+00,1.093098519227738130e+01,0.000000000000000000e+00,3.710682029552913597e-01,0.000000000000000000e+00,-1.000000007874510599e+00,0.000000000000000000e+00 +3.081308583151567149e+01,1.780200000000000102e+02,0.000000000000000000e+00,1.093132465683288856e+01,0.000000000000000000e+00,3.701533723244887497e-01,0.000000000000000000e+00,-1.000000010220957636e+00,0.000000000000000000e+00 +3.081400063372985088e+01,1.780300000000000011e+02,0.000000000000000000e+00,1.093166327395747750e+01,0.000000000000000000e+00,3.692385701009577859e-01,0.000000000000000000e+00,-1.000000009051926098e+00,0.000000000000000000e+00 +3.081491540760729109e+01,1.780399999999999920e+02,0.000000000000000000e+00,1.093200104375594961e+01,0.000000000000000000e+00,3.683237962152360878e-01,0.000000000000000000e+00,-1.000000008784478256e+00,0.000000000000000000e+00 +3.081583015322064867e+01,1.780500000000000114e+02,0.000000000000000000e+00,1.093233796633283283e+01,0.000000000000000000e+00,3.674090505938426010e-01,0.000000000000000000e+00,-1.000000009590638728e+00,0.000000000000000000e+00 +3.081674487064255885e+01,1.780600000000000023e+02,0.000000000000000000e+00,1.093267404179237801e+01,0.000000000000000000e+00,3.664943331631610457e-01,0.000000000000000000e+00,-1.000000007395221324e+00,0.000000000000000000e+00 +3.081765955994563200e+01,1.780699999999999932e+02,0.000000000000000000e+00,1.093300927023855884e+01,0.000000000000000000e+00,3.655796438533247539e-01,0.000000000000000000e+00,-1.000000010861810784e+00,0.000000000000000000e+00 +3.081857422120245715e+01,1.780800000000000125e+02,0.000000000000000000e+00,1.093334365177507550e+01,0.000000000000000000e+00,3.646649825865644901e-01,0.000000000000000000e+00,-1.000000007420893677e+00,0.000000000000000000e+00 +3.081948885448560560e+01,1.780900000000000034e+02,0.000000000000000000e+00,1.093367718650534748e+01,0.000000000000000000e+00,3.637503492966298602e-01,0.000000000000000000e+00,-1.000000009982315197e+00,0.000000000000000000e+00 +3.082040345986762020e+01,1.780999999999999943e+02,0.000000000000000000e+00,1.093400987453252426e+01,0.000000000000000000e+00,3.628357439054842870e-01,0.000000000000000000e+00,-1.000000008098047566e+00,0.000000000000000000e+00 +3.082131803742102960e+01,1.781100000000000136e+02,0.000000000000000000e+00,1.093434171595947468e+01,0.000000000000000000e+00,3.619211663446689764e-01,0.000000000000000000e+00,-1.000000010431366659e+00,0.000000000000000000e+00 +3.082223258721833403e+01,1.781200000000000045e+02,0.000000000000000000e+00,1.093467271088879578e+01,0.000000000000000000e+00,3.610066165378234548e-01,0.000000000000000000e+00,-1.000000006531310381e+00,0.000000000000000000e+00 +3.082314710933201596e+01,1.781299999999999955e+02,0.000000000000000000e+00,1.093500285942280570e+01,0.000000000000000000e+00,3.600920944181668637e-01,0.000000000000000000e+00,-1.000000011433401559e+00,0.000000000000000000e+00 +3.082406160383453653e+01,1.781400000000000148e+02,0.000000000000000000e+00,1.093533216166355260e+01,0.000000000000000000e+00,3.591775999051894930e-01,0.000000000000000000e+00,-1.000000008312847521e+00,0.000000000000000000e+00 +3.082497607079833557e+01,1.781500000000000057e+02,0.000000000000000000e+00,1.093566061771280218e+01,0.000000000000000000e+00,3.582631329337895854e-01,0.000000000000000000e+00,-1.000000007956547421e+00,0.000000000000000000e+00 +3.082589051029582805e+01,1.781599999999999966e+02,0.000000000000000000e+00,1.093598822767205192e+01,0.000000000000000000e+00,3.573486934290222017e-01,0.000000000000000000e+00,-1.000000010531530314e+00,0.000000000000000000e+00 +3.082680492239940762e+01,1.781700000000000159e+02,0.000000000000000000e+00,1.093631499164252219e+01,0.000000000000000000e+00,3.564342813158112855e-01,0.000000000000000000e+00,-1.000000007705795113e+00,0.000000000000000000e+00 +3.082771930718145015e+01,1.781800000000000068e+02,0.000000000000000000e+00,1.093664090972515623e+01,0.000000000000000000e+00,3.555198965267210021e-01,0.000000000000000000e+00,-1.000000008142686303e+00,0.000000000000000000e+00 +3.082863366471431021e+01,1.781899999999999977e+02,0.000000000000000000e+00,1.093696598202062731e+01,0.000000000000000000e+00,3.546055389864149476e-01,0.000000000000000000e+00,-1.000000012007695505e+00,0.000000000000000000e+00 +3.082954799507031751e+01,1.782000000000000171e+02,0.000000000000000000e+00,1.093729020862933154e+01,0.000000000000000000e+00,3.536912086194268778e-01,0.000000000000000000e+00,-1.000000006716172507e+00,0.000000000000000000e+00 +3.083046229832178398e+01,1.782100000000000080e+02,0.000000000000000000e+00,1.093761358965138797e+01,0.000000000000000000e+00,3.527769053618181605e-01,0.000000000000000000e+00,-1.000000009430966896e+00,0.000000000000000000e+00 +3.083137657454100022e+01,1.782199999999999989e+02,0.000000000000000000e+00,1.093793612518664915e+01,0.000000000000000000e+00,3.518626291339789214e-01,0.000000000000000000e+00,-1.000000009691169645e+00,0.000000000000000000e+00 +3.083229082380023556e+01,1.782299999999999898e+02,0.000000000000000000e+00,1.093825781533468700e+01,0.000000000000000000e+00,3.509483798658848408e-01,0.000000000000000000e+00,-1.000000007659334722e+00,0.000000000000000000e+00 +3.083320504617173441e+01,1.782400000000000091e+02,0.000000000000000000e+00,1.093857866019480163e+01,0.000000000000000000e+00,3.500341574873837569e-01,0.000000000000000000e+00,-1.000000009873890372e+00,0.000000000000000000e+00 +3.083411924172772345e+01,1.782500000000000000e+02,0.000000000000000000e+00,1.093889865986602139e+01,0.000000000000000000e+00,3.491199619223668282e-01,0.000000000000000000e+00,-1.000000007995414109e+00,0.000000000000000000e+00 +3.083503341054041158e+01,1.782599999999999909e+02,0.000000000000000000e+00,1.093921781444709751e+01,0.000000000000000000e+00,3.482057931023700426e-01,0.000000000000000000e+00,-1.000000010687615903e+00,0.000000000000000000e+00 +3.083594755268198284e+01,1.782700000000000102e+02,0.000000000000000000e+00,1.093953612403651121e+01,0.000000000000000000e+00,3.472916509510299843e-01,0.000000000000000000e+00,-1.000000007483350606e+00,0.000000000000000000e+00 +3.083686166822459995e+01,1.782800000000000011e+02,0.000000000000000000e+00,1.093985358873246660e+01,0.000000000000000000e+00,3.463775354015725116e-01,0.000000000000000000e+00,-1.000000009171736037e+00,0.000000000000000000e+00 +3.083777575724040787e+01,1.782899999999999920e+02,0.000000000000000000e+00,1.094017020863289957e+01,0.000000000000000000e+00,3.454634463773814668e-01,0.000000000000000000e+00,-1.000000009535904510e+00,0.000000000000000000e+00 +3.083868981980153023e+01,1.783000000000000114e+02,0.000000000000000000e+00,1.094048598383546889e+01,0.000000000000000000e+00,3.445493838075442961e-01,0.000000000000000000e+00,-1.000000008735172585e+00,0.000000000000000000e+00 +3.083960385598006582e+01,1.783100000000000023e+02,0.000000000000000000e+00,1.094080091443756153e+01,0.000000000000000000e+00,3.436353476210232682e-01,0.000000000000000000e+00,-1.000000009055036054e+00,0.000000000000000000e+00 +3.084051786584809918e+01,1.783199999999999932e+02,0.000000000000000000e+00,1.094111500053629271e+01,0.000000000000000000e+00,3.427213377447120846e-01,0.000000000000000000e+00,-1.000000008527767159e+00,0.000000000000000000e+00 +3.084143184947769356e+01,1.783300000000000125e+02,0.000000000000000000e+00,1.094142824222850408e+01,0.000000000000000000e+00,3.418073541073234356e-01,0.000000000000000000e+00,-1.000000009438342996e+00,0.000000000000000000e+00 +3.084234580694088734e+01,1.783400000000000034e+02,0.000000000000000000e+00,1.094174063961076548e+01,0.000000000000000000e+00,3.408933966355019440e-01,0.000000000000000000e+00,-1.000000007691259407e+00,0.000000000000000000e+00 +3.084325973830970469e+01,1.783499999999999943e+02,0.000000000000000000e+00,1.094205219277937324e+01,0.000000000000000000e+00,3.399794652596556666e-01,0.000000000000000000e+00,-1.000000009823970970e+00,0.000000000000000000e+00 +3.084417364365614489e+01,1.783600000000000136e+02,0.000000000000000000e+00,1.094236290183035365e+01,0.000000000000000000e+00,3.390655599042380897e-01,0.000000000000000000e+00,-1.000000009613257523e+00,0.000000000000000000e+00 +3.084508752305218593e+01,1.783700000000000045e+02,0.000000000000000000e+00,1.094267276685945767e+01,0.000000000000000000e+00,3.381516804994104675e-01,0.000000000000000000e+00,-1.000000009342147944e+00,0.000000000000000000e+00 +3.084600137656979157e+01,1.783799999999999955e+02,0.000000000000000000e+00,1.094298178796216625e+01,0.000000000000000000e+00,3.372378269732676515e-01,0.000000000000000000e+00,-1.000000007039353989e+00,0.000000000000000000e+00 +3.084691520428090072e+01,1.783900000000000148e+02,0.000000000000000000e+00,1.094328996523368858e+01,0.000000000000000000e+00,3.363239992557259805e-01,0.000000000000000000e+00,-1.000000011369330810e+00,0.000000000000000000e+00 +3.084782900625743451e+01,1.784000000000000057e+02,0.000000000000000000e+00,1.094359729876896381e+01,0.000000000000000000e+00,3.354101972688040556e-01,0.000000000000000000e+00,-1.000000007596073992e+00,0.000000000000000000e+00 +3.084874278257129276e+01,1.784099999999999966e+02,0.000000000000000000e+00,1.094390378866265401e+01,0.000000000000000000e+00,3.344964209480063566e-01,0.000000000000000000e+00,-1.000000008638147087e+00,0.000000000000000000e+00 +3.084965653329435398e+01,1.784200000000000159e+02,0.000000000000000000e+00,1.094420943500915655e+01,0.000000000000000000e+00,3.335826702170522906e-01,0.000000000000000000e+00,-1.000000008267441842e+00,0.000000000000000000e+00 +3.085057025849847889e+01,1.784300000000000068e+02,0.000000000000000000e+00,1.094451423790259348e+01,0.000000000000000000e+00,3.326689450053722519e-01,0.000000000000000000e+00,-1.000000010892916347e+00,0.000000000000000000e+00 +3.085148395825551049e+01,1.784399999999999977e+02,0.000000000000000000e+00,1.094481819743681683e+01,0.000000000000000000e+00,3.317552452383878414e-01,0.000000000000000000e+00,-1.000000008156700204e+00,0.000000000000000000e+00 +3.085239763263727042e+01,1.784500000000000171e+02,0.000000000000000000e+00,1.094512131370540509e+01,0.000000000000000000e+00,3.308415708491769802e-01,0.000000000000000000e+00,-1.000000008722335743e+00,0.000000000000000000e+00 +3.085331128171555548e+01,1.784600000000000080e+02,0.000000000000000000e+00,1.094542358680167027e+01,0.000000000000000000e+00,3.299279217629214056e-01,0.000000000000000000e+00,-1.000000008486664260e+00,0.000000000000000000e+00 +3.085422490556215180e+01,1.784699999999999989e+02,0.000000000000000000e+00,1.094572501681865084e+01,0.000000000000000000e+00,3.290142979085714514e-01,0.000000000000000000e+00,-1.000000009729253403e+00,0.000000000000000000e+00 +3.085513850424882065e+01,1.784799999999999898e+02,0.000000000000000000e+00,1.094602560384911527e+01,0.000000000000000000e+00,3.281006992130143241e-01,0.000000000000000000e+00,-1.000000008345162117e+00,0.000000000000000000e+00 +3.085605207784730553e+01,1.784900000000000091e+02,0.000000000000000000e+00,1.094632534798556023e+01,0.000000000000000000e+00,3.271871256069069922e-01,0.000000000000000000e+00,-1.000000008741588342e+00,0.000000000000000000e+00 +3.085696562642932861e+01,1.785000000000000000e+02,0.000000000000000000e+00,1.094662424932021416e+01,0.000000000000000000e+00,3.262735770168994631e-01,0.000000000000000000e+00,-1.000000008940678864e+00,0.000000000000000000e+00 +3.085787915006659077e+01,1.785099999999999909e+02,0.000000000000000000e+00,1.094692230794503374e+01,0.000000000000000000e+00,3.253600533714680609e-01,0.000000000000000000e+00,-1.000000009092138598e+00,0.000000000000000000e+00 +3.085879264883078221e+01,1.785200000000000102e+02,0.000000000000000000e+00,1.094721952395170561e+01,0.000000000000000000e+00,3.244465545989716482e-01,0.000000000000000000e+00,-1.000000009345503482e+00,0.000000000000000000e+00 +3.085970612279356473e+01,1.785300000000000011e+02,0.000000000000000000e+00,1.094751589743164644e+01,0.000000000000000000e+00,3.235330806276517368e-01,0.000000000000000000e+00,-1.000000009849774996e+00,0.000000000000000000e+00 +3.086061957202658590e+01,1.785399999999999920e+02,0.000000000000000000e+00,1.094781142847600286e+01,0.000000000000000000e+00,3.226196313856329323e-01,0.000000000000000000e+00,-1.000000008624436498e+00,0.000000000000000000e+00 +3.086153299660147198e+01,1.785500000000000114e+02,0.000000000000000000e+00,1.094810611717565152e+01,0.000000000000000000e+00,3.217062068028680444e-01,0.000000000000000000e+00,-1.000000007946169056e+00,0.000000000000000000e+00 +3.086244639658983147e+01,1.785600000000000023e+02,0.000000000000000000e+00,1.094839996362120083e+01,0.000000000000000000e+00,3.207928068072493089e-01,0.000000000000000000e+00,-1.000000007962980275e+00,0.000000000000000000e+00 +3.086335977206325509e+01,1.785699999999999932e+02,0.000000000000000000e+00,1.094869296790298918e+01,0.000000000000000000e+00,3.198794313265528322e-01,0.000000000000000000e+00,-1.000000010951254570e+00,0.000000000000000000e+00 +3.086427312309331228e+01,1.785800000000000125e+02,0.000000000000000000e+00,1.094898513011108498e+01,0.000000000000000000e+00,3.189660802864945910e-01,0.000000000000000000e+00,-1.000000008540338436e+00,0.000000000000000000e+00 +3.086518644975155112e+01,1.785900000000000034e+02,0.000000000000000000e+00,1.094927645033528485e+01,0.000000000000000000e+00,3.180527536204548200e-01,0.000000000000000000e+00,-1.000000007264113977e+00,0.000000000000000000e+00 +3.086609975210950552e+01,1.785999999999999943e+02,0.000000000000000000e+00,1.094956692866512071e+01,0.000000000000000000e+00,3.171394512558647905e-01,0.000000000000000000e+00,-1.000000011528256794e+00,0.000000000000000000e+00 +3.086701303023869158e+01,1.786100000000000136e+02,0.000000000000000000e+00,1.094985656518985451e+01,0.000000000000000000e+00,3.162261731161510325e-01,0.000000000000000000e+00,-1.000000006569785160e+00,0.000000000000000000e+00 +3.086792628421060058e+01,1.786200000000000045e+02,0.000000000000000000e+00,1.095014535999847460e+01,0.000000000000000000e+00,3.153129191382415542e-01,0.000000000000000000e+00,-1.000000009571685444e+00,0.000000000000000000e+00 +3.086883951409670956e+01,1.786299999999999955e+02,0.000000000000000000e+00,1.095043331317970825e+01,0.000000000000000000e+00,3.143996892433903456e-01,0.000000000000000000e+00,-1.000000010029553632e+00,0.000000000000000000e+00 +3.086975271996847781e+01,1.786400000000000148e+02,0.000000000000000000e+00,1.095072042482200736e+01,0.000000000000000000e+00,3.134864833624632641e-01,0.000000000000000000e+00,-1.000000008086538106e+00,0.000000000000000000e+00 +3.087066590189734328e+01,1.786500000000000057e+02,0.000000000000000000e+00,1.095100669501355739e+01,0.000000000000000000e+00,3.125733014262138121e-01,0.000000000000000000e+00,-1.000000008146411767e+00,0.000000000000000000e+00 +3.087157905995472618e+01,1.786599999999999966e+02,0.000000000000000000e+00,1.095129212384227735e+01,0.000000000000000000e+00,3.116601433613924721e-01,0.000000000000000000e+00,-1.000000010352440460e+00,0.000000000000000000e+00 +3.087249219421202895e+01,1.786700000000000159e+02,0.000000000000000000e+00,1.095157671139581623e+01,0.000000000000000000e+00,3.107470090946374830e-01,0.000000000000000000e+00,-1.000000008455955047e+00,0.000000000000000000e+00 +3.087340530474063272e+01,1.786800000000000068e+02,0.000000000000000000e+00,1.095186045776155304e+01,0.000000000000000000e+00,3.098338985583113381e-01,0.000000000000000000e+00,-1.000000006859655732e+00,0.000000000000000000e+00 +3.087431839161190439e+01,1.786899999999999977e+02,0.000000000000000000e+00,1.095214336302660207e+01,0.000000000000000000e+00,3.089208116807745097e-01,0.000000000000000000e+00,-1.000000012097373991e+00,0.000000000000000000e+00 +3.087523145489719312e+01,1.787000000000000171e+02,0.000000000000000000e+00,1.095242542727780943e+01,0.000000000000000000e+00,3.080077483844399500e-01,0.000000000000000000e+00,-1.000000007264640001e+00,0.000000000000000000e+00 +3.087614449466782673e+01,1.787100000000000080e+02,0.000000000000000000e+00,1.095270665060174764e+01,0.000000000000000000e+00,3.070947086071737497e-01,0.000000000000000000e+00,-1.000000009548144941e+00,0.000000000000000000e+00 +3.087705751099511531e+01,1.787199999999999989e+02,0.000000000000000000e+00,1.095298703308472987e+01,0.000000000000000000e+00,3.061816922711677047e-01,0.000000000000000000e+00,-1.000000008433815646e+00,0.000000000000000000e+00 +3.087797050395035114e+01,1.787299999999999898e+02,0.000000000000000000e+00,1.095326657481279575e+01,0.000000000000000000e+00,3.052686993082314726e-01,0.000000000000000000e+00,-1.000000008323443490e+00,0.000000000000000000e+00 +3.087888347360480878e+01,1.787400000000000091e+02,0.000000000000000000e+00,1.095354527587172022e+01,0.000000000000000000e+00,3.043557296461738004e-01,0.000000000000000000e+00,-1.000000009356392106e+00,0.000000000000000000e+00 +3.087979642002974501e+01,1.787500000000000000e+02,0.000000000000000000e+00,1.095382313634700999e+01,0.000000000000000000e+00,3.034427832126942448e-01,0.000000000000000000e+00,-1.000000009540485513e+00,0.000000000000000000e+00 +3.088070934329639883e+01,1.787599999999999909e+02,0.000000000000000000e+00,1.095410015632390355e+01,0.000000000000000000e+00,3.025298599373290598e-01,0.000000000000000000e+00,-1.000000009013732427e+00,0.000000000000000000e+00 +3.088162224347599150e+01,1.787700000000000102e+02,0.000000000000000000e+00,1.095437633588737292e+01,0.000000000000000000e+00,3.016169597495063082e-01,0.000000000000000000e+00,-1.000000007914275235e+00,0.000000000000000000e+00 +3.088253512063972650e+01,1.787800000000000011e+02,0.000000000000000000e+00,1.095465167512212368e+01,0.000000000000000000e+00,3.007040825785456950e-01,0.000000000000000000e+00,-1.000000008511130467e+00,0.000000000000000000e+00 +3.088344797485878956e+01,1.787899999999999920e+02,0.000000000000000000e+00,1.095492617411259495e+01,0.000000000000000000e+00,2.997912283517133458e-01,0.000000000000000000e+00,-1.000000010941530348e+00,0.000000000000000000e+00 +3.088436080620434865e+01,1.788000000000000114e+02,0.000000000000000000e+00,1.095519983294295763e+01,0.000000000000000000e+00,2.988783969961679166e-01,0.000000000000000000e+00,-1.000000006814829812e+00,0.000000000000000000e+00 +3.088527361474755040e+01,1.788100000000000023e+02,0.000000000000000000e+00,1.095547265169711437e+01,0.000000000000000000e+00,2.979655884467448668e-01,0.000000000000000000e+00,-1.000000009058275019e+00,0.000000000000000000e+00 +3.088618640055953080e+01,1.788199999999999932e+02,0.000000000000000000e+00,1.095574463045870672e+01,0.000000000000000000e+00,2.970528026264969701e-01,0.000000000000000000e+00,-1.000000009280043400e+00,0.000000000000000000e+00 +3.088709916371140096e+01,1.788300000000000125e+02,0.000000000000000000e+00,1.095601576931110444e+01,0.000000000000000000e+00,2.961400394661546920e-01,0.000000000000000000e+00,-1.000000009747247676e+00,0.000000000000000000e+00 +3.088801190427426135e+01,1.788400000000000034e+02,0.000000000000000000e+00,1.095628606833741259e+01,0.000000000000000000e+00,2.952272988943965282e-01,0.000000000000000000e+00,-1.000000008462492262e+00,0.000000000000000000e+00 +3.088892462231919112e+01,1.788499999999999943e+02,0.000000000000000000e+00,1.095655552762046980e+01,0.000000000000000000e+00,2.943145808417414466e-01,0.000000000000000000e+00,-1.000000007692167792e+00,0.000000000000000000e+00 +3.088983731791725518e+01,1.788600000000000136e+02,0.000000000000000000e+00,1.095682414724285003e+01,0.000000000000000000e+00,2.934018852366571117e-01,0.000000000000000000e+00,-1.000000009702886272e+00,0.000000000000000000e+00 +3.089074999113949715e+01,1.788700000000000045e+02,0.000000000000000000e+00,1.095709192728686077e+01,0.000000000000000000e+00,2.924892120055598288e-01,0.000000000000000000e+00,-1.000000008230597981e+00,0.000000000000000000e+00 +3.089166264205694645e+01,1.788799999999999955e+02,0.000000000000000000e+00,1.095735886783454127e+01,0.000000000000000000e+00,2.915765610806002051e-01,0.000000000000000000e+00,-1.000000009805964929e+00,0.000000000000000000e+00 +3.089257527074061116e+01,1.788900000000000148e+02,0.000000000000000000e+00,1.095762496896766791e+01,0.000000000000000000e+00,2.906639323879857129e-01,0.000000000000000000e+00,-1.000000010296452801e+00,0.000000000000000000e+00 +3.089348787726148871e+01,1.789000000000000057e+02,0.000000000000000000e+00,1.095789023076774882e+01,0.000000000000000000e+00,2.897513258577125161e-01,0.000000000000000000e+00,-1.000000005567724504e+00,0.000000000000000000e+00 +3.089440046169055520e+01,1.789099999999999966e+02,0.000000000000000000e+00,1.095815465331602745e+01,0.000000000000000000e+00,2.888387414235666917e-01,0.000000000000000000e+00,-1.000000010682375207e+00,0.000000000000000000e+00 +3.089531302409876901e+01,1.789200000000000159e+02,0.000000000000000000e+00,1.095841823669348614e+01,0.000000000000000000e+00,2.879261790056054093e-01,0.000000000000000000e+00,-1.000000008707782051e+00,0.000000000000000000e+00 +3.089622556455707425e+01,1.789300000000000068e+02,0.000000000000000000e+00,1.095868098098083365e+01,0.000000000000000000e+00,2.870136385393551315e-01,0.000000000000000000e+00,-1.000000008306472177e+00,0.000000000000000000e+00 +3.089713808313639731e+01,1.789399999999999977e+02,0.000000000000000000e+00,1.095894288625851942e+01,0.000000000000000000e+00,2.861011199524540194e-01,0.000000000000000000e+00,-1.000000009609237406e+00,0.000000000000000000e+00 +3.089805057990764681e+01,1.789500000000000171e+02,0.000000000000000000e+00,1.095920395260672642e+01,0.000000000000000000e+00,2.851886231724378162e-01,0.000000000000000000e+00,-1.000000008479065450e+00,0.000000000000000000e+00 +3.089896305494171358e+01,1.789600000000000080e+02,0.000000000000000000e+00,1.095946418010537116e+01,0.000000000000000000e+00,2.842761481306340654e-01,0.000000000000000000e+00,-1.000000009312310922e+00,0.000000000000000000e+00 +3.089987550830947427e+01,1.789699999999999989e+02,0.000000000000000000e+00,1.095972356883410725e+01,0.000000000000000000e+00,2.833636947543753948e-01,0.000000000000000000e+00,-1.000000007970746285e+00,0.000000000000000000e+00 +3.090078794008179131e+01,1.789799999999999898e+02,0.000000000000000000e+00,1.095998211887232188e+01,0.000000000000000000e+00,2.824512629747870651e-01,0.000000000000000000e+00,-1.000000010984005705e+00,0.000000000000000000e+00 +3.090170035032950224e+01,1.789900000000000091e+02,0.000000000000000000e+00,1.096023983029913929e+01,0.000000000000000000e+00,2.815388527170530897e-01,0.000000000000000000e+00,-1.000000005677396553e+00,0.000000000000000000e+00 +3.090261273912343754e+01,1.790000000000000000e+02,0.000000000000000000e+00,1.096049670319341551e+01,0.000000000000000000e+00,2.806264639179385512e-01,0.000000000000000000e+00,-1.000000011383369580e+00,0.000000000000000000e+00 +3.090352510653440277e+01,1.790099999999999909e+02,0.000000000000000000e+00,1.096075273763374902e+01,0.000000000000000000e+00,2.797140964965861842e-01,0.000000000000000000e+00,-1.000000006889598669e+00,0.000000000000000000e+00 +3.090443745263319286e+01,1.790200000000000102e+02,0.000000000000000000e+00,1.096100793369846471e+01,0.000000000000000000e+00,2.788017503915088402e-01,0.000000000000000000e+00,-1.000000009395077827e+00,0.000000000000000000e+00 +3.090534977749058498e+01,1.790300000000000011e+02,0.000000000000000000e+00,1.096126229146563169e+01,0.000000000000000000e+00,2.778894255255440204e-01,0.000000000000000000e+00,-1.000000010489863866e+00,0.000000000000000000e+00 +3.090626208117734208e+01,1.790399999999999920e+02,0.000000000000000000e+00,1.096151581101304906e+01,0.000000000000000000e+00,2.769771218292184090e-01,0.000000000000000000e+00,-1.000000008165297993e+00,0.000000000000000000e+00 +3.090717436376420579e+01,1.790500000000000114e+02,0.000000000000000000e+00,1.096176849241825302e+01,0.000000000000000000e+00,2.760648392349073221e-01,0.000000000000000000e+00,-1.000000006814995235e+00,0.000000000000000000e+00 +3.090808662532190354e+01,1.790600000000000023e+02,0.000000000000000000e+00,1.096202033575851864e+01,0.000000000000000000e+00,2.751525776709939364e-01,0.000000000000000000e+00,-1.000000010833582476e+00,0.000000000000000000e+00 +3.090899886592114498e+01,1.790699999999999932e+02,0.000000000000000000e+00,1.096227134111085633e+01,0.000000000000000000e+00,2.742403370618686775e-01,0.000000000000000000e+00,-1.000000007538045965e+00,0.000000000000000000e+00 +3.090991108563262912e+01,1.790800000000000125e+02,0.000000000000000000e+00,1.096252150855200824e+01,0.000000000000000000e+00,2.733281173435080924e-01,0.000000000000000000e+00,-1.000000009860123606e+00,0.000000000000000000e+00 +3.091082328452703365e+01,1.790900000000000034e+02,0.000000000000000000e+00,1.096277083815845899e+01,0.000000000000000000e+00,2.724159184401079847e-01,0.000000000000000000e+00,-1.000000009384831134e+00,0.000000000000000000e+00 +3.091173546267502559e+01,1.790999999999999943e+02,0.000000000000000000e+00,1.096301933000642492e+01,0.000000000000000000e+00,2.715037402835564495e-01,0.000000000000000000e+00,-1.000000006234773586e+00,0.000000000000000000e+00 +3.091264762014725065e+01,1.791100000000000136e+02,0.000000000000000000e+00,1.096326698417186130e+01,0.000000000000000000e+00,2.705915828056454919e-01,0.000000000000000000e+00,-1.000000011207853756e+00,0.000000000000000000e+00 +3.091355975701434033e+01,1.791200000000000045e+02,0.000000000000000000e+00,1.096351380073046222e+01,0.000000000000000000e+00,2.696794459283336498e-01,0.000000000000000000e+00,-1.000000007346164788e+00,0.000000000000000000e+00 +3.091447187334690838e+01,1.791299999999999955e+02,0.000000000000000000e+00,1.096375977975765181e+01,0.000000000000000000e+00,2.687673295890633529e-01,0.000000000000000000e+00,-1.000000009717022964e+00,0.000000000000000000e+00 +3.091538396921555787e+01,1.791400000000000148e+02,0.000000000000000000e+00,1.096400492132859839e+01,0.000000000000000000e+00,2.678552337115494009e-01,0.000000000000000000e+00,-1.000000009901544695e+00,0.000000000000000000e+00 +3.091629604469087411e+01,1.791500000000000057e+02,0.000000000000000000e+00,1.096424922551820202e+01,0.000000000000000000e+00,2.669431582272013270e-01,0.000000000000000000e+00,-1.000000005884730037e+00,0.000000000000000000e+00 +3.091720809984342466e+01,1.791599999999999966e+02,0.000000000000000000e+00,1.096449269240110169e+01,0.000000000000000000e+00,2.660311030692819600e-01,0.000000000000000000e+00,-1.000000010599823241e+00,0.000000000000000000e+00 +3.091812013474376641e+01,1.791700000000000159e+02,0.000000000000000000e+00,1.096473532205167700e+01,0.000000000000000000e+00,2.651190681592738851e-01,0.000000000000000000e+00,-1.000000009218905195e+00,0.000000000000000000e+00 +3.091903214946243494e+01,1.791800000000000068e+02,0.000000000000000000e+00,1.096497711454403756e+01,0.000000000000000000e+00,2.642070534321990238e-01,0.000000000000000000e+00,-1.000000008267680318e+00,0.000000000000000000e+00 +3.091994414406995162e+01,1.791899999999999977e+02,0.000000000000000000e+00,1.096521806995203541e+01,0.000000000000000000e+00,2.632950588171429906e-01,0.000000000000000000e+00,-1.000000007865643470e+00,0.000000000000000000e+00 +3.092085611863682360e+01,1.792000000000000171e+02,0.000000000000000000e+00,1.096545818834925967e+01,0.000000000000000000e+00,2.623830842430978638e-01,0.000000000000000000e+00,-1.000000010267515282e+00,0.000000000000000000e+00 +3.092176807323354382e+01,1.792100000000000080e+02,0.000000000000000000e+00,1.096569746980903659e+01,0.000000000000000000e+00,2.614711296370149096e-01,0.000000000000000000e+00,-1.000000009183935168e+00,0.000000000000000000e+00 +3.092268000793058746e+01,1.792199999999999989e+02,0.000000000000000000e+00,1.096593591440442772e+01,0.000000000000000000e+00,2.605591949315963496e-01,0.000000000000000000e+00,-1.000000006868482672e+00,0.000000000000000000e+00 +3.092359192279841551e+01,1.792299999999999898e+02,0.000000000000000000e+00,1.096617352220823527e+01,0.000000000000000000e+00,2.596472800575043705e-01,0.000000000000000000e+00,-1.000000009847044291e+00,0.000000000000000000e+00 +3.092450381790747471e+01,1.792400000000000091e+02,0.000000000000000000e+00,1.096641029329300032e+01,0.000000000000000000e+00,2.587353849394653516e-01,0.000000000000000000e+00,-1.000000007555919002e+00,0.000000000000000000e+00 +3.092541569332819762e+01,1.792500000000000000e+02,0.000000000000000000e+00,1.096664622773099751e+01,0.000000000000000000e+00,2.578235095118538989e-01,0.000000000000000000e+00,-1.000000010793004046e+00,0.000000000000000000e+00 +3.092632754913099546e+01,1.792599999999999909e+02,0.000000000000000000e+00,1.096688132559424389e+01,0.000000000000000000e+00,2.569116536992132604e-01,0.000000000000000000e+00,-1.000000006856105905e+00,0.000000000000000000e+00 +3.092723938538627237e+01,1.792700000000000102e+02,0.000000000000000000e+00,1.096711558695449007e+01,0.000000000000000000e+00,2.559998174376843516e-01,0.000000000000000000e+00,-1.000000010816245899e+00,0.000000000000000000e+00 +3.092815120216441471e+01,1.792800000000000011e+02,0.000000000000000000e+00,1.096734901188323086e+01,0.000000000000000000e+00,2.550880006496806240e-01,0.000000000000000000e+00,-1.000000007832878790e+00,0.000000000000000000e+00 +3.092906299953579108e+01,1.792899999999999920e+02,0.000000000000000000e+00,1.096758160045169284e+01,0.000000000000000000e+00,2.541762032711624708e-01,0.000000000000000000e+00,-1.000000008703806342e+00,0.000000000000000000e+00 +3.092997477757075941e+01,1.793000000000000114e+02,0.000000000000000000e+00,1.096781335273084679e+01,0.000000000000000000e+00,2.532644252282595376e-01,0.000000000000000000e+00,-1.000000007133459601e+00,0.000000000000000000e+00 +3.093088653633965990e+01,1.793100000000000023e+02,0.000000000000000000e+00,1.096804426879139882e+01,0.000000000000000000e+00,2.523526664528565333e-01,0.000000000000000000e+00,-1.000000011783141796e+00,0.000000000000000000e+00 +3.093179827591281850e+01,1.793199999999999932e+02,0.000000000000000000e+00,1.096827434870379570e+01,0.000000000000000000e+00,2.514409268689559163e-01,0.000000000000000000e+00,-1.000000005671097592e+00,0.000000000000000000e+00 +3.093270999636054697e+01,1.793300000000000125e+02,0.000000000000000000e+00,1.096850359253821772e+01,0.000000000000000000e+00,2.505292064160578036e-01,0.000000000000000000e+00,-1.000000012417202822e+00,0.000000000000000000e+00 +3.093362169775314285e+01,1.793400000000000034e+02,0.000000000000000000e+00,1.096873200036459295e+01,0.000000000000000000e+00,2.496175050121420547e-01,0.000000000000000000e+00,-1.000000006489416338e+00,0.000000000000000000e+00 +3.093453338016088594e+01,1.793499999999999943e+02,0.000000000000000000e+00,1.096895957225257767e+01,0.000000000000000000e+00,2.487058225984809523e-01,0.000000000000000000e+00,-1.000000007233823096e+00,0.000000000000000000e+00 +3.093544504365404890e+01,1.793600000000000136e+02,0.000000000000000000e+00,1.096918630827157770e+01,0.000000000000000000e+00,2.477941590987234599e-01,0.000000000000000000e+00,-1.000000010488534041e+00,0.000000000000000000e+00 +3.093635668830288310e+01,1.793700000000000045e+02,0.000000000000000000e+00,1.096941220849073240e+01,0.000000000000000000e+00,2.468825144403275496e-01,0.000000000000000000e+00,-1.000000009952738855e+00,0.000000000000000000e+00 +3.093726831417762924e+01,1.793799999999999955e+02,0.000000000000000000e+00,1.096963727297891822e+01,0.000000000000000000e+00,2.459708885565097258e-01,0.000000000000000000e+00,-1.000000007874405572e+00,0.000000000000000000e+00 +3.093817992134851025e+01,1.793900000000000148e+02,0.000000000000000000e+00,1.096986150180475406e+01,0.000000000000000000e+00,2.450592813784513713e-01,0.000000000000000000e+00,-1.000000006501412964e+00,0.000000000000000000e+00 +3.093909150988573487e+01,1.794000000000000057e+02,0.000000000000000000e+00,1.097008489503659945e+01,0.000000000000000000e+00,2.441476928352989406e-01,0.000000000000000000e+00,-1.000000012357316947e+00,0.000000000000000000e+00 +3.094000307985950116e+01,1.794099999999999966e+02,0.000000000000000000e+00,1.097030745274255281e+01,0.000000000000000000e+00,2.432361228502664952e-01,0.000000000000000000e+00,-1.000000006312119938e+00,0.000000000000000000e+00 +3.094091463133999298e+01,1.794200000000000159e+02,0.000000000000000000e+00,1.097052917499044611e+01,0.000000000000000000e+00,2.423245713640206633e-01,0.000000000000000000e+00,-1.000000009852652694e+00,0.000000000000000000e+00 +3.094182616439737643e+01,1.794300000000000068e+02,0.000000000000000000e+00,1.097075006184786083e+01,0.000000000000000000e+00,2.414130382976555911e-01,0.000000000000000000e+00,-1.000000008122881479e+00,0.000000000000000000e+00 +3.094273767910180695e+01,1.794399999999999977e+02,0.000000000000000000e+00,1.097097011338211026e+01,0.000000000000000000e+00,2.405015235858215250e-01,0.000000000000000000e+00,-1.000000007644791244e+00,0.000000000000000000e+00 +3.094364917552342220e+01,1.794500000000000171e+02,0.000000000000000000e+00,1.097118932966025184e+01,0.000000000000000000e+00,2.395900271572376783e-01,0.000000000000000000e+00,-1.000000010664542804e+00,0.000000000000000000e+00 +3.094456065373234921e+01,1.794600000000000080e+02,0.000000000000000000e+00,1.097140771074908194e+01,0.000000000000000000e+00,2.386785489385899739e-01,0.000000000000000000e+00,-1.000000006598838365e+00,0.000000000000000000e+00 +3.094547211379870078e+01,1.794699999999999989e+02,0.000000000000000000e+00,1.097162525671513400e+01,0.000000000000000000e+00,2.377670888662246906e-01,0.000000000000000000e+00,-1.000000010522195337e+00,0.000000000000000000e+00 +3.094638355579257194e+01,1.794799999999999898e+02,0.000000000000000000e+00,1.097184196762468744e+01,0.000000000000000000e+00,2.368556468627620315e-01,0.000000000000000000e+00,-1.000000007573220273e+00,0.000000000000000000e+00 +3.094729497978405064e+01,1.794900000000000091e+02,0.000000000000000000e+00,1.097205784354375524e+01,0.000000000000000000e+00,2.359442228643814643e-01,0.000000000000000000e+00,-1.000000010688316676e+00,0.000000000000000000e+00 +3.094820638584320349e+01,1.795000000000000000e+02,0.000000000000000000e+00,1.097227288453809635e+01,0.000000000000000000e+00,2.350328167954855163e-01,0.000000000000000000e+00,-1.000000007142421765e+00,0.000000000000000000e+00 +3.094911777404009001e+01,1.795099999999999909e+02,0.000000000000000000e+00,1.097248709067320505e+01,0.000000000000000000e+00,2.341214285920882043e-01,0.000000000000000000e+00,-1.000000007733318874e+00,0.000000000000000000e+00 +3.095002914444475550e+01,1.795200000000000102e+02,0.000000000000000000e+00,1.097270046201432159e+01,0.000000000000000000e+00,2.332100581803760453e-01,0.000000000000000000e+00,-1.000000010427847474e+00,0.000000000000000000e+00 +3.095094049712722750e+01,1.795300000000000011e+02,0.000000000000000000e+00,1.097291299862642333e+01,0.000000000000000000e+00,2.322987054884022851e-01,0.000000000000000000e+00,-1.000000008914083027e+00,0.000000000000000000e+00 +3.095185183215751934e+01,1.795399999999999920e+02,0.000000000000000000e+00,1.097312470057422651e+01,0.000000000000000000e+00,2.313873704499860851e-01,0.000000000000000000e+00,-1.000000007573331517e+00,0.000000000000000000e+00 +3.095276314960563724e+01,1.795500000000000114e+02,0.000000000000000000e+00,1.097333556792219156e+01,0.000000000000000000e+00,2.304760529949670955e-01,0.000000000000000000e+00,-1.000000008648294747e+00,0.000000000000000000e+00 +3.095367444954156966e+01,1.795600000000000023e+02,0.000000000000000000e+00,1.097354560073451957e+01,0.000000000000000000e+00,2.295647530511546186e-01,0.000000000000000000e+00,-1.000000007964255921e+00,0.000000000000000000e+00 +3.095458573203529085e+01,1.795699999999999932e+02,0.000000000000000000e+00,1.097375479907515050e+01,0.000000000000000000e+00,2.286534705501757914e-01,0.000000000000000000e+00,-1.000000009902126008e+00,0.000000000000000000e+00 +3.095549699715676439e+01,1.795800000000000125e+02,0.000000000000000000e+00,1.097396316300776675e+01,0.000000000000000000e+00,2.277422054196787948e-01,0.000000000000000000e+00,-1.000000010286004937e+00,0.000000000000000000e+00 +3.095640824497593968e+01,1.795900000000000034e+02,0.000000000000000000e+00,1.097417069259578959e+01,0.000000000000000000e+00,2.268309575911304776e-01,0.000000000000000000e+00,-1.000000004938854881e+00,0.000000000000000000e+00 +3.095731947556275188e+01,1.795999999999999943e+02,0.000000000000000000e+00,1.097437738790238271e+01,0.000000000000000000e+00,2.259197269998170499e-01,0.000000000000000000e+00,-1.000000011076764617e+00,0.000000000000000000e+00 +3.095823068898712549e+01,1.796100000000000136e+02,0.000000000000000000e+00,1.097458324899045579e+01,0.000000000000000000e+00,2.250085135653500379e-01,0.000000000000000000e+00,-1.000000009546871738e+00,0.000000000000000000e+00 +3.095914188531897082e+01,1.796200000000000045e+02,0.000000000000000000e+00,1.097478827592265027e+01,0.000000000000000000e+00,2.240973172248066636e-01,0.000000000000000000e+00,-1.000000006867419300e+00,0.000000000000000000e+00 +3.096005306462818396e+01,1.796299999999999955e+02,0.000000000000000000e+00,1.097499246876135537e+01,0.000000000000000000e+00,2.231861379093375009e-01,0.000000000000000000e+00,-1.000000007417751968e+00,0.000000000000000000e+00 +3.096096422698464679e+01,1.796400000000000148e+02,0.000000000000000000e+00,1.097519582756870271e+01,0.000000000000000000e+00,2.222749755461157495e-01,0.000000000000000000e+00,-1.000000011298107117e+00,0.000000000000000000e+00 +3.096187537245823052e+01,1.796500000000000057e+02,0.000000000000000000e+00,1.097539835240656281e+01,0.000000000000000000e+00,2.213638300622363664e-01,0.000000000000000000e+00,-1.000000007909110034e+00,0.000000000000000000e+00 +3.096278650111879571e+01,1.796599999999999966e+02,0.000000000000000000e+00,1.097560004333654504e+01,0.000000000000000000e+00,2.204527013944647396e-01,0.000000000000000000e+00,-1.000000008048195665e+00,0.000000000000000000e+00 +3.096369761303618517e+01,1.796700000000000159e+02,0.000000000000000000e+00,1.097580090042000656e+01,0.000000000000000000e+00,2.195415894697410331e-01,0.000000000000000000e+00,-1.000000009674373080e+00,0.000000000000000000e+00 +3.096460870828023459e+01,1.796800000000000068e+02,0.000000000000000000e+00,1.097600092371804337e+01,0.000000000000000000e+00,2.186304942168778853e-01,0.000000000000000000e+00,-1.000000006465626923e+00,0.000000000000000000e+00 +3.096551978692076190e+01,1.796899999999999977e+02,0.000000000000000000e+00,1.097620011329149214e+01,0.000000000000000000e+00,2.177194155704605671e-01,0.000000000000000000e+00,-1.000000011359808205e+00,0.000000000000000000e+00 +3.096643084902757437e+01,1.797000000000000171e+02,0.000000000000000000e+00,1.097639846920093554e+01,0.000000000000000000e+00,2.168083534532995738e-01,0.000000000000000000e+00,-1.000000007333556207e+00,0.000000000000000000e+00 +3.096734189467046505e+01,1.797100000000000080e+02,0.000000000000000000e+00,1.097659599150669152e+01,0.000000000000000000e+00,2.158973078037274562e-01,0.000000000000000000e+00,-1.000000007324057583e+00,0.000000000000000000e+00 +3.096825292391921636e+01,1.797199999999999989e+02,0.000000000000000000e+00,1.097679268026882760e+01,0.000000000000000000e+00,2.149862785483027117e-01,0.000000000000000000e+00,-1.000000009287910219e+00,0.000000000000000000e+00 +3.096916393684360003e+01,1.797299999999999898e+02,0.000000000000000000e+00,1.097698853554715015e+01,0.000000000000000000e+00,2.140752656154580880e-01,0.000000000000000000e+00,-1.000000011180894655e+00,0.000000000000000000e+00 +3.097007493351337004e+01,1.797400000000000091e+02,0.000000000000000000e+00,1.097718355740120622e+01,0.000000000000000000e+00,2.131642689355011389e-01,0.000000000000000000e+00,-1.000000004536368392e+00,0.000000000000000000e+00 +3.097098591399827328e+01,1.797500000000000000e+02,0.000000000000000000e+00,1.097737774589028525e+01,0.000000000000000000e+00,2.122532884464647385e-01,0.000000000000000000e+00,-1.000000010854200205e+00,0.000000000000000000e+00 +3.097189687836804239e+01,1.797599999999999909e+02,0.000000000000000000e+00,1.097757110107342626e+01,0.000000000000000000e+00,2.113423240668080572e-01,0.000000000000000000e+00,-1.000000008824107889e+00,0.000000000000000000e+00 +3.097280782669239585e+01,1.797700000000000102e+02,0.000000000000000000e+00,1.097776362300940001e+01,0.000000000000000000e+00,2.104313757344157265e-01,0.000000000000000000e+00,-1.000000009243008359e+00,0.000000000000000000e+00 +3.097371875904104144e+01,1.797800000000000011e+02,0.000000000000000000e+00,1.097795531175672679e+01,0.000000000000000000e+00,2.095204433773489305e-01,0.000000000000000000e+00,-1.000000007923214751e+00,0.000000000000000000e+00 +3.097462967548367629e+01,1.797899999999999920e+02,0.000000000000000000e+00,1.097814616737366755e+01,0.000000000000000000e+00,2.086095269274957642e-01,0.000000000000000000e+00,-1.000000007098889698e+00,0.000000000000000000e+00 +3.097554057608998335e+01,1.798000000000000114e+02,0.000000000000000000e+00,1.097833618991822746e+01,0.000000000000000000e+00,2.076986263147212464e-01,0.000000000000000000e+00,-1.000000009004078816e+00,0.000000000000000000e+00 +3.097645146092963486e+01,1.798100000000000023e+02,0.000000000000000000e+00,1.097852537944815410e+01,0.000000000000000000e+00,2.067877414668675140e-01,0.000000000000000000e+00,-1.000000009449492522e+00,0.000000000000000000e+00 +3.097736233007228890e+01,1.798199999999999932e+02,0.000000000000000000e+00,1.097871373602093570e+01,0.000000000000000000e+00,2.058768723156047253e-01,0.000000000000000000e+00,-1.000000008527121009e+00,0.000000000000000000e+00 +3.097827318358759641e+01,1.798300000000000125e+02,0.000000000000000000e+00,1.097890125969380470e+01,0.000000000000000000e+00,2.049660187925311239e-01,0.000000000000000000e+00,-1.000000008469630997e+00,0.000000000000000000e+00 +3.097918402154519057e+01,1.798400000000000034e+02,0.000000000000000000e+00,1.097908795052373776e+01,0.000000000000000000e+00,2.040551808272231815e-01,0.000000000000000000e+00,-1.000000009368468445e+00,0.000000000000000000e+00 +3.098009484401469393e+01,1.798499999999999943e+02,0.000000000000000000e+00,1.097927380856745394e+01,0.000000000000000000e+00,2.031443583491859550e-01,0.000000000000000000e+00,-1.000000007031838445e+00,0.000000000000000000e+00 +3.098100565106572191e+01,1.798600000000000136e+02,0.000000000000000000e+00,1.097945883388141475e+01,0.000000000000000000e+00,2.022335512917542433e-01,0.000000000000000000e+00,-1.000000007974045868e+00,0.000000000000000000e+00 +3.098191644276787216e+01,1.798700000000000045e+02,0.000000000000000000e+00,1.097964302652182766e+01,0.000000000000000000e+00,2.013227595823412486e-01,0.000000000000000000e+00,-1.000000010144087348e+00,0.000000000000000000e+00 +3.098282721919073524e+01,1.798799999999999955e+02,0.000000000000000000e+00,1.097982638654464083e+01,0.000000000000000000e+00,2.004119831502400029e-01,0.000000000000000000e+00,-1.000000009348541941e+00,0.000000000000000000e+00 +3.098373798040388749e+01,1.798900000000000148e+02,0.000000000000000000e+00,1.098000891400554480e+01,0.000000000000000000e+00,1.995012219285744182e-01,0.000000000000000000e+00,-1.000000005676179526e+00,0.000000000000000000e+00 +3.098464872647689461e+01,1.799000000000000057e+02,0.000000000000000000e+00,1.098019060895997612e+01,0.000000000000000000e+00,1.985904758503989898e-01,0.000000000000000000e+00,-1.000000012065590527e+00,0.000000000000000000e+00 +3.098555945747930807e+01,1.799099999999999966e+02,0.000000000000000000e+00,1.098037147146311732e+01,0.000000000000000000e+00,1.976797448369960186e-01,0.000000000000000000e+00,-1.000000005047013918e+00,0.000000000000000000e+00 +3.098647017348067223e+01,1.799200000000000159e+02,0.000000000000000000e+00,1.098055150156988624e+01,0.000000000000000000e+00,1.967690288310340041e-01,0.000000000000000000e+00,-1.000000010408605089e+00,0.000000000000000000e+00 +3.098738087455052082e+01,1.799300000000000068e+02,0.000000000000000000e+00,1.098073069933495560e+01,0.000000000000000000e+00,1.958583277517069454e-01,0.000000000000000000e+00,-1.000000008962271369e+00,0.000000000000000000e+00 +3.098829156075836977e+01,1.799399999999999977e+02,0.000000000000000000e+00,1.098090906481273166e+01,0.000000000000000000e+00,1.949476415356950765e-01,0.000000000000000000e+00,-1.000000007220217979e+00,0.000000000000000000e+00 +3.098920223217373149e+01,1.799500000000000171e+02,0.000000000000000000e+00,1.098108659805737020e+01,0.000000000000000000e+00,1.940369701137591441e-01,0.000000000000000000e+00,-1.000000009553098756e+00,0.000000000000000000e+00 +3.099011288886610060e+01,1.799600000000000080e+02,0.000000000000000000e+00,1.098126329912277122e+01,0.000000000000000000e+00,1.931263134126909586e-01,0.000000000000000000e+00,-1.000000007479168174e+00,0.000000000000000000e+00 +3.099102353090496464e+01,1.799699999999999989e+02,0.000000000000000000e+00,1.098143916806257536e+01,0.000000000000000000e+00,1.922156713670175321e-01,0.000000000000000000e+00,-1.000000009652539212e+00,0.000000000000000000e+00 +3.099193415835979692e+01,1.799799999999999898e+02,0.000000000000000000e+00,1.098161420493017104e+01,0.000000000000000000e+00,1.913050439033961436e-01,0.000000000000000000e+00,-1.000000007590017281e+00,0.000000000000000000e+00 +3.099284477130006010e+01,1.799900000000000091e+02,0.000000000000000000e+00,1.098178840977868731e+01,0.000000000000000000e+00,1.903944309562202453e-01,0.000000000000000000e+00,-1.000000007803066859e+00,0.000000000000000000e+00 +3.099375536979520973e+01,1.800000000000000000e+02,0.000000000000000000e+00,1.098196178266100098e+01,0.000000000000000000e+00,1.894838324539648011e-01,0.000000000000000000e+00,-1.000000010376513204e+00,0.000000000000000000e+00 +3.099466595391468715e+01,1.800099999999999909e+02,0.000000000000000000e+00,1.098213432362973130e+01,0.000000000000000000e+00,1.885732483250386060e-01,0.000000000000000000e+00,-1.000000006824996346e+00,0.000000000000000000e+00 +3.099557652372792305e+01,1.800200000000000102e+02,0.000000000000000000e+00,1.098230603273723993e+01,0.000000000000000000e+00,1.876626785055879876e-01,0.000000000000000000e+00,-1.000000010086580460e+00,0.000000000000000000e+00 +3.099648707930433744e+01,1.800300000000000011e+02,0.000000000000000000e+00,1.098247691003563808e+01,0.000000000000000000e+00,1.867521229199890498e-01,0.000000000000000000e+00,-1.000000007389891366e+00,0.000000000000000000e+00 +3.099739762071333971e+01,1.800399999999999920e+02,0.000000000000000000e+00,1.098264695557677584e+01,0.000000000000000000e+00,1.858415815042578634e-01,0.000000000000000000e+00,-1.000000007387748191e+00,0.000000000000000000e+00 +3.099830814802432855e+01,1.800500000000000114e+02,0.000000000000000000e+00,1.098281616941225280e+01,0.000000000000000000e+00,1.849310541865423763e-01,0.000000000000000000e+00,-1.000000010162875430e+00,0.000000000000000000e+00 +3.099921866130669201e+01,1.800600000000000023e+02,0.000000000000000000e+00,1.098298455159341103e+01,0.000000000000000000e+00,1.840205408949260324e-01,0.000000000000000000e+00,-1.000000007226570009e+00,0.000000000000000000e+00 +3.100012916062980750e+01,1.800699999999999932e+02,0.000000000000000000e+00,1.098315210217133497e+01,0.000000000000000000e+00,1.831100415652320013e-01,0.000000000000000000e+00,-1.000000009374115262e+00,0.000000000000000000e+00 +3.100103964606303819e+01,1.800800000000000125e+02,0.000000000000000000e+00,1.098331882119685865e+01,0.000000000000000000e+00,1.821995561234648620e-01,0.000000000000000000e+00,-1.000000008115500050e+00,0.000000000000000000e+00 +3.100195011767574371e+01,1.800900000000000034e+02,0.000000000000000000e+00,1.098348470872055671e+01,0.000000000000000000e+00,1.812890845033698628e-01,0.000000000000000000e+00,-1.000000007817250181e+00,0.000000000000000000e+00 +3.100286057553726948e+01,1.800999999999999943e+02,0.000000000000000000e+00,1.098364976479275157e+01,0.000000000000000000e+00,1.803786266347270628e-01,0.000000000000000000e+00,-1.000000008559800868e+00,0.000000000000000000e+00 +3.100377101971695026e+01,1.801100000000000136e+02,0.000000000000000000e+00,1.098381398946350984e+01,0.000000000000000000e+00,1.794681824472537657e-01,0.000000000000000000e+00,-1.000000010423257590e+00,0.000000000000000000e+00 +3.100468145028411016e+01,1.801200000000000045e+02,0.000000000000000000e+00,1.098397738278264235e+01,0.000000000000000000e+00,1.785577518706047695e-01,0.000000000000000000e+00,-1.000000007057821438e+00,0.000000000000000000e+00 +3.100559186730806260e+01,1.801299999999999955e+02,0.000000000000000000e+00,1.098413994479970412e+01,0.000000000000000000e+00,1.776473348402262120e-01,0.000000000000000000e+00,-1.000000007114929756e+00,0.000000000000000000e+00 +3.100650227085811395e+01,1.801400000000000148e+02,0.000000000000000000e+00,1.098430167556399972e+01,0.000000000000000000e+00,1.767369312836979955e-01,0.000000000000000000e+00,-1.000000010673767870e+00,0.000000000000000000e+00 +3.100741266100355631e+01,1.801500000000000057e+02,0.000000000000000000e+00,1.098446257512457613e+01,0.000000000000000000e+00,1.758265411285382940e-01,0.000000000000000000e+00,-1.000000007096167876e+00,0.000000000000000000e+00 +3.100832303781367472e+01,1.801599999999999966e+02,0.000000000000000000e+00,1.098462264353022277e+01,0.000000000000000000e+00,1.749161643119603315e-01,0.000000000000000000e+00,-1.000000007176449879e+00,0.000000000000000000e+00 +3.100923340135773998e+01,1.801700000000000159e+02,0.000000000000000000e+00,1.098478188082948037e+01,0.000000000000000000e+00,1.740058007613604074e-01,0.000000000000000000e+00,-1.000000010992384114e+00,0.000000000000000000e+00 +3.101014375170501935e+01,1.801800000000000068e+02,0.000000000000000000e+00,1.098494028707063208e+01,0.000000000000000000e+00,1.730954504040742303e-01,0.000000000000000000e+00,-1.000000005760278032e+00,0.000000000000000000e+00 +3.101105408892476589e+01,1.801899999999999977e+02,0.000000000000000000e+00,1.098509786230170349e+01,0.000000000000000000e+00,1.721851131790851364e-01,0.000000000000000000e+00,-1.000000010848206111e+00,0.000000000000000000e+00 +3.101196441308622198e+01,1.802000000000000171e+02,0.000000000000000000e+00,1.098525460657047326e+01,0.000000000000000000e+00,1.712747890077548352e-01,0.000000000000000000e+00,-1.000000007040639627e+00,0.000000000000000000e+00 +3.101287472425861935e+01,1.802100000000000080e+02,0.000000000000000000e+00,1.098541051992445716e+01,0.000000000000000000e+00,1.703644778289474526e-01,0.000000000000000000e+00,-1.000000007274585156e+00,0.000000000000000000e+00 +3.101378502251118618e+01,1.802199999999999989e+02,0.000000000000000000e+00,1.098556560241092406e+01,0.000000000000000000e+00,1.694541795697600828e-01,0.000000000000000000e+00,-1.000000009482369556e+00,0.000000000000000000e+00 +3.101469530791313289e+01,1.802299999999999898e+02,0.000000000000000000e+00,1.098571985407688523e+01,0.000000000000000000e+00,1.685438941591819451e-01,0.000000000000000000e+00,-1.000000009451309069e+00,0.000000000000000000e+00 +3.101560558053366634e+01,1.802400000000000091e+02,0.000000000000000000e+00,1.098587327496909616e+01,0.000000000000000000e+00,1.676336215300467669e-01,0.000000000000000000e+00,-1.000000007255956724e+00,0.000000000000000000e+00 +3.101651584044197918e+01,1.802500000000000000e+02,0.000000000000000000e+00,1.098602586513406010e+01,0.000000000000000000e+00,1.667233616151300168e-01,0.000000000000000000e+00,-1.000000007257974444e+00,0.000000000000000000e+00 +3.101742608770725695e+01,1.802599999999999909e+02,0.000000000000000000e+00,1.098617762461802805e+01,0.000000000000000000e+00,1.658131143432465260e-01,0.000000000000000000e+00,-1.000000009531498479e+00,0.000000000000000000e+00 +3.101833632239867455e+01,1.802700000000000102e+02,0.000000000000000000e+00,1.098632855346699522e+01,0.000000000000000000e+00,1.649028796431533106e-01,0.000000000000000000e+00,-1.000000007717887884e+00,0.000000000000000000e+00 +3.101924654458539976e+01,1.802800000000000011e+02,0.000000000000000000e+00,1.098647865172670102e+01,0.000000000000000000e+00,1.639926574494047773e-01,0.000000000000000000e+00,-1.000000008322005307e+00,0.000000000000000000e+00 +3.102015675433658615e+01,1.802899999999999920e+02,0.000000000000000000e+00,1.098662791944263439e+01,0.000000000000000000e+00,1.630824476906438669e-01,0.000000000000000000e+00,-1.000000009272475898e+00,0.000000000000000000e+00 +3.102106695172138018e+01,1.803000000000000114e+02,0.000000000000000000e+00,1.098677635666002850e+01,0.000000000000000000e+00,1.621722502974083935e-01,0.000000000000000000e+00,-1.000000008497204940e+00,0.000000000000000000e+00 +3.102197713680892477e+01,1.803100000000000023e+02,0.000000000000000000e+00,1.098692396342386246e+01,0.000000000000000000e+00,1.612620652021315437e-01,0.000000000000000000e+00,-1.000000006067714553e+00,0.000000000000000000e+00 +3.102288730966834152e+01,1.803199999999999932e+02,0.000000000000000000e+00,1.098707073977886317e+01,0.000000000000000000e+00,1.603518923371906602e-01,0.000000000000000000e+00,-1.000000010632536185e+00,0.000000000000000000e+00 +3.102379747036875557e+01,1.803300000000000125e+02,0.000000000000000000e+00,1.098721668576950528e+01,0.000000000000000000e+00,1.594417316271007357e-01,0.000000000000000000e+00,-1.000000007252399792e+00,0.000000000000000000e+00 +3.102470761897927076e+01,1.803400000000000034e+02,0.000000000000000000e+00,1.098736180144000407e+01,0.000000000000000000e+00,1.585315830099831846e-01,0.000000000000000000e+00,-1.000000006719358181e+00,0.000000000000000000e+00 +3.102561775556899093e+01,1.803499999999999943e+02,0.000000000000000000e+00,1.098750608683432795e+01,0.000000000000000000e+00,1.576214464141460492e-01,0.000000000000000000e+00,-1.000000011248239451e+00,0.000000000000000000e+00 +3.102652788020700925e+01,1.803600000000000136e+02,0.000000000000000000e+00,1.098764954199618948e+01,0.000000000000000000e+00,1.567113217658908098e-01,0.000000000000000000e+00,-1.000000005897099031e+00,0.000000000000000000e+00 +3.102743799296240468e+01,1.803700000000000045e+02,0.000000000000000000e+00,1.098779216696904371e+01,0.000000000000000000e+00,1.558012090051270337e-01,0.000000000000000000e+00,-1.000000010036007803e+00,0.000000000000000000e+00 +3.102834809390425264e+01,1.803799999999999955e+02,0.000000000000000000e+00,1.098793396179610049e+01,0.000000000000000000e+00,1.548911080541442165e-01,0.000000000000000000e+00,-1.000000006577117961e+00,0.000000000000000000e+00 +3.102925818310161787e+01,1.803900000000000148e+02,0.000000000000000000e+00,1.098807492652030859e+01,0.000000000000000000e+00,1.539810188507926003e-01,0.000000000000000000e+00,-1.000000008456652489e+00,0.000000000000000000e+00 +3.103016826062355449e+01,1.804000000000000057e+02,0.000000000000000000e+00,1.098821506118436986e+01,0.000000000000000000e+00,1.530709413211580883e-01,0.000000000000000000e+00,-1.000000009308743110e+00,0.000000000000000000e+00 +3.103107832653911302e+01,1.804099999999999966e+02,0.000000000000000000e+00,1.098835436583072855e+01,0.000000000000000000e+00,1.521608753971289696e-01,0.000000000000000000e+00,-1.000000007055881213e+00,0.000000000000000000e+00 +3.103198838091732625e+01,1.804200000000000159e+02,0.000000000000000000e+00,1.098849284050157671e+01,0.000000000000000000e+00,1.512508210124929309e-01,0.000000000000000000e+00,-1.000000008199940948e+00,0.000000000000000000e+00 +3.103289842382722696e+01,1.804300000000000068e+02,0.000000000000000000e+00,1.098863048523885588e+01,0.000000000000000000e+00,1.503407780951293016e-01,0.000000000000000000e+00,-1.000000008517889283e+00,0.000000000000000000e+00 +3.103380845533783372e+01,1.804399999999999977e+02,0.000000000000000000e+00,1.098876730008425184e+01,0.000000000000000000e+00,1.494307465767693022e-01,0.000000000000000000e+00,-1.000000008076120661e+00,0.000000000000000000e+00 +3.103471847551816154e+01,1.804500000000000171e+02,0.000000000000000000e+00,1.098890328507919811e+01,0.000000000000000000e+00,1.485207263890923335e-01,0.000000000000000000e+00,-1.000000009085544761e+00,0.000000000000000000e+00 +3.103562848443721123e+01,1.804600000000000080e+02,0.000000000000000000e+00,1.098903844026487597e+01,0.000000000000000000e+00,1.476107174617743989e-01,0.000000000000000000e+00,-1.000000007321686590e+00,0.000000000000000000e+00 +3.103653848216398004e+01,1.804699999999999989e+02,0.000000000000000000e+00,1.098917276568221268e+01,0.000000000000000000e+00,1.467007197283443365e-01,0.000000000000000000e+00,-1.000000007139637326e+00,0.000000000000000000e+00 +3.103744846876745100e+01,1.804799999999999898e+02,0.000000000000000000e+00,1.098930626137188504e+01,0.000000000000000000e+00,1.457907331183762867e-01,0.000000000000000000e+00,-1.000000008604493340e+00,0.000000000000000000e+00 +3.103835844431660362e+01,1.804900000000000091e+02,0.000000000000000000e+00,1.098943892737431582e+01,0.000000000000000000e+00,1.448807575613936249e-01,0.000000000000000000e+00,-1.000000009635247045e+00,0.000000000000000000e+00 +3.103926840888040672e+01,1.805000000000000000e+02,0.000000000000000000e+00,1.098957076372967379e+01,0.000000000000000000e+00,1.439707929888217885e-01,0.000000000000000000e+00,-1.000000006005239195e+00,0.000000000000000000e+00 +3.104017836252782203e+01,1.805099999999999909e+02,0.000000000000000000e+00,1.098970177047787544e+01,0.000000000000000000e+00,1.430608393359405761e-01,0.000000000000000000e+00,-1.000000010649811477e+00,0.000000000000000000e+00 +3.104108830532780416e+01,1.805200000000000102e+02,0.000000000000000000e+00,1.098983194765858862e+01,0.000000000000000000e+00,1.421508965262674729e-01,0.000000000000000000e+00,-1.000000006469317082e+00,0.000000000000000000e+00 +3.104199823734929709e+01,1.805300000000000011e+02,0.000000000000000000e+00,1.098996129531122179e+01,0.000000000000000000e+00,1.412409644988879553e-01,0.000000000000000000e+00,-1.000000006398591879e+00,0.000000000000000000e+00 +3.104290815866123765e+01,1.805399999999999920e+02,0.000000000000000000e+00,1.099008981347493830e+01,0.000000000000000000e+00,1.403310431811256864e-01,0.000000000000000000e+00,-1.000000010500371017e+00,0.000000000000000000e+00 +3.104381806933255206e+01,1.805500000000000114e+02,0.000000000000000000e+00,1.099021750218864568e+01,0.000000000000000000e+00,1.394211325002554791e-01,0.000000000000000000e+00,-1.000000008108838490e+00,0.000000000000000000e+00 +3.104472796943216295e+01,1.805600000000000023e+02,0.000000000000000000e+00,1.099034436149099569e+01,0.000000000000000000e+00,1.385112323932651546e-01,0.000000000000000000e+00,-1.000000007867509311e+00,0.000000000000000000e+00 +3.104563785902898232e+01,1.805699999999999932e+02,0.000000000000000000e+00,1.099047039142039317e+01,0.000000000000000000e+00,1.376013427892856800e-01,0.000000000000000000e+00,-1.000000005546257453e+00,0.000000000000000000e+00 +3.104654773819191504e+01,1.805800000000000125e+02,0.000000000000000000e+00,1.099059559201498892e+01,0.000000000000000000e+00,1.366914636213049372e-01,0.000000000000000000e+00,-1.000000009788499566e+00,0.000000000000000000e+00 +3.104745760698985890e+01,1.805900000000000034e+02,0.000000000000000000e+00,1.099071996331268330e+01,0.000000000000000000e+00,1.357815948144542595e-01,0.000000000000000000e+00,-1.000000009926192313e+00,0.000000000000000000e+00 +3.104836746549170101e+01,1.805999999999999943e+02,0.000000000000000000e+00,1.099084350535111909e+01,0.000000000000000000e+00,1.348717363035794314e-01,0.000000000000000000e+00,-1.000000006018697540e+00,0.000000000000000000e+00 +3.104927731376632494e+01,1.806100000000000136e+02,0.000000000000000000e+00,1.099096621816769037e+01,0.000000000000000000e+00,1.339618880234798859e-01,0.000000000000000000e+00,-1.000000006708753553e+00,0.000000000000000000e+00 +3.105018715188260003e+01,1.806200000000000045e+02,0.000000000000000000e+00,1.099108810179954254e+01,0.000000000000000000e+00,1.330520499010991731e-01,0.000000000000000000e+00,-1.000000009909776555e+00,0.000000000000000000e+00 +3.105109697990939566e+01,1.806299999999999955e+02,0.000000000000000000e+00,1.099120915628356521e+01,0.000000000000000000e+00,1.321422218652870961e-01,0.000000000000000000e+00,-1.000000007096768506e+00,0.000000000000000000e+00 +3.105200679791556695e+01,1.806400000000000148e+02,0.000000000000000000e+00,1.099132938165639395e+01,0.000000000000000000e+00,1.312324038526573589e-01,0.000000000000000000e+00,-1.000000009057498751e+00,0.000000000000000000e+00 +3.105291660596996905e+01,1.806500000000000057e+02,0.000000000000000000e+00,1.099144877795441744e+01,0.000000000000000000e+00,1.303225957900162602e-01,0.000000000000000000e+00,-1.000000007265948732e+00,0.000000000000000000e+00 +3.105382640414143935e+01,1.806599999999999966e+02,0.000000000000000000e+00,1.099156734521376855e+01,0.000000000000000000e+00,1.294127976119347212e-01,0.000000000000000000e+00,-1.000000008217522884e+00,0.000000000000000000e+00 +3.105473619249881523e+01,1.806700000000000159e+02,0.000000000000000000e+00,1.099168508347033146e+01,0.000000000000000000e+00,1.285030092470815788e-01,0.000000000000000000e+00,-1.000000007677129599e+00,0.000000000000000000e+00 +3.105564597111092695e+01,1.806800000000000068e+02,0.000000000000000000e+00,1.099180199275973635e+01,0.000000000000000000e+00,1.275932306279861650e-01,0.000000000000000000e+00,-1.000000007847467787e+00,0.000000000000000000e+00 +3.105655574004659414e+01,1.806899999999999977e+02,0.000000000000000000e+00,1.099191807311736291e+01,0.000000000000000000e+00,1.266834616851811868e-01,0.000000000000000000e+00,-1.000000006638576799e+00,0.000000000000000000e+00 +3.105746549937462930e+01,1.807000000000000171e+02,0.000000000000000000e+00,1.099203332457833859e+01,0.000000000000000000e+00,1.257737023511080465e-01,0.000000000000000000e+00,-1.000000010544932483e+00,0.000000000000000000e+00 +3.105837524916383785e+01,1.807100000000000080e+02,0.000000000000000000e+00,1.099214774717754040e+01,0.000000000000000000e+00,1.248639525523070198e-01,0.000000000000000000e+00,-1.000000004597996206e+00,0.000000000000000000e+00 +3.105928498948301808e+01,1.807199999999999989e+02,0.000000000000000000e+00,1.099226134094958951e+01,0.000000000000000000e+00,1.239542122289432197e-01,0.000000000000000000e+00,-1.000000010315793553e+00,0.000000000000000000e+00 +3.106019472040096474e+01,1.807299999999999898e+02,0.000000000000000000e+00,1.099237410592886377e+01,0.000000000000000000e+00,1.230444813016130234e-01,0.000000000000000000e+00,-1.000000006289580190e+00,0.000000000000000000e+00 +3.106110444198645837e+01,1.807400000000000091e+02,0.000000000000000000e+00,1.099248604214947989e+01,0.000000000000000000e+00,1.221347597103962374e-01,0.000000000000000000e+00,-1.000000009744413720e+00,0.000000000000000000e+00 +3.106201415430827950e+01,1.807500000000000000e+02,0.000000000000000000e+00,1.099259714964531121e+01,0.000000000000000000e+00,1.212250473797095995e-01,0.000000000000000000e+00,-1.000000005709181572e+00,0.000000000000000000e+00 +3.106292385743519802e+01,1.807599999999999909e+02,0.000000000000000000e+00,1.099270742844997351e+01,0.000000000000000000e+00,1.203153442475963231e-01,0.000000000000000000e+00,-1.000000009262453693e+00,0.000000000000000000e+00 +3.106383355143598024e+01,1.807700000000000102e+02,0.000000000000000000e+00,1.099281687859683743e+01,0.000000000000000000e+00,1.194056502383894769e-01,0.000000000000000000e+00,-1.000000007578219829e+00,0.000000000000000000e+00 +3.106474323637937829e+01,1.807800000000000011e+02,0.000000000000000000e+00,1.099292550011901604e+01,0.000000000000000000e+00,1.184959652880968606e-01,0.000000000000000000e+00,-1.000000007148545311e+00,0.000000000000000000e+00 +3.106565291233414428e+01,1.807899999999999920e+02,0.000000000000000000e+00,1.099303329304937549e+01,0.000000000000000000e+00,1.175862893268272980e-01,0.000000000000000000e+00,-1.000000008025677678e+00,0.000000000000000000e+00 +3.106656257936902321e+01,1.808000000000000114e+02,0.000000000000000000e+00,1.099314025742052969e+01,0.000000000000000000e+00,1.166766222846489093e-01,0.000000000000000000e+00,-1.000000008114717787e+00,0.000000000000000000e+00 +3.106747223755274945e+01,1.808100000000000023e+02,0.000000000000000000e+00,1.099324639326484032e+01,0.000000000000000000e+00,1.157669640935422295e-01,0.000000000000000000e+00,-1.000000007466960827e+00,0.000000000000000000e+00 +3.106838188695405023e+01,1.808199999999999932e+02,0.000000000000000000e+00,1.099335170061441858e+01,0.000000000000000000e+00,1.148573146854477978e-01,0.000000000000000000e+00,-1.000000008280076180e+00,0.000000000000000000e+00 +3.106929152764165281e+01,1.808300000000000125e+02,0.000000000000000000e+00,1.099345617950112519e+01,0.000000000000000000e+00,1.139476739903136776e-01,0.000000000000000000e+00,-1.000000006311036582e+00,0.000000000000000000e+00 +3.107020115968427021e+01,1.808400000000000034e+02,0.000000000000000000e+00,1.099355982995656866e+01,0.000000000000000000e+00,1.130380419419541455e-01,0.000000000000000000e+00,-1.000000008050382361e+00,0.000000000000000000e+00 +3.107111078315061548e+01,1.808499999999999943e+02,0.000000000000000000e+00,1.099366265201210879e+01,0.000000000000000000e+00,1.121284184682859869e-01,0.000000000000000000e+00,-1.000000007107381128e+00,0.000000000000000000e+00 +3.107202039810939098e+01,1.808600000000000136e+02,0.000000000000000000e+00,1.099376464569885137e+01,0.000000000000000000e+00,1.112188035030456656e-01,0.000000000000000000e+00,-1.000000009972003667e+00,0.000000000000000000e+00 +3.107293000462929200e+01,1.808700000000000045e+02,0.000000000000000000e+00,1.099386581104765348e+01,0.000000000000000000e+00,1.103091969740726819e-01,0.000000000000000000e+00,-1.000000005958470162e+00,0.000000000000000000e+00 +3.107383960277901380e+01,1.808799999999999955e+02,0.000000000000000000e+00,1.099396614808911821e+01,0.000000000000000000e+00,1.093995988189327695e-01,0.000000000000000000e+00,-1.000000007997038587e+00,0.000000000000000000e+00 +3.107474919262723745e+01,1.808900000000000148e+02,0.000000000000000000e+00,1.099406565685360349e+01,0.000000000000000000e+00,1.084900089634365794e-01,0.000000000000000000e+00,-1.000000005400841552e+00,0.000000000000000000e+00 +3.107565877424264045e+01,1.809000000000000057e+02,0.000000000000000000e+00,1.099416433737121146e+01,0.000000000000000000e+00,1.075804273431217595e-01,0.000000000000000000e+00,-1.000000011099998698e+00,0.000000000000000000e+00 +3.107656834769389320e+01,1.809099999999999966e+02,0.000000000000000000e+00,1.099426218967179736e+01,0.000000000000000000e+00,1.066708538817711660e-01,0.000000000000000000e+00,-1.000000005817972992e+00,0.000000000000000000e+00 +3.107747791304966611e+01,1.809200000000000159e+02,0.000000000000000000e+00,1.099435921378495884e+01,0.000000000000000000e+00,1.057612885207072917e-01,0.000000000000000000e+00,-1.000000006778420492e+00,0.000000000000000000e+00 +3.107838747037861538e+01,1.809300000000000068e+02,0.000000000000000000e+00,1.099445540974005198e+01,0.000000000000000000e+00,1.048517311855925727e-01,0.000000000000000000e+00,-1.000000007586683060e+00,0.000000000000000000e+00 +3.107929701974939718e+01,1.809399999999999977e+02,0.000000000000000000e+00,1.099455077756617705e+01,0.000000000000000000e+00,1.039421818079119125e-01,0.000000000000000000e+00,-1.000000008288758346e+00,0.000000000000000000e+00 +3.108020656123065706e+01,1.809500000000000171e+02,0.000000000000000000e+00,1.099464531729218386e+01,0.000000000000000000e+00,1.030326403191143825e-01,0.000000000000000000e+00,-1.000000008930389095e+00,0.000000000000000000e+00 +3.108111609489103699e+01,1.809600000000000080e+02,0.000000000000000000e+00,1.099473902894667177e+01,0.000000000000000000e+00,1.021231066506134016e-01,0.000000000000000000e+00,-1.000000005262153158e+00,0.000000000000000000e+00 +3.108202562079917186e+01,1.809699999999999989e+02,0.000000000000000000e+00,1.099483191255798964e+01,0.000000000000000000e+00,1.012135807376932511e-01,0.000000000000000000e+00,-1.000000008065593526e+00,0.000000000000000000e+00 +3.108293513902369298e+01,1.809799999999999898e+02,0.000000000000000000e+00,1.099492396815423945e+01,0.000000000000000000e+00,1.003040625058379542e-01,0.000000000000000000e+00,-1.000000006648493756e+00,0.000000000000000000e+00 +3.108384464963322102e+01,1.809900000000000091e+02,0.000000000000000000e+00,1.099501519576326736e+01,0.000000000000000000e+00,9.939455189026216719e-02,0.000000000000000000e+00,-1.000000009644551602e+00,0.000000000000000000e+00 +3.108475415269637665e+01,1.810000000000000000e+02,0.000000000000000000e+00,1.099510559541267263e+01,0.000000000000000000e+00,9.848504881833382296e-02,0.000000000000000000e+00,-1.000000006360259208e+00,0.000000000000000000e+00 +3.108566364828177342e+01,1.810099999999999909e+02,0.000000000000000000e+00,1.099519516712980050e+01,0.000000000000000000e+00,9.757555322715234791e-02,0.000000000000000000e+00,-1.000000005428591132e+00,0.000000000000000000e+00 +3.108657313645801779e+01,1.810200000000000102e+02,0.000000000000000000e+00,1.099528391094175106e+01,0.000000000000000000e+00,9.666606504597108351e-02,0.000000000000000000e+00,-1.000000009040204363e+00,0.000000000000000000e+00 +3.108748261729370910e+01,1.810300000000000011e+02,0.000000000000000000e+00,1.099537182687537218e+01,0.000000000000000000e+00,9.575658420205665489e-02,0.000000000000000000e+00,-1.000000006499833116e+00,0.000000000000000000e+00 +3.108839209085744670e+01,1.810399999999999920e+02,0.000000000000000000e+00,1.099545891495725769e+01,0.000000000000000000e+00,9.484711063240838791e-02,0.000000000000000000e+00,-1.000000008587366596e+00,0.000000000000000000e+00 +3.108930155721781929e+01,1.810500000000000114e+02,0.000000000000000000e+00,1.099554517521375629e+01,0.000000000000000000e+00,9.393764426422701597e-02,0.000000000000000000e+00,-1.000000006754114379e+00,0.000000000000000000e+00 +3.109021101644340845e+01,1.810600000000000023e+02,0.000000000000000000e+00,1.099563060767096268e+01,0.000000000000000000e+00,9.302818503249349336e-02,0.000000000000000000e+00,-1.000000007484204589e+00,0.000000000000000000e+00 +3.109112046860279932e+01,1.810699999999999932e+02,0.000000000000000000e+00,1.099571521235472460e+01,0.000000000000000000e+00,9.211873286629707058e-02,0.000000000000000000e+00,-1.000000006523211082e+00,0.000000000000000000e+00 +3.109202991376456282e+01,1.810800000000000125e+02,0.000000000000000000e+00,1.099579898929063759e+01,0.000000000000000000e+00,9.120928769860155161e-02,0.000000000000000000e+00,-1.000000006059349023e+00,0.000000000000000000e+00 +3.109293935199726633e+01,1.810900000000000034e+02,0.000000000000000000e+00,1.099588193850404849e+01,0.000000000000000000e+00,9.029984946038593918e-02,0.000000000000000000e+00,-1.000000008280430341e+00,0.000000000000000000e+00 +3.109384878336947722e+01,1.810999999999999943e+02,0.000000000000000000e+00,1.099596406002005367e+01,0.000000000000000000e+00,8.939041808064480954e-02,0.000000000000000000e+00,-1.000000006782885142e+00,0.000000000000000000e+00 +3.109475820794975220e+01,1.811100000000000136e+02,0.000000000000000000e+00,1.099604535386349724e+01,0.000000000000000000e+00,8.848099349420153470e-02,0.000000000000000000e+00,-1.000000008049328759e+00,0.000000000000000000e+00 +3.109566762580664445e+01,1.811200000000000045e+02,0.000000000000000000e+00,1.099612582005897643e+01,0.000000000000000000e+00,8.757157562998912903e-02,0.000000000000000000e+00,-1.000000007823031334e+00,0.000000000000000000e+00 +3.109657703700870357e+01,1.811299999999999955e+02,0.000000000000000000e+00,1.099620545863083620e+01,0.000000000000000000e+00,8.666216442081685345e-02,0.000000000000000000e+00,-1.000000003994449216e+00,0.000000000000000000e+00 +3.109748644162447206e+01,1.811400000000000148e+02,0.000000000000000000e+00,1.099628426960317285e+01,0.000000000000000000e+00,8.575275980141738863e-02,0.000000000000000000e+00,-1.000000009489210528e+00,0.000000000000000000e+00 +3.109839583972248533e+01,1.811500000000000057e+02,0.000000000000000000e+00,1.099636225299983572e+01,0.000000000000000000e+00,8.484336169477377232e-02,0.000000000000000000e+00,-1.000000007161656379e+00,0.000000000000000000e+00 +3.109930523137127878e+01,1.811599999999999966e+02,0.000000000000000000e+00,1.099643940884441662e+01,0.000000000000000000e+00,8.393397003946626023e-02,0.000000000000000000e+00,-1.000000005640673484e+00,0.000000000000000000e+00 +3.110021461663938425e+01,1.811700000000000159e+02,0.000000000000000000e+00,1.099651573716026398e+01,0.000000000000000000e+00,8.302458476623283956e-02,0.000000000000000000e+00,-1.000000007111232492e+00,0.000000000000000000e+00 +3.110112399559531937e+01,1.811800000000000068e+02,0.000000000000000000e+00,1.099659123797047577e+01,0.000000000000000000e+00,8.211520580382936085e-02,0.000000000000000000e+00,-1.000000007313839090e+00,0.000000000000000000e+00 +3.110203336830760890e+01,1.811899999999999977e+02,0.000000000000000000e+00,1.099666591129789772e+01,0.000000000000000000e+00,8.120583308488996122e-02,0.000000000000000000e+00,-1.000000006284534226e+00,0.000000000000000000e+00 +3.110294273484476335e+01,1.812000000000000171e+02,0.000000000000000000e+00,1.099673975716512686e+01,0.000000000000000000e+00,8.029646654202068912e-02,0.000000000000000000e+00,-1.000000008355165670e+00,0.000000000000000000e+00 +3.110385209527529327e+01,1.812100000000000080e+02,0.000000000000000000e+00,1.099681277559451154e+01,0.000000000000000000e+00,7.938710610389301814e-02,0.000000000000000000e+00,-1.000000004968581768e+00,0.000000000000000000e+00 +3.110476144966770207e+01,1.812199999999999989e+02,0.000000000000000000e+00,1.099688496660814785e+01,0.000000000000000000e+00,7.847775170696456859e-02,0.000000000000000000e+00,-1.000000006900305438e+00,0.000000000000000000e+00 +3.110567079809049318e+01,1.812299999999999898e+02,0.000000000000000000e+00,1.099695633022788677e+01,0.000000000000000000e+00,7.756840327789871203e-02,0.000000000000000000e+00,-1.000000007740456054e+00,0.000000000000000000e+00 +3.110658014061215937e+01,1.812400000000000091e+02,0.000000000000000000e+00,1.099702686647532524e+01,0.000000000000000000e+00,7.665906074919219548e-02,0.000000000000000000e+00,-1.000000005374825918e+00,0.000000000000000000e+00 +3.110748947730119696e+01,1.812500000000000000e+02,0.000000000000000000e+00,1.099709657537181151e+01,0.000000000000000000e+00,7.574972405526872454e-02,0.000000000000000000e+00,-1.000000008430044884e+00,0.000000000000000000e+00 +3.110839880822608805e+01,1.812599999999999909e+02,0.000000000000000000e+00,1.099716545693844694e+01,0.000000000000000000e+00,7.484039312271188737e-02,0.000000000000000000e+00,-1.000000006198139779e+00,0.000000000000000000e+00 +3.110930813345531831e+01,1.812700000000000102e+02,0.000000000000000000e+00,1.099723351119607884e+01,0.000000000000000000e+00,7.393106788784674366e-02,0.000000000000000000e+00,-1.000000005156769012e+00,0.000000000000000000e+00 +3.111021745305736275e+01,1.812800000000000011e+02,0.000000000000000000e+00,1.099730073816530940e+01,0.000000000000000000e+00,7.302174828111229754e-02,0.000000000000000000e+00,-1.000000007486836484e+00,0.000000000000000000e+00 +3.111112676710069991e+01,1.812899999999999920e+02,0.000000000000000000e+00,1.099736713786649034e+01,0.000000000000000000e+00,7.211243423096869165e-02,0.000000000000000000e+00,-1.000000006775441097e+00,0.000000000000000000e+00 +3.111203607565379770e+01,1.813000000000000114e+02,0.000000000000000000e+00,1.099743271031972114e+01,0.000000000000000000e+00,7.120312567171162288e-02,0.000000000000000000e+00,-1.000000005202528630e+00,0.000000000000000000e+00 +3.111294537878512045e+01,1.813100000000000023e+02,0.000000000000000000e+00,1.099749745554485436e+01,0.000000000000000000e+00,7.029382253565864824e-02,0.000000000000000000e+00,-1.000000007096271348e+00,0.000000000000000000e+00 +3.111385467656312898e+01,1.813199999999999932e+02,0.000000000000000000e+00,1.099756137356149388e+01,0.000000000000000000e+00,6.938452475119580298e-02,0.000000000000000000e+00,-1.000000008190781831e+00,0.000000000000000000e+00 +3.111476396905628405e+01,1.813300000000000125e+02,0.000000000000000000e+00,1.099762446438899133e+01,0.000000000000000000e+00,6.847523225059215513e-02,0.000000000000000000e+00,-1.000000004219604000e+00,0.000000000000000000e+00 +3.111567325633303938e+01,1.813400000000000034e+02,0.000000000000000000e+00,1.099768672804644964e+01,0.000000000000000000e+00,6.756594497000018018e-02,0.000000000000000000e+00,-1.000000005955074656e+00,0.000000000000000000e+00 +3.111658253846184508e+01,1.813499999999999943e+02,0.000000000000000000e+00,1.099774816455272664e+01,0.000000000000000000e+00,6.665666283578111639e-02,0.000000000000000000e+00,-1.000000006981613732e+00,0.000000000000000000e+00 +3.111749181551114418e+01,1.813600000000000136e+02,0.000000000000000000e+00,1.099780877392642608e+01,0.000000000000000000e+00,6.574738578013371304e-02,0.000000000000000000e+00,-1.000000007328529117e+00,0.000000000000000000e+00 +3.111840108754937972e+01,1.813700000000000045e+02,0.000000000000000000e+00,1.099786855618590309e+01,0.000000000000000000e+00,6.483811373523389043e-02,0.000000000000000000e+00,-1.000000004876067994e+00,0.000000000000000000e+00 +3.111931035464499118e+01,1.813799999999999955e+02,0.000000000000000000e+00,1.099792751134926405e+01,0.000000000000000000e+00,6.392884663518876021e-02,0.000000000000000000e+00,-1.000000006098444860e+00,0.000000000000000000e+00 +3.112021961686641092e+01,1.813900000000000148e+02,0.000000000000000000e+00,1.099798563943436847e+01,0.000000000000000000e+00,6.301958440822236218e-02,0.000000000000000000e+00,-1.000000006726720514e+00,0.000000000000000000e+00 +3.112112887428207131e+01,1.814000000000000057e+02,0.000000000000000000e+00,1.099804294045882358e+01,0.000000000000000000e+00,6.211032698644403105e-02,0.000000000000000000e+00,-1.000000004639894025e+00,0.000000000000000000e+00 +3.112203812696040117e+01,1.814099999999999966e+02,0.000000000000000000e+00,1.099809941443998795e+01,0.000000000000000000e+00,6.120107430389524344e-02,0.000000000000000000e+00,-1.000000006311191347e+00,0.000000000000000000e+00 +3.112294737496982222e+01,1.814200000000000159e+02,0.000000000000000000e+00,1.099815506139497323e+01,0.000000000000000000e+00,6.029182628873524380e-02,0.000000000000000000e+00,-1.000000007470329022e+00,0.000000000000000000e+00 +3.112385661837875617e+01,1.814300000000000068e+02,0.000000000000000000e+00,1.099820988134063882e+01,0.000000000000000000e+00,5.938258287300957755e-02,0.000000000000000000e+00,-1.000000003846384100e+00,0.000000000000000000e+00 +3.112476585725561762e+01,1.814399999999999977e+02,0.000000000000000000e+00,1.099826387429359542e+01,0.000000000000000000e+00,5.847334399265054217e-02,0.000000000000000000e+00,-1.000000006208936920e+00,0.000000000000000000e+00 +3.112567509166882118e+01,1.814500000000000171e+02,0.000000000000000000e+00,1.099831704027020862e+01,0.000000000000000000e+00,5.756410957380171667e-02,0.000000000000000000e+00,-1.000000005988978646e+00,0.000000000000000000e+00 +3.112658432168677791e+01,1.814600000000000080e+02,0.000000000000000000e+00,1.099836937928658998e+01,0.000000000000000000e+00,5.665487955040132695e-02,0.000000000000000000e+00,-1.000000007509244115e+00,0.000000000000000000e+00 +3.112749354737789176e+01,1.814699999999999989e+02,0.000000000000000000e+00,1.099842089135860412e+01,0.000000000000000000e+00,5.574565385246053884e-02,0.000000000000000000e+00,-1.000000002199620264e+00,0.000000000000000000e+00 +3.112840276881056667e+01,1.814799999999999898e+02,0.000000000000000000e+00,1.099847157650186524e+01,0.000000000000000000e+00,5.483643241778593524e-02,0.000000000000000000e+00,-1.000000007274835179e+00,0.000000000000000000e+00 +3.112931198605320304e+01,1.814900000000000091e+02,0.000000000000000000e+00,1.099852143473174415e+01,0.000000000000000000e+00,5.392721516853529740e-02,0.000000000000000000e+00,-1.000000005568802308e+00,0.000000000000000000e+00 +3.113022119917419772e+01,1.815000000000000000e+02,0.000000000000000000e+00,1.099857046606335409e+01,0.000000000000000000e+00,5.301800204247732878e-02,0.000000000000000000e+00,-1.000000003551556160e+00,0.000000000000000000e+00 +3.113113040824194400e+01,1.815099999999999909e+02,0.000000000000000000e+00,1.099861867051156494e+01,0.000000000000000000e+00,5.210879297150114442e-02,0.000000000000000000e+00,-1.000000007693031323e+00,0.000000000000000000e+00 +3.113203961332483516e+01,1.815200000000000102e+02,0.000000000000000000e+00,1.099866604809099790e+01,0.000000000000000000e+00,5.119958788161641655e-02,0.000000000000000000e+00,-1.000000002974234192e+00,0.000000000000000000e+00 +3.113294881449125739e+01,1.815300000000000011e+02,0.000000000000000000e+00,1.099871259881602015e+01,0.000000000000000000e+00,5.029038671249118353e-02,0.000000000000000000e+00,-1.000000006608579017e+00,0.000000000000000000e+00 +3.113385801180959334e+01,1.815399999999999920e+02,0.000000000000000000e+00,1.099875832270075726e+01,0.000000000000000000e+00,4.938118938814594489e-02,0.000000000000000000e+00,-1.000000005725030894e+00,0.000000000000000000e+00 +3.113476720534822917e+01,1.815500000000000114e+02,0.000000000000000000e+00,1.099880321975907904e+01,0.000000000000000000e+00,4.847199584430646191e-02,0.000000000000000000e+00,-1.000000002494144447e+00,0.000000000000000000e+00 +3.113567639517554042e+01,1.815600000000000023e+02,0.000000000000000000e+00,1.099884729000461014e+01,0.000000000000000000e+00,4.756280601472785002e-02,0.000000000000000000e+00,-1.000000005532978076e+00,0.000000000000000000e+00 +3.113658558135990262e+01,1.815699999999999932e+02,0.000000000000000000e+00,1.099889053345072831e+01,0.000000000000000000e+00,4.665361982533348939e-02,0.000000000000000000e+00,-1.000000006266865693e+00,0.000000000000000000e+00 +3.113749476396969129e+01,1.815800000000000125e+02,0.000000000000000000e+00,1.099893295011055727e+01,0.000000000000000000e+00,4.574443720984551487e-02,0.000000000000000000e+00,-1.000000002567299928e+00,0.000000000000000000e+00 +3.113840394307327841e+01,1.815900000000000034e+02,0.000000000000000000e+00,1.099897453999697383e+01,0.000000000000000000e+00,4.483525810392392785e-02,0.000000000000000000e+00,-1.000000007348332165e+00,0.000000000000000000e+00 +3.113931311873903240e+01,1.815999999999999943e+02,0.000000000000000000e+00,1.099901530312260967e+01,0.000000000000000000e+00,4.392608243149018904e-02,0.000000000000000000e+00,-1.000000001288853912e+00,0.000000000000000000e+00 +3.114022229103531458e+01,1.816100000000000136e+02,0.000000000000000000e+00,1.099905523949984065e+01,0.000000000000000000e+00,4.301691013403465685e-02,0.000000000000000000e+00,-1.000000005898238120e+00,0.000000000000000000e+00 +3.114113146003049337e+01,1.816200000000000045e+02,0.000000000000000000e+00,1.099909434914080286e+01,0.000000000000000000e+00,4.210774113349446957e-02,0.000000000000000000e+00,-1.000000004003405163e+00,0.000000000000000000e+00 +3.114204062579292653e+01,1.816299999999999955e+02,0.000000000000000000e+00,1.099913263205737479e+01,0.000000000000000000e+00,4.119857536742253801e-02,0.000000000000000000e+00,-1.000000004219009142e+00,0.000000000000000000e+00 +3.114294978839097183e+01,1.816400000000000148e+02,0.000000000000000000e+00,1.099917008826119158e+01,0.000000000000000000e+00,4.028941276554202922e-02,0.000000000000000000e+00,-1.000000002265161392e+00,0.000000000000000000e+00 +3.114385894789298348e+01,1.816500000000000057e+02,0.000000000000000000e+00,1.099920671776363790e+01,0.000000000000000000e+00,3.938025326146962074e-02,0.000000000000000000e+00,-1.000000006755935811e+00,0.000000000000000000e+00 +3.114476810436731924e+01,1.816599999999999966e+02,0.000000000000000000e+00,1.099924252057585150e+01,0.000000000000000000e+00,3.847109678099276675e-02,0.000000000000000000e+00,-1.000000000516102494e+00,0.000000000000000000e+00 +3.114567725788232622e+01,1.816700000000000159e+02,0.000000000000000000e+00,1.099927749670871613e+01,0.000000000000000000e+00,3.756194326551618584e-02,0.000000000000000000e+00,-1.000000005053549801e+00,0.000000000000000000e+00 +3.114658640850635507e+01,1.816800000000000068e+02,0.000000000000000000e+00,1.099931164617287571e+01,0.000000000000000000e+00,3.665279263689282668e-02,0.000000000000000000e+00,-1.000000003192109910e+00,0.000000000000000000e+00 +3.114749555630775291e+01,1.816899999999999977e+02,0.000000000000000000e+00,1.099934496897871661e+01,0.000000000000000000e+00,3.574364483259358932e-02,0.000000000000000000e+00,-1.000000003544426752e+00,0.000000000000000000e+00 +3.114840470135486328e+01,1.817000000000000171e+02,0.000000000000000000e+00,1.099937746513638182e+01,0.000000000000000000e+00,3.483449978226130922e-02,0.000000000000000000e+00,-1.000000003977192575e+00,0.000000000000000000e+00 +3.114931384371602974e+01,1.817100000000000080e+02,0.000000000000000000e+00,1.099940913465576386e+01,0.000000000000000000e+00,3.392535741748040068e-02,0.000000000000000000e+00,-1.000000000207527773e+00,0.000000000000000000e+00 +3.115022298345958873e+01,1.817199999999999989e+02,0.000000000000000000e+00,1.099943997754650660e+01,0.000000000000000000e+00,3.301621767373104366e-02,0.000000000000000000e+00,-1.000000005145409432e+00,0.000000000000000000e+00 +3.115113212065388382e+01,1.817299999999999898e+02,0.000000000000000000e+00,1.099946999381800872e+01,0.000000000000000000e+00,3.210708047475842319e-02,0.000000000000000000e+00,-1.000000001612144418e+00,0.000000000000000000e+00 +3.115204125536724789e+01,1.817400000000000091e+02,0.000000000000000000e+00,1.099949918347941313e+01,0.000000000000000000e+00,3.119794575992746247e-02,0.000000000000000000e+00,-1.000000000367804676e+00,0.000000000000000000e+00 +3.115295038766801738e+01,1.817500000000000000e+02,0.000000000000000000e+00,1.099952754653962117e+01,0.000000000000000000e+00,3.028881345882256798e-02,0.000000000000000000e+00,-1.000000003575467922e+00,0.000000000000000000e+00 +3.115385951762452521e+01,1.817599999999999909e+02,0.000000000000000000e+00,1.099955508300728368e+01,0.000000000000000000e+00,2.937968349906346782e-02,0.000000000000000000e+00,-1.000000002651797004e+00,0.000000000000000000e+00 +3.115476864530510426e+01,1.817700000000000102e+02,0.000000000000000000e+00,1.099958179289079929e+01,0.000000000000000000e+00,2.847055581607504243e-02,0.000000000000000000e+00,-9.999999997589730238e-01,0.000000000000000000e+00 +3.115567777077808032e+01,1.817800000000000011e+02,0.000000000000000000e+00,1.099960767619832147e+01,0.000000000000000000e+00,2.756143034331817038e-02,0.000000000000000000e+00,-1.000000001357350454e+00,0.000000000000000000e+00 +3.115658689411178273e+01,1.817899999999999920e+02,0.000000000000000000e+00,1.099963273293775678e+01,0.000000000000000000e+00,2.665230700838212841e-02,0.000000000000000000e+00,-1.000000003160759210e+00,0.000000000000000000e+00 +3.115749601537453728e+01,1.818000000000000114e+02,0.000000000000000000e+00,1.099965696311675956e+01,0.000000000000000000e+00,2.574318574275448815e-02,0.000000000000000000e+00,-9.999999987332645057e-01,0.000000000000000000e+00 +3.115840513463466621e+01,1.818100000000000023e+02,0.000000000000000000e+00,1.099968036674273542e+01,0.000000000000000000e+00,2.483406648377542089e-02,0.000000000000000000e+00,-1.000000000981875692e+00,0.000000000000000000e+00 +3.115931425196049531e+01,1.818199999999999932e+02,0.000000000000000000e+00,1.099970294382284663e+01,0.000000000000000000e+00,2.392494915705259059e-02,0.000000000000000000e+00,-9.999999991713539593e-01,0.000000000000000000e+00 +3.116022336742034682e+01,1.818300000000000125e+02,0.000000000000000000e+00,1.099972469436400146e+01,0.000000000000000000e+00,2.301583369795473510e-02,0.000000000000000000e+00,-9.999999997601722868e-01,0.000000000000000000e+00 +3.116113248108253941e+01,1.818400000000000034e+02,0.000000000000000000e+00,1.099974561837286302e+01,0.000000000000000000e+00,2.210672003598049620e-02,0.000000000000000000e+00,-9.999999984600729253e-01,0.000000000000000000e+00 +3.116204159301539178e+01,1.818499999999999943e+02,0.000000000000000000e+00,1.099976571585584395e+01,0.000000000000000000e+00,2.119760810452839608e-02,0.000000000000000000e+00,-9.999999995794897067e-01,0.000000000000000000e+00 +3.116295070328722261e+01,1.818600000000000136e+02,0.000000000000000000e+00,1.099978498681910999e+01,0.000000000000000000e+00,2.028849783308141544e-02,0.000000000000000000e+00,-9.999999966800332540e-01,0.000000000000000000e+00 +3.116385981196634347e+01,1.818700000000000045e+02,0.000000000000000000e+00,1.099980343126857640e+01,0.000000000000000000e+00,1.937938915697700118e-02,0.000000000000000000e+00,-9.999999983680071258e-01,0.000000000000000000e+00 +3.116476891912107305e+01,1.818799999999999955e+02,0.000000000000000000e+00,1.099982104920991333e+01,0.000000000000000000e+00,1.847028200372973633e-02,0.000000000000000000e+00,-9.999999982041875013e-01,0.000000000000000000e+00 +3.116567802481972649e+01,1.818900000000000148e+02,0.000000000000000000e+00,1.099983784064853864e+01,0.000000000000000000e+00,1.756117630670931545e-02,0.000000000000000000e+00,-9.999999940475223781e-01,0.000000000000000000e+00 +3.116658712913061535e+01,1.819000000000000057e+02,0.000000000000000000e+00,1.099985380558962333e+01,0.000000000000000000e+00,1.665207200123296899e-02,0.000000000000000000e+00,-9.999999966525633388e-01,0.000000000000000000e+00 +3.116749623212205123e+01,1.819099999999999966e+02,0.000000000000000000e+00,1.099986894403809323e+01,0.000000000000000000e+00,1.574296901284196956e-02,0.000000000000000000e+00,-9.999999952801748027e-01,0.000000000000000000e+00 +3.116840533386234213e+01,1.819200000000000159e+02,0.000000000000000000e+00,1.099988325599862016e+01,0.000000000000000000e+00,1.483386727684158496e-02,0.000000000000000000e+00,-9.999999920867844727e-01,0.000000000000000000e+00 +3.116931443441979965e+01,1.819300000000000068e+02,0.000000000000000000e+00,1.099989674147563079e+01,0.000000000000000000e+00,1.392476672657760872e-02,0.000000000000000000e+00,-9.999999956765076581e-01,0.000000000000000000e+00 +3.117022353386273181e+01,1.819399999999999977e+02,0.000000000000000000e+00,1.099990940047330490e+01,0.000000000000000000e+00,1.301566728757473125e-02,0.000000000000000000e+00,-9.999999888608575027e-01,0.000000000000000000e+00 +3.117113263225945019e+01,1.819500000000000171e+02,0.000000000000000000e+00,1.099992123299556823e+01,0.000000000000000000e+00,1.210656890098453856e-02,0.000000000000000000e+00,-9.999999909899498496e-01,0.000000000000000000e+00 +3.117204172967825926e+01,1.819600000000000080e+02,0.000000000000000000e+00,1.099993223904610673e+01,0.000000000000000000e+00,1.119747149036824131e-02,0.000000000000000000e+00,-9.999999870238166499e-01,0.000000000000000000e+00 +3.117295082618746349e+01,1.819699999999999989e+02,0.000000000000000000e+00,1.099994241862835054e+01,0.000000000000000000e+00,1.028837499296060380e-02,0.000000000000000000e+00,-9.999999877144091220e-01,0.000000000000000000e+00 +3.117385992185537091e+01,1.819799999999999898e+02,0.000000000000000000e+00,1.099995177174548644e+01,0.000000000000000000e+00,9.379279336222515889e-03,0.000000000000000000e+00,-9.999999844690047324e-01,0.000000000000000000e+00 +3.117476901675028600e+01,1.819900000000000091e+02,0.000000000000000000e+00,1.099996029840044898e+01,0.000000000000000000e+00,8.470184455427121756e-03,0.000000000000000000e+00,-9.999999794413072518e-01,0.000000000000000000e+00 +3.117567811094051322e+01,1.820000000000000000e+02,0.000000000000000000e+00,1.099996799859592755e+01,0.000000000000000000e+00,7.561090283890228511e-03,0.000000000000000000e+00,-9.999999790834056546e-01,0.000000000000000000e+00 +3.117658720449435705e+01,1.820099999999999909e+02,0.000000000000000000e+00,1.099997487233436466e+01,0.000000000000000000e+00,6.651996749062628195e-03,0.000000000000000000e+00,-9.999999726519658294e-01,0.000000000000000000e+00 +3.117749629748011841e+01,1.820200000000000102e+02,0.000000000000000000e+00,1.099998091961795055e+01,0.000000000000000000e+00,5.742903788162299905e-03,0.000000000000000000e+00,-9.999999687476691657e-01,0.000000000000000000e+00 +3.117840538996610178e+01,1.820300000000000011e+02,0.000000000000000000e+00,1.099998614044863210e+01,0.000000000000000000e+00,4.833811330588836178e-03,0.000000000000000000e+00,-9.999999566263626516e-01,0.000000000000000000e+00 +3.117931448202061162e+01,1.820399999999999920e+02,0.000000000000000000e+00,1.099999053482810574e+01,0.000000000000000000e+00,3.924719315509644577e-03,0.000000000000000000e+00,-9.999999448879532959e-01,0.000000000000000000e+00 +3.118022357371194886e+01,1.820500000000000114e+02,0.000000000000000000e+00,1.099999410275782630e+01,0.000000000000000000e+00,3.015627674274354991e-03,0.000000000000000000e+00,-9.999999270862631739e-01,0.000000000000000000e+00 +3.118113266510841441e+01,1.820600000000000023e+02,0.000000000000000000e+00,1.099999684423899993e+01,0.000000000000000000e+00,2.106536344093049191e-03,0.000000000000000000e+00,-9.999998795795757012e-01,0.000000000000000000e+00 +3.118204175627831276e+01,1.820699999999999932e+02,0.000000000000000000e+00,1.099999875927258941e+01,0.000000000000000000e+00,1.197445283668515433e-03,0.000000000000000000e+00,-9.999997529330637569e-01,0.000000000000000000e+00 +3.118295084728994482e+01,1.820800000000000125e+02,0.000000000000000000e+00,1.099999984785933371e+01,0.000000000000000000e+00,2.883544966444702841e-04,0.000000000000000000e+00,-3.173275029949889636e-01,0.000000000000000000e+00 +3.118385993821160795e+01,1.820900000000000034e+02,0.000000000000000000e+00,1.100000010999978883e+01,0.000000000000000000e+00,-1.250555227443304586e-07,0.000000000000000000e+00,1.375481800434597739e-04,0.000000000000000000e+00 +3.118476902911160664e+01,1.820999999999999943e+02,0.000000000000000000e+00,1.100000010988610200e+01,0.000000000000000000e+00,-1.172395525715981017e-11,0.000000000000000000e+00,1.719513454894101872e-08,0.000000000000000000e+00 +3.118567812001161599e+01,1.821100000000000136e+02,0.000000000000000000e+00,1.100000010988609134e+01,0.000000000000000000e+00,3.907985085719932952e-12,0.000000000000000000e+00,-4.298783637235246409e-09,0.000000000000000000e+00 +3.118658721091162533e+01,1.821200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.118749630181163468e+01,1.821299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.118840539271164403e+01,1.821400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.118931448361165337e+01,1.821500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119022357451166272e+01,1.821599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119113266541167206e+01,1.821700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119204175631168141e+01,1.821800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119295084721169076e+01,1.821899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119385993811170010e+01,1.822000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119476902901170945e+01,1.822100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119567811991171880e+01,1.822199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119658721081172814e+01,1.822299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119749630171173749e+01,1.822400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119840539261174683e+01,1.822500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.119931448351175618e+01,1.822599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120022357441176553e+01,1.822700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120113266531177487e+01,1.822800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120204175621178422e+01,1.822899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120295084711179356e+01,1.823000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120385993801180291e+01,1.823100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120476902891181226e+01,1.823199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120567811981182160e+01,1.823300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120658721071183095e+01,1.823400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120749630161184029e+01,1.823499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120840539251184964e+01,1.823600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.120931448341185899e+01,1.823700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121022357431186833e+01,1.823799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121113266521187768e+01,1.823900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121204175611188703e+01,1.824000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121295084701189637e+01,1.824099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121385993791190572e+01,1.824200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121476902881191506e+01,1.824300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121567811971192441e+01,1.824399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121658721061193376e+01,1.824500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121749630151194310e+01,1.824600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121840539241195245e+01,1.824699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.121931448331196179e+01,1.824799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122022357421197114e+01,1.824900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122113266511198049e+01,1.825000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122204175601198983e+01,1.825099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122295084691199918e+01,1.825200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122385993781200852e+01,1.825300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122476902871201787e+01,1.825399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122567811961202722e+01,1.825500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122658721051203656e+01,1.825600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122749630141204591e+01,1.825699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122840539231205526e+01,1.825800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.122931448321206460e+01,1.825900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123022357411207395e+01,1.825999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123113266501208329e+01,1.826100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123204175591209264e+01,1.826200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123295084681210199e+01,1.826299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123385993771211133e+01,1.826400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123476902861212068e+01,1.826500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123567811951213002e+01,1.826599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123658721041213937e+01,1.826700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123749630131214872e+01,1.826800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123840539221215806e+01,1.826899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.123931448311216741e+01,1.827000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124022357401217675e+01,1.827100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124113266491218610e+01,1.827199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124204175581219545e+01,1.827299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124295084671220479e+01,1.827400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124385993761221414e+01,1.827500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124476902851222349e+01,1.827599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124567811941223283e+01,1.827700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124658721031224218e+01,1.827800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124749630121225152e+01,1.827899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124840539211226087e+01,1.828000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.124931448301227022e+01,1.828100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125022357391227956e+01,1.828199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125113266481228891e+01,1.828300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125204175571229825e+01,1.828400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125295084661230760e+01,1.828499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125385993751231695e+01,1.828600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125476902841232629e+01,1.828700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125567811931233564e+01,1.828799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125658721021234498e+01,1.828900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125749630111235433e+01,1.829000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125840539201236368e+01,1.829099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.125931448291237302e+01,1.829200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126022357381238237e+01,1.829300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126113266471239172e+01,1.829399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126204175561240106e+01,1.829500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126295084651241041e+01,1.829600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126385993741241975e+01,1.829699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126476902831242910e+01,1.829799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126567811921243845e+01,1.829900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126658721011244779e+01,1.830000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126749630101245714e+01,1.830099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126840539191246648e+01,1.830200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.126931448281247583e+01,1.830300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127022357371248518e+01,1.830399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127113266461249452e+01,1.830500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127204175551250387e+01,1.830600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127295084641251322e+01,1.830699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127385993731252256e+01,1.830800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127476902821253191e+01,1.830900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127567811911254125e+01,1.830999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127658721001255060e+01,1.831100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127749630091255995e+01,1.831200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127840539181256929e+01,1.831299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.127931448271257864e+01,1.831400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128022357361258798e+01,1.831500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128113266451259733e+01,1.831599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128204175541260668e+01,1.831700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128295084631261602e+01,1.831800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128385993721262537e+01,1.831899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128476902811263471e+01,1.832000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128567811901264406e+01,1.832100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128658720991265341e+01,1.832199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128749630081266275e+01,1.832299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128840539171267210e+01,1.832400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.128931448261268145e+01,1.832500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129022357351269079e+01,1.832599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129113266441270014e+01,1.832700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129204175531270948e+01,1.832800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129295084621271883e+01,1.832899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129385993711272818e+01,1.833000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129476902801273752e+01,1.833100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129567811891274687e+01,1.833199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129658720981275621e+01,1.833300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129749630071276556e+01,1.833400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129840539161277491e+01,1.833499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.129931448251278425e+01,1.833600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130022357341279360e+01,1.833700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130113266431280294e+01,1.833799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130204175521281229e+01,1.833900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130295084611282164e+01,1.834000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130385993701283098e+01,1.834099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130476902791284033e+01,1.834200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130567811881284968e+01,1.834300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130658720971285902e+01,1.834399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130749630061286837e+01,1.834500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130840539151287771e+01,1.834600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.130931448241288706e+01,1.834699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131022357331289641e+01,1.834799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131113266421290575e+01,1.834900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131204175511291510e+01,1.835000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131295084601292444e+01,1.835099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131385993691293379e+01,1.835200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131476902781294314e+01,1.835300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131567811871295248e+01,1.835399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131658720961296183e+01,1.835500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131749630051297117e+01,1.835600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131840539141298052e+01,1.835699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.131931448231298987e+01,1.835800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132022357321299921e+01,1.835900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132113266411300856e+01,1.835999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132204175501301791e+01,1.836100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132295084591302725e+01,1.836200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132385993681303660e+01,1.836299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132476902771304594e+01,1.836400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132567811861305529e+01,1.836500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132658720951306464e+01,1.836599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132749630041307398e+01,1.836700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132840539131308333e+01,1.836800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.132931448221309267e+01,1.836899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133022357311310202e+01,1.837000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133113266401311137e+01,1.837100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133204175491312071e+01,1.837199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133295084581313006e+01,1.837299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133385993671313940e+01,1.837400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133476902761314875e+01,1.837500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133567811851315810e+01,1.837599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133658720941316744e+01,1.837700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133749630031317679e+01,1.837800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133840539121318614e+01,1.837899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.133931448211319548e+01,1.838000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134022357301320483e+01,1.838100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134113266391321417e+01,1.838199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134204175481322352e+01,1.838300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134295084571323287e+01,1.838400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134385993661324221e+01,1.838499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134476902751325156e+01,1.838600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134567811841326090e+01,1.838700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134658720931327025e+01,1.838799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134749630021327960e+01,1.838900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134840539111328894e+01,1.839000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.134931448201329829e+01,1.839099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135022357291330763e+01,1.839200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135113266381331698e+01,1.839300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135204175471332633e+01,1.839399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135295084561333567e+01,1.839500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135385993651334502e+01,1.839600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135476902741335437e+01,1.839699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135567811831336371e+01,1.839799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135658720921337306e+01,1.839900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135749630011338240e+01,1.840000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135840539101339175e+01,1.840099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.135931448191340110e+01,1.840200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136022357281341044e+01,1.840300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136113266371341979e+01,1.840399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136204175461342913e+01,1.840500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136295084551343848e+01,1.840600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136385993641344783e+01,1.840699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136476902731345717e+01,1.840800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136567811821346652e+01,1.840900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136658720911347586e+01,1.840999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136749630001348521e+01,1.841100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136840539091349456e+01,1.841200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.136931448181350390e+01,1.841299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137022357271351325e+01,1.841400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137113266361352260e+01,1.841500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137204175451353194e+01,1.841599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137295084541354129e+01,1.841700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137385993631355063e+01,1.841800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137476902721355998e+01,1.841899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137567811811356933e+01,1.842000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137658720901357867e+01,1.842100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137749629991358802e+01,1.842199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137840539081359736e+01,1.842299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.137931448171360671e+01,1.842400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138022357261361606e+01,1.842500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138113266351362540e+01,1.842599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138204175441363475e+01,1.842700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138295084531364409e+01,1.842800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138385993621365344e+01,1.842899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138476902711366279e+01,1.843000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138567811801367213e+01,1.843100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138658720891368148e+01,1.843199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138749629981369083e+01,1.843300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138840539071370017e+01,1.843400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.138931448161370952e+01,1.843499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139022357251371886e+01,1.843600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139113266341372821e+01,1.843700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139204175431373756e+01,1.843799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139295084521374690e+01,1.843900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139385993611375625e+01,1.844000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139476902701376559e+01,1.844099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139567811791377494e+01,1.844200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139658720881378429e+01,1.844300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139749629971379363e+01,1.844399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139840539061380298e+01,1.844500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.139931448151381232e+01,1.844600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140022357241382167e+01,1.844699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140113266331383102e+01,1.844799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140204175421384036e+01,1.844900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140295084511384971e+01,1.845000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140385993601385906e+01,1.845099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140476902691386840e+01,1.845200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140567811781387775e+01,1.845300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140658720871388709e+01,1.845399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140749629961389644e+01,1.845500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140840539051390579e+01,1.845600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.140931448141391513e+01,1.845699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141022357231392448e+01,1.845800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141113266321393382e+01,1.845900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141204175411394317e+01,1.845999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141295084501395252e+01,1.846100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141385993591396186e+01,1.846200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141476902681397121e+01,1.846299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141567811771398055e+01,1.846400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141658720861398990e+01,1.846500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141749629951399925e+01,1.846599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141840539041400859e+01,1.846700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.141931448131401794e+01,1.846800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142022357221402729e+01,1.846899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142113266311403663e+01,1.847000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142204175401404598e+01,1.847100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142295084491405532e+01,1.847199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142385993581406467e+01,1.847299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142476902671407402e+01,1.847400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142567811761408336e+01,1.847500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142658720851409271e+01,1.847599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142749629941410205e+01,1.847700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142840539031411140e+01,1.847800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.142931448121412075e+01,1.847899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143022357211413009e+01,1.848000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143113266301413944e+01,1.848100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143204175391414879e+01,1.848199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143295084481415813e+01,1.848300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143385993571416748e+01,1.848400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143476902661417682e+01,1.848499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143567811751418617e+01,1.848600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143658720841419552e+01,1.848700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143749629931420486e+01,1.848799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143840539021421421e+01,1.848900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.143931448111422355e+01,1.849000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144022357201423290e+01,1.849099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144113266291424225e+01,1.849200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144204175381425159e+01,1.849300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144295084471426094e+01,1.849399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144385993561427028e+01,1.849500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144476902651427963e+01,1.849600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144567811741428898e+01,1.849699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144658720831429832e+01,1.849799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144749629921430767e+01,1.849900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144840539011431702e+01,1.850000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.144931448101432636e+01,1.850099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145022357191433571e+01,1.850200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145113266281434505e+01,1.850300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145204175371435440e+01,1.850399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145295084461436375e+01,1.850500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145385993551437309e+01,1.850600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145476902641438244e+01,1.850699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145567811731439178e+01,1.850800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145658720821440113e+01,1.850900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145749629911441048e+01,1.850999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145840539001441982e+01,1.851100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.145931448091442917e+01,1.851200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146022357181443851e+01,1.851299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146113266271444786e+01,1.851400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146204175361445721e+01,1.851500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146295084451446655e+01,1.851599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146385993541447590e+01,1.851700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146476902631448525e+01,1.851800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146567811721449459e+01,1.851899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146658720811450394e+01,1.852000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146749629901451328e+01,1.852100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146840538991452263e+01,1.852199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.146931448081453198e+01,1.852299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147022357171454132e+01,1.852400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147113266261455067e+01,1.852500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147204175351456001e+01,1.852599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147295084441456936e+01,1.852700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147385993531457871e+01,1.852800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147476902621458805e+01,1.852899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147567811711459740e+01,1.853000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147658720801460674e+01,1.853100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147749629891461609e+01,1.853199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147840538981462544e+01,1.853300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.147931448071463478e+01,1.853400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148022357161464413e+01,1.853499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148113266251465348e+01,1.853600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148204175341466282e+01,1.853700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148295084431467217e+01,1.853799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148385993521468151e+01,1.853900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148476902611469086e+01,1.854000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148567811701470021e+01,1.854099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148658720791470955e+01,1.854200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148749629881471890e+01,1.854300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148840538971472824e+01,1.854399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.148931448061473759e+01,1.854500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149022357151474694e+01,1.854600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149113266241475628e+01,1.854699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149204175331476563e+01,1.854799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149295084421477497e+01,1.854900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149385993511478432e+01,1.855000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149476902601479367e+01,1.855099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149567811691480301e+01,1.855200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149658720781481236e+01,1.855300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149749629871482171e+01,1.855399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149840538961483105e+01,1.855500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.149931448051484040e+01,1.855600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150022357141484974e+01,1.855699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150113266231485909e+01,1.855800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150204175321486844e+01,1.855900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150295084411487778e+01,1.855999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150385993501488713e+01,1.856100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150476902591489647e+01,1.856200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150567811681490582e+01,1.856299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150658720771491517e+01,1.856400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150749629861492451e+01,1.856500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150840538951493386e+01,1.856599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.150931448041494320e+01,1.856700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151022357131495255e+01,1.856800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151113266221496190e+01,1.856899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151204175311497124e+01,1.857000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151295084401498059e+01,1.857100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151385993491498994e+01,1.857199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151476902581499928e+01,1.857299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151567811671500863e+01,1.857400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151658720761501797e+01,1.857500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151749629851502732e+01,1.857599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151840538941503667e+01,1.857700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.151931448031504601e+01,1.857800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152022357121505536e+01,1.857899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152113266211506470e+01,1.858000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152204175301507405e+01,1.858100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152295084391508340e+01,1.858199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152385993481509274e+01,1.858300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152476902571510209e+01,1.858400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152567811661511143e+01,1.858499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152658720751512078e+01,1.858600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152749629841513013e+01,1.858700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152840538931513947e+01,1.858799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.152931448021514882e+01,1.858900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153022357111515817e+01,1.859000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153113266201516751e+01,1.859099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153204175291517686e+01,1.859200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153295084381518620e+01,1.859300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153385993471519555e+01,1.859399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153476902561520490e+01,1.859500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153567811651521424e+01,1.859600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153658720741522359e+01,1.859699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153749629831523293e+01,1.859799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153840538921524228e+01,1.859900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.153931448011525163e+01,1.860000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154022357101526097e+01,1.860099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154113266191527032e+01,1.860200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154204175281527966e+01,1.860300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154295084371528901e+01,1.860399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154385993461529836e+01,1.860500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154476902551530770e+01,1.860600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154567811641531705e+01,1.860699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154658720731532640e+01,1.860800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154749629821533574e+01,1.860900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154840538911534509e+01,1.860999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.154931448001535443e+01,1.861100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155022357091536378e+01,1.861200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155113266181537313e+01,1.861299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155204175271538247e+01,1.861400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155295084361539182e+01,1.861500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155385993451540116e+01,1.861599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155476902541541051e+01,1.861700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155567811631541986e+01,1.861800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155658720721542920e+01,1.861899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155749629811543855e+01,1.862000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155840538901544789e+01,1.862100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.155931447991545724e+01,1.862199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156022357081546659e+01,1.862299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156113266171547593e+01,1.862400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156204175261548528e+01,1.862500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156295084351549463e+01,1.862599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156385993441550397e+01,1.862700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156476902531551332e+01,1.862800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156567811621552266e+01,1.862899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156658720711553201e+01,1.863000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156749629801554136e+01,1.863100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156840538891555070e+01,1.863199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.156931447981556005e+01,1.863300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157022357071556939e+01,1.863400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157113266161557874e+01,1.863499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157204175251558809e+01,1.863600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157295084341559743e+01,1.863700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157385993431560678e+01,1.863799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157476902521561613e+01,1.863900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157567811611562547e+01,1.864000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157658720701563482e+01,1.864099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157749629791564416e+01,1.864200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157840538881565351e+01,1.864300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.157931447971566286e+01,1.864399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158022357061567220e+01,1.864500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158113266151568155e+01,1.864600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158204175241569089e+01,1.864699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158295084331570024e+01,1.864799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158385993421570959e+01,1.864900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158476902511571893e+01,1.865000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158567811601572828e+01,1.865099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158658720691573762e+01,1.865200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158749629781574697e+01,1.865300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158840538871575632e+01,1.865399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.158931447961576566e+01,1.865500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159022357051577501e+01,1.865600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159113266141578436e+01,1.865699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159204175231579370e+01,1.865800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159295084321580305e+01,1.865900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159385993411581239e+01,1.865999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159476902501582174e+01,1.866100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159567811591583109e+01,1.866200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159658720681584043e+01,1.866299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159749629771584978e+01,1.866400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159840538861585912e+01,1.866500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.159931447951586847e+01,1.866599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160022357041587782e+01,1.866700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160113266131588716e+01,1.866800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160204175221589651e+01,1.866899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160295084311590585e+01,1.867000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160385993401591520e+01,1.867100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160476902491592455e+01,1.867199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160567811581593389e+01,1.867299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160658720671594324e+01,1.867400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160749629761595259e+01,1.867500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160840538851596193e+01,1.867599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.160931447941597128e+01,1.867700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161022357031598062e+01,1.867800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161113266121598997e+01,1.867899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161204175211599932e+01,1.868000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161295084301600866e+01,1.868100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161385993391601801e+01,1.868199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161476902481602735e+01,1.868300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161567811571603670e+01,1.868400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161658720661604605e+01,1.868499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161749629751605539e+01,1.868600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161840538841606474e+01,1.868700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.161931447931607408e+01,1.868799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162022357021608343e+01,1.868900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162113266111609278e+01,1.869000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162204175201610212e+01,1.869099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162295084291611147e+01,1.869200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162385993381612082e+01,1.869300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162476902471613016e+01,1.869399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162567811561613951e+01,1.869500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162658720651614885e+01,1.869600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162749629741615820e+01,1.869699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162840538831616755e+01,1.869799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.162931447921617689e+01,1.869900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163022357011618624e+01,1.870000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163113266101619558e+01,1.870099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163204175191620493e+01,1.870200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163295084281621428e+01,1.870300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163385993371622362e+01,1.870399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163476902461623297e+01,1.870500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163567811551624231e+01,1.870600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163658720641625166e+01,1.870699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163749629731626101e+01,1.870800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163840538821627035e+01,1.870900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.163931447911627970e+01,1.870999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164022357001628905e+01,1.871100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164113266091629839e+01,1.871200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164204175181630774e+01,1.871299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164295084271631708e+01,1.871400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164385993361632643e+01,1.871500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164476902451633578e+01,1.871599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164567811541634512e+01,1.871700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164658720631635447e+01,1.871800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164749629721636381e+01,1.871899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164840538811637316e+01,1.872000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.164931447901638251e+01,1.872100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165022356991639185e+01,1.872199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165113266081640120e+01,1.872299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165204175171641054e+01,1.872400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165295084261641989e+01,1.872500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165385993351642924e+01,1.872599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165476902441643858e+01,1.872700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165567811531644793e+01,1.872800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165658720621645728e+01,1.872899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165749629711646662e+01,1.873000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165840538801647597e+01,1.873100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.165931447891648531e+01,1.873199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166022356981649466e+01,1.873300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166113266071650401e+01,1.873400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166204175161651335e+01,1.873499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166295084251652270e+01,1.873600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166385993341653204e+01,1.873700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166476902431654139e+01,1.873799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166567811521655074e+01,1.873900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166658720611656008e+01,1.874000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166749629701656943e+01,1.874099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166840538791657877e+01,1.874200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.166931447881658812e+01,1.874300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167022356971659747e+01,1.874399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167113266061660681e+01,1.874500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167204175151661616e+01,1.874600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167295084241662551e+01,1.874699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167385993331663485e+01,1.874799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167476902421664420e+01,1.874900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167567811511665354e+01,1.875000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167658720601666289e+01,1.875099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167749629691667224e+01,1.875200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167840538781668158e+01,1.875300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.167931447871669093e+01,1.875399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168022356961670027e+01,1.875500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168113266051670962e+01,1.875600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168204175141671897e+01,1.875699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168295084231672831e+01,1.875800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168385993321673766e+01,1.875900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168476902411674700e+01,1.875999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168567811501675635e+01,1.876100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168658720591676570e+01,1.876200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168749629681677504e+01,1.876299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168840538771678439e+01,1.876400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.168931447861679374e+01,1.876500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169022356951680308e+01,1.876599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169113266041681243e+01,1.876700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169204175131682177e+01,1.876800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169295084221683112e+01,1.876899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169385993311684047e+01,1.877000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169476902401684981e+01,1.877100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169567811491685916e+01,1.877199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169658720581686850e+01,1.877299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169749629671687785e+01,1.877400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169840538761688720e+01,1.877500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.169931447851689654e+01,1.877599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170022356941690589e+01,1.877700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170113266031691523e+01,1.877800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170204175121692458e+01,1.877899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170295084211693393e+01,1.878000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170385993301694327e+01,1.878100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170476902391695262e+01,1.878199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170567811481696197e+01,1.878300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170658720571697131e+01,1.878400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170749629661698066e+01,1.878499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170840538751699000e+01,1.878600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.170931447841699935e+01,1.878700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171022356931700870e+01,1.878799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171113266021701804e+01,1.878900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171204175111702739e+01,1.879000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171295084201703673e+01,1.879099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171385993291704608e+01,1.879200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171476902381705543e+01,1.879300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171567811471706477e+01,1.879399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171658720561707412e+01,1.879500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171749629651708347e+01,1.879600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171840538741709281e+01,1.879699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.171931447831710216e+01,1.879799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172022356921711150e+01,1.879900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172113266011712085e+01,1.880000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172204175101713020e+01,1.880099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172295084191713954e+01,1.880200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172385993281714889e+01,1.880300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172476902371715823e+01,1.880399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172567811461716758e+01,1.880500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172658720551717693e+01,1.880600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172749629641718627e+01,1.880699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172840538731719562e+01,1.880800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.172931447821720496e+01,1.880900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173022356911721431e+01,1.880999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173113266001722366e+01,1.881100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173204175091723300e+01,1.881200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173295084181724235e+01,1.881299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173385993271725170e+01,1.881400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173476902361726104e+01,1.881500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173567811451727039e+01,1.881599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173658720541727973e+01,1.881700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173749629631728908e+01,1.881800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173840538721729843e+01,1.881899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.173931447811730777e+01,1.882000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174022356901731712e+01,1.882100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174113265991732646e+01,1.882199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174204175081733581e+01,1.882299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174295084171734516e+01,1.882400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174385993261735450e+01,1.882500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174476902351736385e+01,1.882599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174567811441737319e+01,1.882700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174658720531738254e+01,1.882800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174749629621739189e+01,1.882899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174840538711740123e+01,1.883000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.174931447801741058e+01,1.883100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175022356891741993e+01,1.883199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175113265981742927e+01,1.883300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175204175071743862e+01,1.883400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175295084161744796e+01,1.883499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175385993251745731e+01,1.883600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175476902341746666e+01,1.883700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175567811431747600e+01,1.883799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175658720521748535e+01,1.883900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175749629611749469e+01,1.884000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175840538701750404e+01,1.884099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.175931447791751339e+01,1.884200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176022356881752273e+01,1.884300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176113265971753208e+01,1.884399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176204175061754142e+01,1.884500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176295084151755077e+01,1.884600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176385993241756012e+01,1.884699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176476902331756946e+01,1.884799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176567811421757881e+01,1.884900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176658720511758816e+01,1.885000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176749629601759750e+01,1.885099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176840538691760685e+01,1.885200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.176931447781761619e+01,1.885300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177022356871762554e+01,1.885399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177113265961763489e+01,1.885500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177204175051764423e+01,1.885600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177295084141765358e+01,1.885699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177385993231766292e+01,1.885800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177476902321767227e+01,1.885900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177567811411768162e+01,1.885999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177658720501769096e+01,1.886100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177749629591770031e+01,1.886200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177840538681770965e+01,1.886299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.177931447771771900e+01,1.886400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178022356861772835e+01,1.886500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178113265951773769e+01,1.886599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178204175041774704e+01,1.886700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178295084131775639e+01,1.886800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178385993221776573e+01,1.886899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178476902311777508e+01,1.887000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178567811401778442e+01,1.887100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178658720491779377e+01,1.887199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178749629581780312e+01,1.887299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178840538671781246e+01,1.887400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.178931447761782181e+01,1.887500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179022356851783115e+01,1.887599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179113265941784050e+01,1.887700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179204175031784985e+01,1.887800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179295084121785919e+01,1.887899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179385993211786854e+01,1.888000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179476902301787788e+01,1.888100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179567811391788723e+01,1.888199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179658720481789658e+01,1.888300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179749629571790592e+01,1.888400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179840538661791527e+01,1.888499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.179931447751792462e+01,1.888600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180022356841793396e+01,1.888700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180113265931794331e+01,1.888799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180204175021795265e+01,1.888900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180295084111796200e+01,1.889000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180385993201797135e+01,1.889099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180476902291798069e+01,1.889200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180567811381799004e+01,1.889300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180658720471799938e+01,1.889399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180749629561800873e+01,1.889500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180840538651801808e+01,1.889600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.180931447741802742e+01,1.889699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181022356831803677e+01,1.889799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181113265921804611e+01,1.889900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181204175011805546e+01,1.890000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181295084101806481e+01,1.890099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181385993191807415e+01,1.890200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181476902281808350e+01,1.890300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181567811371809285e+01,1.890399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181658720461810219e+01,1.890500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181749629551811154e+01,1.890600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181840538641812088e+01,1.890699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.181931447731813023e+01,1.890800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182022356821813958e+01,1.890900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182113265911814892e+01,1.890999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182204175001815827e+01,1.891100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182295084091816761e+01,1.891200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182385993181817696e+01,1.891299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182476902271818631e+01,1.891400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182567811361819565e+01,1.891500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182658720451820500e+01,1.891599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182749629541821434e+01,1.891700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182840538631822369e+01,1.891800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.182931447721823304e+01,1.891899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183022356811824238e+01,1.892000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183113265901825173e+01,1.892100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183204174991826108e+01,1.892199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183295084081827042e+01,1.892299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183385993171827977e+01,1.892400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183476902261828911e+01,1.892500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183567811351829846e+01,1.892599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183658720441830781e+01,1.892700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183749629531831715e+01,1.892800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183840538621832650e+01,1.892899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.183931447711833584e+01,1.893000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184022356801834519e+01,1.893100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184113265891835454e+01,1.893199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184204174981836388e+01,1.893300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184295084071837323e+01,1.893400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184385993161838257e+01,1.893499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184476902251839192e+01,1.893600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184567811341840127e+01,1.893700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184658720431841061e+01,1.893799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184749629521841996e+01,1.893900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184840538611842931e+01,1.894000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.184931447701843865e+01,1.894099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185022356791844800e+01,1.894200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185113265881845734e+01,1.894300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185204174971846669e+01,1.894399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185295084061847604e+01,1.894500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185385993151848538e+01,1.894600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185476902241849473e+01,1.894699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185567811331850407e+01,1.894799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185658720421851342e+01,1.894900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185749629511852277e+01,1.895000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185840538601853211e+01,1.895099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.185931447691854146e+01,1.895200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186022356781855080e+01,1.895300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186113265871856015e+01,1.895399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186204174961856950e+01,1.895500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186295084051857884e+01,1.895600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186385993141858819e+01,1.895699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186476902231859754e+01,1.895800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186567811321860688e+01,1.895900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186658720411861623e+01,1.895999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186749629501862557e+01,1.896100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186840538591863492e+01,1.896200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.186931447681864427e+01,1.896299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187022356771865361e+01,1.896400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187113265861866296e+01,1.896500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187204174951867230e+01,1.896599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187295084041868165e+01,1.896700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187385993131869100e+01,1.896800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187476902221870034e+01,1.896899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187567811311870969e+01,1.897000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187658720401871904e+01,1.897100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187749629491872838e+01,1.897199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187840538581873773e+01,1.897299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.187931447671874707e+01,1.897400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188022356761875642e+01,1.897500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188113265851876577e+01,1.897599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188204174941877511e+01,1.897700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188295084031878446e+01,1.897800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188385993121879380e+01,1.897899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188476902211880315e+01,1.898000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188567811301881250e+01,1.898100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188658720391882184e+01,1.898199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188749629481883119e+01,1.898300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188840538571884053e+01,1.898400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.188931447661884988e+01,1.898499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189022356751885923e+01,1.898600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189113265841886857e+01,1.898700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189204174931887792e+01,1.898799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189295084021888727e+01,1.898900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189385993111889661e+01,1.899000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189476902201890596e+01,1.899099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189567811291891530e+01,1.899200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189658720381892465e+01,1.899300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189749629471893400e+01,1.899399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189840538561894334e+01,1.899500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.189931447651895269e+01,1.899600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190022356741896203e+01,1.899699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190113265831897138e+01,1.899799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190204174921898073e+01,1.899900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190295084011899007e+01,1.900000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190385993101899942e+01,1.900099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190476902191900876e+01,1.900200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190567811281901811e+01,1.900300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190658720371902746e+01,1.900399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190749629461903680e+01,1.900500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190840538551904615e+01,1.900600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.190931447641905550e+01,1.900699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191022356731906484e+01,1.900800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191113265821907419e+01,1.900900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191204174911908353e+01,1.900999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191295084001909288e+01,1.901100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191385993091910223e+01,1.901200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191476902181911157e+01,1.901299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191567811271912092e+01,1.901400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191658720361913026e+01,1.901500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191749629451913961e+01,1.901599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191840538541914896e+01,1.901700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.191931447631915830e+01,1.901800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192022356721916765e+01,1.901899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192113265811917699e+01,1.902000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192204174901918634e+01,1.902100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192295083991919569e+01,1.902199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192385993081920503e+01,1.902299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192476902171921438e+01,1.902400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192567811261922373e+01,1.902500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192658720351923307e+01,1.902599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192749629441924242e+01,1.902700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192840538531925176e+01,1.902800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.192931447621926111e+01,1.902899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193022356711927046e+01,1.903000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193113265801927980e+01,1.903100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193204174891928915e+01,1.903199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193295083981929849e+01,1.903300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193385993071930784e+01,1.903400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193476902161931719e+01,1.903499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193567811251932653e+01,1.903600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193658720341933588e+01,1.903700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193749629431934522e+01,1.903799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193840538521935457e+01,1.903900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.193931447611936392e+01,1.904000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194022356701937326e+01,1.904099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194113265791938261e+01,1.904200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194204174881939196e+01,1.904300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194295083971940130e+01,1.904399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194385993061941065e+01,1.904500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194476902151941999e+01,1.904600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194567811241942934e+01,1.904699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194658720331943869e+01,1.904799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194749629421944803e+01,1.904900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194840538511945738e+01,1.905000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.194931447601946672e+01,1.905099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195022356691947607e+01,1.905200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195113265781948542e+01,1.905300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195204174871949476e+01,1.905399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195295083961950411e+01,1.905500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195385993051951345e+01,1.905600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195476902141952280e+01,1.905699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195567811231953215e+01,1.905800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195658720321954149e+01,1.905900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195749629411955084e+01,1.905999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195840538501956019e+01,1.906100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.195931447591956953e+01,1.906200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196022356681957888e+01,1.906299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196113265771958822e+01,1.906400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196204174861959757e+01,1.906500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196295083951960692e+01,1.906599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196385993041961626e+01,1.906700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196476902131962561e+01,1.906800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196567811221963495e+01,1.906899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196658720311964430e+01,1.907000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196749629401965365e+01,1.907100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196840538491966299e+01,1.907199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.196931447581967234e+01,1.907299999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197022356671968168e+01,1.907400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197113265761969103e+01,1.907500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197204174851970038e+01,1.907599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197295083941970972e+01,1.907700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197385993031971907e+01,1.907800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197476902121972842e+01,1.907899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197567811211973776e+01,1.908000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197658720301974711e+01,1.908100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197749629391975645e+01,1.908199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197840538481976580e+01,1.908300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.197931447571977515e+01,1.908400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198022356661978449e+01,1.908499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198113265751979384e+01,1.908600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198204174841980318e+01,1.908700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198295083931981253e+01,1.908799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198385993021982188e+01,1.908900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198476902111983122e+01,1.909000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198567811201984057e+01,1.909099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198658720291984991e+01,1.909200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198749629381985926e+01,1.909300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198840538471986861e+01,1.909399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.198931447561987795e+01,1.909500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199022356651988730e+01,1.909600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199113265741989665e+01,1.909699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199204174831990599e+01,1.909799999999999898e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199295083921991534e+01,1.909900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199385993011992468e+01,1.910000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199476902101993403e+01,1.910099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199567811191994338e+01,1.910200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199658720281995272e+01,1.910300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199749629371996207e+01,1.910399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199840538461997141e+01,1.910500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.199931447551998076e+01,1.910600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200022356641999011e+01,1.910699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200113265731999945e+01,1.910800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200204174822000880e+01,1.910900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200295083912001814e+01,1.910999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200385993002002749e+01,1.911100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200476902092003684e+01,1.911200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200567811182004618e+01,1.911299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200658720272005553e+01,1.911400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200749629362006488e+01,1.911500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200840538452007422e+01,1.911599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.200931447542008357e+01,1.911700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201022356632009291e+01,1.911800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201113265722010226e+01,1.911899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201204174812011161e+01,1.912000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201295083902012095e+01,1.912100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201385992992013030e+01,1.912199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201476902082013964e+01,1.912300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201567811172014899e+01,1.912400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201658720262015834e+01,1.912500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201749629352016768e+01,1.912599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201840538442017703e+01,1.912700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.201931447532018638e+01,1.912800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202022356622019572e+01,1.912899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202113265712020507e+01,1.913000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202204174802021441e+01,1.913100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202295083892022376e+01,1.913199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202385992982023311e+01,1.913300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202476902072024245e+01,1.913400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202567811162025180e+01,1.913499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202658720252026114e+01,1.913600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202749629342027049e+01,1.913700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202840538432027984e+01,1.913799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.202931447522028918e+01,1.913900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203022356612029853e+01,1.914000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203113265702030787e+01,1.914099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203204174792031722e+01,1.914200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203295083882032657e+01,1.914300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203385992972033591e+01,1.914399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203476902062034526e+01,1.914500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203567811152035461e+01,1.914600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203658720242036395e+01,1.914699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203749629332037330e+01,1.914800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203840538422038264e+01,1.914900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.203931447512039199e+01,1.915000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204022356602040134e+01,1.915099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204113265692041068e+01,1.915200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204204174782042003e+01,1.915300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204295083872042937e+01,1.915399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204385992962043872e+01,1.915500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204476902052044807e+01,1.915600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204567811142045741e+01,1.915699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204658720232046676e+01,1.915800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204749629322047610e+01,1.915900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204840538412048545e+01,1.915999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.204931447502049480e+01,1.916100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205022356592050414e+01,1.916200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205113265682051349e+01,1.916299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205204174772052284e+01,1.916400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205295083862053218e+01,1.916500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205385992952054153e+01,1.916599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205476902042055087e+01,1.916700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205567811132056022e+01,1.916800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205658720222056957e+01,1.916899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205749629312057891e+01,1.917000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205840538402058826e+01,1.917100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.205931447492059760e+01,1.917199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206022356582060695e+01,1.917300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206113265672061630e+01,1.917400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206204174762062564e+01,1.917500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206295083852063499e+01,1.917599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206385992942064433e+01,1.917700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206476902032065368e+01,1.917800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206567811122066303e+01,1.917899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206658720212067237e+01,1.918000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206749629302068172e+01,1.918100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206840538392069107e+01,1.918199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.206931447482070041e+01,1.918300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207022356572070976e+01,1.918400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207113265662071910e+01,1.918499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207204174752072845e+01,1.918600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207295083842073780e+01,1.918700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207385992932074714e+01,1.918799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207476902022075649e+01,1.918900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207567811112076583e+01,1.919000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207658720202077518e+01,1.919099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207749629292078453e+01,1.919200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207840538382079387e+01,1.919300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.207931447472080322e+01,1.919399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208022356562081256e+01,1.919500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208113265652082191e+01,1.919600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208204174742083126e+01,1.919699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208295083832084060e+01,1.919800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208385992922084995e+01,1.919900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208476902012085930e+01,1.920000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208567811102086864e+01,1.920099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208658720192087799e+01,1.920200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208749629282088733e+01,1.920300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208840538372089668e+01,1.920399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.208931447462090603e+01,1.920500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209022356552091537e+01,1.920600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209113265642092472e+01,1.920699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209204174732093406e+01,1.920800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209295083822094341e+01,1.920900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209385992912095276e+01,1.920999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209476902002096210e+01,1.921100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209567811092097145e+01,1.921200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209658720182098079e+01,1.921299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209749629272099014e+01,1.921400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209840538362099949e+01,1.921500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.209931447452100883e+01,1.921599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210022356542101818e+01,1.921700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210113265632102753e+01,1.921800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210204174722103687e+01,1.921899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210295083812104622e+01,1.922000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210385992902105556e+01,1.922100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210476901992106491e+01,1.922199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210567811082107426e+01,1.922300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210658720172108360e+01,1.922400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210749629262109295e+01,1.922500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210840538352110229e+01,1.922599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.210931447442111164e+01,1.922700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211022356532112099e+01,1.922800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211113265622113033e+01,1.922899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211204174712113968e+01,1.923000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211295083802114902e+01,1.923100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211385992892115837e+01,1.923199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211476901982116772e+01,1.923300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211567811072117706e+01,1.923400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211658720162118641e+01,1.923499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211749629252119576e+01,1.923600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211840538342120510e+01,1.923700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.211931447432121445e+01,1.923799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212022356522122379e+01,1.923900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212113265612123314e+01,1.924000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212204174702124249e+01,1.924099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212295083792125183e+01,1.924200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212385992882126118e+01,1.924300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212476901972127052e+01,1.924399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212567811062127987e+01,1.924500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212658720152128922e+01,1.924600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212749629242129856e+01,1.924699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212840538332130791e+01,1.924800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.212931447422131725e+01,1.924900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213022356512132660e+01,1.925000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213113265602133595e+01,1.925099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213204174692134529e+01,1.925200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213295083782135464e+01,1.925300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213385992872136399e+01,1.925399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213476901962137333e+01,1.925500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213567811052138268e+01,1.925600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213658720142139202e+01,1.925699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213749629232140137e+01,1.925800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213840538322141072e+01,1.925900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.213931447412142006e+01,1.925999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214022356502142941e+01,1.926100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214113265592143875e+01,1.926200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214204174682144810e+01,1.926299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214295083772145745e+01,1.926400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214385992862146679e+01,1.926500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214476901952147614e+01,1.926599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214567811042148548e+01,1.926700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214658720132149483e+01,1.926800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214749629222150418e+01,1.926899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214840538312151352e+01,1.927000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.214931447402152287e+01,1.927100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215022356492153222e+01,1.927199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215113265582154156e+01,1.927300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215204174672155091e+01,1.927400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215295083762156025e+01,1.927500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215385992852156960e+01,1.927599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215476901942157895e+01,1.927700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215567811032158829e+01,1.927800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215658720122159764e+01,1.927899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215749629212160698e+01,1.928000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215840538302161633e+01,1.928100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.215931447392162568e+01,1.928199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216022356482163502e+01,1.928300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216113265572164437e+01,1.928400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216204174662165372e+01,1.928499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216295083752166306e+01,1.928600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216385992842167241e+01,1.928700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216476901932168175e+01,1.928799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216567811022169110e+01,1.928900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216658720112170045e+01,1.929000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216749629202170979e+01,1.929099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216840538292171914e+01,1.929200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.216931447382172848e+01,1.929300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217022356472173783e+01,1.929399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217113265562174718e+01,1.929500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217204174652175652e+01,1.929600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217295083742176587e+01,1.929699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217385992832177521e+01,1.929800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217476901922178456e+01,1.929900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217567811012179391e+01,1.930000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217658720102180325e+01,1.930099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217749629192181260e+01,1.930200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217840538282182195e+01,1.930300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.217931447372183129e+01,1.930399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218022356462184064e+01,1.930500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218113265552184998e+01,1.930600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218204174642185933e+01,1.930699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218295083732186868e+01,1.930800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218385992822187802e+01,1.930900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218476901912188737e+01,1.930999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218567811002189671e+01,1.931100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218658720092190606e+01,1.931200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218749629182191541e+01,1.931299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218840538272192475e+01,1.931400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.218931447362193410e+01,1.931500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219022356452194344e+01,1.931599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219113265542195279e+01,1.931700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219204174632196214e+01,1.931800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219295083722197148e+01,1.931899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219385992812198083e+01,1.932000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219476901902199018e+01,1.932100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219567810992199952e+01,1.932199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219658720082200887e+01,1.932300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219749629172201821e+01,1.932400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219840538262202756e+01,1.932500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.219931447352203691e+01,1.932599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220022356442204625e+01,1.932700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220113265532205560e+01,1.932800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220204174622206494e+01,1.932899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220295083712207429e+01,1.933000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220385992802208364e+01,1.933100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220476901892209298e+01,1.933199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220567810982210233e+01,1.933300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220658720072211167e+01,1.933400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220749629162212102e+01,1.933499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220840538252213037e+01,1.933600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.220931447342213971e+01,1.933700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221022356432214906e+01,1.933799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221113265522215841e+01,1.933900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221204174612216775e+01,1.934000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221295083702217710e+01,1.934099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221385992792218644e+01,1.934200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221476901882219579e+01,1.934300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221567810972220514e+01,1.934399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221658720062221448e+01,1.934500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221749629152222383e+01,1.934600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221840538242223317e+01,1.934699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.221931447332224252e+01,1.934800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222022356422225187e+01,1.934900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222113265512226121e+01,1.935000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222204174602227056e+01,1.935099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222295083692227990e+01,1.935200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222385992782228925e+01,1.935300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222476901872229860e+01,1.935399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222567810962230794e+01,1.935500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222658720052231729e+01,1.935600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222749629142232664e+01,1.935699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222840538232233598e+01,1.935800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.222931447322234533e+01,1.935900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223022356412235467e+01,1.935999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223113265502236402e+01,1.936100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223204174592237337e+01,1.936200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223295083682238271e+01,1.936299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223385992772239206e+01,1.936400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223476901862240140e+01,1.936500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223567810952241075e+01,1.936599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223658720042242010e+01,1.936700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223749629132242944e+01,1.936800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223840538222243879e+01,1.936899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.223931447312244813e+01,1.937000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224022356402245748e+01,1.937100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224113265492246683e+01,1.937199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224204174582247617e+01,1.937300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224295083672248552e+01,1.937400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224385992762249487e+01,1.937500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224476901852250421e+01,1.937599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224567810942251356e+01,1.937700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224658720032252290e+01,1.937800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224749629122253225e+01,1.937899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224840538212254160e+01,1.938000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.224931447302255094e+01,1.938100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225022356392256029e+01,1.938199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225113265482256963e+01,1.938300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225204174572257898e+01,1.938400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225295083662258833e+01,1.938499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225385992752259767e+01,1.938600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225476901842260702e+01,1.938700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225567810932261636e+01,1.938799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225658720022262571e+01,1.938900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225749629112263506e+01,1.939000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225840538202264440e+01,1.939099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.225931447292265375e+01,1.939200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226022356382266310e+01,1.939300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226113265472267244e+01,1.939399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226204174562268179e+01,1.939500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226295083652269113e+01,1.939600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226385992742270048e+01,1.939699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226476901832270983e+01,1.939800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226567810922271917e+01,1.939900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226658720012272852e+01,1.940000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226749629102273786e+01,1.940099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226840538192274721e+01,1.940200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.226931447282275656e+01,1.940300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227022356372276590e+01,1.940399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227113265462277525e+01,1.940500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227204174552278459e+01,1.940600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227295083642279394e+01,1.940699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227385992732280329e+01,1.940800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227476901822281263e+01,1.940900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227567810912282198e+01,1.940999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227658720002283133e+01,1.941100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227749629092284067e+01,1.941200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227840538182285002e+01,1.941299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.227931447272285936e+01,1.941400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228022356362286871e+01,1.941500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228113265452287806e+01,1.941599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228204174542288740e+01,1.941700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228295083632289675e+01,1.941800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228385992722290609e+01,1.941899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228476901812291544e+01,1.942000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228567810902292479e+01,1.942100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228658719992293413e+01,1.942199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228749629082294348e+01,1.942300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228840538172295282e+01,1.942400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.228931447262296217e+01,1.942500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229022356352297152e+01,1.942599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229113265442298086e+01,1.942700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229204174532299021e+01,1.942800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229295083622299956e+01,1.942899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229385992712300890e+01,1.943000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229476901802301825e+01,1.943100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229567810892302759e+01,1.943199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229658719982303694e+01,1.943300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229749629072304629e+01,1.943400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229840538162305563e+01,1.943499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.229931447252306498e+01,1.943600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230022356342307432e+01,1.943700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230113265432308367e+01,1.943799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230204174522309302e+01,1.943900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230295083612310236e+01,1.944000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230385992702311171e+01,1.944099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230476901792312105e+01,1.944200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230567810882313040e+01,1.944300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230658719972313975e+01,1.944399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230749629062314909e+01,1.944500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230840538152315844e+01,1.944600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.230931447242316779e+01,1.944699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231022356332317713e+01,1.944800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231113265422318648e+01,1.944900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231204174512319582e+01,1.945000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231295083602320517e+01,1.945099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231385992692321452e+01,1.945200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231476901782322386e+01,1.945300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231567810872323321e+01,1.945399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231658719962324255e+01,1.945500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231749629052325190e+01,1.945600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231840538142326125e+01,1.945699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.231931447232327059e+01,1.945800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232022356322327994e+01,1.945900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232113265412328929e+01,1.945999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232204174502329863e+01,1.946100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232295083592330798e+01,1.946200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232385992682331732e+01,1.946299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232476901772332667e+01,1.946400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232567810862333602e+01,1.946500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232658719952334536e+01,1.946599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232749629042335471e+01,1.946700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232840538132336405e+01,1.946800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.232931447222337340e+01,1.946899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233022356312338275e+01,1.947000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233113265402339209e+01,1.947100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233204174492340144e+01,1.947199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233295083582341078e+01,1.947300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233385992672342013e+01,1.947400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233476901762342948e+01,1.947500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233567810852343882e+01,1.947599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233658719942344817e+01,1.947700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233749629032345752e+01,1.947800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233840538122346686e+01,1.947899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.233931447212347621e+01,1.948000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234022356302348555e+01,1.948100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234113265392349490e+01,1.948199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234204174482350425e+01,1.948300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234295083572351359e+01,1.948400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234385992662352294e+01,1.948499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234476901752353228e+01,1.948600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234567810842354163e+01,1.948700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234658719932355098e+01,1.948799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234749629022356032e+01,1.948900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234840538112356967e+01,1.949000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.234931447202357901e+01,1.949099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235022356292358836e+01,1.949200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235113265382359771e+01,1.949300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235204174472360705e+01,1.949399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235295083562361640e+01,1.949500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235385992652362575e+01,1.949600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235476901742363509e+01,1.949699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235567810832364444e+01,1.949800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235658719922365378e+01,1.949900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235749629012366313e+01,1.950000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235840538102367248e+01,1.950099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.235931447192368182e+01,1.950200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236022356282369117e+01,1.950300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236113265372370051e+01,1.950399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236204174462370986e+01,1.950500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236295083552371921e+01,1.950600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236385992642372855e+01,1.950699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236476901732373790e+01,1.950800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236567810822374724e+01,1.950900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236658719912375659e+01,1.950999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236749629002376594e+01,1.951100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236840538092377528e+01,1.951200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.236931447182378463e+01,1.951299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237022356272379398e+01,1.951400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237113265362380332e+01,1.951500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237204174452381267e+01,1.951599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237295083542382201e+01,1.951700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237385992632383136e+01,1.951800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237476901722384071e+01,1.951899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237567810812385005e+01,1.952000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237658719902385940e+01,1.952100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237749628992386874e+01,1.952199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237840538082387809e+01,1.952300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.237931447172388744e+01,1.952400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238022356262389678e+01,1.952500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238113265352390613e+01,1.952599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238204174442391547e+01,1.952700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238295083532392482e+01,1.952800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238385992622393417e+01,1.952899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238476901712394351e+01,1.953000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238567810802395286e+01,1.953100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238658719892396221e+01,1.953199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238749628982397155e+01,1.953300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238840538072398090e+01,1.953400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.238931447162399024e+01,1.953499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239022356252399959e+01,1.953600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239113265342400894e+01,1.953700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239204174432401828e+01,1.953799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239295083522402763e+01,1.953900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239385992612403697e+01,1.954000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239476901702404632e+01,1.954099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239567810792405567e+01,1.954200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239658719882406501e+01,1.954300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239749628972407436e+01,1.954399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239840538062408370e+01,1.954500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.239931447152409305e+01,1.954600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240022356242410240e+01,1.954699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240113265332411174e+01,1.954800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240204174422412109e+01,1.954900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240295083512413044e+01,1.955000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240385992602413978e+01,1.955099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240476901692414913e+01,1.955200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240567810782415847e+01,1.955300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240658719872416782e+01,1.955399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240749628962417717e+01,1.955500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240840538052418651e+01,1.955600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.240931447142419586e+01,1.955699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241022356232420520e+01,1.955800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241113265322421455e+01,1.955900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241204174412422390e+01,1.955999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241295083502423324e+01,1.956100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241385992592424259e+01,1.956200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241476901682425193e+01,1.956299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241567810772426128e+01,1.956400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241658719862427063e+01,1.956500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241749628952427997e+01,1.956599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241840538042428932e+01,1.956700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.241931447132429867e+01,1.956800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242022356222430801e+01,1.956899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242113265312431736e+01,1.957000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242204174402432670e+01,1.957100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242295083492433605e+01,1.957199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242385992582434540e+01,1.957300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242476901672435474e+01,1.957400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242567810762436409e+01,1.957500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242658719852437343e+01,1.957599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242749628942438278e+01,1.957700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242840538032439213e+01,1.957800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.242931447122440147e+01,1.957899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243022356212441082e+01,1.958000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243113265302442016e+01,1.958100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243204174392442951e+01,1.958199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243295083482443886e+01,1.958300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243385992572444820e+01,1.958400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243476901662445755e+01,1.958499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243567810752446690e+01,1.958600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243658719842447624e+01,1.958700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243749628932448559e+01,1.958799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243840538022449493e+01,1.958900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.243931447112450428e+01,1.959000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244022356202451363e+01,1.959099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244113265292452297e+01,1.959200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244204174382453232e+01,1.959300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244295083472454166e+01,1.959399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244385992562455101e+01,1.959500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244476901652456036e+01,1.959600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244567810742456970e+01,1.959699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244658719832457905e+01,1.959800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244749628922458839e+01,1.959900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244840538012459774e+01,1.960000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.244931447102460709e+01,1.960099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245022356192461643e+01,1.960200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245113265282462578e+01,1.960300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245204174372463513e+01,1.960399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245295083462464447e+01,1.960500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245385992552465382e+01,1.960600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245476901642466316e+01,1.960699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245567810732467251e+01,1.960800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245658719822468186e+01,1.960900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245749628912469120e+01,1.960999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245840538002470055e+01,1.961100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.245931447092470989e+01,1.961200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246022356182471924e+01,1.961299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246113265272472859e+01,1.961400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246204174362473793e+01,1.961500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246295083452474728e+01,1.961599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246385992542475663e+01,1.961700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246476901632476597e+01,1.961800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246567810722477532e+01,1.961899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246658719812478466e+01,1.962000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246749628902479401e+01,1.962100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246840537992480336e+01,1.962199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.246931447082481270e+01,1.962300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247022356172482205e+01,1.962400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247113265262483139e+01,1.962500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247204174352484074e+01,1.962599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247295083442485009e+01,1.962700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247385992532485943e+01,1.962800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247476901622486878e+01,1.962899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247567810712487812e+01,1.963000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247658719802488747e+01,1.963100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247749628892489682e+01,1.963199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247840537982490616e+01,1.963300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.247931447072491551e+01,1.963400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248022356162492486e+01,1.963499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248113265252493420e+01,1.963600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248204174342494355e+01,1.963700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248295083432495289e+01,1.963799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248385992522496224e+01,1.963900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248476901612497159e+01,1.964000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248567810702498093e+01,1.964099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248658719792499028e+01,1.964200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248749628882499962e+01,1.964300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248840537972500897e+01,1.964399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.248931447062501832e+01,1.964500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249022356152502766e+01,1.964600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249113265242503701e+01,1.964699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249204174332504635e+01,1.964800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249295083422505570e+01,1.964900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249385992512506505e+01,1.965000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249476901602507439e+01,1.965099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249567810692508374e+01,1.965200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249658719782509309e+01,1.965300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249749628872510243e+01,1.965399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249840537962511178e+01,1.965500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.249931447052512112e+01,1.965600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250022356142513047e+01,1.965699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250113265232513982e+01,1.965800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250204174322514916e+01,1.965900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250295083412515851e+01,1.965999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250385992502516785e+01,1.966100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250476901592517720e+01,1.966200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250567810682518655e+01,1.966299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250658719772519589e+01,1.966400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250749628862520524e+01,1.966500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250840537952521458e+01,1.966599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.250931447042522393e+01,1.966700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251022356132523328e+01,1.966800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251113265222524262e+01,1.966899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251204174312525197e+01,1.967000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251295083402526132e+01,1.967100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251385992492527066e+01,1.967199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251476901582528001e+01,1.967300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251567810672528935e+01,1.967400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251658719762529870e+01,1.967500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251749628852530805e+01,1.967599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251840537942531739e+01,1.967700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.251931447032532674e+01,1.967800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252022356122533608e+01,1.967899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252113265212534543e+01,1.968000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252204174302535478e+01,1.968100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252295083392536412e+01,1.968199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252385992482537347e+01,1.968300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252476901572538281e+01,1.968400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252567810662539216e+01,1.968499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252658719752540151e+01,1.968600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252749628842541085e+01,1.968700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252840537932542020e+01,1.968799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.252931447022542955e+01,1.968900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253022356112543889e+01,1.969000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253113265202544824e+01,1.969099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253204174292545758e+01,1.969200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253295083382546693e+01,1.969300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253385992472547628e+01,1.969399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253476901562548562e+01,1.969500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253567810652549497e+01,1.969600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253658719742550431e+01,1.969699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253749628832551366e+01,1.969800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253840537922552301e+01,1.969900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.253931447012553235e+01,1.970000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254022356102554170e+01,1.970099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254113265192555104e+01,1.970200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254204174282556039e+01,1.970300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254295083372556974e+01,1.970399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254385992462557908e+01,1.970500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254476901552558843e+01,1.970600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254567810642559778e+01,1.970699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254658719732560712e+01,1.970800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254749628822561647e+01,1.970900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254840537912562581e+01,1.970999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.254931447002563516e+01,1.971100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255022356092564451e+01,1.971200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255113265182565385e+01,1.971299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255204174272566320e+01,1.971400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255295083362567254e+01,1.971500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255385992452568189e+01,1.971599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255476901542569124e+01,1.971700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255567810632570058e+01,1.971800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255658719722570993e+01,1.971899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255749628812571927e+01,1.972000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255840537902572862e+01,1.972100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.255931446992573797e+01,1.972199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256022356082574731e+01,1.972300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256113265172575666e+01,1.972400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256204174262576601e+01,1.972500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256295083352577535e+01,1.972599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256385992442578470e+01,1.972700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256476901532579404e+01,1.972800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256567810622580339e+01,1.972899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256658719712581274e+01,1.973000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256749628802582208e+01,1.973100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256840537892583143e+01,1.973199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.256931446982584077e+01,1.973300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257022356072585012e+01,1.973400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257113265162585947e+01,1.973499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257204174252586881e+01,1.973600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257295083342587816e+01,1.973700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257385992432588750e+01,1.973799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257476901522589685e+01,1.973900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257567810612590620e+01,1.974000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257658719702591554e+01,1.974099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257749628792592489e+01,1.974200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257840537882593424e+01,1.974300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.257931446972594358e+01,1.974399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258022356062595293e+01,1.974500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258113265152596227e+01,1.974600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258204174242597162e+01,1.974699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258295083332598097e+01,1.974800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258385992422599031e+01,1.974900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258476901512599966e+01,1.975000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258567810602600900e+01,1.975099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258658719692601835e+01,1.975200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258749628782602770e+01,1.975300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258840537872603704e+01,1.975399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.258931446962604639e+01,1.975500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259022356052605573e+01,1.975600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259113265142606508e+01,1.975699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259204174232607443e+01,1.975800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259295083322608377e+01,1.975900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259385992412609312e+01,1.975999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259476901502610247e+01,1.976100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259567810592611181e+01,1.976200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259658719682612116e+01,1.976299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259749628772613050e+01,1.976400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259840537862613985e+01,1.976500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.259931446952614920e+01,1.976599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260022356042615854e+01,1.976700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260113265132616789e+01,1.976800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260204174222617723e+01,1.976899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260295083312618658e+01,1.977000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260385992402619593e+01,1.977100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260476901492620527e+01,1.977199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260567810582621462e+01,1.977300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260658719672622397e+01,1.977400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260749628762623331e+01,1.977500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260840537852624266e+01,1.977599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.260931446942625200e+01,1.977700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261022356032626135e+01,1.977800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261113265122627070e+01,1.977899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261204174212628004e+01,1.978000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261295083302628939e+01,1.978100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261385992392629873e+01,1.978199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261476901482630808e+01,1.978300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261567810572631743e+01,1.978400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261658719662632677e+01,1.978499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261749628752633612e+01,1.978600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261840537842634546e+01,1.978700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.261931446932635481e+01,1.978799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262022356022636416e+01,1.978900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262113265112637350e+01,1.979000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262204174202638285e+01,1.979099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262295083292639220e+01,1.979200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262385992382640154e+01,1.979300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262476901472641089e+01,1.979399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262567810562642023e+01,1.979500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262658719652642958e+01,1.979600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262749628742643893e+01,1.979699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262840537832644827e+01,1.979800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.262931446922645762e+01,1.979900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263022356012646696e+01,1.980000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263113265102647631e+01,1.980099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263204174192648566e+01,1.980200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263295083282649500e+01,1.980300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263385992372650435e+01,1.980399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263476901462651369e+01,1.980500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263567810552652304e+01,1.980600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263658719642653239e+01,1.980699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263749628732654173e+01,1.980800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263840537822655108e+01,1.980900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.263931446912656043e+01,1.980999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264022356002656977e+01,1.981100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264113265092657912e+01,1.981200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264204174182658846e+01,1.981299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264295083272659781e+01,1.981400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264385992362660716e+01,1.981500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264476901452661650e+01,1.981599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264567810542662585e+01,1.981700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264658719632663519e+01,1.981800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264749628722664454e+01,1.981899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264840537812665389e+01,1.982000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.264931446902666323e+01,1.982100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265022355992667258e+01,1.982199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265113265082668192e+01,1.982300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265204174172669127e+01,1.982400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265295083262670062e+01,1.982500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265385992352670996e+01,1.982599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265476901442671931e+01,1.982700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265567810532672866e+01,1.982800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265658719622673800e+01,1.982899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265749628712674735e+01,1.983000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265840537802675669e+01,1.983100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.265931446892676604e+01,1.983199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266022355982677539e+01,1.983300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266113265072678473e+01,1.983400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266204174162679408e+01,1.983499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266295083252680342e+01,1.983600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266385992342681277e+01,1.983700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266476901432682212e+01,1.983799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266567810522683146e+01,1.983900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266658719612684081e+01,1.984000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266749628702685015e+01,1.984099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266840537792685950e+01,1.984200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.266931446882686885e+01,1.984300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267022355972687819e+01,1.984399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267113265062688754e+01,1.984500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267204174152689689e+01,1.984600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267295083242690623e+01,1.984699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267385992332691558e+01,1.984800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267476901422692492e+01,1.984900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267567810512693427e+01,1.985000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267658719602694362e+01,1.985099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267749628692695296e+01,1.985200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267840537782696231e+01,1.985300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.267931446872697165e+01,1.985399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268022355962698100e+01,1.985500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268113265052699035e+01,1.985600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268204174142699969e+01,1.985699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268295083232700904e+01,1.985800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268385992322701838e+01,1.985900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268476901412702773e+01,1.985999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268567810502703708e+01,1.986100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268658719592704642e+01,1.986200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268749628682705577e+01,1.986299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268840537772706512e+01,1.986400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.268931446862707446e+01,1.986500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269022355952708381e+01,1.986599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269113265042709315e+01,1.986700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269204174132710250e+01,1.986800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269295083222711185e+01,1.986899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269385992312712119e+01,1.987000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269476901402713054e+01,1.987100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269567810492713988e+01,1.987199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269658719582714923e+01,1.987300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269749628672715858e+01,1.987400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269840537762716792e+01,1.987500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.269931446852717727e+01,1.987599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270022355942718661e+01,1.987700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270113265032719596e+01,1.987800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270204174122720531e+01,1.987899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270295083212721465e+01,1.988000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270385992302722400e+01,1.988100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270476901392723335e+01,1.988199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270567810482724269e+01,1.988300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270658719572725204e+01,1.988400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270749628662726138e+01,1.988499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270840537752727073e+01,1.988600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.270931446842728008e+01,1.988700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271022355932728942e+01,1.988799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271113265022729877e+01,1.988900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271204174112730811e+01,1.989000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271295083202731746e+01,1.989099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271385992292732681e+01,1.989200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271476901382733615e+01,1.989300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271567810472734550e+01,1.989399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271658719562735484e+01,1.989500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271749628652736419e+01,1.989600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271840537742737354e+01,1.989699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.271931446832738288e+01,1.989800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272022355922739223e+01,1.989900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272113265012740158e+01,1.990000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272204174102741092e+01,1.990099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272295083192742027e+01,1.990200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272385992282742961e+01,1.990300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272476901372743896e+01,1.990399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272567810462744831e+01,1.990500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272658719552745765e+01,1.990600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272749628642746700e+01,1.990699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272840537732747634e+01,1.990800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.272931446822748569e+01,1.990900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273022355912749504e+01,1.990999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273113265002750438e+01,1.991100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273204174092751373e+01,1.991200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273295083182752307e+01,1.991299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273385992272753242e+01,1.991400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273476901362754177e+01,1.991500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273567810452755111e+01,1.991599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273658719542756046e+01,1.991700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273749628632756981e+01,1.991800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273840537722757915e+01,1.991899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.273931446812758850e+01,1.992000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274022355902759784e+01,1.992100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274113264992760719e+01,1.992199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274204174082761654e+01,1.992300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274295083172762588e+01,1.992400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274385992262763523e+01,1.992500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274476901352764457e+01,1.992599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274567810442765392e+01,1.992700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274658719532766327e+01,1.992800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274749628622767261e+01,1.992899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274840537712768196e+01,1.993000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.274931446802769130e+01,1.993100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275022355892770065e+01,1.993199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275113264982771000e+01,1.993300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275204174072771934e+01,1.993400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275295083162772869e+01,1.993499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275385992252773804e+01,1.993600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275476901342774738e+01,1.993700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275567810432775673e+01,1.993799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275658719522776607e+01,1.993900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275749628612777542e+01,1.994000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275840537702778477e+01,1.994099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.275931446792779411e+01,1.994200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276022355882780346e+01,1.994300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276113264972781280e+01,1.994399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276204174062782215e+01,1.994500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276295083152783150e+01,1.994600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276385992242784084e+01,1.994699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276476901332785019e+01,1.994800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276567810422785954e+01,1.994900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276658719512786888e+01,1.995000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276749628602787823e+01,1.995099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276840537692788757e+01,1.995200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.276931446782789692e+01,1.995300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277022355872790627e+01,1.995399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277113264962791561e+01,1.995500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277204174052792496e+01,1.995600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277295083142793430e+01,1.995699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277385992232794365e+01,1.995800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277476901322795300e+01,1.995900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277567810412796234e+01,1.995999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277658719502797169e+01,1.996100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277749628592798103e+01,1.996200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277840537682799038e+01,1.996299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.277931446772799973e+01,1.996400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278022355862800907e+01,1.996500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278113264952801842e+01,1.996599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278204174042802777e+01,1.996700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278295083132803711e+01,1.996800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278385992222804646e+01,1.996899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278476901312805580e+01,1.997000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278567810402806515e+01,1.997100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278658719492807450e+01,1.997199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278749628582808384e+01,1.997300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278840537672809319e+01,1.997400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.278931446762810253e+01,1.997500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279022355852811188e+01,1.997599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279113264942812123e+01,1.997700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279204174032813057e+01,1.997800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279295083122813992e+01,1.997899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279385992212814926e+01,1.998000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279476901302815861e+01,1.998100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279567810392816796e+01,1.998199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279658719482817730e+01,1.998300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279749628572818665e+01,1.998400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279840537662819600e+01,1.998499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.279931446752820534e+01,1.998600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280022355842821469e+01,1.998700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280113264932822403e+01,1.998799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280204174022823338e+01,1.998900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280295083112824273e+01,1.999000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280385992202825207e+01,1.999099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280476901292826142e+01,1.999200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280567810382827076e+01,1.999300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280658719472828011e+01,1.999399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280749628562828946e+01,1.999500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280840537652829880e+01,1.999600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.280931446742830815e+01,1.999699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281022355832831749e+01,1.999800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281113264922832684e+01,1.999900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281204174012833619e+01,2.000000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281295083102834553e+01,2.000099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281385992192835488e+01,2.000200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281476901282836423e+01,2.000300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281567810372837357e+01,2.000399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281658719462838292e+01,2.000500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281749628552839226e+01,2.000600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281840537642840161e+01,2.000699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.281931446732841096e+01,2.000800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282022355822842030e+01,2.000900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282113264912842965e+01,2.000999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282204174002843899e+01,2.001100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282295083092844834e+01,2.001200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282385992182845769e+01,2.001299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282476901272846703e+01,2.001400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282567810362847638e+01,2.001500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282658719452848572e+01,2.001599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282749628542849507e+01,2.001700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282840537632850442e+01,2.001800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.282931446722851376e+01,2.001899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283022355812852311e+01,2.002000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283113264902853246e+01,2.002100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283204173992854180e+01,2.002199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283295083082855115e+01,2.002300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283385992172856049e+01,2.002400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283476901262856984e+01,2.002500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283567810352857919e+01,2.002599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283658719442858853e+01,2.002700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283749628532859788e+01,2.002800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283840537622860722e+01,2.002899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.283931446712861657e+01,2.003000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284022355802862592e+01,2.003100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284113264892863526e+01,2.003199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284204173982864461e+01,2.003300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284295083072865395e+01,2.003400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284385992162866330e+01,2.003499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284476901252867265e+01,2.003600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284567810342868199e+01,2.003700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284658719432869134e+01,2.003799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284749628522870069e+01,2.003900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284840537612871003e+01,2.004000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.284931446702871938e+01,2.004099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285022355792872872e+01,2.004200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285113264882873807e+01,2.004300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285204173972874742e+01,2.004399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285295083062875676e+01,2.004500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285385992152876611e+01,2.004600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285476901242877545e+01,2.004699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285567810332878480e+01,2.004800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285658719422879415e+01,2.004900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285749628512880349e+01,2.005000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285840537602881284e+01,2.005099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.285931446692882218e+01,2.005200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286022355782883153e+01,2.005300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286113264872884088e+01,2.005399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286204173962885022e+01,2.005500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286295083052885957e+01,2.005600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286385992142886892e+01,2.005699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286476901232887826e+01,2.005800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286567810322888761e+01,2.005900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286658719412889695e+01,2.005999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286749628502890630e+01,2.006100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286840537592891565e+01,2.006200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.286931446682892499e+01,2.006299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287022355772893434e+01,2.006400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287113264862894368e+01,2.006500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287204173952895303e+01,2.006599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287295083042896238e+01,2.006700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287385992132897172e+01,2.006800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287476901222898107e+01,2.006899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287567810312899041e+01,2.007000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287658719402899976e+01,2.007100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287749628492900911e+01,2.007199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287840537582901845e+01,2.007300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.287931446672902780e+01,2.007400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288022355762903715e+01,2.007500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288113264852904649e+01,2.007599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288204173942905584e+01,2.007700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288295083032906518e+01,2.007800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288385992122907453e+01,2.007899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288476901212908388e+01,2.008000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288567810302909322e+01,2.008100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288658719392910257e+01,2.008199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288749628482911191e+01,2.008300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288840537572912126e+01,2.008400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.288931446662913061e+01,2.008499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289022355752913995e+01,2.008600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289113264842914930e+01,2.008700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289204173932915864e+01,2.008799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289295083022916799e+01,2.008900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289385992112917734e+01,2.009000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289476901202918668e+01,2.009099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289567810292919603e+01,2.009200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289658719382920538e+01,2.009300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289749628472921472e+01,2.009399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289840537562922407e+01,2.009500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.289931446652923341e+01,2.009600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290022355742924276e+01,2.009699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290113264832925211e+01,2.009800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290204173922926145e+01,2.009900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290295083012927080e+01,2.010000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290385992102928014e+01,2.010099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290476901192928949e+01,2.010200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290567810282929884e+01,2.010300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290658719372930818e+01,2.010399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290749628462931753e+01,2.010500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290840537552932688e+01,2.010600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.290931446642933622e+01,2.010699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291022355732934557e+01,2.010800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291113264822935491e+01,2.010900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291204173912936426e+01,2.010999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291295083002937361e+01,2.011100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291385992092938295e+01,2.011200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291476901182939230e+01,2.011299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291567810272940164e+01,2.011400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291658719362941099e+01,2.011500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291749628452942034e+01,2.011599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291840537542942968e+01,2.011700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.291931446632943903e+01,2.011800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292022355722944837e+01,2.011899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292113264812945772e+01,2.012000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292204173902946707e+01,2.012100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292295082992947641e+01,2.012199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292385992082948576e+01,2.012300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292476901172949511e+01,2.012400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292567810262950445e+01,2.012500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292658719352951380e+01,2.012599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292749628442952314e+01,2.012700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292840537532953249e+01,2.012800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.292931446622954184e+01,2.012899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293022355712955118e+01,2.013000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293113264802956053e+01,2.013100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293204173892956987e+01,2.013199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293295082982957922e+01,2.013300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293385992072958857e+01,2.013400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293476901162959791e+01,2.013499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293567810252960726e+01,2.013600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293658719342961660e+01,2.013700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293749628432962595e+01,2.013799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293840537522963530e+01,2.013900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.293931446612964464e+01,2.014000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294022355702965399e+01,2.014099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294113264792966334e+01,2.014200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294204173882967268e+01,2.014300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294295082972968203e+01,2.014399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294385992062969137e+01,2.014500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294476901152970072e+01,2.014600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294567810242971007e+01,2.014699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294658719332971941e+01,2.014800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294749628422972876e+01,2.014900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294840537512973810e+01,2.015000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.294931446602974745e+01,2.015099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295022355692975680e+01,2.015200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295113264782976614e+01,2.015300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295204173872977549e+01,2.015399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295295082962978483e+01,2.015500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295385992052979418e+01,2.015600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295476901142980353e+01,2.015699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295567810232981287e+01,2.015800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295658719322982222e+01,2.015900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295749628412983157e+01,2.015999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295840537502984091e+01,2.016100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.295931446592985026e+01,2.016200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296022355682985960e+01,2.016299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296113264772986895e+01,2.016400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296204173862987830e+01,2.016500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296295082952988764e+01,2.016599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296385992042989699e+01,2.016700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296476901132990633e+01,2.016800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296567810222991568e+01,2.016899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296658719312992503e+01,2.017000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296749628402993437e+01,2.017100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296840537492994372e+01,2.017199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.296931446582995306e+01,2.017300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297022355672996241e+01,2.017400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297113264762997176e+01,2.017500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297204173852998110e+01,2.017599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297295082942999045e+01,2.017700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297385992032999980e+01,2.017800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297476901123000914e+01,2.017899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297567810213001849e+01,2.018000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297658719303002783e+01,2.018100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297749628393003718e+01,2.018199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297840537483004653e+01,2.018300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.297931446573005587e+01,2.018400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298022355663006522e+01,2.018499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298113264753007456e+01,2.018600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298204173843008391e+01,2.018700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298295082933009326e+01,2.018799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298385992023010260e+01,2.018900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298476901113011195e+01,2.019000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298567810203012129e+01,2.019099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298658719293013064e+01,2.019200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298749628383013999e+01,2.019300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298840537473014933e+01,2.019399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.298931446563015868e+01,2.019500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299022355653016803e+01,2.019600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299113264743017737e+01,2.019699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299204173833018672e+01,2.019800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299295082923019606e+01,2.019900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299385992013020541e+01,2.020000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299476901103021476e+01,2.020099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299567810193022410e+01,2.020200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299658719283023345e+01,2.020300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299749628373024279e+01,2.020399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299840537463025214e+01,2.020500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.299931446553026149e+01,2.020600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300022355643027083e+01,2.020699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300113264733028018e+01,2.020800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300204173823028952e+01,2.020900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300295082913029887e+01,2.020999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300385992003030822e+01,2.021100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300476901093031756e+01,2.021200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300567810183032691e+01,2.021299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300658719273033626e+01,2.021400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300749628363034560e+01,2.021500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300840537453035495e+01,2.021599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.300931446543036429e+01,2.021700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301022355633037364e+01,2.021800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301113264723038299e+01,2.021899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301204173813039233e+01,2.022000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301295082903040168e+01,2.022100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301385991993041102e+01,2.022199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301476901083042037e+01,2.022300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301567810173042972e+01,2.022400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301658719263043906e+01,2.022500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301749628353044841e+01,2.022599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301840537443045775e+01,2.022700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.301931446533046710e+01,2.022800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302022355623047645e+01,2.022899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302113264713048579e+01,2.023000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302204173803049514e+01,2.023100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302295082893050449e+01,2.023199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302385991983051383e+01,2.023300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302476901073052318e+01,2.023400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302567810163053252e+01,2.023499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302658719253054187e+01,2.023600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302749628343055122e+01,2.023700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302840537433056056e+01,2.023799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.302931446523056991e+01,2.023900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303022355613057925e+01,2.024000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303113264703058860e+01,2.024099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303204173793059795e+01,2.024200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303295082883060729e+01,2.024300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303385991973061664e+01,2.024399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303476901063062598e+01,2.024500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303567810153063533e+01,2.024600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303658719243064468e+01,2.024699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303749628333065402e+01,2.024800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303840537423066337e+01,2.024900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.303931446513067272e+01,2.025000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304022355603068206e+01,2.025099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304113264693069141e+01,2.025200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304204173783070075e+01,2.025300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304295082873071010e+01,2.025399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304385991963071945e+01,2.025500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304476901053072879e+01,2.025600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304567810143073814e+01,2.025699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304658719233074748e+01,2.025800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304749628323075683e+01,2.025900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304840537413076618e+01,2.025999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.304931446503077552e+01,2.026100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305022355593078487e+01,2.026200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305113264683079422e+01,2.026299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305204173773080356e+01,2.026400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305295082863081291e+01,2.026500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305385991953082225e+01,2.026599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305476901043083160e+01,2.026700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305567810133084095e+01,2.026800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305658719223085029e+01,2.026899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305749628313085964e+01,2.027000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305840537403086898e+01,2.027100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.305931446493087833e+01,2.027199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306022355583088768e+01,2.027300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306113264673089702e+01,2.027400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306204173763090637e+01,2.027500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306295082853091571e+01,2.027599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306385991943092506e+01,2.027700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306476901033093441e+01,2.027800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306567810123094375e+01,2.027899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306658719213095310e+01,2.028000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306749628303096245e+01,2.028100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306840537393097179e+01,2.028199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.306931446483098114e+01,2.028300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307022355573099048e+01,2.028400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307113264663099983e+01,2.028499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307204173753100918e+01,2.028600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307295082843101852e+01,2.028700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307385991933102787e+01,2.028799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307476901023103721e+01,2.028900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307567810113104656e+01,2.029000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307658719203105591e+01,2.029099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307749628293106525e+01,2.029200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307840537383107460e+01,2.029300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.307931446473108394e+01,2.029399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308022355563109329e+01,2.029500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308113264653110264e+01,2.029600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308204173743111198e+01,2.029699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308295082833112133e+01,2.029800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308385991923113068e+01,2.029900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308476901013114002e+01,2.030000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308567810103114937e+01,2.030099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308658719193115871e+01,2.030200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308749628283116806e+01,2.030300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308840537373117741e+01,2.030399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.308931446463118675e+01,2.030500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309022355553119610e+01,2.030600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309113264643120544e+01,2.030699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309204173733121479e+01,2.030800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309295082823122414e+01,2.030900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309385991913123348e+01,2.030999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309476901003124283e+01,2.031100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309567810093125217e+01,2.031200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309658719183126152e+01,2.031299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309749628273127087e+01,2.031400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309840537363128021e+01,2.031500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.309931446453128956e+01,2.031599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310022355543129891e+01,2.031700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310113264633130825e+01,2.031800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310204173723131760e+01,2.031899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310295082813132694e+01,2.032000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310385991903133629e+01,2.032100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310476900993134564e+01,2.032199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310567810083135498e+01,2.032300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310658719173136433e+01,2.032400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310749628263137367e+01,2.032500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310840537353138302e+01,2.032599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.310931446443139237e+01,2.032700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311022355533140171e+01,2.032800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311113264623141106e+01,2.032899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311204173713142040e+01,2.033000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311295082803142975e+01,2.033100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311385991893143910e+01,2.033199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311476900983144844e+01,2.033300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311567810073145779e+01,2.033400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311658719163146714e+01,2.033499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311749628253147648e+01,2.033600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311840537343148583e+01,2.033700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.311931446433149517e+01,2.033799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312022355523150452e+01,2.033900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312113264613151387e+01,2.034000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312204173703152321e+01,2.034099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312295082793153256e+01,2.034200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312385991883154190e+01,2.034300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312476900973155125e+01,2.034399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312567810063156060e+01,2.034500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312658719153156994e+01,2.034600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312749628243157929e+01,2.034699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312840537333158863e+01,2.034800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.312931446423159798e+01,2.034900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313022355513160733e+01,2.035000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313113264603161667e+01,2.035099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313204173693162602e+01,2.035200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313295082783163537e+01,2.035300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313385991873164471e+01,2.035399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313476900963165406e+01,2.035500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313567810053166340e+01,2.035600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313658719143167275e+01,2.035699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313749628233168210e+01,2.035800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313840537323169144e+01,2.035900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.313931446413170079e+01,2.035999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314022355503171013e+01,2.036100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314113264593171948e+01,2.036200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314204173683172883e+01,2.036299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314295082773173817e+01,2.036400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314385991863174752e+01,2.036500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314476900953175686e+01,2.036599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314567810043176621e+01,2.036700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314658719133177556e+01,2.036800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314749628223178490e+01,2.036899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314840537313179425e+01,2.037000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.314931446403180360e+01,2.037100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315022355493181294e+01,2.037199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315113264583182229e+01,2.037300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315204173673183163e+01,2.037400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315295082763184098e+01,2.037500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315385991853185033e+01,2.037599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315476900943185967e+01,2.037700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315567810033186902e+01,2.037800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315658719123187836e+01,2.037899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315749628213188771e+01,2.038000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315840537303189706e+01,2.038100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.315931446393190640e+01,2.038199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316022355483191575e+01,2.038300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316113264573192509e+01,2.038400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316204173663193444e+01,2.038499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316295082753194379e+01,2.038600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316385991843195313e+01,2.038700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316476900933196248e+01,2.038799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316567810023197183e+01,2.038900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316658719113198117e+01,2.039000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316749628203199052e+01,2.039099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316840537293199986e+01,2.039200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.316931446383200921e+01,2.039300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317022355473201856e+01,2.039399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317113264563202790e+01,2.039500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317204173653203725e+01,2.039600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317295082743204659e+01,2.039699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317385991833205594e+01,2.039800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317476900923206529e+01,2.039900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317567810013207463e+01,2.040000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317658719103208398e+01,2.040099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317749628193209332e+01,2.040200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317840537283210267e+01,2.040300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.317931446373211202e+01,2.040399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318022355463212136e+01,2.040500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318113264553213071e+01,2.040600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318204173643214006e+01,2.040699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318295082733214940e+01,2.040800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318385991823215875e+01,2.040900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318476900913216809e+01,2.040999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318567810003217744e+01,2.041100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318658719093218679e+01,2.041200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318749628183219613e+01,2.041299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318840537273220548e+01,2.041400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.318931446363221482e+01,2.041500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319022355453222417e+01,2.041599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319113264543223352e+01,2.041700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319204173633224286e+01,2.041800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319295082723225221e+01,2.041899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319385991813226156e+01,2.042000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319476900903227090e+01,2.042100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319567809993228025e+01,2.042199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319658719083228959e+01,2.042300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319749628173229894e+01,2.042400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319840537263230829e+01,2.042500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.319931446353231763e+01,2.042599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320022355443232698e+01,2.042700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320113264533233632e+01,2.042800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320204173623234567e+01,2.042899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320295082713235502e+01,2.043000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320385991803236436e+01,2.043100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320476900893237371e+01,2.043199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320567809983238305e+01,2.043300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320658719073239240e+01,2.043400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320749628163240175e+01,2.043499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320840537253241109e+01,2.043600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.320931446343242044e+01,2.043700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321022355433242979e+01,2.043799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321113264523243913e+01,2.043900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321204173613244848e+01,2.044000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321295082703245782e+01,2.044099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321385991793246717e+01,2.044200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321476900883247652e+01,2.044300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321567809973248586e+01,2.044399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321658719063249521e+01,2.044500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321749628153250455e+01,2.044600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321840537243251390e+01,2.044699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.321931446333252325e+01,2.044800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322022355423253259e+01,2.044900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322113264513254194e+01,2.045000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322204173603255128e+01,2.045099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322295082693256063e+01,2.045200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322385991783256998e+01,2.045300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322476900873257932e+01,2.045399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322567809963258867e+01,2.045500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322658719053259802e+01,2.045600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322749628143260736e+01,2.045699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322840537233261671e+01,2.045800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.322931446323262605e+01,2.045900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323022355413263540e+01,2.045999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323113264503264475e+01,2.046100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323204173593265409e+01,2.046200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323295082683266344e+01,2.046299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323385991773267278e+01,2.046400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323476900863268213e+01,2.046500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323567809953269148e+01,2.046599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323658719043270082e+01,2.046700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323749628133271017e+01,2.046800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323840537223271951e+01,2.046899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.323931446313272886e+01,2.047000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324022355403273821e+01,2.047100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324113264493274755e+01,2.047199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324204173583275690e+01,2.047300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324295082673276625e+01,2.047400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324385991763277559e+01,2.047500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324476900853278494e+01,2.047599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324567809943279428e+01,2.047700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324658719033280363e+01,2.047800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324749628123281298e+01,2.047899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324840537213282232e+01,2.048000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.324931446303283167e+01,2.048100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325022355393284101e+01,2.048199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325113264483285036e+01,2.048300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325204173573285971e+01,2.048400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325295082663286905e+01,2.048499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325385991753287840e+01,2.048600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325476900843288774e+01,2.048700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325567809933289709e+01,2.048799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325658719023290644e+01,2.048900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325749628113291578e+01,2.049000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325840537203292513e+01,2.049099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.325931446293293448e+01,2.049200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326022355383294382e+01,2.049300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326113264473295317e+01,2.049399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326204173563296251e+01,2.049500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326295082653297186e+01,2.049600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326385991743298121e+01,2.049699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326476900833299055e+01,2.049800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326567809923299990e+01,2.049900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326658719013300924e+01,2.050000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326749628103301859e+01,2.050099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326840537193302794e+01,2.050200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.326931446283303728e+01,2.050300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327022355373304663e+01,2.050399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327113264463305597e+01,2.050500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327204173553306532e+01,2.050600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327295082643307467e+01,2.050699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327385991733308401e+01,2.050800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327476900823309336e+01,2.050900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327567809913310271e+01,2.050999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327658719003311205e+01,2.051100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327749628093312140e+01,2.051200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327840537183313074e+01,2.051299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.327931446273314009e+01,2.051400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328022355363314944e+01,2.051500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328113264453315878e+01,2.051599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328204173543316813e+01,2.051700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328295082633317747e+01,2.051800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328385991723318682e+01,2.051899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328476900813319617e+01,2.052000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328567809903320551e+01,2.052100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328658718993321486e+01,2.052199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328749628083322420e+01,2.052300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328840537173323355e+01,2.052400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.328931446263324290e+01,2.052500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329022355353325224e+01,2.052599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329113264443326159e+01,2.052700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329204173533327094e+01,2.052800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329295082623328028e+01,2.052899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329385991713328963e+01,2.053000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329476900803329897e+01,2.053100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329567809893330832e+01,2.053199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329658718983331767e+01,2.053300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329749628073332701e+01,2.053400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329840537163333636e+01,2.053499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.329931446253334570e+01,2.053600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330022355343335505e+01,2.053700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330113264433336440e+01,2.053799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330204173523337374e+01,2.053900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330295082613338309e+01,2.054000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330385991703339243e+01,2.054099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330476900793340178e+01,2.054200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330567809883341113e+01,2.054300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330658718973342047e+01,2.054399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330749628063342982e+01,2.054500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330840537153343917e+01,2.054600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.330931446243344851e+01,2.054699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331022355333345786e+01,2.054800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331113264423346720e+01,2.054900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331204173513347655e+01,2.055000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331295082603348590e+01,2.055099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331385991693349524e+01,2.055200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331476900783350459e+01,2.055300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331567809873351393e+01,2.055399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331658718963352328e+01,2.055500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331749628053353263e+01,2.055600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331840537143354197e+01,2.055699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.331931446233355132e+01,2.055800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332022355323356066e+01,2.055900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332113264413357001e+01,2.055999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332204173503357936e+01,2.056100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332295082593358870e+01,2.056200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332385991683359805e+01,2.056299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332476900773360740e+01,2.056400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332567809863361674e+01,2.056500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332658718953362609e+01,2.056599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332749628043363543e+01,2.056700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332840537133364478e+01,2.056800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.332931446223365413e+01,2.056899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333022355313366347e+01,2.057000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333113264403367282e+01,2.057100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333204173493368216e+01,2.057199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333295082583369151e+01,2.057300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333385991673370086e+01,2.057400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333476900763371020e+01,2.057500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333567809853371955e+01,2.057599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333658718943372889e+01,2.057700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333749628033373824e+01,2.057800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333840537123374759e+01,2.057899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.333931446213375693e+01,2.058000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334022355303376628e+01,2.058100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334113264393377563e+01,2.058199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334204173483378497e+01,2.058300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334295082573379432e+01,2.058400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334385991663380366e+01,2.058499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334476900753381301e+01,2.058600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334567809843382236e+01,2.058700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334658718933383170e+01,2.058799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334749628023384105e+01,2.058900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334840537113385039e+01,2.059000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.334931446203385974e+01,2.059099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335022355293386909e+01,2.059200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335113264383387843e+01,2.059300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335204173473388778e+01,2.059399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335295082563389713e+01,2.059500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335385991653390647e+01,2.059600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335476900743391582e+01,2.059699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335567809833392516e+01,2.059800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335658718923393451e+01,2.059900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335749628013394386e+01,2.060000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335840537103395320e+01,2.060099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.335931446193396255e+01,2.060200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336022355283397189e+01,2.060300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336113264373398124e+01,2.060399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336204173463399059e+01,2.060500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336295082553399993e+01,2.060600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336385991643400928e+01,2.060699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336476900733401862e+01,2.060800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336567809823402797e+01,2.060900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336658718913403732e+01,2.060999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336749628003404666e+01,2.061100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336840537093405601e+01,2.061200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.336931446183406536e+01,2.061299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337022355273407470e+01,2.061400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337113264363408405e+01,2.061500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337204173453409339e+01,2.061599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337295082543410274e+01,2.061700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337385991633411209e+01,2.061800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337476900723412143e+01,2.061899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337567809813413078e+01,2.062000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337658718903414012e+01,2.062100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337749627993414947e+01,2.062199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337840537083415882e+01,2.062300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.337931446173416816e+01,2.062400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338022355263417751e+01,2.062500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338113264353418685e+01,2.062599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338204173443419620e+01,2.062700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338295082533420555e+01,2.062800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338385991623421489e+01,2.062899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338476900713422424e+01,2.063000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338567809803423359e+01,2.063100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338658718893424293e+01,2.063199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338749627983425228e+01,2.063300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338840537073426162e+01,2.063400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.338931446163427097e+01,2.063499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339022355253428032e+01,2.063600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339113264343428966e+01,2.063700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339204173433429901e+01,2.063799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339295082523430835e+01,2.063900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339385991613431770e+01,2.064000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339476900703432705e+01,2.064099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339567809793433639e+01,2.064200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339658718883434574e+01,2.064300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339749627973435508e+01,2.064399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339840537063436443e+01,2.064500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.339931446153437378e+01,2.064600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340022355243438312e+01,2.064699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340113264333439247e+01,2.064800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340204173423440182e+01,2.064900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340295082513441116e+01,2.065000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340385991603442051e+01,2.065099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340476900693442985e+01,2.065200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340567809783443920e+01,2.065300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340658718873444855e+01,2.065399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340749627963445789e+01,2.065500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340840537053446724e+01,2.065600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.340931446143447658e+01,2.065699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341022355233448593e+01,2.065800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341113264323449528e+01,2.065900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341204173413450462e+01,2.065999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341295082503451397e+01,2.066100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341385991593452331e+01,2.066200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341476900683453266e+01,2.066299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341567809773454201e+01,2.066400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341658718863455135e+01,2.066500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341749627953456070e+01,2.066599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341840537043457005e+01,2.066700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.341931446133457939e+01,2.066800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342022355223458874e+01,2.066899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342113264313459808e+01,2.067000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342204173403460743e+01,2.067100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342295082493461678e+01,2.067199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342385991583462612e+01,2.067300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342476900673463547e+01,2.067400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342567809763464481e+01,2.067500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342658718853465416e+01,2.067599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342749627943466351e+01,2.067700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342840537033467285e+01,2.067800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.342931446123468220e+01,2.067899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343022355213469154e+01,2.068000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343113264303470089e+01,2.068100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343204173393471024e+01,2.068199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343295082483471958e+01,2.068300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343385991573472893e+01,2.068400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343476900663473828e+01,2.068499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343567809753474762e+01,2.068600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343658718843475697e+01,2.068700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343749627933476631e+01,2.068799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343840537023477566e+01,2.068900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.343931446113478501e+01,2.069000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344022355203479435e+01,2.069099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344113264293480370e+01,2.069200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344204173383481304e+01,2.069300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344295082473482239e+01,2.069399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344385991563483174e+01,2.069500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344476900653484108e+01,2.069600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344567809743485043e+01,2.069699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344658718833485977e+01,2.069800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344749627923486912e+01,2.069900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344840537013487847e+01,2.070000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.344931446103488781e+01,2.070099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345022355193489716e+01,2.070200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345113264283490651e+01,2.070300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345204173373491585e+01,2.070399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345295082463492520e+01,2.070500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345385991553493454e+01,2.070600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345476900643494389e+01,2.070699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345567809733495324e+01,2.070800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345658718823496258e+01,2.070900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345749627913497193e+01,2.070999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345840537003498127e+01,2.071100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.345931446093499062e+01,2.071200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346022355183499997e+01,2.071299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346113264273500931e+01,2.071400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346204173363501866e+01,2.071500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346295082453502800e+01,2.071599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346385991543503735e+01,2.071700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346476900633504670e+01,2.071800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346567809723505604e+01,2.071899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346658718813506539e+01,2.072000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346749627903507474e+01,2.072100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346840536993508408e+01,2.072199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.346931446083509343e+01,2.072300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347022355173510277e+01,2.072400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347113264263511212e+01,2.072500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347204173353512147e+01,2.072599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347295082443513081e+01,2.072700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347385991533514016e+01,2.072800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347476900623514950e+01,2.072899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347567809713515885e+01,2.073000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347658718803516820e+01,2.073100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347749627893517754e+01,2.073199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347840536983518689e+01,2.073300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.347931446073519623e+01,2.073400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348022355163520558e+01,2.073499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348113264253521493e+01,2.073600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348204173343522427e+01,2.073700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348295082433523362e+01,2.073799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348385991523524297e+01,2.073900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348476900613525231e+01,2.074000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348567809703526166e+01,2.074099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348658718793527100e+01,2.074200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348749627883528035e+01,2.074300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348840536973528970e+01,2.074399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.348931446063529904e+01,2.074500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349022355153530839e+01,2.074600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349113264243531773e+01,2.074699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349204173333532708e+01,2.074800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349295082423533643e+01,2.074900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349385991513534577e+01,2.075000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349476900603535512e+01,2.075099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349567809693536447e+01,2.075200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349658718783537381e+01,2.075300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349749627873538316e+01,2.075399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349840536963539250e+01,2.075500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.349931446053540185e+01,2.075600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350022355143541120e+01,2.075699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350113264233542054e+01,2.075800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350204173323542989e+01,2.075900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350295082413543923e+01,2.075999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350385991503544858e+01,2.076100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350476900593545793e+01,2.076200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350567809683546727e+01,2.076299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350658718773547662e+01,2.076400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350749627863548596e+01,2.076500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350840536953549531e+01,2.076599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.350931446043550466e+01,2.076700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351022355133551400e+01,2.076800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351113264223552335e+01,2.076899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351204173313553270e+01,2.077000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351295082403554204e+01,2.077100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351385991493555139e+01,2.077199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351476900583556073e+01,2.077300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351567809673557008e+01,2.077400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351658718763557943e+01,2.077500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351749627853558877e+01,2.077599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351840536943559812e+01,2.077700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.351931446033560746e+01,2.077800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352022355123561681e+01,2.077899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352113264213562616e+01,2.078000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352204173303563550e+01,2.078100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352295082393564485e+01,2.078199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352385991483565419e+01,2.078300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352476900573566354e+01,2.078400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352567809663567289e+01,2.078499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352658718753568223e+01,2.078600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352749627843569158e+01,2.078700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352840536933570093e+01,2.078799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.352931446023571027e+01,2.078900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353022355113571962e+01,2.079000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353113264203572896e+01,2.079099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353204173293573831e+01,2.079200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353295082383574766e+01,2.079300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353385991473575700e+01,2.079399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353476900563576635e+01,2.079500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353567809653577569e+01,2.079600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353658718743578504e+01,2.079699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353749627833579439e+01,2.079800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353840536923580373e+01,2.079900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.353931446013581308e+01,2.080000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354022355103582242e+01,2.080099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354113264193583177e+01,2.080200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354204173283584112e+01,2.080300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354295082373585046e+01,2.080399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354385991463585981e+01,2.080500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354476900553586916e+01,2.080600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354567809643587850e+01,2.080699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354658718733588785e+01,2.080800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354749627823589719e+01,2.080900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354840536913590654e+01,2.080999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.354931446003591589e+01,2.081100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355022355093592523e+01,2.081200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355113264183593458e+01,2.081299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355204173273594392e+01,2.081400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355295082363595327e+01,2.081500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355385991453596262e+01,2.081599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355476900543597196e+01,2.081700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355567809633598131e+01,2.081800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355658718723599065e+01,2.081899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355749627813600000e+01,2.082000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355840536903600935e+01,2.082100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.355931445993601869e+01,2.082199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356022355083602804e+01,2.082300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356113264173603739e+01,2.082400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356204173263604673e+01,2.082500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356295082353605608e+01,2.082599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356385991443606542e+01,2.082700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356476900533607477e+01,2.082800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356567809623608412e+01,2.082899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356658718713609346e+01,2.083000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356749627803610281e+01,2.083100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356840536893611215e+01,2.083199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.356931445983612150e+01,2.083300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357022355073613085e+01,2.083400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357113264163614019e+01,2.083499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357204173253614954e+01,2.083600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357295082343615888e+01,2.083700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357385991433616823e+01,2.083799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357476900523617758e+01,2.083900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357567809613618692e+01,2.084000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357658718703619627e+01,2.084099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357749627793620562e+01,2.084200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357840536883621496e+01,2.084300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.357931445973622431e+01,2.084399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358022355063623365e+01,2.084500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358113264153624300e+01,2.084600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358204173243625235e+01,2.084699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358295082333626169e+01,2.084800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358385991423627104e+01,2.084900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358476900513628038e+01,2.085000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358567809603628973e+01,2.085099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358658718693629908e+01,2.085200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358749627783630842e+01,2.085300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358840536873631777e+01,2.085399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.358931445963632711e+01,2.085500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359022355053633646e+01,2.085600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359113264143634581e+01,2.085699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359204173233635515e+01,2.085800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359295082323636450e+01,2.085900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359385991413637385e+01,2.085999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359476900503638319e+01,2.086100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359567809593639254e+01,2.086200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359658718683640188e+01,2.086299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359749627773641123e+01,2.086400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359840536863642058e+01,2.086500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.359931445953642992e+01,2.086599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360022355043643927e+01,2.086700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360113264133644861e+01,2.086800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360204173223645796e+01,2.086899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360295082313646731e+01,2.087000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360385991403647665e+01,2.087100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360476900493648600e+01,2.087199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360567809583649534e+01,2.087300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360658718673650469e+01,2.087400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360749627763651404e+01,2.087500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360840536853652338e+01,2.087599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.360931445943653273e+01,2.087700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361022355033654208e+01,2.087800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361113264123655142e+01,2.087899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361204173213656077e+01,2.088000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361295082303657011e+01,2.088100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361385991393657946e+01,2.088199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361476900483658881e+01,2.088300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361567809573659815e+01,2.088400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361658718663660750e+01,2.088499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361749627753661684e+01,2.088600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361840536843662619e+01,2.088700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.361931445933663554e+01,2.088799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362022355023664488e+01,2.088900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362113264113665423e+01,2.089000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362204173203666357e+01,2.089099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362295082293667292e+01,2.089200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362385991383668227e+01,2.089300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362476900473669161e+01,2.089399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362567809563670096e+01,2.089500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362658718653671031e+01,2.089600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362749627743671965e+01,2.089699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362840536833672900e+01,2.089800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.362931445923673834e+01,2.089900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363022355013674769e+01,2.090000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363113264103675704e+01,2.090099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363204173193676638e+01,2.090200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363295082283677573e+01,2.090300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363385991373678507e+01,2.090399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363476900463679442e+01,2.090500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363567809553680377e+01,2.090600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363658718643681311e+01,2.090699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363749627733682246e+01,2.090800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363840536823683181e+01,2.090900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.363931445913684115e+01,2.090999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364022355003685050e+01,2.091100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364113264093685984e+01,2.091200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364204173183686919e+01,2.091299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364295082273687854e+01,2.091400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364385991363688788e+01,2.091500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364476900453689723e+01,2.091599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364567809543690657e+01,2.091700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364658718633691592e+01,2.091800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364749627723692527e+01,2.091899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364840536813693461e+01,2.092000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.364931445903694396e+01,2.092100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365022354993695330e+01,2.092199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365113264083696265e+01,2.092300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365204173173697200e+01,2.092400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365295082263698134e+01,2.092500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365385991353699069e+01,2.092599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365476900443700004e+01,2.092700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365567809533700938e+01,2.092800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365658718623701873e+01,2.092899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365749627713702807e+01,2.093000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365840536803703742e+01,2.093100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.365931445893704677e+01,2.093199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366022354983705611e+01,2.093300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366113264073706546e+01,2.093400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366204173163707480e+01,2.093499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366295082253708415e+01,2.093600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366385991343709350e+01,2.093700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366476900433710284e+01,2.093799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366567809523711219e+01,2.093900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366658718613712153e+01,2.094000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366749627703713088e+01,2.094099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366840536793714023e+01,2.094200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.366931445883714957e+01,2.094300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367022354973715892e+01,2.094399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367113264063716827e+01,2.094500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367204173153717761e+01,2.094600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367295082243718696e+01,2.094699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367385991333719630e+01,2.094800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367476900423720565e+01,2.094900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367567809513721500e+01,2.095000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367658718603722434e+01,2.095099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367749627693723369e+01,2.095200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367840536783724303e+01,2.095300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.367931445873725238e+01,2.095399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368022354963726173e+01,2.095500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368113264053727107e+01,2.095600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368204173143728042e+01,2.095699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368295082233728976e+01,2.095800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368385991323729911e+01,2.095900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368476900413730846e+01,2.095999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368567809503731780e+01,2.096100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368658718593732715e+01,2.096200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368749627683733650e+01,2.096299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368840536773734584e+01,2.096400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.368931445863735519e+01,2.096500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369022354953736453e+01,2.096599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369113264043737388e+01,2.096700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369204173133738323e+01,2.096800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369295082223739257e+01,2.096899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369385991313740192e+01,2.097000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369476900403741126e+01,2.097100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369567809493742061e+01,2.097199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369658718583742996e+01,2.097300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369749627673743930e+01,2.097400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369840536763744865e+01,2.097500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.369931445853745799e+01,2.097599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370022354943746734e+01,2.097700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370113264033747669e+01,2.097800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370204173123748603e+01,2.097899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370295082213749538e+01,2.098000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370385991303750473e+01,2.098100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370476900393751407e+01,2.098199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370567809483752342e+01,2.098300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370658718573753276e+01,2.098400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370749627663754211e+01,2.098499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370840536753755146e+01,2.098600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.370931445843756080e+01,2.098700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371022354933757015e+01,2.098799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371113264023757949e+01,2.098900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371204173113758884e+01,2.099000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371295082203759819e+01,2.099099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371385991293760753e+01,2.099200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371476900383761688e+01,2.099300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371567809473762622e+01,2.099399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371658718563763557e+01,2.099500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371749627653764492e+01,2.099600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371840536743765426e+01,2.099699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.371931445833766361e+01,2.099800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372022354923767296e+01,2.099900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372113264013768230e+01,2.100000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372204173103769165e+01,2.100099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372295082193770099e+01,2.100200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372385991283771034e+01,2.100300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372476900373771969e+01,2.100399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372567809463772903e+01,2.100500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372658718553773838e+01,2.100600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372749627643774772e+01,2.100699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372840536733775707e+01,2.100800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.372931445823776642e+01,2.100900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373022354913777576e+01,2.100999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373113264003778511e+01,2.101100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373204173093779445e+01,2.101200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373295082183780380e+01,2.101299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373385991273781315e+01,2.101400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373476900363782249e+01,2.101500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373567809453783184e+01,2.101599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373658718543784119e+01,2.101700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373749627633785053e+01,2.101800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373840536723785988e+01,2.101899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.373931445813786922e+01,2.102000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374022354903787857e+01,2.102100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374113263993788792e+01,2.102199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374204173083789726e+01,2.102300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374295082173790661e+01,2.102400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374385991263791595e+01,2.102500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374476900353792530e+01,2.102599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374567809443793465e+01,2.102700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374658718533794399e+01,2.102800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374749627623795334e+01,2.102899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374840536713796268e+01,2.103000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.374931445803797203e+01,2.103100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375022354893798138e+01,2.103199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375113263983799072e+01,2.103300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375204173073800007e+01,2.103400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375295082163800942e+01,2.103499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375385991253801876e+01,2.103600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375476900343802811e+01,2.103700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375567809433803745e+01,2.103799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375658718523804680e+01,2.103900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375749627613805615e+01,2.104000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375840536703806549e+01,2.104099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.375931445793807484e+01,2.104200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376022354883808418e+01,2.104300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376113263973809353e+01,2.104399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376204173063810288e+01,2.104500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376295082153811222e+01,2.104600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376385991243812157e+01,2.104699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376476900333813091e+01,2.104800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376567809423814026e+01,2.104900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376658718513814961e+01,2.105000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376749627603815895e+01,2.105099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376840536693816830e+01,2.105200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.376931445783817765e+01,2.105300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377022354873818699e+01,2.105399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377113263963819634e+01,2.105500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377204173053820568e+01,2.105600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377295082143821503e+01,2.105699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377385991233822438e+01,2.105800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377476900323823372e+01,2.105900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377567809413824307e+01,2.105999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377658718503825241e+01,2.106100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377749627593826176e+01,2.106200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377840536683827111e+01,2.106299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.377931445773828045e+01,2.106400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378022354863828980e+01,2.106500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378113263953829914e+01,2.106599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378204173043830849e+01,2.106700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378295082133831784e+01,2.106800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378385991223832718e+01,2.106899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378476900313833653e+01,2.107000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378567809403834588e+01,2.107100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378658718493835522e+01,2.107199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378749627583836457e+01,2.107300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378840536673837391e+01,2.107400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.378931445763838326e+01,2.107500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379022354853839261e+01,2.107599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379113263943840195e+01,2.107700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379204173033841130e+01,2.107800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379295082123842064e+01,2.107899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379385991213842999e+01,2.108000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379476900303843934e+01,2.108100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379567809393844868e+01,2.108199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379658718483845803e+01,2.108300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379749627573846738e+01,2.108400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379840536663847672e+01,2.108499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.379931445753848607e+01,2.108600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380022354843849541e+01,2.108700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380113263933850476e+01,2.108799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380204173023851411e+01,2.108900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380295082113852345e+01,2.109000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380385991203853280e+01,2.109099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380476900293854214e+01,2.109200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380567809383855149e+01,2.109300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380658718473856084e+01,2.109399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380749627563857018e+01,2.109500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380840536653857953e+01,2.109600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.380931445743858887e+01,2.109699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381022354833859822e+01,2.109800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381113263923860757e+01,2.109900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381204173013861691e+01,2.110000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381295082103862626e+01,2.110099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381385991193863561e+01,2.110200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381476900283864495e+01,2.110300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381567809373865430e+01,2.110399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381658718463866364e+01,2.110500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381749627553867299e+01,2.110600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381840536643868234e+01,2.110699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.381931445733869168e+01,2.110800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382022354823870103e+01,2.110900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382113263913871037e+01,2.110999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382204173003871972e+01,2.111100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382295082093872907e+01,2.111200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382385991183873841e+01,2.111299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382476900273874776e+01,2.111400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382567809363875710e+01,2.111500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382658718453876645e+01,2.111599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382749627543877580e+01,2.111700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382840536633878514e+01,2.111800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.382931445723879449e+01,2.111899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383022354813880384e+01,2.112000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383113263903881318e+01,2.112100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383204172993882253e+01,2.112199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383295082083883187e+01,2.112300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383385991173884122e+01,2.112400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383476900263885057e+01,2.112500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383567809353885991e+01,2.112599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383658718443886926e+01,2.112700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383749627533887860e+01,2.112800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383840536623888795e+01,2.112899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.383931445713889730e+01,2.113000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384022354803890664e+01,2.113100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384113263893891599e+01,2.113199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384204172983892533e+01,2.113300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384295082073893468e+01,2.113400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384385991163894403e+01,2.113499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384476900253895337e+01,2.113600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384567809343896272e+01,2.113700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384658718433897207e+01,2.113799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384749627523898141e+01,2.113900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384840536613899076e+01,2.114000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.384931445703900010e+01,2.114099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385022354793900945e+01,2.114200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385113263883901880e+01,2.114300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385204172973902814e+01,2.114399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385295082063903749e+01,2.114500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385385991153904683e+01,2.114600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385476900243905618e+01,2.114699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385567809333906553e+01,2.114800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385658718423907487e+01,2.114900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385749627513908422e+01,2.115000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385840536603909356e+01,2.115099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.385931445693910291e+01,2.115200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386022354783911226e+01,2.115300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386113263873912160e+01,2.115399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386204172963913095e+01,2.115500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386295082053914030e+01,2.115600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386385991143914964e+01,2.115699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386476900233915899e+01,2.115800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386567809323916833e+01,2.115900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386658718413917768e+01,2.115999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386749627503918703e+01,2.116100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386840536593919637e+01,2.116200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.386931445683920572e+01,2.116299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387022354773921506e+01,2.116400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387113263863922441e+01,2.116500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387204172953923376e+01,2.116599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387295082043924310e+01,2.116700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387385991133925245e+01,2.116800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387476900223926179e+01,2.116899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387567809313927114e+01,2.117000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387658718403928049e+01,2.117100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387749627493928983e+01,2.117199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387840536583929918e+01,2.117300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.387931445673930853e+01,2.117400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388022354763931787e+01,2.117500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388113263853932722e+01,2.117599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388204172943933656e+01,2.117700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388295082033934591e+01,2.117800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388385991123935526e+01,2.117899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388476900213936460e+01,2.118000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388567809303937395e+01,2.118100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388658718393938329e+01,2.118199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388749627483939264e+01,2.118300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388840536573940199e+01,2.118400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.388931445663941133e+01,2.118499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389022354753942068e+01,2.118600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389113263843943002e+01,2.118700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389204172933943937e+01,2.118799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389295082023944872e+01,2.118900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389385991113945806e+01,2.119000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389476900203946741e+01,2.119099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389567809293947676e+01,2.119200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389658718383948610e+01,2.119300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389749627473949545e+01,2.119399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389840536563950479e+01,2.119500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.389931445653951414e+01,2.119600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390022354743952349e+01,2.119699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390113263833953283e+01,2.119800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390204172923954218e+01,2.119900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390295082013955152e+01,2.120000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390385991103956087e+01,2.120099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390476900193957022e+01,2.120200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390567809283957956e+01,2.120300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390658718373958891e+01,2.120399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390749627463959825e+01,2.120500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390840536553960760e+01,2.120600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.390931445643961695e+01,2.120699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391022354733962629e+01,2.120800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391113263823963564e+01,2.120900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391204172913964499e+01,2.120999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391295082003965433e+01,2.121100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391385991093966368e+01,2.121200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391476900183967302e+01,2.121299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391567809273968237e+01,2.121400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391658718363969172e+01,2.121500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391749627453970106e+01,2.121599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391840536543971041e+01,2.121700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.391931445633971975e+01,2.121800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392022354723972910e+01,2.121899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392113263813973845e+01,2.122000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392204172903974779e+01,2.122100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392295081993975714e+01,2.122199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392385991083976648e+01,2.122300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392476900173977583e+01,2.122400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392567809263978518e+01,2.122500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392658718353979452e+01,2.122599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392749627443980387e+01,2.122700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392840536533981322e+01,2.122800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.392931445623982256e+01,2.122899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393022354713983191e+01,2.123000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393113263803984125e+01,2.123100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393204172893985060e+01,2.123199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393295081983985995e+01,2.123300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393385991073986929e+01,2.123400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393476900163987864e+01,2.123499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393567809253988798e+01,2.123600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393658718343989733e+01,2.123700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393749627433990668e+01,2.123799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393840536523991602e+01,2.123900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.393931445613992537e+01,2.124000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394022354703993472e+01,2.124099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394113263793994406e+01,2.124200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394204172883995341e+01,2.124300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394295081973996275e+01,2.124399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394385991063997210e+01,2.124500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394476900153998145e+01,2.124600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394567809243999079e+01,2.124699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394658718334000014e+01,2.124800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394749627424000948e+01,2.124900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394840536514001883e+01,2.125000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.394931445604002818e+01,2.125099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395022354694003752e+01,2.125200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395113263784004687e+01,2.125300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395204172874005621e+01,2.125399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395295081964006556e+01,2.125500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395385991054007491e+01,2.125600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395476900144008425e+01,2.125699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395567809234009360e+01,2.125800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395658718324010295e+01,2.125900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395749627414011229e+01,2.125999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395840536504012164e+01,2.126100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.395931445594013098e+01,2.126200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396022354684014033e+01,2.126299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396113263774014968e+01,2.126400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396204172864015902e+01,2.126500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396295081954016837e+01,2.126599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396385991044017771e+01,2.126700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396476900134018706e+01,2.126800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396567809224019641e+01,2.126899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396658718314020575e+01,2.127000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396749627404021510e+01,2.127100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396840536494022444e+01,2.127199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.396931445584023379e+01,2.127300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397022354674024314e+01,2.127400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397113263764025248e+01,2.127500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397204172854026183e+01,2.127599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397295081944027118e+01,2.127700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397385991034028052e+01,2.127800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397476900124028987e+01,2.127899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397567809214029921e+01,2.128000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397658718304030856e+01,2.128100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397749627394031791e+01,2.128199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397840536484032725e+01,2.128300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.397931445574033660e+01,2.128400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398022354664034594e+01,2.128499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398113263754035529e+01,2.128600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398204172844036464e+01,2.128700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398295081934037398e+01,2.128799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398385991024038333e+01,2.128900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398476900114039267e+01,2.129000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398567809204040202e+01,2.129099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398658718294041137e+01,2.129200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398749627384042071e+01,2.129300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398840536474043006e+01,2.129399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.398931445564043941e+01,2.129500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399022354654044875e+01,2.129600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399113263744045810e+01,2.129699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399204172834046744e+01,2.129800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399295081924047679e+01,2.129900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399385991014048614e+01,2.130000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399476900104049548e+01,2.130099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399567809194050483e+01,2.130200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399658718284051417e+01,2.130300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399749627374052352e+01,2.130399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399840536464053287e+01,2.130500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.399931445554054221e+01,2.130600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400022354644055156e+01,2.130699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400113263734056090e+01,2.130800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400204172824057025e+01,2.130900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400295081914057960e+01,2.130999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400385991004058894e+01,2.131100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400476900094059829e+01,2.131200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400567809184060764e+01,2.131299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400658718274061698e+01,2.131400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400749627364062633e+01,2.131500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400840536454063567e+01,2.131599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.400931445544064502e+01,2.131700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401022354634065437e+01,2.131800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401113263724066371e+01,2.131899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401204172814067306e+01,2.132000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401295081904068240e+01,2.132100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401385990994069175e+01,2.132199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401476900084070110e+01,2.132300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401567809174071044e+01,2.132400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401658718264071979e+01,2.132500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401749627354072913e+01,2.132599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401840536444073848e+01,2.132700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.401931445534074783e+01,2.132800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402022354624075717e+01,2.132899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402113263714076652e+01,2.133000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402204172804077587e+01,2.133100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402295081894078521e+01,2.133199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402385990984079456e+01,2.133300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402476900074080390e+01,2.133400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402567809164081325e+01,2.133499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402658718254082260e+01,2.133600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402749627344083194e+01,2.133700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402840536434084129e+01,2.133799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.402931445524085063e+01,2.133900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403022354614085998e+01,2.134000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403113263704086933e+01,2.134099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403204172794087867e+01,2.134200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403295081884088802e+01,2.134300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403385990974089736e+01,2.134399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403476900064090671e+01,2.134500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403567809154091606e+01,2.134600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403658718244092540e+01,2.134699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403749627334093475e+01,2.134800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403840536424094410e+01,2.134900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.403931445514095344e+01,2.135000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404022354604096279e+01,2.135099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404113263694097213e+01,2.135200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404204172784098148e+01,2.135300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404295081874099083e+01,2.135399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404385990964100017e+01,2.135500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404476900054100952e+01,2.135600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404567809144101886e+01,2.135699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404658718234102821e+01,2.135800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404749627324103756e+01,2.135900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404840536414104690e+01,2.135999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.404931445504105625e+01,2.136100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405022354594106559e+01,2.136200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405113263684107494e+01,2.136299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405204172774108429e+01,2.136400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405295081864109363e+01,2.136500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405385990954110298e+01,2.136599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405476900044111233e+01,2.136700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405567809134112167e+01,2.136800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405658718224113102e+01,2.136899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405749627314114036e+01,2.137000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405840536404114971e+01,2.137100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.405931445494115906e+01,2.137199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406022354584116840e+01,2.137300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406113263674117775e+01,2.137400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406204172764118709e+01,2.137500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406295081854119644e+01,2.137599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406385990944120579e+01,2.137700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406476900034121513e+01,2.137800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406567809124122448e+01,2.137899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406658718214123382e+01,2.138000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406749627304124317e+01,2.138100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406840536394125252e+01,2.138199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.406931445484126186e+01,2.138300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407022354574127121e+01,2.138400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407113263664128056e+01,2.138499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407204172754128990e+01,2.138600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407295081844129925e+01,2.138700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407385990934130859e+01,2.138799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407476900024131794e+01,2.138900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407567809114132729e+01,2.139000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407658718204133663e+01,2.139099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407749627294134598e+01,2.139200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407840536384135532e+01,2.139300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.407931445474136467e+01,2.139399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408022354564137402e+01,2.139500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408113263654138336e+01,2.139600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408204172744139271e+01,2.139699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408295081834140206e+01,2.139800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408385990924141140e+01,2.139900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408476900014142075e+01,2.140000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408567809104143009e+01,2.140099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408658718194143944e+01,2.140200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408749627284144879e+01,2.140300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408840536374145813e+01,2.140399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.408931445464146748e+01,2.140500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409022354554147682e+01,2.140600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409113263644148617e+01,2.140699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409204172734149552e+01,2.140800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409295081824150486e+01,2.140900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409385990914151421e+01,2.140999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409476900004152355e+01,2.141100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409567809094153290e+01,2.141200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409658718184154225e+01,2.141299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409749627274155159e+01,2.141400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409840536364156094e+01,2.141500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.409931445454157029e+01,2.141599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410022354544157963e+01,2.141700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410113263634158898e+01,2.141800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410204172724159832e+01,2.141899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410295081814160767e+01,2.142000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410385990904161702e+01,2.142100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410476899994162636e+01,2.142199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410567809084163571e+01,2.142300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410658718174164505e+01,2.142400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410749627264165440e+01,2.142500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410840536354166375e+01,2.142599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.410931445444167309e+01,2.142700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411022354534168244e+01,2.142800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411113263624169178e+01,2.142899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411204172714170113e+01,2.143000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411295081804171048e+01,2.143100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411385990894171982e+01,2.143199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411476899984172917e+01,2.143300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411567809074173852e+01,2.143400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411658718164174786e+01,2.143499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411749627254175721e+01,2.143600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411840536344176655e+01,2.143700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.411931445434177590e+01,2.143799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412022354524178525e+01,2.143900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412113263614179459e+01,2.144000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412204172704180394e+01,2.144099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412295081794181328e+01,2.144200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412385990884182263e+01,2.144300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412476899974183198e+01,2.144399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412567809064184132e+01,2.144500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412658718154185067e+01,2.144600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412749627244186001e+01,2.144699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412840536334186936e+01,2.144800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.412931445424187871e+01,2.144900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413022354514188805e+01,2.145000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413113263604189740e+01,2.145099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413204172694190675e+01,2.145200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413295081784191609e+01,2.145300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413385990874192544e+01,2.145399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413476899964193478e+01,2.145500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413567809054194413e+01,2.145600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413658718144195348e+01,2.145699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413749627234196282e+01,2.145800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413840536324197217e+01,2.145900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.413931445414198151e+01,2.145999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414022354504199086e+01,2.146100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414113263594200021e+01,2.146200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414204172684200955e+01,2.146299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414295081774201890e+01,2.146400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414385990864202824e+01,2.146500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414476899954203759e+01,2.146599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414567809044204694e+01,2.146700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414658718134205628e+01,2.146800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414749627224206563e+01,2.146899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414840536314207498e+01,2.147000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.414931445404208432e+01,2.147100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415022354494209367e+01,2.147199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415113263584210301e+01,2.147300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415204172674211236e+01,2.147400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415295081764212171e+01,2.147500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415385990854213105e+01,2.147599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415476899944214040e+01,2.147700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415567809034214974e+01,2.147800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415658718124215909e+01,2.147899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415749627214216844e+01,2.148000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415840536304217778e+01,2.148100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.415931445394218713e+01,2.148199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416022354484219647e+01,2.148300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416113263574220582e+01,2.148400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416204172664221517e+01,2.148499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416295081754222451e+01,2.148600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416385990844223386e+01,2.148700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416476899934224321e+01,2.148799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416567809024225255e+01,2.148900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416658718114226190e+01,2.149000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416749627204227124e+01,2.149099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416840536294228059e+01,2.149200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.416931445384228994e+01,2.149300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417022354474229928e+01,2.149399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417113263564230863e+01,2.149500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417204172654231797e+01,2.149600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417295081744232732e+01,2.149699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417385990834233667e+01,2.149800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417476899924234601e+01,2.149900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417567809014235536e+01,2.150000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417658718104236470e+01,2.150099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417749627194237405e+01,2.150200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417840536284238340e+01,2.150300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.417931445374239274e+01,2.150399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418022354464240209e+01,2.150500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418113263554241144e+01,2.150600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418204172644242078e+01,2.150699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418295081734243013e+01,2.150800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418385990824243947e+01,2.150900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418476899914244882e+01,2.150999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418567809004245817e+01,2.151100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418658718094246751e+01,2.151200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418749627184247686e+01,2.151299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418840536274248620e+01,2.151400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.418931445364249555e+01,2.151500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419022354454250490e+01,2.151599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419113263544251424e+01,2.151700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419204172634252359e+01,2.151800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419295081724253293e+01,2.151899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419385990814254228e+01,2.152000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419476899904255163e+01,2.152100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419567808994256097e+01,2.152199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419658718084257032e+01,2.152300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419749627174257967e+01,2.152400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419840536264258901e+01,2.152500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.419931445354259836e+01,2.152599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420022354444260770e+01,2.152700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420113263534261705e+01,2.152800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420204172624262640e+01,2.152899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420295081714263574e+01,2.153000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420385990804264509e+01,2.153100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420476899894265443e+01,2.153199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420567808984266378e+01,2.153300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420658718074267313e+01,2.153400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420749627164268247e+01,2.153499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420840536254269182e+01,2.153600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.420931445344270116e+01,2.153700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421022354434271051e+01,2.153799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421113263524271986e+01,2.153900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421204172614272920e+01,2.154000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421295081704273855e+01,2.154099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421385990794274790e+01,2.154200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421476899884275724e+01,2.154300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421567808974276659e+01,2.154399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421658718064277593e+01,2.154500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421749627154278528e+01,2.154600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421840536244279463e+01,2.154699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.421931445334280397e+01,2.154800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422022354424281332e+01,2.154900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422113263514282266e+01,2.155000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422204172604283201e+01,2.155099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422295081694284136e+01,2.155200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422385990784285070e+01,2.155300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422476899874286005e+01,2.155399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422567808964286939e+01,2.155500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422658718054287874e+01,2.155600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422749627144288809e+01,2.155699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422840536234289743e+01,2.155800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.422931445324290678e+01,2.155900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423022354414291613e+01,2.155999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423113263504292547e+01,2.156100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423204172594293482e+01,2.156200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423295081684294416e+01,2.156299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423385990774295351e+01,2.156400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423476899864296286e+01,2.156500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423567808954297220e+01,2.156599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423658718044298155e+01,2.156700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423749627134299089e+01,2.156800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423840536224300024e+01,2.156899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.423931445314300959e+01,2.157000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424022354404301893e+01,2.157100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424113263494302828e+01,2.157199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424204172584303763e+01,2.157300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424295081674304697e+01,2.157400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424385990764305632e+01,2.157500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424476899854306566e+01,2.157599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424567808944307501e+01,2.157700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424658718034308436e+01,2.157800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424749627124309370e+01,2.157899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424840536214310305e+01,2.158000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.424931445304311239e+01,2.158100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425022354394312174e+01,2.158199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425113263484313109e+01,2.158300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425204172574314043e+01,2.158400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425295081664314978e+01,2.158499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425385990754315912e+01,2.158600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425476899844316847e+01,2.158700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425567808934317782e+01,2.158799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425658718024318716e+01,2.158900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425749627114319651e+01,2.159000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425840536204320586e+01,2.159099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.425931445294321520e+01,2.159200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426022354384322455e+01,2.159300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426113263474323389e+01,2.159399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426204172564324324e+01,2.159500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426295081654325259e+01,2.159600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426385990744326193e+01,2.159699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426476899834327128e+01,2.159800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426567808924328062e+01,2.159900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426658718014328997e+01,2.160000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426749627104329932e+01,2.160099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426840536194330866e+01,2.160200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.426931445284331801e+01,2.160300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427022354374332735e+01,2.160399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427113263464333670e+01,2.160500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427204172554334605e+01,2.160600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427295081644335539e+01,2.160699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427385990734336474e+01,2.160800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427476899824337409e+01,2.160900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427567808914338343e+01,2.160999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427658718004339278e+01,2.161100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427749627094340212e+01,2.161200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427840536184341147e+01,2.161299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.427931445274342082e+01,2.161400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428022354364343016e+01,2.161500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428113263454343951e+01,2.161599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428204172544344885e+01,2.161700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428295081634345820e+01,2.161800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428385990724346755e+01,2.161899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428476899814347689e+01,2.162000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428567808904348624e+01,2.162100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428658717994349558e+01,2.162199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428749627084350493e+01,2.162300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428840536174351428e+01,2.162400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.428931445264352362e+01,2.162500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429022354354353297e+01,2.162599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429113263444354232e+01,2.162700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429204172534355166e+01,2.162800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429295081624356101e+01,2.162899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429385990714357035e+01,2.163000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429476899804357970e+01,2.163100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429567808894358905e+01,2.163199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429658717984359839e+01,2.163300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429749627074360774e+01,2.163400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429840536164361708e+01,2.163499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.429931445254362643e+01,2.163600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430022354344363578e+01,2.163700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430113263434364512e+01,2.163799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430204172524365447e+01,2.163900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430295081614366381e+01,2.164000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430385990704367316e+01,2.164099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430476899794368251e+01,2.164200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430567808884369185e+01,2.164300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430658717974370120e+01,2.164399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430749627064371055e+01,2.164500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430840536154371989e+01,2.164600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.430931445244372924e+01,2.164699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431022354334373858e+01,2.164800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431113263424374793e+01,2.164900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431204172514375728e+01,2.165000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431295081604376662e+01,2.165099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431385990694377597e+01,2.165200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431476899784378531e+01,2.165300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431567808874379466e+01,2.165399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431658717964380401e+01,2.165500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431749627054381335e+01,2.165600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431840536144382270e+01,2.165699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.431931445234383204e+01,2.165800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432022354324384139e+01,2.165900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432113263414385074e+01,2.165999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432204172504386008e+01,2.166100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432295081594386943e+01,2.166200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432385990684387878e+01,2.166299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432476899774388812e+01,2.166400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432567808864389747e+01,2.166500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432658717954390681e+01,2.166599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432749627044391616e+01,2.166700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432840536134392551e+01,2.166800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.432931445224393485e+01,2.166899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433022354314394420e+01,2.167000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433113263404395354e+01,2.167100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433204172494396289e+01,2.167199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433295081584397224e+01,2.167300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433385990674398158e+01,2.167400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433476899764399093e+01,2.167500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433567808854400027e+01,2.167599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433658717944400962e+01,2.167700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433749627034401897e+01,2.167800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433840536124402831e+01,2.167899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.433931445214403766e+01,2.168000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434022354304404701e+01,2.168100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434113263394405635e+01,2.168199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434204172484406570e+01,2.168300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434295081574407504e+01,2.168400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434385990664408439e+01,2.168499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434476899754409374e+01,2.168600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434567808844410308e+01,2.168700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434658717934411243e+01,2.168799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434749627024412177e+01,2.168900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434840536114413112e+01,2.169000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.434931445204414047e+01,2.169099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435022354294414981e+01,2.169200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435113263384415916e+01,2.169300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435204172474416850e+01,2.169399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435295081564417785e+01,2.169500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435385990654418720e+01,2.169600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435476899744419654e+01,2.169699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435567808834420589e+01,2.169800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435658717924421524e+01,2.169900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435749627014422458e+01,2.170000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435840536104423393e+01,2.170099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.435931445194424327e+01,2.170200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436022354284425262e+01,2.170300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436113263374426197e+01,2.170399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436204172464427131e+01,2.170500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436295081554428066e+01,2.170600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436385990644429000e+01,2.170699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436476899734429935e+01,2.170800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436567808824430870e+01,2.170900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436658717914431804e+01,2.170999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436749627004432739e+01,2.171100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436840536094433673e+01,2.171200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.436931445184434608e+01,2.171299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437022354274435543e+01,2.171400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437113263364436477e+01,2.171500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437204172454437412e+01,2.171599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437295081544438347e+01,2.171700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437385990634439281e+01,2.171800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437476899724440216e+01,2.171899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437567808814441150e+01,2.172000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437658717904442085e+01,2.172100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437749626994443020e+01,2.172199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437840536084443954e+01,2.172300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.437931445174444889e+01,2.172400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438022354264445823e+01,2.172500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438113263354446758e+01,2.172599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438204172444447693e+01,2.172700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438295081534448627e+01,2.172800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438385990624449562e+01,2.172899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438476899714450497e+01,2.173000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438567808804451431e+01,2.173100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438658717894452366e+01,2.173199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438749626984453300e+01,2.173300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438840536074454235e+01,2.173400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.438931445164455170e+01,2.173499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439022354254456104e+01,2.173600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439113263344457039e+01,2.173700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439204172434457973e+01,2.173799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439295081524458908e+01,2.173900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439385990614459843e+01,2.174000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439476899704460777e+01,2.174099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439567808794461712e+01,2.174200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439658717884462646e+01,2.174300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439749626974463581e+01,2.174399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439840536064464516e+01,2.174500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.439931445154465450e+01,2.174600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440022354244466385e+01,2.174699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440113263334467320e+01,2.174800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440204172424468254e+01,2.174900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440295081514469189e+01,2.175000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440385990604470123e+01,2.175099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440476899694471058e+01,2.175200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440567808784471993e+01,2.175300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440658717874472927e+01,2.175399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440749626964473862e+01,2.175500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440840536054474796e+01,2.175600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.440931445144475731e+01,2.175699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441022354234476666e+01,2.175800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441113263324477600e+01,2.175900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441204172414478535e+01,2.175999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441295081504479469e+01,2.176100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441385990594480404e+01,2.176200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441476899684481339e+01,2.176299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441567808774482273e+01,2.176400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441658717864483208e+01,2.176500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441749626954484143e+01,2.176599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441840536044485077e+01,2.176700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.441931445134486012e+01,2.176800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442022354224486946e+01,2.176899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442113263314487881e+01,2.177000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442204172404488816e+01,2.177100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442295081494489750e+01,2.177199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442385990584490685e+01,2.177300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442476899674491619e+01,2.177400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442567808764492554e+01,2.177500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442658717854493489e+01,2.177599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442749626944494423e+01,2.177700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442840536034495358e+01,2.177800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.442931445124496292e+01,2.177899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443022354214497227e+01,2.178000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443113263304498162e+01,2.178100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443204172394499096e+01,2.178199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443295081484500031e+01,2.178300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443385990574500966e+01,2.178400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443476899664501900e+01,2.178499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443567808754502835e+01,2.178600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443658717844503769e+01,2.178700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443749626934504704e+01,2.178799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443840536024505639e+01,2.178900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.443931445114506573e+01,2.179000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444022354204507508e+01,2.179099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444113263294508442e+01,2.179200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444204172384509377e+01,2.179300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444295081474510312e+01,2.179399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444385990564511246e+01,2.179500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444476899654512181e+01,2.179600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444567808744513115e+01,2.179699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444658717834514050e+01,2.179800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444749626924514985e+01,2.179900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444840536014515919e+01,2.180000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.444931445104516854e+01,2.180099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445022354194517789e+01,2.180200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445113263284518723e+01,2.180300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445204172374519658e+01,2.180399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445295081464520592e+01,2.180500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445385990554521527e+01,2.180600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445476899644522462e+01,2.180699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445567808734523396e+01,2.180800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445658717824524331e+01,2.180900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445749626914525265e+01,2.180999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445840536004526200e+01,2.181100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.445931445094527135e+01,2.181200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446022354184528069e+01,2.181299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446113263274529004e+01,2.181400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446204172364529938e+01,2.181500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446295081454530873e+01,2.181599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446385990544531808e+01,2.181700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446476899634532742e+01,2.181800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446567808724533677e+01,2.181899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446658717814534612e+01,2.182000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446749626904535546e+01,2.182100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446840535994536481e+01,2.182199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.446931445084537415e+01,2.182300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447022354174538350e+01,2.182400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447113263264539285e+01,2.182500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447204172354540219e+01,2.182599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447295081444541154e+01,2.182700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447385990534542088e+01,2.182800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447476899624543023e+01,2.182899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447567808714543958e+01,2.183000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447658717804544892e+01,2.183100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447749626894545827e+01,2.183199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447840535984546761e+01,2.183300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.447931445074547696e+01,2.183400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448022354164548631e+01,2.183499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448113263254549565e+01,2.183600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448204172344550500e+01,2.183700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448295081434551435e+01,2.183799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448385990524552369e+01,2.183900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448476899614553304e+01,2.184000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448567808704554238e+01,2.184099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448658717794555173e+01,2.184200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448749626884556108e+01,2.184300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448840535974557042e+01,2.184399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.448931445064557977e+01,2.184500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449022354154558911e+01,2.184600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449113263244559846e+01,2.184699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449204172334560781e+01,2.184800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449295081424561715e+01,2.184900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449385990514562650e+01,2.185000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449476899604563584e+01,2.185099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449567808694564519e+01,2.185200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449658717784565454e+01,2.185300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449749626874566388e+01,2.185399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449840535964567323e+01,2.185500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.449931445054568258e+01,2.185600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450022354144569192e+01,2.185699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450113263234570127e+01,2.185800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450204172324571061e+01,2.185900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450295081414571996e+01,2.185999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450385990504572931e+01,2.186100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450476899594573865e+01,2.186200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450567808684574800e+01,2.186299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450658717774575734e+01,2.186400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450749626864576669e+01,2.186500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450840535954577604e+01,2.186599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.450931445044578538e+01,2.186700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451022354134579473e+01,2.186800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451113263224580407e+01,2.186899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451204172314581342e+01,2.187000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451295081404582277e+01,2.187100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451385990494583211e+01,2.187199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451476899584584146e+01,2.187300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451567808674585081e+01,2.187400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451658717764586015e+01,2.187500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451749626854586950e+01,2.187599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451840535944587884e+01,2.187700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.451931445034588819e+01,2.187800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452022354124589754e+01,2.187899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452113263214590688e+01,2.188000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452204172304591623e+01,2.188100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452295081394592557e+01,2.188199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452385990484593492e+01,2.188300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452476899574594427e+01,2.188400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452567808664595361e+01,2.188499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452658717754596296e+01,2.188600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452749626844597231e+01,2.188700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452840535934598165e+01,2.188799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.452931445024599100e+01,2.188900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453022354114600034e+01,2.189000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453113263204600969e+01,2.189099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453204172294601904e+01,2.189200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453295081384602838e+01,2.189300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453385990474603773e+01,2.189399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453476899564604707e+01,2.189500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453567808654605642e+01,2.189600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453658717744606577e+01,2.189699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453749626834607511e+01,2.189800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453840535924608446e+01,2.189900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.453931445014609380e+01,2.190000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454022354104610315e+01,2.190099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454113263194611250e+01,2.190200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454204172284612184e+01,2.190300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454295081374613119e+01,2.190399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454385990464614054e+01,2.190500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454476899554614988e+01,2.190600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454567808644615923e+01,2.190699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454658717734616857e+01,2.190800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454749626824617792e+01,2.190900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454840535914618727e+01,2.190999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.454931445004619661e+01,2.191100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455022354094620596e+01,2.191200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455113263184621530e+01,2.191299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455204172274622465e+01,2.191400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455295081364623400e+01,2.191500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455385990454624334e+01,2.191599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455476899544625269e+01,2.191700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455567808634626203e+01,2.191800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455658717724627138e+01,2.191899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455749626814628073e+01,2.192000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455840535904629007e+01,2.192100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.455931444994629942e+01,2.192199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456022354084630877e+01,2.192300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456113263174631811e+01,2.192400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456204172264632746e+01,2.192500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456295081354633680e+01,2.192599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456385990444634615e+01,2.192700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456476899534635550e+01,2.192800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456567808624636484e+01,2.192899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456658717714637419e+01,2.193000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456749626804638353e+01,2.193100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456840535894639288e+01,2.193199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.456931444984640223e+01,2.193300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457022354074641157e+01,2.193400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457113263164642092e+01,2.193499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457204172254643026e+01,2.193600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457295081344643961e+01,2.193700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457385990434644896e+01,2.193799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457476899524645830e+01,2.193900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457567808614646765e+01,2.194000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457658717704647700e+01,2.194099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457749626794648634e+01,2.194200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457840535884649569e+01,2.194300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.457931444974650503e+01,2.194399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458022354064651438e+01,2.194500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458113263154652373e+01,2.194600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458204172244653307e+01,2.194699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458295081334654242e+01,2.194800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458385990424655176e+01,2.194900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458476899514656111e+01,2.195000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458567808604657046e+01,2.195099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458658717694657980e+01,2.195200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458749626784658915e+01,2.195300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458840535874659849e+01,2.195399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.458931444964660784e+01,2.195500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459022354054661719e+01,2.195600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459113263144662653e+01,2.195699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459204172234663588e+01,2.195800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459295081324664523e+01,2.195900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459385990414665457e+01,2.195999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459476899504666392e+01,2.196100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459567808594667326e+01,2.196200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459658717684668261e+01,2.196299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459749626774669196e+01,2.196400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459840535864670130e+01,2.196500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.459931444954671065e+01,2.196599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460022354044671999e+01,2.196700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460113263134672934e+01,2.196800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460204172224673869e+01,2.196899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460295081314674803e+01,2.197000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460385990404675738e+01,2.197100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460476899494676672e+01,2.197199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460567808584677607e+01,2.197300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460658717674678542e+01,2.197400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460749626764679476e+01,2.197500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460840535854680411e+01,2.197599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.460931444944681346e+01,2.197700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461022354034682280e+01,2.197800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461113263124683215e+01,2.197899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461204172214684149e+01,2.198000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461295081304685084e+01,2.198100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461385990394686019e+01,2.198199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461476899484686953e+01,2.198300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461567808574687888e+01,2.198400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461658717664688822e+01,2.198499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461749626754689757e+01,2.198600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461840535844690692e+01,2.198700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.461931444934691626e+01,2.198799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462022354024692561e+01,2.198900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462113263114693495e+01,2.199000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462204172204694430e+01,2.199099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462295081294695365e+01,2.199200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462385990384696299e+01,2.199300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462476899474697234e+01,2.199399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462567808564698169e+01,2.199500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462658717654699103e+01,2.199600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462749626744700038e+01,2.199699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462840535834700972e+01,2.199800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.462931444924701907e+01,2.199900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463022354014702842e+01,2.200000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463113263104703776e+01,2.200099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463204172194704711e+01,2.200200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463295081284705645e+01,2.200300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463385990374706580e+01,2.200399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463476899464707515e+01,2.200500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463567808554708449e+01,2.200600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463658717644709384e+01,2.200699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463749626734710318e+01,2.200800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463840535824711253e+01,2.200900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.463931444914712188e+01,2.200999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464022354004713122e+01,2.201100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464113263094714057e+01,2.201200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464204172184714992e+01,2.201299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464295081274715926e+01,2.201400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464385990364716861e+01,2.201500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464476899454717795e+01,2.201599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464567808544718730e+01,2.201700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464658717634719665e+01,2.201800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464749626724720599e+01,2.201899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464840535814721534e+01,2.202000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.464931444904722468e+01,2.202100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465022353994723403e+01,2.202199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465113263084724338e+01,2.202300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465204172174725272e+01,2.202400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465295081264726207e+01,2.202500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465385990354727141e+01,2.202599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465476899444728076e+01,2.202700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465567808534729011e+01,2.202800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465658717624729945e+01,2.202899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465749626714730880e+01,2.203000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465840535804731815e+01,2.203100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.465931444894732749e+01,2.203199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466022353984733684e+01,2.203300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466113263074734618e+01,2.203400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466204172164735553e+01,2.203499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466295081254736488e+01,2.203600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466385990344737422e+01,2.203700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466476899434738357e+01,2.203799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466567808524739291e+01,2.203900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466658717614740226e+01,2.204000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466749626704741161e+01,2.204099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466840535794742095e+01,2.204200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.466931444884743030e+01,2.204300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467022353974743964e+01,2.204399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467113263064744899e+01,2.204500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467204172154745834e+01,2.204600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467295081244746768e+01,2.204699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467385990334747703e+01,2.204800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467476899424748638e+01,2.204900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467567808514749572e+01,2.205000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467658717604750507e+01,2.205099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467749626694751441e+01,2.205200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467840535784752376e+01,2.205300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.467931444874753311e+01,2.205399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468022353964754245e+01,2.205500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468113263054755180e+01,2.205600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468204172144756114e+01,2.205699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468295081234757049e+01,2.205800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468385990324757984e+01,2.205900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468476899414758918e+01,2.205999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468567808504759853e+01,2.206100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468658717594760788e+01,2.206200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468749626684761722e+01,2.206299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468840535774762657e+01,2.206400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.468931444864763591e+01,2.206500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469022353954764526e+01,2.206599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469113263044765461e+01,2.206700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469204172134766395e+01,2.206800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469295081224767330e+01,2.206899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469385990314768264e+01,2.207000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469476899404769199e+01,2.207100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469567808494770134e+01,2.207199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469658717584771068e+01,2.207300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469749626674772003e+01,2.207400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469840535764772937e+01,2.207500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.469931444854773872e+01,2.207599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470022353944774807e+01,2.207700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470113263034775741e+01,2.207800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470204172124776676e+01,2.207899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470295081214777611e+01,2.208000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470385990304778545e+01,2.208100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470476899394779480e+01,2.208199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470567808484780414e+01,2.208300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470658717574781349e+01,2.208400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470749626664782284e+01,2.208499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470840535754783218e+01,2.208600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.470931444844784153e+01,2.208700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471022353934785087e+01,2.208799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471113263024786022e+01,2.208900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471204172114786957e+01,2.209000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471295081204787891e+01,2.209099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471385990294788826e+01,2.209200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471476899384789760e+01,2.209300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471567808474790695e+01,2.209399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471658717564791630e+01,2.209500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471749626654792564e+01,2.209600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471840535744793499e+01,2.209699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.471931444834794434e+01,2.209800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472022353924795368e+01,2.209900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472113263014796303e+01,2.210000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472204172104797237e+01,2.210099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472295081194798172e+01,2.210200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472385990284799107e+01,2.210300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472476899374800041e+01,2.210399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472567808464800976e+01,2.210500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472658717554801910e+01,2.210600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472749626644802845e+01,2.210699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472840535734803780e+01,2.210800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.472931444824804714e+01,2.210900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473022353914805649e+01,2.210999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473113263004806583e+01,2.211100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473204172094807518e+01,2.211200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473295081184808453e+01,2.211299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473385990274809387e+01,2.211400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473476899364810322e+01,2.211500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473567808454811257e+01,2.211599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473658717544812191e+01,2.211700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473749626634813126e+01,2.211800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473840535724814060e+01,2.211899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.473931444814814995e+01,2.212000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474022353904815930e+01,2.212100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474113262994816864e+01,2.212199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474204172084817799e+01,2.212300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474295081174818733e+01,2.212400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474385990264819668e+01,2.212500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474476899354820603e+01,2.212599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474567808444821537e+01,2.212700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474658717534822472e+01,2.212800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474749626624823406e+01,2.212899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474840535714824341e+01,2.213000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.474931444804825276e+01,2.213100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475022353894826210e+01,2.213199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475113262984827145e+01,2.213300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475204172074828080e+01,2.213400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475295081164829014e+01,2.213499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475385990254829949e+01,2.213600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475476899344830883e+01,2.213700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475567808434831818e+01,2.213799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475658717524832753e+01,2.213900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475749626614833687e+01,2.214000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475840535704834622e+01,2.214099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.475931444794835556e+01,2.214200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476022353884836491e+01,2.214300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476113262974837426e+01,2.214399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476204172064838360e+01,2.214500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476295081154839295e+01,2.214600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476385990244840229e+01,2.214699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476476899334841164e+01,2.214800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476567808424842099e+01,2.214900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476658717514843033e+01,2.215000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476749626604843968e+01,2.215099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476840535694844903e+01,2.215200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.476931444784845837e+01,2.215300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477022353874846772e+01,2.215399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477113262964847706e+01,2.215500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477204172054848641e+01,2.215600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477295081144849576e+01,2.215699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477385990234850510e+01,2.215800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477476899324851445e+01,2.215900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477567808414852379e+01,2.215999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477658717504853314e+01,2.216100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477749626594854249e+01,2.216200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477840535684855183e+01,2.216299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.477931444774856118e+01,2.216400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478022353864857052e+01,2.216500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478113262954857987e+01,2.216599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478204172044858922e+01,2.216700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478295081134859856e+01,2.216800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478385990224860791e+01,2.216899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478476899314861726e+01,2.217000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478567808404862660e+01,2.217100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478658717494863595e+01,2.217199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478749626584864529e+01,2.217300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478840535674865464e+01,2.217400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.478931444764866399e+01,2.217500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479022353854867333e+01,2.217599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479113262944868268e+01,2.217700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479204172034869202e+01,2.217800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479295081124870137e+01,2.217899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479385990214871072e+01,2.218000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479476899304872006e+01,2.218100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479567808394872941e+01,2.218199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479658717484873875e+01,2.218300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479749626574874810e+01,2.218400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479840535664875745e+01,2.218499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.479931444754876679e+01,2.218600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480022353844877614e+01,2.218700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480113262934878549e+01,2.218799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480204172024879483e+01,2.218900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480295081114880418e+01,2.219000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480385990204881352e+01,2.219099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480476899294882287e+01,2.219200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480567808384883222e+01,2.219300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480658717474884156e+01,2.219399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480749626564885091e+01,2.219500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480840535654886025e+01,2.219600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.480931444744886960e+01,2.219699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481022353834887895e+01,2.219800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481113262924888829e+01,2.219900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481204172014889764e+01,2.220000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481295081104890698e+01,2.220099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481385990194891633e+01,2.220200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481476899284892568e+01,2.220300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481567808374893502e+01,2.220399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481658717464894437e+01,2.220500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481749626554895372e+01,2.220600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481840535644896306e+01,2.220699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.481931444734897241e+01,2.220800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482022353824898175e+01,2.220900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482113262914899110e+01,2.220999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482204172004900045e+01,2.221100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482295081094900979e+01,2.221200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482385990184901914e+01,2.221299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482476899274902848e+01,2.221400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482567808364903783e+01,2.221500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482658717454904718e+01,2.221599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482749626544905652e+01,2.221700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482840535634906587e+01,2.221800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.482931444724907522e+01,2.221899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483022353814908456e+01,2.222000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483113262904909391e+01,2.222100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483204171994910325e+01,2.222199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483295081084911260e+01,2.222300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483385990174912195e+01,2.222400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483476899264913129e+01,2.222500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483567808354914064e+01,2.222599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483658717444914998e+01,2.222700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483749626534915933e+01,2.222800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483840535624916868e+01,2.222899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.483931444714917802e+01,2.223000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484022353804918737e+01,2.223100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484113262894919671e+01,2.223199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484204171984920606e+01,2.223300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484295081074921541e+01,2.223400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484385990164922475e+01,2.223499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484476899254923410e+01,2.223600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484567808344924345e+01,2.223700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484658717434925279e+01,2.223799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484749626524926214e+01,2.223900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484840535614927148e+01,2.224000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.484931444704928083e+01,2.224099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485022353794929018e+01,2.224200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485113262884929952e+01,2.224300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485204171974930887e+01,2.224399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485295081064931821e+01,2.224500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485385990154932756e+01,2.224600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485476899244933691e+01,2.224699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485567808334934625e+01,2.224800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485658717424935560e+01,2.224900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485749626514936494e+01,2.225000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485840535604937429e+01,2.225099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.485931444694938364e+01,2.225200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486022353784939298e+01,2.225300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486113262874940233e+01,2.225399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486204171964941168e+01,2.225500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486295081054942102e+01,2.225600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486385990144943037e+01,2.225699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486476899234943971e+01,2.225800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486567808324944906e+01,2.225900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486658717414945841e+01,2.225999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486749626504946775e+01,2.226100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486840535594947710e+01,2.226200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.486931444684948644e+01,2.226299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487022353774949579e+01,2.226400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487113262864950514e+01,2.226500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487204171954951448e+01,2.226599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487295081044952383e+01,2.226700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487385990134953317e+01,2.226800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487476899224954252e+01,2.226899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487567808314955187e+01,2.227000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487658717404956121e+01,2.227100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487749626494957056e+01,2.227199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487840535584957991e+01,2.227300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.487931444674958925e+01,2.227400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488022353764959860e+01,2.227500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488113262854960794e+01,2.227599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488204171944961729e+01,2.227700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488295081034962664e+01,2.227800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488385990124963598e+01,2.227899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488476899214964533e+01,2.228000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488567808304965467e+01,2.228100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488658717394966402e+01,2.228199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488749626484967337e+01,2.228300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488840535574968271e+01,2.228400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.488931444664969206e+01,2.228499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489022353754970140e+01,2.228600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489113262844971075e+01,2.228700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489204171934972010e+01,2.228799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489295081024972944e+01,2.228900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489385990114973879e+01,2.229000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489476899204974814e+01,2.229099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489567808294975748e+01,2.229200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489658717384976683e+01,2.229300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489749626474977617e+01,2.229399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489840535564978552e+01,2.229500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.489931444654979487e+01,2.229600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490022353744980421e+01,2.229699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490113262834981356e+01,2.229800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490204171924982290e+01,2.229900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490295081014983225e+01,2.230000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490385990104984160e+01,2.230099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490476899194985094e+01,2.230200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490567808284986029e+01,2.230300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490658717374986963e+01,2.230399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490749626464987898e+01,2.230500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490840535554988833e+01,2.230600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.490931444644989767e+01,2.230699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491022353734990702e+01,2.230800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491113262824991637e+01,2.230900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491204171914992571e+01,2.230999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491295081004993506e+01,2.231100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491385990094994440e+01,2.231200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491476899184995375e+01,2.231299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491567808274996310e+01,2.231400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491658717364997244e+01,2.231500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491749626454998179e+01,2.231599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491840535544999113e+01,2.231700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.491931444635000048e+01,2.231800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492022353725000983e+01,2.231899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492113262815001917e+01,2.232000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492204171905002852e+01,2.232100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492295080995003786e+01,2.232199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492385990085004721e+01,2.232300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492476899175005656e+01,2.232400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492567808265006590e+01,2.232500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492658717355007525e+01,2.232599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492749626445008460e+01,2.232700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492840535535009394e+01,2.232800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.492931444625010329e+01,2.232899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493022353715011263e+01,2.233000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493113262805012198e+01,2.233100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493204171895013133e+01,2.233199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493295080985014067e+01,2.233300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493385990075015002e+01,2.233400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493476899165015936e+01,2.233499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493567808255016871e+01,2.233600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493658717345017806e+01,2.233700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493749626435018740e+01,2.233799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493840535525019675e+01,2.233900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.493931444615020609e+01,2.234000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494022353705021544e+01,2.234099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494113262795022479e+01,2.234200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494204171885023413e+01,2.234300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494295080975024348e+01,2.234399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494385990065025283e+01,2.234500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494476899155026217e+01,2.234600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494567808245027152e+01,2.234699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494658717335028086e+01,2.234800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494749626425029021e+01,2.234900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494840535515029956e+01,2.235000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.494931444605030890e+01,2.235099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495022353695031825e+01,2.235200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495113262785032759e+01,2.235300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495204171875033694e+01,2.235399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495295080965034629e+01,2.235500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495385990055035563e+01,2.235600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495476899145036498e+01,2.235699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495567808235037432e+01,2.235800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495658717325038367e+01,2.235900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495749626415039302e+01,2.235999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495840535505040236e+01,2.236100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.495931444595041171e+01,2.236200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496022353685042106e+01,2.236299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496113262775043040e+01,2.236400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496204171865043975e+01,2.236500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496295080955044909e+01,2.236599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496385990045045844e+01,2.236700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496476899135046779e+01,2.236800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496567808225047713e+01,2.236899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496658717315048648e+01,2.237000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496749626405049582e+01,2.237100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496840535495050517e+01,2.237199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.496931444585051452e+01,2.237300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497022353675052386e+01,2.237400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497113262765053321e+01,2.237500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497204171855054256e+01,2.237599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497295080945055190e+01,2.237700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497385990035056125e+01,2.237800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497476899125057059e+01,2.237899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497567808215057994e+01,2.238000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497658717305058929e+01,2.238100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497749626395059863e+01,2.238199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497840535485060798e+01,2.238300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.497931444575061732e+01,2.238400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498022353665062667e+01,2.238499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498113262755063602e+01,2.238600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498204171845064536e+01,2.238700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498295080935065471e+01,2.238799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498385990025066405e+01,2.238900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498476899115067340e+01,2.239000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498567808205068275e+01,2.239099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498658717295069209e+01,2.239200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498749626385070144e+01,2.239300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498840535475071079e+01,2.239399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.498931444565072013e+01,2.239500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499022353655072948e+01,2.239600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499113262745073882e+01,2.239699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499204171835074817e+01,2.239800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499295080925075752e+01,2.239900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499385990015076686e+01,2.240000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499476899105077621e+01,2.240099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499567808195078555e+01,2.240200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499658717285079490e+01,2.240300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499749626375080425e+01,2.240399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499840535465081359e+01,2.240500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.499931444555082294e+01,2.240600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500022353645083228e+01,2.240699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500113262735084163e+01,2.240800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500204171825085098e+01,2.240900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500295080915086032e+01,2.240999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500385990005086967e+01,2.241100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500476899095087902e+01,2.241200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500567808185088836e+01,2.241299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500658717275089771e+01,2.241400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500749626365090705e+01,2.241500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500840535455091640e+01,2.241599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.500931444545092575e+01,2.241700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501022353635093509e+01,2.241800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501113262725094444e+01,2.241899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501204171815095378e+01,2.242000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501295080905096313e+01,2.242100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501385989995097248e+01,2.242199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501476899085098182e+01,2.242300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501567808175099117e+01,2.242400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501658717265100051e+01,2.242500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501749626355100986e+01,2.242599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501840535445101921e+01,2.242700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.501931444535102855e+01,2.242800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502022353625103790e+01,2.242899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502113262715104725e+01,2.243000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502204171805105659e+01,2.243100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502295080895106594e+01,2.243199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502385989985107528e+01,2.243300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502476899075108463e+01,2.243400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502567808165109398e+01,2.243499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502658717255110332e+01,2.243600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502749626345111267e+01,2.243700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502840535435112201e+01,2.243799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.502931444525113136e+01,2.243900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503022353615114071e+01,2.244000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503113262705115005e+01,2.244099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503204171795115940e+01,2.244200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503295080885116874e+01,2.244300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503385989975117809e+01,2.244399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503476899065118744e+01,2.244500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503567808155119678e+01,2.244600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503658717245120613e+01,2.244699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503749626335121548e+01,2.244800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503840535425122482e+01,2.244900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.503931444515123417e+01,2.245000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504022353605124351e+01,2.245099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504113262695125286e+01,2.245200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504204171785126221e+01,2.245300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504295080875127155e+01,2.245399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504385989965128090e+01,2.245500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504476899055129024e+01,2.245600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504567808145129959e+01,2.245699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504658717235130894e+01,2.245800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504749626325131828e+01,2.245900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504840535415132763e+01,2.245999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.504931444505133697e+01,2.246100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505022353595134632e+01,2.246200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505113262685135567e+01,2.246299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505204171775136501e+01,2.246400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505295080865137436e+01,2.246500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505385989955138371e+01,2.246599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505476899045139305e+01,2.246700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505567808135140240e+01,2.246800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505658717225141174e+01,2.246899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505749626315142109e+01,2.247000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505840535405143044e+01,2.247100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.505931444495143978e+01,2.247199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506022353585144913e+01,2.247300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506113262675145847e+01,2.247400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506204171765146782e+01,2.247500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506295080855147717e+01,2.247599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506385989945148651e+01,2.247700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506476899035149586e+01,2.247800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506567808125150520e+01,2.247899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506658717215151455e+01,2.248000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506749626305152390e+01,2.248100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506840535395153324e+01,2.248199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.506931444485154259e+01,2.248300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507022353575155194e+01,2.248400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507113262665156128e+01,2.248499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507204171755157063e+01,2.248600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507295080845157997e+01,2.248700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507385989935158932e+01,2.248799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507476899025159867e+01,2.248900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507567808115160801e+01,2.249000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507658717205161736e+01,2.249099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507749626295162670e+01,2.249200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507840535385163605e+01,2.249300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.507931444475164540e+01,2.249399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508022353565165474e+01,2.249500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508113262655166409e+01,2.249600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508204171745167343e+01,2.249699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508295080835168278e+01,2.249800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508385989925169213e+01,2.249900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508476899015170147e+01,2.250000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508567808105171082e+01,2.250099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508658717195172017e+01,2.250200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508749626285172951e+01,2.250300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508840535375173886e+01,2.250399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.508931444465174820e+01,2.250500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509022353555175755e+01,2.250600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509113262645176690e+01,2.250699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509204171735177624e+01,2.250800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509295080825178559e+01,2.250900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509385989915179493e+01,2.250999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509476899005180428e+01,2.251100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509567808095181363e+01,2.251200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509658717185182297e+01,2.251299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509749626275183232e+01,2.251400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509840535365184166e+01,2.251500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.509931444455185101e+01,2.251599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510022353545186036e+01,2.251700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510113262635186970e+01,2.251800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510204171725187905e+01,2.251899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510295080815188840e+01,2.252000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510385989905189774e+01,2.252100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510476898995190709e+01,2.252199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510567808085191643e+01,2.252300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510658717175192578e+01,2.252400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510749626265193513e+01,2.252500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510840535355194447e+01,2.252599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.510931444445195382e+01,2.252700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511022353535196316e+01,2.252800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511113262625197251e+01,2.252899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511204171715198186e+01,2.253000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511295080805199120e+01,2.253100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511385989895200055e+01,2.253199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511476898985200990e+01,2.253300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511567808075201924e+01,2.253400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511658717165202859e+01,2.253499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511749626255203793e+01,2.253600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511840535345204728e+01,2.253700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.511931444435205663e+01,2.253799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512022353525206597e+01,2.253900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512113262615207532e+01,2.254000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512204171705208466e+01,2.254099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512295080795209401e+01,2.254200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512385989885210336e+01,2.254300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512476898975211270e+01,2.254399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512567808065212205e+01,2.254500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512658717155213139e+01,2.254600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512749626245214074e+01,2.254699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512840535335215009e+01,2.254800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.512931444425215943e+01,2.254900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513022353515216878e+01,2.255000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513113262605217813e+01,2.255099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513204171695218747e+01,2.255200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513295080785219682e+01,2.255300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513385989875220616e+01,2.255399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513476898965221551e+01,2.255500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513567808055222486e+01,2.255600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513658717145223420e+01,2.255699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513749626235224355e+01,2.255800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513840535325225289e+01,2.255900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.513931444415226224e+01,2.255999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514022353505227159e+01,2.256100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514113262595228093e+01,2.256200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514204171685229028e+01,2.256299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514295080775229962e+01,2.256400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514385989865230897e+01,2.256500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514476898955231832e+01,2.256599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514567808045232766e+01,2.256700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514658717135233701e+01,2.256800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514749626225234636e+01,2.256899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514840535315235570e+01,2.257000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.514931444405236505e+01,2.257100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515022353495237439e+01,2.257199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515113262585238374e+01,2.257300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515204171675239309e+01,2.257400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515295080765240243e+01,2.257500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515385989855241178e+01,2.257599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515476898945242112e+01,2.257700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515567808035243047e+01,2.257800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515658717125243982e+01,2.257899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515749626215244916e+01,2.258000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515840535305245851e+01,2.258100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.515931444395246785e+01,2.258199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516022353485247720e+01,2.258300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516113262575248655e+01,2.258400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516204171665249589e+01,2.258499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516295080755250524e+01,2.258600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516385989845251459e+01,2.258700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516476898935252393e+01,2.258799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516567808025253328e+01,2.258900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516658717115254262e+01,2.259000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516749626205255197e+01,2.259099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516840535295256132e+01,2.259200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.516931444385257066e+01,2.259300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517022353475258001e+01,2.259399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517113262565258935e+01,2.259500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517204171655259870e+01,2.259600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517295080745260805e+01,2.259699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517385989835261739e+01,2.259800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517476898925262674e+01,2.259900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517567808015263608e+01,2.260000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517658717105264543e+01,2.260099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517749626195265478e+01,2.260200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517840535285266412e+01,2.260300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.517931444375267347e+01,2.260399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518022353465268282e+01,2.260500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518113262555269216e+01,2.260600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518204171645270151e+01,2.260699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518295080735271085e+01,2.260800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518385989825272020e+01,2.260900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518476898915272955e+01,2.260999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518567808005273889e+01,2.261100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518658717095274824e+01,2.261200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518749626185275758e+01,2.261299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518840535275276693e+01,2.261400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.518931444365277628e+01,2.261500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519022353455278562e+01,2.261599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519113262545279497e+01,2.261700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519204171635280431e+01,2.261800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519295080725281366e+01,2.261899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519385989815282301e+01,2.262000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519476898905283235e+01,2.262100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519567807995284170e+01,2.262199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519658717085285105e+01,2.262300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519749626175286039e+01,2.262400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519840535265286974e+01,2.262500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.519931444355287908e+01,2.262599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520022353445288843e+01,2.262700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520113262535289778e+01,2.262800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520204171625290712e+01,2.262899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520295080715291647e+01,2.263000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520385989805292581e+01,2.263100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520476898895293516e+01,2.263199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520567807985294451e+01,2.263300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520658717075295385e+01,2.263400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520749626165296320e+01,2.263499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520840535255297254e+01,2.263600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.520931444345298189e+01,2.263700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521022353435299124e+01,2.263799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521113262525300058e+01,2.263900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521204171615300993e+01,2.264000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521295080705301928e+01,2.264099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521385989795302862e+01,2.264200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521476898885303797e+01,2.264300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521567807975304731e+01,2.264399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521658717065305666e+01,2.264500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521749626155306601e+01,2.264600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521840535245307535e+01,2.264699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.521931444335308470e+01,2.264800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522022353425309404e+01,2.264900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522113262515310339e+01,2.265000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522204171605311274e+01,2.265099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522295080695312208e+01,2.265200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522385989785313143e+01,2.265300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522476898875314077e+01,2.265399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522567807965315012e+01,2.265500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522658717055315947e+01,2.265600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522749626145316881e+01,2.265699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522840535235317816e+01,2.265800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.522931444325318751e+01,2.265900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523022353415319685e+01,2.265999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523113262505320620e+01,2.266100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523204171595321554e+01,2.266200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523295080685322489e+01,2.266299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523385989775323424e+01,2.266400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523476898865324358e+01,2.266500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523567807955325293e+01,2.266599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523658717045326227e+01,2.266700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523749626135327162e+01,2.266800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523840535225328097e+01,2.266899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.523931444315329031e+01,2.267000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524022353405329966e+01,2.267100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524113262495330900e+01,2.267199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524204171585331835e+01,2.267300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524295080675332770e+01,2.267400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524385989765333704e+01,2.267500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524476898855334639e+01,2.267599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524567807945335574e+01,2.267700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524658717035336508e+01,2.267800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524749626125337443e+01,2.267899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524840535215338377e+01,2.268000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.524931444305339312e+01,2.268100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525022353395340247e+01,2.268199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525113262485341181e+01,2.268300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525204171575342116e+01,2.268400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525295080665343050e+01,2.268499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525385989755343985e+01,2.268600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525476898845344920e+01,2.268700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525567807935345854e+01,2.268799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525658717025346789e+01,2.268900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525749626115347723e+01,2.269000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525840535205348658e+01,2.269099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.525931444295349593e+01,2.269200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526022353385350527e+01,2.269300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526113262475351462e+01,2.269399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526204171565352397e+01,2.269500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526295080655353331e+01,2.269600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526385989745354266e+01,2.269699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526476898835355200e+01,2.269800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526567807925356135e+01,2.269900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526658717015357070e+01,2.270000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526749626105358004e+01,2.270099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526840535195358939e+01,2.270200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.526931444285359873e+01,2.270300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527022353375360808e+01,2.270399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527113262465361743e+01,2.270500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527204171555362677e+01,2.270600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527295080645363612e+01,2.270699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527385989735364547e+01,2.270800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527476898825365481e+01,2.270900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527567807915366416e+01,2.270999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527658717005367350e+01,2.271100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527749626095368285e+01,2.271200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527840535185369220e+01,2.271299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.527931444275370154e+01,2.271400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528022353365371089e+01,2.271500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528113262455372023e+01,2.271599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528204171545372958e+01,2.271700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528295080635373893e+01,2.271800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528385989725374827e+01,2.271899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528476898815375762e+01,2.272000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528567807905376696e+01,2.272100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528658716995377631e+01,2.272199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528749626085378566e+01,2.272300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528840535175379500e+01,2.272400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.528931444265380435e+01,2.272500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529022353355381370e+01,2.272599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529113262445382304e+01,2.272700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529204171535383239e+01,2.272800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529295080625384173e+01,2.272899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529385989715385108e+01,2.273000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529476898805386043e+01,2.273100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529567807895386977e+01,2.273199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529658716985387912e+01,2.273300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529749626075388846e+01,2.273400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529840535165389781e+01,2.273499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.529931444255390716e+01,2.273600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530022353345391650e+01,2.273700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530113262435392585e+01,2.273799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530204171525393519e+01,2.273900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530295080615394454e+01,2.274000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530385989705395389e+01,2.274099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530476898795396323e+01,2.274200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530567807885397258e+01,2.274300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530658716975398193e+01,2.274399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530749626065399127e+01,2.274500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530840535155400062e+01,2.274600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.530931444245400996e+01,2.274699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531022353335401931e+01,2.274800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531113262425402866e+01,2.274900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531204171515403800e+01,2.275000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531295080605404735e+01,2.275099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531385989695405669e+01,2.275200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531476898785406604e+01,2.275300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531567807875407539e+01,2.275399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531658716965408473e+01,2.275500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531749626055409408e+01,2.275600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531840535145410342e+01,2.275699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.531931444235411277e+01,2.275800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532022353325412212e+01,2.275900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532113262415413146e+01,2.275999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532204171505414081e+01,2.276100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532295080595415016e+01,2.276200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532385989685415950e+01,2.276299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532476898775416885e+01,2.276400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532567807865417819e+01,2.276500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532658716955418754e+01,2.276599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532749626045419689e+01,2.276700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532840535135420623e+01,2.276800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.532931444225421558e+01,2.276899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533022353315422492e+01,2.277000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533113262405423427e+01,2.277100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533204171495424362e+01,2.277199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533295080585425296e+01,2.277300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533385989675426231e+01,2.277400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533476898765427165e+01,2.277500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533567807855428100e+01,2.277599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533658716945429035e+01,2.277700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533749626035429969e+01,2.277800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533840535125430904e+01,2.277899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.533931444215431839e+01,2.278000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534022353305432773e+01,2.278100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534113262395433708e+01,2.278199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534204171485434642e+01,2.278300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534295080575435577e+01,2.278400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534385989665436512e+01,2.278499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534476898755437446e+01,2.278600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534567807845438381e+01,2.278700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534658716935439315e+01,2.278799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534749626025440250e+01,2.278900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534840535115441185e+01,2.279000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.534931444205442119e+01,2.279099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535022353295443054e+01,2.279200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535113262385443988e+01,2.279300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535204171475444923e+01,2.279399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535295080565445858e+01,2.279500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535385989655446792e+01,2.279600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535476898745447727e+01,2.279699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535567807835448662e+01,2.279800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535658716925449596e+01,2.279900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535749626015450531e+01,2.280000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535840535105451465e+01,2.280099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.535931444195452400e+01,2.280200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536022353285453335e+01,2.280300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536113262375454269e+01,2.280399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536204171465455204e+01,2.280500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536295080555456138e+01,2.280600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536385989645457073e+01,2.280699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536476898735458008e+01,2.280800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536567807825458942e+01,2.280900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536658716915459877e+01,2.280999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536749626005460811e+01,2.281100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536840535095461746e+01,2.281200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.536931444185462681e+01,2.281299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537022353275463615e+01,2.281400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537113262365464550e+01,2.281500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537204171455465485e+01,2.281599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537295080545466419e+01,2.281700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537385989635467354e+01,2.281800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537476898725468288e+01,2.281899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537567807815469223e+01,2.282000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537658716905470158e+01,2.282100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537749625995471092e+01,2.282199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537840535085472027e+01,2.282300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.537931444175472961e+01,2.282400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538022353265473896e+01,2.282500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538113262355474831e+01,2.282599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538204171445475765e+01,2.282700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538295080535476700e+01,2.282800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538385989625477634e+01,2.282899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538476898715478569e+01,2.283000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538567807805479504e+01,2.283100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538658716895480438e+01,2.283199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538749625985481373e+01,2.283300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538840535075482308e+01,2.283400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.538931444165483242e+01,2.283499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539022353255484177e+01,2.283600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539113262345485111e+01,2.283700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539204171435486046e+01,2.283799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539295080525486981e+01,2.283900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539385989615487915e+01,2.284000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539476898705488850e+01,2.284099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539567807795489784e+01,2.284200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539658716885490719e+01,2.284300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539749625975491654e+01,2.284399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539840535065492588e+01,2.284500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.539931444155493523e+01,2.284600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540022353245494457e+01,2.284699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540113262335495392e+01,2.284800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540204171425496327e+01,2.284900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540295080515497261e+01,2.285000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540385989605498196e+01,2.285099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540476898695499131e+01,2.285200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540567807785500065e+01,2.285300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540658716875501000e+01,2.285399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540749625965501934e+01,2.285500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540840535055502869e+01,2.285600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.540931444145503804e+01,2.285699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541022353235504738e+01,2.285800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541113262325505673e+01,2.285900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541204171415506607e+01,2.285999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541295080505507542e+01,2.286100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541385989595508477e+01,2.286200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541476898685509411e+01,2.286299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541567807775510346e+01,2.286400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541658716865511281e+01,2.286500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541749625955512215e+01,2.286599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541840535045513150e+01,2.286700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.541931444135514084e+01,2.286800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542022353225515019e+01,2.286899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542113262315515954e+01,2.287000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542204171405516888e+01,2.287100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542295080495517823e+01,2.287199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542385989585518757e+01,2.287300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542476898675519692e+01,2.287400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542567807765520627e+01,2.287500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542658716855521561e+01,2.287599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542749625945522496e+01,2.287700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542840535035523430e+01,2.287800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.542931444125524365e+01,2.287899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543022353215525300e+01,2.288000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543113262305526234e+01,2.288100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543204171395527169e+01,2.288199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543295080485528104e+01,2.288300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543385989575529038e+01,2.288400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543476898665529973e+01,2.288499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543567807755530907e+01,2.288600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543658716845531842e+01,2.288700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543749625935532777e+01,2.288799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543840535025533711e+01,2.288900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.543931444115534646e+01,2.289000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544022353205535580e+01,2.289099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544113262295536515e+01,2.289200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544204171385537450e+01,2.289300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544295080475538384e+01,2.289399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544385989565539319e+01,2.289500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544476898655540253e+01,2.289600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544567807745541188e+01,2.289699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544658716835542123e+01,2.289800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544749625925543057e+01,2.289900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544840535015543992e+01,2.290000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.544931444105544927e+01,2.290099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545022353195545861e+01,2.290200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545113262285546796e+01,2.290300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545204171375547730e+01,2.290399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545295080465548665e+01,2.290500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545385989555549600e+01,2.290600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545476898645550534e+01,2.290699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545567807735551469e+01,2.290800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545658716825552403e+01,2.290900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545749625915553338e+01,2.290999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545840535005554273e+01,2.291100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.545931444095555207e+01,2.291200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546022353185556142e+01,2.291299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546113262275557076e+01,2.291400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546204171365558011e+01,2.291500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546295080455558946e+01,2.291599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546385989545559880e+01,2.291700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546476898635560815e+01,2.291800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546567807725561750e+01,2.291899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546658716815562684e+01,2.292000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546749625905563619e+01,2.292100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546840534995564553e+01,2.292199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.546931444085565488e+01,2.292300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547022353175566423e+01,2.292400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547113262265567357e+01,2.292500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547204171355568292e+01,2.292599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547295080445569226e+01,2.292700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547385989535570161e+01,2.292800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547476898625571096e+01,2.292899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547567807715572030e+01,2.293000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547658716805572965e+01,2.293100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547749625895573899e+01,2.293199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547840534985574834e+01,2.293300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.547931444075575769e+01,2.293400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548022353165576703e+01,2.293499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548113262255577638e+01,2.293600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548204171345578573e+01,2.293700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548295080435579507e+01,2.293799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548385989525580442e+01,2.293900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548476898615581376e+01,2.294000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548567807705582311e+01,2.294099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548658716795583246e+01,2.294200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548749625885584180e+01,2.294300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548840534975585115e+01,2.294399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.548931444065586049e+01,2.294500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549022353155586984e+01,2.294600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549113262245587919e+01,2.294699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549204171335588853e+01,2.294800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549295080425589788e+01,2.294900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549385989515590722e+01,2.295000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549476898605591657e+01,2.295099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549567807695592592e+01,2.295200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549658716785593526e+01,2.295300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549749625875594461e+01,2.295399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549840534965595396e+01,2.295500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.549931444055596330e+01,2.295600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550022353145597265e+01,2.295699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550113262235598199e+01,2.295800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550204171325599134e+01,2.295900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550295080415600069e+01,2.295999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550385989505601003e+01,2.296100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550476898595601938e+01,2.296200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550567807685602872e+01,2.296299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550658716775603807e+01,2.296400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550749625865604742e+01,2.296500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550840534955605676e+01,2.296599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.550931444045606611e+01,2.296700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551022353135607545e+01,2.296800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551113262225608480e+01,2.296899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551204171315609415e+01,2.297000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551295080405610349e+01,2.297100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551385989495611284e+01,2.297199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551476898585612219e+01,2.297300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551567807675613153e+01,2.297400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551658716765614088e+01,2.297500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551749625855615022e+01,2.297599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551840534945615957e+01,2.297700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.551931444035616892e+01,2.297800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552022353125617826e+01,2.297899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552113262215618761e+01,2.298000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552204171305619695e+01,2.298100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552295080395620630e+01,2.298199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552385989485621565e+01,2.298300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552476898575622499e+01,2.298400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552567807665623434e+01,2.298499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552658716755624368e+01,2.298600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552749625845625303e+01,2.298700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552840534935626238e+01,2.298799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.552931444025627172e+01,2.298900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553022353115628107e+01,2.299000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553113262205629042e+01,2.299099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553204171295629976e+01,2.299200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553295080385630911e+01,2.299300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553385989475631845e+01,2.299399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553476898565632780e+01,2.299500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553567807655633715e+01,2.299600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553658716745634649e+01,2.299699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553749625835635584e+01,2.299800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553840534925636518e+01,2.299900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.553931444015637453e+01,2.300000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554022353105638388e+01,2.300099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554113262195639322e+01,2.300200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554204171285640257e+01,2.300300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554295080375641191e+01,2.300399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554385989465642126e+01,2.300500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554476898555643061e+01,2.300600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554567807645643995e+01,2.300699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554658716735644930e+01,2.300800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554749625825645865e+01,2.300900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554840534915646799e+01,2.300999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.554931444005647734e+01,2.301100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555022353095648668e+01,2.301200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555113262185649603e+01,2.301299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555204171275650538e+01,2.301400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555295080365651472e+01,2.301500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555385989455652407e+01,2.301599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555476898545653341e+01,2.301700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555567807635654276e+01,2.301800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555658716725655211e+01,2.301899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555749625815656145e+01,2.302000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555840534905657080e+01,2.302100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.555931443995658015e+01,2.302199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556022353085658949e+01,2.302300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556113262175659884e+01,2.302400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556204171265660818e+01,2.302500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556295080355661753e+01,2.302599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556385989445662688e+01,2.302700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556476898535663622e+01,2.302800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556567807625664557e+01,2.302899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556658716715665491e+01,2.303000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556749625805666426e+01,2.303100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556840534895667361e+01,2.303199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.556931443985668295e+01,2.303300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557022353075669230e+01,2.303400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557113262165670164e+01,2.303499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557204171255671099e+01,2.303600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557295080345672034e+01,2.303700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557385989435672968e+01,2.303799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557476898525673903e+01,2.303900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557567807615674838e+01,2.304000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557658716705675772e+01,2.304099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557749625795676707e+01,2.304200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557840534885677641e+01,2.304300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.557931443975678576e+01,2.304399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558022353065679511e+01,2.304500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558113262155680445e+01,2.304600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558204171245681380e+01,2.304699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558295080335682314e+01,2.304800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558385989425683249e+01,2.304900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558476898515684184e+01,2.305000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558567807605685118e+01,2.305099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558658716695686053e+01,2.305200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558749625785686987e+01,2.305300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558840534875687922e+01,2.305399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.558931443965688857e+01,2.305500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559022353055689791e+01,2.305600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559113262145690726e+01,2.305699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559204171235691661e+01,2.305800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559295080325692595e+01,2.305900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559385989415693530e+01,2.305999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559476898505694464e+01,2.306100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559567807595695399e+01,2.306200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559658716685696334e+01,2.306299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559749625775697268e+01,2.306400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559840534865698203e+01,2.306500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.559931443955699137e+01,2.306599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560022353045700072e+01,2.306700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560113262135701007e+01,2.306800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560204171225701941e+01,2.306899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560295080315702876e+01,2.307000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560385989405703810e+01,2.307100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560476898495704745e+01,2.307199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560567807585705680e+01,2.307300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560658716675706614e+01,2.307400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560749625765707549e+01,2.307500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560840534855708484e+01,2.307599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.560931443945709418e+01,2.307700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561022353035710353e+01,2.307800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561113262125711287e+01,2.307899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561204171215712222e+01,2.308000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561295080305713157e+01,2.308100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561385989395714091e+01,2.308199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561476898485715026e+01,2.308300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561567807575715960e+01,2.308400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561658716665716895e+01,2.308499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561749625755717830e+01,2.308600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561840534845718764e+01,2.308700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.561931443935719699e+01,2.308799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562022353025720633e+01,2.308900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562113262115721568e+01,2.309000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562204171205722503e+01,2.309099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562295080295723437e+01,2.309200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562385989385724372e+01,2.309300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562476898475725307e+01,2.309399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562567807565726241e+01,2.309500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562658716655727176e+01,2.309600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562749625745728110e+01,2.309699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562840534835729045e+01,2.309800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.562931443925729980e+01,2.309900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563022353015730914e+01,2.310000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563113262105731849e+01,2.310099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563204171195732783e+01,2.310200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563295080285733718e+01,2.310300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563385989375734653e+01,2.310399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563476898465735587e+01,2.310500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563567807555736522e+01,2.310600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563658716645737456e+01,2.310699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563749625735738391e+01,2.310800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563840534825739326e+01,2.310900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.563931443915740260e+01,2.310999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564022353005741195e+01,2.311100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564113262095742130e+01,2.311200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564204171185743064e+01,2.311299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564295080275743999e+01,2.311400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564385989365744933e+01,2.311500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564476898455745868e+01,2.311599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564567807545746803e+01,2.311700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564658716635747737e+01,2.311800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564749625725748672e+01,2.311899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564840534815749606e+01,2.312000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.564931443905750541e+01,2.312100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565022352995751476e+01,2.312199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565113262085752410e+01,2.312300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565204171175753345e+01,2.312400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565295080265754279e+01,2.312500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565385989355755214e+01,2.312599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565476898445756149e+01,2.312700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565567807535757083e+01,2.312800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565658716625758018e+01,2.312899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565749625715758953e+01,2.313000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565840534805759887e+01,2.313100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.565931443895760822e+01,2.313199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566022352985761756e+01,2.313300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566113262075762691e+01,2.313400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566204171165763626e+01,2.313499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566295080255764560e+01,2.313600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566385989345765495e+01,2.313700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566476898435766429e+01,2.313799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566567807525767364e+01,2.313900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566658716615768299e+01,2.314000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566749625705769233e+01,2.314099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566840534795770168e+01,2.314200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.566931443885771102e+01,2.314300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567022352975772037e+01,2.314399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567113262065772972e+01,2.314500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567204171155773906e+01,2.314600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567295080245774841e+01,2.314699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567385989335775776e+01,2.314800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567476898425776710e+01,2.314900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567567807515777645e+01,2.315000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567658716605778579e+01,2.315099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567749625695779514e+01,2.315200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567840534785780449e+01,2.315300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.567931443875781383e+01,2.315399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568022352965782318e+01,2.315500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568113262055783252e+01,2.315600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568204171145784187e+01,2.315699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568295080235785122e+01,2.315800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568385989325786056e+01,2.315900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568476898415786991e+01,2.315999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568567807505787925e+01,2.316100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568658716595788860e+01,2.316200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568749625685789795e+01,2.316299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568840534775790729e+01,2.316400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.568931443865791664e+01,2.316500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569022352955792599e+01,2.316599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569113262045793533e+01,2.316700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569204171135794468e+01,2.316800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569295080225795402e+01,2.316899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569385989315796337e+01,2.317000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569476898405797272e+01,2.317100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569567807495798206e+01,2.317199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569658716585799141e+01,2.317300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569749625675800075e+01,2.317400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569840534765801010e+01,2.317500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.569931443855801945e+01,2.317599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570022352945802879e+01,2.317700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570113262035803814e+01,2.317800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570204171125804748e+01,2.317899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570295080215805683e+01,2.318000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570385989305806618e+01,2.318100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570476898395807552e+01,2.318199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570567807485808487e+01,2.318300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570658716575809422e+01,2.318400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570749625665810356e+01,2.318499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570840534755811291e+01,2.318600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.570931443845812225e+01,2.318700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571022352935813160e+01,2.318799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571113262025814095e+01,2.318900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571204171115815029e+01,2.319000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571295080205815964e+01,2.319099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571385989295816898e+01,2.319200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571476898385817833e+01,2.319300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571567807475818768e+01,2.319399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571658716565819702e+01,2.319500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571749625655820637e+01,2.319600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571840534745821572e+01,2.319699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.571931443835822506e+01,2.319800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572022352925823441e+01,2.319900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572113262015824375e+01,2.320000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572204171105825310e+01,2.320099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572295080195826245e+01,2.320200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572385989285827179e+01,2.320300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572476898375828114e+01,2.320399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572567807465829048e+01,2.320500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572658716555829983e+01,2.320600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572749625645830918e+01,2.320699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572840534735831852e+01,2.320800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.572931443825832787e+01,2.320900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573022352915833721e+01,2.320999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573113262005834656e+01,2.321100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573204171095835591e+01,2.321200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573295080185836525e+01,2.321299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573385989275837460e+01,2.321400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573476898365838395e+01,2.321500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573567807455839329e+01,2.321599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573658716545840264e+01,2.321700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573749625635841198e+01,2.321800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573840534725842133e+01,2.321899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.573931443815843068e+01,2.322000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574022352905844002e+01,2.322100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574113261995844937e+01,2.322199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574204171085845871e+01,2.322300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574295080175846806e+01,2.322400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574385989265847741e+01,2.322500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574476898355848675e+01,2.322599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574567807445849610e+01,2.322700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574658716535850544e+01,2.322800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574749625625851479e+01,2.322899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574840534715852414e+01,2.323000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.574931443805853348e+01,2.323100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575022352895854283e+01,2.323199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575113261985855218e+01,2.323300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575204171075856152e+01,2.323400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575295080165857087e+01,2.323499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575385989255858021e+01,2.323600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575476898345858956e+01,2.323700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575567807435859891e+01,2.323799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575658716525860825e+01,2.323900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575749625615861760e+01,2.324000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575840534705862694e+01,2.324099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.575931443795863629e+01,2.324200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576022352885864564e+01,2.324300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576113261975865498e+01,2.324399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576204171065866433e+01,2.324500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576295080155867367e+01,2.324600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576385989245868302e+01,2.324699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576476898335869237e+01,2.324800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576567807425870171e+01,2.324900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576658716515871106e+01,2.325000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576749625605872041e+01,2.325099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576840534695872975e+01,2.325200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.576931443785873910e+01,2.325300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577022352875874844e+01,2.325399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577113261965875779e+01,2.325500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577204171055876714e+01,2.325600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577295080145877648e+01,2.325699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577385989235878583e+01,2.325800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577476898325879517e+01,2.325900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577567807415880452e+01,2.325999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577658716505881387e+01,2.326100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577749625595882321e+01,2.326200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577840534685883256e+01,2.326299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.577931443775884190e+01,2.326400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578022352865885125e+01,2.326500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578113261955886060e+01,2.326599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578204171045886994e+01,2.326700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578295080135887929e+01,2.326800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578385989225888864e+01,2.326899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578476898315889798e+01,2.327000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578567807405890733e+01,2.327100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578658716495891667e+01,2.327199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578749625585892602e+01,2.327300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578840534675893537e+01,2.327400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.578931443765894471e+01,2.327500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579022352855895406e+01,2.327599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579113261945896340e+01,2.327700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579204171035897275e+01,2.327800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579295080125898210e+01,2.327899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579385989215899144e+01,2.328000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579476898305900079e+01,2.328100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579567807395901013e+01,2.328199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579658716485901948e+01,2.328300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579749625575902883e+01,2.328400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579840534665903817e+01,2.328499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.579931443755904752e+01,2.328600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580022352845905687e+01,2.328700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580113261935906621e+01,2.328799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580204171025907556e+01,2.328900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580295080115908490e+01,2.329000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580385989205909425e+01,2.329099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580476898295910360e+01,2.329200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580567807385911294e+01,2.329300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580658716475912229e+01,2.329399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580749625565913163e+01,2.329500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580840534655914098e+01,2.329600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.580931443745915033e+01,2.329699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581022352835915967e+01,2.329800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581113261925916902e+01,2.329900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581204171015917836e+01,2.330000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581295080105918771e+01,2.330099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581385989195919706e+01,2.330200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581476898285920640e+01,2.330300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581567807375921575e+01,2.330399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581658716465922510e+01,2.330500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581749625555923444e+01,2.330600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581840534645924379e+01,2.330699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.581931443735925313e+01,2.330800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582022352825926248e+01,2.330900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582113261915927183e+01,2.330999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582204171005928117e+01,2.331100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582295080095929052e+01,2.331200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582385989185929986e+01,2.331299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582476898275930921e+01,2.331400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582567807365931856e+01,2.331500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582658716455932790e+01,2.331599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582749625545933725e+01,2.331700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582840534635934659e+01,2.331800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.582931443725935594e+01,2.331899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583022352815936529e+01,2.332000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583113261905937463e+01,2.332100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583204170995938398e+01,2.332199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583295080085939333e+01,2.332300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583385989175940267e+01,2.332400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583476898265941202e+01,2.332500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583567807355942136e+01,2.332599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583658716445943071e+01,2.332700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583749625535944006e+01,2.332800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583840534625944940e+01,2.332899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.583931443715945875e+01,2.333000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584022352805946809e+01,2.333100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584113261895947744e+01,2.333199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584204170985948679e+01,2.333300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584295080075949613e+01,2.333400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584385989165950548e+01,2.333499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584476898255951482e+01,2.333600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584567807345952417e+01,2.333700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584658716435953352e+01,2.333799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584749625525954286e+01,2.333900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584840534615955221e+01,2.334000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.584931443705956156e+01,2.334099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585022352795957090e+01,2.334200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585113261885958025e+01,2.334300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585204170975958959e+01,2.334399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585295080065959894e+01,2.334500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585385989155960829e+01,2.334600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585476898245961763e+01,2.334699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585567807335962698e+01,2.334800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585658716425963632e+01,2.334900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585749625515964567e+01,2.335000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585840534605965502e+01,2.335099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.585931443695966436e+01,2.335200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586022352785967371e+01,2.335300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586113261875968306e+01,2.335399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586204170965969240e+01,2.335500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586295080055970175e+01,2.335600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586385989145971109e+01,2.335699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586476898235972044e+01,2.335800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586567807325972979e+01,2.335900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586658716415973913e+01,2.335999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586749625505974848e+01,2.336100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586840534595975782e+01,2.336200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.586931443685976717e+01,2.336299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587022352775977652e+01,2.336400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587113261865978586e+01,2.336500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587204170955979521e+01,2.336599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587295080045980455e+01,2.336700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587385989135981390e+01,2.336800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587476898225982325e+01,2.336899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587567807315983259e+01,2.337000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587658716405984194e+01,2.337100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587749625495985129e+01,2.337199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587840534585986063e+01,2.337300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.587931443675986998e+01,2.337400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588022352765987932e+01,2.337500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588113261855988867e+01,2.337599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588204170945989802e+01,2.337700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588295080035990736e+01,2.337800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588385989125991671e+01,2.337899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588476898215992605e+01,2.338000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588567807305993540e+01,2.338100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588658716395994475e+01,2.338199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588749625485995409e+01,2.338300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588840534575996344e+01,2.338400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.588931443665997278e+01,2.338499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589022352755998213e+01,2.338600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589113261845999148e+01,2.338700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589204170936000082e+01,2.338799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589295080026001017e+01,2.338900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589385989116001952e+01,2.339000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589476898206002886e+01,2.339099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589567807296003821e+01,2.339200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589658716386004755e+01,2.339300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589749625476005690e+01,2.339399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589840534566006625e+01,2.339500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.589931443656007559e+01,2.339600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590022352746008494e+01,2.339699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590113261836009428e+01,2.339800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590204170926010363e+01,2.339900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590295080016011298e+01,2.340000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590385989106012232e+01,2.340099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590476898196013167e+01,2.340200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590567807286014101e+01,2.340300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590658716376015036e+01,2.340399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590749625466015971e+01,2.340500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590840534556016905e+01,2.340600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.590931443646017840e+01,2.340699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591022352736018775e+01,2.340800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591113261826019709e+01,2.340900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591204170916020644e+01,2.340999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591295080006021578e+01,2.341100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591385989096022513e+01,2.341200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591476898186023448e+01,2.341299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591567807276024382e+01,2.341400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591658716366025317e+01,2.341500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591749625456026251e+01,2.341599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591840534546027186e+01,2.341700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.591931443636028121e+01,2.341800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592022352726029055e+01,2.341899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592113261816029990e+01,2.342000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592204170906030924e+01,2.342100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592295079996031859e+01,2.342199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592385989086032794e+01,2.342300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592476898176033728e+01,2.342400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592567807266034663e+01,2.342500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592658716356035598e+01,2.342599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592749625446036532e+01,2.342700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592840534536037467e+01,2.342800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.592931443626038401e+01,2.342899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593022352716039336e+01,2.343000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593113261806040271e+01,2.343100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593204170896041205e+01,2.343199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593295079986042140e+01,2.343300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593385989076043074e+01,2.343400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593476898166044009e+01,2.343499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593567807256044944e+01,2.343600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593658716346045878e+01,2.343700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593749625436046813e+01,2.343799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593840534526047747e+01,2.343900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.593931443616048682e+01,2.344000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594022352706049617e+01,2.344099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594113261796050551e+01,2.344200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594204170886051486e+01,2.344300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594295079976052421e+01,2.344399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594385989066053355e+01,2.344500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594476898156054290e+01,2.344600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594567807246055224e+01,2.344699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594658716336056159e+01,2.344800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594749625426057094e+01,2.344900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594840534516058028e+01,2.345000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.594931443606058963e+01,2.345099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595022352696059897e+01,2.345200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595113261786060832e+01,2.345300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595204170876061767e+01,2.345399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595295079966062701e+01,2.345500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595385989056063636e+01,2.345600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595476898146064570e+01,2.345699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595567807236065505e+01,2.345800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595658716326066440e+01,2.345900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595749625416067374e+01,2.345999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595840534506068309e+01,2.346100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.595931443596069244e+01,2.346200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596022352686070178e+01,2.346299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596113261776071113e+01,2.346400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596204170866072047e+01,2.346500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596295079956072982e+01,2.346599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596385989046073917e+01,2.346700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596476898136074851e+01,2.346800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596567807226075786e+01,2.346899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596658716316076720e+01,2.347000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596749625406077655e+01,2.347100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596840534496078590e+01,2.347199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.596931443586079524e+01,2.347300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597022352676080459e+01,2.347400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597113261766081393e+01,2.347500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597204170856082328e+01,2.347599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597295079946083263e+01,2.347700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597385989036084197e+01,2.347800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597476898126085132e+01,2.347899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597567807216086067e+01,2.348000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597658716306087001e+01,2.348100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597749625396087936e+01,2.348199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597840534486088870e+01,2.348300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.597931443576089805e+01,2.348400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598022352666090740e+01,2.348499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598113261756091674e+01,2.348600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598204170846092609e+01,2.348700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598295079936093543e+01,2.348799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598385989026094478e+01,2.348900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598476898116095413e+01,2.349000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598567807206096347e+01,2.349099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598658716296097282e+01,2.349200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598749625386098216e+01,2.349300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598840534476099151e+01,2.349399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.598931443566100086e+01,2.349500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599022352656101020e+01,2.349600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599113261746101955e+01,2.349699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599204170836102890e+01,2.349800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599295079926103824e+01,2.349900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599385989016104759e+01,2.350000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599476898106105693e+01,2.350099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599567807196106628e+01,2.350200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599658716286107563e+01,2.350300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599749625376108497e+01,2.350399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599840534466109432e+01,2.350500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.599931443556110366e+01,2.350600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600022352646111301e+01,2.350699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600113261736112236e+01,2.350800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600204170826113170e+01,2.350900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600295079916114105e+01,2.350999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600385989006115040e+01,2.351100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600476898096115974e+01,2.351200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600567807186116909e+01,2.351299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600658716276117843e+01,2.351400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600749625366118778e+01,2.351500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600840534456119713e+01,2.351599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.600931443546120647e+01,2.351700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601022352636121582e+01,2.351800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601113261726122516e+01,2.351899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601204170816123451e+01,2.352000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601295079906124386e+01,2.352100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601385988996125320e+01,2.352199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601476898086126255e+01,2.352300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601567807176127189e+01,2.352400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601658716266128124e+01,2.352500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601749625356129059e+01,2.352599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601840534446129993e+01,2.352700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.601931443536130928e+01,2.352800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602022352626131863e+01,2.352899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602113261716132797e+01,2.353000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602204170806133732e+01,2.353100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602295079896134666e+01,2.353199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602385988986135601e+01,2.353300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602476898076136536e+01,2.353400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602567807166137470e+01,2.353499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602658716256138405e+01,2.353600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602749625346139339e+01,2.353700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602840534436140274e+01,2.353799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.602931443526141209e+01,2.353900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603022352616142143e+01,2.354000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603113261706143078e+01,2.354099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603204170796144012e+01,2.354200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603295079886144947e+01,2.354300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603385988976145882e+01,2.354399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603476898066146816e+01,2.354500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603567807156147751e+01,2.354600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603658716246148686e+01,2.354699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603749625336149620e+01,2.354800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603840534426150555e+01,2.354900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.603931443516151489e+01,2.355000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604022352606152424e+01,2.355099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604113261696153359e+01,2.355200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604204170786154293e+01,2.355300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604295079876155228e+01,2.355399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604385988966156162e+01,2.355500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604476898056157097e+01,2.355600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604567807146158032e+01,2.355699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604658716236158966e+01,2.355800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604749625326159901e+01,2.355900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604840534416160835e+01,2.355999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.604931443506161770e+01,2.356100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605022352596162705e+01,2.356200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605113261686163639e+01,2.356299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605204170776164574e+01,2.356400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605295079866165509e+01,2.356500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605385988956166443e+01,2.356599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605476898046167378e+01,2.356700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605567807136168312e+01,2.356800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605658716226169247e+01,2.356899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605749625316170182e+01,2.357000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605840534406171116e+01,2.357100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.605931443496172051e+01,2.357199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606022352586172985e+01,2.357300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606113261676173920e+01,2.357400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606204170766174855e+01,2.357500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606295079856175789e+01,2.357599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606385988946176724e+01,2.357700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606476898036177658e+01,2.357800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606567807126178593e+01,2.357899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606658716216179528e+01,2.358000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606749625306180462e+01,2.358100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606840534396181397e+01,2.358199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.606931443486182332e+01,2.358300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607022352576183266e+01,2.358400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607113261666184201e+01,2.358499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607204170756185135e+01,2.358600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607295079846186070e+01,2.358700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607385988936187005e+01,2.358799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607476898026187939e+01,2.358900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607567807116188874e+01,2.359000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607658716206189808e+01,2.359099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607749625296190743e+01,2.359200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607840534386191678e+01,2.359300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.607931443476192612e+01,2.359399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608022352566193547e+01,2.359500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608113261656194481e+01,2.359600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608204170746195416e+01,2.359699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608295079836196351e+01,2.359800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608385988926197285e+01,2.359900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608476898016198220e+01,2.360000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608567807106199155e+01,2.360099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608658716196200089e+01,2.360200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608749625286201024e+01,2.360300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608840534376201958e+01,2.360399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.608931443466202893e+01,2.360500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609022352556203828e+01,2.360600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609113261646204762e+01,2.360699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609204170736205697e+01,2.360800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609295079826206631e+01,2.360900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609385988916207566e+01,2.360999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609476898006208501e+01,2.361100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609567807096209435e+01,2.361200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609658716186210370e+01,2.361299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609749625276211304e+01,2.361400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609840534366212239e+01,2.361500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.609931443456213174e+01,2.361599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610022352546214108e+01,2.361700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610113261636215043e+01,2.361800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610204170726215978e+01,2.361899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610295079816216912e+01,2.362000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610385988906217847e+01,2.362100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610476897996218781e+01,2.362199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610567807086219716e+01,2.362300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610658716176220651e+01,2.362400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610749625266221585e+01,2.362500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610840534356222520e+01,2.362599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.610931443446223454e+01,2.362700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611022352536224389e+01,2.362800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611113261626225324e+01,2.362899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611204170716226258e+01,2.363000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611295079806227193e+01,2.363100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611385988896228127e+01,2.363199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611476897986229062e+01,2.363300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611567807076229997e+01,2.363400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611658716166230931e+01,2.363499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611749625256231866e+01,2.363600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611840534346232801e+01,2.363700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.611931443436233735e+01,2.363799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612022352526234670e+01,2.363900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612113261616235604e+01,2.364000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612204170706236539e+01,2.364099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612295079796237474e+01,2.364200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612385988886238408e+01,2.364300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612476897976239343e+01,2.364399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612567807066240277e+01,2.364500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612658716156241212e+01,2.364600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612749625246242147e+01,2.364699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612840534336243081e+01,2.364800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.612931443426244016e+01,2.364900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613022352516244950e+01,2.365000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613113261606245885e+01,2.365099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613204170696246820e+01,2.365200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613295079786247754e+01,2.365300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613385988876248689e+01,2.365399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613476897966249624e+01,2.365500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613567807056250558e+01,2.365600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613658716146251493e+01,2.365699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613749625236252427e+01,2.365800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613840534326253362e+01,2.365900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.613931443416254297e+01,2.365999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614022352506255231e+01,2.366100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614113261596256166e+01,2.366200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614204170686257100e+01,2.366299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614295079776258035e+01,2.366400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614385988866258970e+01,2.366500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614476897956259904e+01,2.366599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614567807046260839e+01,2.366700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614658716136261773e+01,2.366800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614749625226262708e+01,2.366899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614840534316263643e+01,2.367000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.614931443406264577e+01,2.367100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615022352496265512e+01,2.367199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615113261586266447e+01,2.367300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615204170676267381e+01,2.367400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615295079766268316e+01,2.367500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615385988856269250e+01,2.367599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615476897946270185e+01,2.367700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615567807036271120e+01,2.367800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615658716126272054e+01,2.367899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615749625216272989e+01,2.368000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615840534306273923e+01,2.368100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.615931443396274858e+01,2.368199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616022352486275793e+01,2.368300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616113261576276727e+01,2.368400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616204170666277662e+01,2.368499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616295079756278597e+01,2.368600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616385988846279531e+01,2.368700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616476897936280466e+01,2.368799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616567807026281400e+01,2.368900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616658716116282335e+01,2.369000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616749625206283270e+01,2.369099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616840534296284204e+01,2.369200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.616931443386285139e+01,2.369300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617022352476286073e+01,2.369399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617113261566287008e+01,2.369500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617204170656287943e+01,2.369600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617295079746288877e+01,2.369699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617385988836289812e+01,2.369800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617476897926290746e+01,2.369900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617567807016291681e+01,2.370000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617658716106292616e+01,2.370099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617749625196293550e+01,2.370200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617840534286294485e+01,2.370300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.617931443376295420e+01,2.370399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618022352466296354e+01,2.370500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618113261556297289e+01,2.370600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618204170646298223e+01,2.370699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618295079736299158e+01,2.370800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618385988826300093e+01,2.370900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618476897916301027e+01,2.370999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618567807006301962e+01,2.371100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618658716096302896e+01,2.371200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618749625186303831e+01,2.371299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618840534276304766e+01,2.371400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.618931443366305700e+01,2.371500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619022352456306635e+01,2.371599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619113261546307569e+01,2.371700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619204170636308504e+01,2.371800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619295079726309439e+01,2.371899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619385988816310373e+01,2.372000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619476897906311308e+01,2.372100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619567806996312243e+01,2.372199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619658716086313177e+01,2.372300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619749625176314112e+01,2.372400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619840534266315046e+01,2.372500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.619931443356315981e+01,2.372599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620022352446316916e+01,2.372700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620113261536317850e+01,2.372800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620204170626318785e+01,2.372899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620295079716319719e+01,2.373000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620385988806320654e+01,2.373100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620476897896321589e+01,2.373199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620567806986322523e+01,2.373300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620658716076323458e+01,2.373400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620749625166324392e+01,2.373499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620840534256325327e+01,2.373600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.620931443346326262e+01,2.373700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621022352436327196e+01,2.373799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621113261526328131e+01,2.373900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621204170616329066e+01,2.374000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621295079706330000e+01,2.374099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621385988796330935e+01,2.374200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621476897886331869e+01,2.374300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621567806976332804e+01,2.374399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621658716066333739e+01,2.374500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621749625156334673e+01,2.374600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621840534246335608e+01,2.374699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.621931443336336542e+01,2.374800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622022352426337477e+01,2.374900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622113261516338412e+01,2.375000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622204170606339346e+01,2.375099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622295079696340281e+01,2.375200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622385988786341215e+01,2.375300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622476897876342150e+01,2.375399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622567806966343085e+01,2.375500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622658716056344019e+01,2.375600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622749625146344954e+01,2.375699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622840534236345889e+01,2.375800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.622931443326346823e+01,2.375900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623022352416347758e+01,2.375999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623113261506348692e+01,2.376100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623204170596349627e+01,2.376200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623295079686350562e+01,2.376299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623385988776351496e+01,2.376400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623476897866352431e+01,2.376500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623567806956353365e+01,2.376599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623658716046354300e+01,2.376700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623749625136355235e+01,2.376800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623840534226356169e+01,2.376899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.623931443316357104e+01,2.377000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624022352406358038e+01,2.377100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624113261496358973e+01,2.377199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624204170586359908e+01,2.377300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624295079676360842e+01,2.377400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624385988766361777e+01,2.377500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624476897856362712e+01,2.377599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624567806946363646e+01,2.377700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624658716036364581e+01,2.377800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624749625126365515e+01,2.377899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624840534216366450e+01,2.378000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.624931443306367385e+01,2.378100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625022352396368319e+01,2.378199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625113261486369254e+01,2.378300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625204170576370188e+01,2.378400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625295079666371123e+01,2.378499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625385988756372058e+01,2.378600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625476897846372992e+01,2.378700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625567806936373927e+01,2.378799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625658716026374861e+01,2.378900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625749625116375796e+01,2.379000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625840534206376731e+01,2.379099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.625931443296377665e+01,2.379200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626022352386378600e+01,2.379300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626113261476379535e+01,2.379399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626204170566380469e+01,2.379500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626295079656381404e+01,2.379600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626385988746382338e+01,2.379699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626476897836383273e+01,2.379800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626567806926384208e+01,2.379900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626658716016385142e+01,2.380000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626749625106386077e+01,2.380099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626840534196387011e+01,2.380200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.626931443286387946e+01,2.380300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627022352376388881e+01,2.380399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627113261466389815e+01,2.380500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627204170556390750e+01,2.380600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627295079646391684e+01,2.380699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627385988736392619e+01,2.380800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627476897826393554e+01,2.380900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627567806916394488e+01,2.380999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627658716006395423e+01,2.381100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627749625096396358e+01,2.381200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627840534186397292e+01,2.381299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.627931443276398227e+01,2.381400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628022352366399161e+01,2.381500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628113261456400096e+01,2.381599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628204170546401031e+01,2.381700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628295079636401965e+01,2.381800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628385988726402900e+01,2.381899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628476897816403834e+01,2.382000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628567806906404769e+01,2.382100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628658715996405704e+01,2.382199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628749625086406638e+01,2.382300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628840534176407573e+01,2.382400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.628931443266408507e+01,2.382500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629022352356409442e+01,2.382599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629113261446410377e+01,2.382700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629204170536411311e+01,2.382800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629295079626412246e+01,2.382899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629385988716413181e+01,2.383000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629476897806414115e+01,2.383100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629567806896415050e+01,2.383199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629658715986415984e+01,2.383300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629749625076416919e+01,2.383400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629840534166417854e+01,2.383499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.629931443256418788e+01,2.383600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630022352346419723e+01,2.383700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630113261436420657e+01,2.383799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630204170526421592e+01,2.383900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630295079616422527e+01,2.384000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630385988706423461e+01,2.384099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630476897796424396e+01,2.384200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630567806886425331e+01,2.384300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630658715976426265e+01,2.384399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630749625066427200e+01,2.384500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630840534156428134e+01,2.384600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.630931443246429069e+01,2.384699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631022352336430004e+01,2.384800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631113261426430938e+01,2.384900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631204170516431873e+01,2.385000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631295079606432807e+01,2.385099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631385988696433742e+01,2.385200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631476897786434677e+01,2.385300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631567806876435611e+01,2.385399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631658715966436546e+01,2.385500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631749625056437480e+01,2.385600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631840534146438415e+01,2.385699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.631931443236439350e+01,2.385800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632022352326440284e+01,2.385900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632113261416441219e+01,2.385999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632204170506442154e+01,2.386100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632295079596443088e+01,2.386200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632385988686444023e+01,2.386299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632476897776444957e+01,2.386400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632567806866445892e+01,2.386500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632658715956446827e+01,2.386599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632749625046447761e+01,2.386700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632840534136448696e+01,2.386800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.632931443226449630e+01,2.386899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633022352316450565e+01,2.387000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633113261406451500e+01,2.387100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633204170496452434e+01,2.387199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633295079586453369e+01,2.387300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633385988676454303e+01,2.387400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633476897766455238e+01,2.387500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633567806856456173e+01,2.387599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633658715946457107e+01,2.387700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633749625036458042e+01,2.387800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633840534126458977e+01,2.387899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.633931443216459911e+01,2.388000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634022352306460846e+01,2.388100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634113261396461780e+01,2.388199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634204170486462715e+01,2.388300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634295079576463650e+01,2.388400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634385988666464584e+01,2.388499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634476897756465519e+01,2.388600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634567806846466453e+01,2.388700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634658715936467388e+01,2.388799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634749625026468323e+01,2.388900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634840534116469257e+01,2.389000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.634931443206470192e+01,2.389099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635022352296471126e+01,2.389200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635113261386472061e+01,2.389300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635204170476472996e+01,2.389399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635295079566473930e+01,2.389500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635385988656474865e+01,2.389600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635476897746475800e+01,2.389699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635567806836476734e+01,2.389800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635658715926477669e+01,2.389900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635749625016478603e+01,2.390000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635840534106479538e+01,2.390099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.635931443196480473e+01,2.390200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636022352286481407e+01,2.390300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636113261376482342e+01,2.390399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636204170466483276e+01,2.390500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636295079556484211e+01,2.390600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636385988646485146e+01,2.390699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636476897736486080e+01,2.390800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636567806826487015e+01,2.390900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636658715916487949e+01,2.390999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636749625006488884e+01,2.391100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636840534096489819e+01,2.391200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.636931443186490753e+01,2.391299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637022352276491688e+01,2.391400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637113261366492623e+01,2.391500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637204170456493557e+01,2.391599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637295079546494492e+01,2.391700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637385988636495426e+01,2.391800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637476897726496361e+01,2.391899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637567806816497296e+01,2.392000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637658715906498230e+01,2.392100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637749624996499165e+01,2.392199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637840534086500099e+01,2.392300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.637931443176501034e+01,2.392400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638022352266501969e+01,2.392500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638113261356502903e+01,2.392599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638204170446503838e+01,2.392700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638295079536504772e+01,2.392800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638385988626505707e+01,2.392899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638476897716506642e+01,2.393000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638567806806507576e+01,2.393100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638658715896508511e+01,2.393199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638749624986509446e+01,2.393300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638840534076510380e+01,2.393400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.638931443166511315e+01,2.393499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639022352256512249e+01,2.393600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639113261346513184e+01,2.393700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639204170436514119e+01,2.393799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639295079526515053e+01,2.393900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639385988616515988e+01,2.394000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639476897706516922e+01,2.394099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639567806796517857e+01,2.394200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639658715886518792e+01,2.394300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639749624976519726e+01,2.394399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639840534066520661e+01,2.394500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.639931443156521595e+01,2.394600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640022352246522530e+01,2.394699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640113261336523465e+01,2.394800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640204170426524399e+01,2.394900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640295079516525334e+01,2.395000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640385988606526269e+01,2.395099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640476897696527203e+01,2.395200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640567806786528138e+01,2.395300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640658715876529072e+01,2.395399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640749624966530007e+01,2.395500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640840534056530942e+01,2.395600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.640931443146531876e+01,2.395699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641022352236532811e+01,2.395800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641113261326533745e+01,2.395900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641204170416534680e+01,2.395999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641295079506535615e+01,2.396100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641385988596536549e+01,2.396200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641476897686537484e+01,2.396299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641567806776538418e+01,2.396400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641658715866539353e+01,2.396500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641749624956540288e+01,2.396599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641840534046541222e+01,2.396700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.641931443136542157e+01,2.396800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642022352226543092e+01,2.396899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642113261316544026e+01,2.397000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642204170406544961e+01,2.397100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642295079496545895e+01,2.397199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642385988586546830e+01,2.397300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642476897676547765e+01,2.397400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642567806766548699e+01,2.397500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642658715856549634e+01,2.397599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642749624946550568e+01,2.397700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642840534036551503e+01,2.397800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.642931443126552438e+01,2.397899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643022352216553372e+01,2.398000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643113261306554307e+01,2.398100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643204170396555241e+01,2.398199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643295079486556176e+01,2.398300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643385988576557111e+01,2.398400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643476897666558045e+01,2.398499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643567806756558980e+01,2.398600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643658715846559915e+01,2.398700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643749624936560849e+01,2.398799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643840534026561784e+01,2.398900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.643931443116562718e+01,2.399000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644022352206563653e+01,2.399099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644113261296564588e+01,2.399200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644204170386565522e+01,2.399300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644295079476566457e+01,2.399399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644385988566567391e+01,2.399500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644476897656568326e+01,2.399600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644567806746569261e+01,2.399699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644658715836570195e+01,2.399800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644749624926571130e+01,2.399900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644840534016572065e+01,2.400000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.644931443106572999e+01,2.400099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645022352196573934e+01,2.400200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645113261286574868e+01,2.400300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645204170376575803e+01,2.400399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645295079466576738e+01,2.400500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645385988556577672e+01,2.400600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645476897646578607e+01,2.400699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645567806736579541e+01,2.400800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645658715826580476e+01,2.400900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645749624916581411e+01,2.400999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645840534006582345e+01,2.401100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.645931443096583280e+01,2.401200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646022352186584214e+01,2.401299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646113261276585149e+01,2.401400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646204170366586084e+01,2.401500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646295079456587018e+01,2.401599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646385988546587953e+01,2.401700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646476897636588888e+01,2.401800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646567806726589822e+01,2.401899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646658715816590757e+01,2.402000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646749624906591691e+01,2.402100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646840533996592626e+01,2.402199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.646931443086593561e+01,2.402300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647022352176594495e+01,2.402400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647113261266595430e+01,2.402500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647204170356596364e+01,2.402599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647295079446597299e+01,2.402700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647385988536598234e+01,2.402800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647476897626599168e+01,2.402899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647567806716600103e+01,2.403000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647658715806601037e+01,2.403100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647749624896601972e+01,2.403199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647840533986602907e+01,2.403300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.647931443076603841e+01,2.403400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648022352166604776e+01,2.403499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648113261256605711e+01,2.403600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648204170346606645e+01,2.403700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648295079436607580e+01,2.403799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648385988526608514e+01,2.403900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648476897616609449e+01,2.404000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648567806706610384e+01,2.404099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648658715796611318e+01,2.404200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648749624886612253e+01,2.404300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648840533976613187e+01,2.404399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.648931443066614122e+01,2.404500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649022352156615057e+01,2.404600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649113261246615991e+01,2.404699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649204170336616926e+01,2.404800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649295079426617860e+01,2.404900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649385988516618795e+01,2.405000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649476897606619730e+01,2.405099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649567806696620664e+01,2.405200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649658715786621599e+01,2.405300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649749624876622534e+01,2.405399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649840533966623468e+01,2.405500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.649931443056624403e+01,2.405600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650022352146625337e+01,2.405699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650113261236626272e+01,2.405800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650204170326627207e+01,2.405900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650295079416628141e+01,2.405999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650385988506629076e+01,2.406100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650476897596630010e+01,2.406200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650567806686630945e+01,2.406299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650658715776631880e+01,2.406400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650749624866632814e+01,2.406500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650840533956633749e+01,2.406599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.650931443046634683e+01,2.406700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651022352136635618e+01,2.406800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651113261226636553e+01,2.406899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651204170316637487e+01,2.407000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651295079406638422e+01,2.407100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651385988496639357e+01,2.407199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651476897586640291e+01,2.407300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651567806676641226e+01,2.407400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651658715766642160e+01,2.407500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651749624856643095e+01,2.407599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651840533946644030e+01,2.407700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.651931443036644964e+01,2.407800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652022352126645899e+01,2.407899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652113261216646833e+01,2.408000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652204170306647768e+01,2.408100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652295079396648703e+01,2.408199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652385988486649637e+01,2.408300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652476897576650572e+01,2.408400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652567806666651506e+01,2.408499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652658715756652441e+01,2.408600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652749624846653376e+01,2.408700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652840533936654310e+01,2.408799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.652931443026655245e+01,2.408900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653022352116656180e+01,2.409000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653113261206657114e+01,2.409099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653204170296658049e+01,2.409200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653295079386658983e+01,2.409300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653385988476659918e+01,2.409399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653476897566660853e+01,2.409500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653567806656661787e+01,2.409600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653658715746662722e+01,2.409699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653749624836663656e+01,2.409800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653840533926664591e+01,2.409900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.653931443016665526e+01,2.410000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654022352106666460e+01,2.410099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654113261196667395e+01,2.410200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654204170286668329e+01,2.410300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654295079376669264e+01,2.410399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654385988466670199e+01,2.410500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654476897556671133e+01,2.410600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654567806646672068e+01,2.410699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654658715736673003e+01,2.410800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654749624826673937e+01,2.410900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654840533916674872e+01,2.410999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.654931443006675806e+01,2.411100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655022352096676741e+01,2.411200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655113261186677676e+01,2.411299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655204170276678610e+01,2.411400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655295079366679545e+01,2.411500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655385988456680479e+01,2.411599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655476897546681414e+01,2.411700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655567806636682349e+01,2.411800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655658715726683283e+01,2.411899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655749624816684218e+01,2.412000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655840533906685152e+01,2.412100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.655931442996686087e+01,2.412199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656022352086687022e+01,2.412300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656113261176687956e+01,2.412400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656204170266688891e+01,2.412500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656295079356689826e+01,2.412599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656385988446690760e+01,2.412700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656476897536691695e+01,2.412800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656567806626692629e+01,2.412899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656658715716693564e+01,2.413000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656749624806694499e+01,2.413100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656840533896695433e+01,2.413199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.656931442986696368e+01,2.413300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657022352076697302e+01,2.413400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657113261166698237e+01,2.413499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657204170256699172e+01,2.413600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657295079346700106e+01,2.413700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657385988436701041e+01,2.413799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657476897526701975e+01,2.413900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657567806616702910e+01,2.414000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657658715706703845e+01,2.414099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657749624796704779e+01,2.414200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657840533886705714e+01,2.414300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.657931442976706649e+01,2.414399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658022352066707583e+01,2.414500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658113261156708518e+01,2.414600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658204170246709452e+01,2.414699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658295079336710387e+01,2.414800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658385988426711322e+01,2.414900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658476897516712256e+01,2.415000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658567806606713191e+01,2.415099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658658715696714125e+01,2.415200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658749624786715060e+01,2.415300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658840533876715995e+01,2.415399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.658931442966716929e+01,2.415500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659022352056717864e+01,2.415600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659113261146718798e+01,2.415699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659204170236719733e+01,2.415800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659295079326720668e+01,2.415900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659385988416721602e+01,2.415999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659476897506722537e+01,2.416100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659567806596723472e+01,2.416200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659658715686724406e+01,2.416299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659749624776725341e+01,2.416400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659840533866726275e+01,2.416500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.659931442956727210e+01,2.416599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660022352046728145e+01,2.416700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660113261136729079e+01,2.416800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660204170226730014e+01,2.416899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660295079316730948e+01,2.417000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660385988406731883e+01,2.417100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660476897496732818e+01,2.417199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660567806586733752e+01,2.417300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660658715676734687e+01,2.417400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660749624766735622e+01,2.417500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660840533856736556e+01,2.417599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.660931442946737491e+01,2.417700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661022352036738425e+01,2.417800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661113261126739360e+01,2.417899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661204170216740295e+01,2.418000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661295079306741229e+01,2.418100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661385988396742164e+01,2.418199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661476897486743098e+01,2.418300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661567806576744033e+01,2.418400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661658715666744968e+01,2.418499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661749624756745902e+01,2.418600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661840533846746837e+01,2.418700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.661931442936747771e+01,2.418799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662022352026748706e+01,2.418900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662113261116749641e+01,2.419000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662204170206750575e+01,2.419099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662295079296751510e+01,2.419200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662385988386752445e+01,2.419300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662476897476753379e+01,2.419399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662567806566754314e+01,2.419500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662658715656755248e+01,2.419600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662749624746756183e+01,2.419699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662840533836757118e+01,2.419800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.662931442926758052e+01,2.419900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663022352016758987e+01,2.420000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663113261106759921e+01,2.420099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663204170196760856e+01,2.420200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663295079286761791e+01,2.420300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663385988376762725e+01,2.420399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663476897466763660e+01,2.420500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663567806556764594e+01,2.420600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663658715646765529e+01,2.420699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663749624736766464e+01,2.420800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663840533826767398e+01,2.420900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.663931442916768333e+01,2.420999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664022352006769268e+01,2.421100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664113261096770202e+01,2.421200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664204170186771137e+01,2.421299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664295079276772071e+01,2.421400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664385988366773006e+01,2.421500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664476897456773941e+01,2.421599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664567806546774875e+01,2.421700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664658715636775810e+01,2.421800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664749624726776744e+01,2.421899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664840533816777679e+01,2.422000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.664931442906778614e+01,2.422100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665022351996779548e+01,2.422199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665113261086780483e+01,2.422300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665204170176781417e+01,2.422400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665295079266782352e+01,2.422500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665385988356783287e+01,2.422599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665476897446784221e+01,2.422700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665567806536785156e+01,2.422800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665658715626786091e+01,2.422899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665749624716787025e+01,2.423000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665840533806787960e+01,2.423100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.665931442896788894e+01,2.423199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666022351986789829e+01,2.423300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666113261076790764e+01,2.423400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666204170166791698e+01,2.423499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666295079256792633e+01,2.423600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666385988346793567e+01,2.423700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666476897436794502e+01,2.423799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666567806526795437e+01,2.423900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666658715616796371e+01,2.424000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666749624706797306e+01,2.424099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666840533796798240e+01,2.424200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.666931442886799175e+01,2.424300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667022351976800110e+01,2.424399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667113261066801044e+01,2.424500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667204170156801979e+01,2.424600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667295079246802914e+01,2.424699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667385988336803848e+01,2.424800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667476897426804783e+01,2.424900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667567806516805717e+01,2.425000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667658715606806652e+01,2.425099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667749624696807587e+01,2.425200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667840533786808521e+01,2.425300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.667931442876809456e+01,2.425399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668022351966810390e+01,2.425500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668113261056811325e+01,2.425600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668204170146812260e+01,2.425699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668295079236813194e+01,2.425800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668385988326814129e+01,2.425900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668476897416815063e+01,2.425999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668567806506815998e+01,2.426100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668658715596816933e+01,2.426200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668749624686817867e+01,2.426299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668840533776818802e+01,2.426400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.668931442866819737e+01,2.426500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669022351956820671e+01,2.426599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669113261046821606e+01,2.426700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669204170136822540e+01,2.426800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669295079226823475e+01,2.426899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669385988316824410e+01,2.427000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669476897406825344e+01,2.427100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669567806496826279e+01,2.427199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669658715586827213e+01,2.427300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669749624676828148e+01,2.427400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669840533766829083e+01,2.427500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.669931442856830017e+01,2.427599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670022351946830952e+01,2.427700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670113261036831886e+01,2.427800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670204170126832821e+01,2.427899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670295079216833756e+01,2.428000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670385988306834690e+01,2.428100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670476897396835625e+01,2.428199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670567806486836560e+01,2.428300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670658715576837494e+01,2.428400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670749624666838429e+01,2.428499999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670840533756839363e+01,2.428600000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.670931442846840298e+01,2.428700000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671022351936841233e+01,2.428799999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671113261026842167e+01,2.428900000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671204170116843102e+01,2.429000000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671295079206844036e+01,2.429099999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671385988296844971e+01,2.429200000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671476897386845906e+01,2.429300000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671567806476846840e+01,2.429399999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671658715566847775e+01,2.429500000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671749624656848709e+01,2.429600000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671840533746849644e+01,2.429699999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.671931442836850579e+01,2.429800000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672022351926851513e+01,2.429900000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672113261016852448e+01,2.430000000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672204170106853383e+01,2.430099999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672295079196854317e+01,2.430200000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672385988286855252e+01,2.430300000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672476897376856186e+01,2.430399999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672567806466857121e+01,2.430500000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672658715556858056e+01,2.430600000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672749624646858990e+01,2.430699999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672840533736859925e+01,2.430800000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.672931442826860859e+01,2.430900000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673022351916861794e+01,2.430999999999999943e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673113261006862729e+01,2.431100000000000136e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673204170096863663e+01,2.431200000000000045e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673295079186864598e+01,2.431299999999999955e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673385988276865532e+01,2.431400000000000148e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673476897366866467e+01,2.431500000000000057e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673567806456867402e+01,2.431599999999999966e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673658715546868336e+01,2.431700000000000159e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673749624636869271e+01,2.431800000000000068e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673840533726870206e+01,2.431899999999999977e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.673931442816871140e+01,2.432000000000000171e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674022351906872075e+01,2.432100000000000080e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674113260996873009e+01,2.432199999999999989e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674204170086873944e+01,2.432300000000000182e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674295079176874879e+01,2.432400000000000091e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674385988266875813e+01,2.432500000000000000e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674476897356876748e+01,2.432599999999999909e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674567806446877682e+01,2.432700000000000102e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674658715536878617e+01,2.432800000000000011e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674749624626879552e+01,2.432899999999999920e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674840533716880486e+01,2.433000000000000114e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.674931442806881421e+01,2.433100000000000023e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.675022351896882356e+01,2.433199999999999932e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +3.675113260986883290e+01,2.433300000000000125e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00,-6.448175455852874163e-09,0.000000000000000000e+00 +3.675204170076884225e+01,2.433400000000000034e+02,0.000000000000000000e+00,1.100000010988609489e+01,0.000000000000000000e+00,-5.861977628579901044e-12,0.000000000000000000e+00,-1.719513454894098564e-08,0.000000000000000000e+00 +3.675295079166885159e+01,2.433499999999999943e+02,0.000000000000000000e+00,1.100000010988608956e+01,0.000000000000000000e+00,-2.149391797145962720e-11,0.000000000000000000e+00,5.547580283852073419e-06,0.000000000000000000e+00 +3.675385988256886094e+01,2.433600000000000136e+02,0.000000000000000000e+00,1.100000010988607002e+01,0.000000000000000000e+00,5.021760835150103848e-09,0.000000000000000000e+00,1.265518914966227548e-04,0.000000000000000000e+00 +3.675476897346887029e+01,2.433700000000000045e+02,0.000000000000000000e+00,1.100000010989063526e+01,0.000000000000000000e+00,1.200689337737088088e-07,0.000000000000000000e+00,-9.636968300250298158e-01,0.000000000000000000e+00 +3.675567806436887963e+01,2.433799999999999955e+02,0.000000000000000000e+00,1.100000010999978883e+01,0.000000000000000000e+00,-8.759679496095380954e-04,0.000000000000000000e+00,-9.999997523476323869e-01,0.000000000000000000e+00 +3.675658715526888187e+01,2.433900000000000148e+02,0.000000000000000000e+00,1.099999931366529715e+01,0.000000000000000000e+00,-1.785058624471041891e-03,0.000000000000000000e+00,-9.999998820972653135e-01,0.000000000000000000e+00 +3.675749624623469458e+01,2.434000000000000057e+02,0.000000000000000000e+00,1.099999769088462820e+01,0.000000000000000000e+00,-2.694149483099519873e-03,0.000000000000000000e+00,-9.999999241101501513e-01,0.000000000000000000e+00 +3.675840533733462223e+01,2.434099999999999966e+02,0.000000000000000000e+00,1.099999524165731124e+01,0.000000000000000000e+00,-3.603240514035663169e-03,0.000000000000000000e+00,-9.999999450165126813e-01,0.000000000000000000e+00 +3.675931442863696219e+01,2.434200000000000159e+02,0.000000000000000000e+00,1.099999196598269968e+01,0.000000000000000000e+00,-4.512331766393194200e-03,0.000000000000000000e+00,-9.999999577114024873e-01,0.000000000000000000e+00 +3.676022352021001893e+01,2.434300000000000068e+02,0.000000000000000000e+00,1.099998786385991600e+01,0.000000000000000000e+00,-5.421423301008752513e-03,0.000000000000000000e+00,-9.999999686412920363e-01,0.000000000000000000e+00 +3.676113261212209693e+01,2.434399999999999977e+02,0.000000000000000000e+00,1.099998293528784110e+01,0.000000000000000000e+00,-6.330515184579604306e-03,0.000000000000000000e+00,-9.999999735053212158e-01,0.000000000000000000e+00 +3.676204170444149355e+01,2.434500000000000171e+02,0.000000000000000000e+00,1.099997718026510896e+01,0.000000000000000000e+00,-7.239607479893382311e-03,0.000000000000000000e+00,-9.999999765997901191e-01,0.000000000000000000e+00 +3.676295079723652037e+01,2.434600000000000080e+02,0.000000000000000000e+00,1.099997059879011019e+01,0.000000000000000000e+00,-8.148700253643744937e-03,0.000000000000000000e+00,-9.999999822205849487e-01,0.000000000000000000e+00 +3.676385989057546766e+01,2.434699999999999989e+02,0.000000000000000000e+00,1.099996319086098850e+01,0.000000000000000000e+00,-9.057793576430057947e-03,0.000000000000000000e+00,-9.999999817669138480e-01,0.000000000000000000e+00 +3.676476898452664699e+01,2.434800000000000182e+02,0.000000000000000000e+00,1.099995495647563715e+01,0.000000000000000000e+00,-9.966887511033162630e-03,0.000000000000000000e+00,-9.999999902807477081e-01,0.000000000000000000e+00 +3.676567807915835573e+01,2.434900000000000091e+02,0.000000000000000000e+00,1.099994589563170599e+01,0.000000000000000000e+00,-1.087598213390891452e-02,0.000000000000000000e+00,-9.999999841149121993e-01,0.000000000000000000e+00 +3.676658717453890546e+01,2.435000000000000000e+02,0.000000000000000000e+00,1.099993600832658913e+01,0.000000000000000000e+00,-1.178507750001615319e-02,0.000000000000000000e+00,-9.999999933561586341e-01,0.000000000000000000e+00 +3.676749627073659354e+01,2.435099999999999909e+02,0.000000000000000000e+00,1.099992529455744439e+01,0.000000000000000000e+00,-1.269417369166598794e-02,0.000000000000000000e+00,-9.999999900578234735e-01,0.000000000000000000e+00 +3.676840536781973157e+01,2.435200000000000102e+02,0.000000000000000000e+00,1.099991375432116847e+01,0.000000000000000000e+00,-1.360327076576394074e-02,0.000000000000000000e+00,-9.999999935589696243e-01,0.000000000000000000e+00 +3.676931446585661689e+01,2.435300000000000011e+02,0.000000000000000000e+00,1.099990138761442005e+01,0.000000000000000000e+00,-1.451236879679725957e-02,0.000000000000000000e+00,-9.999999931071367198e-01,0.000000000000000000e+00 +3.677022356491556820e+01,2.435399999999999920e+02,0.000000000000000000e+00,1.099988819443360377e+01,0.000000000000000000e+00,-1.542146784947886692e-02,0.000000000000000000e+00,-9.999999929950198485e-01,0.000000000000000000e+00 +3.677113266506488287e+01,2.435500000000000114e+02,0.000000000000000000e+00,1.099987417477487917e+01,0.000000000000000000e+00,-1.633056799242492071e-02,0.000000000000000000e+00,-9.999999975148580189e-01,0.000000000000000000e+00 +3.677204176637287247e+01,2.435600000000000023e+02,0.000000000000000000e+00,1.099985932863415705e+01,0.000000000000000000e+00,-1.723966929815446900e-02,0.000000000000000000e+00,-9.999999959131000704e-01,0.000000000000000000e+00 +3.677295086890784148e+01,2.435699999999999932e+02,0.000000000000000000e+00,1.099984365600709602e+01,0.000000000000000000e+00,-1.814877182941135661e-02,0.000000000000000000e+00,-9.999999967799044764e-01,0.000000000000000000e+00 +3.677385997273810858e+01,2.435800000000000125e+02,0.000000000000000000e+00,1.099982715688911128e+01,0.000000000000000000e+00,-1.905787565674966350e-02,0.000000000000000000e+00,-9.999999979583061860e-01,0.000000000000000000e+00 +3.677476907793197825e+01,2.435900000000000034e+02,0.000000000000000000e+00,1.099980983127536760e+01,0.000000000000000000e+00,-1.996698084876353391e-02,0.000000000000000000e+00,-9.999999972909634494e-01,0.000000000000000000e+00 +3.677567818455776205e+01,2.435999999999999943e+02,0.000000000000000000e+00,1.099979167916078104e+01,0.000000000000000000e+00,-2.087608747208687457e-02,0.000000000000000000e+00,-9.999999990681145423e-01,0.000000000000000000e+00 +3.677658729268377868e+01,2.436100000000000136e+02,0.000000000000000000e+00,1.099977270054002076e+01,0.000000000000000000e+00,-2.178519559725494020e-02,0.000000000000000000e+00,-9.999999989823131763e-01,0.000000000000000000e+00 +3.677749640237833972e+01,2.436200000000000045e+02,0.000000000000000000e+00,1.099975289540750545e+01,0.000000000000000000e+00,-2.269430529088817261e-02,0.000000000000000000e+00,-1.000000001322975507e+00,0.000000000000000000e+00 +3.677840551370975675e+01,2.436299999999999955e+02,0.000000000000000000e+00,1.099973226375740687e+01,0.000000000000000000e+00,-2.360341662350773015e-02,0.000000000000000000e+00,-9.999999974833319039e-01,0.000000000000000000e+00 +3.677931462674634844e+01,2.436400000000000148e+02,0.000000000000000000e+00,1.099971080558364633e+01,0.000000000000000000e+00,-2.451252965781147708e-02,0.000000000000000000e+00,-1.000000000349139828e+00,0.000000000000000000e+00 +3.678022374155643348e+01,2.436500000000000057e+02,0.000000000000000000e+00,1.099968852087990179e+01,0.000000000000000000e+00,-2.542164446821314899e-02,0.000000000000000000e+00,-1.000000001312838060e+00,0.000000000000000000e+00 +3.678113285820833056e+01,2.436599999999999966e+02,0.000000000000000000e+00,1.099966540963959716e+01,0.000000000000000000e+00,-2.633076112130256288e-02,0.000000000000000000e+00,-1.000000000363672648e+00,0.000000000000000000e+00 +3.678204197677035836e+01,2.436700000000000159e+02,0.000000000000000000e+00,1.099964147185590946e+01,0.000000000000000000e+00,-2.723987968366112233e-02,0.000000000000000000e+00,-1.000000001789003390e+00,0.000000000000000000e+00 +3.678295109731084267e+01,2.436800000000000068e+02,0.000000000000000000e+00,1.099961670752176879e+01,0.000000000000000000e+00,-2.814900022576937236e-02,0.000000000000000000e+00,-1.000000001278737782e+00,0.000000000000000000e+00 +3.678386021989810217e+01,2.436899999999999977e+02,0.000000000000000000e+00,1.099959111662985478e+01,0.000000000000000000e+00,-2.905812281419094603e-02,0.000000000000000000e+00,-1.000000003119387193e+00,0.000000000000000000e+00 +3.678476934460046266e+01,2.437000000000000171e+02,0.000000000000000000e+00,1.099956469917260016e+01,0.000000000000000000e+00,-2.996724751938796560e-02,0.000000000000000000e+00,-1.000000000850901127e+00,0.000000000000000000e+00 +3.678567847148624992e+01,2.437100000000000080e+02,0.000000000000000000e+00,1.099953745514218717e+01,0.000000000000000000e+00,-3.087637440595114233e-02,0.000000000000000000e+00,-1.000000000908219500e+00,0.000000000000000000e+00 +3.678658760062379685e+01,2.437199999999999989e+02,0.000000000000000000e+00,1.099950938453055294e+01,0.000000000000000000e+00,-3.178550354432298219e-02,0.000000000000000000e+00,-1.000000003278129990e+00,0.000000000000000000e+00 +3.678749673208142923e+01,2.437300000000000182e+02,0.000000000000000000e+00,1.099948048732938410e+01,0.000000000000000000e+00,-3.269463500493567654e-02,0.000000000000000000e+00,-1.000000003648693347e+00,0.000000000000000000e+00 +3.678840586592747997e+01,2.437400000000000091e+02,0.000000000000000000e+00,1.099945076353011686e+01,0.000000000000000000e+00,-3.360376885430303717e-02,0.000000000000000000e+00,-1.000000002005960509e+00,0.000000000000000000e+00 +3.678931500223028195e+01,2.437500000000000000e+02,0.000000000000000000e+00,1.099942021312394047e+01,0.000000000000000000e+00,-3.451290515892796451e-02,0.000000000000000000e+00,-1.000000002633998797e+00,0.000000000000000000e+00 +3.679022414105816807e+01,2.437599999999999909e+02,0.000000000000000000e+00,1.099938883610179730e+01,0.000000000000000000e+00,-3.542204398920999198e-02,0.000000000000000000e+00,-1.000000003368832324e+00,0.000000000000000000e+00 +3.679113328247947834e+01,2.437700000000000102e+02,0.000000000000000000e+00,1.099935663245437922e+01,0.000000000000000000e+00,-3.633118541358319742e-02,0.000000000000000000e+00,-1.000000004195352066e+00,0.000000000000000000e+00 +3.679204242656255275e+01,2.437800000000000011e+02,0.000000000000000000e+00,1.099932360217212945e+01,0.000000000000000000e+00,-3.724032950046986257e-02,0.000000000000000000e+00,-1.000000002948904676e+00,0.000000000000000000e+00 +3.679295157337573130e+01,2.437899999999999920e+02,0.000000000000000000e+00,1.099928974524524250e+01,0.000000000000000000e+00,-3.814947631632627234e-02,0.000000000000000000e+00,-1.000000003911802215e+00,0.000000000000000000e+00 +3.679386072298735399e+01,2.438000000000000114e+02,0.000000000000000000e+00,1.099925506166366596e+01,0.000000000000000000e+00,-3.905862593150399853e-02,0.000000000000000000e+00,-1.000000002769514396e+00,0.000000000000000000e+00 +3.679476987546576794e+01,2.438100000000000023e+02,0.000000000000000000e+00,1.099921955141709695e+01,0.000000000000000000e+00,-3.996777841243415869e-02,0.000000000000000000e+00,-1.000000003803504400e+00,0.000000000000000000e+00 +3.679567903087932024e+01,2.438199999999999932e+02,0.000000000000000000e+00,1.099918321449498571e+01,0.000000000000000000e+00,-4.087693382944251191e-02,0.000000000000000000e+00,-1.000000004847571455e+00,0.000000000000000000e+00 +3.679658818929635800e+01,2.438300000000000125e+02,0.000000000000000000e+00,1.099914605088653197e+01,0.000000000000000000e+00,-4.178609225088761314e-02,0.000000000000000000e+00,-1.000000005884162713e+00,0.000000000000000000e+00 +3.679749735078523543e+01,2.438400000000000034e+02,0.000000000000000000e+00,1.099910806058068680e+01,0.000000000000000000e+00,-4.269525374511430604e-02,0.000000000000000000e+00,-1.000000002597347670e+00,0.000000000000000000e+00 +3.679840651541430674e+01,2.438499999999999943e+02,0.000000000000000000e+00,1.099906924356615256e+01,0.000000000000000000e+00,-4.360441837654584207e-02,0.000000000000000000e+00,-1.000000003564986972e+00,0.000000000000000000e+00 +3.679931568325192615e+01,2.438600000000000136e+02,0.000000000000000000e+00,1.099902959983138651e+01,0.000000000000000000e+00,-4.451358621740649640e-02,0.000000000000000000e+00,-1.000000004470267490e+00,0.000000000000000000e+00 +3.680022485436645496e+01,2.438700000000000045e+02,0.000000000000000000e+00,1.099898912936459361e+01,0.000000000000000000e+00,-4.542275733599826504e-02,0.000000000000000000e+00,-1.000000007443101468e+00,0.000000000000000000e+00 +3.680113402882625451e+01,2.438799999999999955e+02,0.000000000000000000e+00,1.099894783215373018e+01,0.000000000000000000e+00,-4.633193180256205829e-02,0.000000000000000000e+00,-1.000000001719027365e+00,0.000000000000000000e+00 +3.680204320669968610e+01,2.438900000000000148e+02,0.000000000000000000e+00,1.099890570818650204e+01,0.000000000000000000e+00,-4.724110967755450197e-02,0.000000000000000000e+00,-1.000000006619090831e+00,0.000000000000000000e+00 +3.680295238805511815e+01,2.439000000000000057e+02,0.000000000000000000e+00,1.099886275745037345e+01,0.000000000000000000e+00,-4.815029103900102248e-02,0.000000000000000000e+00,-1.000000002782153175e+00,0.000000000000000000e+00 +3.680386157296091199e+01,2.439099999999999966e+02,0.000000000000000000e+00,1.099881897993255109e+01,0.000000000000000000e+00,-4.905947594732690958e-02,0.000000000000000000e+00,-1.000000007379256983e+00,0.000000000000000000e+00 +3.680477076148545024e+01,2.439200000000000159e+02,0.000000000000000000e+00,1.099877437562000004e+01,0.000000000000000000e+00,-4.996866447857173377e-02,0.000000000000000000e+00,-1.000000003197762277e+00,0.000000000000000000e+00 +3.680567995369710133e+01,2.439300000000000068e+02,0.000000000000000000e+00,1.099872894449942962e+01,0.000000000000000000e+00,-5.087785669312826914e-02,0.000000000000000000e+00,-1.000000007407607638e+00,0.000000000000000000e+00 +3.680658914966424078e+01,2.439399999999999977e+02,0.000000000000000000e+00,1.099868268655730752e+01,0.000000000000000000e+00,-5.178705266700279336e-02,0.000000000000000000e+00,-1.000000002795683907e+00,0.000000000000000000e+00 +3.680749834945525123e+01,2.439500000000000171e+02,0.000000000000000000e+00,1.099863560177984567e+01,0.000000000000000000e+00,-5.269625246055433671e-02,0.000000000000000000e+00,-1.000000006530828323e+00,0.000000000000000000e+00 +3.680840755313851531e+01,2.439600000000000080e+02,0.000000000000000000e+00,1.099858769015301441e+01,0.000000000000000000e+00,-5.360545614975466278e-02,0.000000000000000000e+00,-1.000000005697104344e+00,0.000000000000000000e+00 +3.680931676078241566e+01,2.439699999999999989e+02,0.000000000000000000e+00,1.099853895166252826e+01,0.000000000000000000e+00,-5.451466379883528057e-02,0.000000000000000000e+00,-1.000000004569227219e+00,0.000000000000000000e+00 +3.681022597245534200e+01,2.439800000000000182e+02,0.000000000000000000e+00,1.099848938629385664e+01,0.000000000000000000e+00,-5.542387547591723362e-02,0.000000000000000000e+00,-1.000000007421330883e+00,0.000000000000000000e+00 +3.681113518822569119e+01,2.439900000000000091e+02,0.000000000000000000e+00,1.099843899403222025e+01,0.000000000000000000e+00,-5.633309125301069059e-02,0.000000000000000000e+00,-1.000000003485569389e+00,0.000000000000000000e+00 +3.681204440816185297e+01,2.440000000000000000e+02,0.000000000000000000e+00,1.099838777486258756e+01,0.000000000000000000e+00,-5.724231119233860049e-02,0.000000000000000000e+00,-1.000000005630458766e+00,0.000000000000000000e+00 +3.681295363233222417e+01,2.440099999999999909e+02,0.000000000000000000e+00,1.099833572876968368e+01,0.000000000000000000e+00,-5.815153536782731447e-02,0.000000000000000000e+00,-1.000000007384915790e+00,0.000000000000000000e+00 +3.681386286080520165e+01,2.440200000000000102e+02,0.000000000000000000e+00,1.099828285573797970e+01,0.000000000000000000e+00,-5.906076384752274172e-02,0.000000000000000000e+00,-1.000000004426474520e+00,0.000000000000000000e+00 +3.681477209364919645e+01,2.440300000000000011e+02,0.000000000000000000e+00,1.099822915575169802e+01,0.000000000000000000e+00,-5.996999669554388401e-02,0.000000000000000000e+00,-1.000000007473361263e+00,0.000000000000000000e+00 +3.681568133093261252e+01,2.440399999999999920e+02,0.000000000000000000e+00,1.099817462879481589e+01,0.000000000000000000e+00,-6.087923398575836864e-02,0.000000000000000000e+00,-1.000000003607469434e+00,0.000000000000000000e+00 +3.681659057272386804e+01,2.440500000000000114e+02,0.000000000000000000e+00,1.099811927485105656e+01,0.000000000000000000e+00,-6.178847578029154908e-02,0.000000000000000000e+00,-1.000000007843346861e+00,0.000000000000000000e+00 +3.681749981909136693e+01,2.440600000000000023e+02,0.000000000000000000e+00,1.099806309390389991e+01,0.000000000000000000e+00,-6.269772215492398770e-02,0.000000000000000000e+00,-1.000000005113688584e+00,0.000000000000000000e+00 +3.681840907010353448e+01,2.440699999999999932e+02,0.000000000000000000e+00,1.099800608593657003e+01,0.000000000000000000e+00,-6.360697317173982790e-02,0.000000000000000000e+00,-1.000000006134736052e+00,0.000000000000000000e+00 +3.681931832582878883e+01,2.440800000000000125e+02,0.000000000000000000e+00,1.099794825093204764e+01,0.000000000000000000e+00,-6.451622890257040221e-02,0.000000000000000000e+00,-1.000000006581789558e+00,0.000000000000000000e+00 +3.682022758633555526e+01,2.440900000000000034e+02,0.000000000000000000e+00,1.099788958887306123e+01,0.000000000000000000e+00,-6.542548941531835249e-02,0.000000000000000000e+00,-1.000000006426982724e+00,0.000000000000000000e+00 +3.682113685169225903e+01,2.440999999999999943e+02,0.000000000000000000e+00,1.099783009974209058e+01,0.000000000000000000e+00,-6.633475477786456020e-02,0.000000000000000000e+00,-1.000000005642148304e+00,0.000000000000000000e+00 +3.682204612196733251e+01,2.441100000000000136e+02,0.000000000000000000e+00,1.099776978352136680e+01,0.000000000000000000e+00,-6.724402505806792441e-02,0.000000000000000000e+00,-1.000000006347226300e+00,0.000000000000000000e+00 +3.682295539722921518e+01,2.441200000000000045e+02,0.000000000000000000e+00,1.099770864019287231e+01,0.000000000000000000e+00,-6.815330032571863261e-02,0.000000000000000000e+00,-1.000000006364606842e+00,0.000000000000000000e+00 +3.682386467754633941e+01,2.441299999999999955e+02,0.000000000000000000e+00,1.099764666973833904e+01,0.000000000000000000e+00,-6.906258064863057822e-02,0.000000000000000000e+00,-1.000000007813361291e+00,0.000000000000000000e+00 +3.682477396298715178e+01,2.441400000000000148e+02,0.000000000000000000e+00,1.099758387213925026e+01,0.000000000000000000e+00,-6.997186609654827694e-02,0.000000000000000000e+00,-1.000000004218348781e+00,0.000000000000000000e+00 +3.682568325362009887e+01,2.441500000000000057e+02,0.000000000000000000e+00,1.099752024737683875e+01,0.000000000000000000e+00,-7.088115673333232614e-02,0.000000000000000000e+00,-1.000000006291581922e+00,0.000000000000000000e+00 +3.682659254951363437e+01,2.441599999999999966e+02,0.000000000000000000e+00,1.099745579543209217e+01,0.000000000000000000e+00,-7.179045263258752863e-02,0.000000000000000000e+00,-1.000000007557075188e+00,0.000000000000000000e+00 +3.682750185073621196e+01,2.441700000000000159e+02,0.000000000000000000e+00,1.099739051628574416e+01,0.000000000000000000e+00,-7.269975386203410272e-02,0.000000000000000000e+00,-1.000000007983843142e+00,0.000000000000000000e+00 +3.682841115735628534e+01,2.441800000000000068e+02,0.000000000000000000e+00,1.099732440991827964e+01,0.000000000000000000e+00,-7.360906048936807777e-02,0.000000000000000000e+00,-1.000000003243823876e+00,0.000000000000000000e+00 +3.682932046944232241e+01,2.441899999999999977e+02,0.000000000000000000e+00,1.099725747630993489e+01,0.000000000000000000e+00,-7.451837257835396133e-02,0.000000000000000000e+00,-1.000000008343655988e+00,0.000000000000000000e+00 +3.683022978706278394e+01,2.442000000000000171e+02,0.000000000000000000e+00,1.099718971544070101e+01,0.000000000000000000e+00,-7.542769020640607835e-02,0.000000000000000000e+00,-1.000000008212670322e+00,0.000000000000000000e+00 +3.683113911028615206e+01,2.442100000000000080e+02,0.000000000000000000e+00,1.099712112729031155e+01,0.000000000000000000e+00,-7.633701343723896249e-02,0.000000000000000000e+00,-1.000000004966750788e+00,0.000000000000000000e+00 +3.683204843918089466e+01,2.442199999999999989e+02,0.000000000000000000e+00,1.099705171183825492e+01,0.000000000000000000e+00,-7.724634233649529946e-02,0.000000000000000000e+00,-1.000000007165983362e+00,0.000000000000000000e+00 +3.683295777381548675e+01,2.442300000000000182e+02,0.000000000000000000e+00,1.099698146906377261e+01,0.000000000000000000e+00,-7.815567697760596177e-02,0.000000000000000000e+00,-1.000000006183916712e+00,0.000000000000000000e+00 +3.683386711425841753e+01,2.442400000000000091e+02,0.000000000000000000e+00,1.099691039894585209e+01,0.000000000000000000e+00,-7.906501742616184325e-02,0.000000000000000000e+00,-1.000000006283205733e+00,0.000000000000000000e+00 +3.683477646057817623e+01,2.442500000000000000e+02,0.000000000000000000e+00,1.099683850146323394e+01,0.000000000000000000e+00,-7.997436375163437250e-02,0.000000000000000000e+00,-1.000000007429614479e+00,0.000000000000000000e+00 +3.683568581284325205e+01,2.442599999999999909e+02,0.000000000000000000e+00,1.099676577659440824e+01,0.000000000000000000e+00,-8.088371602346827727e-02,0.000000000000000000e+00,-1.000000007440426941e+00,0.000000000000000000e+00 +3.683659517112214843e+01,2.442700000000000102e+02,0.000000000000000000e+00,1.099669222431761462e+01,0.000000000000000000e+00,-8.179307430912789723e-02,0.000000000000000000e+00,-1.000000006280635789e+00,0.000000000000000000e+00 +3.683750453548336168e+01,2.442800000000000011e+02,0.000000000000000000e+00,1.099661784461084402e+01,0.000000000000000000e+00,-8.270243867605023280e-02,0.000000000000000000e+00,-1.000000008211037184e+00,0.000000000000000000e+00 +3.683841390599539523e+01,2.442899999999999920e+02,0.000000000000000000e+00,1.099654263745183869e+01,0.000000000000000000e+00,-8.361180919555147306e-02,0.000000000000000000e+00,-1.000000006751634585e+00,0.000000000000000000e+00 +3.683932328272676671e+01,2.443000000000000114e+02,0.000000000000000000e+00,1.099646660281808863e+01,0.000000000000000000e+00,-8.452118593305972538e-02,0.000000000000000000e+00,-1.000000006162349964e+00,0.000000000000000000e+00 +3.684023266574598665e+01,2.443100000000000023e+02,0.000000000000000000e+00,1.099638974068683694e+01,0.000000000000000000e+00,-8.543056895788160576e-02,0.000000000000000000e+00,-1.000000006406596809e+00,0.000000000000000000e+00 +3.684114205512157270e+01,2.443199999999999932e+02,0.000000000000000000e+00,1.099631205103507625e+01,0.000000000000000000e+00,-8.633995833929519748e-02,0.000000000000000000e+00,-1.000000007447304329e+00,0.000000000000000000e+00 +3.684205145092205669e+01,2.443300000000000125e+02,0.000000000000000000e+00,1.099623353383954871e+01,0.000000000000000000e+00,-8.724935414654966248e-02,0.000000000000000000e+00,-1.000000007099132837e+00,0.000000000000000000e+00 +3.684296085321596337e+01,2.443400000000000034e+02,0.000000000000000000e+00,1.099615418907674602e+01,0.000000000000000000e+00,-8.815875644691165136e-02,0.000000000000000000e+00,-1.000000007472273023e+00,0.000000000000000000e+00 +3.684387026207182458e+01,2.443499999999999943e+02,0.000000000000000000e+00,1.099607401672291118e+01,0.000000000000000000e+00,-8.906816530957169242e-02,0.000000000000000000e+00,-1.000000006380602269e+00,0.000000000000000000e+00 +3.684477967755818639e+01,2.443600000000000136e+02,0.000000000000000000e+00,1.099599301675403673e+01,0.000000000000000000e+00,-8.997758080173716422e-02,0.000000000000000000e+00,-1.000000008081252334e+00,0.000000000000000000e+00 +3.684568909974359485e+01,2.443700000000000045e+02,0.000000000000000000e+00,1.099591118914586652e+01,0.000000000000000000e+00,-9.088700299449192777e-02,0.000000000000000000e+00,-1.000000006091763316e+00,0.000000000000000000e+00 +3.684659852869659602e+01,2.443799999999999955e+02,0.000000000000000000e+00,1.099582853387389214e+01,0.000000000000000000e+00,-9.179643195302959746e-02,0.000000000000000000e+00,-1.000000008963928044e+00,0.000000000000000000e+00 +3.684750796448574306e+01,2.443900000000000148e+02,0.000000000000000000e+00,1.099574505091335830e+01,0.000000000000000000e+00,-9.270586775032610416e-02,0.000000000000000000e+00,-1.000000005919063018e+00,0.000000000000000000e+00 +3.684841740717959624e+01,2.444000000000000057e+02,0.000000000000000000e+00,1.099566074023925566e+01,0.000000000000000000e+00,-9.361531044956002134e-02,0.000000000000000000e+00,-1.000000007655801992e+00,0.000000000000000000e+00 +3.684932685684671583e+01,2.444099999999999966e+02,0.000000000000000000e+00,1.099557560182632976e+01,0.000000000000000000e+00,-9.452476012364485758e-02,0.000000000000000000e+00,-1.000000007690248660e+00,0.000000000000000000e+00 +3.685023631355567630e+01,2.444200000000000159e+02,0.000000000000000000e+00,1.099548963564907211e+01,0.000000000000000000e+00,-9.543421683960263968e-02,0.000000000000000000e+00,-1.000000005981587448e+00,0.000000000000000000e+00 +3.685114577737505925e+01,2.444300000000000068e+02,0.000000000000000000e+00,1.099540284168172555e+01,0.000000000000000000e+00,-9.634368066442353107e-02,0.000000000000000000e+00,-1.000000008931208217e+00,0.000000000000000000e+00 +3.685205524837343916e+01,2.444399999999999977e+02,0.000000000000000000e+00,1.099531521989828420e+01,0.000000000000000000e+00,-9.725315167092488111e-02,0.000000000000000000e+00,-1.000000005759327459e+00,0.000000000000000000e+00 +3.685296472661940470e+01,2.444500000000000171e+02,0.000000000000000000e+00,1.099522677027248818e+01,0.000000000000000000e+00,-9.816262992212555771e-02,0.000000000000000000e+00,-1.000000007161715887e+00,0.000000000000000000e+00 +3.685387421218154458e+01,2.444600000000000080e+02,0.000000000000000000e+00,1.099513749277783248e+01,0.000000000000000000e+00,-9.907211549077739321e-02,0.000000000000000000e+00,-1.000000008800496110e+00,0.000000000000000000e+00 +3.685478370512845459e+01,2.444699999999999989e+02,0.000000000000000000e+00,1.099504738738755805e+01,0.000000000000000000e+00,-9.998160844569255190e-02,0.000000000000000000e+00,-1.000000006337781633e+00,0.000000000000000000e+00 +3.685569320552874473e+01,2.444800000000000182e+02,0.000000000000000000e+00,1.099495645407465538e+01,0.000000000000000000e+00,-1.008911088517434468e-01,0.000000000000000000e+00,-1.000000008320075739e+00,0.000000000000000000e+00 +3.685660271345101791e+01,2.444900000000000091e+02,0.000000000000000000e+00,1.099486469281186807e+01,0.000000000000000000e+00,-1.018006167815811158e-01,0.000000000000000000e+00,-1.000000008261171303e+00,0.000000000000000000e+00 +3.685751222896388413e+01,2.445000000000000000e+02,0.000000000000000000e+00,1.099477210357168566e+01,0.000000000000000000e+00,-1.027101323019630474e-01,0.000000000000000000e+00,-1.000000006117017337e+00,0.000000000000000000e+00 +3.685842175213596761e+01,2.445099999999999909e+02,0.000000000000000000e+00,1.099467868632634904e+01,0.000000000000000000e+00,-1.036196554796123270e-01,0.000000000000000000e+00,-1.000000008285009789e+00,0.000000000000000000e+00 +3.685933128303589967e+01,2.445200000000000102e+02,0.000000000000000000e+00,1.099458444104785038e+01,0.000000000000000000e+00,-1.045291863870763810e-01,0.000000000000000000e+00,-1.000000006130845387e+00,0.000000000000000000e+00 +3.686024082173230454e+01,2.445300000000000011e+02,0.000000000000000000e+00,1.099448936770792784e+01,0.000000000000000000e+00,-1.054387250890553157e-01,0.000000000000000000e+00,-1.000000008198314028e+00,0.000000000000000000e+00 +3.686115036829382063e+01,2.445399999999999920e+02,0.000000000000000000e+00,1.099439346627807268e+01,0.000000000000000000e+00,-1.063482716580259752e-01,0.000000000000000000e+00,-1.000000007999721108e+00,0.000000000000000000e+00 +3.686205992278908639e+01,2.445500000000000114e+02,0.000000000000000000e+00,1.099429673672952212e+01,0.000000000000000000e+00,-1.072578261605703076e-01,0.000000000000000000e+00,-1.000000007636210109e+00,0.000000000000000000e+00 +3.686296948528675443e+01,2.445600000000000023e+02,0.000000000000000000e+00,1.099419917903326471e+01,0.000000000000000000e+00,-1.081673886651872973e-01,0.000000000000000000e+00,-1.000000007061161211e+00,0.000000000000000000e+00 +3.686387905585548452e+01,2.445699999999999932e+02,0.000000000000000000e+00,1.099410079316003852e+01,0.000000000000000000e+00,-1.090769592403395410e-01,0.000000000000000000e+00,-1.000000006227548255e+00,0.000000000000000000e+00 +3.686478863456393640e+01,2.445800000000000125e+02,0.000000000000000000e+00,1.099400157908033115e+01,0.000000000000000000e+00,-1.099865379544529287e-01,0.000000000000000000e+00,-1.000000009382059130e+00,0.000000000000000000e+00 +3.686569822148076980e+01,2.445900000000000034e+02,0.000000000000000000e+00,1.099390153676437976e+01,0.000000000000000000e+00,-1.108961248798221999e-01,0.000000000000000000e+00,-1.000000007888681930e+00,0.000000000000000000e+00 +3.686660781667466580e+01,2.445999999999999943e+02,0.000000000000000000e+00,1.099380066618216745e+01,0.000000000000000000e+00,-1.118057200808930951e-01,0.000000000000000000e+00,-1.000000005993360919e+00,0.000000000000000000e+00 +3.686751742021429834e+01,2.446100000000000136e+02,0.000000000000000000e+00,1.099369896730343044e+01,0.000000000000000000e+00,-1.127153236259795938e-01,0.000000000000000000e+00,-1.000000010088234470e+00,0.000000000000000000e+00 +3.686842703216835559e+01,2.446200000000000045e+02,0.000000000000000000e+00,1.099359644009765447e+01,0.000000000000000000e+00,-1.136249355892163110e-01,0.000000000000000000e+00,-1.000000005095792233e+00,0.000000000000000000e+00 +3.686933665260553283e+01,2.446299999999999955e+02,0.000000000000000000e+00,1.099349308453406948e+01,0.000000000000000000e+00,-1.145345560310295357e-01,0.000000000000000000e+00,-1.000000010288726537e+00,0.000000000000000000e+00 +3.687024628159452533e+01,2.446400000000000148e+02,0.000000000000000000e+00,1.099338890058166207e+01,0.000000000000000000e+00,-1.154441850293827093e-01,0.000000000000000000e+00,-1.000000006295344468e+00,0.000000000000000000e+00 +3.687115591920404256e+01,2.446500000000000057e+02,0.000000000000000000e+00,1.099328388820915947e+01,0.000000000000000000e+00,-1.163538226446247520e-01,0.000000000000000000e+00,-1.000000005946599435e+00,0.000000000000000000e+00 +3.687206556550279402e+01,2.446599999999999966e+02,0.000000000000000000e+00,1.099317804738504556e+01,0.000000000000000000e+00,-1.172634689487824650e-01,0.000000000000000000e+00,-1.000000011338249450e+00,0.000000000000000000e+00 +3.687297522055949628e+01,2.446700000000000159e+02,0.000000000000000000e+00,1.099307137807755019e+01,0.000000000000000000e+00,-1.181731240157957025e-01,0.000000000000000000e+00,-1.000000005245561541e+00,0.000000000000000000e+00 +3.687388488444287304e+01,2.446800000000000068e+02,0.000000000000000000e+00,1.099296388025464744e+01,0.000000000000000000e+00,-1.190827879039423470e-01,0.000000000000000000e+00,-1.000000009084143660e+00,0.000000000000000000e+00 +3.687479455722165511e+01,2.446899999999999977e+02,0.000000000000000000e+00,1.099285555388406976e+01,0.000000000000000000e+00,-1.199924606909878178e-01,0.000000000000000000e+00,-1.000000005628751243e+00,0.000000000000000000e+00 +3.687570423896458038e+01,2.447000000000000171e+02,0.000000000000000000e+00,1.099274639893329031e+01,0.000000000000000000e+00,-1.209021424390350069e-01,0.000000000000000000e+00,-1.000000009853492688e+00,0.000000000000000000e+00 +3.687661392974039387e+01,2.447100000000000080e+02,0.000000000000000000e+00,1.099263641536953706e+01,0.000000000000000000e+00,-1.218118332238151691e-01,0.000000000000000000e+00,-1.000000008826101183e+00,0.000000000000000000e+00 +3.687752362961785479e+01,2.447199999999999989e+02,0.000000000000000000e+00,1.099252560315978045e+01,0.000000000000000000e+00,-1.227215331093020889e-01,0.000000000000000000e+00,-1.000000004640434259e+00,0.000000000000000000e+00 +3.687843333866571527e+01,2.447300000000000182e+02,0.000000000000000000e+00,1.099241396227074397e+01,0.000000000000000000e+00,-1.236312421613810636e-01,0.000000000000000000e+00,-1.000000010121671501e+00,0.000000000000000000e+00 +3.687934305695273451e+01,2.447400000000000091e+02,0.000000000000000000e+00,1.099230149266890244e+01,0.000000000000000000e+00,-1.245409604576115103e-01,0.000000000000000000e+00,-1.000000008044291233e+00,0.000000000000000000e+00 +3.688025278454769307e+01,2.447500000000000000e+02,0.000000000000000000e+00,1.099218819432047134e+01,0.000000000000000000e+00,-1.254506880598895424e-01,0.000000000000000000e+00,-1.000000006939925301e+00,0.000000000000000000e+00 +3.688116252151937147e+01,2.447599999999999909e+02,0.000000000000000000e+00,1.099207406719142099e+01,0.000000000000000000e+00,-1.263604250378796146e-01,0.000000000000000000e+00,-1.000000008900005621e+00,0.000000000000000000e+00 +3.688207226793655025e+01,2.447700000000000102e+02,0.000000000000000000e+00,1.099195911124746949e+01,0.000000000000000000e+00,-1.272701714631559455e-01,0.000000000000000000e+00,-1.000000005284419125e+00,0.000000000000000000e+00 +3.688298202386802416e+01,2.447800000000000011e+02,0.000000000000000000e+00,1.099184332645408091e+01,0.000000000000000000e+00,-1.281799273994395638e-01,0.000000000000000000e+00,-1.000000011061318306e+00,0.000000000000000000e+00 +3.688389178938259505e+01,2.447899999999999920e+02,0.000000000000000000e+00,1.099172671277647240e+01,0.000000000000000000e+00,-1.290896929240760160e-01,0.000000000000000000e+00,-1.000000006858841051e+00,0.000000000000000000e+00 +3.688480156454907188e+01,2.448000000000000114e+02,0.000000000000000000e+00,1.099160927017960176e+01,0.000000000000000000e+00,-1.299994680967943017e-01,0.000000000000000000e+00,-1.000000007644146427e+00,0.000000000000000000e+00 +3.688571134943627072e+01,2.448100000000000023e+02,0.000000000000000000e+00,1.099149099862818346e+01,0.000000000000000000e+00,-1.309092529909473002e-01,0.000000000000000000e+00,-1.000000006921965667e+00,0.000000000000000000e+00 +3.688662114411301474e+01,2.448199999999999932e+02,0.000000000000000000e+00,1.099137189808667614e+01,0.000000000000000000e+00,-1.318190476739860006e-01,0.000000000000000000e+00,-1.000000008927359740e+00,0.000000000000000000e+00 +3.688753094864812709e+01,2.448300000000000125e+02,0.000000000000000000e+00,1.099125196851928798e+01,0.000000000000000000e+00,-1.327288522172218044e-01,0.000000000000000000e+00,-1.000000007164667748e+00,0.000000000000000000e+00 +3.688844076311045228e+01,2.448400000000000034e+02,0.000000000000000000e+00,1.099113120988997316e+01,0.000000000000000000e+00,-1.336386666860637784e-01,0.000000000000000000e+00,-1.000000010159986408e+00,0.000000000000000000e+00 +3.688935058756882768e+01,2.448499999999999943e+02,0.000000000000000000e+00,1.099100962216243715e+01,0.000000000000000000e+00,-1.345484911536856121e-01,0.000000000000000000e+00,-1.000000007125242840e+00,0.000000000000000000e+00 +3.689026042209211198e+01,2.448600000000000136e+02,0.000000000000000000e+00,1.099088720530012964e+01,0.000000000000000000e+00,-1.354583256834533123e-01,0.000000000000000000e+00,-1.000000006585482382e+00,0.000000000000000000e+00 +3.689117026674916389e+01,2.448700000000000045e+02,0.000000000000000000e+00,1.099076395926625338e+01,0.000000000000000000e+00,-1.363681703464967587e-01,0.000000000000000000e+00,-1.000000008481310321e+00,0.000000000000000000e+00 +3.689208012160884920e+01,2.448799999999999955e+02,0.000000000000000000e+00,1.099063988402375713e+01,0.000000000000000000e+00,-1.372780252138995072e-01,0.000000000000000000e+00,-1.000000008461628065e+00,0.000000000000000000e+00 +3.689298998674004793e+01,2.448900000000000148e+02,0.000000000000000000e+00,1.099051497953533563e+01,0.000000000000000000e+00,-1.381878903527939684e-01,0.000000000000000000e+00,-1.000000008612233593e+00,0.000000000000000000e+00 +3.689389986221163298e+01,2.449000000000000057e+02,0.000000000000000000e+00,1.099038924576343312e+01,0.000000000000000000e+00,-1.390977658322180566e-01,0.000000000000000000e+00,-1.000000006727223001e+00,0.000000000000000000e+00 +3.689480974809250569e+01,2.449099999999999966e+02,0.000000000000000000e+00,1.099026268267024165e+01,0.000000000000000000e+00,-1.400076517192103687e-01,0.000000000000000000e+00,-1.000000009182638872e+00,0.000000000000000000e+00 +3.689571964445156027e+01,2.449200000000000159e+02,0.000000000000000000e+00,1.099013529021770275e+01,0.000000000000000000e+00,-1.409175480866188268e-01,0.000000000000000000e+00,-1.000000007334886698e+00,0.000000000000000000e+00 +3.689662955135770517e+01,2.449300000000000068e+02,0.000000000000000000e+00,1.099000706836750219e+01,0.000000000000000000e+00,-1.418274549994345268e-01,0.000000000000000000e+00,-1.000000009704640869e+00,0.000000000000000000e+00 +3.689753946887984881e+01,2.449399999999999977e+02,0.000000000000000000e+00,1.098987801708107703e+01,0.000000000000000000e+00,-1.427373725304094954e-01,0.000000000000000000e+00,-1.000000005502446054e+00,0.000000000000000000e+00 +3.689844939708692095e+01,2.449500000000000171e+02,0.000000000000000000e+00,1.098974813631960856e+01,0.000000000000000000e+00,-1.436473007424862725e-01,0.000000000000000000e+00,-1.000000009684136604e+00,0.000000000000000000e+00 +3.689935933604784424e+01,2.449600000000000080e+02,0.000000000000000000e+00,1.098961742604403113e+01,0.000000000000000000e+00,-1.445572397122241448e-01,0.000000000000000000e+00,-1.000000009314104821e+00,0.000000000000000000e+00 +3.690026928583156263e+01,2.449699999999999989e+02,0.000000000000000000e+00,1.098948588621501976e+01,0.000000000000000000e+00,-1.454671895044200303e-01,0.000000000000000000e+00,-1.000000006474995207e+00,0.000000000000000000e+00 +3.690117924650702719e+01,2.449800000000000182e+02,0.000000000000000000e+00,1.098935351679300076e+01,0.000000000000000000e+00,-1.463771501857739910e-01,0.000000000000000000e+00,-1.000000007538918601e+00,0.000000000000000000e+00 +3.690208921814318899e+01,2.449900000000000091e+02,0.000000000000000000e+00,1.098922031773815000e+01,0.000000000000000000e+00,-1.472871218287926665e-01,0.000000000000000000e+00,-1.000000010296468789e+00,0.000000000000000000e+00 +3.690299920080900620e+01,2.450000000000000000e+02,0.000000000000000000e+00,1.098908628901038753e+01,0.000000000000000000e+00,-1.481971045039805757e-01,0.000000000000000000e+00,-1.000000006102457428e+00,0.000000000000000000e+00 +3.690390919457345831e+01,2.450099999999999909e+02,0.000000000000000000e+00,1.098895143056937940e+01,0.000000000000000000e+00,-1.491070982739835515e-01,0.000000000000000000e+00,-1.000000007763193199e+00,0.000000000000000000e+00 +3.690481919950551770e+01,2.450200000000000102e+02,0.000000000000000000e+00,1.098881574237454473e+01,0.000000000000000000e+00,-1.500171032131093762e-01,0.000000000000000000e+00,-1.000000010922720284e+00,0.000000000000000000e+00 +3.690572921567417808e+01,2.450300000000000011e+02,0.000000000000000000e+00,1.098867922438504507e+01,0.000000000000000000e+00,-1.509271193917104681e-01,0.000000000000000000e+00,-1.000000004790653207e+00,0.000000000000000000e+00 +3.690663924314843314e+01,2.450399999999999920e+02,0.000000000000000000e+00,1.098854187655978798e+01,0.000000000000000000e+00,-1.518371468703282323e-01,0.000000000000000000e+00,-1.000000010750617063e+00,0.000000000000000000e+00 +3.690754928199729079e+01,2.450500000000000114e+02,0.000000000000000000e+00,1.098840369885743584e+01,0.000000000000000000e+00,-1.527471857289722235e-01,0.000000000000000000e+00,-1.000000007286631520e+00,0.000000000000000000e+00 +3.690845933228976605e+01,2.450600000000000023e+02,0.000000000000000000e+00,1.098826469123638816e+01,0.000000000000000000e+00,-1.536572360280803740e-01,0.000000000000000000e+00,-1.000000009346234897e+00,0.000000000000000000e+00 +3.690936939409488105e+01,2.450699999999999932e+02,0.000000000000000000e+00,1.098812485365479930e+01,0.000000000000000000e+00,-1.545672978417021171e-01,0.000000000000000000e+00,-1.000000006137949926e+00,0.000000000000000000e+00 +3.691027946748166499e+01,2.450800000000000125e+02,0.000000000000000000e+00,1.098798418607056604e+01,0.000000000000000000e+00,-1.554773712340747349e-01,0.000000000000000000e+00,-1.000000008317929012e+00,0.000000000000000000e+00 +3.691118955251916134e+01,2.450900000000000034e+02,0.000000000000000000e+00,1.098784268844133649e+01,0.000000000000000000e+00,-1.563874562791420786e-01,0.000000000000000000e+00,-1.000000009383646082e+00,0.000000000000000000e+00 +3.691209964927642062e+01,2.450999999999999943e+02,0.000000000000000000e+00,1.098770036072450118e+01,0.000000000000000000e+00,-1.572975530449390591e-01,0.000000000000000000e+00,-1.000000009266770240e+00,0.000000000000000000e+00 +3.691300975782249338e+01,2.451100000000000136e+02,0.000000000000000000e+00,1.098755720287719839e+01,0.000000000000000000e+00,-1.582076615994472135e-01,0.000000000000000000e+00,-1.000000005753939547e+00,0.000000000000000000e+00 +3.691391987822645149e+01,2.451200000000000045e+02,0.000000000000000000e+00,1.098741321485631417e+01,0.000000000000000000e+00,-1.591177820086425165e-01,0.000000000000000000e+00,-1.000000009498378306e+00,0.000000000000000000e+00 +3.691483001055736679e+01,2.451299999999999955e+02,0.000000000000000000e+00,1.098726839661848409e+01,0.000000000000000000e+00,-1.600279143482056243e-01,0.000000000000000000e+00,-1.000000009707654014e+00,0.000000000000000000e+00 +3.691574015488433247e+01,2.451400000000000148e+02,0.000000000000000000e+00,1.098712274812008438e+01,0.000000000000000000e+00,-1.609380586840037930e-01,0.000000000000000000e+00,-1.000000006311961620e+00,0.000000000000000000e+00 +3.691665031127643459e+01,2.451500000000000057e+02,0.000000000000000000e+00,1.098697626931724081e+01,0.000000000000000000e+00,-1.618482150818496834e-01,0.000000000000000000e+00,-1.000000007818219849e+00,0.000000000000000000e+00 +3.691756047980277344e+01,2.451599999999999966e+02,0.000000000000000000e+00,1.098682896016582866e+01,0.000000000000000000e+00,-1.627583836153076724e-01,0.000000000000000000e+00,-1.000000009866472084e+00,0.000000000000000000e+00 +3.691847066053247062e+01,2.451700000000000159e+02,0.000000000000000000e+00,1.098668082062146567e+01,0.000000000000000000e+00,-1.636685643539831370e-01,0.000000000000000000e+00,-1.000000008096934900e+00,0.000000000000000000e+00 +3.691938085353464061e+01,2.451800000000000068e+02,0.000000000000000000e+00,1.098653185063951554e+01,0.000000000000000000e+00,-1.645787573635224543e-01,0.000000000000000000e+00,-1.000000006726462720e+00,0.000000000000000000e+00 +3.692029105887841212e+01,2.451899999999999977e+02,0.000000000000000000e+00,1.098638205017509151e+01,0.000000000000000000e+00,-1.654889627134193408e-01,0.000000000000000000e+00,-1.000000009970800408e+00,0.000000000000000000e+00 +3.692120127663292806e+01,2.452000000000000171e+02,0.000000000000000000e+00,1.098623141918305279e+01,0.000000000000000000e+00,-1.663991804770141025e-01,0.000000000000000000e+00,-1.000000007036910610e+00,0.000000000000000000e+00 +3.692211150686733845e+01,2.452100000000000080e+02,0.000000000000000000e+00,1.098607995761800105e+01,0.000000000000000000e+00,-1.673094107178324519e-01,0.000000000000000000e+00,-1.000000008572144550e+00,0.000000000000000000e+00 +3.692302174965080752e+01,2.452199999999999989e+02,0.000000000000000000e+00,1.098592766543428922e+01,0.000000000000000000e+00,-1.682196535091009804e-01,0.000000000000000000e+00,-1.000000010214704416e+00,0.000000000000000000e+00 +3.692393200505249240e+01,2.452300000000000182e+02,0.000000000000000000e+00,1.098577454258601271e+01,0.000000000000000000e+00,-1.691299089200855865e-01,0.000000000000000000e+00,-1.000000005459319663e+00,0.000000000000000000e+00 +3.692484227314157863e+01,2.452400000000000091e+02,0.000000000000000000e+00,1.098562058902701288e+01,0.000000000000000000e+00,-1.700401770141401758e-01,0.000000000000000000e+00,-1.000000011382419673e+00,0.000000000000000000e+00 +3.692575255398725176e+01,2.452500000000000000e+02,0.000000000000000000e+00,1.098546580471088241e+01,0.000000000000000000e+00,-1.709504578701723509e-01,0.000000000000000000e+00,-1.000000006471274849e+00,0.000000000000000000e+00 +3.692666284765870444e+01,2.452599999999999909e+02,0.000000000000000000e+00,1.098531018959095107e+01,0.000000000000000000e+00,-1.718607515475168712e-01,0.000000000000000000e+00,-1.000000007800929236e+00,0.000000000000000000e+00 +3.692757315422515063e+01,2.452700000000000102e+02,0.000000000000000000e+00,1.098515374362030350e+01,0.000000000000000000e+00,-1.727710581210613050e-01,0.000000000000000000e+00,-1.000000008864522894e+00,0.000000000000000000e+00 +3.692848347375579721e+01,2.452800000000000011e+02,0.000000000000000000e+00,1.098499646675176500e+01,0.000000000000000000e+00,-1.736813776597798953e-01,0.000000000000000000e+00,-1.000000009586106131e+00,0.000000000000000000e+00 +3.692939380631987945e+01,2.452899999999999920e+02,0.000000000000000000e+00,1.098483835893790683e+01,0.000000000000000000e+00,-1.745917102325875436e-01,0.000000000000000000e+00,-1.000000007745958985e+00,0.000000000000000000e+00 +3.693030415198662553e+01,2.453000000000000114e+02,0.000000000000000000e+00,1.098467942013104626e+01,0.000000000000000000e+00,-1.755020559063882879e-01,0.000000000000000000e+00,-1.000000007554388892e+00,0.000000000000000000e+00 +3.693121451082529205e+01,2.453100000000000023e+02,0.000000000000000000e+00,1.098451965028324828e+01,0.000000000000000000e+00,-1.764124147519288699e-01,0.000000000000000000e+00,-1.000000008934001983e+00,0.000000000000000000e+00 +3.693212488290512852e+01,2.453199999999999932e+02,0.000000000000000000e+00,1.098435904934632212e+01,0.000000000000000000e+00,-1.773227868398956075e-01,0.000000000000000000e+00,-1.000000009663727596e+00,0.000000000000000000e+00 +3.693303526829539862e+01,2.453300000000000125e+02,0.000000000000000000e+00,1.098419761727182120e+01,0.000000000000000000e+00,-1.782331722389628725e-01,0.000000000000000000e+00,-1.000000005379402257e+00,0.000000000000000000e+00 +3.693394566706538029e+01,2.453400000000000034e+02,0.000000000000000000e+00,1.098403535401104492e+01,0.000000000000000000e+00,-1.791435710138419568e-01,0.000000000000000000e+00,-1.000000011004946954e+00,0.000000000000000000e+00 +3.693485607928435854e+01,2.453499999999999943e+02,0.000000000000000000e+00,1.098387225951504220e+01,0.000000000000000000e+00,-1.800539832428409981e-01,0.000000000000000000e+00,-1.000000007172819894e+00,0.000000000000000000e+00 +3.693576650502163261e+01,2.453600000000000136e+02,0.000000000000000000e+00,1.098370833373459909e+01,0.000000000000000000e+00,-1.809644089866460082e-01,0.000000000000000000e+00,-1.000000008805939755e+00,0.000000000000000000e+00 +3.693667694434650883e+01,2.453700000000000045e+02,0.000000000000000000e+00,1.098354357662025471e+01,0.000000000000000000e+00,-1.818748483195392618e-01,0.000000000000000000e+00,-1.000000009395152212e+00,0.000000000000000000e+00 +3.693758739732830065e+01,2.453799999999999955e+02,0.000000000000000000e+00,1.098337798812228883e+01,0.000000000000000000e+00,-1.827853013098872659e-01,0.000000000000000000e+00,-1.000000006717641332e+00,0.000000000000000000e+00 +3.693849786403634283e+01,2.453900000000000148e+02,0.000000000000000000e+00,1.098321156819072719e+01,0.000000000000000000e+00,-1.836957680240430268e-01,0.000000000000000000e+00,-1.000000009264488066e+00,0.000000000000000000e+00 +3.693940834453996302e+01,2.454000000000000057e+02,0.000000000000000000e+00,1.098304431677534332e+01,0.000000000000000000e+00,-1.846062485361007754e-01,0.000000000000000000e+00,-1.000000008383268746e+00,0.000000000000000000e+00 +3.694031883890851731e+01,2.454099999999999966e+02,0.000000000000000000e+00,1.098287623382565137e+01,0.000000000000000000e+00,-1.855167429122874245e-01,0.000000000000000000e+00,-1.000000008278365771e+00,0.000000000000000000e+00 +3.694122934721136176e+01,2.454200000000000159e+02,0.000000000000000000e+00,1.098270731929091326e+01,0.000000000000000000e+00,-1.864272512226683720e-01,0.000000000000000000e+00,-1.000000008867978130e+00,0.000000000000000000e+00 +3.694213986951786666e+01,2.454300000000000068e+02,0.000000000000000000e+00,1.098253757312013512e+01,0.000000000000000000e+00,-1.873377735372451225e-01,0.000000000000000000e+00,-1.000000010069823642e+00,0.000000000000000000e+00 +3.694305040589740941e+01,2.454399999999999977e+02,0.000000000000000000e+00,1.098236699526206728e+01,0.000000000000000000e+00,-1.882483099259548986e-01,0.000000000000000000e+00,-1.000000005373878009e+00,0.000000000000000000e+00 +3.694396095641938160e+01,2.454500000000000171e+02,0.000000000000000000e+00,1.098219558566520426e+01,0.000000000000000000e+00,-1.891588604528179063e-01,0.000000000000000000e+00,-1.000000009694721026e+00,0.000000000000000000e+00 +3.694487152115318196e+01,2.454600000000000080e+02,0.000000000000000000e+00,1.098202334427779014e+01,0.000000000000000000e+00,-1.900694251954455072e-01,0.000000000000000000e+00,-1.000000007951396874e+00,0.000000000000000000e+00 +3.694578210016822339e+01,2.454699999999999989e+02,0.000000000000000000e+00,1.098185027104780609e+01,0.000000000000000000e+00,-1.909800042177278168e-01,0.000000000000000000e+00,-1.000000010772222225e+00,0.000000000000000000e+00 +3.694669269353393304e+01,2.454800000000000182e+02,0.000000000000000000e+00,1.098167636592298280e+01,0.000000000000000000e+00,-1.918905975932435892e-01,0.000000000000000000e+00,-1.000000005219173316e+00,0.000000000000000000e+00 +3.694760330131973802e+01,2.454900000000000091e+02,0.000000000000000000e+00,1.098150162885079162e+01,0.000000000000000000e+00,-1.928012053838011886e-01,0.000000000000000000e+00,-1.000000010487911206e+00,0.000000000000000000e+00 +3.694851392359508679e+01,2.455000000000000000e+02,0.000000000000000000e+00,1.098132605977845522e+01,0.000000000000000000e+00,-1.937118276686995433e-01,0.000000000000000000e+00,-1.000000009355351160e+00,0.000000000000000000e+00 +3.694942456042943491e+01,2.455099999999999909e+02,0.000000000000000000e+00,1.098114965865293158e+01,0.000000000000000000e+00,-1.946224645115650631e-01,0.000000000000000000e+00,-1.000000006020874466e+00,0.000000000000000000e+00 +3.695033521189224501e+01,2.455200000000000102e+02,0.000000000000000000e+00,1.098097242542092822e+01,0.000000000000000000e+00,-1.955331159798590901e-01,0.000000000000000000e+00,-1.000000011108488129e+00,0.000000000000000000e+00 +3.695124587805300109e+01,2.455300000000000011e+02,0.000000000000000000e+00,1.098079436002889864e+01,0.000000000000000000e+00,-1.964437821507288850e-01,0.000000000000000000e+00,-1.000000005254013002e+00,0.000000000000000000e+00 +3.695215655898118712e+01,2.455399999999999920e+02,0.000000000000000000e+00,1.098061546242303343e+01,0.000000000000000000e+00,-1.973544630836986391e-01,0.000000000000000000e+00,-1.000000011931819310e+00,0.000000000000000000e+00 +3.695306725474630127e+01,2.455500000000000114e+02,0.000000000000000000e+00,1.098043573254927630e+01,0.000000000000000000e+00,-1.982651588596812675e-01,0.000000000000000000e+00,-1.000000007494213472e+00,0.000000000000000000e+00 +3.695397796541786306e+01,2.455600000000000023e+02,0.000000000000000000e+00,1.098025517035330445e+01,0.000000000000000000e+00,-1.991758695380652922e-01,0.000000000000000000e+00,-1.000000006846575307e+00,0.000000000000000000e+00 +3.695488869106538488e+01,2.455699999999999932e+02,0.000000000000000000e+00,1.098007377578054822e+01,0.000000000000000000e+00,-2.000865951918247565e-01,0.000000000000000000e+00,-1.000000009900357201e+00,0.000000000000000000e+00 +3.695579943175840754e+01,2.455800000000000125e+02,0.000000000000000000e+00,1.097989154877617857e+01,0.000000000000000000e+00,-2.009973358938645926e-01,0.000000000000000000e+00,-1.000000008000710094e+00,0.000000000000000000e+00 +3.695671018756647186e+01,2.455900000000000034e+02,0.000000000000000000e+00,1.097970848928510712e+01,0.000000000000000000e+00,-2.019080917092188621e-01,0.000000000000000000e+00,-1.000000009625082509e+00,0.000000000000000000e+00 +3.695762095855913998e+01,2.455999999999999943e+02,0.000000000000000000e+00,1.097952459725199326e+01,0.000000000000000000e+00,-2.028188627106538855e-01,0.000000000000000000e+00,-1.000000008259745110e+00,0.000000000000000000e+00 +3.695853174480598113e+01,2.456100000000000136e+02,0.000000000000000000e+00,1.097933987262123701e+01,0.000000000000000000e+00,-2.037296489650150533e-01,0.000000000000000000e+00,-1.000000008097946314e+00,0.000000000000000000e+00 +3.695944254637657167e+01,2.456200000000000045e+02,0.000000000000000000e+00,1.097915431533698438e+01,0.000000000000000000e+00,-2.046404505429784138e-01,0.000000000000000000e+00,-1.000000009049361038e+00,0.000000000000000000e+00 +3.696035336334050214e+01,2.456299999999999955e+02,0.000000000000000000e+00,1.097896792534312382e+01,0.000000000000000000e+00,-2.055512675151494328e-01,0.000000000000000000e+00,-1.000000006741090797e+00,0.000000000000000000e+00 +3.696126419576737732e+01,2.456400000000000148e+02,0.000000000000000000e+00,1.097878070258328620e+01,0.000000000000000000e+00,-2.064620999481623365e-01,0.000000000000000000e+00,-1.000000009646900834e+00,0.000000000000000000e+00 +3.696217504372680906e+01,2.456500000000000057e+02,0.000000000000000000e+00,1.097859264700084836e+01,0.000000000000000000e+00,-2.073729479163812506e-01,0.000000000000000000e+00,-1.000000009110699972e+00,0.000000000000000000e+00 +3.696308590728843058e+01,2.456599999999999966e+02,0.000000000000000000e+00,1.097840375853892603e+01,0.000000000000000000e+00,-2.082838114862978207e-01,0.000000000000000000e+00,-1.000000009323005923e+00,0.000000000000000000e+00 +3.696399678652187504e+01,2.456700000000000159e+02,0.000000000000000000e+00,1.097821403714038091e+01,0.000000000000000000e+00,-2.091946907282324353e-01,0.000000000000000000e+00,-1.000000008050651257e+00,0.000000000000000000e+00 +3.696490768149678985e+01,2.456800000000000068e+02,0.000000000000000000e+00,1.097802348274781714e+01,0.000000000000000000e+00,-2.101055857104832392e-01,0.000000000000000000e+00,-1.000000007342044306e+00,0.000000000000000000e+00 +3.696581859228284372e+01,2.456899999999999977e+02,0.000000000000000000e+00,1.097783209530358306e+01,0.000000000000000000e+00,-2.110164965032261808e-01,0.000000000000000000e+00,-1.000000009244629950e+00,0.000000000000000000e+00 +3.696672951894971249e+01,2.457000000000000171e+02,0.000000000000000000e+00,1.097763987474976943e+01,0.000000000000000000e+00,-2.119274231785143181e-01,0.000000000000000000e+00,-1.000000009383409605e+00,0.000000000000000000e+00 +3.696764046156707906e+01,2.457100000000000080e+02,0.000000000000000000e+00,1.097744682102820768e+01,0.000000000000000000e+00,-2.128383658044275262e-01,0.000000000000000000e+00,-1.000000007664674007e+00,0.000000000000000000e+00 +3.696855142020464058e+01,2.457199999999999989e+02,0.000000000000000000e+00,1.097725293408047342e+01,0.000000000000000000e+00,-2.137493244489723498e-01,0.000000000000000000e+00,-1.000000008275324204e+00,0.000000000000000000e+00 +3.696946239493210840e+01,2.457300000000000182e+02,0.000000000000000000e+00,1.097705821384788649e+01,0.000000000000000000e+00,-2.146602991839815788e-01,0.000000000000000000e+00,-1.000000011120282917e+00,0.000000000000000000e+00 +3.697037338581920807e+01,2.457400000000000091e+02,0.000000000000000000e+00,1.097686266027150737e+01,0.000000000000000000e+00,-2.155712900812137289e-01,0.000000000000000000e+00,-1.000000005402428283e+00,0.000000000000000000e+00 +3.697128439293567936e+01,2.457500000000000000e+02,0.000000000000000000e+00,1.097666627329213718e+01,0.000000000000000000e+00,-2.164822972026034520e-01,0.000000000000000000e+00,-1.000000010289602947e+00,0.000000000000000000e+00 +3.697219541635126205e+01,2.457599999999999909e+02,0.000000000000000000e+00,1.097646905285032659e+01,0.000000000000000000e+00,-2.173933206275596719e-01,0.000000000000000000e+00,-1.000000008562916154e+00,0.000000000000000000e+00 +3.697310645613571722e+01,2.457700000000000102e+02,0.000000000000000000e+00,1.097627099888635982e+01,0.000000000000000000e+00,-2.183043604198171284e-01,0.000000000000000000e+00,-1.000000008687244701e+00,0.000000000000000000e+00 +3.697401751235882017e+01,2.457800000000000011e+02,0.000000000000000000e+00,1.097607211134026883e+01,0.000000000000000000e+00,-2.192154166508346602e-01,0.000000000000000000e+00,-1.000000008425422804e+00,0.000000000000000000e+00 +3.697492858509035329e+01,2.457899999999999920e+02,0.000000000000000000e+00,1.097587239015182625e+01,0.000000000000000000e+00,-2.201264893900454767e-01,0.000000000000000000e+00,-1.000000007680250880e+00,0.000000000000000000e+00 +3.697583967440012032e+01,2.458000000000000114e+02,0.000000000000000000e+00,1.097567183526054713e+01,0.000000000000000000e+00,-2.210375787068067643e-01,0.000000000000000000e+00,-1.000000010633730341e+00,0.000000000000000000e+00 +3.697675078035792495e+01,2.458100000000000023e+02,0.000000000000000000e+00,1.097547044660568893e+01,0.000000000000000000e+00,-2.219486846742985409e-01,0.000000000000000000e+00,-1.000000006488296567e+00,0.000000000000000000e+00 +3.697766190303359224e+01,2.458199999999999932e+02,0.000000000000000000e+00,1.097526822412624803e+01,0.000000000000000000e+00,-2.228598073558757664e-01,0.000000000000000000e+00,-1.000000010124346250e+00,0.000000000000000000e+00 +3.697857304249695432e+01,2.458300000000000125e+02,0.000000000000000000e+00,1.097506516776096852e+01,0.000000000000000000e+00,-2.237709468284638792e-01,0.000000000000000000e+00,-1.000000008603990187e+00,0.000000000000000000e+00 +3.697948419881786464e+01,2.458400000000000034e+02,0.000000000000000000e+00,1.097486127744832984e+01,0.000000000000000000e+00,-2.246821031572130423e-01,0.000000000000000000e+00,-1.000000008247206473e+00,0.000000000000000000e+00 +3.698039537206618377e+01,2.458499999999999943e+02,0.000000000000000000e+00,1.097465655312655741e+01,0.000000000000000000e+00,-2.255932764130445800e-01,0.000000000000000000e+00,-1.000000008953985109e+00,0.000000000000000000e+00 +3.698130656231177937e+01,2.458600000000000136e+02,0.000000000000000000e+00,1.097445099473361729e+01,0.000000000000000000e+00,-2.265044666668016293e-01,0.000000000000000000e+00,-1.000000008484463576e+00,0.000000000000000000e+00 +3.698221776962454754e+01,2.458700000000000045e+02,0.000000000000000000e+00,1.097424460220721620e+01,0.000000000000000000e+00,-2.274156739872993382e-01,0.000000000000000000e+00,-1.000000006738158920e+00,0.000000000000000000e+00 +3.698312899407438437e+01,2.458799999999999955e+02,0.000000000000000000e+00,1.097403737548480329e+01,0.000000000000000000e+00,-2.283268984432742232e-01,0.000000000000000000e+00,-1.000000012170947139e+00,0.000000000000000000e+00 +3.698404023573120014e+01,2.458900000000000148e+02,0.000000000000000000e+00,1.097382931450357013e+01,0.000000000000000000e+00,-2.292381401111811268e-01,0.000000000000000000e+00,-1.000000005428087535e+00,0.000000000000000000e+00 +3.698495149466492649e+01,2.459000000000000057e+02,0.000000000000000000e+00,1.097362041920044362e+01,0.000000000000000000e+00,-2.301493990498511832e-01,0.000000000000000000e+00,-1.000000012077898237e+00,0.000000000000000000e+00 +3.698586277094549501e+01,2.459099999999999966e+02,0.000000000000000000e+00,1.097341068951210197e+01,0.000000000000000000e+00,-2.310606753414278514e-01,0.000000000000000000e+00,-1.000000006348477521e+00,0.000000000000000000e+00 +3.698677406464286577e+01,2.459200000000000159e+02,0.000000000000000000e+00,1.097320012537495337e+01,0.000000000000000000e+00,-2.319719690445827265e-01,0.000000000000000000e+00,-1.000000009527582501e+00,0.000000000000000000e+00 +3.698768537582699878e+01,2.459300000000000068e+02,0.000000000000000000e+00,1.097298872672515735e+01,0.000000000000000000e+00,-2.328832802373997923e-01,0.000000000000000000e+00,-1.000000008677900620e+00,0.000000000000000000e+00 +3.698859670456787541e+01,2.459399999999999977e+02,0.000000000000000000e+00,1.097277649349860695e+01,0.000000000000000000e+00,-2.337946089861866750e-01,0.000000000000000000e+00,-1.000000007973665728e+00,0.000000000000000000e+00 +3.698950805093549121e+01,2.459500000000000171e+02,0.000000000000000000e+00,1.097256342563093945e+01,0.000000000000000000e+00,-2.347059553610683358e-01,0.000000000000000000e+00,-1.000000009449388827e+00,0.000000000000000000e+00 +3.699041941499984887e+01,2.459600000000000080e+02,0.000000000000000000e+00,1.097234952305753275e+01,0.000000000000000000e+00,-2.356173194340373533e-01,0.000000000000000000e+00,-1.000000006584694123e+00,0.000000000000000000e+00 +3.699133079683096526e+01,2.459699999999999989e+02,0.000000000000000000e+00,1.097213478571350365e+01,0.000000000000000000e+00,-2.365287012711573544e-01,0.000000000000000000e+00,-1.000000012105811464e+00,0.000000000000000000e+00 +3.699224219649887857e+01,2.459800000000000182e+02,0.000000000000000000e+00,1.097191921353371313e+01,0.000000000000000000e+00,-2.374401009501039550e-01,0.000000000000000000e+00,-1.000000006660741736e+00,0.000000000000000000e+00 +3.699315361407363412e+01,2.459900000000000091e+02,0.000000000000000000e+00,1.097170280645275575e+01,0.000000000000000000e+00,-2.383515185309290629e-01,0.000000000000000000e+00,-1.000000009389989453e+00,0.000000000000000000e+00 +3.699406504962529141e+01,2.460000000000000000e+02,0.000000000000000000e+00,1.097148556440497558e+01,0.000000000000000000e+00,-2.392629540911429820e-01,0.000000000000000000e+00,-1.000000007356768528e+00,0.000000000000000000e+00 +3.699497650322392417e+01,2.460100000000000193e+02,0.000000000000000000e+00,1.097126748732445023e+01,0.000000000000000000e+00,-2.401744076964788810e-01,0.000000000000000000e+00,-1.000000011145631973e+00,0.000000000000000000e+00 +3.699588797493962034e+01,2.460200000000000102e+02,0.000000000000000000e+00,1.097104857514500154e+01,0.000000000000000000e+00,-2.410858794223309509e-01,0.000000000000000000e+00,-1.000000005682404991e+00,0.000000000000000000e+00 +3.699679946484247495e+01,2.460300000000000011e+02,0.000000000000000000e+00,1.097082882780018664e+01,0.000000000000000000e+00,-2.419973693303675566e-01,0.000000000000000000e+00,-1.000000012240412461e+00,0.000000000000000000e+00 +3.699771097300261147e+01,2.460399999999999920e+02,0.000000000000000000e+00,1.097060824522331046e+01,0.000000000000000000e+00,-2.429088775016612356e-01,0.000000000000000000e+00,-1.000000005055358132e+00,0.000000000000000000e+00 +3.699862249949015336e+01,2.460500000000000114e+02,0.000000000000000000e+00,1.097038682734740789e+01,0.000000000000000000e+00,-2.438204039938142720e-01,0.000000000000000000e+00,-1.000000011812228085e+00,0.000000000000000000e+00 +3.699953404437525251e+01,2.460600000000000023e+02,0.000000000000000000e+00,1.097016457410526513e+01,0.000000000000000000e+00,-2.447319488896782802e-01,0.000000000000000000e+00,-1.000000006747464365e+00,0.000000000000000000e+00 +3.700044560772806079e+01,2.460699999999999932e+02,0.000000000000000000e+00,1.096994148542939662e+01,0.000000000000000000e+00,-2.456435122486345657e-01,0.000000000000000000e+00,-1.000000008992302236e+00,0.000000000000000000e+00 +3.700135718961874431e+01,2.460800000000000125e+02,0.000000000000000000e+00,1.096971756125206632e+01,0.000000000000000000e+00,-2.465550941475175561e-01,0.000000000000000000e+00,-1.000000009885572139e+00,0.000000000000000000e+00 +3.700226879011749759e+01,2.460900000000000034e+02,0.000000000000000000e+00,1.096949280150527173e+01,0.000000000000000000e+00,-2.474666946552807056e-01,0.000000000000000000e+00,-1.000000009317485894e+00,0.000000000000000000e+00 +3.700318040929451513e+01,2.460999999999999943e+02,0.000000000000000000e+00,1.096926720612075101e+01,0.000000000000000000e+00,-2.483783138407915092e-01,0.000000000000000000e+00,-1.000000007177595185e+00,0.000000000000000000e+00 +3.700409204722001277e+01,2.461100000000000136e+02,0.000000000000000000e+00,1.096904077502998298e+01,0.000000000000000000e+00,-2.492899517728309478e-01,0.000000000000000000e+00,-1.000000007629724852e+00,0.000000000000000000e+00 +3.700500370396421346e+01,2.461200000000000045e+02,0.000000000000000000e+00,1.096881350816418710e+01,0.000000000000000000e+00,-2.502016085239902043e-01,0.000000000000000000e+00,-1.000000010561933106e+00,0.000000000000000000e+00 +3.700591537959736854e+01,2.461299999999999955e+02,0.000000000000000000e+00,1.096858540545431993e+01,0.000000000000000000e+00,-2.511132841667729210e-01,0.000000000000000000e+00,-1.000000009450609184e+00,0.000000000000000000e+00 +3.700682707418972939e+01,2.461400000000000148e+02,0.000000000000000000e+00,1.096835646683107512e+01,0.000000000000000000e+00,-2.520249787677497633e-01,0.000000000000000000e+00,-1.000000006321318358e+00,0.000000000000000000e+00 +3.700773878781156867e+01,2.461500000000000057e+02,0.000000000000000000e+00,1.096812669222488879e+01,0.000000000000000000e+00,-2.529366923953523805e-01,0.000000000000000000e+00,-1.000000011745902251e+00,0.000000000000000000e+00 +3.700865052053317328e+01,2.461599999999999966e+02,0.000000000000000000e+00,1.096789608156593765e+01,0.000000000000000000e+00,-2.538484251276655335e-01,0.000000000000000000e+00,-1.000000006378472861e+00,0.000000000000000000e+00 +3.700956227242484431e+01,2.461700000000000159e+02,0.000000000000000000e+00,1.096766463478413023e+01,0.000000000000000000e+00,-2.547601770251504139e-01,0.000000000000000000e+00,-1.000000009337825180e+00,0.000000000000000000e+00 +3.701047404355689707e+01,2.461800000000000068e+02,0.000000000000000000e+00,1.096743235180912279e+01,0.000000000000000000e+00,-2.556719481657142024e-01,0.000000000000000000e+00,-1.000000009825260383e+00,0.000000000000000000e+00 +3.701138583399965398e+01,2.461899999999999977e+02,0.000000000000000000e+00,1.096719923257030338e+01,0.000000000000000000e+00,-2.565837386174331103e-01,0.000000000000000000e+00,-1.000000007726673523e+00,0.000000000000000000e+00 +3.701229764382347298e+01,2.462000000000000171e+02,0.000000000000000000e+00,1.096696527699680068e+01,0.000000000000000000e+00,-2.574955484482939205e-01,0.000000000000000000e+00,-1.000000009336934781e+00,0.000000000000000000e+00 +3.701320947309870490e+01,2.462100000000000080e+02,0.000000000000000000e+00,1.096673048501748404e+01,0.000000000000000000e+00,-2.584073777320379239e-01,0.000000000000000000e+00,-1.000000008130896623e+00,0.000000000000000000e+00 +3.701412132189572191e+01,2.462199999999999989e+02,0.000000000000000000e+00,1.096649485656095813e+01,0.000000000000000000e+00,-2.593192265364715476e-01,0.000000000000000000e+00,-1.000000008265808482e+00,0.000000000000000000e+00 +3.701503319028491745e+01,2.462300000000000182e+02,0.000000000000000000e+00,1.096625839155556825e+01,0.000000000000000000e+00,-2.602310949332068413e-01,0.000000000000000000e+00,-1.000000009625322317e+00,0.000000000000000000e+00 +3.701594507833669923e+01,2.462400000000000091e+02,0.000000000000000000e+00,1.096602108992939684e+01,0.000000000000000000e+00,-2.611429829937648162e-01,0.000000000000000000e+00,-1.000000009956313107e+00,0.000000000000000000e+00 +3.701685698612148201e+01,2.462500000000000000e+02,0.000000000000000000e+00,1.096578295161026340e+01,0.000000000000000000e+00,-2.620548907876269484e-01,0.000000000000000000e+00,-1.000000007005789060e+00,0.000000000000000000e+00 +3.701776891370970191e+01,2.462600000000000193e+02,0.000000000000000000e+00,1.096554397652572632e+01,0.000000000000000000e+00,-2.629668183822351790e-01,0.000000000000000000e+00,-1.000000009200467055e+00,0.000000000000000000e+00 +3.701868086117180923e+01,2.462700000000000102e+02,0.000000000000000000e+00,1.096530416460308466e+01,0.000000000000000000e+00,-2.638787658527311231e-01,0.000000000000000000e+00,-1.000000010013999630e+00,0.000000000000000000e+00 +3.701959282857826850e+01,2.462800000000000011e+02,0.000000000000000000e+00,1.096506351576937099e+01,0.000000000000000000e+00,-2.647907332683200887e-01,0.000000000000000000e+00,-1.000000007192469731e+00,0.000000000000000000e+00 +3.702050481599955845e+01,2.462899999999999920e+02,0.000000000000000000e+00,1.096482202995135680e+01,0.000000000000000000e+00,-2.657027206961670163e-01,0.000000000000000000e+00,-1.000000009160115777e+00,0.000000000000000000e+00 +3.702141682350617202e+01,2.463000000000000114e+02,0.000000000000000000e+00,1.096457970707555418e+01,0.000000000000000000e+00,-2.666147282111349104e-01,0.000000000000000000e+00,-1.000000009390248357e+00,0.000000000000000000e+00 +3.702232885116862349e+01,2.463100000000000023e+02,0.000000000000000000e+00,1.096433654706820882e+01,0.000000000000000000e+00,-2.675267558821499136e-01,0.000000000000000000e+00,-1.000000007763329979e+00,0.000000000000000000e+00 +3.702324089905743421e+01,2.463199999999999932e+02,0.000000000000000000e+00,1.096409254985530524e+01,0.000000000000000000e+00,-2.684388037780444658e-01,0.000000000000000000e+00,-1.000000010565536002e+00,0.000000000000000000e+00 +3.702415296724315397e+01,2.463300000000000125e+02,0.000000000000000000e+00,1.096384771536256686e+01,0.000000000000000000e+00,-2.693508719733997969e-01,0.000000000000000000e+00,-1.000000006999243851e+00,0.000000000000000000e+00 +3.702506505579633256e+01,2.463400000000000034e+02,0.000000000000000000e+00,1.096360204351545065e+01,0.000000000000000000e+00,-2.702629605329645579e-01,0.000000000000000000e+00,-1.000000009755457997e+00,0.000000000000000000e+00 +3.702597716478754819e+01,2.463499999999999943e+02,0.000000000000000000e+00,1.096335553423915599e+01,0.000000000000000000e+00,-2.711750695330781835e-01,0.000000000000000000e+00,-1.000000008036179500e+00,0.000000000000000000e+00 +3.702688929428738618e+01,2.463600000000000136e+02,0.000000000000000000e+00,1.096310818745861404e+01,0.000000000000000000e+00,-2.720871990402469742e-01,0.000000000000000000e+00,-1.000000010260128080e+00,0.000000000000000000e+00 +3.702780144436645315e+01,2.463700000000000045e+02,0.000000000000000000e+00,1.096286000309849662e+01,0.000000000000000000e+00,-2.729993491286717977e-01,0.000000000000000000e+00,-1.000000007764659804e+00,0.000000000000000000e+00 +3.702871361509536285e+01,2.463799999999999955e+02,0.000000000000000000e+00,1.096261098108320908e+01,0.000000000000000000e+00,-2.739115198646677185e-01,0.000000000000000000e+00,-1.000000008967034448e+00,0.000000000000000000e+00 +3.702962580654475744e+01,2.463900000000000148e+02,0.000000000000000000e+00,1.096236112133689744e+01,0.000000000000000000e+00,-2.748237113222434802e-01,0.000000000000000000e+00,-1.000000007339020058e+00,0.000000000000000000e+00 +3.703053801878528617e+01,2.464000000000000057e+02,0.000000000000000000e+00,1.096211042378344125e+01,0.000000000000000000e+00,-2.757359235694687993e-01,0.000000000000000000e+00,-1.000000011295963720e+00,0.000000000000000000e+00 +3.703145025188761963e+01,2.464099999999999966e+02,0.000000000000000000e+00,1.096185888834645894e+01,0.000000000000000000e+00,-2.766481566821059057e-01,0.000000000000000000e+00,-1.000000007905766708e+00,0.000000000000000000e+00 +3.703236250592243550e+01,2.464200000000000159e+02,0.000000000000000000e+00,1.096160651494930072e+01,0.000000000000000000e+00,-2.775604107241360086e-01,0.000000000000000000e+00,-1.000000007716887573e+00,0.000000000000000000e+00 +3.703327478096043990e+01,2.464300000000000068e+02,0.000000000000000000e+00,1.096135330351505921e+01,0.000000000000000000e+00,-2.784726857691789959e-01,0.000000000000000000e+00,-1.000000010603816936e+00,0.000000000000000000e+00 +3.703418707707234603e+01,2.464399999999999977e+02,0.000000000000000000e+00,1.096109925396656060e+01,0.000000000000000000e+00,-2.793849818907565563e-01,0.000000000000000000e+00,-1.000000007903766752e+00,0.000000000000000000e+00 +3.703509939432888132e+01,2.464500000000000171e+02,0.000000000000000000e+00,1.096084436622636460e+01,0.000000000000000000e+00,-2.802972991545035208e-01,0.000000000000000000e+00,-1.000000010162212405e+00,0.000000000000000000e+00 +3.703601173280079450e+01,2.464600000000000080e+02,0.000000000000000000e+00,1.096058864021677159e+01,0.000000000000000000e+00,-2.812096376356916227e-01,0.000000000000000000e+00,-1.000000006581880818e+00,0.000000000000000000e+00 +3.703692409255885565e+01,2.464699999999999989e+02,0.000000000000000000e+00,1.096033207585981373e+01,0.000000000000000000e+00,-2.821219973997581842e-01,0.000000000000000000e+00,-1.000000009840469106e+00,0.000000000000000000e+00 +3.703783647367384191e+01,2.464800000000000182e+02,0.000000000000000000e+00,1.096007467307726380e+01,0.000000000000000000e+00,-2.830343785237233734e-01,0.000000000000000000e+00,-1.000000009140404211e+00,0.000000000000000000e+00 +3.703874887621655176e+01,2.464900000000000091e+02,0.000000000000000000e+00,1.095981643179062459e+01,0.000000000000000000e+00,-2.839467810747724474e-01,0.000000000000000000e+00,-1.000000008622062397e+00,0.000000000000000000e+00 +3.703966130025779790e+01,2.465000000000000000e+02,0.000000000000000000e+00,1.095955735192113778e+01,0.000000000000000000e+00,-2.848592051238846290e-01,0.000000000000000000e+00,-1.000000010290875263e+00,0.000000000000000000e+00 +3.704057374586840723e+01,2.465100000000000193e+02,0.000000000000000000e+00,1.095929743338978035e+01,0.000000000000000000e+00,-2.857716507438854969e-01,0.000000000000000000e+00,-1.000000007617294795e+00,0.000000000000000000e+00 +3.704148621311922795e+01,2.465200000000000102e+02,0.000000000000000000e+00,1.095903667611726284e+01,0.000000000000000000e+00,-2.866841180016593271e-01,0.000000000000000000e+00,-1.000000009006744905e+00,0.000000000000000000e+00 +3.704239870208112961e+01,2.465300000000000011e+02,0.000000000000000000e+00,1.095877508002403466e+01,0.000000000000000000e+00,-2.875966069717765805e-01,0.000000000000000000e+00,-1.000000007928999235e+00,0.000000000000000000e+00 +3.704331121282498174e+01,2.465399999999999920e+02,0.000000000000000000e+00,1.095851264503027700e+01,0.000000000000000000e+00,-2.885091177228657489e-01,0.000000000000000000e+00,-1.000000008520852246e+00,0.000000000000000000e+00 +3.704422374542168939e+01,2.465500000000000114e+02,0.000000000000000000e+00,1.095824937105590813e+01,0.000000000000000000e+00,-2.894216503273468466e-01,0.000000000000000000e+00,-1.000000010651866056e+00,0.000000000000000000e+00 +3.704513629994215762e+01,2.465600000000000023e+02,0.000000000000000000e+00,1.095798525802057988e+01,0.000000000000000000e+00,-2.903342048575377476e-01,0.000000000000000000e+00,-1.000000007791729706e+00,0.000000000000000000e+00 +3.704604887645731992e+01,2.465699999999999932e+02,0.000000000000000000e+00,1.095772030584367762e+01,0.000000000000000000e+00,-2.912467813798138572e-01,0.000000000000000000e+00,-1.000000010474475065e+00,0.000000000000000000e+00 +3.704696147503813108e+01,2.465800000000000125e+02,0.000000000000000000e+00,1.095745451444432561e+01,0.000000000000000000e+00,-2.921593799701804883e-01,0.000000000000000000e+00,-1.000000005770786515e+00,0.000000000000000000e+00 +3.704787409575554591e+01,2.465900000000000034e+02,0.000000000000000000e+00,1.095718788374137809e+01,0.000000000000000000e+00,-2.930720006928607124e-01,0.000000000000000000e+00,-1.000000010611221235e+00,0.000000000000000000e+00 +3.704878673868054761e+01,2.465999999999999943e+02,0.000000000000000000e+00,1.095692041365342995e+01,0.000000000000000000e+00,-2.939846436275456720e-01,0.000000000000000000e+00,-1.000000009933181389e+00,0.000000000000000000e+00 +3.704969940388413363e+01,2.466100000000000136e+02,0.000000000000000000e+00,1.095665210409880252e+01,0.000000000000000000e+00,-2.948973088401971032e-01,0.000000000000000000e+00,-1.000000007869872753e+00,0.000000000000000000e+00 +3.705061209143732270e+01,2.466200000000000045e+02,0.000000000000000000e+00,1.095638295499555603e+01,0.000000000000000000e+00,-2.958099964005658222e-01,0.000000000000000000e+00,-1.000000008552393016e+00,0.000000000000000000e+00 +3.705152480141114069e+01,2.466299999999999955e+02,0.000000000000000000e+00,1.095611296626148601e+01,0.000000000000000000e+00,-2.967227063821902266e-01,0.000000000000000000e+00,-1.000000009714223204e+00,0.000000000000000000e+00 +3.705243753387664185e+01,2.466400000000000148e+02,0.000000000000000000e+00,1.095584213781411975e+01,0.000000000000000000e+00,-2.976354388565574105e-01,0.000000000000000000e+00,-1.000000006956389687e+00,0.000000000000000000e+00 +3.705335028890489468e+01,2.466500000000000057e+02,0.000000000000000000e+00,1.095557046957071812e+01,0.000000000000000000e+00,-2.985481938911566102e-01,0.000000000000000000e+00,-1.000000010804935391e+00,0.000000000000000000e+00 +3.705426306656697477e+01,2.466599999999999966e+02,0.000000000000000000e+00,1.095529796144827905e+01,0.000000000000000000e+00,-2.994609715631020852e-01,0.000000000000000000e+00,-1.000000008331829893e+00,0.000000000000000000e+00 +3.705517586693399323e+01,2.466700000000000159e+02,0.000000000000000000e+00,1.095502461336352873e+01,0.000000000000000000e+00,-3.003737719377252424e-01,0.000000000000000000e+00,-1.000000010061491640e+00,0.000000000000000000e+00 +3.705608869007706829e+01,2.466800000000000068e+02,0.000000000000000000e+00,1.095475042523293219e+01,0.000000000000000000e+00,-3.012865950899814571e-01,0.000000000000000000e+00,-1.000000007329930884e+00,0.000000000000000000e+00 +3.705700153606733238e+01,2.466899999999999977e+02,0.000000000000000000e+00,1.095447539697268446e+01,0.000000000000000000e+00,-3.021994410869350278e-01,0.000000000000000000e+00,-1.000000008527941908e+00,0.000000000000000000e+00 +3.705791440497593925e+01,2.467000000000000171e+02,0.000000000000000000e+00,1.095419952849871770e+01,0.000000000000000000e+00,-3.031123100033272233e-01,0.000000000000000000e+00,-1.000000009254385036e+00,0.000000000000000000e+00 +3.705882729687406396e+01,2.467100000000000080e+02,0.000000000000000000e+00,1.095392281972669402e+01,0.000000000000000000e+00,-3.040252019098994563e-01,0.000000000000000000e+00,-1.000000009371946330e+00,0.000000000000000000e+00 +3.705974021183289580e+01,2.467199999999999989e+02,0.000000000000000000e+00,1.095364527057200910e+01,0.000000000000000000e+00,-3.049381168772854478e-01,0.000000000000000000e+00,-1.000000008742534030e+00,0.000000000000000000e+00 +3.706065314992363824e+01,2.467300000000000182e+02,0.000000000000000000e+00,1.095336688094979216e+01,0.000000000000000000e+00,-3.058510549760105612e-01,0.000000000000000000e+00,-1.000000009359045094e+00,0.000000000000000000e+00 +3.706156611121752320e+01,2.467400000000000091e+02,0.000000000000000000e+00,1.095308765077490598e+01,0.000000000000000000e+00,-3.067640162784373570e-01,0.000000000000000000e+00,-1.000000008951171138e+00,0.000000000000000000e+00 +3.706247909578578970e+01,2.467500000000000000e+02,0.000000000000000000e+00,1.095280757996194509e+01,0.000000000000000000e+00,-3.076770008548735946e-01,0.000000000000000000e+00,-1.000000007379762135e+00,0.000000000000000000e+00 +3.706339210369969805e+01,2.467600000000000193e+02,0.000000000000000000e+00,1.095252666842523759e+01,0.000000000000000000e+00,-3.085900087755178434e-01,0.000000000000000000e+00,-1.000000010897572844e+00,0.000000000000000000e+00 +3.706430513503052282e+01,2.467700000000000102e+02,0.000000000000000000e+00,1.095224491607884509e+01,0.000000000000000000e+00,-3.095030401162955358e-01,0.000000000000000000e+00,-1.000000008709672095e+00,0.000000000000000000e+00 +3.706521818984956695e+01,2.467800000000000011e+02,0.000000000000000000e+00,1.095196232283655746e+01,0.000000000000000000e+00,-3.104160949432941408e-01,0.000000000000000000e+00,-1.000000007068413410e+00,0.000000000000000000e+00 +3.706613126822814763e+01,2.467899999999999920e+02,0.000000000000000000e+00,1.095167888861190164e+01,0.000000000000000000e+00,-3.113291733283277130e-01,0.000000000000000000e+00,-1.000000010093152758e+00,0.000000000000000000e+00 +3.706704437023759624e+01,2.468000000000000114e+02,0.000000000000000000e+00,1.095139461331813635e+01,0.000000000000000000e+00,-3.122422753469898948e-01,0.000000000000000000e+00,-1.000000009119925926e+00,0.000000000000000000e+00 +3.706795749594925837e+01,2.468100000000000023e+02,0.000000000000000000e+00,1.095110949686824853e+01,0.000000000000000000e+00,-3.131554010669815868e-01,0.000000000000000000e+00,-1.000000008267919016e+00,0.000000000000000000e+00 +3.706887064543450805e+01,2.468199999999999932e+02,0.000000000000000000e+00,1.095082353917496043e+01,0.000000000000000000e+00,-3.140685505597831106e-01,0.000000000000000000e+00,-1.000000009524615097e+00,0.000000000000000000e+00 +3.706978381876473350e+01,2.468300000000000125e+02,0.000000000000000000e+00,1.095053674015072609e+01,0.000000000000000000e+00,-3.149817238987080437e-01,0.000000000000000000e+00,-1.000000008486311209e+00,0.000000000000000000e+00 +3.707069701601134426e+01,2.468400000000000034e+02,0.000000000000000000e+00,1.095024909970772953e+01,0.000000000000000000e+00,-3.158949211530670542e-01,0.000000000000000000e+00,-1.000000009270029411e+00,0.000000000000000000e+00 +3.707161023724575699e+01,2.468499999999999943e+02,0.000000000000000000e+00,1.094996061775788831e+01,0.000000000000000000e+00,-3.168081423959488441e-01,0.000000000000000000e+00,-1.000000009601473616e+00,0.000000000000000000e+00 +3.707252348253942387e+01,2.468600000000000136e+02,0.000000000000000000e+00,1.094967129421285001e+01,0.000000000000000000e+00,-3.177213876983837615e-01,0.000000000000000000e+00,-1.000000007206646613e+00,0.000000000000000000e+00 +3.707343675196380417e+01,2.468700000000000045e+02,0.000000000000000000e+00,1.094938112898399396e+01,0.000000000000000000e+00,-3.186346571293439123e-01,0.000000000000000000e+00,-1.000000010459452415e+00,0.000000000000000000e+00 +3.707435004559037850e+01,2.468799999999999955e+02,0.000000000000000000e+00,1.094909012198243303e+01,0.000000000000000000e+00,-3.195479507654676588e-01,0.000000000000000000e+00,-1.000000008566220178e+00,0.000000000000000000e+00 +3.707526336349064167e+01,2.468900000000000148e+02,0.000000000000000000e+00,1.094879827311900655e+01,0.000000000000000000e+00,-3.204612686735544003e-01,0.000000000000000000e+00,-1.000000007769961563e+00,0.000000000000000000e+00 +3.707617670573611690e+01,2.469000000000000057e+02,0.000000000000000000e+00,1.094850558230428916e+01,0.000000000000000000e+00,-3.213746109261239048e-01,0.000000000000000000e+00,-1.000000010053687660e+00,0.000000000000000000e+00 +3.707709007239833454e+01,2.469099999999999966e+02,0.000000000000000000e+00,1.094821204944858550e+01,0.000000000000000000e+00,-3.222879775975260319e-01,0.000000000000000000e+00,-1.000000008882607316e+00,0.000000000000000000e+00 +3.707800346354885335e+01,2.469200000000000159e+02,0.000000000000000000e+00,1.094791767446192843e+01,0.000000000000000000e+00,-3.232013687561609006e-01,0.000000000000000000e+00,-1.000000008367956550e+00,0.000000000000000000e+00 +3.707891687925925339e+01,2.469300000000000068e+02,0.000000000000000000e+00,1.094762245725408434e+01,0.000000000000000000e+00,-3.241147844742025552e-01,0.000000000000000000e+00,-1.000000008362448511e+00,0.000000000000000000e+00 +3.707983031960112186e+01,2.469399999999999977e+02,0.000000000000000000e+00,1.094732639773454963e+01,0.000000000000000000e+00,-3.250282248237095217e-01,0.000000000000000000e+00,-1.000000010846180620e+00,0.000000000000000000e+00 +3.708074378464607435e+01,2.469500000000000171e+02,0.000000000000000000e+00,1.094702949581255069e+01,0.000000000000000000e+00,-3.259416898785681416e-01,0.000000000000000000e+00,-1.000000007155599002e+00,0.000000000000000000e+00 +3.708165727446574067e+01,2.469600000000000080e+02,0.000000000000000000e+00,1.094673175139704213e+01,0.000000000000000000e+00,-3.268551797047699603e-01,0.000000000000000000e+00,-1.000000009914312482e+00,0.000000000000000000e+00 +3.708257078913177196e+01,2.469699999999999989e+02,0.000000000000000000e+00,1.094643316439671388e+01,0.000000000000000000e+00,-3.277686943798570618e-01,0.000000000000000000e+00,-1.000000008329038348e+00,0.000000000000000000e+00 +3.708348432871584066e+01,2.469800000000000182e+02,0.000000000000000000e+00,1.094613373471998052e+01,0.000000000000000000e+00,-3.286822339715311236e-01,0.000000000000000000e+00,-1.000000008635959503e+00,0.000000000000000000e+00 +3.708439789328963343e+01,2.469900000000000091e+02,0.000000000000000000e+00,1.094583346227499021e+01,0.000000000000000000e+00,-3.295957985532099177e-01,0.000000000000000000e+00,-1.000000010684046092e+00,0.000000000000000000e+00 +3.708531148292485824e+01,2.470000000000000000e+02,0.000000000000000000e+00,1.094553234696961930e+01,0.000000000000000000e+00,-3.305093881981926995e-01,0.000000000000000000e+00,-1.000000007937811519e+00,0.000000000000000000e+00 +3.708622509769323727e+01,2.470100000000000193e+02,0.000000000000000000e+00,1.094523038871147236e+01,0.000000000000000000e+00,-3.314230029738273187e-01,0.000000000000000000e+00,-1.000000008758884951e+00,0.000000000000000000e+00 +3.708713873766652824e+01,2.470200000000000102e+02,0.000000000000000000e+00,1.094492758740788751e+01,0.000000000000000000e+00,-3.323366429551202206e-01,0.000000000000000000e+00,-1.000000008738765933e+00,0.000000000000000000e+00 +3.708805240291649596e+01,2.470300000000000011e+02,0.000000000000000000e+00,1.094462394296592933e+01,0.000000000000000000e+00,-3.332503082130697236e-01,0.000000000000000000e+00,-1.000000009853375671e+00,0.000000000000000000e+00 +3.708896609351491946e+01,2.470399999999999920e+02,0.000000000000000000e+00,1.094431945529239236e+01,0.000000000000000000e+00,-3.341639988204990197e-01,0.000000000000000000e+00,-1.000000007694104909e+00,0.000000000000000000e+00 +3.708987980953361330e+01,2.470500000000000114e+02,0.000000000000000000e+00,1.094401412429379938e+01,0.000000000000000000e+00,-3.350777148462227850e-01,0.000000000000000000e+00,-1.000000008491327197e+00,0.000000000000000000e+00 +3.709079355104439912e+01,2.470600000000000023e+02,0.000000000000000000e+00,1.094370794987640494e+01,0.000000000000000000e+00,-3.359914563647680708e-01,0.000000000000000000e+00,-1.000000012090461965e+00,0.000000000000000000e+00 +3.709170731811912702e+01,2.470699999999999932e+02,0.000000000000000000e+00,1.094340093194619001e+01,0.000000000000000000e+00,-3.369052234505406362e-01,0.000000000000000000e+00,-1.000000005573040252e+00,0.000000000000000000e+00 +3.709262111082965419e+01,2.470800000000000125e+02,0.000000000000000000e+00,1.094309307040886203e+01,0.000000000000000000e+00,-3.378190161661614455e-01,0.000000000000000000e+00,-1.000000010058475386e+00,0.000000000000000000e+00 +3.709353492924787332e+01,2.470900000000000034e+02,0.000000000000000000e+00,1.094278436516986552e+01,0.000000000000000000e+00,-3.387328345935698426e-01,0.000000000000000000e+00,-1.000000010499711323e+00,0.000000000000000000e+00 +3.709444877344568425e+01,2.470999999999999943e+02,0.000000000000000000e+00,1.094247481613436435e+01,0.000000000000000000e+00,-3.396466788009752658e-01,0.000000000000000000e+00,-1.000000006742272518e+00,0.000000000000000000e+00 +3.709536264349501522e+01,2.471100000000000136e+02,0.000000000000000000e+00,1.094216442320725413e+01,0.000000000000000000e+00,-3.405605488564656391e-01,0.000000000000000000e+00,-1.000000009264995882e+00,0.000000000000000000e+00 +3.709627653946780867e+01,2.471200000000000045e+02,0.000000000000000000e+00,1.094185318629316228e+01,0.000000000000000000e+00,-3.414744448377251551e-01,0.000000000000000000e+00,-1.000000009403232193e+00,0.000000000000000000e+00 +3.709719046143602839e+01,2.471299999999999955e+02,0.000000000000000000e+00,1.094154110529643908e+01,0.000000000000000000e+00,-3.423883668145397685e-01,0.000000000000000000e+00,-1.000000009127097300e+00,0.000000000000000000e+00 +3.709810440947165944e+01,2.471400000000000148e+02,0.000000000000000000e+00,1.094122818012116483e+01,0.000000000000000000e+00,-3.433023148585159778e-01,0.000000000000000000e+00,-1.000000010405688311e+00,0.000000000000000000e+00 +3.709901838364671534e+01,2.471500000000000057e+02,0.000000000000000000e+00,1.094091441067114800e+01,0.000000000000000000e+00,-3.442162890430801592e-01,0.000000000000000000e+00,-1.000000006701917021e+00,0.000000000000000000e+00 +3.709993238403321669e+01,2.471599999999999966e+02,0.000000000000000000e+00,1.094059979684992356e+01,0.000000000000000000e+00,-3.451302894357041740e-01,0.000000000000000000e+00,-1.000000010615471835e+00,0.000000000000000000e+00 +3.710084641070320544e+01,2.471700000000000159e+02,0.000000000000000000e+00,1.094028433856075821e+01,0.000000000000000000e+00,-3.460443161153962666e-01,0.000000000000000000e+00,-1.000000007103398314e+00,0.000000000000000000e+00 +3.710176046372875192e+01,2.471800000000000068e+02,0.000000000000000000e+00,1.093996803570663978e+01,0.000000000000000000e+00,-3.469583691474356080e-01,0.000000000000000000e+00,-1.000000010889709579e+00,0.000000000000000000e+00 +3.710267454318194069e+01,2.471899999999999977e+02,0.000000000000000000e+00,1.093965088819028963e+01,0.000000000000000000e+00,-3.478724486105801428e-01,0.000000000000000000e+00,-1.000000006932155960e+00,0.000000000000000000e+00 +3.710358864913488475e+01,2.472000000000000171e+02,0.000000000000000000e+00,1.093933289591415026e+01,0.000000000000000000e+00,-3.487865545698586867e-01,0.000000000000000000e+00,-1.000000009952157320e+00,0.000000000000000000e+00 +3.710450278165970417e+01,2.472100000000000080e+02,0.000000000000000000e+00,1.093901405878039768e+01,0.000000000000000000e+00,-3.497006871037773301e-01,0.000000000000000000e+00,-1.000000009159380587e+00,0.000000000000000000e+00 +3.710541694082855457e+01,2.472199999999999989e+02,0.000000000000000000e+00,1.093869437669092903e+01,0.000000000000000000e+00,-3.506148462809992594e-01,0.000000000000000000e+00,-1.000000008644598370e+00,0.000000000000000000e+00 +3.710633112671359868e+01,2.472300000000000182e+02,0.000000000000000000e+00,1.093837384954737146e+01,0.000000000000000000e+00,-3.515290321739477641e-01,0.000000000000000000e+00,-1.000000010371135284e+00,0.000000000000000000e+00 +3.710724533938703473e+01,2.472400000000000091e+02,0.000000000000000000e+00,1.093805247725107854e+01,0.000000000000000000e+00,-3.524432448568617926e-01,0.000000000000000000e+00,-1.000000007800958768e+00,0.000000000000000000e+00 +3.710815957892106809e+01,2.472500000000000000e+02,0.000000000000000000e+00,1.093773025970312851e+01,0.000000000000000000e+00,-3.533574843980239466e-01,0.000000000000000000e+00,-1.000000009272490109e+00,0.000000000000000000e+00 +3.710907384538792542e+01,2.472600000000000193e+02,0.000000000000000000e+00,1.093740719680432960e+01,0.000000000000000000e+00,-3.542717508733608800e-01,0.000000000000000000e+00,-1.000000008247063255e+00,0.000000000000000000e+00 +3.710998813885986891e+01,2.472700000000000102e+02,0.000000000000000000e+00,1.093708328845521294e+01,0.000000000000000000e+00,-3.551860443528422340e-01,0.000000000000000000e+00,-1.000000008811131824e+00,0.000000000000000000e+00 +3.711090245940916788e+01,2.472800000000000011e+02,0.000000000000000000e+00,1.093675853455603786e+01,0.000000000000000000e+00,-3.561003649101947555e-01,0.000000000000000000e+00,-1.000000010800329742e+00,0.000000000000000000e+00 +3.711181680710811293e+01,2.472899999999999920e+02,0.000000000000000000e+00,1.093643293500678837e+01,0.000000000000000000e+00,-3.570147126190160725e-01,0.000000000000000000e+00,-1.000000007676121294e+00,0.000000000000000000e+00 +3.711273118202902310e+01,2.473000000000000114e+02,0.000000000000000000e+00,1.093610648970717314e+01,0.000000000000000000e+00,-3.579290875469463562e-01,0.000000000000000000e+00,-1.000000007772465560e+00,0.000000000000000000e+00 +3.711364558424423876e+01,2.473100000000000023e+02,0.000000000000000000e+00,1.093577919855663083e+01,0.000000000000000000e+00,-3.588434897692671099e-01,0.000000000000000000e+00,-1.000000010922907023e+00,0.000000000000000000e+00 +3.711456001382611447e+01,2.473199999999999932e+02,0.000000000000000000e+00,1.093545106145432300e+01,0.000000000000000000e+00,-3.597579193611291082e-01,0.000000000000000000e+00,-1.000000008464332346e+00,0.000000000000000000e+00 +3.711547447084702611e+01,2.473300000000000125e+02,0.000000000000000000e+00,1.093512207829913407e+01,0.000000000000000000e+00,-3.606723763897826118e-01,0.000000000000000000e+00,-1.000000008727615963e+00,0.000000000000000000e+00 +3.711638895537937799e+01,2.473400000000000034e+02,0.000000000000000000e+00,1.093479224898967850e+01,0.000000000000000000e+00,-3.615868609301172154e-01,0.000000000000000000e+00,-1.000000009421348812e+00,0.000000000000000000e+00 +3.711730346749559573e+01,2.473499999999999943e+02,0.000000000000000000e+00,1.093446157342429359e+01,0.000000000000000000e+00,-3.625013730549486168e-01,0.000000000000000000e+00,-1.000000008254150474e+00,0.000000000000000000e+00 +3.711821800726811915e+01,2.473600000000000136e+02,0.000000000000000000e+00,1.093413005150104134e+01,0.000000000000000000e+00,-3.634159128350184509e-01,0.000000000000000000e+00,-1.000000009306053483e+00,0.000000000000000000e+00 +3.711913257476940942e+01,2.473700000000000045e+02,0.000000000000000000e+00,1.093379768311771016e+01,0.000000000000000000e+00,-3.643304803448211837e-01,0.000000000000000000e+00,-1.000000010284489260e+00,0.000000000000000000e+00 +3.712004717007195609e+01,2.473799999999999955e+02,0.000000000000000000e+00,1.093346446817181139e+01,0.000000000000000000e+00,-3.652450756567762746e-01,0.000000000000000000e+00,-1.000000006773881234e+00,0.000000000000000000e+00 +3.712096179324827006e+01,2.473900000000000148e+02,0.000000000000000000e+00,1.093313040656058099e+01,0.000000000000000000e+00,-3.661596988392862295e-01,0.000000000000000000e+00,-1.000000009222368647e+00,0.000000000000000000e+00 +3.712187644437087641e+01,2.474000000000000057e+02,0.000000000000000000e+00,1.093279549818098317e+01,0.000000000000000000e+00,-3.670743499703312818e-01,0.000000000000000000e+00,-1.000000011089230867e+00,0.000000000000000000e+00 +3.712279112351233579e+01,2.474099999999999966e+02,0.000000000000000000e+00,1.093245974292970146e+01,0.000000000000000000e+00,-3.679890291219312659e-01,0.000000000000000000e+00,-1.000000007958295134e+00,0.000000000000000000e+00 +3.712370583074521591e+01,2.474200000000000159e+02,0.000000000000000000e+00,1.093212314070314406e+01,0.000000000000000000e+00,-3.689037363620882859e-01,0.000000000000000000e+00,-1.000000008151687769e+00,0.000000000000000000e+00 +3.712462056614211292e+01,2.474300000000000068e+02,0.000000000000000000e+00,1.093178569139744738e+01,0.000000000000000000e+00,-3.698184717664384502e-01,0.000000000000000000e+00,-1.000000009374333532e+00,0.000000000000000000e+00 +3.712553532977563719e+01,2.474399999999999977e+02,0.000000000000000000e+00,1.093144739490846895e+01,0.000000000000000000e+00,-3.707332354085406401e-01,0.000000000000000000e+00,-1.000000009331857731e+00,0.000000000000000000e+00 +3.712645012171843462e+01,2.474500000000000171e+02,0.000000000000000000e+00,1.093110825113178919e+01,0.000000000000000000e+00,-3.716480273598769535e-01,0.000000000000000000e+00,-1.000000007852200001e+00,0.000000000000000000e+00 +3.712736494204316529e+01,2.474600000000000080e+02,0.000000000000000000e+00,1.093076825996271317e+01,0.000000000000000000e+00,-3.725628476917940413e-01,0.000000000000000000e+00,-1.000000011130192545e+00,0.000000000000000000e+00 +3.712827979082251773e+01,2.474699999999999989e+02,0.000000000000000000e+00,1.093042742129627065e+01,0.000000000000000000e+00,-3.734776964813278921e-01,0.000000000000000000e+00,-1.000000008380179883e+00,0.000000000000000000e+00 +3.712919466812919467e+01,2.474800000000000182e+02,0.000000000000000000e+00,1.093008573502721070e+01,0.000000000000000000e+00,-3.743925737956695365e-01,0.000000000000000000e+00,-1.000000007918619538e+00,0.000000000000000000e+00 +3.713010957403592016e+01,2.474900000000000091e+02,0.000000000000000000e+00,1.092974320105001063e+01,0.000000000000000000e+00,-3.753074797096405124e-01,0.000000000000000000e+00,-1.000000009570569226e+00,0.000000000000000000e+00 +3.713102450861544668e+01,2.475000000000000000e+02,0.000000000000000000e+00,1.092939981925886883e+01,0.000000000000000000e+00,-3.762224142979248009e-01,0.000000000000000000e+00,-1.000000008917209859e+00,0.000000000000000000e+00 +3.713193947194054800e+01,2.475100000000000193e+02,0.000000000000000000e+00,1.092905558954770484e+01,0.000000000000000000e+00,-3.771373776311858772e-01,0.000000000000000000e+00,-1.000000010027544572e+00,0.000000000000000000e+00 +3.713285446408401924e+01,2.475200000000000102e+02,0.000000000000000000e+00,1.092871051181016284e+01,0.000000000000000000e+00,-3.780523697838325536e-01,0.000000000000000000e+00,-1.000000006360634464e+00,0.000000000000000000e+00 +3.713376948511867681e+01,2.475300000000000011e+02,0.000000000000000000e+00,1.092836458593960813e+01,0.000000000000000000e+00,-3.789673908243111899e-01,0.000000000000000000e+00,-1.000000010470305067e+00,0.000000000000000000e+00 +3.713468453511736556e+01,2.475399999999999920e+02,0.000000000000000000e+00,1.092801781182913246e+01,0.000000000000000000e+00,-3.798824408325776614e-01,0.000000000000000000e+00,-1.000000009450112248e+00,0.000000000000000000e+00 +3.713559961415294453e+01,2.475500000000000114e+02,0.000000000000000000e+00,1.092767018937154333e+01,0.000000000000000000e+00,-3.807975198768007163e-01,0.000000000000000000e+00,-1.000000009487912678e+00,0.000000000000000000e+00 +3.713651472229829409e+01,2.475600000000000023e+02,0.000000000000000000e+00,1.092732171845937472e+01,0.000000000000000000e+00,-3.817126280308338893e-01,0.000000000000000000e+00,-1.000000008284601005e+00,0.000000000000000000e+00 +3.713742985962633014e+01,2.475699999999999932e+02,0.000000000000000000e+00,1.092697239898488171e+01,0.000000000000000000e+00,-3.826277653664495459e-01,0.000000000000000000e+00,-1.000000009904509435e+00,0.000000000000000000e+00 +3.713834502620997569e+01,2.475800000000000125e+02,0.000000000000000000e+00,1.092662223084004225e+01,0.000000000000000000e+00,-3.835429319591622810e-01,0.000000000000000000e+00,-1.000000007805805335e+00,0.000000000000000000e+00 +3.713926022212218925e+01,2.475900000000000034e+02,0.000000000000000000e+00,1.092627121391655365e+01,0.000000000000000000e+00,-3.844581278785227374e-01,0.000000000000000000e+00,-1.000000008172486465e+00,0.000000000000000000e+00 +3.714017544743595067e+01,2.475999999999999943e+02,0.000000000000000000e+00,1.092591934810583787e+01,0.000000000000000000e+00,-3.853733531997639017e-01,0.000000000000000000e+00,-1.000000010824363628e+00,0.000000000000000000e+00 +3.714109070222425402e+01,2.476100000000000136e+02,0.000000000000000000e+00,1.092556663329903621e+01,0.000000000000000000e+00,-3.862886079979770404e-01,0.000000000000000000e+00,-1.000000009219660591e+00,0.000000000000000000e+00 +3.714200598656012886e+01,2.476200000000000045e+02,0.000000000000000000e+00,1.092521306938700931e+01,0.000000000000000000e+00,-3.872038923422890799e-01,0.000000000000000000e+00,-1.000000007419525438e+00,0.000000000000000000e+00 +3.714292130051661900e+01,2.476299999999999955e+02,0.000000000000000000e+00,1.092485865626034247e+01,0.000000000000000000e+00,-3.881192063055668995e-01,0.000000000000000000e+00,-1.000000009483059671e+00,0.000000000000000000e+00 +3.714383664416678954e+01,2.476400000000000148e+02,0.000000000000000000e+00,1.092450339380934210e+01,0.000000000000000000e+00,-3.890345499644159988e-01,0.000000000000000000e+00,-1.000000008867977686e+00,0.000000000000000000e+00 +3.714475201758373402e+01,2.476500000000000057e+02,0.000000000000000000e+00,1.092414728192403217e+01,0.000000000000000000e+00,-3.899499233894768158e-01,0.000000000000000000e+00,-1.000000009632677545e+00,0.000000000000000000e+00 +3.714566742084056727e+01,2.476599999999999966e+02,0.000000000000000000e+00,1.092379032049415954e+01,0.000000000000000000e+00,-3.908653266551279093e-01,0.000000000000000000e+00,-1.000000009474513618e+00,0.000000000000000000e+00 +3.714658285401043258e+01,2.476700000000000159e+02,0.000000000000000000e+00,1.092343250940919042e+01,0.000000000000000000e+00,-3.917807598336633945e-01,0.000000000000000000e+00,-1.000000008210829128e+00,0.000000000000000000e+00 +3.714749831716648742e+01,2.476800000000000068e+02,0.000000000000000000e+00,1.092307384855831209e+01,0.000000000000000000e+00,-3.926962229972335017e-01,0.000000000000000000e+00,-1.000000009897267894e+00,0.000000000000000000e+00 +3.714841381038191770e+01,2.476899999999999977e+02,0.000000000000000000e+00,1.092271433783043300e+01,0.000000000000000000e+00,-3.936117162217247500e-01,0.000000000000000000e+00,-1.000000007991211692e+00,0.000000000000000000e+00 +3.714932933372993773e+01,2.477000000000000171e+02,0.000000000000000000e+00,1.092235397711417910e+01,0.000000000000000000e+00,-3.945272395770575424e-01,0.000000000000000000e+00,-1.000000008666542595e+00,0.000000000000000000e+00 +3.715024488728377605e+01,2.477100000000000080e+02,0.000000000000000000e+00,1.092199276629789928e+01,0.000000000000000000e+00,-3.954427931388280748e-01,0.000000000000000000e+00,-1.000000009618655428e+00,0.000000000000000000e+00 +3.715116047111668962e+01,2.477199999999999989e+02,0.000000000000000000e+00,1.092163070526965996e+01,0.000000000000000000e+00,-3.963583769805463786e-01,0.000000000000000000e+00,-1.000000008543241892e+00,0.000000000000000000e+00 +3.715207608530195671e+01,2.477300000000000182e+02,0.000000000000000000e+00,1.092126779391724689e+01,0.000000000000000000e+00,-3.972739911736363760e-01,0.000000000000000000e+00,-1.000000009492119313e+00,0.000000000000000000e+00 +3.715299172991288401e+01,2.477400000000000091e+02,0.000000000000000000e+00,1.092090403212816696e+01,0.000000000000000000e+00,-3.981896357932556141e-01,0.000000000000000000e+00,-1.000000010159973751e+00,0.000000000000000000e+00 +3.715390740502279954e+01,2.477500000000000000e+02,0.000000000000000000e+00,1.092053941978964460e+01,0.000000000000000000e+00,-3.991053109124747533e-01,0.000000000000000000e+00,-1.000000008241367144e+00,0.000000000000000000e+00 +3.715482311070505261e+01,2.477600000000000193e+02,0.000000000000000000e+00,1.092017395678862357e+01,0.000000000000000000e+00,-4.000210166022772351e-01,0.000000000000000000e+00,-1.000000007786048695e+00,0.000000000000000000e+00 +3.715573884703302099e+01,2.477700000000000102e+02,0.000000000000000000e+00,1.091980764301176876e+01,0.000000000000000000e+00,-4.009367529373787375e-01,0.000000000000000000e+00,-1.000000010723923305e+00,0.000000000000000000e+00 +3.715665461408011083e+01,2.477800000000000011e+02,0.000000000000000000e+00,1.091944047834546261e+01,0.000000000000000000e+00,-4.018525199942864501e-01,0.000000000000000000e+00,-1.000000008393659323e+00,0.000000000000000000e+00 +3.715757041191973542e+01,2.477899999999999920e+02,0.000000000000000000e+00,1.091907246267580334e+01,0.000000000000000000e+00,-4.027683178415999432e-01,0.000000000000000000e+00,-1.000000009079092145e+00,0.000000000000000000e+00 +3.715848624062535066e+01,2.478000000000000114e+02,0.000000000000000000e+00,1.091870359588861206e+01,0.000000000000000000e+00,-4.036841465555290331e-01,0.000000000000000000e+00,-1.000000008354567704e+00,0.000000000000000000e+00 +3.715940210027042667e+01,2.478100000000000023e+02,0.000000000000000000e+00,1.091833387786942566e+01,0.000000000000000000e+00,-4.046000062082547588e-01,0.000000000000000000e+00,-1.000000008147989172e+00,0.000000000000000000e+00 +3.716031799092845489e+01,2.478199999999999932e+02,0.000000000000000000e+00,1.091796330850350039e+01,0.000000000000000000e+00,-4.055158968737480607e-01,0.000000000000000000e+00,-1.000000010386445926e+00,0.000000000000000000e+00 +3.716123391267296228e+01,2.478300000000000125e+02,0.000000000000000000e+00,1.091759188767581001e+01,0.000000000000000000e+00,-4.064318186277693368e-01,0.000000000000000000e+00,-1.000000010643373294e+00,0.000000000000000000e+00 +3.716214986557749000e+01,2.478400000000000034e+02,0.000000000000000000e+00,1.091721961527104412e+01,0.000000000000000000e+00,-4.073477715420490974e-01,0.000000000000000000e+00,-1.000000006611229342e+00,0.000000000000000000e+00 +3.716306584971561477e+01,2.478499999999999943e+02,0.000000000000000000e+00,1.091684649117361161e+01,0.000000000000000000e+00,-4.082637556862284689e-01,0.000000000000000000e+00,-1.000000010800555561e+00,0.000000000000000000e+00 +3.716398186516092750e+01,2.478600000000000136e+02,0.000000000000000000e+00,1.091647251526764251e+01,0.000000000000000000e+00,-4.091797711414325578e-01,0.000000000000000000e+00,-1.000000006082611526e+00,0.000000000000000000e+00 +3.716489791198704751e+01,2.478700000000000045e+02,0.000000000000000000e+00,1.091609768743697728e+01,0.000000000000000000e+00,-4.100958179731211128e-01,0.000000000000000000e+00,-1.000000011316358295e+00,0.000000000000000000e+00 +3.716581399026761545e+01,2.478799999999999955e+02,0.000000000000000000e+00,1.091572200756518107e+01,0.000000000000000000e+00,-4.110118962640539886e-01,0.000000000000000000e+00,-1.000000009373853027e+00,0.000000000000000000e+00 +3.716673010007630040e+01,2.478900000000000148e+02,0.000000000000000000e+00,1.091534547553552770e+01,0.000000000000000000e+00,-4.119280060813256261e-01,0.000000000000000000e+00,-1.000000008528417306e+00,0.000000000000000000e+00 +3.716764624148679275e+01,2.479000000000000057e+02,0.000000000000000000e+00,1.091496809123101386e+01,0.000000000000000000e+00,-4.128441474996341065e-01,0.000000000000000000e+00,-1.000000008585282929e+00,0.000000000000000000e+00 +3.716856241457281840e+01,2.479099999999999966e+02,0.000000000000000000e+00,1.091458985453435204e+01,0.000000000000000000e+00,-4.137603205935240225e-01,0.000000000000000000e+00,-1.000000009349214958e+00,0.000000000000000000e+00 +3.716947861940811748e+01,2.479200000000000159e+02,0.000000000000000000e+00,1.091421076532797052e+01,0.000000000000000000e+00,-4.146765254373860898e-01,0.000000000000000000e+00,-1.000000008508605820e+00,0.000000000000000000e+00 +3.717039485606645144e+01,2.479300000000000068e+02,0.000000000000000000e+00,1.091383082349401334e+01,0.000000000000000000e+00,-4.155927621035180874e-01,0.000000000000000000e+00,-1.000000010099477921e+00,0.000000000000000000e+00 +3.717131112462161724e+01,2.479399999999999977e+02,0.000000000000000000e+00,1.091345002891434213e+01,0.000000000000000000e+00,-4.165090306679407606e-01,0.000000000000000000e+00,-1.000000007577759753e+00,0.000000000000000000e+00 +3.717222742514744027e+01,2.479500000000000171e+02,0.000000000000000000e+00,1.091306838147053249e+01,0.000000000000000000e+00,-4.174253312007038530e-01,0.000000000000000000e+00,-1.000000011324980509e+00,0.000000000000000000e+00 +3.717314375771775303e+01,2.479600000000000080e+02,0.000000000000000000e+00,1.091268588104387938e+01,0.000000000000000000e+00,-4.183416637813948125e-01,0.000000000000000000e+00,-1.000000006334538893e+00,0.000000000000000000e+00 +3.717406012240643065e+01,2.479699999999999989e+02,0.000000000000000000e+00,1.091230252751538821e+01,0.000000000000000000e+00,-4.192580284758753995e-01,0.000000000000000000e+00,-1.000000011447553350e+00,0.000000000000000000e+00 +3.717497651928736246e+01,2.479800000000000182e+02,0.000000000000000000e+00,1.091191832076578727e+01,0.000000000000000000e+00,-4.201744253672977658e-01,0.000000000000000000e+00,-1.000000007427128468e+00,0.000000000000000000e+00 +3.717589294843446623e+01,2.479900000000000091e+02,0.000000000000000000e+00,1.091153326067551177e+01,0.000000000000000000e+00,-4.210908545212111442e-01,0.000000000000000000e+00,-1.000000008881397839e+00,0.000000000000000000e+00 +3.717680940992169525e+01,2.480000000000000000e+02,0.000000000000000000e+00,1.091114734712471979e+01,0.000000000000000000e+00,-4.220073160165770942e-01,0.000000000000000000e+00,-1.000000011379335696e+00,0.000000000000000000e+00 +3.717772590382300990e+01,2.480100000000000193e+02,0.000000000000000000e+00,1.091076057999327986e+01,0.000000000000000000e+00,-4.229238099283221808e-01,0.000000000000000000e+00,-1.000000006262478314e+00,0.000000000000000000e+00 +3.717864243021241322e+01,2.480200000000000102e+02,0.000000000000000000e+00,1.091037295916077454e+01,0.000000000000000000e+00,-4.238403363234629073e-01,0.000000000000000000e+00,-1.000000010247784843e+00,0.000000000000000000e+00 +3.717955898916392243e+01,2.480300000000000011e+02,0.000000000000000000e+00,1.090998448450650748e+01,0.000000000000000000e+00,-4.247568952843627232e-01,0.000000000000000000e+00,-1.000000008331752621e+00,0.000000000000000000e+00 +3.718047558075158321e+01,2.480399999999999920e+02,0.000000000000000000e+00,1.090959515590948925e+01,0.000000000000000000e+00,-4.256734868796595572e-01,0.000000000000000000e+00,-1.000000010884793511e+00,0.000000000000000000e+00 +3.718139220504946962e+01,2.480500000000000114e+02,0.000000000000000000e+00,1.090920497324844973e+01,0.000000000000000000e+00,-4.265901111875222695e-01,0.000000000000000000e+00,-1.000000007133853730e+00,0.000000000000000000e+00 +3.718230886213167707e+01,2.480600000000000023e+02,0.000000000000000000e+00,1.090881393640182928e+01,0.000000000000000000e+00,-4.275067682762707655e-01,0.000000000000000000e+00,-1.000000009561069270e+00,0.000000000000000000e+00 +3.718322555207233648e+01,2.480699999999999932e+02,0.000000000000000000e+00,1.090842204524778758e+01,0.000000000000000000e+00,-4.284234582256924440e-01,0.000000000000000000e+00,-1.000000009506742060e+00,0.000000000000000000e+00 +3.718414227494559299e+01,2.480800000000000125e+02,0.000000000000000000e+00,1.090802929966419299e+01,0.000000000000000000e+00,-4.293401811076626995e-01,0.000000000000000000e+00,-1.000000008881287705e+00,0.000000000000000000e+00 +3.718505903082562014e+01,2.480900000000000034e+02,0.000000000000000000e+00,1.090763569952862966e+01,0.000000000000000000e+00,-4.302569369958340606e-01,0.000000000000000000e+00,-1.000000009594353978e+00,0.000000000000000000e+00 +3.718597581978662703e+01,2.480999999999999943e+02,0.000000000000000000e+00,1.090724124471839573e+01,0.000000000000000000e+00,-4.311737259656358012e-01,0.000000000000000000e+00,-1.000000007214179254e+00,0.000000000000000000e+00 +3.718689264190283694e+01,2.481100000000000136e+02,0.000000000000000000e+00,1.090684593511050160e+01,0.000000000000000000e+00,-4.320905480884603134e-01,0.000000000000000000e+00,-1.000000009988819105e+00,0.000000000000000000e+00 +3.718780949724850871e+01,2.481200000000000045e+02,0.000000000000000000e+00,1.090644977058167342e+01,0.000000000000000000e+00,-4.330074034432881414e-01,0.000000000000000000e+00,-1.000000009259289113e+00,0.000000000000000000e+00 +3.718872638589791535e+01,2.481299999999999955e+02,0.000000000000000000e+00,1.090605275100834604e+01,0.000000000000000000e+00,-4.339242921011872700e-01,0.000000000000000000e+00,-1.000000009045994398e+00,0.000000000000000000e+00 +3.718964330792537254e+01,2.481400000000000148e+02,0.000000000000000000e+00,1.090565487626667007e+01,0.000000000000000000e+00,-4.348412141369380479e-01,0.000000000000000000e+00,-1.000000009141945423e+00,0.000000000000000000e+00 +3.719056026340521015e+01,2.481500000000000057e+02,0.000000000000000000e+00,1.090525614623250839e+01,0.000000000000000000e+00,-4.357581696251574543e-01,0.000000000000000000e+00,-1.000000009339748530e+00,0.000000000000000000e+00 +3.719147725241178648e+01,2.481599999999999966e+02,0.000000000000000000e+00,1.090485656078143606e+01,0.000000000000000000e+00,-4.366751586402987662e-01,0.000000000000000000e+00,-1.000000007319268747e+00,0.000000000000000000e+00 +3.719239427501948825e+01,2.481700000000000159e+02,0.000000000000000000e+00,1.090445611978874041e+01,0.000000000000000000e+00,-4.375921812547141632e-01,0.000000000000000000e+00,-1.000000011321337867e+00,0.000000000000000000e+00 +3.719331133130273059e+01,2.481800000000000068e+02,0.000000000000000000e+00,1.090405482312942276e+01,0.000000000000000000e+00,-4.385092375483394811e-01,0.000000000000000000e+00,-1.000000008463497458e+00,0.000000000000000000e+00 +3.719422842133594997e+01,2.481899999999999977e+02,0.000000000000000000e+00,1.090365267067819133e+01,0.000000000000000000e+00,-4.394263275893234288e-01,0.000000000000000000e+00,-1.000000009097480991e+00,0.000000000000000000e+00 +3.719514554519361837e+01,2.482000000000000171e+02,0.000000000000000000e+00,1.090324966230947190e+01,0.000000000000000000e+00,-4.403434514553345447e-01,0.000000000000000000e+00,-1.000000006677392639e+00,0.000000000000000000e+00 +3.719606270295022199e+01,2.482100000000000080e+02,0.000000000000000000e+00,1.090284579789739894e+01,0.000000000000000000e+00,-4.412606092180648698e-01,0.000000000000000000e+00,-1.000000011551219092e+00,0.000000000000000000e+00 +3.719697989468028965e+01,2.482199999999999989e+02,0.000000000000000000e+00,1.090244107731582091e+01,0.000000000000000000e+00,-4.421778009587240543e-01,0.000000000000000000e+00,-1.000000008726350087e+00,0.000000000000000000e+00 +3.719789712045835728e+01,2.482300000000000182e+02,0.000000000000000000e+00,1.090203550043829139e+01,0.000000000000000000e+00,-4.430950267447977819e-01,0.000000000000000000e+00,-1.000000008549714492e+00,0.000000000000000000e+00 +3.719881438035900345e+01,2.482400000000000091e+02,0.000000000000000000e+00,1.090162906713808155e+01,0.000000000000000000e+00,-4.440122866532887347e-01,0.000000000000000000e+00,-1.000000008697262466e+00,0.000000000000000000e+00 +3.719973167445683515e+01,2.482500000000000000e+02,0.000000000000000000e+00,1.090122177728817121e+01,0.000000000000000000e+00,-4.449295807590950558e-01,0.000000000000000000e+00,-1.000000011067518679e+00,0.000000000000000000e+00 +3.720064900282647358e+01,2.482600000000000193e+02,0.000000000000000000e+00,1.090081363076125065e+01,0.000000000000000000e+00,-4.458469091388835848e-01,0.000000000000000000e+00,-1.000000007003661651e+00,0.000000000000000000e+00 +3.720156636554257545e+01,2.482700000000000102e+02,0.000000000000000000e+00,1.090040462742971883e+01,0.000000000000000000e+00,-4.467642718614071029e-01,0.000000000000000000e+00,-1.000000008957591557e+00,0.000000000000000000e+00 +3.720248376267981882e+01,2.482800000000000011e+02,0.000000000000000000e+00,1.089999476716569049e+01,0.000000000000000000e+00,-4.476816690068682880e-01,0.000000000000000000e+00,-1.000000010382027460e+00,0.000000000000000000e+00 +3.720340119431291726e+01,2.482899999999999920e+02,0.000000000000000000e+00,1.089958404984098550e+01,0.000000000000000000e+00,-4.485991006494910449e-01,0.000000000000000000e+00,-1.000000008952385944e+00,0.000000000000000000e+00 +3.720431866051660563e+01,2.483000000000000114e+02,0.000000000000000000e+00,1.089917247532713418e+01,0.000000000000000000e+00,-4.495165668613938514e-01,0.000000000000000000e+00,-1.000000008674505558e+00,0.000000000000000000e+00 +3.720523616136564726e+01,2.483100000000000023e+02,0.000000000000000000e+00,1.089876004349537908e+01,0.000000000000000000e+00,-4.504340677183976682e-01,0.000000000000000000e+00,-1.000000009332323803e+00,0.000000000000000000e+00 +3.720615369693484098e+01,2.483199999999999932e+02,0.000000000000000000e+00,1.089834675421667143e+01,0.000000000000000000e+00,-4.513516032961528146e-01,0.000000000000000000e+00,-1.000000008599629009e+00,0.000000000000000000e+00 +3.720707126729899983e+01,2.483300000000000125e+02,0.000000000000000000e+00,1.089793260736167113e+01,0.000000000000000000e+00,-4.522691736682027952e-01,0.000000000000000000e+00,-1.000000008369581694e+00,0.000000000000000000e+00 +3.720798887253297238e+01,2.483400000000000034e+02,0.000000000000000000e+00,1.089751760280074855e+01,0.000000000000000000e+00,-4.531867789098557586e-01,0.000000000000000000e+00,-1.000000010534377592e+00,0.000000000000000000e+00 +3.720890651271163563e+01,2.483499999999999943e+02,0.000000000000000000e+00,1.089710174040398272e+01,0.000000000000000000e+00,-4.541044190981839423e-01,0.000000000000000000e+00,-1.000000008547469621e+00,0.000000000000000000e+00 +3.720982418790988788e+01,2.483600000000000136e+02,0.000000000000000000e+00,1.089668502004115958e+01,0.000000000000000000e+00,-4.550220943042799782e-01,0.000000000000000000e+00,-1.000000008519239536e+00,0.000000000000000000e+00 +3.721074189820266298e+01,2.483700000000000045e+02,0.000000000000000000e+00,1.089626744158177729e+01,0.000000000000000000e+00,-4.559398046048714348e-01,0.000000000000000000e+00,-1.000000008121266548e+00,0.000000000000000000e+00 +3.721165964366491608e+01,2.483799999999999955e+02,0.000000000000000000e+00,1.089584900489504093e+01,0.000000000000000000e+00,-4.568575500745770679e-01,0.000000000000000000e+00,-1.000000011351870777e+00,0.000000000000000000e+00 +3.721257742437163074e+01,2.483900000000000148e+02,0.000000000000000000e+00,1.089542970984986425e+01,0.000000000000000000e+00,-4.577753307917131198e-01,0.000000000000000000e+00,-1.000000007446654626e+00,0.000000000000000000e+00 +3.721349524039782608e+01,2.484000000000000057e+02,0.000000000000000000e+00,1.089500955631486612e+01,0.000000000000000000e+00,-4.586931468247444910e-01,0.000000000000000000e+00,-1.000000008838309196e+00,0.000000000000000000e+00 +3.721441309181854251e+01,2.484099999999999966e+02,0.000000000000000000e+00,1.089458854415837941e+01,0.000000000000000000e+00,-4.596109982535747651e-01,0.000000000000000000e+00,-1.000000011087747165e+00,0.000000000000000000e+00 +3.721533097870884887e+01,2.484200000000000159e+02,0.000000000000000000e+00,1.089416667324844035e+01,0.000000000000000000e+00,-4.605288851540616513e-01,0.000000000000000000e+00,-1.000000007648283118e+00,0.000000000000000000e+00 +3.721624890114384954e+01,2.484300000000000068e+02,0.000000000000000000e+00,1.089374394345279207e+01,0.000000000000000000e+00,-4.614468075960818094e-01,0.000000000000000000e+00,-1.000000008839994514e+00,0.000000000000000000e+00 +3.721716685919866308e+01,2.484399999999999977e+02,0.000000000000000000e+00,1.089332035463888992e+01,0.000000000000000000e+00,-4.623647656590129662e-01,0.000000000000000000e+00,-1.000000008115032646e+00,0.000000000000000000e+00 +3.721808485294845070e+01,2.484500000000000171e+02,0.000000000000000000e+00,1.089289590667389263e+01,0.000000000000000000e+00,-4.632827594162508000e-01,0.000000000000000000e+00,-1.000000011573982439e+00,0.000000000000000000e+00 +3.721900288246839494e+01,2.484600000000000080e+02,0.000000000000000000e+00,1.089247059942466755e+01,0.000000000000000000e+00,-4.642007889468197090e-01,0.000000000000000000e+00,-1.000000008454248857e+00,0.000000000000000000e+00 +3.721992094783370675e+01,2.484699999999999989e+02,0.000000000000000000e+00,1.089204443275778544e+01,0.000000000000000000e+00,-4.651188543198922498e-01,0.000000000000000000e+00,-1.000000006963115640e+00,0.000000000000000000e+00 +3.722083904911962549e+01,2.484800000000000182e+02,0.000000000000000000e+00,1.089161740653952926e+01,0.000000000000000000e+00,-4.660369556122039292e-01,0.000000000000000000e+00,-1.000000011089623220e+00,0.000000000000000000e+00 +3.722175718640141895e+01,2.484900000000000091e+02,0.000000000000000000e+00,1.089118952063588708e+01,0.000000000000000000e+00,-4.669550929041815235e-01,0.000000000000000000e+00,-1.000000007964600091e+00,0.000000000000000000e+00 +3.722267535975439046e+01,2.485000000000000000e+02,0.000000000000000000e+00,1.089076077491254857e+01,0.000000000000000000e+00,-4.678732662644649598e-01,0.000000000000000000e+00,-1.000000010005463125e+00,0.000000000000000000e+00 +3.722359356925386464e+01,2.485100000000000193e+02,0.000000000000000000e+00,1.089033116923491562e+01,0.000000000000000000e+00,-4.687914757731239113e-01,0.000000000000000000e+00,-1.000000008557810460e+00,0.000000000000000000e+00 +3.722451181497519457e+01,2.485200000000000102e+02,0.000000000000000000e+00,1.088990070346809169e+01,0.000000000000000000e+00,-4.697097215023105510e-01,0.000000000000000000e+00,-1.000000009714850924e+00,0.000000000000000000e+00 +3.722543009699376171e+01,2.485300000000000011e+02,0.000000000000000000e+00,1.088946937747688892e+01,0.000000000000000000e+00,-4.706280035298008313e-01,0.000000000000000000e+00,-1.000000009035994397e+00,0.000000000000000000e+00 +3.722634841538498307e+01,2.485399999999999920e+02,0.000000000000000000e+00,1.088903719112582280e+01,0.000000000000000000e+00,-4.715463219293220543e-01,0.000000000000000000e+00,-1.000000008399794194e+00,0.000000000000000000e+00 +3.722726677022430408e+01,2.485500000000000114e+02,0.000000000000000000e+00,1.088860414427911572e+01,0.000000000000000000e+00,-4.724646767763555077e-01,0.000000000000000000e+00,-1.000000007577841243e+00,0.000000000000000000e+00 +3.722818516158719149e+01,2.485600000000000023e+02,0.000000000000000000e+00,1.088817023680069518e+01,0.000000000000000000e+00,-4.733830681462017909e-01,0.000000000000000000e+00,-1.000000010552467566e+00,0.000000000000000000e+00 +3.722910358954914756e+01,2.485699999999999932e+02,0.000000000000000000e+00,1.088773546855419383e+01,0.000000000000000000e+00,-4.743014961178481093e-01,0.000000000000000000e+00,-1.000000010776144643e+00,0.000000000000000000e+00 +3.723002205418570298e+01,2.485800000000000125e+02,0.000000000000000000e+00,1.088729983940294588e+01,0.000000000000000000e+00,-4.752199607642976220e-01,0.000000000000000000e+00,-1.000000005913905143e+00,0.000000000000000000e+00 +3.723094055557240978e+01,2.485900000000000034e+02,0.000000000000000000e+00,1.088686334920999244e+01,0.000000000000000000e+00,-4.761384621564377917e-01,0.000000000000000000e+00,-1.000000010473802492e+00,0.000000000000000000e+00 +3.723185909378486258e+01,2.485999999999999943e+02,0.000000000000000000e+00,1.088642599783808329e+01,0.000000000000000000e+00,-4.770570003785110647e-01,0.000000000000000000e+00,-1.000000009485694674e+00,0.000000000000000000e+00 +3.723277766889867735e+01,2.486100000000000136e+02,0.000000000000000000e+00,1.088598778514966448e+01,0.000000000000000000e+00,-4.779755755010391405e-01,0.000000000000000000e+00,-1.000000009034216708e+00,0.000000000000000000e+00 +3.723369628098949846e+01,2.486200000000000045e+02,0.000000000000000000e+00,1.088554871100689070e+01,0.000000000000000000e+00,-4.788941876001620024e-01,0.000000000000000000e+00,-1.000000008887127922e+00,0.000000000000000000e+00 +3.723461493013300583e+01,2.486299999999999955e+02,0.000000000000000000e+00,1.088510877527162002e+01,0.000000000000000000e+00,-4.798128367518358917e-01,0.000000000000000000e+00,-1.000000008811003260e+00,0.000000000000000000e+00 +3.723553361640490778e+01,2.486400000000000148e+02,0.000000000000000000e+00,1.088466797780541384e+01,0.000000000000000000e+00,-4.807315230318322530e-01,0.000000000000000000e+00,-1.000000008572684340e+00,0.000000000000000000e+00 +3.723645233988094105e+01,2.486500000000000057e+02,0.000000000000000000e+00,1.088422631846953692e+01,0.000000000000000000e+00,-4.816502465157380120e-01,0.000000000000000000e+00,-1.000000010042363163e+00,0.000000000000000000e+00 +3.723737110063686373e+01,2.486599999999999966e+02,0.000000000000000000e+00,1.088378379712495736e+01,0.000000000000000000e+00,-4.825690072808880848e-01,0.000000000000000000e+00,-1.000000008776626981e+00,0.000000000000000000e+00 +3.723828989874847650e+01,2.486700000000000159e+02,0.000000000000000000e+00,1.088334041363234483e+01,0.000000000000000000e+00,-4.834878054005647963e-01,0.000000000000000000e+00,-1.000000008749079461e+00,0.000000000000000000e+00 +3.723920873429160139e+01,2.486800000000000068e+02,0.000000000000000000e+00,1.088289616785207414e+01,0.000000000000000000e+00,-4.844066409517311378e-01,0.000000000000000000e+00,-1.000000009723926997e+00,0.000000000000000000e+00 +3.724012760734209593e+01,2.486899999999999977e+02,0.000000000000000000e+00,1.088245105964422166e+01,0.000000000000000000e+00,-4.853255140111635280e-01,0.000000000000000000e+00,-1.000000009360543451e+00,0.000000000000000000e+00 +3.724104651797584609e+01,2.487000000000000171e+02,0.000000000000000000e+00,1.088200508886856532e+01,0.000000000000000000e+00,-4.862444246535176928e-01,0.000000000000000000e+00,-1.000000007422958914e+00,0.000000000000000000e+00 +3.724196546626876625e+01,2.487100000000000080e+02,0.000000000000000000e+00,1.088155825538458643e+01,0.000000000000000000e+00,-4.871633729532624524e-01,0.000000000000000000e+00,-1.000000009983965654e+00,0.000000000000000000e+00 +3.724288445229680633e+01,2.487199999999999989e+02,0.000000000000000000e+00,1.088111055905146962e+01,0.000000000000000000e+00,-4.880823589904774162e-01,0.000000000000000000e+00,-1.000000008391860540e+00,0.000000000000000000e+00 +3.724380347613593756e+01,2.487300000000000182e+02,0.000000000000000000e+00,1.088066199972809756e+01,0.000000000000000000e+00,-4.890013828373218074e-01,0.000000000000000000e+00,-1.000000010821260554e+00,0.000000000000000000e+00 +3.724472253786216669e+01,2.487400000000000091e+02,0.000000000000000000e+00,1.088021257727305802e+01,0.000000000000000000e+00,-4.899204445734976487e-01,0.000000000000000000e+00,-1.000000006517990148e+00,0.000000000000000000e+00 +3.724564163755152890e+01,2.487500000000000000e+02,0.000000000000000000e+00,1.087976229154463681e+01,0.000000000000000000e+00,-4.908395442688536225e-01,0.000000000000000000e+00,-1.000000012065356492e+00,0.000000000000000000e+00 +3.724656077528009490e+01,2.487600000000000193e+02,0.000000000000000000e+00,1.087931114240082664e+01,0.000000000000000000e+00,-4.917586820085104171e-01,0.000000000000000000e+00,-1.000000006196166913e+00,0.000000000000000000e+00 +3.724747995112396382e+01,2.487700000000000102e+02,0.000000000000000000e+00,1.087885912969931290e+01,0.000000000000000000e+00,-4.926778578580720547e-01,0.000000000000000000e+00,-1.000000011797605115e+00,0.000000000000000000e+00 +3.724839916515925609e+01,2.487800000000000011e+02,0.000000000000000000e+00,1.087840625329749145e+01,0.000000000000000000e+00,-4.935970719042100385e-01,0.000000000000000000e+00,-1.000000007604434860e+00,0.000000000000000000e+00 +3.724931841746213479e+01,2.487899999999999920e+02,0.000000000000000000e+00,1.087795251305244904e+01,0.000000000000000000e+00,-4.945163242140797055e-01,0.000000000000000000e+00,-1.000000008091195491e+00,0.000000000000000000e+00 +3.725023770810879142e+01,2.488000000000000114e+02,0.000000000000000000e+00,1.087749790882098111e+01,0.000000000000000000e+00,-4.954356148681722805e-01,0.000000000000000000e+00,-1.000000010912093895e+00,0.000000000000000000e+00 +3.725115703717543880e+01,2.488100000000000023e+02,0.000000000000000000e+00,1.087704244045957935e+01,0.000000000000000000e+00,-4.963549439448537437e-01,0.000000000000000000e+00,-1.000000007417587655e+00,0.000000000000000000e+00 +3.725207640473833237e+01,2.488199999999999932e+02,0.000000000000000000e+00,1.087658610782443347e+01,0.000000000000000000e+00,-4.972743115145690784e-01,0.000000000000000000e+00,-1.000000009974089332e+00,0.000000000000000000e+00 +3.725299581087375600e+01,2.488300000000000125e+02,0.000000000000000000e+00,1.087612891077143829e+01,0.000000000000000000e+00,-4.981937176591632044e-01,0.000000000000000000e+00,-1.000000007829979332e+00,0.000000000000000000e+00 +3.725391525565802198e+01,2.488400000000000034e+02,0.000000000000000000e+00,1.087567084915618310e+01,0.000000000000000000e+00,-4.991131624506272013e-01,0.000000000000000000e+00,-1.000000011247156317e+00,0.000000000000000000e+00 +3.725483473916747101e+01,2.488499999999999943e+02,0.000000000000000000e+00,1.087521192283396054e+01,0.000000000000000000e+00,-5.000326459704182991e-01,0.000000000000000000e+00,-1.000000007373351929e+00,0.000000000000000000e+00 +3.725575426147847935e+01,2.488600000000000136e+02,0.000000000000000000e+00,1.087475213165975774e+01,0.000000000000000000e+00,-5.009521682882075444e-01,0.000000000000000000e+00,-1.000000010670053063e+00,0.000000000000000000e+00 +3.725667382266745165e+01,2.488700000000000045e+02,0.000000000000000000e+00,1.087429147548826691e+01,0.000000000000000000e+00,-5.018717294869945444e-01,0.000000000000000000e+00,-1.000000008285782283e+00,0.000000000000000000e+00 +3.725759342281082809e+01,2.488799999999999955e+02,0.000000000000000000e+00,1.087382995417387299e+01,0.000000000000000000e+00,-5.027913296379927788e-01,0.000000000000000000e+00,-1.000000008376736416e+00,0.000000000000000000e+00 +3.725851306198507729e+01,2.488900000000000148e+02,0.000000000000000000e+00,1.087336756757066425e+01,0.000000000000000000e+00,-5.037109688199471469e-01,0.000000000000000000e+00,-1.000000008594287282e+00,0.000000000000000000e+00 +3.725943274026670338e+01,2.489000000000000057e+02,0.000000000000000000e+00,1.087290431553242520e+01,0.000000000000000000e+00,-5.046306471094742507e-01,0.000000000000000000e+00,-1.000000010790597305e+00,0.000000000000000000e+00 +3.726035245773223181e+01,2.489099999999999966e+02,0.000000000000000000e+00,1.087244019791263838e+01,0.000000000000000000e+00,-5.055503645849256378e-01,0.000000000000000000e+00,-1.000000008417102126e+00,0.000000000000000000e+00 +3.726127221445822357e+01,2.489200000000000159e+02,0.000000000000000000e+00,1.087197521456448257e+01,0.000000000000000000e+00,-5.064701213186615369e-01,0.000000000000000000e+00,-1.000000007524916024e+00,0.000000000000000000e+00 +3.726219201052128227e+01,2.489300000000000068e+02,0.000000000000000000e+00,1.087150936534083812e+01,0.000000000000000000e+00,-5.073899173886390335e-01,0.000000000000000000e+00,-1.000000012062449484e+00,0.000000000000000000e+00 +3.726311184599802573e+01,2.489399999999999977e+02,0.000000000000000000e+00,1.087104265009428161e+01,0.000000000000000000e+00,-5.083097528764789486e-01,0.000000000000000000e+00,-1.000000007083500897e+00,0.000000000000000000e+00 +3.726403172096511440e+01,2.489500000000000171e+02,0.000000000000000000e+00,1.087057506867708234e+01,0.000000000000000000e+00,-5.092296278500858531e-01,0.000000000000000000e+00,-1.000000009132487433e+00,0.000000000000000000e+00 +3.726495163549924428e+01,2.489600000000000080e+02,0.000000000000000000e+00,1.087010662094121471e+01,0.000000000000000000e+00,-5.101495423926144523e-01,0.000000000000000000e+00,-1.000000009559895098e+00,0.000000000000000000e+00 +3.726587158967713265e+01,2.489699999999999989e+02,0.000000000000000000e+00,1.086963730673834405e+01,0.000000000000000000e+00,-5.110694965792950129e-01,0.000000000000000000e+00,-1.000000008114827255e+00,0.000000000000000000e+00 +3.726679158357553234e+01,2.489800000000000182e+02,0.000000000000000000e+00,1.086916712591983369e+01,0.000000000000000000e+00,-5.119894904851587381e-01,0.000000000000000000e+00,-1.000000010840606413e+00,0.000000000000000000e+00 +3.726771161727123172e+01,2.489900000000000091e+02,0.000000000000000000e+00,1.086869607833674500e+01,0.000000000000000000e+00,-5.129095241908286917e-01,0.000000000000000000e+00,-1.000000006991065948e+00,0.000000000000000000e+00 +3.726863169084104754e+01,2.490000000000000000e+02,0.000000000000000000e+00,1.086822416383983203e+01,0.000000000000000000e+00,-5.138295977670732650e-01,0.000000000000000000e+00,-1.000000011001473066e+00,0.000000000000000000e+00 +3.726955180436182502e+01,2.490100000000000193e+02,0.000000000000000000e+00,1.086775138227955040e+01,0.000000000000000000e+00,-5.147497112979743106e-01,0.000000000000000000e+00,-1.000000007929896295e+00,0.000000000000000000e+00 +3.727047195791045198e+01,2.490200000000000102e+02,0.000000000000000000e+00,1.086727773350604487e+01,0.000000000000000000e+00,-5.156698648538979857e-01,0.000000000000000000e+00,-1.000000008011848518e+00,0.000000000000000000e+00 +3.727139215156384466e+01,2.490300000000000011e+02,0.000000000000000000e+00,1.086680321736916177e+01,0.000000000000000000e+00,-5.165900585146605550e-01,0.000000000000000000e+00,-1.000000010991558108e+00,0.000000000000000000e+00 +3.727231238539894775e+01,2.490399999999999920e+02,0.000000000000000000e+00,1.086632783371844013e+01,0.000000000000000000e+00,-5.175102923598756677e-01,0.000000000000000000e+00,-1.000000008221830550e+00,0.000000000000000000e+00 +3.727323265949273434e+01,2.490500000000000114e+02,0.000000000000000000e+00,1.086585158240311166e+01,0.000000000000000000e+00,-5.184305664612319786e-01,0.000000000000000000e+00,-1.000000009934747247e+00,0.000000000000000000e+00 +3.727415297392222726e+01,2.490600000000000023e+02,0.000000000000000000e+00,1.086537446327210787e+01,0.000000000000000000e+00,-5.193508808998666959e-01,0.000000000000000000e+00,-1.000000007482906739e+00,0.000000000000000000e+00 +3.727507332876446355e+01,2.490699999999999932e+02,0.000000000000000000e+00,1.086489647617405119e+01,0.000000000000000000e+00,-5.202712357489914785e-01,0.000000000000000000e+00,-1.000000008997659950e+00,0.000000000000000000e+00 +3.727599372409652290e+01,2.490800000000000125e+02,0.000000000000000000e+00,1.086441762095726205e+01,0.000000000000000000e+00,-5.211916310893341953e-01,0.000000000000000000e+00,-1.000000010026090402e+00,0.000000000000000000e+00 +3.727691415999552049e+01,2.490900000000000034e+02,0.000000000000000000e+00,1.086393789746975180e+01,0.000000000000000000e+00,-5.221120669975573003e-01,0.000000000000000000e+00,-1.000000010309131548e+00,0.000000000000000000e+00 +3.727783463653859286e+01,2.490999999999999943e+02,0.000000000000000000e+00,1.086345730555922628e+01,0.000000000000000000e+00,-5.230325435501175235e-01,0.000000000000000000e+00,-1.000000007491509191e+00,0.000000000000000000e+00 +3.727875515380291205e+01,2.491100000000000136e+02,0.000000000000000000e+00,1.086297584507308578e+01,0.000000000000000000e+00,-5.239530608213363028e-01,0.000000000000000000e+00,-1.000000009698591263e+00,0.000000000000000000e+00 +3.727967571186569273e+01,2.491200000000000045e+02,0.000000000000000000e+00,1.086249351585842682e+01,0.000000000000000000e+00,-5.248736188930475111e-01,0.000000000000000000e+00,-1.000000008284366304e+00,0.000000000000000000e+00 +3.728059631080417802e+01,2.491299999999999955e+02,0.000000000000000000e+00,1.086201031776203507e+01,0.000000000000000000e+00,-5.257942178391591392e-01,0.000000000000000000e+00,-1.000000009276050594e+00,0.000000000000000000e+00 +3.728151695069563942e+01,2.491400000000000148e+02,0.000000000000000000e+00,1.086152625063039245e+01,0.000000000000000000e+00,-5.267148577391607134e-01,0.000000000000000000e+00,-1.000000010315165389e+00,0.000000000000000000e+00 +3.728243763161738400e+01,2.491500000000000057e+02,0.000000000000000000e+00,1.086104131430967179e+01,0.000000000000000000e+00,-5.276355386704038031e-01,0.000000000000000000e+00,-1.000000006949068210e+00,0.000000000000000000e+00 +3.728335835364675432e+01,2.491599999999999966e+02,0.000000000000000000e+00,1.086055550864573860e+01,0.000000000000000000e+00,-5.285562607061735640e-01,0.000000000000000000e+00,-1.000000009391782685e+00,0.000000000000000000e+00 +3.728427911686112850e+01,2.491700000000000159e+02,0.000000000000000000e+00,1.086006883348415464e+01,0.000000000000000000e+00,-5.294770239291926028e-01,0.000000000000000000e+00,-1.000000011092804675e+00,0.000000000000000000e+00 +3.728519992133790595e+01,2.491800000000000068e+02,0.000000000000000000e+00,1.085958128867016903e+01,0.000000000000000000e+00,-5.303978284161858792e-01,0.000000000000000000e+00,-1.000000007598877749e+00,0.000000000000000000e+00 +3.728612076715453583e+01,2.491899999999999977e+02,0.000000000000000000e+00,1.085909287404872359e+01,0.000000000000000000e+00,-5.313186742398109397e-01,0.000000000000000000e+00,-1.000000009119754063e+00,0.000000000000000000e+00 +3.728704165438848861e+01,2.492000000000000171e+02,0.000000000000000000e+00,1.085860358946445636e+01,0.000000000000000000e+00,-5.322395614821602283e-01,0.000000000000000000e+00,-1.000000009105200149e+00,0.000000000000000000e+00 +3.728796258311727030e+01,2.492100000000000080e+02,0.000000000000000000e+00,1.085811343476169277e+01,0.000000000000000000e+00,-5.331604902193280981e-01,0.000000000000000000e+00,-1.000000009384379496e+00,0.000000000000000000e+00 +3.728888355341842953e+01,2.492199999999999989e+02,0.000000000000000000e+00,1.085762240978445092e+01,0.000000000000000000e+00,-5.340814605291269723e-01,0.000000000000000000e+00,-1.000000007596185458e+00,0.000000000000000000e+00 +3.728980456536953625e+01,2.492300000000000182e+02,0.000000000000000000e+00,1.085713051437643983e+01,0.000000000000000000e+00,-5.350024724872284310e-01,0.000000000000000000e+00,-1.000000009755951602e+00,0.000000000000000000e+00 +3.729072561904820304e+01,2.492400000000000091e+02,0.000000000000000000e+00,1.085663774838106121e+01,0.000000000000000000e+00,-5.359235261748780399e-01,0.000000000000000000e+00,-1.000000011407269795e+00,0.000000000000000000e+00 +3.729164671453207092e+01,2.492500000000000000e+02,0.000000000000000000e+00,1.085614411164140414e+01,0.000000000000000000e+00,-5.368446216692509543e-01,0.000000000000000000e+00,-1.000000006001744879e+00,0.000000000000000000e+00 +3.729256785189881640e+01,2.492600000000000193e+02,0.000000000000000000e+00,1.085564960400024859e+01,0.000000000000000000e+00,-5.377657590415242383e-01,0.000000000000000000e+00,-1.000000010019014951e+00,0.000000000000000000e+00 +3.729348903122615155e+01,2.492700000000000102e+02,0.000000000000000000e+00,1.085515422530007079e+01,0.000000000000000000e+00,-5.386869383780887865e-01,0.000000000000000000e+00,-1.000000010627728919e+00,0.000000000000000000e+00 +3.729441025259182396e+01,2.492800000000000011e+02,0.000000000000000000e+00,1.085465797538302901e+01,0.000000000000000000e+00,-5.396081597535502539e-01,0.000000000000000000e+00,-1.000000007559409765e+00,0.000000000000000000e+00 +3.729533151607360963e+01,2.492899999999999920e+02,0.000000000000000000e+00,1.085416085409097420e+01,0.000000000000000000e+00,-5.405294232423006884e-01,0.000000000000000000e+00,-1.000000008914772476e+00,0.000000000000000000e+00 +3.729625282174932721e+01,2.493000000000000114e+02,0.000000000000000000e+00,1.085366286126544999e+01,0.000000000000000000e+00,-5.414507289262291412e-01,0.000000000000000000e+00,-1.000000008144162011e+00,0.000000000000000000e+00 +3.729717416969681665e+01,2.493100000000000023e+02,0.000000000000000000e+00,1.085316399674768562e+01,0.000000000000000000e+00,-5.423720768812250181e-01,0.000000000000000000e+00,-1.000000011253109111e+00,0.000000000000000000e+00 +3.729809555999396764e+01,2.493199999999999932e+02,0.000000000000000000e+00,1.085266426037860121e+01,0.000000000000000000e+00,-5.432934671887452716e-01,0.000000000000000000e+00,-1.000000007507177768e+00,0.000000000000000000e+00 +3.729901699271869830e+01,2.493300000000000125e+02,0.000000000000000000e+00,1.085216365199880251e+01,0.000000000000000000e+00,-5.442148999203907378e-01,0.000000000000000000e+00,-1.000000009187330674e+00,0.000000000000000000e+00 +3.729993846794895518e+01,2.493400000000000034e+02,0.000000000000000000e+00,1.085166217144858969e+01,0.000000000000000000e+00,-5.451363751591125073e-01,0.000000000000000000e+00,-1.000000009742612939e+00,0.000000000000000000e+00 +3.730085998576272743e+01,2.493499999999999943e+02,0.000000000000000000e+00,1.085115981856794676e+01,0.000000000000000000e+00,-5.460578929818601379e-01,0.000000000000000000e+00,-1.000000008899313730e+00,0.000000000000000000e+00 +3.730178154623803266e+01,2.493600000000000136e+02,0.000000000000000000e+00,1.085065659319654685e+01,0.000000000000000000e+00,-5.469794534653654727e-01,0.000000000000000000e+00,-1.000000008474751567e+00,0.000000000000000000e+00 +3.730270314945292398e+01,2.493700000000000045e+02,0.000000000000000000e+00,1.085015249517375224e+01,0.000000000000000000e+00,-5.479010566880697652e-01,0.000000000000000000e+00,-1.000000010283780938e+00,0.000000000000000000e+00 +3.730362479548549715e+01,2.493799999999999955e+02,0.000000000000000000e+00,1.084964752433861257e+01,0.000000000000000000e+00,-5.488227027301217920e-01,0.000000000000000000e+00,-1.000000007777267053e+00,0.000000000000000000e+00 +3.730454648441387633e+01,2.493900000000000148e+02,0.000000000000000000e+00,1.084914168052986305e+01,0.000000000000000000e+00,-5.497443916656692409e-01,0.000000000000000000e+00,-1.000000009042813387e+00,0.000000000000000000e+00 +3.730546821631622123e+01,2.494000000000000057e+02,0.000000000000000000e+00,1.084863496358592982e+01,0.000000000000000000e+00,-5.506661235763488094e-01,0.000000000000000000e+00,-1.000000009620623853e+00,0.000000000000000000e+00 +3.730638999127072708e+01,2.494099999999999966e+02,0.000000000000000000e+00,1.084812737334492283e+01,0.000000000000000000e+00,-5.515878985397217882e-01,0.000000000000000000e+00,-1.000000009233154685e+00,0.000000000000000000e+00 +3.730731180935562463e+01,2.494200000000000159e+02,0.000000000000000000e+00,1.084761890964463937e+01,0.000000000000000000e+00,-5.525097166331286447e-01,0.000000000000000000e+00,-1.000000009692705527e+00,0.000000000000000000e+00 +3.730823367064917306e+01,2.494300000000000068e+02,0.000000000000000000e+00,1.084710957232256412e+01,0.000000000000000000e+00,-5.534315779356155929e-01,0.000000000000000000e+00,-1.000000006539553343e+00,0.000000000000000000e+00 +3.730915557522968129e+01,2.494399999999999977e+02,0.000000000000000000e+00,1.084659936121586732e+01,0.000000000000000000e+00,-5.543534825221527740e-01,0.000000000000000000e+00,-1.000000012034046204e+00,0.000000000000000000e+00 +3.731007752317547954e+01,2.494500000000000171e+02,0.000000000000000000e+00,1.084608827616140836e+01,0.000000000000000000e+00,-5.552754304790485929e-01,0.000000000000000000e+00,-1.000000007086788933e+00,0.000000000000000000e+00 +3.731099951456494779e+01,2.494600000000000080e+02,0.000000000000000000e+00,1.084557631699572511e+01,0.000000000000000000e+00,-5.561974218750477261e-01,0.000000000000000000e+00,-1.000000010224764146e+00,0.000000000000000000e+00 +3.731192154947648731e+01,2.494699999999999989e+02,0.000000000000000000e+00,1.084506348355504990e+01,0.000000000000000000e+00,-5.571194567960114918e-01,0.000000000000000000e+00,-1.000000008628548320e+00,0.000000000000000000e+00 +3.731284362798853493e+01,2.494800000000000182e+02,0.000000000000000000e+00,1.084454977567529355e+01,0.000000000000000000e+00,-5.580415353160173009e-01,0.000000000000000000e+00,-1.000000008284687825e+00,0.000000000000000000e+00 +3.731376575017957720e+01,2.494900000000000091e+02,0.000000000000000000e+00,1.084403519319205600e+01,0.000000000000000000e+00,-5.589636575146978981e-01,0.000000000000000000e+00,-1.000000008910014282e+00,0.000000000000000000e+00 +3.731468791612812197e+01,2.495000000000000000e+02,0.000000000000000000e+00,1.084351973594062102e+01,0.000000000000000000e+00,-5.598858234714607640e-01,0.000000000000000000e+00,-1.000000010220729596e+00,0.000000000000000000e+00 +3.731561012591271975e+01,2.495100000000000193e+02,0.000000000000000000e+00,1.084300340375595617e+01,0.000000000000000000e+00,-5.608080332654875599e-01,0.000000000000000000e+00,-1.000000007756011389e+00,0.000000000000000000e+00 +3.731653237961196368e+01,2.495200000000000102e+02,0.000000000000000000e+00,1.084248619647271283e+01,0.000000000000000000e+00,-5.617302869718818759e-01,0.000000000000000000e+00,-1.000000011673278122e+00,0.000000000000000000e+00 +3.731745467730446819e+01,2.495300000000000011e+02,0.000000000000000000e+00,1.084196811392522974e+01,0.000000000000000000e+00,-5.626525846751508908e-01,0.000000000000000000e+00,-1.000000007069416830e+00,0.000000000000000000e+00 +3.731837701906889038e+01,2.495399999999999920e+02,0.000000000000000000e+00,1.084144915594752412e+01,0.000000000000000000e+00,-5.635749264460928609e-01,0.000000000000000000e+00,-1.000000008275989449e+00,0.000000000000000000e+00 +3.731929940498392284e+01,2.495500000000000114e+02,0.000000000000000000e+00,1.084092932237330409e+01,0.000000000000000000e+00,-5.644973123687602179e-01,0.000000000000000000e+00,-1.000000010829560138e+00,0.000000000000000000e+00 +3.732022183512830082e+01,2.495600000000000023e+02,0.000000000000000000e+00,1.084040861303595626e+01,0.000000000000000000e+00,-5.654197425231251017e-01,0.000000000000000000e+00,-1.000000008180068622e+00,0.000000000000000000e+00 +3.732114430958078088e+01,2.495699999999999932e+02,0.000000000000000000e+00,1.083988702776854929e+01,0.000000000000000000e+00,-5.663422169831537900e-01,0.000000000000000000e+00,-1.000000008390674600e+00,0.000000000000000000e+00 +3.732206682842017642e+01,2.495800000000000125e+02,0.000000000000000000e+00,1.083936456640383916e+01,0.000000000000000000e+00,-5.672647358302865817e-01,0.000000000000000000e+00,-1.000000009085239006e+00,0.000000000000000000e+00 +3.732298939172531504e+01,2.495900000000000034e+02,0.000000000000000000e+00,1.083884122877426215e+01,0.000000000000000000e+00,-5.681872991438083886e-01,0.000000000000000000e+00,-1.000000009974251869e+00,0.000000000000000000e+00 +3.732391199957508121e+01,2.495999999999999943e+02,0.000000000000000000e+00,1.083831701471193654e+01,0.000000000000000000e+00,-5.691099070027735296e-01,0.000000000000000000e+00,-1.000000008682025099e+00,0.000000000000000000e+00 +3.732483465204838069e+01,2.496100000000000136e+02,0.000000000000000000e+00,1.083779192404866265e+01,0.000000000000000000e+00,-5.700325594840809362e-01,0.000000000000000000e+00,-1.000000009091644104e+00,0.000000000000000000e+00 +3.732575734922416189e+01,2.496200000000000045e+02,0.000000000000000000e+00,1.083726595661592462e+01,0.000000000000000000e+00,-5.709552566682487562e-01,0.000000000000000000e+00,-1.000000008825584485e+00,0.000000000000000000e+00 +3.732668009118140873e+01,2.496299999999999955e+02,0.000000000000000000e+00,1.083673911224488684e+01,0.000000000000000000e+00,-5.718779986336381960e-01,0.000000000000000000e+00,-1.000000009678760238e+00,0.000000000000000000e+00 +3.732760287799914067e+01,2.496400000000000148e+02,0.000000000000000000e+00,1.083621139076639572e+01,0.000000000000000000e+00,-5.728007854603034410e-01,0.000000000000000000e+00,-1.000000009272957291e+00,0.000000000000000000e+00 +3.732852570975641981e+01,2.496500000000000057e+02,0.000000000000000000e+00,1.083568279201097795e+01,0.000000000000000000e+00,-5.737236172261409584e-01,0.000000000000000000e+00,-1.000000009401633028e+00,0.000000000000000000e+00 +3.732944858653234377e+01,2.496599999999999966e+02,0.000000000000000000e+00,1.083515331580884222e+01,0.000000000000000000e+00,-5.746464940107390840e-01,0.000000000000000000e+00,-1.000000007685644787e+00,0.000000000000000000e+00 +3.733037150840603857e+01,2.496700000000000159e+02,0.000000000000000000e+00,1.083462296198987751e+01,0.000000000000000000e+00,-5.755694158915274361e-01,0.000000000000000000e+00,-1.000000008002435825e+00,0.000000000000000000e+00 +3.733129447545667290e+01,2.496800000000000068e+02,0.000000000000000000e+00,1.083409173038365481e+01,0.000000000000000000e+00,-5.764923829495511853e-01,0.000000000000000000e+00,-1.000000012141705863e+00,0.000000000000000000e+00 +3.733221748776345805e+01,2.496899999999999977e+02,0.000000000000000000e+00,1.083355962081942359e+01,0.000000000000000000e+00,-5.774153952675448176e-01,0.000000000000000000e+00,-1.000000007298228244e+00,0.000000000000000000e+00 +3.733314054540563376e+01,2.497000000000000171e+02,0.000000000000000000e+00,1.083302663312611003e+01,0.000000000000000000e+00,-5.783384529164605770e-01,0.000000000000000000e+00,-1.000000007771263633e+00,0.000000000000000000e+00 +3.733406364846248948e+01,2.497100000000000080e+02,0.000000000000000000e+00,1.083249276713232767e+01,0.000000000000000000e+00,-5.792615559804864533e-01,0.000000000000000000e+00,-1.000000011178489689e+00,0.000000000000000000e+00 +3.733498679701333600e+01,2.497199999999999989e+02,0.000000000000000000e+00,1.083195802266636498e+01,0.000000000000000000e+00,-5.801847045416492765e-01,0.000000000000000000e+00,-1.000000008884867730e+00,0.000000000000000000e+00 +3.733590999113752673e+01,2.497300000000000182e+02,0.000000000000000000e+00,1.083142239955618713e+01,0.000000000000000000e+00,-5.811078986740418895e-01,0.000000000000000000e+00,-1.000000006846791356e+00,0.000000000000000000e+00 +3.733683323091445772e+01,2.497400000000000091e+02,0.000000000000000000e+00,1.083088589762944309e+01,0.000000000000000000e+00,-5.820311384572930402e-01,0.000000000000000000e+00,-1.000000011017109669e+00,0.000000000000000000e+00 +3.733775651642356053e+01,2.497500000000000000e+02,0.000000000000000000e+00,1.083034851671346033e+01,0.000000000000000000e+00,-5.829544239765652724e-01,0.000000000000000000e+00,-1.000000008593175282e+00,0.000000000000000000e+00 +3.733867984774430226e+01,2.497600000000000193e+02,0.000000000000000000e+00,1.082981025663523944e+01,0.000000000000000000e+00,-5.838777553052385549e-01,0.000000000000000000e+00,-1.000000009694965497e+00,0.000000000000000000e+00 +3.733960322495618556e+01,2.497700000000000102e+02,0.000000000000000000e+00,1.082927111722146485e+01,0.000000000000000000e+00,-5.848011325260742410e-01,0.000000000000000000e+00,-1.000000007770964983e+00,0.000000000000000000e+00 +3.734052664813875566e+01,2.497800000000000011e+02,0.000000000000000000e+00,1.082873109829849589e+01,0.000000000000000000e+00,-5.857245557158221594e-01,0.000000000000000000e+00,-1.000000008770712157e+00,0.000000000000000000e+00 +3.734145011737160047e+01,2.497899999999999920e+02,0.000000000000000000e+00,1.082819019969237218e+01,0.000000000000000000e+00,-5.866480249567638250e-01,0.000000000000000000e+00,-1.000000010308788934e+00,0.000000000000000000e+00 +3.734237363273432919e+01,2.498000000000000114e+02,0.000000000000000000e+00,1.082764842122880822e+01,0.000000000000000000e+00,-5.875715403290161509e-01,0.000000000000000000e+00,-1.000000007917753342e+00,0.000000000000000000e+00 +3.734329719430660788e+01,2.498100000000000023e+02,0.000000000000000000e+00,1.082710576273319525e+01,0.000000000000000000e+00,-5.884951019086082091e-01,0.000000000000000000e+00,-1.000000011707877778e+00,0.000000000000000000e+00 +3.734422080216813100e+01,2.498199999999999932e+02,0.000000000000000000e+00,1.082656222403060475e+01,0.000000000000000000e+00,-5.894187097809445719e-01,0.000000000000000000e+00,-1.000000006798915653e+00,0.000000000000000000e+00 +3.734514445639862856e+01,2.498300000000000125e+02,0.000000000000000000e+00,1.082601780494577959e+01,0.000000000000000000e+00,-5.903423640177246634e-01,0.000000000000000000e+00,-1.000000009545181756e+00,0.000000000000000000e+00 +3.734606815707788030e+01,2.498400000000000034e+02,0.000000000000000000e+00,1.082547250530314642e+01,0.000000000000000000e+00,-5.912660647057914609e-01,0.000000000000000000e+00,-1.000000007148810877e+00,0.000000000000000000e+00 +3.734699190428568727e+01,2.498499999999999943e+02,0.000000000000000000e+00,1.082492632492680151e+01,0.000000000000000000e+00,-5.921898119202053667e-01,0.000000000000000000e+00,-1.000000011795459276e+00,0.000000000000000000e+00 +3.734791569810190737e+01,2.498600000000000136e+02,0.000000000000000000e+00,1.082437926364052139e+01,0.000000000000000000e+00,-5.931136057473215262e-01,0.000000000000000000e+00,-1.000000006526222895e+00,0.000000000000000000e+00 +3.734883953860642691e+01,2.498700000000000045e+02,0.000000000000000000e+00,1.082383132126775216e+01,0.000000000000000000e+00,-5.940374462578672521e-01,0.000000000000000000e+00,-1.000000011848966031e+00,0.000000000000000000e+00 +3.734976342587916776e+01,2.498799999999999955e+02,0.000000000000000000e+00,1.082328249763162376e+01,0.000000000000000000e+00,-5.949613335415540050e-01,0.000000000000000000e+00,-1.000000006644082173e+00,0.000000000000000000e+00 +3.735068736000009437e+01,2.498900000000000148e+02,0.000000000000000000e+00,1.082273279255493215e+01,0.000000000000000000e+00,-5.958852676686202665e-01,0.000000000000000000e+00,-1.000000009333050111e+00,0.000000000000000000e+00 +3.735161134104921388e+01,2.499000000000000057e+02,0.000000000000000000e+00,1.082218220586015711e+01,0.000000000000000000e+00,-5.968092487263628731e-01,0.000000000000000000e+00,-1.000000011282750956e+00,0.000000000000000000e+00 +3.735253536910656891e+01,2.499099999999999966e+02,0.000000000000000000e+00,1.082163073736944625e+01,0.000000000000000000e+00,-5.977332767941413438e-01,0.000000000000000000e+00,-1.000000005943835424e+00,0.000000000000000000e+00 +3.735345944425223763e+01,2.499200000000000159e+02,0.000000000000000000e+00,1.082107838690462209e+01,0.000000000000000000e+00,-5.986573519453018966e-01,0.000000000000000000e+00,-1.000000011728941596e+00,0.000000000000000000e+00 +3.735438356656634085e+01,2.499300000000000068e+02,0.000000000000000000e+00,1.082052515428718742e+01,0.000000000000000000e+00,-5.995814742702442190e-01,0.000000000000000000e+00,-1.000000007525728485e+00,0.000000000000000000e+00 +3.735530773612904198e+01,2.499399999999999977e+02,0.000000000000000000e+00,1.081997103933830928e+01,0.000000000000000000e+00,-6.005056438398972407e-01,0.000000000000000000e+00,-1.000000009663177591e+00,0.000000000000000000e+00 +3.735623195302053290e+01,2.499500000000000171e+02,0.000000000000000000e+00,1.081941604187883677e+01,0.000000000000000000e+00,-6.014298607403191221e-01,0.000000000000000000e+00,-1.000000007430670523e+00,0.000000000000000000e+00 +3.735715621732105518e+01,2.499600000000000080e+02,0.000000000000000000e+00,1.081886016172928677e+01,0.000000000000000000e+00,-6.023541250477086884e-01,0.000000000000000000e+00,-1.000000010912666326e+00,0.000000000000000000e+00 +3.735808052911088595e+01,2.499699999999999989e+02,0.000000000000000000e+00,1.081830339870985291e+01,0.000000000000000000e+00,-6.032784368476246106e-01,0.000000000000000000e+00,-1.000000007320754447e+00,0.000000000000000000e+00 +3.735900488847033785e+01,2.499800000000000182e+02,0.000000000000000000e+00,1.081774575264039662e+01,0.000000000000000000e+00,-6.042027962138446506e-01,0.000000000000000000e+00,-1.000000010894703584e+00,0.000000000000000000e+00 +3.735992929547977326e+01,2.499900000000000091e+02,0.000000000000000000e+00,1.081718722334045779e+01,0.000000000000000000e+00,-6.051272032333483430e-01,0.000000000000000000e+00,-1.000000006767942651e+00,0.000000000000000000e+00 +3.736085375021958299e+01,2.500000000000000000e+02,0.000000000000000000e+00,1.081662781062924239e+01,0.000000000000000000e+00,-6.060516579794122949e-01,0.000000000000000000e+00,-1.000000011254312371e+00,0.000000000000000000e+00 +3.736177825277020048e+01,2.500100000000000193e+02,0.000000000000000000e+00,1.081606751432563485e+01,0.000000000000000000e+00,-6.069761605404337956e-01,0.000000000000000000e+00,-1.000000007410594138e+00,0.000000000000000000e+00 +3.736270280321210180e+01,2.500200000000000102e+02,0.000000000000000000e+00,1.081550633424818386e+01,0.000000000000000000e+00,-6.079007109891861882e-01,0.000000000000000000e+00,-1.000000009468787754e+00,0.000000000000000000e+00 +3.736362740162579854e+01,2.500300000000000011e+02,0.000000000000000000e+00,1.081494427021511662e+01,0.000000000000000000e+00,-6.088253094116402586e-01,0.000000000000000000e+00,-1.000000010875897960e+00,0.000000000000000000e+00 +3.736455204809185204e+01,2.500399999999999920e+02,0.000000000000000000e+00,1.081438132204432634e+01,0.000000000000000000e+00,-6.097499558877482739e-01,0.000000000000000000e+00,-1.000000007160429361e+00,0.000000000000000000e+00 +3.736547674269085206e+01,2.500500000000000114e+02,0.000000000000000000e+00,1.081381748955337763e+01,0.000000000000000000e+00,-6.106746504933675546e-01,0.000000000000000000e+00,-1.000000008391896511e+00,0.000000000000000000e+00 +3.736640148550343099e+01,2.500600000000000023e+02,0.000000000000000000e+00,1.081325277255951001e+01,0.000000000000000000e+00,-6.115993933137063854e-01,0.000000000000000000e+00,-1.000000010094863390e+00,0.000000000000000000e+00 +3.736732627661026385e+01,2.500699999999999932e+02,0.000000000000000000e+00,1.081268717087962905e+01,0.000000000000000000e+00,-6.125241844298749960e-01,0.000000000000000000e+00,-1.000000009873318829e+00,0.000000000000000000e+00 +3.736825111609206829e+01,2.500800000000000125e+02,0.000000000000000000e+00,1.081212068433030993e+01,0.000000000000000000e+00,-6.134490239208079121e-01,0.000000000000000000e+00,-1.000000007407256808e+00,0.000000000000000000e+00 +3.736917600402959039e+01,2.500900000000000034e+02,0.000000000000000000e+00,1.081155331272779918e+01,0.000000000000000000e+00,-6.143739118651836417e-01,0.000000000000000000e+00,-1.000000008605971713e+00,0.000000000000000000e+00 +3.737010094050363307e+01,2.500999999999999943e+02,0.000000000000000000e+00,1.081098505588801473e+01,0.000000000000000000e+00,-6.152988483471864001e-01,0.000000000000000000e+00,-1.000000011069829053e+00,0.000000000000000000e+00 +3.737102592559502767e+01,2.501100000000000136e+02,0.000000000000000000e+00,1.081041591362654053e+01,0.000000000000000000e+00,-6.162238334488217006e-01,0.000000000000000000e+00,-1.000000008248487893e+00,0.000000000000000000e+00 +3.737195095938465528e+01,2.501200000000000045e+02,0.000000000000000000e+00,1.080984588575862837e+01,0.000000000000000000e+00,-6.171488672460764269e-01,0.000000000000000000e+00,-1.000000008123764550e+00,0.000000000000000000e+00 +3.737287604195342539e+01,2.501299999999999955e+02,0.000000000000000000e+00,1.080927497209920318e+01,0.000000000000000000e+00,-6.180739498223610795e-01,0.000000000000000000e+00,-1.000000008295454546e+00,0.000000000000000000e+00 +3.737380117338229724e+01,2.501400000000000148e+02,0.000000000000000000e+00,1.080870317246285595e+01,0.000000000000000000e+00,-6.189990812589066804e-01,0.000000000000000000e+00,-1.000000010514238591e+00,0.000000000000000000e+00 +3.737472635375226560e+01,2.501500000000000057e+02,0.000000000000000000e+00,1.080813048666384546e+01,0.000000000000000000e+00,-6.199242616386047011e-01,0.000000000000000000e+00,-1.000000008229369408e+00,0.000000000000000000e+00 +3.737565158314437497e+01,2.501599999999999966e+02,0.000000000000000000e+00,1.080755691451609657e+01,0.000000000000000000e+00,-6.208494910383267618e-01,0.000000000000000000e+00,-1.000000009416307734e+00,0.000000000000000000e+00 +3.737657686163969828e+01,2.501700000000000159e+02,0.000000000000000000e+00,1.080698245583320549e+01,0.000000000000000000e+00,-6.217747695423642140e-01,0.000000000000000000e+00,-1.000000009597643791e+00,0.000000000000000000e+00 +3.737750218931935819e+01,2.501800000000000068e+02,0.000000000000000000e+00,1.080640711042843272e+01,0.000000000000000000e+00,-6.227000972309068016e-01,0.000000000000000000e+00,-1.000000008447254229e+00,0.000000000000000000e+00 +3.737842756626452001e+01,2.501899999999999977e+02,0.000000000000000000e+00,1.080583087811470655e+01,0.000000000000000000e+00,-6.236254741838833660e-01,0.000000000000000000e+00,-1.000000009786081501e+00,0.000000000000000000e+00 +3.737935299255637744e+01,2.502000000000000171e+02,0.000000000000000000e+00,1.080525375870462312e+01,0.000000000000000000e+00,-6.245509004847996648e-01,0.000000000000000000e+00,-1.000000007063174268e+00,0.000000000000000000e+00 +3.738027846827618106e+01,2.502100000000000080e+02,0.000000000000000000e+00,1.080467575201044284e+01,0.000000000000000000e+00,-6.254763762111402725e-01,0.000000000000000000e+00,-1.000000010319048949e+00,0.000000000000000000e+00 +3.738120399350521694e+01,2.502199999999999989e+02,0.000000000000000000e+00,1.080409685784409568e+01,0.000000000000000000e+00,-6.264019014497231863e-01,0.000000000000000000e+00,-1.000000008854982747e+00,0.000000000000000000e+00 +3.738212956832480671e+01,2.502300000000000182e+02,0.000000000000000000e+00,1.080351707601717237e+01,0.000000000000000000e+00,-6.273274762775061797e-01,0.000000000000000000e+00,-1.000000010634852110e+00,0.000000000000000000e+00 +3.738305519281631462e+01,2.502400000000000091e+02,0.000000000000000000e+00,1.080293640634093322e+01,0.000000000000000000e+00,-6.282531007788593191e-01,0.000000000000000000e+00,-1.000000007034451466e+00,0.000000000000000000e+00 +3.738398086706115464e+01,2.502500000000000000e+02,0.000000000000000000e+00,1.080235484862630102e+01,0.000000000000000000e+00,-6.291787750302114679e-01,0.000000000000000000e+00,-1.000000008088289150e+00,0.000000000000000000e+00 +3.738490659114077630e+01,2.502600000000000193e+02,0.000000000000000000e+00,1.080177240268386818e+01,0.000000000000000000e+00,-6.301044991173214704e-01,0.000000000000000000e+00,-1.000000011389172494e+00,0.000000000000000000e+00 +3.738583236513667174e+01,2.502700000000000102e+02,0.000000000000000000e+00,1.080118906832388781e+01,0.000000000000000000e+00,-6.310302731237620311e-01,0.000000000000000000e+00,-1.000000008313945754e+00,0.000000000000000000e+00 +3.738675818913037574e+01,2.502800000000000011e+02,0.000000000000000000e+00,1.080060484535627552e+01,0.000000000000000000e+00,-6.319560971251644288e-01,0.000000000000000000e+00,-1.000000006819737219e+00,0.000000000000000000e+00 +3.738768406320346571e+01,2.502899999999999920e+02,0.000000000000000000e+00,1.080001973359061651e+01,0.000000000000000000e+00,-6.328819712045681278e-01,0.000000000000000000e+00,-1.000000010715216048e+00,0.000000000000000000e+00 +3.738860998743755459e+01,2.503000000000000114e+02,0.000000000000000000e+00,1.079943373283615848e+01,0.000000000000000000e+00,-6.338078954485812933e-01,0.000000000000000000e+00,-1.000000009304817583e+00,0.000000000000000000e+00 +3.738953596191430506e+01,2.503100000000000023e+02,0.000000000000000000e+00,1.079884684290180807e+01,0.000000000000000000e+00,-6.347338699339510892e-01,0.000000000000000000e+00,-1.000000008468982404e+00,0.000000000000000000e+00 +3.739046198671542243e+01,2.503199999999999932e+02,0.000000000000000000e+00,1.079825906359613974e+01,0.000000000000000000e+00,-6.356598947429114022e-01,0.000000000000000000e+00,-1.000000009942249246e+00,0.000000000000000000e+00 +3.739138806192264752e+01,2.503300000000000125e+02,0.000000000000000000e+00,1.079767039472739043e+01,0.000000000000000000e+00,-6.365859699593446885e-01,0.000000000000000000e+00,-1.000000007173545313e+00,0.000000000000000000e+00 +3.739231418761777093e+01,2.503400000000000034e+02,0.000000000000000000e+00,1.079708083610345781e+01,0.000000000000000000e+00,-6.375120956611088907e-01,0.000000000000000000e+00,-1.000000010180364551e+00,0.000000000000000000e+00 +3.739324036388261163e+01,2.503499999999999943e+02,0.000000000000000000e+00,1.079649038753190560e+01,0.000000000000000000e+00,-6.384382719353816071e-01,0.000000000000000000e+00,-1.000000010339735068e+00,0.000000000000000000e+00 +3.739416659079905259e+01,2.503600000000000136e+02,0.000000000000000000e+00,1.079589904881995466e+01,0.000000000000000000e+00,-6.393644988613969016e-01,0.000000000000000000e+00,-1.000000007313427641e+00,0.000000000000000000e+00 +3.739509286844899805e+01,2.503700000000000045e+02,0.000000000000000000e+00,1.079530681977449014e+01,0.000000000000000000e+00,-6.402907765181176103e-01,0.000000000000000000e+00,-1.000000009043053639e+00,0.000000000000000000e+00 +3.739601919691440912e+01,2.503799999999999955e+02,0.000000000000000000e+00,1.079471370020206145e+01,0.000000000000000000e+00,-6.412171049919052068e-01,0.000000000000000000e+00,-1.000000008976687171e+00,0.000000000000000000e+00 +3.739694557627728244e+01,2.503900000000000148e+02,0.000000000000000000e+00,1.079411968990887516e+01,0.000000000000000000e+00,-6.421434843630949851e-01,0.000000000000000000e+00,-1.000000008842935495e+00,0.000000000000000000e+00 +3.739787200661966438e+01,2.504000000000000057e+02,0.000000000000000000e+00,1.079352478870080034e+01,0.000000000000000000e+00,-6.430699147136661464e-01,0.000000000000000000e+00,-1.000000008300075072e+00,0.000000000000000000e+00 +3.739879848802362972e+01,2.504099999999999966e+02,0.000000000000000000e+00,1.079292899638336678e+01,0.000000000000000000e+00,-6.439963961253241109e-01,0.000000000000000000e+00,-1.000000011143586276e+00,0.000000000000000000e+00 +3.739972502057131720e+01,2.504200000000000159e+02,0.000000000000000000e+00,1.079233231276176497e+01,0.000000000000000000e+00,-6.449229286833337849e-01,0.000000000000000000e+00,-1.000000006684065745e+00,0.000000000000000000e+00 +3.740065160434488689e+01,2.504300000000000068e+02,0.000000000000000000e+00,1.079173473764084257e+01,0.000000000000000000e+00,-6.458495124630989626e-01,0.000000000000000000e+00,-1.000000011130095512e+00,0.000000000000000000e+00 +3.740157823942655568e+01,2.504399999999999977e+02,0.000000000000000000e+00,1.079113627082511329e+01,0.000000000000000000e+00,-6.467761475550848349e-01,0.000000000000000000e+00,-1.000000007585226447e+00,0.000000000000000000e+00 +3.740250492589858311e+01,2.504500000000000171e+02,0.000000000000000000e+00,1.079053691211874266e+01,0.000000000000000000e+00,-6.477028340341434154e-01,0.000000000000000000e+00,-1.000000008116644246e+00,0.000000000000000000e+00 +3.740343166384327134e+01,2.504600000000000080e+02,0.000000000000000000e+00,1.078993666132556228e+01,0.000000000000000000e+00,-6.486295719863518494e-01,0.000000000000000000e+00,-1.000000010308623510e+00,0.000000000000000000e+00 +3.740435845334295806e+01,2.504699999999999989e+02,0.000000000000000000e+00,1.078933551824905912e+01,0.000000000000000000e+00,-6.495563614955923715e-01,0.000000000000000000e+00,-1.000000009677784352e+00,0.000000000000000000e+00 +3.740528529448003070e+01,2.504800000000000182e+02,0.000000000000000000e+00,1.078873348269237731e+01,0.000000000000000000e+00,-6.504832026416355051e-01,0.000000000000000000e+00,-1.000000007945011538e+00,0.000000000000000000e+00 +3.740621218733691933e+01,2.504900000000000091e+02,0.000000000000000000e+00,1.078813055445832170e+01,0.000000000000000000e+00,-6.514100955058899078e-01,0.000000000000000000e+00,-1.000000008897267145e+00,0.000000000000000000e+00 +3.740713913199609664e+01,2.505000000000000000e+02,0.000000000000000000e+00,1.078752673334935608e+01,0.000000000000000000e+00,-6.523370401733179502e-01,0.000000000000000000e+00,-1.000000008050281997e+00,0.000000000000000000e+00 +3.740806612854008506e+01,2.505100000000000193e+02,0.000000000000000000e+00,1.078692201916759963e+01,0.000000000000000000e+00,-6.532640367247691815e-01,0.000000000000000000e+00,-1.000000011255293364e+00,0.000000000000000000e+00 +3.740899317705144256e+01,2.505200000000000102e+02,0.000000000000000000e+00,1.078631641171483047e+01,0.000000000000000000e+00,-6.541910852465609993e-01,0.000000000000000000e+00,-1.000000007827354986e+00,0.000000000000000000e+00 +3.740992027761277683e+01,2.505300000000000011e+02,0.000000000000000000e+00,1.078570991079248031e+01,0.000000000000000000e+00,-6.551181858151492454e-01,0.000000000000000000e+00,-1.000000007749736186e+00,0.000000000000000000e+00 +3.741084743030673110e+01,2.505399999999999920e+02,0.000000000000000000e+00,1.078510251620164340e+01,0.000000000000000000e+00,-6.560453385162886564e-01,0.000000000000000000e+00,-1.000000010669323869e+00,0.000000000000000000e+00 +3.741177463521599833e+01,2.505500000000000114e+02,0.000000000000000000e+00,1.078449422774306754e+01,0.000000000000000000e+00,-6.569725434354510840e-01,0.000000000000000000e+00,-1.000000007968374183e+00,0.000000000000000000e+00 +3.741270189242332123e+01,2.505600000000000023e+02,0.000000000000000000e+00,1.078388504521715419e+01,0.000000000000000000e+00,-6.578998006501620699e-01,0.000000000000000000e+00,-1.000000009624556263e+00,0.000000000000000000e+00 +3.741362920201147801e+01,2.505699999999999932e+02,0.000000000000000000e+00,1.078327496842396549e+01,0.000000000000000000e+00,-6.588271102472428309e-01,0.000000000000000000e+00,-1.000000009085470376e+00,0.000000000000000000e+00 +3.741455656406328956e+01,2.505800000000000125e+02,0.000000000000000000e+00,1.078266399716321544e+01,0.000000000000000000e+00,-6.597544723074830753e-01,0.000000000000000000e+00,-1.000000008062603252e+00,0.000000000000000000e+00 +3.741548397866163356e+01,2.505900000000000034e+02,0.000000000000000000e+00,1.078205213123427519e+01,0.000000000000000000e+00,-6.606818869133037619e-01,0.000000000000000000e+00,-1.000000010330793998e+00,0.000000000000000000e+00 +3.741641144588941614e+01,2.505999999999999943e+02,0.000000000000000000e+00,1.078143937043617129e+01,0.000000000000000000e+00,-6.616093541506712361e-01,0.000000000000000000e+00,-1.000000007273271763e+00,0.000000000000000000e+00 +3.741733896582960028e+01,2.506100000000000136e+02,0.000000000000000000e+00,1.078082571456758210e+01,0.000000000000000000e+00,-6.625368740976046444e-01,0.000000000000000000e+00,-1.000000008858151324e+00,0.000000000000000000e+00 +3.741826653856519158e+01,2.506200000000000045e+02,0.000000000000000000e+00,1.078021116342684493e+01,0.000000000000000000e+00,-6.634644468414130358e-01,0.000000000000000000e+00,-1.000000010597142719e+00,0.000000000000000000e+00 +3.741919416417923827e+01,2.506299999999999955e+02,0.000000000000000000e+00,1.077959571681194717e+01,0.000000000000000000e+00,-6.643920724652874199e-01,0.000000000000000000e+00,-1.000000008003723018e+00,0.000000000000000000e+00 +3.742012184275482412e+01,2.506400000000000148e+02,0.000000000000000000e+00,1.077897937452052979e+01,0.000000000000000000e+00,-6.653197510483015442e-01,0.000000000000000000e+00,-1.000000008976188237e+00,0.000000000000000000e+00 +3.742104957437509682e+01,2.506500000000000057e+02,0.000000000000000000e+00,1.077836213634989093e+01,0.000000000000000000e+00,-6.662474826769008152e-01,0.000000000000000000e+00,-1.000000009025964864e+00,0.000000000000000000e+00 +3.742197735912323253e+01,2.506599999999999966e+02,0.000000000000000000e+00,1.077774400209697880e+01,0.000000000000000000e+00,-6.671752674334117117e-01,0.000000000000000000e+00,-1.000000009856229388e+00,0.000000000000000000e+00 +3.742290519708246421e+01,2.506700000000000159e+02,0.000000000000000000e+00,1.077712497155839522e+01,0.000000000000000000e+00,-6.681031054017858573e-01,0.000000000000000000e+00,-1.000000006979335554e+00,0.000000000000000000e+00 +3.742383308833606037e+01,2.506800000000000068e+02,0.000000000000000000e+00,1.077650504453039382e+01,0.000000000000000000e+00,-6.690309966618560589e-01,0.000000000000000000e+00,-1.000000010349037849e+00,0.000000000000000000e+00 +3.742476103296733925e+01,2.506899999999999977e+02,0.000000000000000000e+00,1.077588422080888364e+01,0.000000000000000000e+00,-6.699589413027362550e-01,0.000000000000000000e+00,-1.000000009287212999e+00,0.000000000000000000e+00 +3.742568903105966172e+01,2.507000000000000171e+02,0.000000000000000000e+00,1.077526250018942022e+01,0.000000000000000000e+00,-6.708869394036773848e-01,0.000000000000000000e+00,-1.000000007556900883e+00,0.000000000000000000e+00 +3.742661708269643839e+01,2.507100000000000080e+02,0.000000000000000000e+00,1.077463988246721449e+01,0.000000000000000000e+00,-6.718149910474673359e-01,0.000000000000000000e+00,-1.000000010980799381e+00,0.000000000000000000e+00 +3.742754518796112251e+01,2.507199999999999989e+02,0.000000000000000000e+00,1.077401636743712920e+01,0.000000000000000000e+00,-6.727430963223434146e-01,0.000000000000000000e+00,-1.000000006820249032e+00,0.000000000000000000e+00 +3.742847334693721706e+01,2.507300000000000182e+02,0.000000000000000000e+00,1.077339195489367363e+01,0.000000000000000000e+00,-6.736712553047657925e-01,0.000000000000000000e+00,-1.000000009145067370e+00,0.000000000000000000e+00 +3.742940155970826055e+01,2.507400000000000091e+02,0.000000000000000000e+00,1.077276664463101419e+01,0.000000000000000000e+00,-6.745994680842988256e-01,0.000000000000000000e+00,-1.000000011401181776e+00,0.000000000000000000e+00 +3.743032982635784833e+01,2.507500000000000000e+02,0.000000000000000000e+00,1.077214043644296204e+01,0.000000000000000000e+00,-6.755277347444696989e-01,0.000000000000000000e+00,-1.000000007038696737e+00,0.000000000000000000e+00 +3.743125814696961839e+01,2.507600000000000193e+02,0.000000000000000000e+00,1.077151333012297840e+01,0.000000000000000000e+00,-6.764560553627709805e-01,0.000000000000000000e+00,-1.000000008058056888e+00,0.000000000000000000e+00 +3.743218652162724425e+01,2.507700000000000102e+02,0.000000000000000000e+00,1.077088532546417987e+01,0.000000000000000000e+00,-6.773844300278809571e-01,0.000000000000000000e+00,-1.000000009966859116e+00,0.000000000000000000e+00 +3.743311495041446335e+01,2.507800000000000011e+02,0.000000000000000000e+00,1.077025642225932778e+01,0.000000000000000000e+00,-6.783128588243538815e-01,0.000000000000000000e+00,-1.000000008274847252e+00,0.000000000000000000e+00 +3.743404343341504870e+01,2.507899999999999920e+02,0.000000000000000000e+00,1.076962662030083173e+01,0.000000000000000000e+00,-6.792413418326210817e-01,0.000000000000000000e+00,-1.000000010854382726e+00,0.000000000000000000e+00 +3.743497197071281590e+01,2.508000000000000114e+02,0.000000000000000000e+00,1.076899591938075318e+01,0.000000000000000000e+00,-6.801698791404692246e-01,0.000000000000000000e+00,-1.000000007033110760e+00,0.000000000000000000e+00 +3.743590056239163744e+01,2.508100000000000023e+02,0.000000000000000000e+00,1.076836431929079829e+01,0.000000000000000000e+00,-6.810984708258216447e-01,0.000000000000000000e+00,-1.000000008800534967e+00,0.000000000000000000e+00 +3.743682920853542129e+01,2.508199999999999932e+02,0.000000000000000000e+00,1.076773181982232686e+01,0.000000000000000000e+00,-6.820271169777809561e-01,0.000000000000000000e+00,-1.000000009603844164e+00,0.000000000000000000e+00 +3.743775790922813229e+01,2.508300000000000125e+02,0.000000000000000000e+00,1.076709842076634160e+01,0.000000000000000000e+00,-6.829558176794114921e-01,0.000000000000000000e+00,-1.000000009070154405e+00,0.000000000000000000e+00 +3.743868666455377792e+01,2.508400000000000034e+02,0.000000000000000000e+00,1.076646412191349356e+01,0.000000000000000000e+00,-6.838845730134776035e-01,0.000000000000000000e+00,-1.000000008885987945e+00,0.000000000000000000e+00 +3.743961547459640116e+01,2.508499999999999943e+02,0.000000000000000000e+00,1.076582892305408201e+01,0.000000000000000000e+00,-6.848133830643564623e-01,0.000000000000000000e+00,-1.000000008676052543e+00,0.000000000000000000e+00 +3.744054433944010896e+01,2.508600000000000136e+02,0.000000000000000000e+00,1.076519282397805277e+01,0.000000000000000000e+00,-6.857422479161233708e-01,0.000000000000000000e+00,-1.000000008065766721e+00,0.000000000000000000e+00 +3.744147325916904379e+01,2.508700000000000045e+02,0.000000000000000000e+00,1.076455582447499815e+01,0.000000000000000000e+00,-6.866711676525524277e-01,0.000000000000000000e+00,-1.000000010795650596e+00,0.000000000000000000e+00 +3.744240223386740496e+01,2.508799999999999955e+02,0.000000000000000000e+00,1.076391792433415695e+01,0.000000000000000000e+00,-6.876001423609393592e-01,0.000000000000000000e+00,-1.000000008255632400e+00,0.000000000000000000e+00 +3.744333126361942732e+01,2.508900000000000148e+02,0.000000000000000000e+00,1.076327912334441095e+01,0.000000000000000000e+00,-6.885291721206283633e-01,0.000000000000000000e+00,-1.000000008301562548e+00,0.000000000000000000e+00 +3.744426034850939544e+01,2.509000000000000057e+02,0.000000000000000000e+00,1.076263942129429196e+01,0.000000000000000000e+00,-6.894582570183085402e-01,0.000000000000000000e+00,-1.000000008496913173e+00,0.000000000000000000e+00 +3.744518948862164365e+01,2.509099999999999966e+02,0.000000000000000000e+00,1.076199881797197477e+01,0.000000000000000000e+00,-6.903873971384526520e-01,0.000000000000000000e+00,-1.000000010519770166e+00,0.000000000000000000e+00 +3.744611868404055599e+01,2.509200000000000159e+02,0.000000000000000000e+00,1.076135731316527888e+01,0.000000000000000000e+00,-6.913165925671399537e-01,0.000000000000000000e+00,-1.000000007818520054e+00,0.000000000000000000e+00 +3.744704793485055916e+01,2.509300000000000068e+02,0.000000000000000000e+00,1.076071490666166675e+01,0.000000000000000000e+00,-6.922458433844091985e-01,0.000000000000000000e+00,-1.000000008242367455e+00,0.000000000000000000e+00 +3.744797724113612958e+01,2.509399999999999977e+02,0.000000000000000000e+00,1.076007159824824910e+01,0.000000000000000000e+00,-6.931751496776400456e-01,0.000000000000000000e+00,-1.000000009351778907e+00,0.000000000000000000e+00 +3.744890660298179341e+01,2.509500000000000171e+02,0.000000000000000000e+00,1.075942738771177787e+01,0.000000000000000000e+00,-6.941045115319929293e-01,0.000000000000000000e+00,-1.000000008708662902e+00,0.000000000000000000e+00 +3.744983602047211946e+01,2.509600000000000080e+02,0.000000000000000000e+00,1.075878227483864791e+01,0.000000000000000000e+00,-6.950339290304099471e-01,0.000000000000000000e+00,-1.000000010042915832e+00,0.000000000000000000e+00 +3.745076549369171914e+01,2.509699999999999989e+02,0.000000000000000000e+00,1.075813625941489882e+01,0.000000000000000000e+00,-6.959634022593473857e-01,0.000000000000000000e+00,-1.000000008858852540e+00,0.000000000000000000e+00 +3.745169502272526785e+01,2.509800000000000182e+02,0.000000000000000000e+00,1.075748934122621137e+01,0.000000000000000000e+00,-6.968929313011307247e-01,0.000000000000000000e+00,-1.000000006828769328e+00,0.000000000000000000e+00 +3.745262460765747647e+01,2.509900000000000091e+02,0.000000000000000000e+00,1.075684152005791105e+01,0.000000000000000000e+00,-6.978225162396873849e-01,0.000000000000000000e+00,-1.000000011789537790e+00,0.000000000000000000e+00 +3.745355424857310567e+01,2.510000000000000000e+02,0.000000000000000000e+00,1.075619279569496634e+01,0.000000000000000000e+00,-6.987521571662780318e-01,0.000000000000000000e+00,-1.000000006911625272e+00,0.000000000000000000e+00 +3.745448394555696581e+01,2.510100000000000193e+02,0.000000000000000000e+00,1.075554316792198151e+01,0.000000000000000000e+00,-6.996818541565661409e-01,0.000000000000000000e+00,-1.000000010306711706e+00,0.000000000000000000e+00 +3.745541369869391701e+01,2.510200000000000102e+02,0.000000000000000000e+00,1.075489263652321092e+01,0.000000000000000000e+00,-7.006116073031010139e-01,0.000000000000000000e+00,-1.000000007201323315e+00,0.000000000000000000e+00 +3.745634350806886204e+01,2.510300000000000011e+02,0.000000000000000000e+00,1.075424120128254302e+01,0.000000000000000000e+00,-7.015414166847450117e-01,0.000000000000000000e+00,-1.000000009536749834e+00,0.000000000000000000e+00 +3.745727337376676047e+01,2.510399999999999920e+02,0.000000000000000000e+00,1.075358886198351271e+01,0.000000000000000000e+00,-7.024712823915114646e-01,0.000000000000000000e+00,-1.000000008705550281e+00,0.000000000000000000e+00 +3.745820329587261455e+01,2.510500000000000114e+02,0.000000000000000000e+00,1.075293561840929080e+01,0.000000000000000000e+00,-7.034012045054587325e-01,0.000000000000000000e+00,-1.000000008426749964e+00,0.000000000000000000e+00 +3.745913327447146912e+01,2.510600000000000023e+02,0.000000000000000000e+00,1.075228147034269099e+01,0.000000000000000000e+00,-7.043311831121517042e-01,0.000000000000000000e+00,-1.000000010363941705e+00,0.000000000000000000e+00 +3.746006330964843301e+01,2.510699999999999932e+02,0.000000000000000000e+00,1.075162641756616644e+01,0.000000000000000000e+00,-7.052612182987511025e-01,0.000000000000000000e+00,-1.000000007964780169e+00,0.000000000000000000e+00 +3.746099340148864343e+01,2.510800000000000125e+02,0.000000000000000000e+00,1.075097045986180788e+01,0.000000000000000000e+00,-7.061913101463723752e-01,0.000000000000000000e+00,-1.000000009051839944e+00,0.000000000000000000e+00 +3.746192355007730868e+01,2.510900000000000034e+02,0.000000000000000000e+00,1.075031359701134903e+01,0.000000000000000000e+00,-7.071214587434551113e-01,0.000000000000000000e+00,-1.000000009125293188e+00,0.000000000000000000e+00 +3.746285375549966545e+01,2.510999999999999943e+02,0.000000000000000000e+00,1.074965582879615944e+01,0.000000000000000000e+00,-7.080516641743025419e-01,0.000000000000000000e+00,-1.000000007792145373e+00,0.000000000000000000e+00 +3.746378401784101442e+01,2.511100000000000136e+02,0.000000000000000000e+00,1.074899715499724806e+01,0.000000000000000000e+00,-7.089819265229010403e-01,0.000000000000000000e+00,-1.000000010815920160e+00,0.000000000000000000e+00 +3.746471433718669886e+01,2.511200000000000045e+02,0.000000000000000000e+00,1.074833757539526324e+01,0.000000000000000000e+00,-7.099122458786476519e-01,0.000000000000000000e+00,-1.000000007539347369e+00,0.000000000000000000e+00 +3.746564471362211179e+01,2.511299999999999955e+02,0.000000000000000000e+00,1.074767708977048741e+01,0.000000000000000000e+00,-7.108426223210739803e-01,0.000000000000000000e+00,-1.000000009880519514e+00,0.000000000000000000e+00 +3.746657514723269600e+01,2.511400000000000148e+02,0.000000000000000000e+00,1.074701569790284594e+01,0.000000000000000000e+00,-7.117730559408487201e-01,0.000000000000000000e+00,-1.000000007182569428e+00,0.000000000000000000e+00 +3.746750563810393686e+01,2.511500000000000057e+02,0.000000000000000000e+00,1.074635339957189650e+01,0.000000000000000000e+00,-7.127035468187746803e-01,0.000000000000000000e+00,-1.000000009307084436e+00,0.000000000000000000e+00 +3.746843618632138373e+01,2.511599999999999966e+02,0.000000000000000000e+00,1.074569019455683794e+01,0.000000000000000000e+00,-7.136340950448798459e-01,0.000000000000000000e+00,-1.000000009700627635e+00,0.000000000000000000e+00 +3.746936679197062148e+01,2.511700000000000159e+02,0.000000000000000000e+00,1.074502608263650139e+01,0.000000000000000000e+00,-7.145647007031438180e-01,0.000000000000000000e+00,-1.000000007965287763e+00,0.000000000000000000e+00 +3.747029745513729182e+01,2.511800000000000068e+02,0.000000000000000000e+00,1.074436106358935561e+01,0.000000000000000000e+00,-7.154953638772251212e-01,0.000000000000000000e+00,-1.000000009854036476e+00,0.000000000000000000e+00 +3.747122817590707911e+01,2.511899999999999977e+02,0.000000000000000000e+00,1.074369513719350699e+01,0.000000000000000000e+00,-7.164260846561859575e-01,0.000000000000000000e+00,-1.000000006763574145e+00,0.000000000000000000e+00 +3.747215895436573163e+01,2.512000000000000171e+02,0.000000000000000000e+00,1.074302830322669422e+01,0.000000000000000000e+00,-7.173568631211311164e-01,0.000000000000000000e+00,-1.000000010595419209e+00,0.000000000000000000e+00 +3.747308979059903322e+01,2.512100000000000080e+02,0.000000000000000000e+00,1.074236056146629537e+01,0.000000000000000000e+00,-7.182876993642927088e-01,0.000000000000000000e+00,-1.000000008645508975e+00,0.000000000000000000e+00 +3.747402068469281744e+01,2.512199999999999989e+02,0.000000000000000000e+00,1.074169191168931725e+01,0.000000000000000000e+00,-7.192185934661278202e-01,0.000000000000000000e+00,-1.000000008712237820e+00,0.000000000000000000e+00 +3.747495163673298180e+01,2.512300000000000182e+02,0.000000000000000000e+00,1.074102235367240610e+01,0.000000000000000000e+00,-7.201495455144024671e-01,0.000000000000000000e+00,-1.000000010390708960e+00,0.000000000000000000e+00 +3.747588264680545933e+01,2.512400000000000091e+02,0.000000000000000000e+00,1.074035188719184042e+01,0.000000000000000000e+00,-7.210805555965561497e-01,0.000000000000000000e+00,-1.000000007128988289e+00,0.000000000000000000e+00 +3.747681371499624703e+01,2.512500000000000000e+02,0.000000000000000000e+00,1.073968051202353102e+01,0.000000000000000000e+00,-7.220116237939785409e-01,0.000000000000000000e+00,-1.000000008768549220e+00,0.000000000000000000e+00 +3.747774484139137741e+01,2.512600000000000193e+02,0.000000000000000000e+00,1.073900822794302634e+01,0.000000000000000000e+00,-7.229427501972723880e-01,0.000000000000000000e+00,-1.000000008754837744e+00,0.000000000000000000e+00 +3.747867602607693982e+01,2.512700000000000102e+02,0.000000000000000000e+00,1.073833503472550355e+01,0.000000000000000000e+00,-7.238739348909881688e-01,0.000000000000000000e+00,-1.000000008730701939e+00,0.000000000000000000e+00 +3.747960726913908047e+01,2.512800000000000011e+02,0.000000000000000000e+00,1.073766093214577388e+01,0.000000000000000000e+00,-7.248051779612564305e-01,0.000000000000000000e+00,-1.000000010336690170e+00,0.000000000000000000e+00 +3.748053857066398109e+01,2.512899999999999920e+02,0.000000000000000000e+00,1.073698591997828089e+01,0.000000000000000000e+00,-7.257364794957861243e-01,0.000000000000000000e+00,-1.000000007020271475e+00,0.000000000000000000e+00 +3.748146993073789446e+01,2.513000000000000114e+02,0.000000000000000000e+00,1.073630999799709862e+01,0.000000000000000000e+00,-7.266678395762343756e-01,0.000000000000000000e+00,-1.000000008612181635e+00,0.000000000000000000e+00 +3.748240134944710178e+01,2.513100000000000023e+02,0.000000000000000000e+00,1.073563316597593698e+01,0.000000000000000000e+00,-7.275992582934647235e-01,0.000000000000000000e+00,-1.000000010606020284e+00,0.000000000000000000e+00 +3.748333282687795531e+01,2.513199999999999932e+02,0.000000000000000000e+00,1.073495542368813283e+01,0.000000000000000000e+00,-7.285307357341948009e-01,0.000000000000000000e+00,-1.000000008496660042e+00,0.000000000000000000e+00 +3.748426436311684284e+01,2.513300000000000125e+02,0.000000000000000000e+00,1.073427677090665355e+01,0.000000000000000000e+00,-7.294622719809965572e-01,0.000000000000000000e+00,-1.000000008014709563e+00,0.000000000000000000e+00 +3.748519595825020900e+01,2.513400000000000034e+02,0.000000000000000000e+00,1.073359720740410062e+01,0.000000000000000000e+00,-7.303938671218308532e-01,0.000000000000000000e+00,-1.000000008747368163e+00,0.000000000000000000e+00 +3.748612761236455526e+01,2.513499999999999943e+02,0.000000000000000000e+00,1.073291673295270421e+01,0.000000000000000000e+00,-7.313255212443253717e-01,0.000000000000000000e+00,-1.000000008234561699e+00,0.000000000000000000e+00 +3.748705932554642573e+01,2.513600000000000136e+02,0.000000000000000000e+00,1.073223534732432327e+01,0.000000000000000000e+00,-7.322572344338671435e-01,0.000000000000000000e+00,-1.000000010154960428e+00,0.000000000000000000e+00 +3.748799109788242134e+01,2.513700000000000045e+02,0.000000000000000000e+00,1.073155305029044726e+01,0.000000000000000000e+00,-7.331890067793219723e-01,0.000000000000000000e+00,-1.000000007955526460e+00,0.000000000000000000e+00 +3.748892292945918570e+01,2.513799999999999955e+02,0.000000000000000000e+00,1.073086984162219260e+01,0.000000000000000000e+00,-7.341208383635011714e-01,0.000000000000000000e+00,-1.000000009404409917e+00,0.000000000000000000e+00 +3.748985482036342631e+01,2.513900000000000148e+02,0.000000000000000000e+00,1.073018572109030799e+01,0.000000000000000000e+00,-7.350527292765058895e-01,0.000000000000000000e+00,-1.000000009993583516e+00,0.000000000000000000e+00 +3.749078677068189336e+01,2.514000000000000057e+02,0.000000000000000000e+00,1.072950068846516736e+01,0.000000000000000000e+00,-7.359846796042882611e-01,0.000000000000000000e+00,-1.000000007260903878e+00,0.000000000000000000e+00 +3.749171878050139384e+01,2.514099999999999966e+02,0.000000000000000000e+00,1.072881474351677333e+01,0.000000000000000000e+00,-7.369166894305572146e-01,0.000000000000000000e+00,-1.000000008969125220e+00,0.000000000000000000e+00 +3.749265084990878449e+01,2.514200000000000159e+02,0.000000000000000000e+00,1.072812788601475908e+01,0.000000000000000000e+00,-7.378487588463082947e-01,0.000000000000000000e+00,-1.000000008563546761e+00,0.000000000000000000e+00 +3.749358297899097181e+01,2.514300000000000068e+02,0.000000000000000000e+00,1.072744011572838119e+01,0.000000000000000000e+00,-7.387808879364798909e-01,0.000000000000000000e+00,-1.000000007670371227e+00,0.000000000000000000e+00 +3.749451516783491911e+01,2.514399999999999977e+02,0.000000000000000000e+00,1.072675143242652496e+01,0.000000000000000000e+00,-7.397130767875779167e-01,0.000000000000000000e+00,-1.000000009956858671e+00,0.000000000000000000e+00 +3.749544741652763946e+01,2.514500000000000171e+02,0.000000000000000000e+00,1.072606183587770268e+01,0.000000000000000000e+00,-7.406453254895790650e-01,0.000000000000000000e+00,-1.000000008869383006e+00,0.000000000000000000e+00 +3.749637972515619566e+01,2.514600000000000080e+02,0.000000000000000000e+00,1.072537132585005004e+01,0.000000000000000000e+00,-7.415776341264027627e-01,0.000000000000000000e+00,-1.000000010117824800e+00,0.000000000000000000e+00 +3.749731209380770025e+01,2.514699999999999989e+02,0.000000000000000000e+00,1.072467990211133149e+01,0.000000000000000000e+00,-7.425100027873438036e-01,0.000000000000000000e+00,-1.000000007149001835e+00,0.000000000000000000e+00 +3.749824452256932972e+01,2.514800000000000182e+02,0.000000000000000000e+00,1.072398756442893486e+01,0.000000000000000000e+00,-7.434424315556393825e-01,0.000000000000000000e+00,-1.000000007712233741e+00,0.000000000000000000e+00 +3.749917701152830318e+01,2.514900000000000091e+02,0.000000000000000000e+00,1.072329431256987675e+01,0.000000000000000000e+00,-7.443749205218045395e-01,0.000000000000000000e+00,-1.000000011381425136e+00,0.000000000000000000e+00 +3.750010956077189661e+01,2.515000000000000000e+02,0.000000000000000000e+00,1.072260014630079539e+01,0.000000000000000000e+00,-7.453074697760101452e-01,0.000000000000000000e+00,-1.000000007518468514e+00,0.000000000000000000e+00 +3.750104217038743570e+01,2.515100000000000193e+02,0.000000000000000000e+00,1.072190506538795063e+01,0.000000000000000000e+00,-7.462400793985590752e-01,0.000000000000000000e+00,-1.000000007953178116e+00,0.000000000000000000e+00 +3.750197484046229590e+01,2.515200000000000102e+02,0.000000000000000000e+00,1.072120906959723285e+01,0.000000000000000000e+00,-7.471727494808388936e-01,0.000000000000000000e+00,-1.000000010214156632e+00,0.000000000000000000e+00 +3.750290757108391659e+01,2.515300000000000011e+02,0.000000000000000000e+00,1.072051215869415230e+01,0.000000000000000000e+00,-7.481054801119856323e-01,0.000000000000000000e+00,-1.000000007748816699e+00,0.000000000000000000e+00 +3.750384036233977980e+01,2.515399999999999920e+02,0.000000000000000000e+00,1.071981433244384085e+01,0.000000000000000000e+00,-7.490382713750763921e-01,0.000000000000000000e+00,-1.000000008295688358e+00,0.000000000000000000e+00 +3.750477321431742439e+01,2.515500000000000114e+02,0.000000000000000000e+00,1.071911559061105734e+01,0.000000000000000000e+00,-7.499711233604593463e-01,0.000000000000000000e+00,-1.000000009382365995e+00,0.000000000000000000e+00 +3.750570612710443896e+01,2.515600000000000023e+02,0.000000000000000000e+00,1.071841593296018047e+01,0.000000000000000000e+00,-7.509040361562298038e-01,0.000000000000000000e+00,-1.000000010578993681e+00,0.000000000000000000e+00 +3.750663910078847607e+01,2.515699999999999932e+02,0.000000000000000000e+00,1.071771535925521057e+01,0.000000000000000000e+00,-7.518370098501353516e-01,0.000000000000000000e+00,-1.000000007373158528e+00,0.000000000000000000e+00 +3.750757213545723090e+01,2.515800000000000125e+02,0.000000000000000000e+00,1.071701386925976962e+01,0.000000000000000000e+00,-7.527700445257666795e-01,0.000000000000000000e+00,-1.000000007495779553e+00,0.000000000000000000e+00 +3.750850523119844837e+01,2.515900000000000034e+02,0.000000000000000000e+00,1.071631146273710478e+01,0.000000000000000000e+00,-7.537031402739807762e-01,0.000000000000000000e+00,-1.000000010512418491e+00,0.000000000000000000e+00 +3.750943838809994446e+01,2.515999999999999943e+02,0.000000000000000000e+00,1.071560813945008128e+01,0.000000000000000000e+00,-7.546362971852833557e-01,0.000000000000000000e+00,-1.000000007829758397e+00,0.000000000000000000e+00 +3.751037160624957068e+01,2.516100000000000136e+02,0.000000000000000000e+00,1.071490389916118247e+01,0.000000000000000000e+00,-7.555695153422148369e-01,0.000000000000000000e+00,-1.000000007173215799e+00,0.000000000000000000e+00 +3.751130488573524246e+01,2.516200000000000045e+02,0.000000000000000000e+00,1.071419874163251684e+01,0.000000000000000000e+00,-7.565027948345782738e-01,0.000000000000000000e+00,-1.000000010145899010e+00,0.000000000000000000e+00 +3.751223822664492502e+01,2.516299999999999955e+02,0.000000000000000000e+00,1.071349266662581101e+01,0.000000000000000000e+00,-7.574361357537271466e-01,0.000000000000000000e+00,-1.000000010192992672e+00,0.000000000000000000e+00 +3.751317162906663327e+01,2.516400000000000148e+02,0.000000000000000000e+00,1.071278567390240788e+01,0.000000000000000000e+00,-7.583695381849512307e-01,0.000000000000000000e+00,-1.000000006879719905e+00,0.000000000000000000e+00 +3.751410509308844610e+01,2.516500000000000057e+02,0.000000000000000000e+00,1.071207776322327199e+01,0.000000000000000000e+00,-7.593030022131879164e-01,0.000000000000000000e+00,-1.000000009960229752e+00,0.000000000000000000e+00 +3.751503861879849211e+01,2.516599999999999966e+02,0.000000000000000000e+00,1.071136893434898951e+01,0.000000000000000000e+00,-7.602365279325338232e-01,0.000000000000000000e+00,-1.000000006765863647e+00,0.000000000000000000e+00 +3.751597220628495677e+01,2.516700000000000159e+02,0.000000000000000000e+00,1.071065918703975939e+01,0.000000000000000000e+00,-7.611701154253136536e-01,0.000000000000000000e+00,-1.000000011123424182e+00,0.000000000000000000e+00 +3.751690585563607527e+01,2.516800000000000068e+02,0.000000000000000000e+00,1.070994852105540396e+01,0.000000000000000000e+00,-7.621037647868146303e-01,0.000000000000000000e+00,-1.000000008326753731e+00,0.000000000000000000e+00 +3.751783956694013256e+01,2.516899999999999977e+02,0.000000000000000000e+00,1.070923693615535655e+01,0.000000000000000000e+00,-7.630374760986484706e-01,0.000000000000000000e+00,-1.000000006087488957e+00,0.000000000000000000e+00 +3.751877334028547750e+01,2.517000000000000171e+02,0.000000000000000000e+00,1.070852443209867388e+01,0.000000000000000000e+00,-7.639712494496809780e-01,0.000000000000000000e+00,-1.000000012110237702e+00,0.000000000000000000e+00 +3.751970717576051584e+01,2.517100000000000080e+02,0.000000000000000000e+00,1.070781100864402902e+01,0.000000000000000000e+00,-7.649050849360274906e-01,0.000000000000000000e+00,-1.000000005581919593e+00,0.000000000000000000e+00 +3.752064107345369592e+01,2.517199999999999989e+02,0.000000000000000000e+00,1.070709666554970418e+01,0.000000000000000000e+00,-7.658389826344222939e-01,0.000000000000000000e+00,-1.000000010501327585e+00,0.000000000000000000e+00 +3.752157503345353007e+01,2.517300000000000182e+02,0.000000000000000000e+00,1.070638140257360860e+01,0.000000000000000000e+00,-7.667729426440660356e-01,0.000000000000000000e+00,-1.000000008093339776e+00,0.000000000000000000e+00 +3.752250905584858742e+01,2.517400000000000091e+02,0.000000000000000000e+00,1.070566521947325711e+01,0.000000000000000000e+00,-7.677069650466800121e-01,0.000000000000000000e+00,-1.000000010131197214e+00,0.000000000000000000e+00 +3.752344314072747977e+01,2.517500000000000000e+02,0.000000000000000000e+00,1.070494811600578622e+01,0.000000000000000000e+00,-7.686410499350363468e-01,0.000000000000000000e+00,-1.000000008023708586e+00,0.000000000000000000e+00 +3.752437728817888285e+01,2.517600000000000193e+02,0.000000000000000000e+00,1.070423009192794339e+01,0.000000000000000000e+00,-7.695751973939376489e-01,0.000000000000000000e+00,-1.000000007432200633e+00,0.000000000000000000e+00 +3.752531149829152923e+01,2.517700000000000102e+02,0.000000000000000000e+00,1.070351114699609418e+01,0.000000000000000000e+00,-7.705094075135298093e-01,0.000000000000000000e+00,-1.000000009942189960e+00,0.000000000000000000e+00 +3.752624577115420834e+01,2.517800000000000011e+02,0.000000000000000000e+00,1.070279128096621690e+01,0.000000000000000000e+00,-7.714436803854956004e-01,0.000000000000000000e+00,-1.000000008999513357e+00,0.000000000000000000e+00 +3.752718010685575223e+01,2.517899999999999920e+02,0.000000000000000000e+00,1.070207049359390084e+01,0.000000000000000000e+00,-7.723780160954499818e-01,0.000000000000000000e+00,-1.000000006190379986e+00,0.000000000000000000e+00 +3.752811450548506400e+01,2.518000000000000114e+02,0.000000000000000000e+00,1.070134878463435157e+01,0.000000000000000000e+00,-7.733124147305449059e-01,0.000000000000000000e+00,-1.000000011235901765e+00,0.000000000000000000e+00 +3.752904896713108940e+01,2.518100000000000023e+02,0.000000000000000000e+00,1.070062615384238924e+01,0.000000000000000000e+00,-7.742468763870715698e-01,0.000000000000000000e+00,-1.000000007409633795e+00,0.000000000000000000e+00 +3.752998349188283811e+01,2.518199999999999932e+02,0.000000000000000000e+00,1.069990260097243961e+01,0.000000000000000000e+00,-7.751814011457470732e-01,0.000000000000000000e+00,-1.000000008498737269e+00,0.000000000000000000e+00 +3.753091807982937667e+01,2.518300000000000125e+02,0.000000000000000000e+00,1.069917812577854832e+01,0.000000000000000000e+00,-7.761159891002279432e-01,0.000000000000000000e+00,-1.000000009980857696e+00,0.000000000000000000e+00 +3.753185273105982134e+01,2.518400000000000034e+02,0.000000000000000000e+00,1.069845272801436842e+01,0.000000000000000000e+00,-7.770506403400007089e-01,0.000000000000000000e+00,-1.000000007335825281e+00,0.000000000000000000e+00 +3.753278744566334524e+01,2.518499999999999943e+02,0.000000000000000000e+00,1.069772640743316394e+01,0.000000000000000000e+00,-7.779853549503829013e-01,0.000000000000000000e+00,-1.000000010274376905e+00,0.000000000000000000e+00 +3.753372222372918543e+01,2.518600000000000136e+02,0.000000000000000000e+00,1.069699916378781346e+01,0.000000000000000000e+00,-7.789201330258247458e-01,0.000000000000000000e+00,-1.000000006142722997e+00,0.000000000000000000e+00 +3.753465706534662161e+01,2.518700000000000045e+02,0.000000000000000000e+00,1.069627099683080118e+01,0.000000000000000000e+00,-7.798549746490044399e-01,0.000000000000000000e+00,-1.000000010745754064e+00,0.000000000000000000e+00 +3.753559197060500452e+01,2.518799999999999955e+02,0.000000000000000000e+00,1.069554190631422763e+01,0.000000000000000000e+00,-7.807898799174312066e-01,0.000000000000000000e+00,-1.000000007365682730e+00,0.000000000000000000e+00 +3.753652693959372755e+01,2.518900000000000148e+02,0.000000000000000000e+00,1.069481189198979543e+01,0.000000000000000000e+00,-7.817248489130417255e-01,0.000000000000000000e+00,-1.000000009769840048e+00,0.000000000000000000e+00 +3.753746197240224802e+01,2.519000000000000057e+02,0.000000000000000000e+00,1.069408095360882349e+01,0.000000000000000000e+00,-7.826598817307005573e-01,0.000000000000000000e+00,-1.000000007338963437e+00,0.000000000000000000e+00 +3.753839706912008722e+01,2.519099999999999966e+02,0.000000000000000000e+00,1.069334909092223462e+01,0.000000000000000000e+00,-7.835949784553999375e-01,0.000000000000000000e+00,-1.000000009770768417e+00,0.000000000000000000e+00 +3.753933222983680906e+01,2.519200000000000159e+02,0.000000000000000000e+00,1.069261630368056437e+01,0.000000000000000000e+00,-7.845301391812568026e-01,0.000000000000000000e+00,-1.000000008477981428e+00,0.000000000000000000e+00 +3.754026745464204140e+01,2.519300000000000068e+02,0.000000000000000000e+00,1.069188259163395216e+01,0.000000000000000000e+00,-7.854653639944148003e-01,0.000000000000000000e+00,-1.000000007062293195e+00,0.000000000000000000e+00 +3.754120274362546184e+01,2.519399999999999977e+02,0.000000000000000000e+00,1.069114795453214839e+01,0.000000000000000000e+00,-7.864006529844423943e-01,0.000000000000000000e+00,-1.000000011151262136e+00,0.000000000000000000e+00 +3.754213809687681902e+01,2.519500000000000171e+02,0.000000000000000000e+00,1.069041239212451089e+01,0.000000000000000000e+00,-7.873360062462287923e-01,0.000000000000000000e+00,-1.000000006067999214e+00,0.000000000000000000e+00 +3.754307351448590424e+01,2.519600000000000080e+02,0.000000000000000000e+00,1.068967590415999958e+01,0.000000000000000000e+00,-7.882714238609923596e-01,0.000000000000000000e+00,-1.000000009620631181e+00,0.000000000000000000e+00 +3.754400899654257984e+01,2.519699999999999989e+02,0.000000000000000000e+00,1.068893849038718891e+01,0.000000000000000000e+00,-7.892069059266660913e-01,0.000000000000000000e+00,-1.000000009161986281e+00,0.000000000000000000e+00 +3.754494454313675078e+01,2.519800000000000182e+02,0.000000000000000000e+00,1.068820015055425188e+01,0.000000000000000000e+00,-7.901424525294099555e-01,0.000000000000000000e+00,-1.000000008286333619e+00,0.000000000000000000e+00 +3.754588015435839310e+01,2.519900000000000091e+02,0.000000000000000000e+00,1.068746088440897068e+01,0.000000000000000000e+00,-7.910780637588034070e-01,0.000000000000000000e+00,-1.000000008555117503e+00,0.000000000000000000e+00 +3.754681583029753256e+01,2.520000000000000000e+02,0.000000000000000000e+00,1.068672069169873318e+01,0.000000000000000000e+00,-7.920137397059443529e-01,0.000000000000000000e+00,-1.000000009499672604e+00,0.000000000000000000e+00 +3.754775157104425176e+01,2.520100000000000193e+02,0.000000000000000000e+00,1.068597957217053107e+01,0.000000000000000000e+00,-7.929494804615500048e-01,0.000000000000000000e+00,-1.000000006593926294e+00,0.000000000000000000e+00 +3.754868737668869016e+01,2.520200000000000102e+02,0.000000000000000000e+00,1.068523752557095996e+01,0.000000000000000000e+00,-7.938852861121599158e-01,0.000000000000000000e+00,-1.000000009509755428e+00,0.000000000000000000e+00 +3.754962324732105117e+01,2.520300000000000011e+02,0.000000000000000000e+00,1.068449455164622286e+01,0.000000000000000000e+00,-7.948211567534223532e-01,0.000000000000000000e+00,-1.000000007634415766e+00,0.000000000000000000e+00 +3.755055918303159501e+01,2.520399999999999920e+02,0.000000000000000000e+00,1.068375065014212133e+01,0.000000000000000000e+00,-7.957570924711118154e-01,0.000000000000000000e+00,-1.000000010636397985e+00,0.000000000000000000e+00 +3.755149518391063879e+01,2.520500000000000114e+02,0.000000000000000000e+00,1.068300582080406436e+01,0.000000000000000000e+00,-7.966930933601096276e-01,0.000000000000000000e+00,-1.000000007903696364e+00,0.000000000000000000e+00 +3.755243125004855642e+01,2.520600000000000023e+02,0.000000000000000000e+00,1.068226006337705947e+01,0.000000000000000000e+00,-7.976291595054226802e-01,0.000000000000000000e+00,-1.000000007073999830e+00,0.000000000000000000e+00 +3.755336738153577869e+01,2.520699999999999932e+02,0.000000000000000000e+00,1.068151337760572162e+01,0.000000000000000000e+00,-7.985652909992648762e-01,0.000000000000000000e+00,-1.000000009698090775e+00,0.000000000000000000e+00 +3.755430357846279321e+01,2.520800000000000125e+02,0.000000000000000000e+00,1.068076576323426607e+01,0.000000000000000000e+00,-7.995014879353606885e-01,0.000000000000000000e+00,-1.000000009219223163e+00,0.000000000000000000e+00 +3.755523984092015866e+01,2.520900000000000034e+02,0.000000000000000000e+00,1.068001722000650666e+01,0.000000000000000000e+00,-8.004377504013548972e-01,0.000000000000000000e+00,-1.000000007189380424e+00,0.000000000000000000e+00 +3.755617616899847633e+01,2.520999999999999943e+02,0.000000000000000000e+00,1.067926774766586107e+01,0.000000000000000000e+00,-8.013740784864034072e-01,0.000000000000000000e+00,-1.000000009209187857e+00,0.000000000000000000e+00 +3.755711256278841148e+01,2.521100000000000136e+02,0.000000000000000000e+00,1.067851734595534907e+01,0.000000000000000000e+00,-8.023104722849648818e-01,0.000000000000000000e+00,-1.000000008721629641e+00,0.000000000000000000e+00 +3.755804902238069332e+01,2.521200000000000045e+02,0.000000000000000000e+00,1.067776601461758723e+01,0.000000000000000000e+00,-8.032469318854171814e-01,0.000000000000000000e+00,-1.000000007274227887e+00,0.000000000000000000e+00 +3.755898554786610788e+01,2.521299999999999955e+02,0.000000000000000000e+00,1.067701375339479419e+01,0.000000000000000000e+00,-8.041834573776458495e-01,0.000000000000000000e+00,-1.000000008437649468e+00,0.000000000000000000e+00 +3.755992213933549806e+01,2.521400000000000148e+02,0.000000000000000000e+00,1.067626056202878893e+01,0.000000000000000000e+00,-8.051200488549394851e-01,0.000000000000000000e+00,-1.000000009704393511e+00,0.000000000000000000e+00 +3.756085879687976359e+01,2.521500000000000057e+02,0.000000000000000000e+00,1.067550644026098716e+01,0.000000000000000000e+00,-8.060567064082976296e-01,0.000000000000000000e+00,-1.000000008568500132e+00,0.000000000000000000e+00 +3.756179552058986815e+01,2.521599999999999966e+02,0.000000000000000000e+00,1.067475138783240318e+01,0.000000000000000000e+00,-8.069934301264316545e-01,0.000000000000000000e+00,-1.000000008596529044e+00,0.000000000000000000e+00 +3.756273231055683937e+01,2.521700000000000159e+02,0.000000000000000000e+00,1.067399540448365158e+01,0.000000000000000000e+00,-8.079302201014528784e-01,0.000000000000000000e+00,-1.000000007280292369e+00,0.000000000000000000e+00 +3.756366916687174751e+01,2.521800000000000068e+02,0.000000000000000000e+00,1.067323848995494373e+01,0.000000000000000000e+00,-8.088670764231824517e-01,0.000000000000000000e+00,-1.000000010206592904e+00,0.000000000000000000e+00 +3.756460608962574099e+01,2.521899999999999977e+02,0.000000000000000000e+00,1.067248064398608953e+01,0.000000000000000000e+00,-8.098039991867351794e-01,0.000000000000000000e+00,-1.000000006771236238e+00,0.000000000000000000e+00 +3.756554307891001088e+01,2.522000000000000171e+02,0.000000000000000000e+00,1.067172186631649211e+01,0.000000000000000000e+00,-8.107409884773503217e-01,0.000000000000000000e+00,-1.000000010651830751e+00,0.000000000000000000e+00 +3.756648013481581927e+01,2.522100000000000080e+02,0.000000000000000000e+00,1.067096215668515669e+01,0.000000000000000000e+00,-8.116780443931422839e-01,0.000000000000000000e+00,-1.000000005176103768e+00,0.000000000000000000e+00 +3.756741725743449223e+01,2.522199999999999989e+02,0.000000000000000000e+00,1.067020151483067814e+01,0.000000000000000000e+00,-8.126151670166628094e-01,0.000000000000000000e+00,-1.000000012106062153e+00,0.000000000000000000e+00 +3.756835444685739844e+01,2.522300000000000182e+02,0.000000000000000000e+00,1.066943994049125521e+01,0.000000000000000000e+00,-8.135523564509168359e-01,0.000000000000000000e+00,-1.000000006681581510e+00,0.000000000000000000e+00 +3.756929170317598476e+01,2.522400000000000091e+02,0.000000000000000000e+00,1.066867743340467101e+01,0.000000000000000000e+00,-8.144896127757652593e-01,0.000000000000000000e+00,-1.000000006615030745e+00,0.000000000000000000e+00 +3.757022902648174778e+01,2.522500000000000000e+02,0.000000000000000000e+00,1.066791399330831425e+01,0.000000000000000000e+00,-8.154269360877288708e-01,0.000000000000000000e+00,-1.000000011411751322e+00,0.000000000000000000e+00 +3.757116641686624803e+01,2.522600000000000193e+02,0.000000000000000000e+00,1.066714961993916333e+01,0.000000000000000000e+00,-8.163643264829261170e-01,0.000000000000000000e+00,-1.000000006429561106e+00,0.000000000000000000e+00 +3.757210387442110289e+01,2.522700000000000102e+02,0.000000000000000000e+00,1.066638431303378631e+01,0.000000000000000000e+00,-8.173017840438103754e-01,0.000000000000000000e+00,-1.000000009368082532e+00,0.000000000000000000e+00 +3.757304139923799369e+01,2.522800000000000011e+02,0.000000000000000000e+00,1.066561807232835335e+01,0.000000000000000000e+00,-8.182393088694873695e-01,0.000000000000000000e+00,-1.000000009626805353e+00,0.000000000000000000e+00 +3.757397899140866571e+01,2.522899999999999920e+02,0.000000000000000000e+00,1.066485089755862070e+01,0.000000000000000000e+00,-8.191769010491860570e-01,0.000000000000000000e+00,-1.000000006711649236e+00,0.000000000000000000e+00 +3.757491665102492107e+01,2.523000000000000114e+02,0.000000000000000000e+00,1.066408278845993962e+01,0.000000000000000000e+00,-8.201145606717322734e-01,0.000000000000000000e+00,-1.000000008208909774e+00,0.000000000000000000e+00 +3.757585437817861873e+01,2.523100000000000023e+02,0.000000000000000000e+00,1.066331374476725635e+01,0.000000000000000000e+00,-8.210522878331258934e-01,0.000000000000000000e+00,-1.000000009580033433e+00,0.000000000000000000e+00 +3.757679217296168162e+01,2.523199999999999932e+02,0.000000000000000000e+00,1.066254376621510502e+01,0.000000000000000000e+00,-8.219900826251723691e-01,0.000000000000000000e+00,-1.000000008307661448e+00,0.000000000000000000e+00 +3.757773003546609658e+01,2.523300000000000125e+02,0.000000000000000000e+00,1.066177285253761120e+01,0.000000000000000000e+00,-8.229279451373772147e-01,0.000000000000000000e+00,-1.000000007933314006e+00,0.000000000000000000e+00 +3.757866796578390733e+01,2.523400000000000034e+02,0.000000000000000000e+00,1.066100100346849366e+01,0.000000000000000000e+00,-8.238658754626282388e-01,0.000000000000000000e+00,-1.000000007956176162e+00,0.000000000000000000e+00 +3.757960596400722153e+01,2.523499999999999943e+02,0.000000000000000000e+00,1.066022821874106086e+01,0.000000000000000000e+00,-8.248038736934049098e-01,0.000000000000000000e+00,-1.000000007876289398e+00,0.000000000000000000e+00 +3.758054403022821077e+01,2.523600000000000136e+02,0.000000000000000000e+00,1.065945449808821088e+01,0.000000000000000000e+00,-8.257419399217791334e-01,0.000000000000000000e+00,-1.000000009209827789e+00,0.000000000000000000e+00 +3.758148216453909640e+01,2.523700000000000045e+02,0.000000000000000000e+00,1.065867984124243151e+01,0.000000000000000000e+00,-8.266800742413066283e-01,0.000000000000000000e+00,-1.000000009435996873e+00,0.000000000000000000e+00 +3.758242036703217792e+01,2.523799999999999955e+02,0.000000000000000000e+00,1.065790424793579838e+01,0.000000000000000000e+00,-8.276182767432399556e-01,0.000000000000000000e+00,-1.000000008051848521e+00,0.000000000000000000e+00 +3.758335863779980457e+01,2.523900000000000148e+02,0.000000000000000000e+00,1.065712771789997682e+01,0.000000000000000000e+00,-8.285565475184212270e-01,0.000000000000000000e+00,-1.000000006571193589e+00,0.000000000000000000e+00 +3.758429697693438953e+01,2.524000000000000057e+02,0.000000000000000000e+00,1.065635025086622178e+01,0.000000000000000000e+00,-8.294948866591744796e-01,0.000000000000000000e+00,-1.000000008523038053e+00,0.000000000000000000e+00 +3.758523538452841706e+01,2.524099999999999966e+02,0.000000000000000000e+00,1.065557184656537615e+01,0.000000000000000000e+00,-8.304332942611972745e-01,0.000000000000000000e+00,-1.000000009365481501e+00,0.000000000000000000e+00 +3.758617386067442112e+01,2.524200000000000159e+02,0.000000000000000000e+00,1.065479250472786710e+01,0.000000000000000000e+00,-8.313717704159874211e-01,0.000000000000000000e+00,-1.000000008592180301e+00,0.000000000000000000e+00 +3.758711240546499965e+01,2.524300000000000068e+02,0.000000000000000000e+00,1.065401222508370971e+01,0.000000000000000000e+00,-8.323103152146293926e-01,0.000000000000000000e+00,-1.000000007711777661e+00,0.000000000000000000e+00 +3.758805101899281453e+01,2.524399999999999977e+02,0.000000000000000000e+00,1.065323100736250694e+01,0.000000000000000000e+00,-8.332489287496855912e-01,0.000000000000000000e+00,-1.000000010246811399e+00,0.000000000000000000e+00 +3.758898970135059869e+01,2.524500000000000171e+02,0.000000000000000000e+00,1.065244885129344787e+01,0.000000000000000000e+00,-8.341876111170872798e-01,0.000000000000000000e+00,-1.000000005607647902e+00,0.000000000000000000e+00 +3.758992845263113480e+01,2.524600000000000080e+02,0.000000000000000000e+00,1.065166575660530413e+01,0.000000000000000000e+00,-8.351263624028878452e-01,0.000000000000000000e+00,-1.000000009409431900e+00,0.000000000000000000e+00 +3.759086727292727659e+01,2.524699999999999989e+02,0.000000000000000000e+00,1.065088172302643876e+01,0.000000000000000000e+00,-8.360651827078615650e-01,0.000000000000000000e+00,-1.000000009044829774e+00,0.000000000000000000e+00 +3.759180616233193462e+01,2.524800000000000182e+02,0.000000000000000000e+00,1.065009675028479208e+01,0.000000000000000000e+00,-8.370040721210102452e-01,0.000000000000000000e+00,-1.000000006018830545e+00,0.000000000000000000e+00 +3.759274512093808340e+01,2.524900000000000091e+02,0.000000000000000000e+00,1.064931083810789225e+01,0.000000000000000000e+00,-8.379430307328107341e-01,0.000000000000000000e+00,-1.000000009890003039e+00,0.000000000000000000e+00 +3.759368414883876142e+01,2.525000000000000000e+02,0.000000000000000000e+00,1.064852398622285357e+01,0.000000000000000000e+00,-8.388820586427779835e-01,0.000000000000000000e+00,-1.000000008055437206e+00,0.000000000000000000e+00 +3.759462324612707107e+01,2.525100000000000193e+02,0.000000000000000000e+00,1.064773619435636753e+01,0.000000000000000000e+00,-8.398211559386560277e-01,0.000000000000000000e+00,-1.000000008057183809e+00,0.000000000000000000e+00 +3.759556241289617873e+01,2.525200000000000102e+02,0.000000000000000000e+00,1.064694746223471356e+01,0.000000000000000000e+00,-8.407603227153340741e-01,0.000000000000000000e+00,-1.000000009377627341e+00,0.000000000000000000e+00 +3.759650164923931470e+01,2.525300000000000011e+02,0.000000000000000000e+00,1.064615778958375181e+01,0.000000000000000000e+00,-8.416995590672787797e-01,0.000000000000000000e+00,-1.000000007471298247e+00,0.000000000000000000e+00 +3.759744095524976615e+01,2.525399999999999920e+02,0.000000000000000000e+00,1.064536717612892325e+01,0.000000000000000000e+00,-8.426388650847508321e-01,0.000000000000000000e+00,-1.000000007860089468e+00,0.000000000000000000e+00 +3.759838033102089128e+01,2.525500000000000114e+02,0.000000000000000000e+00,1.064457562159525317e+01,0.000000000000000000e+00,-8.435782408632608309e-01,0.000000000000000000e+00,-1.000000008010148544e+00,0.000000000000000000e+00 +3.759931977664610514e+01,2.525600000000000023e+02,0.000000000000000000e+00,1.064378312570734586e+01,0.000000000000000000e+00,-8.445176864960030061e-01,0.000000000000000000e+00,-1.000000009413117397e+00,0.000000000000000000e+00 +3.760025929221889385e+01,2.525699999999999932e+02,0.000000000000000000e+00,1.064298968818938640e+01,0.000000000000000000e+00,-8.454572020776366381e-01,0.000000000000000000e+00,-1.000000005509888101e+00,0.000000000000000000e+00 +3.760119887783280035e+01,2.525800000000000125e+02,0.000000000000000000e+00,1.064219530876513886e+01,0.000000000000000000e+00,-8.463967876967222193e-01,0.000000000000000000e+00,-1.000000011875086692e+00,0.000000000000000000e+00 +3.760213853358143865e+01,2.525900000000000034e+02,0.000000000000000000e+00,1.064139998715795166e+01,0.000000000000000000e+00,-8.473364434565178183e-01,0.000000000000000000e+00,-1.000000005852838214e+00,0.000000000000000000e+00 +3.760307825955847960e+01,2.525999999999999943e+02,0.000000000000000000e+00,1.064060372309074332e+01,0.000000000000000000e+00,-8.482761694390573703e-01,0.000000000000000000e+00,-1.000000009047789185e+00,0.000000000000000000e+00 +3.760401805585765800e+01,2.526100000000000136e+02,0.000000000000000000e+00,1.063980651628602203e+01,0.000000000000000000e+00,-8.492159657467402978e-01,0.000000000000000000e+00,-1.000000006853570378e+00,0.000000000000000000e+00 +3.760495792257277969e+01,2.526200000000000045e+02,0.000000000000000000e+00,1.063900836646586612e+01,0.000000000000000000e+00,-8.501558324683041734e-01,0.000000000000000000e+00,-1.000000008798251905e+00,0.000000000000000000e+00 +3.760589785979771449e+01,2.526299999999999955e+02,0.000000000000000000e+00,1.063820927335193645e+01,0.000000000000000000e+00,-8.510957697015055778e-01,0.000000000000000000e+00,-1.000000010331538736e+00,0.000000000000000000e+00 +3.760683786762638903e+01,2.526400000000000148e+02,0.000000000000000000e+00,1.063740923666546756e+01,0.000000000000000000e+00,-8.520357775398891276e-01,0.000000000000000000e+00,-1.000000004895398753e+00,0.000000000000000000e+00 +3.760777794615279390e+01,2.526500000000000057e+02,0.000000000000000000e+00,1.063660825612727123e+01,0.000000000000000000e+00,-8.529758560708988746e-01,0.000000000000000000e+00,-1.000000010050008825e+00,0.000000000000000000e+00 +3.760871809547099787e+01,2.526599999999999966e+02,0.000000000000000000e+00,1.063580633145774179e+01,0.000000000000000000e+00,-8.539160053985512810e-01,0.000000000000000000e+00,-1.000000007174904226e+00,0.000000000000000000e+00 +3.760965831567512652e+01,2.526700000000000159e+02,0.000000000000000000e+00,1.063500346237684013e+01,0.000000000000000000e+00,-8.548562256094225376e-01,0.000000000000000000e+00,-1.000000009805834367e+00,0.000000000000000000e+00 +3.761059860685936229e+01,2.526800000000000068e+02,0.000000000000000000e+00,1.063419964860410971e+01,0.000000000000000000e+00,-8.557965168028796032e-01,0.000000000000000000e+00,-1.000000005354834798e+00,0.000000000000000000e+00 +3.761153896911796579e+01,2.526899999999999977e+02,0.000000000000000000e+00,1.063339488985866410e+01,0.000000000000000000e+00,-8.567368790665184086e-01,0.000000000000000000e+00,-1.000000011367115027e+00,0.000000000000000000e+00 +3.761247940254525446e+01,2.527000000000000171e+02,0.000000000000000000e+00,1.063258918585919766e+01,0.000000000000000000e+00,-8.576773125044986346e-01,0.000000000000000000e+00,-1.000000005213233401e+00,0.000000000000000000e+00 +3.761341990723561679e+01,2.527100000000000080e+02,0.000000000000000000e+00,1.063178253632396952e+01,0.000000000000000000e+00,-8.586178171997643771e-01,0.000000000000000000e+00,-1.000000008450013356e+00,0.000000000000000000e+00 +3.761436048328350523e+01,2.527199999999999989e+02,0.000000000000000000e+00,1.063097494097082318e+01,0.000000000000000000e+00,-8.595583932555983520e-01,0.000000000000000000e+00,-1.000000010497332337e+00,0.000000000000000000e+00 +3.761530113078342907e+01,2.527300000000000182e+02,0.000000000000000000e+00,1.063016639951716691e+01,0.000000000000000000e+00,-8.604990407653986262e-01,0.000000000000000000e+00,-1.000000004796689046e+00,0.000000000000000000e+00 +3.761624184982997576e+01,2.527400000000000091e+02,0.000000000000000000e+00,1.062935691167998264e+01,0.000000000000000000e+00,-8.614397598164589276e-01,0.000000000000000000e+00,-1.000000010882547086e+00,0.000000000000000000e+00 +3.761718264051779670e+01,2.527500000000000000e+02,0.000000000000000000e+00,1.062854647717583134e+01,0.000000000000000000e+00,-8.623805505145148986e-01,0.000000000000000000e+00,-1.000000006135496777e+00,0.000000000000000000e+00 +3.761812350294160012e+01,2.527600000000000193e+02,0.000000000000000000e+00,1.062773509572083519e+01,0.000000000000000000e+00,-8.633214129440888174e-01,0.000000000000000000e+00,-1.000000008077497338e+00,0.000000000000000000e+00 +3.761906443719616533e+01,2.527700000000000102e+02,0.000000000000000000e+00,1.062692276703069716e+01,0.000000000000000000e+00,-8.642623472062536116e-01,0.000000000000000000e+00,-1.000000008138740348e+00,0.000000000000000000e+00 +3.762000544337633556e+01,2.527800000000000011e+02,0.000000000000000000e+00,1.062610949082068501e+01,0.000000000000000000e+00,-8.652033533940854948e-01,0.000000000000000000e+00,-1.000000009788514221e+00,0.000000000000000000e+00 +3.762094652157703223e+01,2.527899999999999920e+02,0.000000000000000000e+00,1.062529526680563841e+01,0.000000000000000000e+00,-8.661444316039913494e-01,0.000000000000000000e+00,-1.000000006465935121e+00,0.000000000000000000e+00 +3.762188767189322647e+01,2.528000000000000114e+02,0.000000000000000000e+00,1.062448009469996535e+01,0.000000000000000000e+00,-8.670855819262699438e-01,0.000000000000000000e+00,-1.000000007654062939e+00,0.000000000000000000e+00 +3.762282889441996048e+01,2.528100000000000023e+02,0.000000000000000000e+00,1.062366397421764752e+01,0.000000000000000000e+00,-8.680268044602110766e-01,0.000000000000000000e+00,-1.000000008794474704e+00,0.000000000000000000e+00 +3.762377018925235461e+01,2.528199999999999932e+02,0.000000000000000000e+00,1.062284690507223139e+01,0.000000000000000000e+00,-8.689680993008812582e-01,0.000000000000000000e+00,-1.000000007336018015e+00,0.000000000000000000e+00 +3.762471155648557897e+01,2.528300000000000125e+02,0.000000000000000000e+00,1.062202888697683179e+01,0.000000000000000000e+00,-8.699094665410120886e-01,0.000000000000000000e+00,-1.000000006739944602e+00,0.000000000000000000e+00 +3.762565299621488180e+01,2.528400000000000034e+02,0.000000000000000000e+00,1.062120991964413363e+01,0.000000000000000000e+00,-8.708509062766599529e-01,0.000000000000000000e+00,-1.000000010464193956e+00,0.000000000000000000e+00 +3.762659450853557530e+01,2.528499999999999943e+02,0.000000000000000000e+00,1.062039000278638845e+01,0.000000000000000000e+00,-8.717924186072040227e-01,0.000000000000000000e+00,-1.000000005935055336e+00,0.000000000000000000e+00 +3.762753609354303563e+01,2.528600000000000136e+02,0.000000000000000000e+00,1.061956913611541076e+01,0.000000000000000000e+00,-8.727340036202522189e-01,0.000000000000000000e+00,-1.000000008631673154e+00,0.000000000000000000e+00 +3.762847775133271000e+01,2.528700000000000045e+02,0.000000000000000000e+00,1.061874731934258875e+01,0.000000000000000000e+00,-8.736756614180538616e-01,0.000000000000000000e+00,-1.000000007983039119e+00,0.000000000000000000e+00 +3.762941948200010955e+01,2.528799999999999955e+02,0.000000000000000000e+00,1.061792455217887010e+01,0.000000000000000000e+00,-8.746173920929720680e-01,0.000000000000000000e+00,-1.000000007442606087e+00,0.000000000000000000e+00 +3.763036128564081650e+01,2.528900000000000148e+02,0.000000000000000000e+00,1.061710083433477081e+01,0.000000000000000000e+00,-8.755591957406890780e-01,0.000000000000000000e+00,-1.000000008458781231e+00,0.000000000000000000e+00 +3.763130316235047701e+01,2.529000000000000057e+02,0.000000000000000000e+00,1.061627616552037168e+01,0.000000000000000000e+00,-8.765010724583188750e-01,0.000000000000000000e+00,-1.000000008472716306e+00,0.000000000000000000e+00 +3.763224511222480828e+01,2.529099999999999966e+02,0.000000000000000000e+00,1.061545054544531652e+01,0.000000000000000000e+00,-8.774430223406330942e-01,0.000000000000000000e+00,-1.000000006928707830e+00,0.000000000000000000e+00 +3.763318713535959859e+01,2.529200000000000159e+02,0.000000000000000000e+00,1.061462397381881395e+01,0.000000000000000000e+00,-8.783850454819474018e-01,0.000000000000000000e+00,-1.000000007272560332e+00,0.000000000000000000e+00 +3.763412923185069303e+01,2.529300000000000068e+02,0.000000000000000000e+00,1.061379645034963737e+01,0.000000000000000000e+00,-8.793271419798912580e-01,0.000000000000000000e+00,-1.000000008944783580e+00,0.000000000000000000e+00 +3.763507140179400778e+01,2.529399999999999977e+02,0.000000000000000000e+00,1.061296797474612141e+01,0.000000000000000000e+00,-8.802693119316353787e-01,0.000000000000000000e+00,-1.000000007383329947e+00,0.000000000000000000e+00 +3.763601364528553717e+01,2.529500000000000171e+02,0.000000000000000000e+00,1.061213854671616197e+01,0.000000000000000000e+00,-8.812115554301203080e-01,0.000000000000000000e+00,-1.000000006030500099e+00,0.000000000000000000e+00 +3.763695596242133234e+01,2.529600000000000080e+02,0.000000000000000000e+00,1.061130816596721971e+01,0.000000000000000000e+00,-8.821538725715978302e-01,0.000000000000000000e+00,-1.000000010324139987e+00,0.000000000000000000e+00 +3.763789835329751554e+01,2.529699999999999989e+02,0.000000000000000000e+00,1.061047683220631654e+01,0.000000000000000000e+00,-8.830962634575126868e-01,0.000000000000000000e+00,-1.000000005700069972e+00,0.000000000000000000e+00 +3.763884081801028714e+01,2.529800000000000182e+02,0.000000000000000000e+00,1.060964454514003030e+01,0.000000000000000000e+00,-8.840387281756530991e-01,0.000000000000000000e+00,-1.000000009594511186e+00,0.000000000000000000e+00 +3.763978335665589725e+01,2.529900000000000091e+02,0.000000000000000000e+00,1.060881130447450715e+01,0.000000000000000000e+00,-8.849812668303081997e-01,0.000000000000000000e+00,-1.000000005444587892e+00,0.000000000000000000e+00 +3.764072596933068127e+01,2.530000000000000000e+02,0.000000000000000000e+00,1.060797710991544562e+01,0.000000000000000000e+00,-8.859238795102253317e-01,0.000000000000000000e+00,-1.000000010678025131e+00,0.000000000000000000e+00 +3.764166865613103852e+01,2.530100000000000193e+02,0.000000000000000000e+00,1.060714196116811081e+01,0.000000000000000000e+00,-8.868665663206477534e-01,0.000000000000000000e+00,-1.000000004737684023e+00,0.000000000000000000e+00 +3.764261141715343228e+01,2.530200000000000102e+02,0.000000000000000000e+00,1.060630585793731839e+01,0.000000000000000000e+00,-8.878093273475092806e-01,0.000000000000000000e+00,-1.000000009041704496e+00,0.000000000000000000e+00 +3.764355425249440401e+01,2.530300000000000011e+02,0.000000000000000000e+00,1.060546879992745239e+01,0.000000000000000000e+00,-8.887521626970040778e-01,0.000000000000000000e+00,-1.000000007031732308e+00,0.000000000000000000e+00 +3.764449716225055198e+01,2.530399999999999920e+02,0.000000000000000000e+00,1.060463078684244564e+01,0.000000000000000000e+00,-8.896950724597847415e-01,0.000000000000000000e+00,-1.000000008129100504e+00,0.000000000000000000e+00 +3.764544014651855974e+01,2.530500000000000114e+02,0.000000000000000000e+00,1.060379181838579399e+01,0.000000000000000000e+00,-8.906380567354559297e-01,0.000000000000000000e+00,-1.000000007766100207e+00,0.000000000000000000e+00 +3.764638320539516769e+01,2.530600000000000023e+02,0.000000000000000000e+00,1.060295189426054741e+01,0.000000000000000000e+00,-8.915811156193848008e-01,0.000000000000000000e+00,-1.000000007368103905e+00,0.000000000000000000e+00 +3.764732633897718728e+01,2.530699999999999932e+02,0.000000000000000000e+00,1.060211101416931356e+01,0.000000000000000000e+00,-8.925242492083520496e-01,0.000000000000000000e+00,-1.000000008357902148e+00,0.000000000000000000e+00 +3.764826954736150100e+01,2.530800000000000125e+02,0.000000000000000000e+00,1.060126917781425604e+01,0.000000000000000000e+00,-8.934674576005500191e-01,0.000000000000000000e+00,-1.000000006168066724e+00,0.000000000000000000e+00 +3.764921283064506241e+01,2.530900000000000034e+02,0.000000000000000000e+00,1.060042638489709255e+01,0.000000000000000000e+00,-8.944107408899327760e-01,0.000000000000000000e+00,-1.000000008207870827e+00,0.000000000000000000e+00 +3.765015618892490323e+01,2.530999999999999943e+02,0.000000000000000000e+00,1.059958263511909848e+01,0.000000000000000000e+00,-8.953540991775131852e-01,0.000000000000000000e+00,-1.000000007911602040e+00,0.000000000000000000e+00 +3.765109962229810492e+01,2.531100000000000136e+02,0.000000000000000000e+00,1.059873792818109983e+01,0.000000000000000000e+00,-8.962975325581807873e-01,0.000000000000000000e+00,-1.000000006697979504e+00,0.000000000000000000e+00 +3.765204313086184129e+01,2.531200000000000045e+02,0.000000000000000000e+00,1.059789226378347848e+01,0.000000000000000000e+00,-8.972410411282333298e-01,0.000000000000000000e+00,-1.000000007978540717e+00,0.000000000000000000e+00 +3.765298671471333591e+01,2.531299999999999955e+02,0.000000000000000000e+00,1.059704564162617046e+01,0.000000000000000000e+00,-8.981846249872577070e-01,0.000000000000000000e+00,-1.000000007182169526e+00,0.000000000000000000e+00 +3.765393037394989761e+01,2.531400000000000148e+02,0.000000000000000000e+00,1.059619806140866238e+01,0.000000000000000000e+00,-8.991282842305982070e-01,0.000000000000000000e+00,-1.000000005723734375e+00,0.000000000000000000e+00 +3.765487410866889917e+01,2.531500000000000057e+02,0.000000000000000000e+00,1.059534952282999498e+01,0.000000000000000000e+00,-9.000720189550044381e-01,0.000000000000000000e+00,-1.000000009002893542e+00,0.000000000000000000e+00 +3.765581791896779151e+01,2.531599999999999966e+02,0.000000000000000000e+00,1.059450002558876136e+01,0.000000000000000000e+00,-9.010158292623927645e-01,0.000000000000000000e+00,-1.000000008459288381e+00,0.000000000000000000e+00 +3.765676180494408243e+01,2.531700000000000159e+02,0.000000000000000000e+00,1.059364956938310165e+01,0.000000000000000000e+00,-9.019597152466714007e-01,0.000000000000000000e+00,-1.000000005503593803e+00,0.000000000000000000e+00 +3.765770576669536496e+01,2.531800000000000068e+02,0.000000000000000000e+00,1.059279815391071011e+01,0.000000000000000000e+00,-9.029036770031502179e-01,0.000000000000000000e+00,-1.000000007524284529e+00,0.000000000000000000e+00 +3.765864980431929609e+01,2.531899999999999977e+02,0.000000000000000000e+00,1.059194577886883337e+01,0.000000000000000000e+00,-9.038477146341845625e-01,0.000000000000000000e+00,-1.000000007953479431e+00,0.000000000000000000e+00 +3.765959391791360389e+01,2.532000000000000171e+02,0.000000000000000000e+00,1.059109244395426330e+01,0.000000000000000000e+00,-9.047918282360012387e-01,0.000000000000000000e+00,-1.000000008196583190e+00,0.000000000000000000e+00 +3.766053810757608744e+01,2.532100000000000080e+02,0.000000000000000000e+00,1.059023814886334236e+01,0.000000000000000000e+00,-9.057360179062249328e-01,0.000000000000000000e+00,-1.000000005672967651e+00,0.000000000000000000e+00 +3.766148237340462401e+01,2.532199999999999989e+02,0.000000000000000000e+00,1.058938289329196181e+01,0.000000000000000000e+00,-9.066802837401148896e-01,0.000000000000000000e+00,-1.000000007761230547e+00,0.000000000000000000e+00 +3.766242671549714771e+01,2.532300000000000182e+02,0.000000000000000000e+00,1.058852667693556349e+01,0.000000000000000000e+00,-9.076246258399691680e-01,0.000000000000000000e+00,-1.000000007893282250e+00,0.000000000000000000e+00 +3.766337113395167790e+01,2.532400000000000091e+02,0.000000000000000000e+00,1.058766949948913272e+01,0.000000000000000000e+00,-9.085690443019555085e-01,0.000000000000000000e+00,-1.000000005478159260e+00,0.000000000000000000e+00 +3.766431562886630502e+01,2.532500000000000000e+02,0.000000000000000000e+00,1.058681136064720363e+01,0.000000000000000000e+00,-9.095135392217548187e-01,0.000000000000000000e+00,-1.000000007887164033e+00,0.000000000000000000e+00 +3.766526020033918343e+01,2.532600000000000193e+02,0.000000000000000000e+00,1.058595226010385915e+01,0.000000000000000000e+00,-9.104581107020820463e-01,0.000000000000000000e+00,-1.000000008551349850e+00,0.000000000000000000e+00 +3.766620484846854566e+01,2.532700000000000102e+02,0.000000000000000000e+00,1.058509219755272390e+01,0.000000000000000000e+00,-9.114027588395199331e-01,0.000000000000000000e+00,-1.000000004886574478e+00,0.000000000000000000e+00 +3.766714957335268821e+01,2.532800000000000011e+02,0.000000000000000000e+00,1.058423117268696956e+01,0.000000000000000000e+00,-9.123474837282816718e-01,0.000000000000000000e+00,-1.000000008237460047e+00,0.000000000000000000e+00 +3.766809437508999281e+01,2.532899999999999920e+02,0.000000000000000000e+00,1.058336918519931658e+01,0.000000000000000000e+00,-9.132922854733701579e-01,0.000000000000000000e+00,-1.000000008054032774e+00,0.000000000000000000e+00 +3.766903925377890516e+01,2.533000000000000114e+02,0.000000000000000000e+00,1.058250623478202357e+01,0.000000000000000000e+00,-9.142371641698938678e-01,0.000000000000000000e+00,-1.000000005729365204e+00,0.000000000000000000e+00 +3.766998420951794913e+01,2.533100000000000023e+02,0.000000000000000000e+00,1.058164232112689618e+01,0.000000000000000000e+00,-9.151821199143493901e-01,0.000000000000000000e+00,-1.000000006631226013e+00,0.000000000000000000e+00 +3.767092924240571250e+01,2.533199999999999932e+02,0.000000000000000000e+00,1.058077744392528530e+01,0.000000000000000000e+00,-9.161271528083781979e-01,0.000000000000000000e+00,-1.000000008167239773e+00,0.000000000000000000e+00 +3.767187435254086125e+01,2.533300000000000125e+02,0.000000000000000000e+00,1.057991160286808174e+01,0.000000000000000000e+00,-9.170722629512452206e-01,0.000000000000000000e+00,-1.000000005759013710e+00,0.000000000000000000e+00 +3.767281954002213240e+01,2.533400000000000034e+02,0.000000000000000000e+00,1.057904479764571803e+01,0.000000000000000000e+00,-9.180174504379610134e-01,0.000000000000000000e+00,-1.000000006756785131e+00,0.000000000000000000e+00 +3.767376480494834112e+01,2.533499999999999943e+02,0.000000000000000000e+00,1.057817702794817194e+01,0.000000000000000000e+00,-9.189627153705561824e-01,0.000000000000000000e+00,-1.000000008566249710e+00,0.000000000000000000e+00 +3.767471014741836655e+01,2.533600000000000136e+02,0.000000000000000000e+00,1.057730829346495938e+01,0.000000000000000000e+00,-9.199080578486827919e-01,0.000000000000000000e+00,-1.000000004619575389e+00,0.000000000000000000e+00 +3.767565556753117306e+01,2.533700000000000045e+02,0.000000000000000000e+00,1.057643859388513619e+01,0.000000000000000000e+00,-9.208534779658570368e-01,0.000000000000000000e+00,-1.000000008221583858e+00,0.000000000000000000e+00 +3.767660106538578901e+01,2.533799999999999955e+02,0.000000000000000000e+00,1.057556792889730346e+01,0.000000000000000000e+00,-9.217989758282468804e-01,0.000000000000000000e+00,-1.000000006840566780e+00,0.000000000000000000e+00 +3.767754664108132090e+01,2.533900000000000148e+02,0.000000000000000000e+00,1.057469629818959511e+01,0.000000000000000000e+00,-9.227445515302459267e-01,0.000000000000000000e+00,-1.000000005828768801e+00,0.000000000000000000e+00 +3.767849229471694628e+01,2.534000000000000057e+02,0.000000000000000000e+00,1.057382370144968853e+01,0.000000000000000000e+00,-9.236902051713816730e-01,0.000000000000000000e+00,-1.000000006561725163e+00,0.000000000000000000e+00 +3.767943802639191375e+01,2.534099999999999966e+02,0.000000000000000000e+00,1.057295013836479924e+01,0.000000000000000000e+00,-9.246359368525564060e-01,0.000000000000000000e+00,-1.000000008426844555e+00,0.000000000000000000e+00 +3.768038383620555720e+01,2.534200000000000159e+02,0.000000000000000000e+00,1.057207560862167917e+01,0.000000000000000000e+00,-9.255817466741673716e-01,0.000000000000000000e+00,-1.000000004855241320e+00,0.000000000000000000e+00 +3.768132972425726734e+01,2.534300000000000068e+02,0.000000000000000000e+00,1.057120011190661657e+01,0.000000000000000000e+00,-9.265276347304727267e-01,0.000000000000000000e+00,-1.000000007145787739e+00,0.000000000000000000e+00 +3.768227569064652727e+01,2.534399999999999977e+02,0.000000000000000000e+00,1.057032364790544143e+01,0.000000000000000000e+00,-9.274736011264919089e-01,0.000000000000000000e+00,-1.000000006742078451e+00,0.000000000000000000e+00 +3.768322173547288401e+01,2.534500000000000171e+02,0.000000000000000000e+00,1.056944621630351477e+01,0.000000000000000000e+00,-9.284196459592253259e-01,0.000000000000000000e+00,-1.000000005013170101e+00,0.000000000000000000e+00 +3.768416785883595566e+01,2.534600000000000080e+02,0.000000000000000000e+00,1.056856781678573576e+01,0.000000000000000000e+00,-9.293657693270425124e-01,0.000000000000000000e+00,-1.000000007295317017e+00,0.000000000000000000e+00 +3.768511406083544557e+01,2.534699999999999989e+02,0.000000000000000000e+00,1.056768844903653992e+01,0.000000000000000000e+00,-9.303119713334364604e-01,0.000000000000000000e+00,-1.000000007016142334e+00,0.000000000000000000e+00 +3.768606034157112816e+01,2.534800000000000182e+02,0.000000000000000000e+00,1.056680811273989384e+01,0.000000000000000000e+00,-9.312582520757565208e-01,0.000000000000000000e+00,-1.000000005541452630e+00,0.000000000000000000e+00 +3.768700670114284890e+01,2.534900000000000091e+02,0.000000000000000000e+00,1.056592680757930047e+01,0.000000000000000000e+00,-9.322046116527188397e-01,0.000000000000000000e+00,-1.000000006216576143e+00,0.000000000000000000e+00 +3.768795313965052429e+01,2.535000000000000000e+02,0.000000000000000000e+00,1.056504453323779735e+01,0.000000000000000000e+00,-9.331510501662804158e-01,0.000000000000000000e+00,-1.000000008419119846e+00,0.000000000000000000e+00 +3.768889965719416324e+01,2.535100000000000193e+02,0.000000000000000000e+00,1.056416128939795307e+01,0.000000000000000000e+00,-9.340975677178847691e-01,0.000000000000000000e+00,-1.000000003595074460e+00,0.000000000000000000e+00 +3.768984625387383147e+01,2.535200000000000102e+02,0.000000000000000000e+00,1.056327707574186725e+01,0.000000000000000000e+00,-9.350441644009538367e-01,0.000000000000000000e+00,-1.000000006980702016e+00,0.000000000000000000e+00 +3.769079292978967288e+01,2.535300000000000011e+02,0.000000000000000000e+00,1.056239189195117767e+01,0.000000000000000000e+00,-9.359908403234070695e-01,0.000000000000000000e+00,-1.000000006055646207e+00,0.000000000000000000e+00 +3.769173968504192374e+01,2.535399999999999920e+02,0.000000000000000000e+00,1.056150573770704604e+01,0.000000000000000000e+00,-9.369375955813876722e-01,0.000000000000000000e+00,-1.000000006139927899e+00,0.000000000000000000e+00 +3.769268651973087003e+01,2.535500000000000114e+02,0.000000000000000000e+00,1.056061861269016866e+01,0.000000000000000000e+00,-9.378844302761506491e-01,0.000000000000000000e+00,-1.000000006604787828e+00,0.000000000000000000e+00 +3.769363343395689725e+01,2.535600000000000023e+02,0.000000000000000000e+00,1.055973051658077111e+01,0.000000000000000000e+00,-9.388313445084316422e-01,0.000000000000000000e+00,-1.000000004840942758e+00,0.000000000000000000e+00 +3.769458042782045482e+01,2.535699999999999932e+02,0.000000000000000000e+00,1.055884144905860822e+01,0.000000000000000000e+00,-9.397783383765713205e-01,0.000000000000000000e+00,-1.000000006160269628e+00,0.000000000000000000e+00 +3.769552750142206321e+01,2.535800000000000125e+02,0.000000000000000000e+00,1.055795140980296587e+01,0.000000000000000000e+00,-9.407254119840166018e-01,0.000000000000000000e+00,-1.000000005969301498e+00,0.000000000000000000e+00 +3.769647465486233529e+01,2.535900000000000034e+02,0.000000000000000000e+00,1.055706039849265565e+01,0.000000000000000000e+00,-9.416725654299406001e-01,0.000000000000000000e+00,-1.000000005616611620e+00,0.000000000000000000e+00 +3.769742188824194074e+01,2.535999999999999943e+02,0.000000000000000000e+00,1.055616841480601842e+01,0.000000000000000000e+00,-9.426197988148697915e-01,0.000000000000000000e+00,-1.000000004468376336e+00,0.000000000000000000e+00 +3.769836920166164163e+01,2.536100000000000136e+02,0.000000000000000000e+00,1.055527545842092252e+01,0.000000000000000000e+00,-9.435671122388066268e-01,0.000000000000000000e+00,-1.000000007826957971e+00,0.000000000000000000e+00 +3.769931659522227108e+01,2.536200000000000045e+02,0.000000000000000000e+00,1.055438152901476379e+01,0.000000000000000000e+00,-9.445145058068533661e-01,0.000000000000000000e+00,-1.000000003181851227e+00,0.000000000000000000e+00 +3.770026406902474037e+01,2.536299999999999955e+02,0.000000000000000000e+00,1.055348662626446021e+01,0.000000000000000000e+00,-9.454619796123366893e-01,0.000000000000000000e+00,-1.000000007705228011e+00,0.000000000000000000e+00 +3.770121162317003183e+01,2.536400000000000148e+02,0.000000000000000000e+00,1.055259074984646261e+01,0.000000000000000000e+00,-9.464095337649297557e-01,0.000000000000000000e+00,-1.000000002951342282e+00,0.000000000000000000e+00 +3.770215925775921306e+01,2.536500000000000057e+02,0.000000000000000000e+00,1.055169389943673863e+01,0.000000000000000000e+00,-9.473571683569050883e-01,0.000000000000000000e+00,-1.000000008062606582e+00,0.000000000000000000e+00 +3.770310697289341562e+01,2.536599999999999966e+02,0.000000000000000000e+00,1.055079607471078873e+01,0.000000000000000000e+00,-9.483048834987516384e-01,0.000000000000000000e+00,-1.000000002618900208e+00,0.000000000000000000e+00 +3.770405476867386341e+01,2.536700000000000159e+02,0.000000000000000000e+00,1.054989727534362842e+01,0.000000000000000000e+00,-9.492526792816838865e-01,0.000000000000000000e+00,-1.000000007731263185e+00,0.000000000000000000e+00 +3.770500264520185141e+01,2.536800000000000068e+02,0.000000000000000000e+00,1.054899750100980604e+01,0.000000000000000000e+00,-9.502005558170018018e-01,0.000000000000000000e+00,-1.000000002983758796e+00,0.000000000000000000e+00 +3.770595060257875275e+01,2.536899999999999977e+02,0.000000000000000000e+00,1.054809675138338321e+01,0.000000000000000000e+00,-9.511485131967319928e-01,0.000000000000000000e+00,-1.000000005524083413e+00,0.000000000000000000e+00 +3.770689864090601873e+01,2.537000000000000171e+02,0.000000000000000000e+00,1.054719502613795257e+01,0.000000000000000000e+00,-9.520965515292330039e-01,0.000000000000000000e+00,-1.000000004822767519e+00,0.000000000000000000e+00 +3.770784676028517168e+01,2.537100000000000080e+02,0.000000000000000000e+00,1.054629232494662183e+01,0.000000000000000000e+00,-9.530446709129597460e-01,0.000000000000000000e+00,-1.000000004185796154e+00,0.000000000000000000e+00 +3.770879496081781923e+01,2.537199999999999989e+02,0.000000000000000000e+00,1.054538864748202265e+01,0.000000000000000000e+00,-9.539928714495790052e-01,0.000000000000000000e+00,-1.000000004940209797e+00,0.000000000000000000e+00 +3.770974324260564714e+01,2.537300000000000182e+02,0.000000000000000000e+00,1.054448399341630704e+01,0.000000000000000000e+00,-9.549411532420940540e-01,0.000000000000000000e+00,-1.000000004460726677e+00,0.000000000000000000e+00 +3.771069160575041934e+01,2.537400000000000091e+02,0.000000000000000000e+00,1.054357836242114566e+01,0.000000000000000000e+00,-9.558895163910969828e-01,0.000000000000000000e+00,-1.000000006047087497e+00,0.000000000000000000e+00 +3.771164005035397793e+01,2.537500000000000000e+02,0.000000000000000000e+00,1.054267175416772950e+01,0.000000000000000000e+00,-9.568379610003875380e-01,0.000000000000000000e+00,-1.000000003122836878e+00,0.000000000000000000e+00 +3.771258857651823604e+01,2.537600000000000193e+02,0.000000000000000000e+00,1.054176416832676644e+01,0.000000000000000000e+00,-9.577864871676065039e-01,0.000000000000000000e+00,-1.000000002933845833e+00,0.000000000000000000e+00 +3.771353718434519209e+01,2.537700000000000102e+02,0.000000000000000000e+00,1.054085560456848647e+01,0.000000000000000000e+00,-9.587350949973456604e-01,0.000000000000000000e+00,-1.000000006797214791e+00,0.000000000000000000e+00 +3.771448587393692264e+01,2.537800000000000011e+02,0.000000000000000000e+00,1.053994606256263467e+01,0.000000000000000000e+00,-9.596837845955257240e-01,0.000000000000000000e+00,-1.000000002215714501e+00,0.000000000000000000e+00 +3.771543464539558244e+01,2.537899999999999920e+02,0.000000000000000000e+00,1.053903554197846937e+01,0.000000000000000000e+00,-9.606325560562902766e-01,0.000000000000000000e+00,-1.000000002348387484e+00,0.000000000000000000e+00 +3.771638349882341146e+01,2.538000000000000114e+02,0.000000000000000000e+00,1.053812404248477286e+01,0.000000000000000000e+00,-9.615814094863458505e-01,0.000000000000000000e+00,-1.000000006533564578e+00,0.000000000000000000e+00 +3.771733243432271365e+01,2.538100000000000023e+02,0.000000000000000000e+00,1.053721156374983892e+01,0.000000000000000000e+00,-9.625303449918514165e-01,0.000000000000000000e+00,-1.000000000304541059e+00,0.000000000000000000e+00 +3.771828145199589244e+01,2.538199999999999932e+02,0.000000000000000000e+00,1.053629810544147283e+01,0.000000000000000000e+00,-9.634793626653170850e-01,0.000000000000000000e+00,-1.000000006669714114e+00,0.000000000000000000e+00 +3.771923055194541519e+01,2.538300000000000125e+02,0.000000000000000000e+00,1.053538366722700381e+01,0.000000000000000000e+00,-9.644284626211671041e-01,0.000000000000000000e+00,-1.000000001300830554e+00,0.000000000000000000e+00 +3.772017973427382742e+01,2.538400000000000034e+02,0.000000000000000000e+00,1.053446824877326371e+01,0.000000000000000000e+00,-9.653776449508164603e-01,0.000000000000000000e+00,-1.000000003254378766e+00,0.000000000000000000e+00 +3.772112899908376704e+01,2.538499999999999943e+02,0.000000000000000000e+00,1.053355184974660830e+01,0.000000000000000000e+00,-9.663269097638466087e-01,0.000000000000000000e+00,-1.000000002007145117e+00,0.000000000000000000e+00 +3.772207834647794300e+01,2.538600000000000136e+02,0.000000000000000000e+00,1.053263446981289952e+01,0.000000000000000000e+00,-9.672762571599304859e-01,0.000000000000000000e+00,-1.000000002807277522e+00,0.000000000000000000e+00 +3.772302777655914952e+01,2.538700000000000045e+02,0.000000000000000000e+00,1.053171610863751440e+01,0.000000000000000000e+00,-9.682256872438029793e-01,0.000000000000000000e+00,-1.000000003016543237e+00,0.000000000000000000e+00 +3.772397728943025896e+01,2.538799999999999955e+02,0.000000000000000000e+00,1.053079676588533964e+01,0.000000000000000000e+00,-9.691752001177745823e-01,0.000000000000000000e+00,-1.000000001967270791e+00,0.000000000000000000e+00 +3.772492688519421478e+01,2.538900000000000148e+02,0.000000000000000000e+00,1.052987644122077349e+01,0.000000000000000000e+00,-9.701247958836018981e-01,0.000000000000000000e+00,-1.000000000960440394e+00,0.000000000000000000e+00 +3.772587656395405986e+01,2.539000000000000057e+02,0.000000000000000000e+00,1.052895513430772567e+01,0.000000000000000000e+00,-9.710744746443571440e-01,0.000000000000000000e+00,-1.000000003264003956e+00,0.000000000000000000e+00 +3.772682632581290108e+01,2.539099999999999966e+02,0.000000000000000000e+00,1.052803284480961565e+01,0.000000000000000000e+00,-9.720242365062968792e-01,0.000000000000000000e+00,-1.000000000328518768e+00,0.000000000000000000e+00 +3.772777617087393054e+01,2.539200000000000159e+02,0.000000000000000000e+00,1.052710957238936906e+01,0.000000000000000000e+00,-9.729740815676385379e-01,0.000000000000000000e+00,-9.999999993584343105e-01,0.000000000000000000e+00 +3.772872609924042564e+01,2.539300000000000068e+02,0.000000000000000000e+00,1.052618531670942481e+01,0.000000000000000000e+00,-9.739240099335227940e-01,0.000000000000000000e+00,-1.000000003614049504e+00,0.000000000000000000e+00 +3.772967611101574192e+01,2.539399999999999977e+02,0.000000000000000000e+00,1.052526007743172798e+01,0.000000000000000000e+00,-9.748740217122691121e-01,0.000000000000000000e+00,-9.999999986424759069e-01,0.000000000000000000e+00 +3.773062620630331310e+01,2.539500000000000171e+02,0.000000000000000000e+00,1.052433385421772627e+01,0.000000000000000000e+00,-9.758241169985477637e-01,0.000000000000000000e+00,-9.999999995117326845e-01,0.000000000000000000e+00 +3.773157638520665103e+01,2.539600000000000080e+02,0.000000000000000000e+00,1.052340664672838244e+01,0.000000000000000000e+00,-9.767742959014252824e-01,0.000000000000000000e+00,-1.000000001606039302e+00,0.000000000000000000e+00 +3.773252664782936705e+01,2.539699999999999989e+02,0.000000000000000000e+00,1.052247845462416009e+01,0.000000000000000000e+00,-9.777245585256648663e-01,0.000000000000000000e+00,-9.999999963778939405e-01,0.000000000000000000e+00 +3.773347699427513646e+01,2.539800000000000182e+02,0.000000000000000000e+00,1.052154927756502723e+01,0.000000000000000000e+00,-9.786749049679884793e-01,0.000000000000000000e+00,-1.000000000849450510e+00,0.000000000000000000e+00 +3.773442742464771982e+01,2.539900000000000091e+02,0.000000000000000000e+00,1.052061911521046333e+01,0.000000000000000000e+00,-9.796253353413763021e-01,0.000000000000000000e+00,-9.999999966374151228e-01,0.000000000000000000e+00 +3.773537793905095583e+01,2.540000000000000000e+02,0.000000000000000000e+00,1.051968796721944344e+01,0.000000000000000000e+00,-9.805758497414192032e-01,0.000000000000000000e+00,-9.999999987898962051e-01,0.000000000000000000e+00 +3.773632853758878269e+01,2.540100000000000193e+02,0.000000000000000000e+00,1.051875583325045405e+01,0.000000000000000000e+00,-9.815264482780925448e-01,0.000000000000000000e+00,-9.999999967916276544e-01,0.000000000000000000e+00 +3.773727922036520255e+01,2.540200000000000102e+02,0.000000000000000000e+00,1.051782271296147897e+01,0.000000000000000000e+00,-9.824771310514587297e-01,0.000000000000000000e+00,-9.999999958544062428e-01,0.000000000000000000e+00 +3.773822998748430280e+01,2.540300000000000011e+02,0.000000000000000000e+00,1.051688860601000819e+01,0.000000000000000000e+00,-9.834278981666165764e-01,0.000000000000000000e+00,-9.999999933258160167e-01,0.000000000000000000e+00 +3.773918083905025611e+01,2.540399999999999920e+02,0.000000000000000000e+00,1.051595351205303253e+01,0.000000000000000000e+00,-9.843787497262255215e-01,0.000000000000000000e+00,-9.999999963750541010e-01,0.000000000000000000e+00 +3.774013177516732043e+01,2.540500000000000114e+02,0.000000000000000000e+00,1.051501743074704542e+01,0.000000000000000000e+00,-9.853296858398445934e-01,0.000000000000000000e+00,-9.999999944898368964e-01,0.000000000000000000e+00 +3.774108279593983895e+01,2.540600000000000023e+02,0.000000000000000000e+00,1.051408036174803584e+01,0.000000000000000000e+00,-9.862807066071195283e-01,0.000000000000000000e+00,-9.999999909092009975e-01,0.000000000000000000e+00 +3.774203390147222592e+01,2.540699999999999932e+02,0.000000000000000000e+00,1.051314230471149713e+01,0.000000000000000000e+00,-9.872318121308583105e-01,0.000000000000000000e+00,-9.999999908314127772e-01,0.000000000000000000e+00 +3.774298509186898798e+01,2.540800000000000125e+02,0.000000000000000000e+00,1.051220325929242350e+01,0.000000000000000000e+00,-9.881830025188960143e-01,0.000000000000000000e+00,-9.999999896350608708e-01,0.000000000000000000e+00 +3.774393636723470991e+01,2.540900000000000034e+02,0.000000000000000000e+00,1.051126322514530465e+01,0.000000000000000000e+00,-9.891342778747554965e-01,0.000000000000000000e+00,-9.999999866260846915e-01,0.000000000000000000e+00 +3.774488772767406175e+01,2.540999999999999943e+02,0.000000000000000000e+00,1.051032220192412936e+01,0.000000000000000000e+00,-9.900856383013822981e-01,0.000000000000000000e+00,-9.999999869953306586e-01,0.000000000000000000e+00 +3.774583917329179883e+01,2.541100000000000136e+02,0.000000000000000000e+00,1.050938018928238549e+01,0.000000000000000000e+00,-9.910370839067437210e-01,0.000000000000000000e+00,-9.999999802345329591e-01,0.000000000000000000e+00 +3.774679070419275462e+01,2.541200000000000045e+02,0.000000000000000000e+00,1.050843718687305461e+01,0.000000000000000000e+00,-9.919886147888925532e-01,0.000000000000000000e+00,-9.999999813409510274e-01,0.000000000000000000e+00 +3.774774232048185496e+01,2.541299999999999955e+02,0.000000000000000000e+00,1.050749319434862095e+01,0.000000000000000000e+00,-9.929402310602351012e-01,0.000000000000000000e+00,-9.999999739205462923e-01,0.000000000000000000e+00 +3.774869402226410386e+01,2.541400000000000148e+02,0.000000000000000000e+00,1.050654821136105710e+01,0.000000000000000000e+00,-9.938919328176613055e-01,0.000000000000000000e+00,-9.999999690419977272e-01,0.000000000000000000e+00 +3.774964580964458349e+01,2.541500000000000057e+02,0.000000000000000000e+00,1.050560223756183831e+01,0.000000000000000000e+00,-9.948437201686779474e-01,0.000000000000000000e+00,-9.999999601193821919e-01,0.000000000000000000e+00 +3.775059768272847549e+01,2.541599999999999966e+02,0.000000000000000000e+00,1.050465527260193177e+01,0.000000000000000000e+00,-9.957955932146076439e-01,0.000000000000000000e+00,-9.999999484120328797e-01,0.000000000000000000e+00 +3.775154964162103255e+01,2.541700000000000159e+02,0.000000000000000000e+00,1.050370731613180197e+01,0.000000000000000000e+00,-9.967475520580550974e-01,0.000000000000000000e+00,-9.999999292965213726e-01,0.000000000000000000e+00 +3.775250168642759974e+01,2.541800000000000068e+02,0.000000000000000000e+00,1.050275836780140892e+01,0.000000000000000000e+00,-9.976995967973070201e-01,0.000000000000000000e+00,-9.999998863977156427e-01,0.000000000000000000e+00 +3.775345381725360028e+01,2.541899999999999977e+02,0.000000000000000000e+00,1.050180842726021169e+01,0.000000000000000000e+00,-9.986517275151415296e-01,0.000000000000000000e+00,-9.999997661332294951e-01,0.000000000000000000e+00 +3.775440603420454266e+01,2.542000000000000171e+02,0.000000000000000000e+00,1.050085749415718261e+01,0.000000000000000000e+00,-9.996039442433932720e-01,0.000000000000000000e+00,-4.159027620156162675e-01,0.000000000000000000e+00 +3.775535833738602776e+01,2.542100000000000080e+02,0.000000000000000000e+00,1.049990556814085529e+01,0.000000000000000000e+00,-1.000000009766848885e+00,0.000000000000000000e+00,1.450160272616598923e-10,0.000000000000000000e+00 +3.775631072690373458e+01,2.542199999999999989e+02,0.000000000000000000e+00,1.049895317861384747e+01,0.000000000000000000e+00,-1.000000009766710773e+00,0.000000000000000000e+00,-6.804877623250731220e-10,0.000000000000000000e+00 +3.775726320281536630e+01,2.542300000000000182e+02,0.000000000000000000e+00,1.049800070269291119e+01,0.000000000000000000e+00,-1.000000009767358922e+00,0.000000000000000000e+00,-1.494186652279107120e-09,0.000000000000000000e+00 +3.775821576514444189e+01,2.542400000000000091e+02,0.000000000000000000e+00,1.049704814035453104e+01,0.000000000000000000e+00,-1.000000009768782228e+00,0.000000000000000000e+00,-3.307423515322555754e-10,0.000000000000000000e+00 +3.775916841391448742e+01,2.542500000000000000e+02,0.000000000000000000e+00,1.049609549157518096e+01,0.000000000000000000e+00,-1.000000009769097309e+00,0.000000000000000000e+00,8.583604870320591418e-10,0.000000000000000000e+00 +3.776012114914903606e+01,2.542600000000000193e+02,0.000000000000000000e+00,1.049514275633132598e+01,0.000000000000000000e+00,-1.000000009768279519e+00,0.000000000000000000e+00,-1.831919442974351237e-09,0.000000000000000000e+00 +3.776107397087163520e+01,2.542700000000000102e+02,0.000000000000000000e+00,1.049418993459942051e+01,0.000000000000000000e+00,-1.000000009770025011e+00,0.000000000000000000e+00,-5.666993523544448303e-10,0.000000000000000000e+00 +3.776202687910583933e+01,2.542800000000000011e+02,0.000000000000000000e+00,1.049323702635590472e+01,0.000000000000000000e+00,-1.000000009770565024e+00,0.000000000000000000e+00,7.465213210365710549e-10,0.000000000000000000e+00 +3.776297987387522426e+01,2.542899999999999920e+02,0.000000000000000000e+00,1.049228403157721168e+01,0.000000000000000000e+00,-1.000000009769853593e+00,0.000000000000000000e+00,-1.794610324684403888e-09,0.000000000000000000e+00 +3.776393295520335869e+01,2.543000000000000114e+02,0.000000000000000000e+00,1.049133095023976381e+01,0.000000000000000000e+00,-1.000000009771564002e+00,0.000000000000000000e+00,1.594106573243674220e-09,0.000000000000000000e+00 +3.776488612311383974e+01,2.543100000000000023e+02,0.000000000000000000e+00,1.049037778231996931e+01,0.000000000000000000e+00,-1.000000009770044551e+00,0.000000000000000000e+00,-2.765848567671087830e-09,0.000000000000000000e+00 +3.776583937763026455e+01,2.543199999999999932e+02,0.000000000000000000e+00,1.048942452779423107e+01,0.000000000000000000e+00,-1.000000009772681109e+00,0.000000000000000000e+00,7.725691455172314536e-10,0.000000000000000000e+00 +3.776679271877624444e+01,2.543300000000000125e+02,0.000000000000000000e+00,1.048847118663893418e+01,0.000000000000000000e+00,-1.000000009771944587e+00,0.000000000000000000e+00,-1.465814972705491620e-09,0.000000000000000000e+00 +3.776774614657540496e+01,2.543400000000000034e+02,0.000000000000000000e+00,1.048751775883046022e+01,0.000000000000000000e+00,-1.000000009773342136e+00,0.000000000000000000e+00,2.978403127139407773e-10,0.000000000000000000e+00 +3.776869966105137166e+01,2.543499999999999943e+02,0.000000000000000000e+00,1.048656424434517476e+01,0.000000000000000000e+00,-1.000000009773058141e+00,0.000000000000000000e+00,2.090979543161612275e-10,0.000000000000000000e+00 +3.776965326222779140e+01,2.543600000000000136e+02,0.000000000000000000e+00,1.048561064315943625e+01,0.000000000000000000e+00,-1.000000009772858744e+00,0.000000000000000000e+00,2.288692627022853688e-10,0.000000000000000000e+00 +3.777060695012831815e+01,2.543700000000000045e+02,0.000000000000000000e+00,1.048465695524959074e+01,0.000000000000000000e+00,-1.000000009772640475e+00,0.000000000000000000e+00,-1.586806726172200969e-09,0.000000000000000000e+00 +3.777156072477661297e+01,2.543799999999999955e+02,0.000000000000000000e+00,1.048370318059197359e+01,0.000000000000000000e+00,-1.000000009774153931e+00,0.000000000000000000e+00,-1.325244851793308089e-09,0.000000000000000000e+00 +3.777251458619635827e+01,2.543900000000000148e+02,0.000000000000000000e+00,1.048274931916290775e+01,0.000000000000000000e+00,-1.000000009775418031e+00,0.000000000000000000e+00,1.019039886236310588e-09,0.000000000000000000e+00 +3.777346853441123642e+01,2.544000000000000057e+02,0.000000000000000000e+00,1.048179537093870728e+01,0.000000000000000000e+00,-1.000000009774445919e+00,0.000000000000000000e+00,-2.352795056666398748e-09,0.000000000000000000e+00 +3.777442256944494403e+01,2.544099999999999966e+02,0.000000000000000000e+00,1.048084133589567735e+01,0.000000000000000000e+00,-1.000000009776690568e+00,0.000000000000000000e+00,2.228074945650808898e-09,0.000000000000000000e+00 +3.777537669132118481e+01,2.544200000000000159e+02,0.000000000000000000e+00,1.047988721401010714e+01,0.000000000000000000e+00,-1.000000009774564713e+00,0.000000000000000000e+00,-2.793333700278950791e-09,0.000000000000000000e+00 +3.777633090006368377e+01,2.544300000000000068e+02,0.000000000000000000e+00,1.047893300525828231e+01,0.000000000000000000e+00,-1.000000009777230137e+00,0.000000000000000000e+00,2.101789894048923536e-09,0.000000000000000000e+00 +3.777728519569616594e+01,2.544399999999999977e+02,0.000000000000000000e+00,1.047797870961646893e+01,0.000000000000000000e+00,-1.000000009775224408e+00,0.000000000000000000e+00,-2.586690135275924053e-09,0.000000000000000000e+00 +3.777823957824237766e+01,2.544500000000000171e+02,0.000000000000000000e+00,1.047702432706093134e+01,0.000000000000000000e+00,-1.000000009777693100e+00,0.000000000000000000e+00,7.027953883753894956e-10,0.000000000000000000e+00 +3.777919404772606526e+01,2.544600000000000080e+02,0.000000000000000000e+00,1.047606985756791431e+01,0.000000000000000000e+00,-1.000000009777022303e+00,0.000000000000000000e+00,-1.673435757861687137e-09,0.000000000000000000e+00 +3.778014860417098930e+01,2.544699999999999989e+02,0.000000000000000000e+00,1.047511530111365907e+01,0.000000000000000000e+00,-1.000000009778619692e+00,0.000000000000000000e+00,1.990774475540564518e-09,0.000000000000000000e+00 +3.778110324760092453e+01,2.544800000000000182e+02,0.000000000000000000e+00,1.047416065767439086e+01,0.000000000000000000e+00,-1.000000009776719212e+00,0.000000000000000000e+00,-1.942450418577135461e-09,0.000000000000000000e+00 +3.778205797803965282e+01,2.544900000000000091e+02,0.000000000000000000e+00,1.047320592722632959e+01,0.000000000000000000e+00,-1.000000009778573729e+00,0.000000000000000000e+00,-1.769952413790844936e-09,0.000000000000000000e+00 +3.778301279551097025e+01,2.545000000000000000e+02,0.000000000000000000e+00,1.047225110974567741e+01,0.000000000000000000e+00,-1.000000009780263710e+00,0.000000000000000000e+00,5.645845056903576366e-10,0.000000000000000000e+00 +3.778396770003867999e+01,2.545100000000000193e+02,0.000000000000000000e+00,1.047129620520862936e+01,0.000000000000000000e+00,-1.000000009779724586e+00,0.000000000000000000e+00,1.172777831716594374e-09,0.000000000000000000e+00 +3.778492269164659945e+01,2.545200000000000102e+02,0.000000000000000000e+00,1.047034121359137160e+01,0.000000000000000000e+00,-1.000000009778604593e+00,0.000000000000000000e+00,-1.884549980010678059e-09,0.000000000000000000e+00 +3.778587777035855311e+01,2.545300000000000011e+02,0.000000000000000000e+00,1.046938613487007785e+01,0.000000000000000000e+00,-1.000000009780404486e+00,0.000000000000000000e+00,-8.092178734982522209e-10,0.000000000000000000e+00 +3.778683293619837968e+01,2.545399999999999920e+02,0.000000000000000000e+00,1.046843096902090764e+01,0.000000000000000000e+00,-1.000000009781177424e+00,0.000000000000000000e+00,5.104511126667857434e-10,0.000000000000000000e+00 +3.778778818918993210e+01,2.545500000000000114e+02,0.000000000000000000e+00,1.046747571602001337e+01,0.000000000000000000e+00,-1.000000009780689814e+00,0.000000000000000000e+00,1.350387222267019318e-10,0.000000000000000000e+00 +3.778874352935706327e+01,2.545600000000000023e+02,0.000000000000000000e+00,1.046652037584353678e+01,0.000000000000000000e+00,-1.000000009780560806e+00,0.000000000000000000e+00,-1.925694888754482164e-09,0.000000000000000000e+00 +3.778969895672364743e+01,2.545699999999999932e+02,0.000000000000000000e+00,1.046556494846760721e+01,0.000000000000000000e+00,-1.000000009782400667e+00,0.000000000000000000e+00,1.728923742319010644e-10,0.000000000000000000e+00 +3.779065447131356592e+01,2.545800000000000125e+02,0.000000000000000000e+00,1.046460943386834153e+01,0.000000000000000000e+00,-1.000000009782235466e+00,0.000000000000000000e+00,6.004208414259924775e-10,0.000000000000000000e+00 +3.779161007315070719e+01,2.545900000000000034e+02,0.000000000000000000e+00,1.046365383202184951e+01,0.000000000000000000e+00,-1.000000009781661703e+00,0.000000000000000000e+00,-6.345199613566981357e-10,0.000000000000000000e+00 +3.779256576225898101e+01,2.545999999999999943e+02,0.000000000000000000e+00,1.046269814290422850e+01,0.000000000000000000e+00,-1.000000009782268107e+00,0.000000000000000000e+00,-1.578836985131662762e-09,0.000000000000000000e+00 +3.779352153866229713e+01,2.546100000000000136e+02,0.000000000000000000e+00,1.046174236649156342e+01,0.000000000000000000e+00,-1.000000009783777122e+00,0.000000000000000000e+00,-2.801505981417668205e-10,0.000000000000000000e+00 +3.779447740238457953e+01,2.546200000000000045e+02,0.000000000000000000e+00,1.046078650275992850e+01,0.000000000000000000e+00,-1.000000009784044908e+00,0.000000000000000000e+00,1.322580230816217768e-09,0.000000000000000000e+00 +3.779543335344976640e+01,2.546299999999999955e+02,0.000000000000000000e+00,1.045983055168538911e+01,0.000000000000000000e+00,-1.000000009782780586e+00,0.000000000000000000e+00,-2.592196874648081012e-09,0.000000000000000000e+00 +3.779638939188180302e+01,2.546400000000000148e+02,0.000000000000000000e+00,1.045887451324399997e+01,0.000000000000000000e+00,-1.000000009785258825e+00,0.000000000000000000e+00,1.587549340265858868e-09,0.000000000000000000e+00 +3.779734551770464890e+01,2.546500000000000057e+02,0.000000000000000000e+00,1.045791838741179980e+01,0.000000000000000000e+00,-1.000000009783740929e+00,0.000000000000000000e+00,-1.677270422823516448e-09,0.000000000000000000e+00 +3.779830173094227064e+01,2.546599999999999966e+02,0.000000000000000000e+00,1.045696217416482376e+01,0.000000000000000000e+00,-1.000000009785344757e+00,0.000000000000000000e+00,-7.197927307503116640e-10,0.000000000000000000e+00 +3.779925803161864906e+01,2.546700000000000159e+02,0.000000000000000000e+00,1.045600587347908927e+01,0.000000000000000000e+00,-1.000000009786033095e+00,0.000000000000000000e+00,5.804249233176177896e-10,0.000000000000000000e+00 +3.780021441975777208e+01,2.546800000000000068e+02,0.000000000000000000e+00,1.045504948533060663e+01,0.000000000000000000e+00,-1.000000009785477983e+00,0.000000000000000000e+00,2.894894703555032195e-10,0.000000000000000000e+00 +3.780117089538364183e+01,2.546899999999999977e+02,0.000000000000000000e+00,1.045409300969537547e+01,0.000000000000000000e+00,-1.000000009785201094e+00,0.000000000000000000e+00,-1.583805899877422658e-09,0.000000000000000000e+00 +3.780212745852027467e+01,2.547000000000000171e+02,0.000000000000000000e+00,1.045313644654938301e+01,0.000000000000000000e+00,-1.000000009786716104e+00,0.000000000000000000e+00,-1.148925963488244090e-09,0.000000000000000000e+00 +3.780308410919169404e+01,2.547100000000000080e+02,0.000000000000000000e+00,1.045217979586860402e+01,0.000000000000000000e+00,-1.000000009787815225e+00,0.000000000000000000e+00,1.599994081951509266e-09,0.000000000000000000e+00 +3.780404084742193049e+01,2.547199999999999989e+02,0.000000000000000000e+00,1.045122305762900439e+01,0.000000000000000000e+00,-1.000000009786284449e+00,0.000000000000000000e+00,-1.091395907871311030e-09,0.000000000000000000e+00 +3.780499767323502880e+01,2.547300000000000182e+02,0.000000000000000000e+00,1.045026623180654113e+01,0.000000000000000000e+00,-1.000000009787328725e+00,0.000000000000000000e+00,-1.452122113191241748e-09,0.000000000000000000e+00 +3.780595458665504793e+01,2.547400000000000091e+02,0.000000000000000000e+00,1.044930931837715526e+01,0.000000000000000000e+00,-1.000000009788718280e+00,0.000000000000000000e+00,5.234399985067664278e-10,0.000000000000000000e+00 +3.780691158770605398e+01,2.547500000000000000e+02,0.000000000000000000e+00,1.044835231731677894e+01,0.000000000000000000e+00,-1.000000009788217348e+00,0.000000000000000000e+00,-9.755601103459866585e-10,0.000000000000000000e+00 +3.780786867641212723e+01,2.547600000000000193e+02,0.000000000000000000e+00,1.044739522860133540e+01,0.000000000000000000e+00,-1.000000009789151045e+00,0.000000000000000000e+00,1.815465890043422878e-09,0.000000000000000000e+00 +3.780882585279736219e+01,2.547700000000000102e+02,0.000000000000000000e+00,1.044643805220673372e+01,0.000000000000000000e+00,-1.000000009787413324e+00,0.000000000000000000e+00,-2.728748277251114114e-09,0.000000000000000000e+00 +3.780978311688585336e+01,2.547800000000000011e+02,0.000000000000000000e+00,1.044548078810887581e+01,0.000000000000000000e+00,-1.000000009790025457e+00,0.000000000000000000e+00,9.096540332312443914e-10,0.000000000000000000e+00 +3.781074046870170946e+01,2.547899999999999920e+02,0.000000000000000000e+00,1.044452343628364588e+01,0.000000000000000000e+00,-1.000000009789154598e+00,0.000000000000000000e+00,-8.325748787342997961e-10,0.000000000000000000e+00 +3.781169790826906052e+01,2.548000000000000114e+02,0.000000000000000000e+00,1.044356599670692454e+01,0.000000000000000000e+00,-1.000000009789951738e+00,0.000000000000000000e+00,-2.130871655653175452e-09,0.000000000000000000e+00 +3.781265543561203657e+01,2.548100000000000023e+02,0.000000000000000000e+00,1.044260846935457643e+01,0.000000000000000000e+00,-1.000000009791992106e+00,0.000000000000000000e+00,2.832786176079179653e-09,0.000000000000000000e+00 +3.781361305075478185e+01,2.548199999999999932e+02,0.000000000000000000e+00,1.044165085420245553e+01,0.000000000000000000e+00,-1.000000009789279387e+00,0.000000000000000000e+00,-3.367407175468272720e-09,0.000000000000000000e+00 +3.781457075372145482e+01,2.548300000000000125e+02,0.000000000000000000e+00,1.044069315122641051e+01,0.000000000000000000e+00,-1.000000009792504363e+00,0.000000000000000000e+00,2.518368840171369967e-09,0.000000000000000000e+00 +3.781552854453621393e+01,2.548400000000000034e+02,0.000000000000000000e+00,1.043973536040226868e+01,0.000000000000000000e+00,-1.000000009790092292e+00,0.000000000000000000e+00,-2.740442349284402355e-09,0.000000000000000000e+00 +3.781648642322324605e+01,2.548499999999999943e+02,0.000000000000000000e+00,1.043877748170585740e+01,0.000000000000000000e+00,-1.000000009792717304e+00,0.000000000000000000e+00,2.264563114723699502e-10,0.000000000000000000e+00 +3.781744438980673806e+01,2.548600000000000136e+02,0.000000000000000000e+00,1.043781951511298267e+01,0.000000000000000000e+00,-1.000000009792500366e+00,0.000000000000000000e+00,-1.895847115598852029e-10,0.000000000000000000e+00 +3.781840244431089104e+01,2.548700000000000045e+02,0.000000000000000000e+00,1.043686146059944697e+01,0.000000000000000000e+00,-1.000000009792681999e+00,0.000000000000000000e+00,-1.091518375227438060e-10,0.000000000000000000e+00 +3.781936058675991319e+01,2.548799999999999955e+02,0.000000000000000000e+00,1.043590331814103855e+01,0.000000000000000000e+00,-1.000000009792786582e+00,0.000000000000000000e+00,4.752651096119835190e-10,0.000000000000000000e+00 +3.782031881717803401e+01,2.548900000000000148e+02,0.000000000000000000e+00,1.043494508771353502e+01,0.000000000000000000e+00,-1.000000009792331168e+00,0.000000000000000000e+00,-3.623824377726230085e-10,0.000000000000000000e+00 +3.782127713558948301e+01,2.549000000000000057e+02,0.000000000000000000e+00,1.043398676929270330e+01,0.000000000000000000e+00,-1.000000009792678446e+00,0.000000000000000000e+00,-2.614057253279113437e-09,0.000000000000000000e+00 +3.782223554201850391e+01,2.549099999999999966e+02,0.000000000000000000e+00,1.043302836285429791e+01,0.000000000000000000e+00,-1.000000009795183775e+00,0.000000000000000000e+00,1.462699763156428254e-09,0.000000000000000000e+00 +3.782319403648935463e+01,2.549200000000000159e+02,0.000000000000000000e+00,1.043206986837406092e+01,0.000000000000000000e+00,-1.000000009793781786e+00,0.000000000000000000e+00,-1.659921370950468258e-09,0.000000000000000000e+00 +3.782415261902630021e+01,2.549300000000000068e+02,0.000000000000000000e+00,1.043111128582772906e+01,0.000000000000000000e+00,-1.000000009795372957e+00,0.000000000000000000e+00,1.560173448685544105e-09,0.000000000000000000e+00 +3.782511128965361991e+01,2.549399999999999977e+02,0.000000000000000000e+00,1.043015261519102133e+01,0.000000000000000000e+00,-1.000000009793877265e+00,0.000000000000000000e+00,-2.400723220420844505e-09,0.000000000000000000e+00 +3.782607004839560005e+01,2.549500000000000171e+02,0.000000000000000000e+00,1.042919385643965136e+01,0.000000000000000000e+00,-1.000000009796178979e+00,0.000000000000000000e+00,1.926469288354081609e-09,0.000000000000000000e+00 +3.782702889527654122e+01,2.549600000000000080e+02,0.000000000000000000e+00,1.042823500954931504e+01,0.000000000000000000e+00,-1.000000009794331790e+00,0.000000000000000000e+00,-2.840927833695173459e-09,0.000000000000000000e+00 +3.782798783032075818e+01,2.549699999999999989e+02,0.000000000000000000e+00,1.042727607449570471e+01,0.000000000000000000e+00,-1.000000009797056055e+00,0.000000000000000000e+00,2.624184137286140937e-09,0.000000000000000000e+00 +3.782894685355257280e+01,2.549800000000000182e+02,0.000000000000000000e+00,1.042631705125449315e+01,0.000000000000000000e+00,-1.000000009794539402e+00,0.000000000000000000e+00,-2.918192941316075061e-09,0.000000000000000000e+00 +3.782990596499632119e+01,2.549900000000000091e+02,0.000000000000000000e+00,1.042535793980135139e+01,0.000000000000000000e+00,-1.000000009797338274e+00,0.000000000000000000e+00,-1.460698420000439879e-10,0.000000000000000000e+00 +3.783086516467634652e+01,2.550000000000000000e+02,0.000000000000000000e+00,1.042439874011192913e+01,0.000000000000000000e+00,-1.000000009797478384e+00,0.000000000000000000e+00,1.291129340604698417e-09,0.000000000000000000e+00 +3.783182445261700622e+01,2.550100000000000193e+02,0.000000000000000000e+00,1.042343945216187251e+01,0.000000000000000000e+00,-1.000000009796239819e+00,0.000000000000000000e+00,-2.457965541812414272e-09,0.000000000000000000e+00 +3.783278382884266478e+01,2.550200000000000102e+02,0.000000000000000000e+00,1.042248007592681525e+01,0.000000000000000000e+00,-1.000000009798597933e+00,0.000000000000000000e+00,2.125180798833968720e-09,0.000000000000000000e+00 +3.783374329337770092e+01,2.550300000000000011e+02,0.000000000000000000e+00,1.042152061138237507e+01,0.000000000000000000e+00,-1.000000009796558897e+00,0.000000000000000000e+00,-2.319827532939651211e-09,0.000000000000000000e+00 +3.783470284624650759e+01,2.550399999999999920e+02,0.000000000000000000e+00,1.042056105850416614e+01,0.000000000000000000e+00,-1.000000009798784895e+00,0.000000000000000000e+00,-3.484627021179081601e-10,0.000000000000000000e+00 +3.783566248747348482e+01,2.550500000000000114e+02,0.000000000000000000e+00,1.041960141726778311e+01,0.000000000000000000e+00,-1.000000009799119294e+00,0.000000000000000000e+00,3.287648734126573751e-10,0.000000000000000000e+00 +3.783662221708304685e+01,2.550600000000000023e+02,0.000000000000000000e+00,1.041864168764881526e+01,0.000000000000000000e+00,-1.000000009798803768e+00,0.000000000000000000e+00,-2.789964231931667605e-10,0.000000000000000000e+00 +3.783758203509961504e+01,2.550699999999999932e+02,0.000000000000000000e+00,1.041768186962283949e+01,0.000000000000000000e+00,-1.000000009799071554e+00,0.000000000000000000e+00,-2.359453856074565894e-10,0.000000000000000000e+00 +3.783854194154762496e+01,2.550800000000000125e+02,0.000000000000000000e+00,1.041672196316542021e+01,0.000000000000000000e+00,-1.000000009799298040e+00,0.000000000000000000e+00,4.658335502630874074e-10,0.000000000000000000e+00 +3.783950193645152638e+01,2.550900000000000034e+02,0.000000000000000000e+00,1.041576196825211120e+01,0.000000000000000000e+00,-1.000000009798850842e+00,0.000000000000000000e+00,-2.020199136702642606e-09,0.000000000000000000e+00 +3.784046201983577618e+01,2.550999999999999943e+02,0.000000000000000000e+00,1.041480188485845559e+01,0.000000000000000000e+00,-1.000000009800790401e+00,0.000000000000000000e+00,2.266299558497949842e-11,0.000000000000000000e+00 +3.784142219172483834e+01,2.551100000000000136e+02,0.000000000000000000e+00,1.041384171295998229e+01,0.000000000000000000e+00,-1.000000009800768641e+00,0.000000000000000000e+00,8.199548310140712727e-10,0.000000000000000000e+00 +3.784238245214319818e+01,2.551200000000000045e+02,0.000000000000000000e+00,1.041288145253221309e+01,0.000000000000000000e+00,-1.000000009799981271e+00,0.000000000000000000e+00,-1.545192568281290109e-09,0.000000000000000000e+00 +3.784334280111534099e+01,2.551299999999999955e+02,0.000000000000000000e+00,1.041192110355065736e+01,0.000000000000000000e+00,-1.000000009801465195e+00,0.000000000000000000e+00,6.392433660477606836e-10,0.000000000000000000e+00 +3.784430323866577339e+01,2.551400000000000148e+02,0.000000000000000000e+00,1.041096066599081027e+01,0.000000000000000000e+00,-1.000000009800851242e+00,0.000000000000000000e+00,-3.222506521270138806e-10,0.000000000000000000e+00 +3.784526376481900911e+01,2.551500000000000057e+02,0.000000000000000000e+00,1.041000013982815986e+01,0.000000000000000000e+00,-1.000000009801160772e+00,0.000000000000000000e+00,-2.495016227162087135e-09,0.000000000000000000e+00 +3.784622437959957608e+01,2.551599999999999966e+02,0.000000000000000000e+00,1.040903952503817997e+01,0.000000000000000000e+00,-1.000000009803557521e+00,0.000000000000000000e+00,1.827753161354238008e-09,0.000000000000000000e+00 +3.784718508303200224e+01,2.551700000000000159e+02,0.000000000000000000e+00,1.040807882159633202e+01,0.000000000000000000e+00,-1.000000009801801593e+00,0.000000000000000000e+00,-8.199632896893357813e-10,0.000000000000000000e+00 +3.784814587514084394e+01,2.551800000000000068e+02,0.000000000000000000e+00,1.040711802947807207e+01,0.000000000000000000e+00,-1.000000009802589407e+00,0.000000000000000000e+00,-8.057914462076273337e-10,0.000000000000000000e+00 +3.784910675595065754e+01,2.551899999999999977e+02,0.000000000000000000e+00,1.040615714865883845e+01,0.000000000000000000e+00,-1.000000009803363676e+00,0.000000000000000000e+00,-4.736793658366570793e-11,0.000000000000000000e+00 +3.785006772548601361e+01,2.552000000000000171e+02,0.000000000000000000e+00,1.040519617911406058e+01,0.000000000000000000e+00,-1.000000009803409196e+00,0.000000000000000000e+00,1.462494388122337332e-09,0.000000000000000000e+00 +3.785102878377149693e+01,2.552100000000000080e+02,0.000000000000000000e+00,1.040423512081915725e+01,0.000000000000000000e+00,-1.000000009802003653e+00,0.000000000000000000e+00,-2.036445070130918386e-09,0.000000000000000000e+00 +3.785198993083169938e+01,2.552199999999999989e+02,0.000000000000000000e+00,1.040327397374953655e+01,0.000000000000000000e+00,-1.000000009803960976e+00,0.000000000000000000e+00,-9.209933556539740541e-10,0.000000000000000000e+00 +3.785295116669121995e+01,2.552300000000000182e+02,0.000000000000000000e+00,1.040231273788059063e+01,0.000000000000000000e+00,-1.000000009804846268e+00,0.000000000000000000e+00,9.689516286084182062e-10,0.000000000000000000e+00 +3.785391249137467895e+01,2.552400000000000091e+02,0.000000000000000000e+00,1.040135141318770451e+01,0.000000000000000000e+00,-1.000000009803914791e+00,0.000000000000000000e+00,-2.123644066026851810e-09,0.000000000000000000e+00 +3.785487390490670379e+01,2.552500000000000000e+02,0.000000000000000000e+00,1.040038999964625255e+01,0.000000000000000000e+00,-1.000000009805956491e+00,0.000000000000000000e+00,1.340577958596134033e-09,0.000000000000000000e+00 +3.785583540731193608e+01,2.552600000000000193e+02,0.000000000000000000e+00,1.039942849723159313e+01,0.000000000000000000e+00,-1.000000009804667522e+00,0.000000000000000000e+00,-1.609468483503388941e-10,0.000000000000000000e+00 +3.785679699861502456e+01,2.552700000000000102e+02,0.000000000000000000e+00,1.039846690591907930e+01,0.000000000000000000e+00,-1.000000009804822287e+00,0.000000000000000000e+00,-8.547634707969915219e-10,0.000000000000000000e+00 +3.785775867884062507e+01,2.552800000000000011e+02,0.000000000000000000e+00,1.039750522568404811e+01,0.000000000000000000e+00,-1.000000009805644297e+00,0.000000000000000000e+00,-7.339388899396578656e-10,0.000000000000000000e+00 +3.785872044801341474e+01,2.552899999999999920e+02,0.000000000000000000e+00,1.039654345650182599e+01,0.000000000000000000e+00,-1.000000009806350176e+00,0.000000000000000000e+00,2.096114717021459458e-10,0.000000000000000000e+00 +3.785968230615807784e+01,2.553000000000000114e+02,0.000000000000000000e+00,1.039558159834772866e+01,0.000000000000000000e+00,-1.000000009806148560e+00,0.000000000000000000e+00,6.347777724670378682e-11,0.000000000000000000e+00 +3.786064425329931282e+01,2.553100000000000023e+02,0.000000000000000000e+00,1.039461965119706122e+01,0.000000000000000000e+00,-1.000000009806087498e+00,0.000000000000000000e+00,-1.163728497595952382e-09,0.000000000000000000e+00 +3.786160628946182527e+01,2.553199999999999932e+02,0.000000000000000000e+00,1.039365761502511631e+01,0.000000000000000000e+00,-1.000000009807207046e+00,0.000000000000000000e+00,3.743341781341666366e-10,0.000000000000000000e+00 +3.786256841467033496e+01,2.553300000000000125e+02,0.000000000000000000e+00,1.039269548980717417e+01,0.000000000000000000e+00,-1.000000009806846890e+00,0.000000000000000000e+00,-1.070976635557554433e-09,0.000000000000000000e+00 +3.786353062894956878e+01,2.553400000000000034e+02,0.000000000000000000e+00,1.039173327551850612e+01,0.000000000000000000e+00,-1.000000009807877399e+00,0.000000000000000000e+00,2.637390557928587588e-10,0.000000000000000000e+00 +3.786449293232426783e+01,2.553499999999999943e+02,0.000000000000000000e+00,1.039077097213436929e+01,0.000000000000000000e+00,-1.000000009807623602e+00,0.000000000000000000e+00,-1.367947557313279841e-09,0.000000000000000000e+00 +3.786545532481918741e+01,2.553600000000000136e+02,0.000000000000000000e+00,1.038980857963001192e+01,0.000000000000000000e+00,-1.000000009808940105e+00,0.000000000000000000e+00,1.713640299205548423e-09,0.000000000000000000e+00 +3.786641780645908995e+01,2.553700000000000045e+02,0.000000000000000000e+00,1.038884609798066805e+01,0.000000000000000000e+00,-1.000000009807290757e+00,0.000000000000000000e+00,-1.989373304955528150e-09,0.000000000000000000e+00 +3.786738037726875206e+01,2.553799999999999955e+02,0.000000000000000000e+00,1.038788352716156460e+01,0.000000000000000000e+00,-1.000000009809205670e+00,0.000000000000000000e+00,9.526148529376779479e-10,0.000000000000000000e+00 +3.786834303727296458e+01,2.553900000000000148e+02,0.000000000000000000e+00,1.038692086714791074e+01,0.000000000000000000e+00,-1.000000009808288626e+00,0.000000000000000000e+00,-9.548329324980363603e-10,0.000000000000000000e+00 +3.786930578649652546e+01,2.554000000000000057e+02,0.000000000000000000e+00,1.038595811791491030e+01,0.000000000000000000e+00,-1.000000009809207890e+00,0.000000000000000000e+00,-1.952152561116576320e-09,0.000000000000000000e+00 +3.787026862496423973e+01,2.554099999999999966e+02,0.000000000000000000e+00,1.038499527943775114e+01,0.000000000000000000e+00,-1.000000009811087498e+00,0.000000000000000000e+00,1.798857688914832071e-09,0.000000000000000000e+00 +3.787123155270093378e+01,2.554200000000000159e+02,0.000000000000000000e+00,1.038403235169161043e+01,0.000000000000000000e+00,-1.000000009809355328e+00,0.000000000000000000e+00,-1.188367243290379318e-09,0.000000000000000000e+00 +3.787219456973144105e+01,2.554300000000000068e+02,0.000000000000000000e+00,1.038306933465165827e+01,0.000000000000000000e+00,-1.000000009810499746e+00,0.000000000000000000e+00,5.883647556277578193e-10,0.000000000000000000e+00 +3.787315767608060213e+01,2.554399999999999977e+02,0.000000000000000000e+00,1.038210622829304697e+01,0.000000000000000000e+00,-1.000000009809933088e+00,0.000000000000000000e+00,-5.244536287333607886e-10,0.000000000000000000e+00 +3.787412087177327891e+01,2.554500000000000171e+02,0.000000000000000000e+00,1.038114303259092175e+01,0.000000000000000000e+00,-1.000000009810438240e+00,0.000000000000000000e+00,-6.885264411582233208e-10,0.000000000000000000e+00 +3.787508415683433327e+01,2.554600000000000080e+02,0.000000000000000000e+00,1.038017974752041361e+01,0.000000000000000000e+00,-1.000000009811101487e+00,0.000000000000000000e+00,1.041798035812219650e-10,0.000000000000000000e+00 +3.787604753128865553e+01,2.554699999999999989e+02,0.000000000000000000e+00,1.037921637305664291e+01,0.000000000000000000e+00,-1.000000009811001123e+00,0.000000000000000000e+00,-5.300692697669590814e-11,0.000000000000000000e+00 +3.787701099516112890e+01,2.554800000000000182e+02,0.000000000000000000e+00,1.037825290917471932e+01,0.000000000000000000e+00,-1.000000009811052193e+00,0.000000000000000000e+00,-1.151526202994769649e-09,0.000000000000000000e+00 +3.787797454847665790e+01,2.554900000000000091e+02,0.000000000000000000e+00,1.037728935584974010e+01,0.000000000000000000e+00,-1.000000009812161750e+00,0.000000000000000000e+00,6.437993795903411991e-10,0.000000000000000000e+00 +3.787893819126015416e+01,2.555000000000000000e+02,0.000000000000000000e+00,1.037632571305679008e+01,0.000000000000000000e+00,-1.000000009811541357e+00,0.000000000000000000e+00,-2.311379966388431844e-09,0.000000000000000000e+00 +3.787990192353654351e+01,2.555100000000000193e+02,0.000000000000000000e+00,1.037536198077094518e+01,0.000000000000000000e+00,-1.000000009813768909e+00,0.000000000000000000e+00,1.466825099862147952e-09,0.000000000000000000e+00 +3.788086574533076600e+01,2.555200000000000102e+02,0.000000000000000000e+00,1.037439815896726536e+01,0.000000000000000000e+00,-1.000000009812355151e+00,0.000000000000000000e+00,5.120856429426774025e-10,0.000000000000000000e+00 +3.788182965666776880e+01,2.555300000000000011e+02,0.000000000000000000e+00,1.037343424762080524e+01,0.000000000000000000e+00,-1.000000009811861545e+00,0.000000000000000000e+00,-1.342170849147593264e-09,0.000000000000000000e+00 +3.788279365757251327e+01,2.555399999999999920e+02,0.000000000000000000e+00,1.037247024670660345e+01,0.000000000000000000e+00,-1.000000009813155399e+00,0.000000000000000000e+00,-2.648623716730601227e-10,0.000000000000000000e+00 +3.788375774806996787e+01,2.555500000000000114e+02,0.000000000000000000e+00,1.037150615619968619e+01,0.000000000000000000e+00,-1.000000009813410751e+00,0.000000000000000000e+00,-1.981677277254030448e-09,0.000000000000000000e+00 +3.788472192818512241e+01,2.555600000000000023e+02,0.000000000000000000e+00,1.037054197607507078e+01,0.000000000000000000e+00,-1.000000009815321445e+00,0.000000000000000000e+00,3.068608531124370561e-09,0.000000000000000000e+00 +3.788568619794296666e+01,2.555699999999999932e+02,0.000000000000000000e+00,1.036957770630776032e+01,0.000000000000000000e+00,-1.000000009812362478e+00,0.000000000000000000e+00,-2.299745774494475126e-09,0.000000000000000000e+00 +3.788665055736851173e+01,2.555800000000000125e+02,0.000000000000000000e+00,1.036861334687275260e+01,0.000000000000000000e+00,-1.000000009814580260e+00,0.000000000000000000e+00,-8.854625240156145798e-10,0.000000000000000000e+00 +3.788761500648677583e+01,2.555900000000000034e+02,0.000000000000000000e+00,1.036764889774502407e+01,0.000000000000000000e+00,-1.000000009815434243e+00,0.000000000000000000e+00,1.587744923264798473e-09,0.000000000000000000e+00 +3.788857954532278427e+01,2.555999999999999943e+02,0.000000000000000000e+00,1.036668435889954587e+01,0.000000000000000000e+00,-1.000000009813902802e+00,0.000000000000000000e+00,-2.508804116177957398e-09,0.000000000000000000e+00 +3.788954417390158369e+01,2.556100000000000136e+02,0.000000000000000000e+00,1.036571973031127847e+01,0.000000000000000000e+00,-1.000000009816322866e+00,0.000000000000000000e+00,2.106011710186721358e-09,0.000000000000000000e+00 +3.789050889224822782e+01,2.556200000000000045e+02,0.000000000000000000e+00,1.036475501195516458e+01,0.000000000000000000e+00,-1.000000009814291158e+00,0.000000000000000000e+00,-1.738966501248678315e-09,0.000000000000000000e+00 +3.789147370038777751e+01,2.556299999999999955e+02,0.000000000000000000e+00,1.036379020380614335e+01,0.000000000000000000e+00,-1.000000009815968927e+00,0.000000000000000000e+00,-6.754091563403681245e-10,0.000000000000000000e+00 +3.789243859834531492e+01,2.556400000000000148e+02,0.000000000000000000e+00,1.036282530583913442e+01,0.000000000000000000e+00,-1.000000009816620627e+00,0.000000000000000000e+00,1.486912307198828480e-09,0.000000000000000000e+00 +3.789340358614592930e+01,2.556500000000000057e+02,0.000000000000000000e+00,1.036186031802905028e+01,0.000000000000000000e+00,-1.000000009815185775e+00,0.000000000000000000e+00,-2.873233021539673692e-09,0.000000000000000000e+00 +3.789436866381471702e+01,2.556599999999999966e+02,0.000000000000000000e+00,1.036089524035079279e+01,0.000000000000000000e+00,-1.000000009817958668e+00,0.000000000000000000e+00,1.510791470668763164e-09,0.000000000000000000e+00 +3.789533383137678868e+01,2.556700000000000159e+02,0.000000000000000000e+00,1.035993007277924605e+01,0.000000000000000000e+00,-1.000000009816500501e+00,0.000000000000000000e+00,-6.095971437162229725e-10,0.000000000000000000e+00 +3.789629908885726906e+01,2.556800000000000068e+02,0.000000000000000000e+00,1.035896481528929058e+01,0.000000000000000000e+00,-1.000000009817088920e+00,0.000000000000000000e+00,3.075303558040372378e-10,0.000000000000000000e+00 +3.789726443628129005e+01,2.556899999999999977e+02,0.000000000000000000e+00,1.035799946785578918e+01,0.000000000000000000e+00,-1.000000009816792046e+00,0.000000000000000000e+00,-1.447580914042053425e-09,0.000000000000000000e+00 +3.789822987367400486e+01,2.557000000000000171e+02,0.000000000000000000e+00,1.035703403045359572e+01,0.000000000000000000e+00,-1.000000009818189595e+00,0.000000000000000000e+00,1.755838914763456778e-09,0.000000000000000000e+00 +3.789919540106057383e+01,2.557100000000000080e+02,0.000000000000000000e+00,1.035606850305754989e+01,0.000000000000000000e+00,-1.000000009816494284e+00,0.000000000000000000e+00,-1.507788142663909528e-09,0.000000000000000000e+00 +3.790016101846615726e+01,2.557199999999999989e+02,0.000000000000000000e+00,1.035510288564248427e+01,0.000000000000000000e+00,-1.000000009817950231e+00,0.000000000000000000e+00,-1.701478099608397411e-09,0.000000000000000000e+00 +3.790112672591594389e+01,2.557300000000000182e+02,0.000000000000000000e+00,1.035413717818321366e+01,0.000000000000000000e+00,-1.000000009819593361e+00,0.000000000000000000e+00,1.179888009482349517e-09,0.000000000000000000e+00 +3.790209252343512958e+01,2.557400000000000091e+02,0.000000000000000000e+00,1.035317138065454401e+01,0.000000000000000000e+00,-1.000000009818453828e+00,0.000000000000000000e+00,-4.728767051266657834e-10,0.000000000000000000e+00 +3.790305841104891726e+01,2.557500000000000000e+02,0.000000000000000000e+00,1.035220549303127235e+01,0.000000000000000000e+00,-1.000000009818910574e+00,0.000000000000000000e+00,-9.376198974136898273e-10,0.000000000000000000e+00 +3.790402438878252411e+01,2.557600000000000193e+02,0.000000000000000000e+00,1.035123951528817976e+01,0.000000000000000000e+00,-1.000000009819816293e+00,0.000000000000000000e+00,1.695786736450792518e-09,0.000000000000000000e+00 +3.790499045666118150e+01,2.557700000000000102e+02,0.000000000000000000e+00,1.035027344740003663e+01,0.000000000000000000e+00,-1.000000009818178048e+00,0.000000000000000000e+00,-2.080121074774903869e-09,0.000000000000000000e+00 +3.790595661471012789e+01,2.557800000000000011e+02,0.000000000000000000e+00,1.034930728934160449e+01,0.000000000000000000e+00,-1.000000009820187774e+00,0.000000000000000000e+00,1.064207434552177277e-09,0.000000000000000000e+00 +3.790692286295461599e+01,2.557899999999999920e+02,0.000000000000000000e+00,1.034834104108762709e+01,0.000000000000000000e+00,-1.000000009819159486e+00,0.000000000000000000e+00,-2.182444074533280110e-09,0.000000000000000000e+00 +3.790788920141991269e+01,2.558000000000000114e+02,0.000000000000000000e+00,1.034737470261284287e+01,0.000000000000000000e+00,-1.000000009821268465e+00,0.000000000000000000e+00,1.505143824616455804e-09,0.000000000000000000e+00 +3.790885563013129200e+01,2.558100000000000023e+02,0.000000000000000000e+00,1.034640827389197248e+01,0.000000000000000000e+00,-1.000000009819813851e+00,0.000000000000000000e+00,-1.179696484641896273e-09,0.000000000000000000e+00 +3.790982214911404213e+01,2.558199999999999932e+02,0.000000000000000000e+00,1.034544175489973128e+01,0.000000000000000000e+00,-1.000000009820954050e+00,0.000000000000000000e+00,-7.190078020266312784e-10,0.000000000000000000e+00 +3.791078875839346551e+01,2.558300000000000125e+02,0.000000000000000000e+00,1.034447514561081682e+01,0.000000000000000000e+00,-1.000000009821649050e+00,0.000000000000000000e+00,9.927352624246032791e-10,0.000000000000000000e+00 +3.791175545799487168e+01,2.558400000000000034e+02,0.000000000000000000e+00,1.034350844599991781e+01,0.000000000000000000e+00,-1.000000009820689373e+00,0.000000000000000000e+00,1.623781214226558764e-10,0.000000000000000000e+00 +3.791272224794358436e+01,2.558499999999999943e+02,0.000000000000000000e+00,1.034254165604171227e+01,0.000000000000000000e+00,-1.000000009820532387e+00,0.000000000000000000e+00,-1.300511107652817804e-09,0.000000000000000000e+00 +3.791368912826493442e+01,2.558600000000000136e+02,0.000000000000000000e+00,1.034157477571086403e+01,0.000000000000000000e+00,-1.000000009821789826e+00,0.000000000000000000e+00,-1.487077977369101288e-09,0.000000000000000000e+00 +3.791465609898427402e+01,2.558700000000000045e+02,0.000000000000000000e+00,1.034060780498202448e+01,0.000000000000000000e+00,-1.000000009823227787e+00,0.000000000000000000e+00,1.509210869657869776e-09,0.000000000000000000e+00 +3.791562316012696243e+01,2.558799999999999955e+02,0.000000000000000000e+00,1.033964074382983434e+01,0.000000000000000000e+00,-1.000000009821768288e+00,0.000000000000000000e+00,9.872204209330944864e-11,0.000000000000000000e+00 +3.791659031171837313e+01,2.558900000000000148e+02,0.000000000000000000e+00,1.033867359222892546e+01,0.000000000000000000e+00,-1.000000009821672808e+00,0.000000000000000000e+00,-1.910207613441114844e-09,0.000000000000000000e+00 +3.791755755378388670e+01,2.559000000000000057e+02,0.000000000000000000e+00,1.033770635015391370e+01,0.000000000000000000e+00,-1.000000009823520442e+00,0.000000000000000000e+00,1.186049674278716656e-09,0.000000000000000000e+00 +3.791852488634889795e+01,2.559099999999999966e+02,0.000000000000000000e+00,1.033673901757940250e+01,0.000000000000000000e+00,-1.000000009822373137e+00,0.000000000000000000e+00,-1.995002730588172770e-09,0.000000000000000000e+00 +3.791949230943880877e+01,2.559200000000000159e+02,0.000000000000000000e+00,1.033577159447998817e+01,0.000000000000000000e+00,-1.000000009824303149e+00,0.000000000000000000e+00,1.841739362034064975e-09,0.000000000000000000e+00 +3.792045982307904239e+01,2.559300000000000068e+02,0.000000000000000000e+00,1.033480408083024926e+01,0.000000000000000000e+00,-1.000000009822521241e+00,0.000000000000000000e+00,-5.798927984969735499e-10,0.000000000000000000e+00 +3.792142742729502913e+01,2.559399999999999977e+02,0.000000000000000000e+00,1.033383647660475901e+01,0.000000000000000000e+00,-1.000000009823082348e+00,0.000000000000000000e+00,-1.660582217981346606e-09,0.000000000000000000e+00 +3.792239512211220642e+01,2.559500000000000171e+02,0.000000000000000000e+00,1.033286878177807289e+01,0.000000000000000000e+00,-1.000000009824689284e+00,0.000000000000000000e+00,5.038409654997055433e-10,0.000000000000000000e+00 +3.792336290755603301e+01,2.559600000000000080e+02,0.000000000000000000e+00,1.033190099632473569e+01,0.000000000000000000e+00,-1.000000009824201674e+00,0.000000000000000000e+00,2.312496017852291124e-10,0.000000000000000000e+00 +3.792433078365197474e+01,2.559699999999999989e+02,0.000000000000000000e+00,1.033093312021928334e+01,0.000000000000000000e+00,-1.000000009823977853e+00,0.000000000000000000e+00,-5.730232052038657554e-10,0.000000000000000000e+00 +3.792529875042551168e+01,2.559800000000000182e+02,0.000000000000000000e+00,1.032996515343623756e+01,0.000000000000000000e+00,-1.000000009824532521e+00,0.000000000000000000e+00,-1.899653132592303220e-09,0.000000000000000000e+00 +3.792626680790213101e+01,2.559900000000000091e+02,0.000000000000000000e+00,1.032899709595010762e+01,0.000000000000000000e+00,-1.000000009826371494e+00,0.000000000000000000e+00,1.944886371366847774e-09,0.000000000000000000e+00 +3.792723495610733409e+01,2.560000000000000000e+02,0.000000000000000000e+00,1.032802894773539037e+01,0.000000000000000000e+00,-1.000000009824488556e+00,0.000000000000000000e+00,-4.029298419621314364e-10,0.000000000000000000e+00 +3.792820319506663651e+01,2.560099999999999909e+02,0.000000000000000000e+00,1.032706070876657556e+01,0.000000000000000000e+00,-1.000000009824878688e+00,0.000000000000000000e+00,-1.352910187917783794e-09,0.000000000000000000e+00 +3.792917152480556098e+01,2.560199999999999818e+02,0.000000000000000000e+00,1.032609237901813515e+01,0.000000000000000000e+00,-1.000000009826188752e+00,0.000000000000000000e+00,9.967032437517138989e-10,0.000000000000000000e+00 +3.793013994534965150e+01,2.560300000000000296e+02,0.000000000000000000e+00,1.032512395846453046e+01,0.000000000000000000e+00,-1.000000009825223524e+00,0.000000000000000000e+00,-2.816505869190616420e-09,0.000000000000000000e+00 +3.793110845672445208e+01,2.560400000000000205e+02,0.000000000000000000e+00,1.032415544708021393e+01,0.000000000000000000e+00,-1.000000009827951342e+00,0.000000000000000000e+00,2.366009796291088520e-09,0.000000000000000000e+00 +3.793207705895552806e+01,2.560500000000000114e+02,0.000000000000000000e+00,1.032318684483962024e+01,0.000000000000000000e+00,-1.000000009825659619e+00,0.000000000000000000e+00,-4.893863961570896793e-10,0.000000000000000000e+00 +3.793304575206845186e+01,2.560600000000000023e+02,0.000000000000000000e+00,1.032221815171718049e+01,0.000000000000000000e+00,-1.000000009826133684e+00,0.000000000000000000e+00,-1.905792055979035304e-09,0.000000000000000000e+00 +3.793401453608881013e+01,2.560699999999999932e+02,0.000000000000000000e+00,1.032124936768730628e+01,0.000000000000000000e+00,-1.000000009827979985e+00,0.000000000000000000e+00,1.907904967035563780e-09,0.000000000000000000e+00 +3.793498341104219662e+01,2.560799999999999841e+02,0.000000000000000000e+00,1.032028049272439851e+01,0.000000000000000000e+00,-1.000000009826131464e+00,0.000000000000000000e+00,-2.285604541950218094e-09,0.000000000000000000e+00 +3.793595237695422639e+01,2.560900000000000318e+02,0.000000000000000000e+00,1.031931152680285102e+01,0.000000000000000000e+00,-1.000000009828346137e+00,0.000000000000000000e+00,6.587623921818374528e-10,0.000000000000000000e+00 +3.793692143385051452e+01,2.561000000000000227e+02,0.000000000000000000e+00,1.031834246989703807e+01,0.000000000000000000e+00,-1.000000009827707759e+00,0.000000000000000000e+00,1.289678358841204925e-09,0.000000000000000000e+00 +3.793789058175669737e+01,2.561100000000000136e+02,0.000000000000000000e+00,1.031737332198132862e+01,0.000000000000000000e+00,-1.000000009826457870e+00,0.000000000000000000e+00,-2.274422480144769402e-09,0.000000000000000000e+00 +3.793885982069842555e+01,2.561200000000000045e+02,0.000000000000000000e+00,1.031640408303007739e+01,0.000000000000000000e+00,-1.000000009828662328e+00,0.000000000000000000e+00,1.320818697586632728e-09,0.000000000000000000e+00 +3.793982915070134965e+01,2.561299999999999955e+02,0.000000000000000000e+00,1.031543475301762314e+01,0.000000000000000000e+00,-1.000000009827382019e+00,0.000000000000000000e+00,-3.041766250435041556e-09,0.000000000000000000e+00 +3.794079857179114867e+01,2.561399999999999864e+02,0.000000000000000000e+00,1.031446533191829928e+01,0.000000000000000000e+00,-1.000000009830330772e+00,0.000000000000000000e+00,1.659530641686224340e-09,0.000000000000000000e+00 +3.794176808399349454e+01,2.561499999999999773e+02,0.000000000000000000e+00,1.031349581970641971e+01,0.000000000000000000e+00,-1.000000009828721836e+00,0.000000000000000000e+00,3.109896190159070936e-10,0.000000000000000000e+00 +3.794273768733408758e+01,2.561600000000000250e+02,0.000000000000000000e+00,1.031252621635629474e+01,0.000000000000000000e+00,-1.000000009828420300e+00,0.000000000000000000e+00,-1.406649209269621950e-09,0.000000000000000000e+00 +3.794370738183863523e+01,2.561700000000000159e+02,0.000000000000000000e+00,1.031155652184221694e+01,0.000000000000000000e+00,-1.000000009829784320e+00,0.000000000000000000e+00,2.919272504919595649e-10,0.000000000000000000e+00 +3.794467716753285202e+01,2.561800000000000068e+02,0.000000000000000000e+00,1.031058673613846643e+01,0.000000000000000000e+00,-1.000000009829501213e+00,0.000000000000000000e+00,-2.513772353891504817e-10,0.000000000000000000e+00 +3.794564704444247383e+01,2.561899999999999977e+02,0.000000000000000000e+00,1.030961685921931448e+01,0.000000000000000000e+00,-1.000000009829745018e+00,0.000000000000000000e+00,7.487956198760943091e-10,0.000000000000000000e+00 +3.794661701259323650e+01,2.561999999999999886e+02,0.000000000000000000e+00,1.030864689105901810e+01,0.000000000000000000e+00,-1.000000009829018710e+00,0.000000000000000000e+00,-4.754210268293941050e-10,0.000000000000000000e+00 +3.794758707201089720e+01,2.562099999999999795e+02,0.000000000000000000e+00,1.030767683163182369e+01,0.000000000000000000e+00,-1.000000009829479897e+00,0.000000000000000000e+00,-2.026242795559441652e-09,0.000000000000000000e+00 +3.794855722272122023e+01,2.562200000000000273e+02,0.000000000000000000e+00,1.030670668091196340e+01,0.000000000000000000e+00,-1.000000009831445658e+00,0.000000000000000000e+00,1.765157545238737411e-09,0.000000000000000000e+00 +3.794952746474999117e+01,2.562300000000000182e+02,0.000000000000000000e+00,1.030573643887365698e+01,0.000000000000000000e+00,-1.000000009829733028e+00,0.000000000000000000e+00,-2.301376675134578091e-09,0.000000000000000000e+00 +3.795049779812299562e+01,2.562400000000000091e+02,0.000000000000000000e+00,1.030476610549111705e+01,0.000000000000000000e+00,-1.000000009831966130e+00,0.000000000000000000e+00,8.763490862768946573e-10,0.000000000000000000e+00 +3.795146822286603339e+01,2.562500000000000000e+02,0.000000000000000000e+00,1.030379568073853669e+01,0.000000000000000000e+00,-1.000000009831115699e+00,0.000000000000000000e+00,-1.189709165402072815e-11,0.000000000000000000e+00 +3.795243873900492559e+01,2.562599999999999909e+02,0.000000000000000000e+00,1.030282516459010367e+01,0.000000000000000000e+00,-1.000000009831127246e+00,0.000000000000000000e+00,7.004896807932791827e-10,0.000000000000000000e+00 +3.795340934656550047e+01,2.562699999999999818e+02,0.000000000000000000e+00,1.030185455701998976e+01,0.000000000000000000e+00,-1.000000009830447345e+00,0.000000000000000000e+00,-2.633336874345062962e-09,0.000000000000000000e+00 +3.795438004557359335e+01,2.562800000000000296e+02,0.000000000000000000e+00,1.030088385800235606e+01,0.000000000000000000e+00,-1.000000009833003523e+00,0.000000000000000000e+00,1.305794271496362172e-09,0.000000000000000000e+00 +3.795535083605505378e+01,2.562900000000000205e+02,0.000000000000000000e+00,1.029991306751134772e+01,0.000000000000000000e+00,-1.000000009831735870e+00,0.000000000000000000e+00,-6.691879414053182016e-10,0.000000000000000000e+00 +3.795632171803575261e+01,2.563000000000000114e+02,0.000000000000000000e+00,1.029894218552110452e+01,0.000000000000000000e+00,-1.000000009832385572e+00,0.000000000000000000e+00,8.742530249793919198e-10,0.000000000000000000e+00 +3.795729269154156071e+01,2.563100000000000023e+02,0.000000000000000000e+00,1.029797121200574850e+01,0.000000000000000000e+00,-1.000000009831536696e+00,0.000000000000000000e+00,-1.592165811397006561e-09,0.000000000000000000e+00 +3.795826375659837026e+01,2.563199999999999932e+02,0.000000000000000000e+00,1.029700014693939281e+01,0.000000000000000000e+00,-1.000000009833082792e+00,0.000000000000000000e+00,-5.235840724646936163e-10,0.000000000000000000e+00 +3.795923491323208054e+01,2.563299999999999841e+02,0.000000000000000000e+00,1.029602899029613461e+01,0.000000000000000000e+00,-1.000000009833591275e+00,0.000000000000000000e+00,3.191504054467976002e-10,0.000000000000000000e+00 +3.796020616146860505e+01,2.563400000000000318e+02,0.000000000000000000e+00,1.029505774205006219e+01,0.000000000000000000e+00,-1.000000009833281300e+00,0.000000000000000000e+00,9.461596838088494861e-10,0.000000000000000000e+00 +3.796117750133386437e+01,2.563500000000000227e+02,0.000000000000000000e+00,1.029408640217525139e+01,0.000000000000000000e+00,-1.000000009832362258e+00,0.000000000000000000e+00,-2.399805091012074147e-09,0.000000000000000000e+00 +3.796214893285380043e+01,2.563600000000000136e+02,0.000000000000000000e+00,1.029311497064576564e+01,0.000000000000000000e+00,-1.000000009834693504e+00,0.000000000000000000e+00,1.585244056832003191e-09,0.000000000000000000e+00 +3.796312045605436225e+01,2.563700000000000045e+02,0.000000000000000000e+00,1.029214344743565235e+01,0.000000000000000000e+00,-1.000000009833153403e+00,0.000000000000000000e+00,-2.671533148046973167e-10,0.000000000000000000e+00 +3.796409207096150595e+01,2.563799999999999955e+02,0.000000000000000000e+00,1.029117183251895362e+01,0.000000000000000000e+00,-1.000000009833412973e+00,0.000000000000000000e+00,-4.184016605477892707e-10,0.000000000000000000e+00 +3.796506377760120898e+01,2.563899999999999864e+02,0.000000000000000000e+00,1.029020012586969379e+01,0.000000000000000000e+00,-1.000000009833819536e+00,0.000000000000000000e+00,-7.428156003453340181e-10,0.000000000000000000e+00 +3.796603557599946299e+01,2.563999999999999773e+02,0.000000000000000000e+00,1.028922832746188654e+01,0.000000000000000000e+00,-1.000000009834541403e+00,0.000000000000000000e+00,-1.231664324160486950e-09,0.000000000000000000e+00 +3.796700746618225963e+01,2.564100000000000250e+02,0.000000000000000000e+00,1.028825643726953309e+01,0.000000000000000000e+00,-1.000000009835738446e+00,0.000000000000000000e+00,1.884444319500663707e-09,0.000000000000000000e+00 +3.796797944817561188e+01,2.564200000000000159e+02,0.000000000000000000e+00,1.028728445526662227e+01,0.000000000000000000e+00,-1.000000009833906800e+00,0.000000000000000000e+00,-2.667073968336388494e-09,0.000000000000000000e+00 +3.796895152200553980e+01,2.564300000000000068e+02,0.000000000000000000e+00,1.028631238142713400e+01,0.000000000000000000e+00,-1.000000009836499393e+00,0.000000000000000000e+00,2.042142432986171653e-09,0.000000000000000000e+00 +3.796992368769808479e+01,2.564399999999999977e+02,0.000000000000000000e+00,1.028534021572502866e+01,0.000000000000000000e+00,-1.000000009834514092e+00,0.000000000000000000e+00,-8.973067113245666950e-10,0.000000000000000000e+00 +3.797089594527928824e+01,2.564499999999999886e+02,0.000000000000000000e+00,1.028436795813426308e+01,0.000000000000000000e+00,-1.000000009835386505e+00,0.000000000000000000e+00,-1.989005513965956424e-10,0.000000000000000000e+00 +3.797186829477521286e+01,2.564599999999999795e+02,0.000000000000000000e+00,1.028339560862877455e+01,0.000000000000000000e+00,-1.000000009835579906e+00,0.000000000000000000e+00,-1.491498926932414201e-09,0.000000000000000000e+00 +3.797284073621192846e+01,2.564700000000000273e+02,0.000000000000000000e+00,1.028242316718249150e+01,0.000000000000000000e+00,-1.000000009837030301e+00,0.000000000000000000e+00,8.682844511119783764e-10,0.000000000000000000e+00 +3.797381326961552617e+01,2.564800000000000182e+02,0.000000000000000000e+00,1.028145063376932811e+01,0.000000000000000000e+00,-1.000000009836185866e+00,0.000000000000000000e+00,1.254247589830918806e-09,0.000000000000000000e+00 +3.797478589501209711e+01,2.564900000000000091e+02,0.000000000000000000e+00,1.028047800836318970e+01,0.000000000000000000e+00,-1.000000009834965953e+00,0.000000000000000000e+00,-2.201459679277530720e-09,0.000000000000000000e+00 +3.797575861242775375e+01,2.565000000000000000e+02,0.000000000000000000e+00,1.027950529093796739e+01,0.000000000000000000e+00,-1.000000009837107351e+00,0.000000000000000000e+00,-1.022563893635688275e-10,0.000000000000000000e+00 +3.797673142188861561e+01,2.565099999999999909e+02,0.000000000000000000e+00,1.027853248146753629e+01,0.000000000000000000e+00,-1.000000009837206827e+00,0.000000000000000000e+00,4.998220978083867860e-11,0.000000000000000000e+00 +3.797770432342081648e+01,2.565199999999999818e+02,0.000000000000000000e+00,1.027755957992576441e+01,0.000000000000000000e+00,-1.000000009837158199e+00,0.000000000000000000e+00,1.414887527041213899e-10,0.000000000000000000e+00 +3.797867731705050431e+01,2.565300000000000296e+02,0.000000000000000000e+00,1.027658658628650556e+01,0.000000000000000000e+00,-1.000000009837020531e+00,0.000000000000000000e+00,1.809515462564181640e-10,0.000000000000000000e+00 +3.797965040280383420e+01,2.565400000000000205e+02,0.000000000000000000e+00,1.027561350052360112e+01,0.000000000000000000e+00,-1.000000009836844450e+00,0.000000000000000000e+00,-1.697999866732061451e-09,0.000000000000000000e+00 +3.798062358070698252e+01,2.565500000000000114e+02,0.000000000000000000e+00,1.027464032261088001e+01,0.000000000000000000e+00,-1.000000009838496906e+00,0.000000000000000000e+00,2.014501322392760242e-09,0.000000000000000000e+00 +3.798159685078613279e+01,2.565600000000000023e+02,0.000000000000000000e+00,1.027366705252215695e+01,0.000000000000000000e+00,-1.000000009836536252e+00,0.000000000000000000e+00,-1.799648416452799185e-09,0.000000000000000000e+00 +3.798257021306747561e+01,2.565699999999999932e+02,0.000000000000000000e+00,1.027269369023123957e+01,0.000000000000000000e+00,-1.000000009838287962e+00,0.000000000000000000e+00,-5.930590151104470055e-12,0.000000000000000000e+00 +3.798354366757722289e+01,2.565799999999999841e+02,0.000000000000000000e+00,1.027172023571191595e+01,0.000000000000000000e+00,-1.000000009838293735e+00,0.000000000000000000e+00,-9.556468458267836027e-11,0.000000000000000000e+00 +3.798451721434159367e+01,2.565900000000000318e+02,0.000000000000000000e+00,1.027074668893796705e+01,0.000000000000000000e+00,-1.000000009838386772e+00,0.000000000000000000e+00,-1.847256751572546431e-10,0.000000000000000000e+00 +3.798549085338682119e+01,2.566000000000000227e+02,0.000000000000000000e+00,1.026977304988315964e+01,0.000000000000000000e+00,-1.000000009838566628e+00,0.000000000000000000e+00,-2.654324722254130372e-10,0.000000000000000000e+00 +3.798646458473915288e+01,2.566100000000000136e+02,0.000000000000000000e+00,1.026879931852124805e+01,0.000000000000000000e+00,-1.000000009838825088e+00,0.000000000000000000e+00,-3.278829079363622115e-10,0.000000000000000000e+00 +3.798743840842484332e+01,2.566200000000000045e+02,0.000000000000000000e+00,1.026782549482597418e+01,0.000000000000000000e+00,-1.000000009839144388e+00,0.000000000000000000e+00,-3.643304578189600618e-10,0.000000000000000000e+00 +3.798841232447016836e+01,2.566299999999999955e+02,0.000000000000000000e+00,1.026685157877106747e+01,0.000000000000000000e+00,-1.000000009839499215e+00,0.000000000000000000e+00,-3.654357501219345610e-10,0.000000000000000000e+00 +3.798938633290140388e+01,2.566399999999999864e+02,0.000000000000000000e+00,1.026587757033024495e+01,0.000000000000000000e+00,-1.000000009839855153e+00,0.000000000000000000e+00,-3.232306510165436373e-10,0.000000000000000000e+00 +3.799036043374485416e+01,2.566499999999999773e+02,0.000000000000000000e+00,1.026490346947721122e+01,0.000000000000000000e+00,-1.000000009840170012e+00,0.000000000000000000e+00,-2.279266435473650463e-10,0.000000000000000000e+00 +3.799133462702682351e+01,2.566600000000000250e+02,0.000000000000000000e+00,1.026392927618565842e+01,0.000000000000000000e+00,-1.000000009840392057e+00,0.000000000000000000e+00,-7.179007881493687722e-11,0.000000000000000000e+00 +3.799230891277363042e+01,2.566700000000000159e+02,0.000000000000000000e+00,1.026295499042926629e+01,0.000000000000000000e+00,-1.000000009840462001e+00,0.000000000000000000e+00,1.542770473266366836e-10,0.000000000000000000e+00 +3.799328329101160762e+01,2.566800000000000068e+02,0.000000000000000000e+00,1.026198061218170210e+01,0.000000000000000000e+00,-1.000000009840311677e+00,0.000000000000000000e+00,4.591414123022136854e-10,0.000000000000000000e+00 +3.799425776176710201e+01,2.566899999999999977e+02,0.000000000000000000e+00,1.026100614141662071e+01,0.000000000000000000e+00,-1.000000009839864257e+00,0.000000000000000000e+00,-1.019356631919387168e-09,0.000000000000000000e+00 +3.799523232506646764e+01,2.566999999999999886e+02,0.000000000000000000e+00,1.026003157810766453e+01,0.000000000000000000e+00,-1.000000009840857684e+00,0.000000000000000000e+00,-5.305892069132401156e-10,0.000000000000000000e+00 +3.799620698093607984e+01,2.567099999999999795e+02,0.000000000000000000e+00,1.025905692222846177e+01,0.000000000000000000e+00,-1.000000009841374826e+00,0.000000000000000000e+00,6.264412663298972102e-11,0.000000000000000000e+00 +3.799718172940232108e+01,2.567200000000000273e+02,0.000000000000000000e+00,1.025808217375262998e+01,0.000000000000000000e+00,-1.000000009841313764e+00,0.000000000000000000e+00,7.694245592423683840e-10,0.000000000000000000e+00 +3.799815657049158091e+01,2.567300000000000182e+02,0.000000000000000000e+00,1.025710733265377428e+01,0.000000000000000000e+00,-1.000000009840563697e+00,0.000000000000000000e+00,-2.707989525624418716e-10,0.000000000000000000e+00 +3.799913150423027730e+01,2.567400000000000091e+02,0.000000000000000000e+00,1.025613239890548734e+01,0.000000000000000000e+00,-1.000000009840827708e+00,0.000000000000000000e+00,-1.178740245338589800e-09,0.000000000000000000e+00 +3.800010653064482113e+01,2.567500000000000000e+02,0.000000000000000000e+00,1.025515737248134762e+01,0.000000000000000000e+00,-1.000000009841977011e+00,0.000000000000000000e+00,-7.878774190569584813e-11,0.000000000000000000e+00 +3.800108164976165170e+01,2.567599999999999909e+02,0.000000000000000000e+00,1.025418225335492117e+01,0.000000000000000000e+00,-1.000000009842053839e+00,0.000000000000000000e+00,-6.978655121899286661e-10,0.000000000000000000e+00 +3.800205686160720830e+01,2.567699999999999818e+02,0.000000000000000000e+00,1.025320704149976336e+01,0.000000000000000000e+00,-1.000000009842734405e+00,0.000000000000000000e+00,7.082718213281716667e-10,0.000000000000000000e+00 +3.800303216620795865e+01,2.567800000000000296e+02,0.000000000000000000e+00,1.025223173688941536e+01,0.000000000000000000e+00,-1.000000009842043625e+00,0.000000000000000000e+00,-1.454198013900444891e-09,0.000000000000000000e+00 +3.800400756359036336e+01,2.567900000000000205e+02,0.000000000000000000e+00,1.025125633949740767e+01,0.000000000000000000e+00,-1.000000009843462045e+00,0.000000000000000000e+00,2.159237625065033507e-09,0.000000000000000000e+00 +3.800498305378091146e+01,2.568000000000000114e+02,0.000000000000000000e+00,1.025028084929725480e+01,0.000000000000000000e+00,-1.000000009841355730e+00,0.000000000000000000e+00,-1.510138979090298323e-09,0.000000000000000000e+00 +3.800595863680609909e+01,2.568100000000000023e+02,0.000000000000000000e+00,1.024930526626246419e+01,0.000000000000000000e+00,-1.000000009842828996e+00,0.000000000000000000e+00,-1.253057097994972428e-09,0.000000000000000000e+00 +3.800693431269243661e+01,2.568199999999999932e+02,0.000000000000000000e+00,1.024832959036652369e+01,0.000000000000000000e+00,-1.000000009844051574e+00,0.000000000000000000e+00,1.070890910443208678e-09,0.000000000000000000e+00 +3.800791008146644145e+01,2.568299999999999841e+02,0.000000000000000000e+00,1.024735382158291230e+01,0.000000000000000000e+00,-1.000000009843006632e+00,0.000000000000000000e+00,-1.267380884378095872e-10,0.000000000000000000e+00 +3.800888594315465241e+01,2.568400000000000318e+02,0.000000000000000000e+00,1.024637795988509836e+01,0.000000000000000000e+00,-1.000000009843130311e+00,0.000000000000000000e+00,-1.104586755290396568e-09,0.000000000000000000e+00 +3.800986189778360824e+01,2.568500000000000227e+02,0.000000000000000000e+00,1.024540200524653422e+01,0.000000000000000000e+00,-1.000000009844208337e+00,0.000000000000000000e+00,1.069220033059952343e-11,0.000000000000000000e+00 +3.801083794537987615e+01,2.568600000000000136e+02,0.000000000000000000e+00,1.024442595764065977e+01,0.000000000000000000e+00,-1.000000009844197901e+00,0.000000000000000000e+00,-5.022580687901307555e-10,0.000000000000000000e+00 +3.801181408597002331e+01,2.568700000000000045e+02,0.000000000000000000e+00,1.024344981704090429e+01,0.000000000000000000e+00,-1.000000009844688176e+00,0.000000000000000000e+00,1.094490731814464263e-09,0.000000000000000000e+00 +3.801279031958063115e+01,2.568799999999999955e+02,0.000000000000000000e+00,1.024247358342068281e+01,0.000000000000000000e+00,-1.000000009843619697e+00,0.000000000000000000e+00,-7.825818126983145451e-10,0.000000000000000000e+00 +3.801376664623830237e+01,2.568899999999999864e+02,0.000000000000000000e+00,1.024149725675339972e+01,0.000000000000000000e+00,-1.000000009844383753e+00,0.000000000000000000e+00,-5.319047887374628887e-10,0.000000000000000000e+00 +3.801474306596964681e+01,2.568999999999999773e+02,0.000000000000000000e+00,1.024052083701244342e+01,0.000000000000000000e+00,-1.000000009844903115e+00,0.000000000000000000e+00,-9.550180094620111871e-12,0.000000000000000000e+00 +3.801571957880128139e+01,2.569100000000000250e+02,0.000000000000000000e+00,1.023954432417119165e+01,0.000000000000000000e+00,-1.000000009844912441e+00,0.000000000000000000e+00,7.934988153514556984e-10,0.000000000000000000e+00 +3.801669618475985146e+01,2.569200000000000159e+02,0.000000000000000000e+00,1.023856771820300970e+01,0.000000000000000000e+00,-1.000000009844137505e+00,0.000000000000000000e+00,-1.838741063960334772e-09,0.000000000000000000e+00 +3.801767288387199528e+01,2.569300000000000068e+02,0.000000000000000000e+00,1.023759101908125047e+01,0.000000000000000000e+00,-1.000000009845933402e+00,0.000000000000000000e+00,-4.471388045275763902e-10,0.000000000000000000e+00 +3.801864967616437951e+01,2.569399999999999977e+02,0.000000000000000000e+00,1.023661422677925081e+01,0.000000000000000000e+00,-1.000000009846370164e+00,0.000000000000000000e+00,1.250369027461509792e-09,0.000000000000000000e+00 +3.801962656166367083e+01,2.569499999999999886e+02,0.000000000000000000e+00,1.023563734127033875e+01,0.000000000000000000e+00,-1.000000009845148696e+00,0.000000000000000000e+00,-4.581900387990112668e-10,0.000000000000000000e+00 +3.802060354039656431e+01,2.569599999999999795e+02,0.000000000000000000e+00,1.023466036252782985e+01,0.000000000000000000e+00,-1.000000009845596338e+00,0.000000000000000000e+00,1.977119471563251620e-11,0.000000000000000000e+00 +3.802158061238974796e+01,2.569700000000000273e+02,0.000000000000000000e+00,1.023368329052502368e+01,0.000000000000000000e+00,-1.000000009845577020e+00,0.000000000000000000e+00,-1.029140142500835854e-09,0.000000000000000000e+00 +3.802255777766993816e+01,2.569800000000000182e+02,0.000000000000000000e+00,1.023270612523520917e+01,0.000000000000000000e+00,-1.000000009846582660e+00,0.000000000000000000e+00,1.254208688268273565e-10,0.000000000000000000e+00 +3.802353503626386555e+01,2.569900000000000091e+02,0.000000000000000000e+00,1.023172886663166103e+01,0.000000000000000000e+00,-1.000000009846460092e+00,0.000000000000000000e+00,-2.285531595054612984e-10,0.000000000000000000e+00 +3.802451238819826074e+01,2.570000000000000000e+02,0.000000000000000000e+00,1.023075151468764332e+01,0.000000000000000000e+00,-1.000000009846683469e+00,0.000000000000000000e+00,-2.219434465067188720e-10,0.000000000000000000e+00 +3.802548983349987566e+01,2.570099999999999909e+02,0.000000000000000000e+00,1.022977406937640588e+01,0.000000000000000000e+00,-1.000000009846900406e+00,0.000000000000000000e+00,1.540054044077355247e-10,0.000000000000000000e+00 +3.802646737219546935e+01,2.570199999999999818e+02,0.000000000000000000e+00,1.022879653067118610e+01,0.000000000000000000e+00,-1.000000009846749860e+00,0.000000000000000000e+00,-9.502906169595757574e-10,0.000000000000000000e+00 +3.802744500431182217e+01,2.570300000000000296e+02,0.000000000000000000e+00,1.022781889854520898e+01,0.000000000000000000e+00,-1.000000009847678895e+00,0.000000000000000000e+00,1.912208949533826011e-10,0.000000000000000000e+00 +3.802842272987571448e+01,2.570400000000000205e+02,0.000000000000000000e+00,1.022684117297168527e+01,0.000000000000000000e+00,-1.000000009847491933e+00,0.000000000000000000e+00,-1.294364497493618707e-10,0.000000000000000000e+00 +3.802940054891395505e+01,2.570500000000000114e+02,0.000000000000000000e+00,1.022586335392381507e+01,0.000000000000000000e+00,-1.000000009847618498e+00,0.000000000000000000e+00,-4.541195576878737951e-11,0.000000000000000000e+00 +3.803037846145335266e+01,2.570600000000000023e+02,0.000000000000000000e+00,1.022488544137478428e+01,0.000000000000000000e+00,-1.000000009847662907e+00,0.000000000000000000e+00,4.524868631929900367e-10,0.000000000000000000e+00 +3.803135646752073740e+01,2.570699999999999932e+02,0.000000000000000000e+00,1.022390743529776636e+01,0.000000000000000000e+00,-1.000000009847220372e+00,0.000000000000000000e+00,-4.830907900890945248e-10,0.000000000000000000e+00 +3.803233456714294647e+01,2.570799999999999841e+02,0.000000000000000000e+00,1.022292933566592232e+01,0.000000000000000000e+00,-1.000000009847692883e+00,0.000000000000000000e+00,-9.876536375293381503e-10,0.000000000000000000e+00 +3.803331276034683839e+01,2.570900000000000318e+02,0.000000000000000000e+00,1.022195114245239900e+01,0.000000000000000000e+00,-1.000000009848658999e+00,0.000000000000000000e+00,8.055268586507304686e-10,0.000000000000000000e+00 +3.803429104715927167e+01,2.571000000000000227e+02,0.000000000000000000e+00,1.022097285563033076e+01,0.000000000000000000e+00,-1.000000009847870963e+00,0.000000000000000000e+00,-6.647400295576586029e-10,0.000000000000000000e+00 +3.803526942760712615e+01,2.571100000000000136e+02,0.000000000000000000e+00,1.021999447517284132e+01,0.000000000000000000e+00,-1.000000009848521332e+00,0.000000000000000000e+00,-1.675420229445580728e-09,0.000000000000000000e+00 +3.803624790171729586e+01,2.571200000000000045e+02,0.000000000000000000e+00,1.021901600105303842e+01,0.000000000000000000e+00,-1.000000009850160687e+00,0.000000000000000000e+00,1.491464555745594404e-09,0.000000000000000000e+00 +3.803722646951667485e+01,2.571299999999999955e+02,0.000000000000000000e+00,1.021803743324401736e+01,0.000000000000000000e+00,-1.000000009848701188e+00,0.000000000000000000e+00,-4.308565301365338624e-10,0.000000000000000000e+00 +3.803820513103218559e+01,2.571399999999999864e+02,0.000000000000000000e+00,1.021705877171886456e+01,0.000000000000000000e+00,-1.000000009849122851e+00,0.000000000000000000e+00,-1.225067100369556117e-11,0.000000000000000000e+00 +3.803918388629076475e+01,2.571499999999999773e+02,0.000000000000000000e+00,1.021608001645064867e+01,0.000000000000000000e+00,-1.000000009849134841e+00,0.000000000000000000e+00,-9.545534298377306914e-10,0.000000000000000000e+00 +3.804016273531934189e+01,2.571600000000000250e+02,0.000000000000000000e+00,1.021510116741242769e+01,0.000000000000000000e+00,-1.000000009850069205e+00,0.000000000000000000e+00,4.608998865270231135e-10,0.000000000000000000e+00 +3.804114167814488212e+01,2.571700000000000159e+02,0.000000000000000000e+00,1.021412222457724539e+01,0.000000000000000000e+00,-1.000000009849618010e+00,0.000000000000000000e+00,5.341118178598815824e-10,0.000000000000000000e+00 +3.804212071479435053e+01,2.571800000000000068e+02,0.000000000000000000e+00,1.021314318791813491e+01,0.000000000000000000e+00,-1.000000009849095095e+00,0.000000000000000000e+00,-7.243268061387757804e-10,0.000000000000000000e+00 +3.804309984529472644e+01,2.571899999999999977e+02,0.000000000000000000e+00,1.021216405740811517e+01,0.000000000000000000e+00,-1.000000009849804306e+00,0.000000000000000000e+00,-1.452596331036479349e-09,0.000000000000000000e+00 +3.804407906967300335e+01,2.571999999999999886e+02,0.000000000000000000e+00,1.021118483302019087e+01,0.000000000000000000e+00,-1.000000009851226723e+00,0.000000000000000000e+00,2.063051303028434187e-09,0.000000000000000000e+00 +3.804505838795618899e+01,2.572099999999999795e+02,0.000000000000000000e+00,1.021020551472735427e+01,0.000000000000000000e+00,-1.000000009849206339e+00,0.000000000000000000e+00,-3.134068139134326228e-09,0.000000000000000000e+00 +3.804603780017130532e+01,2.572200000000000273e+02,0.000000000000000000e+00,1.020922610250258877e+01,0.000000000000000000e+00,-1.000000009852275884e+00,0.000000000000000000e+00,1.485048532978582490e-09,0.000000000000000000e+00 +3.804701730634538848e+01,2.572300000000000182e+02,0.000000000000000000e+00,1.020824659631885645e+01,0.000000000000000000e+00,-1.000000009850821270e+00,0.000000000000000000e+00,1.114076209527574006e-09,0.000000000000000000e+00 +3.804799690650548172e+01,2.572400000000000091e+02,0.000000000000000000e+00,1.020726699614911581e+01,0.000000000000000000e+00,-1.000000009849729921e+00,0.000000000000000000e+00,-2.382738405038234989e-09,0.000000000000000000e+00 +3.804897660067864251e+01,2.572500000000000000e+02,0.000000000000000000e+00,1.020628730196630762e+01,0.000000000000000000e+00,-1.000000009852064276e+00,0.000000000000000000e+00,2.106706959083632526e-09,0.000000000000000000e+00 +3.804995638889194254e+01,2.572599999999999909e+02,0.000000000000000000e+00,1.020530751374335665e+01,0.000000000000000000e+00,-1.000000009850000149e+00,0.000000000000000000e+00,-2.062543668970118990e-09,0.000000000000000000e+00 +3.805093627117246768e+01,2.572699999999999818e+02,0.000000000000000000e+00,1.020432763145318233e+01,0.000000000000000000e+00,-1.000000009852021199e+00,0.000000000000000000e+00,-7.953013800055123619e-11,0.000000000000000000e+00 +3.805191624754731095e+01,2.572800000000000296e+02,0.000000000000000000e+00,1.020334765506868280e+01,0.000000000000000000e+00,-1.000000009852099137e+00,0.000000000000000000e+00,6.635937417719655189e-10,0.000000000000000000e+00 +3.805289631804358663e+01,2.572900000000000205e+02,0.000000000000000000e+00,1.020236758456274906e+01,0.000000000000000000e+00,-1.000000009851448768e+00,0.000000000000000000e+00,-1.671397865419343285e-09,0.000000000000000000e+00 +3.805387648268842327e+01,2.573000000000000114e+02,0.000000000000000000e+00,1.020138741990825793e+01,0.000000000000000000e+00,-1.000000009853087013e+00,0.000000000000000000e+00,2.169120126472667374e-09,0.000000000000000000e+00 +3.805485674150894937e+01,2.573100000000000023e+02,0.000000000000000000e+00,1.020040716107807022e+01,0.000000000000000000e+00,-1.000000009850960714e+00,0.000000000000000000e+00,-2.595853897904637655e-09,0.000000000000000000e+00 +3.805583709453232188e+01,2.573199999999999932e+02,0.000000000000000000e+00,1.019942680804503965e+01,0.000000000000000000e+00,-1.000000009853505567e+00,0.000000000000000000e+00,2.527662581566019009e-09,0.000000000000000000e+00 +3.805681754178570486e+01,2.573299999999999841e+02,0.000000000000000000e+00,1.019844636078199862e+01,0.000000000000000000e+00,-1.000000009851027327e+00,0.000000000000000000e+00,-2.780818271439565442e-09,0.000000000000000000e+00 +3.805779808329626945e+01,2.573400000000000318e+02,0.000000000000000000e+00,1.019746581926177598e+01,0.000000000000000000e+00,-1.000000009853754035e+00,0.000000000000000000e+00,1.814150965982482991e-09,0.000000000000000000e+00 +3.805877871909120813e+01,2.573500000000000227e+02,0.000000000000000000e+00,1.019648518345717747e+01,0.000000000000000000e+00,-1.000000009851975014e+00,0.000000000000000000e+00,-2.153361279952053314e-09,0.000000000000000000e+00 +3.805975944919772047e+01,2.573600000000000136e+02,0.000000000000000000e+00,1.019550445334100530e+01,0.000000000000000000e+00,-1.000000009854086880e+00,0.000000000000000000e+00,1.949180668942364357e-09,0.000000000000000000e+00 +3.806074027364302026e+01,2.573700000000000045e+02,0.000000000000000000e+00,1.019452362888604036e+01,0.000000000000000000e+00,-1.000000009852175076e+00,0.000000000000000000e+00,-2.488644685349441917e-09,0.000000000000000000e+00 +3.806172119245433549e+01,2.573799999999999955e+02,0.000000000000000000e+00,1.019354271006505819e+01,0.000000000000000000e+00,-1.000000009854616234e+00,0.000000000000000000e+00,1.159550662236681111e-09,0.000000000000000000e+00 +3.806270220565891549e+01,2.573899999999999864e+02,0.000000000000000000e+00,1.019256169685081304e+01,0.000000000000000000e+00,-1.000000009853478700e+00,0.000000000000000000e+00,-2.036883001636121222e-11,0.000000000000000000e+00 +3.806368331328400956e+01,2.573999999999999773e+02,0.000000000000000000e+00,1.019158058921605381e+01,0.000000000000000000e+00,-1.000000009853498684e+00,0.000000000000000000e+00,-4.806581171189461321e-10,0.000000000000000000e+00 +3.806466451535688122e+01,2.574100000000000250e+02,0.000000000000000000e+00,1.019059938713351166e+01,0.000000000000000000e+00,-1.000000009853970306e+00,0.000000000000000000e+00,-2.127001557973407104e-10,0.000000000000000000e+00 +3.806564581190481533e+01,2.574200000000000159e+02,0.000000000000000000e+00,1.018961809057590528e+01,0.000000000000000000e+00,-1.000000009854179028e+00,0.000000000000000000e+00,7.921186581129334065e-10,0.000000000000000000e+00 +3.806662720295511093e+01,2.574300000000000068e+02,0.000000000000000000e+00,1.018863669951594098e+01,0.000000000000000000e+00,-1.000000009853401650e+00,0.000000000000000000e+00,-1.145644828922625578e-09,0.000000000000000000e+00 +3.806760868853506707e+01,2.574399999999999977e+02,0.000000000000000000e+00,1.018765521392631257e+01,0.000000000000000000e+00,-1.000000009854526084e+00,0.000000000000000000e+00,-4.831875241461470522e-10,0.000000000000000000e+00 +3.806859026867201123e+01,2.574499999999999886e+02,0.000000000000000000e+00,1.018667363377969792e+01,0.000000000000000000e+00,-1.000000009855000371e+00,0.000000000000000000e+00,-9.002345771601128032e-10,0.000000000000000000e+00 +3.806957194339327089e+01,2.574599999999999795e+02,0.000000000000000000e+00,1.018569195904876423e+01,0.000000000000000000e+00,-1.000000009855884109e+00,0.000000000000000000e+00,1.299333980514186891e-09,0.000000000000000000e+00 +3.807055371272619482e+01,2.574700000000000273e+02,0.000000000000000000e+00,1.018471018970616448e+01,0.000000000000000000e+00,-1.000000009854608463e+00,0.000000000000000000e+00,5.943116749517817856e-10,0.000000000000000000e+00 +3.807153557669813893e+01,2.574800000000000182e+02,0.000000000000000000e+00,1.018372832572454101e+01,0.000000000000000000e+00,-1.000000009854024929e+00,0.000000000000000000e+00,-1.160243235693694708e-09,0.000000000000000000e+00 +3.807251753533648042e+01,2.574900000000000091e+02,0.000000000000000000e+00,1.018274636707652014e+01,0.000000000000000000e+00,-1.000000009855164240e+00,0.000000000000000000e+00,-2.717750720743423044e-10,0.000000000000000000e+00 +3.807349958866861073e+01,2.575000000000000000e+02,0.000000000000000000e+00,1.018176431373471402e+01,0.000000000000000000e+00,-1.000000009855431138e+00,0.000000000000000000e+00,-4.153100317945284432e-10,0.000000000000000000e+00 +3.807448173672192127e+01,2.575099999999999909e+02,0.000000000000000000e+00,1.018078216567172412e+01,0.000000000000000000e+00,-1.000000009855839034e+00,0.000000000000000000e+00,2.595154741367430985e-10,0.000000000000000000e+00 +3.807546397952382478e+01,2.575199999999999818e+02,0.000000000000000000e+00,1.017979992286013768e+01,0.000000000000000000e+00,-1.000000009855584127e+00,0.000000000000000000e+00,-1.919279871587363374e-09,0.000000000000000000e+00 +3.807644631710174821e+01,2.575300000000000296e+02,0.000000000000000000e+00,1.017881758527252956e+01,0.000000000000000000e+00,-1.000000009857469507e+00,0.000000000000000000e+00,2.260829574784597420e-09,0.000000000000000000e+00 +3.807742874948313272e+01,2.575400000000000205e+02,0.000000000000000000e+00,1.017783515288145857e+01,0.000000000000000000e+00,-1.000000009855248395e+00,0.000000000000000000e+00,-1.915293544222825644e-09,0.000000000000000000e+00 +3.807841127669543368e+01,2.575500000000000114e+02,0.000000000000000000e+00,1.017685262565947646e+01,0.000000000000000000e+00,-1.000000009857130223e+00,0.000000000000000000e+00,2.124810221972329840e-09,0.000000000000000000e+00 +3.807939389876611358e+01,2.575600000000000023e+02,0.000000000000000000e+00,1.017587000357911364e+01,0.000000000000000000e+00,-1.000000009855042338e+00,0.000000000000000000e+00,-2.169569052731616003e-09,0.000000000000000000e+00 +3.808037661572264909e+01,2.575699999999999932e+02,0.000000000000000000e+00,1.017488728661289521e+01,0.000000000000000000e+00,-1.000000009857174410e+00,0.000000000000000000e+00,-7.139321095572082537e-11,0.000000000000000000e+00 +3.808135942759253112e+01,2.575799999999999841e+02,0.000000000000000000e+00,1.017390447473332493e+01,0.000000000000000000e+00,-1.000000009857244576e+00,0.000000000000000000e+00,1.069665193928199630e-09,0.000000000000000000e+00 +3.808234233440326477e+01,2.575900000000000318e+02,0.000000000000000000e+00,1.017292156791289948e+01,0.000000000000000000e+00,-1.000000009856193195e+00,0.000000000000000000e+00,-5.751012624323478947e-10,0.000000000000000000e+00 +3.808332533618237647e+01,2.576000000000000227e+02,0.000000000000000000e+00,1.017193856612410130e+01,0.000000000000000000e+00,-1.000000009856758520e+00,0.000000000000000000e+00,-1.317681288410099824e-09,0.000000000000000000e+00 +3.808430843295739265e+01,2.576100000000000136e+02,0.000000000000000000e+00,1.017095546933939687e+01,0.000000000000000000e+00,-1.000000009858053929e+00,0.000000000000000000e+00,6.870070409832438854e-10,0.000000000000000000e+00 +3.808529162475585395e+01,2.576200000000000045e+02,0.000000000000000000e+00,1.016997227753124022e+01,0.000000000000000000e+00,-1.000000009857378469e+00,0.000000000000000000e+00,-6.413252433154763692e-11,0.000000000000000000e+00 +3.808627491160532941e+01,2.576299999999999955e+02,0.000000000000000000e+00,1.016898899067207473e+01,0.000000000000000000e+00,-1.000000009857441530e+00,0.000000000000000000e+00,1.131242540603307599e-10,0.000000000000000000e+00 +3.808725829353338099e+01,2.576399999999999864e+02,0.000000000000000000e+00,1.016800560873432779e+01,0.000000000000000000e+00,-1.000000009857330285e+00,0.000000000000000000e+00,-6.086896125167606176e-10,0.000000000000000000e+00 +3.808824177056759908e+01,2.576499999999999773e+02,0.000000000000000000e+00,1.016702213169041435e+01,0.000000000000000000e+00,-1.000000009857928918e+00,0.000000000000000000e+00,-3.837805101241920591e-10,0.000000000000000000e+00 +3.808922534273558114e+01,2.576600000000000250e+02,0.000000000000000000e+00,1.016603855951273516e+01,0.000000000000000000e+00,-1.000000009858306393e+00,0.000000000000000000e+00,7.966061161051128484e-10,0.000000000000000000e+00 +3.809020901006493887e+01,2.576700000000000159e+02,0.000000000000000000e+00,1.016505489217367852e+01,0.000000000000000000e+00,-1.000000009857522798e+00,0.000000000000000000e+00,-2.564286308403777521e-09,0.000000000000000000e+00 +3.809119277258329817e+01,2.576800000000000068e+02,0.000000000000000000e+00,1.016407112964562032e+01,0.000000000000000000e+00,-1.000000009860045447e+00,0.000000000000000000e+00,2.390032910758390829e-09,0.000000000000000000e+00 +3.809217663031829915e+01,2.576899999999999977e+02,0.000000000000000000e+00,1.016308727190091865e+01,0.000000000000000000e+00,-1.000000009857693994e+00,0.000000000000000000e+00,-8.485036704885528541e-10,0.000000000000000000e+00 +3.809316058329758903e+01,2.576999999999999886e+02,0.000000000000000000e+00,1.016210331891192631e+01,0.000000000000000000e+00,-1.000000009858528882e+00,0.000000000000000000e+00,-1.257965420785244849e-09,0.000000000000000000e+00 +3.809414463154883634e+01,2.577099999999999795e+02,0.000000000000000000e+00,1.016111927065097476e+01,0.000000000000000000e+00,-1.000000009859766781e+00,0.000000000000000000e+00,1.167594737019745717e-09,0.000000000000000000e+00 +3.809512877509972384e+01,2.577200000000000273e+02,0.000000000000000000e+00,1.016013512709038480e+01,0.000000000000000000e+00,-1.000000009858617700e+00,0.000000000000000000e+00,-8.978892697313273356e-10,0.000000000000000000e+00 +3.809611301397794136e+01,2.577300000000000182e+02,0.000000000000000000e+00,1.015915088820246659e+01,0.000000000000000000e+00,-1.000000009859501438e+00,0.000000000000000000e+00,-1.087288199056144265e-10,0.000000000000000000e+00 +3.809709734821119298e+01,2.577400000000000091e+02,0.000000000000000000e+00,1.015816655395951251e+01,0.000000000000000000e+00,-1.000000009859608463e+00,0.000000000000000000e+00,1.708591305021729531e-09,0.000000000000000000e+00 +3.809808177782719696e+01,2.577500000000000000e+02,0.000000000000000000e+00,1.015718212433380430e+01,0.000000000000000000e+00,-1.000000009857926475e+00,0.000000000000000000e+00,-2.766634768374193814e-09,0.000000000000000000e+00 +3.809906630285368578e+01,2.577599999999999909e+02,0.000000000000000000e+00,1.015619759929761123e+01,0.000000000000000000e+00,-1.000000009860650296e+00,0.000000000000000000e+00,1.136810470160548882e-09,0.000000000000000000e+00 +3.810005092331840615e+01,2.577699999999999818e+02,0.000000000000000000e+00,1.015521297882318308e+01,0.000000000000000000e+00,-1.000000009859530969e+00,0.000000000000000000e+00,-1.232533944733827112e-09,0.000000000000000000e+00 +3.810103563924911896e+01,2.577800000000000296e+02,0.000000000000000000e+00,1.015422826288276426e+01,0.000000000000000000e+00,-1.000000009860744665e+00,0.000000000000000000e+00,1.128473147276670481e-09,0.000000000000000000e+00 +3.810202045067359222e+01,2.577900000000000205e+02,0.000000000000000000e+00,1.015324345144857965e+01,0.000000000000000000e+00,-1.000000009859633332e+00,0.000000000000000000e+00,-9.299700839898815824e-10,0.000000000000000000e+00 +3.810300535761961527e+01,2.578000000000000114e+02,0.000000000000000000e+00,1.015225854449284526e+01,0.000000000000000000e+00,-1.000000009860549266e+00,0.000000000000000000e+00,-7.213613560347799833e-11,0.000000000000000000e+00 +3.810399036011499163e+01,2.578100000000000023e+02,0.000000000000000000e+00,1.015127354198775933e+01,0.000000000000000000e+00,-1.000000009860620320e+00,0.000000000000000000e+00,4.868716729931845981e-11,0.000000000000000000e+00 +3.810497545818752485e+01,2.578199999999999932e+02,0.000000000000000000e+00,1.015028844390550944e+01,0.000000000000000000e+00,-1.000000009860572359e+00,0.000000000000000000e+00,1.271828813131010362e-09,0.000000000000000000e+00 +3.810596065186505399e+01,2.578299999999999841e+02,0.000000000000000000e+00,1.014930325021826896e+01,0.000000000000000000e+00,-1.000000009859319361e+00,0.000000000000000000e+00,-1.882205075039399790e-09,0.000000000000000000e+00 +3.810694594117541101e+01,2.578400000000000318e+02,0.000000000000000000e+00,1.014831796089819882e+01,0.000000000000000000e+00,-1.000000009861173877e+00,0.000000000000000000e+00,-2.548571934330082300e-10,0.000000000000000000e+00 +3.810793132614644918e+01,2.578500000000000227e+02,0.000000000000000000e+00,1.014733257591744220e+01,0.000000000000000000e+00,-1.000000009861425010e+00,0.000000000000000000e+00,6.739202914511704439e-10,0.000000000000000000e+00 +3.810891680680604310e+01,2.578600000000000136e+02,0.000000000000000000e+00,1.014634709524813339e+01,0.000000000000000000e+00,-1.000000009860760875e+00,0.000000000000000000e+00,-9.162713618143614683e-10,0.000000000000000000e+00 +3.810990238318206735e+01,2.578700000000000045e+02,0.000000000000000000e+00,1.014536151886239246e+01,0.000000000000000000e+00,-1.000000009861663930e+00,0.000000000000000000e+00,4.728465136792295091e-10,0.000000000000000000e+00 +3.811088805530241785e+01,2.578799999999999955e+02,0.000000000000000000e+00,1.014437584673232351e+01,0.000000000000000000e+00,-1.000000009861197858e+00,0.000000000000000000e+00,-6.367828601908048927e-10,0.000000000000000000e+00 +3.811187382319499761e+01,2.578899999999999864e+02,0.000000000000000000e+00,1.014339007883001997e+01,0.000000000000000000e+00,-1.000000009861825578e+00,0.000000000000000000e+00,-5.779363419450918461e-10,0.000000000000000000e+00 +3.811285968688773806e+01,2.578999999999999773e+02,0.000000000000000000e+00,1.014240421512755930e+01,0.000000000000000000e+00,-1.000000009862395345e+00,0.000000000000000000e+00,6.573781053721937364e-10,0.000000000000000000e+00 +3.811384564640856354e+01,2.579100000000000250e+02,0.000000000000000000e+00,1.014141825559700649e+01,0.000000000000000000e+00,-1.000000009861747197e+00,0.000000000000000000e+00,-5.748965926985850955e-10,0.000000000000000000e+00 +3.811483170178543389e+01,2.579200000000000159e+02,0.000000000000000000e+00,1.014043220021041414e+01,0.000000000000000000e+00,-1.000000009862314077e+00,0.000000000000000000e+00,-6.115422358681562125e-10,0.000000000000000000e+00 +3.811581785304630188e+01,2.579300000000000068e+02,0.000000000000000000e+00,1.013944604893981882e+01,0.000000000000000000e+00,-1.000000009862917150e+00,0.000000000000000000e+00,5.569986588644296702e-10,0.000000000000000000e+00 +3.811680410021914867e+01,2.579399999999999977e+02,0.000000000000000000e+00,1.013845980175724470e+01,0.000000000000000000e+00,-1.000000009862367811e+00,0.000000000000000000e+00,1.113213603957987096e-09,0.000000000000000000e+00 +3.811779044333196254e+01,2.579499999999999886e+02,0.000000000000000000e+00,1.013747345863470350e+01,0.000000000000000000e+00,-1.000000009861269801e+00,0.000000000000000000e+00,-2.584115039841492132e-09,0.000000000000000000e+00 +3.811877688241274598e+01,2.579599999999999795e+02,0.000000000000000000e+00,1.013648701954419273e+01,0.000000000000000000e+00,-1.000000009863818873e+00,0.000000000000000000e+00,2.253678233514655466e-09,0.000000000000000000e+00 +3.811976341748951569e+01,2.579700000000000273e+02,0.000000000000000000e+00,1.013550048445769214e+01,0.000000000000000000e+00,-1.000000009861595540e+00,0.000000000000000000e+00,-2.617820219157615095e-09,0.000000000000000000e+00 +3.812075004859030258e+01,2.579800000000000182e+02,0.000000000000000000e+00,1.013451385334717614e+01,0.000000000000000000e+00,-1.000000009864178363e+00,0.000000000000000000e+00,1.062598329670935596e-09,0.000000000000000000e+00 +3.812173677574315178e+01,2.579900000000000091e+02,0.000000000000000000e+00,1.013352712618459606e+01,0.000000000000000000e+00,-1.000000009863129868e+00,0.000000000000000000e+00,5.292223504046715240e-10,0.000000000000000000e+00 +3.812272359897611551e+01,2.580000000000000000e+02,0.000000000000000000e+00,1.013254030294189789e+01,0.000000000000000000e+00,-1.000000009862607619e+00,0.000000000000000000e+00,-5.577442377056698625e-10,0.000000000000000000e+00 +3.812371051831726732e+01,2.580099999999999909e+02,0.000000000000000000e+00,1.013155338359100988e+01,0.000000000000000000e+00,-1.000000009863158068e+00,0.000000000000000000e+00,-3.644443964704854578e-10,0.000000000000000000e+00 +3.812469753379469495e+01,2.580199999999999818e+02,0.000000000000000000e+00,1.013056636810384603e+01,0.000000000000000000e+00,-1.000000009863517780e+00,0.000000000000000000e+00,-7.063234085579423185e-10,0.000000000000000000e+00 +3.812568464543649327e+01,2.580300000000000296e+02,0.000000000000000000e+00,1.012957925645230794e+01,0.000000000000000000e+00,-1.000000009864215000e+00,0.000000000000000000e+00,2.505629324398099910e-10,0.000000000000000000e+00 +3.812667185327077846e+01,2.580400000000000205e+02,0.000000000000000000e+00,1.012859204860828299e+01,0.000000000000000000e+00,-1.000000009863967643e+00,0.000000000000000000e+00,-1.130571907833695850e-09,0.000000000000000000e+00 +3.812765915732567379e+01,2.580500000000000114e+02,0.000000000000000000e+00,1.012760474454364612e+01,0.000000000000000000e+00,-1.000000009865083861e+00,0.000000000000000000e+00,2.448921413835243312e-09,0.000000000000000000e+00 +3.812864655762932387e+01,2.580600000000000023e+02,0.000000000000000000e+00,1.012661734423025628e+01,0.000000000000000000e+00,-1.000000009862665795e+00,0.000000000000000000e+00,-1.754551951216958153e-09,0.000000000000000000e+00 +3.812963405420988039e+01,2.580699999999999932e+02,0.000000000000000000e+00,1.012562984763996354e+01,0.000000000000000000e+00,-1.000000009864398409e+00,0.000000000000000000e+00,-9.784782117201268445e-10,0.000000000000000000e+00 +3.813062164709550217e+01,2.580799999999999841e+02,0.000000000000000000e+00,1.012464225474459667e+01,0.000000000000000000e+00,-1.000000009865364747e+00,0.000000000000000000e+00,1.141596447808824999e-09,0.000000000000000000e+00 +3.813160933631437643e+01,2.580900000000000318e+02,0.000000000000000000e+00,1.012365456551597553e+01,0.000000000000000000e+00,-1.000000009864237205e+00,0.000000000000000000e+00,-8.465602240044926720e-10,0.000000000000000000e+00 +3.813259712189469752e+01,2.581000000000000227e+02,0.000000000000000000e+00,1.012266677992590758e+01,0.000000000000000000e+00,-1.000000009865073425e+00,0.000000000000000000e+00,3.495147913931081219e-10,0.000000000000000000e+00 +3.813358500386467398e+01,2.581100000000000136e+02,0.000000000000000000e+00,1.012167889794618247e+01,0.000000000000000000e+00,-1.000000009864728145e+00,0.000000000000000000e+00,-7.216607520744752971e-10,0.000000000000000000e+00 +3.813457298225252856e+01,2.581200000000000045e+02,0.000000000000000000e+00,1.012069091954857925e+01,0.000000000000000000e+00,-1.000000009865441131e+00,0.000000000000000000e+00,-4.101221790659116890e-10,0.000000000000000000e+00 +3.813556105708649824e+01,2.581299999999999955e+02,0.000000000000000000e+00,1.011970284470486092e+01,0.000000000000000000e+00,-1.000000009865846362e+00,0.000000000000000000e+00,1.292039616563943413e-09,0.000000000000000000e+00 +3.813654922839483419e+01,2.581399999999999864e+02,0.000000000000000000e+00,1.011871467338677810e+01,0.000000000000000000e+00,-1.000000009864569606e+00,0.000000000000000000e+00,-1.060717113544806396e-09,0.000000000000000000e+00 +3.813753749620579470e+01,2.581499999999999773e+02,0.000000000000000000e+00,1.011772640556606895e+01,0.000000000000000000e+00,-1.000000009865617878e+00,0.000000000000000000e+00,-1.846694154344976053e-10,0.000000000000000000e+00 +3.813852586054765936e+01,2.581600000000000250e+02,0.000000000000000000e+00,1.011673804121445386e+01,0.000000000000000000e+00,-1.000000009865800399e+00,0.000000000000000000e+00,2.929262700344913850e-10,0.000000000000000000e+00 +3.813951432144872200e+01,2.581700000000000159e+02,0.000000000000000000e+00,1.011574958030364257e+01,0.000000000000000000e+00,-1.000000009865510853e+00,0.000000000000000000e+00,-1.435962172877251623e-09,0.000000000000000000e+00 +3.814050287893728353e+01,2.581800000000000068e+02,0.000000000000000000e+00,1.011476102280533063e+01,0.000000000000000000e+00,-1.000000009866930384e+00,0.000000000000000000e+00,1.908814305125405746e-09,0.000000000000000000e+00 +3.814149153304165907e+01,2.581899999999999977e+02,0.000000000000000000e+00,1.011377236869119756e+01,0.000000000000000000e+00,-1.000000009865043227e+00,0.000000000000000000e+00,-2.384493380764032885e-09,0.000000000000000000e+00 +3.814248028379018507e+01,2.581999999999999886e+02,0.000000000000000000e+00,1.011278361793291403e+01,0.000000000000000000e+00,-1.000000009867400896e+00,0.000000000000000000e+00,2.047436909531626144e-09,0.000000000000000000e+00 +3.814346913121121219e+01,2.582099999999999795e+02,0.000000000000000000e+00,1.011179477050212938e+01,0.000000000000000000e+00,-1.000000009865376294e+00,0.000000000000000000e+00,-1.137004462088925851e-09,0.000000000000000000e+00 +3.814445807533309818e+01,2.582200000000000273e+02,0.000000000000000000e+00,1.011080582637048764e+01,0.000000000000000000e+00,-1.000000009866500728e+00,0.000000000000000000e+00,-1.027783837440045871e-09,0.000000000000000000e+00 +3.814544711618421502e+01,2.582300000000000182e+02,0.000000000000000000e+00,1.010981678550961149e+01,0.000000000000000000e+00,-1.000000009867517248e+00,0.000000000000000000e+00,5.665951611583400294e-10,0.000000000000000000e+00 +3.814643625379295599e+01,2.582400000000000091e+02,0.000000000000000000e+00,1.010882764789111299e+01,0.000000000000000000e+00,-1.000000009866956807e+00,0.000000000000000000e+00,2.513963918290961656e-11,0.000000000000000000e+00 +3.814742548818771439e+01,2.582500000000000000e+02,0.000000000000000000e+00,1.010783841348659173e+01,0.000000000000000000e+00,-1.000000009866931938e+00,0.000000000000000000e+00,9.879809125516553775e-10,0.000000000000000000e+00 +3.814841481939691192e+01,2.582599999999999909e+02,0.000000000000000000e+00,1.010684908226763135e+01,0.000000000000000000e+00,-1.000000009865954498e+00,0.000000000000000000e+00,-1.978910262488663929e-09,0.000000000000000000e+00 +3.814940424744897740e+01,2.582699999999999818e+02,0.000000000000000000e+00,1.010585965420580301e+01,0.000000000000000000e+00,-1.000000009867912487e+00,0.000000000000000000e+00,2.071167340041303386e-10,0.000000000000000000e+00 +3.815039377237235385e+01,2.582800000000000296e+02,0.000000000000000000e+00,1.010487012927266015e+01,0.000000000000000000e+00,-1.000000009867707540e+00,0.000000000000000000e+00,2.972944761766854563e-10,0.000000000000000000e+00 +3.815138339419549851e+01,2.582900000000000205e+02,0.000000000000000000e+00,1.010388050743974730e+01,0.000000000000000000e+00,-1.000000009867413331e+00,0.000000000000000000e+00,1.159895784385322771e-10,0.000000000000000000e+00 +3.815237311294688993e+01,2.583000000000000114e+02,0.000000000000000000e+00,1.010289078867859303e+01,0.000000000000000000e+00,-1.000000009867298534e+00,0.000000000000000000e+00,-3.263990432939534443e-10,0.000000000000000000e+00 +3.815336292865500667e+01,2.583100000000000023e+02,0.000000000000000000e+00,1.010190097296071166e+01,0.000000000000000000e+00,-1.000000009867621609e+00,0.000000000000000000e+00,-1.020149423270340380e-09,0.000000000000000000e+00 +3.815435284134834859e+01,2.583199999999999932e+02,0.000000000000000000e+00,1.010091106025760332e+01,0.000000000000000000e+00,-1.000000009868631468e+00,0.000000000000000000e+00,1.669355343325514461e-09,0.000000000000000000e+00 +3.815534285105542978e+01,2.583299999999999841e+02,0.000000000000000000e+00,1.009992105054075395e+01,0.000000000000000000e+00,-1.000000009866978790e+00,0.000000000000000000e+00,-1.310594713185512463e-09,0.000000000000000000e+00 +3.815633295780477852e+01,2.583400000000000318e+02,0.000000000000000000e+00,1.009893094378163880e+01,0.000000000000000000e+00,-1.000000009868276418e+00,0.000000000000000000e+00,-8.873228761650852151e-10,0.000000000000000000e+00 +3.815732316162493021e+01,2.583500000000000227e+02,0.000000000000000000e+00,1.009794073995171360e+01,0.000000000000000000e+00,-1.000000009869155049e+00,0.000000000000000000e+00,1.134325571326216262e-09,0.000000000000000000e+00 +3.815831346254444867e+01,2.583600000000000136e+02,0.000000000000000000e+00,1.009695043902242340e+01,0.000000000000000000e+00,-1.000000009868031725e+00,0.000000000000000000e+00,-6.692290512973360945e-10,0.000000000000000000e+00 +3.815930386059189772e+01,2.583700000000000045e+02,0.000000000000000000e+00,1.009596004096520083e+01,0.000000000000000000e+00,-1.000000009868694528e+00,0.000000000000000000e+00,-8.536597170482160350e-10,0.000000000000000000e+00 +3.816029435579586249e+01,2.583799999999999955e+02,0.000000000000000000e+00,1.009496954575146077e+01,0.000000000000000000e+00,-1.000000009869540074e+00,0.000000000000000000e+00,5.892991635954156021e-10,0.000000000000000000e+00 +3.816128494818494232e+01,2.583899999999999864e+02,0.000000000000000000e+00,1.009397895335260564e+01,0.000000000000000000e+00,-1.000000009868956319e+00,0.000000000000000000e+00,4.886063580024897339e-11,0.000000000000000000e+00 +3.816227563778774368e+01,2.583999999999999773e+02,0.000000000000000000e+00,1.009298826374002545e+01,0.000000000000000000e+00,-1.000000009868907913e+00,0.000000000000000000e+00,1.155059637077206925e-09,0.000000000000000000e+00 +3.816326642463289431e+01,2.584100000000000250e+02,0.000000000000000000e+00,1.009199747688509419e+01,0.000000000000000000e+00,-1.000000009867763495e+00,0.000000000000000000e+00,-1.510348801452410963e-09,0.000000000000000000e+00 +3.816425730874903621e+01,2.584200000000000159e+02,0.000000000000000000e+00,1.009100659275917344e+01,0.000000000000000000e+00,-1.000000009869260076e+00,0.000000000000000000e+00,-7.002042413078428471e-10,0.000000000000000000e+00 +3.816524829016482556e+01,2.584300000000000068e+02,0.000000000000000000e+00,1.009001561133360703e+01,0.000000000000000000e+00,-1.000000009869953965e+00,0.000000000000000000e+00,-2.397263877213386888e-11,0.000000000000000000e+00 +3.816623936890892566e+01,2.584399999999999977e+02,0.000000000000000000e+00,1.008902453257972809e+01,0.000000000000000000e+00,-1.000000009869977724e+00,0.000000000000000000e+00,5.284663567274434928e-10,0.000000000000000000e+00 +3.816723054501001400e+01,2.584499999999999886e+02,0.000000000000000000e+00,1.008803335646885557e+01,0.000000000000000000e+00,-1.000000009869453921e+00,0.000000000000000000e+00,-8.402215172534850894e-10,0.000000000000000000e+00 +3.816822181849678941e+01,2.584599999999999795e+02,0.000000000000000000e+00,1.008704208297229421e+01,0.000000000000000000e+00,-1.000000009870286810e+00,0.000000000000000000e+00,1.301756226950944452e-09,0.000000000000000000e+00 +3.816921318939796492e+01,2.584700000000000273e+02,0.000000000000000000e+00,1.008605071206133275e+01,0.000000000000000000e+00,-1.000000009868996287e+00,0.000000000000000000e+00,-2.070914793748793572e-09,0.000000000000000000e+00 +3.817020465774226068e+01,2.584800000000000182e+02,0.000000000000000000e+00,1.008505924370724927e+01,0.000000000000000000e+00,-1.000000009871049533e+00,0.000000000000000000e+00,1.699877676819155259e-09,0.000000000000000000e+00 +3.817119622355841813e+01,2.584900000000000091e+02,0.000000000000000000e+00,1.008406767788130232e+01,0.000000000000000000e+00,-1.000000009869363993e+00,0.000000000000000000e+00,-1.830026910705748249e-09,0.000000000000000000e+00 +3.817218788687519293e+01,2.585000000000000000e+02,0.000000000000000000e+00,1.008307601455474334e+01,0.000000000000000000e+00,-1.000000009871178763e+00,0.000000000000000000e+00,-4.477785260161734224e-12,0.000000000000000000e+00 +3.817317964772134076e+01,2.585099999999999909e+02,0.000000000000000000e+00,1.008208425369880246e+01,0.000000000000000000e+00,-1.000000009871183204e+00,0.000000000000000000e+00,1.765864800899489040e-09,0.000000000000000000e+00 +3.817417150612565280e+01,2.585199999999999818e+02,0.000000000000000000e+00,1.008109239528470091e+01,0.000000000000000000e+00,-1.000000009869431716e+00,0.000000000000000000e+00,-1.924397337532969633e-09,0.000000000000000000e+00 +3.817516346211692024e+01,2.585300000000000296e+02,0.000000000000000000e+00,1.008010043928364574e+01,0.000000000000000000e+00,-1.000000009871340634e+00,0.000000000000000000e+00,-2.325522964511541239e-10,0.000000000000000000e+00 +3.817615551572394850e+01,2.585400000000000205e+02,0.000000000000000000e+00,1.007910838566682443e+01,0.000000000000000000e+00,-1.000000009871571338e+00,0.000000000000000000e+00,1.433894057422498583e-09,0.000000000000000000e+00 +3.817714766697556428e+01,2.585500000000000114e+02,0.000000000000000000e+00,1.007811623440541560e+01,0.000000000000000000e+00,-1.000000009870148698e+00,0.000000000000000000e+00,-5.231956147442287450e-10,0.000000000000000000e+00 +3.817813991590060141e+01,2.585600000000000023e+02,0.000000000000000000e+00,1.007712398547058363e+01,0.000000000000000000e+00,-1.000000009870667839e+00,0.000000000000000000e+00,-6.799978311954358171e-10,0.000000000000000000e+00 +3.817913226252791503e+01,2.585699999999999932e+02,0.000000000000000000e+00,1.007613163883347518e+01,0.000000000000000000e+00,-1.000000009871342632e+00,0.000000000000000000e+00,-8.313995085697010465e-10,0.000000000000000000e+00 +3.818012470688636739e+01,2.585799999999999841e+02,0.000000000000000000e+00,1.007513919446522443e+01,0.000000000000000000e+00,-1.000000009872167750e+00,0.000000000000000000e+00,8.362393068874986737e-10,0.000000000000000000e+00 +3.818111724900484205e+01,2.585900000000000318e+02,0.000000000000000000e+00,1.007414665233695139e+01,0.000000000000000000e+00,-1.000000009871337747e+00,0.000000000000000000e+00,-1.077743196264067745e-09,0.000000000000000000e+00 +3.818210988891222968e+01,2.586000000000000227e+02,0.000000000000000000e+00,1.007315401241976360e+01,0.000000000000000000e+00,-1.000000009872407558e+00,0.000000000000000000e+00,6.493109627315656982e-10,0.000000000000000000e+00 +3.818310262663744226e+01,2.586100000000000136e+02,0.000000000000000000e+00,1.007216127468475086e+01,0.000000000000000000e+00,-1.000000009871762963e+00,0.000000000000000000e+00,6.192782857539675462e-10,0.000000000000000000e+00 +3.818409546220939887e+01,2.586200000000000045e+02,0.000000000000000000e+00,1.007116843910299231e+01,0.000000000000000000e+00,-1.000000009871148121e+00,0.000000000000000000e+00,-1.157482284259649739e-09,0.000000000000000000e+00 +3.818508839565703994e+01,2.586299999999999955e+02,0.000000000000000000e+00,1.007017550564555108e+01,0.000000000000000000e+00,-1.000000009872297424e+00,0.000000000000000000e+00,-1.066809026393998124e-09,0.000000000000000000e+00 +3.818608142700931296e+01,2.586399999999999864e+02,0.000000000000000000e+00,1.006918247428347435e+01,0.000000000000000000e+00,-1.000000009873356799e+00,0.000000000000000000e+00,8.994654153502959383e-10,0.000000000000000000e+00 +3.818707455629518677e+01,2.586499999999999773e+02,0.000000000000000000e+00,1.006818934498779683e+01,0.000000000000000000e+00,-1.000000009872463513e+00,0.000000000000000000e+00,1.149986017315135027e-09,0.000000000000000000e+00 +3.818806778354363729e+01,2.586600000000000250e+02,0.000000000000000000e+00,1.006719611772954082e+01,0.000000000000000000e+00,-1.000000009871321316e+00,0.000000000000000000e+00,-2.105044712778149877e-09,0.000000000000000000e+00 +3.818906110878366178e+01,2.586700000000000159e+02,0.000000000000000000e+00,1.006620279247971261e+01,0.000000000000000000e+00,-1.000000009873412310e+00,0.000000000000000000e+00,1.464020644509170210e-10,0.000000000000000000e+00 +3.819005453204426459e+01,2.586800000000000068e+02,0.000000000000000000e+00,1.006520936920930076e+01,0.000000000000000000e+00,-1.000000009873266871e+00,0.000000000000000000e+00,7.120472445065934519e-10,0.000000000000000000e+00 +3.819104805335447139e+01,2.586899999999999977e+02,0.000000000000000000e+00,1.006421584788928492e+01,0.000000000000000000e+00,-1.000000009872559437e+00,0.000000000000000000e+00,-3.966601076489047281e-10,0.000000000000000000e+00 +3.819204167274331496e+01,2.586999999999999886e+02,0.000000000000000000e+00,1.006322222849062875e+01,0.000000000000000000e+00,-1.000000009872953566e+00,0.000000000000000000e+00,4.296913124288143839e-10,0.000000000000000000e+00 +3.819303539023984939e+01,2.587099999999999795e+02,0.000000000000000000e+00,1.006222851098427995e+01,0.000000000000000000e+00,-1.000000009872526574e+00,0.000000000000000000e+00,-3.981457653917438662e-10,0.000000000000000000e+00 +3.819402920587314298e+01,2.587200000000000273e+02,0.000000000000000000e+00,1.006123469534117376e+01,0.000000000000000000e+00,-1.000000009872922258e+00,0.000000000000000000e+00,-1.070329945238136641e-09,0.000000000000000000e+00 +3.819502311967227115e+01,2.587300000000000182e+02,0.000000000000000000e+00,1.006024078153222945e+01,0.000000000000000000e+00,-1.000000009873986073e+00,0.000000000000000000e+00,2.209250145698365659e-10,0.000000000000000000e+00 +3.819601713166633061e+01,2.587400000000000091e+02,0.000000000000000000e+00,1.005924676952835206e+01,0.000000000000000000e+00,-1.000000009873766471e+00,0.000000000000000000e+00,-1.103399128542960370e-10,0.000000000000000000e+00 +3.819701124188443231e+01,2.587500000000000000e+02,0.000000000000000000e+00,1.005825265930043422e+01,0.000000000000000000e+00,-1.000000009873876161e+00,0.000000000000000000e+00,-2.566154467928116293e-10,0.000000000000000000e+00 +3.819800545035569428e+01,2.587599999999999909e+02,0.000000000000000000e+00,1.005725845081935255e+01,0.000000000000000000e+00,-1.000000009874131290e+00,0.000000000000000000e+00,1.589339957297071793e-09,0.000000000000000000e+00 +3.819899975710926299e+01,2.587699999999999818e+02,0.000000000000000000e+00,1.005626414405596947e+01,0.000000000000000000e+00,-1.000000009872550999e+00,0.000000000000000000e+00,-1.749284568409380766e-09,0.000000000000000000e+00 +3.819999416217427779e+01,2.587800000000000296e+02,0.000000000000000000e+00,1.005526973898113496e+01,0.000000000000000000e+00,-1.000000009874290496e+00,0.000000000000000000e+00,5.173208524937698319e-10,0.000000000000000000e+00 +3.820098866557991357e+01,2.587900000000000205e+02,0.000000000000000000e+00,1.005427523556567948e+01,0.000000000000000000e+00,-1.000000009873776019e+00,0.000000000000000000e+00,-5.831283659340503701e-10,0.000000000000000000e+00 +3.820198326735534522e+01,2.588000000000000114e+02,0.000000000000000000e+00,1.005328063378042458e+01,0.000000000000000000e+00,-1.000000009874356000e+00,0.000000000000000000e+00,-1.447631457153565410e-09,0.000000000000000000e+00 +3.820297796752977604e+01,2.588100000000000023e+02,0.000000000000000000e+00,1.005228593359617406e+01,0.000000000000000000e+00,-1.000000009875795959e+00,0.000000000000000000e+00,1.524047740333204882e-09,0.000000000000000000e+00 +3.820397276613240933e+01,2.588199999999999932e+02,0.000000000000000000e+00,1.005129113498371751e+01,0.000000000000000000e+00,-1.000000009874279838e+00,0.000000000000000000e+00,-6.338411312113158687e-10,0.000000000000000000e+00 +3.820496766319246973e+01,2.588299999999999841e+02,0.000000000000000000e+00,1.005029623791383386e+01,0.000000000000000000e+00,-1.000000009874910445e+00,0.000000000000000000e+00,1.063140937005913026e-09,0.000000000000000000e+00 +3.820596265873919606e+01,2.588400000000000318e+02,0.000000000000000000e+00,1.004930124235728250e+01,0.000000000000000000e+00,-1.000000009873852624e+00,0.000000000000000000e+00,-5.524929375350458098e-10,0.000000000000000000e+00 +3.820695775280184137e+01,2.588500000000000227e+02,0.000000000000000000e+00,1.004830614828481217e+01,0.000000000000000000e+00,-1.000000009874402407e+00,0.000000000000000000e+00,-1.881101255567268836e-09,0.000000000000000000e+00 +3.820795294540967291e+01,2.588600000000000136e+02,0.000000000000000000e+00,1.004731095566715382e+01,0.000000000000000000e+00,-1.000000009876274465e+00,0.000000000000000000e+00,6.730779745389226938e-10,0.000000000000000000e+00 +3.820894823659197215e+01,2.588700000000000045e+02,0.000000000000000000e+00,1.004631566447502422e+01,0.000000000000000000e+00,-1.000000009875604556e+00,0.000000000000000000e+00,1.739077258205929780e-09,0.000000000000000000e+00 +3.820994362637803476e+01,2.588799999999999955e+02,0.000000000000000000e+00,1.004532027467912947e+01,0.000000000000000000e+00,-1.000000009873873497e+00,0.000000000000000000e+00,-2.256383078128678076e-09,0.000000000000000000e+00 +3.821093911479717775e+01,2.588899999999999864e+02,0.000000000000000000e+00,1.004432478625015968e+01,0.000000000000000000e+00,-1.000000009876119700e+00,0.000000000000000000e+00,1.244723804739992020e-09,0.000000000000000000e+00 +3.821193470187871810e+01,2.588999999999999773e+02,0.000000000000000000e+00,1.004332919915878541e+01,0.000000000000000000e+00,-1.000000009874880469e+00,0.000000000000000000e+00,-2.086227738520972532e-09,0.000000000000000000e+00 +3.821293038765200123e+01,2.589100000000000250e+02,0.000000000000000000e+00,1.004233351337567015e+01,0.000000000000000000e+00,-1.000000009876957696e+00,0.000000000000000000e+00,2.096055218852727895e-09,0.000000000000000000e+00 +3.821392617214637966e+01,2.589200000000000159e+02,0.000000000000000000e+00,1.004133772887145604e+01,0.000000000000000000e+00,-1.000000009874870477e+00,0.000000000000000000e+00,-5.308736812912981118e-10,0.000000000000000000e+00 +3.821492205539122011e+01,2.589300000000000068e+02,0.000000000000000000e+00,1.004034184561677812e+01,0.000000000000000000e+00,-1.000000009875399165e+00,0.000000000000000000e+00,-9.992187555608467825e-10,0.000000000000000000e+00 +3.821591803741591065e+01,2.589399999999999977e+02,0.000000000000000000e+00,1.003934586358225012e+01,0.000000000000000000e+00,-1.000000009876394369e+00,0.000000000000000000e+00,6.999633319992485742e-10,0.000000000000000000e+00 +3.821691411824984641e+01,2.589499999999999886e+02,0.000000000000000000e+00,1.003834978273847334e+01,0.000000000000000000e+00,-1.000000009875697149e+00,0.000000000000000000e+00,-7.944018470968910817e-10,0.000000000000000000e+00 +3.821791029792244387e+01,2.589599999999999795e+02,0.000000000000000000e+00,1.003735360305603663e+01,0.000000000000000000e+00,-1.000000009876488516e+00,0.000000000000000000e+00,-1.016305538169238232e-10,0.000000000000000000e+00 +3.821890657646312661e+01,2.589700000000000273e+02,0.000000000000000000e+00,1.003635732450551110e+01,0.000000000000000000e+00,-1.000000009876589768e+00,0.000000000000000000e+00,-7.909013920375252612e-10,0.000000000000000000e+00 +3.821990295390133952e+01,2.589800000000000182e+02,0.000000000000000000e+00,1.003536094705745541e+01,0.000000000000000000e+00,-1.000000009877377805e+00,0.000000000000000000e+00,7.264250687068442531e-10,0.000000000000000000e+00 +3.822089943026654169e+01,2.589900000000000091e+02,0.000000000000000000e+00,1.003436447068241222e+01,0.000000000000000000e+00,-1.000000009876653939e+00,0.000000000000000000e+00,8.820954841988564813e-10,0.000000000000000000e+00 +3.822189600558819933e+01,2.590000000000000000e+02,0.000000000000000000e+00,1.003336789535091178e+01,0.000000000000000000e+00,-1.000000009875774865e+00,0.000000000000000000e+00,-2.101090248919455938e-09,0.000000000000000000e+00 +3.822289267989579997e+01,2.590099999999999909e+02,0.000000000000000000e+00,1.003237122103346834e+01,0.000000000000000000e+00,-1.000000009877868967e+00,0.000000000000000000e+00,7.291045768563218234e-10,0.000000000000000000e+00 +3.822388945321884535e+01,2.590199999999999818e+02,0.000000000000000000e+00,1.003137444770057840e+01,0.000000000000000000e+00,-1.000000009877142215e+00,0.000000000000000000e+00,4.405822075515373879e-10,0.000000000000000000e+00 +3.822488632558685140e+01,2.590300000000000296e+02,0.000000000000000000e+00,1.003037757532272956e+01,0.000000000000000000e+00,-1.000000009876703011e+00,0.000000000000000000e+00,-1.166380045036000299e-09,0.000000000000000000e+00 +3.822588329702934118e+01,2.590400000000000205e+02,0.000000000000000000e+00,1.002938060387039165e+01,0.000000000000000000e+00,-1.000000009877865859e+00,0.000000000000000000e+00,1.279171484039476980e-09,0.000000000000000000e+00 +3.822688036757586616e+01,2.590500000000000114e+02,0.000000000000000000e+00,1.002838353331401855e+01,0.000000000000000000e+00,-1.000000009876590434e+00,0.000000000000000000e+00,-1.146775456741071222e-09,0.000000000000000000e+00 +3.822787753725598492e+01,2.590600000000000023e+02,0.000000000000000000e+00,1.002738636362405344e+01,0.000000000000000000e+00,-1.000000009877733964e+00,0.000000000000000000e+00,4.994100158663695345e-10,0.000000000000000000e+00 +3.822887480609927024e+01,2.590699999999999932e+02,0.000000000000000000e+00,1.002638909477092000e+01,0.000000000000000000e+00,-1.000000009877235918e+00,0.000000000000000000e+00,-9.176831705347717867e-10,0.000000000000000000e+00 +3.822987217413530914e+01,2.590799999999999841e+02,0.000000000000000000e+00,1.002539172672503121e+01,0.000000000000000000e+00,-1.000000009878151186e+00,0.000000000000000000e+00,-2.938431071636725156e-11,0.000000000000000000e+00 +3.823086964139370281e+01,2.590900000000000318e+02,0.000000000000000000e+00,1.002439425945678231e+01,0.000000000000000000e+00,-1.000000009878180496e+00,0.000000000000000000e+00,1.387602784085419426e-09,0.000000000000000000e+00 +3.823186720790407378e+01,2.591000000000000227e+02,0.000000000000000000e+00,1.002339669293655611e+01,0.000000000000000000e+00,-1.000000009876796270e+00,0.000000000000000000e+00,-2.009753966297036773e-09,0.000000000000000000e+00 +3.823286487369605169e+01,2.591100000000000136e+02,0.000000000000000000e+00,1.002239902713472119e+01,0.000000000000000000e+00,-1.000000009878801333e+00,0.000000000000000000e+00,4.967136619474720573e-10,0.000000000000000000e+00 +3.823386263879928748e+01,2.591200000000000045e+02,0.000000000000000000e+00,1.002140126202162662e+01,0.000000000000000000e+00,-1.000000009878305729e+00,0.000000000000000000e+00,-5.785515018454086154e-12,0.000000000000000000e+00 +3.823486050324344632e+01,2.591299999999999955e+02,0.000000000000000000e+00,1.002040339756761256e+01,0.000000000000000000e+00,-1.000000009878311502e+00,0.000000000000000000e+00,6.274433768358604941e-11,0.000000000000000000e+00 +3.823585846705820046e+01,2.591399999999999864e+02,0.000000000000000000e+00,1.001940543374300141e+01,0.000000000000000000e+00,-1.000000009878248886e+00,0.000000000000000000e+00,-1.071886920995219291e-09,0.000000000000000000e+00 +3.823685653027324349e+01,2.591499999999999773e+02,0.000000000000000000e+00,1.001840737051810137e+01,0.000000000000000000e+00,-1.000000009879318696e+00,0.000000000000000000e+00,1.950693256526597116e-09,0.000000000000000000e+00 +3.823785469291827610e+01,2.591600000000000250e+02,0.000000000000000000e+00,1.001740920786320466e+01,0.000000000000000000e+00,-1.000000009877371587e+00,0.000000000000000000e+00,-1.557018168952649325e-09,0.000000000000000000e+00 +3.823885295502302739e+01,2.591700000000000159e+02,0.000000000000000000e+00,1.001641094574859281e+01,0.000000000000000000e+00,-1.000000009878925900e+00,0.000000000000000000e+00,-8.876343234761081096e-10,0.000000000000000000e+00 +3.823985131661723358e+01,2.591800000000000068e+02,0.000000000000000000e+00,1.001541258414452606e+01,0.000000000000000000e+00,-1.000000009879812080e+00,0.000000000000000000e+00,2.184728247792385250e-09,0.000000000000000000e+00 +3.824084977773063798e+01,2.591899999999999977e+02,0.000000000000000000e+00,1.001441412302125400e+01,0.000000000000000000e+00,-1.000000009877630713e+00,0.000000000000000000e+00,-3.019934484810341088e-09,0.000000000000000000e+00 +3.824184833839301234e+01,2.591999999999999886e+02,0.000000000000000000e+00,1.001341556234901375e+01,0.000000000000000000e+00,-1.000000009880646301e+00,0.000000000000000000e+00,1.326050611846197245e-09,0.000000000000000000e+00 +3.824284699863414261e+01,2.592099999999999795e+02,0.000000000000000000e+00,1.001241690209801938e+01,0.000000000000000000e+00,-1.000000009879322027e+00,0.000000000000000000e+00,9.793209899409522812e-10,0.000000000000000000e+00 +3.824384575848381473e+01,2.592200000000000273e+02,0.000000000000000000e+00,1.001141814223847959e+01,0.000000000000000000e+00,-1.000000009878343921e+00,0.000000000000000000e+00,-2.265218032469153850e-09,0.000000000000000000e+00 +3.824484461797184309e+01,2.592300000000000182e+02,0.000000000000000000e+00,1.001041928274058357e+01,0.000000000000000000e+00,-1.000000009880606555e+00,0.000000000000000000e+00,2.284774587464132389e-09,0.000000000000000000e+00 +3.824584357712805627e+01,2.592400000000000091e+02,0.000000000000000000e+00,1.000942032357450273e+01,0.000000000000000000e+00,-1.000000009878324159e+00,0.000000000000000000e+00,-1.382418499954094792e-09,0.000000000000000000e+00 +3.824684263598228995e+01,2.592500000000000000e+02,0.000000000000000000e+00,1.000842126471040139e+01,0.000000000000000000e+00,-1.000000009879705276e+00,0.000000000000000000e+00,-7.958113401357979706e-10,0.000000000000000000e+00 +3.824784179456440114e+01,2.592599999999999909e+02,0.000000000000000000e+00,1.000742210611842076e+01,0.000000000000000000e+00,-1.000000009880500418e+00,0.000000000000000000e+00,4.941937251425303281e-10,0.000000000000000000e+00 +3.824884105290425396e+01,2.592699999999999818e+02,0.000000000000000000e+00,1.000642284776869140e+01,0.000000000000000000e+00,-1.000000009880006591e+00,0.000000000000000000e+00,7.187756592704034099e-10,0.000000000000000000e+00 +3.824984041103174093e+01,2.592800000000000296e+02,0.000000000000000000e+00,1.000542348963132966e+01,0.000000000000000000e+00,-1.000000009879288276e+00,0.000000000000000000e+00,-1.888402759983394043e-09,0.000000000000000000e+00 +3.825083986897676169e+01,2.592900000000000205e+02,0.000000000000000000e+00,1.000442403167643590e+01,0.000000000000000000e+00,-1.000000009881175655e+00,0.000000000000000000e+00,1.573437722698671862e-09,0.000000000000000000e+00 +3.825183942676923010e+01,2.593000000000000114e+02,0.000000000000000000e+00,1.000342447387409273e+01,0.000000000000000000e+00,-1.000000009879602914e+00,0.000000000000000000e+00,-1.330946895971098213e-09,0.000000000000000000e+00 +3.825283908443907421e+01,2.593100000000000023e+02,0.000000000000000000e+00,1.000242481619437385e+01,0.000000000000000000e+00,-1.000000009880933405e+00,0.000000000000000000e+00,7.529137341788267918e-11,0.000000000000000000e+00 +3.825383884201623630e+01,2.593199999999999932e+02,0.000000000000000000e+00,1.000142505860733166e+01,0.000000000000000000e+00,-1.000000009880858132e+00,0.000000000000000000e+00,4.694691873895683717e-10,0.000000000000000000e+00 +3.825483869953067995e+01,2.593299999999999841e+02,0.000000000000000000e+00,1.000042520108300792e+01,0.000000000000000000e+00,-1.000000009880388729e+00,0.000000000000000000e+00,-1.367852925119790682e-10,0.000000000000000000e+00 +3.825583865701238295e+01,2.593400000000000318e+02,0.000000000000000000e+00,9.999425243591428369e+00,0.000000000000000000e+00,-1.000000009880525509e+00,0.000000000000000000e+00,4.374027302550567949e-11,0.000000000000000000e+00 +3.825683871449133022e+01,2.593500000000000227e+02,0.000000000000000000e+00,9.998425186102602780e+00,0.000000000000000000e+00,-1.000000009880481766e+00,0.000000000000000000e+00,-7.557208044571441324e-10,0.000000000000000000e+00 +3.825783887199752087e+01,2.593600000000000136e+02,0.000000000000000000e+00,9.997425028586526707e+00,0.000000000000000000e+00,-1.000000009881237606e+00,0.000000000000000000e+00,-7.469876988340487185e-10,0.000000000000000000e+00 +3.825883912956098243e+01,2.593700000000000045e+02,0.000000000000000000e+00,9.996424771013179722e+00,0.000000000000000000e+00,-1.000000009881984786e+00,0.000000000000000000e+00,1.853631542985813445e-09,0.000000000000000000e+00 +3.825983948721174954e+01,2.593799999999999955e+02,0.000000000000000000e+00,9.995424413352527182e+00,0.000000000000000000e+00,-1.000000009880130492e+00,0.000000000000000000e+00,-1.817713223170196576e-09,0.000000000000000000e+00 +3.826083994497987106e+01,2.593899999999999864e+02,0.000000000000000000e+00,9.994423955574522012e+00,0.000000000000000000e+00,-1.000000009881949037e+00,0.000000000000000000e+00,6.733076825241179912e-10,0.000000000000000000e+00 +3.826184050289541005e+01,2.593999999999999773e+02,0.000000000000000000e+00,9.993423397649095818e+00,0.000000000000000000e+00,-1.000000009881275354e+00,0.000000000000000000e+00,4.635461232125095066e-10,0.000000000000000000e+00 +3.826284116098844379e+01,2.594100000000000250e+02,0.000000000000000000e+00,9.992422739546171329e+00,0.000000000000000000e+00,-1.000000009880811502e+00,0.000000000000000000e+00,-6.605259116472018446e-10,0.000000000000000000e+00 +3.826384191928907086e+01,2.594200000000000159e+02,0.000000000000000000e+00,9.991421981235653504e+00,0.000000000000000000e+00,-1.000000009881472529e+00,0.000000000000000000e+00,-9.151483054158820991e-10,0.000000000000000000e+00 +3.826484277782740406e+01,2.594300000000000068e+02,0.000000000000000000e+00,9.990421122687431321e+00,0.000000000000000000e+00,-1.000000009882388463e+00,0.000000000000000000e+00,-2.901561397478138576e-10,0.000000000000000000e+00 +3.826584373663356331e+01,2.594399999999999977e+02,0.000000000000000000e+00,9.989420163871379543e+00,0.000000000000000000e+00,-1.000000009882678897e+00,0.000000000000000000e+00,1.224389463251763022e-09,0.000000000000000000e+00 +3.826684479573768982e+01,2.594499999999999886e+02,0.000000000000000000e+00,9.988419104757358724e+00,0.000000000000000000e+00,-1.000000009881453211e+00,0.000000000000000000e+00,9.425966939251300978e-11,0.000000000000000000e+00 +3.826784595516993903e+01,2.594599999999999795e+02,0.000000000000000000e+00,9.987417945315215206e+00,0.000000000000000000e+00,-1.000000009881358842e+00,0.000000000000000000e+00,-1.896314457692014360e-09,0.000000000000000000e+00 +3.826884721496048058e+01,2.594700000000000273e+02,0.000000000000000000e+00,9.986416685514777569e+00,0.000000000000000000e+00,-1.000000009883257546e+00,0.000000000000000000e+00,5.776405013372619891e-10,0.000000000000000000e+00 +3.826984857513950544e+01,2.594800000000000182e+02,0.000000000000000000e+00,9.985415325325858404e+00,0.000000000000000000e+00,-1.000000009882679119e+00,0.000000000000000000e+00,4.401157087834801489e-10,0.000000000000000000e+00 +3.827085003573720456e+01,2.594900000000000091e+02,0.000000000000000000e+00,9.984413864718259646e+00,0.000000000000000000e+00,-1.000000009882238361e+00,0.000000000000000000e+00,-5.263122940766506485e-10,0.000000000000000000e+00 +3.827185159678380444e+01,2.595000000000000000e+02,0.000000000000000000e+00,9.983412303661765463e+00,0.000000000000000000e+00,-1.000000009882765495e+00,0.000000000000000000e+00,1.230525052911578731e-09,0.000000000000000000e+00 +3.827285325830952445e+01,2.595099999999999909e+02,0.000000000000000000e+00,9.982410642126144040e+00,0.000000000000000000e+00,-1.000000009881532925e+00,0.000000000000000000e+00,-1.360734168276698317e-09,0.000000000000000000e+00 +3.827385502034461950e+01,2.595199999999999818e+02,0.000000000000000000e+00,9.981408880081151125e+00,0.000000000000000000e+00,-1.000000009882896057e+00,0.000000000000000000e+00,5.616149790138721274e-10,0.000000000000000000e+00 +3.827485688291934451e+01,2.595300000000000296e+02,0.000000000000000000e+00,9.980407017496522926e+00,0.000000000000000000e+00,-1.000000009882333396e+00,0.000000000000000000e+00,-1.841575388081742002e-09,0.000000000000000000e+00 +3.827585884606398281e+01,2.595400000000000205e+02,0.000000000000000000e+00,9.979405054341984993e+00,0.000000000000000000e+00,-1.000000009884178587e+00,0.000000000000000000e+00,2.058102891327537210e-09,0.000000000000000000e+00 +3.827686090980881772e+01,2.595500000000000114e+02,0.000000000000000000e+00,9.978402990587243337e+00,0.000000000000000000e+00,-1.000000009882116236e+00,0.000000000000000000e+00,-1.883081402298558429e-09,0.000000000000000000e+00 +3.827786307418416101e+01,2.595600000000000023e+02,0.000000000000000000e+00,9.977400826201995088e+00,0.000000000000000000e+00,-1.000000009884003394e+00,0.000000000000000000e+00,4.973635915300417628e-10,0.000000000000000000e+00 +3.827886533922033863e+01,2.595699999999999932e+02,0.000000000000000000e+00,9.976398561155914280e+00,0.000000000000000000e+00,-1.000000009883504903e+00,0.000000000000000000e+00,3.661734653624010264e-10,0.000000000000000000e+00 +3.827986770494767654e+01,2.595799999999999841e+02,0.000000000000000000e+00,9.975396195418666068e+00,0.000000000000000000e+00,-1.000000009883137864e+00,0.000000000000000000e+00,-4.961561712088572260e-10,0.000000000000000000e+00 +3.828087017139653625e+01,2.595900000000000318e+02,0.000000000000000000e+00,9.974393728959897842e+00,0.000000000000000000e+00,-1.000000009883635244e+00,0.000000000000000000e+00,-3.122812044028190480e-10,0.000000000000000000e+00 +3.828187273859728634e+01,2.596000000000000227e+02,0.000000000000000000e+00,9.973391161749241007e+00,0.000000000000000000e+00,-1.000000009883948326e+00,0.000000000000000000e+00,9.289985652646952265e-10,0.000000000000000000e+00 +3.828287540658030252e+01,2.596100000000000136e+02,0.000000000000000000e+00,9.972388493756312755e+00,0.000000000000000000e+00,-1.000000009883016849e+00,0.000000000000000000e+00,-2.967182184761764744e-10,0.000000000000000000e+00 +3.828387817537598892e+01,2.596200000000000045e+02,0.000000000000000000e+00,9.971385724950716067e+00,0.000000000000000000e+00,-1.000000009883314389e+00,0.000000000000000000e+00,-4.434827084915112264e-10,0.000000000000000000e+00 +3.828488104501475675e+01,2.596299999999999955e+02,0.000000000000000000e+00,9.970382855302036162e+00,0.000000000000000000e+00,-1.000000009883759144e+00,0.000000000000000000e+00,-1.267883189821955694e-09,0.000000000000000000e+00 +3.828588401552703857e+01,2.596399999999999864e+02,0.000000000000000000e+00,9.969379884779844048e+00,0.000000000000000000e+00,-1.000000009885030794e+00,0.000000000000000000e+00,7.725628092343596337e-10,0.000000000000000000e+00 +3.828688708694327403e+01,2.596499999999999773e+02,0.000000000000000000e+00,9.968376813353694743e+00,0.000000000000000000e+00,-1.000000009884255858e+00,0.000000000000000000e+00,3.906693874082660500e-10,0.000000000000000000e+00 +3.828789025929392409e+01,2.596600000000000250e+02,0.000000000000000000e+00,9.967373640993130834e+00,0.000000000000000000e+00,-1.000000009883863950e+00,0.000000000000000000e+00,-6.356314829354896475e-10,0.000000000000000000e+00 +3.828889353260946393e+01,2.596700000000000159e+02,0.000000000000000000e+00,9.966370367667677144e+00,0.000000000000000000e+00,-1.000000009884501662e+00,0.000000000000000000e+00,-5.308936071209914331e-10,0.000000000000000000e+00 +3.828989690692038295e+01,2.596800000000000068e+02,0.000000000000000000e+00,9.965366993346842506e+00,0.000000000000000000e+00,-1.000000009885034347e+00,0.000000000000000000e+00,7.138350781707305980e-10,0.000000000000000000e+00 +3.829090038225718473e+01,2.596899999999999977e+02,0.000000000000000000e+00,9.964363518000121545e+00,0.000000000000000000e+00,-1.000000009884318031e+00,0.000000000000000000e+00,-4.170625007888835211e-10,0.000000000000000000e+00 +3.829190395865039420e+01,2.596999999999999886e+02,0.000000000000000000e+00,9.963359941596994673e+00,0.000000000000000000e+00,-1.000000009884736585e+00,0.000000000000000000e+00,-3.860481511816339729e-10,0.000000000000000000e+00 +3.829290763613054338e+01,2.597099999999999795e+02,0.000000000000000000e+00,9.962356264106924542e+00,0.000000000000000000e+00,-1.000000009885124053e+00,0.000000000000000000e+00,8.171451080143605376e-10,0.000000000000000000e+00 +3.829391141472818560e+01,2.597200000000000273e+02,0.000000000000000000e+00,9.961352485499359588e+00,0.000000000000000000e+00,-1.000000009884303820e+00,0.000000000000000000e+00,-3.218262959770250546e-10,0.000000000000000000e+00 +3.829491529447388842e+01,2.597300000000000182e+02,0.000000000000000000e+00,9.960348605743734041e+00,0.000000000000000000e+00,-1.000000009884626895e+00,0.000000000000000000e+00,-2.673874780333245720e-10,0.000000000000000000e+00 +3.829591927539823359e+01,2.597400000000000091e+02,0.000000000000000000e+00,9.959344624809464364e+00,0.000000000000000000e+00,-1.000000009884895347e+00,0.000000000000000000e+00,-7.702371480225204599e-10,0.000000000000000000e+00 +3.829692335753181709e+01,2.597500000000000000e+02,0.000000000000000000e+00,9.958340542665952810e+00,0.000000000000000000e+00,-1.000000009885668728e+00,0.000000000000000000e+00,-5.881780805403787232e-11,0.000000000000000000e+00 +3.829792754090525619e+01,2.597599999999999909e+02,0.000000000000000000e+00,9.957336359282585647e+00,0.000000000000000000e+00,-1.000000009885727792e+00,0.000000000000000000e+00,1.165182675087344459e-10,0.000000000000000000e+00 +3.829893182554917530e+01,2.597699999999999818e+02,0.000000000000000000e+00,9.956332074628734929e+00,0.000000000000000000e+00,-1.000000009885610774e+00,0.000000000000000000e+00,-2.332341062224089213e-10,0.000000000000000000e+00 +3.829993621149422722e+01,2.597800000000000296e+02,0.000000000000000000e+00,9.955327688673756725e+00,0.000000000000000000e+00,-1.000000009885845031e+00,0.000000000000000000e+00,6.633790937395898897e-10,0.000000000000000000e+00 +3.830094069877106477e+01,2.597900000000000205e+02,0.000000000000000000e+00,9.954323201386991116e+00,0.000000000000000000e+00,-1.000000009885178676e+00,0.000000000000000000e+00,-7.039817483715530225e-10,0.000000000000000000e+00 +3.830194528741036208e+01,2.598000000000000114e+02,0.000000000000000000e+00,9.953318612737763971e+00,0.000000000000000000e+00,-1.000000009885885888e+00,0.000000000000000000e+00,9.567439346223457281e-10,0.000000000000000000e+00 +3.830294997744280749e+01,2.598100000000000023e+02,0.000000000000000000e+00,9.952313922695383397e+00,0.000000000000000000e+00,-1.000000009884924657e+00,0.000000000000000000e+00,-1.383370865772295501e-09,0.000000000000000000e+00 +3.830395476889911066e+01,2.598199999999999932e+02,0.000000000000000000e+00,9.951309131229145066e+00,0.000000000000000000e+00,-1.000000009886314656e+00,0.000000000000000000e+00,-6.750433411341081163e-10,0.000000000000000000e+00 +3.830495966180999545e+01,2.598299999999999841e+02,0.000000000000000000e+00,9.950304238308325111e+00,0.000000000000000000e+00,-1.000000009886993002e+00,0.000000000000000000e+00,1.332495999345206998e-09,0.000000000000000000e+00 +3.830596465620619995e+01,2.598400000000000318e+02,0.000000000000000000e+00,9.949299243902187229e+00,0.000000000000000000e+00,-1.000000009885653851e+00,0.000000000000000000e+00,-6.263048603397148436e-10,0.000000000000000000e+00 +3.830696975211846933e+01,2.598500000000000227e+02,0.000000000000000000e+00,9.948294147979980906e+00,0.000000000000000000e+00,-1.000000009886283348e+00,0.000000000000000000e+00,4.943663767948790511e-10,0.000000000000000000e+00 +3.830797494957757721e+01,2.598600000000000136e+02,0.000000000000000000e+00,9.947288950510936090e+00,0.000000000000000000e+00,-1.000000009885786412e+00,0.000000000000000000e+00,-5.698553960335632043e-10,0.000000000000000000e+00 +3.830898024861430429e+01,2.598700000000000045e+02,0.000000000000000000e+00,9.946283651464270292e+00,0.000000000000000000e+00,-1.000000009886359287e+00,0.000000000000000000e+00,-2.917453102121281362e-10,0.000000000000000000e+00 +3.830998564925945260e+01,2.598799999999999955e+02,0.000000000000000000e+00,9.945278250809183263e+00,0.000000000000000000e+00,-1.000000009886652608e+00,0.000000000000000000e+00,-4.180303154473327199e-10,0.000000000000000000e+00 +3.831099115154383128e+01,2.598899999999999864e+02,0.000000000000000000e+00,9.944272748514860538e+00,0.000000000000000000e+00,-1.000000009887072938e+00,0.000000000000000000e+00,8.180907181298280942e-10,0.000000000000000000e+00 +3.831199675549827788e+01,2.598999999999999773e+02,0.000000000000000000e+00,9.943267144550471670e+00,0.000000000000000000e+00,-1.000000009886250263e+00,0.000000000000000000e+00,-1.841125134980500841e-09,0.000000000000000000e+00 +3.831300246115363706e+01,2.599100000000000250e+02,0.000000000000000000e+00,9.942261438885171998e+00,0.000000000000000000e+00,-1.000000009888101893e+00,0.000000000000000000e+00,2.152434875427165667e-09,0.000000000000000000e+00 +3.831400826854076769e+01,2.599200000000000159e+02,0.000000000000000000e+00,9.941255631488097322e+00,0.000000000000000000e+00,-1.000000009885936958e+00,0.000000000000000000e+00,-1.238131882286646963e-09,0.000000000000000000e+00 +3.831501417769054285e+01,2.599300000000000068e+02,0.000000000000000000e+00,9.940249722328374560e+00,0.000000000000000000e+00,-1.000000009887182406e+00,0.000000000000000000e+00,2.886989899765327252e-10,0.000000000000000000e+00 +3.831602018863386405e+01,2.599399999999999977e+02,0.000000000000000000e+00,9.939243711375107537e+00,0.000000000000000000e+00,-1.000000009886891972e+00,0.000000000000000000e+00,-2.033709440858935237e-09,0.000000000000000000e+00 +3.831702630140163279e+01,2.599499999999999886e+02,0.000000000000000000e+00,9.938237598597389422e+00,0.000000000000000000e+00,-1.000000009888938113e+00,0.000000000000000000e+00,2.335163846031330953e-09,0.000000000000000000e+00 +3.831803251602477900e+01,2.599599999999999795e+02,0.000000000000000000e+00,9.937231383964293840e+00,0.000000000000000000e+00,-1.000000009886588437e+00,0.000000000000000000e+00,-6.306201626531383146e-10,0.000000000000000000e+00 +3.831903883253423970e+01,2.599700000000000273e+02,0.000000000000000000e+00,9.936225067444885539e+00,0.000000000000000000e+00,-1.000000009887223040e+00,0.000000000000000000e+00,-3.936012742471833469e-10,0.000000000000000000e+00 +3.832004525096096614e+01,2.599800000000000182e+02,0.000000000000000000e+00,9.935218649008206171e+00,0.000000000000000000e+00,-1.000000009887619168e+00,0.000000000000000000e+00,-4.504777990915699867e-10,0.000000000000000000e+00 +3.832105177133593799e+01,2.599900000000000091e+02,0.000000000000000000e+00,9.934212128623284954e+00,0.000000000000000000e+00,-1.000000009888072583e+00,0.000000000000000000e+00,9.617454584009427816e-10,0.000000000000000000e+00 +3.832205839369013489e+01,2.600000000000000000e+02,0.000000000000000000e+00,9.933205506259135120e+00,0.000000000000000000e+00,-1.000000009887104468e+00,0.000000000000000000e+00,-1.404314874572419160e-09,0.000000000000000000e+00 +3.832306511805455784e+01,2.600099999999999909e+02,0.000000000000000000e+00,9.932198781884755689e+00,0.000000000000000000e+00,-1.000000009888518226e+00,0.000000000000000000e+00,1.226418021051081716e-09,0.000000000000000000e+00 +3.832407194446022913e+01,2.600199999999999818e+02,0.000000000000000000e+00,9.931191955469126142e+00,0.000000000000000000e+00,-1.000000009887283436e+00,0.000000000000000000e+00,-1.650347427489394676e-09,0.000000000000000000e+00 +3.832507887293818527e+01,2.600300000000000296e+02,0.000000000000000000e+00,9.930185026981215302e+00,0.000000000000000000e+00,-1.000000009888945218e+00,0.000000000000000000e+00,4.897180648760830750e-10,0.000000000000000000e+00 +3.832608590351946987e+01,2.600400000000000205e+02,0.000000000000000000e+00,9.929177996389970673e+00,0.000000000000000000e+00,-1.000000009888452057e+00,0.000000000000000000e+00,6.497311034827922995e-10,0.000000000000000000e+00 +3.832709303623515495e+01,2.600500000000000114e+02,0.000000000000000000e+00,9.928170863664329104e+00,0.000000000000000000e+00,-1.000000009887797692e+00,0.000000000000000000e+00,-1.158903955695475611e-09,0.000000000000000000e+00 +3.832810027111631257e+01,2.600600000000000023e+02,0.000000000000000000e+00,9.927163628773209680e+00,0.000000000000000000e+00,-1.000000009888964980e+00,0.000000000000000000e+00,3.288775503957814182e-10,0.000000000000000000e+00 +3.832910760819405027e+01,2.600699999999999932e+02,0.000000000000000000e+00,9.926156291685513722e+00,0.000000000000000000e+00,-1.000000009888633690e+00,0.000000000000000000e+00,-1.293777028448105729e-10,0.000000000000000000e+00 +3.833011504749946852e+01,2.600799999999999841e+02,0.000000000000000000e+00,9.925148852370130115e+00,0.000000000000000000e+00,-1.000000009888764030e+00,0.000000000000000000e+00,9.787190181270886461e-10,0.000000000000000000e+00 +3.833112258906370329e+01,2.600900000000000318e+02,0.000000000000000000e+00,9.924141310795929982e+00,0.000000000000000000e+00,-1.000000009887777930e+00,0.000000000000000000e+00,-1.585712025519992122e-09,0.000000000000000000e+00 +3.833213023291789767e+01,2.601000000000000227e+02,0.000000000000000000e+00,9.923133666931770236e+00,0.000000000000000000e+00,-1.000000009889375763e+00,0.000000000000000000e+00,9.373171265620372593e-10,0.000000000000000000e+00 +3.833313797909321607e+01,2.601100000000000136e+02,0.000000000000000000e+00,9.922125920746488248e+00,0.000000000000000000e+00,-1.000000009888431185e+00,0.000000000000000000e+00,-1.892509741346078499e-10,0.000000000000000000e+00 +3.833414582762083000e+01,2.601200000000000045e+02,0.000000000000000000e+00,9.921118072208910732e+00,0.000000000000000000e+00,-1.000000009888621921e+00,0.000000000000000000e+00,-1.454374876368974108e-09,0.000000000000000000e+00 +3.833515377853192518e+01,2.601299999999999955e+02,0.000000000000000000e+00,9.920110121287844862e+00,0.000000000000000000e+00,-1.000000009890087860e+00,0.000000000000000000e+00,6.484769209851618201e-10,0.000000000000000000e+00 +3.833616183185771575e+01,2.601399999999999864e+02,0.000000000000000000e+00,9.919102067952081825e+00,0.000000000000000000e+00,-1.000000009889434160e+00,0.000000000000000000e+00,8.856184544655602936e-10,0.000000000000000000e+00 +3.833716998762943007e+01,2.601499999999999773e+02,0.000000000000000000e+00,9.918093912170400372e+00,0.000000000000000000e+00,-1.000000009888541319e+00,0.000000000000000000e+00,-7.304893913466607898e-10,0.000000000000000000e+00 +3.833817824587829648e+01,2.601600000000000250e+02,0.000000000000000000e+00,9.917085653911561494e+00,0.000000000000000000e+00,-1.000000009889277841e+00,0.000000000000000000e+00,-6.938613438362069384e-10,0.000000000000000000e+00 +3.833918660663557887e+01,2.601700000000000159e+02,0.000000000000000000e+00,9.916077293144308413e+00,0.000000000000000000e+00,-1.000000009889977504e+00,0.000000000000000000e+00,1.005787477194779536e-09,0.000000000000000000e+00 +3.834019506993254112e+01,2.601800000000000068e+02,0.000000000000000000e+00,9.915068829837370146e+00,0.000000000000000000e+00,-1.000000009888963204e+00,0.000000000000000000e+00,-8.608207285801608941e-10,0.000000000000000000e+00 +3.834120363580047552e+01,2.601899999999999977e+02,0.000000000000000000e+00,9.914060263959461494e+00,0.000000000000000000e+00,-1.000000009889831398e+00,0.000000000000000000e+00,7.037759411660714760e-10,0.000000000000000000e+00 +3.834221230427068150e+01,2.601999999999999886e+02,0.000000000000000000e+00,9.913051595479277722e+00,0.000000000000000000e+00,-1.000000009889121522e+00,0.000000000000000000e+00,-1.273139159169204185e-09,0.000000000000000000e+00 +3.834322107537447977e+01,2.602099999999999795e+02,0.000000000000000000e+00,9.912042824365501659e+00,0.000000000000000000e+00,-1.000000009890405828e+00,0.000000000000000000e+00,2.013837804136649767e-10,0.000000000000000000e+00 +3.834422994914320526e+01,2.602200000000000273e+02,0.000000000000000000e+00,9.911033950586796593e+00,0.000000000000000000e+00,-1.000000009890202657e+00,0.000000000000000000e+00,-9.683043119009117123e-11,0.000000000000000000e+00 +3.834523892560820713e+01,2.602300000000000182e+02,0.000000000000000000e+00,9.910024974111813378e+00,0.000000000000000000e+00,-1.000000009890300356e+00,0.000000000000000000e+00,-4.121475777665623456e-10,0.000000000000000000e+00 +3.834624800480085582e+01,2.602400000000000091e+02,0.000000000000000000e+00,9.909015894909185107e+00,0.000000000000000000e+00,-1.000000009890716246e+00,0.000000000000000000e+00,1.011231921599411724e-09,0.000000000000000000e+00 +3.834725718675252892e+01,2.602500000000000000e+02,0.000000000000000000e+00,9.908006712947528882e+00,0.000000000000000000e+00,-1.000000009889695729e+00,0.000000000000000000e+00,-1.047869257448243591e-09,0.000000000000000000e+00 +3.834826647149462531e+01,2.602599999999999909e+02,0.000000000000000000e+00,9.906997428195447597e+00,0.000000000000000000e+00,-1.000000009890753327e+00,0.000000000000000000e+00,3.977229956526022325e-10,0.000000000000000000e+00 +3.834927585905856517e+01,2.602699999999999818e+02,0.000000000000000000e+00,9.905988040621524604e+00,0.000000000000000000e+00,-1.000000009890351871e+00,0.000000000000000000e+00,1.273551725304824993e-10,0.000000000000000000e+00 +3.835028534947577583e+01,2.602800000000000296e+02,0.000000000000000000e+00,9.904978550194330822e+00,0.000000000000000000e+00,-1.000000009890223307e+00,0.000000000000000000e+00,-1.038091807113277960e-10,0.000000000000000000e+00 +3.835129494277769879e+01,2.602900000000000205e+02,0.000000000000000000e+00,9.903968956882419405e+00,0.000000000000000000e+00,-1.000000009890328112e+00,0.000000000000000000e+00,-2.841266753493184812e-10,0.000000000000000000e+00 +3.835230463899580400e+01,2.603000000000000114e+02,0.000000000000000000e+00,9.902959260654327522e+00,0.000000000000000000e+00,-1.000000009890614994e+00,0.000000000000000000e+00,-4.026183476892447400e-10,0.000000000000000000e+00 +3.835331443816156849e+01,2.603100000000000023e+02,0.000000000000000000e+00,9.901949461478576353e+00,0.000000000000000000e+00,-1.000000009891021557e+00,0.000000000000000000e+00,-4.483097216113577795e-10,0.000000000000000000e+00 +3.835432434030648352e+01,2.603199999999999932e+02,0.000000000000000000e+00,9.900939559323671091e+00,0.000000000000000000e+00,-1.000000009891474306e+00,0.000000000000000000e+00,1.330941758851300632e-09,0.000000000000000000e+00 +3.835533434546206166e+01,2.603299999999999841e+02,0.000000000000000000e+00,9.899929554158100942e+00,0.000000000000000000e+00,-1.000000009890130048e+00,0.000000000000000000e+00,-2.017531773824977437e-09,0.000000000000000000e+00 +3.835634445365982970e+01,2.603400000000000318e+02,0.000000000000000000e+00,9.898919445950340901e+00,0.000000000000000000e+00,-1.000000009892167974e+00,0.000000000000000000e+00,1.703890884941095961e-09,0.000000000000000000e+00 +3.835735466493133572e+01,2.603500000000000227e+02,0.000000000000000000e+00,9.897909234668844647e+00,0.000000000000000000e+00,-1.000000009890446684e+00,0.000000000000000000e+00,-1.419104832051248480e-09,0.000000000000000000e+00 +3.835836497930812783e+01,2.603600000000000136e+02,0.000000000000000000e+00,9.896898920282056977e+00,0.000000000000000000e+00,-1.000000009891880426e+00,0.000000000000000000e+00,8.082599973490679703e-10,0.000000000000000000e+00 +3.835937539682178965e+01,2.603700000000000045e+02,0.000000000000000000e+00,9.895888502758399596e+00,0.000000000000000000e+00,-1.000000009891063746e+00,0.000000000000000000e+00,-3.049892170332281606e-10,0.000000000000000000e+00 +3.836038591750391191e+01,2.603799999999999955e+02,0.000000000000000000e+00,9.894877982066283550e+00,0.000000000000000000e+00,-1.000000009891371944e+00,0.000000000000000000e+00,4.734759706826538998e-10,0.000000000000000000e+00 +3.836139654138609956e+01,2.603899999999999864e+02,0.000000000000000000e+00,9.893867358174100346e+00,0.000000000000000000e+00,-1.000000009890893438e+00,0.000000000000000000e+00,-2.062870196734119295e-09,0.000000000000000000e+00 +3.836240726849997884e+01,2.603999999999999773e+02,0.000000000000000000e+00,9.892856631050227278e+00,0.000000000000000000e+00,-1.000000009892978436e+00,0.000000000000000000e+00,2.529448741718085109e-09,0.000000000000000000e+00 +3.836341809887718313e+01,2.604100000000000250e+02,0.000000000000000000e+00,9.891845800663022104e+00,0.000000000000000000e+00,-1.000000009890421593e+00,0.000000000000000000e+00,-1.385289027151108184e-09,0.000000000000000000e+00 +3.836442903254937420e+01,2.604200000000000159e+02,0.000000000000000000e+00,9.890834866980833695e+00,0.000000000000000000e+00,-1.000000009891822028e+00,0.000000000000000000e+00,-1.625851687065063311e-09,0.000000000000000000e+00 +3.836544006954822095e+01,2.604300000000000068e+02,0.000000000000000000e+00,9.889823829971986058e+00,0.000000000000000000e+00,-1.000000009893465824e+00,0.000000000000000000e+00,1.816077134761247298e-09,0.000000000000000000e+00 +3.836645120990541358e+01,2.604399999999999977e+02,0.000000000000000000e+00,9.888812689604790762e+00,0.000000000000000000e+00,-1.000000009891629515e+00,0.000000000000000000e+00,2.643692038236482146e-10,0.000000000000000000e+00 +3.836746245365265651e+01,2.604499999999999886e+02,0.000000000000000000e+00,9.887801445847546944e+00,0.000000000000000000e+00,-1.000000009891362174e+00,0.000000000000000000e+00,-1.055392696573712690e-09,0.000000000000000000e+00 +3.836847380082166836e+01,2.604599999999999795e+02,0.000000000000000000e+00,9.886790098668532423e+00,0.000000000000000000e+00,-1.000000009892429542e+00,0.000000000000000000e+00,-3.964726972992631161e-10,0.000000000000000000e+00 +3.836948525144418909e+01,2.604700000000000273e+02,0.000000000000000000e+00,9.885778648036009031e+00,0.000000000000000000e+00,-1.000000009892830555e+00,0.000000000000000000e+00,5.151861712113905549e-10,0.000000000000000000e+00 +3.837049680555196574e+01,2.604800000000000182e+02,0.000000000000000000e+00,9.884767093918224390e+00,0.000000000000000000e+00,-1.000000009892309416e+00,0.000000000000000000e+00,-4.499461368497294785e-11,0.000000000000000000e+00 +3.837150846317677377e+01,2.604900000000000091e+02,0.000000000000000000e+00,9.883755436283410134e+00,0.000000000000000000e+00,-1.000000009892354935e+00,0.000000000000000000e+00,-3.287562587395720097e-10,0.000000000000000000e+00 +3.837252022435039578e+01,2.605000000000000000e+02,0.000000000000000000e+00,9.882743675099780134e+00,0.000000000000000000e+00,-1.000000009892687558e+00,0.000000000000000000e+00,-3.249921083985978991e-10,0.000000000000000000e+00 +3.837353208910463565e+01,2.605099999999999909e+02,0.000000000000000000e+00,9.881731810335532273e+00,0.000000000000000000e+00,-1.000000009893016406e+00,0.000000000000000000e+00,-2.303894497591121176e-11,0.000000000000000000e+00 +3.837454405747131148e+01,2.605199999999999818e+02,0.000000000000000000e+00,9.880719841958848448e+00,0.000000000000000000e+00,-1.000000009893039721e+00,0.000000000000000000e+00,5.888590072404287027e-10,0.000000000000000000e+00 +3.837555612948225559e+01,2.605300000000000296e+02,0.000000000000000000e+00,9.879707769937894568e+00,0.000000000000000000e+00,-1.000000009892443753e+00,0.000000000000000000e+00,-2.123536262677002111e-10,0.000000000000000000e+00 +3.837656830516931450e+01,2.605400000000000205e+02,0.000000000000000000e+00,9.878695594240820554e+00,0.000000000000000000e+00,-1.000000009892658692e+00,0.000000000000000000e+00,-6.806464820414528590e-10,0.000000000000000000e+00 +3.837758058456436316e+01,2.605500000000000114e+02,0.000000000000000000e+00,9.877683314835758566e+00,0.000000000000000000e+00,-1.000000009893347697e+00,0.000000000000000000e+00,9.286374148545963035e-10,0.000000000000000000e+00 +3.837859296769928363e+01,2.605600000000000023e+02,0.000000000000000000e+00,9.876670931690824773e+00,0.000000000000000000e+00,-1.000000009892407560e+00,0.000000000000000000e+00,-2.306223468143924448e-09,0.000000000000000000e+00 +3.837960545460597217e+01,2.605699999999999932e+02,0.000000000000000000e+00,9.875658444774121136e+00,0.000000000000000000e+00,-1.000000009894742581e+00,0.000000000000000000e+00,1.757120029876602806e-09,0.000000000000000000e+00 +3.838061804531634635e+01,2.605799999999999841e+02,0.000000000000000000e+00,9.874645854053728300e+00,0.000000000000000000e+00,-1.000000009892963337e+00,0.000000000000000000e+00,-7.318938313367905028e-10,0.000000000000000000e+00 +3.838163073986233798e+01,2.605900000000000318e+02,0.000000000000000000e+00,9.873633159497718026e+00,0.000000000000000000e+00,-1.000000009893704522e+00,0.000000000000000000e+00,6.331613581129638005e-10,0.000000000000000000e+00 +3.838264353827590014e+01,2.606000000000000227e+02,0.000000000000000000e+00,9.872620361074138984e+00,0.000000000000000000e+00,-1.000000009893063257e+00,0.000000000000000000e+00,-1.064513909762610252e-09,0.000000000000000000e+00 +3.838365644058899306e+01,2.606100000000000136e+02,0.000000000000000000e+00,9.871607458751027409e+00,0.000000000000000000e+00,-1.000000009894141506e+00,0.000000000000000000e+00,1.113065699066278357e-09,0.000000000000000000e+00 +3.838466944683359827e+01,2.606200000000000045e+02,0.000000000000000000e+00,9.870594452496399995e+00,0.000000000000000000e+00,-1.000000009893013964e+00,0.000000000000000000e+00,-1.478529080868112092e-09,0.000000000000000000e+00 +3.838568255704171150e+01,2.606299999999999955e+02,0.000000000000000000e+00,9.869581342278261005e+00,0.000000000000000000e+00,-1.000000009894511876e+00,0.000000000000000000e+00,1.556832570760330731e-09,0.000000000000000000e+00 +3.838669577124535692e+01,2.606399999999999864e+02,0.000000000000000000e+00,9.868568128064593381e+00,0.000000000000000000e+00,-1.000000009892934472e+00,0.000000000000000000e+00,-1.882732577758860926e-09,0.000000000000000000e+00 +3.838770908947655869e+01,2.606499999999999773e+02,0.000000000000000000e+00,9.867554809823369411e+00,0.000000000000000000e+00,-1.000000009894842279e+00,0.000000000000000000e+00,2.055850307338073671e-09,0.000000000000000000e+00 +3.838872251176736228e+01,2.606600000000000250e+02,0.000000000000000000e+00,9.866541387522538287e+00,0.000000000000000000e+00,-1.000000009892758834e+00,0.000000000000000000e+00,-2.184458928744242339e-09,0.000000000000000000e+00 +3.838973603814983449e+01,2.606700000000000159e+02,0.000000000000000000e+00,9.865527861130040321e+00,0.000000000000000000e+00,-1.000000009894972841e+00,0.000000000000000000e+00,9.734969678123905319e-10,0.000000000000000000e+00 +3.839074966865605631e+01,2.606800000000000068e+02,0.000000000000000000e+00,9.864514230613790957e+00,0.000000000000000000e+00,-1.000000009893986075e+00,0.000000000000000000e+00,-5.633611488673178689e-10,0.000000000000000000e+00 +3.839176340331812298e+01,2.606899999999999977e+02,0.000000000000000000e+00,9.863500495941696755e+00,0.000000000000000000e+00,-1.000000009894557174e+00,0.000000000000000000e+00,1.320652653691932379e-10,0.000000000000000000e+00 +3.839277724216814391e+01,2.606999999999999886e+02,0.000000000000000000e+00,9.862486657081642960e+00,0.000000000000000000e+00,-1.000000009894423281e+00,0.000000000000000000e+00,-3.854245037896151036e-10,0.000000000000000000e+00 +3.839379118523825696e+01,2.607099999999999795e+02,0.000000000000000000e+00,9.861472714001500606e+00,0.000000000000000000e+00,-1.000000009894814079e+00,0.000000000000000000e+00,1.351255732153850256e-09,0.000000000000000000e+00 +3.839480523256059996e+01,2.607200000000000273e+02,0.000000000000000000e+00,9.860458666669122962e+00,0.000000000000000000e+00,-1.000000009893443842e+00,0.000000000000000000e+00,-1.556050393958618093e-09,0.000000000000000000e+00 +3.839581938416733919e+01,2.607300000000000182e+02,0.000000000000000000e+00,9.859444515052349090e+00,0.000000000000000000e+00,-1.000000009895021913e+00,0.000000000000000000e+00,-4.593018097538387570e-10,0.000000000000000000e+00 +3.839683364009065514e+01,2.607400000000000091e+02,0.000000000000000000e+00,9.858430259118996730e+00,0.000000000000000000e+00,-1.000000009895487763e+00,0.000000000000000000e+00,1.198045858256297455e-09,0.000000000000000000e+00 +3.839784800036274248e+01,2.607500000000000000e+02,0.000000000000000000e+00,9.857415898836871193e+00,0.000000000000000000e+00,-1.000000009894272512e+00,0.000000000000000000e+00,-2.517103921664798977e-11,0.000000000000000000e+00 +3.839886246501581724e+01,2.607599999999999909e+02,0.000000000000000000e+00,9.856401434173761800e+00,0.000000000000000000e+00,-1.000000009894298048e+00,0.000000000000000000e+00,-2.389470640425031432e-09,0.000000000000000000e+00 +3.839987703408210251e+01,2.607699999999999818e+02,0.000000000000000000e+00,9.855386865097438331e+00,0.000000000000000000e+00,-1.000000009896722331e+00,0.000000000000000000e+00,2.743735028389686418e-09,0.000000000000000000e+00 +3.840089170759384274e+01,2.607800000000000296e+02,0.000000000000000000e+00,9.854372191575652806e+00,0.000000000000000000e+00,-1.000000009893938335e+00,0.000000000000000000e+00,-1.868208471737473967e-09,0.000000000000000000e+00 +3.840190648558330366e+01,2.607900000000000205e+02,0.000000000000000000e+00,9.853357413576148360e+00,0.000000000000000000e+00,-1.000000009895834152e+00,0.000000000000000000e+00,1.039026517203847757e-09,0.000000000000000000e+00 +3.840292136808276524e+01,2.608000000000000114e+02,0.000000000000000000e+00,9.852342531066641484e+00,0.000000000000000000e+00,-1.000000009894779662e+00,0.000000000000000000e+00,-5.983248745892679757e-10,0.000000000000000000e+00 +3.840393635512452164e+01,2.608100000000000023e+02,0.000000000000000000e+00,9.851327544014839788e+00,0.000000000000000000e+00,-1.000000009895386954e+00,0.000000000000000000e+00,1.303710742968720951e-10,0.000000000000000000e+00 +3.840495144674088834e+01,2.608199999999999932e+02,0.000000000000000000e+00,9.850312452388429563e+00,0.000000000000000000e+00,-1.000000009895254616e+00,0.000000000000000000e+00,-2.117218057298586470e-10,0.000000000000000000e+00 +3.840596664296418794e+01,2.608299999999999841e+02,0.000000000000000000e+00,9.849297256155082891e+00,0.000000000000000000e+00,-1.000000009895469555e+00,0.000000000000000000e+00,1.110987525560332373e-10,0.000000000000000000e+00 +3.840698194382677144e+01,2.608400000000000318e+02,0.000000000000000000e+00,9.848281955282454092e+00,0.000000000000000000e+00,-1.000000009895356756e+00,0.000000000000000000e+00,-6.136042599918526681e-10,0.000000000000000000e+00 +3.840799734936099696e+01,2.608500000000000227e+02,0.000000000000000000e+00,9.847266549738181496e+00,0.000000000000000000e+00,-1.000000009895979813e+00,0.000000000000000000e+00,-6.500560856797313877e-10,0.000000000000000000e+00 +3.840901285959924394e+01,2.608600000000000136e+02,0.000000000000000000e+00,9.846251039489885670e+00,0.000000000000000000e+00,-1.000000009896639952e+00,0.000000000000000000e+00,1.734178650574986154e-09,0.000000000000000000e+00 +3.841002847457390601e+01,2.608700000000000045e+02,0.000000000000000000e+00,9.845235424505171196e+00,0.000000000000000000e+00,-1.000000009894878694e+00,0.000000000000000000e+00,-2.058414255870848470e-09,0.000000000000000000e+00 +3.841104419431739814e+01,2.608799999999999955e+02,0.000000000000000000e+00,9.844219704751628441e+00,0.000000000000000000e+00,-1.000000009896969466e+00,0.000000000000000000e+00,1.758083880372515111e-09,0.000000000000000000e+00 +3.841206001886214949e+01,2.608899999999999864e+02,0.000000000000000000e+00,9.843203880196824684e+00,0.000000000000000000e+00,-1.000000009895183561e+00,0.000000000000000000e+00,-2.298627404152098381e-09,0.000000000000000000e+00 +3.841307594824060345e+01,2.608999999999999773e+02,0.000000000000000000e+00,9.842187950808318320e+00,0.000000000000000000e+00,-1.000000009897518805e+00,0.000000000000000000e+00,1.274746582004325040e-09,0.000000000000000000e+00 +3.841409198248522472e+01,2.609100000000000250e+02,0.000000000000000000e+00,9.841171916553642873e+00,0.000000000000000000e+00,-1.000000009896223618e+00,0.000000000000000000e+00,4.420617380415774368e-10,0.000000000000000000e+00 +3.841510812162849220e+01,2.609200000000000159e+02,0.000000000000000000e+00,9.840155777400322989e+00,0.000000000000000000e+00,-1.000000009895774422e+00,0.000000000000000000e+00,-1.341342954873882536e-09,0.000000000000000000e+00 +3.841612436570289901e+01,2.609300000000000068e+02,0.000000000000000000e+00,9.839139533315861996e+00,0.000000000000000000e+00,-1.000000009897137554e+00,0.000000000000000000e+00,1.094985598659261619e-09,0.000000000000000000e+00 +3.841714071474095960e+01,2.609399999999999977e+02,0.000000000000000000e+00,9.838123184267745458e+00,0.000000000000000000e+00,-1.000000009896024666e+00,0.000000000000000000e+00,-8.357905324054202823e-10,0.000000000000000000e+00 +3.841815716877520259e+01,2.609499999999999886e+02,0.000000000000000000e+00,9.837106730223446505e+00,0.000000000000000000e+00,-1.000000009896874209e+00,0.000000000000000000e+00,1.475478760563295329e-09,0.000000000000000000e+00 +3.841917372783817086e+01,2.609599999999999795e+02,0.000000000000000000e+00,9.836090171150416950e+00,0.000000000000000000e+00,-1.000000009895374298e+00,0.000000000000000000e+00,-2.274033647209752889e-09,0.000000000000000000e+00 +3.842019039196242858e+01,2.609700000000000273e+02,0.000000000000000000e+00,9.835073507016096173e+00,0.000000000000000000e+00,-1.000000009897686226e+00,0.000000000000000000e+00,1.678269521164093104e-09,0.000000000000000000e+00 +3.842120716118056123e+01,2.609800000000000182e+02,0.000000000000000000e+00,9.834056737787900460e+00,0.000000000000000000e+00,-1.000000009895979813e+00,0.000000000000000000e+00,-2.123331904041448687e-09,0.000000000000000000e+00 +3.842222403552516141e+01,2.609900000000000091e+02,0.000000000000000000e+00,9.833039863433237215e+00,0.000000000000000000e+00,-1.000000009898138975e+00,0.000000000000000000e+00,1.797134688084488946e-09,0.000000000000000000e+00 +3.842324101502884304e+01,2.610000000000000000e+02,0.000000000000000000e+00,9.832022883919488976e+00,0.000000000000000000e+00,-1.000000009896311326e+00,0.000000000000000000e+00,-2.921051538137104158e-10,0.000000000000000000e+00 +3.842425809972423423e+01,2.610099999999999909e+02,0.000000000000000000e+00,9.831005799214029395e+00,0.000000000000000000e+00,-1.000000009896608422e+00,0.000000000000000000e+00,-1.506652625464238340e-09,0.000000000000000000e+00 +3.842527528964398442e+01,2.610199999999999818e+02,0.000000000000000000e+00,9.829988609284209033e+00,0.000000000000000000e+00,-1.000000009898140974e+00,0.000000000000000000e+00,1.596860347630696969e-09,0.000000000000000000e+00 +3.842629258482076438e+01,2.610300000000000296e+02,0.000000000000000000e+00,9.828971314097362466e+00,0.000000000000000000e+00,-1.000000009896516495e+00,0.000000000000000000e+00,-1.269979323409054974e-09,0.000000000000000000e+00 +3.842730998528724484e+01,2.610400000000000205e+02,0.000000000000000000e+00,9.827953913620811832e+00,0.000000000000000000e+00,-1.000000009897808573e+00,0.000000000000000000e+00,2.046945007045124737e-10,0.000000000000000000e+00 +3.842832749107613211e+01,2.610500000000000114e+02,0.000000000000000000e+00,9.826936407821856179e+00,0.000000000000000000e+00,-1.000000009897600295e+00,0.000000000000000000e+00,8.826263668746261052e-10,0.000000000000000000e+00 +3.842934510222013245e+01,2.610600000000000023e+02,0.000000000000000000e+00,9.825918796667782118e+00,0.000000000000000000e+00,-1.000000009896702124e+00,0.000000000000000000e+00,-9.386070290610070396e-10,0.000000000000000000e+00 +3.843036281875198057e+01,2.610699999999999932e+02,0.000000000000000000e+00,9.824901080125858499e+00,0.000000000000000000e+00,-1.000000009897657360e+00,0.000000000000000000e+00,-1.012246753346523614e-10,0.000000000000000000e+00 +3.843138064070443249e+01,2.610799999999999841e+02,0.000000000000000000e+00,9.823883258163334631e+00,0.000000000000000000e+00,-1.000000009897760389e+00,0.000000000000000000e+00,-2.399474304577357453e-11,0.000000000000000000e+00 +3.843239856811024424e+01,2.610900000000000318e+02,0.000000000000000000e+00,9.822865330747445611e+00,0.000000000000000000e+00,-1.000000009897784814e+00,0.000000000000000000e+00,-6.944667777086769354e-10,0.000000000000000000e+00 +3.843341660100220736e+01,2.611000000000000227e+02,0.000000000000000000e+00,9.821847297845408775e+00,0.000000000000000000e+00,-1.000000009898491804e+00,0.000000000000000000e+00,1.326852382634668352e-09,0.000000000000000000e+00 +3.843443473941311339e+01,2.611100000000000136e+02,0.000000000000000000e+00,9.820829159424423693e+00,0.000000000000000000e+00,-1.000000009897140885e+00,0.000000000000000000e+00,-2.515611834022383117e-09,0.000000000000000000e+00 +3.843545298337578231e+01,2.611200000000000045e+02,0.000000000000000000e+00,9.819810915451675726e+00,0.000000000000000000e+00,-1.000000009899702391e+00,0.000000000000000000e+00,3.209165756548454608e-09,0.000000000000000000e+00 +3.843647133292304829e+01,2.611299999999999955e+02,0.000000000000000000e+00,9.818792565894327140e+00,0.000000000000000000e+00,-1.000000009896434339e+00,0.000000000000000000e+00,-2.043510754393185536e-09,0.000000000000000000e+00 +3.843748978808775973e+01,2.611399999999999864e+02,0.000000000000000000e+00,9.817774110719533098e+00,0.000000000000000000e+00,-1.000000009898515563e+00,0.000000000000000000e+00,-1.132065573660557431e-09,0.000000000000000000e+00 +3.843850834890279344e+01,2.611499999999999773e+02,0.000000000000000000e+00,9.816755549894420341e+00,0.000000000000000000e+00,-1.000000009899668640e+00,0.000000000000000000e+00,2.527210970392788349e-09,0.000000000000000000e+00 +3.843952701540102623e+01,2.611600000000000250e+02,0.000000000000000000e+00,9.815736883386104950e+00,0.000000000000000000e+00,-1.000000009897094255e+00,0.000000000000000000e+00,-1.324501242912775564e-09,0.000000000000000000e+00 +3.844054578761535623e+01,2.611700000000000159e+02,0.000000000000000000e+00,9.814718111161688796e+00,0.000000000000000000e+00,-1.000000009898443620e+00,0.000000000000000000e+00,-6.914935416872056814e-10,0.000000000000000000e+00 +3.844156466557870999e+01,2.611800000000000068e+02,0.000000000000000000e+00,9.813699233188248883e+00,0.000000000000000000e+00,-1.000000009899148168e+00,0.000000000000000000e+00,1.012182181140617654e-09,0.000000000000000000e+00 +3.844258364932402117e+01,2.611899999999999977e+02,0.000000000000000000e+00,9.812680249432849777e+00,0.000000000000000000e+00,-1.000000009898116771e+00,0.000000000000000000e+00,-1.332150546429931868e-09,0.000000000000000000e+00 +3.844360273888424473e+01,2.611999999999999886e+02,0.000000000000000000e+00,9.811661159862540060e+00,0.000000000000000000e+00,-1.000000009899474351e+00,0.000000000000000000e+00,8.396426245418415302e-10,0.000000000000000000e+00 +3.844462193429234986e+01,2.612099999999999795e+02,0.000000000000000000e+00,9.810641964444346996e+00,0.000000000000000000e+00,-1.000000009898618591e+00,0.000000000000000000e+00,6.981772381574409904e-10,0.000000000000000000e+00 +3.844564123558131996e+01,2.612200000000000273e+02,0.000000000000000000e+00,9.809622663145285415e+00,0.000000000000000000e+00,-1.000000009897906939e+00,0.000000000000000000e+00,-1.743192483097992957e-09,0.000000000000000000e+00 +3.844666064278416684e+01,2.612300000000000182e+02,0.000000000000000000e+00,9.808603255932350606e+00,0.000000000000000000e+00,-1.000000009899683961e+00,0.000000000000000000e+00,3.654595795644529474e-10,0.000000000000000000e+00 +3.844768015593390942e+01,2.612400000000000091e+02,0.000000000000000000e+00,9.807583742772518320e+00,0.000000000000000000e+00,-1.000000009899311371e+00,0.000000000000000000e+00,1.979548441206673017e-10,0.000000000000000000e+00 +3.844869977506358083e+01,2.612500000000000000e+02,0.000000000000000000e+00,9.806564123632751873e+00,0.000000000000000000e+00,-1.000000009899109532e+00,0.000000000000000000e+00,1.184121594206886007e-09,0.000000000000000000e+00 +3.844971950020624263e+01,2.612599999999999909e+02,0.000000000000000000e+00,9.805544398479995039e+00,0.000000000000000000e+00,-1.000000009897902054e+00,0.000000000000000000e+00,-1.787101764854610668e-09,0.000000000000000000e+00 +3.845073933139497058e+01,2.612699999999999818e+02,0.000000000000000000e+00,9.804524567281175607e+00,0.000000000000000000e+00,-1.000000009899724596e+00,0.000000000000000000e+00,-1.645843588718902519e-10,0.000000000000000000e+00 +3.845175926866284755e+01,2.612800000000000296e+02,0.000000000000000000e+00,9.803504630003200049e+00,0.000000000000000000e+00,-1.000000009899892461e+00,0.000000000000000000e+00,9.397311703845683242e-10,0.000000000000000000e+00 +3.845277931204298483e+01,2.612900000000000205e+02,0.000000000000000000e+00,9.802484586612962403e+00,0.000000000000000000e+00,-1.000000009898933895e+00,0.000000000000000000e+00,-1.695562688690865369e-10,0.000000000000000000e+00 +3.845379946156850792e+01,2.613000000000000114e+02,0.000000000000000000e+00,9.801464437077338943e+00,0.000000000000000000e+00,-1.000000009899106868e+00,0.000000000000000000e+00,-1.770688366155264917e-09,0.000000000000000000e+00 +3.845481971727256365e+01,2.613100000000000023e+02,0.000000000000000000e+00,9.800444181363186402e+00,0.000000000000000000e+00,-1.000000009900913422e+00,0.000000000000000000e+00,1.265640555887699086e-09,0.000000000000000000e+00 +3.845584007918830594e+01,2.613199999999999932e+02,0.000000000000000000e+00,9.799423819437343752e+00,0.000000000000000000e+00,-1.000000009899622011e+00,0.000000000000000000e+00,4.199504737626219474e-10,0.000000000000000000e+00 +3.845686054734891002e+01,2.613299999999999841e+02,0.000000000000000000e+00,9.798403351266637529e+00,0.000000000000000000e+00,-1.000000009899193465e+00,0.000000000000000000e+00,-8.824568629769985635e-10,0.000000000000000000e+00 +3.845788112178757245e+01,2.613400000000000318e+02,0.000000000000000000e+00,9.797382776817872951e+00,0.000000000000000000e+00,-1.000000009900094078e+00,0.000000000000000000e+00,7.820764276780301651e-10,0.000000000000000000e+00 +3.845890180253750401e+01,2.613500000000000227e+02,0.000000000000000000e+00,9.796362096057837476e+00,0.000000000000000000e+00,-1.000000009899295828e+00,0.000000000000000000e+00,-1.396497243548540510e-09,0.000000000000000000e+00 +3.845992258963192967e+01,2.613600000000000136e+02,0.000000000000000000e+00,9.795341308953304349e+00,0.000000000000000000e+00,-1.000000009900721354e+00,0.000000000000000000e+00,1.118821384277341864e-09,0.000000000000000000e+00 +3.846094348310410282e+01,2.613700000000000045e+02,0.000000000000000000e+00,9.794320415471025498e+00,0.000000000000000000e+00,-1.000000009899579156e+00,0.000000000000000000e+00,-1.831161398030767867e-10,0.000000000000000000e+00 +3.846196448298728399e+01,2.613799999999999955e+02,0.000000000000000000e+00,9.793299415577740419e+00,0.000000000000000000e+00,-1.000000009899766118e+00,0.000000000000000000e+00,-1.763559482011688896e-10,0.000000000000000000e+00 +3.846298558931474787e+01,2.613899999999999864e+02,0.000000000000000000e+00,9.792278309240167289e+00,0.000000000000000000e+00,-1.000000009899946196e+00,0.000000000000000000e+00,-5.529302291673087756e-10,0.000000000000000000e+00 +3.846400680211979761e+01,2.613999999999999773e+02,0.000000000000000000e+00,9.791257096425008299e+00,0.000000000000000000e+00,-1.000000009900510856e+00,0.000000000000000000e+00,4.019903159522240391e-10,0.000000000000000000e+00 +3.846502812143574346e+01,2.614100000000000250e+02,0.000000000000000000e+00,9.790235777098947878e+00,0.000000000000000000e+00,-1.000000009900100295e+00,0.000000000000000000e+00,-7.049857281311996106e-10,0.000000000000000000e+00 +3.846604954729592407e+01,2.614200000000000159e+02,0.000000000000000000e+00,9.789214351228654465e+00,0.000000000000000000e+00,-1.000000009900820386e+00,0.000000000000000000e+00,-4.562475047371382886e-10,0.000000000000000000e+00 +3.846707107973368522e+01,2.614300000000000068e+02,0.000000000000000000e+00,9.788192818780776960e+00,0.000000000000000000e+00,-1.000000009901286457e+00,0.000000000000000000e+00,1.159734461375943502e-09,0.000000000000000000e+00 +3.846809271878240111e+01,2.614399999999999977e+02,0.000000000000000000e+00,9.787171179721948278e+00,0.000000000000000000e+00,-1.000000009900101627e+00,0.000000000000000000e+00,-9.501180375291874999e-10,0.000000000000000000e+00 +3.846911446447544591e+01,2.614499999999999886e+02,0.000000000000000000e+00,9.786149434018785342e+00,0.000000000000000000e+00,-1.000000009901072406e+00,0.000000000000000000e+00,3.324631377765450386e-11,0.000000000000000000e+00 +3.847013631684622936e+01,2.614599999999999795e+02,0.000000000000000000e+00,9.785127581637883765e+00,0.000000000000000000e+00,-1.000000009901038434e+00,0.000000000000000000e+00,7.180888474359204205e-10,0.000000000000000000e+00 +3.847115827592816828e+01,2.614700000000000273e+02,0.000000000000000000e+00,9.784105622545824943e+00,0.000000000000000000e+00,-1.000000009900304576e+00,0.000000000000000000e+00,-5.833183624245461386e-10,0.000000000000000000e+00 +3.847218034175470081e+01,2.614800000000000182e+02,0.000000000000000000e+00,9.783083556709172512e+00,0.000000000000000000e+00,-1.000000009900900766e+00,0.000000000000000000e+00,-4.566134500772518467e-10,0.000000000000000000e+00 +3.847320251435927929e+01,2.614900000000000091e+02,0.000000000000000000e+00,9.782061384094470569e+00,0.000000000000000000e+00,-1.000000009901367504e+00,0.000000000000000000e+00,1.108181928036744003e-09,0.000000000000000000e+00 +3.847422479377537741e+01,2.615000000000000000e+02,0.000000000000000000e+00,9.781039104668247219e+00,0.000000000000000000e+00,-1.000000009900234632e+00,0.000000000000000000e+00,-9.749331240284265602e-10,0.000000000000000000e+00 +3.847524718003649014e+01,2.615099999999999909e+02,0.000000000000000000e+00,9.780016718397014586e+00,0.000000000000000000e+00,-1.000000009901231390e+00,0.000000000000000000e+00,1.051054375023986613e-10,0.000000000000000000e+00 +3.847626967317611957e+01,2.615199999999999818e+02,0.000000000000000000e+00,9.778994225247263472e+00,0.000000000000000000e+00,-1.000000009901123921e+00,0.000000000000000000e+00,-7.382667891651250007e-10,0.000000000000000000e+00 +3.847729227322778911e+01,2.615300000000000296e+02,0.000000000000000000e+00,9.777971625185470472e+00,0.000000000000000000e+00,-1.000000009901878872e+00,0.000000000000000000e+00,-9.487907349128411213e-11,0.000000000000000000e+00 +3.847831498022504348e+01,2.615400000000000205e+02,0.000000000000000000e+00,9.776948918178092640e+00,0.000000000000000000e+00,-1.000000009901975906e+00,0.000000000000000000e+00,3.493008284693688638e-10,0.000000000000000000e+00 +3.847933779420143452e+01,2.615500000000000114e+02,0.000000000000000000e+00,9.775926104191571042e+00,0.000000000000000000e+00,-1.000000009901618636e+00,0.000000000000000000e+00,6.056229702332434457e-10,0.000000000000000000e+00 +3.848036071519054957e+01,2.615600000000000023e+02,0.000000000000000000e+00,9.774903183192328981e+00,0.000000000000000000e+00,-1.000000009900999132e+00,0.000000000000000000e+00,-1.009265999703952821e-09,0.000000000000000000e+00 +3.848138374322597599e+01,2.615699999999999932e+02,0.000000000000000000e+00,9.773880155146771997e+00,0.000000000000000000e+00,-1.000000009902031639e+00,0.000000000000000000e+00,6.076664601375671464e-10,0.000000000000000000e+00 +3.848240687834132956e+01,2.615799999999999841e+02,0.000000000000000000e+00,9.772857020021286090e+00,0.000000000000000000e+00,-1.000000009901409914e+00,0.000000000000000000e+00,3.769307675711035839e-10,0.000000000000000000e+00 +3.848343012057024026e+01,2.615900000000000318e+02,0.000000000000000000e+00,9.771833777782243047e+00,0.000000000000000000e+00,-1.000000009901024223e+00,0.000000000000000000e+00,-1.687006259626520959e-09,0.000000000000000000e+00 +3.848445346994635941e+01,2.616000000000000227e+02,0.000000000000000000e+00,9.770810428395995118e+00,0.000000000000000000e+00,-1.000000009902750620e+00,0.000000000000000000e+00,1.212347748277871551e-09,0.000000000000000000e+00 +3.848547692650334540e+01,2.616100000000000136e+02,0.000000000000000000e+00,9.769786971828875011e+00,0.000000000000000000e+00,-1.000000009901509834e+00,0.000000000000000000e+00,-1.089436766855125483e-09,0.000000000000000000e+00 +3.848650049027488507e+01,2.616200000000000045e+02,0.000000000000000000e+00,9.768763408047203001e+00,0.000000000000000000e+00,-1.000000009902624942e+00,0.000000000000000000e+00,1.595157030970887016e-09,0.000000000000000000e+00 +3.848752416129467235e+01,2.616299999999999955e+02,0.000000000000000000e+00,9.767739737017276269e+00,0.000000000000000000e+00,-1.000000009900992026e+00,0.000000000000000000e+00,-8.944436008619770762e-10,0.000000000000000000e+00 +3.848854793959642961e+01,2.616399999999999864e+02,0.000000000000000000e+00,9.766715958705379563e+00,0.000000000000000000e+00,-1.000000009901907738e+00,0.000000000000000000e+00,-1.763760268772581721e-09,0.000000000000000000e+00 +3.848957182521389342e+01,2.616499999999999773e+02,0.000000000000000000e+00,9.765692073077774538e+00,0.000000000000000000e+00,-1.000000009903713627e+00,0.000000000000000000e+00,2.386128529699945379e-09,0.000000000000000000e+00 +3.849059581818082165e+01,2.616600000000000250e+02,0.000000000000000000e+00,9.764668080100706860e+00,0.000000000000000000e+00,-1.000000009901270248e+00,0.000000000000000000e+00,-1.985630110946929245e-09,0.000000000000000000e+00 +3.849161991853097931e+01,2.616700000000000159e+02,0.000000000000000000e+00,9.763643979740409762e+00,0.000000000000000000e+00,-1.000000009903303733e+00,0.000000000000000000e+00,2.072574033425274237e-09,0.000000000000000000e+00 +3.849264412629815268e+01,2.616800000000000068e+02,0.000000000000000000e+00,9.762619771963089832e+00,0.000000000000000000e+00,-1.000000009901180986e+00,0.000000000000000000e+00,-2.361532742595560017e-09,0.000000000000000000e+00 +3.849366844151615652e+01,2.616899999999999977e+02,0.000000000000000000e+00,9.761595456734944776e+00,0.000000000000000000e+00,-1.000000009903599940e+00,0.000000000000000000e+00,1.655543837542994404e-09,0.000000000000000000e+00 +3.849469286421881264e+01,2.616999999999999886e+02,0.000000000000000000e+00,9.760571034022145653e+00,0.000000000000000000e+00,-1.000000009901903963e+00,0.000000000000000000e+00,-1.099678957375357768e-09,0.000000000000000000e+00 +3.849571739443995710e+01,2.617099999999999795e+02,0.000000000000000000e+00,9.759546503790854644e+00,0.000000000000000000e+00,-1.000000009903030618e+00,0.000000000000000000e+00,-4.583320579846818504e-10,0.000000000000000000e+00 +3.849674203221345437e+01,2.617200000000000273e+02,0.000000000000000000e+00,9.758521866007209056e+00,0.000000000000000000e+00,-1.000000009903500242e+00,0.000000000000000000e+00,1.897490519833791777e-09,0.000000000000000000e+00 +3.849776677757318311e+01,2.617300000000000182e+02,0.000000000000000000e+00,9.757497120637331989e+00,0.000000000000000000e+00,-1.000000009901555797e+00,0.000000000000000000e+00,-2.476639994997261121e-09,0.000000000000000000e+00 +3.849879163055303621e+01,2.617400000000000091e+02,0.000000000000000000e+00,9.756472267647330554e+00,0.000000000000000000e+00,-1.000000009904093989e+00,0.000000000000000000e+00,1.654458319411637240e-09,0.000000000000000000e+00 +3.849981659118692789e+01,2.617500000000000000e+02,0.000000000000000000e+00,9.755447307003286994e+00,0.000000000000000000e+00,-1.000000009902398235e+00,0.000000000000000000e+00,-9.175787861185541716e-10,0.000000000000000000e+00 +3.850084165950878656e+01,2.617599999999999909e+02,0.000000000000000000e+00,9.754422238671274670e+00,0.000000000000000000e+00,-1.000000009903338816e+00,0.000000000000000000e+00,-3.465466931612323830e-11,0.000000000000000000e+00 +3.850186683555256906e+01,2.617699999999999818e+02,0.000000000000000000e+00,9.753397062617342073e+00,0.000000000000000000e+00,-1.000000009903374343e+00,0.000000000000000000e+00,9.334120440991520222e-10,0.000000000000000000e+00 +3.850289211935223221e+01,2.617800000000000296e+02,0.000000000000000000e+00,9.752371778807523484e+00,0.000000000000000000e+00,-1.000000009902417331e+00,0.000000000000000000e+00,-1.379182454002705832e-09,0.000000000000000000e+00 +3.850391751094176840e+01,2.617900000000000205e+02,0.000000000000000000e+00,9.751346387207835420e+00,0.000000000000000000e+00,-1.000000009903831533e+00,0.000000000000000000e+00,-2.013667486112266653e-10,0.000000000000000000e+00 +3.850494301035517708e+01,2.618000000000000114e+02,0.000000000000000000e+00,9.750320887784273083e+00,0.000000000000000000e+00,-1.000000009904038034e+00,0.000000000000000000e+00,1.098740620830822217e-09,0.000000000000000000e+00 +3.850596861762647194e+01,2.618100000000000023e+02,0.000000000000000000e+00,9.749295280502817462e+00,0.000000000000000000e+00,-1.000000009902911158e+00,0.000000000000000000e+00,-8.427482384609212079e-10,0.000000000000000000e+00 +3.850699433278970218e+01,2.618199999999999932e+02,0.000000000000000000e+00,9.748269565329431785e+00,0.000000000000000000e+00,-1.000000009903775577e+00,0.000000000000000000e+00,7.415750576016097224e-10,0.000000000000000000e+00 +3.850802015587891702e+01,2.618299999999999841e+02,0.000000000000000000e+00,9.747243742230057961e+00,0.000000000000000000e+00,-1.000000009903014853e+00,0.000000000000000000e+00,-8.897531383735339744e-10,0.000000000000000000e+00 +3.850904608692819409e+01,2.618400000000000318e+02,0.000000000000000000e+00,9.746217811170623690e+00,0.000000000000000000e+00,-1.000000009903927678e+00,0.000000000000000000e+00,1.027945164612475211e-09,0.000000000000000000e+00 +3.851007212597161811e+01,2.618500000000000227e+02,0.000000000000000000e+00,9.745191772117035356e+00,0.000000000000000000e+00,-1.000000009902872966e+00,0.000000000000000000e+00,-1.929953206481190599e-09,0.000000000000000000e+00 +3.851109827304330935e+01,2.618600000000000136e+02,0.000000000000000000e+00,9.744165625035185130e+00,0.000000000000000000e+00,-1.000000009904853382e+00,0.000000000000000000e+00,3.712805221614074044e-10,0.000000000000000000e+00 +3.851212452817738807e+01,2.618700000000000045e+02,0.000000000000000000e+00,9.743139369890942092e+00,0.000000000000000000e+00,-1.000000009904472353e+00,0.000000000000000000e+00,1.196366577260674915e-09,0.000000000000000000e+00 +3.851315089140800296e+01,2.618799999999999955e+02,0.000000000000000000e+00,9.742113006650162887e+00,0.000000000000000000e+00,-1.000000009903244447e+00,0.000000000000000000e+00,-1.127234991519321243e-09,0.000000000000000000e+00 +3.851417736276931691e+01,2.618899999999999864e+02,0.000000000000000000e+00,9.741086535278684622e+00,0.000000000000000000e+00,-1.000000009904401521e+00,0.000000000000000000e+00,1.576794713513276753e-10,0.000000000000000000e+00 +3.851520394229551414e+01,2.618999999999999773e+02,0.000000000000000000e+00,9.740059955742323083e+00,0.000000000000000000e+00,-1.000000009904239651e+00,0.000000000000000000e+00,5.190546635565413176e-12,0.000000000000000000e+00 +3.851623063002078595e+01,2.619100000000000250e+02,0.000000000000000000e+00,9.739033268006879851e+00,0.000000000000000000e+00,-1.000000009904234322e+00,0.000000000000000000e+00,1.139637391620512799e-10,0.000000000000000000e+00 +3.851725742597935920e+01,2.619200000000000159e+02,0.000000000000000000e+00,9.738006472038136963e+00,0.000000000000000000e+00,-1.000000009904117304e+00,0.000000000000000000e+00,4.966738324235020927e-10,0.000000000000000000e+00 +3.851828433020546782e+01,2.619300000000000068e+02,0.000000000000000000e+00,9.736979567801858693e+00,0.000000000000000000e+00,-1.000000009903607268e+00,0.000000000000000000e+00,-5.188905075109597197e-10,0.000000000000000000e+00 +3.851931134273336710e+01,2.619399999999999977e+02,0.000000000000000000e+00,9.735952555263791552e+00,0.000000000000000000e+00,-1.000000009904140175e+00,0.000000000000000000e+00,-1.234396786799069076e-09,0.000000000000000000e+00 +3.852033846359732649e+01,2.619499999999999886e+02,0.000000000000000000e+00,9.734925434389662513e+00,0.000000000000000000e+00,-1.000000009905408049e+00,0.000000000000000000e+00,1.728405502574131517e-09,0.000000000000000000e+00 +3.852136569283162970e+01,2.619599999999999795e+02,0.000000000000000000e+00,9.733898205145180782e+00,0.000000000000000000e+00,-1.000000009903632581e+00,0.000000000000000000e+00,-1.718497003124970776e-09,0.000000000000000000e+00 +3.852239303047059593e+01,2.619700000000000273e+02,0.000000000000000000e+00,9.732870867496041356e+00,0.000000000000000000e+00,-1.000000009905398057e+00,0.000000000000000000e+00,2.212998621756933290e-10,0.000000000000000000e+00 +3.852342047654854440e+01,2.619800000000000182e+02,0.000000000000000000e+00,9.731843421407914363e+00,0.000000000000000000e+00,-1.000000009905170684e+00,0.000000000000000000e+00,8.274098841758649054e-10,0.000000000000000000e+00 +3.852444803109982274e+01,2.619900000000000091e+02,0.000000000000000000e+00,9.730815866846457496e+00,0.000000000000000000e+00,-1.000000009904320475e+00,0.000000000000000000e+00,1.127872436000621072e-10,0.000000000000000000e+00 +3.852547569415879281e+01,2.620000000000000000e+02,0.000000000000000000e+00,9.729788203777308908e+00,0.000000000000000000e+00,-1.000000009904204568e+00,0.000000000000000000e+00,-2.268469326597560611e-10,0.000000000000000000e+00 +3.852650346575983775e+01,2.620099999999999909e+02,0.000000000000000000e+00,9.728760432166087213e+00,0.000000000000000000e+00,-1.000000009904437714e+00,0.000000000000000000e+00,-1.859516314263968724e-09,0.000000000000000000e+00 +3.852753134593734785e+01,2.620199999999999818e+02,0.000000000000000000e+00,9.727732551978393261e+00,0.000000000000000000e+00,-1.000000009906349074e+00,0.000000000000000000e+00,1.950039451676065048e-09,0.000000000000000000e+00 +3.852855933472574890e+01,2.620300000000000296e+02,0.000000000000000000e+00,9.726704563179808360e+00,0.000000000000000000e+00,-1.000000009904344456e+00,0.000000000000000000e+00,-5.511713318025995392e-10,0.000000000000000000e+00 +3.852958743215947379e+01,2.620400000000000205e+02,0.000000000000000000e+00,9.725676465735901388e+00,0.000000000000000000e+00,-1.000000009904911114e+00,0.000000000000000000e+00,-9.460918403456414665e-10,0.000000000000000000e+00 +3.853061563827297675e+01,2.620500000000000114e+02,0.000000000000000000e+00,9.724648259612216350e+00,0.000000000000000000e+00,-1.000000009905883891e+00,0.000000000000000000e+00,7.767022533983233879e-10,0.000000000000000000e+00 +3.853164395310072621e+01,2.620600000000000023e+02,0.000000000000000000e+00,9.723619944774281265e+00,0.000000000000000000e+00,-1.000000009905085196e+00,0.000000000000000000e+00,-4.093610653852950002e-10,0.000000000000000000e+00 +3.853267237667721190e+01,2.620699999999999932e+02,0.000000000000000000e+00,9.722591521187608166e+00,0.000000000000000000e+00,-1.000000009905506193e+00,0.000000000000000000e+00,5.468364499698499400e-10,0.000000000000000000e+00 +3.853370090903694489e+01,2.620799999999999841e+02,0.000000000000000000e+00,9.721562988817687767e+00,0.000000000000000000e+00,-1.000000009904943754e+00,0.000000000000000000e+00,-1.378279261468072430e-09,0.000000000000000000e+00 +3.853472955021445046e+01,2.620900000000000318e+02,0.000000000000000000e+00,9.720534347629994798e+00,0.000000000000000000e+00,-1.000000009906361509e+00,0.000000000000000000e+00,2.220338065274546384e-09,0.000000000000000000e+00 +3.853575830024426807e+01,2.621000000000000227e+02,0.000000000000000000e+00,9.719505597589982671e+00,0.000000000000000000e+00,-1.000000009904077336e+00,0.000000000000000000e+00,-2.071189780130012952e-09,0.000000000000000000e+00 +3.853678715916096564e+01,2.621100000000000136e+02,0.000000000000000000e+00,9.718476738663092362e+00,0.000000000000000000e+00,-1.000000009906208298e+00,0.000000000000000000e+00,8.642530988277760334e-10,0.000000000000000000e+00 +3.853781612699912529e+01,2.621200000000000045e+02,0.000000000000000000e+00,9.717447770814738206e+00,0.000000000000000000e+00,-1.000000009905319009e+00,0.000000000000000000e+00,-7.077278471772605655e-10,0.000000000000000000e+00 +3.853884520379334333e+01,2.621299999999999955e+02,0.000000000000000000e+00,9.716418694010323875e+00,0.000000000000000000e+00,-1.000000009906047316e+00,0.000000000000000000e+00,-6.235112432071384598e-11,0.000000000000000000e+00 +3.853987438957824452e+01,2.621399999999999864e+02,0.000000000000000000e+00,9.715389508215229952e+00,0.000000000000000000e+00,-1.000000009906111487e+00,0.000000000000000000e+00,-5.416854310686600991e-10,0.000000000000000000e+00 +3.854090368438845360e+01,2.621499999999999773e+02,0.000000000000000000e+00,9.714360213394821031e+00,0.000000000000000000e+00,-1.000000009906669041e+00,0.000000000000000000e+00,1.220226935653700912e-09,0.000000000000000000e+00 +3.854193308825863795e+01,2.621600000000000250e+02,0.000000000000000000e+00,9.713330809514442166e+00,0.000000000000000000e+00,-1.000000009905412934e+00,0.000000000000000000e+00,2.066207408616368407e-10,0.000000000000000000e+00 +3.854296260122345785e+01,2.621700000000000159e+02,0.000000000000000000e+00,9.712301296539422424e+00,0.000000000000000000e+00,-1.000000009905200216e+00,0.000000000000000000e+00,-1.891522375884130789e-09,0.000000000000000000e+00 +3.854399222331760910e+01,2.621800000000000068e+02,0.000000000000000000e+00,9.711271674435069556e+00,0.000000000000000000e+00,-1.000000009907147769e+00,0.000000000000000000e+00,1.640108767814244235e-09,0.000000000000000000e+00 +3.854502195457580171e+01,2.621899999999999977e+02,0.000000000000000000e+00,9.710241943166671774e+00,0.000000000000000000e+00,-1.000000009905458898e+00,0.000000000000000000e+00,-9.137580770954911272e-10,0.000000000000000000e+00 +3.854605179503276702e+01,2.621999999999999886e+02,0.000000000000000000e+00,9.709212102699504854e+00,0.000000000000000000e+00,-1.000000009906399923e+00,0.000000000000000000e+00,5.109431252181068056e-10,0.000000000000000000e+00 +3.854708174472325055e+01,2.622099999999999795e+02,0.000000000000000000e+00,9.708182152998819703e+00,0.000000000000000000e+00,-1.000000009905873677e+00,0.000000000000000000e+00,-7.715069455645545881e-10,0.000000000000000000e+00 +3.854811180368201207e+01,2.622200000000000273e+02,0.000000000000000000e+00,9.707152094029853018e+00,0.000000000000000000e+00,-1.000000009906668375e+00,0.000000000000000000e+00,2.739539775367547948e-10,0.000000000000000000e+00 +3.854914197194383974e+01,2.622300000000000182e+02,0.000000000000000000e+00,9.706121925757820179e+00,0.000000000000000000e+00,-1.000000009906386156e+00,0.000000000000000000e+00,-1.360572714877086735e-09,0.000000000000000000e+00 +3.855017224954353594e+01,2.622400000000000091e+02,0.000000000000000000e+00,9.705091648147920580e+00,0.000000000000000000e+00,-1.000000009907787923e+00,0.000000000000000000e+00,1.031149910710467200e-09,0.000000000000000000e+00 +3.855120263651591728e+01,2.622500000000000000e+02,0.000000000000000000e+00,9.704061261165332297e+00,0.000000000000000000e+00,-1.000000009906725440e+00,0.000000000000000000e+00,7.685937779239701353e-10,0.000000000000000000e+00 +3.855223313289582165e+01,2.622599999999999909e+02,0.000000000000000000e+00,9.703030764775219197e+00,0.000000000000000000e+00,-1.000000009905933407e+00,0.000000000000000000e+00,-4.606333042797987383e-10,0.000000000000000000e+00 +3.855326373871810830e+01,2.622699999999999818e+02,0.000000000000000000e+00,9.702000158942723829e+00,0.000000000000000000e+00,-1.000000009906408138e+00,0.000000000000000000e+00,-9.713634056368101786e-10,0.000000000000000000e+00 +3.855429445401765065e+01,2.622800000000000296e+02,0.000000000000000000e+00,9.700969443632969202e+00,0.000000000000000000e+00,-1.000000009907409337e+00,0.000000000000000000e+00,9.206400842140485543e-10,0.000000000000000000e+00 +3.855532527882934346e+01,2.622900000000000205e+02,0.000000000000000000e+00,9.699938618811060564e+00,0.000000000000000000e+00,-1.000000009906460319e+00,0.000000000000000000e+00,-1.458350870908058179e-09,0.000000000000000000e+00 +3.855635621318810280e+01,2.623000000000000114e+02,0.000000000000000000e+00,9.698907684442087174e+00,0.000000000000000000e+00,-1.000000009907963783e+00,0.000000000000000000e+00,1.932847137184173051e-09,0.000000000000000000e+00 +3.855738725712885895e+01,2.623100000000000023e+02,0.000000000000000000e+00,9.697876640491115197e+00,0.000000000000000000e+00,-1.000000009905970932e+00,0.000000000000000000e+00,-5.902363014250987919e-10,0.000000000000000000e+00 +3.855841841068656350e+01,2.623199999999999932e+02,0.000000000000000000e+00,9.696845486923198365e+00,0.000000000000000000e+00,-1.000000009906579557e+00,0.000000000000000000e+00,-6.599350270124394034e-10,0.000000000000000000e+00 +3.855944967389618228e+01,2.623299999999999841e+02,0.000000000000000000e+00,9.695814223703365542e+00,0.000000000000000000e+00,-1.000000009907260123e+00,0.000000000000000000e+00,6.566354878122574271e-11,0.000000000000000000e+00 +3.856048104679270239e+01,2.623400000000000318e+02,0.000000000000000000e+00,9.694782850796629603e+00,0.000000000000000000e+00,-1.000000009907192400e+00,0.000000000000000000e+00,-7.060771467640270013e-11,0.000000000000000000e+00 +3.856151252941112517e+01,2.623500000000000227e+02,0.000000000000000000e+00,9.693751368167985660e+00,0.000000000000000000e+00,-1.000000009907265230e+00,0.000000000000000000e+00,-1.055559122542421950e-09,0.000000000000000000e+00 +3.856254412178648039e+01,2.623600000000000136e+02,0.000000000000000000e+00,9.692719775782409286e+00,0.000000000000000000e+00,-1.000000009908354137e+00,0.000000000000000000e+00,4.627264686514682358e-10,0.000000000000000000e+00 +3.856357582395381201e+01,2.623700000000000045e+02,0.000000000000000000e+00,9.691688073604856513e+00,0.000000000000000000e+00,-1.000000009907876741e+00,0.000000000000000000e+00,1.157984231260738636e-09,0.000000000000000000e+00 +3.856460763594817820e+01,2.623799999999999955e+02,0.000000000000000000e+00,9.690656261600267385e+00,0.000000000000000000e+00,-1.000000009906681919e+00,0.000000000000000000e+00,-6.237946271165734141e-10,0.000000000000000000e+00 +3.856563955780465847e+01,2.623899999999999864e+02,0.000000000000000000e+00,9.689624339733562408e+00,0.000000000000000000e+00,-1.000000009907325627e+00,0.000000000000000000e+00,-1.531888511572331742e-09,0.000000000000000000e+00 +3.856667158955835362e+01,2.623999999999999773e+02,0.000000000000000000e+00,9.688592307969640771e+00,0.000000000000000000e+00,-1.000000009908906584e+00,0.000000000000000000e+00,1.779770201522819664e-09,0.000000000000000000e+00 +3.856770373124438578e+01,2.624100000000000250e+02,0.000000000000000000e+00,9.687560166273383899e+00,0.000000000000000000e+00,-1.000000009907069609e+00,0.000000000000000000e+00,-6.799533755061962309e-10,0.000000000000000000e+00 +3.856873598289788418e+01,2.624200000000000159e+02,0.000000000000000000e+00,9.686527914609659007e+00,0.000000000000000000e+00,-1.000000009907771492e+00,0.000000000000000000e+00,-5.607243174973715865e-10,0.000000000000000000e+00 +3.856976834455400649e+01,2.624300000000000068e+02,0.000000000000000000e+00,9.685495552943308439e+00,0.000000000000000000e+00,-1.000000009908350362e+00,0.000000000000000000e+00,4.823822791267105471e-10,0.000000000000000000e+00 +3.857080081624792456e+01,2.624399999999999977e+02,0.000000000000000000e+00,9.684463081239158555e+00,0.000000000000000000e+00,-1.000000009907852316e+00,0.000000000000000000e+00,7.954265898724975751e-10,0.000000000000000000e+00 +3.857183339801483157e+01,2.624499999999999886e+02,0.000000000000000000e+00,9.683430499462017949e+00,0.000000000000000000e+00,-1.000000009907030973e+00,0.000000000000000000e+00,-1.272460841046734600e-09,0.000000000000000000e+00 +3.857286608988994203e+01,2.624599999999999795e+02,0.000000000000000000e+00,9.682397807576675675e+00,0.000000000000000000e+00,-1.000000009908345033e+00,0.000000000000000000e+00,-7.116249088463265707e-10,0.000000000000000000e+00 +3.857389889190848464e+01,2.624700000000000273e+02,0.000000000000000000e+00,9.681365005547899472e+00,0.000000000000000000e+00,-1.000000009909080001e+00,0.000000000000000000e+00,2.489561626389807704e-09,0.000000000000000000e+00 +3.857493180410570943e+01,2.624800000000000182e+02,0.000000000000000000e+00,9.680332093340441091e+00,0.000000000000000000e+00,-1.000000009906508502e+00,0.000000000000000000e+00,-3.309532053767111698e-09,0.000000000000000000e+00 +3.857596482651688063e+01,2.624900000000000091e+02,0.000000000000000000e+00,9.679299070919036296e+00,0.000000000000000000e+00,-1.000000009909927323e+00,0.000000000000000000e+00,1.881011468111890804e-09,0.000000000000000000e+00 +3.857699795917728380e+01,2.625000000000000000e+02,0.000000000000000000e+00,9.678265938248392430e+00,0.000000000000000000e+00,-1.000000009907983989e+00,0.000000000000000000e+00,-2.357460390069673759e-10,0.000000000000000000e+00 +3.857803120212222581e+01,2.625099999999999909e+02,0.000000000000000000e+00,9.677232695293209730e+00,0.000000000000000000e+00,-1.000000009908227572e+00,0.000000000000000000e+00,3.397216928049076486e-10,0.000000000000000000e+00 +3.857906455538703483e+01,2.625199999999999818e+02,0.000000000000000000e+00,9.676199342018161786e+00,0.000000000000000000e+00,-1.000000009907876519e+00,0.000000000000000000e+00,-1.370773534727384786e-09,0.000000000000000000e+00 +3.858009801900705327e+01,2.625300000000000296e+02,0.000000000000000000e+00,9.675165878387906204e+00,0.000000000000000000e+00,-1.000000009909293164e+00,0.000000000000000000e+00,1.298658463763200197e-09,0.000000000000000000e+00 +3.858113159301763773e+01,2.625400000000000205e+02,0.000000000000000000e+00,9.674132304367079271e+00,0.000000000000000000e+00,-1.000000009907950904e+00,0.000000000000000000e+00,-1.616651695239093659e-09,0.000000000000000000e+00 +3.858216527745417324e+01,2.625500000000000114e+02,0.000000000000000000e+00,9.673098619920303065e+00,0.000000000000000000e+00,-1.000000009909622012e+00,0.000000000000000000e+00,1.535504657508518345e-09,0.000000000000000000e+00 +3.858319907235205903e+01,2.625600000000000023e+02,0.000000000000000000e+00,9.672064825012174794e+00,0.000000000000000000e+00,-1.000000009908034615e+00,0.000000000000000000e+00,-8.685014963283161893e-10,0.000000000000000000e+00 +3.858423297774670857e+01,2.625699999999999932e+02,0.000000000000000000e+00,9.671030919607279230e+00,0.000000000000000000e+00,-1.000000009908932563e+00,0.000000000000000000e+00,1.157233989207720551e-09,0.000000000000000000e+00 +3.858526699367356372e+01,2.625799999999999841e+02,0.000000000000000000e+00,9.669996903670176280e+00,0.000000000000000000e+00,-1.000000009907735965e+00,0.000000000000000000e+00,-2.343636755854027694e-09,0.000000000000000000e+00 +3.858630112016808056e+01,2.625900000000000318e+02,0.000000000000000000e+00,9.668962777165411637e+00,0.000000000000000000e+00,-1.000000009910159582e+00,0.000000000000000000e+00,1.931602835595507737e-09,0.000000000000000000e+00 +3.858733535726573649e+01,2.626000000000000227e+02,0.000000000000000000e+00,9.667928540057506126e+00,0.000000000000000000e+00,-1.000000009908161847e+00,0.000000000000000000e+00,-9.522811651162553369e-10,0.000000000000000000e+00 +3.858836970500202312e+01,2.626100000000000136e+02,0.000000000000000000e+00,9.666894192310969913e+00,0.000000000000000000e+00,-1.000000009909146836e+00,0.000000000000000000e+00,-1.016788382134971340e-09,0.000000000000000000e+00 +3.858940416341245339e+01,2.626200000000000045e+02,0.000000000000000000e+00,9.665859733890286520e+00,0.000000000000000000e+00,-1.000000009910198662e+00,0.000000000000000000e+00,1.748551509184274216e-09,0.000000000000000000e+00 +3.859043873253256152e+01,2.626299999999999955e+02,0.000000000000000000e+00,9.664825164759923481e+00,0.000000000000000000e+00,-1.000000009908389664e+00,0.000000000000000000e+00,-9.403869654529102546e-10,0.000000000000000000e+00 +3.859147341239790308e+01,2.626399999999999864e+02,0.000000000000000000e+00,9.663790484884332344e+00,0.000000000000000000e+00,-1.000000009909362664e+00,0.000000000000000000e+00,8.872852154117420006e-10,0.000000000000000000e+00 +3.859250820304404073e+01,2.626499999999999773e+02,0.000000000000000000e+00,9.662755694227939784e+00,0.000000000000000000e+00,-1.000000009908444509e+00,0.000000000000000000e+00,-1.052398538985156214e-09,0.000000000000000000e+00 +3.859354310450656556e+01,2.626600000000000250e+02,0.000000000000000000e+00,9.661720792755158271e+00,0.000000000000000000e+00,-1.000000009909533638e+00,0.000000000000000000e+00,-1.096265150901195684e-10,0.000000000000000000e+00 +3.859457811682108996e+01,2.626700000000000159e+02,0.000000000000000000e+00,9.660685780430377179e+00,0.000000000000000000e+00,-1.000000009909647103e+00,0.000000000000000000e+00,4.110017649617736900e-10,0.000000000000000000e+00 +3.859561324002324056e+01,2.626800000000000068e+02,0.000000000000000000e+00,9.659650657217969894e+00,0.000000000000000000e+00,-1.000000009909221665e+00,0.000000000000000000e+00,-1.133994521056700695e-09,0.000000000000000000e+00 +3.859664847414866529e+01,2.626899999999999977e+02,0.000000000000000000e+00,9.658615423082290263e+00,0.000000000000000000e+00,-1.000000009910395615e+00,0.000000000000000000e+00,2.408434589567278868e-10,0.000000000000000000e+00 +3.859768381923302627e+01,2.626999999999999886e+02,0.000000000000000000e+00,9.657580077987670819e+00,0.000000000000000000e+00,-1.000000009910146259e+00,0.000000000000000000e+00,1.233895558366638947e-09,0.000000000000000000e+00 +3.859871927531200697e+01,2.627099999999999795e+02,0.000000000000000000e+00,9.656544621898428105e+00,0.000000000000000000e+00,-1.000000009908868615e+00,0.000000000000000000e+00,-1.454614178330236479e-09,0.000000000000000000e+00 +3.859975484242131216e+01,2.627200000000000273e+02,0.000000000000000000e+00,9.655509054778859124e+00,0.000000000000000000e+00,-1.000000009910374965e+00,0.000000000000000000e+00,4.727417893987646765e-10,0.000000000000000000e+00 +3.860079052059666793e+01,2.627300000000000182e+02,0.000000000000000000e+00,9.654473376593237788e+00,0.000000000000000000e+00,-1.000000009909885357e+00,0.000000000000000000e+00,4.021625711223312254e-10,0.000000000000000000e+00 +3.860182630987381458e+01,2.627400000000000091e+02,0.000000000000000000e+00,9.653437587305823797e+00,0.000000000000000000e+00,-1.000000009909468801e+00,0.000000000000000000e+00,4.072638096959360420e-12,0.000000000000000000e+00 +3.860286221028852083e+01,2.627500000000000000e+02,0.000000000000000000e+00,9.652401686880855536e+00,0.000000000000000000e+00,-1.000000009909464582e+00,0.000000000000000000e+00,-7.072770273165844921e-10,0.000000000000000000e+00 +3.860389822187655540e+01,2.627599999999999909e+02,0.000000000000000000e+00,9.651365675282551848e+00,0.000000000000000000e+00,-1.000000009910197329e+00,0.000000000000000000e+00,-6.429101035065366829e-11,0.000000000000000000e+00 +3.860493434467372964e+01,2.627699999999999818e+02,0.000000000000000000e+00,9.650329552475112038e+00,0.000000000000000000e+00,-1.000000009910263943e+00,0.000000000000000000e+00,2.918498520736690390e-10,0.000000000000000000e+00 +3.860597057871585491e+01,2.627800000000000296e+02,0.000000000000000000e+00,9.649293318422717647e+00,0.000000000000000000e+00,-1.000000009909961518e+00,0.000000000000000000e+00,-1.279544907753404197e-09,0.000000000000000000e+00 +3.860700692403877099e+01,2.627900000000000205e+02,0.000000000000000000e+00,9.648256973089530675e+00,0.000000000000000000e+00,-1.000000009911287568e+00,0.000000000000000000e+00,1.850770470002604207e-09,0.000000000000000000e+00 +3.860804338067833896e+01,2.628000000000000114e+02,0.000000000000000000e+00,9.647220516439691806e+00,0.000000000000000000e+00,-1.000000009909369325e+00,0.000000000000000000e+00,-1.879704392843312945e-09,0.000000000000000000e+00 +3.860907994867043413e+01,2.628100000000000023e+02,0.000000000000000000e+00,9.646183948437327516e+00,0.000000000000000000e+00,-1.000000009911317767e+00,0.000000000000000000e+00,7.706495407706071863e-10,0.000000000000000000e+00 +3.861011662805094602e+01,2.628199999999999932e+02,0.000000000000000000e+00,9.645147269046537630e+00,0.000000000000000000e+00,-1.000000009910518850e+00,0.000000000000000000e+00,1.547344230942409538e-09,0.000000000000000000e+00 +3.861115341885579966e+01,2.628299999999999841e+02,0.000000000000000000e+00,9.644110478231409544e+00,0.000000000000000000e+00,-1.000000009908914578e+00,0.000000000000000000e+00,-2.837170936544629682e-09,0.000000000000000000e+00 +3.861219032112092719e+01,2.628400000000000318e+02,0.000000000000000000e+00,9.643073575956009336e+00,0.000000000000000000e+00,-1.000000009911856447e+00,0.000000000000000000e+00,8.466274996472580619e-10,0.000000000000000000e+00 +3.861322733488228209e+01,2.628500000000000227e+02,0.000000000000000000e+00,9.642036562184378212e+00,0.000000000000000000e+00,-1.000000009910978482e+00,0.000000000000000000e+00,1.047358707810940989e-09,0.000000000000000000e+00 +3.861426446017583203e+01,2.628600000000000136e+02,0.000000000000000000e+00,9.640999436880546725e+00,0.000000000000000000e+00,-1.000000009909892240e+00,0.000000000000000000e+00,-5.679361760001298366e-10,0.000000000000000000e+00 +3.861530169703758020e+01,2.628700000000000045e+02,0.000000000000000000e+00,9.639962200008522331e+00,0.000000000000000000e+00,-1.000000009910481324e+00,0.000000000000000000e+00,-6.826059596637884879e-10,0.000000000000000000e+00 +3.861633904550352980e+01,2.628799999999999955e+02,0.000000000000000000e+00,9.638924851532291171e+00,0.000000000000000000e+00,-1.000000009911189425e+00,0.000000000000000000e+00,7.148506010272248889e-10,0.000000000000000000e+00 +3.861737650560971957e+01,2.628899999999999864e+02,0.000000000000000000e+00,9.637887391415821625e+00,0.000000000000000000e+00,-1.000000009910447796e+00,0.000000000000000000e+00,-1.311631066469311448e-09,0.000000000000000000e+00 +3.861841407739219534e+01,2.628999999999999773e+02,0.000000000000000000e+00,9.636849819623064306e+00,0.000000000000000000e+00,-1.000000009911808707e+00,0.000000000000000000e+00,1.500649111308239853e-09,0.000000000000000000e+00 +3.861945176088702425e+01,2.629100000000000250e+02,0.000000000000000000e+00,9.635812136117946736e+00,0.000000000000000000e+00,-1.000000009910251508e+00,0.000000000000000000e+00,-7.328061838719250358e-10,0.000000000000000000e+00 +3.862048955613030188e+01,2.629200000000000159e+02,0.000000000000000000e+00,9.634774340864382225e+00,0.000000000000000000e+00,-1.000000009911012011e+00,0.000000000000000000e+00,2.494481705960864785e-10,0.000000000000000000e+00 +3.862152746315813800e+01,2.629300000000000068e+02,0.000000000000000000e+00,9.633736433826259216e+00,0.000000000000000000e+00,-1.000000009910753107e+00,0.000000000000000000e+00,-4.870774419312693526e-10,0.000000000000000000e+00 +3.862256548200665662e+01,2.629399999999999977e+02,0.000000000000000000e+00,9.632698414967450162e+00,0.000000000000000000e+00,-1.000000009911258703e+00,0.000000000000000000e+00,3.689583031500653951e-10,0.000000000000000000e+00 +3.862360361271201015e+01,2.629499999999999886e+02,0.000000000000000000e+00,9.631660284251806203e+00,0.000000000000000000e+00,-1.000000009910875676e+00,0.000000000000000000e+00,-4.649442932428066831e-10,0.000000000000000000e+00 +3.862464185531036520e+01,2.629599999999999795e+02,0.000000000000000000e+00,9.630622041643160713e+00,0.000000000000000000e+00,-1.000000009911358401e+00,0.000000000000000000e+00,-1.327749738079528537e-09,0.000000000000000000e+00 +3.862568020983790973e+01,2.629700000000000273e+02,0.000000000000000000e+00,9.629583687105325751e+00,0.000000000000000000e+00,-1.000000009912737076e+00,0.000000000000000000e+00,1.089625244909714171e-09,0.000000000000000000e+00 +3.862671867633084588e+01,2.629800000000000182e+02,0.000000000000000000e+00,9.628545220602093835e+00,0.000000000000000000e+00,-1.000000009911605536e+00,0.000000000000000000e+00,2.105897021718719390e-10,0.000000000000000000e+00 +3.862775725482540423e+01,2.629900000000000091e+02,0.000000000000000000e+00,9.627506642097241496e+00,0.000000000000000000e+00,-1.000000009911386822e+00,0.000000000000000000e+00,9.908405937091461140e-10,0.000000000000000000e+00 +3.862879594535782957e+01,2.630000000000000000e+02,0.000000000000000000e+00,9.626467951554522173e+00,0.000000000000000000e+00,-1.000000009910357646e+00,0.000000000000000000e+00,-1.494971188024603760e-09,0.000000000000000000e+00 +3.862983474796438799e+01,2.630099999999999909e+02,0.000000000000000000e+00,9.625429148937671542e+00,0.000000000000000000e+00,-1.000000009911910626e+00,0.000000000000000000e+00,-6.486628449270578371e-10,0.000000000000000000e+00 +3.863087366268135980e+01,2.630199999999999818e+02,0.000000000000000000e+00,9.624390234210402184e+00,0.000000000000000000e+00,-1.000000009912584531e+00,0.000000000000000000e+00,1.895985372211465752e-09,0.000000000000000000e+00 +3.863191268954505375e+01,2.630300000000000296e+02,0.000000000000000000e+00,9.623351207336410695e+00,0.000000000000000000e+00,-1.000000009910614551e+00,0.000000000000000000e+00,-2.073349864346267373e-09,0.000000000000000000e+00 +3.863295182859179278e+01,2.630400000000000205e+02,0.000000000000000000e+00,9.622312068279375907e+00,0.000000000000000000e+00,-1.000000009912769050e+00,0.000000000000000000e+00,6.185406284424385836e-10,0.000000000000000000e+00 +3.863399107985791403e+01,2.630500000000000114e+02,0.000000000000000000e+00,9.621272817002950006e+00,0.000000000000000000e+00,-1.000000009912126231e+00,0.000000000000000000e+00,1.153629929624776062e-10,0.000000000000000000e+00 +3.863503044337979020e+01,2.630600000000000023e+02,0.000000000000000000e+00,9.620233453470772744e+00,0.000000000000000000e+00,-1.000000009912006327e+00,0.000000000000000000e+00,1.364554054212236795e-09,0.000000000000000000e+00 +3.863606991919380107e+01,2.630699999999999932e+02,0.000000000000000000e+00,9.619193977646460780e+00,0.000000000000000000e+00,-1.000000009910587906e+00,0.000000000000000000e+00,-2.195481460992087589e-09,0.000000000000000000e+00 +3.863710950733634775e+01,2.630799999999999841e+02,0.000000000000000000e+00,9.618154389493613010e+00,0.000000000000000000e+00,-1.000000009912870302e+00,0.000000000000000000e+00,9.550668351691147555e-10,0.000000000000000000e+00 +3.863814920784385265e+01,2.630900000000000318e+02,0.000000000000000000e+00,9.617114688975803460e+00,0.000000000000000000e+00,-1.000000009911877319e+00,0.000000000000000000e+00,-6.752224700821483534e-10,0.000000000000000000e+00 +3.863918902075275241e+01,2.631000000000000227e+02,0.000000000000000000e+00,9.616074876056593723e+00,0.000000000000000000e+00,-1.000000009912579424e+00,0.000000000000000000e+00,1.143825325811923812e-09,0.000000000000000000e+00 +3.864022894609951919e+01,2.631100000000000136e+02,0.000000000000000000e+00,9.615034950699520522e+00,0.000000000000000000e+00,-1.000000009911389931e+00,0.000000000000000000e+00,-1.787607565133677145e-09,0.000000000000000000e+00 +3.864126898392062515e+01,2.631200000000000045e+02,0.000000000000000000e+00,9.613994912868104592e+00,0.000000000000000000e+00,-1.000000009913249110e+00,0.000000000000000000e+00,2.040593857712962768e-09,0.000000000000000000e+00 +3.864230913425257796e+01,2.631299999999999955e+02,0.000000000000000000e+00,9.612954762525841801e+00,0.000000000000000000e+00,-1.000000009911126586e+00,0.000000000000000000e+00,-2.135785445252692923e-09,0.000000000000000000e+00 +3.864334939713189243e+01,2.631399999999999864e+02,0.000000000000000000e+00,9.611914499636215581e+00,0.000000000000000000e+00,-1.000000009913348364e+00,0.000000000000000000e+00,4.731684920698750626e-10,0.000000000000000000e+00 +3.864438977259511176e+01,2.631499999999999773e+02,0.000000000000000000e+00,9.610874124162680943e+00,0.000000000000000000e+00,-1.000000009912856092e+00,0.000000000000000000e+00,3.073021556952828362e-11,0.000000000000000000e+00 +3.864543026067880049e+01,2.631600000000000250e+02,0.000000000000000000e+00,9.609833636068680462e+00,0.000000000000000000e+00,-1.000000009912824117e+00,0.000000000000000000e+00,1.475744180791127451e-09,0.000000000000000000e+00 +3.864647086141953025e+01,2.631700000000000159e+02,0.000000000000000000e+00,9.608793035317633624e+00,0.000000000000000000e+00,-1.000000009911288457e+00,0.000000000000000000e+00,-1.741001813120133008e-09,0.000000000000000000e+00 +3.864751157485390820e+01,2.631800000000000068e+02,0.000000000000000000e+00,9.607752321872942147e+00,0.000000000000000000e+00,-1.000000009913100341e+00,0.000000000000000000e+00,2.374418069771474544e-10,0.000000000000000000e+00 +3.864855240101854861e+01,2.631899999999999977e+02,0.000000000000000000e+00,9.606711495697982883e+00,0.000000000000000000e+00,-1.000000009912853205e+00,0.000000000000000000e+00,8.624197928487773570e-10,0.000000000000000000e+00 +3.864959333995009416e+01,2.631999999999999886e+02,0.000000000000000000e+00,9.605670556756118472e+00,0.000000000000000000e+00,-1.000000009911955479e+00,0.000000000000000000e+00,-1.489395218219957006e-09,0.000000000000000000e+00 +3.865063439168520176e+01,2.632099999999999795e+02,0.000000000000000000e+00,9.604629505010690238e+00,0.000000000000000000e+00,-1.000000009913506016e+00,0.000000000000000000e+00,-2.473881150114021053e-10,0.000000000000000000e+00 +3.865167555626055673e+01,2.632200000000000273e+02,0.000000000000000000e+00,9.603588340425016412e+00,0.000000000000000000e+00,-1.000000009913763588e+00,0.000000000000000000e+00,1.322529971921414473e-09,0.000000000000000000e+00 +3.865271683371285150e+01,2.632300000000000182e+02,0.000000000000000000e+00,9.602547062962399238e+00,0.000000000000000000e+00,-1.000000009912386467e+00,0.000000000000000000e+00,-4.115133973918145429e-11,0.000000000000000000e+00 +3.865375822407880690e+01,2.632400000000000091e+02,0.000000000000000000e+00,9.601505672586121420e+00,0.000000000000000000e+00,-1.000000009912429322e+00,0.000000000000000000e+00,-1.047219996580373545e-09,0.000000000000000000e+00 +3.865479972739516512e+01,2.632500000000000000e+02,0.000000000000000000e+00,9.600464169259442571e+00,0.000000000000000000e+00,-1.000000009913520005e+00,0.000000000000000000e+00,-4.476635674476276698e-11,0.000000000000000000e+00 +3.865584134369867542e+01,2.632599999999999909e+02,0.000000000000000000e+00,9.599422552945602760e+00,0.000000000000000000e+00,-1.000000009913566634e+00,0.000000000000000000e+00,1.341139792624040529e-09,0.000000000000000000e+00 +3.865688307302612969e+01,2.632699999999999818e+02,0.000000000000000000e+00,9.598380823607824297e+00,0.000000000000000000e+00,-1.000000009912169530e+00,0.000000000000000000e+00,-1.784511264003991848e-09,0.000000000000000000e+00 +3.865792491541431986e+01,2.632800000000000296e+02,0.000000000000000000e+00,9.597338981209309949e+00,0.000000000000000000e+00,-1.000000009914028709e+00,0.000000000000000000e+00,4.121426220229108990e-10,0.000000000000000000e+00 +3.865896687090005912e+01,2.632900000000000205e+02,0.000000000000000000e+00,9.596297025713237616e+00,0.000000000000000000e+00,-1.000000009913599275e+00,0.000000000000000000e+00,-2.377979475708607405e-10,0.000000000000000000e+00 +3.866000893952019624e+01,2.633000000000000114e+02,0.000000000000000000e+00,9.595254957082770986e+00,0.000000000000000000e+00,-1.000000009913847077e+00,0.000000000000000000e+00,1.188008394785578552e-09,0.000000000000000000e+00 +3.866105112131158705e+01,2.633100000000000023e+02,0.000000000000000000e+00,9.594212775281050654e+00,0.000000000000000000e+00,-1.000000009912608956e+00,0.000000000000000000e+00,-2.030217055547032693e-10,0.000000000000000000e+00 +3.866209341631110874e+01,2.633199999999999932e+02,0.000000000000000000e+00,9.593170480271199452e+00,0.000000000000000000e+00,-1.000000009912820564e+00,0.000000000000000000e+00,-1.125125025964567958e-09,0.000000000000000000e+00 +3.866313582455565978e+01,2.633299999999999841e+02,0.000000000000000000e+00,9.592128072016317120e+00,0.000000000000000000e+00,-1.000000009913993404e+00,0.000000000000000000e+00,6.922110936458787628e-11,0.000000000000000000e+00 +3.866417834608215998e+01,2.633400000000000318e+02,0.000000000000000000e+00,9.591085550479483857e+00,0.000000000000000000e+00,-1.000000009913921240e+00,0.000000000000000000e+00,1.243714900285301573e-10,0.000000000000000000e+00 +3.866522098092754334e+01,2.633500000000000227e+02,0.000000000000000000e+00,9.590042915623762099e+00,0.000000000000000000e+00,-1.000000009913791565e+00,0.000000000000000000e+00,6.899312020940626090e-10,0.000000000000000000e+00 +3.866626372912877230e+01,2.633600000000000136e+02,0.000000000000000000e+00,9.589000167412192965e+00,0.000000000000000000e+00,-1.000000009913072141e+00,0.000000000000000000e+00,-1.488300841905570330e-09,0.000000000000000000e+00 +3.866730659072283061e+01,2.633700000000000045e+02,0.000000000000000000e+00,9.587957305807798036e+00,0.000000000000000000e+00,-1.000000009914624233e+00,0.000000000000000000e+00,1.385949178996010228e-10,0.000000000000000000e+00 +3.866834956574670912e+01,2.633799999999999955e+02,0.000000000000000000e+00,9.586914330773575799e+00,0.000000000000000000e+00,-1.000000009914479682e+00,0.000000000000000000e+00,6.833199562135833326e-10,0.000000000000000000e+00 +3.866939265423743421e+01,2.633899999999999864e+02,0.000000000000000000e+00,9.585871242272508752e+00,0.000000000000000000e+00,-1.000000009913766919e+00,0.000000000000000000e+00,1.613396172582284817e-10,0.000000000000000000e+00 +3.867043585623203938e+01,2.633999999999999773e+02,0.000000000000000000e+00,9.584828040267558080e+00,0.000000000000000000e+00,-1.000000009913598609e+00,0.000000000000000000e+00,2.189978876784363436e-10,0.000000000000000000e+00 +3.867147917176759364e+01,2.634100000000000250e+02,0.000000000000000000e+00,9.583784724721663650e+00,0.000000000000000000e+00,-1.000000009913370125e+00,0.000000000000000000e+00,-7.607699002072354401e-10,0.000000000000000000e+00 +3.867252260088116600e+01,2.634200000000000159e+02,0.000000000000000000e+00,9.582741295597745790e+00,0.000000000000000000e+00,-1.000000009914163934e+00,0.000000000000000000e+00,-1.133051372704984862e-09,0.000000000000000000e+00 +3.867356614360986100e+01,2.634300000000000068e+02,0.000000000000000000e+00,9.581697752858703510e+00,0.000000000000000000e+00,-1.000000009915346322e+00,0.000000000000000000e+00,2.378191365647421667e-09,0.000000000000000000e+00 +3.867460979999079740e+01,2.634399999999999977e+02,0.000000000000000000e+00,9.580654096467416281e+00,0.000000000000000000e+00,-1.000000009912864307e+00,0.000000000000000000e+00,-1.628898536424361400e-09,0.000000000000000000e+00 +3.867565357006112237e+01,2.634499999999999886e+02,0.000000000000000000e+00,9.579610326386747587e+00,0.000000000000000000e+00,-1.000000009914564503e+00,0.000000000000000000e+00,-9.380514485039083381e-11,0.000000000000000000e+00 +3.867669745385799018e+01,2.634599999999999795e+02,0.000000000000000000e+00,9.578566442579532492e+00,0.000000000000000000e+00,-1.000000009914662424e+00,0.000000000000000000e+00,4.738664135321357359e-10,0.000000000000000000e+00 +3.867774145141857645e+01,2.634700000000000273e+02,0.000000000000000000e+00,9.577522445008591845e+00,0.000000000000000000e+00,-1.000000009914167709e+00,0.000000000000000000e+00,9.016941674841224443e-11,0.000000000000000000e+00 +3.867878556278009228e+01,2.634800000000000182e+02,0.000000000000000000e+00,9.576478333636725182e+00,0.000000000000000000e+00,-1.000000009914073562e+00,0.000000000000000000e+00,-1.230976056053001464e-09,0.000000000000000000e+00 +3.867982978797975591e+01,2.634900000000000091e+02,0.000000000000000000e+00,9.575434108426710722e+00,0.000000000000000000e+00,-1.000000009915358978e+00,0.000000000000000000e+00,1.411779193104608985e-09,0.000000000000000000e+00 +3.868087412705480688e+01,2.635000000000000000e+02,0.000000000000000000e+00,9.574389769341305367e+00,0.000000000000000000e+00,-1.000000009913884602e+00,0.000000000000000000e+00,-1.740083194469357141e-09,0.000000000000000000e+00 +3.868191858004250605e+01,2.635099999999999909e+02,0.000000000000000000e+00,9.573345316343250033e+00,0.000000000000000000e+00,-1.000000009915702037e+00,0.000000000000000000e+00,2.355286323864796050e-09,0.000000000000000000e+00 +3.868296314698014271e+01,2.635199999999999818e+02,0.000000000000000000e+00,9.572300749395258990e+00,0.000000000000000000e+00,-1.000000009913241783e+00,0.000000000000000000e+00,-2.569064942069332407e-09,0.000000000000000000e+00 +3.868400782790501324e+01,2.635300000000000296e+02,0.000000000000000000e+00,9.571256068460034072e+00,0.000000000000000000e+00,-1.000000009915925636e+00,0.000000000000000000e+00,1.407550275032383138e-09,0.000000000000000000e+00 +3.868505262285444246e+01,2.635400000000000205e+02,0.000000000000000000e+00,9.570211273500246918e+00,0.000000000000000000e+00,-1.000000009914455035e+00,0.000000000000000000e+00,-3.493522656413540191e-10,0.000000000000000000e+00 +3.868609753186576938e+01,2.635500000000000114e+02,0.000000000000000000e+00,9.569166364478558506e+00,0.000000000000000000e+00,-1.000000009914820076e+00,0.000000000000000000e+00,3.114930067288483462e-10,0.000000000000000000e+00 +3.868714255497636145e+01,2.635600000000000023e+02,0.000000000000000000e+00,9.568121341357603171e+00,0.000000000000000000e+00,-1.000000009914494559e+00,0.000000000000000000e+00,-1.475712237676727504e-09,0.000000000000000000e+00 +3.868818769222360743e+01,2.635699999999999932e+02,0.000000000000000000e+00,9.567076204099997483e+00,0.000000000000000000e+00,-1.000000009916036880e+00,0.000000000000000000e+00,8.078780045870878896e-10,0.000000000000000000e+00 +3.868923294364490317e+01,2.635799999999999841e+02,0.000000000000000000e+00,9.566030952668334919e+00,0.000000000000000000e+00,-1.000000009915192445e+00,0.000000000000000000e+00,6.720606723185665155e-10,0.000000000000000000e+00 +3.869027830927768008e+01,2.635900000000000318e+02,0.000000000000000000e+00,9.564985587025192970e+00,0.000000000000000000e+00,-1.000000009914489896e+00,0.000000000000000000e+00,-2.419069074748690863e-10,0.000000000000000000e+00 +3.869132378915938375e+01,2.636000000000000227e+02,0.000000000000000000e+00,9.563940107133126034e+00,0.000000000000000000e+00,-1.000000009914742805e+00,0.000000000000000000e+00,-2.945462746727055519e-10,0.000000000000000000e+00 +3.869236938332747400e+01,2.636100000000000136e+02,0.000000000000000000e+00,9.562894512954667192e+00,0.000000000000000000e+00,-1.000000009915050780e+00,0.000000000000000000e+00,-1.096518148833112113e-09,0.000000000000000000e+00 +3.869341509181944616e+01,2.636200000000000045e+02,0.000000000000000000e+00,9.561848804452329986e+00,0.000000000000000000e+00,-1.000000009916197419e+00,0.000000000000000000e+00,6.152908812518476359e-10,0.000000000000000000e+00 +3.869446091467279558e+01,2.636299999999999955e+02,0.000000000000000000e+00,9.560802981588606642e+00,0.000000000000000000e+00,-1.000000009915553933e+00,0.000000000000000000e+00,1.605567966350798970e-09,0.000000000000000000e+00 +3.869550685192506023e+01,2.636399999999999864e+02,0.000000000000000000e+00,9.559757044325971620e+00,0.000000000000000000e+00,-1.000000009913874610e+00,0.000000000000000000e+00,-1.356612761466975062e-09,0.000000000000000000e+00 +3.869655290361378519e+01,2.636499999999999773e+02,0.000000000000000000e+00,9.558710992626878067e+00,0.000000000000000000e+00,-1.000000009915293697e+00,0.000000000000000000e+00,-1.762703201041798112e-09,0.000000000000000000e+00 +3.869759906977653685e+01,2.636600000000000250e+02,0.000000000000000000e+00,9.557664826453754259e+00,0.000000000000000000e+00,-1.000000009917137778e+00,0.000000000000000000e+00,2.022483198607189579e-09,0.000000000000000000e+00 +3.869864535045090292e+01,2.636700000000000159e+02,0.000000000000000000e+00,9.556618545769010709e+00,0.000000000000000000e+00,-1.000000009915021693e+00,0.000000000000000000e+00,2.767082248596517191e-10,0.000000000000000000e+00 +3.869969174567449954e+01,2.636800000000000068e+02,0.000000000000000000e+00,9.555572150535041942e+00,0.000000000000000000e+00,-1.000000009914732146e+00,0.000000000000000000e+00,-2.115610129593490212e-09,0.000000000000000000e+00 +3.870073825548494995e+01,2.636899999999999977e+02,0.000000000000000000e+00,9.554525640714215839e+00,0.000000000000000000e+00,-1.000000009916946153e+00,0.000000000000000000e+00,1.346535643911586571e-09,0.000000000000000000e+00 +3.870178487991990579e+01,2.636999999999999886e+02,0.000000000000000000e+00,9.553479016268878965e+00,0.000000000000000000e+00,-1.000000009915536836e+00,0.000000000000000000e+00,9.458869894794593350e-10,0.000000000000000000e+00 +3.870283161901704005e+01,2.637099999999999795e+02,0.000000000000000000e+00,9.552432277161363672e+00,0.000000000000000000e+00,-1.000000009914546739e+00,0.000000000000000000e+00,-1.679035886015464286e-09,0.000000000000000000e+00 +3.870387847281404703e+01,2.637200000000000273e+02,0.000000000000000000e+00,9.551385423353977444e+00,0.000000000000000000e+00,-1.000000009916304444e+00,0.000000000000000000e+00,-3.054000388054085170e-11,0.000000000000000000e+00 +3.870492544134863522e+01,2.637300000000000182e+02,0.000000000000000000e+00,9.550338454809004674e+00,0.000000000000000000e+00,-1.000000009916336419e+00,0.000000000000000000e+00,1.042487515064773184e-09,0.000000000000000000e+00 +3.870597252465854154e+01,2.637400000000000091e+02,0.000000000000000000e+00,9.549291371488713764e+00,0.000000000000000000e+00,-1.000000009915244847e+00,0.000000000000000000e+00,-1.684632876452548273e-09,0.000000000000000000e+00 +3.870701972278151715e+01,2.637500000000000000e+02,0.000000000000000000e+00,9.548244173355351805e+00,0.000000000000000000e+00,-1.000000009917008992e+00,0.000000000000000000e+00,1.521833696312862321e-09,0.000000000000000000e+00 +3.870806703575534158e+01,2.637599999999999909e+02,0.000000000000000000e+00,9.547196860371141014e+00,0.000000000000000000e+00,-1.000000009915415156e+00,0.000000000000000000e+00,-6.614099091608141081e-10,0.000000000000000000e+00 +3.870911446361780861e+01,2.637699999999999818e+02,0.000000000000000000e+00,9.546149432498289400e+00,0.000000000000000000e+00,-1.000000009916107935e+00,0.000000000000000000e+00,-1.225169826032159913e-10,0.000000000000000000e+00 +3.871016200640673333e+01,2.637800000000000296e+02,0.000000000000000000e+00,9.545101889698978326e+00,0.000000000000000000e+00,-1.000000009916236277e+00,0.000000000000000000e+00,-8.477753512269517904e-11,0.000000000000000000e+00 +3.871120966415995213e+01,2.637900000000000205e+02,0.000000000000000000e+00,9.544054231935371391e+00,0.000000000000000000e+00,-1.000000009916325094e+00,0.000000000000000000e+00,-5.346756110563109294e-10,0.000000000000000000e+00 +3.871225743691532273e+01,2.638000000000000114e+02,0.000000000000000000e+00,9.543006459169610878e+00,0.000000000000000000e+00,-1.000000009916885313e+00,0.000000000000000000e+00,1.779089813939994730e-09,0.000000000000000000e+00 +3.871330532471072416e+01,2.638100000000000023e+02,0.000000000000000000e+00,9.541958571363817754e+00,0.000000000000000000e+00,-1.000000009915021026e+00,0.000000000000000000e+00,-1.218275742183959582e-09,0.000000000000000000e+00 +3.871435332758405679e+01,2.638199999999999932e+02,0.000000000000000000e+00,9.540910568480095222e+00,0.000000000000000000e+00,-1.000000009916297783e+00,0.000000000000000000e+00,-1.422577932504861036e-09,0.000000000000000000e+00 +3.871540144557324226e+01,2.638299999999999841e+02,0.000000000000000000e+00,9.539862450480519840e+00,0.000000000000000000e+00,-1.000000009917788812e+00,0.000000000000000000e+00,1.177972721302870609e-09,0.000000000000000000e+00 +3.871644967871621645e+01,2.638400000000000318e+02,0.000000000000000000e+00,9.538814217327150402e+00,0.000000000000000000e+00,-1.000000009916554022e+00,0.000000000000000000e+00,1.311068143056261332e-10,0.000000000000000000e+00 +3.871749802705094368e+01,2.638500000000000227e+02,0.000000000000000000e+00,9.537765868982027939e+00,0.000000000000000000e+00,-1.000000009916416577e+00,0.000000000000000000e+00,3.017878472299926097e-10,0.000000000000000000e+00 +3.871854649061540954e+01,2.638600000000000136e+02,0.000000000000000000e+00,9.536717405407168613e+00,0.000000000000000000e+00,-1.000000009916100163e+00,0.000000000000000000e+00,8.787943091546012419e-11,0.000000000000000000e+00 +3.871959506944761387e+01,2.638700000000000045e+02,0.000000000000000000e+00,9.535668826564569045e+00,0.000000000000000000e+00,-1.000000009916008015e+00,0.000000000000000000e+00,-2.109933113929949950e-09,0.000000000000000000e+00 +3.872064376358557780e+01,2.638799999999999955e+02,0.000000000000000000e+00,9.534620132416204541e+00,0.000000000000000000e+00,-1.000000009918220689e+00,0.000000000000000000e+00,1.797638916486343714e-09,0.000000000000000000e+00 +3.872169257306735091e+01,2.638899999999999864e+02,0.000000000000000000e+00,9.533571322924027314e+00,0.000000000000000000e+00,-1.000000009916335308e+00,0.000000000000000000e+00,5.194818803223713602e-10,0.000000000000000000e+00 +3.872274149793100406e+01,2.638999999999999773e+02,0.000000000000000000e+00,9.532522398049975365e+00,0.000000000000000000e+00,-1.000000009915790411e+00,0.000000000000000000e+00,-1.082875668876851923e-09,0.000000000000000000e+00 +3.872379053821461525e+01,2.639100000000000250e+02,0.000000000000000000e+00,9.531473357755960052e+00,0.000000000000000000e+00,-1.000000009916926391e+00,0.000000000000000000e+00,-1.381382266487055570e-09,0.000000000000000000e+00 +3.872483969395629799e+01,2.639200000000000159e+02,0.000000000000000000e+00,9.530424202003871414e+00,0.000000000000000000e+00,-1.000000009918375676e+00,0.000000000000000000e+00,1.251720042169177829e-09,0.000000000000000000e+00 +3.872588896519418000e+01,2.639300000000000068e+02,0.000000000000000000e+00,9.529374930755579953e+00,0.000000000000000000e+00,-1.000000009917062282e+00,0.000000000000000000e+00,3.755804667735763179e-10,0.000000000000000000e+00 +3.872693835196641743e+01,2.639399999999999977e+02,0.000000000000000000e+00,9.528325543972938405e+00,0.000000000000000000e+00,-1.000000009916668153e+00,0.000000000000000000e+00,-7.658882077250968928e-10,0.000000000000000000e+00 +3.872798785431117352e+01,2.639499999999999886e+02,0.000000000000000000e+00,9.527276041617774638e+00,0.000000000000000000e+00,-1.000000009917471955e+00,0.000000000000000000e+00,1.066202043315058331e-09,0.000000000000000000e+00 +3.872903747226663995e+01,2.639599999999999795e+02,0.000000000000000000e+00,9.526226423651895203e+00,0.000000000000000000e+00,-1.000000009916352850e+00,0.000000000000000000e+00,-5.632903247440034471e-10,0.000000000000000000e+00 +3.873008720587103682e+01,2.639700000000000273e+02,0.000000000000000000e+00,9.525176690037088889e+00,0.000000000000000000e+00,-1.000000009916944155e+00,0.000000000000000000e+00,-8.022248462260667706e-10,0.000000000000000000e+00 +3.873113705516259131e+01,2.639800000000000182e+02,0.000000000000000000e+00,9.524126840735119615e+00,0.000000000000000000e+00,-1.000000009917786370e+00,0.000000000000000000e+00,3.635308507382289150e-10,0.000000000000000000e+00 +3.873218702017956616e+01,2.639900000000000091e+02,0.000000000000000000e+00,9.523076875707731759e+00,0.000000000000000000e+00,-1.000000009917404675e+00,0.000000000000000000e+00,-2.751026743140929293e-10,0.000000000000000000e+00 +3.873323710096023120e+01,2.640000000000000000e+02,0.000000000000000000e+00,9.522026794916650161e+00,0.000000000000000000e+00,-1.000000009917693555e+00,0.000000000000000000e+00,5.201214107296561565e-10,0.000000000000000000e+00 +3.873428729754289179e+01,2.640099999999999909e+02,0.000000000000000000e+00,9.520976598323576567e+00,0.000000000000000000e+00,-1.000000009917147326e+00,0.000000000000000000e+00,-4.585442745899967299e-10,0.000000000000000000e+00 +3.873533760996586039e+01,2.640199999999999818e+02,0.000000000000000000e+00,9.519926285890193185e+00,0.000000000000000000e+00,-1.000000009917628940e+00,0.000000000000000000e+00,2.600033373411067578e-11,0.000000000000000000e+00 +3.873638803826747790e+01,2.640300000000000296e+02,0.000000000000000000e+00,9.518875857578159128e+00,0.000000000000000000e+00,-1.000000009917601629e+00,0.000000000000000000e+00,3.766461981903174847e-10,0.000000000000000000e+00 +3.873743858248610650e+01,2.640400000000000205e+02,0.000000000000000000e+00,9.517825313349113969e+00,0.000000000000000000e+00,-1.000000009917205945e+00,0.000000000000000000e+00,-9.996295731649354413e-10,0.000000000000000000e+00 +3.873848924266012261e+01,2.640500000000000114e+02,0.000000000000000000e+00,9.516774653164675968e+00,0.000000000000000000e+00,-1.000000009918256216e+00,0.000000000000000000e+00,7.389680192674691698e-10,0.000000000000000000e+00 +3.873954001882793818e+01,2.640600000000000023e+02,0.000000000000000000e+00,9.515723876986440288e+00,0.000000000000000000e+00,-1.000000009917479726e+00,0.000000000000000000e+00,7.792431068926128852e-10,0.000000000000000000e+00 +3.874059091102797225e+01,2.640699999999999932e+02,0.000000000000000000e+00,9.514672984775984332e+00,0.000000000000000000e+00,-1.000000009916660826e+00,0.000000000000000000e+00,-2.469302492393004014e-09,0.000000000000000000e+00 +3.874164191929867229e+01,2.640799999999999841e+02,0.000000000000000000e+00,9.513621976494862409e+00,0.000000000000000000e+00,-1.000000009919256083e+00,0.000000000000000000e+00,2.262854761619092317e-09,0.000000000000000000e+00 +3.874269304367850708e+01,2.640900000000000318e+02,0.000000000000000000e+00,9.512570852104603958e+00,0.000000000000000000e+00,-1.000000009916877541e+00,0.000000000000000000e+00,-1.087368300881286305e-09,0.000000000000000000e+00 +3.874374428420595962e+01,2.641000000000000227e+02,0.000000000000000000e+00,9.511519611566725985e+00,0.000000000000000000e+00,-1.000000009918020627e+00,0.000000000000000000e+00,3.562912983470904436e-10,0.000000000000000000e+00 +3.874479564091954131e+01,2.641100000000000136e+02,0.000000000000000000e+00,9.510468254842715297e+00,0.000000000000000000e+00,-1.000000009917646038e+00,0.000000000000000000e+00,-1.428597634501004660e-09,0.000000000000000000e+00 +3.874584711385778490e+01,2.641200000000000045e+02,0.000000000000000000e+00,9.509416781894042714e+00,0.000000000000000000e+00,-1.000000009919148170e+00,0.000000000000000000e+00,1.607707286795739654e-09,0.000000000000000000e+00 +3.874689870305924444e+01,2.641299999999999955e+02,0.000000000000000000e+00,9.508365192682154188e+00,0.000000000000000000e+00,-1.000000009917457522e+00,0.000000000000000000e+00,-1.598239862867865015e-10,0.000000000000000000e+00 +3.874795040856248818e+01,2.641399999999999864e+02,0.000000000000000000e+00,9.507313487168479682e+00,0.000000000000000000e+00,-1.000000009917625610e+00,0.000000000000000000e+00,-1.895298595573327058e-09,0.000000000000000000e+00 +3.874900223040611280e+01,2.641499999999999773e+02,0.000000000000000000e+00,9.506261665314422515e+00,0.000000000000000000e+00,-1.000000009919619126e+00,0.000000000000000000e+00,1.230815710916397225e-09,0.000000000000000000e+00 +3.875005416862873631e+01,2.641600000000000250e+02,0.000000000000000000e+00,9.505209727081364690e+00,0.000000000000000000e+00,-1.000000009918324384e+00,0.000000000000000000e+00,1.207041010013528283e-09,0.000000000000000000e+00 +3.875110622326899090e+01,2.641700000000000159e+02,0.000000000000000000e+00,9.504157672430672221e+00,0.000000000000000000e+00,-1.000000009917054511e+00,0.000000000000000000e+00,-1.950593672501203915e-09,0.000000000000000000e+00 +3.875215839436554432e+01,2.641800000000000068e+02,0.000000000000000000e+00,9.503105501323686255e+00,0.000000000000000000e+00,-1.000000009919106869e+00,0.000000000000000000e+00,1.400904224253273346e-09,0.000000000000000000e+00 +3.875321068195707142e+01,2.641899999999999977e+02,0.000000000000000000e+00,9.502053213721723068e+00,0.000000000000000000e+00,-1.000000009917632715e+00,0.000000000000000000e+00,-1.559201062693106017e-09,0.000000000000000000e+00 +3.875426308608227544e+01,2.641999999999999886e+02,0.000000000000000000e+00,9.501000809586084728e+00,0.000000000000000000e+00,-1.000000009919273625e+00,0.000000000000000000e+00,4.132796457496454730e-10,0.000000000000000000e+00 +3.875531560677987386e+01,2.642099999999999795e+02,0.000000000000000000e+00,9.499948288878044877e+00,0.000000000000000000e+00,-1.000000009918838639e+00,0.000000000000000000e+00,9.169615114269028015e-10,0.000000000000000000e+00 +3.875636824408861969e+01,2.642200000000000273e+02,0.000000000000000000e+00,9.498895651558861175e+00,0.000000000000000000e+00,-1.000000009917873411e+00,0.000000000000000000e+00,-3.163767798261728148e-11,0.000000000000000000e+00 +3.875742099804727303e+01,2.642300000000000182e+02,0.000000000000000000e+00,9.497842897589768185e+00,0.000000000000000000e+00,-1.000000009917906718e+00,0.000000000000000000e+00,-8.144744716552062304e-10,0.000000000000000000e+00 +3.875847386869462241e+01,2.642400000000000091e+02,0.000000000000000000e+00,9.496790026931977380e+00,0.000000000000000000e+00,-1.000000009918764254e+00,0.000000000000000000e+00,1.859883092814929958e-10,0.000000000000000000e+00 +3.875952685606947767e+01,2.642500000000000000e+02,0.000000000000000000e+00,9.495737039546678915e+00,0.000000000000000000e+00,-1.000000009918568411e+00,0.000000000000000000e+00,-2.201250175312526441e-10,0.000000000000000000e+00 +3.876057996021066998e+01,2.642599999999999909e+02,0.000000000000000000e+00,9.494683935395043406e+00,0.000000000000000000e+00,-1.000000009918800226e+00,0.000000000000000000e+00,-4.157455873032628214e-10,0.000000000000000000e+00 +3.876163318115705181e+01,2.642699999999999818e+02,0.000000000000000000e+00,9.493630714438218376e+00,0.000000000000000000e+00,-1.000000009919238098e+00,0.000000000000000000e+00,-3.857657350763585186e-10,0.000000000000000000e+00 +3.876268651894748984e+01,2.642800000000000296e+02,0.000000000000000000e+00,9.492577376637330033e+00,0.000000000000000000e+00,-1.000000009919644439e+00,0.000000000000000000e+00,1.485981793287586934e-09,0.000000000000000000e+00 +3.876373997362088630e+01,2.642900000000000205e+02,0.000000000000000000e+00,9.491523921953483267e+00,0.000000000000000000e+00,-1.000000009918079025e+00,0.000000000000000000e+00,-1.188653507174067664e-09,0.000000000000000000e+00 +3.876479354521615761e+01,2.643000000000000114e+02,0.000000000000000000e+00,9.490470350347763429e+00,0.000000000000000000e+00,-1.000000009919331356e+00,0.000000000000000000e+00,-3.911163164504005239e-10,0.000000000000000000e+00 +3.876584723377224151e+01,2.643100000000000023e+02,0.000000000000000000e+00,9.489416661781229223e+00,0.000000000000000000e+00,-1.000000009919743471e+00,0.000000000000000000e+00,6.917523198841152118e-10,0.000000000000000000e+00 +3.876690103932809706e+01,2.643199999999999932e+02,0.000000000000000000e+00,9.488362856214921592e+00,0.000000000000000000e+00,-1.000000009919014499e+00,0.000000000000000000e+00,4.761457906853499674e-10,0.000000000000000000e+00 +3.876795496192270463e+01,2.643299999999999841e+02,0.000000000000000000e+00,9.487308933609860162e+00,0.000000000000000000e+00,-1.000000009918512678e+00,0.000000000000000000e+00,-1.022757098405066530e-09,0.000000000000000000e+00 +3.876900900159506591e+01,2.643400000000000318e+02,0.000000000000000000e+00,9.486254893927041465e+00,0.000000000000000000e+00,-1.000000009919590704e+00,0.000000000000000000e+00,1.007688230915059491e-09,0.000000000000000000e+00 +3.877006315838421102e+01,2.643500000000000227e+02,0.000000000000000000e+00,9.485200737127438941e+00,0.000000000000000000e+00,-1.000000009918528443e+00,0.000000000000000000e+00,-1.411112225707752055e-09,0.000000000000000000e+00 +3.877111743232918428e+01,2.643600000000000136e+02,0.000000000000000000e+00,9.484146463172008268e+00,0.000000000000000000e+00,-1.000000009920016142e+00,0.000000000000000000e+00,1.325666287536448772e-09,0.000000000000000000e+00 +3.877217182346905133e+01,2.643700000000000045e+02,0.000000000000000000e+00,9.483092072021678476e+00,0.000000000000000000e+00,-1.000000009918618371e+00,0.000000000000000000e+00,-1.951534430133448497e-09,0.000000000000000000e+00 +3.877322633184290623e+01,2.643799999999999955e+02,0.000000000000000000e+00,9.482037563637362609e+00,0.000000000000000000e+00,-1.000000009920676280e+00,0.000000000000000000e+00,1.552337435410905781e-09,0.000000000000000000e+00 +3.877428095748986436e+01,2.643899999999999864e+02,0.000000000000000000e+00,9.480982937979945291e+00,0.000000000000000000e+00,-1.000000009919039146e+00,0.000000000000000000e+00,-9.254464082921707273e-10,0.000000000000000000e+00 +3.877533570044904820e+01,2.643999999999999773e+02,0.000000000000000000e+00,9.479928195010296932e+00,0.000000000000000000e+00,-1.000000009920015254e+00,0.000000000000000000e+00,1.808587569741081702e-09,0.000000000000000000e+00 +3.877639056075962287e+01,2.644100000000000250e+02,0.000000000000000000e+00,9.478873334689259522e+00,0.000000000000000000e+00,-1.000000009918107446e+00,0.000000000000000000e+00,-1.405540486866360458e-09,0.000000000000000000e+00 +3.877744553846076059e+01,2.644200000000000159e+02,0.000000000000000000e+00,9.477818356977659064e+00,0.000000000000000000e+00,-1.000000009919590260e+00,0.000000000000000000e+00,-9.739618746194580338e-10,0.000000000000000000e+00 +3.877850063359166199e+01,2.644300000000000068e+02,0.000000000000000000e+00,9.476763261836293140e+00,0.000000000000000000e+00,-1.000000009920617883e+00,0.000000000000000000e+00,1.519699572338366988e-09,0.000000000000000000e+00 +3.877955584619154195e+01,2.644399999999999977e+02,0.000000000000000000e+00,9.475708049225941565e+00,0.000000000000000000e+00,-1.000000009919014277e+00,0.000000000000000000e+00,-1.885421148742098009e-09,0.000000000000000000e+00 +3.878061117629965082e+01,2.644499999999999886e+02,0.000000000000000000e+00,9.474652719107364618e+00,0.000000000000000000e+00,-1.000000009921004018e+00,0.000000000000000000e+00,1.587734478805186985e-09,0.000000000000000000e+00 +3.878166662395525321e+01,2.644599999999999795e+02,0.000000000000000000e+00,9.473597271441294154e+00,0.000000000000000000e+00,-1.000000009919328248e+00,0.000000000000000000e+00,-8.052432133326907657e-10,0.000000000000000000e+00 +3.878272218919762793e+01,2.644700000000000273e+02,0.000000000000000000e+00,9.472541706188447819e+00,0.000000000000000000e+00,-1.000000009920178234e+00,0.000000000000000000e+00,5.191010494981071501e-10,0.000000000000000000e+00 +3.878377787206608929e+01,2.644800000000000182e+02,0.000000000000000000e+00,9.471486023309514835e+00,0.000000000000000000e+00,-1.000000009919630228e+00,0.000000000000000000e+00,-8.006472660579816202e-10,0.000000000000000000e+00 +3.878483367259996584e+01,2.644900000000000091e+02,0.000000000000000000e+00,9.470430222765166661e+00,0.000000000000000000e+00,-1.000000009920475552e+00,0.000000000000000000e+00,1.625088613933050285e-09,0.000000000000000000e+00 +3.878588959083860743e+01,2.645000000000000000e+02,0.000000000000000000e+00,9.469374304516049889e+00,0.000000000000000000e+00,-1.000000009918759591e+00,0.000000000000000000e+00,-1.747910895876046278e-09,0.000000000000000000e+00 +3.878694562682139235e+01,2.645099999999999909e+02,0.000000000000000000e+00,9.468318268522793346e+00,0.000000000000000000e+00,-1.000000009920605448e+00,0.000000000000000000e+00,2.474511840333832203e-10,0.000000000000000000e+00 +3.878800178058771309e+01,2.645199999999999818e+02,0.000000000000000000e+00,9.467262114745997437e+00,0.000000000000000000e+00,-1.000000009920344102e+00,0.000000000000000000e+00,-3.382366551868700277e-10,0.000000000000000000e+00 +3.878905805217698344e+01,2.645300000000000296e+02,0.000000000000000000e+00,9.466205843146246579e+00,0.000000000000000000e+00,-1.000000009920701372e+00,0.000000000000000000e+00,1.287425961155513996e-09,0.000000000000000000e+00 +3.879011444162865274e+01,2.645400000000000205e+02,0.000000000000000000e+00,9.465149453684100322e+00,0.000000000000000000e+00,-1.000000009919341348e+00,0.000000000000000000e+00,-1.226543582515402692e-09,0.000000000000000000e+00 +3.879117094898217744e+01,2.645500000000000114e+02,0.000000000000000000e+00,9.464092946320098676e+00,0.000000000000000000e+00,-1.000000009920637201e+00,0.000000000000000000e+00,9.288412444238245616e-11,0.000000000000000000e+00 +3.879222757427703527e+01,2.645600000000000023e+02,0.000000000000000000e+00,9.463036321014755003e+00,0.000000000000000000e+00,-1.000000009920539057e+00,0.000000000000000000e+00,4.864315413388533215e-10,0.000000000000000000e+00 +3.879328431755273954e+01,2.645699999999999932e+02,0.000000000000000000e+00,9.461979577728564905e+00,0.000000000000000000e+00,-1.000000009920025024e+00,0.000000000000000000e+00,-3.025413384689453038e-11,0.000000000000000000e+00 +3.879434117884881772e+01,2.645799999999999841e+02,0.000000000000000000e+00,9.460922716422000889e+00,0.000000000000000000e+00,-1.000000009920056998e+00,0.000000000000000000e+00,1.497832501764248300e-10,0.000000000000000000e+00 +3.879539815820481863e+01,2.645900000000000318e+02,0.000000000000000000e+00,9.459865737055512369e+00,0.000000000000000000e+00,-1.000000009919898680e+00,0.000000000000000000e+00,-2.138321368932440926e-09,0.000000000000000000e+00 +3.879645525566031949e+01,2.646000000000000227e+02,0.000000000000000000e+00,9.458808639589527445e+00,0.000000000000000000e+00,-1.000000009922159094e+00,0.000000000000000000e+00,2.658321139909705884e-09,0.000000000000000000e+00 +3.879751247125490465e+01,2.646100000000000136e+02,0.000000000000000000e+00,9.457751423984449346e+00,0.000000000000000000e+00,-1.000000009919348676e+00,0.000000000000000000e+00,-1.338777207491334272e-09,0.000000000000000000e+00 +3.879856980502820107e+01,2.646200000000000045e+02,0.000000000000000000e+00,9.456694090200667091e+00,0.000000000000000000e+00,-1.000000009920764210e+00,0.000000000000000000e+00,1.889827112839936942e-10,0.000000000000000000e+00 +3.879962725701984283e+01,2.646299999999999955e+02,0.000000000000000000e+00,9.455636638198537725e+00,0.000000000000000000e+00,-1.000000009920564370e+00,0.000000000000000000e+00,-6.874002334780640183e-10,0.000000000000000000e+00 +3.880068482726948531e+01,2.646399999999999864e+02,0.000000000000000000e+00,9.454579067938402304e+00,0.000000000000000000e+00,-1.000000009921291344e+00,0.000000000000000000e+00,8.118141105066323248e-10,0.000000000000000000e+00 +3.880174251581681943e+01,2.646499999999999773e+02,0.000000000000000000e+00,9.453521379380577017e+00,0.000000000000000000e+00,-1.000000009920432698e+00,0.000000000000000000e+00,-6.066408883322853867e-11,0.000000000000000000e+00 +3.880280032270154322e+01,2.646600000000000250e+02,0.000000000000000000e+00,9.452463572485358512e+00,0.000000000000000000e+00,-1.000000009920496868e+00,0.000000000000000000e+00,-1.141784485499294291e-10,0.000000000000000000e+00 +3.880385824796339023e+01,2.646700000000000159e+02,0.000000000000000000e+00,9.451405647213018568e+00,0.000000000000000000e+00,-1.000000009920617661e+00,0.000000000000000000e+00,-9.202508480361323607e-10,0.000000000000000000e+00 +3.880491629164210821e+01,2.646800000000000068e+02,0.000000000000000000e+00,9.450347603523807649e+00,0.000000000000000000e+00,-1.000000009921591326e+00,0.000000000000000000e+00,7.100981200896986993e-10,0.000000000000000000e+00 +3.880597445377746624e+01,2.646899999999999977e+02,0.000000000000000000e+00,9.449289441377953125e+00,0.000000000000000000e+00,-1.000000009920839927e+00,0.000000000000000000e+00,3.189208886066216565e-11,0.000000000000000000e+00 +3.880703273440925472e+01,2.646999999999999886e+02,0.000000000000000000e+00,9.448231160735662826e+00,0.000000000000000000e+00,-1.000000009920806177e+00,0.000000000000000000e+00,-1.350856325554359793e-09,0.000000000000000000e+00 +3.880809113357729956e+01,2.647099999999999795e+02,0.000000000000000000e+00,9.447172761557119713e+00,0.000000000000000000e+00,-1.000000009922235922e+00,0.000000000000000000e+00,1.333503912741975768e-09,0.000000000000000000e+00 +3.880914965132143379e+01,2.647200000000000273e+02,0.000000000000000000e+00,9.446114243802483657e+00,0.000000000000000000e+00,-1.000000009920824384e+00,0.000000000000000000e+00,1.722013597085645152e-10,0.000000000000000000e+00 +3.881020828768151887e+01,2.647300000000000182e+02,0.000000000000000000e+00,9.445055607431896760e+00,0.000000000000000000e+00,-1.000000009920642086e+00,0.000000000000000000e+00,-6.123893031273728213e-11,0.000000000000000000e+00 +3.881126704269743755e+01,2.647400000000000091e+02,0.000000000000000000e+00,9.443996852405474485e+00,0.000000000000000000e+00,-1.000000009920706923e+00,0.000000000000000000e+00,-9.373538818525088157e-10,0.000000000000000000e+00 +3.881232591640909391e+01,2.647500000000000000e+02,0.000000000000000000e+00,9.442937978683310973e+00,0.000000000000000000e+00,-1.000000009921699462e+00,0.000000000000000000e+00,7.286218179008874931e-10,0.000000000000000000e+00 +3.881338490885642045e+01,2.647599999999999909e+02,0.000000000000000000e+00,9.441878986225477277e+00,0.000000000000000000e+00,-1.000000009920927857e+00,0.000000000000000000e+00,-1.383911722731542952e-09,0.000000000000000000e+00 +3.881444402007936390e+01,2.647699999999999818e+02,0.000000000000000000e+00,9.440819874992024907e+00,0.000000000000000000e+00,-1.000000009922393573e+00,0.000000000000000000e+00,6.592810410233056557e-10,0.000000000000000000e+00 +3.881550325011789937e+01,2.647800000000000296e+02,0.000000000000000000e+00,9.439760644942978729e+00,0.000000000000000000e+00,-1.000000009921695243e+00,0.000000000000000000e+00,5.397323401707548296e-10,0.000000000000000000e+00 +3.881656259901202333e+01,2.647900000000000205e+02,0.000000000000000000e+00,9.438701296038345845e+00,0.000000000000000000e+00,-1.000000009921123478e+00,0.000000000000000000e+00,-1.435631699694687386e-10,0.000000000000000000e+00 +3.881762206680174643e+01,2.648000000000000114e+02,0.000000000000000000e+00,9.437641828238108488e+00,0.000000000000000000e+00,-1.000000009921275579e+00,0.000000000000000000e+00,2.093481873723906112e-10,0.000000000000000000e+00 +3.881868165352711486e+01,2.648100000000000023e+02,0.000000000000000000e+00,9.436582241502225799e+00,0.000000000000000000e+00,-1.000000009921053756e+00,0.000000000000000000e+00,-1.551600881073955151e-09,0.000000000000000000e+00 +3.881974135922818903e+01,2.648199999999999932e+02,0.000000000000000000e+00,9.435522535790635601e+00,0.000000000000000000e+00,-1.000000009922697997e+00,0.000000000000000000e+00,9.170282786276210020e-10,0.000000000000000000e+00 +3.882080118394505774e+01,2.648299999999999841e+02,0.000000000000000000e+00,9.434462711063250850e+00,0.000000000000000000e+00,-1.000000009921726107e+00,0.000000000000000000e+00,1.303429075521734691e-09,0.000000000000000000e+00 +3.882186112771782405e+01,2.648400000000000318e+02,0.000000000000000000e+00,9.433402767279966739e+00,0.000000000000000000e+00,-1.000000009920344546e+00,0.000000000000000000e+00,-1.954923956649066904e-09,0.000000000000000000e+00 +3.882292119058661939e+01,2.648500000000000227e+02,0.000000000000000000e+00,9.432342704400653588e+00,0.000000000000000000e+00,-1.000000009922416888e+00,0.000000000000000000e+00,6.413055278126033535e-10,0.000000000000000000e+00 +3.882398137259159654e+01,2.648600000000000136e+02,0.000000000000000000e+00,9.431282522385155076e+00,0.000000000000000000e+00,-1.000000009921736988e+00,0.000000000000000000e+00,-3.756932730505140003e-10,0.000000000000000000e+00 +3.882504167377292958e+01,2.648700000000000045e+02,0.000000000000000000e+00,9.430222221193298893e+00,0.000000000000000000e+00,-1.000000009922135336e+00,0.000000000000000000e+00,-2.483400941407699147e-10,0.000000000000000000e+00 +3.882610209417082103e+01,2.648799999999999955e+02,0.000000000000000000e+00,9.429161800784886083e+00,0.000000000000000000e+00,-1.000000009922398680e+00,0.000000000000000000e+00,1.037634997584688658e-09,0.000000000000000000e+00 +3.882716263382548760e+01,2.648899999999999864e+02,0.000000000000000000e+00,9.428101261119696375e+00,0.000000000000000000e+00,-1.000000009921298227e+00,0.000000000000000000e+00,-1.239118393771387543e-09,0.000000000000000000e+00 +3.882822329277717444e+01,2.648999999999999773e+02,0.000000000000000000e+00,9.427040602157488181e+00,0.000000000000000000e+00,-1.000000009922612509e+00,0.000000000000000000e+00,8.331029554350789890e-10,0.000000000000000000e+00 +3.882928407106614088e+01,2.649100000000000250e+02,0.000000000000000000e+00,9.425979823857993267e+00,0.000000000000000000e+00,-1.000000009921728772e+00,0.000000000000000000e+00,-6.247569078569295180e-10,0.000000000000000000e+00 +3.883034496873268182e+01,2.649200000000000159e+02,0.000000000000000000e+00,9.424918926180925638e+00,0.000000000000000000e+00,-1.000000009922391575e+00,0.000000000000000000e+00,7.176047977591613753e-10,0.000000000000000000e+00 +3.883140598581710634e+01,2.649300000000000068e+02,0.000000000000000000e+00,9.423857909085972651e+00,0.000000000000000000e+00,-1.000000009921630184e+00,0.000000000000000000e+00,-1.436512787519888001e-09,0.000000000000000000e+00 +3.883246712235975195e+01,2.649399999999999977e+02,0.000000000000000000e+00,9.422796772532802123e+00,0.000000000000000000e+00,-1.000000009923154520e+00,0.000000000000000000e+00,8.176634877412200552e-10,0.000000000000000000e+00 +3.883352837840097038e+01,2.649499999999999886e+02,0.000000000000000000e+00,9.421735516481055228e+00,0.000000000000000000e+00,-1.000000009922286770e+00,0.000000000000000000e+00,1.185143798673519599e-09,0.000000000000000000e+00 +3.883458975398114177e+01,2.649599999999999795e+02,0.000000000000000000e+00,9.420674140890355375e+00,0.000000000000000000e+00,-1.000000009921028887e+00,0.000000000000000000e+00,-1.892669568332471080e-09,0.000000000000000000e+00 +3.883565124914066757e+01,2.649700000000000273e+02,0.000000000000000000e+00,9.419612645720301103e+00,0.000000000000000000e+00,-1.000000009923037947e+00,0.000000000000000000e+00,1.058964001494231119e-09,0.000000000000000000e+00 +3.883671286391997057e+01,2.649800000000000182e+02,0.000000000000000000e+00,9.418551030930464307e+00,0.000000000000000000e+00,-1.000000009921913735e+00,0.000000000000000000e+00,-9.785372573062032131e-10,0.000000000000000000e+00 +3.883777459835950197e+01,2.649900000000000091e+02,0.000000000000000000e+00,9.417489296480400895e+00,0.000000000000000000e+00,-1.000000009922952682e+00,0.000000000000000000e+00,-1.089464501606027399e-10,0.000000000000000000e+00 +3.883883645249972716e+01,2.650000000000000000e+02,0.000000000000000000e+00,9.416427442329638353e+00,0.000000000000000000e+00,-1.000000009923068367e+00,0.000000000000000000e+00,5.317074555276472968e-10,0.000000000000000000e+00 +3.883989842638113998e+01,2.650099999999999909e+02,0.000000000000000000e+00,9.415365468437684626e+00,0.000000000000000000e+00,-1.000000009922503708e+00,0.000000000000000000e+00,9.598087406103552627e-10,0.000000000000000000e+00 +3.884096052004426269e+01,2.650199999999999818e+02,0.000000000000000000e+00,9.414303374764024568e+00,0.000000000000000000e+00,-1.000000009921484301e+00,0.000000000000000000e+00,-1.957237094572307236e-09,0.000000000000000000e+00 +3.884202273352963175e+01,2.650300000000000296e+02,0.000000000000000000e+00,9.413241161268119939e+00,0.000000000000000000e+00,-1.000000009923563304e+00,0.000000000000000000e+00,1.242390756108273584e-09,0.000000000000000000e+00 +3.884308506687780493e+01,2.650400000000000205e+02,0.000000000000000000e+00,9.412178827909405854e+00,0.000000000000000000e+00,-1.000000009922243471e+00,0.000000000000000000e+00,-4.443177423348964518e-10,0.000000000000000000e+00 +3.884414752012936844e+01,2.650500000000000114e+02,0.000000000000000000e+00,9.411116374647301441e+00,0.000000000000000000e+00,-1.000000009922715538e+00,0.000000000000000000e+00,-7.050606020810866717e-10,0.000000000000000000e+00 +3.884521009332492980e+01,2.650600000000000023e+02,0.000000000000000000e+00,9.410053801441197407e+00,0.000000000000000000e+00,-1.000000009923464717e+00,0.000000000000000000e+00,2.047662645091013478e-09,0.000000000000000000e+00 +3.884627278650511784e+01,2.650699999999999932e+02,0.000000000000000000e+00,9.408991108250463142e+00,0.000000000000000000e+00,-1.000000009921288679e+00,0.000000000000000000e+00,-1.607024726727747196e-09,0.000000000000000000e+00 +3.884733559971058980e+01,2.650799999999999841e+02,0.000000000000000000e+00,9.407928295034448496e+00,0.000000000000000000e+00,-1.000000009922996647e+00,0.000000000000000000e+00,-6.429879582573690709e-10,0.000000000000000000e+00 +3.884839853298201717e+01,2.650900000000000318e+02,0.000000000000000000e+00,9.406865361752473120e+00,0.000000000000000000e+00,-1.000000009923680100e+00,0.000000000000000000e+00,2.366546615310117226e-10,0.000000000000000000e+00 +3.884946158636009983e+01,2.651000000000000227e+02,0.000000000000000000e+00,9.405802308363838904e+00,0.000000000000000000e+00,-1.000000009923428523e+00,0.000000000000000000e+00,1.048221993331168925e-09,0.000000000000000000e+00 +3.885052475988556608e+01,2.651100000000000136e+02,0.000000000000000000e+00,9.404739134827824643e+00,0.000000000000000000e+00,-1.000000009922314081e+00,0.000000000000000000e+00,-1.334614370367073839e-09,0.000000000000000000e+00 +3.885158805359915135e+01,2.651200000000000045e+02,0.000000000000000000e+00,9.403675841103686039e+00,0.000000000000000000e+00,-1.000000009923733169e+00,0.000000000000000000e+00,9.604963240112273895e-10,0.000000000000000000e+00 +3.885265146754163368e+01,2.651299999999999955e+02,0.000000000000000000e+00,9.402612427150652152e+00,0.000000000000000000e+00,-1.000000009922711763e+00,0.000000000000000000e+00,9.478609101890346992e-11,0.000000000000000000e+00 +3.885371500175379822e+01,2.651399999999999864e+02,0.000000000000000000e+00,9.401548892927934276e+00,0.000000000000000000e+00,-1.000000009922610955e+00,0.000000000000000000e+00,-7.740684381247037704e-10,0.000000000000000000e+00 +3.885477865627645855e+01,2.651499999999999773e+02,0.000000000000000000e+00,9.400485238394717058e+00,0.000000000000000000e+00,-1.000000009923434297e+00,0.000000000000000000e+00,-5.907135497342131324e-11,0.000000000000000000e+00 +3.885584243115045666e+01,2.651600000000000250e+02,0.000000000000000000e+00,9.399421463510162056e+00,0.000000000000000000e+00,-1.000000009923497135e+00,0.000000000000000000e+00,6.841483725625054877e-10,0.000000000000000000e+00 +3.885690632641664877e+01,2.651700000000000159e+02,0.000000000000000000e+00,9.398357568233409509e+00,0.000000000000000000e+00,-1.000000009922769273e+00,0.000000000000000000e+00,-1.665101279900369077e-09,0.000000000000000000e+00 +3.885797034211592660e+01,2.651800000000000068e+02,0.000000000000000000e+00,9.397293552523576565e+00,0.000000000000000000e+00,-1.000000009924540967e+00,0.000000000000000000e+00,2.322614867836579509e-09,0.000000000000000000e+00 +3.885903447828918900e+01,2.651899999999999977e+02,0.000000000000000000e+00,9.396229416339753726e+00,0.000000000000000000e+00,-1.000000009922069388e+00,0.000000000000000000e+00,-1.455251478853942389e-09,0.000000000000000000e+00 +3.886009873497737033e+01,2.651999999999999886e+02,0.000000000000000000e+00,9.395165159641015507e+00,0.000000000000000000e+00,-1.000000009923618149e+00,0.000000000000000000e+00,-4.332924693833814708e-10,0.000000000000000000e+00 +3.886116311222141917e+01,2.652099999999999795e+02,0.000000000000000000e+00,9.394100782386404447e+00,0.000000000000000000e+00,-1.000000009924079336e+00,0.000000000000000000e+00,6.981538751260018460e-10,0.000000000000000000e+00 +3.886222761006231252e+01,2.652200000000000273e+02,0.000000000000000000e+00,9.393036284534945324e+00,0.000000000000000000e+00,-1.000000009923336153e+00,0.000000000000000000e+00,3.885608856466183688e-10,0.000000000000000000e+00 +3.886329222854105581e+01,2.652300000000000182e+02,0.000000000000000000e+00,9.391971666045639822e+00,0.000000000000000000e+00,-1.000000009922922484e+00,0.000000000000000000e+00,-1.345315175208759475e-09,0.000000000000000000e+00 +3.886435696769866865e+01,2.652400000000000091e+02,0.000000000000000000e+00,9.390906926877464755e+00,0.000000000000000000e+00,-1.000000009924354893e+00,0.000000000000000000e+00,2.139415424146368820e-10,0.000000000000000000e+00 +3.886542182757619202e+01,2.652500000000000000e+02,0.000000000000000000e+00,9.389842066989372071e+00,0.000000000000000000e+00,-1.000000009924127076e+00,0.000000000000000000e+00,3.811313775349616580e-10,0.000000000000000000e+00 +3.886648680821470236e+01,2.652599999999999909e+02,0.000000000000000000e+00,9.388777086340294176e+00,0.000000000000000000e+00,-1.000000009923721178e+00,0.000000000000000000e+00,7.396612456375208900e-10,0.000000000000000000e+00 +3.886755190965529039e+01,2.652699999999999818e+02,0.000000000000000000e+00,9.387711984889138606e+00,0.000000000000000000e+00,-1.000000009922933364e+00,0.000000000000000000e+00,-1.825180143459654893e-09,0.000000000000000000e+00 +3.886861713193906809e+01,2.652800000000000296e+02,0.000000000000000000e+00,9.386646762594789806e+00,0.000000000000000000e+00,-1.000000009924877586e+00,0.000000000000000000e+00,2.096134521321419945e-09,0.000000000000000000e+00 +3.886968247510717589e+01,2.652900000000000205e+02,0.000000000000000000e+00,9.385581419416105575e+00,0.000000000000000000e+00,-1.000000009922644484e+00,0.000000000000000000e+00,-1.568640136538791019e-09,0.000000000000000000e+00 +3.887074793920078264e+01,2.653000000000000114e+02,0.000000000000000000e+00,9.384515955311927726e+00,0.000000000000000000e+00,-1.000000009924315814e+00,0.000000000000000000e+00,-2.808936973632931824e-10,0.000000000000000000e+00 +3.887181352426107139e+01,2.653100000000000023e+02,0.000000000000000000e+00,9.383450370241066096e+00,0.000000000000000000e+00,-1.000000009924615130e+00,0.000000000000000000e+00,1.278046214882226789e-09,0.000000000000000000e+00 +3.887287923032924652e+01,2.653199999999999932e+02,0.000000000000000000e+00,9.382384664162312760e+00,0.000000000000000000e+00,-1.000000009923253108e+00,0.000000000000000000e+00,-1.564980891481655159e-09,0.000000000000000000e+00 +3.887394505744654793e+01,2.653299999999999841e+02,0.000000000000000000e+00,9.381318837034436697e+00,0.000000000000000000e+00,-1.000000009924921107e+00,0.000000000000000000e+00,5.890925452141846100e-10,0.000000000000000000e+00 +3.887501100565422973e+01,2.653400000000000318e+02,0.000000000000000000e+00,9.380252888816178469e+00,0.000000000000000000e+00,-1.000000009924293165e+00,0.000000000000000000e+00,1.500474007510449365e-09,0.000000000000000000e+00 +3.887607707499356735e+01,2.653500000000000227e+02,0.000000000000000000e+00,9.379186819466260872e+00,0.000000000000000000e+00,-1.000000009922693556e+00,0.000000000000000000e+00,-1.937857282533118666e-09,0.000000000000000000e+00 +3.887714326550586463e+01,2.653600000000000136e+02,0.000000000000000000e+00,9.378120628943381831e+00,0.000000000000000000e+00,-1.000000009924759681e+00,0.000000000000000000e+00,-3.327613021808845332e-10,0.000000000000000000e+00 +3.887820957723245385e+01,2.653700000000000045e+02,0.000000000000000000e+00,9.377054317206210854e+00,0.000000000000000000e+00,-1.000000009925114508e+00,0.000000000000000000e+00,1.641755027285606523e-09,0.000000000000000000e+00 +3.887927601021468149e+01,2.653799999999999955e+02,0.000000000000000000e+00,9.375987884213399681e+00,0.000000000000000000e+00,-1.000000009923363686e+00,0.000000000000000000e+00,-6.818181646117445021e-10,0.000000000000000000e+00 +3.888034256449392245e+01,2.653899999999999864e+02,0.000000000000000000e+00,9.374921329923576963e+00,0.000000000000000000e+00,-1.000000009924090882e+00,0.000000000000000000e+00,-1.038743700750158738e-09,0.000000000000000000e+00 +3.888140924011157296e+01,2.653999999999999773e+02,0.000000000000000000e+00,9.373854654295342925e+00,0.000000000000000000e+00,-1.000000009925198885e+00,0.000000000000000000e+00,5.850854341732204931e-10,0.000000000000000000e+00 +3.888247603710905054e+01,2.654100000000000250e+02,0.000000000000000000e+00,9.372787857287276481e+00,0.000000000000000000e+00,-1.000000009924574718e+00,0.000000000000000000e+00,1.084085087224227509e-09,0.000000000000000000e+00 +3.888354295552780115e+01,2.654200000000000159e+02,0.000000000000000000e+00,9.371720938857935224e+00,0.000000000000000000e+00,-1.000000009923418087e+00,0.000000000000000000e+00,-1.084585966222907530e-09,0.000000000000000000e+00 +3.888460999540929919e+01,2.654300000000000068e+02,0.000000000000000000e+00,9.370653898965851880e+00,0.000000000000000000e+00,-1.000000009924575384e+00,0.000000000000000000e+00,3.370739091473824470e-10,0.000000000000000000e+00 +3.888567715679502612e+01,2.654399999999999977e+02,0.000000000000000000e+00,9.369586737569532531e+00,0.000000000000000000e+00,-1.000000009924215671e+00,0.000000000000000000e+00,-8.752521242206827533e-10,0.000000000000000000e+00 +3.888674443972650607e+01,2.654499999999999886e+02,0.000000000000000000e+00,9.368519454627463716e+00,0.000000000000000000e+00,-1.000000009925149813e+00,0.000000000000000000e+00,-2.517077333252622406e-11,0.000000000000000000e+00 +3.888781184424527027e+01,2.654599999999999795e+02,0.000000000000000000e+00,9.367452050098105332e+00,0.000000000000000000e+00,-1.000000009925176681e+00,0.000000000000000000e+00,1.342426959179591710e-09,0.000000000000000000e+00 +3.888887937039288545e+01,2.654700000000000273e+02,0.000000000000000000e+00,9.366384523939895956e+00,0.000000000000000000e+00,-1.000000009923743605e+00,0.000000000000000000e+00,-1.430247617476224848e-09,0.000000000000000000e+00 +3.888994701821093258e+01,2.654800000000000182e+02,0.000000000000000000e+00,9.365316876111251077e+00,0.000000000000000000e+00,-1.000000009925270605e+00,0.000000000000000000e+00,1.024370609042347029e-09,0.000000000000000000e+00 +3.889101478774102816e+01,2.654900000000000091e+02,0.000000000000000000e+00,9.364249106570557757e+00,0.000000000000000000e+00,-1.000000009924176814e+00,0.000000000000000000e+00,-6.277349318736582851e-10,0.000000000000000000e+00 +3.889208267902480287e+01,2.655000000000000000e+02,0.000000000000000000e+00,9.363181215276185299e+00,0.000000000000000000e+00,-1.000000009924847166e+00,0.000000000000000000e+00,-1.363852781204583656e-10,0.000000000000000000e+00 +3.889315069210391584e+01,2.655099999999999909e+02,0.000000000000000000e+00,9.362113202186474581e+00,0.000000000000000000e+00,-1.000000009924992828e+00,0.000000000000000000e+00,-6.011909055186511034e-10,0.000000000000000000e+00 +3.889421882702004751e+01,2.655199999999999818e+02,0.000000000000000000e+00,9.361045067259745167e+00,0.000000000000000000e+00,-1.000000009925634981e+00,0.000000000000000000e+00,1.107669715137475385e-09,0.000000000000000000e+00 +3.889528708381489963e+01,2.655300000000000296e+02,0.000000000000000000e+00,9.359976810454291751e+00,0.000000000000000000e+00,-1.000000009924451705e+00,0.000000000000000000e+00,-1.218110592084378291e-09,0.000000000000000000e+00 +3.889635546253020237e+01,2.655400000000000205e+02,0.000000000000000000e+00,9.358908431728387711e+00,0.000000000000000000e+00,-1.000000009925753108e+00,0.000000000000000000e+00,1.775108855990834214e-09,0.000000000000000000e+00 +3.889742396320770723e+01,2.655500000000000114e+02,0.000000000000000000e+00,9.357839931040278003e+00,0.000000000000000000e+00,-1.000000009923856403e+00,0.000000000000000000e+00,-2.343200320494647506e-09,0.000000000000000000e+00 +3.889849258588918701e+01,2.655600000000000023e+02,0.000000000000000000e+00,9.356771308348189820e+00,0.000000000000000000e+00,-1.000000009926360400e+00,0.000000000000000000e+00,1.999709816465940253e-09,0.000000000000000000e+00 +3.889956133061645005e+01,2.655699999999999932e+02,0.000000000000000000e+00,9.355702563610318379e+00,0.000000000000000000e+00,-1.000000009924223221e+00,0.000000000000000000e+00,-7.335240360030866188e-10,0.000000000000000000e+00 +3.890063019743131889e+01,2.655799999999999841e+02,0.000000000000000000e+00,9.354633696784844687e+00,0.000000000000000000e+00,-1.000000009925007260e+00,0.000000000000000000e+00,-1.193112629901008565e-09,0.000000000000000000e+00 +3.890169918637563740e+01,2.655900000000000318e+02,0.000000000000000000e+00,9.353564707829917779e+00,0.000000000000000000e+00,-1.000000009926282685e+00,0.000000000000000000e+00,2.188230880089037506e-09,0.000000000000000000e+00 +3.890276829749127785e+01,2.656000000000000227e+02,0.000000000000000000e+00,9.352495596703665370e+00,0.000000000000000000e+00,-1.000000009923943223e+00,0.000000000000000000e+00,-1.450554826098462361e-09,0.000000000000000000e+00 +3.890383753082013385e+01,2.656100000000000136e+02,0.000000000000000000e+00,9.351426363364195637e+00,0.000000000000000000e+00,-1.000000009925494204e+00,0.000000000000000000e+00,-1.213675539931984945e-09,0.000000000000000000e+00 +3.890490688640412742e+01,2.656200000000000045e+02,0.000000000000000000e+00,9.350357007769584783e+00,0.000000000000000000e+00,-1.000000009926792055e+00,0.000000000000000000e+00,1.358662876845698882e-09,0.000000000000000000e+00 +3.890597636428520900e+01,2.656299999999999955e+02,0.000000000000000000e+00,9.349287529877889469e+00,0.000000000000000000e+00,-1.000000009925338995e+00,0.000000000000000000e+00,7.182817641421811648e-11,0.000000000000000000e+00 +3.890704596450533614e+01,2.656399999999999864e+02,0.000000000000000000e+00,9.348217929647145041e+00,0.000000000000000000e+00,-1.000000009925262168e+00,0.000000000000000000e+00,-3.979157841257036425e-10,0.000000000000000000e+00 +3.890811568710650903e+01,2.656499999999999773e+02,0.000000000000000000e+00,9.347148207035358425e+00,0.000000000000000000e+00,-1.000000009925687827e+00,0.000000000000000000e+00,1.517178680319829839e-09,0.000000000000000000e+00 +3.890918553213073494e+01,2.656600000000000250e+02,0.000000000000000000e+00,9.346078362000513451e+00,0.000000000000000000e+00,-1.000000009924064681e+00,0.000000000000000000e+00,-1.924790922370850898e-09,0.000000000000000000e+00 +3.891025549962005670e+01,2.656700000000000159e+02,0.000000000000000000e+00,9.345008394500572635e+00,0.000000000000000000e+00,-1.000000009926124145e+00,0.000000000000000000e+00,1.552106505339529695e-10,0.000000000000000000e+00 +3.891132558961653842e+01,2.656800000000000068e+02,0.000000000000000000e+00,9.343938304493468294e+00,0.000000000000000000e+00,-1.000000009925958055e+00,0.000000000000000000e+00,1.452339762485583261e-11,0.000000000000000000e+00 +3.891239580216226557e+01,2.656899999999999977e+02,0.000000000000000000e+00,9.342868091937114983e+00,0.000000000000000000e+00,-1.000000009925942512e+00,0.000000000000000000e+00,7.744233385054422000e-10,0.000000000000000000e+00 +3.891346613729935910e+01,2.656999999999999886e+02,0.000000000000000000e+00,9.341797756789400609e+00,0.000000000000000000e+00,-1.000000009925113620e+00,0.000000000000000000e+00,-6.504991604326172786e-10,0.000000000000000000e+00 +3.891453659506994711e+01,2.657099999999999795e+02,0.000000000000000000e+00,9.340727299008189988e+00,0.000000000000000000e+00,-1.000000009925809952e+00,0.000000000000000000e+00,4.083820404454013762e-10,0.000000000000000000e+00 +3.891560717551618609e+01,2.657200000000000273e+02,0.000000000000000000e+00,9.339656718551321291e+00,0.000000000000000000e+00,-1.000000009925372746e+00,0.000000000000000000e+00,-6.824942891004414667e-10,0.000000000000000000e+00 +3.891667787868026807e+01,2.657300000000000182e+02,0.000000000000000000e+00,9.338586015376611371e+00,0.000000000000000000e+00,-1.000000009926103495e+00,0.000000000000000000e+00,-8.062089313428503216e-10,0.000000000000000000e+00 +3.891774870460439928e+01,2.657400000000000091e+02,0.000000000000000000e+00,9.337515189441850438e+00,0.000000000000000000e+00,-1.000000009926966804e+00,0.000000000000000000e+00,1.602280916479661936e-09,0.000000000000000000e+00 +3.891881965333081439e+01,2.657500000000000000e+02,0.000000000000000000e+00,9.336444240704805608e+00,0.000000000000000000e+00,-1.000000009925250843e+00,0.000000000000000000e+00,-1.184988002830703917e-09,0.000000000000000000e+00 +3.891989072490176937e+01,2.657599999999999909e+02,0.000000000000000000e+00,9.335373169123222681e+00,0.000000000000000000e+00,-1.000000009926520050e+00,0.000000000000000000e+00,1.690632157988347714e-09,0.000000000000000000e+00 +3.892096191935954153e+01,2.657699999999999818e+02,0.000000000000000000e+00,9.334301974654817258e+00,0.000000000000000000e+00,-1.000000009924709055e+00,0.000000000000000000e+00,-2.140199177664517765e-09,0.000000000000000000e+00 +3.892203323674643656e+01,2.657800000000000296e+02,0.000000000000000000e+00,9.333230657257287177e+00,0.000000000000000000e+00,-1.000000009927001887e+00,0.000000000000000000e+00,1.270169984709077688e-09,0.000000000000000000e+00 +3.892310467710478861e+01,2.657900000000000205e+02,0.000000000000000000e+00,9.332159216888298303e+00,0.000000000000000000e+00,-1.000000009925640976e+00,0.000000000000000000e+00,-4.419907908475626473e-10,0.000000000000000000e+00 +3.892417624047695313e+01,2.658000000000000114e+02,0.000000000000000000e+00,9.331087653505500512e+00,0.000000000000000000e+00,-1.000000009926114597e+00,0.000000000000000000e+00,4.767482562221515121e-10,0.000000000000000000e+00 +3.892524792690529978e+01,2.658100000000000023e+02,0.000000000000000000e+00,9.330015967066513483e+00,0.000000000000000000e+00,-1.000000009925603672e+00,0.000000000000000000e+00,-5.968509242641722287e-10,0.000000000000000000e+00 +3.892631973643224086e+01,2.658199999999999932e+02,0.000000000000000000e+00,9.328944157528935577e+00,0.000000000000000000e+00,-1.000000009926243383e+00,0.000000000000000000e+00,-5.522463625056626812e-10,0.000000000000000000e+00 +3.892739166910019577e+01,2.658299999999999841e+02,0.000000000000000000e+00,9.327872224850338512e+00,0.000000000000000000e+00,-1.000000009926835354e+00,0.000000000000000000e+00,6.261248794042234010e-10,0.000000000000000000e+00 +3.892846372495161944e+01,2.658400000000000318e+02,0.000000000000000000e+00,9.326800168988270912e+00,0.000000000000000000e+00,-1.000000009926164113e+00,0.000000000000000000e+00,-1.358553472131941373e-10,0.000000000000000000e+00 +3.892953590402898811e+01,2.658500000000000227e+02,0.000000000000000000e+00,9.325727989900258308e+00,0.000000000000000000e+00,-1.000000009926309774e+00,0.000000000000000000e+00,-1.273911611618192272e-09,0.000000000000000000e+00 +3.893060820637479935e+01,2.658600000000000136e+02,0.000000000000000000e+00,9.324655687543799587e+00,0.000000000000000000e+00,-1.000000009927675793e+00,0.000000000000000000e+00,1.861577098842965818e-09,0.000000000000000000e+00 +3.893168063203158624e+01,2.658700000000000045e+02,0.000000000000000000e+00,9.323583261876368766e+00,0.000000000000000000e+00,-1.000000009925679390e+00,0.000000000000000000e+00,-1.523497977199377438e-09,0.000000000000000000e+00 +3.893275318104188898e+01,2.658799999999999955e+02,0.000000000000000000e+00,9.322510712855420323e+00,0.000000000000000000e+00,-1.000000009927313416e+00,0.000000000000000000e+00,9.428910163102085032e-10,0.000000000000000000e+00 +3.893382585344828328e+01,2.658899999999999864e+02,0.000000000000000000e+00,9.321438040438376760e+00,0.000000000000000000e+00,-1.000000009926302003e+00,0.000000000000000000e+00,1.241865016213378345e-11,0.000000000000000000e+00 +3.893489864929336619e+01,2.658999999999999773e+02,0.000000000000000000e+00,9.320365244582642816e+00,0.000000000000000000e+00,-1.000000009926288680e+00,0.000000000000000000e+00,3.348510572317379269e-10,0.000000000000000000e+00 +3.893597156861976316e+01,2.659100000000000250e+02,0.000000000000000000e+00,9.319292325245594810e+00,0.000000000000000000e+00,-1.000000009925929412e+00,0.000000000000000000e+00,-1.159221065938927278e-09,0.000000000000000000e+00 +3.893704461147012097e+01,2.659200000000000159e+02,0.000000000000000000e+00,9.318219282384585966e+00,0.000000000000000000e+00,-1.000000009927173306e+00,0.000000000000000000e+00,1.752494090330124200e-10,0.000000000000000000e+00 +3.893811777788710771e+01,2.659300000000000068e+02,0.000000000000000000e+00,9.317146115956942864e+00,0.000000000000000000e+00,-1.000000009926985234e+00,0.000000000000000000e+00,1.269842960999050529e-09,0.000000000000000000e+00 +3.893919106791342699e+01,2.659399999999999977e+02,0.000000000000000000e+00,9.316072825919970768e+00,0.000000000000000000e+00,-1.000000009925622324e+00,0.000000000000000000e+00,-2.482921027214088971e-09,0.000000000000000000e+00 +3.894026448159179665e+01,2.659499999999999886e+02,0.000000000000000000e+00,9.314999412230950071e+00,0.000000000000000000e+00,-1.000000009928287525e+00,0.000000000000000000e+00,1.267895708356186416e-09,0.000000000000000000e+00 +3.894133801896495584e+01,2.659599999999999795e+02,0.000000000000000000e+00,9.313925874847130970e+00,0.000000000000000000e+00,-1.000000009926926392e+00,0.000000000000000000e+00,2.061902670207913333e-10,0.000000000000000000e+00 +3.894241168007567921e+01,2.659700000000000273e+02,0.000000000000000000e+00,9.312852213725747674e+00,0.000000000000000000e+00,-1.000000009926705014e+00,0.000000000000000000e+00,5.159332133352232755e-10,0.000000000000000000e+00 +3.894348546496676278e+01,2.659800000000000182e+02,0.000000000000000000e+00,9.311778428824004195e+00,0.000000000000000000e+00,-1.000000009926151012e+00,0.000000000000000000e+00,-8.677843791499017759e-10,0.000000000000000000e+00 +3.894455937368102383e+01,2.659900000000000091e+02,0.000000000000000000e+00,9.310704520099081449e+00,0.000000000000000000e+00,-1.000000009927082933e+00,0.000000000000000000e+00,6.936099176109693202e-10,0.000000000000000000e+00 +3.894563340626130810e+01,2.660000000000000000e+02,0.000000000000000000e+00,9.309630487508133712e+00,0.000000000000000000e+00,-1.000000009926337974e+00,0.000000000000000000e+00,-9.432420159272061078e-10,0.000000000000000000e+00 +3.894670756275048262e+01,2.660099999999999909e+02,0.000000000000000000e+00,9.308556331008293938e+00,0.000000000000000000e+00,-1.000000009927351163e+00,0.000000000000000000e+00,3.982944651837568427e-10,0.000000000000000000e+00 +3.894778184319144287e+01,2.660199999999999818e+02,0.000000000000000000e+00,9.307482050556666664e+00,0.000000000000000000e+00,-1.000000009926923283e+00,0.000000000000000000e+00,-1.421459873001768144e-09,0.000000000000000000e+00 +3.894885624762710563e+01,2.660300000000000296e+02,0.000000000000000000e+00,9.306407646110335108e+00,0.000000000000000000e+00,-1.000000009928450506e+00,0.000000000000000000e+00,1.308055006529827229e-09,0.000000000000000000e+00 +3.894993077610041610e+01,2.660400000000000205e+02,0.000000000000000000e+00,9.305333117626354067e+00,0.000000000000000000e+00,-1.000000009927044964e+00,0.000000000000000000e+00,9.118136256721665474e-10,0.000000000000000000e+00 +3.895100542865434079e+01,2.660500000000000114e+02,0.000000000000000000e+00,9.304258465061758798e+00,0.000000000000000000e+00,-1.000000009926065081e+00,0.000000000000000000e+00,-1.053846397486957807e-09,0.000000000000000000e+00 +3.895208020533187465e+01,2.660600000000000023e+02,0.000000000000000000e+00,9.303183688373556137e+00,0.000000000000000000e+00,-1.000000009927197731e+00,0.000000000000000000e+00,4.296701232990195756e-11,0.000000000000000000e+00 +3.895315510617603394e+01,2.660699999999999932e+02,0.000000000000000000e+00,9.302108787518726274e+00,0.000000000000000000e+00,-1.000000009927151545e+00,0.000000000000000000e+00,-3.949203631167420688e-10,0.000000000000000000e+00 +3.895423013122986333e+01,2.660799999999999841e+02,0.000000000000000000e+00,9.301033762454228082e+00,0.000000000000000000e+00,-1.000000009927576095e+00,0.000000000000000000e+00,-8.114345118644430661e-10,0.000000000000000000e+00 +3.895530528053642172e+01,2.660900000000000318e+02,0.000000000000000000e+00,9.299958613136993790e+00,0.000000000000000000e+00,-1.000000009928448508e+00,0.000000000000000000e+00,1.882872138971494537e-09,0.000000000000000000e+00 +3.895638055413881062e+01,2.661000000000000227e+02,0.000000000000000000e+00,9.298883339523930758e+00,0.000000000000000000e+00,-1.000000009926423905e+00,0.000000000000000000e+00,-1.512235260984723902e-09,0.000000000000000000e+00 +3.895745595208013867e+01,2.661100000000000136e+02,0.000000000000000000e+00,9.297807941571925028e+00,0.000000000000000000e+00,-1.000000009928050160e+00,0.000000000000000000e+00,-2.256529203523286087e-10,0.000000000000000000e+00 +3.895853147440355713e+01,2.661200000000000045e+02,0.000000000000000000e+00,9.296732419237830669e+00,0.000000000000000000e+00,-1.000000009928292855e+00,0.000000000000000000e+00,1.150634843068580171e-09,0.000000000000000000e+00 +3.895960712115222435e+01,2.661299999999999955e+02,0.000000000000000000e+00,9.295656772478482210e+00,0.000000000000000000e+00,-1.000000009927055178e+00,0.000000000000000000e+00,-4.353082368603793093e-10,0.000000000000000000e+00 +3.896068289236934135e+01,2.661399999999999864e+02,0.000000000000000000e+00,9.294581001250689312e+00,0.000000000000000000e+00,-1.000000009927523470e+00,0.000000000000000000e+00,-3.607542618008486287e-10,0.000000000000000000e+00 +3.896175878809811621e+01,2.661499999999999773e+02,0.000000000000000000e+00,9.293505105511233211e+00,0.000000000000000000e+00,-1.000000009927911604e+00,0.000000000000000000e+00,1.391054336524782189e-09,0.000000000000000000e+00 +3.896283480838179258e+01,2.661600000000000250e+02,0.000000000000000000e+00,9.292429085216872053e+00,0.000000000000000000e+00,-1.000000009926414801e+00,0.000000000000000000e+00,-1.298662259116123268e-09,0.000000000000000000e+00 +3.896391095326364251e+01,2.661700000000000159e+02,0.000000000000000000e+00,9.291352940324340892e+00,0.000000000000000000e+00,-1.000000009927812350e+00,0.000000000000000000e+00,-7.425078159479192444e-10,0.000000000000000000e+00 +3.896498722278695226e+01,2.661800000000000068e+02,0.000000000000000000e+00,9.290276670790344582e+00,0.000000000000000000e+00,-1.000000009928611489e+00,0.000000000000000000e+00,1.541984720224883132e-09,0.000000000000000000e+00 +3.896606361699504362e+01,2.661899999999999977e+02,0.000000000000000000e+00,9.289200276571566661e+00,0.000000000000000000e+00,-1.000000009926951705e+00,0.000000000000000000e+00,-2.092318487479749173e-09,0.000000000000000000e+00 +3.896714013593125969e+01,2.661999999999999886e+02,0.000000000000000000e+00,9.288123757624667576e+00,0.000000000000000000e+00,-1.000000009929204126e+00,0.000000000000000000e+00,2.167146560985600058e-09,0.000000000000000000e+00 +3.896821677963895780e+01,2.662099999999999795e+02,0.000000000000000000e+00,9.287047113906275797e+00,0.000000000000000000e+00,-1.000000009926870881e+00,0.000000000000000000e+00,-9.873520130683933611e-10,0.000000000000000000e+00 +3.896929354816153790e+01,2.662200000000000273e+02,0.000000000000000000e+00,9.285970345373003809e+00,0.000000000000000000e+00,-1.000000009927934030e+00,0.000000000000000000e+00,-8.111513092034483137e-10,0.000000000000000000e+00 +3.897037044154242125e+01,2.662300000000000182e+02,0.000000000000000000e+00,9.284893451981430346e+00,0.000000000000000000e+00,-1.000000009928807554e+00,0.000000000000000000e+00,1.179269805036881773e-09,0.000000000000000000e+00 +3.897144745982504332e+01,2.662400000000000091e+02,0.000000000000000000e+00,9.283816433688112824e+00,0.000000000000000000e+00,-1.000000009927537459e+00,0.000000000000000000e+00,-1.123474636957060647e-09,0.000000000000000000e+00 +3.897252460305287514e+01,2.662500000000000000e+02,0.000000000000000000e+00,9.282739290449585567e+00,0.000000000000000000e+00,-1.000000009928747602e+00,0.000000000000000000e+00,1.485081759515544290e-09,0.000000000000000000e+00 +3.897360187126940900e+01,2.662599999999999909e+02,0.000000000000000000e+00,9.281662022222352704e+00,0.000000000000000000e+00,-1.000000009927147770e+00,0.000000000000000000e+00,-1.692652466822867906e-09,0.000000000000000000e+00 +3.897467926451816567e+01,2.662699999999999818e+02,0.000000000000000000e+00,9.280584628962898819e+00,0.000000000000000000e+00,-1.000000009928971423e+00,0.000000000000000000e+00,1.604670008109245698e-09,0.000000000000000000e+00 +3.897575678284268719e+01,2.662800000000000296e+02,0.000000000000000000e+00,9.279507110627676525e+00,0.000000000000000000e+00,-1.000000009927242361e+00,0.000000000000000000e+00,-8.474690448514817437e-10,0.000000000000000000e+00 +3.897683442628654404e+01,2.662900000000000205e+02,0.000000000000000000e+00,9.278429467173120671e+00,0.000000000000000000e+00,-1.000000009928155631e+00,0.000000000000000000e+00,1.493663273888337757e-10,0.000000000000000000e+00 +3.897791219489332804e+01,2.663000000000000114e+02,0.000000000000000000e+00,9.277351698555634130e+00,0.000000000000000000e+00,-1.000000009927994649e+00,0.000000000000000000e+00,-1.505643688942529080e-09,0.000000000000000000e+00 +3.897899008870665938e+01,2.663100000000000023e+02,0.000000000000000000e+00,9.276273804731598460e+00,0.000000000000000000e+00,-1.000000009929617573e+00,0.000000000000000000e+00,1.849858378484159144e-09,0.000000000000000000e+00 +3.898006810777018671e+01,2.663199999999999932e+02,0.000000000000000000e+00,9.275195785657366798e+00,0.000000000000000000e+00,-1.000000009927623390e+00,0.000000000000000000e+00,-4.679200321658591128e-10,0.000000000000000000e+00 +3.898114625212758000e+01,2.663299999999999841e+02,0.000000000000000000e+00,9.274117641289272740e+00,0.000000000000000000e+00,-1.000000009928127875e+00,0.000000000000000000e+00,-7.965247802778498121e-10,0.000000000000000000e+00 +3.898222452182253051e+01,2.663400000000000318e+02,0.000000000000000000e+00,9.273039371583617907e+00,0.000000000000000000e+00,-1.000000009928986744e+00,0.000000000000000000e+00,8.792051113073916722e-10,0.000000000000000000e+00 +3.898330291689875793e+01,2.663500000000000227e+02,0.000000000000000000e+00,9.271960976496680829e+00,0.000000000000000000e+00,-1.000000009928038613e+00,0.000000000000000000e+00,-5.558730062147585233e-12,0.000000000000000000e+00 +3.898438143740001749e+01,2.663600000000000136e+02,0.000000000000000000e+00,9.270882455984716941e+00,0.000000000000000000e+00,-1.000000009928044609e+00,0.000000000000000000e+00,-1.903540659997442221e-09,0.000000000000000000e+00 +3.898546008337007152e+01,2.663700000000000045e+02,0.000000000000000000e+00,9.269803810003953259e+00,0.000000000000000000e+00,-1.000000009930097855e+00,0.000000000000000000e+00,2.834292766346156576e-09,0.000000000000000000e+00 +3.898653885485272497e+01,2.663799999999999955e+02,0.000000000000000000e+00,9.268725038510590153e+00,0.000000000000000000e+00,-1.000000009927040301e+00,0.000000000000000000e+00,-2.563944091033330523e-09,0.000000000000000000e+00 +3.898761775189179701e+01,2.663899999999999864e+02,0.000000000000000000e+00,9.267646141460810227e+00,0.000000000000000000e+00,-1.000000009929806533e+00,0.000000000000000000e+00,1.759856922451349426e-09,0.000000000000000000e+00 +3.898869677453113525e+01,2.663999999999999773e+02,0.000000000000000000e+00,9.266567118810758785e+00,0.000000000000000000e+00,-1.000000009927907607e+00,0.000000000000000000e+00,-9.619239023193126176e-10,0.000000000000000000e+00 +3.898977592281461568e+01,2.664100000000000250e+02,0.000000000000000000e+00,9.265487970516566918e+00,0.000000000000000000e+00,-1.000000009928945666e+00,0.000000000000000000e+00,-3.086027423776471815e-11,0.000000000000000000e+00 +3.899085519678613565e+01,2.664200000000000159e+02,0.000000000000000000e+00,9.264408696534331966e+00,0.000000000000000000e+00,-1.000000009928978972e+00,0.000000000000000000e+00,-6.377047103546568902e-12,0.000000000000000000e+00 +3.899193459648962090e+01,2.664300000000000068e+02,0.000000000000000000e+00,9.263329296820129954e+00,0.000000000000000000e+00,-1.000000009928985856e+00,0.000000000000000000e+00,6.547024511811211452e-10,0.000000000000000000e+00 +3.899301412196901850e+01,2.664399999999999977e+02,0.000000000000000000e+00,9.262249771330010262e+00,0.000000000000000000e+00,-1.000000009928279088e+00,0.000000000000000000e+00,-1.077881141043692569e-09,0.000000000000000000e+00 +3.899409377326831105e+01,2.664499999999999886e+02,0.000000000000000000e+00,9.261170120019997398e+00,0.000000000000000000e+00,-1.000000009929442824e+00,0.000000000000000000e+00,9.097482014601358380e-10,0.000000000000000000e+00 +3.899517355043150246e+01,2.664599999999999795e+02,0.000000000000000000e+00,9.260090342846087452e+00,0.000000000000000000e+00,-1.000000009928460498e+00,0.000000000000000000e+00,-9.834580285657609928e-10,0.000000000000000000e+00 +3.899625345350261085e+01,2.664700000000000273e+02,0.000000000000000000e+00,9.259010439764255196e+00,0.000000000000000000e+00,-1.000000009929522538e+00,0.000000000000000000e+00,8.780805768767304404e-10,0.000000000000000000e+00 +3.899733348252569698e+01,2.664800000000000182e+02,0.000000000000000000e+00,9.257930410730445203e+00,0.000000000000000000e+00,-1.000000009928574185e+00,0.000000000000000000e+00,-1.103279967704435878e-09,0.000000000000000000e+00 +3.899841363754483581e+01,2.664900000000000091e+02,0.000000000000000000e+00,9.256850255700580732e+00,0.000000000000000000e+00,-1.000000009929765898e+00,0.000000000000000000e+00,7.039860278229445472e-10,0.000000000000000000e+00 +3.899949391860413783e+01,2.665000000000000000e+02,0.000000000000000000e+00,9.255769974630554842e+00,0.000000000000000000e+00,-1.000000009929005396e+00,0.000000000000000000e+00,2.279209910108833801e-10,0.000000000000000000e+00 +3.900057432574772776e+01,2.665099999999999909e+02,0.000000000000000000e+00,9.254689567476239276e+00,0.000000000000000000e+00,-1.000000009928759148e+00,0.000000000000000000e+00,5.314110756214586845e-10,0.000000000000000000e+00 +3.900165485901975870e+01,2.665199999999999818e+02,0.000000000000000000e+00,9.253609034193477356e+00,0.000000000000000000e+00,-1.000000009928184941e+00,0.000000000000000000e+00,-1.410150192208577565e-09,0.000000000000000000e+00 +3.900273551846441933e+01,2.665300000000000296e+02,0.000000000000000000e+00,9.252528374738087535e+00,0.000000000000000000e+00,-1.000000009929708833e+00,0.000000000000000000e+00,5.054006058514846664e-10,0.000000000000000000e+00 +3.900381630412591250e+01,2.665400000000000205e+02,0.000000000000000000e+00,9.251447589065859844e+00,0.000000000000000000e+00,-1.000000009929162603e+00,0.000000000000000000e+00,2.117915279670623688e-10,0.000000000000000000e+00 +3.900489721604847659e+01,2.665500000000000114e+02,0.000000000000000000e+00,9.250366677132562998e+00,0.000000000000000000e+00,-1.000000009928933675e+00,0.000000000000000000e+00,-7.507348122031024775e-10,0.000000000000000000e+00 +3.900597825427637133e+01,2.665600000000000023e+02,0.000000000000000000e+00,9.249285638893937289e+00,0.000000000000000000e+00,-1.000000009929745248e+00,0.000000000000000000e+00,6.752743071532676976e-10,0.000000000000000000e+00 +3.900705941885387773e+01,2.665699999999999932e+02,0.000000000000000000e+00,9.248204474305696365e+00,0.000000000000000000e+00,-1.000000009929015166e+00,0.000000000000000000e+00,-1.570527437422030538e-09,0.000000000000000000e+00 +3.900814070982530524e+01,2.665799999999999841e+02,0.000000000000000000e+00,9.247123183323530782e+00,0.000000000000000000e+00,-1.000000009930713363e+00,0.000000000000000000e+00,1.645698961868238216e-09,0.000000000000000000e+00 +3.900922212723499882e+01,2.665900000000000318e+02,0.000000000000000000e+00,9.246041765903100895e+00,0.000000000000000000e+00,-1.000000009928933675e+00,0.000000000000000000e+00,-2.915307841263016009e-10,0.000000000000000000e+00 +3.901030367112731057e+01,2.666000000000000227e+02,0.000000000000000000e+00,9.244960222000047523e+00,0.000000000000000000e+00,-1.000000009929248979e+00,0.000000000000000000e+00,2.305287145466750576e-10,0.000000000000000000e+00 +3.901138534154663517e+01,2.666100000000000136e+02,0.000000000000000000e+00,9.243878551569979507e+00,0.000000000000000000e+00,-1.000000009928999622e+00,0.000000000000000000e+00,-1.324717939162504111e-09,0.000000000000000000e+00 +3.901246713853738868e+01,2.666200000000000045e+02,0.000000000000000000e+00,9.242796754568482598e+00,0.000000000000000000e+00,-1.000000009930432698e+00,0.000000000000000000e+00,1.131645472989064912e-09,0.000000000000000000e+00 +3.901354906214401552e+01,2.666299999999999955e+02,0.000000000000000000e+00,9.241714830951114124e+00,0.000000000000000000e+00,-1.000000009929208344e+00,0.000000000000000000e+00,2.975505731779097062e-11,0.000000000000000000e+00 +3.901463111241097437e+01,2.666399999999999864e+02,0.000000000000000000e+00,9.240632780673410096e+00,0.000000000000000000e+00,-1.000000009929176148e+00,0.000000000000000000e+00,-1.576217845603203447e-09,0.000000000000000000e+00 +3.901571328938276650e+01,2.666499999999999773e+02,0.000000000000000000e+00,9.239550603690876329e+00,0.000000000000000000e+00,-1.000000009930881895e+00,0.000000000000000000e+00,2.397901154437031254e-09,0.000000000000000000e+00 +3.901679559310390033e+01,2.666600000000000250e+02,0.000000000000000000e+00,9.238468299958991992e+00,0.000000000000000000e+00,-1.000000009928286637e+00,0.000000000000000000e+00,-1.678211107013816488e-09,0.000000000000000000e+00 +3.901787802361892687e+01,2.666700000000000159e+02,0.000000000000000000e+00,9.237385869433216712e+00,0.000000000000000000e+00,-1.000000009930103184e+00,0.000000000000000000e+00,-1.384500394744896701e-10,0.000000000000000000e+00 +3.901896058097241848e+01,2.666800000000000068e+02,0.000000000000000000e+00,9.236303312068974591e+00,0.000000000000000000e+00,-1.000000009930253064e+00,0.000000000000000000e+00,9.690366986509136866e-10,0.000000000000000000e+00 +3.902004326520896882e+01,2.666899999999999977e+02,0.000000000000000000e+00,9.235220627821670192e+00,0.000000000000000000e+00,-1.000000009929203904e+00,0.000000000000000000e+00,-1.366745505314158228e-09,0.000000000000000000e+00 +3.902112607637320707e+01,2.666999999999999886e+02,0.000000000000000000e+00,9.234137816646681429e+00,0.000000000000000000e+00,-1.000000009930683831e+00,0.000000000000000000e+00,4.482153596538838901e-10,0.000000000000000000e+00 +3.902220901450977664e+01,2.667099999999999795e+02,0.000000000000000000e+00,9.233054878499356022e+00,0.000000000000000000e+00,-1.000000009930198441e+00,0.000000000000000000e+00,3.725122591332248113e-10,0.000000000000000000e+00 +3.902329207966335645e+01,2.667200000000000273e+02,0.000000000000000000e+00,9.231971813335020371e+00,0.000000000000000000e+00,-1.000000009929794986e+00,0.000000000000000000e+00,-6.108730411233578039e-11,0.000000000000000000e+00 +3.902437527187864674e+01,2.667300000000000182e+02,0.000000000000000000e+00,9.230888621108972458e+00,0.000000000000000000e+00,-1.000000009929861156e+00,0.000000000000000000e+00,6.802851467360299232e-10,0.000000000000000000e+00 +3.902545859120037619e+01,2.667400000000000091e+02,0.000000000000000000e+00,9.229805301776483617e+00,0.000000000000000000e+00,-1.000000009929124190e+00,0.000000000000000000e+00,-1.925847934920313066e-09,0.000000000000000000e+00 +3.902654203767330188e+01,2.667500000000000000e+02,0.000000000000000000e+00,9.228721855292800313e+00,0.000000000000000000e+00,-1.000000009931210743e+00,0.000000000000000000e+00,1.219061880711455384e-09,0.000000000000000000e+00 +3.902762561134220221e+01,2.667599999999999909e+02,0.000000000000000000e+00,9.227638281613138815e+00,0.000000000000000000e+00,-1.000000009929889799e+00,0.000000000000000000e+00,-4.589641944455420850e-10,0.000000000000000000e+00 +3.902870931225188400e+01,2.667699999999999818e+02,0.000000000000000000e+00,9.226554580692695851e+00,0.000000000000000000e+00,-1.000000009930387179e+00,0.000000000000000000e+00,6.230116973401697484e-10,0.000000000000000000e+00 +3.902979314044718251e+01,2.667800000000000296e+02,0.000000000000000000e+00,9.225470752486636172e+00,0.000000000000000000e+00,-1.000000009929711942e+00,0.000000000000000000e+00,-5.407950262395981577e-11,0.000000000000000000e+00 +3.903087709597295429e+01,2.667900000000000205e+02,0.000000000000000000e+00,9.224386796950101441e+00,0.000000000000000000e+00,-1.000000009929770561e+00,0.000000000000000000e+00,-9.585694506980874561e-10,0.000000000000000000e+00 +3.903196117887408434e+01,2.668000000000000114e+02,0.000000000000000000e+00,9.223302714038204897e+00,0.000000000000000000e+00,-1.000000009930809730e+00,0.000000000000000000e+00,9.494456639176609356e-10,0.000000000000000000e+00 +3.903304538919548605e+01,2.668100000000000023e+02,0.000000000000000000e+00,9.222218503706033133e+00,0.000000000000000000e+00,-1.000000009929780331e+00,0.000000000000000000e+00,-3.556931092094068659e-10,0.000000000000000000e+00 +3.903412972698210126e+01,2.668199999999999932e+02,0.000000000000000000e+00,9.221134165908649649e+00,0.000000000000000000e+00,-1.000000009930166023e+00,0.000000000000000000e+00,-3.226864874299912756e-10,0.000000000000000000e+00 +3.903521419227889311e+01,2.668299999999999841e+02,0.000000000000000000e+00,9.220049700601087750e+00,0.000000000000000000e+00,-1.000000009930515965e+00,0.000000000000000000e+00,-4.430275602396339206e-10,0.000000000000000000e+00 +3.903629878513085316e+01,2.668400000000000318e+02,0.000000000000000000e+00,9.218965107738355869e+00,0.000000000000000000e+00,-1.000000009930996470e+00,0.000000000000000000e+00,8.104157980589865555e-10,0.000000000000000000e+00 +3.903738350558300141e+01,2.668500000000000227e+02,0.000000000000000000e+00,9.217880387275435794e+00,0.000000000000000000e+00,-1.000000009930117395e+00,0.000000000000000000e+00,-1.072308360970630818e-09,0.000000000000000000e+00 +3.903846835368037915e+01,2.668600000000000136e+02,0.000000000000000000e+00,9.216795539167284446e+00,0.000000000000000000e+00,-1.000000009931280687e+00,0.000000000000000000e+00,1.474736525236318827e-09,0.000000000000000000e+00 +3.903955332946806323e+01,2.668700000000000045e+02,0.000000000000000000e+00,9.215710563368828545e+00,0.000000000000000000e+00,-1.000000009929680633e+00,0.000000000000000000e+00,-5.850368301068326724e-10,0.000000000000000000e+00 +3.904063843299114467e+01,2.668799999999999955e+02,0.000000000000000000e+00,9.214625459834973498e+00,0.000000000000000000e+00,-1.000000009930315459e+00,0.000000000000000000e+00,-1.196739248023320936e-09,0.000000000000000000e+00 +3.904172366429475005e+01,2.668899999999999864e+02,0.000000000000000000e+00,9.213540228520592734e+00,0.000000000000000000e+00,-1.000000009931614198e+00,0.000000000000000000e+00,1.165706469621560001e-09,0.000000000000000000e+00 +3.904280902342402726e+01,2.668999999999999773e+02,0.000000000000000000e+00,9.212454869380534817e+00,0.000000000000000000e+00,-1.000000009930348988e+00,0.000000000000000000e+00,4.872561798233573100e-10,0.000000000000000000e+00 +3.904389451042415971e+01,2.669100000000000250e+02,0.000000000000000000e+00,9.211369382369625214e+00,0.000000000000000000e+00,-1.000000009929820077e+00,0.000000000000000000e+00,-1.702741283709555119e-09,0.000000000000000000e+00 +3.904498012534034501e+01,2.669200000000000159e+02,0.000000000000000000e+00,9.210283767442659197e+00,0.000000000000000000e+00,-1.000000009931668599e+00,0.000000000000000000e+00,6.425684783662974415e-10,0.000000000000000000e+00 +3.904606586821781633e+01,2.669300000000000068e+02,0.000000000000000000e+00,9.209198024554403617e+00,0.000000000000000000e+00,-1.000000009930970934e+00,0.000000000000000000e+00,5.316617116300259148e-12,0.000000000000000000e+00 +3.904715173910183523e+01,2.669399999999999977e+02,0.000000000000000000e+00,9.208112153659604004e+00,0.000000000000000000e+00,-1.000000009930965161e+00,0.000000000000000000e+00,9.253912215948148736e-10,0.000000000000000000e+00 +3.904823773803767750e+01,2.669499999999999886e+02,0.000000000000000000e+00,9.207026154712975696e+00,0.000000000000000000e+00,-1.000000009929960187e+00,0.000000000000000000e+00,-1.096804765233441542e-09,0.000000000000000000e+00 +3.904932386507066155e+01,2.669599999999999795e+02,0.000000000000000000e+00,9.205940027669209158e+00,0.000000000000000000e+00,-1.000000009931151457e+00,0.000000000000000000e+00,-1.921481557422900565e-11,0.000000000000000000e+00 +3.905041012024612002e+01,2.669700000000000273e+02,0.000000000000000000e+00,9.204853772482964658e+00,0.000000000000000000e+00,-1.000000009931172329e+00,0.000000000000000000e+00,1.164607450379227556e-09,0.000000000000000000e+00 +3.905149650360941394e+01,2.669800000000000182e+02,0.000000000000000000e+00,9.203767389108879371e+00,0.000000000000000000e+00,-1.000000009929907119e+00,0.000000000000000000e+00,-2.040377058706589451e-09,0.000000000000000000e+00 +3.905258301520593989e+01,2.669900000000000091e+02,0.000000000000000000e+00,9.202680877501563828e+00,0.000000000000000000e+00,-1.000000009932124012e+00,0.000000000000000000e+00,9.181021539154016578e-10,0.000000000000000000e+00 +3.905366965508111576e+01,2.670000000000000000e+02,0.000000000000000000e+00,9.201594237615596583e+00,0.000000000000000000e+00,-1.000000009931126366e+00,0.000000000000000000e+00,1.029550519578869805e-09,0.000000000000000000e+00 +3.905475642328038077e+01,2.670099999999999909e+02,0.000000000000000000e+00,9.200507469405536654e+00,0.000000000000000000e+00,-1.000000009930007483e+00,0.000000000000000000e+00,-1.684390051553933255e-09,0.000000000000000000e+00 +3.905584331984920965e+01,2.670199999999999818e+02,0.000000000000000000e+00,9.199420572825912856e+00,0.000000000000000000e+00,-1.000000009931838241e+00,0.000000000000000000e+00,3.139601783093899058e-10,0.000000000000000000e+00 +3.905693034483310555e+01,2.670300000000000296e+02,0.000000000000000000e+00,9.198333547831223811e+00,0.000000000000000000e+00,-1.000000009931496958e+00,0.000000000000000000e+00,1.026939002246493983e-09,0.000000000000000000e+00 +3.905801749827758584e+01,2.670400000000000205e+02,0.000000000000000000e+00,9.197246394375946821e+00,0.000000000000000000e+00,-1.000000009930380518e+00,0.000000000000000000e+00,-1.027021847950596346e-09,0.000000000000000000e+00 +3.905910478022820342e+01,2.670500000000000114e+02,0.000000000000000000e+00,9.196159112414530767e+00,0.000000000000000000e+00,-1.000000009931497180e+00,0.000000000000000000e+00,1.815300232563048202e-10,0.000000000000000000e+00 +3.906019219073053961e+01,2.670600000000000023e+02,0.000000000000000000e+00,9.195071701901394334e+00,0.000000000000000000e+00,-1.000000009931299783e+00,0.000000000000000000e+00,1.631331134581518348e-10,0.000000000000000000e+00 +3.906127972983019703e+01,2.670699999999999932e+02,0.000000000000000000e+00,9.193984162790933112e+00,0.000000000000000000e+00,-1.000000009931122369e+00,0.000000000000000000e+00,4.389170349394900797e-10,0.000000000000000000e+00 +3.906236739757281384e+01,2.670799999999999841e+02,0.000000000000000000e+00,9.192896495037514271e+00,0.000000000000000000e+00,-1.000000009930644973e+00,0.000000000000000000e+00,-1.973668255728482716e-09,0.000000000000000000e+00 +3.906345519400404953e+01,2.670900000000000318e+02,0.000000000000000000e+00,9.191808698595478333e+00,0.000000000000000000e+00,-1.000000009932791922e+00,0.000000000000000000e+00,1.949555110436129706e-09,0.000000000000000000e+00 +3.906454311916958488e+01,2.671000000000000227e+02,0.000000000000000000e+00,9.190720773419135625e+00,0.000000000000000000e+00,-1.000000009930670952e+00,0.000000000000000000e+00,-1.279958376862673523e-09,0.000000000000000000e+00 +3.906563117311513622e+01,2.671100000000000136e+02,0.000000000000000000e+00,9.189632719462776933e+00,0.000000000000000000e+00,-1.000000009932063616e+00,0.000000000000000000e+00,3.621902350713674680e-10,0.000000000000000000e+00 +3.906671935588644828e+01,2.671200000000000045e+02,0.000000000000000000e+00,9.188544536680657515e+00,0.000000000000000000e+00,-1.000000009931669487e+00,0.000000000000000000e+00,8.928207260730971153e-10,0.000000000000000000e+00 +3.906780766752928713e+01,2.671299999999999955e+02,0.000000000000000000e+00,9.187456225027011314e+00,0.000000000000000000e+00,-1.000000009930697820e+00,0.000000000000000000e+00,-1.168526370264426954e-09,0.000000000000000000e+00 +3.906889610808944724e+01,2.671399999999999864e+02,0.000000000000000000e+00,9.186367784456043850e+00,0.000000000000000000e+00,-1.000000009931969691e+00,0.000000000000000000e+00,1.962271635990545404e-10,0.000000000000000000e+00 +3.906998467761275151e+01,2.671499999999999773e+02,0.000000000000000000e+00,9.185279214921930446e+00,0.000000000000000000e+00,-1.000000009931756084e+00,0.000000000000000000e+00,5.070300652286956239e-10,0.000000000000000000e+00 +3.907107337614504416e+01,2.671600000000000250e+02,0.000000000000000000e+00,9.184190516378823332e+00,0.000000000000000000e+00,-1.000000009931204081e+00,0.000000000000000000e+00,-2.165736551961019614e-10,0.000000000000000000e+00 +3.907216220373220494e+01,2.671700000000000159e+02,0.000000000000000000e+00,9.183101688780846317e+00,0.000000000000000000e+00,-1.000000009931439893e+00,0.000000000000000000e+00,-4.561373163137261507e-10,0.000000000000000000e+00 +3.907325116042014201e+01,2.671800000000000068e+02,0.000000000000000000e+00,9.182012732082094786e+00,0.000000000000000000e+00,-1.000000009931936606e+00,0.000000000000000000e+00,-1.934836753646675318e-10,0.000000000000000000e+00 +3.907434024625478486e+01,2.671899999999999977e+02,0.000000000000000000e+00,9.180923646236637481e+00,0.000000000000000000e+00,-1.000000009932147327e+00,0.000000000000000000e+00,5.901673362419548814e-10,0.000000000000000000e+00 +3.907542946128208428e+01,2.671999999999999886e+02,0.000000000000000000e+00,9.179834431198516498e+00,0.000000000000000000e+00,-1.000000009931504508e+00,0.000000000000000000e+00,4.162275392906559915e-10,0.000000000000000000e+00 +3.907651880554803370e+01,2.672099999999999795e+02,0.000000000000000000e+00,9.178745086921747287e+00,0.000000000000000000e+00,-1.000000009931051093e+00,0.000000000000000000e+00,-6.943775445998311728e-10,0.000000000000000000e+00 +3.907760827909864787e+01,2.672200000000000273e+02,0.000000000000000000e+00,9.177655613360316877e+00,0.000000000000000000e+00,-1.000000009931807599e+00,0.000000000000000000e+00,-1.226377476930604270e-09,0.000000000000000000e+00 +3.907869788197995575e+01,2.672300000000000182e+02,0.000000000000000000e+00,9.176566010468183876e+00,0.000000000000000000e+00,-1.000000009933143863e+00,0.000000000000000000e+00,1.830178584372737553e-09,0.000000000000000000e+00 +3.907978761423803604e+01,2.672400000000000091e+02,0.000000000000000000e+00,9.175476278199280245e+00,0.000000000000000000e+00,-1.000000009931149458e+00,0.000000000000000000e+00,-4.804106682242159868e-10,0.000000000000000000e+00 +3.908087747591897454e+01,2.672500000000000000e+02,0.000000000000000000e+00,9.174386416507514852e+00,0.000000000000000000e+00,-1.000000009931673040e+00,0.000000000000000000e+00,-6.594167174575021399e-10,0.000000000000000000e+00 +3.908196746706889968e+01,2.672599999999999909e+02,0.000000000000000000e+00,9.173296425346762817e+00,0.000000000000000000e+00,-1.000000009932391798e+00,0.000000000000000000e+00,-1.843377287466823038e-10,0.000000000000000000e+00 +3.908305758773396121e+01,2.672699999999999818e+02,0.000000000000000000e+00,9.172206304670874388e+00,0.000000000000000000e+00,-1.000000009932592748e+00,0.000000000000000000e+00,9.635338755175727778e-10,0.000000000000000000e+00 +3.908414783796033021e+01,2.672800000000000296e+02,0.000000000000000000e+00,9.171116054433673170e+00,0.000000000000000000e+00,-1.000000009931542255e+00,0.000000000000000000e+00,-1.849048331653729926e-10,0.000000000000000000e+00 +3.908523821779422036e+01,2.672900000000000205e+02,0.000000000000000000e+00,9.170025674588956122e+00,0.000000000000000000e+00,-1.000000009931743872e+00,0.000000000000000000e+00,-6.212308075330887374e-10,0.000000000000000000e+00 +3.908632872728185248e+01,2.673000000000000114e+02,0.000000000000000000e+00,9.168935165090490003e+00,0.000000000000000000e+00,-1.000000009932421330e+00,0.000000000000000000e+00,-3.271711526209401476e-10,0.000000000000000000e+00 +3.908741936646949711e+01,2.673100000000000023e+02,0.000000000000000000e+00,9.167844525892014929e+00,0.000000000000000000e+00,-1.000000009932778156e+00,0.000000000000000000e+00,7.161488522664095298e-10,0.000000000000000000e+00 +3.908851013540343189e+01,2.673199999999999932e+02,0.000000000000000000e+00,9.166753756947244369e+00,0.000000000000000000e+00,-1.000000009931997003e+00,0.000000000000000000e+00,-4.577678058697987211e-10,0.000000000000000000e+00 +3.908960103412997711e+01,2.673299999999999841e+02,0.000000000000000000e+00,9.165662858209865149e+00,0.000000000000000000e+00,-1.000000009932496381e+00,0.000000000000000000e+00,6.486137744480222331e-10,0.000000000000000000e+00 +3.909069206269547436e+01,2.673400000000000318e+02,0.000000000000000000e+00,9.164571829633533895e+00,0.000000000000000000e+00,-1.000000009931788725e+00,0.000000000000000000e+00,-4.220473298546234750e-10,0.000000000000000000e+00 +3.909178322114628656e+01,2.673500000000000227e+02,0.000000000000000000e+00,9.163480671171882364e+00,0.000000000000000000e+00,-1.000000009932249245e+00,0.000000000000000000e+00,-6.665681935027275370e-10,0.000000000000000000e+00 +3.909287450952881926e+01,2.673600000000000136e+02,0.000000000000000000e+00,9.162389382778512115e+00,0.000000000000000000e+00,-1.000000009932976663e+00,0.000000000000000000e+00,1.425138621033183489e-09,0.000000000000000000e+00 +3.909396592788949221e+01,2.673700000000000045e+02,0.000000000000000000e+00,9.161297964406998062e+00,0.000000000000000000e+00,-1.000000009931421241e+00,0.000000000000000000e+00,-1.583027503726858415e-09,0.000000000000000000e+00 +3.909505747627476069e+01,2.673799999999999955e+02,0.000000000000000000e+00,9.160206416010890251e+00,0.000000000000000000e+00,-1.000000009933149192e+00,0.000000000000000000e+00,7.649777773592205330e-10,0.000000000000000000e+00 +3.909614915473110131e+01,2.673899999999999864e+02,0.000000000000000000e+00,9.159114737543704976e+00,0.000000000000000000e+00,-1.000000009932314082e+00,0.000000000000000000e+00,-4.559627173955191301e-10,0.000000000000000000e+00 +3.909724096330502618e+01,2.673999999999999773e+02,0.000000000000000000e+00,9.158022928958937214e+00,0.000000000000000000e+00,-1.000000009932811906e+00,0.000000000000000000e+00,7.351064843105560377e-10,0.000000000000000000e+00 +3.909833290204306877e+01,2.674100000000000250e+02,0.000000000000000000e+00,9.156930990210049970e+00,0.000000000000000000e+00,-1.000000009932009215e+00,0.000000000000000000e+00,-1.126418906722019177e-10,0.000000000000000000e+00 +3.909942497099179093e+01,2.674200000000000159e+02,0.000000000000000000e+00,9.155838921250481377e+00,0.000000000000000000e+00,-1.000000009932132228e+00,0.000000000000000000e+00,-1.487956093107640275e-09,0.000000000000000000e+00 +3.910051717019778295e+01,2.674300000000000068e+02,0.000000000000000000e+00,9.154746722033639372e+00,0.000000000000000000e+00,-1.000000009933757372e+00,0.000000000000000000e+00,1.093626020066484362e-09,0.000000000000000000e+00 +3.910160949970767064e+01,2.674399999999999977e+02,0.000000000000000000e+00,9.153654392512903470e+00,0.000000000000000000e+00,-1.000000009932562772e+00,0.000000000000000000e+00,2.075202484243126984e-10,0.000000000000000000e+00 +3.910270195956809403e+01,2.674499999999999886e+02,0.000000000000000000e+00,9.152561932641630094e+00,0.000000000000000000e+00,-1.000000009932336065e+00,0.000000000000000000e+00,3.395934864301822275e-10,0.000000000000000000e+00 +3.910379454982572867e+01,2.674599999999999795e+02,0.000000000000000000e+00,9.151469342373143689e+00,0.000000000000000000e+00,-1.000000009931965028e+00,0.000000000000000000e+00,-1.466316019151139409e-09,0.000000000000000000e+00 +3.910488727052727853e+01,2.674700000000000273e+02,0.000000000000000000e+00,9.150376621660742060e+00,0.000000000000000000e+00,-1.000000009933567302e+00,0.000000000000000000e+00,7.598901189400913633e-10,0.000000000000000000e+00 +3.910598012171946891e+01,2.674800000000000182e+02,0.000000000000000000e+00,9.149283770457692810e+00,0.000000000000000000e+00,-1.000000009932736855e+00,0.000000000000000000e+00,-4.008246374612284907e-10,0.000000000000000000e+00 +3.910707310344906773e+01,2.674900000000000091e+02,0.000000000000000000e+00,9.148190788717240451e+00,0.000000000000000000e+00,-1.000000009933174949e+00,0.000000000000000000e+00,1.021137732035305889e-09,0.000000000000000000e+00 +3.910816621576285002e+01,2.675000000000000000e+02,0.000000000000000000e+00,9.147097676392597521e+00,0.000000000000000000e+00,-1.000000009932058731e+00,0.000000000000000000e+00,-9.024015973627077039e-10,0.000000000000000000e+00 +3.910925945870764053e+01,2.675099999999999909e+02,0.000000000000000000e+00,9.146004433436951686e+00,0.000000000000000000e+00,-1.000000009933045275e+00,0.000000000000000000e+00,-2.051129150475743744e-10,0.000000000000000000e+00 +3.911035283233027116e+01,2.675199999999999818e+02,0.000000000000000000e+00,9.144911059803458642e+00,0.000000000000000000e+00,-1.000000009933269540e+00,0.000000000000000000e+00,1.594003858228657503e-10,0.000000000000000000e+00 +3.911144633667761639e+01,2.675300000000000296e+02,0.000000000000000000e+00,9.143817555445249212e+00,0.000000000000000000e+00,-1.000000009933095235e+00,0.000000000000000000e+00,2.101397094086594997e-10,0.000000000000000000e+00 +3.911253997179657915e+01,2.675400000000000205e+02,0.000000000000000000e+00,9.142723920315425801e+00,0.000000000000000000e+00,-1.000000009932865419e+00,0.000000000000000000e+00,-3.207546182903613790e-11,0.000000000000000000e+00 +3.911363373773407659e+01,2.675500000000000114e+02,0.000000000000000000e+00,9.141630154367062389e+00,0.000000000000000000e+00,-1.000000009932900502e+00,0.000000000000000000e+00,-5.470444822912420165e-10,0.000000000000000000e+00 +3.911472763453706847e+01,2.675600000000000023e+02,0.000000000000000000e+00,9.140536257553204535e+00,0.000000000000000000e+00,-1.000000009933498912e+00,0.000000000000000000e+00,1.680514399028177373e-10,0.000000000000000000e+00 +3.911582166225253587e+01,2.675699999999999932e+02,0.000000000000000000e+00,9.139442229826869379e+00,0.000000000000000000e+00,-1.000000009933315059e+00,0.000000000000000000e+00,6.487876193785102922e-10,0.000000000000000000e+00 +3.911691582092748831e+01,2.675799999999999841e+02,0.000000000000000000e+00,9.138348071141047413e+00,0.000000000000000000e+00,-1.000000009932605183e+00,0.000000000000000000e+00,-5.681538483947020980e-10,0.000000000000000000e+00 +3.911801011060896371e+01,2.675900000000000318e+02,0.000000000000000000e+00,9.137253781448700707e+00,0.000000000000000000e+00,-1.000000009933226908e+00,0.000000000000000000e+00,-4.956548724361726572e-10,0.000000000000000000e+00 +3.911910453134403554e+01,2.676000000000000227e+02,0.000000000000000000e+00,9.136159360702761134e+00,0.000000000000000000e+00,-1.000000009933769363e+00,0.000000000000000000e+00,8.842819510702278576e-10,0.000000000000000000e+00 +3.912019908317979144e+01,2.676100000000000136e+02,0.000000000000000000e+00,9.135064808856133922e+00,0.000000000000000000e+00,-1.000000009932801470e+00,0.000000000000000000e+00,-8.559813634206410568e-10,0.000000000000000000e+00 +3.912129376616335463e+01,2.676200000000000045e+02,0.000000000000000000e+00,9.133970125861697653e+00,0.000000000000000000e+00,-1.000000009933738498e+00,0.000000000000000000e+00,2.340483701345074887e-10,0.000000000000000000e+00 +3.912238858034187672e+01,2.676299999999999955e+02,0.000000000000000000e+00,9.132875311672298935e+00,0.000000000000000000e+00,-1.000000009933482259e+00,0.000000000000000000e+00,1.207415048070023257e-09,0.000000000000000000e+00 +3.912348352576253774e+01,2.676399999999999864e+02,0.000000000000000000e+00,9.131780366240759506e+00,0.000000000000000000e+00,-1.000000009932160205e+00,0.000000000000000000e+00,-2.358171561564593368e-09,0.000000000000000000e+00 +3.912457860247254615e+01,2.676499999999999773e+02,0.000000000000000000e+00,9.130685289519872683e+00,0.000000000000000000e+00,-1.000000009934742584e+00,0.000000000000000000e+00,1.407029069017527439e-09,0.000000000000000000e+00 +3.912567381051913884e+01,2.676600000000000250e+02,0.000000000000000000e+00,9.129590081462398032e+00,0.000000000000000000e+00,-1.000000009933201595e+00,0.000000000000000000e+00,6.720089178468635332e-10,0.000000000000000000e+00 +3.912676914994958111e+01,2.676700000000000159e+02,0.000000000000000000e+00,9.128494742021075581e+00,0.000000000000000000e+00,-1.000000009932465517e+00,0.000000000000000000e+00,-1.578170040458817143e-09,0.000000000000000000e+00 +3.912786462081116667e+01,2.676800000000000068e+02,0.000000000000000000e+00,9.127399271148611604e+00,0.000000000000000000e+00,-1.000000009934194356e+00,0.000000000000000000e+00,5.964547978851788877e-10,0.000000000000000000e+00 +3.912896022315121058e+01,2.676899999999999977e+02,0.000000000000000000e+00,9.126303668797682178e+00,0.000000000000000000e+00,-1.000000009933540879e+00,0.000000000000000000e+00,-1.852172094203537154e-10,0.000000000000000000e+00 +3.913005595701707051e+01,2.676999999999999886e+02,0.000000000000000000e+00,9.125207934920940289e+00,0.000000000000000000e+00,-1.000000009933743828e+00,0.000000000000000000e+00,5.361333642772871143e-10,0.000000000000000000e+00 +3.913115182245611834e+01,2.677099999999999795e+02,0.000000000000000000e+00,9.124112069471006947e+00,0.000000000000000000e+00,-1.000000009933156297e+00,0.000000000000000000e+00,-1.778792756866996879e-10,0.000000000000000000e+00 +3.913224781951576148e+01,2.677200000000000273e+02,0.000000000000000000e+00,9.123016072400476517e+00,0.000000000000000000e+00,-1.000000009933351253e+00,0.000000000000000000e+00,-8.277077617042294400e-10,0.000000000000000000e+00 +3.913334394824343576e+01,2.677300000000000182e+02,0.000000000000000000e+00,9.121919943661913166e+00,0.000000000000000000e+00,-1.000000009934258527e+00,0.000000000000000000e+00,8.425968137800400603e-11,0.000000000000000000e+00 +3.913444020868660544e+01,2.677400000000000091e+02,0.000000000000000000e+00,9.120823683207852639e+00,0.000000000000000000e+00,-1.000000009934166156e+00,0.000000000000000000e+00,1.099092153484116213e-09,0.000000000000000000e+00 +3.913553660089276320e+01,2.677500000000000000e+02,0.000000000000000000e+00,9.119727290990804036e+00,0.000000000000000000e+00,-1.000000009932961120e+00,0.000000000000000000e+00,-7.178576232683120787e-10,0.000000000000000000e+00 +3.913663312490943014e+01,2.677599999999999909e+02,0.000000000000000000e+00,9.118630766963248035e+00,0.000000000000000000e+00,-1.000000009933748268e+00,0.000000000000000000e+00,-9.131589875145228784e-10,0.000000000000000000e+00 +3.913772978078414866e+01,2.677699999999999818e+02,0.000000000000000000e+00,9.117534111077633341e+00,0.000000000000000000e+00,-1.000000009934749690e+00,0.000000000000000000e+00,5.314310556409914998e-10,0.000000000000000000e+00 +3.913882656856450382e+01,2.677800000000000296e+02,0.000000000000000000e+00,9.116437323286382011e+00,0.000000000000000000e+00,-1.000000009934166822e+00,0.000000000000000000e+00,6.821741789114788501e-10,0.000000000000000000e+00 +3.913992348829810197e+01,2.677900000000000205e+02,0.000000000000000000e+00,9.115340403541889458e+00,0.000000000000000000e+00,-1.000000009933418532e+00,0.000000000000000000e+00,-4.396154408613069640e-10,0.000000000000000000e+00 +3.914102054003257081e+01,2.678000000000000114e+02,0.000000000000000000e+00,9.114243351796520898e+00,0.000000000000000000e+00,-1.000000009933900813e+00,0.000000000000000000e+00,1.384257697940332244e-10,0.000000000000000000e+00 +3.914211772381558063e+01,2.678100000000000023e+02,0.000000000000000000e+00,9.113146168002611347e+00,0.000000000000000000e+00,-1.000000009933748935e+00,0.000000000000000000e+00,-5.157965073329919455e-10,0.000000000000000000e+00 +3.914321503969482308e+01,2.678199999999999932e+02,0.000000000000000000e+00,9.112048852112469177e+00,0.000000000000000000e+00,-1.000000009934314926e+00,0.000000000000000000e+00,5.685420417663963996e-10,0.000000000000000000e+00 +3.914431248771801819e+01,2.678299999999999841e+02,0.000000000000000000e+00,9.110951404078372562e+00,0.000000000000000000e+00,-1.000000009933690981e+00,0.000000000000000000e+00,-1.012934928828377633e-09,0.000000000000000000e+00 +3.914541006793291444e+01,2.678400000000000318e+02,0.000000000000000000e+00,9.109853823852573029e+00,0.000000000000000000e+00,-1.000000009934802758e+00,0.000000000000000000e+00,6.582171328609891918e-10,0.000000000000000000e+00 +3.914650778038728873e+01,2.678500000000000227e+02,0.000000000000000000e+00,9.108756111387290133e+00,0.000000000000000000e+00,-1.000000009934080225e+00,0.000000000000000000e+00,1.178135463604922663e-09,0.000000000000000000e+00 +3.914760562512895348e+01,2.678600000000000136e+02,0.000000000000000000e+00,9.107658266634718558e+00,0.000000000000000000e+00,-1.000000009932786815e+00,0.000000000000000000e+00,-2.378434535408112369e-09,0.000000000000000000e+00 +3.914870360220574241e+01,2.678700000000000045e+02,0.000000000000000000e+00,9.106560289547022791e+00,0.000000000000000000e+00,-1.000000009935398282e+00,0.000000000000000000e+00,1.795995985082324948e-09,0.000000000000000000e+00 +3.914980171166552481e+01,2.678799999999999955e+02,0.000000000000000000e+00,9.105462180076333567e+00,0.000000000000000000e+00,-1.000000009933426082e+00,0.000000000000000000e+00,-1.011515921843162160e-09,0.000000000000000000e+00 +3.915089995355618413e+01,2.678899999999999864e+02,0.000000000000000000e+00,9.104363938174762083e+00,0.000000000000000000e+00,-1.000000009934536971e+00,0.000000000000000000e+00,-4.686010603702571903e-10,0.000000000000000000e+00 +3.915199832792565360e+01,2.678999999999999773e+02,0.000000000000000000e+00,9.103265563794382231e+00,0.000000000000000000e+00,-1.000000009935051670e+00,0.000000000000000000e+00,1.970191331197664601e-09,0.000000000000000000e+00 +3.915309683482188063e+01,2.679100000000000250e+02,0.000000000000000000e+00,9.102167056887243035e+00,0.000000000000000000e+00,-1.000000009932887401e+00,0.000000000000000000e+00,-2.506350097962932668e-09,0.000000000000000000e+00 +3.915419547429284108e+01,2.679200000000000159e+02,0.000000000000000000e+00,9.101068417405366873e+00,0.000000000000000000e+00,-1.000000009935640977e+00,0.000000000000000000e+00,2.312450806404733812e-09,0.000000000000000000e+00 +3.915529424638655343e+01,2.679300000000000068e+02,0.000000000000000000e+00,9.099969645300738819e+00,0.000000000000000000e+00,-1.000000009933100120e+00,0.000000000000000000e+00,-1.212965678581764086e-09,0.000000000000000000e+00 +3.915639315115105035e+01,2.679399999999999977e+02,0.000000000000000000e+00,9.098870740525326184e+00,0.000000000000000000e+00,-1.000000009934433054e+00,0.000000000000000000e+00,-1.289592697890044157e-09,0.000000000000000000e+00 +3.915749218863440007e+01,2.679499999999999886e+02,0.000000000000000000e+00,9.097771703031057200e+00,0.000000000000000000e+00,-1.000000009935850365e+00,0.000000000000000000e+00,2.098491435089369566e-09,0.000000000000000000e+00 +3.915859135888469922e+01,2.679599999999999795e+02,0.000000000000000000e+00,9.096672532769835229e+00,0.000000000000000000e+00,-1.000000009933543765e+00,0.000000000000000000e+00,-1.318771202606466952e-09,0.000000000000000000e+00 +3.915969066195007287e+01,2.679700000000000273e+02,0.000000000000000000e+00,9.095573229693538764e+00,0.000000000000000000e+00,-1.000000009934993495e+00,0.000000000000000000e+00,2.399312081652543414e-10,0.000000000000000000e+00 +3.916079009787868159e+01,2.679800000000000182e+02,0.000000000000000000e+00,9.094473793754008994e+00,0.000000000000000000e+00,-1.000000009934729706e+00,0.000000000000000000e+00,9.143747389943202618e-10,0.000000000000000000e+00 +3.916188966671870020e+01,2.679900000000000091e+02,0.000000000000000000e+00,9.093374224903064018e+00,0.000000000000000000e+00,-1.000000009933724288e+00,0.000000000000000000e+00,-7.434453918285361911e-10,0.000000000000000000e+00 +3.916298936851834611e+01,2.680000000000000000e+02,0.000000000000000000e+00,9.092274523092491734e+00,0.000000000000000000e+00,-1.000000009934541856e+00,0.000000000000000000e+00,-3.050543552072849566e-10,0.000000000000000000e+00 +3.916408920332586518e+01,2.680099999999999909e+02,0.000000000000000000e+00,9.091174688274048066e+00,0.000000000000000000e+00,-1.000000009934877365e+00,0.000000000000000000e+00,-6.887621148175215991e-10,0.000000000000000000e+00 +3.916518917118952459e+01,2.680199999999999818e+02,0.000000000000000000e+00,9.090074720399462294e+00,0.000000000000000000e+00,-1.000000009935634981e+00,0.000000000000000000e+00,1.062486839135851346e-09,0.000000000000000000e+00 +3.916628927215761991e+01,2.680300000000000296e+02,0.000000000000000000e+00,9.088974619420433498e+00,0.000000000000000000e+00,-1.000000009934466139e+00,0.000000000000000000e+00,5.646805464362885046e-10,0.000000000000000000e+00 +3.916738950627848936e+01,2.680400000000000205e+02,0.000000000000000000e+00,9.087874385288634116e+00,0.000000000000000000e+00,-1.000000009933844858e+00,0.000000000000000000e+00,-6.919425314312271777e-10,0.000000000000000000e+00 +3.916848987360048540e+01,2.680500000000000114e+02,0.000000000000000000e+00,9.086774017955704608e+00,0.000000000000000000e+00,-1.000000009934606249e+00,0.000000000000000000e+00,-1.219882766191564366e-09,0.000000000000000000e+00 +3.916959037417200307e+01,2.680600000000000023e+02,0.000000000000000000e+00,9.085673517373255237e+00,0.000000000000000000e+00,-1.000000009935948730e+00,0.000000000000000000e+00,1.932894688082623813e-09,0.000000000000000000e+00 +3.917069100804145165e+01,2.680699999999999932e+02,0.000000000000000000e+00,9.084572883492867845e+00,0.000000000000000000e+00,-1.000000009933821321e+00,0.000000000000000000e+00,-1.477382922636700138e-09,0.000000000000000000e+00 +3.917179177525728306e+01,2.680799999999999841e+02,0.000000000000000000e+00,9.083472116266099405e+00,0.000000000000000000e+00,-1.000000009935447576e+00,0.000000000000000000e+00,3.001200734376920003e-10,0.000000000000000000e+00 +3.917289267586797763e+01,2.680900000000000318e+02,0.000000000000000000e+00,9.082371215644469586e+00,0.000000000000000000e+00,-1.000000009935117173e+00,0.000000000000000000e+00,-4.497222108243363085e-11,0.000000000000000000e+00 +3.917399370992202989e+01,2.681000000000000227e+02,0.000000000000000000e+00,9.081270181579474965e+00,0.000000000000000000e+00,-1.000000009935166689e+00,0.000000000000000000e+00,4.399887462415467012e-10,0.000000000000000000e+00 +3.917509487746798413e+01,2.681100000000000136e+02,0.000000000000000000e+00,9.080169014022580143e+00,0.000000000000000000e+00,-1.000000009934682188e+00,0.000000000000000000e+00,3.098903306087464841e-10,0.000000000000000000e+00 +3.917619617855439884e+01,2.681200000000000045e+02,0.000000000000000000e+00,9.079067712925221301e+00,0.000000000000000000e+00,-1.000000009934340905e+00,0.000000000000000000e+00,-1.878066475971248615e-09,0.000000000000000000e+00 +3.917729761322987514e+01,2.681299999999999955e+02,0.000000000000000000e+00,9.077966278238804421e+00,0.000000000000000000e+00,-1.000000009936409473e+00,0.000000000000000000e+00,1.217894057894827110e-09,0.000000000000000000e+00 +3.917839918154302836e+01,2.681399999999999864e+02,0.000000000000000000e+00,9.076864709914703511e+00,0.000000000000000000e+00,-1.000000009935067879e+00,0.000000000000000000e+00,8.325901771723573070e-10,0.000000000000000000e+00 +3.917950088354251648e+01,2.681499999999999773e+02,0.000000000000000000e+00,9.075763007904269486e+00,0.000000000000000000e+00,-1.000000009934150613e+00,0.000000000000000000e+00,-1.547087627155742431e-09,0.000000000000000000e+00 +3.918060271927701876e+01,2.681600000000000250e+02,0.000000000000000000e+00,9.074661172158819511e+00,0.000000000000000000e+00,-1.000000009935855250e+00,0.000000000000000000e+00,1.415321639291889860e-09,0.000000000000000000e+00 +3.918170468879525004e+01,2.681700000000000159e+02,0.000000000000000000e+00,9.073559202629638776e+00,0.000000000000000000e+00,-1.000000009934295608e+00,0.000000000000000000e+00,-1.963359129267279880e-09,0.000000000000000000e+00 +3.918280679214595352e+01,2.681800000000000068e+02,0.000000000000000000e+00,9.072457099267989378e+00,0.000000000000000000e+00,-1.000000009936459433e+00,0.000000000000000000e+00,1.501198061498622129e-09,0.000000000000000000e+00 +3.918390902937789377e+01,2.681899999999999977e+02,0.000000000000000000e+00,9.071354862025096111e+00,0.000000000000000000e+00,-1.000000009934804757e+00,0.000000000000000000e+00,1.303216777988111359e-10,0.000000000000000000e+00 +3.918501140053987797e+01,2.681999999999999886e+02,0.000000000000000000e+00,9.070252490852162452e+00,0.000000000000000000e+00,-1.000000009934661094e+00,0.000000000000000000e+00,-1.666585522071032190e-09,0.000000000000000000e+00 +3.918611390568073460e+01,2.682099999999999795e+02,0.000000000000000000e+00,9.069149985700356353e+00,0.000000000000000000e+00,-1.000000009936498513e+00,0.000000000000000000e+00,1.974890338146981689e-09,0.000000000000000000e+00 +3.918721654484932060e+01,2.682200000000000273e+02,0.000000000000000000e+00,9.068047346520815566e+00,0.000000000000000000e+00,-1.000000009934320921e+00,0.000000000000000000e+00,-2.073916320214683928e-09,0.000000000000000000e+00 +3.918831931809452840e+01,2.682300000000000182e+02,0.000000000000000000e+00,9.066944573264654750e+00,0.000000000000000000e+00,-1.000000009936607981e+00,0.000000000000000000e+00,2.276400008269862372e-09,0.000000000000000000e+00 +3.918942222546527177e+01,2.682400000000000091e+02,0.000000000000000000e+00,9.065841665882949485e+00,0.000000000000000000e+00,-1.000000009934097323e+00,0.000000000000000000e+00,-2.479035645993577598e-09,0.000000000000000000e+00 +3.919052526701050709e+01,2.682500000000000000e+02,0.000000000000000000e+00,9.064738624326755811e+00,0.000000000000000000e+00,-1.000000009936831802e+00,0.000000000000000000e+00,1.203438953708550548e-09,0.000000000000000000e+00 +3.919162844277921209e+01,2.682599999999999909e+02,0.000000000000000000e+00,9.063635448547088913e+00,0.000000000000000000e+00,-1.000000009935504197e+00,0.000000000000000000e+00,2.040706791290147499e-10,0.000000000000000000e+00 +3.919273175282039290e+01,2.682699999999999818e+02,0.000000000000000000e+00,9.062532138494944434e+00,0.000000000000000000e+00,-1.000000009935279044e+00,0.000000000000000000e+00,3.835417818003642589e-10,0.000000000000000000e+00 +3.919383519718309117e+01,2.682800000000000296e+02,0.000000000000000000e+00,9.061428694121282490e+00,0.000000000000000000e+00,-1.000000009934855827e+00,0.000000000000000000e+00,-1.155515349856329195e-09,0.000000000000000000e+00 +3.919493877591637698e+01,2.682900000000000205e+02,0.000000000000000000e+00,9.060325115377034777e+00,0.000000000000000000e+00,-1.000000009936131029e+00,0.000000000000000000e+00,1.441854415904657927e-09,0.000000000000000000e+00 +3.919604248906934174e+01,2.683000000000000114e+02,0.000000000000000000e+00,9.059221402213101015e+00,0.000000000000000000e+00,-1.000000009934539635e+00,0.000000000000000000e+00,-2.011148926935359542e-09,0.000000000000000000e+00 +3.919714633669111947e+01,2.683100000000000023e+02,0.000000000000000000e+00,9.058117554580356057e+00,0.000000000000000000e+00,-1.000000009936759637e+00,0.000000000000000000e+00,1.628353445901232932e-09,0.000000000000000000e+00 +3.919825031883086552e+01,2.683199999999999932e+02,0.000000000000000000e+00,9.057013572429637449e+00,0.000000000000000000e+00,-1.000000009934961964e+00,0.000000000000000000e+00,-7.388638115803144827e-10,0.000000000000000000e+00 +3.919935443553777077e+01,2.683299999999999841e+02,0.000000000000000000e+00,9.055909455711761424e+00,0.000000000000000000e+00,-1.000000009935777756e+00,0.000000000000000000e+00,-3.456592424370912187e-10,0.000000000000000000e+00 +3.920045868686105450e+01,2.683400000000000318e+02,0.000000000000000000e+00,9.054805204377506911e+00,0.000000000000000000e+00,-1.000000009936159451e+00,0.000000000000000000e+00,-8.645453770400219866e-11,0.000000000000000000e+00 +3.920156307284996444e+01,2.683500000000000227e+02,0.000000000000000000e+00,9.053700818377626192e+00,0.000000000000000000e+00,-1.000000009936254930e+00,0.000000000000000000e+00,1.515986400222006533e-09,0.000000000000000000e+00 +3.920266759355377673e+01,2.683600000000000136e+02,0.000000000000000000e+00,9.052596297662841351e+00,0.000000000000000000e+00,-1.000000009934580492e+00,0.000000000000000000e+00,-1.341527504430435452e-09,0.000000000000000000e+00 +3.920377224902179591e+01,2.683700000000000045e+02,0.000000000000000000e+00,9.051491642183846054e+00,0.000000000000000000e+00,-1.000000009936062417e+00,0.000000000000000000e+00,9.868289288644291188e-11,0.000000000000000000e+00 +3.920487703930336920e+01,2.683799999999999955e+02,0.000000000000000000e+00,9.050386851891298434e+00,0.000000000000000000e+00,-1.000000009935953393e+00,0.000000000000000000e+00,3.315822795362386998e-11,0.000000000000000000e+00 +3.920598196444785799e+01,2.683899999999999864e+02,0.000000000000000000e+00,9.049281926735831760e+00,0.000000000000000000e+00,-1.000000009935916756e+00,0.000000000000000000e+00,-6.048126133134625030e-11,0.000000000000000000e+00 +3.920708702450465921e+01,2.683999999999999773e+02,0.000000000000000000e+00,9.048176866668047325e+00,0.000000000000000000e+00,-1.000000009935983591e+00,0.000000000000000000e+00,-1.611297283836193441e-10,0.000000000000000000e+00 +3.920819221952321243e+01,2.684100000000000250e+02,0.000000000000000000e+00,9.047071671638516221e+00,0.000000000000000000e+00,-1.000000009936161671e+00,0.000000000000000000e+00,-2.480934016995909612e-10,0.000000000000000000e+00 +3.920929754955296431e+01,2.684200000000000159e+02,0.000000000000000000e+00,9.045966341597779348e+00,0.000000000000000000e+00,-1.000000009936435896e+00,0.000000000000000000e+00,-2.996843169547933099e-10,0.000000000000000000e+00 +3.921040301464341127e+01,2.684300000000000068e+02,0.000000000000000000e+00,9.044860876496347402e+00,0.000000000000000000e+00,-1.000000009936767187e+00,0.000000000000000000e+00,1.158021852051892305e-09,0.000000000000000000e+00 +3.921150861484407102e+01,2.684399999999999977e+02,0.000000000000000000e+00,9.043755276284700884e+00,0.000000000000000000e+00,-1.000000009935486878e+00,0.000000000000000000e+00,-2.132620325537704646e-10,0.000000000000000000e+00 +3.921261435020449682e+01,2.684499999999999886e+02,0.000000000000000000e+00,9.042649540913291872e+00,0.000000000000000000e+00,-1.000000009935722689e+00,0.000000000000000000e+00,-3.272830618003800343e-11,0.000000000000000000e+00 +3.921372022077426323e+01,2.684599999999999795e+02,0.000000000000000000e+00,9.041543670332538696e+00,0.000000000000000000e+00,-1.000000009935758882e+00,0.000000000000000000e+00,-1.184499335392929433e-09,0.000000000000000000e+00 +3.921482622660298034e+01,2.684700000000000273e+02,0.000000000000000000e+00,9.040437664492831260e+00,0.000000000000000000e+00,-1.000000009937068945e+00,0.000000000000000000e+00,7.088060226162304250e-10,0.000000000000000000e+00 +3.921593236774029378e+01,2.684800000000000182e+02,0.000000000000000000e+00,9.039331523344527497e+00,0.000000000000000000e+00,-1.000000009936284906e+00,0.000000000000000000e+00,-1.394958683836754768e-10,0.000000000000000000e+00 +3.921703864423587049e+01,2.684900000000000091e+02,0.000000000000000000e+00,9.038225246837958693e+00,0.000000000000000000e+00,-1.000000009936439227e+00,0.000000000000000000e+00,6.470210633004031555e-10,0.000000000000000000e+00 +3.921814505613941293e+01,2.685000000000000000e+02,0.000000000000000000e+00,9.037118834923422384e+00,0.000000000000000000e+00,-1.000000009935723355e+00,0.000000000000000000e+00,-1.263182071516831585e-09,0.000000000000000000e+00 +3.921925160350065198e+01,2.685099999999999909e+02,0.000000000000000000e+00,9.036012287551187683e+00,0.000000000000000000e+00,-1.000000009937121126e+00,0.000000000000000000e+00,1.404277805163073568e-09,0.000000000000000000e+00 +3.922035828636935406e+01,2.685199999999999818e+02,0.000000000000000000e+00,9.034905604671489954e+00,0.000000000000000000e+00,-1.000000009935567036e+00,0.000000000000000000e+00,-1.482345746437855098e-09,0.000000000000000000e+00 +3.922146510479530690e+01,2.685300000000000296e+02,0.000000000000000000e+00,9.033798786234539691e+00,0.000000000000000000e+00,-1.000000009937207723e+00,0.000000000000000000e+00,1.700005574386270285e-09,0.000000000000000000e+00 +3.922257205882833375e+01,2.685400000000000205e+02,0.000000000000000000e+00,9.032691832190510084e+00,0.000000000000000000e+00,-1.000000009935325895e+00,0.000000000000000000e+00,-6.267689029025934771e-10,0.000000000000000000e+00 +3.922367914851829340e+01,2.685500000000000114e+02,0.000000000000000000e+00,9.031584742489551232e+00,0.000000000000000000e+00,-1.000000009936019785e+00,0.000000000000000000e+00,-1.192219018932858244e-09,0.000000000000000000e+00 +3.922478637391506595e+01,2.685600000000000023e+02,0.000000000000000000e+00,9.030477517081775929e+00,0.000000000000000000e+00,-1.000000009937339840e+00,0.000000000000000000e+00,1.472194942185076732e-09,0.000000000000000000e+00 +3.922589373506856703e+01,2.685699999999999932e+02,0.000000000000000000e+00,9.029370155917268548e+00,0.000000000000000000e+00,-1.000000009935709588e+00,0.000000000000000000e+00,-1.303600888430935324e-09,0.000000000000000000e+00 +3.922700123202874778e+01,2.685799999999999841e+02,0.000000000000000000e+00,9.028262658946086816e+00,0.000000000000000000e+00,-1.000000009937153322e+00,0.000000000000000000e+00,6.404943063771983085e-10,0.000000000000000000e+00 +3.922810886484557358e+01,2.685900000000000318e+02,0.000000000000000000e+00,9.027155026118251158e+00,0.000000000000000000e+00,-1.000000009936443890e+00,0.000000000000000000e+00,8.538876364042324279e-11,0.000000000000000000e+00 +3.922921663356905952e+01,2.686000000000000227e+02,0.000000000000000000e+00,9.026047257383757128e+00,0.000000000000000000e+00,-1.000000009936349299e+00,0.000000000000000000e+00,-5.130713849089123671e-11,0.000000000000000000e+00 +3.923032453824924204e+01,2.686100000000000136e+02,0.000000000000000000e+00,9.024939352692566530e+00,0.000000000000000000e+00,-1.000000009936406142e+00,0.000000000000000000e+00,-1.195750456817557748e-09,0.000000000000000000e+00 +3.923143257893618596e+01,2.686200000000000045e+02,0.000000000000000000e+00,9.023831311994610971e+00,0.000000000000000000e+00,-1.000000009937731082e+00,0.000000000000000000e+00,1.014269426254193451e-09,0.000000000000000000e+00 +3.923254075567999166e+01,2.686299999999999955e+02,0.000000000000000000e+00,9.022723135239790082e+00,0.000000000000000000e+00,-1.000000009936607093e+00,0.000000000000000000e+00,-6.328889053768826732e-10,0.000000000000000000e+00 +3.923364906853079503e+01,2.686399999999999864e+02,0.000000000000000000e+00,9.021614822377976850e+00,0.000000000000000000e+00,-1.000000009937308532e+00,0.000000000000000000e+00,1.115782900754543548e-09,0.000000000000000000e+00 +3.923475751753874619e+01,2.686499999999999773e+02,0.000000000000000000e+00,9.020506373359008734e+00,0.000000000000000000e+00,-1.000000009936071743e+00,0.000000000000000000e+00,-9.475979035303053881e-10,0.000000000000000000e+00 +3.923586610275404496e+01,2.686600000000000250e+02,0.000000000000000000e+00,9.019397788132696547e+00,0.000000000000000000e+00,-1.000000009937122236e+00,0.000000000000000000e+00,4.267772066082370210e-10,0.000000000000000000e+00 +3.923697482422690541e+01,2.686700000000000159e+02,0.000000000000000000e+00,9.018289066648815577e+00,0.000000000000000000e+00,-1.000000009936649059e+00,0.000000000000000000e+00,-5.206402325549791021e-10,0.000000000000000000e+00 +3.923808368200759134e+01,2.686800000000000068e+02,0.000000000000000000e+00,9.017180208857114465e+00,0.000000000000000000e+00,-1.000000009937226375e+00,0.000000000000000000e+00,5.656260813063106633e-10,0.000000000000000000e+00 +3.923919267614638073e+01,2.686899999999999977e+02,0.000000000000000000e+00,9.016071214707308101e+00,0.000000000000000000e+00,-1.000000009936599099e+00,0.000000000000000000e+00,-6.250150248980060919e-10,0.000000000000000000e+00 +3.924030180669358714e+01,2.686999999999999886e+02,0.000000000000000000e+00,9.014962084149082955e+00,0.000000000000000000e+00,-1.000000009937292322e+00,0.000000000000000000e+00,2.606244250094503729e-10,0.000000000000000000e+00 +3.924141107369955250e+01,2.687099999999999795e+02,0.000000000000000000e+00,9.013852817132091744e+00,0.000000000000000000e+00,-1.000000009937003220e+00,0.000000000000000000e+00,3.570635659536336924e-10,0.000000000000000000e+00 +3.924252047721466141e+01,2.687200000000000273e+02,0.000000000000000000e+00,9.012743413605958764e+00,0.000000000000000000e+00,-1.000000009936607093e+00,0.000000000000000000e+00,-3.143933980437321566e-10,0.000000000000000000e+00 +3.924363001728931977e+01,2.687300000000000182e+02,0.000000000000000000e+00,9.011633873520276339e+00,0.000000000000000000e+00,-1.000000009936955925e+00,0.000000000000000000e+00,-2.877415974405419097e-10,0.000000000000000000e+00 +3.924473969397396189e+01,2.687400000000000091e+02,0.000000000000000000e+00,9.010524196824604815e+00,0.000000000000000000e+00,-1.000000009937275225e+00,0.000000000000000000e+00,4.569686243970893007e-10,0.000000000000000000e+00 +3.924584950731906474e+01,2.687500000000000000e+02,0.000000000000000000e+00,9.009414383468474341e+00,0.000000000000000000e+00,-1.000000009936768075e+00,0.000000000000000000e+00,-9.416315172702497287e-10,0.000000000000000000e+00 +3.924695945737512659e+01,2.687599999999999909e+02,0.000000000000000000e+00,9.008304433401384870e+00,0.000000000000000000e+00,-1.000000009937813239e+00,0.000000000000000000e+00,1.305160122820759493e-09,0.000000000000000000e+00 +3.924806954419267413e+01,2.687699999999999818e+02,0.000000000000000000e+00,9.007194346572802601e+00,0.000000000000000000e+00,-1.000000009936364398e+00,0.000000000000000000e+00,-1.430199220660946181e-09,0.000000000000000000e+00 +3.924917976782227669e+01,2.687800000000000296e+02,0.000000000000000000e+00,9.006084122932167091e+00,0.000000000000000000e+00,-1.000000009937952239e+00,0.000000000000000000e+00,9.634807019828702999e-10,0.000000000000000000e+00 +3.925029012831453201e+01,2.687900000000000205e+02,0.000000000000000000e+00,9.004973762428880590e+00,0.000000000000000000e+00,-1.000000009936882428e+00,0.000000000000000000e+00,-1.391656065641400011e-10,0.000000000000000000e+00 +3.925140062572005917e+01,2.688000000000000114e+02,0.000000000000000000e+00,9.003863265012320483e+00,0.000000000000000000e+00,-1.000000009937036971e+00,0.000000000000000000e+00,-3.922546671021137424e-10,0.000000000000000000e+00 +3.925251126008951275e+01,2.688100000000000023e+02,0.000000000000000000e+00,9.002752630631828623e+00,0.000000000000000000e+00,-1.000000009937472623e+00,0.000000000000000000e+00,2.246890219843627896e-10,0.000000000000000000e+00 +3.925362203147358997e+01,2.688199999999999932e+02,0.000000000000000000e+00,9.001641859236716670e+00,0.000000000000000000e+00,-1.000000009937223044e+00,0.000000000000000000e+00,2.936187269146625275e-10,0.000000000000000000e+00 +3.925473293992300228e+01,2.688299999999999841e+02,0.000000000000000000e+00,9.000530950776266081e+00,0.000000000000000000e+00,-1.000000009936896861e+00,0.000000000000000000e+00,-1.630791780689796231e-10,0.000000000000000000e+00 +3.925584398548850373e+01,2.688400000000000318e+02,0.000000000000000000e+00,8.999419905199726344e+00,0.000000000000000000e+00,-1.000000009937078049e+00,0.000000000000000000e+00,-1.122829394957608888e-09,0.000000000000000000e+00 +3.925695516822086972e+01,2.688500000000000227e+02,0.000000000000000000e+00,8.998308722456314968e+00,0.000000000000000000e+00,-1.000000009938325718e+00,0.000000000000000000e+00,1.751269705970273058e-09,0.000000000000000000e+00 +3.925806648817092537e+01,2.688600000000000136e+02,0.000000000000000000e+00,8.997197402495217489e+00,0.000000000000000000e+00,-1.000000009936379497e+00,0.000000000000000000e+00,-1.587635084679505805e-09,0.000000000000000000e+00 +3.925917794538950290e+01,2.688700000000000045e+02,0.000000000000000000e+00,8.996085945265592798e+00,0.000000000000000000e+00,-1.000000009938144085e+00,0.000000000000000000e+00,3.891193016997668550e-10,0.000000000000000000e+00 +3.926028953992748427e+01,2.688799999999999955e+02,0.000000000000000000e+00,8.994974350716560707e+00,0.000000000000000000e+00,-1.000000009937711543e+00,0.000000000000000000e+00,5.117045517652092214e-10,0.000000000000000000e+00 +3.926140127183577988e+01,2.688899999999999864e+02,0.000000000000000000e+00,8.993862618797216157e+00,0.000000000000000000e+00,-1.000000009937142664e+00,0.000000000000000000e+00,2.412422715704529193e-10,0.000000000000000000e+00 +3.926251314116532853e+01,2.688999999999999773e+02,0.000000000000000000e+00,8.992750749456620341e+00,0.000000000000000000e+00,-1.000000009936874434e+00,0.000000000000000000e+00,-1.835850369291773148e-09,0.000000000000000000e+00 +3.926362514796709746e+01,2.689100000000000250e+02,0.000000000000000000e+00,8.991638742643802473e+00,0.000000000000000000e+00,-1.000000009938915912e+00,0.000000000000000000e+00,1.483632494560762569e-09,0.000000000000000000e+00 +3.926473729229208942e+01,2.689200000000000159e+02,0.000000000000000000e+00,8.990526598307758022e+00,0.000000000000000000e+00,-1.000000009937265899e+00,0.000000000000000000e+00,1.670901364555187111e-10,0.000000000000000000e+00 +3.926584957419133559e+01,2.689300000000000068e+02,0.000000000000000000e+00,8.989414316397457583e+00,0.000000000000000000e+00,-1.000000009937080048e+00,0.000000000000000000e+00,-1.452326671505142125e-09,0.000000000000000000e+00 +3.926696199371590268e+01,2.689399999999999977e+02,0.000000000000000000e+00,8.988301896861834450e+00,0.000000000000000000e+00,-1.000000009938695644e+00,0.000000000000000000e+00,9.515993203254519086e-10,0.000000000000000000e+00 +3.926807455091689292e+01,2.689499999999999886e+02,0.000000000000000000e+00,8.987189339649789943e+00,0.000000000000000000e+00,-1.000000009937636936e+00,0.000000000000000000e+00,2.248992633410232387e-10,0.000000000000000000e+00 +3.926918724584542986e+01,2.689599999999999795e+02,0.000000000000000000e+00,8.986076644710198735e+00,0.000000000000000000e+00,-1.000000009937386691e+00,0.000000000000000000e+00,-7.390627641436292612e-10,0.000000000000000000e+00 +3.927030007855267257e+01,2.689700000000000273e+02,0.000000000000000000e+00,8.984963811991899973e+00,0.000000000000000000e+00,-1.000000009938209145e+00,0.000000000000000000e+00,9.498493704661256518e-10,0.000000000000000000e+00 +3.927141304908980857e+01,2.689800000000000182e+02,0.000000000000000000e+00,8.983850841443700830e+00,0.000000000000000000e+00,-1.000000009937151990e+00,0.000000000000000000e+00,-4.225019463661218881e-10,0.000000000000000000e+00 +3.927252615750806797e+01,2.689900000000000091e+02,0.000000000000000000e+00,8.982737733014380055e+00,0.000000000000000000e+00,-1.000000009937622281e+00,0.000000000000000000e+00,-5.319514059009955857e-10,0.000000000000000000e+00 +3.927363940385870222e+01,2.690000000000000000e+02,0.000000000000000000e+00,8.981624486652680872e+00,0.000000000000000000e+00,-1.000000009938214474e+00,0.000000000000000000e+00,6.429691744573471319e-10,0.000000000000000000e+00 +3.927475278819299831e+01,2.690099999999999909e+02,0.000000000000000000e+00,8.980511102307316307e+00,0.000000000000000000e+00,-1.000000009937498602e+00,0.000000000000000000e+00,-1.174509609404907687e-09,0.000000000000000000e+00 +3.927586631056227873e+01,2.690199999999999818e+02,0.000000000000000000e+00,8.979397579926969186e+00,0.000000000000000000e+00,-1.000000009938806445e+00,0.000000000000000000e+00,1.201878787866478665e-09,0.000000000000000000e+00 +3.927697997101789440e+01,2.690300000000000296e+02,0.000000000000000000e+00,8.978283919460286810e+00,0.000000000000000000e+00,-1.000000009937467960e+00,0.000000000000000000e+00,-8.008208874803906548e-10,0.000000000000000000e+00 +3.927809376961122467e+01,2.690400000000000205e+02,0.000000000000000000e+00,8.977170120855889834e+00,0.000000000000000000e+00,-1.000000009938359913e+00,0.000000000000000000e+00,1.432807180206377622e-09,0.000000000000000000e+00 +3.927920770639368442e+01,2.690500000000000114e+02,0.000000000000000000e+00,8.976056184062361609e+00,0.000000000000000000e+00,-1.000000009936763856e+00,0.000000000000000000e+00,-2.096725261332111547e-09,0.000000000000000000e+00 +3.928032178141671693e+01,2.690600000000000023e+02,0.000000000000000000e+00,8.974942109028258841e+00,0.000000000000000000e+00,-1.000000009939099765e+00,0.000000000000000000e+00,1.515154332108844590e-09,0.000000000000000000e+00 +3.928143599473180103e+01,2.690699999999999932e+02,0.000000000000000000e+00,8.973827895702099156e+00,0.000000000000000000e+00,-1.000000009937411560e+00,0.000000000000000000e+00,-5.892088836299237647e-10,0.000000000000000000e+00 +3.928255034639045107e+01,2.690799999999999841e+02,0.000000000000000000e+00,8.972713544032377087e+00,0.000000000000000000e+00,-1.000000009938068146e+00,0.000000000000000000e+00,1.976403892918225350e-10,0.000000000000000000e+00 +3.928366483644420271e+01,2.690900000000000318e+02,0.000000000000000000e+00,8.971599053967548087e+00,0.000000000000000000e+00,-1.000000009937847878e+00,0.000000000000000000e+00,-3.930403765445949626e-10,0.000000000000000000e+00 +3.928477946494463424e+01,2.691000000000000227e+02,0.000000000000000000e+00,8.970484425456039190e+00,0.000000000000000000e+00,-1.000000009938285972e+00,0.000000000000000000e+00,-9.088800919289298256e-10,0.000000000000000000e+00 +3.928589423194335239e+01,2.691100000000000136e+02,0.000000000000000000e+00,8.969369658446243676e+00,0.000000000000000000e+00,-1.000000009939299161e+00,0.000000000000000000e+00,1.531142189351236025e-09,0.000000000000000000e+00 +3.928700913749199231e+01,2.691200000000000045e+02,0.000000000000000000e+00,8.968254752886522851e+00,0.000000000000000000e+00,-1.000000009937592083e+00,0.000000000000000000e+00,-1.969447705053533237e-10,0.000000000000000000e+00 +3.928812418164222464e+01,2.691299999999999955e+02,0.000000000000000000e+00,8.967139708725209601e+00,0.000000000000000000e+00,-1.000000009937811685e+00,0.000000000000000000e+00,-3.534211364228322814e-10,0.000000000000000000e+00 +3.928923936444575560e+01,2.691399999999999864e+02,0.000000000000000000e+00,8.966024525910599507e+00,0.000000000000000000e+00,-1.000000009938205814e+00,0.000000000000000000e+00,-3.450155828455663143e-10,0.000000000000000000e+00 +3.929035468595431269e+01,2.691499999999999773e+02,0.000000000000000000e+00,8.964909204390957953e+00,0.000000000000000000e+00,-1.000000009938590617e+00,0.000000000000000000e+00,-1.496938511303280785e-10,0.000000000000000000e+00 +3.929147014621966605e+01,2.691600000000000250e+02,0.000000000000000000e+00,8.963793744114518347e+00,0.000000000000000000e+00,-1.000000009938757595e+00,0.000000000000000000e+00,2.551644135974043227e-10,0.000000000000000000e+00 +3.929258574529361425e+01,2.691700000000000159e+02,0.000000000000000000e+00,8.962678145029482124e+00,0.000000000000000000e+00,-1.000000009938472934e+00,0.000000000000000000e+00,-5.353407541737033197e-10,0.000000000000000000e+00 +3.929370148322799139e+01,2.691800000000000068e+02,0.000000000000000000e+00,8.961562407084018744e+00,0.000000000000000000e+00,-1.000000009939070234e+00,0.000000000000000000e+00,1.782920459436017364e-09,0.000000000000000000e+00 +3.929481736007465287e+01,2.691899999999999977e+02,0.000000000000000000e+00,8.960446530226263917e+00,0.000000000000000000e+00,-1.000000009937080714e+00,0.000000000000000000e+00,-1.328468479274053386e-09,0.000000000000000000e+00 +3.929593337588550384e+01,2.691999999999999886e+02,0.000000000000000000e+00,8.959330514404324930e+00,0.000000000000000000e+00,-1.000000009938563306e+00,0.000000000000000000e+00,1.396538445133507435e-10,0.000000000000000000e+00 +3.929704953071246365e+01,2.692099999999999795e+02,0.000000000000000000e+00,8.958214359566269991e+00,0.000000000000000000e+00,-1.000000009938407430e+00,0.000000000000000000e+00,-9.215607638750740365e-10,0.000000000000000000e+00 +3.929816582460750141e+01,2.692200000000000273e+02,0.000000000000000000e+00,8.957098065660140662e+00,0.000000000000000000e+00,-1.000000009939436163e+00,0.000000000000000000e+00,1.212219496120571341e-09,0.000000000000000000e+00 +3.929928225762260041e+01,2.692300000000000182e+02,0.000000000000000000e+00,8.955981632633942979e+00,0.000000000000000000e+00,-1.000000009938082801e+00,0.000000000000000000e+00,-5.613895159611997666e-10,0.000000000000000000e+00 +3.930039882980979371e+01,2.692400000000000091e+02,0.000000000000000000e+00,8.954865060435654556e+00,0.000000000000000000e+00,-1.000000009938709633e+00,0.000000000000000000e+00,-5.195635566872162484e-10,0.000000000000000000e+00 +3.930151554122113566e+01,2.692500000000000000e+02,0.000000000000000000e+00,8.953748349013215702e+00,0.000000000000000000e+00,-1.000000009939289836e+00,0.000000000000000000e+00,1.358689077183423985e-09,0.000000000000000000e+00 +3.930263239190871616e+01,2.692599999999999909e+02,0.000000000000000000e+00,8.952631498314536529e+00,0.000000000000000000e+00,-1.000000009937772383e+00,0.000000000000000000e+00,-5.999432475681414220e-10,0.000000000000000000e+00 +3.930374938192465351e+01,2.692699999999999818e+02,0.000000000000000000e+00,8.951514508287496952e+00,0.000000000000000000e+00,-1.000000009938442513e+00,0.000000000000000000e+00,-6.755973072907029084e-10,0.000000000000000000e+00 +3.930486651132110865e+01,2.692800000000000296e+02,0.000000000000000000e+00,8.950397378879939581e+00,0.000000000000000000e+00,-1.000000009939197243e+00,0.000000000000000000e+00,-2.708809094234733833e-10,0.000000000000000000e+00 +3.930598378015026384e+01,2.692900000000000205e+02,0.000000000000000000e+00,8.949280110039676828e+00,0.000000000000000000e+00,-1.000000009939499890e+00,0.000000000000000000e+00,6.368781669303028575e-10,0.000000000000000000e+00 +3.930710118846434398e+01,2.693000000000000114e+02,0.000000000000000000e+00,8.948162701714489131e+00,0.000000000000000000e+00,-1.000000009938788237e+00,0.000000000000000000e+00,6.479252372469035018e-10,0.000000000000000000e+00 +3.930821873631560237e+01,2.693100000000000023e+02,0.000000000000000000e+00,8.947045153852124955e+00,0.000000000000000000e+00,-1.000000009938064149e+00,0.000000000000000000e+00,-2.141601268735325008e-10,0.000000000000000000e+00 +3.930933642375632076e+01,2.693199999999999932e+02,0.000000000000000000e+00,8.945927466400299011e+00,0.000000000000000000e+00,-1.000000009938303513e+00,0.000000000000000000e+00,-5.041470332250765670e-10,0.000000000000000000e+00 +3.931045425083881639e+01,2.693299999999999841e+02,0.000000000000000000e+00,8.944809639306692262e+00,0.000000000000000000e+00,-1.000000009938867063e+00,0.000000000000000000e+00,-1.998063602824403016e-10,0.000000000000000000e+00 +3.931157221761544207e+01,2.693400000000000318e+02,0.000000000000000000e+00,8.943691672518953695e+00,0.000000000000000000e+00,-1.000000009939090440e+00,0.000000000000000000e+00,-6.996320359117074694e-10,0.000000000000000000e+00 +3.931269032413857900e+01,2.693500000000000227e+02,0.000000000000000000e+00,8.942573565984700323e+00,0.000000000000000000e+00,-1.000000009939872703e+00,0.000000000000000000e+00,8.611764980165502816e-10,0.000000000000000000e+00 +3.931380857046065103e+01,2.693600000000000136e+02,0.000000000000000000e+00,8.941455319651515410e+00,0.000000000000000000e+00,-1.000000009938909695e+00,0.000000000000000000e+00,2.432117344535879644e-10,0.000000000000000000e+00 +3.931492695663409620e+01,2.693700000000000045e+02,0.000000000000000000e+00,8.940336933466952019e+00,0.000000000000000000e+00,-1.000000009938637691e+00,0.000000000000000000e+00,3.108750509863533128e-10,0.000000000000000000e+00 +3.931604548271140231e+01,2.693799999999999955e+02,0.000000000000000000e+00,8.939218407378527687e+00,0.000000000000000000e+00,-1.000000009938289969e+00,0.000000000000000000e+00,-1.751877346823313708e-09,0.000000000000000000e+00 +3.931716414874508558e+01,2.693899999999999864e+02,0.000000000000000000e+00,8.938099741333727977e+00,0.000000000000000000e+00,-1.000000009940249734e+00,0.000000000000000000e+00,1.174519909535054398e-09,0.000000000000000000e+00 +3.931828295478769064e+01,2.693999999999999773e+02,0.000000000000000000e+00,8.936980935280002925e+00,0.000000000000000000e+00,-1.000000009938935674e+00,0.000000000000000000e+00,5.967116061797331735e-10,0.000000000000000000e+00 +3.931940190089179765e+01,2.694100000000000250e+02,0.000000000000000000e+00,8.935861989164775920e+00,0.000000000000000000e+00,-1.000000009938267986e+00,0.000000000000000000e+00,-6.226293907562811233e-10,0.000000000000000000e+00 +3.932052098711001520e+01,2.694200000000000159e+02,0.000000000000000000e+00,8.934742902935433051e+00,0.000000000000000000e+00,-1.000000009938964762e+00,0.000000000000000000e+00,-1.041156733152640771e-09,0.000000000000000000e+00 +3.932164021349499450e+01,2.694300000000000068e+02,0.000000000000000000e+00,8.933623676539326652e+00,0.000000000000000000e+00,-1.000000009940130052e+00,0.000000000000000000e+00,7.805713668136926564e-10,0.000000000000000000e+00 +3.932275958009941519e+01,2.694399999999999977e+02,0.000000000000000000e+00,8.932504309923777086e+00,0.000000000000000000e+00,-1.000000009939256307e+00,0.000000000000000000e+00,6.110899737094034417e-10,0.000000000000000000e+00 +3.932387908697599244e+01,2.694499999999999886e+02,0.000000000000000000e+00,8.931384803036074516e+00,0.000000000000000000e+00,-1.000000009938572187e+00,0.000000000000000000e+00,-1.522873025517102310e-09,0.000000000000000000e+00 +3.932499873417746272e+01,2.694599999999999795e+02,0.000000000000000000e+00,8.930265155823473577e+00,0.000000000000000000e+00,-1.000000009940277268e+00,0.000000000000000000e+00,1.484411814722686423e-09,0.000000000000000000e+00 +3.932611852175661227e+01,2.694700000000000273e+02,0.000000000000000000e+00,8.929145368233193381e+00,0.000000000000000000e+00,-1.000000009938615042e+00,0.000000000000000000e+00,-2.603243813512664360e-10,0.000000000000000000e+00 +3.932723844976624861e+01,2.694800000000000182e+02,0.000000000000000000e+00,8.928025440212426389e+00,0.000000000000000000e+00,-1.000000009938906587e+00,0.000000000000000000e+00,-1.067334864270990149e-09,0.000000000000000000e+00 +3.932835851825921480e+01,2.694900000000000091e+02,0.000000000000000000e+00,8.926905371708325987e+00,0.000000000000000000e+00,-1.000000009940102075e+00,0.000000000000000000e+00,5.018857418807138825e-10,0.000000000000000000e+00 +3.932947872728838945e+01,2.695000000000000000e+02,0.000000000000000000e+00,8.925785162668013584e+00,0.000000000000000000e+00,-1.000000009939539858e+00,0.000000000000000000e+00,2.225698900221435358e-10,0.000000000000000000e+00 +3.933059907690668666e+01,2.695099999999999909e+02,0.000000000000000000e+00,8.924664813038580391e+00,0.000000000000000000e+00,-1.000000009939290502e+00,0.000000000000000000e+00,9.496180238617507413e-10,0.000000000000000000e+00 +3.933171956716704898e+01,2.695199999999999818e+02,0.000000000000000000e+00,8.923544322767082093e+00,0.000000000000000000e+00,-1.000000009938226464e+00,0.000000000000000000e+00,-1.538180129437646551e-09,0.000000000000000000e+00 +3.933284019812245447e+01,2.695300000000000296e+02,0.000000000000000000e+00,8.922423691800542400e+00,0.000000000000000000e+00,-1.000000009939950196e+00,0.000000000000000000e+00,-1.442296159755062131e-10,0.000000000000000000e+00 +3.933396096982590961e+01,2.695400000000000205e+02,0.000000000000000000e+00,8.921302920085947719e+00,0.000000000000000000e+00,-1.000000009940111845e+00,0.000000000000000000e+00,9.100379475518414768e-10,0.000000000000000000e+00 +3.933508188233045644e+01,2.695500000000000114e+02,0.000000000000000000e+00,8.920182007570256033e+00,0.000000000000000000e+00,-1.000000009939091772e+00,0.000000000000000000e+00,2.351065129909877894e-10,0.000000000000000000e+00 +3.933620293568917958e+01,2.695600000000000023e+02,0.000000000000000000e+00,8.919060954200391578e+00,0.000000000000000000e+00,-1.000000009938828205e+00,0.000000000000000000e+00,-7.311745218820463516e-10,0.000000000000000000e+00 +3.933732412995518501e+01,2.695699999999999932e+02,0.000000000000000000e+00,8.917939759923243059e+00,0.000000000000000000e+00,-1.000000009939647994e+00,0.000000000000000000e+00,-5.524703345957303640e-10,0.000000000000000000e+00 +3.933844546518161422e+01,2.695799999999999841e+02,0.000000000000000000e+00,8.916818424685665434e+00,0.000000000000000000e+00,-1.000000009940267498e+00,0.000000000000000000e+00,7.929625354311761053e-10,0.000000000000000000e+00 +3.933956694142165134e+01,2.695900000000000318e+02,0.000000000000000000e+00,8.915696948434481683e+00,0.000000000000000000e+00,-1.000000009939378209e+00,0.000000000000000000e+00,-9.070904786795796382e-10,0.000000000000000000e+00 +3.934068855872850179e+01,2.696000000000000227e+02,0.000000000000000000e+00,8.914575331116482815e+00,0.000000000000000000e+00,-1.000000009940395618e+00,0.000000000000000000e+00,1.430338544109404285e-09,0.000000000000000000e+00 +3.934181031715541366e+01,2.696100000000000136e+02,0.000000000000000000e+00,8.913453572678422532e+00,0.000000000000000000e+00,-1.000000009938791123e+00,0.000000000000000000e+00,-6.418494610515273853e-10,0.000000000000000000e+00 +3.934293221675565633e+01,2.696200000000000045e+02,0.000000000000000000e+00,8.912331673067026117e+00,0.000000000000000000e+00,-1.000000009939511214e+00,0.000000000000000000e+00,-1.452934198368407502e-09,0.000000000000000000e+00 +3.934405425758254893e+01,2.696299999999999955e+02,0.000000000000000000e+00,8.911209632228979771e+00,0.000000000000000000e+00,-1.000000009941141466e+00,0.000000000000000000e+00,1.840969475047825247e-09,0.000000000000000000e+00 +3.934517643968943190e+01,2.696399999999999864e+02,0.000000000000000000e+00,8.910087450110937723e+00,0.000000000000000000e+00,-1.000000009939075563e+00,0.000000000000000000e+00,-6.119305169958873435e-10,0.000000000000000000e+00 +3.934629876312968833e+01,2.696499999999999773e+02,0.000000000000000000e+00,8.908965126659525779e+00,0.000000000000000000e+00,-1.000000009939762347e+00,0.000000000000000000e+00,-3.242249544975752944e-10,0.000000000000000000e+00 +3.934742122795672969e+01,2.696600000000000250e+02,0.000000000000000000e+00,8.907842661821328889e+00,0.000000000000000000e+00,-1.000000009940126278e+00,0.000000000000000000e+00,-9.296310501518743392e-11,0.000000000000000000e+00 +3.934854383422399593e+01,2.696700000000000159e+02,0.000000000000000000e+00,8.906720055542901804e+00,0.000000000000000000e+00,-1.000000009940230639e+00,0.000000000000000000e+00,1.513525495712593697e-09,0.000000000000000000e+00 +3.934966658198496958e+01,2.696800000000000068e+02,0.000000000000000000e+00,8.905597307770765525e+00,0.000000000000000000e+00,-1.000000009938531331e+00,0.000000000000000000e+00,-2.524992926365430435e-09,0.000000000000000000e+00 +3.935078947129316873e+01,2.696899999999999977e+02,0.000000000000000000e+00,8.904474418451409079e+00,0.000000000000000000e+00,-1.000000009941366619e+00,0.000000000000000000e+00,1.903243579448893770e-09,0.000000000000000000e+00 +3.935191250220213277e+01,2.696999999999999886e+02,0.000000000000000000e+00,8.903351387531280636e+00,0.000000000000000000e+00,-1.000000009939229217e+00,0.000000000000000000e+00,-6.741369292014113858e-10,0.000000000000000000e+00 +3.935303567476544373e+01,2.697099999999999795e+02,0.000000000000000000e+00,8.902228214956805274e+00,0.000000000000000000e+00,-1.000000009939986390e+00,0.000000000000000000e+00,-3.726063942986707685e-10,0.000000000000000000e+00 +3.935415898903671916e+01,2.697200000000000273e+02,0.000000000000000000e+00,8.901104900674365439e+00,0.000000000000000000e+00,-1.000000009940404944e+00,0.000000000000000000e+00,1.343980778325219672e-11,0.000000000000000000e+00 +3.935528244506960505e+01,2.697300000000000182e+02,0.000000000000000000e+00,8.899981444630313376e+00,0.000000000000000000e+00,-1.000000009940389845e+00,0.000000000000000000e+00,5.078815659742531707e-10,0.000000000000000000e+00 +3.935640604291778288e+01,2.697400000000000091e+02,0.000000000000000000e+00,8.898857846770967583e+00,0.000000000000000000e+00,-1.000000009939819190e+00,0.000000000000000000e+00,-2.718898083821497624e-10,0.000000000000000000e+00 +3.935752978263496971e+01,2.697500000000000000e+02,0.000000000000000000e+00,8.897734107042612806e+00,0.000000000000000000e+00,-1.000000009940124723e+00,0.000000000000000000e+00,5.107168613950364245e-10,0.000000000000000000e+00 +3.935865366427491097e+01,2.697599999999999909e+02,0.000000000000000000e+00,8.896610225391498261e+00,0.000000000000000000e+00,-1.000000009939550738e+00,0.000000000000000000e+00,6.696756186048075531e-11,0.000000000000000000e+00 +3.935977768789139475e+01,2.697699999999999818e+02,0.000000000000000000e+00,8.895486201763841194e+00,0.000000000000000000e+00,-1.000000009939475465e+00,0.000000000000000000e+00,-1.578378100182017472e-09,0.000000000000000000e+00 +3.936090185353823756e+01,2.697800000000000296e+02,0.000000000000000000e+00,8.894362036105823321e+00,0.000000000000000000e+00,-1.000000009941249823e+00,0.000000000000000000e+00,1.219923590967690194e-09,0.000000000000000000e+00 +3.936202616126929144e+01,2.697900000000000205e+02,0.000000000000000000e+00,8.893237728363590833e+00,0.000000000000000000e+00,-1.000000009939878254e+00,0.000000000000000000e+00,5.331677736326965624e-11,0.000000000000000000e+00 +3.936315061113844394e+01,2.698000000000000114e+02,0.000000000000000000e+00,8.892113278483261496e+00,0.000000000000000000e+00,-1.000000009939818302e+00,0.000000000000000000e+00,-8.379547889765906634e-10,0.000000000000000000e+00 +3.936427520319961104e+01,2.698100000000000023e+02,0.000000000000000000e+00,8.890988686410913999e+00,0.000000000000000000e+00,-1.000000009940760659e+00,0.000000000000000000e+00,-2.566454891347144801e-11,0.000000000000000000e+00 +3.936539993750675137e+01,2.698199999999999932e+02,0.000000000000000000e+00,8.889863952092593280e+00,0.000000000000000000e+00,-1.000000009940789525e+00,0.000000000000000000e+00,1.108765653044054791e-09,0.000000000000000000e+00 +3.936652481411385196e+01,2.698299999999999841e+02,0.000000000000000000e+00,8.888739075474312301e+00,0.000000000000000000e+00,-1.000000009939542300e+00,0.000000000000000000e+00,-2.186855784375282828e-10,0.000000000000000000e+00 +3.936764983307492827e+01,2.698400000000000318e+02,0.000000000000000000e+00,8.887614056502050275e+00,0.000000000000000000e+00,-1.000000009939788326e+00,0.000000000000000000e+00,-1.174595506732161275e-09,0.000000000000000000e+00 +3.936877499444404549e+01,2.698500000000000227e+02,0.000000000000000000e+00,8.886488895121749110e+00,0.000000000000000000e+00,-1.000000009941109935e+00,0.000000000000000000e+00,1.069275408719700061e-09,0.000000000000000000e+00 +3.936990029827529014e+01,2.698600000000000136e+02,0.000000000000000000e+00,8.885363591279316964e+00,0.000000000000000000e+00,-1.000000009939906676e+00,0.000000000000000000e+00,-4.772558909694672139e-10,0.000000000000000000e+00 +3.937102574462279136e+01,2.698700000000000045e+02,0.000000000000000000e+00,8.884238144920631797e+00,0.000000000000000000e+00,-1.000000009940443801e+00,0.000000000000000000e+00,-1.791209011245505696e-10,0.000000000000000000e+00 +3.937215133354069962e+01,2.698799999999999955e+02,0.000000000000000000e+00,8.883112555991532489e+00,0.000000000000000000e+00,-1.000000009940645418e+00,0.000000000000000000e+00,-8.171848824172860230e-10,0.000000000000000000e+00 +3.937327706508321512e+01,2.698899999999999864e+02,0.000000000000000000e+00,8.881986824437825945e+00,0.000000000000000000e+00,-1.000000009941565349e+00,0.000000000000000000e+00,1.837298963113526823e-09,0.000000000000000000e+00 +3.937440293930456647e+01,2.698999999999999773e+02,0.000000000000000000e+00,8.880860950205283544e+00,0.000000000000000000e+00,-1.000000009939496781e+00,0.000000000000000000e+00,-6.002607462735038649e-10,0.000000000000000000e+00 +3.937552895625901073e+01,2.699100000000000250e+02,0.000000000000000000e+00,8.879734933239646466e+00,0.000000000000000000e+00,-1.000000009940172685e+00,0.000000000000000000e+00,-1.097643850774712477e-09,0.000000000000000000e+00 +3.937665511600084756e+01,2.699200000000000159e+02,0.000000000000000000e+00,8.878608773486615036e+00,0.000000000000000000e+00,-1.000000009941408807e+00,0.000000000000000000e+00,3.664920302773126507e-10,0.000000000000000000e+00 +3.937778141858440506e+01,2.699300000000000068e+02,0.000000000000000000e+00,8.877482470891857602e+00,0.000000000000000000e+00,-1.000000009940996026e+00,0.000000000000000000e+00,1.015363620017505513e-09,0.000000000000000000e+00 +3.937890786406405397e+01,2.699399999999999977e+02,0.000000000000000000e+00,8.876356025401010541e+00,0.000000000000000000e+00,-1.000000009939852275e+00,0.000000000000000000e+00,-5.256515560546513921e-10,0.000000000000000000e+00 +3.938003445249419343e+01,2.699499999999999886e+02,0.000000000000000000e+00,8.875229436959674700e+00,0.000000000000000000e+00,-1.000000009940444468e+00,0.000000000000000000e+00,-3.330477615573334713e-11,0.000000000000000000e+00 +3.938116118392925102e+01,2.699599999999999795e+02,0.000000000000000000e+00,8.874102705513413625e+00,0.000000000000000000e+00,-1.000000009940481993e+00,0.000000000000000000e+00,-2.825620466430364140e-10,0.000000000000000000e+00 +3.938228805842370406e+01,2.699700000000000273e+02,0.000000000000000000e+00,8.872975831007758885e+00,0.000000000000000000e+00,-1.000000009940800405e+00,0.000000000000000000e+00,1.501289666633967449e-10,0.000000000000000000e+00 +3.938341507603205116e+01,2.699800000000000182e+02,0.000000000000000000e+00,8.871848813388206523e+00,0.000000000000000000e+00,-1.000000009940631207e+00,0.000000000000000000e+00,-1.103169852245099477e-10,0.000000000000000000e+00 +3.938454223680883359e+01,2.699900000000000091e+02,0.000000000000000000e+00,8.870721652600218832e+00,0.000000000000000000e+00,-1.000000009940755552e+00,0.000000000000000000e+00,-1.038423670441009926e-09,0.000000000000000000e+00 +3.938566954080862104e+01,2.700000000000000000e+02,0.000000000000000000e+00,8.869594348589222577e+00,0.000000000000000000e+00,-1.000000009941926171e+00,0.000000000000000000e+00,1.582449517887649737e-09,0.000000000000000000e+00 +3.938679698808602581e+01,2.700099999999999909e+02,0.000000000000000000e+00,8.868466901300608995e+00,0.000000000000000000e+00,-1.000000009940142043e+00,0.000000000000000000e+00,-6.086782454044522870e-10,0.000000000000000000e+00 +3.938792457869568864e+01,2.700199999999999818e+02,0.000000000000000000e+00,8.867339310679739128e+00,0.000000000000000000e+00,-1.000000009940828383e+00,0.000000000000000000e+00,-5.997406025211145966e-10,0.000000000000000000e+00 +3.938905231269228580e+01,2.700300000000000296e+02,0.000000000000000000e+00,8.866211576671933159e+00,0.000000000000000000e+00,-1.000000009941504731e+00,0.000000000000000000e+00,2.352589863835010880e-10,0.000000000000000000e+00 +3.939018019013052907e+01,2.700400000000000205e+02,0.000000000000000000e+00,8.865083699222479297e+00,0.000000000000000000e+00,-1.000000009941239387e+00,0.000000000000000000e+00,5.239997948287608609e-10,0.000000000000000000e+00 +3.939130821106516578e+01,2.700500000000000114e+02,0.000000000000000000e+00,8.863955678276632000e+00,0.000000000000000000e+00,-1.000000009940648305e+00,0.000000000000000000e+00,2.916862821324077463e-10,0.000000000000000000e+00 +3.939243637555097166e+01,2.700600000000000023e+02,0.000000000000000000e+00,8.862827513779610200e+00,0.000000000000000000e+00,-1.000000009940319234e+00,0.000000000000000000e+00,-4.378673250240357323e-10,0.000000000000000000e+00 +3.939356468364277220e+01,2.700699999999999932e+02,0.000000000000000000e+00,8.861699205676597302e+00,0.000000000000000000e+00,-1.000000009940813284e+00,0.000000000000000000e+00,-2.434035621372998669e-10,0.000000000000000000e+00 +3.939469313539540707e+01,2.700799999999999841e+02,0.000000000000000000e+00,8.860570753912741182e+00,0.000000000000000000e+00,-1.000000009941087953e+00,0.000000000000000000e+00,-4.967790879468674034e-10,0.000000000000000000e+00 +3.939582173086377281e+01,2.700900000000000318e+02,0.000000000000000000e+00,8.859442158433155967e+00,0.000000000000000000e+00,-1.000000009941648615e+00,0.000000000000000000e+00,2.209155867998287703e-10,0.000000000000000000e+00 +3.939695047010278728e+01,2.701000000000000227e+02,0.000000000000000000e+00,8.858313419182920256e+00,0.000000000000000000e+00,-1.000000009941399259e+00,0.000000000000000000e+00,5.399252231010257965e-10,0.000000000000000000e+00 +3.939807935316740384e+01,2.701100000000000136e+02,0.000000000000000000e+00,8.857184536107078898e+00,0.000000000000000000e+00,-1.000000009940789747e+00,0.000000000000000000e+00,4.851824331314739226e-10,0.000000000000000000e+00 +3.939920838011261850e+01,2.701200000000000045e+02,0.000000000000000000e+00,8.856055509150641214e+00,0.000000000000000000e+00,-1.000000009940241963e+00,0.000000000000000000e+00,-1.312008332133919709e-09,0.000000000000000000e+00 +3.940033755099345569e+01,2.701299999999999955e+02,0.000000000000000000e+00,8.854926338258580998e+00,0.000000000000000000e+00,-1.000000009941723444e+00,0.000000000000000000e+00,7.457753437248813659e-10,0.000000000000000000e+00 +3.940146686586497538e+01,2.701399999999999864e+02,0.000000000000000000e+00,8.853797023375834740e+00,0.000000000000000000e+00,-1.000000009940881229e+00,0.000000000000000000e+00,-2.821120832173634349e-10,0.000000000000000000e+00 +3.940259632478227303e+01,2.701499999999999773e+02,0.000000000000000000e+00,8.852667564447308735e+00,0.000000000000000000e+00,-1.000000009941199863e+00,0.000000000000000000e+00,-1.922441956298974401e-10,0.000000000000000000e+00 +3.940372592780047967e+01,2.701600000000000250e+02,0.000000000000000000e+00,8.851537961417870193e+00,0.000000000000000000e+00,-1.000000009941417023e+00,0.000000000000000000e+00,-3.533854376820262121e-10,0.000000000000000000e+00 +3.940485567497476893e+01,2.701700000000000159e+02,0.000000000000000000e+00,8.850408214232352577e+00,0.000000000000000000e+00,-1.000000009941816259e+00,0.000000000000000000e+00,6.512624400204728186e-10,0.000000000000000000e+00 +3.940598556636033578e+01,2.701800000000000068e+02,0.000000000000000000e+00,8.849278322835553823e+00,0.000000000000000000e+00,-1.000000009941080403e+00,0.000000000000000000e+00,6.366387809372751774e-11,0.000000000000000000e+00 +3.940711560201241781e+01,2.701899999999999977e+02,0.000000000000000000e+00,8.848148287172238113e+00,0.000000000000000000e+00,-1.000000009941008461e+00,0.000000000000000000e+00,-7.002132317408949881e-10,0.000000000000000000e+00 +3.940824578198628814e+01,2.701999999999999886e+02,0.000000000000000000e+00,8.847018107187132330e+00,0.000000000000000000e+00,-1.000000009941799828e+00,0.000000000000000000e+00,-2.245346507948585122e-10,0.000000000000000000e+00 +3.940937610633725541e+01,2.702099999999999795e+02,0.000000000000000000e+00,8.845887782824927825e+00,0.000000000000000000e+00,-1.000000009942053625e+00,0.000000000000000000e+00,1.513991221946721096e-09,0.000000000000000000e+00 +3.941050657512066380e+01,2.702200000000000273e+02,0.000000000000000000e+00,8.844757314030282203e+00,0.000000000000000000e+00,-1.000000009940342105e+00,0.000000000000000000e+00,-1.019476397015743663e-09,0.000000000000000000e+00 +3.941163718839188590e+01,2.702300000000000182e+02,0.000000000000000000e+00,8.843626700747819314e+00,0.000000000000000000e+00,-1.000000009941494739e+00,0.000000000000000000e+00,-8.498805295262048511e-10,0.000000000000000000e+00 +3.941276794620634405e+01,2.702400000000000091e+02,0.000000000000000000e+00,8.842495942922122154e+00,0.000000000000000000e+00,-1.000000009942455748e+00,0.000000000000000000e+00,2.044910801702524199e-09,0.000000000000000000e+00 +3.941389884861948190e+01,2.702500000000000000e+02,0.000000000000000000e+00,8.841365040497741745e+00,0.000000000000000000e+00,-1.000000009940143153e+00,0.000000000000000000e+00,-2.031888616674840391e-09,0.000000000000000000e+00 +3.941502989568678572e+01,2.702599999999999909e+02,0.000000000000000000e+00,8.840233993419197134e+00,0.000000000000000000e+00,-1.000000009942441315e+00,0.000000000000000000e+00,8.318881509008625924e-10,0.000000000000000000e+00 +3.941616108746377023e+01,2.702699999999999818e+02,0.000000000000000000e+00,8.839102801630962958e+00,0.000000000000000000e+00,-1.000000009941500290e+00,0.000000000000000000e+00,-4.470973853835177111e-10,0.000000000000000000e+00 +3.941729242400599986e+01,2.702800000000000296e+02,0.000000000000000000e+00,8.837971465077487210e+00,0.000000000000000000e+00,-1.000000009942006107e+00,0.000000000000000000e+00,1.096013738265572381e-09,0.000000000000000000e+00 +3.941842390536906038e+01,2.702900000000000205e+02,0.000000000000000000e+00,8.836839983703177026e+00,0.000000000000000000e+00,-1.000000009940765988e+00,0.000000000000000000e+00,-1.450438017681274477e-09,0.000000000000000000e+00 +3.941955553160858017e+01,2.703000000000000114e+02,0.000000000000000000e+00,8.835708357452407569e+00,0.000000000000000000e+00,-1.000000009942407342e+00,0.000000000000000000e+00,1.648406336303479076e-09,0.000000000000000000e+00 +3.942068730278022315e+01,2.703100000000000023e+02,0.000000000000000000e+00,8.834576586269513143e+00,0.000000000000000000e+00,-1.000000009940541723e+00,0.000000000000000000e+00,-2.064461579329720795e-09,0.000000000000000000e+00 +3.942181921893968166e+01,2.703199999999999932e+02,0.000000000000000000e+00,8.833444670098799634e+00,0.000000000000000000e+00,-1.000000009942878521e+00,0.000000000000000000e+00,1.301401328615126778e-09,0.000000000000000000e+00 +3.942295128014269778e+01,2.703299999999999841e+02,0.000000000000000000e+00,8.832312608884528515e+00,0.000000000000000000e+00,-1.000000009941405255e+00,0.000000000000000000e+00,6.803289585071243720e-10,0.000000000000000000e+00 +3.942408348644503491e+01,2.703400000000000318e+02,0.000000000000000000e+00,8.831180402570934618e+00,0.000000000000000000e+00,-1.000000009940634982e+00,0.000000000000000000e+00,-1.129291503385721176e-09,0.000000000000000000e+00 +3.942521583790249906e+01,2.703500000000000227e+02,0.000000000000000000e+00,8.830048051102211915e+00,0.000000000000000000e+00,-1.000000009941913737e+00,0.000000000000000000e+00,5.431040750803612143e-11,0.000000000000000000e+00 +3.942634833457093180e+01,2.703600000000000136e+02,0.000000000000000000e+00,8.828915554422517076e+00,0.000000000000000000e+00,-1.000000009941852230e+00,0.000000000000000000e+00,9.900085984300967537e-11,0.000000000000000000e+00 +3.942748097650621020e+01,2.703700000000000045e+02,0.000000000000000000e+00,8.827782912475974797e+00,0.000000000000000000e+00,-1.000000009941740098e+00,0.000000000000000000e+00,-9.683198151673470390e-10,0.000000000000000000e+00 +3.942861376376425397e+01,2.703799999999999955e+02,0.000000000000000000e+00,8.826650125206672470e+00,0.000000000000000000e+00,-1.000000009942836998e+00,0.000000000000000000e+00,1.029148761932058129e-09,0.000000000000000000e+00 +3.942974669640100416e+01,2.703899999999999864e+02,0.000000000000000000e+00,8.825517192558660184e+00,0.000000000000000000e+00,-1.000000009941671042e+00,0.000000000000000000e+00,5.800589095711047479e-10,0.000000000000000000e+00 +3.943087977447244441e+01,2.703999999999999773e+02,0.000000000000000000e+00,8.824384114475956054e+00,0.000000000000000000e+00,-1.000000009941013790e+00,0.000000000000000000e+00,-9.044622178415954019e-10,0.000000000000000000e+00 +3.943201299803459392e+01,2.704100000000000250e+02,0.000000000000000000e+00,8.823250890902539112e+00,0.000000000000000000e+00,-1.000000009942038748e+00,0.000000000000000000e+00,-6.331989794582827781e-10,0.000000000000000000e+00 +3.943314636714351451e+01,2.704200000000000159e+02,0.000000000000000000e+00,8.822117521782351091e+00,0.000000000000000000e+00,-1.000000009942756396e+00,0.000000000000000000e+00,1.417070864042047690e-09,0.000000000000000000e+00 +3.943427988185529642e+01,2.704300000000000068e+02,0.000000000000000000e+00,8.820984007059299969e+00,0.000000000000000000e+00,-1.000000009941150125e+00,0.000000000000000000e+00,-1.639783378128988654e-09,0.000000000000000000e+00 +3.943541354222606543e+01,2.704399999999999977e+02,0.000000000000000000e+00,8.819850346677259978e+00,0.000000000000000000e+00,-1.000000009943009083e+00,0.000000000000000000e+00,1.279618681353272120e-09,0.000000000000000000e+00 +3.943654734831198994e+01,2.704499999999999886e+02,0.000000000000000000e+00,8.818716540580062713e+00,0.000000000000000000e+00,-1.000000009941558243e+00,0.000000000000000000e+00,-8.557108639969363479e-10,0.000000000000000000e+00 +3.943768130016926676e+01,2.704599999999999795e+02,0.000000000000000000e+00,8.817582588711511349e+00,0.000000000000000000e+00,-1.000000009942528578e+00,0.000000000000000000e+00,2.701897366379909929e-10,0.000000000000000000e+00 +3.943881539785413537e+01,2.704700000000000273e+02,0.000000000000000000e+00,8.816448491015366429e+00,0.000000000000000000e+00,-1.000000009942222157e+00,0.000000000000000000e+00,5.373735036470689497e-10,0.000000000000000000e+00 +3.943994964142287074e+01,2.704800000000000182e+02,0.000000000000000000e+00,8.815314247435356521e+00,0.000000000000000000e+00,-1.000000009941612644e+00,0.000000000000000000e+00,-2.779498016493732046e-11,0.000000000000000000e+00 +3.944108403093177628e+01,2.704900000000000091e+02,0.000000000000000000e+00,8.814179857915172889e+00,0.000000000000000000e+00,-1.000000009941644175e+00,0.000000000000000000e+00,-1.398768732941307483e-09,0.000000000000000000e+00 +3.944221856643719804e+01,2.705000000000000000e+02,0.000000000000000000e+00,8.813045322398469494e+00,0.000000000000000000e+00,-1.000000009943231127e+00,0.000000000000000000e+00,1.968043435049113702e-09,0.000000000000000000e+00 +3.944335324799552467e+01,2.705099999999999909e+02,0.000000000000000000e+00,8.811910640828862995e+00,0.000000000000000000e+00,-1.000000009940998025e+00,0.000000000000000000e+00,-2.318615101999866390e-09,0.000000000000000000e+00 +3.944448807566316617e+01,2.705199999999999818e+02,0.000000000000000000e+00,8.810775813149939850e+00,0.000000000000000000e+00,-1.000000009943629253e+00,0.000000000000000000e+00,2.319881611086582377e-09,0.000000000000000000e+00 +3.944562304949658227e+01,2.705300000000000296e+02,0.000000000000000000e+00,8.809640839305240334e+00,0.000000000000000000e+00,-1.000000009940996248e+00,0.000000000000000000e+00,-2.020098775978978290e-09,0.000000000000000000e+00 +3.944675816955226111e+01,2.705400000000000205e+02,0.000000000000000000e+00,8.808505719238279852e+00,0.000000000000000000e+00,-1.000000009943289303e+00,0.000000000000000000e+00,1.233769843555056300e-09,0.000000000000000000e+00 +3.944789343588672637e+01,2.705500000000000114e+02,0.000000000000000000e+00,8.807370452892525847e+00,0.000000000000000000e+00,-1.000000009941888646e+00,0.000000000000000000e+00,-3.013624431759649702e-10,0.000000000000000000e+00 +3.944902884855654435e+01,2.705600000000000023e+02,0.000000000000000000e+00,8.806235040211419118e+00,0.000000000000000000e+00,-1.000000009942230816e+00,0.000000000000000000e+00,2.927199339629925329e-10,0.000000000000000000e+00 +3.945016440761831689e+01,2.705699999999999932e+02,0.000000000000000000e+00,8.805099481138357831e+00,0.000000000000000000e+00,-1.000000009941898416e+00,0.000000000000000000e+00,-1.092132733174519213e-09,0.000000000000000000e+00 +3.945130011312867424e+01,2.705799999999999841e+02,0.000000000000000000e+00,8.803963775616706400e+00,0.000000000000000000e+00,-1.000000009943138757e+00,0.000000000000000000e+00,1.078503245601267070e-09,0.000000000000000000e+00 +3.945243596514429640e+01,2.705900000000000318e+02,0.000000000000000000e+00,8.802827923589790160e+00,0.000000000000000000e+00,-1.000000009941913737e+00,0.000000000000000000e+00,-5.492483460331445633e-11,0.000000000000000000e+00 +3.945357196372189179e+01,2.706000000000000227e+02,0.000000000000000000e+00,8.801691925000902472e+00,0.000000000000000000e+00,-1.000000009941976131e+00,0.000000000000000000e+00,-3.357604578180584498e-10,0.000000000000000000e+00 +3.945470810891820435e+01,2.706100000000000136e+02,0.000000000000000000e+00,8.800555779793295841e+00,0.000000000000000000e+00,-1.000000009942357604e+00,0.000000000000000000e+00,-1.115018550368341764e-09,0.000000000000000000e+00 +3.945584440079001354e+01,2.706200000000000045e+02,0.000000000000000000e+00,8.799419487910187243e+00,0.000000000000000000e+00,-1.000000009943624590e+00,0.000000000000000000e+00,1.759649579560632480e-09,0.000000000000000000e+00 +3.945698083939414147e+01,2.706299999999999955e+02,0.000000000000000000e+00,8.798283049294756353e+00,0.000000000000000000e+00,-1.000000009941624857e+00,0.000000000000000000e+00,-1.313803588287748353e-09,0.000000000000000000e+00 +3.945811742478744577e+01,2.706399999999999864e+02,0.000000000000000000e+00,8.797146463890150869e+00,0.000000000000000000e+00,-1.000000009943118107e+00,0.000000000000000000e+00,6.914890545089120585e-10,0.000000000000000000e+00 +3.945925415702681960e+01,2.706499999999999773e+02,0.000000000000000000e+00,8.796009731639474083e+00,0.000000000000000000e+00,-1.000000009942332069e+00,0.000000000000000000e+00,-4.476520111244591500e-10,0.000000000000000000e+00 +3.946039103616919164e+01,2.706600000000000250e+02,0.000000000000000000e+00,8.794872852485799086e+00,0.000000000000000000e+00,-1.000000009942840995e+00,0.000000000000000000e+00,7.924681807522343404e-10,0.000000000000000000e+00 +3.946152806227152610e+01,2.706700000000000159e+02,0.000000000000000000e+00,8.793735826372158115e+00,0.000000000000000000e+00,-1.000000009941939938e+00,0.000000000000000000e+00,-1.058700586100466089e-09,0.000000000000000000e+00 +3.946266523539082982e+01,2.706800000000000068e+02,0.000000000000000000e+00,8.792598653241549655e+00,0.000000000000000000e+00,-1.000000009943143864e+00,0.000000000000000000e+00,8.930044756977749237e-10,0.000000000000000000e+00 +3.946380255558413808e+01,2.706899999999999977e+02,0.000000000000000000e+00,8.791461333036931336e+00,0.000000000000000000e+00,-1.000000009942128232e+00,0.000000000000000000e+00,-1.566167068810637691e-09,0.000000000000000000e+00 +3.946494002290852876e+01,2.706999999999999886e+02,0.000000000000000000e+00,8.790323865701228812e+00,0.000000000000000000e+00,-1.000000009943909696e+00,0.000000000000000000e+00,1.199993685004477824e-09,0.000000000000000000e+00 +3.946607763742112240e+01,2.707099999999999795e+02,0.000000000000000000e+00,8.789186251177325104e+00,0.000000000000000000e+00,-1.000000009942544565e+00,0.000000000000000000e+00,-3.912940734454148064e-10,0.000000000000000000e+00 +3.946721539917906085e+01,2.707200000000000273e+02,0.000000000000000000e+00,8.788048489408073038e+00,0.000000000000000000e+00,-1.000000009942989765e+00,0.000000000000000000e+00,5.477407884983622855e-10,0.000000000000000000e+00 +3.946835330823953569e+01,2.707300000000000182e+02,0.000000000000000000e+00,8.786910580336282806e+00,0.000000000000000000e+00,-1.000000009942366486e+00,0.000000000000000000e+00,-7.297061970325579597e-11,0.000000000000000000e+00 +3.946949136465977404e+01,2.707400000000000091e+02,0.000000000000000000e+00,8.785772523904730846e+00,0.000000000000000000e+00,-1.000000009942449530e+00,0.000000000000000000e+00,-8.546601077347532755e-10,0.000000000000000000e+00 +3.947062956849703141e+01,2.707500000000000000e+02,0.000000000000000000e+00,8.784634320056154522e+00,0.000000000000000000e+00,-1.000000009943422308e+00,0.000000000000000000e+00,9.694385865328466540e-10,0.000000000000000000e+00 +3.947176791980861310e+01,2.707599999999999909e+02,0.000000000000000000e+00,8.783495968733253889e+00,0.000000000000000000e+00,-1.000000009942318746e+00,0.000000000000000000e+00,-5.831480397791560663e-11,0.000000000000000000e+00 +3.947290641865185279e+01,2.707699999999999818e+02,0.000000000000000000e+00,8.782357469878695255e+00,0.000000000000000000e+00,-1.000000009942385137e+00,0.000000000000000000e+00,-1.168875011768941562e-09,0.000000000000000000e+00 +3.947404506508411970e+01,2.707800000000000296e+02,0.000000000000000000e+00,8.781218823435104071e+00,0.000000000000000000e+00,-1.000000009943716073e+00,0.000000000000000000e+00,4.026382976006435122e-10,0.000000000000000000e+00 +3.947518385916283279e+01,2.707900000000000205e+02,0.000000000000000000e+00,8.780080029345068482e+00,0.000000000000000000e+00,-1.000000009943257551e+00,0.000000000000000000e+00,5.723935762293379670e-10,0.000000000000000000e+00 +3.947632280094543233e+01,2.708000000000000114e+02,0.000000000000000000e+00,8.778941087551142886e+00,0.000000000000000000e+00,-1.000000009942605628e+00,0.000000000000000000e+00,-6.325532060170381679e-10,0.000000000000000000e+00 +3.947746189048940835e+01,2.708100000000000023e+02,0.000000000000000000e+00,8.777801997995842598e+00,0.000000000000000000e+00,-1.000000009943326162e+00,0.000000000000000000e+00,9.211274463744779388e-10,0.000000000000000000e+00 +3.947860112785227926e+01,2.708199999999999932e+02,0.000000000000000000e+00,8.776662760621643855e+00,0.000000000000000000e+00,-1.000000009942276780e+00,0.000000000000000000e+00,-2.161230972303896498e-10,0.000000000000000000e+00 +3.947974051309160615e+01,2.708299999999999841e+02,0.000000000000000000e+00,8.775523375370989143e+00,0.000000000000000000e+00,-1.000000009942523027e+00,0.000000000000000000e+00,-1.279617789641502457e-09,0.000000000000000000e+00 +3.948088004626498559e+01,2.708400000000000318e+02,0.000000000000000000e+00,8.774383842186280091e+00,0.000000000000000000e+00,-1.000000009943981194e+00,0.000000000000000000e+00,4.915572489902149850e-10,0.000000000000000000e+00 +3.948201972743004973e+01,2.708500000000000227e+02,0.000000000000000000e+00,8.773244161009881026e+00,0.000000000000000000e+00,-1.000000009943420975e+00,0.000000000000000000e+00,1.019610172708367676e-09,0.000000000000000000e+00 +3.948315955664447330e+01,2.708600000000000136e+02,0.000000000000000000e+00,8.772104331784122522e+00,0.000000000000000000e+00,-1.000000009942258794e+00,0.000000000000000000e+00,-1.035254871238513645e-09,0.000000000000000000e+00 +3.948429953396596659e+01,2.708700000000000045e+02,0.000000000000000000e+00,8.770964354451296074e+00,0.000000000000000000e+00,-1.000000009943438961e+00,0.000000000000000000e+00,-1.776161327184851440e-10,0.000000000000000000e+00 +3.948543965945227541e+01,2.708799999999999955e+02,0.000000000000000000e+00,8.769824228953652323e+00,0.000000000000000000e+00,-1.000000009943641466e+00,0.000000000000000000e+00,8.827075343963853432e-10,0.000000000000000000e+00 +3.948657993316118109e+01,2.708899999999999864e+02,0.000000000000000000e+00,8.768683955233408156e+00,0.000000000000000000e+00,-1.000000009942634938e+00,0.000000000000000000e+00,-5.589948867229546564e-10,0.000000000000000000e+00 +3.948772035515050760e+01,2.708999999999999773e+02,0.000000000000000000e+00,8.767543533232743158e+00,0.000000000000000000e+00,-1.000000009943272428e+00,0.000000000000000000e+00,-3.780657907079373371e-10,0.000000000000000000e+00 +3.948886092547811444e+01,2.709100000000000250e+02,0.000000000000000000e+00,8.766402962893796058e+00,0.000000000000000000e+00,-1.000000009943703638e+00,0.000000000000000000e+00,8.564742923041258633e-11,0.000000000000000000e+00 +3.949000164420189662e+01,2.709200000000000159e+02,0.000000000000000000e+00,8.765262244158670057e+00,0.000000000000000000e+00,-1.000000009943605939e+00,0.000000000000000000e+00,8.575306120253834348e-10,0.000000000000000000e+00 +3.949114251137979181e+01,2.709300000000000068e+02,0.000000000000000000e+00,8.764121376969431054e+00,0.000000000000000000e+00,-1.000000009942627610e+00,0.000000000000000000e+00,-7.643989612112972188e-10,0.000000000000000000e+00 +3.949228352706977319e+01,2.709399999999999977e+02,0.000000000000000000e+00,8.762980361268107643e+00,0.000000000000000000e+00,-1.000000009943499801e+00,0.000000000000000000e+00,7.041750721954293719e-10,0.000000000000000000e+00 +3.949342469132984945e+01,2.709499999999999886e+02,0.000000000000000000e+00,8.761839196996687562e+00,0.000000000000000000e+00,-1.000000009942696222e+00,0.000000000000000000e+00,-1.530928997820855850e-09,0.000000000000000000e+00 +3.949456600421806485e+01,2.709599999999999795e+02,0.000000000000000000e+00,8.760697884097124799e+00,0.000000000000000000e+00,-1.000000009944443491e+00,0.000000000000000000e+00,2.102443169145689815e-09,0.000000000000000000e+00 +3.949570746579250624e+01,2.709700000000000273e+02,0.000000000000000000e+00,8.759556422511330709e+00,0.000000000000000000e+00,-1.000000009942043633e+00,0.000000000000000000e+00,-2.003362612509700557e-09,0.000000000000000000e+00 +3.949684907611130313e+01,2.709800000000000182e+02,0.000000000000000000e+00,8.758414812181186448e+00,0.000000000000000000e+00,-1.000000009944330692e+00,0.000000000000000000e+00,1.173272957941431359e-09,0.000000000000000000e+00 +3.949799083523261345e+01,2.709900000000000091e+02,0.000000000000000000e+00,8.757273053048525213e+00,0.000000000000000000e+00,-1.000000009942991097e+00,0.000000000000000000e+00,-6.072689849794375720e-10,0.000000000000000000e+00 +3.949913274321463064e+01,2.710000000000000000e+02,0.000000000000000000e+00,8.756131145055151777e+00,0.000000000000000000e+00,-1.000000009943684542e+00,0.000000000000000000e+00,-5.053110118335610506e-10,0.000000000000000000e+00 +3.950027480011559788e+01,2.710099999999999909e+02,0.000000000000000000e+00,8.754989088142826503e+00,0.000000000000000000e+00,-1.000000009944261636e+00,0.000000000000000000e+00,1.504848923945836786e-09,0.000000000000000000e+00 +3.950141700599379391e+01,2.710199999999999818e+02,0.000000000000000000e+00,8.753846882253274231e+00,0.000000000000000000e+00,-1.000000009942542789e+00,0.000000000000000000e+00,-1.358483011861103041e-09,0.000000000000000000e+00 +3.950255936090752584e+01,2.710300000000000296e+02,0.000000000000000000e+00,8.752704527328184270e+00,0.000000000000000000e+00,-1.000000009944094659e+00,0.000000000000000000e+00,4.617734185459579653e-10,0.000000000000000000e+00 +3.950370186491515057e+01,2.710400000000000205e+02,0.000000000000000000e+00,8.751562023309201521e+00,0.000000000000000000e+00,-1.000000009943567081e+00,0.000000000000000000e+00,1.859677935269067519e-10,0.000000000000000000e+00 +3.950484451807505337e+01,2.710500000000000114e+02,0.000000000000000000e+00,8.750419370137938913e+00,0.000000000000000000e+00,-1.000000009943354584e+00,0.000000000000000000e+00,-7.977889889551365121e-10,0.000000000000000000e+00 +3.950598732044566219e+01,2.710600000000000023e+02,0.000000000000000000e+00,8.749276567755968514e+00,0.000000000000000000e+00,-1.000000009944266299e+00,0.000000000000000000e+00,1.617905259904610802e-09,0.000000000000000000e+00 +3.950713027208544048e+01,2.710699999999999932e+02,0.000000000000000000e+00,8.748133616104823318e+00,0.000000000000000000e+00,-1.000000009942417112e+00,0.000000000000000000e+00,-2.059801415325591583e-09,0.000000000000000000e+00 +3.950827337305289433e+01,2.710799999999999841e+02,0.000000000000000000e+00,8.746990515126002563e+00,0.000000000000000000e+00,-1.000000009944771673e+00,0.000000000000000000e+00,1.791894066295374058e-09,0.000000000000000000e+00 +3.950941662340656535e+01,2.710900000000000318e+02,0.000000000000000000e+00,8.745847264760959305e+00,0.000000000000000000e+00,-1.000000009942723089e+00,0.000000000000000000e+00,-1.752043710616066402e-09,0.000000000000000000e+00 +3.951056002320503779e+01,2.711000000000000227e+02,0.000000000000000000e+00,8.744703864951118177e+00,0.000000000000000000e+00,-1.000000009944726376e+00,0.000000000000000000e+00,9.246443567456014041e-10,0.000000000000000000e+00 +3.951170357250692433e+01,2.711100000000000136e+02,0.000000000000000000e+00,8.743560315637855851e+00,0.000000000000000000e+00,-1.000000009943668999e+00,0.000000000000000000e+00,3.374258168115894017e-10,0.000000000000000000e+00 +3.951284727137088737e+01,2.711200000000000045e+02,0.000000000000000000e+00,8.742416616762518800e+00,0.000000000000000000e+00,-1.000000009943283086e+00,0.000000000000000000e+00,-7.687177517285886031e-10,0.000000000000000000e+00 +3.951399111985562485e+01,2.711299999999999955e+02,0.000000000000000000e+00,8.741272768266410864e+00,0.000000000000000000e+00,-1.000000009944162382e+00,0.000000000000000000e+00,3.485950615235483320e-10,0.000000000000000000e+00 +3.951513511801986311e+01,2.711399999999999864e+02,0.000000000000000000e+00,8.740128770090796806e+00,0.000000000000000000e+00,-1.000000009943763590e+00,0.000000000000000000e+00,-3.570885129137628208e-10,0.000000000000000000e+00 +3.951627926592237827e+01,2.711499999999999773e+02,0.000000000000000000e+00,8.738984622176905859e+00,0.000000000000000000e+00,-1.000000009944172152e+00,0.000000000000000000e+00,1.212971786862034627e-09,0.000000000000000000e+00 +3.951742356362198194e+01,2.711600000000000250e+02,0.000000000000000000e+00,8.737840324465926400e+00,0.000000000000000000e+00,-1.000000009942784152e+00,0.000000000000000000e+00,-1.697860533931312812e-09,0.000000000000000000e+00 +3.951856801117752127e+01,2.711700000000000159e+02,0.000000000000000000e+00,8.736695876899011282e+00,0.000000000000000000e+00,-1.000000009944727264e+00,0.000000000000000000e+00,4.327997627254042057e-10,0.000000000000000000e+00 +3.951971260864787894e+01,2.711800000000000068e+02,0.000000000000000000e+00,8.735551279417268944e+00,0.000000000000000000e+00,-1.000000009944231882e+00,0.000000000000000000e+00,8.497746984998290688e-10,0.000000000000000000e+00 +3.952085735609198736e+01,2.711899999999999977e+02,0.000000000000000000e+00,8.734406531961775855e+00,0.000000000000000000e+00,-1.000000009943259105e+00,0.000000000000000000e+00,-4.183345867368248719e-10,0.000000000000000000e+00 +3.952200225356881447e+01,2.711999999999999886e+02,0.000000000000000000e+00,8.733261634473567625e+00,0.000000000000000000e+00,-1.000000009943738055e+00,0.000000000000000000e+00,-6.335280247032924590e-10,0.000000000000000000e+00 +3.952314730113735664e+01,2.712099999999999795e+02,0.000000000000000000e+00,8.732116586893639010e+00,0.000000000000000000e+00,-1.000000009944463475e+00,0.000000000000000000e+00,2.307314059458371812e-10,0.000000000000000000e+00 +3.952429249885665996e+01,2.712200000000000273e+02,0.000000000000000000e+00,8.730971389162947460e+00,0.000000000000000000e+00,-1.000000009944199242e+00,0.000000000000000000e+00,8.462273129715983674e-10,0.000000000000000000e+00 +3.952543784678580607e+01,2.712300000000000182e+02,0.000000000000000000e+00,8.729826041222413124e+00,0.000000000000000000e+00,-1.000000009943230017e+00,0.000000000000000000e+00,-1.467376956211322808e-09,0.000000000000000000e+00 +3.952658334498391213e+01,2.712400000000000091e+02,0.000000000000000000e+00,8.728680543012917070e+00,0.000000000000000000e+00,-1.000000009944910895e+00,0.000000000000000000e+00,1.440244037701021460e-09,0.000000000000000000e+00 +3.952772899351013791e+01,2.712500000000000000e+02,0.000000000000000000e+00,8.727534894475297733e+00,0.000000000000000000e+00,-1.000000009943260881e+00,0.000000000000000000e+00,-1.232505695921990265e-09,0.000000000000000000e+00 +3.952887479242367874e+01,2.712599999999999909e+02,0.000000000000000000e+00,8.726389095550361574e+00,0.000000000000000000e+00,-1.000000009944673085e+00,0.000000000000000000e+00,1.511365142931993494e-11,0.000000000000000000e+00 +3.953002074178377256e+01,2.712699999999999818e+02,0.000000000000000000e+00,8.725243146178868869e+00,0.000000000000000000e+00,-1.000000009944655766e+00,0.000000000000000000e+00,1.149649105456904895e-09,0.000000000000000000e+00 +3.953116684164969996e+01,2.712800000000000296e+02,0.000000000000000000e+00,8.724097046301546143e+00,0.000000000000000000e+00,-1.000000009943338153e+00,0.000000000000000000e+00,-5.050120543905330661e-10,0.000000000000000000e+00 +3.953231309208076993e+01,2.712900000000000205e+02,0.000000000000000000e+00,8.722950795859080841e+00,0.000000000000000000e+00,-1.000000009943917023e+00,0.000000000000000000e+00,-8.644314020571437070e-10,0.000000000000000000e+00 +3.953345949313633412e+01,2.713000000000000114e+02,0.000000000000000000e+00,8.721804394792117776e+00,0.000000000000000000e+00,-1.000000009944908008e+00,0.000000000000000000e+00,9.721880647596587373e-11,0.000000000000000000e+00 +3.953460604487578678e+01,2.713100000000000023e+02,0.000000000000000000e+00,8.720657843041264456e+00,0.000000000000000000e+00,-1.000000009944796542e+00,0.000000000000000000e+00,1.055711663872326943e-09,0.000000000000000000e+00 +3.953575274735855771e+01,2.713199999999999932e+02,0.000000000000000000e+00,8.719511140547091088e+00,0.000000000000000000e+00,-1.000000009943585955e+00,0.000000000000000000e+00,-6.633148512128335688e-10,0.000000000000000000e+00 +3.953689960064411935e+01,2.713299999999999841e+02,0.000000000000000000e+00,8.718364287250128797e+00,0.000000000000000000e+00,-1.000000009944346679e+00,0.000000000000000000e+00,3.712990515702007750e-10,0.000000000000000000e+00 +3.953804660479197253e+01,2.713400000000000318e+02,0.000000000000000000e+00,8.717217283090866076e+00,0.000000000000000000e+00,-1.000000009943920798e+00,0.000000000000000000e+00,-1.215176628282953598e-09,0.000000000000000000e+00 +3.953919375986167495e+01,2.713500000000000227e+02,0.000000000000000000e+00,8.716070128009755891e+00,0.000000000000000000e+00,-1.000000009945314794e+00,0.000000000000000000e+00,1.354555908016148028e-09,0.000000000000000000e+00 +3.954034106591281272e+01,2.713600000000000136e+02,0.000000000000000000e+00,8.714922821947208575e+00,0.000000000000000000e+00,-1.000000009943760704e+00,0.000000000000000000e+00,9.288487655766753045e-12,0.000000000000000000e+00 +3.954148852300500749e+01,2.713700000000000045e+02,0.000000000000000000e+00,8.713775364843600713e+00,0.000000000000000000e+00,-1.000000009943750046e+00,0.000000000000000000e+00,-1.173484589229199749e-09,0.000000000000000000e+00 +3.954263613119793064e+01,2.713799999999999955e+02,0.000000000000000000e+00,8.712627756639264476e+00,0.000000000000000000e+00,-1.000000009945096746e+00,0.000000000000000000e+00,5.304651231320370900e-10,0.000000000000000000e+00 +3.954378389055128906e+01,2.713899999999999864e+02,0.000000000000000000e+00,8.711479997274492959e+00,0.000000000000000000e+00,-1.000000009944487900e+00,0.000000000000000000e+00,-2.464345509107280245e-10,0.000000000000000000e+00 +3.954493180112482520e+01,2.713999999999999773e+02,0.000000000000000000e+00,8.710332086689543729e+00,0.000000000000000000e+00,-1.000000009944770785e+00,0.000000000000000000e+00,5.690069970541031178e-10,0.000000000000000000e+00 +3.954607986297831701e+01,2.714100000000000250e+02,0.000000000000000000e+00,8.709184024824631720e+00,0.000000000000000000e+00,-1.000000009944117529e+00,0.000000000000000000e+00,-1.039238804998622716e-09,0.000000000000000000e+00 +3.954722807617159930e+01,2.714200000000000159e+02,0.000000000000000000e+00,8.708035811619934563e+00,0.000000000000000000e+00,-1.000000009945310797e+00,0.000000000000000000e+00,1.693422682928322432e-09,0.000000000000000000e+00 +3.954837644076452818e+01,2.714300000000000068e+02,0.000000000000000000e+00,8.706887447015587256e+00,0.000000000000000000e+00,-1.000000009943366130e+00,0.000000000000000000e+00,-1.982230313096762407e-09,0.000000000000000000e+00 +3.954952495681700242e+01,2.714399999999999977e+02,0.000000000000000000e+00,8.705738930951691046e+00,0.000000000000000000e+00,-1.000000009945642754e+00,0.000000000000000000e+00,1.430466147512688305e-09,0.000000000000000000e+00 +3.955067362438897050e+01,2.714499999999999886e+02,0.000000000000000000e+00,8.704590263368299219e+00,0.000000000000000000e+00,-1.000000009943999624e+00,0.000000000000000000e+00,-1.611961293257282716e-10,0.000000000000000000e+00 +3.955182244354040932e+01,2.714599999999999795e+02,0.000000000000000000e+00,8.703441444205434863e+00,0.000000000000000000e+00,-1.000000009944184809e+00,0.000000000000000000e+00,-1.342544025126794007e-09,0.000000000000000000e+00 +3.955297141433134556e+01,2.714700000000000273e+02,0.000000000000000000e+00,8.702292473403074879e+00,0.000000000000000000e+00,-1.000000009945727353e+00,0.000000000000000000e+00,1.949687768046648871e-09,0.000000000000000000e+00 +3.955412053682183426e+01,2.714800000000000182e+02,0.000000000000000000e+00,8.701143350901157092e+00,0.000000000000000000e+00,-1.000000009943486923e+00,0.000000000000000000e+00,-1.019924938936593988e-09,0.000000000000000000e+00 +3.955526981107198026e+01,2.714900000000000091e+02,0.000000000000000000e+00,8.699994076639585572e+00,0.000000000000000000e+00,-1.000000009944659096e+00,0.000000000000000000e+00,-8.061346097724573455e-10,0.000000000000000000e+00 +3.955641923714191677e+01,2.715000000000000000e+02,0.000000000000000000e+00,8.698844650558216429e+00,0.000000000000000000e+00,-1.000000009945585688e+00,0.000000000000000000e+00,1.271720355228718188e-09,0.000000000000000000e+00 +3.955756881509182676e+01,2.715099999999999909e+02,0.000000000000000000e+00,8.697695072596870247e+00,0.000000000000000000e+00,-1.000000009944123747e+00,0.000000000000000000e+00,-1.479550747499938369e-09,0.000000000000000000e+00 +3.955871854498193585e+01,2.715199999999999818e+02,0.000000000000000000e+00,8.696545342695330305e+00,0.000000000000000000e+00,-1.000000009945824830e+00,0.000000000000000000e+00,1.720346586477299231e-09,0.000000000000000000e+00 +3.955986842687249805e+01,2.715300000000000296e+02,0.000000000000000000e+00,8.695395460793333697e+00,0.000000000000000000e+00,-1.000000009943846635e+00,0.000000000000000000e+00,-1.193792401245845269e-09,0.000000000000000000e+00 +3.956101846082381002e+01,2.715400000000000205e+02,0.000000000000000000e+00,8.694245426830585544e+00,0.000000000000000000e+00,-1.000000009945219537e+00,0.000000000000000000e+00,5.525120452618356459e-10,0.000000000000000000e+00 +3.956216864689621104e+01,2.715500000000000114e+02,0.000000000000000000e+00,8.693095240746743002e+00,0.000000000000000000e+00,-1.000000009944584045e+00,0.000000000000000000e+00,2.717798896816650652e-10,0.000000000000000000e+00 +3.956331898515008305e+01,2.715600000000000023e+02,0.000000000000000000e+00,8.691944902481429480e+00,0.000000000000000000e+00,-1.000000009944271406e+00,0.000000000000000000e+00,-6.637268183869701383e-10,0.000000000000000000e+00 +3.956446947564584349e+01,2.715699999999999932e+02,0.000000000000000000e+00,8.690794411974225753e+00,0.000000000000000000e+00,-1.000000009945035018e+00,0.000000000000000000e+00,-8.849806037617156739e-10,0.000000000000000000e+00 +3.956562011844395244e+01,2.715799999999999841e+02,0.000000000000000000e+00,8.689643769164671738e+00,0.000000000000000000e+00,-1.000000009946053314e+00,0.000000000000000000e+00,9.776718319000597991e-10,0.000000000000000000e+00 +3.956677091360491261e+01,2.715900000000000318e+02,0.000000000000000000e+00,8.688492973992268276e+00,0.000000000000000000e+00,-1.000000009944928214e+00,0.000000000000000000e+00,9.269964516008332402e-10,0.000000000000000000e+00 +3.956792186118925514e+01,2.716000000000000227e+02,0.000000000000000000e+00,8.687342026396478900e+00,0.000000000000000000e+00,-1.000000009943861290e+00,0.000000000000000000e+00,-1.006926217468109613e-09,0.000000000000000000e+00 +3.956907296125756091e+01,2.716100000000000136e+02,0.000000000000000000e+00,8.686190926316724514e+00,0.000000000000000000e+00,-1.000000009945020363e+00,0.000000000000000000e+00,-7.734174548474928535e-10,0.000000000000000000e+00 +3.957022421387045341e+01,2.716200000000000045e+02,0.000000000000000000e+00,8.685039673692383388e+00,0.000000000000000000e+00,-1.000000009945910762e+00,0.000000000000000000e+00,1.653081229300104226e-09,0.000000000000000000e+00 +3.957137561908859169e+01,2.716299999999999955e+02,0.000000000000000000e+00,8.683888268462796489e+00,0.000000000000000000e+00,-1.000000009944007395e+00,0.000000000000000000e+00,-1.737510517399304626e-09,0.000000000000000000e+00 +3.957252717697267030e+01,2.716399999999999864e+02,0.000000000000000000e+00,8.682736710567267480e+00,0.000000000000000000e+00,-1.000000009946008239e+00,0.000000000000000000e+00,1.139806902925004387e-09,0.000000000000000000e+00 +3.957367888758343355e+01,2.716499999999999773e+02,0.000000000000000000e+00,8.681584999945052061e+00,0.000000000000000000e+00,-1.000000009944695512e+00,0.000000000000000000e+00,-4.023108045566675334e-10,0.000000000000000000e+00 +3.957483075098165415e+01,2.716600000000000250e+02,0.000000000000000000e+00,8.680433136535373961e+00,0.000000000000000000e+00,-1.000000009945158919e+00,0.000000000000000000e+00,3.602391614384495282e-10,0.000000000000000000e+00 +3.957598276722816166e+01,2.716700000000000159e+02,0.000000000000000000e+00,8.679281120277410722e+00,0.000000000000000000e+00,-1.000000009944743917e+00,0.000000000000000000e+00,-5.602334200249011064e-10,0.000000000000000000e+00 +3.957713493638381408e+01,2.716800000000000068e+02,0.000000000000000000e+00,8.678128951110302580e+00,0.000000000000000000e+00,-1.000000009945389401e+00,0.000000000000000000e+00,-4.588024412076314475e-10,0.000000000000000000e+00 +3.957828725850951201e+01,2.716899999999999977e+02,0.000000000000000000e+00,8.676976628973147143e+00,0.000000000000000000e+00,-1.000000009945918089e+00,0.000000000000000000e+00,6.920619644306467790e-10,0.000000000000000000e+00 +3.957943973366619161e+01,2.716999999999999886e+02,0.000000000000000000e+00,8.675824153805002936e+00,0.000000000000000000e+00,-1.000000009945120505e+00,0.000000000000000000e+00,2.456185431954112025e-10,0.000000000000000000e+00 +3.958059236191483876e+01,2.717099999999999795e+02,0.000000000000000000e+00,8.674671525544889406e+00,0.000000000000000000e+00,-1.000000009944837398e+00,0.000000000000000000e+00,-4.314607386306635679e-10,0.000000000000000000e+00 +3.958174514331648197e+01,2.717200000000000273e+02,0.000000000000000000e+00,8.673518744131783365e+00,0.000000000000000000e+00,-1.000000009945334778e+00,0.000000000000000000e+00,2.542198616562786091e-11,0.000000000000000000e+00 +3.958289807793217818e+01,2.717300000000000182e+02,0.000000000000000000e+00,8.672365809504620771e+00,0.000000000000000000e+00,-1.000000009945305468e+00,0.000000000000000000e+00,3.079117611858947822e-10,0.000000000000000000e+00 +3.958405116582303407e+01,2.717400000000000091e+02,0.000000000000000000e+00,8.671212721602298501e+00,0.000000000000000000e+00,-1.000000009944950419e+00,0.000000000000000000e+00,-8.906881909827520420e-10,0.000000000000000000e+00 +3.958520440705019183e+01,2.717500000000000000e+02,0.000000000000000000e+00,8.670059480363672577e+00,0.000000000000000000e+00,-1.000000009945977597e+00,0.000000000000000000e+00,4.641512376037229960e-10,0.000000000000000000e+00 +3.958635780167483631e+01,2.717599999999999909e+02,0.000000000000000000e+00,8.668906085727556388e+00,0.000000000000000000e+00,-1.000000009945442248e+00,0.000000000000000000e+00,3.947936729048965457e-10,0.000000000000000000e+00 +3.958751134975819497e+01,2.717699999999999818e+02,0.000000000000000000e+00,8.667752537632726018e+00,0.000000000000000000e+00,-1.000000009944986834e+00,0.000000000000000000e+00,2.655986209173102612e-10,0.000000000000000000e+00 +3.958866505136153080e+01,2.717800000000000296e+02,0.000000000000000000e+00,8.666598836017914920e+00,0.000000000000000000e+00,-1.000000009944680412e+00,0.000000000000000000e+00,-1.229288523518389187e-09,0.000000000000000000e+00 +3.958981890654615654e+01,2.717900000000000205e+02,0.000000000000000000e+00,8.665444980821815690e+00,0.000000000000000000e+00,-1.000000009946098833e+00,0.000000000000000000e+00,1.275111214125294438e-09,0.000000000000000000e+00 +3.959097291537341334e+01,2.718000000000000114e+02,0.000000000000000000e+00,8.664290971983078293e+00,0.000000000000000000e+00,-1.000000009944627344e+00,0.000000000000000000e+00,-1.530429886867365674e-09,0.000000000000000000e+00 +3.959212707790469921e+01,2.718100000000000023e+02,0.000000000000000000e+00,8.663136809440317165e+00,0.000000000000000000e+00,-1.000000009946393709e+00,0.000000000000000000e+00,1.052980167390333831e-09,0.000000000000000000e+00 +3.959328139420143344e+01,2.718199999999999932e+02,0.000000000000000000e+00,8.661982493132098782e+00,0.000000000000000000e+00,-1.000000009945178236e+00,0.000000000000000000e+00,-2.808085861610379859e-10,0.000000000000000000e+00 +3.959443586432509221e+01,2.718299999999999841e+02,0.000000000000000000e+00,8.660828022996955866e+00,0.000000000000000000e+00,-1.000000009945502422e+00,0.000000000000000000e+00,-1.701934770970649078e-10,0.000000000000000000e+00 +3.959559048833718720e+01,2.718400000000000318e+02,0.000000000000000000e+00,8.659673398973374958e+00,0.000000000000000000e+00,-1.000000009945698931e+00,0.000000000000000000e+00,8.075901786350353055e-11,0.000000000000000000e+00 +3.959674526629927271e+01,2.718500000000000227e+02,0.000000000000000000e+00,8.658518620999803517e+00,0.000000000000000000e+00,-1.000000009945605672e+00,0.000000000000000000e+00,5.006391410119157220e-10,0.000000000000000000e+00 +3.959790019827293861e+01,2.718600000000000136e+02,0.000000000000000000e+00,8.657363689014648145e+00,0.000000000000000000e+00,-1.000000009945027468e+00,0.000000000000000000e+00,-2.137620840821761107e-10,0.000000000000000000e+00 +3.959905528431982447e+01,2.718700000000000045e+02,0.000000000000000000e+00,8.656208602956274589e+00,0.000000000000000000e+00,-1.000000009945274382e+00,0.000000000000000000e+00,-7.009768937522927743e-10,0.000000000000000000e+00 +3.960021052450160539e+01,2.718799999999999955e+02,0.000000000000000000e+00,8.655053362763005964e+00,0.000000000000000000e+00,-1.000000009946084178e+00,0.000000000000000000e+00,3.978142362397335207e-10,0.000000000000000000e+00 +3.960136591887999202e+01,2.718899999999999864e+02,0.000000000000000000e+00,8.653897968373124527e+00,0.000000000000000000e+00,-1.000000009945624546e+00,0.000000000000000000e+00,-8.812234516088845375e-10,0.000000000000000000e+00 +3.960252146751675184e+01,2.718999999999999773e+02,0.000000000000000000e+00,8.652742419724873457e+00,0.000000000000000000e+00,-1.000000009946642843e+00,0.000000000000000000e+00,8.134762065096250050e-10,0.000000000000000000e+00 +3.960367717047368075e+01,2.719100000000000250e+02,0.000000000000000000e+00,8.651586716756451523e+00,0.000000000000000000e+00,-1.000000009945702706e+00,0.000000000000000000e+00,1.890301544024885510e-10,0.000000000000000000e+00 +3.960483302781261727e+01,2.719200000000000159e+02,0.000000000000000000e+00,8.650430859406020190e+00,0.000000000000000000e+00,-1.000000009945484214e+00,0.000000000000000000e+00,-6.434618033737164338e-11,0.000000000000000000e+00 +3.960598903959544259e+01,2.719300000000000068e+02,0.000000000000000000e+00,8.649274847611696515e+00,0.000000000000000000e+00,-1.000000009945558599e+00,0.000000000000000000e+00,8.162230469810286203e-11,0.000000000000000000e+00 +3.960714520588408050e+01,2.719399999999999977e+02,0.000000000000000000e+00,8.648118681311556699e+00,0.000000000000000000e+00,-1.000000009945464230e+00,0.000000000000000000e+00,-6.734380212449681082e-10,0.000000000000000000e+00 +3.960830152674049742e+01,2.719499999999999886e+02,0.000000000000000000e+00,8.646962360443636086e+00,0.000000000000000000e+00,-1.000000009946242940e+00,0.000000000000000000e+00,3.573141105836087889e-10,0.000000000000000000e+00 +3.960945800222670243e+01,2.719599999999999795e+02,0.000000000000000000e+00,8.645805884945927389e+00,0.000000000000000000e+00,-1.000000009945829715e+00,0.000000000000000000e+00,5.455942436730937957e-10,0.000000000000000000e+00 +3.961061463240474012e+01,2.719700000000000273e+02,0.000000000000000000e+00,8.644649254756384238e+00,0.000000000000000000e+00,-1.000000009945198665e+00,0.000000000000000000e+00,-1.406799885208743521e-09,0.000000000000000000e+00 +3.961177141733670481e+01,2.719800000000000182e+02,0.000000000000000000e+00,8.643492469812917633e+00,0.000000000000000000e+00,-1.000000009946826030e+00,0.000000000000000000e+00,1.167282297518438553e-09,0.000000000000000000e+00 +3.961292835708471927e+01,2.719900000000000091e+02,0.000000000000000000e+00,8.642335530053394166e+00,0.000000000000000000e+00,-1.000000009945475554e+00,0.000000000000000000e+00,3.317923298654061723e-10,0.000000000000000000e+00 +3.961408545171096307e+01,2.720000000000000000e+02,0.000000000000000000e+00,8.641178435415644898e+00,0.000000000000000000e+00,-1.000000009945091639e+00,0.000000000000000000e+00,-1.227217822317571516e-09,0.000000000000000000e+00 +3.961524270127764424e+01,2.720099999999999909e+02,0.000000000000000000e+00,8.640021185837454709e+00,0.000000000000000000e+00,-1.000000009946511836e+00,0.000000000000000000e+00,4.968837535050731046e-10,0.000000000000000000e+00 +3.961640010584702054e+01,2.720199999999999818e+02,0.000000000000000000e+00,8.638863781256565844e+00,0.000000000000000000e+00,-1.000000009945936741e+00,0.000000000000000000e+00,2.280755370323918544e-10,0.000000000000000000e+00 +3.961755766548139235e+01,2.720300000000000296e+02,0.000000000000000000e+00,8.637706221610683244e+00,0.000000000000000000e+00,-1.000000009945672730e+00,0.000000000000000000e+00,-6.766548998858310282e-10,0.000000000000000000e+00 +3.961871538024309558e+01,2.720400000000000205e+02,0.000000000000000000e+00,8.636548506837467443e+00,0.000000000000000000e+00,-1.000000009946456103e+00,0.000000000000000000e+00,4.615901495687642786e-10,0.000000000000000000e+00 +3.961987325019450878e+01,2.720500000000000114e+02,0.000000000000000000e+00,8.635390636874536341e+00,0.000000000000000000e+00,-1.000000009945921642e+00,0.000000000000000000e+00,-3.033393089498907343e-10,0.000000000000000000e+00 +3.962103127539806025e+01,2.720600000000000023e+02,0.000000000000000000e+00,8.634232611659468759e+00,0.000000000000000000e+00,-1.000000009946272916e+00,0.000000000000000000e+00,1.032403998153213719e-09,0.000000000000000000e+00 +3.962218945591621377e+01,2.720699999999999932e+02,0.000000000000000000e+00,8.633074431129799109e+00,0.000000000000000000e+00,-1.000000009945077206e+00,0.000000000000000000e+00,-2.122997318493580713e-09,0.000000000000000000e+00 +3.962334779181146871e+01,2.720799999999999841e+02,0.000000000000000000e+00,8.631916095223022722e+00,0.000000000000000000e+00,-1.000000009947536350e+00,0.000000000000000000e+00,2.175037568909817827e-09,0.000000000000000000e+00 +3.962450628314638124e+01,2.720900000000000318e+02,0.000000000000000000e+00,8.630757603876586970e+00,0.000000000000000000e+00,-1.000000009945016588e+00,0.000000000000000000e+00,-1.927911641330625563e-09,0.000000000000000000e+00 +3.962566492998353596e+01,2.721000000000000227e+02,0.000000000000000000e+00,8.629598957027907247e+00,0.000000000000000000e+00,-1.000000009947250357e+00,0.000000000000000000e+00,1.477931038785934363e-09,0.000000000000000000e+00 +3.962682373238556721e+01,2.721100000000000136e+02,0.000000000000000000e+00,8.628440154614345659e+00,0.000000000000000000e+00,-1.000000009945537727e+00,0.000000000000000000e+00,-8.088923826928110445e-10,0.000000000000000000e+00 +3.962798269041515198e+01,2.721200000000000045e+02,0.000000000000000000e+00,8.627281196573232336e+00,0.000000000000000000e+00,-1.000000009946475199e+00,0.000000000000000000e+00,5.007486214090846033e-10,0.000000000000000000e+00 +3.962914180413500986e+01,2.721299999999999955e+02,0.000000000000000000e+00,8.626122082841847671e+00,0.000000000000000000e+00,-1.000000009945894774e+00,0.000000000000000000e+00,1.465268660488575236e-10,0.000000000000000000e+00 +3.963030107360789600e+01,2.721399999999999864e+02,0.000000000000000000e+00,8.624962813357434754e+00,0.000000000000000000e+00,-1.000000009945724910e+00,0.000000000000000000e+00,-5.195738087024608238e-10,0.000000000000000000e+00 +3.963146049889660816e+01,2.721499999999999773e+02,0.000000000000000000e+00,8.623803388057192265e+00,0.000000000000000000e+00,-1.000000009946327317e+00,0.000000000000000000e+00,-1.462959928416761657e-10,0.000000000000000000e+00 +3.963262008006399384e+01,2.721600000000000250e+02,0.000000000000000000e+00,8.622643806878276251e+00,0.000000000000000000e+00,-1.000000009946496959e+00,0.000000000000000000e+00,-2.661310037135500882e-11,0.000000000000000000e+00 +3.963377981717293608e+01,2.721700000000000159e+02,0.000000000000000000e+00,8.621484069757801905e+00,0.000000000000000000e+00,-1.000000009946527824e+00,0.000000000000000000e+00,-1.290274612268218361e-10,0.000000000000000000e+00 +3.963493971028636054e+01,2.721800000000000068e+02,0.000000000000000000e+00,8.620324176632841784e+00,0.000000000000000000e+00,-1.000000009946677482e+00,0.000000000000000000e+00,8.944572832937428423e-10,0.000000000000000000e+00 +3.963609975946723551e+01,2.721899999999999977e+02,0.000000000000000000e+00,8.619164127440425816e+00,0.000000000000000000e+00,-1.000000009945639867e+00,0.000000000000000000e+00,-8.851504882259490488e-10,0.000000000000000000e+00 +3.963725996477857905e+01,2.721999999999999886e+02,0.000000000000000000e+00,8.618003922117543070e+00,0.000000000000000000e+00,-1.000000009946666824e+00,0.000000000000000000e+00,-1.588272459187036901e-10,0.000000000000000000e+00 +3.963842032628344469e+01,2.722099999999999795e+02,0.000000000000000000e+00,8.616843560601136431e+00,0.000000000000000000e+00,-1.000000009946851121e+00,0.000000000000000000e+00,4.624503199484696145e-10,0.000000000000000000e+00 +3.963958084404492865e+01,2.722200000000000273e+02,0.000000000000000000e+00,8.615683042828109706e+00,0.000000000000000000e+00,-1.000000009946314439e+00,0.000000000000000000e+00,-3.089601488907555883e-10,0.000000000000000000e+00 +3.964074151812616975e+01,2.722300000000000182e+02,0.000000000000000000e+00,8.614522368735324065e+00,0.000000000000000000e+00,-1.000000009946673041e+00,0.000000000000000000e+00,1.931936298143516374e-10,0.000000000000000000e+00 +3.964190234859034945e+01,2.722400000000000091e+02,0.000000000000000000e+00,8.613361538259596273e+00,0.000000000000000000e+00,-1.000000009946448776e+00,0.000000000000000000e+00,6.806767086568110895e-10,0.000000000000000000e+00 +3.964306333550069894e+01,2.722500000000000000e+02,0.000000000000000000e+00,8.612200551337702237e+00,0.000000000000000000e+00,-1.000000009945658519e+00,0.000000000000000000e+00,-1.452195052805882751e-09,0.000000000000000000e+00 +3.964422447892047785e+01,2.722599999999999909e+02,0.000000000000000000e+00,8.611039407906375232e+00,0.000000000000000000e+00,-1.000000009947344726e+00,0.000000000000000000e+00,1.730200329722482045e-09,0.000000000000000000e+00 +3.964538577891299553e+01,2.722699999999999818e+02,0.000000000000000000e+00,8.609878107902302347e+00,0.000000000000000000e+00,-1.000000009945335444e+00,0.000000000000000000e+00,-1.599010268515829124e-09,0.000000000000000000e+00 +3.964654723554161109e+01,2.722800000000000296e+02,0.000000000000000000e+00,8.608716651262135144e+00,0.000000000000000000e+00,-1.000000009947192625e+00,0.000000000000000000e+00,4.446193398085657641e-10,0.000000000000000000e+00 +3.964770884886971913e+01,2.722900000000000205e+02,0.000000000000000000e+00,8.607555037922473673e+00,0.000000000000000000e+00,-1.000000009946676149e+00,0.000000000000000000e+00,-1.070306248348936801e-11,0.000000000000000000e+00 +3.964887061896075693e+01,2.723000000000000114e+02,0.000000000000000000e+00,8.606393267819882453e+00,0.000000000000000000e+00,-1.000000009946688584e+00,0.000000000000000000e+00,-3.009830028947461129e-10,0.000000000000000000e+00 +3.965003254587820436e+01,2.723100000000000023e+02,0.000000000000000000e+00,8.605231340890879821e+00,0.000000000000000000e+00,-1.000000009947038304e+00,0.000000000000000000e+00,9.186862889754754708e-10,0.000000000000000000e+00 +3.965119462968558395e+01,2.723199999999999932e+02,0.000000000000000000e+00,8.604069257071941479e+00,0.000000000000000000e+00,-1.000000009945970714e+00,0.000000000000000000e+00,-2.680413483984608259e-10,0.000000000000000000e+00 +3.965235687044646085e+01,2.723299999999999841e+02,0.000000000000000000e+00,8.602907016299502274e+00,0.000000000000000000e+00,-1.000000009946282242e+00,0.000000000000000000e+00,-1.199241822476621693e-09,0.000000000000000000e+00 +3.965351926822444995e+01,2.723400000000000318e+02,0.000000000000000000e+00,8.601744618509950868e+00,0.000000000000000000e+00,-1.000000009947676238e+00,0.000000000000000000e+00,7.834700982451496845e-10,0.000000000000000000e+00 +3.965468182308320166e+01,2.723500000000000227e+02,0.000000000000000000e+00,8.600582063639633290e+00,0.000000000000000000e+00,-1.000000009946765411e+00,0.000000000000000000e+00,4.508832030459413710e-10,0.000000000000000000e+00 +3.965584453508641616e+01,2.723600000000000136e+02,0.000000000000000000e+00,8.599419351624856489e+00,0.000000000000000000e+00,-1.000000009946241164e+00,0.000000000000000000e+00,-8.500892202042167768e-10,0.000000000000000000e+00 +3.965700740429782201e+01,2.723700000000000045e+02,0.000000000000000000e+00,8.598256482401881229e+00,0.000000000000000000e+00,-1.000000009947229707e+00,0.000000000000000000e+00,8.509288638617370117e-10,0.000000000000000000e+00 +3.965817043078121173e+01,2.723799999999999955e+02,0.000000000000000000e+00,8.597093455906923865e+00,0.000000000000000000e+00,-1.000000009946240054e+00,0.000000000000000000e+00,-9.827213956150348458e-10,0.000000000000000000e+00 +3.965933361460040629e+01,2.723899999999999864e+02,0.000000000000000000e+00,8.595930272076161671e+00,0.000000000000000000e+00,-1.000000009947383139e+00,0.000000000000000000e+00,2.443110324769623534e-10,0.000000000000000000e+00 +3.966049695581926926e+01,2.723999999999999773e+02,0.000000000000000000e+00,8.594766930845723962e+00,0.000000000000000000e+00,-1.000000009947098922e+00,0.000000000000000000e+00,6.236721878939161799e-10,0.000000000000000000e+00 +3.966166045450172106e+01,2.724100000000000250e+02,0.000000000000000000e+00,8.593603432151700972e+00,0.000000000000000000e+00,-1.000000009946373281e+00,0.000000000000000000e+00,1.858551033721179928e-10,0.000000000000000000e+00 +3.966282411071171055e+01,2.724200000000000159e+02,0.000000000000000000e+00,8.592439775930138524e+00,0.000000000000000000e+00,-1.000000009946157009e+00,0.000000000000000000e+00,-1.037137101133206114e-09,0.000000000000000000e+00 +3.966398792451323629e+01,2.724300000000000068e+02,0.000000000000000000e+00,8.591275962117038034e+00,0.000000000000000000e+00,-1.000000009947364044e+00,0.000000000000000000e+00,9.177687199933852551e-10,0.000000000000000000e+00 +3.966515189597033952e+01,2.724399999999999977e+02,0.000000000000000000e+00,8.590111990648356510e+00,0.000000000000000000e+00,-1.000000009946295787e+00,0.000000000000000000e+00,-4.745581401784517574e-10,0.000000000000000000e+00 +3.966631602514710409e+01,2.724499999999999886e+02,0.000000000000000000e+00,8.588947861460011879e+00,0.000000000000000000e+00,-1.000000009946848234e+00,0.000000000000000000e+00,-1.249932696989673316e-09,0.000000000000000000e+00 +3.966748031210766356e+01,2.724599999999999795e+02,0.000000000000000000e+00,8.587783574487874105e+00,0.000000000000000000e+00,-1.000000009948303514e+00,0.000000000000000000e+00,1.241182341046122427e-09,0.000000000000000000e+00 +3.966864475691617997e+01,2.724700000000000273e+02,0.000000000000000000e+00,8.586619129667770522e+00,0.000000000000000000e+00,-1.000000009946858226e+00,0.000000000000000000e+00,4.781784030340300415e-10,0.000000000000000000e+00 +3.966980935963687926e+01,2.724800000000000182e+02,0.000000000000000000e+00,8.585454526935489383e+00,0.000000000000000000e+00,-1.000000009946301338e+00,0.000000000000000000e+00,-8.862639088330202543e-10,0.000000000000000000e+00 +3.967097412033401582e+01,2.724900000000000091e+02,0.000000000000000000e+00,8.584289766226770979e+00,0.000000000000000000e+00,-1.000000009947333623e+00,0.000000000000000000e+00,-2.037615800553375916e-10,0.000000000000000000e+00 +3.967213903907188666e+01,2.725000000000000000e+02,0.000000000000000000e+00,8.583124847477311192e+00,0.000000000000000000e+00,-1.000000009947570989e+00,0.000000000000000000e+00,1.245464195737438683e-09,0.000000000000000000e+00 +3.967330411591484562e+01,2.725099999999999909e+02,0.000000000000000000e+00,8.581959770622765049e+00,0.000000000000000000e+00,-1.000000009946119928e+00,0.000000000000000000e+00,-1.741126496849880628e-09,0.000000000000000000e+00 +3.967446935092727500e+01,2.725199999999999818e+02,0.000000000000000000e+00,8.580794535598744943e+00,0.000000000000000000e+00,-1.000000009948148749e+00,0.000000000000000000e+00,1.334104456646443729e-09,0.000000000000000000e+00 +3.967563474417361391e+01,2.725300000000000296e+02,0.000000000000000000e+00,8.579629142340813530e+00,0.000000000000000000e+00,-1.000000009946593993e+00,0.000000000000000000e+00,3.600564086664124151e-11,0.000000000000000000e+00 +3.967680029571833700e+01,2.725400000000000205e+02,0.000000000000000000e+00,8.578463590784497939e+00,0.000000000000000000e+00,-1.000000009946552026e+00,0.000000000000000000e+00,-3.725791849168320129e-10,0.000000000000000000e+00 +3.967796600562596154e+01,2.725500000000000114e+02,0.000000000000000000e+00,8.577297880865275559e+00,0.000000000000000000e+00,-1.000000009946986346e+00,0.000000000000000000e+00,-1.167484686919276641e-09,0.000000000000000000e+00 +3.967913187396106167e+01,2.725600000000000023e+02,0.000000000000000000e+00,8.576132012518581149e+00,0.000000000000000000e+00,-1.000000009948347479e+00,0.000000000000000000e+00,1.600740999690568384e-09,0.000000000000000000e+00 +3.968029790078823993e+01,2.725699999999999932e+02,0.000000000000000000e+00,8.574965985679805058e+00,0.000000000000000000e+00,-1.000000009946480972e+00,0.000000000000000000e+00,-1.183161094320579585e-09,0.000000000000000000e+00 +3.968146408617214860e+01,2.725799999999999841e+02,0.000000000000000000e+00,8.573799800284298556e+00,0.000000000000000000e+00,-1.000000009947860757e+00,0.000000000000000000e+00,9.636863438142545435e-10,0.000000000000000000e+00 +3.968263043017748259e+01,2.725900000000000318e+02,0.000000000000000000e+00,8.572633456267361396e+00,0.000000000000000000e+00,-1.000000009946736768e+00,0.000000000000000000e+00,-1.071484095345831029e-09,0.000000000000000000e+00 +3.968379693286898657e+01,2.726000000000000227e+02,0.000000000000000000e+00,8.571466953564256031e+00,0.000000000000000000e+00,-1.000000009947986657e+00,0.000000000000000000e+00,5.772551163776371371e-10,0.000000000000000000e+00 +3.968496359431144072e+01,2.726100000000000136e+02,0.000000000000000000e+00,8.570300292110195173e+00,0.000000000000000000e+00,-1.000000009947313195e+00,0.000000000000000000e+00,7.181880268808145008e-10,0.000000000000000000e+00 +3.968613041456967494e+01,2.726200000000000045e+02,0.000000000000000000e+00,8.569133471840352456e+00,0.000000000000000000e+00,-1.000000009946475199e+00,0.000000000000000000e+00,-6.166747464283379943e-10,0.000000000000000000e+00 +3.968729739370856180e+01,2.726299999999999955e+02,0.000000000000000000e+00,8.567966492689855329e+00,0.000000000000000000e+00,-1.000000009947194846e+00,0.000000000000000000e+00,-7.862911547259969981e-10,0.000000000000000000e+00 +3.968846453179302358e+01,2.726399999999999864e+02,0.000000000000000000e+00,8.566799354593785054e+00,0.000000000000000000e+00,-1.000000009948112556e+00,0.000000000000000000e+00,1.541932705258757629e-09,0.000000000000000000e+00 +3.968963182888801811e+01,2.726499999999999773e+02,0.000000000000000000e+00,8.565632057487180262e+00,0.000000000000000000e+00,-1.000000009946312662e+00,0.000000000000000000e+00,-1.422279994353939322e-09,0.000000000000000000e+00 +3.969079928505854582e+01,2.726600000000000250e+02,0.000000000000000000e+00,8.564464601305038727e+00,0.000000000000000000e+00,-1.000000009947973112e+00,0.000000000000000000e+00,7.800745337361473443e-10,0.000000000000000000e+00 +3.969196690036966402e+01,2.726700000000000159e+02,0.000000000000000000e+00,8.563296985982306708e+00,0.000000000000000000e+00,-1.000000009947062285e+00,0.000000000000000000e+00,-9.427309256904220102e-10,0.000000000000000000e+00 +3.969313467488645841e+01,2.726800000000000068e+02,0.000000000000000000e+00,8.562129211453893163e+00,0.000000000000000000e+00,-1.000000009948163182e+00,0.000000000000000000e+00,1.257246761706567300e-09,0.000000000000000000e+00 +3.969430260867407867e+01,2.726899999999999977e+02,0.000000000000000000e+00,8.560961277654657309e+00,0.000000000000000000e+00,-1.000000009946694801e+00,0.000000000000000000e+00,-1.705501175466696663e-09,0.000000000000000000e+00 +3.969547070179769577e+01,2.726999999999999886e+02,0.000000000000000000e+00,8.559793184519419285e+00,0.000000000000000000e+00,-1.000000009948686985e+00,0.000000000000000000e+00,1.918522061318018197e-09,0.000000000000000000e+00 +3.969663895432254463e+01,2.727099999999999795e+02,0.000000000000000000e+00,8.558624931982947714e+00,0.000000000000000000e+00,-1.000000009946445667e+00,0.000000000000000000e+00,-8.570788177673781269e-10,0.000000000000000000e+00 +3.969780736631389573e+01,2.727200000000000273e+02,0.000000000000000000e+00,8.557456519979975695e+00,0.000000000000000000e+00,-1.000000009947447088e+00,0.000000000000000000e+00,-8.894541541077109317e-10,0.000000000000000000e+00 +3.969897593783706213e+01,2.727300000000000182e+02,0.000000000000000000e+00,8.556287948445183034e+00,0.000000000000000000e+00,-1.000000009948486479e+00,0.000000000000000000e+00,5.492546075503985029e-10,0.000000000000000000e+00 +3.970014466895740668e+01,2.727400000000000091e+02,0.000000000000000000e+00,8.555119217313208679e+00,0.000000000000000000e+00,-1.000000009947844548e+00,0.000000000000000000e+00,8.886413315998528912e-10,0.000000000000000000e+00 +3.970131355974034193e+01,2.727500000000000000e+02,0.000000000000000000e+00,8.553950326518648950e+00,0.000000000000000000e+00,-1.000000009946805823e+00,0.000000000000000000e+00,-1.138095625663465522e-09,0.000000000000000000e+00 +3.970248261025130887e+01,2.727599999999999909e+02,0.000000000000000000e+00,8.552781275996053978e+00,0.000000000000000000e+00,-1.000000009948136315e+00,0.000000000000000000e+00,9.987361322508379940e-10,0.000000000000000000e+00 +3.970365182055580533e+01,2.727699999999999818e+02,0.000000000000000000e+00,8.551612065679925934e+00,0.000000000000000000e+00,-1.000000009946968582e+00,0.000000000000000000e+00,-4.667347054941042112e-10,0.000000000000000000e+00 +3.970482119071937177e+01,2.727800000000000296e+02,0.000000000000000000e+00,8.550442695504727908e+00,0.000000000000000000e+00,-1.000000009947514368e+00,0.000000000000000000e+00,-3.058611848784779365e-10,0.000000000000000000e+00 +3.970599072080759129e+01,2.727900000000000205e+02,0.000000000000000000e+00,8.549273165404873254e+00,0.000000000000000000e+00,-1.000000009947872082e+00,0.000000000000000000e+00,2.133711660227150743e-10,0.000000000000000000e+00 +3.970716041088609671e+01,2.728000000000000114e+02,0.000000000000000000e+00,8.548103475314732691e+00,0.000000000000000000e+00,-1.000000009947622504e+00,0.000000000000000000e+00,-1.759501860125025131e-10,0.000000000000000000e+00 +3.970833026102055641e+01,2.728100000000000023e+02,0.000000000000000000e+00,8.546933625168632531e+00,0.000000000000000000e+00,-1.000000009947828339e+00,0.000000000000000000e+00,-1.442328380091986354e-10,0.000000000000000000e+00 +3.970950027127669557e+01,2.728199999999999932e+02,0.000000000000000000e+00,8.545763614900852900e+00,0.000000000000000000e+00,-1.000000009947997093e+00,0.000000000000000000e+00,3.400392944530834394e-10,0.000000000000000000e+00 +3.971067044172027494e+01,2.728299999999999841e+02,0.000000000000000000e+00,8.544593444445629515e+00,0.000000000000000000e+00,-1.000000009947599189e+00,0.000000000000000000e+00,1.062477290345487677e-11,0.000000000000000000e+00 +3.971184077241711208e+01,2.728400000000000318e+02,0.000000000000000000e+00,8.543423113737153685e+00,0.000000000000000000e+00,-1.000000009947586754e+00,0.000000000000000000e+00,-1.099513377394346353e-09,0.000000000000000000e+00 +3.971301126343305299e+01,2.728500000000000227e+02,0.000000000000000000e+00,8.542252622709570531e+00,0.000000000000000000e+00,-1.000000009948873725e+00,0.000000000000000000e+00,9.296026194127638689e-10,0.000000000000000000e+00 +3.971418191483400051e+01,2.728600000000000136e+02,0.000000000000000000e+00,8.541081971296978992e+00,0.000000000000000000e+00,-1.000000009947785484e+00,0.000000000000000000e+00,-3.516113172793344392e-10,0.000000000000000000e+00 +3.971535272668589300e+01,2.728700000000000045e+02,0.000000000000000000e+00,8.539911159433437149e+00,0.000000000000000000e+00,-1.000000009948197155e+00,0.000000000000000000e+00,2.732483568466910834e-10,0.000000000000000000e+00 +3.971652369905472568e+01,2.728799999999999955e+02,0.000000000000000000e+00,8.538740187052953345e+00,0.000000000000000000e+00,-1.000000009947877189e+00,0.000000000000000000e+00,2.428751906172717654e-10,0.000000000000000000e+00 +3.971769483200653639e+01,2.728899999999999864e+02,0.000000000000000000e+00,8.537569054089493292e+00,0.000000000000000000e+00,-1.000000009947592750e+00,0.000000000000000000e+00,-4.089070515449718912e-10,0.000000000000000000e+00 +3.971886612560739849e+01,2.728999999999999773e+02,0.000000000000000000e+00,8.536397760476976515e+00,0.000000000000000000e+00,-1.000000009948071700e+00,0.000000000000000000e+00,9.380636826561551358e-10,0.000000000000000000e+00 +3.972003757992344219e+01,2.729100000000000250e+02,0.000000000000000000e+00,8.535226306149276354e+00,0.000000000000000000e+00,-1.000000009946972801e+00,0.000000000000000000e+00,-8.621269135627564272e-10,0.000000000000000000e+00 +3.972120919502084035e+01,2.729200000000000159e+02,0.000000000000000000e+00,8.534054691040223517e+00,0.000000000000000000e+00,-1.000000009947982882e+00,0.000000000000000000e+00,-6.003172461625055519e-10,0.000000000000000000e+00 +3.972238097096580844e+01,2.729300000000000068e+02,0.000000000000000000e+00,8.532882915083598974e+00,0.000000000000000000e+00,-1.000000009948686319e+00,0.000000000000000000e+00,4.605968576891379520e-10,0.000000000000000000e+00 +3.972355290782460457e+01,2.729399999999999977e+02,0.000000000000000000e+00,8.531710978213141061e+00,0.000000000000000000e+00,-1.000000009948146529e+00,0.000000000000000000e+00,-2.349081287929942442e-10,0.000000000000000000e+00 +3.972472500566354370e+01,2.729499999999999886e+02,0.000000000000000000e+00,8.530538880362543708e+00,0.000000000000000000e+00,-1.000000009948421864e+00,0.000000000000000000e+00,1.224953359619908306e-09,0.000000000000000000e+00 +3.972589726454896919e+01,2.729599999999999795e+02,0.000000000000000000e+00,8.529366621465452880e+00,0.000000000000000000e+00,-1.000000009946985902e+00,0.000000000000000000e+00,-1.591254647016542848e-09,0.000000000000000000e+00 +3.972706968454728838e+01,2.729700000000000273e+02,0.000000000000000000e+00,8.528194201455471912e+00,0.000000000000000000e+00,-1.000000009948851520e+00,0.000000000000000000e+00,3.957706580468997181e-10,0.000000000000000000e+00 +3.972824226572494410e+01,2.729800000000000182e+02,0.000000000000000000e+00,8.527021620266152624e+00,0.000000000000000000e+00,-1.000000009948387447e+00,0.000000000000000000e+00,7.558369554261919158e-10,0.000000000000000000e+00 +3.972941500814842186e+01,2.729900000000000091e+02,0.000000000000000000e+00,8.525848877831007755e+00,0.000000000000000000e+00,-1.000000009947501045e+00,0.000000000000000000e+00,-4.780124832964481974e-10,0.000000000000000000e+00 +3.973058791188425687e+01,2.730000000000000000e+02,0.000000000000000000e+00,8.524675974083502084e+00,0.000000000000000000e+00,-1.000000009948061708e+00,0.000000000000000000e+00,-6.899468535500467170e-10,0.000000000000000000e+00 +3.973176097699903409e+01,2.730099999999999909e+02,0.000000000000000000e+00,8.523502908957052426e+00,0.000000000000000000e+00,-1.000000009948871060e+00,0.000000000000000000e+00,1.441402511895104718e-09,0.000000000000000000e+00 +3.973293420355938110e+01,2.730199999999999818e+02,0.000000000000000000e+00,8.522329682385031191e+00,0.000000000000000000e+00,-1.000000009947179969e+00,0.000000000000000000e+00,-1.795071188739436730e-09,0.000000000000000000e+00 +3.973410759163197525e+01,2.730300000000000296e+02,0.000000000000000000e+00,8.521156294300768153e+00,0.000000000000000000e+00,-1.000000009949286284e+00,0.000000000000000000e+00,1.246310976878088053e-09,0.000000000000000000e+00 +3.973528114128352939e+01,2.730400000000000205e+02,0.000000000000000000e+00,8.519982744637539795e+00,0.000000000000000000e+00,-1.000000009947823676e+00,0.000000000000000000e+00,2.758268023246642234e-10,0.000000000000000000e+00 +3.973645485258080612e+01,2.730500000000000114e+02,0.000000000000000000e+00,8.518809033328585301e+00,0.000000000000000000e+00,-1.000000009947499935e+00,0.000000000000000000e+00,-8.029653463577057343e-10,0.000000000000000000e+00 +3.973762872559062487e+01,2.730600000000000023e+02,0.000000000000000000e+00,8.517635160307092335e+00,0.000000000000000000e+00,-1.000000009948442514e+00,0.000000000000000000e+00,-6.689510181791243659e-10,0.000000000000000000e+00 +3.973880276037983350e+01,2.730699999999999932e+02,0.000000000000000000e+00,8.516461125506202379e+00,0.000000000000000000e+00,-1.000000009949227886e+00,0.000000000000000000e+00,7.085705319658628109e-10,0.000000000000000000e+00 +3.973997695701534383e+01,2.730799999999999841e+02,0.000000000000000000e+00,8.515286928859012505e+00,0.000000000000000000e+00,-1.000000009948395885e+00,0.000000000000000000e+00,7.848600889580339844e-10,0.000000000000000000e+00 +3.974115131556409608e+01,2.730900000000000318e+02,0.000000000000000000e+00,8.514112570298575378e+00,0.000000000000000000e+00,-1.000000009947474178e+00,0.000000000000000000e+00,-4.062711925450299256e-10,0.000000000000000000e+00 +3.974232583609309444e+01,2.731000000000000227e+02,0.000000000000000000e+00,8.512938049757895698e+00,0.000000000000000000e+00,-1.000000009947951352e+00,0.000000000000000000e+00,-2.568852421807262048e-10,0.000000000000000000e+00 +3.974350051866937150e+01,2.731100000000000136e+02,0.000000000000000000e+00,8.511763367169930206e+00,0.000000000000000000e+00,-1.000000009948253110e+00,0.000000000000000000e+00,-1.309574856803062940e-09,0.000000000000000000e+00 +3.974467536336002382e+01,2.731200000000000045e+02,0.000000000000000000e+00,8.510588522467591233e+00,0.000000000000000000e+00,-1.000000009949791657e+00,0.000000000000000000e+00,1.615152458479107623e-09,0.000000000000000000e+00 +3.974585037023218348e+01,2.731299999999999955e+02,0.000000000000000000e+00,8.509413515583743148e+00,0.000000000000000000e+00,-1.000000009947893842e+00,0.000000000000000000e+00,-4.572515856551863711e-10,0.000000000000000000e+00 +3.974702553935302518e+01,2.731399999999999864e+02,0.000000000000000000e+00,8.508238346451209466e+00,0.000000000000000000e+00,-1.000000009948431190e+00,0.000000000000000000e+00,2.251936439316946142e-10,0.000000000000000000e+00 +3.974820087078978048e+01,2.731500000000000341e+02,0.000000000000000000e+00,8.507063015002760409e+00,0.000000000000000000e+00,-1.000000009948166513e+00,0.000000000000000000e+00,-1.633939540996418264e-10,0.000000000000000000e+00 +3.974937636460972357e+01,2.731600000000000250e+02,0.000000000000000000e+00,8.505887521171123566e+00,0.000000000000000000e+00,-1.000000009948358581e+00,0.000000000000000000e+00,-3.046451218324591078e-10,0.000000000000000000e+00 +3.975055202088017126e+01,2.731700000000000159e+02,0.000000000000000000e+00,8.504711864888978567e+00,0.000000000000000000e+00,-1.000000009948716739e+00,0.000000000000000000e+00,-1.667479615873760917e-10,0.000000000000000000e+00 +3.975172783966849011e+01,2.731800000000000068e+02,0.000000000000000000e+00,8.503536046088958855e+00,0.000000000000000000e+00,-1.000000009948912805e+00,0.000000000000000000e+00,2.832246452729378510e-10,0.000000000000000000e+00 +3.975290382104209641e+01,2.731899999999999977e+02,0.000000000000000000e+00,8.502360064703651688e+00,0.000000000000000000e+00,-1.000000009948579738e+00,0.000000000000000000e+00,-2.069141886921244301e-10,0.000000000000000000e+00 +3.975407996506844910e+01,2.731999999999999886e+02,0.000000000000000000e+00,8.501183920665598137e+00,0.000000000000000000e+00,-1.000000009948823099e+00,0.000000000000000000e+00,9.645850748052622007e-10,0.000000000000000000e+00 +3.975525627181504973e+01,2.732099999999999795e+02,0.000000000000000000e+00,8.500007613907291315e+00,0.000000000000000000e+00,-1.000000009947688451e+00,0.000000000000000000e+00,-1.305312583749947443e-09,0.000000000000000000e+00 +3.975643274134945671e+01,2.732200000000000273e+02,0.000000000000000000e+00,8.498831144361179923e+00,0.000000000000000000e+00,-1.000000009949224111e+00,0.000000000000000000e+00,7.176715853153396468e-10,0.000000000000000000e+00 +3.975760937373927106e+01,2.732300000000000182e+02,0.000000000000000000e+00,8.497654511959661150e+00,0.000000000000000000e+00,-1.000000009948379676e+00,0.000000000000000000e+00,-6.336070302017780455e-10,0.000000000000000000e+00 +3.975878616905213647e+01,2.732400000000000091e+02,0.000000000000000000e+00,8.496477716635091326e+00,0.000000000000000000e+00,-1.000000009949125301e+00,0.000000000000000000e+00,1.087811852021179597e-09,0.000000000000000000e+00 +3.975996312735574634e+01,2.732500000000000000e+02,0.000000000000000000e+00,8.495300758319775269e+00,0.000000000000000000e+00,-1.000000009947844992e+00,0.000000000000000000e+00,-4.970494571082142447e-10,0.000000000000000000e+00 +3.976114024871783670e+01,2.732599999999999909e+02,0.000000000000000000e+00,8.494123636945975164e+00,0.000000000000000000e+00,-1.000000009948430080e+00,0.000000000000000000e+00,-2.263289192580047012e-10,0.000000000000000000e+00 +3.976231753320620044e+01,2.732699999999999818e+02,0.000000000000000000e+00,8.492946352445901681e+00,0.000000000000000000e+00,-1.000000009948696533e+00,0.000000000000000000e+00,-6.311815834799990811e-10,0.000000000000000000e+00 +3.976349498088866596e+01,2.732800000000000296e+02,0.000000000000000000e+00,8.491768904751721081e+00,0.000000000000000000e+00,-1.000000009949439717e+00,0.000000000000000000e+00,8.833808644306676424e-10,0.000000000000000000e+00 +3.976467259183311853e+01,2.732900000000000205e+02,0.000000000000000000e+00,8.490591293795551664e+00,0.000000000000000000e+00,-1.000000009948399438e+00,0.000000000000000000e+00,-7.735344826552280701e-10,0.000000000000000000e+00 +3.976585036610748602e+01,2.733000000000000114e+02,0.000000000000000000e+00,8.489413519509467321e+00,0.000000000000000000e+00,-1.000000009949310487e+00,0.000000000000000000e+00,8.352561154933201059e-10,0.000000000000000000e+00 +3.976702830377974607e+01,2.733100000000000023e+02,0.000000000000000000e+00,8.488235581825490428e+00,0.000000000000000000e+00,-1.000000009948326607e+00,0.000000000000000000e+00,-6.596684206969619639e-10,0.000000000000000000e+00 +3.976820640491791892e+01,2.733199999999999932e+02,0.000000000000000000e+00,8.487057480675600729e+00,0.000000000000000000e+00,-1.000000009949103763e+00,0.000000000000000000e+00,-1.042131444875772955e-10,0.000000000000000000e+00 +3.976938466959006746e+01,2.733299999999999841e+02,0.000000000000000000e+00,8.485879215991726454e+00,0.000000000000000000e+00,-1.000000009949226554e+00,0.000000000000000000e+00,-2.600256303179855823e-11,0.000000000000000000e+00 +3.977056309786431854e+01,2.733400000000000318e+02,0.000000000000000000e+00,8.484700787705751424e+00,0.000000000000000000e+00,-1.000000009949257196e+00,0.000000000000000000e+00,8.875439363649604773e-10,0.000000000000000000e+00 +3.977174168980883451e+01,2.733500000000000227e+02,0.000000000000000000e+00,8.483522195749511496e+00,0.000000000000000000e+00,-1.000000009948211144e+00,0.000000000000000000e+00,-1.165834514915558557e-09,0.000000000000000000e+00 +3.977292044549182037e+01,2.733600000000000136e+02,0.000000000000000000e+00,8.482343440054796346e+00,0.000000000000000000e+00,-1.000000009949585378e+00,0.000000000000000000e+00,1.516937554817439690e-09,0.000000000000000000e+00 +3.977409936498154508e+01,2.733700000000000045e+02,0.000000000000000000e+00,8.481164520553344133e+00,0.000000000000000000e+00,-1.000000009947797031e+00,0.000000000000000000e+00,-1.255715643090342734e-09,0.000000000000000000e+00 +3.977527844834630599e+01,2.733799999999999955e+02,0.000000000000000000e+00,8.479985437176852159e+00,0.000000000000000000e+00,-1.000000009949277624e+00,0.000000000000000000e+00,7.723799436320942515e-10,0.000000000000000000e+00 +3.977645769565446443e+01,2.733899999999999864e+02,0.000000000000000000e+00,8.478806189856962661e+00,0.000000000000000000e+00,-1.000000009948366797e+00,0.000000000000000000e+00,-1.308269586293509663e-09,0.000000000000000000e+00 +3.977763710697441724e+01,2.734000000000000341e+02,0.000000000000000000e+00,8.477626778525277018e+00,0.000000000000000000e+00,-1.000000009949909785e+00,0.000000000000000000e+00,1.475057485856280761e-09,0.000000000000000000e+00 +3.977881668237461099e+01,2.734100000000000250e+02,0.000000000000000000e+00,8.476447203113343321e+00,0.000000000000000000e+00,-1.000000009948169843e+00,0.000000000000000000e+00,-1.057767946155352118e-09,0.000000000000000000e+00 +3.977999642192354912e+01,2.734200000000000159e+02,0.000000000000000000e+00,8.475267463552668801e+00,0.000000000000000000e+00,-1.000000009949417734e+00,0.000000000000000000e+00,6.172590723097560594e-11,0.000000000000000000e+00 +3.978117632568977058e+01,2.734300000000000068e+02,0.000000000000000000e+00,8.474087559774705625e+00,0.000000000000000000e+00,-1.000000009949344904e+00,0.000000000000000000e+00,-2.376492910903905613e-10,0.000000000000000000e+00 +3.978235639374187116e+01,2.734399999999999977e+02,0.000000000000000000e+00,8.472907491710863326e+00,0.000000000000000000e+00,-1.000000009949625346e+00,0.000000000000000000e+00,6.281872381124780546e-10,0.000000000000000000e+00 +3.978353662614848929e+01,2.734499999999999886e+02,0.000000000000000000e+00,8.471727259292501699e+00,0.000000000000000000e+00,-1.000000009948883939e+00,0.000000000000000000e+00,1.429637012564888562e-10,0.000000000000000000e+00 +3.978471702297831314e+01,2.734599999999999795e+02,0.000000000000000000e+00,8.470546862450934356e+00,0.000000000000000000e+00,-1.000000009948715185e+00,0.000000000000000000e+00,-3.850077907027640931e-10,0.000000000000000000e+00 +3.978589758430008061e+01,2.734700000000000273e+02,0.000000000000000000e+00,8.469366301117425166e+00,0.000000000000000000e+00,-1.000000009949169710e+00,0.000000000000000000e+00,3.529843205995454886e-10,0.000000000000000000e+00 +3.978707831018256513e+01,2.734800000000000182e+02,0.000000000000000000e+00,8.468185575223190042e+00,0.000000000000000000e+00,-1.000000009948752933e+00,0.000000000000000000e+00,-1.588866107807528530e-10,0.000000000000000000e+00 +3.978825920069461120e+01,2.734900000000000091e+02,0.000000000000000000e+00,8.467004684699398709e+00,0.000000000000000000e+00,-1.000000009948940560e+00,0.000000000000000000e+00,-6.127091782256530361e-10,0.000000000000000000e+00 +3.978944025590509170e+01,2.735000000000000000e+02,0.000000000000000000e+00,8.465823629477171153e+00,0.000000000000000000e+00,-1.000000009949664204e+00,0.000000000000000000e+00,2.992626417370227097e-10,0.000000000000000000e+00 +3.979062147588292930e+01,2.735099999999999909e+02,0.000000000000000000e+00,8.464642409487579400e+00,0.000000000000000000e+00,-1.000000009949310709e+00,0.000000000000000000e+00,6.258828838222293984e-11,0.000000000000000000e+00 +3.979180286069710348e+01,2.735199999999999818e+02,0.000000000000000000e+00,8.463461024661649290e+00,0.000000000000000000e+00,-1.000000009949236768e+00,0.000000000000000000e+00,-1.447034711829935275e-11,0.000000000000000000e+00 +3.979298441041664347e+01,2.735300000000000296e+02,0.000000000000000000e+00,8.462279474930356926e+00,0.000000000000000000e+00,-1.000000009949253865e+00,0.000000000000000000e+00,1.010903884493548440e-10,0.000000000000000000e+00 +3.979416612511061402e+01,2.735400000000000205e+02,0.000000000000000000e+00,8.461097760224630449e+00,0.000000000000000000e+00,-1.000000009949134405e+00,0.000000000000000000e+00,-8.285248292459050938e-10,0.000000000000000000e+00 +3.979534800484813672e+01,2.735500000000000114e+02,0.000000000000000000e+00,8.459915880475350036e+00,0.000000000000000000e+00,-1.000000009950113622e+00,0.000000000000000000e+00,1.044997689338619736e-09,0.000000000000000000e+00 +3.979653004969837582e+01,2.735600000000000023e+02,0.000000000000000000e+00,8.458733835613346130e+00,0.000000000000000000e+00,-1.000000009948878388e+00,0.000000000000000000e+00,-6.015926529261316729e-10,0.000000000000000000e+00 +3.979771225973055238e+01,2.735699999999999932e+02,0.000000000000000000e+00,8.457551625569404763e+00,0.000000000000000000e+00,-1.000000009949589597e+00,0.000000000000000000e+00,6.217904731600286755e-10,0.000000000000000000e+00 +3.979889463501393720e+01,2.735799999999999841e+02,0.000000000000000000e+00,8.456369250274258675e+00,0.000000000000000000e+00,-1.000000009948854407e+00,0.000000000000000000e+00,-3.347923354821480681e-10,0.000000000000000000e+00 +3.980007717561783664e+01,2.735900000000000318e+02,0.000000000000000000e+00,8.455186709658596200e+00,0.000000000000000000e+00,-1.000000009949250313e+00,0.000000000000000000e+00,-8.947824671919429125e-10,0.000000000000000000e+00 +3.980125988161161388e+01,2.736000000000000227e+02,0.000000000000000000e+00,8.454004003653054156e+00,0.000000000000000000e+00,-1.000000009950308577e+00,0.000000000000000000e+00,1.513183495692677424e-09,0.000000000000000000e+00 +3.980244275306467472e+01,2.736100000000000136e+02,0.000000000000000000e+00,8.452821132188221398e+00,0.000000000000000000e+00,-1.000000009948518676e+00,0.000000000000000000e+00,-6.940788509897554050e-10,0.000000000000000000e+00 +3.980362579004648182e+01,2.736200000000000045e+02,0.000000000000000000e+00,8.451638095194642375e+00,0.000000000000000000e+00,-1.000000009949339796e+00,0.000000000000000000e+00,1.351181262108123671e-10,0.000000000000000000e+00 +3.980480899262654759e+01,2.736299999999999955e+02,0.000000000000000000e+00,8.450454892602806467e+00,0.000000000000000000e+00,-1.000000009949179924e+00,0.000000000000000000e+00,-1.042515571276796236e-09,0.000000000000000000e+00 +3.980599236087441994e+01,2.736399999999999864e+02,0.000000000000000000e+00,8.449271524343158646e+00,0.000000000000000000e+00,-1.000000009950413604e+00,0.000000000000000000e+00,8.815865125219812676e-10,0.000000000000000000e+00 +3.980717589485971075e+01,2.736500000000000341e+02,0.000000000000000000e+00,8.448087990346092369e+00,0.000000000000000000e+00,-1.000000009949370217e+00,0.000000000000000000e+00,-4.001193084281642964e-10,0.000000000000000000e+00 +3.980835959465206741e+01,2.736600000000000250e+02,0.000000000000000000e+00,8.446904290541956684e+00,0.000000000000000000e+00,-1.000000009949843838e+00,0.000000000000000000e+00,2.194439745458540567e-10,0.000000000000000000e+00 +3.980954346032119417e+01,2.736700000000000159e+02,0.000000000000000000e+00,8.445720424861047348e+00,0.000000000000000000e+00,-1.000000009949584046e+00,0.000000000000000000e+00,2.379789525252788735e-10,0.000000000000000000e+00 +3.981072749193684501e+01,2.736800000000000068e+02,0.000000000000000000e+00,8.444536393233613936e+00,0.000000000000000000e+00,-1.000000009949302271e+00,0.000000000000000000e+00,-3.090105055403079930e-10,0.000000000000000000e+00 +3.981191168956882365e+01,2.736899999999999977e+02,0.000000000000000000e+00,8.443352195589856279e+00,0.000000000000000000e+00,-1.000000009949668200e+00,0.000000000000000000e+00,-1.209246517620656114e-10,0.000000000000000000e+00 +3.981309605328696932e+01,2.736999999999999886e+02,0.000000000000000000e+00,8.442167831859924476e+00,0.000000000000000000e+00,-1.000000009949811419e+00,0.000000000000000000e+00,8.358564143554270569e-10,0.000000000000000000e+00 +3.981428058316118523e+01,2.737099999999999795e+02,0.000000000000000000e+00,8.440983301973920661e+00,0.000000000000000000e+00,-1.000000009948821322e+00,0.000000000000000000e+00,-1.201410148380440266e-09,0.000000000000000000e+00 +3.981546527926141721e+01,2.737200000000000273e+02,0.000000000000000000e+00,8.439798605861899006e+00,0.000000000000000000e+00,-1.000000009950244628e+00,0.000000000000000000e+00,1.302438164224377655e-10,0.000000000000000000e+00 +3.981665014165766792e+01,2.737300000000000182e+02,0.000000000000000000e+00,8.438613743453860394e+00,0.000000000000000000e+00,-1.000000009950090307e+00,0.000000000000000000e+00,1.067287233762774512e-09,0.000000000000000000e+00 +3.981783517041997555e+01,2.737400000000000091e+02,0.000000000000000000e+00,8.437428714679761299e+00,0.000000000000000000e+00,-1.000000009948825541e+00,0.000000000000000000e+00,-8.837231223944738057e-10,0.000000000000000000e+00 +3.981902036561843516e+01,2.737500000000000000e+02,0.000000000000000000e+00,8.436243519469508456e+00,0.000000000000000000e+00,-1.000000009949872926e+00,0.000000000000000000e+00,6.338984463979361177e-10,0.000000000000000000e+00 +3.982020572732319152e+01,2.737599999999999909e+02,0.000000000000000000e+00,8.435058157752955310e+00,0.000000000000000000e+00,-1.000000009949121527e+00,0.000000000000000000e+00,-6.662115718453712720e-10,0.000000000000000000e+00 +3.982139125560443915e+01,2.737699999999999818e+02,0.000000000000000000e+00,8.433872629459910897e+00,0.000000000000000000e+00,-1.000000009949911339e+00,0.000000000000000000e+00,3.056239734906223923e-10,0.000000000000000000e+00 +3.982257695053242230e+01,2.737800000000000296e+02,0.000000000000000000e+00,8.432686934520130961e+00,0.000000000000000000e+00,-1.000000009949548962e+00,0.000000000000000000e+00,-2.063420767992859543e-10,0.000000000000000000e+00 +3.982376281217742786e+01,2.737900000000000205e+02,0.000000000000000000e+00,8.431501072863325064e+00,0.000000000000000000e+00,-1.000000009949793656e+00,0.000000000000000000e+00,-9.040705668729607582e-10,0.000000000000000000e+00 +3.982494884060979956e+01,2.738000000000000114e+02,0.000000000000000000e+00,8.430315044419151249e+00,0.000000000000000000e+00,-1.000000009950865909e+00,0.000000000000000000e+00,7.721612140405341655e-10,0.000000000000000000e+00 +3.982613503589993087e+01,2.738100000000000023e+02,0.000000000000000000e+00,8.429128849117217825e+00,0.000000000000000000e+00,-1.000000009949949975e+00,0.000000000000000000e+00,1.068707916128881755e-09,0.000000000000000000e+00 +3.982732139811825789e+01,2.738199999999999932e+02,0.000000000000000000e+00,8.427942486887086915e+00,0.000000000000000000e+00,-1.000000009948682100e+00,0.000000000000000000e+00,-1.239975831304503662e-09,0.000000000000000000e+00 +3.982850792733527356e+01,2.738299999999999841e+02,0.000000000000000000e+00,8.426755957658269125e+00,0.000000000000000000e+00,-1.000000009950153368e+00,0.000000000000000000e+00,1.899182432879152328e-10,0.000000000000000000e+00 +3.982969462362151347e+01,2.738400000000000318e+02,0.000000000000000000e+00,8.425569261360221773e+00,0.000000000000000000e+00,-1.000000009949927993e+00,0.000000000000000000e+00,-9.154079804360019822e-10,0.000000000000000000e+00 +3.983088148704757003e+01,2.738500000000000227e+02,0.000000000000000000e+00,8.424382397922357768e+00,0.000000000000000000e+00,-1.000000009951014457e+00,0.000000000000000000e+00,1.784354523998862830e-09,0.000000000000000000e+00 +3.983206851768407830e+01,2.738600000000000136e+02,0.000000000000000000e+00,8.423195367274036727e+00,0.000000000000000000e+00,-1.000000009948896373e+00,0.000000000000000000e+00,-1.761659199947066487e-09,0.000000000000000000e+00 +3.983325571560173017e+01,2.738700000000000045e+02,0.000000000000000000e+00,8.422008169344573858e+00,0.000000000000000000e+00,-1.000000009950987812e+00,0.000000000000000000e+00,1.086879730221716158e-09,0.000000000000000000e+00 +3.983444308087126018e+01,2.738799999999999955e+02,0.000000000000000000e+00,8.420820804063225751e+00,0.000000000000000000e+00,-1.000000009949697288e+00,0.000000000000000000e+00,2.815915529845551083e-10,0.000000000000000000e+00 +3.983563061356345969e+01,2.738899999999999864e+02,0.000000000000000000e+00,8.419633271359208138e+00,0.000000000000000000e+00,-1.000000009949362889e+00,0.000000000000000000e+00,-3.611939964957231131e-10,0.000000000000000000e+00 +3.983681831374916982e+01,2.739000000000000341e+02,0.000000000000000000e+00,8.418445571161681684e+00,0.000000000000000000e+00,-1.000000009949791879e+00,0.000000000000000000e+00,-8.060294055056520897e-10,0.000000000000000000e+00 +3.983800618149927431e+01,2.739100000000000250e+02,0.000000000000000000e+00,8.417257703399757318e+00,0.000000000000000000e+00,-1.000000009950749336e+00,0.000000000000000000e+00,2.396066539791184016e-10,0.000000000000000000e+00 +3.983919421688471374e+01,2.739200000000000159e+02,0.000000000000000000e+00,8.416069668002496229e+00,0.000000000000000000e+00,-1.000000009950464674e+00,0.000000000000000000e+00,2.932057554326998070e-10,0.000000000000000000e+00 +3.984038241997647845e+01,2.739300000000000068e+02,0.000000000000000000e+00,8.414881464898911645e+00,0.000000000000000000e+00,-1.000000009950116286e+00,0.000000000000000000e+00,6.487359193425361671e-10,0.000000000000000000e+00 +3.984157079084560138e+01,2.739399999999999977e+02,0.000000000000000000e+00,8.413693094017965279e+00,0.000000000000000000e+00,-1.000000009949345348e+00,0.000000000000000000e+00,-1.173799584413323528e-09,0.000000000000000000e+00 +3.984275932956317234e+01,2.739499999999999886e+02,0.000000000000000000e+00,8.412504555288569108e+00,0.000000000000000000e+00,-1.000000009950740454e+00,0.000000000000000000e+00,1.148042838501418322e-09,0.000000000000000000e+00 +3.984394803620033088e+01,2.739599999999999795e+02,0.000000000000000000e+00,8.411315848639581816e+00,0.000000000000000000e+00,-1.000000009949375768e+00,0.000000000000000000e+00,-1.151615991961377916e-09,0.000000000000000000e+00 +3.984513691082826625e+01,2.739700000000000273e+02,0.000000000000000000e+00,8.410126973999817679e+00,0.000000000000000000e+00,-1.000000009950744895e+00,0.000000000000000000e+00,7.620954574270756169e-10,0.000000000000000000e+00 +3.984632595351821749e+01,2.739800000000000182e+02,0.000000000000000000e+00,8.408937931298034130e+00,0.000000000000000000e+00,-1.000000009949838731e+00,0.000000000000000000e+00,-6.167227170523183486e-10,0.000000000000000000e+00 +3.984751516434147334e+01,2.739900000000000091e+02,0.000000000000000000e+00,8.407748720462944192e+00,0.000000000000000000e+00,-1.000000009950572144e+00,0.000000000000000000e+00,1.029219347435099955e-09,0.000000000000000000e+00 +3.984870454336937939e+01,2.740000000000000000e+02,0.000000000000000000e+00,8.406559341423205822e+00,0.000000000000000000e+00,-1.000000009949348012e+00,0.000000000000000000e+00,-5.439363164529358279e-10,0.000000000000000000e+00 +3.984989409067331678e+01,2.740099999999999909e+02,0.000000000000000000e+00,8.405369794107430792e+00,0.000000000000000000e+00,-1.000000009949995050e+00,0.000000000000000000e+00,-2.784619586650613226e-10,0.000000000000000000e+00 +3.985108380632473057e+01,2.740199999999999818e+02,0.000000000000000000e+00,8.404180078444175805e+00,0.000000000000000000e+00,-1.000000009950326341e+00,0.000000000000000000e+00,-6.494037901424605395e-10,0.000000000000000000e+00 +3.985227369039511558e+01,2.740300000000000296e+02,0.000000000000000000e+00,8.402990194361949605e+00,0.000000000000000000e+00,-1.000000009951099056e+00,0.000000000000000000e+00,8.873928561833429468e-10,0.000000000000000000e+00 +3.985346374295601635e+01,2.740400000000000205e+02,0.000000000000000000e+00,8.401800141789209420e+00,0.000000000000000000e+00,-1.000000009950043012e+00,0.000000000000000000e+00,-6.499661185709016286e-10,0.000000000000000000e+00 +3.985465396407902006e+01,2.740500000000000114e+02,0.000000000000000000e+00,8.400609920654364515e+00,0.000000000000000000e+00,-1.000000009950816615e+00,0.000000000000000000e+00,1.044573662138158290e-09,0.000000000000000000e+00 +3.985584435383577073e+01,2.740600000000000023e+02,0.000000000000000000e+00,8.399419530885769092e+00,0.000000000000000000e+00,-1.000000009949573165e+00,0.000000000000000000e+00,-2.622254382617182385e-10,0.000000000000000000e+00 +3.985703491229796214e+01,2.740699999999999932e+02,0.000000000000000000e+00,8.398228972411731164e+00,0.000000000000000000e+00,-1.000000009949885360e+00,0.000000000000000000e+00,-7.731383826396828480e-10,0.000000000000000000e+00 +3.985822563953734488e+01,2.740799999999999841e+02,0.000000000000000000e+00,8.397038245160503678e+00,0.000000000000000000e+00,-1.000000009950805957e+00,0.000000000000000000e+00,-4.540098991637947290e-10,0.000000000000000000e+00 +3.985941653562570508e+01,2.740900000000000318e+02,0.000000000000000000e+00,8.395847349060289844e+00,0.000000000000000000e+00,-1.000000009951346636e+00,0.000000000000000000e+00,1.982259797696130019e-09,0.000000000000000000e+00 +3.986060760063489994e+01,2.741000000000000227e+02,0.000000000000000000e+00,8.394656284039243133e+00,0.000000000000000000e+00,-1.000000009948985635e+00,0.000000000000000000e+00,-2.192795645626636105e-09,0.000000000000000000e+00 +3.986179883463682216e+01,2.741100000000000136e+02,0.000000000000000000e+00,8.393465050025469054e+00,0.000000000000000000e+00,-1.000000009951597768e+00,0.000000000000000000e+00,8.287978986990131497e-10,0.000000000000000000e+00 +3.986299023770342131e+01,2.741200000000000045e+02,0.000000000000000000e+00,8.392273646947012722e+00,0.000000000000000000e+00,-1.000000009950610336e+00,0.000000000000000000e+00,1.066271289214677660e-09,0.000000000000000000e+00 +3.986418180990669669e+01,2.741299999999999955e+02,0.000000000000000000e+00,8.391082074731878393e+00,0.000000000000000000e+00,-1.000000009949339796e+00,0.000000000000000000e+00,-1.440994629530763963e-09,0.000000000000000000e+00 +3.986537355131870441e+01,2.741399999999999864e+02,0.000000000000000000e+00,8.389890333308015258e+00,0.000000000000000000e+00,-1.000000009951057089e+00,0.000000000000000000e+00,8.474468044243490262e-10,0.000000000000000000e+00 +3.986656546201154327e+01,2.741500000000000341e+02,0.000000000000000000e+00,8.388698422603317439e+00,0.000000000000000000e+00,-1.000000009950047009e+00,0.000000000000000000e+00,-7.871623249649322113e-10,0.000000000000000000e+00 +3.986775754205736177e+01,2.741600000000000250e+02,0.000000000000000000e+00,8.387506342545634652e+00,0.000000000000000000e+00,-1.000000009950985369e+00,0.000000000000000000e+00,-5.736193638981158669e-11,0.000000000000000000e+00 +3.986894979152837237e+01,2.741700000000000159e+02,0.000000000000000000e+00,8.386314093062759767e+00,0.000000000000000000e+00,-1.000000009951053759e+00,0.000000000000000000e+00,5.726067583681879166e-10,0.000000000000000000e+00 +3.987014221049683016e+01,2.741800000000000068e+02,0.000000000000000000e+00,8.385121674082437693e+00,0.000000000000000000e+00,-1.000000009950370972e+00,0.000000000000000000e+00,-1.109675133504491267e-10,0.000000000000000000e+00 +3.987133479903503996e+01,2.741899999999999977e+02,0.000000000000000000e+00,8.383929085532361825e+00,0.000000000000000000e+00,-1.000000009950503310e+00,0.000000000000000000e+00,4.268663065937362545e-10,0.000000000000000000e+00 +3.987252755721536346e+01,2.741999999999999886e+02,0.000000000000000000e+00,8.382736327340172267e+00,0.000000000000000000e+00,-1.000000009949994162e+00,0.000000000000000000e+00,-2.752923895096540376e-10,0.000000000000000000e+00 +3.987372048511020495e+01,2.742099999999999795e+02,0.000000000000000000e+00,8.381543399433459385e+00,0.000000000000000000e+00,-1.000000009950322566e+00,0.000000000000000000e+00,-9.325854305366711557e-10,0.000000000000000000e+00 +3.987491358279203268e+01,2.742200000000000273e+02,0.000000000000000000e+00,8.380350301739760255e+00,0.000000000000000000e+00,-1.000000009951435231e+00,0.000000000000000000e+00,9.858579707837044128e-10,0.000000000000000000e+00 +3.987610685033335756e+01,2.742300000000000182e+02,0.000000000000000000e+00,8.379157034186560438e+00,0.000000000000000000e+00,-1.000000009950258839e+00,0.000000000000000000e+00,-7.217060312838457068e-10,0.000000000000000000e+00 +3.987730028780674729e+01,2.742400000000000091e+02,0.000000000000000000e+00,8.377963596701297533e+00,0.000000000000000000e+00,-1.000000009951120150e+00,0.000000000000000000e+00,2.183970618247449208e-10,0.000000000000000000e+00 +3.987849389528481225e+01,2.742500000000000000e+02,0.000000000000000000e+00,8.376769989211352296e+00,0.000000000000000000e+00,-1.000000009950859470e+00,0.000000000000000000e+00,9.988289049648315741e-11,0.000000000000000000e+00 +3.987968767284022675e+01,2.742599999999999909e+02,0.000000000000000000e+00,8.375576211644057523e+00,0.000000000000000000e+00,-1.000000009950740232e+00,0.000000000000000000e+00,2.069903431669536613e-10,0.000000000000000000e+00 +3.988088162054570773e+01,2.742699999999999818e+02,0.000000000000000000e+00,8.374382263926692715e+00,0.000000000000000000e+00,-1.000000009950493096e+00,0.000000000000000000e+00,-6.703448476631673912e-10,0.000000000000000000e+00 +3.988207573847402898e+01,2.742800000000000296e+02,0.000000000000000000e+00,8.373188145986485864e+00,0.000000000000000000e+00,-1.000000009951293567e+00,0.000000000000000000e+00,1.240658342686447486e-09,0.000000000000000000e+00 +3.988327002669802113e+01,2.742900000000000205e+02,0.000000000000000000e+00,8.371993857750611667e+00,0.000000000000000000e+00,-1.000000009949811863e+00,0.000000000000000000e+00,-1.494972470351250563e-09,0.000000000000000000e+00 +3.988446448529055033e+01,2.743000000000000114e+02,0.000000000000000000e+00,8.370799399146196862e+00,0.000000000000000000e+00,-1.000000009951597546e+00,0.000000000000000000e+00,1.119303627154142272e-09,0.000000000000000000e+00 +3.988565911432454669e+01,2.743100000000000023e+02,0.000000000000000000e+00,8.369604770100309565e+00,0.000000000000000000e+00,-1.000000009950260393e+00,0.000000000000000000e+00,-8.385216237514780023e-10,0.000000000000000000e+00 +3.988685391387299717e+01,2.743199999999999932e+02,0.000000000000000000e+00,8.368409970539973486e+00,0.000000000000000000e+00,-1.000000009951262259e+00,0.000000000000000000e+00,1.358315168890005571e-10,0.000000000000000000e+00 +3.988804888400892423e+01,2.743299999999999841e+02,0.000000000000000000e+00,8.367215000392153712e+00,0.000000000000000000e+00,-1.000000009951099944e+00,0.000000000000000000e+00,3.446395130552436531e-10,0.000000000000000000e+00 +3.988924402480541431e+01,2.743400000000000318e+02,0.000000000000000000e+00,8.366019859583767371e+00,0.000000000000000000e+00,-1.000000009950688051e+00,0.000000000000000000e+00,-1.738741281747204183e-10,0.000000000000000000e+00 +3.989043933633561068e+01,2.743500000000000227e+02,0.000000000000000000e+00,8.364824548041678298e+00,0.000000000000000000e+00,-1.000000009950895885e+00,0.000000000000000000e+00,-1.400452578175987002e-10,0.000000000000000000e+00 +3.989163481867269923e+01,2.743600000000000136e+02,0.000000000000000000e+00,8.363629065692697040e+00,0.000000000000000000e+00,-1.000000009951063307e+00,0.000000000000000000e+00,4.821028255394708492e-10,0.000000000000000000e+00 +3.989283047188991560e+01,2.743700000000000045e+02,0.000000000000000000e+00,8.362433412463582627e+00,0.000000000000000000e+00,-1.000000009950486879e+00,0.000000000000000000e+00,-7.555454385535912528e-10,0.000000000000000000e+00 +3.989402629606055939e+01,2.743799999999999955e+02,0.000000000000000000e+00,8.361237588281042576e+00,0.000000000000000000e+00,-1.000000009951390378e+00,0.000000000000000000e+00,1.152742883051271687e-09,0.000000000000000000e+00 +3.989522229125797281e+01,2.743899999999999864e+02,0.000000000000000000e+00,8.360041593071729338e+00,0.000000000000000000e+00,-1.000000009950011703e+00,0.000000000000000000e+00,-1.207895797741670205e-09,0.000000000000000000e+00 +3.989641845755555494e+01,2.744000000000000341e+02,0.000000000000000000e+00,8.358845426762247399e+00,0.000000000000000000e+00,-1.000000009951456548e+00,0.000000000000000000e+00,8.908975345991173331e-10,0.000000000000000000e+00 +3.989761479502675456e+01,2.744100000000000250e+02,0.000000000000000000e+00,8.357649089279142629e+00,0.000000000000000000e+00,-1.000000009950390734e+00,0.000000000000000000e+00,-1.203652999338989219e-09,0.000000000000000000e+00 +3.989881130374507734e+01,2.744200000000000159e+02,0.000000000000000000e+00,8.356452580548914710e+00,0.000000000000000000e+00,-1.000000009951830915e+00,0.000000000000000000e+00,1.232241011171483198e-09,0.000000000000000000e+00 +3.990000798378407865e+01,2.744300000000000068e+02,0.000000000000000000e+00,8.355255900498004706e+00,0.000000000000000000e+00,-1.000000009950356317e+00,0.000000000000000000e+00,-4.493390058037098637e-10,0.000000000000000000e+00 +3.990120483521736361e+01,2.744399999999999977e+02,0.000000000000000000e+00,8.354059049052807495e+00,0.000000000000000000e+00,-1.000000009950894109e+00,0.000000000000000000e+00,-1.248397327738301932e-09,0.000000000000000000e+00 +3.990240185811860130e+01,2.744499999999999886e+02,0.000000000000000000e+00,8.352862026139659335e+00,0.000000000000000000e+00,-1.000000009952388469e+00,0.000000000000000000e+00,1.349114561802530731e-09,0.000000000000000000e+00 +3.990359905256150341e+01,2.744599999999999795e+02,0.000000000000000000e+00,8.351664831684844970e+00,0.000000000000000000e+00,-1.000000009950773316e+00,0.000000000000000000e+00,-5.618959617593750483e-11,0.000000000000000000e+00 +3.990479641861983140e+01,2.744700000000000273e+02,0.000000000000000000e+00,8.350467465614601181e+00,0.000000000000000000e+00,-1.000000009950840596e+00,0.000000000000000000e+00,-4.696628439582580077e-10,0.000000000000000000e+00 +3.990599395636741065e+01,2.744800000000000182e+02,0.000000000000000000e+00,8.349269927855106133e+00,0.000000000000000000e+00,-1.000000009951403035e+00,0.000000000000000000e+00,1.453465708553736856e-10,0.000000000000000000e+00 +3.990719166587810918e+01,2.744900000000000091e+02,0.000000000000000000e+00,8.348072218332486472e+00,0.000000000000000000e+00,-1.000000009951228952e+00,0.000000000000000000e+00,5.868638162818274228e-10,0.000000000000000000e+00 +3.990838954722585896e+01,2.745000000000000000e+02,0.000000000000000000e+00,8.346874336972817332e+00,0.000000000000000000e+00,-1.000000009950525959e+00,0.000000000000000000e+00,-3.454697364650390273e-10,0.000000000000000000e+00 +3.990958760048463461e+01,2.745099999999999909e+02,0.000000000000000000e+00,8.345676283702120557e+00,0.000000000000000000e+00,-1.000000009950939850e+00,0.000000000000000000e+00,-1.386128070148636844e-10,0.000000000000000000e+00 +3.991078582572846756e+01,2.745199999999999818e+02,0.000000000000000000e+00,8.344478058446362922e+00,0.000000000000000000e+00,-1.000000009951105939e+00,0.000000000000000000e+00,6.855531435035265512e-12,0.000000000000000000e+00 +3.991198422303144611e+01,2.745300000000000296e+02,0.000000000000000000e+00,8.343279661131459690e+00,0.000000000000000000e+00,-1.000000009951097724e+00,0.000000000000000000e+00,-1.108954529350401311e-09,0.000000000000000000e+00 +3.991318279246770828e+01,2.745400000000000205e+02,0.000000000000000000e+00,8.342081091683272831e+00,0.000000000000000000e+00,-1.000000009952426883e+00,0.000000000000000000e+00,1.497595950056479716e-09,0.000000000000000000e+00 +3.991438153411144185e+01,2.745500000000000114e+02,0.000000000000000000e+00,8.340882350027609249e+00,0.000000000000000000e+00,-1.000000009950631652e+00,0.000000000000000000e+00,-7.900836452904908685e-10,0.000000000000000000e+00 +3.991558044803689143e+01,2.745600000000000023e+02,0.000000000000000000e+00,8.339683436090227886e+00,0.000000000000000000e+00,-1.000000009951578894e+00,0.000000000000000000e+00,7.173802359131351943e-10,0.000000000000000000e+00 +3.991677953431835846e+01,2.745699999999999932e+02,0.000000000000000000e+00,8.338484349796827289e+00,0.000000000000000000e+00,-1.000000009950718693e+00,0.000000000000000000e+00,-1.356049925192159085e-09,0.000000000000000000e+00 +3.991797879303019414e+01,2.745799999999999841e+02,0.000000000000000000e+00,8.337285091073058041e+00,0.000000000000000000e+00,-1.000000009952344948e+00,0.000000000000000000e+00,1.673344128554563015e-09,0.000000000000000000e+00 +3.991917822424679940e+01,2.745900000000000318e+02,0.000000000000000000e+00,8.336085659844512108e+00,0.000000000000000000e+00,-1.000000009950337887e+00,0.000000000000000000e+00,-1.271440117577781098e-09,0.000000000000000000e+00 +3.992037782804263912e+01,2.746000000000000227e+02,0.000000000000000000e+00,8.334886056036735269e+00,0.000000000000000000e+00,-1.000000009951863111e+00,0.000000000000000000e+00,9.592263523136778161e-10,0.000000000000000000e+00 +3.992157760449222081e+01,2.746100000000000136e+02,0.000000000000000000e+00,8.333686279575211131e+00,0.000000000000000000e+00,-1.000000009950712254e+00,0.000000000000000000e+00,-1.471292856634109976e-09,0.000000000000000000e+00 +3.992277755367011594e+01,2.746200000000000045e+02,0.000000000000000000e+00,8.332486330385377116e+00,0.000000000000000000e+00,-1.000000009952477731e+00,0.000000000000000000e+00,1.345083502843939746e-09,0.000000000000000000e+00 +3.992397767565093858e+01,2.746299999999999955e+02,0.000000000000000000e+00,8.331286208392610249e+00,0.000000000000000000e+00,-1.000000009950863467e+00,0.000000000000000000e+00,-4.221510946933890168e-10,0.000000000000000000e+00 +3.992517797050936679e+01,2.746399999999999864e+02,0.000000000000000000e+00,8.330085913522241370e+00,0.000000000000000000e+00,-1.000000009951370172e+00,0.000000000000000000e+00,-5.682126752746336517e-10,0.000000000000000000e+00 +3.992637843832012123e+01,2.746500000000000341e+02,0.000000000000000000e+00,8.328885445699540924e+00,0.000000000000000000e+00,-1.000000009952052293e+00,0.000000000000000000e+00,9.431858799106609543e-10,0.000000000000000000e+00 +3.992757907915798654e+01,2.746600000000000250e+02,0.000000000000000000e+00,8.327684804849727840e+00,0.000000000000000000e+00,-1.000000009950919866e+00,0.000000000000000000e+00,-7.797728423420146894e-10,0.000000000000000000e+00 +3.992877989309779707e+01,2.746700000000000159e+02,0.000000000000000000e+00,8.326483990897969534e+00,0.000000000000000000e+00,-1.000000009951856228e+00,0.000000000000000000e+00,4.620278269585670132e-10,0.000000000000000000e+00 +3.992998088021443692e+01,2.746800000000000068e+02,0.000000000000000000e+00,8.325283003769374801e+00,0.000000000000000000e+00,-1.000000009951301339e+00,0.000000000000000000e+00,-2.218301010553258442e-10,0.000000000000000000e+00 +3.993118204058285414e+01,2.746899999999999977e+02,0.000000000000000000e+00,8.324081843389002699e+00,0.000000000000000000e+00,-1.000000009951567792e+00,0.000000000000000000e+00,-3.291853403880787647e-10,0.000000000000000000e+00 +3.993238337427804652e+01,2.746999999999999886e+02,0.000000000000000000e+00,8.322880509681855443e+00,0.000000000000000000e+00,-1.000000009951963253e+00,0.000000000000000000e+00,1.768584533882297008e-10,0.000000000000000000e+00 +3.993358488137506157e+01,2.747099999999999795e+02,0.000000000000000000e+00,8.321679002572881956e+00,0.000000000000000000e+00,-1.000000009951750757e+00,0.000000000000000000e+00,1.031063430953087022e-10,0.000000000000000000e+00 +3.993478656194900367e+01,2.747200000000000273e+02,0.000000000000000000e+00,8.320477321986977870e+00,0.000000000000000000e+00,-1.000000009951626856e+00,0.000000000000000000e+00,7.184994000921064220e-10,0.000000000000000000e+00 +3.993598841607503402e+01,2.747300000000000182e+02,0.000000000000000000e+00,8.319275467848983752e+00,0.000000000000000000e+00,-1.000000009950763324e+00,0.000000000000000000e+00,-3.988213256330908839e-10,0.000000000000000000e+00 +3.993719044382837069e+01,2.747400000000000091e+02,0.000000000000000000e+00,8.318073440083686876e+00,0.000000000000000000e+00,-1.000000009951242719e+00,0.000000000000000000e+00,-7.507987239461263420e-10,0.000000000000000000e+00 +3.993839264528427435e+01,2.747500000000000000e+02,0.000000000000000000e+00,8.316871238615817674e+00,0.000000000000000000e+00,-1.000000009952145330e+00,0.000000000000000000e+00,-2.999067414746667384e-10,0.000000000000000000e+00 +3.993959502051806965e+01,2.747599999999999909e+02,0.000000000000000000e+00,8.315668863370053288e+00,0.000000000000000000e+00,-1.000000009952505930e+00,0.000000000000000000e+00,9.906201070992789187e-10,0.000000000000000000e+00 +3.994079756960513805e+01,2.747699999999999818e+02,0.000000000000000000e+00,8.314466314271017566e+00,0.000000000000000000e+00,-1.000000009951314661e+00,0.000000000000000000e+00,-5.256081258393405083e-10,0.000000000000000000e+00 +3.994200029262090368e+01,2.747800000000000296e+02,0.000000000000000000e+00,8.313263591243281070e+00,0.000000000000000000e+00,-1.000000009951946822e+00,0.000000000000000000e+00,1.030020754003435860e-10,0.000000000000000000e+00 +3.994320318964085459e+01,2.747900000000000205e+02,0.000000000000000000e+00,8.312060694211355738e+00,0.000000000000000000e+00,-1.000000009951822921e+00,0.000000000000000000e+00,4.579053265971382997e-10,0.000000000000000000e+00 +3.994440626074053569e+01,2.748000000000000114e+02,0.000000000000000000e+00,8.310857623099701996e+00,0.000000000000000000e+00,-1.000000009951272029e+00,0.000000000000000000e+00,-6.492050701037921778e-10,0.000000000000000000e+00 +3.994560950599554161e+01,2.748100000000000023e+02,0.000000000000000000e+00,8.309654377832725203e+00,0.000000000000000000e+00,-1.000000009952053182e+00,0.000000000000000000e+00,5.011329415925675988e-10,0.000000000000000000e+00 +3.994681292548151674e+01,2.748199999999999932e+02,0.000000000000000000e+00,8.308450958334773873e+00,0.000000000000000000e+00,-1.000000009951450108e+00,0.000000000000000000e+00,2.662113803370464756e-10,0.000000000000000000e+00 +3.994801651927416941e+01,2.748299999999999841e+02,0.000000000000000000e+00,8.307247364530145006e+00,0.000000000000000000e+00,-1.000000009951129698e+00,0.000000000000000000e+00,-1.313709490750796075e-09,0.000000000000000000e+00 +3.994922028744925768e+01,2.748400000000000318e+02,0.000000000000000000e+00,8.306043596343078761e+00,0.000000000000000000e+00,-1.000000009952711100e+00,0.000000000000000000e+00,7.023140738943044531e-10,0.000000000000000000e+00 +3.995042423008259647e+01,2.748500000000000227e+02,0.000000000000000000e+00,8.304839653697758450e+00,0.000000000000000000e+00,-1.000000009951865554e+00,0.000000000000000000e+00,2.240514480443328743e-10,0.000000000000000000e+00 +3.995162834725005752e+01,2.748600000000000136e+02,0.000000000000000000e+00,8.303635536518317650e+00,0.000000000000000000e+00,-1.000000009951595770e+00,0.000000000000000000e+00,-2.577600906062428784e-10,0.000000000000000000e+00 +3.995283263902756232e+01,2.748700000000000045e+02,0.000000000000000000e+00,8.302431244728831317e+00,0.000000000000000000e+00,-1.000000009951906188e+00,0.000000000000000000e+00,5.193167854944640344e-10,0.000000000000000000e+00 +3.995403710549108922e+01,2.748799999999999955e+02,0.000000000000000000e+00,8.301226778253319338e+00,0.000000000000000000e+00,-1.000000009951280688e+00,0.000000000000000000e+00,-1.079587202750913130e-09,0.000000000000000000e+00 +3.995524174671667339e+01,2.748899999999999864e+02,0.000000000000000000e+00,8.300022137015748314e+00,0.000000000000000000e+00,-1.000000009952581204e+00,0.000000000000000000e+00,1.105785081769605648e-09,0.000000000000000000e+00 +3.995644656278040685e+01,2.749000000000000341e+02,0.000000000000000000e+00,8.298817320940026221e+00,0.000000000000000000e+00,-1.000000009951248936e+00,0.000000000000000000e+00,-1.453896306951403329e-09,0.000000000000000000e+00 +3.995765155375843136e+01,2.749100000000000250e+02,0.000000000000000000e+00,8.297612329950011301e+00,0.000000000000000000e+00,-1.000000009953000868e+00,0.000000000000000000e+00,1.068799473947557333e-09,0.000000000000000000e+00 +3.995885671972694553e+01,2.749200000000000159e+02,0.000000000000000000e+00,8.296407163969499621e+00,0.000000000000000000e+00,-1.000000009951712787e+00,0.000000000000000000e+00,1.497686202679915986e-10,0.000000000000000000e+00 +3.996006206076221190e+01,2.749300000000000068e+02,0.000000000000000000e+00,8.295201822922239288e+00,0.000000000000000000e+00,-1.000000009951532265e+00,0.000000000000000000e+00,-5.028400135515578996e-10,0.000000000000000000e+00 +3.996126757694053566e+01,2.749399999999999977e+02,0.000000000000000000e+00,8.293996306731918011e+00,0.000000000000000000e+00,-1.000000009952138447e+00,0.000000000000000000e+00,3.720107009019474068e-10,0.000000000000000000e+00 +3.996247326833828595e+01,2.749499999999999886e+02,0.000000000000000000e+00,8.292790615322168435e+00,0.000000000000000000e+00,-1.000000009951689917e+00,0.000000000000000000e+00,-8.529223134472970607e-10,0.000000000000000000e+00 +3.996367913503188163e+01,2.749599999999999795e+02,0.000000000000000000e+00,8.291584748616569911e+00,0.000000000000000000e+00,-1.000000009952718427e+00,0.000000000000000000e+00,7.476713840078173600e-10,0.000000000000000000e+00 +3.996488517709780552e+01,2.749700000000000273e+02,0.000000000000000000e+00,8.290378706538643172e+00,0.000000000000000000e+00,-1.000000009951816704e+00,0.000000000000000000e+00,3.267480109615770516e-10,0.000000000000000000e+00 +3.996609139461259019e+01,2.749800000000000182e+02,0.000000000000000000e+00,8.289172489011857436e+00,0.000000000000000000e+00,-1.000000009951422575e+00,0.000000000000000000e+00,-8.540226381418273529e-10,0.000000000000000000e+00 +3.996729778765281793e+01,2.749900000000000091e+02,0.000000000000000000e+00,8.287966095959623303e+00,0.000000000000000000e+00,-1.000000009952452862e+00,0.000000000000000000e+00,-3.146909849170088861e-10,0.000000000000000000e+00 +3.996850435629513498e+01,2.750000000000000000e+02,0.000000000000000000e+00,8.286759527305294526e+00,0.000000000000000000e+00,-1.000000009952832558e+00,0.000000000000000000e+00,7.621405276236565111e-10,0.000000000000000000e+00 +3.996971110061624444e+01,2.750099999999999909e+02,0.000000000000000000e+00,8.285552782972171570e+00,0.000000000000000000e+00,-1.000000009951912849e+00,0.000000000000000000e+00,-2.391690982564714485e-11,0.000000000000000000e+00 +3.997091802069290623e+01,2.750199999999999818e+02,0.000000000000000000e+00,8.284345862883499834e+00,0.000000000000000000e+00,-1.000000009951941715e+00,0.000000000000000000e+00,-1.931469019395598594e-10,0.000000000000000000e+00 +3.997212511660193002e+01,2.750300000000000296e+02,0.000000000000000000e+00,8.283138766962466093e+00,0.000000000000000000e+00,-1.000000009952174862e+00,0.000000000000000000e+00,2.922530551053483381e-10,0.000000000000000000e+00 +3.997333238842018233e+01,2.750400000000000205e+02,0.000000000000000000e+00,8.281931495132202059e+00,0.000000000000000000e+00,-1.000000009951822033e+00,0.000000000000000000e+00,-9.652691627770367035e-10,0.000000000000000000e+00 +3.997453983622458651e+01,2.750500000000000114e+02,0.000000000000000000e+00,8.280724047315784375e+00,0.000000000000000000e+00,-1.000000009952987545e+00,0.000000000000000000e+00,9.471092702933694320e-10,0.000000000000000000e+00 +3.997574746009212276e+01,2.750600000000000023e+02,0.000000000000000000e+00,8.279516423436231065e+00,0.000000000000000000e+00,-1.000000009951843793e+00,0.000000000000000000e+00,-2.298027441515257668e-11,0.000000000000000000e+00 +3.997695526009982814e+01,2.750699999999999932e+02,0.000000000000000000e+00,8.278308623416508638e+00,0.000000000000000000e+00,-1.000000009951871549e+00,0.000000000000000000e+00,-1.810581461217988253e-10,0.000000000000000000e+00 +3.997816323632478941e+01,2.750799999999999841e+02,0.000000000000000000e+00,8.277100647179523207e+00,0.000000000000000000e+00,-1.000000009952090263e+00,0.000000000000000000e+00,-7.055642600067232671e-10,0.000000000000000000e+00 +3.997937138884416441e+01,2.750900000000000318e+02,0.000000000000000000e+00,8.275892494648125819e+00,0.000000000000000000e+00,-1.000000009952942692e+00,0.000000000000000000e+00,8.759921570786224464e-10,0.000000000000000000e+00 +3.998057971773515362e+01,2.751000000000000227e+02,0.000000000000000000e+00,8.274684165745110676e+00,0.000000000000000000e+00,-1.000000009951884206e+00,0.000000000000000000e+00,-2.634758432246917376e-10,0.000000000000000000e+00 +3.998178822307502145e+01,2.751100000000000136e+02,0.000000000000000000e+00,8.273475660393218689e+00,0.000000000000000000e+00,-1.000000009952202618e+00,0.000000000000000000e+00,-4.339184458379282606e-10,0.000000000000000000e+00 +3.998299690494108205e+01,2.751200000000000045e+02,0.000000000000000000e+00,8.272266978515130376e+00,0.000000000000000000e+00,-1.000000009952727087e+00,0.000000000000000000e+00,4.024455646495594882e-10,0.000000000000000000e+00 +3.998420576341070642e+01,2.751299999999999955e+02,0.000000000000000000e+00,8.271058120033471184e+00,0.000000000000000000e+00,-1.000000009952240587e+00,0.000000000000000000e+00,-1.454542715399245052e-10,0.000000000000000000e+00 +3.998541479856133662e+01,2.751399999999999864e+02,0.000000000000000000e+00,8.269849084870811495e+00,0.000000000000000000e+00,-1.000000009952416447e+00,0.000000000000000000e+00,3.929629297877110016e-10,0.000000000000000000e+00 +3.998662401047045023e+01,2.751500000000000341e+02,0.000000000000000000e+00,8.268639872949663072e+00,0.000000000000000000e+00,-1.000000009951941271e+00,0.000000000000000000e+00,-3.734437981424057989e-10,0.000000000000000000e+00 +3.998783339921559588e+01,2.751600000000000250e+02,0.000000000000000000e+00,8.267430484192482609e+00,0.000000000000000000e+00,-1.000000009952392910e+00,0.000000000000000000e+00,2.570033669850752347e-11,0.000000000000000000e+00 +3.998904296487437193e+01,2.751700000000000159e+02,0.000000000000000000e+00,8.266220918521668182e+00,0.000000000000000000e+00,-1.000000009952361824e+00,0.000000000000000000e+00,-7.989799856905582937e-10,0.000000000000000000e+00 +3.999025270752444072e+01,2.751800000000000068e+02,0.000000000000000000e+00,8.265011175859562798e+00,0.000000000000000000e+00,-1.000000009953328384e+00,0.000000000000000000e+00,8.329977980109716731e-10,0.000000000000000000e+00 +3.999146262724350720e+01,2.751899999999999977e+02,0.000000000000000000e+00,8.263801256128450845e+00,0.000000000000000000e+00,-1.000000009952320523e+00,0.000000000000000000e+00,1.078940301236459257e-10,0.000000000000000000e+00 +3.999267272410935448e+01,2.751999999999999886e+02,0.000000000000000000e+00,8.262591159250563422e+00,0.000000000000000000e+00,-1.000000009952189961e+00,0.000000000000000000e+00,-5.074680042069136124e-10,0.000000000000000000e+00 +3.999388299819980119e+01,2.752099999999999795e+02,0.000000000000000000e+00,8.261380885148071229e+00,0.000000000000000000e+00,-1.000000009952804136e+00,0.000000000000000000e+00,2.395719941539949032e-10,0.000000000000000000e+00 +3.999509344959273704e+01,2.752200000000000273e+02,0.000000000000000000e+00,8.260170433743088125e+00,0.000000000000000000e+00,-1.000000009952514146e+00,0.000000000000000000e+00,-3.649911298342078190e-11,0.000000000000000000e+00 +3.999630407836610146e+01,2.752300000000000182e+02,0.000000000000000000e+00,8.258959804957672901e+00,0.000000000000000000e+00,-1.000000009952558333e+00,0.000000000000000000e+00,-8.325712900105271225e-11,0.000000000000000000e+00 +3.999751488459789783e+01,2.752400000000000091e+02,0.000000000000000000e+00,8.257748998713825728e+00,0.000000000000000000e+00,-1.000000009952659141e+00,0.000000000000000000e+00,1.389860169404029013e-10,0.000000000000000000e+00 +3.999872586836617927e+01,2.752500000000000000e+02,0.000000000000000000e+00,8.256538014933489933e+00,0.000000000000000000e+00,-1.000000009952490831e+00,0.000000000000000000e+00,6.704450221797613699e-10,0.000000000000000000e+00 +3.999993702974906284e+01,2.752599999999999909e+02,0.000000000000000000e+00,8.255326853538552001e+00,0.000000000000000000e+00,-1.000000009951678814e+00,0.000000000000000000e+00,-8.701492098805442994e-10,0.000000000000000000e+00 +4.000114836882471536e+01,2.752699999999999818e+02,0.000000000000000000e+00,8.254115514450841573e+00,0.000000000000000000e+00,-1.000000009952732860e+00,0.000000000000000000e+00,-8.102728419198606320e-10,0.000000000000000000e+00 +4.000235988567137468e+01,2.752800000000000296e+02,0.000000000000000000e+00,8.252903997592127894e+00,0.000000000000000000e+00,-1.000000009953714519e+00,0.000000000000000000e+00,8.885854604195715145e-10,0.000000000000000000e+00 +4.000357158036731420e+01,2.752900000000000205e+02,0.000000000000000000e+00,8.251692302884125141e+00,0.000000000000000000e+00,-1.000000009952637825e+00,0.000000000000000000e+00,6.363382569300260700e-10,0.000000000000000000e+00 +4.000478345299088545e+01,2.753000000000000114e+02,0.000000000000000000e+00,8.250480430248492425e+00,0.000000000000000000e+00,-1.000000009951866664e+00,0.000000000000000000e+00,-3.145500504228385266e-10,0.000000000000000000e+00 +4.000599550362048973e+01,2.753100000000000023e+02,0.000000000000000000e+00,8.249268379606828461e+00,0.000000000000000000e+00,-1.000000009952247915e+00,0.000000000000000000e+00,-7.154641832483993085e-10,0.000000000000000000e+00 +4.000720773233457805e+01,2.753199999999999932e+02,0.000000000000000000e+00,8.248056150880673343e+00,0.000000000000000000e+00,-1.000000009953115221e+00,0.000000000000000000e+00,6.823931912465528094e-10,0.000000000000000000e+00 +4.000842013921167251e+01,2.753299999999999841e+02,0.000000000000000000e+00,8.246843743991510323e+00,0.000000000000000000e+00,-1.000000009952287883e+00,0.000000000000000000e+00,-9.146679969260239523e-10,0.000000000000000000e+00 +4.000963272433034490e+01,2.753400000000000318e+02,0.000000000000000000e+00,8.245631158860767584e+00,0.000000000000000000e+00,-1.000000009953396995e+00,0.000000000000000000e+00,5.749019446904049389e-10,0.000000000000000000e+00 +4.001084548776923100e+01,2.753500000000000227e+02,0.000000000000000000e+00,8.244418395409811140e+00,0.000000000000000000e+00,-1.000000009952699775e+00,0.000000000000000000e+00,3.597185249000273853e-10,0.000000000000000000e+00 +4.001205842960701631e+01,2.753600000000000136e+02,0.000000000000000000e+00,8.243205453559953710e+00,0.000000000000000000e+00,-1.000000009952263458e+00,0.000000000000000000e+00,-3.117101884922446173e-10,0.000000000000000000e+00 +4.001327154992245028e+01,2.753700000000000045e+02,0.000000000000000000e+00,8.241992333232447621e+00,0.000000000000000000e+00,-1.000000009952641600e+00,0.000000000000000000e+00,-1.908783798479128531e-10,0.000000000000000000e+00 +4.001448484879433920e+01,2.753799999999999955e+02,0.000000000000000000e+00,8.240779034348486576e+00,0.000000000000000000e+00,-1.000000009952873192e+00,0.000000000000000000e+00,-4.448293696168985776e-10,0.000000000000000000e+00 +4.001569832630153911e+01,2.753899999999999864e+02,0.000000000000000000e+00,8.239565556829207438e+00,0.000000000000000000e+00,-1.000000009953412983e+00,0.000000000000000000e+00,1.734414422721395164e-10,0.000000000000000000e+00 +4.001691198252297710e+01,2.754000000000000341e+02,0.000000000000000000e+00,8.238351900595688448e+00,0.000000000000000000e+00,-1.000000009953202484e+00,0.000000000000000000e+00,4.982963059335134464e-10,0.000000000000000000e+00 +4.001812581753762998e+01,2.754100000000000250e+02,0.000000000000000000e+00,8.237138065568951006e+00,0.000000000000000000e+00,-1.000000009952597635e+00,0.000000000000000000e+00,-6.343013850028250685e-10,0.000000000000000000e+00 +4.001933983142453854e+01,2.754200000000000159e+02,0.000000000000000000e+00,8.235924051669957890e+00,0.000000000000000000e+00,-1.000000009953367686e+00,0.000000000000000000e+00,4.319489790304151764e-10,0.000000000000000000e+00 +4.002055402426280040e+01,2.754300000000000068e+02,0.000000000000000000e+00,8.234709858819611483e+00,0.000000000000000000e+00,-1.000000009952843216e+00,0.000000000000000000e+00,1.226905314070760728e-10,0.000000000000000000e+00 +4.002176839613156289e+01,2.754399999999999977e+02,0.000000000000000000e+00,8.233495486938759100e+00,0.000000000000000000e+00,-1.000000009952694224e+00,0.000000000000000000e+00,-3.160963423657817428e-10,0.000000000000000000e+00 +4.002298294711004445e+01,2.754499999999999886e+02,0.000000000000000000e+00,8.232280935948187661e+00,0.000000000000000000e+00,-1.000000009953078139e+00,0.000000000000000000e+00,3.606512929771493229e-10,0.000000000000000000e+00 +4.002419767727751321e+01,2.754599999999999795e+02,0.000000000000000000e+00,8.231066205768625466e+00,0.000000000000000000e+00,-1.000000009952640045e+00,0.000000000000000000e+00,-2.140194361056626673e-10,0.000000000000000000e+00 +4.002541258671330127e+01,2.754700000000000273e+02,0.000000000000000000e+00,8.229851296320743970e+00,0.000000000000000000e+00,-1.000000009952900060e+00,0.000000000000000000e+00,4.080570979932800907e-10,0.000000000000000000e+00 +4.002662767549679756e+01,2.754800000000000182e+02,0.000000000000000000e+00,8.228636207525154234e+00,0.000000000000000000e+00,-1.000000009952404234e+00,0.000000000000000000e+00,-1.341291930844027534e-09,0.000000000000000000e+00 +4.002784294370744789e+01,2.754900000000000091e+02,0.000000000000000000e+00,8.227420939302410474e+00,0.000000000000000000e+00,-1.000000009954034264e+00,0.000000000000000000e+00,1.795249850345399122e-09,0.000000000000000000e+00 +4.002905839142475486e+01,2.755000000000000000e+02,0.000000000000000000e+00,8.226205491573004736e+00,0.000000000000000000e+00,-1.000000009951852231e+00,0.000000000000000000e+00,-9.640713246499803537e-10,0.000000000000000000e+00 +4.003027401872828506e+01,2.755099999999999909e+02,0.000000000000000000e+00,8.224989864257377548e+00,0.000000000000000000e+00,-1.000000009953024183e+00,0.000000000000000000e+00,4.182260491070043297e-11,0.000000000000000000e+00 +4.003148982569766190e+01,2.755199999999999818e+02,0.000000000000000000e+00,8.223774057275901939e+00,0.000000000000000000e+00,-1.000000009952973334e+00,0.000000000000000000e+00,4.400767634312724352e-11,0.000000000000000000e+00 +4.003270581241256565e+01,2.755300000000000296e+02,0.000000000000000000e+00,8.222558070548897646e+00,0.000000000000000000e+00,-1.000000009952919822e+00,0.000000000000000000e+00,-9.147131037823269783e-10,0.000000000000000000e+00 +4.003392197895273341e+01,2.755400000000000205e+02,0.000000000000000000e+00,8.221341903996624012e+00,0.000000000000000000e+00,-1.000000009954032265e+00,0.000000000000000000e+00,8.096112967642682357e-10,0.000000000000000000e+00 +4.003513832539797335e+01,2.755500000000000114e+02,0.000000000000000000e+00,8.220125557539279981e+00,0.000000000000000000e+00,-1.000000009953047497e+00,0.000000000000000000e+00,4.548484453390041920e-10,0.000000000000000000e+00 +4.003635485182813625e+01,2.755600000000000023e+02,0.000000000000000000e+00,8.218909031097009432e+00,0.000000000000000000e+00,-1.000000009952494162e+00,0.000000000000000000e+00,-7.361906424795468596e-10,0.000000000000000000e+00 +4.003757155832314396e+01,2.755699999999999932e+02,0.000000000000000000e+00,8.217692324589894071e+00,0.000000000000000000e+00,-1.000000009953389890e+00,0.000000000000000000e+00,-3.215111260763102036e-10,0.000000000000000000e+00 +4.003878844496296807e+01,2.755799999999999841e+02,0.000000000000000000e+00,8.216475437937955206e+00,0.000000000000000000e+00,-1.000000009953781133e+00,0.000000000000000000e+00,5.389348621524784892e-10,0.000000000000000000e+00 +4.004000551182765122e+01,2.755900000000000318e+02,0.000000000000000000e+00,8.215258371061157305e+00,0.000000000000000000e+00,-1.000000009953125213e+00,0.000000000000000000e+00,6.877059823584676783e-10,0.000000000000000000e+00 +4.004122275899728578e+01,2.756000000000000227e+02,0.000000000000000000e+00,8.214041123879406214e+00,0.000000000000000000e+00,-1.000000009952288105e+00,0.000000000000000000e+00,-1.031406128405310949e-09,0.000000000000000000e+00 +4.004244018655202808e+01,2.756100000000000136e+02,0.000000000000000000e+00,8.212823696312547384e+00,0.000000000000000000e+00,-1.000000009953543767e+00,0.000000000000000000e+00,2.175570539209219100e-10,0.000000000000000000e+00 +4.004365779457209129e+01,2.756200000000000045e+02,0.000000000000000000e+00,8.211606088280364091e+00,0.000000000000000000e+00,-1.000000009953278868e+00,0.000000000000000000e+00,-3.179909894948308429e-10,0.000000000000000000e+00 +4.004487558313775253e+01,2.756299999999999955e+02,0.000000000000000000e+00,8.210388299702584547e+00,0.000000000000000000e+00,-1.000000009953666114e+00,0.000000000000000000e+00,9.977675389077288464e-10,0.000000000000000000e+00 +4.004609355232933865e+01,2.756399999999999864e+02,0.000000000000000000e+00,8.209170330498874790e+00,0.000000000000000000e+00,-1.000000009952450863e+00,0.000000000000000000e+00,-5.838434750901710552e-10,0.000000000000000000e+00 +4.004731170222724757e+01,2.756500000000000341e+02,0.000000000000000000e+00,8.207952180588844016e+00,0.000000000000000000e+00,-1.000000009953162072e+00,0.000000000000000000e+00,-2.305502346465734942e-10,0.000000000000000000e+00 +4.004853003291192692e+01,2.756600000000000250e+02,0.000000000000000000e+00,8.206733849892037469e+00,0.000000000000000000e+00,-1.000000009953442959e+00,0.000000000000000000e+00,-2.961174085064257790e-10,0.000000000000000000e+00 +4.004974854446389543e+01,2.756700000000000159e+02,0.000000000000000000e+00,8.205515338327943553e+00,0.000000000000000000e+00,-1.000000009953803781e+00,0.000000000000000000e+00,4.580483894524355914e-10,0.000000000000000000e+00 +4.005096723696372152e+01,2.756800000000000068e+02,0.000000000000000000e+00,8.204296645815990274e+00,0.000000000000000000e+00,-1.000000009953245561e+00,0.000000000000000000e+00,-3.182544503541725105e-10,0.000000000000000000e+00 +4.005218611049203048e+01,2.756899999999999977e+02,0.000000000000000000e+00,8.203077772275547019e+00,0.000000000000000000e+00,-1.000000009953633473e+00,0.000000000000000000e+00,1.004711358373809235e-09,0.000000000000000000e+00 +4.005340516512952576e+01,2.756999999999999886e+02,0.000000000000000000e+00,8.201858717625921003e+00,0.000000000000000000e+00,-1.000000009952408675e+00,0.000000000000000000e+00,-1.508482133829491916e-09,0.000000000000000000e+00 +4.005462440095694632e+01,2.757099999999999795e+02,0.000000000000000000e+00,8.200639481786362595e+00,0.000000000000000000e+00,-1.000000009954247870e+00,0.000000000000000000e+00,5.504604139936513094e-10,0.000000000000000000e+00 +4.005584381805511640e+01,2.757200000000000273e+02,0.000000000000000000e+00,8.199420064676056441e+00,0.000000000000000000e+00,-1.000000009953576630e+00,0.000000000000000000e+00,5.352672747293586148e-11,0.000000000000000000e+00 +4.005706341650490288e+01,2.757300000000000182e+02,0.000000000000000000e+00,8.198200466214133897e+00,0.000000000000000000e+00,-1.000000009953511348e+00,0.000000000000000000e+00,6.267520770192384221e-10,0.000000000000000000e+00 +4.005828319638723656e+01,2.757400000000000091e+02,0.000000000000000000e+00,8.196980686319662368e+00,0.000000000000000000e+00,-1.000000009952746849e+00,0.000000000000000000e+00,-1.268606450636157035e-09,0.000000000000000000e+00 +4.005950315778310511e+01,2.757500000000000000e+02,0.000000000000000000e+00,8.195760724911650641e+00,0.000000000000000000e+00,-1.000000009954294500e+00,0.000000000000000000e+00,1.570144537378086934e-09,0.000000000000000000e+00 +4.006072330077356725e+01,2.757599999999999909e+02,0.000000000000000000e+00,8.194540581909043553e+00,0.000000000000000000e+00,-1.000000009952378699e+00,0.000000000000000000e+00,-1.553898711248518729e-09,0.000000000000000000e+00 +4.006194362543973142e+01,2.757699999999999818e+02,0.000000000000000000e+00,8.193320257230732651e+00,0.000000000000000000e+00,-1.000000009954274960e+00,0.000000000000000000e+00,1.331350977072143330e-09,0.000000000000000000e+00 +4.006316413186277714e+01,2.757800000000000296e+02,0.000000000000000000e+00,8.192099750795540203e+00,0.000000000000000000e+00,-1.000000009952650037e+00,0.000000000000000000e+00,-1.658029030260385013e-09,0.000000000000000000e+00 +4.006438482012393365e+01,2.757900000000000205e+02,0.000000000000000000e+00,8.190879062522236964e+00,0.000000000000000000e+00,-1.000000009954673974e+00,0.000000000000000000e+00,1.442806842954811457e-09,0.000000000000000000e+00 +4.006560569030449415e+01,2.758000000000000114e+02,0.000000000000000000e+00,8.189658192329524411e+00,0.000000000000000000e+00,-1.000000009952912494e+00,0.000000000000000000e+00,-5.200822534870406139e-11,0.000000000000000000e+00 +4.006682674248581577e+01,2.758100000000000023e+02,0.000000000000000000e+00,8.188437140136052506e+00,0.000000000000000000e+00,-1.000000009952975999e+00,0.000000000000000000e+00,-1.330739328257019412e-09,0.000000000000000000e+00 +4.006804797674931251e+01,2.758199999999999932e+02,0.000000000000000000e+00,8.187215905860403709e+00,0.000000000000000000e+00,-1.000000009954601143e+00,0.000000000000000000e+00,1.220374476496941284e-09,0.000000000000000000e+00 +4.006926939317645520e+01,2.758299999999999841e+02,0.000000000000000000e+00,8.185994489421100084e+00,0.000000000000000000e+00,-1.000000009953110558e+00,0.000000000000000000e+00,-6.925269025946787736e-10,0.000000000000000000e+00 +4.007049099184878571e+01,2.758400000000000318e+02,0.000000000000000000e+00,8.184772890736608630e+00,0.000000000000000000e+00,-1.000000009953956548e+00,0.000000000000000000e+00,1.183117415563990516e-10,0.000000000000000000e+00 +4.007171277284790278e+01,2.758500000000000227e+02,0.000000000000000000e+00,8.183551109725328843e+00,0.000000000000000000e+00,-1.000000009953811997e+00,0.000000000000000000e+00,1.230185753549949935e-10,0.000000000000000000e+00 +4.007293473625546198e+01,2.758600000000000136e+02,0.000000000000000000e+00,8.182329146305603373e+00,0.000000000000000000e+00,-1.000000009953661673e+00,0.000000000000000000e+00,5.552269282362836659e-10,0.000000000000000000e+00 +4.007415688215318994e+01,2.758700000000000045e+02,0.000000000000000000e+00,8.181107000395712703e+00,0.000000000000000000e+00,-1.000000009952983104e+00,0.000000000000000000e+00,-9.210013305784028940e-10,0.000000000000000000e+00 +4.007537921062286301e+01,2.758799999999999955e+02,0.000000000000000000e+00,8.179884671913876915e+00,0.000000000000000000e+00,-1.000000009954108871e+00,0.000000000000000000e+00,4.927619893214074289e-10,0.000000000000000000e+00 +4.007660172174632152e+01,2.758899999999999864e+02,0.000000000000000000e+00,8.178662160778252144e+00,0.000000000000000000e+00,-1.000000009953506463e+00,0.000000000000000000e+00,8.480849864785797702e-11,0.000000000000000000e+00 +4.007782441560546260e+01,2.759000000000000341e+02,0.000000000000000000e+00,8.177439466906937682e+00,0.000000000000000000e+00,-1.000000009953402769e+00,0.000000000000000000e+00,-9.135070024426106413e-10,0.000000000000000000e+00 +4.007904729228226159e+01,2.759100000000000250e+02,0.000000000000000000e+00,8.176216590217968871e+00,0.000000000000000000e+00,-1.000000009954519875e+00,0.000000000000000000e+00,1.104177844750823857e-09,0.000000000000000000e+00 +4.008027035185873643e+01,2.759200000000000159e+02,0.000000000000000000e+00,8.174993530629318883e+00,0.000000000000000000e+00,-1.000000009953169400e+00,0.000000000000000000e+00,-9.446369538456119024e-10,0.000000000000000000e+00 +4.008149359441697612e+01,2.759300000000000068e+02,0.000000000000000000e+00,8.173770288058904043e+00,0.000000000000000000e+00,-1.000000009954324920e+00,0.000000000000000000e+00,1.294234850938115130e-09,0.000000000000000000e+00 +4.008271702003912651e+01,2.759399999999999977e+02,0.000000000000000000e+00,8.172546862424573177e+00,0.000000000000000000e+00,-1.000000009952741520e+00,0.000000000000000000e+00,-1.631932676411022673e-09,0.000000000000000000e+00 +4.008394062880740449e+01,2.759499999999999886e+02,0.000000000000000000e+00,8.171323253644120044e+00,0.000000000000000000e+00,-1.000000009954738367e+00,0.000000000000000000e+00,9.999148720314986071e-10,0.000000000000000000e+00 +4.008516442080406961e+01,2.759599999999999795e+02,0.000000000000000000e+00,8.170099461635269122e+00,0.000000000000000000e+00,-1.000000009953514679e+00,0.000000000000000000e+00,-2.585130272698745413e-10,0.000000000000000000e+00 +4.008638839611146665e+01,2.759700000000000273e+02,0.000000000000000000e+00,8.168875486315691603e+00,0.000000000000000000e+00,-1.000000009953831093e+00,0.000000000000000000e+00,5.668296031377314714e-10,0.000000000000000000e+00 +4.008761255481198305e+01,2.759800000000000182e+02,0.000000000000000000e+00,8.167651327602991174e+00,0.000000000000000000e+00,-1.000000009953137203e+00,0.000000000000000000e+00,-1.223261674280932606e-09,0.000000000000000000e+00 +4.008883689698807729e+01,2.759900000000000091e+02,0.000000000000000000e+00,8.166426985414712902e+00,0.000000000000000000e+00,-1.000000009954634894e+00,0.000000000000000000e+00,3.412651402923237290e-10,0.000000000000000000e+00 +4.009006142272226469e+01,2.760000000000000000e+02,0.000000000000000000e+00,8.165202459668336132e+00,0.000000000000000000e+00,-1.000000009954217006e+00,0.000000000000000000e+00,5.614982260835973251e-10,0.000000000000000000e+00 +4.009128613209712455e+01,2.760099999999999909e+02,0.000000000000000000e+00,8.163977750281283363e+00,0.000000000000000000e+00,-1.000000009953529334e+00,0.000000000000000000e+00,-5.162761025978811692e-10,0.000000000000000000e+00 +4.009251102519530008e+01,2.760199999999999818e+02,0.000000000000000000e+00,8.162752857170913146e+00,0.000000000000000000e+00,-1.000000009954161717e+00,0.000000000000000000e+00,7.027044019392388363e-10,0.000000000000000000e+00 +4.009373610209949845e+01,2.760300000000000296e+02,0.000000000000000000e+00,8.161527780254520081e+00,0.000000000000000000e+00,-1.000000009953300850e+00,0.000000000000000000e+00,-4.733527028571950112e-10,0.000000000000000000e+00 +4.009496136289248369e+01,2.760400000000000205e+02,0.000000000000000000e+00,8.160302519449340153e+00,0.000000000000000000e+00,-1.000000009953880831e+00,0.000000000000000000e+00,-4.493638849519668884e-10,0.000000000000000000e+00 +4.009618680765708376e+01,2.760500000000000114e+02,0.000000000000000000e+00,8.159077074672543617e+00,0.000000000000000000e+00,-1.000000009954431501e+00,0.000000000000000000e+00,8.159802421375846736e-10,0.000000000000000000e+00 +4.009741243647618347e+01,2.760600000000000023e+02,0.000000000000000000e+00,8.157851445841240334e+00,0.000000000000000000e+00,-1.000000009953431412e+00,0.000000000000000000e+00,-1.807784087526255898e-10,0.000000000000000000e+00 +4.009863824943274579e+01,2.760699999999999932e+02,0.000000000000000000e+00,8.156625632872479770e+00,0.000000000000000000e+00,-1.000000009953653013e+00,0.000000000000000000e+00,-1.029811199615713760e-09,0.000000000000000000e+00 +4.009986424660977633e+01,2.760799999999999841e+02,0.000000000000000000e+00,8.155399635683245663e+00,0.000000000000000000e+00,-1.000000009954915559e+00,0.000000000000000000e+00,6.743651913173477801e-10,0.000000000000000000e+00 +4.010109042809035884e+01,2.760900000000000318e+02,0.000000000000000000e+00,8.154173454190459580e+00,0.000000000000000000e+00,-1.000000009954088664e+00,0.000000000000000000e+00,2.493182737244362015e-10,0.000000000000000000e+00 +4.010231679395762683e+01,2.761000000000000227e+02,0.000000000000000000e+00,8.152947088310984469e+00,0.000000000000000000e+00,-1.000000009953782909e+00,0.000000000000000000e+00,1.021019304172065114e-10,0.000000000000000000e+00 +4.010354334429478484e+01,2.761100000000000136e+02,0.000000000000000000e+00,8.151720537961617552e+00,0.000000000000000000e+00,-1.000000009953657676e+00,0.000000000000000000e+00,-9.039367558156889052e-10,0.000000000000000000e+00 +4.010477007918510139e+01,2.761200000000000045e+02,0.000000000000000000e+00,8.150493803059093878e+00,0.000000000000000000e+00,-1.000000009954766567e+00,0.000000000000000000e+00,8.156647706233885432e-10,0.000000000000000000e+00 +4.010599699871189472e+01,2.761299999999999955e+02,0.000000000000000000e+00,8.149266883520084548e+00,0.000000000000000000e+00,-1.000000009953765812e+00,0.000000000000000000e+00,-5.958685955194473780e-10,0.000000000000000000e+00 +4.010722410295856122e+01,2.761399999999999864e+02,0.000000000000000000e+00,8.148039779261202042e+00,0.000000000000000000e+00,-1.000000009954497004e+00,0.000000000000000000e+00,8.045638133141645496e-10,0.000000000000000000e+00 +4.010845139200855414e+01,2.761500000000000341e+02,0.000000000000000000e+00,8.146812490198991341e+00,0.000000000000000000e+00,-1.000000009953509572e+00,0.000000000000000000e+00,-8.357375614824601056e-10,0.000000000000000000e+00 +4.010967886594539067e+01,2.761600000000000250e+02,0.000000000000000000e+00,8.145585016249938803e+00,0.000000000000000000e+00,-1.000000009954535418e+00,0.000000000000000000e+00,4.225083971123279691e-10,0.000000000000000000e+00 +4.011090652485264485e+01,2.761700000000000159e+02,0.000000000000000000e+00,8.144357357330463287e+00,0.000000000000000000e+00,-1.000000009954016722e+00,0.000000000000000000e+00,-9.240978226179011158e-11,0.000000000000000000e+00 +4.011213436881396177e+01,2.761800000000000068e+02,0.000000000000000000e+00,8.143129513356925031e+00,0.000000000000000000e+00,-1.000000009954130187e+00,0.000000000000000000e+00,2.169765570776040878e-11,0.000000000000000000e+00 +4.011336239791304337e+01,2.761899999999999977e+02,0.000000000000000000e+00,8.141901484245618548e+00,0.000000000000000000e+00,-1.000000009954103541e+00,0.000000000000000000e+00,-3.693468804647226098e-10,0.000000000000000000e+00 +4.011459061223366263e+01,2.761999999999999886e+02,0.000000000000000000e+00,8.140673269912776178e+00,0.000000000000000000e+00,-1.000000009954557179e+00,0.000000000000000000e+00,1.132999029170040409e-09,0.000000000000000000e+00 +4.011581901185964227e+01,2.762099999999999795e+02,0.000000000000000000e+00,8.139444870274566313e+00,0.000000000000000000e+00,-1.000000009953165403e+00,0.000000000000000000e+00,-1.312294921686243890e-09,0.000000000000000000e+00 +4.011704759687488320e+01,2.762200000000000273e+02,0.000000000000000000e+00,8.138216285247096948e+00,0.000000000000000000e+00,-1.000000009954777669e+00,0.000000000000000000e+00,5.782550463526871934e-10,0.000000000000000000e+00 +4.011827636736334313e+01,2.762300000000000182e+02,0.000000000000000000e+00,8.136987514746406802e+00,0.000000000000000000e+00,-1.000000009954067126e+00,0.000000000000000000e+00,-2.124766433318331253e-10,0.000000000000000000e+00 +4.011950532340903663e+01,2.762400000000000091e+02,0.000000000000000000e+00,8.135758558688477748e+00,0.000000000000000000e+00,-1.000000009954328251e+00,0.000000000000000000e+00,-1.096546286022161142e-10,0.000000000000000000e+00 +4.012073446509605645e+01,2.762500000000000000e+02,0.000000000000000000e+00,8.134529416989224160e+00,0.000000000000000000e+00,-1.000000009954463032e+00,0.000000000000000000e+00,-2.451051898967188713e-10,0.000000000000000000e+00 +4.012196379250854505e+01,2.762599999999999909e+02,0.000000000000000000e+00,8.133300089564498236e+00,0.000000000000000000e+00,-1.000000009954764346e+00,0.000000000000000000e+00,6.004801722037535062e-10,0.000000000000000000e+00 +4.012319330573071596e+01,2.762699999999999818e+02,0.000000000000000000e+00,8.132070576330088230e+00,0.000000000000000000e+00,-1.000000009954026048e+00,0.000000000000000000e+00,1.215224254085300628e-10,0.000000000000000000e+00 +4.012442300484684665e+01,2.762800000000000296e+02,0.000000000000000000e+00,8.130840877201720218e+00,0.000000000000000000e+00,-1.000000009953876612e+00,0.000000000000000000e+00,-4.612820889982137484e-10,0.000000000000000000e+00 +4.012565288994127144e+01,2.762900000000000205e+02,0.000000000000000000e+00,8.129610992095054556e+00,0.000000000000000000e+00,-1.000000009954443936e+00,0.000000000000000000e+00,7.058082780251699086e-11,0.000000000000000000e+00 +4.012688296109839570e+01,2.763000000000000114e+02,0.000000000000000000e+00,8.128380920925687647e+00,0.000000000000000000e+00,-1.000000009954357116e+00,0.000000000000000000e+00,-5.867610036498362838e-10,0.000000000000000000e+00 +4.012811321840268164e+01,2.763100000000000023e+02,0.000000000000000000e+00,8.127150663609153725e+00,0.000000000000000000e+00,-1.000000009955078983e+00,0.000000000000000000e+00,1.132199739816904356e-09,0.000000000000000000e+00 +4.012934366193866254e+01,2.763199999999999932e+02,0.000000000000000000e+00,8.125920220060921295e+00,0.000000000000000000e+00,-1.000000009953685876e+00,0.000000000000000000e+00,-5.939810724262651418e-10,0.000000000000000000e+00 +4.013057429179093560e+01,2.763299999999999841e+02,0.000000000000000000e+00,8.124689590196398470e+00,0.000000000000000000e+00,-1.000000009954416846e+00,0.000000000000000000e+00,1.454059053096101101e-10,0.000000000000000000e+00 +4.013180510804415491e+01,2.763400000000000318e+02,0.000000000000000000e+00,8.123458773930924082e+00,0.000000000000000000e+00,-1.000000009954237878e+00,0.000000000000000000e+00,-1.296008884448111972e-09,0.000000000000000000e+00 +4.013303611078304556e+01,2.763500000000000227e+02,0.000000000000000000e+00,8.122227771179776568e+00,0.000000000000000000e+00,-1.000000009955833269e+00,0.000000000000000000e+00,2.159687485733870378e-09,0.000000000000000000e+00 +4.013426730009239662e+01,2.763600000000000136e+02,0.000000000000000000e+00,8.120996581858166863e+00,0.000000000000000000e+00,-1.000000009953174285e+00,0.000000000000000000e+00,-1.161816886628134539e-09,0.000000000000000000e+00 +4.013549867605706112e+01,2.763700000000000045e+02,0.000000000000000000e+00,8.119765205881249059e+00,0.000000000000000000e+00,-1.000000009954604918e+00,0.000000000000000000e+00,-6.683535862129062212e-10,0.000000000000000000e+00 +4.013673023876194890e+01,2.763799999999999955e+02,0.000000000000000000e+00,8.118533643164102642e+00,0.000000000000000000e+00,-1.000000009955428038e+00,0.000000000000000000e+00,1.338847907379032506e-09,0.000000000000000000e+00 +4.013796198829204087e+01,2.763899999999999864e+02,0.000000000000000000e+00,8.117301893621748476e+00,0.000000000000000000e+00,-1.000000009953778912e+00,0.000000000000000000e+00,-9.480640264059123299e-10,0.000000000000000000e+00 +4.013919392473238190e+01,2.764000000000000341e+02,0.000000000000000000e+00,8.116069957169145255e+00,0.000000000000000000e+00,-1.000000009954946867e+00,0.000000000000000000e+00,7.109401063639059347e-10,0.000000000000000000e+00 +4.014042604816808080e+01,2.764100000000000250e+02,0.000000000000000000e+00,8.114837833721180615e+00,0.000000000000000000e+00,-1.000000009954070901e+00,0.000000000000000000e+00,-6.611009520246071794e-10,0.000000000000000000e+00 +4.014165835868431031e+01,2.764200000000000159e+02,0.000000000000000000e+00,8.113605523192683577e+00,0.000000000000000000e+00,-1.000000009954885583e+00,0.000000000000000000e+00,-3.388776368212873409e-10,0.000000000000000000e+00 +4.014289085636630716e+01,2.764300000000000068e+02,0.000000000000000000e+00,8.112373025498413881e+00,0.000000000000000000e+00,-1.000000009955303248e+00,0.000000000000000000e+00,5.526414979468515158e-10,0.000000000000000000e+00 +4.014412354129937910e+01,2.764399999999999977e+02,0.000000000000000000e+00,8.111140340553069095e+00,0.000000000000000000e+00,-1.000000009954622016e+00,0.000000000000000000e+00,8.891709560046146340e-10,0.000000000000000000e+00 +4.014535641356889073e+01,2.764499999999999886e+02,0.000000000000000000e+00,8.109907468271282838e+00,0.000000000000000000e+00,-1.000000009953525781e+00,0.000000000000000000e+00,-1.619424546953932396e-09,0.000000000000000000e+00 +4.014658947326027771e+01,2.764599999999999795e+02,0.000000000000000000e+00,8.108674408567623004e+00,0.000000000000000000e+00,-1.000000009955522629e+00,0.000000000000000000e+00,1.250618551871489852e-09,0.000000000000000000e+00 +4.014782272045903255e+01,2.764700000000000273e+02,0.000000000000000000e+00,8.107441161356588211e+00,0.000000000000000000e+00,-1.000000009953980307e+00,0.000000000000000000e+00,-9.692349858868324828e-10,0.000000000000000000e+00 +4.014905615525072591e+01,2.764800000000000182e+02,0.000000000000000000e+00,8.106207726552620230e+00,0.000000000000000000e+00,-1.000000009955175795e+00,0.000000000000000000e+00,1.110202802076555673e-09,0.000000000000000000e+00 +4.015028977772097818e+01,2.764900000000000091e+02,0.000000000000000000e+00,8.104974104070088003e+00,0.000000000000000000e+00,-1.000000009953806224e+00,0.000000000000000000e+00,-1.805064770184450027e-09,0.000000000000000000e+00 +4.015152358795548082e+01,2.765000000000000000e+02,0.000000000000000000e+00,8.103740293823301855e+00,0.000000000000000000e+00,-1.000000009956033331e+00,0.000000000000000000e+00,2.000203938171458893e-09,0.000000000000000000e+00 +4.015275758603999634e+01,2.765099999999999909e+02,0.000000000000000000e+00,8.102506295726499275e+00,0.000000000000000000e+00,-1.000000009953565083e+00,0.000000000000000000e+00,-1.427779893489977711e-09,0.000000000000000000e+00 +4.015399177206035120e+01,2.765199999999999818e+02,0.000000000000000000e+00,8.101272109693862689e+00,0.000000000000000000e+00,-1.000000009955327229e+00,0.000000000000000000e+00,7.869941471818775109e-10,0.000000000000000000e+00 +4.015522614610242869e+01,2.765300000000000296e+02,0.000000000000000000e+00,8.100037735639498138e+00,0.000000000000000000e+00,-1.000000009954355784e+00,0.000000000000000000e+00,-6.388519499409882347e-10,0.000000000000000000e+00 +4.015646070825218317e+01,2.765400000000000205e+02,0.000000000000000000e+00,8.098803173477454820e+00,0.000000000000000000e+00,-1.000000009955144487e+00,0.000000000000000000e+00,1.701187591265290013e-10,0.000000000000000000e+00 +4.015769545859563294e+01,2.765500000000000114e+02,0.000000000000000000e+00,8.097568423121710879e+00,0.000000000000000000e+00,-1.000000009954934432e+00,0.000000000000000000e+00,-2.371590202021053635e-10,0.000000000000000000e+00 +4.015893039721886737e+01,2.765600000000000023e+02,0.000000000000000000e+00,8.096333484486182286e+00,0.000000000000000000e+00,-1.000000009955227309e+00,0.000000000000000000e+00,5.155938883284776044e-10,0.000000000000000000e+00 +4.016016552420803265e+01,2.765699999999999932e+02,0.000000000000000000e+00,8.095098357484717511e+00,0.000000000000000000e+00,-1.000000009954590485e+00,0.000000000000000000e+00,1.446965697876655794e-10,0.000000000000000000e+00 +4.016140083964935314e+01,2.765799999999999841e+02,0.000000000000000000e+00,8.093863042031101074e+00,0.000000000000000000e+00,-1.000000009954411739e+00,0.000000000000000000e+00,-1.380248541300562920e-10,0.000000000000000000e+00 +4.016263634362910295e+01,2.765900000000000318e+02,0.000000000000000000e+00,8.092627538039049995e+00,0.000000000000000000e+00,-1.000000009954582270e+00,0.000000000000000000e+00,-2.875078855182895143e-10,0.000000000000000000e+00 +4.016387203623363433e+01,2.766000000000000227e+02,0.000000000000000000e+00,8.091391845422215567e+00,0.000000000000000000e+00,-1.000000009954937541e+00,0.000000000000000000e+00,-2.572802664834086935e-10,0.000000000000000000e+00 +4.016510791754936349e+01,2.766100000000000136e+02,0.000000000000000000e+00,8.090155964094183361e+00,0.000000000000000000e+00,-1.000000009955255509e+00,0.000000000000000000e+00,-1.616737936346260817e-12,0.000000000000000000e+00 +4.016634398766277059e+01,2.766200000000000045e+02,0.000000000000000000e+00,8.088919893968473218e+00,0.000000000000000000e+00,-1.000000009955257507e+00,0.000000000000000000e+00,5.257187691764136123e-10,0.000000000000000000e+00 +4.016758024666039972e+01,2.766299999999999955e+02,0.000000000000000000e+00,8.087683634958539258e+00,0.000000000000000000e+00,-1.000000009954607583e+00,0.000000000000000000e+00,2.084954586797774465e-10,0.000000000000000000e+00 +4.016881669462885895e+01,2.766399999999999864e+02,0.000000000000000000e+00,8.086447186977769874e+00,0.000000000000000000e+00,-1.000000009954349789e+00,0.000000000000000000e+00,-9.049581933233232712e-10,0.000000000000000000e+00 +4.017005333165483449e+01,2.766500000000000341e+02,0.000000000000000000e+00,8.085210549939485958e+00,0.000000000000000000e+00,-1.000000009955468894e+00,0.000000000000000000e+00,7.145203981542092802e-10,0.000000000000000000e+00 +4.017129015782506940e+01,2.766600000000000250e+02,0.000000000000000000e+00,8.083973723756940899e+00,0.000000000000000000e+00,-1.000000009954585156e+00,0.000000000000000000e+00,-6.923325613368396297e-10,0.000000000000000000e+00 +4.017252717322637068e+01,2.766700000000000159e+02,0.000000000000000000e+00,8.082736708343325915e+00,0.000000000000000000e+00,-1.000000009955441582e+00,0.000000000000000000e+00,7.259675080028838723e-10,0.000000000000000000e+00 +4.017376437794561639e+01,2.766800000000000068e+02,0.000000000000000000e+00,8.081499503611761170e+00,0.000000000000000000e+00,-1.000000009954543412e+00,0.000000000000000000e+00,-7.875855816708470629e-10,0.000000000000000000e+00 +4.017500177206975565e+01,2.766899999999999977e+02,0.000000000000000000e+00,8.080262109475304655e+00,0.000000000000000000e+00,-1.000000009955517966e+00,0.000000000000000000e+00,6.155826803324553698e-10,0.000000000000000000e+00 +4.017623935568579441e+01,2.766999999999999886e+02,0.000000000000000000e+00,8.079024525846943305e+00,0.000000000000000000e+00,-1.000000009954756131e+00,0.000000000000000000e+00,-8.178407465328210448e-10,0.000000000000000000e+00 +4.017747712888081679e+01,2.767099999999999795e+02,0.000000000000000000e+00,8.077786752639601886e+00,0.000000000000000000e+00,-1.000000009955768432e+00,0.000000000000000000e+00,7.567320616660761776e-10,0.000000000000000000e+00 +4.017871509174195666e+01,2.767200000000000273e+02,0.000000000000000000e+00,8.076548789766134107e+00,0.000000000000000000e+00,-1.000000009954831626e+00,0.000000000000000000e+00,-4.103194146894953873e-10,0.000000000000000000e+00 +4.017995324435643312e+01,2.767300000000000182e+02,0.000000000000000000e+00,8.075310637139331504e+00,0.000000000000000000e+00,-1.000000009955339664e+00,0.000000000000000000e+00,3.639950694943126393e-10,0.000000000000000000e+00 +4.018119158681152214e+01,2.767400000000000091e+02,0.000000000000000000e+00,8.074072294671914563e+00,0.000000000000000000e+00,-1.000000009954888913e+00,0.000000000000000000e+00,-3.495968175972804221e-10,0.000000000000000000e+00 +4.018243011919457075e+01,2.767500000000000000e+02,0.000000000000000000e+00,8.072833762276539815e+00,0.000000000000000000e+00,-1.000000009955321900e+00,0.000000000000000000e+00,9.706545527949352973e-10,0.000000000000000000e+00 +4.018366884159298280e+01,2.767599999999999909e+02,0.000000000000000000e+00,8.071595039865794519e+00,0.000000000000000000e+00,-1.000000009954119529e+00,0.000000000000000000e+00,-1.417314567381449165e-09,0.000000000000000000e+00 +4.018490775409424032e+01,2.767699999999999818e+02,0.000000000000000000e+00,8.070356127352201980e+00,0.000000000000000000e+00,-1.000000009955875457e+00,0.000000000000000000e+00,6.361525584552899916e-10,0.000000000000000000e+00 +4.018614685678589638e+01,2.767800000000000296e+02,0.000000000000000000e+00,8.069117024648212677e+00,0.000000000000000000e+00,-1.000000009955087199e+00,0.000000000000000000e+00,2.336381887988740733e-10,0.000000000000000000e+00 +4.018738614975555379e+01,2.767900000000000205e+02,0.000000000000000000e+00,8.067877731666216690e+00,0.000000000000000000e+00,-1.000000009954797653e+00,0.000000000000000000e+00,-2.620860222497006633e-10,0.000000000000000000e+00 +4.018862563309090064e+01,2.768000000000000114e+02,0.000000000000000000e+00,8.066638248318533044e+00,0.000000000000000000e+00,-1.000000009955122504e+00,0.000000000000000000e+00,-8.042279228115447798e-10,0.000000000000000000e+00 +4.018986530687968184e+01,2.768100000000000023e+02,0.000000000000000000e+00,8.065398574517413266e+00,0.000000000000000000e+00,-1.000000009956119484e+00,0.000000000000000000e+00,9.652833713824383364e-10,0.000000000000000000e+00 +4.019110517120970627e+01,2.768199999999999932e+02,0.000000000000000000e+00,8.064158710175041378e+00,0.000000000000000000e+00,-1.000000009954922664e+00,0.000000000000000000e+00,4.712866924534588207e-10,0.000000000000000000e+00 +4.019234522616886807e+01,2.768299999999999841e+02,0.000000000000000000e+00,8.062918655203537455e+00,0.000000000000000000e+00,-1.000000009954338243e+00,0.000000000000000000e+00,-1.082073993786684735e-09,0.000000000000000000e+00 +4.019358547184511110e+01,2.768400000000000318e+02,0.000000000000000000e+00,8.061678409514950516e+00,0.000000000000000000e+00,-1.000000009955680280e+00,0.000000000000000000e+00,-1.833013450212763494e-10,0.000000000000000000e+00 +4.019482590832645030e+01,2.768500000000000227e+02,0.000000000000000000e+00,8.060437973021260305e+00,0.000000000000000000e+00,-1.000000009955907654e+00,0.000000000000000000e+00,9.049111325064694416e-10,0.000000000000000000e+00 +4.019606653570097876e+01,2.768600000000000136e+02,0.000000000000000000e+00,8.059197345634382614e+00,0.000000000000000000e+00,-1.000000009954784996e+00,0.000000000000000000e+00,-7.855910665840446295e-11,0.000000000000000000e+00 +4.019730735405684641e+01,2.768700000000000045e+02,0.000000000000000000e+00,8.057956527266165736e+00,0.000000000000000000e+00,-1.000000009954882474e+00,0.000000000000000000e+00,-7.759872180102736449e-10,0.000000000000000000e+00 +4.019854836348227423e+01,2.768799999999999955e+02,0.000000000000000000e+00,8.056715517828386908e+00,0.000000000000000000e+00,-1.000000009955845481e+00,0.000000000000000000e+00,1.162817639197222526e-11,0.000000000000000000e+00 +4.019978956406554715e+01,2.768899999999999864e+02,0.000000000000000000e+00,8.055474317232755865e+00,0.000000000000000000e+00,-1.000000009955831048e+00,0.000000000000000000e+00,1.178378834552726795e-09,0.000000000000000000e+00 +4.020103095589502828e+01,2.769000000000000341e+02,0.000000000000000000e+00,8.054232925390916620e+00,0.000000000000000000e+00,-1.000000009954368219e+00,0.000000000000000000e+00,-6.854933243932356231e-10,0.000000000000000000e+00 +4.020227253905913756e+01,2.769100000000000250e+02,0.000000000000000000e+00,8.052991342214445680e+00,0.000000000000000000e+00,-1.000000009955219316e+00,0.000000000000000000e+00,-9.212411143952620257e-10,0.000000000000000000e+00 +4.020351431364637307e+01,2.769200000000000159e+02,0.000000000000000000e+00,8.051749567614846725e+00,0.000000000000000000e+00,-1.000000009956363289e+00,0.000000000000000000e+00,1.668419335243015271e-09,0.000000000000000000e+00 +4.020475627974529687e+01,2.769300000000000068e+02,0.000000000000000000e+00,8.050507601503557709e+00,0.000000000000000000e+00,-1.000000009954291169e+00,0.000000000000000000e+00,-9.302523542192743823e-10,0.000000000000000000e+00 +4.020599843744453494e+01,2.769399999999999977e+02,0.000000000000000000e+00,8.049265443791952634e+00,0.000000000000000000e+00,-1.000000009955446689e+00,0.000000000000000000e+00,-6.069657098510255381e-10,0.000000000000000000e+00 +4.020724078683279146e+01,2.769499999999999886e+02,0.000000000000000000e+00,8.048023094391329124e+00,0.000000000000000000e+00,-1.000000009956200753e+00,0.000000000000000000e+00,3.811713891263381200e-10,0.000000000000000000e+00 +4.020848332799882741e+01,2.769599999999999795e+02,0.000000000000000000e+00,8.046780553212920850e+00,0.000000000000000000e+00,-1.000000009955727132e+00,0.000000000000000000e+00,9.314297560769393227e-10,0.000000000000000000e+00 +4.020972606103148195e+01,2.769700000000000273e+02,0.000000000000000000e+00,8.045537820167893983e+00,0.000000000000000000e+00,-1.000000009954569613e+00,0.000000000000000000e+00,-1.207116607801471866e-09,0.000000000000000000e+00 +4.021096898601965819e+01,2.769800000000000182e+02,0.000000000000000000e+00,8.044294895167345416e+00,0.000000000000000000e+00,-1.000000009956069968e+00,0.000000000000000000e+00,9.129228752780061740e-10,0.000000000000000000e+00 +4.021221210305233029e+01,2.769900000000000091e+02,0.000000000000000000e+00,8.043051778122299211e+00,0.000000000000000000e+00,-1.000000009954935098e+00,0.000000000000000000e+00,-7.081157948952680929e-10,0.000000000000000000e+00 +4.021345541221853637e+01,2.770000000000000000e+02,0.000000000000000000e+00,8.041808468943717259e+00,0.000000000000000000e+00,-1.000000009955815505e+00,0.000000000000000000e+00,-2.746314603560104209e-10,0.000000000000000000e+00 +4.021469891360738558e+01,2.770099999999999909e+02,0.000000000000000000e+00,8.040564967542486841e+00,0.000000000000000000e+00,-1.000000009956157010e+00,0.000000000000000000e+00,1.110853525344554052e-09,0.000000000000000000e+00 +4.021594260730805814e+01,2.770199999999999818e+02,0.000000000000000000e+00,8.039321273829429515e+00,0.000000000000000000e+00,-1.000000009954775448e+00,0.000000000000000000e+00,-1.096222489284904317e-09,0.000000000000000000e+00 +4.021718649340980534e+01,2.770300000000000296e+02,0.000000000000000000e+00,8.038077387715299338e+00,0.000000000000000000e+00,-1.000000009956139024e+00,0.000000000000000000e+00,1.189933972331978017e-09,0.000000000000000000e+00 +4.021843057200194238e+01,2.770400000000000205e+02,0.000000000000000000e+00,8.036833309110775758e+00,0.000000000000000000e+00,-1.000000009954658653e+00,0.000000000000000000e+00,-1.165658573556695817e-09,0.000000000000000000e+00 +4.021967484317385555e+01,2.770500000000000114e+02,0.000000000000000000e+00,8.035589037926476053e+00,0.000000000000000000e+00,-1.000000009956109048e+00,0.000000000000000000e+00,-8.064851553563660806e-11,0.000000000000000000e+00 +4.022091930701500218e+01,2.770600000000000023e+02,0.000000000000000000e+00,8.034344574072941114e+00,0.000000000000000000e+00,-1.000000009956209412e+00,0.000000000000000000e+00,1.049338722240934129e-09,0.000000000000000000e+00 +4.022216396361490354e+01,2.770699999999999932e+02,0.000000000000000000e+00,8.033099917460647887e+00,0.000000000000000000e+00,-1.000000009954903346e+00,0.000000000000000000e+00,-1.165117084164289859e-09,0.000000000000000000e+00 +4.022340881306315197e+01,2.770799999999999841e+02,0.000000000000000000e+00,8.031855068000004039e+00,0.000000000000000000e+00,-1.000000009956353741e+00,0.000000000000000000e+00,1.348808173579830414e-09,0.000000000000000000e+00 +4.022465385544941796e+01,2.770900000000000318e+02,0.000000000000000000e+00,8.030610025601342628e+00,0.000000000000000000e+00,-1.000000009954674418e+00,0.000000000000000000e+00,-1.674737889710793523e-09,0.000000000000000000e+00 +4.022589909086342885e+01,2.771000000000000227e+02,0.000000000000000000e+00,8.029364790174934541e+00,0.000000000000000000e+00,-1.000000009956759861e+00,0.000000000000000000e+00,1.270299957001262114e-09,0.000000000000000000e+00 +4.022714451939499014e+01,2.771100000000000136e+02,0.000000000000000000e+00,8.028119361630972506e+00,0.000000000000000000e+00,-1.000000009955177793e+00,0.000000000000000000e+00,-7.700834557199564750e-11,0.000000000000000000e+00 +4.022839014113397127e+01,2.771200000000000045e+02,0.000000000000000000e+00,8.026873739879588854e+00,0.000000000000000000e+00,-1.000000009955273716e+00,0.000000000000000000e+00,-1.085078856286324279e-09,0.000000000000000000e+00 +4.022963595617031984e+01,2.771299999999999955e+02,0.000000000000000000e+00,8.025627924830839532e+00,0.000000000000000000e+00,-1.000000009956625524e+00,0.000000000000000000e+00,1.726625708269002952e-09,0.000000000000000000e+00 +4.023088196459404031e+01,2.771399999999999864e+02,0.000000000000000000e+00,8.024381916394711212e+00,0.000000000000000000e+00,-1.000000009954474134e+00,0.000000000000000000e+00,-1.890993257063146465e-09,0.000000000000000000e+00 +4.023212816649522239e+01,2.771500000000000341e+02,0.000000000000000000e+00,8.023135714481126612e+00,0.000000000000000000e+00,-1.000000009956830693e+00,0.000000000000000000e+00,6.958515563929186231e-10,0.000000000000000000e+00 +4.023337456196401263e+01,2.771600000000000250e+02,0.000000000000000000e+00,8.021889318999928520e+00,0.000000000000000000e+00,-1.000000009955963387e+00,0.000000000000000000e+00,3.845648031069091924e-10,0.000000000000000000e+00 +4.023462115109062864e+01,2.771700000000000159e+02,0.000000000000000000e+00,8.020642729860899323e+00,0.000000000000000000e+00,-1.000000009955483993e+00,0.000000000000000000e+00,-4.870872120348215004e-10,0.000000000000000000e+00 +4.023586793396536621e+01,2.771800000000000068e+02,0.000000000000000000e+00,8.019395946973746803e+00,0.000000000000000000e+00,-1.000000009956091285e+00,0.000000000000000000e+00,4.154288189959165748e-10,0.000000000000000000e+00 +4.023711491067859214e+01,2.771899999999999977e+02,0.000000000000000000e+00,8.018148970248107688e+00,0.000000000000000000e+00,-1.000000009955573255e+00,0.000000000000000000e+00,-2.864642233009019149e-10,0.000000000000000000e+00 +4.023836208132073011e+01,2.771999999999999886e+02,0.000000000000000000e+00,8.016901799593551203e+00,0.000000000000000000e+00,-1.000000009955930524e+00,0.000000000000000000e+00,8.825784352769444365e-10,0.000000000000000000e+00 +4.023960944598228906e+01,2.772099999999999795e+02,0.000000000000000000e+00,8.015654434919573745e+00,0.000000000000000000e+00,-1.000000009954829627e+00,0.000000000000000000e+00,-1.735870951508524751e-09,0.000000000000000000e+00 +4.024085700475384186e+01,2.772200000000000273e+02,0.000000000000000000e+00,8.014406876135604207e+00,0.000000000000000000e+00,-1.000000009956995228e+00,0.000000000000000000e+00,1.038370814271410853e-09,0.000000000000000000e+00 +4.024210475772602535e+01,2.772300000000000182e+02,0.000000000000000000e+00,8.013159123150995100e+00,0.000000000000000000e+00,-1.000000009955699598e+00,0.000000000000000000e+00,1.249053683694434183e-10,0.000000000000000000e+00 +4.024335270498956163e+01,2.772400000000000091e+02,0.000000000000000000e+00,8.011911175875036761e+00,0.000000000000000000e+00,-1.000000009955543723e+00,0.000000000000000000e+00,1.373389275144527247e-10,0.000000000000000000e+00 +4.024460084663522963e+01,2.772500000000000000e+02,0.000000000000000000e+00,8.010663034216943146e+00,0.000000000000000000e+00,-1.000000009955372304e+00,0.000000000000000000e+00,-1.154570078545406635e-09,0.000000000000000000e+00 +4.024584918275388645e+01,2.772599999999999909e+02,0.000000000000000000e+00,8.009414698085858930e+00,0.000000000000000000e+00,-1.000000009956813596e+00,0.000000000000000000e+00,8.570337646246651504e-10,0.000000000000000000e+00 +4.024709771343646025e+01,2.772699999999999818e+02,0.000000000000000000e+00,8.008166167390855961e+00,0.000000000000000000e+00,-1.000000009955743563e+00,0.000000000000000000e+00,5.229598242960987334e-10,0.000000000000000000e+00 +4.024834643877394313e+01,2.772800000000000296e+02,0.000000000000000000e+00,8.006917442040940358e+00,0.000000000000000000e+00,-1.000000009955090530e+00,0.000000000000000000e+00,-9.653958013063302566e-10,0.000000000000000000e+00 +4.024959535885740536e+01,2.772900000000000205e+02,0.000000000000000000e+00,8.005668521945043636e+00,0.000000000000000000e+00,-1.000000009956296232e+00,0.000000000000000000e+00,-1.420314787788721143e-10,0.000000000000000000e+00 +4.025084447377798824e+01,2.773000000000000114e+02,0.000000000000000000e+00,8.004419407012024479e+00,0.000000000000000000e+00,-1.000000009956473646e+00,0.000000000000000000e+00,7.637222008567571829e-10,0.000000000000000000e+00 +4.025209378362689705e+01,2.773100000000000023e+02,0.000000000000000000e+00,8.003170097150674067e+00,0.000000000000000000e+00,-1.000000009955519520e+00,0.000000000000000000e+00,-4.734089817672736819e-10,0.000000000000000000e+00 +4.025334328849542231e+01,2.773199999999999932e+02,0.000000000000000000e+00,8.001920592269712529e+00,0.000000000000000000e+00,-1.000000009956111047e+00,0.000000000000000000e+00,1.794551129517520893e-10,0.000000000000000000e+00 +4.025459298847490430e+01,2.773299999999999841e+02,0.000000000000000000e+00,8.000670892277785384e+00,0.000000000000000000e+00,-1.000000009955886782e+00,0.000000000000000000e+00,-6.404303435716722016e-10,0.000000000000000000e+00 +4.025584288365677565e+01,2.773400000000000318e+02,0.000000000000000000e+00,7.999420997083469764e+00,0.000000000000000000e+00,-1.000000009956687252e+00,0.000000000000000000e+00,5.277174204806330862e-10,0.000000000000000000e+00 +4.025709297413253296e+01,2.773500000000000227e+02,0.000000000000000000e+00,7.998170906595269081e+00,0.000000000000000000e+00,-1.000000009956027558e+00,0.000000000000000000e+00,3.232230272321643356e-10,0.000000000000000000e+00 +4.025834325999373675e+01,2.773600000000000136e+02,0.000000000000000000e+00,7.996920620721618356e+00,0.000000000000000000e+00,-1.000000009955623437e+00,0.000000000000000000e+00,-6.339152895046535678e-10,0.000000000000000000e+00 +4.025959374133202573e+01,2.773700000000000045e+02,0.000000000000000000e+00,7.995670139370878893e+00,0.000000000000000000e+00,-1.000000009956416136e+00,0.000000000000000000e+00,5.457565512495784502e-10,0.000000000000000000e+00 +4.026084441823911675e+01,2.773799999999999955e+02,0.000000000000000000e+00,7.994419462451339164e+00,0.000000000000000000e+00,-1.000000009955733571e+00,0.000000000000000000e+00,-6.305218109987000366e-10,0.000000000000000000e+00 +4.026209529080678351e+01,2.773899999999999864e+02,0.000000000000000000e+00,7.993168589871219254e+00,0.000000000000000000e+00,-1.000000009956522273e+00,0.000000000000000000e+00,4.291563027238566991e-10,0.000000000000000000e+00 +4.026334635912688498e+01,2.774000000000000341e+02,0.000000000000000000e+00,7.991917521538663749e+00,0.000000000000000000e+00,-1.000000009955985369e+00,0.000000000000000000e+00,-1.976862255891125552e-10,0.000000000000000000e+00 +4.026459762329134406e+01,2.774100000000000250e+02,0.000000000000000000e+00,7.990666257361748848e+00,0.000000000000000000e+00,-1.000000009956232727e+00,0.000000000000000000e+00,3.761482784271776162e-10,0.000000000000000000e+00 +4.026584908339215474e+01,2.774200000000000159e+02,0.000000000000000000e+00,7.989414797248476141e+00,0.000000000000000000e+00,-1.000000009955761993e+00,0.000000000000000000e+00,-6.340299060295885261e-10,0.000000000000000000e+00 +4.026710073952138913e+01,2.774300000000000068e+02,0.000000000000000000e+00,7.988163141106777054e+00,0.000000000000000000e+00,-1.000000009956555580e+00,0.000000000000000000e+00,2.236671674745870581e-10,0.000000000000000000e+00 +4.026835259177119042e+01,2.774399999999999977e+02,0.000000000000000000e+00,7.986911288844508405e+00,0.000000000000000000e+00,-1.000000009956275582e+00,0.000000000000000000e+00,1.651082472945261503e-10,0.000000000000000000e+00 +4.026960464023377284e+01,2.774499999999999886e+02,0.000000000000000000e+00,7.985659240369457734e+00,0.000000000000000000e+00,-1.000000009956068858e+00,0.000000000000000000e+00,-1.913253182630168860e-10,0.000000000000000000e+00 +4.027085688500142169e+01,2.774599999999999795e+02,0.000000000000000000e+00,7.984406995589338862e+00,0.000000000000000000e+00,-1.000000009956308444e+00,0.000000000000000000e+00,3.370272438599848538e-10,0.000000000000000000e+00 +4.027210932616650041e+01,2.774700000000000273e+02,0.000000000000000000e+00,7.983154554411792780e+00,0.000000000000000000e+00,-1.000000009955886338e+00,0.000000000000000000e+00,-4.633619267220817615e-10,0.000000000000000000e+00 +4.027336196382142930e+01,2.774800000000000182e+02,0.000000000000000000e+00,7.981901916744389425e+00,0.000000000000000000e+00,-1.000000009956466762e+00,0.000000000000000000e+00,2.885366683460480967e-10,0.000000000000000000e+00 +4.027461479805872102e+01,2.774900000000000091e+02,0.000000000000000000e+00,7.980649082494624125e+00,0.000000000000000000e+00,-1.000000009956105274e+00,0.000000000000000000e+00,-1.865979256413927369e-10,0.000000000000000000e+00 +4.027586782897094508e+01,2.775000000000000000e+02,0.000000000000000000e+00,7.979396051569922044e+00,0.000000000000000000e+00,-1.000000009956339087e+00,0.000000000000000000e+00,-1.397935874767035139e-10,0.000000000000000000e+00 +4.027712105665075626e+01,2.775099999999999909e+02,0.000000000000000000e+00,7.978142823877633738e+00,0.000000000000000000e+00,-1.000000009956514280e+00,0.000000000000000000e+00,-8.644937428253307332e-11,0.000000000000000000e+00 +4.027837448119087327e+01,2.775199999999999818e+02,0.000000000000000000e+00,7.976889399325037822e+00,0.000000000000000000e+00,-1.000000009956622637e+00,0.000000000000000000e+00,5.901722550339055700e-10,0.000000000000000000e+00 +4.027962810268408589e+01,2.775300000000000296e+02,0.000000000000000000e+00,7.975635777819340078e+00,0.000000000000000000e+00,-1.000000009955882785e+00,0.000000000000000000e+00,-3.198330092933182912e-10,0.000000000000000000e+00 +4.028088192122326916e+01,2.775400000000000205e+02,0.000000000000000000e+00,7.974381959267674347e+00,0.000000000000000000e+00,-1.000000009956283797e+00,0.000000000000000000e+00,6.037979556584086650e-11,0.000000000000000000e+00 +4.028213593690136207e+01,2.775500000000000114e+02,0.000000000000000000e+00,7.973127943577098975e+00,0.000000000000000000e+00,-1.000000009956208080e+00,0.000000000000000000e+00,-4.778282729426173153e-10,0.000000000000000000e+00 +4.028339014981137467e+01,2.775600000000000023e+02,0.000000000000000000e+00,7.971873730654601253e+00,0.000000000000000000e+00,-1.000000009956807379e+00,0.000000000000000000e+00,3.754406603988160247e-10,0.000000000000000000e+00 +4.028464456004639516e+01,2.775699999999999932e+02,0.000000000000000000e+00,7.970619320407093866e+00,0.000000000000000000e+00,-1.000000009956336422e+00,0.000000000000000000e+00,-1.513207230396510428e-10,0.000000000000000000e+00 +4.028589916769958279e+01,2.775799999999999841e+02,0.000000000000000000e+00,7.969364712741418444e+00,0.000000000000000000e+00,-1.000000009956526270e+00,0.000000000000000000e+00,2.512767303584698302e-10,0.000000000000000000e+00 +4.028715397286416788e+01,2.775900000000000318e+02,0.000000000000000000e+00,7.968109907564341121e+00,0.000000000000000000e+00,-1.000000009956210967e+00,0.000000000000000000e+00,-5.873995710528847584e-11,0.000000000000000000e+00 +4.028840897563345891e+01,2.776000000000000227e+02,0.000000000000000000e+00,7.966854904782556090e+00,0.000000000000000000e+00,-1.000000009956284686e+00,0.000000000000000000e+00,-4.647155512596817690e-10,0.000000000000000000e+00 +4.028966417610083539e+01,2.776100000000000136e+02,0.000000000000000000e+00,7.965599704302682937e+00,0.000000000000000000e+00,-1.000000009956867997e+00,0.000000000000000000e+00,2.117155971881403996e-10,0.000000000000000000e+00 +4.029091957435974791e+01,2.776200000000000045e+02,0.000000000000000000e+00,7.964344306031267529e+00,0.000000000000000000e+00,-1.000000009956602209e+00,0.000000000000000000e+00,3.306982210799718021e-10,0.000000000000000000e+00 +4.029217517050373232e+01,2.776299999999999955e+02,0.000000000000000000e+00,7.963088709874783788e+00,0.000000000000000000e+00,-1.000000009956186986e+00,0.000000000000000000e+00,-5.516661966089425993e-11,0.000000000000000000e+00 +4.029343096462638130e+01,2.776399999999999864e+02,0.000000000000000000e+00,7.961832915739631034e+00,0.000000000000000000e+00,-1.000000009956256264e+00,0.000000000000000000e+00,-3.309475186844454864e-10,0.000000000000000000e+00 +4.029468695682137280e+01,2.776500000000000341e+02,0.000000000000000000e+00,7.960576923532133975e+00,0.000000000000000000e+00,-1.000000009956671931e+00,0.000000000000000000e+00,1.178991306359996340e-10,0.000000000000000000e+00 +4.029594314718245585e+01,2.776600000000000250e+02,0.000000000000000000e+00,7.959320733158543604e+00,0.000000000000000000e+00,-1.000000009956523828e+00,0.000000000000000000e+00,-3.460420837769634810e-10,0.000000000000000000e+00 +4.029719953580345049e+01,2.776700000000000159e+02,0.000000000000000000e+00,7.958064344525038081e+00,0.000000000000000000e+00,-1.000000009956958591e+00,0.000000000000000000e+00,5.810044793008356796e-10,0.000000000000000000e+00 +4.029845612277825495e+01,2.776800000000000068e+02,0.000000000000000000e+00,7.956807757537720072e+00,0.000000000000000000e+00,-1.000000009956228508e+00,0.000000000000000000e+00,-4.252606327613437469e-10,0.000000000000000000e+00 +4.029971290820083851e+01,2.776899999999999977e+02,0.000000000000000000e+00,7.955550972102620300e+00,0.000000000000000000e+00,-1.000000009956762970e+00,0.000000000000000000e+00,6.218034847416392116e-11,0.000000000000000000e+00 +4.030096989216524861e+01,2.776999999999999886e+02,0.000000000000000000e+00,7.954293988125692216e+00,0.000000000000000000e+00,-1.000000009956684810e+00,0.000000000000000000e+00,4.078174424511576478e-10,0.000000000000000000e+00 +4.030222707476560373e+01,2.777099999999999795e+02,0.000000000000000000e+00,7.953036805512817331e+00,0.000000000000000000e+00,-1.000000009956172109e+00,0.000000000000000000e+00,-4.594947037960117381e-10,0.000000000000000000e+00 +4.030348445609610053e+01,2.777200000000000273e+02,0.000000000000000000e+00,7.951779424169802546e+00,0.000000000000000000e+00,-1.000000009956749869e+00,0.000000000000000000e+00,3.217013791098594978e-10,0.000000000000000000e+00 +4.030474203625100671e+01,2.777300000000000182e+02,0.000000000000000000e+00,7.950521844002378380e+00,0.000000000000000000e+00,-1.000000009956345304e+00,0.000000000000000000e+00,-5.666839246575879252e-10,0.000000000000000000e+00 +4.030599981532466103e+01,2.777400000000000091e+02,0.000000000000000000e+00,7.949264064916203409e+00,0.000000000000000000e+00,-1.000000009957058067e+00,0.000000000000000000e+00,2.963588122682892694e-10,0.000000000000000000e+00 +4.030725779341148041e+01,2.777500000000000000e+02,0.000000000000000000e+00,7.948006086816858939e+00,0.000000000000000000e+00,-1.000000009956685254e+00,0.000000000000000000e+00,1.565388130010737220e-10,0.000000000000000000e+00 +4.030851597060595992e+01,2.777599999999999909e+02,0.000000000000000000e+00,7.946747909609854332e+00,0.000000000000000000e+00,-1.000000009956488300e+00,0.000000000000000000e+00,-3.721399042559344022e-10,0.000000000000000000e+00 +4.030977434700266571e+01,2.777699999999999818e+02,0.000000000000000000e+00,7.945489533200622567e+00,0.000000000000000000e+00,-1.000000009956956593e+00,0.000000000000000000e+00,4.451210531778475189e-10,0.000000000000000000e+00 +4.031103292269623495e+01,2.777800000000000296e+02,0.000000000000000000e+00,7.944230957494521128e+00,0.000000000000000000e+00,-1.000000009956396374e+00,0.000000000000000000e+00,-1.427054662131569967e-10,0.000000000000000000e+00 +4.031229169778139010e+01,2.777900000000000205e+02,0.000000000000000000e+00,7.942972182396834668e+00,0.000000000000000000e+00,-1.000000009956576008e+00,0.000000000000000000e+00,-4.010640429268441952e-10,0.000000000000000000e+00 +4.031355067235291756e+01,2.778000000000000114e+02,0.000000000000000000e+00,7.941713207812770570e+00,0.000000000000000000e+00,-1.000000009957080938e+00,0.000000000000000000e+00,2.824990143794016583e-10,0.000000000000000000e+00 +4.031480984650568899e+01,2.778100000000000023e+02,0.000000000000000000e+00,7.940454033647461607e+00,0.000000000000000000e+00,-1.000000009956725222e+00,0.000000000000000000e+00,-2.799858346376675822e-10,0.000000000000000000e+00 +4.031606922033464713e+01,2.778199999999999932e+02,0.000000000000000000e+00,7.939194659805966836e+00,0.000000000000000000e+00,-1.000000009957077829e+00,0.000000000000000000e+00,2.044912196325059776e-10,0.000000000000000000e+00 +4.031732879393480573e+01,2.778299999999999841e+02,0.000000000000000000e+00,7.937935086193268042e+00,0.000000000000000000e+00,-1.000000009956820257e+00,0.000000000000000000e+00,1.085746606642746366e-10,0.000000000000000000e+00 +4.031858856740125674e+01,2.778400000000000318e+02,0.000000000000000000e+00,7.936675312714273289e+00,0.000000000000000000e+00,-1.000000009956683478e+00,0.000000000000000000e+00,4.546723510313116542e-11,0.000000000000000000e+00 +4.031984854082917025e+01,2.778500000000000227e+02,0.000000000000000000e+00,7.935415339273814261e+00,0.000000000000000000e+00,-1.000000009956626190e+00,0.000000000000000000e+00,6.783762231111585583e-11,0.000000000000000000e+00 +4.032110871431378740e+01,2.778600000000000136e+02,0.000000000000000000e+00,7.934155165776647145e+00,0.000000000000000000e+00,-1.000000009956540703e+00,0.000000000000000000e+00,-3.305017391096896276e-10,0.000000000000000000e+00 +4.032236908795043462e+01,2.778700000000000045e+02,0.000000000000000000e+00,7.932894792127452632e+00,0.000000000000000000e+00,-1.000000009956957259e+00,0.000000000000000000e+00,2.166591482736627381e-11,0.000000000000000000e+00 +4.032362966183450226e+01,2.778799999999999955e+02,0.000000000000000000e+00,7.931634218230835032e+00,0.000000000000000000e+00,-1.000000009956929947e+00,0.000000000000000000e+00,5.917553330293668451e-11,0.000000000000000000e+00 +4.032489043606145884e+01,2.778899999999999864e+02,0.000000000000000000e+00,7.930373443991324045e+00,0.000000000000000000e+00,-1.000000009956855340e+00,0.000000000000000000e+00,-1.646438356790877631e-10,0.000000000000000000e+00 +4.032615141072685105e+01,2.779000000000000341e+02,0.000000000000000000e+00,7.929112469313372991e+00,0.000000000000000000e+00,-1.000000009957062952e+00,0.000000000000000000e+00,-3.750113455244782491e-11,0.000000000000000000e+00 +4.032741258592631084e+01,2.779100000000000250e+02,0.000000000000000000e+00,7.927851294101358803e+00,0.000000000000000000e+00,-1.000000009957110247e+00,0.000000000000000000e+00,4.927182167200273097e-10,0.000000000000000000e+00 +4.032867396175552699e+01,2.779200000000000159e+02,0.000000000000000000e+00,7.926589918259582923e+00,0.000000000000000000e+00,-1.000000009956488745e+00,0.000000000000000000e+00,-1.944862462116967247e-10,0.000000000000000000e+00 +4.032993553831028066e+01,2.779300000000000068e+02,0.000000000000000000e+00,7.925328341692271295e+00,0.000000000000000000e+00,-1.000000009956734104e+00,0.000000000000000000e+00,-3.714887981523503504e-10,0.000000000000000000e+00 +4.033119731568641697e+01,2.779399999999999977e+02,0.000000000000000000e+00,7.924066564303571703e+00,0.000000000000000000e+00,-1.000000009957202840e+00,0.000000000000000000e+00,1.530761719813279906e-11,0.000000000000000000e+00 +4.033245929397986629e+01,2.779499999999999886e+02,0.000000000000000000e+00,7.922804585997556437e+00,0.000000000000000000e+00,-1.000000009957183522e+00,0.000000000000000000e+00,4.603868309151072152e-10,0.000000000000000000e+00 +4.033372147328663004e+01,2.779599999999999795e+02,0.000000000000000000e+00,7.921542406678222292e+00,0.000000000000000000e+00,-1.000000009956602431e+00,0.000000000000000000e+00,-6.541482069452333183e-10,0.000000000000000000e+00 +4.033498385370279493e+01,2.779700000000000273e+02,0.000000000000000000e+00,7.920280026249489680e+00,0.000000000000000000e+00,-1.000000009957428215e+00,0.000000000000000000e+00,6.269606676840717778e-10,0.000000000000000000e+00 +4.033624643532451159e+01,2.779800000000000182e+02,0.000000000000000000e+00,7.919017444615199963e+00,0.000000000000000000e+00,-1.000000009956636626e+00,0.000000000000000000e+00,-6.581597998865860606e-10,0.000000000000000000e+00 +4.033750921824801594e+01,2.779900000000000091e+02,0.000000000000000000e+00,7.917754661679121675e+00,0.000000000000000000e+00,-1.000000009957467739e+00,0.000000000000000000e+00,5.581950690743123672e-10,0.000000000000000000e+00 +4.033877220256962204e+01,2.780000000000000000e+02,0.000000000000000000e+00,7.916491677344942524e+00,0.000000000000000000e+00,-1.000000009956762748e+00,0.000000000000000000e+00,-1.258595015092063186e-10,0.000000000000000000e+00 +4.034003538838570790e+01,2.780099999999999909e+02,0.000000000000000000e+00,7.915228491516277387e+00,0.000000000000000000e+00,-1.000000009956921732e+00,0.000000000000000000e+00,-4.284867363661223025e-10,0.000000000000000000e+00 +4.034129877579274392e+01,2.780199999999999818e+02,0.000000000000000000e+00,7.913965104096661207e+00,0.000000000000000000e+00,-1.000000009957463076e+00,0.000000000000000000e+00,2.597220310785989073e-10,0.000000000000000000e+00 +4.034256236488727154e+01,2.780300000000000296e+02,0.000000000000000000e+00,7.912701514989552543e+00,0.000000000000000000e+00,-1.000000009957134894e+00,0.000000000000000000e+00,3.238100652530772232e-10,0.000000000000000000e+00 +4.034382615576590325e+01,2.780400000000000205e+02,0.000000000000000000e+00,7.911437724098334456e+00,0.000000000000000000e+00,-1.000000009956725666e+00,0.000000000000000000e+00,-1.818176286070677735e-10,0.000000000000000000e+00 +4.034509014852534392e+01,2.780500000000000114e+02,0.000000000000000000e+00,7.910173731326311852e+00,0.000000000000000000e+00,-1.000000009956955482e+00,0.000000000000000000e+00,-9.098211057494485666e-11,0.000000000000000000e+00 +4.034635434326235526e+01,2.780600000000000023e+02,0.000000000000000000e+00,7.908909536576711474e+00,0.000000000000000000e+00,-1.000000009957070501e+00,0.000000000000000000e+00,-4.613355331658968167e-10,0.000000000000000000e+00 +4.034761874007379134e+01,2.780699999999999932e+02,0.000000000000000000e+00,7.907645139752683683e+00,0.000000000000000000e+00,-1.000000009957653813e+00,0.000000000000000000e+00,4.282518005961754335e-10,0.000000000000000000e+00 +4.034888333905658442e+01,2.780799999999999841e+02,0.000000000000000000e+00,7.906380540757300679e+00,0.000000000000000000e+00,-1.000000009957112246e+00,0.000000000000000000e+00,-1.457122389154310576e-10,0.000000000000000000e+00 +4.035014814030773067e+01,2.780900000000000318e+02,0.000000000000000000e+00,7.905115739493559168e+00,0.000000000000000000e+00,-1.000000009957296543e+00,0.000000000000000000e+00,9.285475113678593733e-11,0.000000000000000000e+00 +4.035141314392431866e+01,2.781000000000000227e+02,0.000000000000000000e+00,7.903850735864375920e+00,0.000000000000000000e+00,-1.000000009957179081e+00,0.000000000000000000e+00,8.792587144297430922e-11,0.000000000000000000e+00 +4.035267835000350800e+01,2.781100000000000136e+02,0.000000000000000000e+00,7.902585529772591322e+00,0.000000000000000000e+00,-1.000000009957067837e+00,0.000000000000000000e+00,-1.058100068552308349e-10,0.000000000000000000e+00 +4.035394375864252936e+01,2.781200000000000045e+02,0.000000000000000000e+00,7.901320121120967599e+00,0.000000000000000000e+00,-1.000000009957201730e+00,0.000000000000000000e+00,1.207058507220187998e-10,0.000000000000000000e+00 +4.035520936993870578e+01,2.781299999999999955e+02,0.000000000000000000e+00,7.900054509812188819e+00,0.000000000000000000e+00,-1.000000009957048963e+00,0.000000000000000000e+00,-2.869813093398563313e-10,0.000000000000000000e+00 +4.035647518398943134e+01,2.781399999999999864e+02,0.000000000000000000e+00,7.898788695748861777e+00,0.000000000000000000e+00,-1.000000009957412228e+00,0.000000000000000000e+00,3.888359531795166056e-10,0.000000000000000000e+00 +4.035774120089217121e+01,2.781500000000000341e+02,0.000000000000000000e+00,7.897522678833514220e+00,0.000000000000000000e+00,-1.000000009956919955e+00,0.000000000000000000e+00,-5.679917859767014806e-10,0.000000000000000000e+00 +4.035900742074448289e+01,2.781600000000000250e+02,0.000000000000000000e+00,7.896256458968597514e+00,0.000000000000000000e+00,-1.000000009957639158e+00,0.000000000000000000e+00,2.214444607168650427e-10,0.000000000000000000e+00 +4.036027384364398785e+01,2.781700000000000159e+02,0.000000000000000000e+00,7.894990036056482197e+00,0.000000000000000000e+00,-1.000000009957358715e+00,0.000000000000000000e+00,4.242356663132592878e-11,0.000000000000000000e+00 +4.036154046968839282e+01,2.781800000000000068e+02,0.000000000000000000e+00,7.893723409999463314e+00,0.000000000000000000e+00,-1.000000009957304981e+00,0.000000000000000000e+00,5.731520935791821642e-11,0.000000000000000000e+00 +4.036280729897548269e+01,2.781899999999999977e+02,0.000000000000000000e+00,7.892456580699755975e+00,0.000000000000000000e+00,-1.000000009957232372e+00,0.000000000000000000e+00,3.208786125532825854e-10,0.000000000000000000e+00 +4.036407433160312763e+01,2.781999999999999886e+02,0.000000000000000000e+00,7.891189548059497127e+00,0.000000000000000000e+00,-1.000000009956825808e+00,0.000000000000000000e+00,-7.706158296453417698e-10,0.000000000000000000e+00 +4.036534156766926174e+01,2.782099999999999795e+02,0.000000000000000000e+00,7.889922311980745562e+00,0.000000000000000000e+00,-1.000000009957802360e+00,0.000000000000000000e+00,7.084742976648546143e-10,0.000000000000000000e+00 +4.036660900727190437e+01,2.782200000000000273e+02,0.000000000000000000e+00,7.888654872365479243e+00,0.000000000000000000e+00,-1.000000009956904412e+00,0.000000000000000000e+00,-7.158925111240880047e-10,0.000000000000000000e+00 +4.036787665050916019e+01,2.782300000000000182e+02,0.000000000000000000e+00,7.887387229115601528e+00,0.000000000000000000e+00,-1.000000009957811908e+00,0.000000000000000000e+00,5.397666189595869351e-10,0.000000000000000000e+00 +4.036914449747920486e+01,2.782400000000000091e+02,0.000000000000000000e+00,7.886119382132932287e+00,0.000000000000000000e+00,-1.000000009957127567e+00,0.000000000000000000e+00,-4.435460975159059806e-10,0.000000000000000000e+00 +4.037041254828029224e+01,2.782500000000000000e+02,0.000000000000000000e+00,7.884851331319216783e+00,0.000000000000000000e+00,-1.000000009957690006e+00,0.000000000000000000e+00,2.571908598471656879e-10,0.000000000000000000e+00 +4.037168080301076145e+01,2.782599999999999909e+02,0.000000000000000000e+00,7.883583076576117676e+00,0.000000000000000000e+00,-1.000000009957363822e+00,0.000000000000000000e+00,-6.441866089845784594e-11,0.000000000000000000e+00 +4.037294926176902976e+01,2.782699999999999818e+02,0.000000000000000000e+00,7.882314617805221246e+00,0.000000000000000000e+00,-1.000000009957445535e+00,0.000000000000000000e+00,3.034890904646093412e-10,0.000000000000000000e+00 +4.037421792465358550e+01,2.782800000000000296e+02,0.000000000000000000e+00,7.881045954908032947e+00,0.000000000000000000e+00,-1.000000009957060509e+00,0.000000000000000000e+00,-7.904495853043777608e-10,0.000000000000000000e+00 +4.037548679176300226e+01,2.782900000000000205e+02,0.000000000000000000e+00,7.879777087785980072e+00,0.000000000000000000e+00,-1.000000009958063485e+00,0.000000000000000000e+00,5.703898088556489896e-10,0.000000000000000000e+00 +4.037675586319593890e+01,2.783000000000000114e+02,0.000000000000000000e+00,7.878508016340408204e+00,0.000000000000000000e+00,-1.000000009957339620e+00,0.000000000000000000e+00,2.956452537809026760e-11,0.000000000000000000e+00 +4.037802513905111823e+01,2.783100000000000023e+02,0.000000000000000000e+00,7.877238740472587430e+00,0.000000000000000000e+00,-1.000000009957302094e+00,0.000000000000000000e+00,-1.518217379976639714e-10,0.000000000000000000e+00 +4.037929461942736253e+01,2.783199999999999932e+02,0.000000000000000000e+00,7.875969260083705237e+00,0.000000000000000000e+00,-1.000000009957494829e+00,0.000000000000000000e+00,8.271901963440504200e-11,0.000000000000000000e+00 +4.038056430442355804e+01,2.783299999999999841e+02,0.000000000000000000e+00,7.874699575074870062e+00,0.000000000000000000e+00,-1.000000009957389802e+00,0.000000000000000000e+00,-3.136870993555155488e-10,0.000000000000000000e+00 +4.038183419413866915e+01,2.783400000000000318e+02,0.000000000000000000e+00,7.873429685347111295e+00,0.000000000000000000e+00,-1.000000009957788150e+00,0.000000000000000000e+00,3.671330426164616648e-10,0.000000000000000000e+00 +4.038310428867175261e+01,2.783500000000000227e+02,0.000000000000000000e+00,7.872159590801377504e+00,0.000000000000000000e+00,-1.000000009957321856e+00,0.000000000000000000e+00,-5.714115781059114954e-10,0.000000000000000000e+00 +4.038437458812194336e+01,2.783600000000000136e+02,0.000000000000000000e+00,7.870889291338539095e+00,0.000000000000000000e+00,-1.000000009958047720e+00,0.000000000000000000e+00,7.792943035340403797e-10,0.000000000000000000e+00 +4.038564509258844737e+01,2.783700000000000045e+02,0.000000000000000000e+00,7.869618786859383874e+00,0.000000000000000000e+00,-1.000000009957057623e+00,0.000000000000000000e+00,-4.768672050423474977e-10,0.000000000000000000e+00 +4.038691580217055588e+01,2.783799999999999955e+02,0.000000000000000000e+00,7.868348077264623264e+00,0.000000000000000000e+00,-1.000000009957663583e+00,0.000000000000000000e+00,1.174067489433789076e-10,0.000000000000000000e+00 +4.038818671696763829e+01,2.783899999999999864e+02,0.000000000000000000e+00,7.867077162454884309e+00,0.000000000000000000e+00,-1.000000009957514369e+00,0.000000000000000000e+00,-1.320612582581735349e-10,0.000000000000000000e+00 +4.038945783707914927e+01,2.784000000000000341e+02,0.000000000000000000e+00,7.865806042330716785e+00,0.000000000000000000e+00,-1.000000009957682234e+00,0.000000000000000000e+00,-6.898911190590679997e-11,0.000000000000000000e+00 +4.039072916260461454e+01,2.784100000000000250e+02,0.000000000000000000e+00,7.864534716792588753e+00,0.000000000000000000e+00,-1.000000009957769942e+00,0.000000000000000000e+00,3.627018376035230652e-10,0.000000000000000000e+00 +4.039200069364365220e+01,2.784200000000000159e+02,0.000000000000000000e+00,7.863263185740888339e+00,0.000000000000000000e+00,-1.000000009957308755e+00,0.000000000000000000e+00,-4.282926145875976210e-10,0.000000000000000000e+00 +4.039327243029595138e+01,2.784300000000000068e+02,0.000000000000000000e+00,7.861991449075923732e+00,0.000000000000000000e+00,-1.000000009957853431e+00,0.000000000000000000e+00,-1.890606946408463060e-10,0.000000000000000000e+00 +4.039454437266128650e+01,2.784399999999999977e+02,0.000000000000000000e+00,7.860719506697920522e+00,0.000000000000000000e+00,-1.000000009958093905e+00,0.000000000000000000e+00,5.876864012999560581e-10,0.000000000000000000e+00 +4.039581652083951013e+01,2.784499999999999886e+02,0.000000000000000000e+00,7.859447358507025250e+00,0.000000000000000000e+00,-1.000000009957346281e+00,0.000000000000000000e+00,-2.369910825995034059e-10,0.000000000000000000e+00 +4.039708887493056011e+01,2.784599999999999795e+02,0.000000000000000000e+00,7.858175004403304520e+00,0.000000000000000000e+00,-1.000000009957647817e+00,0.000000000000000000e+00,-4.103923336797115640e-10,0.000000000000000000e+00 +4.039836143503445243e+01,2.784700000000000273e+02,0.000000000000000000e+00,7.856902444286741449e+00,0.000000000000000000e+00,-1.000000009958170066e+00,0.000000000000000000e+00,6.709665445631520890e-10,0.000000000000000000e+00 +4.039963420125128124e+01,2.784800000000000182e+02,0.000000000000000000e+00,7.855629678057239218e+00,0.000000000000000000e+00,-1.000000009957316083e+00,0.000000000000000000e+00,-2.251891543097327554e-10,0.000000000000000000e+00 +4.040090717368122597e+01,2.784900000000000091e+02,0.000000000000000000e+00,7.854356705614621958e+00,0.000000000000000000e+00,-1.000000009957602742e+00,0.000000000000000000e+00,-3.011918277139635980e-10,0.000000000000000000e+00 +4.040218035242454420e+01,2.785000000000000000e+02,0.000000000000000000e+00,7.853083526858629426e+00,0.000000000000000000e+00,-1.000000009957986213e+00,0.000000000000000000e+00,-4.812708128494284230e-11,0.000000000000000000e+00 +4.040345373758157166e+01,2.785099999999999909e+02,0.000000000000000000e+00,7.851810141688921441e+00,0.000000000000000000e+00,-1.000000009958047498e+00,0.000000000000000000e+00,5.903328745784072939e-10,0.000000000000000000e+00 +4.040472732925273647e+01,2.785199999999999818e+02,0.000000000000000000e+00,7.850536550005076997e+00,0.000000000000000000e+00,-1.000000009957295655e+00,0.000000000000000000e+00,-5.189414966492192737e-10,0.000000000000000000e+00 +4.040600112753853779e+01,2.785300000000000296e+02,0.000000000000000000e+00,7.849262751706594265e+00,0.000000000000000000e+00,-1.000000009957956681e+00,0.000000000000000000e+00,-3.311484248645364087e-11,0.000000000000000000e+00 +4.040727513253956005e+01,2.785400000000000205e+02,0.000000000000000000e+00,7.847988746692887041e+00,0.000000000000000000e+00,-1.000000009957998870e+00,0.000000000000000000e+00,4.614414228774680418e-10,0.000000000000000000e+00 +4.040854934435646584e+01,2.785500000000000114e+02,0.000000000000000000e+00,7.846714534863290069e+00,0.000000000000000000e+00,-1.000000009957410896e+00,0.000000000000000000e+00,-6.183495911800077545e-10,0.000000000000000000e+00 +4.040982376309001012e+01,2.785600000000000023e+02,0.000000000000000000e+00,7.845440116117056384e+00,0.000000000000000000e+00,-1.000000009958198932e+00,0.000000000000000000e+00,6.706844956527883935e-11,0.000000000000000000e+00 +4.041109838884101890e+01,2.785699999999999932e+02,0.000000000000000000e+00,7.844165490353354642e+00,0.000000000000000000e+00,-1.000000009958113445e+00,0.000000000000000000e+00,3.859728254034918092e-10,0.000000000000000000e+00 +4.041237322171040347e+01,2.785799999999999841e+02,0.000000000000000000e+00,7.842890657471274451e+00,0.000000000000000000e+00,-1.000000009957621394e+00,0.000000000000000000e+00,-1.492441124784723003e-10,0.000000000000000000e+00 +4.041364826179916037e+01,2.785900000000000318e+02,0.000000000000000000e+00,7.841615617369822822e+00,0.000000000000000000e+00,-1.000000009957811686e+00,0.000000000000000000e+00,-3.879367848180762604e-10,0.000000000000000000e+00 +4.041492350920836429e+01,2.786000000000000227e+02,0.000000000000000000e+00,7.840340369947923271e+00,0.000000000000000000e+00,-1.000000009958306402e+00,0.000000000000000000e+00,8.187477531477212534e-10,0.000000000000000000e+00 +4.041619896403916812e+01,2.786100000000000136e+02,0.000000000000000000e+00,7.839064915104417608e+00,0.000000000000000000e+00,-1.000000009957262126e+00,0.000000000000000000e+00,-8.396760875598309389e-10,0.000000000000000000e+00 +4.041747462639281707e+01,2.786200000000000045e+02,0.000000000000000000e+00,7.837789252738067702e+00,0.000000000000000000e+00,-1.000000009958333269e+00,0.000000000000000000e+00,1.543680531663463957e-10,0.000000000000000000e+00 +4.041875049637062745e+01,2.786299999999999955e+02,0.000000000000000000e+00,7.836513382747548384e+00,0.000000000000000000e+00,-1.000000009958136316e+00,0.000000000000000000e+00,5.825705874471240990e-10,0.000000000000000000e+00 +4.042002657407401500e+01,2.786399999999999864e+02,0.000000000000000000e+00,7.835237305031456323e+00,0.000000000000000000e+00,-1.000000009957392910e+00,0.000000000000000000e+00,-5.869991307955432199e-10,0.000000000000000000e+00 +4.042130285960445946e+01,2.786500000000000341e+02,0.000000000000000000e+00,7.833961019488304700e+00,0.000000000000000000e+00,-1.000000009958142089e+00,0.000000000000000000e+00,-2.417889403602822525e-11,0.000000000000000000e+00 +4.042257935306353289e+01,2.786600000000000250e+02,0.000000000000000000e+00,7.832684526016521431e+00,0.000000000000000000e+00,-1.000000009958172953e+00,0.000000000000000000e+00,1.474846129237319423e-10,0.000000000000000000e+00 +4.042385605455288555e+01,2.786700000000000159e+02,0.000000000000000000e+00,7.831407824514454497e+00,0.000000000000000000e+00,-1.000000009957984659e+00,0.000000000000000000e+00,-1.408526703684899768e-11,0.000000000000000000e+00 +4.042513296417425295e+01,2.786800000000000068e+02,0.000000000000000000e+00,7.830130914880368387e+00,0.000000000000000000e+00,-1.000000009958002645e+00,0.000000000000000000e+00,9.492965257262134459e-11,0.000000000000000000e+00 +4.042641008202946296e+01,2.786899999999999977e+02,0.000000000000000000e+00,7.828853797012444105e+00,0.000000000000000000e+00,-1.000000009957881408e+00,0.000000000000000000e+00,-1.251615418828890829e-11,0.000000000000000000e+00 +4.042768740822040741e+01,2.786999999999999886e+02,0.000000000000000000e+00,7.827576470808780051e+00,0.000000000000000000e+00,-1.000000009957897396e+00,0.000000000000000000e+00,-2.777437657719967936e-10,0.000000000000000000e+00 +4.042896494284907760e+01,2.787099999999999795e+02,0.000000000000000000e+00,7.826298936167391140e+00,0.000000000000000000e+00,-1.000000009958252223e+00,0.000000000000000000e+00,-9.888010620693876766e-11,0.000000000000000000e+00 +4.043024268601753590e+01,2.787200000000000273e+02,0.000000000000000000e+00,7.825021192986208796e+00,0.000000000000000000e+00,-1.000000009958378566e+00,0.000000000000000000e+00,5.825850037962156675e-10,0.000000000000000000e+00 +4.043152063782793704e+01,2.787300000000000182e+02,0.000000000000000000e+00,7.823743241163081841e+00,0.000000000000000000e+00,-1.000000009957634051e+00,0.000000000000000000e+00,-3.503972693647202625e-10,0.000000000000000000e+00 +4.043279879838251389e+01,2.787400000000000091e+02,0.000000000000000000e+00,7.822465080595776499e+00,0.000000000000000000e+00,-1.000000009958081915e+00,0.000000000000000000e+00,-1.200222892337272873e-10,0.000000000000000000e+00 +4.043407716778358463e+01,2.787500000000000000e+02,0.000000000000000000e+00,7.821186711181972839e+00,0.000000000000000000e+00,-1.000000009958235347e+00,0.000000000000000000e+00,2.439996500227675024e-10,0.000000000000000000e+00 +4.043535574613355266e+01,2.787599999999999909e+02,0.000000000000000000e+00,7.819908132819269220e+00,0.000000000000000000e+00,-1.000000009957923375e+00,0.000000000000000000e+00,-2.859798774402418888e-10,0.000000000000000000e+00 +4.043663453353490667e+01,2.787699999999999818e+02,0.000000000000000000e+00,7.818629345405180509e+00,0.000000000000000000e+00,-1.000000009958289082e+00,0.000000000000000000e+00,-2.118023046148014283e-11,0.000000000000000000e+00 +4.043791353009021350e+01,2.787800000000000296e+02,0.000000000000000000e+00,7.817350348837136309e+00,0.000000000000000000e+00,-1.000000009958316172e+00,0.000000000000000000e+00,1.024122277163177613e-11,0.000000000000000000e+00 +4.043919273590212526e+01,2.787900000000000205e+02,0.000000000000000000e+00,7.816071143012483624e+00,0.000000000000000000e+00,-1.000000009958303071e+00,0.000000000000000000e+00,4.102760838194165900e-10,0.000000000000000000e+00 +4.044047215107338644e+01,2.788000000000000114e+02,0.000000000000000000e+00,7.814791727828485079e+00,0.000000000000000000e+00,-1.000000009957778158e+00,0.000000000000000000e+00,-3.899067071973096079e-10,0.000000000000000000e+00 +4.044175177570681257e+01,2.788100000000000023e+02,0.000000000000000000e+00,7.813512103182319812e+00,0.000000000000000000e+00,-1.000000009958277092e+00,0.000000000000000000e+00,-1.610031937050047578e-10,0.000000000000000000e+00 +4.044303160990530444e+01,2.788199999999999932e+02,0.000000000000000000e+00,7.812232268971080806e+00,0.000000000000000000e+00,-1.000000009958483149e+00,0.000000000000000000e+00,7.008042672094908189e-11,0.000000000000000000e+00 +4.044431165377186232e+01,2.788299999999999841e+02,0.000000000000000000e+00,7.810952225091778445e+00,0.000000000000000000e+00,-1.000000009958393443e+00,0.000000000000000000e+00,3.635260062704840977e-10,0.000000000000000000e+00 +4.044559190740955046e+01,2.788400000000000318e+02,0.000000000000000000e+00,7.809671971441338734e+00,0.000000000000000000e+00,-1.000000009957928038e+00,0.000000000000000000e+00,-3.060678606024761089e-10,0.000000000000000000e+00 +4.044687237092153254e+01,2.788500000000000227e+02,0.000000000000000000e+00,7.808391507916603302e+00,0.000000000000000000e+00,-1.000000009958319946e+00,0.000000000000000000e+00,-2.529630551706479653e-10,0.000000000000000000e+00 +4.044815304441105752e+01,2.788600000000000136e+02,0.000000000000000000e+00,7.807110834414327627e+00,0.000000000000000000e+00,-1.000000009958643910e+00,0.000000000000000000e+00,5.803847863110426321e-10,0.000000000000000000e+00 +4.044943392798144544e+01,2.788700000000000045e+02,0.000000000000000000e+00,7.805829950831183695e+00,0.000000000000000000e+00,-1.000000009957900504e+00,0.000000000000000000e+00,-4.527229220745676779e-10,0.000000000000000000e+00 +4.045071502173610867e+01,2.788799999999999955e+02,0.000000000000000000e+00,7.804548857063760003e+00,0.000000000000000000e+00,-1.000000009958480485e+00,0.000000000000000000e+00,4.959725703227775247e-10,0.000000000000000000e+00 +4.045199632577855198e+01,2.788899999999999864e+02,0.000000000000000000e+00,7.803267553008557122e+00,0.000000000000000000e+00,-1.000000009957844993e+00,0.000000000000000000e+00,-8.425991040512806130e-10,0.000000000000000000e+00 +4.045327784021235118e+01,2.789000000000000341e+02,0.000000000000000000e+00,7.801986038561993908e+00,0.000000000000000000e+00,-1.000000009958924796e+00,0.000000000000000000e+00,4.589098216134672715e-10,0.000000000000000000e+00 +4.045455956514118157e+01,2.789100000000000250e+02,0.000000000000000000e+00,7.800704313620400399e+00,0.000000000000000000e+00,-1.000000009958336600e+00,0.000000000000000000e+00,1.340648733970037991e-10,0.000000000000000000e+00 +4.045584150066878948e+01,2.789200000000000159e+02,0.000000000000000000e+00,7.799422378080025808e+00,0.000000000000000000e+00,-1.000000009958164737e+00,0.000000000000000000e+00,-1.354282974576865909e-10,0.000000000000000000e+00 +4.045712364689901364e+01,2.789300000000000068e+02,0.000000000000000000e+00,7.798140231837031422e+00,0.000000000000000000e+00,-1.000000009958338376e+00,0.000000000000000000e+00,2.508994167079028288e-10,0.000000000000000000e+00 +4.045840600393578512e+01,2.789399999999999977e+02,0.000000000000000000e+00,7.796857874787493259e+00,0.000000000000000000e+00,-1.000000009958016634e+00,0.000000000000000000e+00,-2.679975350565974915e-10,0.000000000000000000e+00 +4.045968857188310608e+01,2.789499999999999886e+02,0.000000000000000000e+00,7.795575306827402962e+00,0.000000000000000000e+00,-1.000000009958360359e+00,0.000000000000000000e+00,-5.516586854627843608e-10,0.000000000000000000e+00 +4.046097135084507102e+01,2.789599999999999795e+02,0.000000000000000000e+00,7.794292527852665131e+00,0.000000000000000000e+00,-1.000000009959068015e+00,0.000000000000000000e+00,5.384147362208411441e-10,0.000000000000000000e+00 +4.046225434092585971e+01,2.789700000000000273e+02,0.000000000000000000e+00,7.793009537759099103e+00,0.000000000000000000e+00,-1.000000009958377234e+00,0.000000000000000000e+00,3.644213394720244621e-10,0.000000000000000000e+00 +4.046353754222973720e+01,2.789800000000000182e+02,0.000000000000000000e+00,7.791726336442440726e+00,0.000000000000000000e+00,-1.000000009957909608e+00,0.000000000000000000e+00,-4.735313248814368176e-10,0.000000000000000000e+00 +4.046482095486106090e+01,2.789900000000000091e+02,0.000000000000000000e+00,7.790442923798337915e+00,0.000000000000000000e+00,-1.000000009958517344e+00,0.000000000000000000e+00,-2.968381109189166361e-10,0.000000000000000000e+00 +4.046610457892426638e+01,2.790000000000000000e+02,0.000000000000000000e+00,7.789159299722351548e+00,0.000000000000000000e+00,-1.000000009958898373e+00,0.000000000000000000e+00,4.140520673775529601e-10,0.000000000000000000e+00 +4.046738841452387447e+01,2.790099999999999909e+02,0.000000000000000000e+00,7.787875464109958124e+00,0.000000000000000000e+00,-1.000000009958366798e+00,0.000000000000000000e+00,1.034094926918917068e-10,0.000000000000000000e+00 +4.046867246176449839e+01,2.790199999999999818e+02,0.000000000000000000e+00,7.786591416856548875e+00,0.000000000000000000e+00,-1.000000009958234015e+00,0.000000000000000000e+00,-9.059806021911213801e-11,0.000000000000000000e+00 +4.046995672075082950e+01,2.790300000000000296e+02,0.000000000000000000e+00,7.785307157857427107e+00,0.000000000000000000e+00,-1.000000009958350367e+00,0.000000000000000000e+00,-1.073513665745698346e-10,0.000000000000000000e+00 +4.047124119158765865e+01,2.790400000000000205e+02,0.000000000000000000e+00,7.784022687007809971e+00,0.000000000000000000e+00,-1.000000009958488256e+00,0.000000000000000000e+00,-4.250136195727494879e-10,0.000000000000000000e+00 +4.047252587437984772e+01,2.790500000000000114e+02,0.000000000000000000e+00,7.782738004202828463e+00,0.000000000000000000e+00,-1.000000009959034264e+00,0.000000000000000000e+00,6.312804041586723868e-10,0.000000000000000000e+00 +4.047381076923235099e+01,2.790600000000000023e+02,0.000000000000000000e+00,7.781453109337526541e+00,0.000000000000000000e+00,-1.000000009958223135e+00,0.000000000000000000e+00,-1.059159594701576159e-10,0.000000000000000000e+00 +4.047509587625021510e+01,2.790699999999999932e+02,0.000000000000000000e+00,7.780168002306863784e+00,0.000000000000000000e+00,-1.000000009958359248e+00,0.000000000000000000e+00,-4.234211153620687162e-10,0.000000000000000000e+00 +4.047638119553857194e+01,2.790799999999999841e+02,0.000000000000000000e+00,7.778882683005710064e+00,0.000000000000000000e+00,-1.000000009958903480e+00,0.000000000000000000e+00,2.765341550301978582e-10,0.000000000000000000e+00 +4.047766672720263159e+01,2.790900000000000318e+02,0.000000000000000000e+00,7.777597151328849101e+00,0.000000000000000000e+00,-1.000000009958547986e+00,0.000000000000000000e+00,-9.584702851367391362e-11,0.000000000000000000e+00 +4.047895247134769647e+01,2.791000000000000227e+02,0.000000000000000000e+00,7.776311407170979351e+00,0.000000000000000000e+00,-1.000000009958671221e+00,0.000000000000000000e+00,1.338183195488953170e-10,0.000000000000000000e+00 +4.048023842807916139e+01,2.791100000000000136e+02,0.000000000000000000e+00,7.775025450426710449e+00,0.000000000000000000e+00,-1.000000009958499136e+00,0.000000000000000000e+00,-4.920246995102877483e-11,0.000000000000000000e+00 +4.048152459750249932e+01,2.791200000000000045e+02,0.000000000000000000e+00,7.773739280990565881e+00,0.000000000000000000e+00,-1.000000009958562419e+00,0.000000000000000000e+00,-4.556948530035652862e-11,0.000000000000000000e+00 +4.048281097972327558e+01,2.791299999999999955e+02,0.000000000000000000e+00,7.772452898756981199e+00,0.000000000000000000e+00,-1.000000009958621039e+00,0.000000000000000000e+00,-3.311870136516380718e-10,0.000000000000000000e+00 +4.048409757484714078e+01,2.791399999999999864e+02,0.000000000000000000e+00,7.771166303620304916e+00,0.000000000000000000e+00,-1.000000009959047143e+00,0.000000000000000000e+00,2.275994582684499956e-10,0.000000000000000000e+00 +4.048538438297983078e+01,2.791500000000000341e+02,0.000000000000000000e+00,7.769879495474797615e+00,0.000000000000000000e+00,-1.000000009958754266e+00,0.000000000000000000e+00,8.350257542776967089e-11,0.000000000000000000e+00 +4.048667140422718091e+01,2.791600000000000250e+02,0.000000000000000000e+00,7.768592474214633725e+00,0.000000000000000000e+00,-1.000000009958646796e+00,0.000000000000000000e+00,3.700069330301400872e-10,0.000000000000000000e+00 +4.048795863869509759e+01,2.791700000000000159e+02,0.000000000000000000e+00,7.767305239733898858e+00,0.000000000000000000e+00,-1.000000009958170510e+00,0.000000000000000000e+00,-4.592844738618178506e-10,0.000000000000000000e+00 +4.048924608648958667e+01,2.791800000000000068e+02,0.000000000000000000e+00,7.766017791926591585e+00,0.000000000000000000e+00,-1.000000009958761815e+00,0.000000000000000000e+00,-1.984787107668918777e-10,0.000000000000000000e+00 +4.049053374771673219e+01,2.791899999999999977e+02,0.000000000000000000e+00,7.764730130686620768e+00,0.000000000000000000e+00,-1.000000009959017389e+00,0.000000000000000000e+00,1.410327243190158505e-10,0.000000000000000000e+00 +4.049182162248271766e+01,2.791999999999999886e+02,0.000000000000000000e+00,7.763442255907809120e+00,0.000000000000000000e+00,-1.000000009958835756e+00,0.000000000000000000e+00,8.601914038171002729e-11,0.000000000000000000e+00 +4.049310971089380473e+01,2.792099999999999795e+02,0.000000000000000000e+00,7.762154167483891420e+00,0.000000000000000000e+00,-1.000000009958724956e+00,0.000000000000000000e+00,2.333679192728241590e-10,0.000000000000000000e+00 +4.049439801305635456e+01,2.792200000000000273e+02,0.000000000000000000e+00,7.760865865308513634e+00,0.000000000000000000e+00,-1.000000009958424307e+00,0.000000000000000000e+00,-4.249555201918563205e-10,0.000000000000000000e+00 +4.049568652907679933e+01,2.792300000000000182e+02,0.000000000000000000e+00,7.759577349275233793e+00,0.000000000000000000e+00,-1.000000009958971869e+00,0.000000000000000000e+00,3.132363617593364560e-10,0.000000000000000000e+00 +4.049697525906167783e+01,2.792400000000000091e+02,0.000000000000000000e+00,7.758288619277520226e+00,0.000000000000000000e+00,-1.000000009958568192e+00,0.000000000000000000e+00,-1.655501372238731575e-10,0.000000000000000000e+00 +4.049826420311760700e+01,2.792500000000000000e+02,0.000000000000000000e+00,7.756999675208755107e+00,0.000000000000000000e+00,-1.000000009958781577e+00,0.000000000000000000e+00,-1.939422319249275179e-10,0.000000000000000000e+00 +4.049955336135129613e+01,2.792599999999999909e+02,0.000000000000000000e+00,7.755710516962230017e+00,0.000000000000000000e+00,-1.000000009959031599e+00,0.000000000000000000e+00,2.893150978455004878e-10,0.000000000000000000e+00 +4.050084273386953981e+01,2.792699999999999818e+02,0.000000000000000000e+00,7.754421144431148605e+00,0.000000000000000000e+00,-1.000000009958658564e+00,0.000000000000000000e+00,-2.563800967982472320e-10,0.000000000000000000e+00 +4.050213232077921788e+01,2.792800000000000296e+02,0.000000000000000000e+00,7.753131557508626592e+00,0.000000000000000000e+00,-1.000000009958989189e+00,0.000000000000000000e+00,-1.661287097442137738e-10,0.000000000000000000e+00 +4.050342212218730964e+01,2.792900000000000205e+02,0.000000000000000000e+00,7.751841756087689106e+00,0.000000000000000000e+00,-1.000000009959203462e+00,0.000000000000000000e+00,6.220614269581072811e-10,0.000000000000000000e+00 +4.050471213820087968e+01,2.793000000000000114e+02,0.000000000000000000e+00,7.750551740061273343e+00,0.000000000000000000e+00,-1.000000009958400993e+00,0.000000000000000000e+00,-4.980481968117029460e-10,0.000000000000000000e+00 +4.050600236892707784e+01,2.793100000000000023e+02,0.000000000000000000e+00,7.749261509322228569e+00,0.000000000000000000e+00,-1.000000009959043590e+00,0.000000000000000000e+00,2.713515057140270949e-10,0.000000000000000000e+00 +4.050729281447314634e+01,2.793199999999999932e+02,0.000000000000000000e+00,7.747971063763311683e+00,0.000000000000000000e+00,-1.000000009958693425e+00,0.000000000000000000e+00,-2.083398555500741525e-10,0.000000000000000000e+00 +4.050858347494641265e+01,2.793299999999999841e+02,0.000000000000000000e+00,7.746680403277193427e+00,0.000000000000000000e+00,-1.000000009958962321e+00,0.000000000000000000e+00,-2.736692766095230971e-10,0.000000000000000000e+00 +4.050987435045429663e+01,2.793400000000000318e+02,0.000000000000000000e+00,7.745389527756453063e+00,0.000000000000000000e+00,-1.000000009959315594e+00,0.000000000000000000e+00,6.695266881252741399e-10,0.000000000000000000e+00 +4.051116544110431050e+01,2.793500000000000227e+02,0.000000000000000000e+00,7.744098437093581033e+00,0.000000000000000000e+00,-1.000000009958451175e+00,0.000000000000000000e+00,-5.120776057779760172e-10,0.000000000000000000e+00 +4.051245674700405175e+01,2.793600000000000136e+02,0.000000000000000000e+00,7.742807131180979852e+00,0.000000000000000000e+00,-1.000000009959112424e+00,0.000000000000000000e+00,-2.664835253203383127e-11,0.000000000000000000e+00 +4.051374826826121023e+01,2.793700000000000045e+02,0.000000000000000000e+00,7.741515609910958773e+00,0.000000000000000000e+00,-1.000000009959146841e+00,0.000000000000000000e+00,5.775711564415435670e-11,0.000000000000000000e+00 +4.051504000498356106e+01,2.793799999999999955e+02,0.000000000000000000e+00,7.740223873175740010e+00,0.000000000000000000e+00,-1.000000009959072234e+00,0.000000000000000000e+00,3.366884230871230858e-10,0.000000000000000000e+00 +4.051633195727897885e+01,2.793899999999999864e+02,0.000000000000000000e+00,7.738931920867455183e+00,0.000000000000000000e+00,-1.000000009958637248e+00,0.000000000000000000e+00,-1.907410769810907805e-10,0.000000000000000000e+00 +4.051762412525541635e+01,2.794000000000000341e+02,0.000000000000000000e+00,7.737639752878146204e+00,0.000000000000000000e+00,-1.000000009958883718e+00,0.000000000000000000e+00,-3.972249886497864147e-10,0.000000000000000000e+00 +4.051891650902092579e+01,2.794100000000000250e+02,0.000000000000000000e+00,7.736347369099763505e+00,0.000000000000000000e+00,-1.000000009959397085e+00,0.000000000000000000e+00,3.117832764169231066e-10,0.000000000000000000e+00 +4.052020910868364467e+01,2.794200000000000159e+02,0.000000000000000000e+00,7.735054769424167809e+00,0.000000000000000000e+00,-1.000000009958994074e+00,0.000000000000000000e+00,-1.270970113459198681e-10,0.000000000000000000e+00 +4.052150192435180287e+01,2.794300000000000068e+02,0.000000000000000000e+00,7.733761953743131023e+00,0.000000000000000000e+00,-1.000000009959158387e+00,0.000000000000000000e+00,4.751603405407865990e-10,0.000000000000000000e+00 +4.052279495613372262e+01,2.794399999999999977e+02,0.000000000000000000e+00,7.732468921948332685e+00,0.000000000000000000e+00,-1.000000009958543989e+00,0.000000000000000000e+00,-4.737073345951847662e-10,0.000000000000000000e+00 +4.052408820413781143e+01,2.794499999999999886e+02,0.000000000000000000e+00,7.731175673931363512e+00,0.000000000000000000e+00,-1.000000009959156611e+00,0.000000000000000000e+00,-2.545815452768043805e-10,0.000000000000000000e+00 +4.052538166847256917e+01,2.794599999999999795e+02,0.000000000000000000e+00,7.729882209583720964e+00,0.000000000000000000e+00,-1.000000009959485903e+00,0.000000000000000000e+00,6.640668963360111358e-10,0.000000000000000000e+00 +4.052667534924659520e+01,2.794700000000000273e+02,0.000000000000000000e+00,7.728588528796813684e+00,0.000000000000000000e+00,-1.000000009958626812e+00,0.000000000000000000e+00,-8.377958148916518630e-10,0.000000000000000000e+00 +4.052796924656855992e+01,2.794800000000000182e+02,0.000000000000000000e+00,7.727294631461960606e+00,0.000000000000000000e+00,-1.000000009959710834e+00,0.000000000000000000e+00,6.092820300800698787e-10,0.000000000000000000e+00 +4.052926336054724743e+01,2.794900000000000091e+02,0.000000000000000000e+00,7.726000517470385631e+00,0.000000000000000000e+00,-1.000000009958922353e+00,0.000000000000000000e+00,-2.353688957061754360e-10,0.000000000000000000e+00 +4.053055769129151287e+01,2.795000000000000000e+02,0.000000000000000000e+00,7.724706186713226508e+00,0.000000000000000000e+00,-1.000000009959226999e+00,0.000000000000000000e+00,4.037649850801668671e-10,0.000000000000000000e+00 +4.053185223891031796e+01,2.795099999999999909e+02,0.000000000000000000e+00,7.723411639081525948e+00,0.000000000000000000e+00,-1.000000009958704306e+00,0.000000000000000000e+00,-5.887395494889453152e-10,0.000000000000000000e+00 +4.053314700351270972e+01,2.795199999999999818e+02,0.000000000000000000e+00,7.722116874466237846e+00,0.000000000000000000e+00,-1.000000009959466585e+00,0.000000000000000000e+00,2.983498639601845480e-11,0.000000000000000000e+00 +4.053444198520782749e+01,2.795300000000000296e+02,0.000000000000000000e+00,7.720821892758221949e+00,0.000000000000000000e+00,-1.000000009959427949e+00,0.000000000000000000e+00,2.038382180933223966e-10,0.000000000000000000e+00 +4.053573718410490301e+01,2.795400000000000205e+02,0.000000000000000000e+00,7.719526693848249188e+00,0.000000000000000000e+00,-1.000000009959163938e+00,0.000000000000000000e+00,-1.371263403955013949e-12,0.000000000000000000e+00 +4.053703260031325328e+01,2.795500000000000114e+02,0.000000000000000000e+00,7.718231277626998121e+00,0.000000000000000000e+00,-1.000000009959165714e+00,0.000000000000000000e+00,7.197924781994966436e-12,0.000000000000000000e+00 +4.053832823394229479e+01,2.795600000000000023e+02,0.000000000000000000e+00,7.716935643985054938e+00,0.000000000000000000e+00,-1.000000009959156388e+00,0.000000000000000000e+00,2.942086241458050505e-10,0.000000000000000000e+00 +4.053962408510152926e+01,2.795699999999999932e+02,0.000000000000000000e+00,7.715639792812914344e+00,0.000000000000000000e+00,-1.000000009958775138e+00,0.000000000000000000e+00,-6.628433437326367439e-10,0.000000000000000000e+00 +4.054092015390055792e+01,2.795799999999999841e+02,0.000000000000000000e+00,7.714343724000979563e+00,0.000000000000000000e+00,-1.000000009959634228e+00,0.000000000000000000e+00,3.734183921704689387e-10,0.000000000000000000e+00 +4.054221644044906725e+01,2.795900000000000318e+02,0.000000000000000000e+00,7.713047437439559673e+00,0.000000000000000000e+00,-1.000000009959150171e+00,0.000000000000000000e+00,-2.336041738863494088e-10,0.000000000000000000e+00 +4.054351294485684321e+01,2.796000000000000227e+02,0.000000000000000000e+00,7.711750933018874932e+00,0.000000000000000000e+00,-1.000000009959453040e+00,0.000000000000000000e+00,2.236332612098357620e-10,0.000000000000000000e+00 +4.054480966723374991e+01,2.796100000000000136e+02,0.000000000000000000e+00,7.710454210629050564e+00,0.000000000000000000e+00,-1.000000009959163050e+00,0.000000000000000000e+00,-3.032066688174250461e-10,0.000000000000000000e+00 +4.054610660768976516e+01,2.796200000000000045e+02,0.000000000000000000e+00,7.709157270160121200e+00,0.000000000000000000e+00,-1.000000009959556291e+00,0.000000000000000000e+00,3.623831444017117332e-10,0.000000000000000000e+00 +4.054740376633493781e+01,2.796299999999999955e+02,0.000000000000000000e+00,7.707860111502027323e+00,0.000000000000000000e+00,-1.000000009959086222e+00,0.000000000000000000e+00,-3.535935764267958959e-10,0.000000000000000000e+00 +4.054870114327942332e+01,2.796399999999999864e+02,0.000000000000000000e+00,7.706562734544618820e+00,0.000000000000000000e+00,-1.000000009959544967e+00,0.000000000000000000e+00,2.524020999639845297e-10,0.000000000000000000e+00 +4.054999873863346949e+01,2.796500000000000341e+02,0.000000000000000000e+00,7.705265139177650546e+00,0.000000000000000000e+00,-1.000000009959217451e+00,0.000000000000000000e+00,1.343066354631984493e-10,0.000000000000000000e+00 +4.055129655250740939e+01,2.796600000000000250e+02,0.000000000000000000e+00,7.703967325290786761e+00,0.000000000000000000e+00,-1.000000009959043146e+00,0.000000000000000000e+00,-1.144407710955594137e-10,0.000000000000000000e+00 +4.055259458501166847e+01,2.796700000000000159e+02,0.000000000000000000e+00,7.702669292773597576e+00,0.000000000000000000e+00,-1.000000009959191694e+00,0.000000000000000000e+00,-4.287812753075084098e-10,0.000000000000000000e+00 +4.055389283625677876e+01,2.796800000000000068e+02,0.000000000000000000e+00,7.701371041515559845e+00,0.000000000000000000e+00,-1.000000009959748359e+00,0.000000000000000000e+00,3.103736920884334871e-10,0.000000000000000000e+00 +4.055519130635335046e+01,2.796899999999999977e+02,0.000000000000000000e+00,7.700072571406057165e+00,0.000000000000000000e+00,-1.000000009959345348e+00,0.000000000000000000e+00,6.018353693481985979e-11,0.000000000000000000e+00 +4.055648999541209321e+01,2.796999999999999886e+02,0.000000000000000000e+00,7.698773882334381646e+00,0.000000000000000000e+00,-1.000000009959267189e+00,0.000000000000000000e+00,-5.948959793783103754e-11,0.000000000000000000e+00 +4.055778890354380906e+01,2.797099999999999795e+02,0.000000000000000000e+00,7.697474974189730368e+00,0.000000000000000000e+00,-1.000000009959344460e+00,0.000000000000000000e+00,1.657907305877346098e-11,0.000000000000000000e+00 +4.055908803085939240e+01,2.797200000000000273e+02,0.000000000000000000e+00,7.696175846861207148e+00,0.000000000000000000e+00,-1.000000009959322922e+00,0.000000000000000000e+00,-1.727692162928713622e-10,0.000000000000000000e+00 +4.056038737746983713e+01,2.797300000000000182e+02,0.000000000000000000e+00,7.694876500237822547e+00,0.000000000000000000e+00,-1.000000009959547409e+00,0.000000000000000000e+00,-3.536814031755385076e-11,0.000000000000000000e+00 +4.056168694348622239e+01,2.797400000000000091e+02,0.000000000000000000e+00,7.693576934208492979e+00,0.000000000000000000e+00,-1.000000009959593372e+00,0.000000000000000000e+00,-3.177470086518984877e-11,0.000000000000000000e+00 +4.056298672901972679e+01,2.797500000000000000e+02,0.000000000000000000e+00,7.692277148662041597e+00,0.000000000000000000e+00,-1.000000009959634673e+00,0.000000000000000000e+00,4.293984002087552017e-10,0.000000000000000000e+00 +4.056428673418162134e+01,2.797599999999999909e+02,0.000000000000000000e+00,7.690977143487197409e+00,0.000000000000000000e+00,-1.000000009959076452e+00,0.000000000000000000e+00,-6.878776644729007097e-10,0.000000000000000000e+00 +4.056558695908327650e+01,2.797699999999999818e+02,0.000000000000000000e+00,7.689676918572596165e+00,0.000000000000000000e+00,-1.000000009959970848e+00,0.000000000000000000e+00,3.602722186843582262e-10,0.000000000000000000e+00 +4.056688740383614089e+01,2.797800000000000296e+02,0.000000000000000000e+00,7.688376473806776801e+00,0.000000000000000000e+00,-1.000000009959502334e+00,0.000000000000000000e+00,-3.755757536610927956e-11,0.000000000000000000e+00 +4.056818806855177684e+01,2.797900000000000205e+02,0.000000000000000000e+00,7.687075809078187660e+00,0.000000000000000000e+00,-1.000000009959551184e+00,0.000000000000000000e+00,2.853892844884849027e-10,0.000000000000000000e+00 +4.056948895334182481e+01,2.798000000000000114e+02,0.000000000000000000e+00,7.685774924275180275e+00,0.000000000000000000e+00,-1.000000009959179925e+00,0.000000000000000000e+00,-1.790207514576961128e-10,0.000000000000000000e+00 +4.057079005831803187e+01,2.798100000000000023e+02,0.000000000000000000e+00,7.684473819286012919e+00,0.000000000000000000e+00,-1.000000009959412850e+00,0.000000000000000000e+00,-3.151528625671421727e-10,0.000000000000000000e+00 +4.057209138359223743e+01,2.798199999999999932e+02,0.000000000000000000e+00,7.683172493998847941e+00,0.000000000000000000e+00,-1.000000009959822966e+00,0.000000000000000000e+00,-5.681003313332802957e-11,0.000000000000000000e+00 +4.057339292927636620e+01,2.798299999999999841e+02,0.000000000000000000e+00,7.681870948301753543e+00,0.000000000000000000e+00,-1.000000009959896907e+00,0.000000000000000000e+00,6.613068685227462912e-10,0.000000000000000000e+00 +4.057469469548244945e+01,2.798400000000000318e+02,0.000000000000000000e+00,7.680569182082703783e+00,0.000000000000000000e+00,-1.000000009959036040e+00,0.000000000000000000e+00,-7.137220154222160150e-10,0.000000000000000000e+00 +4.057599668232261081e+01,2.798500000000000227e+02,0.000000000000000000e+00,7.679267195229578569e+00,0.000000000000000000e+00,-1.000000009959965297e+00,0.000000000000000000e+00,7.673129327153273086e-11,0.000000000000000000e+00 +4.057729888990905920e+01,2.798600000000000136e+02,0.000000000000000000e+00,7.677964987630159222e+00,0.000000000000000000e+00,-1.000000009959865377e+00,0.000000000000000000e+00,4.787220772076825168e-10,0.000000000000000000e+00 +4.057860131835411011e+01,2.798700000000000045e+02,0.000000000000000000e+00,7.676662559172135580e+00,0.000000000000000000e+00,-1.000000009959241876e+00,0.000000000000000000e+00,-4.869932220054006125e-10,0.000000000000000000e+00 +4.057990396777017139e+01,2.798799999999999955e+02,0.000000000000000000e+00,7.675359909743101561e+00,0.000000000000000000e+00,-1.000000009959876257e+00,0.000000000000000000e+00,3.865289482995438089e-10,0.000000000000000000e+00 +4.058120683826974329e+01,2.798899999999999864e+02,0.000000000000000000e+00,7.674057039230553379e+00,0.000000000000000000e+00,-1.000000009959372660e+00,0.000000000000000000e+00,-4.961998389560878445e-10,0.000000000000000000e+00 +4.058250992996542550e+01,2.799000000000000341e+02,0.000000000000000000e+00,7.672753947521894879e+00,0.000000000000000000e+00,-1.000000009960019254e+00,0.000000000000000000e+00,5.927150100377404236e-10,0.000000000000000000e+00 +4.058381324296991011e+01,2.799100000000000250e+02,0.000000000000000000e+00,7.671450634504431321e+00,0.000000000000000000e+00,-1.000000009959246761e+00,0.000000000000000000e+00,-4.628149280249913272e-10,0.000000000000000000e+00 +4.058511677739598156e+01,2.799200000000000159e+02,0.000000000000000000e+00,7.670147100065375589e+00,0.000000000000000000e+00,-1.000000009959850056e+00,0.000000000000000000e+00,6.420742730216858488e-11,0.000000000000000000e+00 +4.058642053335653088e+01,2.799300000000000068e+02,0.000000000000000000e+00,7.668843344091841097e+00,0.000000000000000000e+00,-1.000000009959766345e+00,0.000000000000000000e+00,1.496783430411758621e-10,0.000000000000000000e+00 +4.058772451096453437e+01,2.799399999999999977e+02,0.000000000000000000e+00,7.667539366470847995e+00,0.000000000000000000e+00,-1.000000009959571168e+00,0.000000000000000000e+00,-1.385864099991367516e-10,0.000000000000000000e+00 +4.058902871033307491e+01,2.799499999999999886e+02,0.000000000000000000e+00,7.666235167089319624e+00,0.000000000000000000e+00,-1.000000009959751912e+00,0.000000000000000000e+00,-2.109082990925085505e-10,0.000000000000000000e+00 +4.059033313157532064e+01,2.799599999999999795e+02,0.000000000000000000e+00,7.664930745834082515e+00,0.000000000000000000e+00,-1.000000009960027025e+00,0.000000000000000000e+00,5.216496731459732493e-10,0.000000000000000000e+00 +4.059163777480453916e+01,2.799700000000000273e+02,0.000000000000000000e+00,7.663626102591867273e+00,0.000000000000000000e+00,-1.000000009959346459e+00,0.000000000000000000e+00,-4.820822130078896572e-10,0.000000000000000000e+00 +4.059294264013410469e+01,2.799800000000000182e+02,0.000000000000000000e+00,7.662321237249309469e+00,0.000000000000000000e+00,-1.000000009959975511e+00,0.000000000000000000e+00,-2.432969241465191004e-11,0.000000000000000000e+00 +4.059424772767746958e+01,2.799900000000000091e+02,0.000000000000000000e+00,7.661016149692945199e+00,0.000000000000000000e+00,-1.000000009960007263e+00,0.000000000000000000e+00,3.970337768196182494e-10,0.000000000000000000e+00 +4.059555303754819988e+01,2.800000000000000000e+02,0.000000000000000000e+00,7.659710839809216409e+00,0.000000000000000000e+00,-1.000000009959489011e+00,0.000000000000000000e+00,-1.921901138009921436e-10,0.000000000000000000e+00 +4.059685856985994690e+01,2.800099999999999909e+02,0.000000000000000000e+00,7.658405307484468238e+00,0.000000000000000000e+00,-1.000000009959739922e+00,0.000000000000000000e+00,-1.600177633585638882e-10,0.000000000000000000e+00 +4.059816432472646142e+01,2.800199999999999818e+02,0.000000000000000000e+00,7.657099552604947235e+00,0.000000000000000000e+00,-1.000000009959948866e+00,0.000000000000000000e+00,3.944504936469134509e-11,0.000000000000000000e+00 +4.059947030226159370e+01,2.800300000000000296e+02,0.000000000000000000e+00,7.655793575056804023e+00,0.000000000000000000e+00,-1.000000009959897351e+00,0.000000000000000000e+00,-4.623803234550140083e-11,0.000000000000000000e+00 +4.060077650257929349e+01,2.800400000000000205e+02,0.000000000000000000e+00,7.654487374726092419e+00,0.000000000000000000e+00,-1.000000009959957747e+00,0.000000000000000000e+00,1.714934363649917522e-10,0.000000000000000000e+00 +4.060208292579360290e+01,2.800500000000000114e+02,0.000000000000000000e+00,7.653180951498768536e+00,0.000000000000000000e+00,-1.000000009959733704e+00,0.000000000000000000e+00,-2.798825399689890633e-10,0.000000000000000000e+00 +4.060338957201866350e+01,2.800600000000000023e+02,0.000000000000000000e+00,7.651874305260691678e+00,0.000000000000000000e+00,-1.000000009960099412e+00,0.000000000000000000e+00,2.286931269886081361e-10,0.000000000000000000e+00 +4.060469644136871636e+01,2.800699999999999932e+02,0.000000000000000000e+00,7.650567435897622559e+00,0.000000000000000000e+00,-1.000000009959800540e+00,0.000000000000000000e+00,2.048713271849974022e-10,0.000000000000000000e+00 +4.060600353395809492e+01,2.800799999999999841e+02,0.000000000000000000e+00,7.649260343295225972e+00,0.000000000000000000e+00,-1.000000009959532754e+00,0.000000000000000000e+00,-2.822868758868649516e-10,0.000000000000000000e+00 +4.060731084990123207e+01,2.800900000000000318e+02,0.000000000000000000e+00,7.647953027339068122e+00,0.000000000000000000e+00,-1.000000009959901792e+00,0.000000000000000000e+00,-1.248167230703914838e-10,0.000000000000000000e+00 +4.060861838931266021e+01,2.801000000000000227e+02,0.000000000000000000e+00,7.646645487914616623e+00,0.000000000000000000e+00,-1.000000009960064995e+00,0.000000000000000000e+00,2.253108491437382323e-10,0.000000000000000000e+00 +4.060992615230701119e+01,2.801100000000000136e+02,0.000000000000000000e+00,7.645337724907242283e+00,0.000000000000000000e+00,-1.000000009959770342e+00,0.000000000000000000e+00,-2.009965497660231905e-10,0.000000000000000000e+00 +4.061123413899900925e+01,2.801200000000000045e+02,0.000000000000000000e+00,7.644029738202218205e+00,0.000000000000000000e+00,-1.000000009960033243e+00,0.000000000000000000e+00,-2.966907604568519665e-10,0.000000000000000000e+00 +4.061254234950347808e+01,2.801299999999999955e+02,0.000000000000000000e+00,7.642721527684718019e+00,0.000000000000000000e+00,-1.000000009960421377e+00,0.000000000000000000e+00,5.253989654388365888e-10,0.000000000000000000e+00 +4.061385078393534798e+01,2.801399999999999864e+02,0.000000000000000000e+00,7.641413093239817655e+00,0.000000000000000000e+00,-1.000000009959733926e+00,0.000000000000000000e+00,-2.597700598128174356e-10,0.000000000000000000e+00 +4.061515944240963449e+01,2.801500000000000341e+02,0.000000000000000000e+00,7.640104434752496232e+00,0.000000000000000000e+00,-1.000000009960073877e+00,0.000000000000000000e+00,1.051795261896370394e-11,0.000000000000000000e+00 +4.061646832504145976e+01,2.801600000000000250e+02,0.000000000000000000e+00,7.638795552107631615e+00,0.000000000000000000e+00,-1.000000009960060110e+00,0.000000000000000000e+00,3.680652748821690989e-10,0.000000000000000000e+00 +4.061777743194604540e+01,2.801700000000000159e+02,0.000000000000000000e+00,7.637486445190004858e+00,0.000000000000000000e+00,-1.000000009959578273e+00,0.000000000000000000e+00,-6.730878898899368041e-10,0.000000000000000000e+00 +4.061908676323871248e+01,2.801800000000000068e+02,0.000000000000000000e+00,7.636177113884298429e+00,0.000000000000000000e+00,-1.000000009960459568e+00,0.000000000000000000e+00,5.839549728263175898e-10,0.000000000000000000e+00 +4.062039631903487447e+01,2.801899999999999977e+02,0.000000000000000000e+00,7.634867558075093541e+00,0.000000000000000000e+00,-1.000000009959694847e+00,0.000000000000000000e+00,-4.543353483575096656e-10,0.000000000000000000e+00 +4.062170609945004429e+01,2.801999999999999886e+02,0.000000000000000000e+00,7.633557777646876374e+00,0.000000000000000000e+00,-1.000000009960289926e+00,0.000000000000000000e+00,4.251035724842282007e-10,0.000000000000000000e+00 +4.062301610459984147e+01,2.802099999999999795e+02,0.000000000000000000e+00,7.632247772484030079e+00,0.000000000000000000e+00,-1.000000009959733038e+00,0.000000000000000000e+00,-3.328389702774411057e-10,0.000000000000000000e+00 +4.062432633459997788e+01,2.802200000000000273e+02,0.000000000000000000e+00,7.630937542470841883e+00,0.000000000000000000e+00,-1.000000009960169134e+00,0.000000000000000000e+00,-7.014851238957683172e-11,0.000000000000000000e+00 +4.062563678956627200e+01,2.802300000000000182e+02,0.000000000000000000e+00,7.629627087491496873e+00,0.000000000000000000e+00,-1.000000009960261060e+00,0.000000000000000000e+00,2.471717479723987784e-10,0.000000000000000000e+00 +4.062694746961463466e+01,2.802400000000000091e+02,0.000000000000000000e+00,7.628316407430082435e+00,0.000000000000000000e+00,-1.000000009959937097e+00,0.000000000000000000e+00,-3.448630759967407311e-10,0.000000000000000000e+00 +4.062825837486107616e+01,2.802500000000000000e+02,0.000000000000000000e+00,7.627005502170586482e+00,0.000000000000000000e+00,-1.000000009960389180e+00,0.000000000000000000e+00,2.916267999250654689e-10,0.000000000000000000e+00 +4.062956950542170631e+01,2.802599999999999909e+02,0.000000000000000000e+00,7.625694371596895671e+00,0.000000000000000000e+00,-1.000000009960006819e+00,0.000000000000000000e+00,1.588263147791010891e-10,0.000000000000000000e+00 +4.063088086141274147e+01,2.802699999999999818e+02,0.000000000000000000e+00,7.624383015592798962e+00,0.000000000000000000e+00,-1.000000009959798541e+00,0.000000000000000000e+00,-6.724409770771844250e-10,0.000000000000000000e+00 +4.063219244295049037e+01,2.802800000000000296e+02,0.000000000000000000e+00,7.623071434041984062e+00,0.000000000000000000e+00,-1.000000009960680503e+00,0.000000000000000000e+00,4.494017304375367429e-10,0.000000000000000000e+00 +4.063350425015136835e+01,2.802900000000000205e+02,0.000000000000000000e+00,7.621759626828037426e+00,0.000000000000000000e+00,-1.000000009960090974e+00,0.000000000000000000e+00,-1.963149902000199334e-11,0.000000000000000000e+00 +4.063481628313189020e+01,2.803000000000000114e+02,0.000000000000000000e+00,7.620447593834448696e+00,0.000000000000000000e+00,-1.000000009960116731e+00,0.000000000000000000e+00,5.600782401325337841e-11,0.000000000000000000e+00 +4.063612854200866309e+01,2.803100000000000023e+02,0.000000000000000000e+00,7.619135334944604487e+00,0.000000000000000000e+00,-1.000000009960043235e+00,0.000000000000000000e+00,-2.854046179401670097e-10,0.000000000000000000e+00 +4.063744102689840076e+01,2.803199999999999932e+02,0.000000000000000000e+00,7.617822850041791938e+00,0.000000000000000000e+00,-1.000000009960417824e+00,0.000000000000000000e+00,5.768002946081043376e-11,0.000000000000000000e+00 +4.063875373791792356e+01,2.803299999999999841e+02,0.000000000000000000e+00,7.616510139009196934e+00,0.000000000000000000e+00,-1.000000009960342107e+00,0.000000000000000000e+00,1.243035663771987312e-10,0.000000000000000000e+00 +4.064006667518413707e+01,2.803400000000000318e+02,0.000000000000000000e+00,7.615197201729905885e+00,0.000000000000000000e+00,-1.000000009960178904e+00,0.000000000000000000e+00,-1.403458166889986440e-11,0.000000000000000000e+00 +4.064137983881406058e+01,2.803500000000000227e+02,0.000000000000000000e+00,7.613884038086903949e+00,0.000000000000000000e+00,-1.000000009960197334e+00,0.000000000000000000e+00,2.278958285049347546e-10,0.000000000000000000e+00 +4.064269322892480574e+01,2.803600000000000136e+02,0.000000000000000000e+00,7.612570647963075032e+00,0.000000000000000000e+00,-1.000000009959898017e+00,0.000000000000000000e+00,-6.235628262704247610e-10,0.000000000000000000e+00 +4.064400684563359789e+01,2.803700000000000045e+02,0.000000000000000000e+00,7.611257031241202675e+00,0.000000000000000000e+00,-1.000000009960717140e+00,0.000000000000000000e+00,5.908374807454929514e-10,0.000000000000000000e+00 +4.064532068905774764e+01,2.803799999999999955e+02,0.000000000000000000e+00,7.609943187803967390e+00,0.000000000000000000e+00,-1.000000009959940872e+00,0.000000000000000000e+00,-1.753957208126104151e-10,0.000000000000000000e+00 +4.064663475931467218e+01,2.803899999999999864e+02,0.000000000000000000e+00,7.608629117533951991e+00,0.000000000000000000e+00,-1.000000009960171354e+00,0.000000000000000000e+00,-2.779153551367341400e-10,0.000000000000000000e+00 +4.064794905652190238e+01,2.804000000000000341e+02,0.000000000000000000e+00,7.607314820313634485e+00,0.000000000000000000e+00,-1.000000009960536618e+00,0.000000000000000000e+00,3.535418606518722597e-10,0.000000000000000000e+00 +4.064926358079705437e+01,2.804100000000000250e+02,0.000000000000000000e+00,7.606000296025392515e+00,0.000000000000000000e+00,-1.000000009960071878e+00,0.000000000000000000e+00,-2.661661217326031596e-10,0.000000000000000000e+00 +4.065057833225785089e+01,2.804200000000000159e+02,0.000000000000000000e+00,7.604685544551503362e+00,0.000000000000000000e+00,-1.000000009960421821e+00,0.000000000000000000e+00,-9.456044624986596290e-12,0.000000000000000000e+00 +4.065189331102211412e+01,2.804300000000000068e+02,0.000000000000000000e+00,7.603370565774140388e+00,0.000000000000000000e+00,-1.000000009960434255e+00,0.000000000000000000e+00,1.666339677002043493e-10,0.000000000000000000e+00 +4.065320851720777995e+01,2.804399999999999977e+02,0.000000000000000000e+00,7.602055359575376592e+00,0.000000000000000000e+00,-1.000000009960215097e+00,0.000000000000000000e+00,-1.796027083186979735e-10,0.000000000000000000e+00 +4.065452395093286952e+01,2.804499999999999886e+02,0.000000000000000000e+00,7.600739925837182831e+00,0.000000000000000000e+00,-1.000000009960451353e+00,0.000000000000000000e+00,5.063109881911287232e-11,0.000000000000000000e+00 +4.065583961231551768e+01,2.804599999999999795e+02,0.000000000000000000e+00,7.599424264441426935e+00,0.000000000000000000e+00,-1.000000009960384739e+00,0.000000000000000000e+00,-9.837607053796107967e-11,0.000000000000000000e+00 +4.065715550147396584e+01,2.804700000000000273e+02,0.000000000000000000e+00,7.598108375269875481e+00,0.000000000000000000e+00,-1.000000009960514191e+00,0.000000000000000000e+00,-4.099699102845421371e-11,0.000000000000000000e+00 +4.065847161852654068e+01,2.804800000000000182e+02,0.000000000000000000e+00,7.596792258204192017e+00,0.000000000000000000e+00,-1.000000009960568148e+00,0.000000000000000000e+00,2.933391693330975388e-10,0.000000000000000000e+00 +4.065978796359168257e+01,2.804900000000000091e+02,0.000000000000000000e+00,7.595475913125937950e+00,0.000000000000000000e+00,-1.000000009960182012e+00,0.000000000000000000e+00,-4.739161799856869403e-11,0.000000000000000000e+00 +4.066110453678793135e+01,2.805000000000000000e+02,0.000000000000000000e+00,7.594159339916572549e+00,0.000000000000000000e+00,-1.000000009960244407e+00,0.000000000000000000e+00,-4.793986319780522154e-10,0.000000000000000000e+00 +4.066242133823394056e+01,2.805099999999999909e+02,0.000000000000000000e+00,7.592842538457451163e+00,0.000000000000000000e+00,-1.000000009960875680e+00,0.000000000000000000e+00,6.059303299824865361e-10,0.000000000000000000e+00 +4.066373836804844899e+01,2.805199999999999818e+02,0.000000000000000000e+00,7.591525508629826113e+00,0.000000000000000000e+00,-1.000000009960077652e+00,0.000000000000000000e+00,-3.035868765497954830e-10,0.000000000000000000e+00 +4.066505562635030913e+01,2.805300000000000296e+02,0.000000000000000000e+00,7.590208250314849359e+00,0.000000000000000000e+00,-1.000000009960477554e+00,0.000000000000000000e+00,-6.421239858433919516e-11,0.000000000000000000e+00 +4.066637311325847293e+01,2.805400000000000205e+02,0.000000000000000000e+00,7.588890763393566274e+00,0.000000000000000000e+00,-1.000000009960562153e+00,0.000000000000000000e+00,-1.388499535134601476e-10,0.000000000000000000e+00 +4.066769082889199183e+01,2.805500000000000114e+02,0.000000000000000000e+00,7.587573047746920984e+00,0.000000000000000000e+00,-1.000000009960745118e+00,0.000000000000000000e+00,5.674337893959797945e-10,0.000000000000000000e+00 +4.066900877337003095e+01,2.805600000000000023e+02,0.000000000000000000e+00,7.586255103255753696e+00,0.000000000000000000e+00,-1.000000009959997271e+00,0.000000000000000000e+00,-4.290388432968673509e-10,0.000000000000000000e+00 +4.067032694681185490e+01,2.805699999999999932e+02,0.000000000000000000e+00,7.584936929800802474e+00,0.000000000000000000e+00,-1.000000009960562819e+00,0.000000000000000000e+00,1.145252140292051439e-11,0.000000000000000000e+00 +4.067164534933682773e+01,2.805799999999999841e+02,0.000000000000000000e+00,7.583618527262698805e+00,0.000000000000000000e+00,-1.000000009960547720e+00,0.000000000000000000e+00,-8.284795772557912318e-11,0.000000000000000000e+00 +4.067296398106442012e+01,2.805900000000000318e+02,0.000000000000000000e+00,7.582299895521972921e+00,0.000000000000000000e+00,-1.000000009960656966e+00,0.000000000000000000e+00,-1.282909893959903321e-10,0.000000000000000000e+00 +4.067428284211420930e+01,2.806000000000000227e+02,0.000000000000000000e+00,7.580981034459050250e+00,0.000000000000000000e+00,-1.000000009960826164e+00,0.000000000000000000e+00,4.585352617129434788e-10,0.000000000000000000e+00 +4.067560193260586487e+01,2.806100000000000136e+02,0.000000000000000000e+00,7.579661943954252301e+00,0.000000000000000000e+00,-1.000000009960221314e+00,0.000000000000000000e+00,-2.913312885374177293e-10,0.000000000000000000e+00 +4.067692125265917724e+01,2.806200000000000045e+02,0.000000000000000000e+00,7.578342623887797558e+00,0.000000000000000000e+00,-1.000000009960605674e+00,0.000000000000000000e+00,-2.628424406683813803e-10,0.000000000000000000e+00 +4.067824080239403628e+01,2.806299999999999955e+02,0.000000000000000000e+00,7.577023074139797920e+00,0.000000000000000000e+00,-1.000000009960952507e+00,0.000000000000000000e+00,6.156037330624090473e-10,0.000000000000000000e+00 +4.067956058193042423e+01,2.806399999999999864e+02,0.000000000000000000e+00,7.575703294590262260e+00,0.000000000000000000e+00,-1.000000009960140046e+00,0.000000000000000000e+00,-6.414015243876896308e-10,0.000000000000000000e+00 +4.068088059138844415e+01,2.806500000000000341e+02,0.000000000000000000e+00,7.574383285119096421e+00,0.000000000000000000e+00,-1.000000009960986702e+00,0.000000000000000000e+00,1.175613809922426435e-10,0.000000000000000000e+00 +4.068220083088829142e+01,2.806600000000000250e+02,0.000000000000000000e+00,7.573063045606097887e+00,0.000000000000000000e+00,-1.000000009960831493e+00,0.000000000000000000e+00,4.171944882036255411e-10,0.000000000000000000e+00 +4.068352130055027516e+01,2.806700000000000159e+02,0.000000000000000000e+00,7.571742575930962893e+00,0.000000000000000000e+00,-1.000000009960280600e+00,0.000000000000000000e+00,-1.783821728787493741e-10,0.000000000000000000e+00 +4.068484200049480393e+01,2.806800000000000068e+02,0.000000000000000000e+00,7.570421875973281978e+00,0.000000000000000000e+00,-1.000000009960516190e+00,0.000000000000000000e+00,-6.690265911573881387e-11,0.000000000000000000e+00 +4.068616293084239288e+01,2.806899999999999977e+02,0.000000000000000000e+00,7.569100945612539100e+00,0.000000000000000000e+00,-1.000000009960604563e+00,0.000000000000000000e+00,-1.934460411501255753e-10,0.000000000000000000e+00 +4.068748409171365665e+01,2.806999999999999886e+02,0.000000000000000000e+00,7.567779784728114301e+00,0.000000000000000000e+00,-1.000000009960860137e+00,0.000000000000000000e+00,2.453361621791005167e-11,0.000000000000000000e+00 +4.068880548322932356e+01,2.807099999999999795e+02,0.000000000000000000e+00,7.566458393199281929e+00,0.000000000000000000e+00,-1.000000009960827718e+00,0.000000000000000000e+00,1.515442320668858642e-10,0.000000000000000000e+00 +4.069012710551022849e+01,2.807200000000000273e+02,0.000000000000000000e+00,7.565136770905211527e+00,0.000000000000000000e+00,-1.000000009960627434e+00,0.000000000000000000e+00,-2.457544189445731631e-10,0.000000000000000000e+00 +4.069144895867730582e+01,2.807300000000000182e+02,0.000000000000000000e+00,7.563814917724966946e+00,0.000000000000000000e+00,-1.000000009960952285e+00,0.000000000000000000e+00,4.304569508424080668e-10,0.000000000000000000e+00 +4.069277104285159652e+01,2.807400000000000091e+02,0.000000000000000000e+00,7.562492833537505454e+00,0.000000000000000000e+00,-1.000000009960383185e+00,0.000000000000000000e+00,-2.858016668368009848e-10,0.000000000000000000e+00 +4.069409335815424811e+01,2.807500000000000000e+02,0.000000000000000000e+00,7.561170518221680403e+00,0.000000000000000000e+00,-1.000000009960761105e+00,0.000000000000000000e+00,-2.882700695880174535e-10,0.000000000000000000e+00 +4.069541590470651471e+01,2.807599999999999909e+02,0.000000000000000000e+00,7.559847971656236787e+00,0.000000000000000000e+00,-1.000000009961142355e+00,0.000000000000000000e+00,4.967046806776577017e-10,0.000000000000000000e+00 +4.069673868262975702e+01,2.807699999999999818e+02,0.000000000000000000e+00,7.558525193719814794e+00,0.000000000000000000e+00,-1.000000009960485325e+00,0.000000000000000000e+00,-3.945753219810673578e-10,0.000000000000000000e+00 +4.069806169204544233e+01,2.807800000000000296e+02,0.000000000000000000e+00,7.557202184290949809e+00,0.000000000000000000e+00,-1.000000009961007352e+00,0.000000000000000000e+00,1.575675778975150002e-10,0.000000000000000000e+00 +4.069938493307514449e+01,2.807900000000000205e+02,0.000000000000000000e+00,7.555878943248067969e+00,0.000000000000000000e+00,-1.000000009960798852e+00,0.000000000000000000e+00,1.981413484836373852e-10,0.000000000000000000e+00 +4.070070840584053684e+01,2.808000000000000114e+02,0.000000000000000000e+00,7.554555470469491496e+00,0.000000000000000000e+00,-1.000000009960536618e+00,0.000000000000000000e+00,-1.982743872662715426e-10,0.000000000000000000e+00 +4.070203211046340641e+01,2.808100000000000023e+02,0.000000000000000000e+00,7.553231765833435141e+00,0.000000000000000000e+00,-1.000000009960799074e+00,0.000000000000000000e+00,5.719096379029234309e-11,0.000000000000000000e+00 +4.070335604706564681e+01,2.808199999999999932e+02,0.000000000000000000e+00,7.551907829218006185e+00,0.000000000000000000e+00,-1.000000009960723357e+00,0.000000000000000000e+00,2.599133605071892612e-11,0.000000000000000000e+00 +4.070468021576925821e+01,2.808299999999999841e+02,0.000000000000000000e+00,7.550583660501206218e+00,0.000000000000000000e+00,-1.000000009960688940e+00,0.000000000000000000e+00,-2.176183142872504261e-10,0.000000000000000000e+00 +4.070600461669634029e+01,2.808400000000000318e+02,0.000000000000000000e+00,7.549259259560929358e+00,0.000000000000000000e+00,-1.000000009960977154e+00,0.000000000000000000e+00,-9.135683979223833146e-11,0.000000000000000000e+00 +4.070732924996911350e+01,2.808500000000000227e+02,0.000000000000000000e+00,7.547934626274962255e+00,0.000000000000000000e+00,-1.000000009961098169e+00,0.000000000000000000e+00,4.789945587256615368e-10,0.000000000000000000e+00 +4.070865411570989068e+01,2.808600000000000136e+02,0.000000000000000000e+00,7.546609760520984977e+00,0.000000000000000000e+00,-1.000000009960463565e+00,0.000000000000000000e+00,-4.552833381262891844e-10,0.000000000000000000e+00 +4.070997921404110542e+01,2.808700000000000045e+02,0.000000000000000000e+00,7.545284662176571011e+00,0.000000000000000000e+00,-1.000000009961066860e+00,0.000000000000000000e+00,2.169629728658564013e-10,0.000000000000000000e+00 +4.071130454508529084e+01,2.808799999999999955e+02,0.000000000000000000e+00,7.543959331119183709e+00,0.000000000000000000e+00,-1.000000009960779312e+00,0.000000000000000000e+00,-4.638339354350100377e-10,0.000000000000000000e+00 +4.071263010896508661e+01,2.808899999999999864e+02,0.000000000000000000e+00,7.542633767226181618e+00,0.000000000000000000e+00,-1.000000009961394154e+00,0.000000000000000000e+00,6.111349341388535931e-10,0.000000000000000000e+00 +4.071395590580324608e+01,2.809000000000000341e+02,0.000000000000000000e+00,7.541307970374813152e+00,0.000000000000000000e+00,-1.000000009960583913e+00,0.000000000000000000e+00,-5.256276684796676097e-10,0.000000000000000000e+00 +4.071528193572262921e+01,2.809100000000000250e+02,0.000000000000000000e+00,7.539981940442221919e+00,0.000000000000000000e+00,-1.000000009961280911e+00,0.000000000000000000e+00,2.439327337283429714e-10,0.000000000000000000e+00 +4.071660819884620253e+01,2.809200000000000159e+02,0.000000000000000000e+00,7.538655677305439617e+00,0.000000000000000000e+00,-1.000000009960957392e+00,0.000000000000000000e+00,-3.582184138080899818e-11,0.000000000000000000e+00 +4.071793469529703913e+01,2.809300000000000068e+02,0.000000000000000000e+00,7.537329180841393139e+00,0.000000000000000000e+00,-1.000000009961004910e+00,0.000000000000000000e+00,2.264412298042729318e-10,0.000000000000000000e+00 +4.071926142519831870e+01,2.809399999999999977e+02,0.000000000000000000e+00,7.536002450926899243e+00,0.000000000000000000e+00,-1.000000009960704483e+00,0.000000000000000000e+00,-4.077902010048729221e-10,0.000000000000000000e+00 +4.072058838867333463e+01,2.809499999999999886e+02,0.000000000000000000e+00,7.534675487438667218e+00,0.000000000000000000e+00,-1.000000009961245606e+00,0.000000000000000000e+00,1.560940761042911915e-10,0.000000000000000000e+00 +4.072191558584548687e+01,2.809599999999999795e+02,0.000000000000000000e+00,7.533348290253296220e+00,0.000000000000000000e+00,-1.000000009961038439e+00,0.000000000000000000e+00,4.799089180437634468e-10,0.000000000000000000e+00 +4.072324301683828196e+01,2.809700000000000273e+02,0.000000000000000000e+00,7.532020859247278821e+00,0.000000000000000000e+00,-1.000000009960401393e+00,0.000000000000000000e+00,-8.706746566664888388e-10,0.000000000000000000e+00 +4.072457068177534012e+01,2.809800000000000182e+02,0.000000000000000000e+00,7.530693194296998350e+00,0.000000000000000000e+00,-1.000000009961557357e+00,0.000000000000000000e+00,7.148440374220503551e-10,0.000000000000000000e+00 +4.072589858078038105e+01,2.809900000000000091e+02,0.000000000000000000e+00,7.529365295278726222e+00,0.000000000000000000e+00,-1.000000009960608116e+00,0.000000000000000000e+00,-2.283753851217871028e-10,0.000000000000000000e+00 +4.072722671397724525e+01,2.810000000000000000e+02,0.000000000000000000e+00,7.528037162068629939e+00,0.000000000000000000e+00,-1.000000009960911429e+00,0.000000000000000000e+00,-9.812057420198273396e-11,0.000000000000000000e+00 +4.072855508148987980e+01,2.810099999999999909e+02,0.000000000000000000e+00,7.526708794542763314e+00,0.000000000000000000e+00,-1.000000009961041769e+00,0.000000000000000000e+00,-3.282364618435892793e-10,0.000000000000000000e+00 +4.072988368344233834e+01,2.810199999999999818e+02,0.000000000000000000e+00,7.525380192577072691e+00,0.000000000000000000e+00,-1.000000009961477865e+00,0.000000000000000000e+00,1.642563580551317828e-10,0.000000000000000000e+00 +4.073121251995878112e+01,2.810300000000000296e+02,0.000000000000000000e+00,7.524051356047394279e+00,0.000000000000000000e+00,-1.000000009961259595e+00,0.000000000000000000e+00,4.492445104012130705e-10,0.000000000000000000e+00 +4.073254159116348205e+01,2.810400000000000205e+02,0.000000000000000000e+00,7.522722284829455930e+00,0.000000000000000000e+00,-1.000000009960662517e+00,0.000000000000000000e+00,-4.010582134367340233e-10,0.000000000000000000e+00 +4.073387089718082166e+01,2.810500000000000114e+02,0.000000000000000000e+00,7.521392978798875362e+00,0.000000000000000000e+00,-1.000000009961195646e+00,0.000000000000000000e+00,2.040843543070153488e-10,0.000000000000000000e+00 +4.073520043813529412e+01,2.810600000000000023e+02,0.000000000000000000e+00,7.520063437831158382e+00,0.000000000000000000e+00,-1.000000009960924308e+00,0.000000000000000000e+00,-1.718213411001259476e-10,0.000000000000000000e+00 +4.073653021415150022e+01,2.810699999999999932e+02,0.000000000000000000e+00,7.518733661801703327e+00,0.000000000000000000e+00,-1.000000009961152792e+00,0.000000000000000000e+00,5.609500664783544624e-11,0.000000000000000000e+00 +4.073786022535416151e+01,2.810799999999999841e+02,0.000000000000000000e+00,7.517403650585796626e+00,0.000000000000000000e+00,-1.000000009961078185e+00,0.000000000000000000e+00,-3.989385427538584112e-11,0.000000000000000000e+00 +4.073919047186809195e+01,2.810900000000000318e+02,0.000000000000000000e+00,7.516073404058615459e+00,0.000000000000000000e+00,-1.000000009961131253e+00,0.000000000000000000e+00,-3.813444610817104082e-10,0.000000000000000000e+00 +4.074052095381822625e+01,2.811000000000000227e+02,0.000000000000000000e+00,7.514742922095225985e+00,0.000000000000000000e+00,-1.000000009961638625e+00,0.000000000000000000e+00,6.130466244819800305e-10,0.000000000000000000e+00 +4.074185167132961283e+01,2.811100000000000136e+02,0.000000000000000000e+00,7.513412204570583341e+00,0.000000000000000000e+00,-1.000000009960822833e+00,0.000000000000000000e+00,-4.893160986619963984e-10,0.000000000000000000e+00 +4.074318262452740669e+01,2.811200000000000045e+02,0.000000000000000000e+00,7.512081251359534306e+00,0.000000000000000000e+00,-1.000000009961474090e+00,0.000000000000000000e+00,4.004909089808492754e-10,0.000000000000000000e+00 +4.074451381353686941e+01,2.811299999999999955e+02,0.000000000000000000e+00,7.510750062336811084e+00,0.000000000000000000e+00,-1.000000009960940961e+00,0.000000000000000000e+00,-1.490943048072314739e-10,0.000000000000000000e+00 +4.074584523848338335e+01,2.811399999999999864e+02,0.000000000000000000e+00,7.509418637377038408e+00,0.000000000000000000e+00,-1.000000009961139469e+00,0.000000000000000000e+00,-5.519179710970600069e-11,0.000000000000000000e+00 +4.074717689949243038e+01,2.811500000000000341e+02,0.000000000000000000e+00,7.508086976354727327e+00,0.000000000000000000e+00,-1.000000009961212966e+00,0.000000000000000000e+00,-2.417338799290814819e-10,0.000000000000000000e+00 +4.074850879668961312e+01,2.811600000000000250e+02,0.000000000000000000e+00,7.506755079144278753e+00,0.000000000000000000e+00,-1.000000009961534930e+00,0.000000000000000000e+00,3.700372514114990827e-10,0.000000000000000000e+00 +4.074984093020064080e+01,2.811700000000000159e+02,0.000000000000000000e+00,7.505422945619981689e+00,0.000000000000000000e+00,-1.000000009961041991e+00,0.000000000000000000e+00,-1.436556335915200912e-10,0.000000000000000000e+00 +4.075117330015133632e+01,2.811800000000000068e+02,0.000000000000000000e+00,7.504090575656015005e+00,0.000000000000000000e+00,-1.000000009961233394e+00,0.000000000000000000e+00,-2.029483763521306322e-10,0.000000000000000000e+00 +4.075250590666763628e+01,2.811899999999999977e+02,0.000000000000000000e+00,7.502757969126443882e+00,0.000000000000000000e+00,-1.000000009961503844e+00,0.000000000000000000e+00,2.700499972075657548e-10,0.000000000000000000e+00 +4.075383874987558386e+01,2.811999999999999886e+02,0.000000000000000000e+00,7.501425125905222480e+00,0.000000000000000000e+00,-1.000000009961143910e+00,0.000000000000000000e+00,-1.465772861041568992e-10,0.000000000000000000e+00 +4.075517182990133591e+01,2.812099999999999795e+02,0.000000000000000000e+00,7.500092045866193935e+00,0.000000000000000000e+00,-1.000000009961339309e+00,0.000000000000000000e+00,1.257343006295425192e-10,0.000000000000000000e+00 +4.075650514687116299e+01,2.812200000000000273e+02,0.000000000000000000e+00,7.498758728883087699e+00,0.000000000000000000e+00,-1.000000009961171665e+00,0.000000000000000000e+00,-3.335113015524099428e-10,0.000000000000000000e+00 +4.075783870091144223e+01,2.812300000000000182e+02,0.000000000000000000e+00,7.497425174829522199e+00,0.000000000000000000e+00,-1.000000009961616421e+00,0.000000000000000000e+00,5.293945738662016335e-11,0.000000000000000000e+00 +4.075917249214867866e+01,2.812400000000000091e+02,0.000000000000000000e+00,7.496091383579002176e+00,0.000000000000000000e+00,-1.000000009961545810e+00,0.000000000000000000e+00,3.645181962949720547e-10,0.000000000000000000e+00 +4.076050652070946967e+01,2.812500000000000000e+02,0.000000000000000000e+00,7.494757355004921351e+00,0.000000000000000000e+00,-1.000000009961059533e+00,0.000000000000000000e+00,-3.173573021263284028e-10,0.000000000000000000e+00 +4.076184078672054056e+01,2.812599999999999909e+02,0.000000000000000000e+00,7.493423088980560642e+00,0.000000000000000000e+00,-1.000000009961482972e+00,0.000000000000000000e+00,8.252815879870830105e-11,0.000000000000000000e+00 +4.076317529030872322e+01,2.812699999999999818e+02,0.000000000000000000e+00,7.492088585379086396e+00,0.000000000000000000e+00,-1.000000009961372838e+00,0.000000000000000000e+00,1.455630618753356449e-10,0.000000000000000000e+00 +4.076451003160096320e+01,2.812800000000000296e+02,0.000000000000000000e+00,7.490753844073553935e+00,0.000000000000000000e+00,-1.000000009961178549e+00,0.000000000000000000e+00,-4.790250656346158742e-11,0.000000000000000000e+00 +4.076584501072431266e+01,2.812900000000000205e+02,0.000000000000000000e+00,7.489418864936904896e+00,0.000000000000000000e+00,-1.000000009961242498e+00,0.000000000000000000e+00,-4.185733378358189526e-10,0.000000000000000000e+00 +4.076718022780595163e+01,2.813000000000000114e+02,0.000000000000000000e+00,7.488083647841967228e+00,0.000000000000000000e+00,-1.000000009961801384e+00,0.000000000000000000e+00,6.070475988167128064e-10,0.000000000000000000e+00 +4.076851568297315964e+01,2.813100000000000023e+02,0.000000000000000000e+00,7.486748192661455192e+00,0.000000000000000000e+00,-1.000000009960990699e+00,0.000000000000000000e+00,-3.778617117404678247e-10,0.000000000000000000e+00 +4.076985137635333700e+01,2.813199999999999932e+02,0.000000000000000000e+00,7.485412499267972031e+00,0.000000000000000000e+00,-1.000000009961495406e+00,0.000000000000000000e+00,-3.054931457503358400e-10,0.000000000000000000e+00 +4.077118730807399771e+01,2.813299999999999841e+02,0.000000000000000000e+00,7.484076567534003743e+00,0.000000000000000000e+00,-1.000000009961903524e+00,0.000000000000000000e+00,4.046480138063590320e-10,0.000000000000000000e+00 +4.077252347826276946e+01,2.813400000000000318e+02,0.000000000000000000e+00,7.482740397331924420e+00,0.000000000000000000e+00,-1.000000009961362846e+00,0.000000000000000000e+00,-1.568458015706339118e-10,0.000000000000000000e+00 +4.077385988704738651e+01,2.813500000000000227e+02,0.000000000000000000e+00,7.481403988533995353e+00,0.000000000000000000e+00,-1.000000009961572456e+00,0.000000000000000000e+00,7.940561778150833602e-11,0.000000000000000000e+00 +4.077519653455570392e+01,2.813600000000000136e+02,0.000000000000000000e+00,7.480067341012361481e+00,0.000000000000000000e+00,-1.000000009961466318e+00,0.000000000000000000e+00,1.983124865471976677e-10,0.000000000000000000e+00 +4.077653342091569044e+01,2.813700000000000045e+02,0.000000000000000000e+00,7.478730454639054948e+00,0.000000000000000000e+00,-1.000000009961201197e+00,0.000000000000000000e+00,-2.158795273883467446e-10,0.000000000000000000e+00 +4.077787054625543561e+01,2.813799999999999955e+02,0.000000000000000000e+00,7.477393329285993318e+00,0.000000000000000000e+00,-1.000000009961489855e+00,0.000000000000000000e+00,-8.998906474373421245e-11,0.000000000000000000e+00 +4.077920791070312845e+01,2.813899999999999864e+02,0.000000000000000000e+00,7.476055964824978695e+00,0.000000000000000000e+00,-1.000000009961610203e+00,0.000000000000000000e+00,1.593617177382706475e-10,0.000000000000000000e+00 +4.078054551438708586e+01,2.814000000000000341e+02,0.000000000000000000e+00,7.474718361127699495e+00,0.000000000000000000e+00,-1.000000009961397041e+00,0.000000000000000000e+00,1.163464340681156744e-10,0.000000000000000000e+00 +4.078188335743573134e+01,2.814100000000000250e+02,0.000000000000000000e+00,7.473380518065729561e+00,0.000000000000000000e+00,-1.000000009961241387e+00,0.000000000000000000e+00,-6.342317857576598883e-10,0.000000000000000000e+00 +4.078322143997760207e+01,2.814200000000000159e+02,0.000000000000000000e+00,7.472042435510527270e+00,0.000000000000000000e+00,-1.000000009962090042e+00,0.000000000000000000e+00,4.682055577245482996e-10,0.000000000000000000e+00 +4.078455976214136314e+01,2.814300000000000068e+02,0.000000000000000000e+00,7.470704113333434648e+00,0.000000000000000000e+00,-1.000000009961463432e+00,0.000000000000000000e+00,3.201541018678872656e-11,0.000000000000000000e+00 +4.078589832405577909e+01,2.814399999999999977e+02,0.000000000000000000e+00,7.469365551405681813e+00,0.000000000000000000e+00,-1.000000009961420577e+00,0.000000000000000000e+00,-3.726722129561947074e-10,0.000000000000000000e+00 +4.078723712584974237e+01,2.814499999999999886e+02,0.000000000000000000e+00,7.468026749598380754e+00,0.000000000000000000e+00,-1.000000009961919512e+00,0.000000000000000000e+00,3.241849521154989973e-10,0.000000000000000000e+00 +4.078857616765225913e+01,2.814599999999999795e+02,0.000000000000000000e+00,7.466687707782527994e+00,0.000000000000000000e+00,-1.000000009961485414e+00,0.000000000000000000e+00,2.226610360878552538e-10,0.000000000000000000e+00 +4.078991544959244209e+01,2.814700000000000273e+02,0.000000000000000000e+00,7.465348425829006374e+00,0.000000000000000000e+00,-1.000000009961187208e+00,0.000000000000000000e+00,-5.952586467550694640e-10,0.000000000000000000e+00 +4.079125497179952475e+01,2.814800000000000182e+02,0.000000000000000000e+00,7.464008903608581491e+00,0.000000000000000000e+00,-1.000000009961984571e+00,0.000000000000000000e+00,4.259371273967816671e-10,0.000000000000000000e+00 +4.079259473440285433e+01,2.814900000000000091e+02,0.000000000000000000e+00,7.462669140991901706e+00,0.000000000000000000e+00,-1.000000009961413916e+00,0.000000000000000000e+00,-9.660574804999995728e-11,0.000000000000000000e+00 +4.079393473753190591e+01,2.815000000000000000e+02,0.000000000000000000e+00,7.461329137849502580e+00,0.000000000000000000e+00,-1.000000009961543368e+00,0.000000000000000000e+00,-1.022213442348350352e-10,0.000000000000000000e+00 +4.079527498131625407e+01,2.815099999999999909e+02,0.000000000000000000e+00,7.459988894051800656e+00,0.000000000000000000e+00,-1.000000009961680369e+00,0.000000000000000000e+00,-3.975480688139647633e-12,0.000000000000000000e+00 +4.079661546588560128e+01,2.815199999999999818e+02,0.000000000000000000e+00,7.458648409469097018e+00,0.000000000000000000e+00,-1.000000009961685699e+00,0.000000000000000000e+00,-2.148029973243796419e-10,0.000000000000000000e+00 +4.079795619136976370e+01,2.815300000000000296e+02,0.000000000000000000e+00,7.457307683971576395e+00,0.000000000000000000e+00,-1.000000009961973690e+00,0.000000000000000000e+00,3.353106250446034872e-10,0.000000000000000000e+00 +4.079929715789867828e+01,2.815400000000000205e+02,0.000000000000000000e+00,7.455966717429306279e+00,0.000000000000000000e+00,-1.000000009961524050e+00,0.000000000000000000e+00,-2.475057990238130484e-10,0.000000000000000000e+00 +4.080063836560238855e+01,2.815500000000000114e+02,0.000000000000000000e+00,7.454625509712238696e+00,0.000000000000000000e+00,-1.000000009961856007e+00,0.000000000000000000e+00,9.368768069111526324e-11,0.000000000000000000e+00 +4.080197981461105883e+01,2.815600000000000023e+02,0.000000000000000000e+00,7.453284060690206658e+00,0.000000000000000000e+00,-1.000000009961730330e+00,0.000000000000000000e+00,-3.988457250306475767e-11,0.000000000000000000e+00 +4.080332150505497424e+01,2.815699999999999932e+02,0.000000000000000000e+00,7.451942370232927715e+00,0.000000000000000000e+00,-1.000000009961783842e+00,0.000000000000000000e+00,4.206154869986123300e-10,0.000000000000000000e+00 +4.080466343706453358e+01,2.815799999999999841e+02,0.000000000000000000e+00,7.450600438210001286e+00,0.000000000000000000e+00,-1.000000009961219405e+00,0.000000000000000000e+00,-4.150803367568321743e-10,0.000000000000000000e+00 +4.080600561077025645e+01,2.815900000000000318e+02,0.000000000000000000e+00,7.449258264490910442e+00,0.000000000000000000e+00,-1.000000009961776515e+00,0.000000000000000000e+00,4.962202824970225754e-13,0.000000000000000000e+00 +4.080734802630277613e+01,2.816000000000000227e+02,0.000000000000000000e+00,7.447915848945018347e+00,0.000000000000000000e+00,-1.000000009961775849e+00,0.000000000000000000e+00,-2.217704942671987390e-10,0.000000000000000000e+00 +4.080869068379284670e+01,2.816100000000000136e+02,0.000000000000000000e+00,7.446573191441572703e+00,0.000000000000000000e+00,-1.000000009962073610e+00,0.000000000000000000e+00,4.783492766966650862e-10,0.000000000000000000e+00 +4.081003358337133591e+01,2.816200000000000045e+02,0.000000000000000000e+00,7.445230291849702198e+00,0.000000000000000000e+00,-1.000000009961431235e+00,0.000000000000000000e+00,-2.790556393215636585e-10,0.000000000000000000e+00 +4.081137672516923942e+01,2.816299999999999955e+02,0.000000000000000000e+00,7.443887150038419165e+00,0.000000000000000000e+00,-1.000000009961806047e+00,0.000000000000000000e+00,5.156969941770809871e-11,0.000000000000000000e+00 +4.081272010931765948e+01,2.816399999999999864e+02,0.000000000000000000e+00,7.442543765876615147e+00,0.000000000000000000e+00,-1.000000009961736769e+00,0.000000000000000000e+00,-4.167798412511208536e-10,0.000000000000000000e+00 +4.081406373594782622e+01,2.816500000000000341e+02,0.000000000000000000e+00,7.441200139233065336e+00,0.000000000000000000e+00,-1.000000009962296765e+00,0.000000000000000000e+00,3.674667039467025131e-10,0.000000000000000000e+00 +4.081540760519107636e+01,2.816600000000000250e+02,0.000000000000000000e+00,7.439856269976425018e+00,0.000000000000000000e+00,-1.000000009961802938e+00,0.000000000000000000e+00,2.725766911173788353e-11,0.000000000000000000e+00 +4.081675171717888162e+01,2.816700000000000159e+02,0.000000000000000000e+00,7.438512157975233130e+00,0.000000000000000000e+00,-1.000000009961766301e+00,0.000000000000000000e+00,1.220592623583915264e-10,0.000000000000000000e+00 +4.081809607204281320e+01,2.816800000000000068e+02,0.000000000000000000e+00,7.437167803097907814e+00,0.000000000000000000e+00,-1.000000009961602210e+00,0.000000000000000000e+00,-2.485331394833057115e-10,0.000000000000000000e+00 +4.081944066991457731e+01,2.816899999999999977e+02,0.000000000000000000e+00,7.435823205212749087e+00,0.000000000000000000e+00,-1.000000009961936387e+00,0.000000000000000000e+00,-1.799682024224291084e-11,0.000000000000000000e+00 +4.082078551092599383e+01,2.816999999999999886e+02,0.000000000000000000e+00,7.434478364187937061e+00,0.000000000000000000e+00,-1.000000009961960590e+00,0.000000000000000000e+00,-8.567578360126980377e-11,0.000000000000000000e+00 +4.082213059520899634e+01,2.817099999999999795e+02,0.000000000000000000e+00,7.433133279891533718e+00,0.000000000000000000e+00,-1.000000009962075831e+00,0.000000000000000000e+00,1.231263408296508834e-10,0.000000000000000000e+00 +4.082347592289564631e+01,2.817200000000000273e+02,0.000000000000000000e+00,7.431787952191481139e+00,0.000000000000000000e+00,-1.000000009961910186e+00,0.000000000000000000e+00,2.011579683652046056e-10,0.000000000000000000e+00 +4.082482149411811889e+01,2.817300000000000182e+02,0.000000000000000000e+00,7.430442380955602388e+00,0.000000000000000000e+00,-1.000000009961639513e+00,0.000000000000000000e+00,-2.580427401491682974e-10,0.000000000000000000e+00 +4.082616730900871715e+01,2.817400000000000091e+02,0.000000000000000000e+00,7.429096566051600625e+00,0.000000000000000000e+00,-1.000000009961986791e+00,0.000000000000000000e+00,-1.892080661316783067e-10,0.000000000000000000e+00 +4.082751336769985073e+01,2.817500000000000000e+02,0.000000000000000000e+00,7.427750507347058218e+00,0.000000000000000000e+00,-1.000000009962241476e+00,0.000000000000000000e+00,4.904994190557709661e-10,0.000000000000000000e+00 +4.082885967032405716e+01,2.817599999999999909e+02,0.000000000000000000e+00,7.426404204709438517e+00,0.000000000000000000e+00,-1.000000009961581116e+00,0.000000000000000000e+00,-9.481709678977716533e-11,0.000000000000000000e+00 +4.083020621701399477e+01,2.817699999999999818e+02,0.000000000000000000e+00,7.425057658006085859e+00,0.000000000000000000e+00,-1.000000009961708791e+00,0.000000000000000000e+00,-3.899161296324480961e-10,0.000000000000000000e+00 +4.083155300790244269e+01,2.817800000000000296e+02,0.000000000000000000e+00,7.423710867104222011e+00,0.000000000000000000e+00,-1.000000009962233927e+00,0.000000000000000000e+00,1.778618147342360080e-10,0.000000000000000000e+00 +4.083290004312229371e+01,2.817900000000000205e+02,0.000000000000000000e+00,7.422363831870948836e+00,0.000000000000000000e+00,-1.000000009961994341e+00,0.000000000000000000e+00,2.244706540423687120e-10,0.000000000000000000e+00 +4.083424732280656855e+01,2.818000000000000114e+02,0.000000000000000000e+00,7.421016552173249181e+00,0.000000000000000000e+00,-1.000000009961691916e+00,0.000000000000000000e+00,-6.541752853223625165e-10,0.000000000000000000e+00 +4.083559484708840870e+01,2.818100000000000023e+02,0.000000000000000000e+00,7.419669027877984213e+00,0.000000000000000000e+00,-1.000000009962573433e+00,0.000000000000000000e+00,5.611376409964655241e-10,0.000000000000000000e+00 +4.083694261610107645e+01,2.818199999999999932e+02,0.000000000000000000e+00,7.418321258851892530e+00,0.000000000000000000e+00,-1.000000009961817149e+00,0.000000000000000000e+00,4.282715354134696273e-11,0.000000000000000000e+00 +4.083829062997794779e+01,2.818299999999999841e+02,0.000000000000000000e+00,7.416973244961595491e+00,0.000000000000000000e+00,-1.000000009961759417e+00,0.000000000000000000e+00,-1.679836871795365407e-10,0.000000000000000000e+00 +4.083963888885251947e+01,2.818400000000000318e+02,0.000000000000000000e+00,7.415624986073590108e+00,0.000000000000000000e+00,-1.000000009961985903e+00,0.000000000000000000e+00,-4.752086215599944037e-10,0.000000000000000000e+00 +4.084098739285842328e+01,2.818500000000000227e+02,0.000000000000000000e+00,7.414276482054252604e+00,0.000000000000000000e+00,-1.000000009962626724e+00,0.000000000000000000e+00,6.711965476154976717e-10,0.000000000000000000e+00 +4.084233614212940466e+01,2.818600000000000136e+02,0.000000000000000000e+00,7.412927732769837519e+00,0.000000000000000000e+00,-1.000000009961721448e+00,0.000000000000000000e+00,-6.205422298797788282e-11,0.000000000000000000e+00 +4.084368513679932278e+01,2.818700000000000045e+02,0.000000000000000000e+00,7.411578738086480378e+00,0.000000000000000000e+00,-1.000000009961805159e+00,0.000000000000000000e+00,-6.354051841961782818e-10,0.000000000000000000e+00 +4.084503437700217177e+01,2.818799999999999955e+02,0.000000000000000000e+00,7.410229497870191473e+00,0.000000000000000000e+00,-1.000000009962662473e+00,0.000000000000000000e+00,4.987211889694208832e-10,0.000000000000000000e+00 +4.084638386287205947e+01,2.818899999999999864e+02,0.000000000000000000e+00,7.408880011986859415e+00,0.000000000000000000e+00,-1.000000009961989456e+00,0.000000000000000000e+00,1.200924339694965858e-11,0.000000000000000000e+00 +4.084773359454322161e+01,2.819000000000000341e+02,0.000000000000000000e+00,7.407530280302253800e+00,0.000000000000000000e+00,-1.000000009961973246e+00,0.000000000000000000e+00,-5.937735705761312848e-11,0.000000000000000000e+00 +4.084908357215000763e+01,2.819100000000000250e+02,0.000000000000000000e+00,7.406180302682018990e+00,0.000000000000000000e+00,-1.000000009962053404e+00,0.000000000000000000e+00,-1.172530196449867933e-10,0.000000000000000000e+00 +4.085043379582689482e+01,2.819200000000000159e+02,0.000000000000000000e+00,7.404830078991677667e+00,0.000000000000000000e+00,-1.000000009962211722e+00,0.000000000000000000e+00,-7.530447767974265469e-11,0.000000000000000000e+00 +4.085178426570848842e+01,2.819300000000000068e+02,0.000000000000000000e+00,7.403479609096629943e+00,0.000000000000000000e+00,-1.000000009962313419e+00,0.000000000000000000e+00,1.517322196597212552e-10,0.000000000000000000e+00 +4.085313498192950732e+01,2.819399999999999977e+02,0.000000000000000000e+00,7.402128892862153364e+00,0.000000000000000000e+00,-1.000000009962108471e+00,0.000000000000000000e+00,1.630453963334778382e-10,0.000000000000000000e+00 +4.085448594462479832e+01,2.819499999999999886e+02,0.000000000000000000e+00,7.400777930153402906e+00,0.000000000000000000e+00,-1.000000009961888203e+00,0.000000000000000000e+00,-4.412268049250186835e-10,0.000000000000000000e+00 +4.085583715392932902e+01,2.819599999999999795e+02,0.000000000000000000e+00,7.399426720835410087e+00,0.000000000000000000e+00,-1.000000009962484393e+00,0.000000000000000000e+00,3.713186289353138239e-10,0.000000000000000000e+00 +4.085718860997819490e+01,2.819700000000000273e+02,0.000000000000000000e+00,7.398075264773082083e+00,0.000000000000000000e+00,-1.000000009961982572e+00,0.000000000000000000e+00,-2.319496211513525635e-10,0.000000000000000000e+00 +4.085854031290660515e+01,2.819800000000000182e+02,0.000000000000000000e+00,7.396723561831205274e+00,0.000000000000000000e+00,-1.000000009962296099e+00,0.000000000000000000e+00,2.672188966790083359e-10,0.000000000000000000e+00 +4.085989226284990394e+01,2.819900000000000091e+02,0.000000000000000000e+00,7.395371611874439921e+00,0.000000000000000000e+00,-1.000000009961934833e+00,0.000000000000000000e+00,-4.745675843035785906e-10,0.000000000000000000e+00 +4.086124445994354915e+01,2.820000000000000000e+02,0.000000000000000000e+00,7.394019414767324605e+00,0.000000000000000000e+00,-1.000000009962576542e+00,0.000000000000000000e+00,5.437648620645191768e-10,0.000000000000000000e+00 +4.086259690432312652e+01,2.820099999999999909e+02,0.000000000000000000e+00,7.392666970374271784e+00,0.000000000000000000e+00,-1.000000009961841130e+00,0.000000000000000000e+00,-4.753789261392225406e-10,0.000000000000000000e+00 +4.086394959612434974e+01,2.820199999999999818e+02,0.000000000000000000e+00,7.391314278559573125e+00,0.000000000000000000e+00,-1.000000009962484171e+00,0.000000000000000000e+00,4.385290298072592714e-10,0.000000000000000000e+00 +4.086530253548305325e+01,2.820300000000000296e+02,0.000000000000000000e+00,7.389961339187392397e+00,0.000000000000000000e+00,-1.000000009961890868e+00,0.000000000000000000e+00,-5.101561351924211039e-10,0.000000000000000000e+00 +4.086665572253519230e+01,2.820400000000000205e+02,0.000000000000000000e+00,7.388608152121772576e+00,0.000000000000000000e+00,-1.000000009962581204e+00,0.000000000000000000e+00,1.620913371146739569e-10,0.000000000000000000e+00 +4.086800915741685003e+01,2.820500000000000114e+02,0.000000000000000000e+00,7.387254717226628742e+00,0.000000000000000000e+00,-1.000000009962361824e+00,0.000000000000000000e+00,1.171174239389352697e-10,0.000000000000000000e+00 +4.086936284026423749e+01,2.820600000000000023e+02,0.000000000000000000e+00,7.385901034365754292e+00,0.000000000000000000e+00,-1.000000009962203285e+00,0.000000000000000000e+00,-7.199597704869035283e-11,0.000000000000000000e+00 +4.087071677121368651e+01,2.820699999999999932e+02,0.000000000000000000e+00,7.384547103402816504e+00,0.000000000000000000e+00,-1.000000009962300762e+00,0.000000000000000000e+00,1.662654627943117789e-10,0.000000000000000000e+00 +4.087207095040165683e+01,2.820799999999999841e+02,0.000000000000000000e+00,7.383192924201357421e+00,0.000000000000000000e+00,-1.000000009962075609e+00,0.000000000000000000e+00,-5.331322803115504654e-10,0.000000000000000000e+00 +4.087342537796472897e+01,2.820900000000000318e+02,0.000000000000000000e+00,7.381838496624794743e+00,0.000000000000000000e+00,-1.000000009962797698e+00,0.000000000000000000e+00,3.383097059613498995e-10,0.000000000000000000e+00 +4.087478005403961134e+01,2.821000000000000227e+02,0.000000000000000000e+00,7.380483820536419159e+00,0.000000000000000000e+00,-1.000000009962339398e+00,0.000000000000000000e+00,4.473914756456403667e-10,0.000000000000000000e+00 +4.087613497876313318e+01,2.821100000000000136e+02,0.000000000000000000e+00,7.379128895799398791e+00,0.000000000000000000e+00,-1.000000009961733216e+00,0.000000000000000000e+00,-6.001809970193771866e-10,0.000000000000000000e+00 +4.087749015227225868e+01,2.821200000000000045e+02,0.000000000000000000e+00,7.377773722276774748e+00,0.000000000000000000e+00,-1.000000009962546565e+00,0.000000000000000000e+00,1.854436571772601711e-10,0.000000000000000000e+00 +4.087884557470407287e+01,2.821299999999999955e+02,0.000000000000000000e+00,7.376418299831460246e+00,0.000000000000000000e+00,-1.000000009962295211e+00,0.000000000000000000e+00,-9.663573934172301712e-12,0.000000000000000000e+00 +4.088020124619578155e+01,2.821399999999999864e+02,0.000000000000000000e+00,7.375062628326245928e+00,0.000000000000000000e+00,-1.000000009962308312e+00,0.000000000000000000e+00,-1.293698365407210878e-10,0.000000000000000000e+00 +4.088155716688472552e+01,2.821500000000000341e+02,0.000000000000000000e+00,7.373706707623794543e+00,0.000000000000000000e+00,-1.000000009962483727e+00,0.000000000000000000e+00,-8.579408993891464159e-11,0.000000000000000000e+00 +4.088291333690836638e+01,2.821600000000000250e+02,0.000000000000000000e+00,7.372350537586642716e+00,0.000000000000000000e+00,-1.000000009962600078e+00,0.000000000000000000e+00,2.096985038646190709e-10,0.000000000000000000e+00 +4.088426975640429362e+01,2.821700000000000159e+02,0.000000000000000000e+00,7.370994118077200952e+00,0.000000000000000000e+00,-1.000000009962315639e+00,0.000000000000000000e+00,-1.198056697056528899e-10,0.000000000000000000e+00 +4.088562642551022464e+01,2.821800000000000068e+02,0.000000000000000000e+00,7.369637448957753634e+00,0.000000000000000000e+00,-1.000000009962478176e+00,0.000000000000000000e+00,-2.045485294743174911e-11,0.000000000000000000e+00 +4.088698334436400472e+01,2.821899999999999977e+02,0.000000000000000000e+00,7.368280530090457248e+00,0.000000000000000000e+00,-1.000000009962505931e+00,0.000000000000000000e+00,1.143624770557234306e-10,0.000000000000000000e+00 +4.088834051310359996e+01,2.821999999999999886e+02,0.000000000000000000e+00,7.366923361337342158e+00,0.000000000000000000e+00,-1.000000009962350722e+00,0.000000000000000000e+00,-1.084525844367391785e-10,0.000000000000000000e+00 +4.088969793186710433e+01,2.822099999999999795e+02,0.000000000000000000e+00,7.365565942560311719e+00,0.000000000000000000e+00,-1.000000009962497938e+00,0.000000000000000000e+00,-1.177548609430850515e-10,0.000000000000000000e+00 +4.089105560079274682e+01,2.822200000000000273e+02,0.000000000000000000e+00,7.364208273621141387e+00,0.000000000000000000e+00,-1.000000009962657810e+00,0.000000000000000000e+00,1.752915872304386518e-10,0.000000000000000000e+00 +4.089241352001887719e+01,2.822300000000000182e+02,0.000000000000000000e+00,7.362850354381479612e+00,0.000000000000000000e+00,-1.000000009962419778e+00,0.000000000000000000e+00,-1.029975154778280281e-10,0.000000000000000000e+00 +4.089377168968398024e+01,2.822400000000000091e+02,0.000000000000000000e+00,7.361492184702847830e+00,0.000000000000000000e+00,-1.000000009962559666e+00,0.000000000000000000e+00,9.954589909009291843e-11,0.000000000000000000e+00 +4.089513010992665443e+01,2.822500000000000000e+02,0.000000000000000000e+00,7.360133764446638693e+00,0.000000000000000000e+00,-1.000000009962424441e+00,0.000000000000000000e+00,-8.972186186631436872e-11,0.000000000000000000e+00 +4.089648878088564032e+01,2.822599999999999909e+02,0.000000000000000000e+00,7.358775093474117845e+00,0.000000000000000000e+00,-1.000000009962546343e+00,0.000000000000000000e+00,3.805530822176543825e-10,0.000000000000000000e+00 +4.089784770269979930e+01,2.822699999999999818e+02,0.000000000000000000e+00,7.357416171646422143e+00,0.000000000000000000e+00,-1.000000009962029202e+00,0.000000000000000000e+00,-8.036045195576047519e-10,0.000000000000000000e+00 +4.089920687550812062e+01,2.822800000000000296e+02,0.000000000000000000e+00,7.356056998824561433e+00,0.000000000000000000e+00,-1.000000009963121439e+00,0.000000000000000000e+00,7.737286812011122489e-10,0.000000000000000000e+00 +4.090056629944972144e+01,2.822900000000000205e+02,0.000000000000000000e+00,7.354697574869414112e+00,0.000000000000000000e+00,-1.000000009962069614e+00,0.000000000000000000e+00,-5.645526161296113335e-10,0.000000000000000000e+00 +4.090192597466385394e+01,2.823000000000000114e+02,0.000000000000000000e+00,7.353337899641735120e+00,0.000000000000000000e+00,-1.000000009962837222e+00,0.000000000000000000e+00,7.674014341389179737e-11,0.000000000000000000e+00 +4.090328590128989816e+01,2.823100000000000023e+02,0.000000000000000000e+00,7.351977973002145283e+00,0.000000000000000000e+00,-1.000000009962732861e+00,0.000000000000000000e+00,3.855887158950259385e-10,0.000000000000000000e+00 +4.090464607946735498e+01,2.823199999999999932e+02,0.000000000000000000e+00,7.350617794811140193e+00,0.000000000000000000e+00,-1.000000009962208392e+00,0.000000000000000000e+00,-5.069504565176830211e-10,0.000000000000000000e+00 +4.090600650933585314e+01,2.823299999999999841e+02,0.000000000000000000e+00,7.349257364929085767e+00,0.000000000000000000e+00,-1.000000009962898062e+00,0.000000000000000000e+00,3.686378399730917370e-10,0.000000000000000000e+00 +4.090736719103516350e+01,2.823400000000000318e+02,0.000000000000000000e+00,7.347896683216216474e+00,0.000000000000000000e+00,-1.000000009962396463e+00,0.000000000000000000e+00,-2.550129555493484936e-10,0.000000000000000000e+00 +4.090872812470517772e+01,2.823500000000000227e+02,0.000000000000000000e+00,7.346535749532640658e+00,0.000000000000000000e+00,-1.000000009962743519e+00,0.000000000000000000e+00,1.104362091205146038e-10,0.000000000000000000e+00 +4.091008931048592245e+01,2.823600000000000136e+02,0.000000000000000000e+00,7.345174563738334328e+00,0.000000000000000000e+00,-1.000000009962593195e+00,0.000000000000000000e+00,1.179181465712012688e-10,0.000000000000000000e+00 +4.091145074851754515e+01,2.823700000000000045e+02,0.000000000000000000e+00,7.343813125693145594e+00,0.000000000000000000e+00,-1.000000009962432657e+00,0.000000000000000000e+00,-1.418669053199880609e-10,0.000000000000000000e+00 +4.091281243894033537e+01,2.823799999999999955e+02,0.000000000000000000e+00,7.342451435256792003e+00,0.000000000000000000e+00,-1.000000009962625835e+00,0.000000000000000000e+00,-9.831020920580625107e-11,0.000000000000000000e+00 +4.091417438189469635e+01,2.823899999999999864e+02,0.000000000000000000e+00,7.341089492288860541e+00,0.000000000000000000e+00,-1.000000009962759728e+00,0.000000000000000000e+00,-1.392062115893530228e-10,0.000000000000000000e+00 +4.091553657752118056e+01,2.824000000000000341e+02,0.000000000000000000e+00,7.339727296648808519e+00,0.000000000000000000e+00,-1.000000009962949354e+00,0.000000000000000000e+00,3.049256352312106244e-10,0.000000000000000000e+00 +4.091689902596045414e+01,2.824100000000000250e+02,0.000000000000000000e+00,7.338364848195962686e+00,0.000000000000000000e+00,-1.000000009962533909e+00,0.000000000000000000e+00,-1.098245474048038222e-10,0.000000000000000000e+00 +4.091826172735331824e+01,2.824200000000000159e+02,0.000000000000000000e+00,7.337002146789520118e+00,0.000000000000000000e+00,-1.000000009962683567e+00,0.000000000000000000e+00,1.435273875598845306e-10,0.000000000000000000e+00 +4.091962468184071611e+01,2.824300000000000068e+02,0.000000000000000000e+00,7.335639192288545551e+00,0.000000000000000000e+00,-1.000000009962487946e+00,0.000000000000000000e+00,-2.778799515389231667e-10,0.000000000000000000e+00 +4.092098788956370470e+01,2.824399999999999977e+02,0.000000000000000000e+00,7.334275984551974048e+00,0.000000000000000000e+00,-1.000000009962866754e+00,0.000000000000000000e+00,1.516167400876319996e-10,0.000000000000000000e+00 +4.092235135066348306e+01,2.824499999999999886e+02,0.000000000000000000e+00,7.332912523438608332e+00,0.000000000000000000e+00,-1.000000009962660030e+00,0.000000000000000000e+00,9.036696836402908342e-11,0.000000000000000000e+00 +4.092371506528138525e+01,2.824599999999999795e+02,0.000000000000000000e+00,7.331548808807121453e+00,0.000000000000000000e+00,-1.000000009962536796e+00,0.000000000000000000e+00,-3.695403049340165903e-10,0.000000000000000000e+00 +4.092507903355886612e+01,2.824700000000000273e+02,0.000000000000000000e+00,7.330184840516054123e+00,0.000000000000000000e+00,-1.000000009963040837e+00,0.000000000000000000e+00,2.967165838421329708e-10,0.000000000000000000e+00 +4.092644325563751551e+01,2.824800000000000182e+02,0.000000000000000000e+00,7.328820618423814715e+00,0.000000000000000000e+00,-1.000000009962636049e+00,0.000000000000000000e+00,-2.053684249425836355e-10,0.000000000000000000e+00 +4.092780773165905117e+01,2.824900000000000091e+02,0.000000000000000000e+00,7.327456142388681926e+00,0.000000000000000000e+00,-1.000000009962916270e+00,0.000000000000000000e+00,1.249552976058000874e-10,0.000000000000000000e+00 +4.092917246176533297e+01,2.825000000000000000e+02,0.000000000000000000e+00,7.326091412268800340e+00,0.000000000000000000e+00,-1.000000009962745740e+00,0.000000000000000000e+00,-4.977760364242584918e-11,0.000000000000000000e+00 +4.093053744609834865e+01,2.825099999999999909e+02,0.000000000000000000e+00,7.324726427922183980e+00,0.000000000000000000e+00,-1.000000009962813685e+00,0.000000000000000000e+00,-1.611778241999069781e-10,0.000000000000000000e+00 +4.093190268480021388e+01,2.825199999999999818e+02,0.000000000000000000e+00,7.323361189206713640e+00,0.000000000000000000e+00,-1.000000009963033731e+00,0.000000000000000000e+00,3.609970509197181192e-10,0.000000000000000000e+00 +4.093326817801318640e+01,2.825300000000000296e+02,0.000000000000000000e+00,7.321995695980137775e+00,0.000000000000000000e+00,-1.000000009962540792e+00,0.000000000000000000e+00,-2.970354215160611327e-10,0.000000000000000000e+00 +4.093463392587964478e+01,2.825400000000000205e+02,0.000000000000000000e+00,7.320629948100073392e+00,0.000000000000000000e+00,-1.000000009962946468e+00,0.000000000000000000e+00,3.400559356642263928e-10,0.000000000000000000e+00 +4.093599992854210967e+01,2.825500000000000114e+02,0.000000000000000000e+00,7.319263945424002493e+00,0.000000000000000000e+00,-1.000000009962481951e+00,0.000000000000000000e+00,-4.916239290088688148e-10,0.000000000000000000e+00 +4.093736618614322254e+01,2.825600000000000023e+02,0.000000000000000000e+00,7.317897687809276519e+00,0.000000000000000000e+00,-1.000000009963153635e+00,0.000000000000000000e+00,1.569653111138382918e-10,0.000000000000000000e+00 +4.093873269882577404e+01,2.825699999999999932e+02,0.000000000000000000e+00,7.316531175113111019e+00,0.000000000000000000e+00,-1.000000009962939140e+00,0.000000000000000000e+00,-1.624596274199665684e-13,0.000000000000000000e+00 +4.094009946673267564e+01,2.825799999999999841e+02,0.000000000000000000e+00,7.315164407192590978e+00,0.000000000000000000e+00,-1.000000009962939362e+00,0.000000000000000000e+00,8.235164449136619375e-11,0.000000000000000000e+00 +4.094146649000698091e+01,2.825900000000000318e+02,0.000000000000000000e+00,7.313797383904666383e+00,0.000000000000000000e+00,-1.000000009962826786e+00,0.000000000000000000e+00,2.224865273336849667e-11,0.000000000000000000e+00 +4.094283376879187131e+01,2.826000000000000227e+02,0.000000000000000000e+00,7.312430105106153988e+00,0.000000000000000000e+00,-1.000000009962796366e+00,0.000000000000000000e+00,-8.605533964770065856e-11,0.000000000000000000e+00 +4.094420130323066331e+01,2.826100000000000136e+02,0.000000000000000000e+00,7.311062570653736437e+00,0.000000000000000000e+00,-1.000000009962914049e+00,0.000000000000000000e+00,-1.493511440076353371e-10,0.000000000000000000e+00 +4.094556909346680840e+01,2.826200000000000045e+02,0.000000000000000000e+00,7.309694780403962255e+00,0.000000000000000000e+00,-1.000000009963118330e+00,0.000000000000000000e+00,4.012249531983557344e-10,0.000000000000000000e+00 +4.094693713964389303e+01,2.826299999999999955e+02,0.000000000000000000e+00,7.308326734213245857e+00,0.000000000000000000e+00,-1.000000009962569436e+00,0.000000000000000000e+00,-2.383855773348932374e-10,0.000000000000000000e+00 +4.094830544190563870e+01,2.826399999999999864e+02,0.000000000000000000e+00,7.306958431937868426e+00,0.000000000000000000e+00,-1.000000009962895620e+00,0.000000000000000000e+00,-7.609387574667136913e-11,0.000000000000000000e+00 +4.094967400039589478e+01,2.826500000000000341e+02,0.000000000000000000e+00,7.305589873433974368e+00,0.000000000000000000e+00,-1.000000009962999759e+00,0.000000000000000000e+00,3.374106979757189050e-11,0.000000000000000000e+00 +4.095104281525865986e+01,2.826600000000000250e+02,0.000000000000000000e+00,7.304221058557574864e+00,0.000000000000000000e+00,-1.000000009962953573e+00,0.000000000000000000e+00,1.848923682325061926e-10,0.000000000000000000e+00 +4.095241188663804621e+01,2.826700000000000159e+02,0.000000000000000000e+00,7.302851987164546088e+00,0.000000000000000000e+00,-1.000000009962700442e+00,0.000000000000000000e+00,-4.743059736624099149e-10,0.000000000000000000e+00 +4.095378121467832244e+01,2.826800000000000068e+02,0.000000000000000000e+00,7.301482659110629214e+00,0.000000000000000000e+00,-1.000000009963349923e+00,0.000000000000000000e+00,5.183151699212169567e-10,0.000000000000000000e+00 +4.095515079952387794e+01,2.826899999999999977e+02,0.000000000000000000e+00,7.300113074251428635e+00,0.000000000000000000e+00,-1.000000009962640046e+00,0.000000000000000000e+00,-5.305371717950740747e-10,0.000000000000000000e+00 +4.095652064131924419e+01,2.826999999999999886e+02,0.000000000000000000e+00,7.298743232442416407e+00,0.000000000000000000e+00,-1.000000009963366798e+00,0.000000000000000000e+00,2.614102897242535312e-10,0.000000000000000000e+00 +4.095789074020908771e+01,2.827099999999999795e+02,0.000000000000000000e+00,7.297373133538925138e+00,0.000000000000000000e+00,-1.000000009963008640e+00,0.000000000000000000e+00,1.497196317010721990e-10,0.000000000000000000e+00 +4.095926109633820289e+01,2.827200000000000273e+02,0.000000000000000000e+00,7.296002777396155103e+00,0.000000000000000000e+00,-1.000000009962803471e+00,0.000000000000000000e+00,-2.974389867582547334e-10,0.000000000000000000e+00 +4.096063170985153334e+01,2.827300000000000182e+02,0.000000000000000000e+00,7.294632163869168906e+00,0.000000000000000000e+00,-1.000000009963211145e+00,0.000000000000000000e+00,-3.806374234714426160e-11,0.000000000000000000e+00 +4.096200258089415058e+01,2.827400000000000091e+02,0.000000000000000000e+00,7.293261292812892371e+00,0.000000000000000000e+00,-1.000000009963263325e+00,0.000000000000000000e+00,5.488245973537895510e-10,0.000000000000000000e+00 +4.096337370961126823e+01,2.827500000000000000e+02,0.000000000000000000e+00,7.291890164082116321e+00,0.000000000000000000e+00,-1.000000009962510816e+00,0.000000000000000000e+00,-8.014668109669659478e-10,0.000000000000000000e+00 +4.096474509614822779e+01,2.827599999999999909e+02,0.000000000000000000e+00,7.290518777531495687e+00,0.000000000000000000e+00,-1.000000009963609937e+00,0.000000000000000000e+00,7.284691627449763729e-10,0.000000000000000000e+00 +4.096611674065051290e+01,2.827699999999999818e+02,0.000000000000000000e+00,7.289147133015545066e+00,0.000000000000000000e+00,-1.000000009962610736e+00,0.000000000000000000e+00,-4.308489047330473081e-10,0.000000000000000000e+00 +4.096748864326374218e+01,2.827800000000000296e+02,0.000000000000000000e+00,7.287775230388647607e+00,0.000000000000000000e+00,-1.000000009963201819e+00,0.000000000000000000e+00,6.472844687256304991e-11,0.000000000000000000e+00 +4.096886080413367637e+01,2.827900000000000205e+02,0.000000000000000000e+00,7.286403069505044350e+00,0.000000000000000000e+00,-1.000000009963113001e+00,0.000000000000000000e+00,-4.837540407769421366e-11,0.000000000000000000e+00 +4.097023322340620410e+01,2.828000000000000114e+02,0.000000000000000000e+00,7.285030650218842219e+00,0.000000000000000000e+00,-1.000000009963179393e+00,0.000000000000000000e+00,2.699777325080365387e-10,0.000000000000000000e+00 +4.097160590122736323e+01,2.828100000000000023e+02,0.000000000000000000e+00,7.283657972384009582e+00,0.000000000000000000e+00,-1.000000009962808800e+00,0.000000000000000000e+00,-2.988764776327290700e-10,0.000000000000000000e+00 +4.097297883774331950e+01,2.828199999999999932e+02,0.000000000000000000e+00,7.282285035854378030e+00,0.000000000000000000e+00,-1.000000009963219139e+00,0.000000000000000000e+00,-2.435190108229055751e-10,0.000000000000000000e+00 +4.097435203310037366e+01,2.828299999999999841e+02,0.000000000000000000e+00,7.280911840483639708e+00,0.000000000000000000e+00,-1.000000009963553538e+00,0.000000000000000000e+00,5.314050803766283935e-10,0.000000000000000000e+00 +4.097572548744497567e+01,2.828400000000000318e+02,0.000000000000000000e+00,7.279538386125349980e+00,0.000000000000000000e+00,-1.000000009962823677e+00,0.000000000000000000e+00,-2.316275728401790320e-10,0.000000000000000000e+00 +4.097709920092371050e+01,2.828500000000000227e+02,0.000000000000000000e+00,7.278164672632927434e+00,0.000000000000000000e+00,-1.000000009963141867e+00,0.000000000000000000e+00,-8.096546768563632877e-11,0.000000000000000000e+00 +4.097847317368329811e+01,2.828600000000000136e+02,0.000000000000000000e+00,7.276790699859649436e+00,0.000000000000000000e+00,-1.000000009963253111e+00,0.000000000000000000e+00,1.379869387125896115e-10,0.000000000000000000e+00 +4.097984740587060060e+01,2.828700000000000045e+02,0.000000000000000000e+00,7.275416467658656572e+00,0.000000000000000000e+00,-1.000000009963063485e+00,0.000000000000000000e+00,-4.175982130960071380e-10,0.000000000000000000e+00 +4.098122189763261503e+01,2.828799999999999955e+02,0.000000000000000000e+00,7.274041975882950872e+00,0.000000000000000000e+00,-1.000000009963637471e+00,0.000000000000000000e+00,6.996880816850779757e-10,0.000000000000000000e+00 +4.098259664911647349e+01,2.828899999999999864e+02,0.000000000000000000e+00,7.272667224385394036e+00,0.000000000000000000e+00,-1.000000009962675573e+00,0.000000000000000000e+00,-6.420669525865357656e-10,0.000000000000000000e+00 +4.098397166046945728e+01,2.829000000000000341e+02,0.000000000000000000e+00,7.271292213018711870e+00,0.000000000000000000e+00,-1.000000009963558423e+00,0.000000000000000000e+00,3.527794386714218772e-10,0.000000000000000000e+00 +4.098534693183898270e+01,2.829100000000000250e+02,0.000000000000000000e+00,7.269916941635486296e+00,0.000000000000000000e+00,-1.000000009963073255e+00,0.000000000000000000e+00,2.437511211066297518e-11,0.000000000000000000e+00 +4.098672246337260106e+01,2.829200000000000159e+02,0.000000000000000000e+00,7.268541410088164234e+00,0.000000000000000000e+00,-1.000000009963039727e+00,0.000000000000000000e+00,-5.900566123547241126e-10,0.000000000000000000e+00 +4.098809825521800576e+01,2.829300000000000068e+02,0.000000000000000000e+00,7.267165618229050494e+00,0.000000000000000000e+00,-1.000000009963851522e+00,0.000000000000000000e+00,4.844132025710570196e-10,0.000000000000000000e+00 +4.098947430752303944e+01,2.829399999999999977e+02,0.000000000000000000e+00,7.265789565910309555e+00,0.000000000000000000e+00,-1.000000009963184944e+00,0.000000000000000000e+00,6.098385032325063365e-11,0.000000000000000000e+00 +4.099085062043566552e+01,2.829499999999999886e+02,0.000000000000000000e+00,7.264413252983969116e+00,0.000000000000000000e+00,-1.000000009963101011e+00,0.000000000000000000e+00,1.150085948559713720e-10,0.000000000000000000e+00 +4.099222719410400373e+01,2.829599999999999795e+02,0.000000000000000000e+00,7.263036679301913878e+00,0.000000000000000000e+00,-1.000000009962942693e+00,0.000000000000000000e+00,-6.616982405377614046e-10,0.000000000000000000e+00 +4.099360402867630881e+01,2.829700000000000273e+02,0.000000000000000000e+00,7.261659844715889101e+00,0.000000000000000000e+00,-1.000000009963853742e+00,0.000000000000000000e+00,6.401277193540017389e-10,0.000000000000000000e+00 +4.099498112430097763e+01,2.829800000000000182e+02,0.000000000000000000e+00,7.260282749077497932e+00,0.000000000000000000e+00,-1.000000009962972225e+00,0.000000000000000000e+00,-9.672639687977598588e-11,0.000000000000000000e+00 +4.099635848112654912e+01,2.829900000000000091e+02,0.000000000000000000e+00,7.258905392238206744e+00,0.000000000000000000e+00,-1.000000009963105452e+00,0.000000000000000000e+00,-4.313178887300637526e-10,0.000000000000000000e+00 +4.099773609930169016e+01,2.830000000000000000e+02,0.000000000000000000e+00,7.257527774049337133e+00,0.000000000000000000e+00,-1.000000009963699643e+00,0.000000000000000000e+00,2.025649073362782243e-10,0.000000000000000000e+00 +4.099911397897523102e+01,2.830099999999999909e+02,0.000000000000000000e+00,7.256149894362070363e+00,0.000000000000000000e+00,-1.000000009963420533e+00,0.000000000000000000e+00,3.190154094409458347e-11,0.000000000000000000e+00 +4.100049212029612278e+01,2.830199999999999818e+02,0.000000000000000000e+00,7.254771753027448256e+00,0.000000000000000000e+00,-1.000000009963376568e+00,0.000000000000000000e+00,9.149815029462416856e-11,0.000000000000000000e+00 +4.100187052341346572e+01,2.830300000000000296e+02,0.000000000000000000e+00,7.253393349896369635e+00,0.000000000000000000e+00,-1.000000009963250447e+00,0.000000000000000000e+00,1.368990331632050527e-11,0.000000000000000000e+00 +4.100324918847650935e+01,2.830400000000000205e+02,0.000000000000000000e+00,7.252014684819592105e+00,0.000000000000000000e+00,-1.000000009963231573e+00,0.000000000000000000e+00,-1.030573270784826693e-10,0.000000000000000000e+00 +4.100462811563463106e+01,2.830500000000000114e+02,0.000000000000000000e+00,7.250635757647731161e+00,0.000000000000000000e+00,-1.000000009963373682e+00,0.000000000000000000e+00,-1.584205119426000428e-10,0.000000000000000000e+00 +4.100600730503735747e+01,2.830600000000000023e+02,0.000000000000000000e+00,7.249256568231260189e+00,0.000000000000000000e+00,-1.000000009963592174e+00,0.000000000000000000e+00,4.133602541859876438e-10,0.000000000000000000e+00 +4.100738675683436441e+01,2.830699999999999932e+02,0.000000000000000000e+00,7.247877116420510468e+00,0.000000000000000000e+00,-1.000000009963021963e+00,0.000000000000000000e+00,-6.215317465944283100e-10,0.000000000000000000e+00 +4.100876647117545559e+01,2.830799999999999841e+02,0.000000000000000000e+00,7.246497402065672055e+00,0.000000000000000000e+00,-1.000000009963879499e+00,0.000000000000000000e+00,5.697630656323792785e-10,0.000000000000000000e+00 +4.101014644821059107e+01,2.830900000000000318e+02,0.000000000000000000e+00,7.245117425016789348e+00,0.000000000000000000e+00,-1.000000009963093239e+00,0.000000000000000000e+00,-1.113247551501132558e-10,0.000000000000000000e+00 +4.101152668808985879e+01,2.831000000000000227e+02,0.000000000000000000e+00,7.243737185123768185e+00,0.000000000000000000e+00,-1.000000009963246894e+00,0.000000000000000000e+00,-2.320968474774609030e-10,0.000000000000000000e+00 +4.101290719096350301e+01,2.831100000000000136e+02,0.000000000000000000e+00,7.242356682236367860e+00,0.000000000000000000e+00,-1.000000009963567305e+00,0.000000000000000000e+00,-1.592044965951001388e-10,0.000000000000000000e+00 +4.101428795698191010e+01,2.831200000000000045e+02,0.000000000000000000e+00,7.240975916204205554e+00,0.000000000000000000e+00,-1.000000009963787129e+00,0.000000000000000000e+00,2.077302970468116499e-10,0.000000000000000000e+00 +4.101566898629560143e+01,2.831299999999999955e+02,0.000000000000000000e+00,7.239594886876755453e+00,0.000000000000000000e+00,-1.000000009963500247e+00,0.000000000000000000e+00,3.777655518213490815e-11,0.000000000000000000e+00 +4.101705027905524759e+01,2.831399999999999864e+02,0.000000000000000000e+00,7.238213594103348747e+00,0.000000000000000000e+00,-1.000000009963448067e+00,0.000000000000000000e+00,3.625857362864949414e-10,0.000000000000000000e+00 +4.101843183541166127e+01,2.831500000000000341e+02,0.000000000000000000e+00,7.236832037733171852e+00,0.000000000000000000e+00,-1.000000009962947134e+00,0.000000000000000000e+00,-5.776803741064540978e-10,0.000000000000000000e+00 +4.101981365551579728e+01,2.831600000000000250e+02,0.000000000000000000e+00,7.235450217615268187e+00,0.000000000000000000e+00,-1.000000009963745384e+00,0.000000000000000000e+00,1.087663247762002052e-10,0.000000000000000000e+00 +4.102119573951875964e+01,2.831700000000000159e+02,0.000000000000000000e+00,7.234068133598534622e+00,0.000000000000000000e+00,-1.000000009963595060e+00,0.000000000000000000e+00,1.970912677490366557e-10,0.000000000000000000e+00 +4.102257808757179447e+01,2.831800000000000068e+02,0.000000000000000000e+00,7.232685785531726808e+00,0.000000000000000000e+00,-1.000000009963322611e+00,0.000000000000000000e+00,-2.107044261427410160e-10,0.000000000000000000e+00 +4.102396069982629001e+01,2.831899999999999977e+02,0.000000000000000000e+00,7.231303173263454731e+00,0.000000000000000000e+00,-1.000000009963613934e+00,0.000000000000000000e+00,-8.365550370804131763e-11,0.000000000000000000e+00 +4.102534357643378371e+01,2.831999999999999886e+02,0.000000000000000000e+00,7.229920296642182720e+00,0.000000000000000000e+00,-1.000000009963729619e+00,0.000000000000000000e+00,2.141556637740442854e-10,0.000000000000000000e+00 +4.102672671754595513e+01,2.832099999999999795e+02,0.000000000000000000e+00,7.228537155516231216e+00,0.000000000000000000e+00,-1.000000009963433412e+00,0.000000000000000000e+00,-1.436526620809847445e-10,0.000000000000000000e+00 +4.102811012331462592e+01,2.832200000000000273e+02,0.000000000000000000e+00,7.227153749733775889e+00,0.000000000000000000e+00,-1.000000009963632142e+00,0.000000000000000000e+00,3.374790299590675649e-10,0.000000000000000000e+00 +4.102949379389176698e+01,2.832300000000000182e+02,0.000000000000000000e+00,7.225770079142845859e+00,0.000000000000000000e+00,-1.000000009963165182e+00,0.000000000000000000e+00,-5.609133645708339625e-10,0.000000000000000000e+00 +4.103087772942949840e+01,2.832400000000000091e+02,0.000000000000000000e+00,7.224386143591326359e+00,0.000000000000000000e+00,-1.000000009963941450e+00,0.000000000000000000e+00,5.101152375313149115e-10,0.000000000000000000e+00 +4.103226193008007527e+01,2.832500000000000000e+02,0.000000000000000000e+00,7.223001942926954300e+00,0.000000000000000000e+00,-1.000000009963235348e+00,0.000000000000000000e+00,-5.204423848503384073e-10,0.000000000000000000e+00 +4.103364639599590902e+01,2.832599999999999909e+02,0.000000000000000000e+00,7.221617476997324481e+00,0.000000000000000000e+00,-1.000000009963955883e+00,0.000000000000000000e+00,1.584278945204377447e-10,0.000000000000000000e+00 +4.103503112732955316e+01,2.832699999999999818e+02,0.000000000000000000e+00,7.220232745649881601e+00,0.000000000000000000e+00,-1.000000009963736503e+00,0.000000000000000000e+00,3.312239560962527559e-10,0.000000000000000000e+00 +4.103641612423371043e+01,2.832800000000000296e+02,0.000000000000000000e+00,7.218847748731927361e+00,0.000000000000000000e+00,-1.000000009963277758e+00,0.000000000000000000e+00,-3.614553472839453524e-10,0.000000000000000000e+00 +4.103780138686121859e+01,2.832900000000000205e+02,0.000000000000000000e+00,7.217462486090616025e+00,0.000000000000000000e+00,-1.000000009963778469e+00,0.000000000000000000e+00,3.509690947764642931e-11,0.000000000000000000e+00 +4.103918691536507879e+01,2.833000000000000114e+02,0.000000000000000000e+00,7.216076957572953532e+00,0.000000000000000000e+00,-1.000000009963729841e+00,0.000000000000000000e+00,2.344151670314704598e-10,0.000000000000000000e+00 +4.104057270989842010e+01,2.833100000000000023e+02,0.000000000000000000e+00,7.214691163025801046e+00,0.000000000000000000e+00,-1.000000009963404990e+00,0.000000000000000000e+00,-1.223915202197936521e-10,0.000000000000000000e+00 +4.104195877061454212e+01,2.833199999999999932e+02,0.000000000000000000e+00,7.213305102295872295e+00,0.000000000000000000e+00,-1.000000009963574632e+00,0.000000000000000000e+00,-4.694510836695631594e-10,0.000000000000000000e+00 +4.104334509766687233e+01,2.833299999999999841e+02,0.000000000000000000e+00,7.211918775229732681e+00,0.000000000000000000e+00,-1.000000009964225445e+00,0.000000000000000000e+00,6.823427578795702012e-10,0.000000000000000000e+00 +4.104473169120898746e+01,2.833400000000000318e+02,0.000000000000000000e+00,7.210532181673800167e+00,0.000000000000000000e+00,-1.000000009963279313e+00,0.000000000000000000e+00,-2.598520006026689606e-10,0.000000000000000000e+00 +4.104611855139462051e+01,2.833500000000000227e+02,0.000000000000000000e+00,7.209145321474347945e+00,0.000000000000000000e+00,-1.000000009963639691e+00,0.000000000000000000e+00,4.145947226112625347e-11,0.000000000000000000e+00 +4.104750567837765374e+01,2.833600000000000136e+02,0.000000000000000000e+00,7.207758194477497327e+00,0.000000000000000000e+00,-1.000000009963582182e+00,0.000000000000000000e+00,-1.574836719556906055e-10,0.000000000000000000e+00 +4.104889307231210438e+01,2.833700000000000045e+02,0.000000000000000000e+00,7.206370800529223963e+00,0.000000000000000000e+00,-1.000000009963800673e+00,0.000000000000000000e+00,-2.909046806856469712e-10,0.000000000000000000e+00 +4.105028073335214600e+01,2.833799999999999955e+02,0.000000000000000000e+00,7.204983139475354292e+00,0.000000000000000000e+00,-1.000000009964204351e+00,0.000000000000000000e+00,6.672881064318337318e-10,0.000000000000000000e+00 +4.105166866165210138e+01,2.833899999999999864e+02,0.000000000000000000e+00,7.203595211161566425e+00,0.000000000000000000e+00,-1.000000009963278202e+00,0.000000000000000000e+00,-4.070777007127143206e-10,0.000000000000000000e+00 +4.105305685736644250e+01,2.834000000000000341e+02,0.000000000000000000e+00,7.202207015433391923e+00,0.000000000000000000e+00,-1.000000009963843306e+00,0.000000000000000000e+00,-1.813505513648442562e-10,0.000000000000000000e+00 +4.105444532064979057e+01,2.834100000000000250e+02,0.000000000000000000e+00,7.200818552136209583e+00,0.000000000000000000e+00,-1.000000009964095105e+00,0.000000000000000000e+00,5.255593866964440834e-10,0.000000000000000000e+00 +4.105583405165690891e+01,2.834200000000000159e+02,0.000000000000000000e+00,7.199429821115251649e+00,0.000000000000000000e+00,-1.000000009963365244e+00,0.000000000000000000e+00,-4.842142892904210080e-10,0.000000000000000000e+00 +4.105722305054271715e+01,2.834300000000000068e+02,0.000000000000000000e+00,7.198040822215602041e+00,0.000000000000000000e+00,-1.000000009964037817e+00,0.000000000000000000e+00,1.173142019862683259e-10,0.000000000000000000e+00 +4.105861231746228412e+01,2.834399999999999977e+02,0.000000000000000000e+00,7.196651555282191914e+00,0.000000000000000000e+00,-1.000000009963874836e+00,0.000000000000000000e+00,1.332713361247372511e-10,0.000000000000000000e+00 +4.106000185257082791e+01,2.834499999999999886e+02,0.000000000000000000e+00,7.195262020159805871e+00,0.000000000000000000e+00,-1.000000009963689651e+00,0.000000000000000000e+00,1.287721304754364165e-10,0.000000000000000000e+00 +4.106139165602370866e+01,2.834599999999999795e+02,0.000000000000000000e+00,7.193872216693077526e+00,0.000000000000000000e+00,-1.000000009963510683e+00,0.000000000000000000e+00,-2.509453367865971082e-10,0.000000000000000000e+00 +4.106278172797644288e+01,2.834700000000000273e+02,0.000000000000000000e+00,7.192482144726490390e+00,0.000000000000000000e+00,-1.000000009963859515e+00,0.000000000000000000e+00,1.932432746069923837e-11,0.000000000000000000e+00 +4.106417206858470337e+01,2.834800000000000182e+02,0.000000000000000000e+00,7.191091804104376983e+00,0.000000000000000000e+00,-1.000000009963832648e+00,0.000000000000000000e+00,-3.340386645997197172e-10,0.000000000000000000e+00 +4.106556267800430504e+01,2.834900000000000091e+02,0.000000000000000000e+00,7.189701194670920614e+00,0.000000000000000000e+00,-1.000000009964297165e+00,0.000000000000000000e+00,6.312301464579133007e-10,0.000000000000000000e+00 +4.106695355639121203e+01,2.835000000000000000e+02,0.000000000000000000e+00,7.188310316270152711e+00,0.000000000000000000e+00,-1.000000009963419201e+00,0.000000000000000000e+00,-6.518576641056328841e-10,0.000000000000000000e+00 +4.106834470390154479e+01,2.835099999999999909e+02,0.000000000000000000e+00,7.186919168745956377e+00,0.000000000000000000e+00,-1.000000009964326031e+00,0.000000000000000000e+00,5.128954640631788916e-10,0.000000000000000000e+00 +4.106973612069158008e+01,2.835199999999999818e+02,0.000000000000000000e+00,7.185527751942059282e+00,0.000000000000000000e+00,-1.000000009963612380e+00,0.000000000000000000e+00,-3.578723705734097033e-10,0.000000000000000000e+00 +4.107112780691772969e+01,2.835300000000000296e+02,0.000000000000000000e+00,7.184136065702042551e+00,0.000000000000000000e+00,-1.000000009964110426e+00,0.000000000000000000e+00,5.120587680741096960e-10,0.000000000000000000e+00 +4.107251976273656879e+01,2.835400000000000205e+02,0.000000000000000000e+00,7.182744109869331872e+00,0.000000000000000000e+00,-1.000000009963397662e+00,0.000000000000000000e+00,-4.397110566969285802e-10,0.000000000000000000e+00 +4.107391198830482182e+01,2.835500000000000114e+02,0.000000000000000000e+00,7.181351884287204612e+00,0.000000000000000000e+00,-1.000000009964009839e+00,0.000000000000000000e+00,1.028504385073347172e-10,0.000000000000000000e+00 +4.107530448377936949e+01,2.835600000000000023e+02,0.000000000000000000e+00,7.179959388798782705e+00,0.000000000000000000e+00,-1.000000009963866621e+00,0.000000000000000000e+00,-4.623386613004425053e-11,0.000000000000000000e+00 +4.107669724931723465e+01,2.835699999999999932e+02,0.000000000000000000e+00,7.178566623247038869e+00,0.000000000000000000e+00,-1.000000009963931014e+00,0.000000000000000000e+00,-3.207051523451252549e-10,0.000000000000000000e+00 +4.107809028507560356e+01,2.835799999999999841e+02,0.000000000000000000e+00,7.177173587474792171e+00,0.000000000000000000e+00,-1.000000009964377767e+00,0.000000000000000000e+00,3.005628942615569627e-10,0.000000000000000000e+00 +4.107948359121180459e+01,2.835900000000000318e+02,0.000000000000000000e+00,7.175780281324708909e+00,0.000000000000000000e+00,-1.000000009963958991e+00,0.000000000000000000e+00,9.448525754741760576e-11,0.000000000000000000e+00 +4.108087716788332244e+01,2.836000000000000227e+02,0.000000000000000000e+00,7.174386704639304391e+00,0.000000000000000000e+00,-1.000000009963827319e+00,0.000000000000000000e+00,8.315636756565584592e-11,0.000000000000000000e+00 +4.108227101524779812e+01,2.836100000000000136e+02,0.000000000000000000e+00,7.172992857260939381e+00,0.000000000000000000e+00,-1.000000009963711411e+00,0.000000000000000000e+00,-8.314021185929409905e-11,0.000000000000000000e+00 +4.108366513346302185e+01,2.836200000000000045e+02,0.000000000000000000e+00,7.171598739031821879e+00,0.000000000000000000e+00,-1.000000009963827319e+00,0.000000000000000000e+00,-2.966668788587930668e-10,0.000000000000000000e+00 +4.108505952268694728e+01,2.836299999999999955e+02,0.000000000000000000e+00,7.170204349794006227e+00,0.000000000000000000e+00,-1.000000009964240988e+00,0.000000000000000000e+00,6.209210249118829795e-12,0.000000000000000000e+00 +4.108645418307766306e+01,2.836399999999999864e+02,0.000000000000000000e+00,7.168809689389393114e+00,0.000000000000000000e+00,-1.000000009964232328e+00,0.000000000000000000e+00,4.762652181667506863e-10,0.000000000000000000e+00 +4.108784911479342838e+01,2.836500000000000341e+02,0.000000000000000000e+00,7.167414757659730462e+00,0.000000000000000000e+00,-1.000000009963567971e+00,0.000000000000000000e+00,-6.039688528262904297e-10,0.000000000000000000e+00 +4.108924431799264454e+01,2.836600000000000250e+02,0.000000000000000000e+00,7.166019554446612538e+00,0.000000000000000000e+00,-1.000000009964410630e+00,0.000000000000000000e+00,5.242924856907824195e-10,0.000000000000000000e+00 +4.109063979283387624e+01,2.836700000000000159e+02,0.000000000000000000e+00,7.164624079591476402e+00,0.000000000000000000e+00,-1.000000009963678993e+00,0.000000000000000000e+00,-5.930748907249543939e-10,0.000000000000000000e+00 +4.109203553947583742e+01,2.836800000000000068e+02,0.000000000000000000e+00,7.163228332935609011e+00,0.000000000000000000e+00,-1.000000009964506775e+00,0.000000000000000000e+00,7.125691799181661104e-10,0.000000000000000000e+00 +4.109343155807739834e+01,2.836899999999999977e+02,0.000000000000000000e+00,7.161832314320138337e+00,0.000000000000000000e+00,-1.000000009963512015e+00,0.000000000000000000e+00,-4.648289720856127670e-10,0.000000000000000000e+00 +4.109482784879758555e+01,2.836999999999999886e+02,0.000000000000000000e+00,7.160436023586042253e+00,0.000000000000000000e+00,-1.000000009964161052e+00,0.000000000000000000e+00,8.506158605522468378e-11,0.000000000000000000e+00 +4.109622441179557484e+01,2.837099999999999795e+02,0.000000000000000000e+00,7.159039460574138758e+00,0.000000000000000000e+00,-1.000000009964042258e+00,0.000000000000000000e+00,-2.626062298476056658e-10,0.000000000000000000e+00 +4.109762124723069832e+01,2.837200000000000273e+02,0.000000000000000000e+00,7.157642625125093971e+00,0.000000000000000000e+00,-1.000000009964409076e+00,0.000000000000000000e+00,4.225991054919747814e-10,0.000000000000000000e+00 +4.109901835526245151e+01,2.837300000000000182e+02,0.000000000000000000e+00,7.156245517079416807e+00,0.000000000000000000e+00,-1.000000009963818659e+00,0.000000000000000000e+00,-4.816276302725454754e-10,0.000000000000000000e+00 +4.110041573605047915e+01,2.837400000000000091e+02,0.000000000000000000e+00,7.154848136277462523e+00,0.000000000000000000e+00,-1.000000009964491676e+00,0.000000000000000000e+00,3.194866505141553240e-10,0.000000000000000000e+00 +4.110181338975458942e+01,2.837500000000000000e+02,0.000000000000000000e+00,7.153450482559427392e+00,0.000000000000000000e+00,-1.000000009964045145e+00,0.000000000000000000e+00,2.055370301608383424e-10,0.000000000000000000e+00 +4.110321131653473259e+01,2.837599999999999909e+02,0.000000000000000000e+00,7.152052555765354924e+00,0.000000000000000000e+00,-1.000000009963757819e+00,0.000000000000000000e+00,-2.583797511108761251e-10,0.000000000000000000e+00 +4.110460951655102235e+01,2.837699999999999818e+02,0.000000000000000000e+00,7.150654355735130530e+00,0.000000000000000000e+00,-1.000000009964119085e+00,0.000000000000000000e+00,-5.398398352673848361e-11,0.000000000000000000e+00 +4.110600798996373584e+01,2.837800000000000296e+02,0.000000000000000000e+00,7.149255882308482413e+00,0.000000000000000000e+00,-1.000000009964194581e+00,0.000000000000000000e+00,1.984317122368928754e-11,0.000000000000000000e+00 +4.110740673693329938e+01,2.837900000000000205e+02,0.000000000000000000e+00,7.147857135324983346e+00,0.000000000000000000e+00,-1.000000009964166825e+00,0.000000000000000000e+00,7.253244029489275147e-11,0.000000000000000000e+00 +4.110880575762029565e+01,2.838000000000000114e+02,0.000000000000000000e+00,7.146458114624048896e+00,0.000000000000000000e+00,-1.000000009964065351e+00,0.000000000000000000e+00,-2.386596032887171467e-10,0.000000000000000000e+00 +4.111020505218546361e+01,2.838100000000000023e+02,0.000000000000000000e+00,7.145058820044937420e+00,0.000000000000000000e+00,-1.000000009964399306e+00,0.000000000000000000e+00,1.032825667623805491e-10,0.000000000000000000e+00 +4.111160462078970568e+01,2.838199999999999932e+02,0.000000000000000000e+00,7.143659251426749179e+00,0.000000000000000000e+00,-1.000000009964254755e+00,0.000000000000000000e+00,3.012214681787782507e-10,0.000000000000000000e+00 +4.111300446359408056e+01,2.838299999999999841e+02,0.000000000000000000e+00,7.142259408608428117e+00,0.000000000000000000e+00,-1.000000009963833092e+00,0.000000000000000000e+00,-4.399287067853259092e-10,0.000000000000000000e+00 +4.111440458075979620e+01,2.838400000000000318e+02,0.000000000000000000e+00,7.140859291428760081e+00,0.000000000000000000e+00,-1.000000009964449044e+00,0.000000000000000000e+00,2.559141098227528296e-10,0.000000000000000000e+00 +4.111580497244823107e+01,2.838500000000000227e+02,0.000000000000000000e+00,7.139458899726371044e+00,0.000000000000000000e+00,-1.000000009964090664e+00,0.000000000000000000e+00,-2.184513539798635534e-10,0.000000000000000000e+00 +4.111720563882091284e+01,2.838600000000000136e+02,0.000000000000000000e+00,7.138058233339731551e+00,0.000000000000000000e+00,-1.000000009964396641e+00,0.000000000000000000e+00,5.927777778123165098e-11,0.000000000000000000e+00 +4.111860658003953262e+01,2.838700000000000045e+02,0.000000000000000000e+00,7.136657292107151385e+00,0.000000000000000000e+00,-1.000000009964313596e+00,0.000000000000000000e+00,2.945875966726062462e-10,0.000000000000000000e+00 +4.112000779626593783e+01,2.838799999999999955e+02,0.000000000000000000e+00,7.135256075866783121e+00,0.000000000000000000e+00,-1.000000009963900816e+00,0.000000000000000000e+00,-3.051448694195585488e-10,0.000000000000000000e+00 +4.112140928766213932e+01,2.838899999999999864e+02,0.000000000000000000e+00,7.133854584456620351e+00,0.000000000000000000e+00,-1.000000009964328473e+00,0.000000000000000000e+00,-2.721370279367468622e-10,0.000000000000000000e+00 +4.112281105439029716e+01,2.839000000000000341e+02,0.000000000000000000e+00,7.132452817714495907e+00,0.000000000000000000e+00,-1.000000009964709946e+00,0.000000000000000000e+00,5.047324143093967065e-10,0.000000000000000000e+00 +4.112421309661273483e+01,2.839100000000000250e+02,0.000000000000000000e+00,7.131050775478084525e+00,0.000000000000000000e+00,-1.000000009964002290e+00,0.000000000000000000e+00,-1.222393563853137049e-10,0.000000000000000000e+00 +4.112561541449194635e+01,2.839200000000000159e+02,0.000000000000000000e+00,7.129648457584902843e+00,0.000000000000000000e+00,-1.000000009964173708e+00,0.000000000000000000e+00,-2.331906263202690150e-10,0.000000000000000000e+00 +4.112701800819056785e+01,2.839300000000000068e+02,0.000000000000000000e+00,7.128245863872304966e+00,0.000000000000000000e+00,-1.000000009964500780e+00,0.000000000000000000e+00,2.830025903533802052e-10,0.000000000000000000e+00 +4.112842087787140599e+01,2.839399999999999977e+02,0.000000000000000000e+00,7.126842994177486013e+00,0.000000000000000000e+00,-1.000000009964103764e+00,0.000000000000000000e+00,-2.668056284390205949e-10,0.000000000000000000e+00 +4.112982402369743085e+01,2.839499999999999886e+02,0.000000000000000000e+00,7.125439848337482118e+00,0.000000000000000000e+00,-1.000000009964478132e+00,0.000000000000000000e+00,3.480764047290576890e-11,0.000000000000000000e+00 +4.113122744583176171e+01,2.839599999999999795e+02,0.000000000000000000e+00,7.124036426189166882e+00,0.000000000000000000e+00,-1.000000009964429282e+00,0.000000000000000000e+00,-5.283391871440516010e-11,0.000000000000000000e+00 +4.113263114443768842e+01,2.839700000000000273e+02,0.000000000000000000e+00,7.122632727569254918e+00,0.000000000000000000e+00,-1.000000009964503445e+00,0.000000000000000000e+00,4.841100582428811825e-10,0.000000000000000000e+00 +4.113403511967865711e+01,2.839800000000000182e+02,0.000000000000000000e+00,7.121228752314299193e+00,0.000000000000000000e+00,-1.000000009963823766e+00,0.000000000000000000e+00,-4.939763847351368813e-10,0.000000000000000000e+00 +4.113543937171827025e+01,2.839900000000000091e+02,0.000000000000000000e+00,7.119824500260692801e+00,0.000000000000000000e+00,-1.000000009964517433e+00,0.000000000000000000e+00,-1.707392107759619697e-10,0.000000000000000000e+00 +4.113684390072030084e+01,2.840000000000000000e+02,0.000000000000000000e+00,7.118419971244664524e+00,0.000000000000000000e+00,-1.000000009964757242e+00,0.000000000000000000e+00,6.644870777863814122e-10,0.000000000000000000e+00 +4.113824870684868529e+01,2.840099999999999909e+02,0.000000000000000000e+00,7.117015165102284158e+00,0.000000000000000000e+00,-1.000000009963823766e+00,0.000000000000000000e+00,-5.744371672810455816e-10,0.000000000000000000e+00 +4.113965379026750924e+01,2.840199999999999818e+02,0.000000000000000000e+00,7.115610081669460740e+00,0.000000000000000000e+00,-1.000000009964630898e+00,0.000000000000000000e+00,2.758650020105974728e-10,0.000000000000000000e+00 +4.114105915114102885e+01,2.840300000000000296e+02,0.000000000000000000e+00,7.114204720781937219e+00,0.000000000000000000e+00,-1.000000009964243208e+00,0.000000000000000000e+00,-2.704396369508072225e-10,0.000000000000000000e+00 +4.114246478963366371e+01,2.840400000000000205e+02,0.000000000000000000e+00,7.112799082275298446e+00,0.000000000000000000e+00,-1.000000009964623349e+00,0.000000000000000000e+00,1.497232011703926733e-10,0.000000000000000000e+00 +4.114387070590998974e+01,2.840500000000000114e+02,0.000000000000000000e+00,7.111393165984964071e+00,0.000000000000000000e+00,-1.000000009964412850e+00,0.000000000000000000e+00,-1.482724650361229420e-10,0.000000000000000000e+00 +4.114527690013474626e+01,2.840600000000000023e+02,0.000000000000000000e+00,7.109986971746192985e+00,0.000000000000000000e+00,-1.000000009964621350e+00,0.000000000000000000e+00,2.974335323540039606e-10,0.000000000000000000e+00 +4.114668337247284313e+01,2.840699999999999932e+02,0.000000000000000000e+00,7.108580499394079766e+00,0.000000000000000000e+00,-1.000000009964203018e+00,0.000000000000000000e+00,-1.949351106478689058e-10,0.000000000000000000e+00 +4.114809012308934655e+01,2.840799999999999841e+02,0.000000000000000000e+00,7.107173748763557342e+00,0.000000000000000000e+00,-1.000000009964477243e+00,0.000000000000000000e+00,-1.636499641903334869e-10,0.000000000000000000e+00 +4.114949715214949322e+01,2.840900000000000318e+02,0.000000000000000000e+00,7.105766719689393440e+00,0.000000000000000000e+00,-1.000000009964707504e+00,0.000000000000000000e+00,5.044217533189285571e-10,0.000000000000000000e+00 +4.115090445981866907e+01,2.841000000000000227e+02,0.000000000000000000e+00,7.104359412006193253e+00,0.000000000000000000e+00,-1.000000009963997627e+00,0.000000000000000000e+00,-3.177054143273066665e-10,0.000000000000000000e+00 +4.115231204626243766e+01,2.841100000000000136e+02,0.000000000000000000e+00,7.102951825548399434e+00,0.000000000000000000e+00,-1.000000009964444825e+00,0.000000000000000000e+00,-2.728507788196383959e-10,0.000000000000000000e+00 +4.115371991164651888e+01,2.841200000000000045e+02,0.000000000000000000e+00,7.101543960150287660e+00,0.000000000000000000e+00,-1.000000009964828962e+00,0.000000000000000000e+00,3.046492598415352413e-10,0.000000000000000000e+00 +4.115512805613680314e+01,2.841299999999999955e+02,0.000000000000000000e+00,7.100135815645971071e+00,0.000000000000000000e+00,-1.000000009964399972e+00,0.000000000000000000e+00,-2.613914680780431555e-10,0.000000000000000000e+00 +4.115653647989934427e+01,2.841399999999999864e+02,0.000000000000000000e+00,7.098727391869399383e+00,0.000000000000000000e+00,-1.000000009964768122e+00,0.000000000000000000e+00,3.833401377889873179e-10,0.000000000000000000e+00 +4.115794518310035244e+01,2.841500000000000341e+02,0.000000000000000000e+00,7.097318688654355334e+00,0.000000000000000000e+00,-1.000000009964228109e+00,0.000000000000000000e+00,-3.314162544896272817e-10,0.000000000000000000e+00 +4.115935416590620832e+01,2.841600000000000250e+02,0.000000000000000000e+00,7.095909705834459125e+00,0.000000000000000000e+00,-1.000000009964695069e+00,0.000000000000000000e+00,3.950050427309778873e-10,0.000000000000000000e+00 +4.116076342848346314e+01,2.841700000000000159e+02,0.000000000000000000e+00,7.094500443243163090e+00,0.000000000000000000e+00,-1.000000009964138403e+00,0.000000000000000000e+00,-4.528974700673614609e-10,0.000000000000000000e+00 +4.116217297099882444e+01,2.841800000000000068e+02,0.000000000000000000e+00,7.093090900713757030e+00,0.000000000000000000e+00,-1.000000009964776782e+00,0.000000000000000000e+00,3.712233909821078100e-10,0.000000000000000000e+00 +4.116358279361917027e+01,2.841899999999999977e+02,0.000000000000000000e+00,7.091681078079361988e+00,0.000000000000000000e+00,-1.000000009964253422e+00,0.000000000000000000e+00,-5.923906746415532412e-10,0.000000000000000000e+00 +4.116499289651154214e+01,2.841999999999999886e+02,0.000000000000000000e+00,7.090270975172936474e+00,0.000000000000000000e+00,-1.000000009965088754e+00,0.000000000000000000e+00,3.468307187738601305e-10,0.000000000000000000e+00 +4.116640327984315206e+01,2.842099999999999795e+02,0.000000000000000000e+00,7.088860591827269353e+00,0.000000000000000000e+00,-1.000000009964599590e+00,0.000000000000000000e+00,1.784965044911351562e-10,0.000000000000000000e+00 +4.116781394378137549e+01,2.842200000000000273e+02,0.000000000000000000e+00,7.087449927874986955e+00,0.000000000000000000e+00,-1.000000009964347791e+00,0.000000000000000000e+00,-8.686989705768405225e-11,0.000000000000000000e+00 +4.116922488849375839e+01,2.842300000000000182e+02,0.000000000000000000e+00,7.086038983148546855e+00,0.000000000000000000e+00,-1.000000009964470360e+00,0.000000000000000000e+00,-3.321482709634300625e-10,0.000000000000000000e+00 +4.117063611414800306e+01,2.842400000000000091e+02,0.000000000000000000e+00,7.084627757480239651e+00,0.000000000000000000e+00,-1.000000009964939096e+00,0.000000000000000000e+00,4.505368055834548046e-10,0.000000000000000000e+00 +4.117204762091198944e+01,2.842500000000000000e+02,0.000000000000000000e+00,7.083216250702188965e+00,0.000000000000000000e+00,-1.000000009964303160e+00,0.000000000000000000e+00,-2.964709063263099347e-10,0.000000000000000000e+00 +4.117345940895376089e+01,2.842599999999999909e+02,0.000000000000000000e+00,7.081804462646353215e+00,0.000000000000000000e+00,-1.000000009964721714e+00,0.000000000000000000e+00,2.190459728372034149e-10,0.000000000000000000e+00 +4.117487147844152418e+01,2.842699999999999818e+02,0.000000000000000000e+00,7.080392393144520291e+00,0.000000000000000000e+00,-1.000000009964412406e+00,0.000000000000000000e+00,-5.593755710810600236e-10,0.000000000000000000e+00 +4.117628382954365662e+01,2.842800000000000296e+02,0.000000000000000000e+00,7.078980042028312880e+00,0.000000000000000000e+00,-1.000000009965202441e+00,0.000000000000000000e+00,6.037473263871440271e-10,0.000000000000000000e+00 +4.117769646242870607e+01,2.842900000000000205e+02,0.000000000000000000e+00,7.077567409129183140e+00,0.000000000000000000e+00,-1.000000009964349568e+00,0.000000000000000000e+00,-1.811980615046492857e-10,0.000000000000000000e+00 +4.117910937726539089e+01,2.843000000000000114e+02,0.000000000000000000e+00,7.076154494278418916e+00,0.000000000000000000e+00,-1.000000009964605585e+00,0.000000000000000000e+00,-1.247550211682005656e-10,0.000000000000000000e+00 +4.118052257422259288e+01,2.843100000000000023e+02,0.000000000000000000e+00,7.074741297307135746e+00,0.000000000000000000e+00,-1.000000009964781889e+00,0.000000000000000000e+00,4.712724408922098983e-13,0.000000000000000000e+00 +4.118193605346936437e+01,2.843199999999999932e+02,0.000000000000000000e+00,7.073327818046282189e+00,0.000000000000000000e+00,-1.000000009964781222e+00,0.000000000000000000e+00,3.128623807479734645e-10,0.000000000000000000e+00 +4.118334981517492110e+01,2.843299999999999841e+02,0.000000000000000000e+00,7.071914056326638054e+00,0.000000000000000000e+00,-1.000000009964338910e+00,0.000000000000000000e+00,-4.018347448151408390e-10,0.000000000000000000e+00 +4.118476385950865648e+01,2.843400000000000318e+02,0.000000000000000000e+00,7.070500011978814392e+00,0.000000000000000000e+00,-1.000000009964907122e+00,0.000000000000000000e+00,1.957748078082484410e-10,0.000000000000000000e+00 +4.118617818664012731e+01,2.843500000000000227e+02,0.000000000000000000e+00,7.069085684833250838e+00,0.000000000000000000e+00,-1.000000009964630232e+00,0.000000000000000000e+00,4.081096078981982648e-12,0.000000000000000000e+00 +4.118759279673906093e+01,2.843600000000000136e+02,0.000000000000000000e+00,7.067671074720220048e+00,0.000000000000000000e+00,-1.000000009964624459e+00,0.000000000000000000e+00,-4.135206240071860109e-10,0.000000000000000000e+00 +4.118900768997536233e+01,2.843700000000000045e+02,0.000000000000000000e+00,7.066256181469823261e+00,0.000000000000000000e+00,-1.000000009965209546e+00,0.000000000000000000e+00,3.927267227470158560e-10,0.000000000000000000e+00 +4.119042286651909279e+01,2.843799999999999955e+02,0.000000000000000000e+00,7.064841004911991185e+00,0.000000000000000000e+00,-1.000000009964653769e+00,0.000000000000000000e+00,-1.195356890302909091e-10,0.000000000000000000e+00 +4.119183832654049127e+01,2.843899999999999864e+02,0.000000000000000000e+00,7.063425544876486661e+00,0.000000000000000000e+00,-1.000000009964822967e+00,0.000000000000000000e+00,3.869231783684211324e-10,0.000000000000000000e+00 +4.119325407020997432e+01,2.844000000000000341e+02,0.000000000000000000e+00,7.062009801192899339e+00,0.000000000000000000e+00,-1.000000009964275183e+00,0.000000000000000000e+00,-6.277028948659152492e-10,0.000000000000000000e+00 +4.119467009769811483e+01,2.844100000000000250e+02,0.000000000000000000e+00,7.060593773690650110e+00,0.000000000000000000e+00,-1.000000009965164027e+00,0.000000000000000000e+00,5.002743715253746069e-10,0.000000000000000000e+00 +4.119608640917566333e+01,2.844200000000000159e+02,0.000000000000000000e+00,7.059177462198985786e+00,0.000000000000000000e+00,-1.000000009964455483e+00,0.000000000000000000e+00,-5.373226383924150479e-10,0.000000000000000000e+00 +4.119750300481354799e+01,2.844300000000000068e+02,0.000000000000000000e+00,7.057760866546986200e+00,0.000000000000000000e+00,-1.000000009965216652e+00,0.000000000000000000e+00,3.634192380257963608e-10,0.000000000000000000e+00 +4.119891988478286038e+01,2.844399999999999977e+02,0.000000000000000000e+00,7.056343986563555326e+00,0.000000000000000000e+00,-1.000000009964701730e+00,0.000000000000000000e+00,-2.170050011105600674e-10,0.000000000000000000e+00 +4.120033704925486262e+01,2.844499999999999886e+02,0.000000000000000000e+00,7.054926822077429271e+00,0.000000000000000000e+00,-1.000000009965009262e+00,0.000000000000000000e+00,4.951733175625861395e-10,0.000000000000000000e+00 +4.120175449840099446e+01,2.844599999999999795e+02,0.000000000000000000e+00,7.053509372917169173e+00,0.000000000000000000e+00,-1.000000009964307379e+00,0.000000000000000000e+00,-4.734603561280215135e-10,0.000000000000000000e+00 +4.120317223239287330e+01,2.844700000000000273e+02,0.000000000000000000e+00,7.052091638911166527e+00,0.000000000000000000e+00,-1.000000009964978620e+00,0.000000000000000000e+00,9.191709153901449919e-11,0.000000000000000000e+00 +4.120459025140227283e+01,2.844800000000000182e+02,0.000000000000000000e+00,7.050673619887636967e+00,0.000000000000000000e+00,-1.000000009964848280e+00,0.000000000000000000e+00,1.017616624949138920e-10,0.000000000000000000e+00 +4.120600855560115150e+01,2.844900000000000091e+02,0.000000000000000000e+00,7.049255315674626488e+00,0.000000000000000000e+00,-1.000000009964703951e+00,0.000000000000000000e+00,-3.210325927860115997e-10,0.000000000000000000e+00 +4.120742714516163829e+01,2.845000000000000000e+02,0.000000000000000000e+00,7.047836726100006999e+00,0.000000000000000000e+00,-1.000000009965159364e+00,0.000000000000000000e+00,2.680732149997602592e-10,0.000000000000000000e+00 +4.120884602025603272e+01,2.845099999999999909e+02,0.000000000000000000e+00,7.046417850991476328e+00,0.000000000000000000e+00,-1.000000009964779002e+00,0.000000000000000000e+00,-2.154480456443344761e-10,0.000000000000000000e+00 +4.121026518105680481e+01,2.845199999999999818e+02,0.000000000000000000e+00,7.044998690176560885e+00,0.000000000000000000e+00,-1.000000009965084757e+00,0.000000000000000000e+00,1.143506188076918295e-10,0.000000000000000000e+00 +4.121168462773660934e+01,2.845300000000000296e+02,0.000000000000000000e+00,7.043579243482611218e+00,0.000000000000000000e+00,-1.000000009964922443e+00,0.000000000000000000e+00,5.677279236469408104e-11,0.000000000000000000e+00 +4.121310436046826453e+01,2.845400000000000205e+02,0.000000000000000000e+00,7.042159510736805572e+00,0.000000000000000000e+00,-1.000000009964841841e+00,0.000000000000000000e+00,1.743495981914375222e-10,0.000000000000000000e+00 +4.121452437942477331e+01,2.845500000000000114e+02,0.000000000000000000e+00,7.040739491766147218e+00,0.000000000000000000e+00,-1.000000009964594261e+00,0.000000000000000000e+00,-2.914099719897777424e-10,0.000000000000000000e+00 +4.121594468477930207e+01,2.845600000000000023e+02,0.000000000000000000e+00,7.039319186397465344e+00,0.000000000000000000e+00,-1.000000009965008152e+00,0.000000000000000000e+00,1.025356108081240526e-10,0.000000000000000000e+00 +4.121736527670519479e+01,2.845699999999999932e+02,0.000000000000000000e+00,7.037898594457413282e+00,0.000000000000000000e+00,-1.000000009964862491e+00,0.000000000000000000e+00,-2.816034798061530487e-10,0.000000000000000000e+00 +4.121878615537598023e+01,2.845799999999999841e+02,0.000000000000000000e+00,7.036477715772471164e+00,0.000000000000000000e+00,-1.000000009965262615e+00,0.000000000000000000e+00,4.381003008152808019e-10,0.000000000000000000e+00 +4.122020732096534346e+01,2.845900000000000318e+02,0.000000000000000000e+00,7.035056550168942380e+00,0.000000000000000000e+00,-1.000000009964640002e+00,0.000000000000000000e+00,-2.536844476147406608e-10,0.000000000000000000e+00 +4.122162877364716138e+01,2.846000000000000227e+02,0.000000000000000000e+00,7.033635097472957121e+00,0.000000000000000000e+00,-1.000000009965000602e+00,0.000000000000000000e+00,-3.592095670731998313e-11,0.000000000000000000e+00 +4.122305051359548145e+01,2.846100000000000136e+02,0.000000000000000000e+00,7.032213357510467056e+00,0.000000000000000000e+00,-1.000000009965051673e+00,0.000000000000000000e+00,-1.035251319343331017e-10,0.000000000000000000e+00 +4.122447254098452873e+01,2.846200000000000045e+02,0.000000000000000000e+00,7.030791330107249770e+00,0.000000000000000000e+00,-1.000000009965198888e+00,0.000000000000000000e+00,1.055336915445903839e-10,0.000000000000000000e+00 +4.122589485598869885e+01,2.846299999999999955e+02,0.000000000000000000e+00,7.029369015088906103e+00,0.000000000000000000e+00,-1.000000009965048786e+00,0.000000000000000000e+00,2.759553567583324869e-10,0.000000000000000000e+00 +4.122731745878256504e+01,2.846399999999999864e+02,0.000000000000000000e+00,7.027946412280861033e+00,0.000000000000000000e+00,-1.000000009964656211e+00,0.000000000000000000e+00,-3.461228002530114434e-10,0.000000000000000000e+00 +4.122874034954088529e+01,2.846500000000000341e+02,0.000000000000000000e+00,7.026523521508362791e+00,0.000000000000000000e+00,-1.000000009965148706e+00,0.000000000000000000e+00,1.185753245890620759e-10,0.000000000000000000e+00 +4.123016352843858812e+01,2.846600000000000250e+02,0.000000000000000000e+00,7.025100342596481084e+00,0.000000000000000000e+00,-1.000000009964979952e+00,0.000000000000000000e+00,3.899714075326344724e-11,0.000000000000000000e+00 +4.123158699565077256e+01,2.846700000000000159e+02,0.000000000000000000e+00,7.023676875370110650e+00,0.000000000000000000e+00,-1.000000009964924441e+00,0.000000000000000000e+00,-2.183397379677688457e-11,0.000000000000000000e+00 +4.123301075135272953e+01,2.846800000000000068e+02,0.000000000000000000e+00,7.022253119653967701e+00,0.000000000000000000e+00,-1.000000009964955527e+00,0.000000000000000000e+00,-3.770274768682589763e-10,0.000000000000000000e+00 +4.123443479571991332e+01,2.846899999999999977e+02,0.000000000000000000e+00,7.020829075272590813e+00,0.000000000000000000e+00,-1.000000009965492431e+00,0.000000000000000000e+00,4.107799570128473007e-10,0.000000000000000000e+00 +4.123585912892797012e+01,2.846999999999999886e+02,0.000000000000000000e+00,7.019404742050340040e+00,0.000000000000000000e+00,-1.000000009964907344e+00,0.000000000000000000e+00,-1.597586476576395549e-10,0.000000000000000000e+00 +4.123728375115271660e+01,2.847099999999999795e+02,0.000000000000000000e+00,7.017980119811399575e+00,0.000000000000000000e+00,-1.000000009965134939e+00,0.000000000000000000e+00,2.243958657228354290e-10,0.000000000000000000e+00 +4.123870866257014711e+01,2.847200000000000273e+02,0.000000000000000000e+00,7.016555208379772424e+00,0.000000000000000000e+00,-1.000000009964815195e+00,0.000000000000000000e+00,-4.988678309832302058e-10,0.000000000000000000e+00 +4.124013386335643361e+01,2.847300000000000182e+02,0.000000000000000000e+00,7.015130007579284843e+00,0.000000000000000000e+00,-1.000000009965526182e+00,0.000000000000000000e+00,4.196367751156636479e-10,0.000000000000000000e+00 +4.124155935368793280e+01,2.847400000000000091e+02,0.000000000000000000e+00,7.013704517233581903e+00,0.000000000000000000e+00,-1.000000009964927994e+00,0.000000000000000000e+00,4.485183115939309892e-11,0.000000000000000000e+00 +4.124298513374117192e+01,2.847500000000000000e+02,0.000000000000000000e+00,7.012278737166132814e+00,0.000000000000000000e+00,-1.000000009964864045e+00,0.000000000000000000e+00,-1.855990084887355614e-10,0.000000000000000000e+00 +4.124441120369287006e+01,2.847599999999999909e+02,0.000000000000000000e+00,7.010852667200224708e+00,0.000000000000000000e+00,-1.000000009965128722e+00,0.000000000000000000e+00,-1.464875412046187362e-10,0.000000000000000000e+00 +4.124583756371991683e+01,2.847699999999999818e+02,0.000000000000000000e+00,7.009426307158965308e+00,0.000000000000000000e+00,-1.000000009965337666e+00,0.000000000000000000e+00,2.882462606570080531e-10,0.000000000000000000e+00 +4.124726421399937948e+01,2.847800000000000296e+02,0.000000000000000000e+00,7.007999656865282923e+00,0.000000000000000000e+00,-1.000000009964926440e+00,0.000000000000000000e+00,-6.457767337762137106e-11,0.000000000000000000e+00 +4.124869115470851710e+01,2.847900000000000205e+02,0.000000000000000000e+00,7.006572716141926449e+00,0.000000000000000000e+00,-1.000000009965018588e+00,0.000000000000000000e+00,-2.056730148578462082e-10,0.000000000000000000e+00 +4.125011838602475933e+01,2.848000000000000114e+02,0.000000000000000000e+00,7.005145484811462708e+00,0.000000000000000000e+00,-1.000000009965312131e+00,0.000000000000000000e+00,-8.243910236571839834e-12,0.000000000000000000e+00 +4.125154590812572053e+01,2.848100000000000023e+02,0.000000000000000000e+00,7.003717962696278221e+00,0.000000000000000000e+00,-1.000000009965323899e+00,0.000000000000000000e+00,2.174082627670469799e-10,0.000000000000000000e+00 +4.125297372118919270e+01,2.848199999999999932e+02,0.000000000000000000e+00,7.002290149618579207e+00,0.000000000000000000e+00,-1.000000009965013481e+00,0.000000000000000000e+00,-2.719381491474525223e-10,0.000000000000000000e+00 +4.125440182539315259e+01,2.848299999999999841e+02,0.000000000000000000e+00,7.000862045400390699e+00,0.000000000000000000e+00,-1.000000009965401837e+00,0.000000000000000000e+00,3.923567205042074734e-10,0.000000000000000000e+00 +4.125583022091575458e+01,2.848400000000000318e+02,0.000000000000000000e+00,6.999433649863554763e+00,0.000000000000000000e+00,-1.000000009964841396e+00,0.000000000000000000e+00,-2.746247509246325113e-10,0.000000000000000000e+00 +4.125725890793533779e+01,2.848500000000000227e+02,0.000000000000000000e+00,6.998004962829734055e+00,0.000000000000000000e+00,-1.000000009965233749e+00,0.000000000000000000e+00,3.123277186942222731e-11,0.000000000000000000e+00 +4.125868788663042608e+01,2.848600000000000136e+02,0.000000000000000000e+00,6.996575984120406488e+00,0.000000000000000000e+00,-1.000000009965189118e+00,0.000000000000000000e+00,-3.027872750982634791e-10,0.000000000000000000e+00 +4.126011715717972095e+01,2.848700000000000045e+02,0.000000000000000000e+00,6.995146713556869678e+00,0.000000000000000000e+00,-1.000000009965621883e+00,0.000000000000000000e+00,1.551681353815961832e-10,0.000000000000000000e+00 +4.126154671976210864e+01,2.848799999999999955e+02,0.000000000000000000e+00,6.993717150960237383e+00,0.000000000000000000e+00,-1.000000009965400061e+00,0.000000000000000000e+00,2.293658647893497356e-10,0.000000000000000000e+00 +4.126297657455665302e+01,2.848899999999999864e+02,0.000000000000000000e+00,6.992287296151442177e+00,0.000000000000000000e+00,-1.000000009965072101e+00,0.000000000000000000e+00,4.797532980906450122e-11,0.000000000000000000e+00 +4.126440672174260982e+01,2.849000000000000341e+02,0.000000000000000000e+00,6.990857148951232780e+00,0.000000000000000000e+00,-1.000000009965003489e+00,0.000000000000000000e+00,-2.595415694150218301e-10,0.000000000000000000e+00 +4.126583716149941239e+01,2.849100000000000250e+02,0.000000000000000000e+00,6.989426709180174058e+00,0.000000000000000000e+00,-1.000000009965374748e+00,0.000000000000000000e+00,-1.316065889463932554e-10,0.000000000000000000e+00 +4.126726789400667883e+01,2.849200000000000159e+02,0.000000000000000000e+00,6.987995976658647024e+00,0.000000000000000000e+00,-1.000000009965563041e+00,0.000000000000000000e+00,5.606099909553672903e-10,0.000000000000000000e+00 +4.126869891944421198e+01,2.849300000000000068e+02,0.000000000000000000e+00,6.986564951206849727e+00,0.000000000000000000e+00,-1.000000009964760794e+00,0.000000000000000000e+00,-6.560570570946780668e-10,0.000000000000000000e+00 +4.127013023799199942e+01,2.849399999999999977e+02,0.000000000000000000e+00,6.985133632644797252e+00,0.000000000000000000e+00,-1.000000009965699821e+00,0.000000000000000000e+00,2.500230115348370376e-10,0.000000000000000000e+00 +4.127156184983021348e+01,2.849499999999999886e+02,0.000000000000000000e+00,6.983702020792316389e+00,0.000000000000000000e+00,-1.000000009965341885e+00,0.000000000000000000e+00,-6.016690221749373186e-11,0.000000000000000000e+00 +4.127299375513920410e+01,2.849599999999999795e+02,0.000000000000000000e+00,6.982270115469053628e+00,0.000000000000000000e+00,-1.000000009965428038e+00,0.000000000000000000e+00,2.767420105545484251e-10,0.000000000000000000e+00 +4.127442595409952020e+01,2.849700000000000273e+02,0.000000000000000000e+00,6.980837916494468054e+00,0.000000000000000000e+00,-1.000000009965031689e+00,0.000000000000000000e+00,-3.420976675650619824e-10,0.000000000000000000e+00 +4.127585844689188121e+01,2.849800000000000182e+02,0.000000000000000000e+00,6.979405423687834897e+00,0.000000000000000000e+00,-1.000000009965521741e+00,0.000000000000000000e+00,3.776714722631358427e-10,0.000000000000000000e+00 +4.127729123369719844e+01,2.849900000000000091e+02,0.000000000000000000e+00,6.977972636868241985e+00,0.000000000000000000e+00,-1.000000009964980618e+00,0.000000000000000000e+00,-4.626571635510627922e-10,0.000000000000000000e+00 +4.127872431469656789e+01,2.850000000000000000e+02,0.000000000000000000e+00,6.976539555854594177e+00,0.000000000000000000e+00,-1.000000009965643644e+00,0.000000000000000000e+00,2.947942950813085730e-10,0.000000000000000000e+00 +4.128015769007127034e+01,2.850099999999999909e+02,0.000000000000000000e+00,6.975106180465607153e+00,0.000000000000000000e+00,-1.000000009965221093e+00,0.000000000000000000e+00,-2.461018882184939811e-10,0.000000000000000000e+00 +4.128159136000277840e+01,2.850199999999999818e+02,0.000000000000000000e+00,6.973672510519813628e+00,0.000000000000000000e+00,-1.000000009965573922e+00,0.000000000000000000e+00,2.059460255441647692e-10,0.000000000000000000e+00 +4.128302532467274233e+01,2.850300000000000296e+02,0.000000000000000000e+00,6.972238545835557133e+00,0.000000000000000000e+00,-1.000000009965278602e+00,0.000000000000000000e+00,5.433999316269490320e-11,0.000000000000000000e+00 +4.128445958426301132e+01,2.850400000000000205e+02,0.000000000000000000e+00,6.970804286230996460e+00,0.000000000000000000e+00,-1.000000009965200665e+00,0.000000000000000000e+00,-1.386855217436305182e-10,0.000000000000000000e+00 +4.128589413895561222e+01,2.850500000000000114e+02,0.000000000000000000e+00,6.969369731524102107e+00,0.000000000000000000e+00,-1.000000009965399617e+00,0.000000000000000000e+00,-2.409474546990037254e-10,0.000000000000000000e+00 +4.128732898893275660e+01,2.850600000000000023e+02,0.000000000000000000e+00,6.967934881532657165e+00,0.000000000000000000e+00,-1.000000009965745340e+00,0.000000000000000000e+00,3.094384695826527705e-10,0.000000000000000000e+00 +4.128876413437685500e+01,2.850699999999999932e+02,0.000000000000000000e+00,6.966499736074257321e+00,0.000000000000000000e+00,-1.000000009965301251e+00,0.000000000000000000e+00,-8.121086828436452574e-11,0.000000000000000000e+00 +4.129019957547049557e+01,2.850799999999999841e+02,0.000000000000000000e+00,6.965064294966311742e+00,0.000000000000000000e+00,-1.000000009965417824e+00,0.000000000000000000e+00,1.283640608212186188e-11,0.000000000000000000e+00 +4.129163531239645835e+01,2.850900000000000318e+02,0.000000000000000000e+00,6.963628558026039528e+00,0.000000000000000000e+00,-1.000000009965399395e+00,0.000000000000000000e+00,-1.380788883746320712e-10,0.000000000000000000e+00 +4.129307134533771517e+01,2.851000000000000227e+02,0.000000000000000000e+00,6.962192525070472371e+00,0.000000000000000000e+00,-1.000000009965597680e+00,0.000000000000000000e+00,2.829028638213540672e-11,0.000000000000000000e+00 +4.129450767447742265e+01,2.851100000000000136e+02,0.000000000000000000e+00,6.960756195916452782e+00,0.000000000000000000e+00,-1.000000009965557046e+00,0.000000000000000000e+00,2.136016932831394316e-10,0.000000000000000000e+00 +4.129594429999892213e+01,2.851200000000000045e+02,0.000000000000000000e+00,6.959319570380634978e+00,0.000000000000000000e+00,-1.000000009965250181e+00,0.000000000000000000e+00,-3.098285125927174296e-10,0.000000000000000000e+00 +4.129738122208575390e+01,2.851299999999999955e+02,0.000000000000000000e+00,6.957882648279483995e+00,0.000000000000000000e+00,-1.000000009965695380e+00,0.000000000000000000e+00,3.113095012060176276e-10,0.000000000000000000e+00 +4.129881844092164300e+01,2.851399999999999864e+02,0.000000000000000000e+00,6.956445429429273908e+00,0.000000000000000000e+00,-1.000000009965247960e+00,0.000000000000000000e+00,5.962314943452229129e-11,0.000000000000000000e+00 +4.130025595669049920e+01,2.851500000000000341e+02,0.000000000000000000e+00,6.955007913646091389e+00,0.000000000000000000e+00,-1.000000009965162251e+00,0.000000000000000000e+00,-5.011324839494861140e-10,0.000000000000000000e+00 +4.130169376957643124e+01,2.851600000000000250e+02,0.000000000000000000e+00,6.953570100745831262e+00,0.000000000000000000e+00,-1.000000009965882786e+00,0.000000000000000000e+00,4.800304474632263663e-10,0.000000000000000000e+00 +4.130313187976373257e+01,2.851700000000000159e+02,0.000000000000000000e+00,6.952131990544197393e+00,0.000000000000000000e+00,-1.000000009965192449e+00,0.000000000000000000e+00,-2.991658431578038017e-10,0.000000000000000000e+00 +4.130457028743688852e+01,2.851800000000000068e+02,0.000000000000000000e+00,6.950693582856706243e+00,0.000000000000000000e+00,-1.000000009965622771e+00,0.000000000000000000e+00,-1.284078856786225801e-10,0.000000000000000000e+00 +4.130600899278057625e+01,2.851899999999999977e+02,0.000000000000000000e+00,6.949254877498679761e+00,0.000000000000000000e+00,-1.000000009965807513e+00,0.000000000000000000e+00,2.671010122623543705e-10,0.000000000000000000e+00 +4.130744799597966477e+01,2.851999999999999886e+02,0.000000000000000000e+00,6.947815874285250715e+00,0.000000000000000000e+00,-1.000000009965423153e+00,0.000000000000000000e+00,-2.653487053143750475e-10,0.000000000000000000e+00 +4.130888729721920782e+01,2.852099999999999795e+02,0.000000000000000000e+00,6.946376573031360913e+00,0.000000000000000000e+00,-1.000000009965805070e+00,0.000000000000000000e+00,5.526438698038341585e-10,0.000000000000000000e+00 +4.131032689668446523e+01,2.852200000000000273e+02,0.000000000000000000e+00,6.944936973551758541e+00,0.000000000000000000e+00,-1.000000009965009484e+00,0.000000000000000000e+00,-5.735017040073617379e-10,0.000000000000000000e+00 +4.131176679456087442e+01,2.852300000000000182e+02,0.000000000000000000e+00,6.943497075661002604e+00,0.000000000000000000e+00,-1.000000009965835268e+00,0.000000000000000000e+00,3.476682476492145933e-10,0.000000000000000000e+00 +4.131320699103407179e+01,2.852400000000000091e+02,0.000000000000000000e+00,6.942056879173455819e+00,0.000000000000000000e+00,-1.000000009965334558e+00,0.000000000000000000e+00,-4.046296477395809830e-10,0.000000000000000000e+00 +4.131464748628987849e+01,2.852500000000000000e+02,0.000000000000000000e+00,6.940616383903292608e+00,0.000000000000000000e+00,-1.000000009965917425e+00,0.000000000000000000e+00,3.019066662461111726e-10,0.000000000000000000e+00 +4.131608828051432170e+01,2.852599999999999909e+02,0.000000000000000000e+00,6.939175589664491106e+00,0.000000000000000000e+00,-1.000000009965482439e+00,0.000000000000000000e+00,3.482222695226189004e-11,0.000000000000000000e+00 +4.131752937389361335e+01,2.852699999999999818e+02,0.000000000000000000e+00,6.937734496270839379e+00,0.000000000000000000e+00,-1.000000009965432257e+00,0.000000000000000000e+00,-2.144357229296513694e-10,0.000000000000000000e+00 +4.131897076661415724e+01,2.852800000000000296e+02,0.000000000000000000e+00,6.936293103535930094e+00,0.000000000000000000e+00,-1.000000009965741343e+00,0.000000000000000000e+00,1.165906011596873071e-10,0.000000000000000000e+00 +4.132041245886255609e+01,2.852900000000000205e+02,0.000000000000000000e+00,6.934851411273162292e+00,0.000000000000000000e+00,-1.000000009965573255e+00,0.000000000000000000e+00,-1.176442605158078037e-10,0.000000000000000000e+00 +4.132185445082560449e+01,2.853000000000000114e+02,0.000000000000000000e+00,6.933409419295742282e+00,0.000000000000000000e+00,-1.000000009965742898e+00,0.000000000000000000e+00,7.251168191420674478e-11,0.000000000000000000e+00 +4.132329674269028885e+01,2.853100000000000023e+02,0.000000000000000000e+00,6.931967127416680974e+00,0.000000000000000000e+00,-1.000000009965638315e+00,0.000000000000000000e+00,-3.001451509213055305e-11,0.000000000000000000e+00 +4.132473933464379456e+01,2.853199999999999932e+02,0.000000000000000000e+00,6.930524535448795653e+00,0.000000000000000000e+00,-1.000000009965681613e+00,0.000000000000000000e+00,1.374224825080488783e-10,0.000000000000000000e+00 +4.132618222687350595e+01,2.853299999999999841e+02,0.000000000000000000e+00,6.929081643204708207e+00,0.000000000000000000e+00,-1.000000009965483327e+00,0.000000000000000000e+00,-1.412402849890064834e-10,0.000000000000000000e+00 +4.132762541956698499e+01,2.853400000000000318e+02,0.000000000000000000e+00,6.927638450496846012e+00,0.000000000000000000e+00,-1.000000009965687164e+00,0.000000000000000000e+00,-3.030342143323935358e-10,0.000000000000000000e+00 +4.132906891291200679e+01,2.853500000000000227e+02,0.000000000000000000e+00,6.926194957137440156e+00,0.000000000000000000e+00,-1.000000009966124592e+00,0.000000000000000000e+00,6.414681933679725296e-10,0.000000000000000000e+00 +4.133051270709653124e+01,2.853600000000000136e+02,0.000000000000000000e+00,6.924751162938526328e+00,0.000000000000000000e+00,-1.000000009965198444e+00,0.000000000000000000e+00,-5.793690501121854846e-10,0.000000000000000000e+00 +4.133195680230871716e+01,2.853700000000000045e+02,0.000000000000000000e+00,6.923307067711946594e+00,0.000000000000000000e+00,-1.000000009966035108e+00,0.000000000000000000e+00,4.321302464158246096e-10,0.000000000000000000e+00 +4.133340119873692942e+01,2.853799999999999955e+02,0.000000000000000000e+00,6.921862671269342293e+00,0.000000000000000000e+00,-1.000000009965410941e+00,0.000000000000000000e+00,-4.455653598081049054e-10,0.000000000000000000e+00 +4.133484589656971053e+01,2.853899999999999864e+02,0.000000000000000000e+00,6.920417973422162916e+00,0.000000000000000000e+00,-1.000000009966054648e+00,0.000000000000000000e+00,3.317608944146332896e-10,0.000000000000000000e+00 +4.133629089599581619e+01,2.854000000000000341e+02,0.000000000000000000e+00,6.918972973981657226e+00,0.000000000000000000e+00,-1.000000009965575254e+00,0.000000000000000000e+00,-7.758419133498365679e-11,0.000000000000000000e+00 +4.133773619720418679e+01,2.854100000000000250e+02,0.000000000000000000e+00,6.917527672758880364e+00,0.000000000000000000e+00,-1.000000009965687386e+00,0.000000000000000000e+00,-2.577407495183292783e-10,0.000000000000000000e+00 +4.133918180038397594e+01,2.854200000000000159e+02,0.000000000000000000e+00,6.916082069564687629e+00,0.000000000000000000e+00,-1.000000009966059977e+00,0.000000000000000000e+00,3.533596713471608586e-10,0.000000000000000000e+00 +4.134062770572451484e+01,2.854300000000000068e+02,0.000000000000000000e+00,6.914636164209737146e+00,0.000000000000000000e+00,-1.000000009965549053e+00,0.000000000000000000e+00,-2.296895052302298026e-10,0.000000000000000000e+00 +4.134207391341534787e+01,2.854399999999999977e+02,0.000000000000000000e+00,6.913189956504490752e+00,0.000000000000000000e+00,-1.000000009965881231e+00,0.000000000000000000e+00,2.558905899950444378e-10,0.000000000000000000e+00 +4.134352042364621127e+01,2.854499999999999886e+02,0.000000000000000000e+00,6.911743446259209556e+00,0.000000000000000000e+00,-1.000000009965511083e+00,0.000000000000000000e+00,-1.740367198812085866e-10,0.000000000000000000e+00 +4.134496723660704731e+01,2.854599999999999795e+02,0.000000000000000000e+00,6.910296633283958379e+00,0.000000000000000000e+00,-1.000000009965762882e+00,0.000000000000000000e+00,-1.061800707409798919e-10,0.000000000000000000e+00 +4.134641435248798302e+01,2.854700000000000273e+02,0.000000000000000000e+00,6.908849517388601313e+00,0.000000000000000000e+00,-1.000000009965916536e+00,0.000000000000000000e+00,1.733502220579801006e-10,0.000000000000000000e+00 +4.134786177147935859e+01,2.854800000000000182e+02,0.000000000000000000e+00,6.907402098382804390e+00,0.000000000000000000e+00,-1.000000009965665626e+00,0.000000000000000000e+00,-4.294503835982477108e-11,0.000000000000000000e+00 +4.134930949377169895e+01,2.854900000000000091e+02,0.000000000000000000e+00,6.905954376076034684e+00,0.000000000000000000e+00,-1.000000009965727799e+00,0.000000000000000000e+00,-1.915253958921551530e-10,0.000000000000000000e+00 +4.135075751955574219e+01,2.855000000000000000e+02,0.000000000000000000e+00,6.904506350277558546e+00,0.000000000000000000e+00,-1.000000009966005132e+00,0.000000000000000000e+00,-1.318473210884785343e-10,0.000000000000000000e+00 +4.135220584902242535e+01,2.855099999999999909e+02,0.000000000000000000e+00,6.903058020796442484e+00,0.000000000000000000e+00,-1.000000009966196091e+00,0.000000000000000000e+00,2.754417863431159312e-10,0.000000000000000000e+00 +4.135365448236287733e+01,2.855199999999999818e+02,0.000000000000000000e+00,6.901609387441553167e+00,0.000000000000000000e+00,-1.000000009965797076e+00,0.000000000000000000e+00,-9.869075435791874358e-11,0.000000000000000000e+00 +4.135510341976843307e+01,2.855300000000000296e+02,0.000000000000000000e+00,6.900160450021557423e+00,0.000000000000000000e+00,-1.000000009965940073e+00,0.000000000000000000e+00,1.558189838862117098e-10,0.000000000000000000e+00 +4.135655266143062647e+01,2.855400000000000205e+02,0.000000000000000000e+00,6.898711208344919577e+00,0.000000000000000000e+00,-1.000000009965714254e+00,0.000000000000000000e+00,-8.869247091495742329e-11,0.000000000000000000e+00 +4.135800220754119749e+01,2.855500000000000114e+02,0.000000000000000000e+00,6.897261662219904110e+00,0.000000000000000000e+00,-1.000000009965842818e+00,0.000000000000000000e+00,1.542220239038148603e-10,0.000000000000000000e+00 +4.135945205829207794e+01,2.855600000000000023e+02,0.000000000000000000e+00,6.895811811454573004e+00,0.000000000000000000e+00,-1.000000009965619219e+00,0.000000000000000000e+00,-2.417729760903324605e-10,0.000000000000000000e+00 +4.136090221387541277e+01,2.855699999999999932e+02,0.000000000000000000e+00,6.894361655856787507e+00,0.000000000000000000e+00,-1.000000009965969827e+00,0.000000000000000000e+00,1.319597708293274165e-10,0.000000000000000000e+00 +4.136235267448353881e+01,2.855799999999999841e+02,0.000000000000000000e+00,6.892911195234205479e+00,0.000000000000000000e+00,-1.000000009965778425e+00,0.000000000000000000e+00,-2.718227927797289386e-10,0.000000000000000000e+00 +4.136380344030899892e+01,2.855900000000000318e+02,0.000000000000000000e+00,6.891460429394284048e+00,0.000000000000000000e+00,-1.000000009966172776e+00,0.000000000000000000e+00,3.771971614709304239e-10,0.000000000000000000e+00 +4.136525451154454203e+01,2.856000000000000227e+02,0.000000000000000000e+00,6.890009358144276064e+00,0.000000000000000000e+00,-1.000000009965625436e+00,0.000000000000000000e+00,-3.104145604487737224e-10,0.000000000000000000e+00 +4.136670588838312312e+01,2.856100000000000136e+02,0.000000000000000000e+00,6.888557981291233645e+00,0.000000000000000000e+00,-1.000000009966075964e+00,0.000000000000000000e+00,-8.320845216896868867e-11,0.000000000000000000e+00 +4.136815757101788904e+01,2.856200000000000045e+02,0.000000000000000000e+00,6.887106298642002855e+00,0.000000000000000000e+00,-1.000000009966196757e+00,0.000000000000000000e+00,3.576903580554101872e-10,0.000000000000000000e+00 +4.136960955964219266e+01,2.856299999999999955e+02,0.000000000000000000e+00,6.885654310003228140e+00,0.000000000000000000e+00,-1.000000009965677394e+00,0.000000000000000000e+00,-1.090121664722399095e-10,0.000000000000000000e+00 +4.137106185444960005e+01,2.856399999999999864e+02,0.000000000000000000e+00,6.884202015181350554e+00,0.000000000000000000e+00,-1.000000009965835712e+00,0.000000000000000000e+00,-7.597141585924684391e-11,0.000000000000000000e+00 +4.137251445563386909e+01,2.856500000000000341e+02,0.000000000000000000e+00,6.882749413982605091e+00,0.000000000000000000e+00,-1.000000009965946068e+00,0.000000000000000000e+00,-2.422319638464826935e-10,0.000000000000000000e+00 +4.137396736338897085e+01,2.856600000000000250e+02,0.000000000000000000e+00,6.881296506213023356e+00,0.000000000000000000e+00,-1.000000009966298009e+00,0.000000000000000000e+00,3.763352583963691868e-10,0.000000000000000000e+00 +4.137542057790908245e+01,2.856700000000000159e+02,0.000000000000000000e+00,6.879843291678431783e+00,0.000000000000000000e+00,-1.000000009965751113e+00,0.000000000000000000e+00,-1.790384804378124918e-10,0.000000000000000000e+00 +4.137687409938857286e+01,2.856800000000000068e+02,0.000000000000000000e+00,6.878389770184453411e+00,0.000000000000000000e+00,-1.000000009966011350e+00,0.000000000000000000e+00,-8.232197337430903841e-11,0.000000000000000000e+00 +4.137832792802203130e+01,2.856899999999999977e+02,0.000000000000000000e+00,6.876935941536503449e+00,0.000000000000000000e+00,-1.000000009966131032e+00,0.000000000000000000e+00,-3.084512778951106609e-11,0.000000000000000000e+00 +4.137978206400425307e+01,2.856999999999999886e+02,0.000000000000000000e+00,6.875481805539792823e+00,0.000000000000000000e+00,-1.000000009966175885e+00,0.000000000000000000e+00,1.198430958326554428e-10,0.000000000000000000e+00 +4.138123650753022531e+01,2.857099999999999795e+02,0.000000000000000000e+00,6.874027361999326402e+00,0.000000000000000000e+00,-1.000000009966001580e+00,0.000000000000000000e+00,9.448048870103382783e-11,0.000000000000000000e+00 +4.138269125879514831e+01,2.857200000000000273e+02,0.000000000000000000e+00,6.872572610719902997e+00,0.000000000000000000e+00,-1.000000009965864134e+00,0.000000000000000000e+00,3.784523822011411937e-11,0.000000000000000000e+00 +4.138414631799443555e+01,2.857300000000000182e+02,0.000000000000000000e+00,6.871117551506114474e+00,0.000000000000000000e+00,-1.000000009965809067e+00,0.000000000000000000e+00,-3.246678070746303117e-10,0.000000000000000000e+00 +4.138560168532369943e+01,2.857400000000000091e+02,0.000000000000000000e+00,6.869662184162345753e+00,0.000000000000000000e+00,-1.000000009966281578e+00,0.000000000000000000e+00,-9.152228553904534062e-12,0.000000000000000000e+00 +4.138705736097876553e+01,2.857500000000000000e+02,0.000000000000000000e+00,6.868206508492773921e+00,0.000000000000000000e+00,-1.000000009966294900e+00,0.000000000000000000e+00,2.903691774174319765e-10,0.000000000000000000e+00 +4.138851334515565839e+01,2.857599999999999909e+02,0.000000000000000000e+00,6.866750524301370007e+00,0.000000000000000000e+00,-1.000000009965872128e+00,0.000000000000000000e+00,-1.174038178611182073e-10,0.000000000000000000e+00 +4.138996963805061569e+01,2.857699999999999818e+02,0.000000000000000000e+00,6.865294231391897206e+00,0.000000000000000000e+00,-1.000000009966043102e+00,0.000000000000000000e+00,1.693610116832199786e-10,0.000000000000000000e+00 +4.139142623986008829e+01,2.857800000000000296e+02,0.000000000000000000e+00,6.863837629567909104e+00,0.000000000000000000e+00,-1.000000009965796410e+00,0.000000000000000000e+00,-3.778189646408157770e-10,0.000000000000000000e+00 +4.139288315078072600e+01,2.857900000000000205e+02,0.000000000000000000e+00,6.862380718632752341e+00,0.000000000000000000e+00,-1.000000009966346859e+00,0.000000000000000000e+00,6.125493554366127232e-11,0.000000000000000000e+00 +4.139434037100939179e+01,2.858000000000000114e+02,0.000000000000000000e+00,6.860923498389563058e+00,0.000000000000000000e+00,-1.000000009966257597e+00,0.000000000000000000e+00,3.772015273909036982e-10,0.000000000000000000e+00 +4.139579790074316179e+01,2.858100000000000023e+02,0.000000000000000000e+00,6.859465968641270450e+00,0.000000000000000000e+00,-1.000000009965707815e+00,0.000000000000000000e+00,-5.368953623787859324e-10,0.000000000000000000e+00 +4.139725574017931109e+01,2.858199999999999932e+02,0.000000000000000000e+00,6.858008129190594104e+00,0.000000000000000000e+00,-1.000000009966490522e+00,0.000000000000000000e+00,3.919645258262736131e-10,0.000000000000000000e+00 +4.139871388951532793e+01,2.858299999999999841e+02,0.000000000000000000e+00,6.856549979840041331e+00,0.000000000000000000e+00,-1.000000009965918979e+00,0.000000000000000000e+00,-3.303738051186419964e-11,0.000000000000000000e+00 +4.140017234894892084e+01,2.858400000000000318e+02,0.000000000000000000e+00,6.855091520391913384e+00,0.000000000000000000e+00,-1.000000009965967163e+00,0.000000000000000000e+00,-4.100634622069734869e-10,0.000000000000000000e+00 +4.140163111867799728e+01,2.858500000000000227e+02,0.000000000000000000e+00,6.853632750648298355e+00,0.000000000000000000e+00,-1.000000009966565351e+00,0.000000000000000000e+00,2.424246797035398532e-10,0.000000000000000000e+00 +4.140309019890067788e+01,2.858600000000000136e+02,0.000000000000000000e+00,6.852173670411073836e+00,0.000000000000000000e+00,-1.000000009966211634e+00,0.000000000000000000e+00,-1.414984021837439633e-11,0.000000000000000000e+00 +4.140454958981529643e+01,2.858700000000000045e+02,0.000000000000000000e+00,6.850714279481908697e+00,0.000000000000000000e+00,-1.000000009966232284e+00,0.000000000000000000e+00,2.193518698015520080e-10,0.000000000000000000e+00 +4.140600929162039989e+01,2.858799999999999955e+02,0.000000000000000000e+00,6.849254577662258647e+00,0.000000000000000000e+00,-1.000000009965912096e+00,0.000000000000000000e+00,-1.593840348010921233e-10,0.000000000000000000e+00 +4.140746930451474128e+01,2.858899999999999864e+02,0.000000000000000000e+00,6.847794564753368896e+00,0.000000000000000000e+00,-1.000000009966144798e+00,0.000000000000000000e+00,-1.681690517644712756e-10,0.000000000000000000e+00 +4.140892962869728677e+01,2.859000000000000341e+02,0.000000000000000000e+00,6.846334240556271489e+00,0.000000000000000000e+00,-1.000000009966390380e+00,0.000000000000000000e+00,3.408269526012288343e-10,0.000000000000000000e+00 +4.141039026436721571e+01,2.859100000000000250e+02,0.000000000000000000e+00,6.844873604871787087e+00,0.000000000000000000e+00,-1.000000009965892556e+00,0.000000000000000000e+00,-1.484910308482353666e-10,0.000000000000000000e+00 +4.141185121172392058e+01,2.859200000000000159e+02,0.000000000000000000e+00,6.843412657500524965e+00,0.000000000000000000e+00,-1.000000009966109493e+00,0.000000000000000000e+00,-2.381123661422029468e-10,0.000000000000000000e+00 +4.141331247096699997e+01,2.859300000000000068e+02,0.000000000000000000e+00,6.841951398242879456e+00,0.000000000000000000e+00,-1.000000009966457437e+00,0.000000000000000000e+00,2.201347454556564075e-10,0.000000000000000000e+00 +4.141477404229627979e+01,2.859399999999999977e+02,0.000000000000000000e+00,6.840489826899032622e+00,0.000000000000000000e+00,-1.000000009966135694e+00,0.000000000000000000e+00,-2.866152715909836397e-10,0.000000000000000000e+00 +4.141623592591179204e+01,2.859499999999999886e+02,0.000000000000000000e+00,6.839027943268954246e+00,0.000000000000000000e+00,-1.000000009966554693e+00,0.000000000000000000e+00,4.689341867883840090e-10,0.000000000000000000e+00 +4.141769812201377476e+01,2.859599999999999795e+02,0.000000000000000000e+00,6.837565747152398288e+00,0.000000000000000000e+00,-1.000000009965869019e+00,0.000000000000000000e+00,-2.713103073351005540e-10,0.000000000000000000e+00 +4.141916063080269339e+01,2.859700000000000273e+02,0.000000000000000000e+00,6.836103238348907318e+00,0.000000000000000000e+00,-1.000000009966265813e+00,0.000000000000000000e+00,-2.799044190097218884e-10,0.000000000000000000e+00 +4.142062345247921229e+01,2.859800000000000182e+02,0.000000000000000000e+00,6.834640416657806306e+00,0.000000000000000000e+00,-1.000000009966675263e+00,0.000000000000000000e+00,5.921655811435834944e-10,0.000000000000000000e+00 +4.142208658724423032e+01,2.859900000000000091e+02,0.000000000000000000e+00,6.833177281878207054e+00,0.000000000000000000e+00,-1.000000009965808845e+00,0.000000000000000000e+00,-4.084491243631334850e-10,0.000000000000000000e+00 +4.142355003529884527e+01,2.860000000000000000e+02,0.000000000000000000e+00,6.831713833809008207e+00,0.000000000000000000e+00,-1.000000009966406589e+00,0.000000000000000000e+00,1.877978156595972317e-10,0.000000000000000000e+00 +4.142501379684437524e+01,2.860099999999999909e+02,0.000000000000000000e+00,6.830250072248889026e+00,0.000000000000000000e+00,-1.000000009966131698e+00,0.000000000000000000e+00,-3.708136337243435611e-10,0.000000000000000000e+00 +4.142647787208235854e+01,2.860199999999999818e+02,0.000000000000000000e+00,6.828785996996316499e+00,0.000000000000000000e+00,-1.000000009966674597e+00,0.000000000000000000e+00,1.394991481714982536e-10,0.000000000000000000e+00 +4.142794226121453960e+01,2.860300000000000296e+02,0.000000000000000000e+00,6.827321607849539120e+00,0.000000000000000000e+00,-1.000000009966470316e+00,0.000000000000000000e+00,2.123873870684623531e-10,0.000000000000000000e+00 +4.142940696444289017e+01,2.860400000000000205e+02,0.000000000000000000e+00,6.825856904606591335e+00,0.000000000000000000e+00,-1.000000009966159231e+00,0.000000000000000000e+00,6.062578798632671171e-13,0.000000000000000000e+00 +4.143087198196958809e+01,2.860500000000000114e+02,0.000000000000000000e+00,6.824391887065289986e+00,0.000000000000000000e+00,-1.000000009966158343e+00,0.000000000000000000e+00,-3.438259719546175286e-10,0.000000000000000000e+00 +4.143233731399703856e+01,2.860600000000000023e+02,0.000000000000000000e+00,6.822926555023234307e+00,0.000000000000000000e+00,-1.000000009966662162e+00,0.000000000000000000e+00,5.716072480255776834e-10,0.000000000000000000e+00 +4.143380296072785995e+01,2.860699999999999932e+02,0.000000000000000000e+00,6.821460908277805935e+00,0.000000000000000000e+00,-1.000000009965824388e+00,0.000000000000000000e+00,-4.082031856491294363e-10,0.000000000000000000e+00 +4.143526892236488379e+01,2.860799999999999841e+02,0.000000000000000000e+00,6.819994946626171561e+00,0.000000000000000000e+00,-1.000000009966422798e+00,0.000000000000000000e+00,-2.365403896449364674e-10,0.000000000000000000e+00 +4.143673519911116898e+01,2.860900000000000318e+02,0.000000000000000000e+00,6.818528669865275837e+00,0.000000000000000000e+00,-1.000000009966769632e+00,0.000000000000000000e+00,4.115099577693696868e-10,0.000000000000000000e+00 +4.143820179116998048e+01,2.861000000000000227e+02,0.000000000000000000e+00,6.817062077791847585e+00,0.000000000000000000e+00,-1.000000009966166115e+00,0.000000000000000000e+00,3.784229639531759183e-11,0.000000000000000000e+00 +4.143966869874481063e+01,2.861100000000000136e+02,0.000000000000000000e+00,6.815595170202398023e+00,0.000000000000000000e+00,-1.000000009966110603e+00,0.000000000000000000e+00,-3.775848511556874811e-10,0.000000000000000000e+00 +4.144113592203937202e+01,2.861200000000000045e+02,0.000000000000000000e+00,6.814127946893217214e+00,0.000000000000000000e+00,-1.000000009966664605e+00,0.000000000000000000e+00,1.432849209439063614e-10,0.000000000000000000e+00 +4.144260346125759042e+01,2.861299999999999955e+02,0.000000000000000000e+00,6.812660407660375839e+00,0.000000000000000000e+00,-1.000000009966454328e+00,0.000000000000000000e+00,1.037722139253242726e-10,0.000000000000000000e+00 +4.144407131660361188e+01,2.861399999999999864e+02,0.000000000000000000e+00,6.811192552299726977e+00,0.000000000000000000e+00,-1.000000009966302006e+00,0.000000000000000000e+00,7.123350114508866278e-11,0.000000000000000000e+00 +4.144553948828180268e+01,2.861500000000000341e+02,0.000000000000000000e+00,6.809724380606902550e+00,0.000000000000000000e+00,-1.000000009966197423e+00,0.000000000000000000e+00,-2.122935833875259534e-10,0.000000000000000000e+00 +4.144700797649675650e+01,2.861600000000000250e+02,0.000000000000000000e+00,6.808255892377314211e+00,0.000000000000000000e+00,-1.000000009966509174e+00,0.000000000000000000e+00,-1.801989895902913233e-10,0.000000000000000000e+00 +4.144847678145328018e+01,2.861700000000000159e+02,0.000000000000000000e+00,6.806787087406152459e+00,0.000000000000000000e+00,-1.000000009966773851e+00,0.000000000000000000e+00,3.216281224016691280e-10,0.000000000000000000e+00 +4.144994590335640083e+01,2.861800000000000068e+02,0.000000000000000000e+00,6.805317965488387522e+00,0.000000000000000000e+00,-1.000000009966301340e+00,0.000000000000000000e+00,-1.981031306276309705e-10,0.000000000000000000e+00 +4.145141534241137293e+01,2.861899999999999977e+02,0.000000000000000000e+00,6.803848526418769360e+00,0.000000000000000000e+00,-1.000000009966592440e+00,0.000000000000000000e+00,6.224322375035858073e-11,0.000000000000000000e+00 +4.145288509882367123e+01,2.861999999999999886e+02,0.000000000000000000e+00,6.802378769991824115e+00,0.000000000000000000e+00,-1.000000009966500958e+00,0.000000000000000000e+00,2.371377465257210286e-11,0.000000000000000000e+00 +4.145435517279898363e+01,2.862099999999999795e+02,0.000000000000000000e+00,6.800908696001857656e+00,0.000000000000000000e+00,-1.000000009966466097e+00,0.000000000000000000e+00,2.533956331849633022e-10,0.000000000000000000e+00 +4.145582556454323253e+01,2.862200000000000273e+02,0.000000000000000000e+00,6.799438304242952924e+00,0.000000000000000000e+00,-1.000000009966093506e+00,0.000000000000000000e+00,-3.253572865712053830e-10,0.000000000000000000e+00 +4.145729627426256059e+01,2.862300000000000182e+02,0.000000000000000000e+00,6.797967594508970812e+00,0.000000000000000000e+00,-1.000000009966572012e+00,0.000000000000000000e+00,8.664254645403322824e-11,0.000000000000000000e+00 +4.145876730216332362e+01,2.862400000000000091e+02,0.000000000000000000e+00,6.796496566593547506e+00,0.000000000000000000e+00,-1.000000009966444559e+00,0.000000000000000000e+00,3.018250790007192150e-12,0.000000000000000000e+00 +4.146023864845211193e+01,2.862500000000000000e+02,0.000000000000000000e+00,6.795025220290098034e+00,0.000000000000000000e+00,-1.000000009966440118e+00,0.000000000000000000e+00,-4.188425164813949761e-10,0.000000000000000000e+00 +4.146171031333572898e+01,2.862599999999999909e+02,0.000000000000000000e+00,6.793553555391812715e+00,0.000000000000000000e+00,-1.000000009967056513e+00,0.000000000000000000e+00,6.181717908669980456e-10,0.000000000000000000e+00 +4.146318229702121272e+01,2.862699999999999818e+02,0.000000000000000000e+00,6.792081571691657160e+00,0.000000000000000000e+00,-1.000000009966146575e+00,0.000000000000000000e+00,-4.191135147320305050e-10,0.000000000000000000e+00 +4.146465459971582135e+01,2.862800000000000296e+02,0.000000000000000000e+00,6.790609268982375823e+00,0.000000000000000000e+00,-1.000000009966763637e+00,0.000000000000000000e+00,3.161894665439044541e-10,0.000000000000000000e+00 +4.146612722162703335e+01,2.862900000000000205e+02,0.000000000000000000e+00,6.789136647056484009e+00,0.000000000000000000e+00,-1.000000009966298009e+00,0.000000000000000000e+00,-2.963727629559775564e-10,0.000000000000000000e+00 +4.146760016296256168e+01,2.863000000000000114e+02,0.000000000000000000e+00,6.787663705706275863e+00,0.000000000000000000e+00,-1.000000009966734549e+00,0.000000000000000000e+00,3.579514751506619471e-10,0.000000000000000000e+00 +4.146907342393033957e+01,2.863100000000000023e+02,0.000000000000000000e+00,6.786190444723817272e+00,0.000000000000000000e+00,-1.000000009966207193e+00,0.000000000000000000e+00,-4.273389664630032637e-10,0.000000000000000000e+00 +4.147054700473852051e+01,2.863199999999999932e+02,0.000000000000000000e+00,6.784716863900951189e+00,0.000000000000000000e+00,-1.000000009966836911e+00,0.000000000000000000e+00,-3.916925416490018179e-11,0.000000000000000000e+00 +4.147202090559549248e+01,2.863299999999999841e+02,0.000000000000000000e+00,6.783242963029291417e+00,0.000000000000000000e+00,-1.000000009966894643e+00,0.000000000000000000e+00,4.530596971539704267e-10,0.000000000000000000e+00 +4.147349512670986371e+01,2.863400000000000318e+02,0.000000000000000000e+00,6.781768741900227937e+00,0.000000000000000000e+00,-1.000000009966226733e+00,0.000000000000000000e+00,-4.258558395274523885e-10,0.000000000000000000e+00 +4.147496966829046983e+01,2.863500000000000227e+02,0.000000000000000000e+00,6.780294200304924246e+00,0.000000000000000000e+00,-1.000000009966854675e+00,0.000000000000000000e+00,3.434108790866370911e-10,0.000000000000000000e+00 +4.147644453054638092e+01,2.863600000000000136e+02,0.000000000000000000e+00,6.778819338034313802e+00,0.000000000000000000e+00,-1.000000009966348191e+00,0.000000000000000000e+00,-3.478517804955072038e-10,0.000000000000000000e+00 +4.147791971368688735e+01,2.863700000000000045e+02,0.000000000000000000e+00,6.777344154879106242e+00,0.000000000000000000e+00,-1.000000009966861336e+00,0.000000000000000000e+00,1.100061947582415095e-10,0.000000000000000000e+00 +4.147939521792150686e+01,2.863799999999999955e+02,0.000000000000000000e+00,6.775868650629780277e+00,0.000000000000000000e+00,-1.000000009966699022e+00,0.000000000000000000e+00,2.435858480558298476e-10,0.000000000000000000e+00 +4.148087104345999165e+01,2.863899999999999864e+02,0.000000000000000000e+00,6.774392825076589020e+00,0.000000000000000000e+00,-1.000000009966339531e+00,0.000000000000000000e+00,-1.938936200823465388e-10,0.000000000000000000e+00 +4.148234719051231423e+01,2.864000000000000341e+02,0.000000000000000000e+00,6.772916678009556435e+00,0.000000000000000000e+00,-1.000000009966625747e+00,0.000000000000000000e+00,-2.269369418409810147e-10,0.000000000000000000e+00 +4.148382365928868154e+01,2.864100000000000250e+02,0.000000000000000000e+00,6.771440209218476447e+00,0.000000000000000000e+00,-1.000000009966960812e+00,0.000000000000000000e+00,3.040201890911422495e-10,0.000000000000000000e+00 +4.148530044999952082e+01,2.864200000000000159e+02,0.000000000000000000e+00,6.769963418492914720e+00,0.000000000000000000e+00,-1.000000009966511838e+00,0.000000000000000000e+00,-6.869778706455913463e-11,0.000000000000000000e+00 +4.148677756285550799e+01,2.864300000000000068e+02,0.000000000000000000e+00,6.768486305622208654e+00,0.000000000000000000e+00,-1.000000009966613312e+00,0.000000000000000000e+00,3.712177493150748771e-11,0.000000000000000000e+00 +4.148825499806752504e+01,2.864399999999999977e+02,0.000000000000000000e+00,6.767008870395463838e+00,0.000000000000000000e+00,-1.000000009966558467e+00,0.000000000000000000e+00,-3.125361847194377867e-11,0.000000000000000000e+00 +4.148973275584670262e+01,2.864499999999999886e+02,0.000000000000000000e+00,6.765531112601556707e+00,0.000000000000000000e+00,-1.000000009966604653e+00,0.000000000000000000e+00,-1.119176013839187086e-10,0.000000000000000000e+00 +4.149121083640439167e+01,2.864599999999999795e+02,0.000000000000000000e+00,6.764053032029132773e+00,0.000000000000000000e+00,-1.000000009966770076e+00,0.000000000000000000e+00,-4.385610730911497083e-11,0.000000000000000000e+00 +4.149268923995218472e+01,2.864700000000000273e+02,0.000000000000000000e+00,6.762574628466606619e+00,0.000000000000000000e+00,-1.000000009966834913e+00,0.000000000000000000e+00,-7.102535891122984798e-11,0.000000000000000000e+00 +4.149416796670189456e+01,2.864800000000000182e+02,0.000000000000000000e+00,6.761095901702161903e+00,0.000000000000000000e+00,-1.000000009966939940e+00,0.000000000000000000e+00,3.748658376279201066e-10,0.000000000000000000e+00 +4.149564701686556134e+01,2.864900000000000091e+02,0.000000000000000000e+00,6.759616851523750469e+00,0.000000000000000000e+00,-1.000000009966385495e+00,0.000000000000000000e+00,-1.684050700536598532e-10,0.000000000000000000e+00 +4.149712639065547393e+01,2.865000000000000000e+02,0.000000000000000000e+00,6.758137477719093233e+00,0.000000000000000000e+00,-1.000000009966634629e+00,0.000000000000000000e+00,-3.190292536288284249e-10,0.000000000000000000e+00 +4.149860608828414144e+01,2.865099999999999909e+02,0.000000000000000000e+00,6.756657780075676634e+00,0.000000000000000000e+00,-1.000000009967106696e+00,0.000000000000000000e+00,4.902913103352293294e-10,0.000000000000000000e+00 +4.150008610996431457e+01,2.865199999999999818e+02,0.000000000000000000e+00,6.755177758380755293e+00,0.000000000000000000e+00,-1.000000009966381054e+00,0.000000000000000000e+00,-4.157863552618813128e-10,0.000000000000000000e+00 +4.150156645590896431e+01,2.865300000000000296e+02,0.000000000000000000e+00,6.753697412421352908e+00,0.000000000000000000e+00,-1.000000009966996561e+00,0.000000000000000000e+00,3.699567655877861630e-10,0.000000000000000000e+00 +4.150304712633130322e+01,2.865400000000000205e+02,0.000000000000000000e+00,6.752216741984256032e+00,0.000000000000000000e+00,-1.000000009966448777e+00,0.000000000000000000e+00,-2.313409560113323569e-10,0.000000000000000000e+00 +4.150452812144477832e+01,2.865500000000000114e+02,0.000000000000000000e+00,6.750735746856021180e+00,0.000000000000000000e+00,-1.000000009966791392e+00,0.000000000000000000e+00,-2.967949614690583671e-11,0.000000000000000000e+00 +4.150600944146307114e+01,2.865600000000000023e+02,0.000000000000000000e+00,6.749254426822967723e+00,0.000000000000000000e+00,-1.000000009966835357e+00,0.000000000000000000e+00,-7.598082151004091747e-11,0.000000000000000000e+00 +4.150749108660009057e+01,2.865699999999999932e+02,0.000000000000000000e+00,6.747772781671182329e+00,0.000000000000000000e+00,-1.000000009966947934e+00,0.000000000000000000e+00,1.992747700101976129e-10,0.000000000000000000e+00 +4.150897305706998708e+01,2.865799999999999841e+02,0.000000000000000000e+00,6.746290811186516301e+00,0.000000000000000000e+00,-1.000000009966652614e+00,0.000000000000000000e+00,-2.528585982660222913e-10,0.000000000000000000e+00 +4.151045535308714562e+01,2.865900000000000318e+02,0.000000000000000000e+00,6.744808515154586459e+00,0.000000000000000000e+00,-1.000000009967027426e+00,0.000000000000000000e+00,3.497008878669207406e-10,0.000000000000000000e+00 +4.151193797486618564e+01,2.866000000000000227e+02,0.000000000000000000e+00,6.743325893360772483e+00,0.000000000000000000e+00,-1.000000009966508951e+00,0.000000000000000000e+00,-2.519988102306620864e-10,0.000000000000000000e+00 +4.151342092262196104e+01,2.866100000000000136e+02,0.000000000000000000e+00,6.741842945590220459e+00,0.000000000000000000e+00,-1.000000009966882653e+00,0.000000000000000000e+00,-2.767934238789031305e-10,0.000000000000000000e+00 +4.151490419656956021e+01,2.866200000000000045e+02,0.000000000000000000e+00,6.740359671627837557e+00,0.000000000000000000e+00,-1.000000009967293213e+00,0.000000000000000000e+00,4.406168512998654290e-10,0.000000000000000000e+00 +4.151638779692431314e+01,2.866299999999999955e+02,0.000000000000000000e+00,6.738876071258295575e+00,0.000000000000000000e+00,-1.000000009966639514e+00,0.000000000000000000e+00,4.788259439620144966e-11,0.000000000000000000e+00 +4.151787172390179137e+01,2.866399999999999864e+02,0.000000000000000000e+00,6.737392144266030947e+00,0.000000000000000000e+00,-1.000000009966568459e+00,0.000000000000000000e+00,-4.800669060267480099e-10,0.000000000000000000e+00 +4.151935597771778674e+01,2.866500000000000341e+02,0.000000000000000000e+00,6.735907890435240297e+00,0.000000000000000000e+00,-1.000000009967281001e+00,0.000000000000000000e+00,2.313804593812766443e-10,0.000000000000000000e+00 +4.152084055858834688e+01,2.866600000000000250e+02,0.000000000000000000e+00,6.734423309549882219e+00,0.000000000000000000e+00,-1.000000009966937498e+00,0.000000000000000000e+00,3.337604154588577459e-10,0.000000000000000000e+00 +4.152232546672974678e+01,2.866700000000000159e+02,0.000000000000000000e+00,6.732938401393679939e+00,0.000000000000000000e+00,-1.000000009966441894e+00,0.000000000000000000e+00,-4.079889514541823595e-10,0.000000000000000000e+00 +4.152381070235851013e+01,2.866800000000000068e+02,0.000000000000000000e+00,6.731453165750116874e+00,0.000000000000000000e+00,-1.000000009967047854e+00,0.000000000000000000e+00,1.868353573450420036e-10,0.000000000000000000e+00 +4.152529626569138799e+01,2.866899999999999977e+02,0.000000000000000000e+00,6.729967602402435745e+00,0.000000000000000000e+00,-1.000000009966770298e+00,0.000000000000000000e+00,-1.300087107767326672e-10,0.000000000000000000e+00 +4.152678215694537300e+01,2.866999999999999886e+02,0.000000000000000000e+00,6.728481711133643017e+00,0.000000000000000000e+00,-1.000000009966963477e+00,0.000000000000000000e+00,1.703186292155124185e-11,0.000000000000000000e+00 +4.152826837633769941e+01,2.867099999999999795e+02,0.000000000000000000e+00,6.726995491726503573e+00,0.000000000000000000e+00,-1.000000009966938164e+00,0.000000000000000000e+00,-8.962158337757269025e-12,0.000000000000000000e+00 +4.152975492408584302e+01,2.867200000000000273e+02,0.000000000000000000e+00,6.725508943963543373e+00,0.000000000000000000e+00,-1.000000009966951486e+00,0.000000000000000000e+00,-3.882743738593589123e-11,0.000000000000000000e+00 +4.153124180040752123e+01,2.867300000000000182e+02,0.000000000000000000e+00,6.724022067627047683e+00,0.000000000000000000e+00,-1.000000009967009218e+00,0.000000000000000000e+00,9.525549414015746921e-11,0.000000000000000000e+00 +4.153272900552068592e+01,2.867400000000000091e+02,0.000000000000000000e+00,6.722534862499061070e+00,0.000000000000000000e+00,-1.000000009966867554e+00,0.000000000000000000e+00,-2.407729289990664397e-10,0.000000000000000000e+00 +4.153421653964353055e+01,2.867500000000000000e+02,0.000000000000000000e+00,6.721047328361387407e+00,0.000000000000000000e+00,-1.000000009967225711e+00,0.000000000000000000e+00,3.265310589574069513e-10,0.000000000000000000e+00 +4.153570440299449729e+01,2.867599999999999909e+02,0.000000000000000000e+00,6.719559464995588094e+00,0.000000000000000000e+00,-1.000000009966739878e+00,0.000000000000000000e+00,-4.013592782756287753e-11,0.000000000000000000e+00 +4.153719259579226986e+01,2.867699999999999818e+02,0.000000000000000000e+00,6.718071272182984721e+00,0.000000000000000000e+00,-1.000000009966799608e+00,0.000000000000000000e+00,-3.680052224836010627e-10,0.000000000000000000e+00 +4.153868111825576648e+01,2.867800000000000296e+02,0.000000000000000000e+00,6.716582749704654631e+00,0.000000000000000000e+00,-1.000000009967347392e+00,0.000000000000000000e+00,3.137865546371763704e-10,0.000000000000000000e+00 +4.154016997060414695e+01,2.867900000000000205e+02,0.000000000000000000e+00,6.715093897341432694e+00,0.000000000000000000e+00,-1.000000009966880210e+00,0.000000000000000000e+00,-2.290253370577408769e-10,0.000000000000000000e+00 +4.154165915305682688e+01,2.868000000000000114e+02,0.000000000000000000e+00,6.713604714873913082e+00,0.000000000000000000e+00,-1.000000009967221271e+00,0.000000000000000000e+00,1.772465731072499516e-10,0.000000000000000000e+00 +4.154314866583344923e+01,2.868100000000000023e+02,0.000000000000000000e+00,6.712115202082443943e+00,0.000000000000000000e+00,-1.000000009966957260e+00,0.000000000000000000e+00,1.011974109446973619e-10,0.000000000000000000e+00 +4.154463850915391276e+01,2.868199999999999932e+02,0.000000000000000000e+00,6.710625358747131841e+00,0.000000000000000000e+00,-1.000000009966806491e+00,0.000000000000000000e+00,-2.854951428012842726e-10,0.000000000000000000e+00 +4.154612868323835073e+01,2.868299999999999841e+02,0.000000000000000000e+00,6.709135184647838201e+00,0.000000000000000000e+00,-1.000000009967231929e+00,0.000000000000000000e+00,3.882229269434548844e-10,0.000000000000000000e+00 +4.154761918830715217e+01,2.868400000000000318e+02,0.000000000000000000e+00,6.707644679564179313e+00,0.000000000000000000e+00,-1.000000009966653280e+00,0.000000000000000000e+00,-5.056500482130218928e-10,0.000000000000000000e+00 +4.154911002458094060e+01,2.868500000000000227e+02,0.000000000000000000e+00,6.706153843275528992e+00,0.000000000000000000e+00,-1.000000009967407122e+00,0.000000000000000000e+00,4.029410649564986694e-10,0.000000000000000000e+00 +4.155060119228059534e+01,2.868600000000000136e+02,0.000000000000000000e+00,6.704662675561012364e+00,0.000000000000000000e+00,-1.000000009966806269e+00,0.000000000000000000e+00,-3.104010754771893437e-10,0.000000000000000000e+00 +4.155209269162723018e+01,2.868700000000000045e+02,0.000000000000000000e+00,6.703171176199512971e+00,0.000000000000000000e+00,-1.000000009967269232e+00,0.000000000000000000e+00,3.226857694382921744e-10,0.000000000000000000e+00 +4.155358452284220760e+01,2.868799999999999955e+02,0.000000000000000000e+00,6.701679344969664776e+00,0.000000000000000000e+00,-1.000000009966787839e+00,0.000000000000000000e+00,-3.196378102864292362e-10,0.000000000000000000e+00 +4.155507668614713879e+01,2.868899999999999864e+02,0.000000000000000000e+00,6.700187181649858381e+00,0.000000000000000000e+00,-1.000000009967264791e+00,0.000000000000000000e+00,3.290881799469122274e-10,0.000000000000000000e+00 +4.155656918176388359e+01,2.869000000000000341e+02,0.000000000000000000e+00,6.698694686018234812e+00,0.000000000000000000e+00,-1.000000009966773629e+00,0.000000000000000000e+00,-3.489461549354983730e-10,0.000000000000000000e+00 +4.155806200991455057e+01,2.869100000000000250e+02,0.000000000000000000e+00,6.697201857852690843e+00,0.000000000000000000e+00,-1.000000009967294545e+00,0.000000000000000000e+00,2.107188875072832522e-10,0.000000000000000000e+00 +4.155955517082148276e+01,2.869200000000000159e+02,0.000000000000000000e+00,6.695708696930872783e+00,0.000000000000000000e+00,-1.000000009966979908e+00,0.000000000000000000e+00,-2.085904627201265831e-10,0.000000000000000000e+00 +4.156104866470728609e+01,2.869300000000000068e+02,0.000000000000000000e+00,6.694215203030181804e+00,0.000000000000000000e+00,-1.000000009967291437e+00,0.000000000000000000e+00,1.597895447792972918e-10,0.000000000000000000e+00 +4.156254249179480809e+01,2.869399999999999977e+02,0.000000000000000000e+00,6.692721375927768612e+00,0.000000000000000000e+00,-1.000000009967052739e+00,0.000000000000000000e+00,-1.017966631546967521e-10,0.000000000000000000e+00 +4.156403665230714495e+01,2.869499999999999886e+02,0.000000000000000000e+00,6.691227215400536998e+00,0.000000000000000000e+00,-1.000000009967204839e+00,0.000000000000000000e+00,-2.362343936576494912e-11,0.000000000000000000e+00 +4.156553114646764868e+01,2.869599999999999795e+02,0.000000000000000000e+00,6.689732721225140288e+00,0.000000000000000000e+00,-1.000000009967240144e+00,0.000000000000000000e+00,1.717144432364095439e-10,0.000000000000000000e+00 +4.156702597449990577e+01,2.869700000000000273e+02,0.000000000000000000e+00,6.688237893177983118e+00,0.000000000000000000e+00,-1.000000009966983461e+00,0.000000000000000000e+00,-1.361824907962596623e-10,0.000000000000000000e+00 +4.156852113662776560e+01,2.869800000000000182e+02,0.000000000000000000e+00,6.686742731035220544e+00,0.000000000000000000e+00,-1.000000009967187076e+00,0.000000000000000000e+00,2.316218030798942970e-11,0.000000000000000000e+00 +4.157001663307532624e+01,2.869900000000000091e+02,0.000000000000000000e+00,6.685247234572756270e+00,0.000000000000000000e+00,-1.000000009967152437e+00,0.000000000000000000e+00,3.043067316105074628e-11,0.000000000000000000e+00 +4.157151246406692735e+01,2.870000000000000000e+02,0.000000000000000000e+00,6.683751403566244420e+00,0.000000000000000000e+00,-1.000000009967106918e+00,0.000000000000000000e+00,6.173818309659479423e-11,0.000000000000000000e+00 +4.157300862982717149e+01,2.870099999999999909e+02,0.000000000000000000e+00,6.682255237791087765e+00,0.000000000000000000e+00,-1.000000009967014547e+00,0.000000000000000000e+00,-1.038631106998480246e-10,0.000000000000000000e+00 +4.157450513058090280e+01,2.870199999999999818e+02,0.000000000000000000e+00,6.680758737022437721e+00,0.000000000000000000e+00,-1.000000009967169978e+00,0.000000000000000000e+00,-2.891198120570755144e-10,0.000000000000000000e+00 +4.157600196655322833e+01,2.870300000000000296e+02,0.000000000000000000e+00,6.679261901035193461e+00,0.000000000000000000e+00,-1.000000009967602743e+00,0.000000000000000000e+00,4.739968647739729084e-10,0.000000000000000000e+00 +4.157749913796949670e+01,2.870400000000000205e+02,0.000000000000000000e+00,6.677764729604001914e+00,0.000000000000000000e+00,-1.000000009966893089e+00,0.000000000000000000e+00,-4.105766956702057762e-10,0.000000000000000000e+00 +4.157899664505531234e+01,2.870500000000000114e+02,0.000000000000000000e+00,6.676267222503259546e+00,0.000000000000000000e+00,-1.000000009967507930e+00,0.000000000000000000e+00,4.032207200401508623e-10,0.000000000000000000e+00 +4.158049448803653547e+01,2.870600000000000023e+02,0.000000000000000000e+00,6.674769379507106137e+00,0.000000000000000000e+00,-1.000000009966903969e+00,0.000000000000000000e+00,-7.543871336877209708e-11,0.000000000000000000e+00 +4.158199266713927500e+01,2.870699999999999932e+02,0.000000000000000000e+00,6.673271200389431890e+00,0.000000000000000000e+00,-1.000000009967016990e+00,0.000000000000000000e+00,-4.794987874414724995e-10,0.000000000000000000e+00 +4.158349118258990273e+01,2.870799999999999841e+02,0.000000000000000000e+00,6.671772684923870322e+00,0.000000000000000000e+00,-1.000000009967735526e+00,0.000000000000000000e+00,5.536108132711104483e-10,0.000000000000000000e+00 +4.158499003461503207e+01,2.870900000000000318e+02,0.000000000000000000e+00,6.670273832883800935e+00,0.000000000000000000e+00,-1.000000009966905745e+00,0.000000000000000000e+00,-3.557598159750627970e-10,0.000000000000000000e+00 +4.158648922344153931e+01,2.871000000000000227e+02,0.000000000000000000e+00,6.668774644042351873e+00,0.000000000000000000e+00,-1.000000009967439096e+00,0.000000000000000000e+00,1.337131184346916576e-10,0.000000000000000000e+00 +4.158798874929654943e+01,2.871100000000000136e+02,0.000000000000000000e+00,6.667275118172391934e+00,0.000000000000000000e+00,-1.000000009967238590e+00,0.000000000000000000e+00,-1.703977772441783438e-10,0.000000000000000000e+00 +4.158948861240745742e+01,2.871200000000000045e+02,0.000000000000000000e+00,6.665775255046537673e+00,0.000000000000000000e+00,-1.000000009967494163e+00,0.000000000000000000e+00,4.906529620480720123e-10,0.000000000000000000e+00 +4.159098881300189277e+01,2.871299999999999955e+02,0.000000000000000000e+00,6.664275054437148071e+00,0.000000000000000000e+00,-1.000000009966758086e+00,0.000000000000000000e+00,-4.662743679280423409e-10,0.000000000000000000e+00 +4.159248935130775493e+01,2.871399999999999864e+02,0.000000000000000000e+00,6.662774516116328094e+00,0.000000000000000000e+00,-1.000000009967457748e+00,0.000000000000000000e+00,-9.897407674057274334e-11,0.000000000000000000e+00 +4.159399022755319919e+01,2.871500000000000341e+02,0.000000000000000000e+00,6.661273639855922468e+00,0.000000000000000000e+00,-1.000000009967606296e+00,0.000000000000000000e+00,1.934662634746408106e-10,0.000000000000000000e+00 +4.159549144196663661e+01,2.871600000000000250e+02,0.000000000000000000e+00,6.659772425427521902e+00,0.000000000000000000e+00,-1.000000009967315862e+00,0.000000000000000000e+00,1.978589626632670557e-10,0.000000000000000000e+00 +4.159699299477673406e+01,2.871700000000000159e+02,0.000000000000000000e+00,6.658270872602459534e+00,0.000000000000000000e+00,-1.000000009967018766e+00,0.000000000000000000e+00,-2.984956480164139242e-10,0.000000000000000000e+00 +4.159849488621241420e+01,2.871800000000000068e+02,0.000000000000000000e+00,6.656768981151810038e+00,0.000000000000000000e+00,-1.000000009967467074e+00,0.000000000000000000e+00,6.636667376851785339e-11,0.000000000000000000e+00 +4.159999711650286258e+01,2.871899999999999977e+02,0.000000000000000000e+00,6.655266750846388746e+00,0.000000000000000000e+00,-1.000000009967367376e+00,0.000000000000000000e+00,2.918588000815706514e-10,0.000000000000000000e+00 +4.160149968587752056e+01,2.871999999999999886e+02,0.000000000000000000e+00,6.653764181456754301e+00,0.000000000000000000e+00,-1.000000009966928838e+00,0.000000000000000000e+00,-6.193396784019247707e-10,0.000000000000000000e+00 +4.160300259456609240e+01,2.872099999999999795e+02,0.000000000000000000e+00,6.652261272753206001e+00,0.000000000000000000e+00,-1.000000009967859649e+00,0.000000000000000000e+00,6.590814516155241750e-10,0.000000000000000000e+00 +4.160450584279853103e+01,2.872200000000000273e+02,0.000000000000000000e+00,6.650758024505781130e+00,0.000000000000000000e+00,-1.000000009966868886e+00,0.000000000000000000e+00,-4.072917699013288532e-10,0.000000000000000000e+00 +4.160600943080506653e+01,2.872300000000000182e+02,0.000000000000000000e+00,6.649254436484262065e+00,0.000000000000000000e+00,-1.000000009967481285e+00,0.000000000000000000e+00,-9.921616819935473357e-11,0.000000000000000000e+00 +4.160751335881617052e+01,2.872400000000000091e+02,0.000000000000000000e+00,6.647750508458165619e+00,0.000000000000000000e+00,-1.000000009967630499e+00,0.000000000000000000e+00,1.938115538636780303e-10,0.000000000000000000e+00 +4.160901762706259177e+01,2.872500000000000000e+02,0.000000000000000000e+00,6.646246240196751032e+00,0.000000000000000000e+00,-1.000000009967338954e+00,0.000000000000000000e+00,-1.301623072403564685e-10,0.000000000000000000e+00 +4.161052223577532772e+01,2.872599999999999909e+02,0.000000000000000000e+00,6.644741631469016419e+00,0.000000000000000000e+00,-1.000000009967534798e+00,0.000000000000000000e+00,2.894791757622130334e-10,0.000000000000000000e+00 +4.161202718518564581e+01,2.872699999999999818e+02,0.000000000000000000e+00,6.643236682043696995e+00,0.000000000000000000e+00,-1.000000009967099146e+00,0.000000000000000000e+00,-3.251109081331261987e-10,0.000000000000000000e+00 +4.161353247552506929e+01,2.872800000000000296e+02,0.000000000000000000e+00,6.641731391689267738e+00,0.000000000000000000e+00,-1.000000009967588532e+00,0.000000000000000000e+00,1.706298040678895819e-10,0.000000000000000000e+00 +4.161503810702539141e+01,2.872900000000000205e+02,0.000000000000000000e+00,6.640225760173938951e+00,0.000000000000000000e+00,-1.000000009967331627e+00,0.000000000000000000e+00,4.423278916592513631e-13,0.000000000000000000e+00 +4.161654407991866123e+01,2.873000000000000114e+02,0.000000000000000000e+00,6.638719787265660699e+00,0.000000000000000000e+00,-1.000000009967330961e+00,0.000000000000000000e+00,-2.587031306211792229e-10,0.000000000000000000e+00 +4.161805039443719068e+01,2.873100000000000023e+02,0.000000000000000000e+00,6.637213472732118369e+00,0.000000000000000000e+00,-1.000000009967720649e+00,0.000000000000000000e+00,3.601863191561814968e-10,0.000000000000000000e+00 +4.161955705081355461e+01,2.873199999999999932e+02,0.000000000000000000e+00,6.635706816340733560e+00,0.000000000000000000e+00,-1.000000009967177972e+00,0.000000000000000000e+00,-3.057352514247884197e-10,0.000000000000000000e+00 +4.162106404928060499e+01,2.873299999999999841e+02,0.000000000000000000e+00,6.634199817858665860e+00,0.000000000000000000e+00,-1.000000009967638714e+00,0.000000000000000000e+00,2.757621255573866004e-10,0.000000000000000000e+00 +4.162257139007143536e+01,2.873400000000000318e+02,0.000000000000000000e+00,6.632692477052807511e+00,0.000000000000000000e+00,-1.000000009967223047e+00,0.000000000000000000e+00,-5.581736070687823860e-11,0.000000000000000000e+00 +4.162407907341942348e+01,2.873500000000000227e+02,0.000000000000000000e+00,6.631184793689788748e+00,0.000000000000000000e+00,-1.000000009967307202e+00,0.000000000000000000e+00,-3.324721667785977748e-10,0.000000000000000000e+00 +4.162558709955821001e+01,2.873600000000000136e+02,0.000000000000000000e+00,6.629676767535972459e+00,0.000000000000000000e+00,-1.000000009967808579e+00,0.000000000000000000e+00,4.123307168117542490e-10,0.000000000000000000e+00 +4.162709546872169142e+01,2.873700000000000045e+02,0.000000000000000000e+00,6.628168398357455970e+00,0.000000000000000000e+00,-1.000000009967186632e+00,0.000000000000000000e+00,-3.677900834441257368e-10,0.000000000000000000e+00 +4.162860418114403416e+01,2.873799999999999955e+02,0.000000000000000000e+00,6.626659685920072818e+00,0.000000000000000000e+00,-1.000000009967741521e+00,0.000000000000000000e+00,2.460204261391565631e-10,0.000000000000000000e+00 +4.163011323705968181e+01,2.873899999999999864e+02,0.000000000000000000e+00,6.625150629989386530e+00,0.000000000000000000e+00,-1.000000009967370262e+00,0.000000000000000000e+00,-2.903909855600305991e-10,0.000000000000000000e+00 +4.163162263670332663e+01,2.874000000000000341e+02,0.000000000000000000e+00,6.623641230330696850e+00,0.000000000000000000e+00,-1.000000009967808579e+00,0.000000000000000000e+00,1.604581485967935168e-10,0.000000000000000000e+00 +4.163313238030993801e+01,2.874100000000000250e+02,0.000000000000000000e+00,6.622131486709033510e+00,0.000000000000000000e+00,-1.000000009967566328e+00,0.000000000000000000e+00,2.261488380241537292e-10,0.000000000000000000e+00 +4.163464246811476244e+01,2.874200000000000159e+02,0.000000000000000000e+00,6.620621398889160680e+00,0.000000000000000000e+00,-1.000000009967224823e+00,0.000000000000000000e+00,-2.935736305960479856e-10,0.000000000000000000e+00 +4.163615290035329508e+01,2.874300000000000068e+02,0.000000000000000000e+00,6.619110966635573412e+00,0.000000000000000000e+00,-1.000000009967668246e+00,0.000000000000000000e+00,3.461232706320321916e-10,0.000000000000000000e+00 +4.163766367726131534e+01,2.874399999999999977e+02,0.000000000000000000e+00,6.617600189712496750e+00,0.000000000000000000e+00,-1.000000009967145331e+00,0.000000000000000000e+00,-3.902732826660846627e-10,0.000000000000000000e+00 +4.163917479907485841e+01,2.874499999999999886e+02,0.000000000000000000e+00,6.616089067883889285e+00,0.000000000000000000e+00,-1.000000009967735082e+00,0.000000000000000000e+00,2.027312298853393382e-11,0.000000000000000000e+00 +4.164068626603024370e+01,2.874599999999999795e+02,0.000000000000000000e+00,6.614577600913436939e+00,0.000000000000000000e+00,-1.000000009967704440e+00,0.000000000000000000e+00,2.106160641381886588e-10,0.000000000000000000e+00 +4.164219807836405352e+01,2.874700000000000273e+02,0.000000000000000000e+00,6.613065788564558289e+00,0.000000000000000000e+00,-1.000000009967386028e+00,0.000000000000000000e+00,-1.776758652241720188e-11,0.000000000000000000e+00 +4.164371023631314017e+01,2.874800000000000182e+02,0.000000000000000000e+00,6.611553630600401021e+00,0.000000000000000000e+00,-1.000000009967412895e+00,0.000000000000000000e+00,-4.747705437982240848e-10,0.000000000000000000e+00 +4.164522274011462599e+01,2.874900000000000091e+02,0.000000000000000000e+00,6.610041126783841037e+00,0.000000000000000000e+00,-1.000000009968130987e+00,0.000000000000000000e+00,5.819525543170984520e-10,0.000000000000000000e+00 +4.164673559000590330e+01,2.875000000000000000e+02,0.000000000000000000e+00,6.608528276877482455e+00,0.000000000000000000e+00,-1.000000009967250580e+00,0.000000000000000000e+00,-1.505540139684912591e-10,0.000000000000000000e+00 +4.164824878622464155e+01,2.875099999999999909e+02,0.000000000000000000e+00,6.607015080643661165e+00,0.000000000000000000e+00,-1.000000009967478398e+00,0.000000000000000000e+00,-1.525734135447855413e-10,0.000000000000000000e+00 +4.164976232900878017e+01,2.875199999999999818e+02,0.000000000000000000e+00,6.605501537844436832e+00,0.000000000000000000e+00,-1.000000009967709325e+00,0.000000000000000000e+00,-1.012034025718624690e-11,0.000000000000000000e+00 +4.165127621859652862e+01,2.875300000000000296e+02,0.000000000000000000e+00,6.603987648241598230e+00,0.000000000000000000e+00,-1.000000009967724646e+00,0.000000000000000000e+00,8.109080450408265042e-11,0.000000000000000000e+00 +4.165279045522637347e+01,2.875400000000000205e+02,0.000000000000000000e+00,6.602473411596661457e+00,0.000000000000000000e+00,-1.000000009967601855e+00,0.000000000000000000e+00,-7.506143233054741822e-11,0.000000000000000000e+00 +4.165430503913707128e+01,2.875500000000000114e+02,0.000000000000000000e+00,6.600958827670869056e+00,0.000000000000000000e+00,-1.000000009967715542e+00,0.000000000000000000e+00,1.005475204381371051e-10,0.000000000000000000e+00 +4.165581997056764862e+01,2.875600000000000023e+02,0.000000000000000000e+00,6.599443896225189121e+00,0.000000000000000000e+00,-1.000000009967563219e+00,0.000000000000000000e+00,2.593706515412149555e-11,0.000000000000000000e+00 +4.165733524975741631e+01,2.875699999999999932e+02,0.000000000000000000e+00,6.597928617020316189e+00,0.000000000000000000e+00,-1.000000009967523917e+00,0.000000000000000000e+00,-1.060684944037040100e-10,0.000000000000000000e+00 +4.165885087694595512e+01,2.875799999999999841e+02,0.000000000000000000e+00,6.596412989816669459e+00,0.000000000000000000e+00,-1.000000009967684678e+00,0.000000000000000000e+00,-1.031147333037315623e-10,0.000000000000000000e+00 +4.166036685237312298e+01,2.875900000000000318e+02,0.000000000000000000e+00,6.594897014374392796e+00,0.000000000000000000e+00,-1.000000009967840997e+00,0.000000000000000000e+00,2.280010547335493657e-10,0.000000000000000000e+00 +4.166188317627904780e+01,2.876000000000000227e+02,0.000000000000000000e+00,6.593380690453354731e+00,0.000000000000000000e+00,-1.000000009967495274e+00,0.000000000000000000e+00,-7.861812158557082654e-11,0.000000000000000000e+00 +4.166339984890413461e+01,2.876100000000000136e+02,0.000000000000000000e+00,6.591864017813148457e+00,0.000000000000000000e+00,-1.000000009967614512e+00,0.000000000000000000e+00,-5.635198189986172659e-11,0.000000000000000000e+00 +4.166491687048907266e+01,2.876200000000000045e+02,0.000000000000000000e+00,6.590346996213089170e+00,0.000000000000000000e+00,-1.000000009967699999e+00,0.000000000000000000e+00,-2.833047526500051913e-10,0.000000000000000000e+00 +4.166643424127482120e+01,2.876299999999999955e+02,0.000000000000000000e+00,6.588829625412215840e+00,0.000000000000000000e+00,-1.000000009968129877e+00,0.000000000000000000e+00,5.916428903500081245e-10,0.000000000000000000e+00 +4.166795196150261660e+01,2.876399999999999864e+02,0.000000000000000000e+00,6.587311905169289439e+00,0.000000000000000000e+00,-1.000000009967231929e+00,0.000000000000000000e+00,-3.217889552902794216e-10,0.000000000000000000e+00 +4.166947003141397943e+01,2.876500000000000341e+02,0.000000000000000000e+00,6.585793835242795602e+00,0.000000000000000000e+00,-1.000000009967720427e+00,0.000000000000000000e+00,-1.291246211403282580e-10,0.000000000000000000e+00 +4.167098845125070028e+01,2.876600000000000250e+02,0.000000000000000000e+00,6.584275415390937525e+00,0.000000000000000000e+00,-1.000000009967916492e+00,0.000000000000000000e+00,2.074582020492541426e-10,0.000000000000000000e+00 +4.167250722125485396e+01,2.876700000000000159e+02,0.000000000000000000e+00,6.582756645371642179e+00,0.000000000000000000e+00,-1.000000009967601411e+00,0.000000000000000000e+00,-2.711389685475661965e-10,0.000000000000000000e+00 +4.167402634166879949e+01,2.876800000000000068e+02,0.000000000000000000e+00,6.581237524942557648e+00,0.000000000000000000e+00,-1.000000009968013304e+00,0.000000000000000000e+00,1.708292766501939874e-10,0.000000000000000000e+00 +4.167554581273515879e+01,2.876899999999999977e+02,0.000000000000000000e+00,6.579718053861050464e+00,0.000000000000000000e+00,-1.000000009967753734e+00,0.000000000000000000e+00,1.899288164523974575e-10,0.000000000000000000e+00 +4.167706563469685221e+01,2.876999999999999886e+02,0.000000000000000000e+00,6.578198231884209157e+00,0.000000000000000000e+00,-1.000000009967465076e+00,0.000000000000000000e+00,-4.009493658534902915e-10,0.000000000000000000e+00 +4.167858580779707012e+01,2.877099999999999795e+02,0.000000000000000000e+00,6.576678058768840707e+00,0.000000000000000000e+00,-1.000000009968074588e+00,0.000000000000000000e+00,1.324506504319553372e-10,0.000000000000000000e+00 +4.168010633227928707e+01,2.877200000000000273e+02,0.000000000000000000e+00,6.575157534271469650e+00,0.000000000000000000e+00,-1.000000009967873194e+00,0.000000000000000000e+00,6.540702591436838805e-11,0.000000000000000000e+00 +4.168162720838725477e+01,2.877300000000000182e+02,0.000000000000000000e+00,6.573636658148341638e+00,0.000000000000000000e+00,-1.000000009967773718e+00,0.000000000000000000e+00,-1.985111154363782262e-11,0.000000000000000000e+00 +4.168314843636501621e+01,2.877400000000000091e+02,0.000000000000000000e+00,6.572115430155418991e+00,0.000000000000000000e+00,-1.000000009967803916e+00,0.000000000000000000e+00,7.442444148473866789e-11,0.000000000000000000e+00 +4.168467001645688441e+01,2.877500000000000000e+02,0.000000000000000000e+00,6.570593850048381590e+00,0.000000000000000000e+00,-1.000000009967690673e+00,0.000000000000000000e+00,1.623827951014755484e-10,0.000000000000000000e+00 +4.168619194890747082e+01,2.877599999999999909e+02,0.000000000000000000e+00,6.569071917582626874e+00,0.000000000000000000e+00,-1.000000009967443537e+00,0.000000000000000000e+00,-3.241069146590857197e-10,0.000000000000000000e+00 +4.168771423396165687e+01,2.877699999999999818e+02,0.000000000000000000e+00,6.567549632513268953e+00,0.000000000000000000e+00,-1.000000009967936920e+00,0.000000000000000000e+00,-3.587390850153280334e-11,0.000000000000000000e+00 +4.168923687186460825e+01,2.877800000000000296e+02,0.000000000000000000e+00,6.566026994595136834e+00,0.000000000000000000e+00,-1.000000009967991543e+00,0.000000000000000000e+00,7.523026488900553149e-11,0.000000000000000000e+00 +4.169075986286178903e+01,2.877900000000000205e+02,0.000000000000000000e+00,6.564504003582777081e+00,0.000000000000000000e+00,-1.000000009967876968e+00,0.000000000000000000e+00,2.098962285126226833e-10,0.000000000000000000e+00 +4.169228320719893333e+01,2.878000000000000114e+02,0.000000000000000000e+00,6.562980659230451153e+00,0.000000000000000000e+00,-1.000000009967557224e+00,0.000000000000000000e+00,-1.983350523196457209e-10,0.000000000000000000e+00 +4.169380690512205945e+01,2.878100000000000023e+02,0.000000000000000000e+00,6.561456961292135404e+00,0.000000000000000000e+00,-1.000000009967859427e+00,0.000000000000000000e+00,-1.835739509565412800e-10,0.000000000000000000e+00 +4.169533095687748414e+01,2.878199999999999932e+02,0.000000000000000000e+00,6.559932909521519306e+00,0.000000000000000000e+00,-1.000000009968139203e+00,0.000000000000000000e+00,7.195592693473319816e-11,0.000000000000000000e+00 +4.169685536271180126e+01,2.878299999999999841e+02,0.000000000000000000e+00,6.558408503672007228e+00,0.000000000000000000e+00,-1.000000009968029513e+00,0.000000000000000000e+00,3.859086946607263832e-10,0.000000000000000000e+00 +4.169838012287188889e+01,2.878400000000000318e+02,0.000000000000000000e+00,6.556883743496717543e+00,0.000000000000000000e+00,-1.000000009967441095e+00,0.000000000000000000e+00,-5.679546496080310801e-10,0.000000000000000000e+00 +4.169990523760492351e+01,2.878500000000000227e+02,0.000000000000000000e+00,6.555358628748481742e+00,0.000000000000000000e+00,-1.000000009968307291e+00,0.000000000000000000e+00,4.666595946060698895e-10,0.000000000000000000e+00 +4.170143070715835876e+01,2.878600000000000136e+02,0.000000000000000000e+00,6.553833159179840884e+00,0.000000000000000000e+00,-1.000000009967595416e+00,0.000000000000000000e+00,-1.263151179690802689e-10,0.000000000000000000e+00 +4.170295653177993955e+01,2.878700000000000045e+02,0.000000000000000000e+00,6.552307334543052697e+00,0.000000000000000000e+00,-1.000000009967788150e+00,0.000000000000000000e+00,-2.362764897356298841e-10,0.000000000000000000e+00 +4.170448271171769505e+01,2.878799999999999955e+02,0.000000000000000000e+00,6.550781154590082700e+00,0.000000000000000000e+00,-1.000000009968148751e+00,0.000000000000000000e+00,3.389137879271618470e-10,0.000000000000000000e+00 +4.170600924721995284e+01,2.878899999999999864e+02,0.000000000000000000e+00,6.549254619072608641e+00,0.000000000000000000e+00,-1.000000009967631387e+00,0.000000000000000000e+00,-4.857117025847681826e-10,0.000000000000000000e+00 +4.170753613853532471e+01,2.879000000000000341e+02,0.000000000000000000e+00,6.547727727742020498e+00,0.000000000000000000e+00,-1.000000009968373016e+00,0.000000000000000000e+00,5.414277483708769519e-10,0.000000000000000000e+00 +4.170906338591270668e+01,2.879100000000000250e+02,0.000000000000000000e+00,6.546200480349415152e+00,0.000000000000000000e+00,-1.000000009967546122e+00,0.000000000000000000e+00,-1.851820788260106929e-10,0.000000000000000000e+00 +4.171059098960129319e+01,2.879200000000000159e+02,0.000000000000000000e+00,6.544672876645603488e+00,0.000000000000000000e+00,-1.000000009967829007e+00,0.000000000000000000e+00,-1.767102512762142948e-10,0.000000000000000000e+00 +4.171211894985056290e+01,2.879300000000000068e+02,0.000000000000000000e+00,6.543144916381101517e+00,0.000000000000000000e+00,-1.000000009968099013e+00,0.000000000000000000e+00,8.717220167550411795e-12,0.000000000000000000e+00 +4.171364726691029290e+01,2.879399999999999977e+02,0.000000000000000000e+00,6.541616599306135704e+00,0.000000000000000000e+00,-1.000000009968085690e+00,0.000000000000000000e+00,1.953653755674523291e-10,0.000000000000000000e+00 +4.171517594103055160e+01,2.879499999999999886e+02,0.000000000000000000e+00,6.540087925170641192e+00,0.000000000000000000e+00,-1.000000009967787040e+00,0.000000000000000000e+00,-1.720846618830587156e-10,0.000000000000000000e+00 +4.171670497246169163e+01,2.879599999999999795e+02,0.000000000000000000e+00,6.538558893724260912e+00,0.000000000000000000e+00,-1.000000009968050163e+00,0.000000000000000000e+00,-1.283436926081071054e-10,0.000000000000000000e+00 +4.171823436145436403e+01,2.879700000000000273e+02,0.000000000000000000e+00,6.537029504716343808e+00,0.000000000000000000e+00,-1.000000009968246450e+00,0.000000000000000000e+00,1.512475643375850327e-10,0.000000000000000000e+00 +4.171976410825951120e+01,2.879800000000000182e+02,0.000000000000000000e+00,6.535499757895946615e+00,0.000000000000000000e+00,-1.000000009968015080e+00,0.000000000000000000e+00,1.136268037534310719e-10,0.000000000000000000e+00 +4.172129421312837394e+01,2.879900000000000091e+02,0.000000000000000000e+00,6.533969653011832968e+00,0.000000000000000000e+00,-1.000000009967841219e+00,0.000000000000000000e+00,-3.511015158672278092e-11,0.000000000000000000e+00 +4.172282467631247727e+01,2.880000000000000000e+02,0.000000000000000000e+00,6.532439189812471625e+00,0.000000000000000000e+00,-1.000000009967894954e+00,0.000000000000000000e+00,-8.818996704920107278e-11,0.000000000000000000e+00 +4.172435549806365174e+01,2.880099999999999909e+02,0.000000000000000000e+00,6.530908368046036472e+00,0.000000000000000000e+00,-1.000000009968029957e+00,0.000000000000000000e+00,1.603869183033105541e-10,0.000000000000000000e+00 +4.172588667863401923e+01,2.880199999999999818e+02,0.000000000000000000e+00,6.529377187460406518e+00,0.000000000000000000e+00,-1.000000009967784376e+00,0.000000000000000000e+00,-2.186317970818206177e-10,0.000000000000000000e+00 +4.172741821827599296e+01,2.880300000000000296e+02,0.000000000000000000e+00,6.527845647803165896e+00,0.000000000000000000e+00,-1.000000009968119219e+00,0.000000000000000000e+00,1.182769892828479654e-10,0.000000000000000000e+00 +4.172895011724228453e+01,2.880400000000000205e+02,0.000000000000000000e+00,6.526313748821601202e+00,0.000000000000000000e+00,-1.000000009967938031e+00,0.000000000000000000e+00,-1.353489995947615499e-10,0.000000000000000000e+00 +4.173048237578591113e+01,2.880500000000000114e+02,0.000000000000000000e+00,6.524781490262704153e+00,0.000000000000000000e+00,-1.000000009968145420e+00,0.000000000000000000e+00,-1.448792528227539129e-11,0.000000000000000000e+00 +4.173201499416016702e+01,2.880600000000000023e+02,0.000000000000000000e+00,6.523248871873168042e+00,0.000000000000000000e+00,-1.000000009968167625e+00,0.000000000000000000e+00,-6.764271860781367487e-11,0.000000000000000000e+00 +4.173354797261866622e+01,2.880699999999999932e+02,0.000000000000000000e+00,6.521715893399389508e+00,0.000000000000000000e+00,-1.000000009968271319e+00,0.000000000000000000e+00,2.922289670888027114e-10,0.000000000000000000e+00 +4.173508131141530697e+01,2.880799999999999841e+02,0.000000000000000000e+00,6.520182554587466761e+00,0.000000000000000000e+00,-1.000000009967823233e+00,0.000000000000000000e+00,-2.370001715292709309e-10,0.000000000000000000e+00 +4.173661501080428593e+01,2.880900000000000318e+02,0.000000000000000000e+00,6.518648855183200475e+00,0.000000000000000000e+00,-1.000000009968186720e+00,0.000000000000000000e+00,6.498964335526783758e-11,0.000000000000000000e+00 +4.173814907104010530e+01,2.881000000000000227e+02,0.000000000000000000e+00,6.517114794932090227e+00,0.000000000000000000e+00,-1.000000009968087022e+00,0.000000000000000000e+00,-1.024539847363374840e-10,0.000000000000000000e+00 +4.173968349237756570e+01,2.881100000000000136e+02,0.000000000000000000e+00,6.515580373579338058e+00,0.000000000000000000e+00,-1.000000009968244230e+00,0.000000000000000000e+00,2.256929173057590887e-10,0.000000000000000000e+00 +4.174121827507175908e+01,2.881200000000000045e+02,0.000000000000000000e+00,6.514045590869844915e+00,0.000000000000000000e+00,-1.000000009967897840e+00,0.000000000000000000e+00,-2.486376520384250683e-10,0.000000000000000000e+00 +4.174275341937809003e+01,2.881299999999999955e+02,0.000000000000000000e+00,6.512510446548212428e+00,0.000000000000000000e+00,-1.000000009968279535e+00,0.000000000000000000e+00,1.934838728674727607e-10,0.000000000000000000e+00 +4.174428892555225445e+01,2.881399999999999864e+02,0.000000000000000000e+00,6.510974940358739360e+00,0.000000000000000000e+00,-1.000000009967982439e+00,0.000000000000000000e+00,-1.211519107262720423e-10,0.000000000000000000e+00 +4.174582479385026090e+01,2.881500000000000341e+02,0.000000000000000000e+00,6.509439072045425156e+00,0.000000000000000000e+00,-1.000000009968168513e+00,0.000000000000000000e+00,1.490192787674001174e-10,0.000000000000000000e+00 +4.174736102452840925e+01,2.881600000000000250e+02,0.000000000000000000e+00,6.507902841351965506e+00,0.000000000000000000e+00,-1.000000009967939585e+00,0.000000000000000000e+00,-2.894424564742867067e-10,0.000000000000000000e+00 +4.174889761784330489e+01,2.881700000000000159e+02,0.000000000000000000e+00,6.506366248021755005e+00,0.000000000000000000e+00,-1.000000009968384340e+00,0.000000000000000000e+00,2.802724834696725030e-10,0.000000000000000000e+00 +4.175043457405185876e+01,2.881800000000000068e+02,0.000000000000000000e+00,6.504829291797883606e+00,0.000000000000000000e+00,-1.000000009967953574e+00,0.000000000000000000e+00,-1.857449853759813491e-10,0.000000000000000000e+00 +4.175197189341128023e+01,2.881899999999999977e+02,0.000000000000000000e+00,6.503291972423140166e+00,0.000000000000000000e+00,-1.000000009968239123e+00,0.000000000000000000e+00,2.945802629326800566e-11,0.000000000000000000e+00 +4.175350957617908421e+01,2.881999999999999886e+02,0.000000000000000000e+00,6.501754289640007123e+00,0.000000000000000000e+00,-1.000000009968193826e+00,0.000000000000000000e+00,1.154943570050194399e-11,0.000000000000000000e+00 +4.175504762261309821e+01,2.882099999999999795e+02,0.000000000000000000e+00,6.500216243190664045e+00,0.000000000000000000e+00,-1.000000009968176062e+00,0.000000000000000000e+00,-2.540274787857914403e-11,0.000000000000000000e+00 +4.175658603297144111e+01,2.882200000000000273e+02,0.000000000000000000e+00,6.498677832816984967e+00,0.000000000000000000e+00,-1.000000009968215142e+00,0.000000000000000000e+00,1.321784658361381921e-10,0.000000000000000000e+00 +4.175812480751255151e+01,2.882300000000000182e+02,0.000000000000000000e+00,6.497139058260538391e+00,0.000000000000000000e+00,-1.000000009968011749e+00,0.000000000000000000e+00,-5.150277190943990527e-11,0.000000000000000000e+00 +4.175966394649515934e+01,2.882400000000000091e+02,0.000000000000000000e+00,6.495599919262587285e+00,0.000000000000000000e+00,-1.000000009968091019e+00,0.000000000000000000e+00,-3.610109233312787256e-10,0.000000000000000000e+00 +4.176120345017831426e+01,2.882500000000000000e+02,0.000000000000000000e+00,6.494060415564087307e+00,0.000000000000000000e+00,-1.000000009968646797e+00,0.000000000000000000e+00,5.417485345054878593e-10,0.000000000000000000e+00 +4.176274331882136437e+01,2.882599999999999909e+02,0.000000000000000000e+00,6.492520546905686807e+00,0.000000000000000000e+00,-1.000000009967812575e+00,0.000000000000000000e+00,-4.986595263766607352e-10,0.000000000000000000e+00 +4.176428355268397041e+01,2.882699999999999818e+02,0.000000000000000000e+00,6.490980313027729487e+00,0.000000000000000000e+00,-1.000000009968580628e+00,0.000000000000000000e+00,4.782190794167197590e-10,0.000000000000000000e+00 +4.176582415202609866e+01,2.882800000000000296e+02,0.000000000000000000e+00,6.489439713670246412e+00,0.000000000000000000e+00,-1.000000009967843884e+00,0.000000000000000000e+00,-4.291134440517206338e-10,0.000000000000000000e+00 +4.176736511710802091e+01,2.882900000000000205e+02,0.000000000000000000e+00,6.487898748572964891e+00,0.000000000000000000e+00,-1.000000009968505132e+00,0.000000000000000000e+00,-1.051640127526956943e-11,0.000000000000000000e+00 +4.176890644819032161e+01,2.883000000000000114e+02,0.000000000000000000e+00,6.486357417475298703e+00,0.000000000000000000e+00,-1.000000009968521342e+00,0.000000000000000000e+00,4.539701632362755673e-10,0.000000000000000000e+00 +4.177044814553389784e+01,2.883100000000000023e+02,0.000000000000000000e+00,6.484815720116355209e+00,0.000000000000000000e+00,-1.000000009967821457e+00,0.000000000000000000e+00,-3.127502644438334542e-10,0.000000000000000000e+00 +4.177199020939995222e+01,2.883199999999999932e+02,0.000000000000000000e+00,6.483273656234931792e+00,0.000000000000000000e+00,-1.000000009968303738e+00,0.000000000000000000e+00,-2.241419734873637365e-10,0.000000000000000000e+00 +4.177353264004999289e+01,2.883299999999999841e+02,0.000000000000000000e+00,6.481731225569512311e+00,0.000000000000000000e+00,-1.000000009968649461e+00,0.000000000000000000e+00,5.621645852621373660e-10,0.000000000000000000e+00 +4.177507543774585486e+01,2.883400000000000318e+02,0.000000000000000000e+00,6.480188427858271538e+00,0.000000000000000000e+00,-1.000000009967782155e+00,0.000000000000000000e+00,-3.470604800880161602e-10,0.000000000000000000e+00 +4.177661860274967154e+01,2.883500000000000227e+02,0.000000000000000000e+00,6.478645262839074270e+00,0.000000000000000000e+00,-1.000000009968317727e+00,0.000000000000000000e+00,-1.206941963154846865e-10,0.000000000000000000e+00 +4.177816213532388900e+01,2.883600000000000136e+02,0.000000000000000000e+00,6.477101730249469114e+00,0.000000000000000000e+00,-1.000000009968504022e+00,0.000000000000000000e+00,-3.279108528035654808e-11,0.000000000000000000e+00 +4.177970603573127306e+01,2.883700000000000045e+02,0.000000000000000000e+00,6.475557829826694700e+00,0.000000000000000000e+00,-1.000000009968554648e+00,0.000000000000000000e+00,1.364531683313415387e-10,0.000000000000000000e+00 +4.178125030423489505e+01,2.883799999999999955e+02,0.000000000000000000e+00,6.474013561307676135e+00,0.000000000000000000e+00,-1.000000009968343928e+00,0.000000000000000000e+00,2.341719727321268636e-10,0.000000000000000000e+00 +4.178279494109814607e+01,2.883899999999999864e+02,0.000000000000000000e+00,6.472468924429024995e+00,0.000000000000000000e+00,-1.000000009967982217e+00,0.000000000000000000e+00,-2.632907907152753606e-10,0.000000000000000000e+00 +4.178433994658472983e+01,2.884000000000000341e+02,0.000000000000000000e+00,6.470923918927038443e+00,0.000000000000000000e+00,-1.000000009968389003e+00,0.000000000000000000e+00,-1.968462230756982655e-11,0.000000000000000000e+00 +4.178588532095866270e+01,2.884100000000000250e+02,0.000000000000000000e+00,6.469378544537697451e+00,0.000000000000000000e+00,-1.000000009968419423e+00,0.000000000000000000e+00,7.010074142797853486e-11,0.000000000000000000e+00 +4.178743106448428080e+01,2.884200000000000159e+02,0.000000000000000000e+00,6.467832800996669462e+00,0.000000000000000000e+00,-1.000000009968311065e+00,0.000000000000000000e+00,-1.447636558050611788e-10,0.000000000000000000e+00 +4.178897717742623286e+01,2.884300000000000068e+02,0.000000000000000000e+00,6.466286688039305730e+00,0.000000000000000000e+00,-1.000000009968534886e+00,0.000000000000000000e+00,3.009445336961210786e-10,0.000000000000000000e+00 +4.179052366004948027e+01,2.884399999999999977e+02,0.000000000000000000e+00,6.464740205400640427e+00,0.000000000000000000e+00,-1.000000009968069481e+00,0.000000000000000000e+00,-2.280947028228478900e-10,0.000000000000000000e+00 +4.179207051261931127e+01,2.884499999999999886e+02,0.000000000000000000e+00,6.463193352815392423e+00,0.000000000000000000e+00,-1.000000009968422310e+00,0.000000000000000000e+00,-2.454050436931769691e-11,0.000000000000000000e+00 +4.179361773540131964e+01,2.884599999999999795e+02,0.000000000000000000e+00,6.461646130017960843e+00,0.000000000000000000e+00,-1.000000009968460279e+00,0.000000000000000000e+00,2.137812756536741444e-11,0.000000000000000000e+00 +4.179516532866142597e+01,2.884700000000000273e+02,0.000000000000000000e+00,6.460098536742428621e+00,0.000000000000000000e+00,-1.000000009968427195e+00,0.000000000000000000e+00,1.318241195150958071e-10,0.000000000000000000e+00 +4.179671329266586355e+01,2.884800000000000182e+02,0.000000000000000000e+00,6.458550572722559835e+00,0.000000000000000000e+00,-1.000000009968223136e+00,0.000000000000000000e+00,-2.098068271981358202e-10,0.000000000000000000e+00 +4.179826162768119246e+01,2.884900000000000091e+02,0.000000000000000000e+00,6.457002237691799706e+00,0.000000000000000000e+00,-1.000000009968547987e+00,0.000000000000000000e+00,-3.957129329996559344e-11,0.000000000000000000e+00 +4.179981033397427836e+01,2.885000000000000000e+02,0.000000000000000000e+00,6.455453531383272825e+00,0.000000000000000000e+00,-1.000000009968609271e+00,0.000000000000000000e+00,1.262824192138337198e-10,0.000000000000000000e+00 +4.180135941181232084e+01,2.885099999999999909e+02,0.000000000000000000e+00,6.453904453529784924e+00,0.000000000000000000e+00,-1.000000009968413650e+00,0.000000000000000000e+00,1.418724117961841899e-10,0.000000000000000000e+00 +4.180290886146283924e+01,2.885199999999999818e+02,0.000000000000000000e+00,6.452355003863821103e+00,0.000000000000000000e+00,-1.000000009968193826e+00,0.000000000000000000e+00,-1.372536771726893469e-10,0.000000000000000000e+00 +4.180445868319366554e+01,2.885300000000000296e+02,0.000000000000000000e+00,6.450805182117544945e+00,0.000000000000000000e+00,-1.000000009968406545e+00,0.000000000000000000e+00,-1.160216855370424249e-10,0.000000000000000000e+00 +4.180600887727295856e+01,2.885400000000000205e+02,0.000000000000000000e+00,6.449254988022797619e+00,0.000000000000000000e+00,-1.000000009968586401e+00,0.000000000000000000e+00,6.143375563509367834e-11,0.000000000000000000e+00 +4.180755944396920398e+01,2.885500000000000114e+02,0.000000000000000000e+00,6.447704421311098777e+00,0.000000000000000000e+00,-1.000000009968491144e+00,0.000000000000000000e+00,2.514026534466371336e-10,0.000000000000000000e+00 +4.180911038355119302e+01,2.885600000000000023e+02,0.000000000000000000e+00,6.446153481713645661e+00,0.000000000000000000e+00,-1.000000009968101233e+00,0.000000000000000000e+00,-4.268236804543266612e-10,0.000000000000000000e+00 +4.181066169628806506e+01,2.885699999999999932e+02,0.000000000000000000e+00,6.444602168961312216e+00,0.000000000000000000e+00,-1.000000009968763370e+00,0.000000000000000000e+00,4.680765485137173642e-10,0.000000000000000000e+00 +4.181221338244926500e+01,2.885799999999999841e+02,0.000000000000000000e+00,6.443050482784646427e+00,0.000000000000000000e+00,-1.000000009968037062e+00,0.000000000000000000e+00,-5.263341479581009983e-10,0.000000000000000000e+00 +4.181376544230456460e+01,2.885900000000000318e+02,0.000000000000000000e+00,6.441498422913875643e+00,0.000000000000000000e+00,-1.000000009968853965e+00,0.000000000000000000e+00,1.373087973543478754e-10,0.000000000000000000e+00 +4.181531787612406958e+01,2.886000000000000227e+02,0.000000000000000000e+00,6.439945989078897703e+00,0.000000000000000000e+00,-1.000000009968640802e+00,0.000000000000000000e+00,1.056736939270953592e-10,0.000000000000000000e+00 +4.181687068417819830e+01,2.886100000000000136e+02,0.000000000000000000e+00,6.438393181009288924e+00,0.000000000000000000e+00,-1.000000009968476711e+00,0.000000000000000000e+00,-2.373153380580510359e-11,0.000000000000000000e+00 +4.181842386673770307e+01,2.886200000000000045e+02,0.000000000000000000e+00,6.436839998434297883e+00,0.000000000000000000e+00,-1.000000009968513570e+00,0.000000000000000000e+00,-2.215361671347873317e-11,0.000000000000000000e+00 +4.181997742407367014e+01,2.886299999999999955e+02,0.000000000000000000e+00,6.435286441082846309e+00,0.000000000000000000e+00,-1.000000009968547987e+00,0.000000000000000000e+00,3.393686509050421634e-10,0.000000000000000000e+00 +4.182153135645749842e+01,2.886399999999999864e+02,0.000000000000000000e+00,6.433732508683529083e+00,0.000000000000000000e+00,-1.000000009968020631e+00,0.000000000000000000e+00,-5.482873126256256229e-10,0.000000000000000000e+00 +4.182308566416092077e+01,2.886500000000000341e+02,0.000000000000000000e+00,6.432178200964614234e+00,0.000000000000000000e+00,-1.000000009968872838e+00,0.000000000000000000e+00,1.184003057508245924e-10,0.000000000000000000e+00 +4.182464034745599690e+01,2.886600000000000250e+02,0.000000000000000000e+00,6.430623517654038501e+00,0.000000000000000000e+00,-1.000000009968688763e+00,0.000000000000000000e+00,3.636823753142523374e-10,0.000000000000000000e+00 +4.182619540661512048e+01,2.886700000000000159e+02,0.000000000000000000e+00,6.429068458479413550e+00,0.000000000000000000e+00,-1.000000009968123216e+00,0.000000000000000000e+00,-3.153435784670982460e-10,0.000000000000000000e+00 +4.182775084191101200e+01,2.886800000000000068e+02,0.000000000000000000e+00,6.427513023168020645e+00,0.000000000000000000e+00,-1.000000009968613712e+00,0.000000000000000000e+00,1.482855178885150237e-10,0.000000000000000000e+00 +4.182930665361671174e+01,2.886899999999999977e+02,0.000000000000000000e+00,6.425957211446808870e+00,0.000000000000000000e+00,-1.000000009968383008e+00,0.000000000000000000e+00,-2.160249583245225999e-10,0.000000000000000000e+00 +4.183086284200560812e+01,2.886999999999999886e+02,0.000000000000000000e+00,6.424401023042399572e+00,0.000000000000000000e+00,-1.000000009968719183e+00,0.000000000000000000e+00,-7.617529154801164514e-11,0.000000000000000000e+00 +4.183241940735140929e+01,2.887099999999999795e+02,0.000000000000000000e+00,6.422844457681081032e+00,0.000000000000000000e+00,-1.000000009968837755e+00,0.000000000000000000e+00,4.335520198706196669e-10,0.000000000000000000e+00 +4.183397634992815739e+01,2.887200000000000273e+02,0.000000000000000000e+00,6.421287515088811126e+00,0.000000000000000000e+00,-1.000000009968162740e+00,0.000000000000000000e+00,-2.865882621289841155e-10,0.000000000000000000e+00 +4.183553367001022849e+01,2.887300000000000182e+02,0.000000000000000000e+00,6.419730194991216443e+00,0.000000000000000000e+00,-1.000000009968609049e+00,0.000000000000000000e+00,-1.710559745846542467e-10,0.000000000000000000e+00 +4.183709136787232552e+01,2.887400000000000091e+02,0.000000000000000000e+00,6.418172497113587838e+00,0.000000000000000000e+00,-1.000000009968875503e+00,0.000000000000000000e+00,2.801787053324858976e-10,0.000000000000000000e+00 +4.183864944378949957e+01,2.887500000000000000e+02,0.000000000000000000e+00,6.416614421180884875e+00,0.000000000000000000e+00,-1.000000009968438963e+00,0.000000000000000000e+00,-1.622818285468292016e-10,0.000000000000000000e+00 +4.184020789803711438e+01,2.887599999999999909e+02,0.000000000000000000e+00,6.415055966917734054e+00,0.000000000000000000e+00,-1.000000009968691872e+00,0.000000000000000000e+00,-1.666581424263069122e-10,0.000000000000000000e+00 +4.184176673089088183e+01,2.887699999999999818e+02,0.000000000000000000e+00,6.413497134048425252e+00,0.000000000000000000e+00,-1.000000009968951664e+00,0.000000000000000000e+00,5.015618344232598763e-10,0.000000000000000000e+00 +4.184332594262684779e+01,2.887800000000000296e+02,0.000000000000000000e+00,6.411937922296914394e+00,0.000000000000000000e+00,-1.000000009968169623e+00,0.000000000000000000e+00,-4.807957224261344830e-10,0.000000000000000000e+00 +4.184488553352139206e+01,2.887900000000000205e+02,0.000000000000000000e+00,6.410378331386823447e+00,0.000000000000000000e+00,-1.000000009968919468e+00,0.000000000000000000e+00,4.096516201308748170e-10,0.000000000000000000e+00 +4.184644550385122841e+01,2.888000000000000114e+02,0.000000000000000000e+00,6.408818361041434208e+00,0.000000000000000000e+00,-1.000000009968280423e+00,0.000000000000000000e+00,-2.422020106805371658e-10,0.000000000000000000e+00 +4.184800585389341165e+01,2.888100000000000023e+02,0.000000000000000000e+00,6.407258010983696295e+00,0.000000000000000000e+00,-1.000000009968658343e+00,0.000000000000000000e+00,-1.038568863802180270e-11,0.000000000000000000e+00 +4.184956658392533058e+01,2.888199999999999932e+02,0.000000000000000000e+00,6.405697280936218263e+00,0.000000000000000000e+00,-1.000000009968674552e+00,0.000000000000000000e+00,-1.177706232228279056e-10,0.000000000000000000e+00 +4.185112769422471501e+01,2.888299999999999841e+02,0.000000000000000000e+00,6.404136170621272939e+00,0.000000000000000000e+00,-1.000000009968858405e+00,0.000000000000000000e+00,3.796750375330848423e-11,0.000000000000000000e+00 +4.185268918506962876e+01,2.888400000000000318e+02,0.000000000000000000e+00,6.402574679760793863e+00,0.000000000000000000e+00,-1.000000009968799120e+00,0.000000000000000000e+00,-3.468843483260006015e-11,0.000000000000000000e+00 +4.185425105673847668e+01,2.888500000000000227e+02,0.000000000000000000e+00,6.401012808076376182e+00,0.000000000000000000e+00,-1.000000009968853298e+00,0.000000000000000000e+00,2.662114304447416849e-10,0.000000000000000000e+00 +4.185581330951000467e+01,2.888600000000000136e+02,0.000000000000000000e+00,6.399450555289274867e+00,0.000000000000000000e+00,-1.000000009968437409e+00,0.000000000000000000e+00,-2.768036840118061393e-10,0.000000000000000000e+00 +4.185737594366329972e+01,2.888700000000000045e+02,0.000000000000000000e+00,6.397887921120405608e+00,0.000000000000000000e+00,-1.000000009968869952e+00,0.000000000000000000e+00,3.082737795885588478e-11,0.000000000000000000e+00 +4.185893895947778276e+01,2.888799999999999955e+02,0.000000000000000000e+00,6.396324905290341256e+00,0.000000000000000000e+00,-1.000000009968821768e+00,0.000000000000000000e+00,3.360357486918307662e-10,0.000000000000000000e+00 +4.186050235723322288e+01,2.888899999999999864e+02,0.000000000000000000e+00,6.394761507519315380e+00,0.000000000000000000e+00,-1.000000009968296411e+00,0.000000000000000000e+00,-2.110004526695009085e-10,0.000000000000000000e+00 +4.186206613720973024e+01,2.889000000000000341e+02,0.000000000000000000e+00,6.393197727527219598e+00,0.000000000000000000e+00,-1.000000009968626369e+00,0.000000000000000000e+00,-2.800821600515136389e-10,0.000000000000000000e+00 +4.186363029968775606e+01,2.889100000000000250e+02,0.000000000000000000e+00,6.391633565033600917e+00,0.000000000000000000e+00,-1.000000009969064463e+00,0.000000000000000000e+00,3.680057555162569294e-10,0.000000000000000000e+00 +4.186519484494809262e+01,2.889200000000000159e+02,0.000000000000000000e+00,6.390069019757664393e+00,0.000000000000000000e+00,-1.000000009968488701e+00,0.000000000000000000e+00,-2.031836662540026347e-10,0.000000000000000000e+00 +4.186675977327188036e+01,2.889300000000000068e+02,0.000000000000000000e+00,6.388504091418273134e+00,0.000000000000000000e+00,-1.000000009968806669e+00,0.000000000000000000e+00,6.184803300298395740e-11,0.000000000000000000e+00 +4.186832508494060789e+01,2.889399999999999977e+02,0.000000000000000000e+00,6.386938779733942972e+00,0.000000000000000000e+00,-1.000000009968709858e+00,0.000000000000000000e+00,-4.609102218585751343e-11,0.000000000000000000e+00 +4.186989078023609778e+01,2.889499999999999886e+02,0.000000000000000000e+00,6.385373084422846901e+00,0.000000000000000000e+00,-1.000000009968782022e+00,0.000000000000000000e+00,7.741393535309614285e-11,0.000000000000000000e+00 +4.187145685944052076e+01,2.889599999999999795e+02,0.000000000000000000e+00,6.383807005202811524e+00,0.000000000000000000e+00,-1.000000009968660786e+00,0.000000000000000000e+00,-4.109303232820538632e-10,0.000000000000000000e+00 +4.187302332283639572e+01,2.889700000000000273e+02,0.000000000000000000e+00,6.382240541791317945e+00,0.000000000000000000e+00,-1.000000009969304493e+00,0.000000000000000000e+00,5.400728465502593398e-10,0.000000000000000000e+00 +4.187459017070659684e+01,2.889800000000000182e+02,0.000000000000000000e+00,6.380673693905499100e+00,0.000000000000000000e+00,-1.000000009968458281e+00,0.000000000000000000e+00,-8.174902358123399317e-11,0.000000000000000000e+00 +4.187615740333433223e+01,2.889900000000000091e+02,0.000000000000000000e+00,6.379106461262144201e+00,0.000000000000000000e+00,-1.000000009968586401e+00,0.000000000000000000e+00,-2.240817847213685595e-10,0.000000000000000000e+00 +4.187772502100315819e+01,2.890000000000000000e+02,0.000000000000000000e+00,6.377538843577690741e+00,0.000000000000000000e+00,-1.000000009968937675e+00,0.000000000000000000e+00,-4.673123706623623208e-12,0.000000000000000000e+00 +4.187929302399698628e+01,2.890099999999999909e+02,0.000000000000000000e+00,6.375970840568228937e+00,0.000000000000000000e+00,-1.000000009968945003e+00,0.000000000000000000e+00,9.796989490047845885e-11,0.000000000000000000e+00 +4.188086141260007622e+01,2.890199999999999818e+02,0.000000000000000000e+00,6.374402451949500836e+00,0.000000000000000000e+00,-1.000000009968791348e+00,0.000000000000000000e+00,-3.212961800153150130e-11,0.000000000000000000e+00 +4.188243018709704302e+01,2.890300000000000296e+02,0.000000000000000000e+00,6.372833677436898547e+00,0.000000000000000000e+00,-1.000000009968841752e+00,0.000000000000000000e+00,-1.491466216312018583e-10,0.000000000000000000e+00 +4.188399934777283562e+01,2.890400000000000205e+02,0.000000000000000000e+00,6.371264516745463347e+00,0.000000000000000000e+00,-1.000000009969075787e+00,0.000000000000000000e+00,3.528274051759080539e-10,0.000000000000000000e+00 +4.188556889491276536e+01,2.890500000000000114e+02,0.000000000000000000e+00,6.369694969589885680e+00,0.000000000000000000e+00,-1.000000009968522008e+00,0.000000000000000000e+00,-8.288128521671095577e-11,0.000000000000000000e+00 +4.188713882880249173e+01,2.890600000000000023e+02,0.000000000000000000e+00,6.368125035684506052e+00,0.000000000000000000e+00,-1.000000009968652126e+00,0.000000000000000000e+00,-1.278263058126237257e-10,0.000000000000000000e+00 +4.188870914972803661e+01,2.890699999999999932e+02,0.000000000000000000e+00,6.366554714743310583e+00,0.000000000000000000e+00,-1.000000009968852854e+00,0.000000000000000000e+00,-2.554482041348374235e-10,0.000000000000000000e+00 +4.189027985797575582e+01,2.890799999999999841e+02,0.000000000000000000e+00,6.364984006479933676e+00,0.000000000000000000e+00,-1.000000009969254089e+00,0.000000000000000000e+00,1.410483738354833907e-10,0.000000000000000000e+00 +4.189185095383236757e+01,2.890900000000000318e+02,0.000000000000000000e+00,6.363412910607656237e+00,0.000000000000000000e+00,-1.000000009969032488e+00,0.000000000000000000e+00,2.300301331297053050e-10,0.000000000000000000e+00 +4.189342243758495243e+01,2.891000000000000227e+02,0.000000000000000000e+00,6.361841426839406566e+00,0.000000000000000000e+00,-1.000000009968671000e+00,0.000000000000000000e+00,-9.958918591838686845e-11,0.000000000000000000e+00 +4.189499430952093206e+01,2.891100000000000136e+02,0.000000000000000000e+00,6.360269554887757693e+00,0.000000000000000000e+00,-1.000000009968827541e+00,0.000000000000000000e+00,1.203248536533056786e-10,0.000000000000000000e+00 +4.189656656992809047e+01,2.891200000000000045e+02,0.000000000000000000e+00,6.358697294464926486e+00,0.000000000000000000e+00,-1.000000009968638359e+00,0.000000000000000000e+00,-2.986199016462202871e-10,0.000000000000000000e+00 +4.189813921909456695e+01,2.891299999999999955e+02,0.000000000000000000e+00,6.357124645282775433e+00,0.000000000000000000e+00,-1.000000009969107984e+00,0.000000000000000000e+00,-2.921940026764456846e-11,0.000000000000000000e+00 +4.189971225730884896e+01,2.891399999999999864e+02,0.000000000000000000e+00,6.355551607052809082e+00,0.000000000000000000e+00,-1.000000009969153947e+00,0.000000000000000000e+00,1.011841833044449853e-10,0.000000000000000000e+00 +4.190128568485979343e+01,2.891500000000000341e+02,0.000000000000000000e+00,6.353978179486176714e+00,0.000000000000000000e+00,-1.000000009968994741e+00,0.000000000000000000e+00,3.426994909621488485e-10,0.000000000000000000e+00 +4.190285950203661258e+01,2.891600000000000250e+02,0.000000000000000000e+00,6.352404362293669671e+00,0.000000000000000000e+00,-1.000000009968455394e+00,0.000000000000000000e+00,-4.869105087709824120e-10,0.000000000000000000e+00 +4.190443370912886678e+01,2.891700000000000159e+02,0.000000000000000000e+00,6.350830155185721360e+00,0.000000000000000000e+00,-1.000000009969221892e+00,0.000000000000000000e+00,3.724252559643812684e-10,0.000000000000000000e+00 +4.190600830642648589e+01,2.891800000000000068e+02,0.000000000000000000e+00,6.349255557872403699e+00,0.000000000000000000e+00,-1.000000009968635473e+00,0.000000000000000000e+00,-4.111029118626581186e-10,0.000000000000000000e+00 +4.190758329421975503e+01,2.891899999999999977e+02,0.000000000000000000e+00,6.347680570063433336e+00,0.000000000000000000e+00,-1.000000009969282955e+00,0.000000000000000000e+00,2.804841766496364567e-10,0.000000000000000000e+00 +4.190915867279932172e+01,2.891999999999999886e+02,0.000000000000000000e+00,6.346105191468162765e+00,0.000000000000000000e+00,-1.000000009968841086e+00,0.000000000000000000e+00,-1.640213840940805408e-10,0.000000000000000000e+00 +4.191073444245618873e+01,2.892099999999999795e+02,0.000000000000000000e+00,6.344529421795587432e+00,0.000000000000000000e+00,-1.000000009969099546e+00,0.000000000000000000e+00,2.972501595974439435e-10,0.000000000000000000e+00 +4.191231060348172122e+01,2.892200000000000273e+02,0.000000000000000000e+00,6.342953260754338629e+00,0.000000000000000000e+00,-1.000000009968631032e+00,0.000000000000000000e+00,-2.274595959610049821e-10,0.000000000000000000e+00 +4.191388715616765381e+01,2.892300000000000182e+02,0.000000000000000000e+00,6.341376708052687938e+00,0.000000000000000000e+00,-1.000000009968989634e+00,0.000000000000000000e+00,-5.421063670408365037e-11,0.000000000000000000e+00 +4.191546410080607643e+01,2.892400000000000091e+02,0.000000000000000000e+00,6.339799763398541899e+00,0.000000000000000000e+00,-1.000000009969075121e+00,0.000000000000000000e+00,-5.630873335070544414e-13,0.000000000000000000e+00 +4.191704143768944846e+01,2.892500000000000000e+02,0.000000000000000000e+00,6.338222426499445561e+00,0.000000000000000000e+00,-1.000000009969076009e+00,0.000000000000000000e+00,1.877429038221802716e-10,0.000000000000000000e+00 +4.191861916711058456e+01,2.892599999999999909e+02,0.000000000000000000e+00,6.336644697062579823e+00,0.000000000000000000e+00,-1.000000009968779802e+00,0.000000000000000000e+00,-3.032123290707091817e-10,0.000000000000000000e+00 +4.192019728936266887e+01,2.892699999999999818e+02,0.000000000000000000e+00,6.335066574794761429e+00,0.000000000000000000e+00,-1.000000009969258308e+00,0.000000000000000000e+00,2.081867685065629538e-10,0.000000000000000000e+00 +4.192177580473925502e+01,2.892800000000000296e+02,0.000000000000000000e+00,6.333488059402440307e+00,0.000000000000000000e+00,-1.000000009968929682e+00,0.000000000000000000e+00,-1.610232797769793729e-10,0.000000000000000000e+00 +4.192335471353425191e+01,2.892900000000000205e+02,0.000000000000000000e+00,6.331909150591703117e+00,0.000000000000000000e+00,-1.000000009969183923e+00,0.000000000000000000e+00,2.717732791722440984e-10,0.000000000000000000e+00 +4.192493401604194503e+01,2.893000000000000114e+02,0.000000000000000000e+00,6.330329848068267928e+00,0.000000000000000000e+00,-1.000000009968754711e+00,0.000000000000000000e+00,-3.737531854233982371e-10,0.000000000000000000e+00 +4.192651371255697512e+01,2.893100000000000023e+02,0.000000000000000000e+00,6.328750151537487767e+00,0.000000000000000000e+00,-1.000000009969345127e+00,0.000000000000000000e+00,2.963703520285090670e-10,0.000000000000000000e+00 +4.192809380337436664e+01,2.893199999999999932e+02,0.000000000000000000e+00,6.327170060704345289e+00,0.000000000000000000e+00,-1.000000009968876835e+00,0.000000000000000000e+00,-3.068332124506920270e-10,0.000000000000000000e+00 +4.192967428878949931e+01,2.893299999999999841e+02,0.000000000000000000e+00,6.325589575273458109e+00,0.000000000000000000e+00,-1.000000009969361781e+00,0.000000000000000000e+00,2.092798926857642276e-10,0.000000000000000000e+00 +4.193125516909812234e+01,2.893400000000000318e+02,0.000000000000000000e+00,6.324008694949071696e+00,0.000000000000000000e+00,-1.000000009969030934e+00,0.000000000000000000e+00,-2.948845225646102023e-11,0.000000000000000000e+00 +4.193283644459636861e+01,2.893500000000000227e+02,0.000000000000000000e+00,6.322427419435064699e+00,0.000000000000000000e+00,-1.000000009969077563e+00,0.000000000000000000e+00,3.022512514504181917e-10,0.000000000000000000e+00 +4.193441811558071919e+01,2.893600000000000136e+02,0.000000000000000000e+00,6.320845748434943623e+00,0.000000000000000000e+00,-1.000000009968599501e+00,0.000000000000000000e+00,-3.107370469165308193e-10,0.000000000000000000e+00 +4.193600018234804594e+01,2.893700000000000045e+02,0.000000000000000000e+00,6.319263681651845488e+00,0.000000000000000000e+00,-1.000000009969091108e+00,0.000000000000000000e+00,-1.884441741419535408e-10,0.000000000000000000e+00 +4.193758264519558310e+01,2.893799999999999955e+02,0.000000000000000000e+00,6.317681218788533393e+00,0.000000000000000000e+00,-1.000000009969389314e+00,0.000000000000000000e+00,2.195393002369717700e-10,0.000000000000000000e+00 +4.193916550442093438e+01,2.893899999999999864e+02,0.000000000000000000e+00,6.316098359547400065e+00,0.000000000000000000e+00,-1.000000009969041814e+00,0.000000000000000000e+00,1.109342351846452407e-10,0.000000000000000000e+00 +4.194074876032208721e+01,2.894000000000000341e+02,0.000000000000000000e+00,6.314515103630466086e+00,0.000000000000000000e+00,-1.000000009968866177e+00,0.000000000000000000e+00,-2.518178804615870802e-10,0.000000000000000000e+00 +4.194233241319739136e+01,2.894100000000000250e+02,0.000000000000000000e+00,6.312931450739377226e+00,0.000000000000000000e+00,-1.000000009969264969e+00,0.000000000000000000e+00,1.010663458696623564e-10,0.000000000000000000e+00 +4.194391646334557322e+01,2.894200000000000159e+02,0.000000000000000000e+00,6.311347400575404443e+00,0.000000000000000000e+00,-1.000000009969104875e+00,0.000000000000000000e+00,1.639638748923305035e-11,0.000000000000000000e+00 +4.194550091106573575e+01,2.894300000000000068e+02,0.000000000000000000e+00,6.309762952839445660e+00,0.000000000000000000e+00,-1.000000009969078896e+00,0.000000000000000000e+00,-2.428017608584633547e-10,0.000000000000000000e+00 +4.194708575665735850e+01,2.894399999999999977e+02,0.000000000000000000e+00,6.308178107232022214e+00,0.000000000000000000e+00,-1.000000009969463699e+00,0.000000000000000000e+00,2.941463522795839202e-10,0.000000000000000000e+00 +4.194867100042029762e+01,2.894499999999999886e+02,0.000000000000000000e+00,6.306592863453278852e+00,0.000000000000000000e+00,-1.000000009968997405e+00,0.000000000000000000e+00,-2.299366359934725688e-10,0.000000000000000000e+00 +4.195025664265478582e+01,2.894599999999999795e+02,0.000000000000000000e+00,6.305007221202985512e+00,0.000000000000000000e+00,-1.000000009969362003e+00,0.000000000000000000e+00,2.165788919583859621e-10,0.000000000000000000e+00 +4.195184268366142533e+01,2.894700000000000273e+02,0.000000000000000000e+00,6.303421180180531991e+00,0.000000000000000000e+00,-1.000000009969018500e+00,0.000000000000000000e+00,-2.207233329697344110e-10,0.000000000000000000e+00 +4.195342912374120914e+01,2.894800000000000182e+02,0.000000000000000000e+00,6.301834740084932385e+00,0.000000000000000000e+00,-1.000000009969368664e+00,0.000000000000000000e+00,1.355910464604881286e-10,0.000000000000000000e+00 +4.195501596319549975e+01,2.894900000000000091e+02,0.000000000000000000e+00,6.300247900614819763e+00,0.000000000000000000e+00,-1.000000009969153503e+00,0.000000000000000000e+00,1.396138183909731884e-10,0.000000000000000000e+00 +4.195660320232604334e+01,2.895000000000000000e+02,0.000000000000000000e+00,6.298660661468449717e+00,0.000000000000000000e+00,-1.000000009968931902e+00,0.000000000000000000e+00,-2.937025598078456421e-10,0.000000000000000000e+00 +4.195819084143496980e+01,2.895099999999999909e+02,0.000000000000000000e+00,6.297073022343696813e+00,0.000000000000000000e+00,-1.000000009969398196e+00,0.000000000000000000e+00,1.586992288773480041e-10,0.000000000000000000e+00 +4.195977888082477847e+01,2.895199999999999818e+02,0.000000000000000000e+00,6.295484982938053697e+00,0.000000000000000000e+00,-1.000000009969146175e+00,0.000000000000000000e+00,2.795756951695895194e-12,0.000000000000000000e+00 +4.196136732079835951e+01,2.895300000000000296e+02,0.000000000000000000e+00,6.293896542948633765e+00,0.000000000000000000e+00,-1.000000009969141734e+00,0.000000000000000000e+00,-1.410103503259912280e-10,0.000000000000000000e+00 +4.196295616165898679e+01,2.895400000000000205e+02,0.000000000000000000e+00,6.292307702072166720e+00,0.000000000000000000e+00,-1.000000009969365777e+00,0.000000000000000000e+00,3.467783330833444478e-10,0.000000000000000000e+00 +4.196454540371031072e+01,2.895500000000000114e+02,0.000000000000000000e+00,6.290718460004999457e+00,0.000000000000000000e+00,-1.000000009968814663e+00,0.000000000000000000e+00,-3.753255595658407690e-10,0.000000000000000000e+00 +4.196613504725636545e+01,2.895600000000000023e+02,0.000000000000000000e+00,6.289128816443096959e+00,0.000000000000000000e+00,-1.000000009969411296e+00,0.000000000000000000e+00,7.177841014120449624e-11,0.000000000000000000e+00 +4.196772509260157591e+01,2.895699999999999932e+02,0.000000000000000000e+00,6.287538771082036959e+00,0.000000000000000000e+00,-1.000000009969297166e+00,0.000000000000000000e+00,1.995046995134914818e-10,0.000000000000000000e+00 +4.196931554005074361e+01,2.895799999999999841e+02,0.000000000000000000e+00,6.285948323617015276e+00,0.000000000000000000e+00,-1.000000009968979864e+00,0.000000000000000000e+00,-4.233342846389300649e-10,0.000000000000000000e+00 +4.197090638990906086e+01,2.895900000000000318e+02,0.000000000000000000e+00,6.284357473742841371e+00,0.000000000000000000e+00,-1.000000009969653325e+00,0.000000000000000000e+00,2.288468582842430906e-10,0.000000000000000000e+00 +4.197249764248210369e+01,2.896000000000000227e+02,0.000000000000000000e+00,6.282766221153936570e+00,0.000000000000000000e+00,-1.000000009969289172e+00,0.000000000000000000e+00,-2.985416294902659560e-11,0.000000000000000000e+00 +4.197408929807583178e+01,2.896100000000000136e+02,0.000000000000000000e+00,6.281174565544338506e+00,0.000000000000000000e+00,-1.000000009969336690e+00,0.000000000000000000e+00,1.253836131459431679e-10,0.000000000000000000e+00 +4.197568135699660274e+01,2.896200000000000045e+02,0.000000000000000000e+00,6.279582506607694903e+00,0.000000000000000000e+00,-1.000000009969137071e+00,0.000000000000000000e+00,-8.575236613159136553e-11,0.000000000000000000e+00 +4.197727381955115789e+01,2.896299999999999955e+02,0.000000000000000000e+00,6.277990044037266237e+00,0.000000000000000000e+00,-1.000000009969273629e+00,0.000000000000000000e+00,-3.945002507915843006e-11,0.000000000000000000e+00 +4.197886668604662219e+01,2.896399999999999864e+02,0.000000000000000000e+00,6.276397177525923077e+00,0.000000000000000000e+00,-1.000000009969336467e+00,0.000000000000000000e+00,1.859115935602857630e-10,0.000000000000000000e+00 +4.198045995679051146e+01,2.896500000000000341e+02,0.000000000000000000e+00,6.274803906766146966e+00,0.000000000000000000e+00,-1.000000009969040260e+00,0.000000000000000000e+00,-1.851677565077249745e-10,0.000000000000000000e+00 +4.198205363209073937e+01,2.896600000000000250e+02,0.000000000000000000e+00,6.273210231450029539e+00,0.000000000000000000e+00,-1.000000009969335357e+00,0.000000000000000000e+00,-1.791311178865825959e-10,0.000000000000000000e+00 +4.198364771225561043e+01,2.896700000000000159e+02,0.000000000000000000e+00,6.271616151269269857e+00,0.000000000000000000e+00,-1.000000009969620907e+00,0.000000000000000000e+00,4.775151781256053769e-10,0.000000000000000000e+00 +4.198524219759380571e+01,2.896800000000000068e+02,0.000000000000000000e+00,6.270021665915176179e+00,0.000000000000000000e+00,-1.000000009968859516e+00,0.000000000000000000e+00,-3.853677370824916353e-10,0.000000000000000000e+00 +4.198683708841441842e+01,2.896899999999999977e+02,0.000000000000000000e+00,6.268426775078665969e+00,0.000000000000000000e+00,-1.000000009969474135e+00,0.000000000000000000e+00,-4.746277882498761245e-11,0.000000000000000000e+00 +4.198843238502691833e+01,2.896999999999999886e+02,0.000000000000000000e+00,6.266831478450259674e+00,0.000000000000000000e+00,-1.000000009969549852e+00,0.000000000000000000e+00,3.697258330213579497e-10,0.000000000000000000e+00 +4.199002808774118023e+01,2.897099999999999795e+02,0.000000000000000000e+00,6.265235775720086941e+00,0.000000000000000000e+00,-1.000000009968959880e+00,0.000000000000000000e+00,-2.519394024475890985e-10,0.000000000000000000e+00 +4.199162419686746972e+01,2.897200000000000273e+02,0.000000000000000000e+00,6.263639666577883069e+00,0.000000000000000000e+00,-1.000000009969362003e+00,0.000000000000000000e+00,-2.403315178833094721e-10,0.000000000000000000e+00 +4.199322071271645029e+01,2.897300000000000182e+02,0.000000000000000000e+00,6.262043150712985451e+00,0.000000000000000000e+00,-1.000000009969745696e+00,0.000000000000000000e+00,3.319011066150045115e-10,0.000000000000000000e+00 +4.199481763559917624e+01,2.897400000000000091e+02,0.000000000000000000e+00,6.260446227814337128e+00,0.000000000000000000e+00,-1.000000009969215675e+00,0.000000000000000000e+00,1.807127802102268154e-12,0.000000000000000000e+00 +4.199641496582710687e+01,2.897500000000000000e+02,0.000000000000000000e+00,6.258848897570485903e+00,0.000000000000000000e+00,-1.000000009969212789e+00,0.000000000000000000e+00,-2.555738536942825155e-10,0.000000000000000000e+00 +4.199801270371208517e+01,2.897599999999999909e+02,0.000000000000000000e+00,6.257251159669579899e+00,0.000000000000000000e+00,-1.000000009969621129e+00,0.000000000000000000e+00,1.861781074631804526e-10,0.000000000000000000e+00 +4.199961084956636626e+01,2.897699999999999818e+02,0.000000000000000000e+00,6.255653013799369333e+00,0.000000000000000000e+00,-1.000000009969323589e+00,0.000000000000000000e+00,-1.326527471907290225e-10,0.000000000000000000e+00 +4.200120940370258893e+01,2.897800000000000296e+02,0.000000000000000000e+00,6.254054459647207409e+00,0.000000000000000000e+00,-1.000000009969535641e+00,0.000000000000000000e+00,1.108165883234251441e-10,0.000000000000000000e+00 +4.200280836643381122e+01,2.897900000000000205e+02,0.000000000000000000e+00,6.252455496900045873e+00,0.000000000000000000e+00,-1.000000009969358450e+00,0.000000000000000000e+00,1.542427975799387647e-10,0.000000000000000000e+00 +4.200440773807347483e+01,2.898000000000000114e+02,0.000000000000000000e+00,6.250856125244437678e+00,0.000000000000000000e+00,-1.000000009969111758e+00,0.000000000000000000e+00,-4.151414916410381836e-10,0.000000000000000000e+00 +4.200600751893542650e+01,2.898100000000000023e+02,0.000000000000000000e+00,6.249256344366534321e+00,0.000000000000000000e+00,-1.000000009969775894e+00,0.000000000000000000e+00,4.189205627645479836e-10,0.000000000000000000e+00 +4.200760770933392507e+01,2.898199999999999932e+02,0.000000000000000000e+00,6.247656153952084068e+00,0.000000000000000000e+00,-1.000000009969105541e+00,0.000000000000000000e+00,-1.845053595407602337e-10,0.000000000000000000e+00 +4.200920830958361307e+01,2.898299999999999841e+02,0.000000000000000000e+00,6.246055553686436390e+00,0.000000000000000000e+00,-1.000000009969400860e+00,0.000000000000000000e+00,-2.078967503699395446e-10,0.000000000000000000e+00 +4.201080931999955226e+01,2.898400000000000318e+02,0.000000000000000000e+00,6.244454543254533974e+00,0.000000000000000000e+00,-1.000000009969733705e+00,0.000000000000000000e+00,2.838262613833915162e-10,0.000000000000000000e+00 +4.201241074089720229e+01,2.898500000000000227e+02,0.000000000000000000e+00,6.242853122340917160e+00,0.000000000000000000e+00,-1.000000009969279180e+00,0.000000000000000000e+00,-1.576100139311447692e-10,0.000000000000000000e+00 +4.201401257259242783e+01,2.898600000000000136e+02,0.000000000000000000e+00,6.241251290629723059e+00,0.000000000000000000e+00,-1.000000009969531645e+00,0.000000000000000000e+00,1.369206142940929867e-10,0.000000000000000000e+00 +4.201561481540149856e+01,2.898700000000000045e+02,0.000000000000000000e+00,6.239649047804681103e+00,0.000000000000000000e+00,-1.000000009969312265e+00,0.000000000000000000e+00,-2.783430139050492171e-10,0.000000000000000000e+00 +4.201721746964108917e+01,2.898799999999999955e+02,0.000000000000000000e+00,6.238046393549116608e+00,0.000000000000000000e+00,-1.000000009969758352e+00,0.000000000000000000e+00,2.644202760145933602e-10,0.000000000000000000e+00 +4.201882053562827934e+01,2.898899999999999864e+02,0.000000000000000000e+00,6.236443327545946325e+00,0.000000000000000000e+00,-1.000000009969334469e+00,0.000000000000000000e+00,-2.312563553319819860e-11,0.000000000000000000e+00 +4.202042401368056090e+01,2.899000000000000341e+02,0.000000000000000000e+00,6.234839849477681994e+00,0.000000000000000000e+00,-1.000000009969371551e+00,0.000000000000000000e+00,-1.636375635457070107e-10,0.000000000000000000e+00 +4.202202790411583067e+01,2.899100000000000250e+02,0.000000000000000000e+00,6.233235959026425022e+00,0.000000000000000000e+00,-1.000000009969634007e+00,0.000000000000000000e+00,1.289940579643517615e-10,0.000000000000000000e+00 +4.202363220725239046e+01,2.899200000000000159e+02,0.000000000000000000e+00,6.231631655873868247e+00,0.000000000000000000e+00,-1.000000009969427062e+00,0.000000000000000000e+00,1.059914344825193066e-10,0.000000000000000000e+00 +4.202523692340896133e+01,2.899300000000000068e+02,0.000000000000000000e+00,6.230026939701295952e+00,0.000000000000000000e+00,-1.000000009969256975e+00,0.000000000000000000e+00,-2.892572033211895393e-10,0.000000000000000000e+00 +4.202684205290467645e+01,2.899399999999999977e+02,0.000000000000000000e+00,6.228421810189581187e+00,0.000000000000000000e+00,-1.000000009969721271e+00,0.000000000000000000e+00,-7.924518146659464524e-11,0.000000000000000000e+00 +4.202844759605906688e+01,2.899499999999999886e+02,0.000000000000000000e+00,6.226816267019184892e+00,0.000000000000000000e+00,-1.000000009969848502e+00,0.000000000000000000e+00,3.341819025367647397e-10,0.000000000000000000e+00 +4.203005355319208292e+01,2.899599999999999795e+02,0.000000000000000000e+00,6.225210309870157666e+00,0.000000000000000000e+00,-1.000000009969311821e+00,0.000000000000000000e+00,-1.367069345828217011e-10,0.000000000000000000e+00 +4.203165992462408695e+01,2.899700000000000273e+02,0.000000000000000000e+00,6.223603938422137993e+00,0.000000000000000000e+00,-1.000000009969531423e+00,0.000000000000000000e+00,1.748125862311767881e-10,0.000000000000000000e+00 +4.203326671067586062e+01,2.899800000000000182e+02,0.000000000000000000e+00,6.221997152354348692e+00,0.000000000000000000e+00,-1.000000009969250536e+00,0.000000000000000000e+00,-5.055131331413900468e-10,0.000000000000000000e+00 +4.203487391166858345e+01,2.899900000000000091e+02,0.000000000000000000e+00,6.220389951345600466e+00,0.000000000000000000e+00,-1.000000009970062997e+00,0.000000000000000000e+00,5.197470761978072482e-10,0.000000000000000000e+00 +4.203648152792386838e+01,2.900000000000000000e+02,0.000000000000000000e+00,6.218782335074286571e+00,0.000000000000000000e+00,-1.000000009969227444e+00,0.000000000000000000e+00,-2.395769660735488495e-10,0.000000000000000000e+00 +4.203808955976373340e+01,2.900099999999999909e+02,0.000000000000000000e+00,6.217174303218389042e+00,0.000000000000000000e+00,-1.000000009969612691e+00,0.000000000000000000e+00,-8.572842973949821584e-11,0.000000000000000000e+00 +4.203969800751061570e+01,2.900199999999999818e+02,0.000000000000000000e+00,6.215565855455468913e+00,0.000000000000000000e+00,-1.000000009969750581e+00,0.000000000000000000e+00,2.426273576248297580e-10,0.000000000000000000e+00 +4.204130687148737167e+01,2.900300000000000296e+02,0.000000000000000000e+00,6.213956991462672441e+00,0.000000000000000000e+00,-1.000000009969360226e+00,0.000000000000000000e+00,-3.345955891086878294e-10,0.000000000000000000e+00 +4.204291615201726984e+01,2.900400000000000205e+02,0.000000000000000000e+00,6.212347710916728438e+00,0.000000000000000000e+00,-1.000000009969898684e+00,0.000000000000000000e+00,1.914632590860869397e-10,0.000000000000000000e+00 +4.204452584942400506e+01,2.900500000000000114e+02,0.000000000000000000e+00,6.210738013493944720e+00,0.000000000000000000e+00,-1.000000009969590486e+00,0.000000000000000000e+00,5.681730778216442928e-11,0.000000000000000000e+00 +4.204613596403168430e+01,2.900600000000000023e+02,0.000000000000000000e+00,6.209127898870212547e+00,0.000000000000000000e+00,-1.000000009969499004e+00,0.000000000000000000e+00,-1.007832149751780558e-10,0.000000000000000000e+00 +4.204774649616484083e+01,2.900699999999999932e+02,0.000000000000000000e+00,6.207517366721001295e+00,0.000000000000000000e+00,-1.000000009969661319e+00,0.000000000000000000e+00,1.336995369021070248e-11,0.000000000000000000e+00 +4.204935744614842008e+01,2.900799999999999841e+02,0.000000000000000000e+00,6.205906416721359342e+00,0.000000000000000000e+00,-1.000000009969639780e+00,0.000000000000000000e+00,9.783715073368537119e-12,0.000000000000000000e+00 +4.205096881430780087e+01,2.900900000000000318e+02,0.000000000000000000e+00,6.204295048545914071e+00,0.000000000000000000e+00,-1.000000009969624015e+00,0.000000000000000000e+00,1.847402155719117980e-10,0.000000000000000000e+00 +4.205258060096877415e+01,2.901000000000000227e+02,0.000000000000000000e+00,6.202683261868870090e+00,0.000000000000000000e+00,-1.000000009969326253e+00,0.000000000000000000e+00,-1.914408572555920986e-10,0.000000000000000000e+00 +4.205419280645756430e+01,2.901100000000000136e+02,0.000000000000000000e+00,6.201071056364009237e+00,0.000000000000000000e+00,-1.000000009969634895e+00,0.000000000000000000e+00,-1.374160544076748136e-10,0.000000000000000000e+00 +4.205580543110080782e+01,2.901200000000000045e+02,0.000000000000000000e+00,6.199458431704687911e+00,0.000000000000000000e+00,-1.000000009969856496e+00,0.000000000000000000e+00,3.017411405691711360e-10,0.000000000000000000e+00 +4.205741847522557464e+01,2.901299999999999955e+02,0.000000000000000000e+00,6.197845387563838848e+00,0.000000000000000000e+00,-1.000000009969369774e+00,0.000000000000000000e+00,-2.821206167459482170e-10,0.000000000000000000e+00 +4.205903193915936100e+01,2.901399999999999864e+02,0.000000000000000000e+00,6.196231923613970238e+00,0.000000000000000000e+00,-1.000000009969824966e+00,0.000000000000000000e+00,1.154329650512791183e-10,0.000000000000000000e+00 +4.206064582323008239e+01,2.901500000000000341e+02,0.000000000000000000e+00,6.194618039527161280e+00,0.000000000000000000e+00,-1.000000009969638670e+00,0.000000000000000000e+00,8.830591327893959991e-11,0.000000000000000000e+00 +4.206226012776608059e+01,2.901600000000000250e+02,0.000000000000000000e+00,6.193003734975066621e+00,0.000000000000000000e+00,-1.000000009969496118e+00,0.000000000000000000e+00,-4.041486695769807293e-10,0.000000000000000000e+00 +4.206387485309613794e+01,2.901700000000000159e+02,0.000000000000000000e+00,6.191389009628911921e+00,0.000000000000000000e+00,-1.000000009970148707e+00,0.000000000000000000e+00,3.006610019630968577e-10,0.000000000000000000e+00 +4.206548999954945600e+01,2.901800000000000068e+02,0.000000000000000000e+00,6.189773863159492961e+00,0.000000000000000000e+00,-1.000000009969663095e+00,0.000000000000000000e+00,1.195733126057864772e-10,0.000000000000000000e+00 +4.206710556745566265e+01,2.901899999999999977e+02,0.000000000000000000e+00,6.188158295237179196e+00,0.000000000000000000e+00,-1.000000009969469916e+00,0.000000000000000000e+00,-3.046262562320839477e-10,0.000000000000000000e+00 +4.206872155714482631e+01,2.901999999999999886e+02,0.000000000000000000e+00,6.186542305531907537e+00,0.000000000000000000e+00,-1.000000009969962189e+00,0.000000000000000000e+00,3.497410518945417472e-10,0.000000000000000000e+00 +4.207033796894743460e+01,2.902099999999999795e+02,0.000000000000000000e+00,6.184925893713183243e+00,0.000000000000000000e+00,-1.000000009969396864e+00,0.000000000000000000e+00,-3.345430483100501097e-10,0.000000000000000000e+00 +4.207195480319441572e+01,2.902200000000000273e+02,0.000000000000000000e+00,6.183309059450082579e+00,0.000000000000000000e+00,-1.000000009969937764e+00,0.000000000000000000e+00,3.244329095926211714e-10,0.000000000000000000e+00 +4.207357206021713125e+01,2.902300000000000182e+02,0.000000000000000000e+00,6.181691802411245718e+00,0.000000000000000000e+00,-1.000000009969413073e+00,0.000000000000000000e+00,-4.267448575333912592e-10,0.000000000000000000e+00 +4.207518974034736914e+01,2.902400000000000091e+02,0.000000000000000000e+00,6.180074122264882952e+00,0.000000000000000000e+00,-1.000000009970103410e+00,0.000000000000000000e+00,4.321221916073118515e-10,0.000000000000000000e+00 +4.207680784391735074e+01,2.902500000000000000e+02,0.000000000000000000e+00,6.178456018678766704e+00,0.000000000000000000e+00,-1.000000009969404191e+00,0.000000000000000000e+00,-1.878121278402751551e-10,0.000000000000000000e+00 +4.207842637125974505e+01,2.902599999999999909e+02,0.000000000000000000e+00,6.176837491320238627e+00,0.000000000000000000e+00,-1.000000009969708170e+00,0.000000000000000000e+00,-2.844560355485675558e-10,0.000000000000000000e+00 +4.208004532270764031e+01,2.902699999999999818e+02,0.000000000000000000e+00,6.175218539856200728e+00,0.000000000000000000e+00,-1.000000009970168691e+00,0.000000000000000000e+00,4.468655938925393704e-10,0.000000000000000000e+00 +4.208166469859457237e+01,2.902800000000000296e+02,0.000000000000000000e+00,6.173599163953119806e+00,0.000000000000000000e+00,-1.000000009969445047e+00,0.000000000000000000e+00,-3.972620094469223727e-10,0.000000000000000000e+00 +4.208328449925451764e+01,2.902900000000000205e+02,0.000000000000000000e+00,6.171979363277027453e+00,0.000000000000000000e+00,-1.000000009970088533e+00,0.000000000000000000e+00,1.995382071336171683e-10,0.000000000000000000e+00 +4.208490472502187885e+01,2.903000000000000114e+02,0.000000000000000000e+00,6.170359137493512947e+00,0.000000000000000000e+00,-1.000000009969765236e+00,0.000000000000000000e+00,1.745500975129207184e-10,0.000000000000000000e+00 +4.208652537623150636e+01,2.903100000000000023e+02,0.000000000000000000e+00,6.168738486267730359e+00,0.000000000000000000e+00,-1.000000009969482351e+00,0.000000000000000000e+00,-1.627245298882154832e-10,0.000000000000000000e+00 +4.208814645321868397e+01,2.903199999999999932e+02,0.000000000000000000e+00,6.167117409264392336e+00,0.000000000000000000e+00,-1.000000009969746140e+00,0.000000000000000000e+00,-1.658313305035003826e-10,0.000000000000000000e+00 +4.208976795631914314e+01,2.903299999999999841e+02,0.000000000000000000e+00,6.165495906147770100e+00,0.000000000000000000e+00,-1.000000009970015036e+00,0.000000000000000000e+00,1.360801012031594717e-10,0.000000000000000000e+00 +4.209138988586904873e+01,2.903400000000000318e+02,0.000000000000000000e+00,6.163873976581694336e+00,0.000000000000000000e+00,-1.000000009969794323e+00,0.000000000000000000e+00,3.969099389619515913e-11,0.000000000000000000e+00 +4.209301224220501325e+01,2.903500000000000227e+02,0.000000000000000000e+00,6.162251620229554305e+00,0.000000000000000000e+00,-1.000000009969729931e+00,0.000000000000000000e+00,-1.438077757512093277e-10,0.000000000000000000e+00 +4.209463502566409687e+01,2.903600000000000136e+02,0.000000000000000000e+00,6.160628836754295179e+00,0.000000000000000000e+00,-1.000000009969963299e+00,0.000000000000000000e+00,2.329592276638107248e-10,0.000000000000000000e+00 +4.209625823658379318e+01,2.903700000000000045e+02,0.000000000000000000e+00,6.159005625818418039e+00,0.000000000000000000e+00,-1.000000009969585157e+00,0.000000000000000000e+00,-2.037685216664684704e-10,0.000000000000000000e+00 +4.209788187530204340e+01,2.903799999999999955e+02,0.000000000000000000e+00,6.157381987083980768e+00,0.000000000000000000e+00,-1.000000009969916004e+00,0.000000000000000000e+00,-1.307056058864005886e-10,0.000000000000000000e+00 +4.209950594215723640e+01,2.903899999999999864e+02,0.000000000000000000e+00,6.155757920212593604e+00,0.000000000000000000e+00,-1.000000009970128279e+00,0.000000000000000000e+00,4.271415110649179981e-10,0.000000000000000000e+00 +4.210113043748820871e+01,2.904000000000000341e+02,0.000000000000000000e+00,6.154133424865421809e+00,0.000000000000000000e+00,-1.000000009969434389e+00,0.000000000000000000e+00,-2.362664884090717714e-10,0.000000000000000000e+00 +4.210275536163424448e+01,2.904100000000000250e+02,0.000000000000000000e+00,6.152508500703184779e+00,0.000000000000000000e+00,-1.000000009969818304e+00,0.000000000000000000e+00,-1.240447237957574023e-10,0.000000000000000000e+00 +4.210438071493507550e+01,2.904200000000000159e+02,0.000000000000000000e+00,6.150883147386150718e+00,0.000000000000000000e+00,-1.000000009970019921e+00,0.000000000000000000e+00,6.828852092006954719e-11,0.000000000000000000e+00 +4.210600649773087412e+01,2.904300000000000068e+02,0.000000000000000000e+00,6.149257364574141072e+00,0.000000000000000000e+00,-1.000000009969908898e+00,0.000000000000000000e+00,-1.624837212298053080e-11,0.000000000000000000e+00 +4.210763271036227451e+01,2.904399999999999977e+02,0.000000000000000000e+00,6.147631151926527870e+00,0.000000000000000000e+00,-1.000000009969935322e+00,0.000000000000000000e+00,-6.156367969898077767e-11,0.000000000000000000e+00 +4.210925935317035140e+01,2.904499999999999886e+02,0.000000000000000000e+00,6.146004509102231950e+00,0.000000000000000000e+00,-1.000000009970035464e+00,0.000000000000000000e+00,2.476907164710284609e-10,0.000000000000000000e+00 +4.211088642649664138e+01,2.904599999999999795e+02,0.000000000000000000e+00,6.144377435759722950e+00,0.000000000000000000e+00,-1.000000009969632453e+00,0.000000000000000000e+00,-1.132390463993842094e-10,0.000000000000000000e+00 +4.211251393068312154e+01,2.904700000000000273e+02,0.000000000000000000e+00,6.142749931557019316e+00,0.000000000000000000e+00,-1.000000009969816750e+00,0.000000000000000000e+00,-1.564467260516600112e-10,0.000000000000000000e+00 +4.211414186607222376e+01,2.904800000000000182e+02,0.000000000000000000e+00,6.141121996151684748e+00,0.000000000000000000e+00,-1.000000009970071435e+00,0.000000000000000000e+00,1.009066225499621120e-10,0.000000000000000000e+00 +4.211577023300684175e+01,2.904900000000000091e+02,0.000000000000000000e+00,6.139493629200829972e+00,0.000000000000000000e+00,-1.000000009969907122e+00,0.000000000000000000e+00,-2.835542189658141423e-11,0.000000000000000000e+00 +4.211739903183032396e+01,2.905000000000000000e+02,0.000000000000000000e+00,6.137864830361111856e+00,0.000000000000000000e+00,-1.000000009969953307e+00,0.000000000000000000e+00,1.103932614786029622e-10,0.000000000000000000e+00 +4.211902826288645940e+01,2.905099999999999909e+02,0.000000000000000000e+00,6.136235599288730747e+00,0.000000000000000000e+00,-1.000000009969773451e+00,0.000000000000000000e+00,-1.674534633516933017e-10,0.000000000000000000e+00 +4.212065792651951313e+01,2.905199999999999818e+02,0.000000000000000000e+00,6.134605935639431351e+00,0.000000000000000000e+00,-1.000000009970046344e+00,0.000000000000000000e+00,1.274978157663421615e-10,0.000000000000000000e+00 +4.212228802307419073e+01,2.905300000000000296e+02,0.000000000000000000e+00,6.132975839068500079e+00,0.000000000000000000e+00,-1.000000009969838510e+00,0.000000000000000000e+00,-2.138016889605141976e-11,0.000000000000000000e+00 +4.212391855289566678e+01,2.905400000000000205e+02,0.000000000000000000e+00,6.131345309230766816e+00,0.000000000000000000e+00,-1.000000009969873371e+00,0.000000000000000000e+00,-2.918910522840160042e-10,0.000000000000000000e+00 +4.212554951632957057e+01,2.905500000000000114e+02,0.000000000000000000e+00,6.129714345780601370e+00,0.000000000000000000e+00,-1.000000009970349435e+00,0.000000000000000000e+00,3.052880010475853381e-10,0.000000000000000000e+00 +4.212718091372199325e+01,2.905600000000000023e+02,0.000000000000000000e+00,6.128082948371913474e+00,0.000000000000000000e+00,-1.000000009969851389e+00,0.000000000000000000e+00,8.967064120073622384e-11,0.000000000000000000e+00 +4.212881274541948073e+01,2.905699999999999932e+02,0.000000000000000000e+00,6.126451116658154561e+00,0.000000000000000000e+00,-1.000000009969705062e+00,0.000000000000000000e+00,-2.805032251484787726e-10,0.000000000000000000e+00 +4.213044501176904788e+01,2.905799999999999841e+02,0.000000000000000000e+00,6.124818850292312433e+00,0.000000000000000000e+00,-1.000000009970162917e+00,0.000000000000000000e+00,1.846856889353034613e-10,0.000000000000000000e+00 +4.213207771311817140e+01,2.905900000000000318e+02,0.000000000000000000e+00,6.123186148926912153e+00,0.000000000000000000e+00,-1.000000009969861381e+00,0.000000000000000000e+00,-1.896670526802655620e-10,0.000000000000000000e+00 +4.213371084981478276e+01,2.906000000000000227e+02,0.000000000000000000e+00,6.121553012214017819e+00,0.000000000000000000e+00,-1.000000009970171133e+00,0.000000000000000000e+00,-7.897287934924488373e-11,0.000000000000000000e+00 +4.213534442220728948e+01,2.906100000000000136e+02,0.000000000000000000e+00,6.119919439805227235e+00,0.000000000000000000e+00,-1.000000009970300141e+00,0.000000000000000000e+00,1.762486937157388084e-10,0.000000000000000000e+00 +4.213697843064455384e+01,2.906200000000000045e+02,0.000000000000000000e+00,6.118285431351674575e+00,0.000000000000000000e+00,-1.000000009970012149e+00,0.000000000000000000e+00,2.365204684547542902e-10,0.000000000000000000e+00 +4.213861287547590706e+01,2.906299999999999955e+02,0.000000000000000000e+00,6.116650986504028609e+00,0.000000000000000000e+00,-1.000000009969625570e+00,0.000000000000000000e+00,-2.350991147901043485e-10,0.000000000000000000e+00 +4.214024775705114223e+01,2.906399999999999864e+02,0.000000000000000000e+00,6.115016104912490924e+00,0.000000000000000000e+00,-1.000000009970009929e+00,0.000000000000000000e+00,-2.467134110923029180e-10,0.000000000000000000e+00 +4.214188307572053560e+01,2.906500000000000341e+02,0.000000000000000000e+00,6.113380786226794150e+00,0.000000000000000000e+00,-1.000000009970413384e+00,0.000000000000000000e+00,5.291313677149754043e-10,0.000000000000000000e+00 +4.214351883183481817e+01,2.906600000000000250e+02,0.000000000000000000e+00,6.111745030096203735e+00,0.000000000000000000e+00,-1.000000009969547854e+00,0.000000000000000000e+00,-5.664451964287120841e-10,0.000000000000000000e+00 +4.214515502574518990e+01,2.906700000000000159e+02,0.000000000000000000e+00,6.110108836169517943e+00,0.000000000000000000e+00,-1.000000009970474668e+00,0.000000000000000000e+00,4.462241234773132699e-10,0.000000000000000000e+00 +4.214679165780332681e+01,2.906800000000000068e+02,0.000000000000000000e+00,6.108472204095059865e+00,0.000000000000000000e+00,-1.000000009969744363e+00,0.000000000000000000e+00,-4.143659323110428552e-10,0.000000000000000000e+00 +4.214842872836138099e+01,2.906899999999999977e+02,0.000000000000000000e+00,6.106835133520687187e+00,0.000000000000000000e+00,-1.000000009970422710e+00,0.000000000000000000e+00,4.968346607285800697e-10,0.000000000000000000e+00 +4.215006623777195927e+01,2.906999999999999886e+02,0.000000000000000000e+00,6.105197624093780639e+00,0.000000000000000000e+00,-1.000000009969609138e+00,0.000000000000000000e+00,-4.643019715926665554e-10,0.000000000000000000e+00 +4.215170418638815875e+01,2.907099999999999795e+02,0.000000000000000000e+00,6.103559675461252887e+00,0.000000000000000000e+00,-1.000000009970369641e+00,0.000000000000000000e+00,3.455919366774072828e-10,0.000000000000000000e+00 +4.215334257456353839e+01,2.907200000000000273e+02,0.000000000000000000e+00,6.101921287269537864e+00,0.000000000000000000e+00,-1.000000009969803427e+00,0.000000000000000000e+00,-3.818104540870405595e-10,0.000000000000000000e+00 +4.215498140265214033e+01,2.907300000000000182e+02,0.000000000000000000e+00,6.100282459164599658e+00,0.000000000000000000e+00,-1.000000009970429149e+00,0.000000000000000000e+00,3.330801094289126703e-10,0.000000000000000000e+00 +4.215662067100847565e+01,2.907400000000000091e+02,0.000000000000000000e+00,6.098643190791922741e+00,0.000000000000000000e+00,-1.000000009969883141e+00,0.000000000000000000e+00,-1.518025486841378001e-10,0.000000000000000000e+00 +4.215826037998753151e+01,2.907500000000000000e+02,0.000000000000000000e+00,6.097003481796519075e+00,0.000000000000000000e+00,-1.000000009970132053e+00,0.000000000000000000e+00,-1.796501529836898328e-10,0.000000000000000000e+00 +4.215990052994477821e+01,2.907599999999999909e+02,0.000000000000000000e+00,6.095363331822920117e+00,0.000000000000000000e+00,-1.000000009970426706e+00,0.000000000000000000e+00,2.536351325374253673e-10,0.000000000000000000e+00 +4.216154112123616216e+01,2.907699999999999818e+02,0.000000000000000000e+00,6.093722740515180369e+00,0.000000000000000000e+00,-1.000000009970010595e+00,0.000000000000000000e+00,1.631812379679088847e-10,0.000000000000000000e+00 +4.216318215421810578e+01,2.907800000000000296e+02,0.000000000000000000e+00,6.092081707516876499e+00,0.000000000000000000e+00,-1.000000009969742809e+00,0.000000000000000000e+00,-4.434196085254598007e-10,0.000000000000000000e+00 +4.216482362924751470e+01,2.907900000000000205e+02,0.000000000000000000e+00,6.090440232471103776e+00,0.000000000000000000e+00,-1.000000009970470671e+00,0.000000000000000000e+00,4.184169028868111028e-10,0.000000000000000000e+00 +4.216646554668177060e+01,2.908000000000000114e+02,0.000000000000000000e+00,6.088798315020475194e+00,0.000000000000000000e+00,-1.000000009969783665e+00,0.000000000000000000e+00,-2.092872495674068582e-10,0.000000000000000000e+00 +4.216810790687874544e+01,2.908100000000000023e+02,0.000000000000000000e+00,6.087155954807125902e+00,0.000000000000000000e+00,-1.000000009970127390e+00,0.000000000000000000e+00,-3.403379510259339192e-10,0.000000000000000000e+00 +4.216975071019678722e+01,2.908199999999999932e+02,0.000000000000000000e+00,6.085513151472704330e+00,0.000000000000000000e+00,-1.000000009970686499e+00,0.000000000000000000e+00,3.628120650956792142e-10,0.000000000000000000e+00 +4.217139395699472715e+01,2.908299999999999841e+02,0.000000000000000000e+00,6.083869904658376626e+00,0.000000000000000000e+00,-1.000000009970090309e+00,0.000000000000000000e+00,-6.376203109945141861e-11,0.000000000000000000e+00 +4.217303764763188667e+01,2.908400000000000318e+02,0.000000000000000000e+00,6.082226214004826659e+00,0.000000000000000000e+00,-1.000000009970195114e+00,0.000000000000000000e+00,3.713945171071769257e-11,0.000000000000000000e+00 +4.217468178246807042e+01,2.908500000000000227e+02,0.000000000000000000e+00,6.080582079152249797e+00,0.000000000000000000e+00,-1.000000009970134052e+00,0.000000000000000000e+00,1.863221414761829640e-11,0.000000000000000000e+00 +4.217632636186356621e+01,2.908600000000000136e+02,0.000000000000000000e+00,6.078937499740356465e+00,0.000000000000000000e+00,-1.000000009970103410e+00,0.000000000000000000e+00,-1.050140724334180253e-10,0.000000000000000000e+00 +4.217797138617915209e+01,2.908700000000000045e+02,0.000000000000000000e+00,6.077292475408369476e+00,0.000000000000000000e+00,-1.000000009970276160e+00,0.000000000000000000e+00,7.286922036265952123e-12,0.000000000000000000e+00 +4.217961685577608932e+01,2.908799999999999955e+02,0.000000000000000000e+00,6.075647005795023148e+00,0.000000000000000000e+00,-1.000000009970264170e+00,0.000000000000000000e+00,4.222572320275657188e-11,0.000000000000000000e+00 +4.218126277101613653e+01,2.908899999999999864e+02,0.000000000000000000e+00,6.074001090538563297e+00,0.000000000000000000e+00,-1.000000009970194670e+00,0.000000000000000000e+00,1.551004048332271155e-11,0.000000000000000000e+00 +4.218290913226154260e+01,2.909000000000000341e+02,0.000000000000000000e+00,6.072354729276745466e+00,0.000000000000000000e+00,-1.000000009970169135e+00,0.000000000000000000e+00,-5.703451156877788926e-11,0.000000000000000000e+00 +4.218455593987503249e+01,2.909100000000000250e+02,0.000000000000000000e+00,6.070707921646834038e+00,0.000000000000000000e+00,-1.000000009970263060e+00,0.000000000000000000e+00,1.694395703191202662e-10,0.000000000000000000e+00 +4.218620319421984277e+01,2.909200000000000159e+02,0.000000000000000000e+00,6.069060667285601340e+00,0.000000000000000000e+00,-1.000000009969983950e+00,0.000000000000000000e+00,-2.691161549732555776e-10,0.000000000000000000e+00 +4.218785089565968605e+01,2.909300000000000068e+02,0.000000000000000000e+00,6.067412965829327653e+00,0.000000000000000000e+00,-1.000000009970427373e+00,0.000000000000000000e+00,2.817071134486397935e-10,0.000000000000000000e+00 +4.218949904455878652e+01,2.909399999999999977e+02,0.000000000000000000e+00,6.065764816913797652e+00,0.000000000000000000e+00,-1.000000009969963077e+00,0.000000000000000000e+00,-1.206795835696441993e-10,0.000000000000000000e+00 +4.219114764128184447e+01,2.909499999999999886e+02,0.000000000000000000e+00,6.064116220174303962e+00,0.000000000000000000e+00,-1.000000009970162029e+00,0.000000000000000000e+00,-1.478461710780228856e-10,0.000000000000000000e+00 +4.219279668619406465e+01,2.909599999999999795e+02,0.000000000000000000e+00,6.062467175245640938e+00,0.000000000000000000e+00,-1.000000009970405834e+00,0.000000000000000000e+00,2.203628116842962539e-10,0.000000000000000000e+00 +4.219444617966114919e+01,2.909700000000000273e+02,0.000000000000000000e+00,6.060817681762107334e+00,0.000000000000000000e+00,-1.000000009970042347e+00,0.000000000000000000e+00,-2.988959318093984331e-10,0.000000000000000000e+00 +4.219609612204929761e+01,2.909800000000000182e+02,0.000000000000000000e+00,6.059167739357505411e+00,0.000000000000000000e+00,-1.000000009970535508e+00,0.000000000000000000e+00,2.745972639501530472e-10,0.000000000000000000e+00 +4.219774651372521390e+01,2.909900000000000091e+02,0.000000000000000000e+00,6.057517347665136498e+00,0.000000000000000000e+00,-1.000000009970082315e+00,0.000000000000000000e+00,-3.183707422565657674e-10,0.000000000000000000e+00 +4.219939735505608525e+01,2.910000000000000000e+02,0.000000000000000000e+00,6.055866506317805431e+00,0.000000000000000000e+00,-1.000000009970607895e+00,0.000000000000000000e+00,2.289977243443535463e-10,0.000000000000000000e+00 +4.220104864640961040e+01,2.910099999999999909e+02,0.000000000000000000e+00,6.054215214947813450e+00,0.000000000000000000e+00,-1.000000009970229753e+00,0.000000000000000000e+00,-1.303976650768174714e-11,0.000000000000000000e+00 +4.220270038815399261e+01,2.910199999999999818e+02,0.000000000000000000e+00,6.052563473186963527e+00,0.000000000000000000e+00,-1.000000009970251291e+00,0.000000000000000000e+00,-4.125892930125546688e-11,0.000000000000000000e+00 +4.220435258065793249e+01,2.910300000000000296e+02,0.000000000000000000e+00,6.050911280666554148e+00,0.000000000000000000e+00,-1.000000009970319459e+00,0.000000000000000000e+00,1.717085277673081977e-10,0.000000000000000000e+00 +4.220600522429062806e+01,2.910400000000000205e+02,0.000000000000000000e+00,6.049258637017381091e+00,0.000000000000000000e+00,-1.000000009970035686e+00,0.000000000000000000e+00,-3.216976559729329205e-10,0.000000000000000000e+00 +4.220765831942178892e+01,2.910500000000000114e+02,0.000000000000000000e+00,6.047605541869736534e+00,0.000000000000000000e+00,-1.000000009970567483e+00,0.000000000000000000e+00,1.325381286904165803e-10,0.000000000000000000e+00 +4.220931186642163624e+01,2.910600000000000023e+02,0.000000000000000000e+00,6.045951994853405509e+00,0.000000000000000000e+00,-1.000000009970348325e+00,0.000000000000000000e+00,-6.067969019860041002e-11,0.000000000000000000e+00 +4.221096586566088149e+01,2.910699999999999932e+02,0.000000000000000000e+00,6.044297995597669448e+00,0.000000000000000000e+00,-1.000000009970448689e+00,0.000000000000000000e+00,1.037446206852310168e-10,0.000000000000000000e+00 +4.221262031751075483e+01,2.910799999999999841e+02,0.000000000000000000e+00,6.042643543731300859e+00,0.000000000000000000e+00,-1.000000009970277048e+00,0.000000000000000000e+00,7.916244750386586290e-12,0.000000000000000000e+00 +4.221427522234299090e+01,2.910900000000000318e+02,0.000000000000000000e+00,6.040988638882565098e+00,0.000000000000000000e+00,-1.000000009970263948e+00,0.000000000000000000e+00,8.987171869037788204e-12,0.000000000000000000e+00 +4.221593058052983594e+01,2.911000000000000227e+02,0.000000000000000000e+00,6.039333280679217708e+00,0.000000000000000000e+00,-1.000000009970249071e+00,0.000000000000000000e+00,-1.842535885566320004e-10,0.000000000000000000e+00 +4.221758639244404065e+01,2.911100000000000136e+02,0.000000000000000000e+00,6.037677468748504417e+00,0.000000000000000000e+00,-1.000000009970554160e+00,0.000000000000000000e+00,1.099319640734680219e-10,0.000000000000000000e+00 +4.221924265845887447e+01,2.911200000000000045e+02,0.000000000000000000e+00,6.036021202717159362e+00,0.000000000000000000e+00,-1.000000009970372084e+00,0.000000000000000000e+00,-4.489890909976086893e-11,0.000000000000000000e+00 +4.222089937894811129e+01,2.911299999999999955e+02,0.000000000000000000e+00,6.034364482211405978e+00,0.000000000000000000e+00,-1.000000009970446468e+00,0.000000000000000000e+00,3.576187968650721583e-10,0.000000000000000000e+00 +4.222255655428604371e+01,2.911399999999999864e+02,0.000000000000000000e+00,6.032707306856953444e+00,0.000000000000000000e+00,-1.000000009969853831e+00,0.000000000000000000e+00,-5.857765173563724571e-10,0.000000000000000000e+00 +4.222421418484747591e+01,2.911500000000000341e+02,0.000000000000000000e+00,6.031049676278998461e+00,0.000000000000000000e+00,-1.000000009970824832e+00,0.000000000000000000e+00,3.950528025825194031e-10,0.000000000000000000e+00 +4.222587227100772367e+01,2.911600000000000250e+02,0.000000000000000000e+00,6.029391590102219034e+00,0.000000000000000000e+00,-1.000000009970169801e+00,0.000000000000000000e+00,-2.170184869044899036e-10,0.000000000000000000e+00 +4.222753081314262147e+01,2.911700000000000159e+02,0.000000000000000000e+00,6.027733047950782463e+00,0.000000000000000000e+00,-1.000000009970529735e+00,0.000000000000000000e+00,2.025037937680614559e-10,0.000000000000000000e+00 +4.222918981162852958e+01,2.911800000000000068e+02,0.000000000000000000e+00,6.026074049448334691e+00,0.000000000000000000e+00,-1.000000009970193782e+00,0.000000000000000000e+00,-2.440616390363140087e-10,0.000000000000000000e+00 +4.223084926684231277e+01,2.911899999999999977e+02,0.000000000000000000e+00,6.024414594218006513e+00,0.000000000000000000e+00,-1.000000009970598791e+00,0.000000000000000000e+00,9.805258599641761652e-11,0.000000000000000000e+00 +4.223250917916136160e+01,2.911999999999999886e+02,0.000000000000000000e+00,6.022754681882407368e+00,0.000000000000000000e+00,-1.000000009970436032e+00,0.000000000000000000e+00,-1.979233872170463414e-11,0.000000000000000000e+00 +4.223416954896358533e+01,2.912099999999999795e+02,0.000000000000000000e+00,6.021094312063628884e+00,0.000000000000000000e+00,-1.000000009970468895e+00,0.000000000000000000e+00,9.037792192312406158e-11,0.000000000000000000e+00 +4.223583037662741191e+01,2.912200000000000273e+02,0.000000000000000000e+00,6.019433484383240440e+00,0.000000000000000000e+00,-1.000000009970318793e+00,0.000000000000000000e+00,-1.724191721586971574e-10,0.000000000000000000e+00 +4.223749166253180221e+01,2.912300000000000182e+02,0.000000000000000000e+00,6.017772198462290056e+00,0.000000000000000000e+00,-1.000000009970605230e+00,0.000000000000000000e+00,2.023027769409303950e-10,0.000000000000000000e+00 +4.223915340705622157e+01,2.912400000000000091e+02,0.000000000000000000e+00,6.016110453921301726e+00,0.000000000000000000e+00,-1.000000009970269055e+00,0.000000000000000000e+00,-2.711765083920401523e-11,0.000000000000000000e+00 +4.224081561058067535e+01,2.912500000000000000e+02,0.000000000000000000e+00,6.014448250380277194e+00,0.000000000000000000e+00,-1.000000009970314130e+00,0.000000000000000000e+00,-1.708073529779502274e-10,0.000000000000000000e+00 +4.224247827348568052e+01,2.912599999999999909e+02,0.000000000000000000e+00,6.012785587458691516e+00,0.000000000000000000e+00,-1.000000009970598125e+00,0.000000000000000000e+00,1.392516184077633366e-10,0.000000000000000000e+00 +4.224414139615229402e+01,2.912699999999999818e+02,0.000000000000000000e+00,6.011122464775493945e+00,0.000000000000000000e+00,-1.000000009970366532e+00,0.000000000000000000e+00,-1.254653074076231701e-11,0.000000000000000000e+00 +4.224580497896209152e+01,2.912800000000000296e+02,0.000000000000000000e+00,6.009458881949107933e+00,0.000000000000000000e+00,-1.000000009970387405e+00,0.000000000000000000e+00,-2.553980205111237788e-10,0.000000000000000000e+00 +4.224746902229718160e+01,2.912900000000000205e+02,0.000000000000000000e+00,6.007794838597427578e+00,0.000000000000000000e+00,-1.000000009970812398e+00,0.000000000000000000e+00,1.015172806300733169e-10,0.000000000000000000e+00 +4.224913352654019860e+01,2.913000000000000114e+02,0.000000000000000000e+00,6.006130334337817622e+00,0.000000000000000000e+00,-1.000000009970643422e+00,0.000000000000000000e+00,1.469658978612348249e-10,0.000000000000000000e+00 +4.225079849207430271e+01,2.913100000000000023e+02,0.000000000000000000e+00,6.004465368787114343e+00,0.000000000000000000e+00,-1.000000009970398729e+00,0.000000000000000000e+00,-6.732958660021753773e-11,0.000000000000000000e+00 +4.225246391928318701e+01,2.913199999999999932e+02,0.000000000000000000e+00,6.002799941561621999e+00,0.000000000000000000e+00,-1.000000009970510861e+00,0.000000000000000000e+00,1.522159627956514610e-10,0.000000000000000000e+00 +4.225412980855108458e+01,2.913299999999999841e+02,0.000000000000000000e+00,6.001134052277111941e+00,0.000000000000000000e+00,-1.000000009970257286e+00,0.000000000000000000e+00,-1.018044851961377945e-10,0.000000000000000000e+00 +4.225579616026276142e+01,2.913400000000000318e+02,0.000000000000000000e+00,5.999467700548823501e+00,0.000000000000000000e+00,-1.000000009970426929e+00,0.000000000000000000e+00,-1.342806630811480486e-10,0.000000000000000000e+00 +4.225746297480350222e+01,2.913500000000000227e+02,0.000000000000000000e+00,5.997800885991460440e+00,0.000000000000000000e+00,-1.000000009970650749e+00,0.000000000000000000e+00,1.092059049082160892e-10,0.000000000000000000e+00 +4.225913025255914590e+01,2.913600000000000136e+02,0.000000000000000000e+00,5.996133608219191835e+00,0.000000000000000000e+00,-1.000000009970468673e+00,0.000000000000000000e+00,4.540105092771238786e-11,0.000000000000000000e+00 +4.226079799391605718e+01,2.913700000000000045e+02,0.000000000000000000e+00,5.994465866845651192e+00,0.000000000000000000e+00,-1.000000009970392956e+00,0.000000000000000000e+00,-2.672725920721778627e-10,0.000000000000000000e+00 +4.226246619926114079e+01,2.913799999999999955e+02,0.000000000000000000e+00,5.992797661483933780e+00,0.000000000000000000e+00,-1.000000009970838821e+00,0.000000000000000000e+00,1.856282402850092950e-10,0.000000000000000000e+00 +4.226413486898184146e+01,2.913899999999999864e+02,0.000000000000000000e+00,5.991128991746595744e+00,0.000000000000000000e+00,-1.000000009970529069e+00,0.000000000000000000e+00,-1.318325189197028496e-10,0.000000000000000000e+00 +4.226580400346613686e+01,2.914000000000000341e+02,0.000000000000000000e+00,5.989459857245655883e+00,0.000000000000000000e+00,-1.000000009970749115e+00,0.000000000000000000e+00,1.157036705513308037e-10,0.000000000000000000e+00 +4.226747360310255175e+01,2.914100000000000250e+02,0.000000000000000000e+00,5.987790257592590315e+00,0.000000000000000000e+00,-1.000000009970555936e+00,0.000000000000000000e+00,3.284004609639112466e-11,0.000000000000000000e+00 +4.226914366828015801e+01,2.914200000000000159e+02,0.000000000000000000e+00,5.986120192398335149e+00,0.000000000000000000e+00,-1.000000009970501091e+00,0.000000000000000000e+00,-1.329185693154840573e-13,0.000000000000000000e+00 +4.227081419938855333e+01,2.914300000000000068e+02,0.000000000000000000e+00,5.984449661273282928e+00,0.000000000000000000e+00,-1.000000009970501313e+00,0.000000000000000000e+00,7.919735973957734128e-11,0.000000000000000000e+00 +4.227248519681788963e+01,2.914399999999999977e+02,0.000000000000000000e+00,5.982778663827282628e+00,0.000000000000000000e+00,-1.000000009970368975e+00,0.000000000000000000e+00,-3.014238811488235336e-10,0.000000000000000000e+00 +4.227415666095886593e+01,2.914499999999999886e+02,0.000000000000000000e+00,5.981107199669638774e+00,0.000000000000000000e+00,-1.000000009970872794e+00,0.000000000000000000e+00,1.937657901755596820e-10,0.000000000000000000e+00 +4.227582859220272837e+01,2.914599999999999795e+02,0.000000000000000000e+00,5.979435268409108772e+00,0.000000000000000000e+00,-1.000000009970548831e+00,0.000000000000000000e+00,4.089320132893993177e-11,0.000000000000000000e+00 +4.227750099094125602e+01,2.914700000000000273e+02,0.000000000000000000e+00,5.977762869653905575e+00,0.000000000000000000e+00,-1.000000009970480441e+00,0.000000000000000000e+00,-5.773885477066029508e-11,0.000000000000000000e+00 +4.227917385756678925e+01,2.914800000000000182e+02,0.000000000000000000e+00,5.976090003011692353e+00,0.000000000000000000e+00,-1.000000009970577031e+00,0.000000000000000000e+00,-3.542979311719477869e-11,0.000000000000000000e+00 +4.228084719247221557e+01,2.914900000000000091e+02,0.000000000000000000e+00,5.974416668089583382e+00,0.000000000000000000e+00,-1.000000009970636317e+00,0.000000000000000000e+00,-1.408835382024328831e-10,0.000000000000000000e+00 +4.228252099605096959e+01,2.915000000000000000e+02,0.000000000000000000e+00,5.972742864494143156e+00,0.000000000000000000e+00,-1.000000009970872128e+00,0.000000000000000000e+00,3.286361586910865840e-10,0.000000000000000000e+00 +4.228419526869703304e+01,2.915099999999999909e+02,0.000000000000000000e+00,5.971068591831384609e+00,0.000000000000000000e+00,-1.000000009970321901e+00,0.000000000000000000e+00,-4.582115365663167162e-10,0.000000000000000000e+00 +4.228587001080494900e+01,2.915199999999999818e+02,0.000000000000000000e+00,5.969393849706770006e+00,0.000000000000000000e+00,-1.000000009971089288e+00,0.000000000000000000e+00,4.205721700927163230e-10,0.000000000000000000e+00 +4.228754522276980765e+01,2.915300000000000296e+02,0.000000000000000000e+00,5.967718637725204722e+00,0.000000000000000000e+00,-1.000000009970384740e+00,0.000000000000000000e+00,-1.294622433491438057e-10,0.000000000000000000e+00 +4.228922090498726050e+01,2.915400000000000205e+02,0.000000000000000000e+00,5.966042955491044353e+00,0.000000000000000000e+00,-1.000000009970601678e+00,0.000000000000000000e+00,-1.361820025246272778e-10,0.000000000000000000e+00 +4.229089705785350617e+01,2.915500000000000114e+02,0.000000000000000000e+00,5.964366802608084939e+00,0.000000000000000000e+00,-1.000000009970829939e+00,0.000000000000000000e+00,1.572009943261631083e-10,0.000000000000000000e+00 +4.229257368176530463e+01,2.915600000000000023e+02,0.000000000000000000e+00,5.962690178679567410e+00,0.000000000000000000e+00,-1.000000009970566373e+00,0.000000000000000000e+00,-1.223360462954108502e-10,0.000000000000000000e+00 +4.229425077711997716e+01,2.915699999999999932e+02,0.000000000000000000e+00,5.961013083308175808e+00,0.000000000000000000e+00,-1.000000009970771542e+00,0.000000000000000000e+00,4.817943293931427981e-11,0.000000000000000000e+00 +4.229592834431539217e+01,2.915799999999999841e+02,0.000000000000000000e+00,5.959335516096033736e+00,0.000000000000000000e+00,-1.000000009970690718e+00,0.000000000000000000e+00,1.141954653147897890e-10,0.000000000000000000e+00 +4.229760638374998649e+01,2.915900000000000318e+02,0.000000000000000000e+00,5.957657476644706129e+00,0.000000000000000000e+00,-1.000000009970499093e+00,0.000000000000000000e+00,-1.620510483333284895e-10,0.000000000000000000e+00 +4.229928489582275830e+01,2.916000000000000227e+02,0.000000000000000000e+00,5.955978964555196598e+00,0.000000000000000000e+00,-1.000000009970771098e+00,0.000000000000000000e+00,-7.128237249121595698e-11,0.000000000000000000e+00 +4.230096388093326709e+01,2.916100000000000136e+02,0.000000000000000000e+00,5.954299979427945644e+00,0.000000000000000000e+00,-1.000000009970890780e+00,0.000000000000000000e+00,1.500606411719722436e-10,0.000000000000000000e+00 +4.230264333948163369e+01,2.916200000000000045e+02,0.000000000000000000e+00,5.952620520862831555e+00,0.000000000000000000e+00,-1.000000009970638759e+00,0.000000000000000000e+00,-4.692202814973855992e-11,0.000000000000000000e+00 +4.230432327186854735e+01,2.916299999999999955e+02,0.000000000000000000e+00,5.950940588459168623e+00,0.000000000000000000e+00,-1.000000009970717585e+00,0.000000000000000000e+00,4.862657246980037890e-11,0.000000000000000000e+00 +4.230600367849525867e+01,2.916399999999999864e+02,0.000000000000000000e+00,5.949260181815704485e+00,0.000000000000000000e+00,-1.000000009970635872e+00,0.000000000000000000e+00,-1.097751936260682599e-10,0.000000000000000000e+00 +4.230768455976357956e+01,2.916500000000000341e+02,0.000000000000000000e+00,5.947579300530621005e+00,0.000000000000000000e+00,-1.000000009970820392e+00,0.000000000000000000e+00,1.892459775034800396e-10,0.000000000000000000e+00 +4.230936591607590458e+01,2.916600000000000250e+02,0.000000000000000000e+00,5.945897944201531615e+00,0.000000000000000000e+00,-1.000000009970502202e+00,0.000000000000000000e+00,-2.261596061185416666e-10,0.000000000000000000e+00 +4.231104774783518252e+01,2.916700000000000159e+02,0.000000000000000000e+00,5.944216112425482201e+00,0.000000000000000000e+00,-1.000000009970882564e+00,0.000000000000000000e+00,-1.478266852465224286e-11,0.000000000000000000e+00 +4.231273005544494481e+01,2.916800000000000068e+02,0.000000000000000000e+00,5.942533804798946662e+00,0.000000000000000000e+00,-1.000000009970907433e+00,0.000000000000000000e+00,2.811870633673619782e-10,0.000000000000000000e+00 +4.231441283930928421e+01,2.916899999999999977e+02,0.000000000000000000e+00,5.940851020917829572e+00,0.000000000000000000e+00,-1.000000009970434256e+00,0.000000000000000000e+00,-1.914063314812202277e-10,0.000000000000000000e+00 +4.231609609983286902e+01,2.916999999999999886e+02,0.000000000000000000e+00,5.939167760377463523e+00,0.000000000000000000e+00,-1.000000009970756443e+00,0.000000000000000000e+00,-9.007131885536273721e-11,0.000000000000000000e+00 +4.231777983742093596e+01,2.917099999999999795e+02,0.000000000000000000e+00,5.937484022772605563e+00,0.000000000000000000e+00,-1.000000009970908099e+00,0.000000000000000000e+00,4.680271344002562048e-11,0.000000000000000000e+00 +4.231946405247931153e+01,2.917200000000000273e+02,0.000000000000000000e+00,5.935799807697439867e+00,0.000000000000000000e+00,-1.000000009970829273e+00,0.000000000000000000e+00,-3.426832040357062666e-12,0.000000000000000000e+00 +4.232114874541437644e+01,2.917300000000000182e+02,0.000000000000000000e+00,5.934115114745575070e+00,0.000000000000000000e+00,-1.000000009970835047e+00,0.000000000000000000e+00,1.631236148836872397e-10,0.000000000000000000e+00 +4.232283391663310823e+01,2.917400000000000091e+02,0.000000000000000000e+00,5.932429943510042492e+00,0.000000000000000000e+00,-1.000000009970560155e+00,0.000000000000000000e+00,-2.994141215317453511e-10,0.000000000000000000e+00 +4.232451956654304581e+01,2.917500000000000000e+02,0.000000000000000000e+00,5.930744293583296134e+00,0.000000000000000000e+00,-1.000000009971064863e+00,0.000000000000000000e+00,2.649582224443135033e-10,0.000000000000000000e+00 +4.232620569555231782e+01,2.917599999999999909e+02,0.000000000000000000e+00,5.929058164557209132e+00,0.000000000000000000e+00,-1.000000009970618109e+00,0.000000000000000000e+00,-2.374993741418852770e-10,0.000000000000000000e+00 +4.232789230406963554e+01,2.917699999999999818e+02,0.000000000000000000e+00,5.927371556023077304e+00,0.000000000000000000e+00,-1.000000009971018677e+00,0.000000000000000000e+00,1.630698544621854275e-10,0.000000000000000000e+00 +4.232957939250427870e+01,2.917800000000000296e+02,0.000000000000000000e+00,5.925684467571612046e+00,0.000000000000000000e+00,-1.000000009970743564e+00,0.000000000000000000e+00,7.894597599073997894e-13,0.000000000000000000e+00 +4.233126696126611677e+01,2.917900000000000205e+02,0.000000000000000000e+00,5.923996898792944776e+00,0.000000000000000000e+00,-1.000000009970742232e+00,0.000000000000000000e+00,-2.367704791745262192e-12,0.000000000000000000e+00 +4.233295501076560896e+01,2.918000000000000114e+02,0.000000000000000000e+00,5.922308849276621601e+00,0.000000000000000000e+00,-1.000000009970746229e+00,0.000000000000000000e+00,-6.049076951935563623e-11,0.000000000000000000e+00 +4.233464354141379005e+01,2.918100000000000023e+02,0.000000000000000000e+00,5.920620318611604205e+00,0.000000000000000000e+00,-1.000000009970848369e+00,0.000000000000000000e+00,-7.440872585493903502e-11,0.000000000000000000e+00 +4.233633255362228454e+01,2.918199999999999932e+02,0.000000000000000000e+00,5.918931306386268076e+00,0.000000000000000000e+00,-1.000000009970974046e+00,0.000000000000000000e+00,5.546205741990840221e-11,0.000000000000000000e+00 +4.233802204780330669e+01,2.918299999999999841e+02,0.000000000000000000e+00,5.917241812188401617e+00,0.000000000000000000e+00,-1.000000009970880344e+00,0.000000000000000000e+00,1.187758024871657947e-10,0.000000000000000000e+00 +4.233971202436965342e+01,2.918400000000000318e+02,0.000000000000000000e+00,5.915551835605205255e+00,0.000000000000000000e+00,-1.000000009970679615e+00,0.000000000000000000e+00,-9.286560737671046072e-11,0.000000000000000000e+00 +4.234140248373471138e+01,2.918500000000000227e+02,0.000000000000000000e+00,5.913861376223289668e+00,0.000000000000000000e+00,-1.000000009970836601e+00,0.000000000000000000e+00,-1.655870817222641856e-10,0.000000000000000000e+00 +4.234309342631246409e+01,2.918600000000000136e+02,0.000000000000000000e+00,5.912170433628674004e+00,0.000000000000000000e+00,-1.000000009971116599e+00,0.000000000000000000e+00,3.145386253450133707e-10,0.000000000000000000e+00 +4.234478485251748481e+01,2.918700000000000045e+02,0.000000000000000000e+00,5.910479007406785890e+00,0.000000000000000000e+00,-1.000000009970584580e+00,0.000000000000000000e+00,-4.098593895414424404e-10,0.000000000000000000e+00 +4.234647676276493655e+01,2.918799999999999955e+02,0.000000000000000000e+00,5.908787097142461420e+00,0.000000000000000000e+00,-1.000000009971278025e+00,0.000000000000000000e+00,2.499387234967984571e-10,0.000000000000000000e+00 +4.234816915747058630e+01,2.918899999999999864e+02,0.000000000000000000e+00,5.907094702419938947e+00,0.000000000000000000e+00,-1.000000009970855031e+00,0.000000000000000000e+00,-8.119042373517664579e-11,0.000000000000000000e+00 +4.234986203705078367e+01,2.919000000000000341e+02,0.000000000000000000e+00,5.905401822822865299e+00,0.000000000000000000e+00,-1.000000009970992476e+00,0.000000000000000000e+00,2.556962098610912781e-10,0.000000000000000000e+00 +4.235155540192247514e+01,2.919100000000000250e+02,0.000000000000000000e+00,5.903708457934287779e+00,0.000000000000000000e+00,-1.000000009970559489e+00,0.000000000000000000e+00,-1.795914658624381097e-10,0.000000000000000000e+00 +4.235324925250321826e+01,2.919200000000000159e+02,0.000000000000000000e+00,5.902014607336657726e+00,0.000000000000000000e+00,-1.000000009970863690e+00,0.000000000000000000e+00,-3.826690665103669343e-11,0.000000000000000000e+00 +4.235494358921116032e+01,2.919300000000000068e+02,0.000000000000000000e+00,5.900320270611825180e+00,0.000000000000000000e+00,-1.000000009970928527e+00,0.000000000000000000e+00,-1.376951131873533487e-10,0.000000000000000000e+00 +4.235663841246504546e+01,2.919399999999999977e+02,0.000000000000000000e+00,5.898625447341041550e+00,0.000000000000000000e+00,-1.000000009971161896e+00,0.000000000000000000e+00,2.522593825289042809e-10,0.000000000000000000e+00 +4.235833372268422892e+01,2.919499999999999886e+02,0.000000000000000000e+00,5.896930137104956060e+00,0.000000000000000000e+00,-1.000000009970734238e+00,0.000000000000000000e+00,-3.002411831239207609e-10,0.000000000000000000e+00 +4.236002952028866275e+01,2.919599999999999795e+02,0.000000000000000000e+00,5.895234339483616637e+00,0.000000000000000000e+00,-1.000000009971243387e+00,0.000000000000000000e+00,1.730504583363177355e-10,0.000000000000000000e+00 +4.236172580569890300e+01,2.919700000000000273e+02,0.000000000000000000e+00,5.893538054056464581e+00,0.000000000000000000e+00,-1.000000009970949844e+00,0.000000000000000000e+00,-6.634745627135679444e-11,0.000000000000000000e+00 +4.236342257933610966e+01,2.919800000000000182e+02,0.000000000000000000e+00,5.891841280402339009e+00,0.000000000000000000e+00,-1.000000009971062420e+00,0.000000000000000000e+00,3.328191992522888497e-10,0.000000000000000000e+00 +4.236511984162205380e+01,2.919900000000000091e+02,0.000000000000000000e+00,5.890144018099470635e+00,0.000000000000000000e+00,-1.000000009970497539e+00,0.000000000000000000e+00,-3.624120797719150831e-10,0.000000000000000000e+00 +4.236681759297911043e+01,2.920000000000000000e+02,0.000000000000000000e+00,5.888446266725484435e+00,0.000000000000000000e+00,-1.000000009971112824e+00,0.000000000000000000e+00,1.242122838671468871e-10,0.000000000000000000e+00 +4.236851583383026565e+01,2.920099999999999909e+02,0.000000000000000000e+00,5.886748025857393429e+00,0.000000000000000000e+00,-1.000000009970901882e+00,0.000000000000000000e+00,-2.450851199427586921e-10,0.000000000000000000e+00 +4.237021456459911661e+01,2.920199999999999818e+02,0.000000000000000000e+00,5.885049295071604014e+00,0.000000000000000000e+00,-1.000000009971318216e+00,0.000000000000000000e+00,1.897391483139714020e-10,0.000000000000000000e+00 +4.237191378570987155e+01,2.920300000000000296e+02,0.000000000000000000e+00,5.883350073943908853e+00,0.000000000000000000e+00,-1.000000009970995807e+00,0.000000000000000000e+00,1.149602205667985513e-11,0.000000000000000000e+00 +4.237361349758734264e+01,2.920400000000000205e+02,0.000000000000000000e+00,5.881650362049490433e+00,0.000000000000000000e+00,-1.000000009970976267e+00,0.000000000000000000e+00,-4.205283713653997242e-11,0.000000000000000000e+00 +4.237531370065696734e+01,2.920500000000000114e+02,0.000000000000000000e+00,5.879950158962915729e+00,0.000000000000000000e+00,-1.000000009971047765e+00,0.000000000000000000e+00,1.528870726940206812e-10,0.000000000000000000e+00 +4.237701439534478709e+01,2.920600000000000023e+02,0.000000000000000000e+00,5.878249464258137102e+00,0.000000000000000000e+00,-1.000000009970787751e+00,0.000000000000000000e+00,-2.008754479530699511e-10,0.000000000000000000e+00 +4.237871558207746858e+01,2.920699999999999932e+02,0.000000000000000000e+00,5.876548277508491402e+00,0.000000000000000000e+00,-1.000000009971129478e+00,0.000000000000000000e+00,2.501408646434505729e-10,0.000000000000000000e+00 +4.238041726128229669e+01,2.920799999999999841e+02,0.000000000000000000e+00,5.874846598286696420e+00,0.000000000000000000e+00,-1.000000009970703818e+00,0.000000000000000000e+00,-2.078033441115391410e-10,0.000000000000000000e+00 +4.238211943338716736e+01,2.920900000000000318e+02,0.000000000000000000e+00,5.873144426164853549e+00,0.000000000000000000e+00,-1.000000009971057535e+00,0.000000000000000000e+00,-2.202624957046692149e-10,0.000000000000000000e+00 +4.238382209882060181e+01,2.921000000000000227e+02,0.000000000000000000e+00,5.871441760714441571e+00,0.000000000000000000e+00,-1.000000009971432569e+00,0.000000000000000000e+00,3.407929219380612200e-10,0.000000000000000000e+00 +4.238552525801173942e+01,2.921100000000000136e+02,0.000000000000000000e+00,5.869738601506319320e+00,0.000000000000000000e+00,-1.000000009970852144e+00,0.000000000000000000e+00,-2.319951944036723895e-10,0.000000000000000000e+00 +4.238722891139034488e+01,2.921200000000000045e+02,0.000000000000000000e+00,5.868034948110724791e+00,0.000000000000000000e+00,-1.000000009971247383e+00,0.000000000000000000e+00,3.348621339470572598e-10,0.000000000000000000e+00 +4.238893305938680811e+01,2.921299999999999955e+02,0.000000000000000000e+00,5.866330800097268927e+00,0.000000000000000000e+00,-1.000000009970676729e+00,0.000000000000000000e+00,-2.735432920220995584e-10,0.000000000000000000e+00 +4.239063770243213725e+01,2.921399999999999864e+02,0.000000000000000000e+00,5.864626157034940945e+00,0.000000000000000000e+00,-1.000000009971143022e+00,0.000000000000000000e+00,-8.946173068753458317e-11,0.000000000000000000e+00 +4.239234284095797278e+01,2.921500000000000341e+02,0.000000000000000000e+00,5.862921018492100345e+00,0.000000000000000000e+00,-1.000000009971295567e+00,0.000000000000000000e+00,1.036256665081161518e-10,0.000000000000000000e+00 +4.239404847539658761e+01,2.921600000000000250e+02,0.000000000000000000e+00,5.861215384036481346e+00,0.000000000000000000e+00,-1.000000009971118820e+00,0.000000000000000000e+00,1.357413658265038697e-10,0.000000000000000000e+00 +4.239575460618086566e+01,2.921700000000000159e+02,0.000000000000000000e+00,5.859509253235189341e+00,0.000000000000000000e+00,-1.000000009970887227e+00,0.000000000000000000e+00,-1.610727652480195917e-10,0.000000000000000000e+00 +4.239746123374433751e+01,2.921800000000000068e+02,0.000000000000000000e+00,5.857802625654699114e+00,0.000000000000000000e+00,-1.000000009971162118e+00,0.000000000000000000e+00,-4.006135886806310689e-11,0.000000000000000000e+00 +4.239916835852115895e+01,2.921899999999999977e+02,0.000000000000000000e+00,5.856095500860853065e+00,0.000000000000000000e+00,-1.000000009971230508e+00,0.000000000000000000e+00,3.319702693560024172e-10,0.000000000000000000e+00 +4.240087598094612531e+01,2.921999999999999886e+02,0.000000000000000000e+00,5.854387878418862101e+00,0.000000000000000000e+00,-1.000000009970663628e+00,0.000000000000000000e+00,-4.276786951251233651e-10,0.000000000000000000e+00 +4.240258410145465007e+01,2.922099999999999795e+02,0.000000000000000000e+00,5.852679757893303858e+00,0.000000000000000000e+00,-1.000000009971394155e+00,0.000000000000000000e+00,2.567922586038033290e-10,0.000000000000000000e+00 +4.240429272048280041e+01,2.922200000000000273e+02,0.000000000000000000e+00,5.850971138848117370e+00,0.000000000000000000e+00,-1.000000009970955395e+00,0.000000000000000000e+00,-2.116358640598910517e-10,0.000000000000000000e+00 +4.240600183846726878e+01,2.922300000000000182e+02,0.000000000000000000e+00,5.849262020846609289e+00,0.000000000000000000e+00,-1.000000009971317105e+00,0.000000000000000000e+00,1.348151363353706757e-10,0.000000000000000000e+00 +4.240771145584538715e+01,2.922400000000000091e+02,0.000000000000000000e+00,5.847552403451445002e+00,0.000000000000000000e+00,-1.000000009971086623e+00,0.000000000000000000e+00,-7.998251573329207399e-11,0.000000000000000000e+00 +4.240942157305512694e+01,2.922500000000000000e+02,0.000000000000000000e+00,5.845842286224653073e+00,0.000000000000000000e+00,-1.000000009971223403e+00,0.000000000000000000e+00,2.004170271947739318e-10,0.000000000000000000e+00 +4.241113219053510619e+01,2.922599999999999909e+02,0.000000000000000000e+00,5.844131668727619910e+00,0.000000000000000000e+00,-1.000000009970880566e+00,0.000000000000000000e+00,-9.200394564263541742e-11,0.000000000000000000e+00 +4.241284330872457531e+01,2.922699999999999818e+02,0.000000000000000000e+00,5.842420550521091549e+00,0.000000000000000000e+00,-1.000000009971037995e+00,0.000000000000000000e+00,-2.032834567936914037e-10,0.000000000000000000e+00 +4.241455492806343130e+01,2.922800000000000296e+02,0.000000000000000000e+00,5.840708931165169204e+00,0.000000000000000000e+00,-1.000000009971385939e+00,0.000000000000000000e+00,1.478463614097045978e-11,0.000000000000000000e+00 +4.241626704899221778e+01,2.922900000000000205e+02,0.000000000000000000e+00,5.838996810219310163e+00,0.000000000000000000e+00,-1.000000009971360626e+00,0.000000000000000000e+00,1.050179369305768454e-10,0.000000000000000000e+00 +4.241797967195212493e+01,2.923000000000000114e+02,0.000000000000000000e+00,5.837284187242326894e+00,0.000000000000000000e+00,-1.000000009971180770e+00,0.000000000000000000e+00,2.180103209723858965e-10,0.000000000000000000e+00 +4.241969279738498244e+01,2.923100000000000023e+02,0.000000000000000000e+00,5.835571061792384384e+00,0.000000000000000000e+00,-1.000000009970807291e+00,0.000000000000000000e+00,-4.016846919875670070e-10,0.000000000000000000e+00 +4.242140642573328080e+01,2.923199999999999932e+02,0.000000000000000000e+00,5.833857433426999251e+00,0.000000000000000000e+00,-1.000000009971495629e+00,0.000000000000000000e+00,2.129599079426555287e-10,0.000000000000000000e+00 +4.242312055744014998e+01,2.923299999999999841e+02,0.000000000000000000e+00,5.832143301703036187e+00,0.000000000000000000e+00,-1.000000009971130588e+00,0.000000000000000000e+00,9.880819138884204648e-11,0.000000000000000000e+00 +4.242483519294937366e+01,2.923400000000000318e+02,0.000000000000000000e+00,5.830428666176712404e+00,0.000000000000000000e+00,-1.000000009970961168e+00,0.000000000000000000e+00,-2.857215812002601401e-10,0.000000000000000000e+00 +4.242655033270539633e+01,2.923500000000000227e+02,0.000000000000000000e+00,5.828713526403590528e+00,0.000000000000000000e+00,-1.000000009971451220e+00,0.000000000000000000e+00,1.208814922306834140e-10,0.000000000000000000e+00 +4.242826597715330195e+01,2.923600000000000136e+02,0.000000000000000000e+00,5.826997881938578594e+00,0.000000000000000000e+00,-1.000000009971243831e+00,0.000000000000000000e+00,-3.389896019596399969e-11,0.000000000000000000e+00 +4.242998212673883529e+01,2.923700000000000045e+02,0.000000000000000000e+00,5.825281732335931828e+00,0.000000000000000000e+00,-1.000000009971302006e+00,0.000000000000000000e+00,3.136670523521319681e-10,0.000000000000000000e+00 +4.243169878190840194e+01,2.923799999999999955e+02,0.000000000000000000e+00,5.823565077149247315e+00,0.000000000000000000e+00,-1.000000009970763548e+00,0.000000000000000000e+00,-4.852971299160984546e-10,0.000000000000000000e+00 +4.243341594310906117e+01,2.923899999999999864e+02,0.000000000000000000e+00,5.821847915931465778e+00,0.000000000000000000e+00,-1.000000009971596882e+00,0.000000000000000000e+00,1.398712133901602085e-10,0.000000000000000000e+00 +4.243513361078853308e+01,2.924000000000000341e+02,0.000000000000000000e+00,5.820130248234865356e+00,0.000000000000000000e+00,-1.000000009971356629e+00,0.000000000000000000e+00,2.420531320922215188e-10,0.000000000000000000e+00 +4.243685178539519853e+01,2.924100000000000250e+02,0.000000000000000000e+00,5.818412073611067825e+00,0.000000000000000000e+00,-1.000000009970940740e+00,0.000000000000000000e+00,-3.153642651839620314e-10,0.000000000000000000e+00 +4.243857046737809924e+01,2.924200000000000159e+02,0.000000000000000000e+00,5.816693391611031494e+00,0.000000000000000000e+00,-1.000000009971482751e+00,0.000000000000000000e+00,1.348394263099165689e-10,0.000000000000000000e+00 +4.244028965718693769e+01,2.924300000000000068e+02,0.000000000000000000e+00,5.814974201785049424e+00,0.000000000000000000e+00,-1.000000009971250936e+00,0.000000000000000000e+00,-4.622437464438905935e-11,0.000000000000000000e+00 +4.244200935527208429e+01,2.924399999999999977e+02,0.000000000000000000e+00,5.813254503682752983e+00,0.000000000000000000e+00,-1.000000009971330428e+00,0.000000000000000000e+00,2.096262122548606944e-10,0.000000000000000000e+00 +4.244372956208457737e+01,2.924499999999999886e+02,0.000000000000000000e+00,5.811534296853105630e+00,0.000000000000000000e+00,-1.000000009970969828e+00,0.000000000000000000e+00,-1.316228233692077638e-10,0.000000000000000000e+00 +4.244545027807612314e+01,2.924599999999999795e+02,0.000000000000000000e+00,5.809813580844404690e+00,0.000000000000000000e+00,-1.000000009971196313e+00,0.000000000000000000e+00,-5.160151044986708905e-13,0.000000000000000000e+00 +4.244717150369908865e+01,2.924700000000000273e+02,0.000000000000000000e+00,5.808092355204276913e+00,0.000000000000000000e+00,-1.000000009971197201e+00,0.000000000000000000e+00,-1.274179705510875140e-10,0.000000000000000000e+00 +4.244889323940651593e+01,2.924800000000000182e+02,0.000000000000000000e+00,5.806370619479680251e+00,0.000000000000000000e+00,-1.000000009971416581e+00,0.000000000000000000e+00,-4.203030861017200121e-11,0.000000000000000000e+00 +4.245061548565212206e+01,2.924900000000000091e+02,0.000000000000000000e+00,5.804648373216900303e+00,0.000000000000000000e+00,-1.000000009971488968e+00,0.000000000000000000e+00,1.285024182195393266e-10,0.000000000000000000e+00 +4.245233824289029201e+01,2.925000000000000000e+02,0.000000000000000000e+00,5.802925615961550321e+00,0.000000000000000000e+00,-1.000000009971267589e+00,0.000000000000000000e+00,-4.174766975609905330e-11,0.000000000000000000e+00 +4.245406151157609287e+01,2.925099999999999909e+02,0.000000000000000000e+00,5.801202347258569425e+00,0.000000000000000000e+00,-1.000000009971339532e+00,0.000000000000000000e+00,-7.870447924884750745e-11,0.000000000000000000e+00 +4.245578529216525254e+01,2.925199999999999818e+02,0.000000000000000000e+00,5.799478566652219946e+00,0.000000000000000000e+00,-1.000000009971475201e+00,0.000000000000000000e+00,1.926463418946804402e-10,0.000000000000000000e+00 +4.245750958511418816e+01,2.925300000000000296e+02,0.000000000000000000e+00,5.797754273686087423e+00,0.000000000000000000e+00,-1.000000009971143022e+00,0.000000000000000000e+00,5.265302633755929827e-11,0.000000000000000000e+00 +4.245923439087999895e+01,2.925400000000000205e+02,0.000000000000000000e+00,5.796029467903079713e+00,0.000000000000000000e+00,-1.000000009971052206e+00,0.000000000000000000e+00,-3.203285935529268408e-10,0.000000000000000000e+00 +4.246095970992045210e+01,2.925500000000000114e+02,0.000000000000000000e+00,5.794304148845423441e+00,0.000000000000000000e+00,-1.000000009971604875e+00,0.000000000000000000e+00,1.477009883926637931e-10,0.000000000000000000e+00 +4.246268554269400397e+01,2.925600000000000023e+02,0.000000000000000000e+00,5.792578316054663112e+00,0.000000000000000000e+00,-1.000000009971349968e+00,0.000000000000000000e+00,1.448273319910054094e-10,0.000000000000000000e+00 +4.246441188965979308e+01,2.925699999999999932e+02,0.000000000000000000e+00,5.790851969071662886e+00,0.000000000000000000e+00,-1.000000009971099946e+00,0.000000000000000000e+00,-1.465843278923116988e-10,0.000000000000000000e+00 +4.246613875127763293e+01,2.925799999999999841e+02,0.000000000000000000e+00,5.789125107436601247e+00,0.000000000000000000e+00,-1.000000009971353077e+00,0.000000000000000000e+00,-2.460339810913238091e-10,0.000000000000000000e+00 +4.246786612800804050e+01,2.925900000000000318e+02,0.000000000000000000e+00,5.787397730688970121e+00,0.000000000000000000e+00,-1.000000009971778070e+00,0.000000000000000000e+00,3.270478826556606053e-10,0.000000000000000000e+00 +4.246959402031220776e+01,2.926000000000000227e+02,0.000000000000000000e+00,5.785669838367574869e+00,0.000000000000000000e+00,-1.000000009971212966e+00,0.000000000000000000e+00,-2.762055062997045503e-11,0.000000000000000000e+00 +4.247132242865201590e+01,2.926100000000000136e+02,0.000000000000000000e+00,5.783941430010534290e+00,0.000000000000000000e+00,-1.000000009971260706e+00,0.000000000000000000e+00,6.614108897141480198e-11,0.000000000000000000e+00 +4.247305135349003535e+01,2.926200000000000045e+02,0.000000000000000000e+00,5.782212505155274407e+00,0.000000000000000000e+00,-1.000000009971146353e+00,0.000000000000000000e+00,-3.931329637559921581e-10,0.000000000000000000e+00 +4.247478079528953288e+01,2.926299999999999955e+02,0.000000000000000000e+00,5.780483063338531124e+00,0.000000000000000000e+00,-1.000000009971826254e+00,0.000000000000000000e+00,2.676149787786038996e-10,0.000000000000000000e+00 +4.247651075451446445e+01,2.926399999999999864e+02,0.000000000000000000e+00,5.778753104096345794e+00,0.000000000000000000e+00,-1.000000009971363291e+00,0.000000000000000000e+00,1.594944200798255678e-10,0.000000000000000000e+00 +4.247824123162948950e+01,2.926500000000000341e+02,0.000000000000000000e+00,5.777022626964068763e+00,0.000000000000000000e+00,-1.000000009971087289e+00,0.000000000000000000e+00,-2.285872451601715979e-10,0.000000000000000000e+00 +4.247997222709994958e+01,2.926600000000000250e+02,0.000000000000000000e+00,5.775291631476352272e+00,0.000000000000000000e+00,-1.000000009971482973e+00,0.000000000000000000e+00,-1.118228688012341371e-10,0.000000000000000000e+00 +4.248170374139188255e+01,2.926700000000000159e+02,0.000000000000000000e+00,5.773560117167150452e+00,0.000000000000000000e+00,-1.000000009971676596e+00,0.000000000000000000e+00,4.054927649343941603e-10,0.000000000000000000e+00 +4.248343577497204393e+01,2.926800000000000068e+02,0.000000000000000000e+00,5.771828083569720214e+00,0.000000000000000000e+00,-1.000000009970974268e+00,0.000000000000000000e+00,-5.536526197729416450e-10,0.000000000000000000e+00 +4.248516832830787138e+01,2.926899999999999977e+02,0.000000000000000000e+00,5.770095530216619473e+00,0.000000000000000000e+00,-1.000000009971933501e+00,0.000000000000000000e+00,4.612386896591897566e-10,0.000000000000000000e+00 +4.248690140186750597e+01,2.926999999999999886e+02,0.000000000000000000e+00,5.768362456639700042e+00,0.000000000000000000e+00,-1.000000009971134141e+00,0.000000000000000000e+00,-1.985292332260865058e-10,0.000000000000000000e+00 +4.248863499611980643e+01,2.927099999999999795e+02,0.000000000000000000e+00,5.766628862370116515e+00,0.000000000000000000e+00,-1.000000009971478310e+00,0.000000000000000000e+00,3.111490650811040407e-11,0.000000000000000000e+00 +4.249036911153432072e+01,2.927200000000000273e+02,0.000000000000000000e+00,5.764894746938313830e+00,0.000000000000000000e+00,-1.000000009971424353e+00,0.000000000000000000e+00,-1.283903967847861113e-10,0.000000000000000000e+00 +4.249210374858130734e+01,2.927300000000000182e+02,0.000000000000000000e+00,5.763160109874033488e+00,0.000000000000000000e+00,-1.000000009971647064e+00,0.000000000000000000e+00,1.140193641257561704e-10,0.000000000000000000e+00 +4.249383890773172823e+01,2.927400000000000091e+02,0.000000000000000000e+00,5.761424950706308223e+00,0.000000000000000000e+00,-1.000000009971449222e+00,0.000000000000000000e+00,7.458280096321384089e-11,0.000000000000000000e+00 +4.249557458945726296e+01,2.927500000000000000e+02,0.000000000000000000e+00,5.759689268963462894e+00,0.000000000000000000e+00,-1.000000009971319770e+00,0.000000000000000000e+00,-4.297130638812259692e-11,0.000000000000000000e+00 +4.249731079423030167e+01,2.927599999999999909e+02,0.000000000000000000e+00,5.757953064173110924e+00,0.000000000000000000e+00,-1.000000009971394377e+00,0.000000000000000000e+00,-3.477580964206441495e-11,0.000000000000000000e+00 +4.249904752252394502e+01,2.927699999999999818e+02,0.000000000000000000e+00,5.756216335862153421e+00,0.000000000000000000e+00,-1.000000009971454773e+00,0.000000000000000000e+00,1.009728057906023289e-11,0.000000000000000000e+00 +4.250078477481199712e+01,2.927800000000000296e+02,0.000000000000000000e+00,5.754479083556778285e+00,0.000000000000000000e+00,-1.000000009971437231e+00,0.000000000000000000e+00,3.961028207438935321e-12,0.000000000000000000e+00 +4.250252255156898684e+01,2.927900000000000205e+02,0.000000000000000000e+00,5.752741306782458430e+00,0.000000000000000000e+00,-1.000000009971430348e+00,0.000000000000000000e+00,-1.396160131575558287e-10,0.000000000000000000e+00 +4.250426085327016068e+01,2.928000000000000114e+02,0.000000000000000000e+00,5.751003005063950013e+00,0.000000000000000000e+00,-1.000000009971673043e+00,0.000000000000000000e+00,8.287594944281781225e-11,0.000000000000000000e+00 +4.250599968039148280e+01,2.928100000000000023e+02,0.000000000000000000e+00,5.749264177925290653e+00,0.000000000000000000e+00,-1.000000009971528936e+00,0.000000000000000000e+00,0.000000000000000000e+00,0.000000000000000000e+00 +4.250773903340962789e+01,2.928199999999999932e+02,0.000000000000000000e+00,5.747524824889799433e+00,0.000000000000000000e+00,-1.000000009971528936e+00,0.000000000000000000e+00,1.169005501200150138e-10,0.000000000000000000e+00 +4.250947891280200253e+01,2.928299999999999841e+02,0.000000000000000000e+00,5.745784945480073347e+00,0.000000000000000000e+00,-1.000000009971325543e+00,0.000000000000000000e+00,-2.333475782663863932e-10,0.000000000000000000e+00 +4.251121931904673090e+01,2.928400000000000318e+02,0.000000000000000000e+00,5.744044539217987300e+00,0.000000000000000000e+00,-1.000000009971731663e+00,0.000000000000000000e+00,4.323721600296476347e-11,0.000000000000000000e+00 +4.251296025262266909e+01,2.928500000000000227e+02,0.000000000000000000e+00,5.742303605624690555e+00,0.000000000000000000e+00,-1.000000009971656389e+00,0.000000000000000000e+00,2.816580005854372551e-10,0.000000000000000000e+00 +4.251470171400938369e+01,2.928600000000000136e+02,0.000000000000000000e+00,5.740562144220608509e+00,0.000000000000000000e+00,-1.000000009971165893e+00,0.000000000000000000e+00,-4.717519818289266091e-10,0.000000000000000000e+00 +4.251644370368718029e+01,2.928700000000000045e+02,0.000000000000000000e+00,5.738820154525439143e+00,0.000000000000000000e+00,-1.000000009971987680e+00,0.000000000000000000e+00,3.423974382956685844e-10,0.000000000000000000e+00 +4.251818622213709631e+01,2.928799999999999955e+02,0.000000000000000000e+00,5.737077636058148578e+00,0.000000000000000000e+00,-1.000000009971391046e+00,0.000000000000000000e+00,1.681531021002048884e-11,0.000000000000000000e+00 +4.251992926984088683e+01,2.928899999999999864e+02,0.000000000000000000e+00,5.735334588336977291e+00,0.000000000000000000e+00,-1.000000009971361736e+00,0.000000000000000000e+00,-5.756220464566283102e-11,0.000000000000000000e+00 +4.252167284728104590e+01,2.929000000000000341e+02,0.000000000000000000e+00,5.733591010879430350e+00,0.000000000000000000e+00,-1.000000009971462100e+00,0.000000000000000000e+00,-2.431645736051748877e-10,0.000000000000000000e+00 +4.252341695494080653e+01,2.929100000000000250e+02,0.000000000000000000e+00,5.731846903202280075e+00,0.000000000000000000e+00,-1.000000009971886206e+00,0.000000000000000000e+00,2.658723947843624944e-10,0.000000000000000000e+00 +4.252516159330412648e+01,2.929200000000000159e+02,0.000000000000000000e+00,5.730102264821563374e+00,0.000000000000000000e+00,-1.000000009971422354e+00,0.000000000000000000e+00,-5.674628789332597454e-11,0.000000000000000000e+00 +4.252690676285570248e+01,2.929300000000000068e+02,0.000000000000000000e+00,5.728357095252582631e+00,0.000000000000000000e+00,-1.000000009971521386e+00,0.000000000000000000e+00,-1.101509382481488467e-10,0.000000000000000000e+00 +4.252865246408097732e+01,2.929399999999999977e+02,0.000000000000000000e+00,5.726611394009899492e+00,0.000000000000000000e+00,-1.000000009971713677e+00,0.000000000000000000e+00,4.056286494889333687e-11,0.000000000000000000e+00 +4.253039869746612567e+01,2.929499999999999886e+02,0.000000000000000000e+00,5.724865160607336634e+00,0.000000000000000000e+00,-1.000000009971642845e+00,0.000000000000000000e+00,4.093184861532344523e-11,0.000000000000000000e+00 +4.253214546349806824e+01,2.929599999999999795e+02,0.000000000000000000e+00,5.723118394557975996e+00,0.000000000000000000e+00,-1.000000009971571346e+00,0.000000000000000000e+00,1.200894246901570836e-10,0.000000000000000000e+00 +4.253389276266446473e+01,2.929700000000000273e+02,0.000000000000000000e+00,5.721371095374156113e+00,0.000000000000000000e+00,-1.000000009971361514e+00,0.000000000000000000e+00,-3.634613211259787650e-10,0.000000000000000000e+00 +4.253564059545372089e+01,2.929800000000000182e+02,0.000000000000000000e+00,5.719623262567471222e+00,0.000000000000000000e+00,-1.000000009971996784e+00,0.000000000000000000e+00,2.757194939702940677e-10,0.000000000000000000e+00 +4.253738896235498856e+01,2.929900000000000091e+02,0.000000000000000000e+00,5.717874895648767719e+00,0.000000000000000000e+00,-1.000000009971514725e+00,0.000000000000000000e+00,-5.446683837802715959e-11,0.000000000000000000e+00 +4.253913786385817275e+01,2.930000000000000000e+02,0.000000000000000000e+00,5.716125994128147703e+00,0.000000000000000000e+00,-1.000000009971609982e+00,0.000000000000000000e+00,4.302706440050134652e-11,0.000000000000000000e+00 +4.254088730045391742e+01,2.930099999999999909e+02,0.000000000000000000e+00,5.714376557514960986e+00,0.000000000000000000e+00,-1.000000009971534709e+00,0.000000000000000000e+00,-6.699509441361105014e-11,0.000000000000000000e+00 +4.254263727263361972e+01,2.930199999999999818e+02,0.000000000000000000e+00,5.712626585317807759e+00,0.000000000000000000e+00,-1.000000009971651949e+00,0.000000000000000000e+00,-1.470142721423281880e-10,0.000000000000000000e+00 +4.254438778088943707e+01,2.930300000000000296e+02,0.000000000000000000e+00,5.710876077044535037e+00,0.000000000000000000e+00,-1.000000009971909298e+00,0.000000000000000000e+00,3.304588393322051664e-10,0.000000000000000000e+00 +4.254613882571427297e+01,2.930400000000000205e+02,0.000000000000000000e+00,5.709125032202235772e+00,0.000000000000000000e+00,-1.000000009971330650e+00,0.000000000000000000e+00,-1.325993711206127739e-10,0.000000000000000000e+00 +4.254789040760179120e+01,2.930500000000000114e+02,0.000000000000000000e+00,5.707373450297248851e+00,0.000000000000000000e+00,-1.000000009971562909e+00,0.000000000000000000e+00,-1.363605635633611047e-10,0.000000000000000000e+00 +4.254964252704641581e+01,2.930600000000000023e+02,0.000000000000000000e+00,5.705621330835152882e+00,0.000000000000000000e+00,-1.000000009971801829e+00,0.000000000000000000e+00,-1.760994383617400825e-11,0.000000000000000000e+00 +4.255139518454332404e+01,2.930699999999999932e+02,0.000000000000000000e+00,5.703868673320768856e+00,0.000000000000000000e+00,-1.000000009971832693e+00,0.000000000000000000e+00,1.776918112354817001e-10,0.000000000000000000e+00 +4.255314838058845339e+01,2.930799999999999841e+02,0.000000000000000000e+00,5.702115477258157483e+00,0.000000000000000000e+00,-1.000000009971521164e+00,0.000000000000000000e+00,-1.718130238668029704e-10,0.000000000000000000e+00 +4.255490211567850878e+01,2.930900000000000318e+02,0.000000000000000000e+00,5.700361742150617417e+00,0.000000000000000000e+00,-1.000000009971822479e+00,0.000000000000000000e+00,4.683217912572709012e-11,0.000000000000000000e+00 +4.255665639031094827e+01,2.931000000000000227e+02,0.000000000000000000e+00,5.698607467500681700e+00,0.000000000000000000e+00,-1.000000009971740322e+00,0.000000000000000000e+00,2.148555884277349471e-10,0.000000000000000000e+00 +4.255841120498401153e+01,2.931100000000000136e+02,0.000000000000000000e+00,5.696852652810119544e+00,0.000000000000000000e+00,-1.000000009971363291e+00,0.000000000000000000e+00,-2.836029999198139466e-10,0.000000000000000000e+00 +4.256016656019669853e+01,2.931200000000000045e+02,0.000000000000000000e+00,5.695097297579932771e+00,0.000000000000000000e+00,-1.000000009971861115e+00,0.000000000000000000e+00,-4.463916671961145796e-11,0.000000000000000000e+00 +4.256192245644876948e+01,2.931299999999999955e+02,0.000000000000000000e+00,5.693341401310352268e+00,0.000000000000000000e+00,-1.000000009971939496e+00,0.000000000000000000e+00,3.179401991525562561e-10,0.000000000000000000e+00 +4.256367889424076623e+01,2.931399999999999864e+02,0.000000000000000000e+00,5.691584963500840644e+00,0.000000000000000000e+00,-1.000000009971381054e+00,0.000000000000000000e+00,-3.815369132811116733e-10,0.000000000000000000e+00 +4.256543587407399798e+01,2.931500000000000341e+02,0.000000000000000000e+00,5.689827983650088683e+00,0.000000000000000000e+00,-1.000000009972051407e+00,0.000000000000000000e+00,4.132567029584297213e-10,0.000000000000000000e+00 +4.256719339645054845e+01,2.931600000000000250e+02,0.000000000000000000e+00,5.688070461256010013e+00,0.000000000000000000e+00,-1.000000009971325099e+00,0.000000000000000000e+00,-2.058698734119189944e-10,0.000000000000000000e+00 +4.256895146187328294e+01,2.931700000000000159e+02,0.000000000000000000e+00,5.686312395815747323e+00,0.000000000000000000e+00,-1.000000009971687032e+00,0.000000000000000000e+00,-2.558057968543071183e-10,0.000000000000000000e+00 +4.257071007084583414e+01,2.931800000000000068e+02,0.000000000000000000e+00,5.684553786825661703e+00,0.000000000000000000e+00,-1.000000009972136894e+00,0.000000000000000000e+00,2.331328651076657703e-10,0.000000000000000000e+00 +4.257246922387261634e+01,2.931899999999999977e+02,0.000000000000000000e+00,5.682794633781337090e+00,0.000000000000000000e+00,-1.000000009971726778e+00,0.000000000000000000e+00,8.555233769644279383e-11,0.000000000000000000e+00 +4.257422892145882543e+01,2.931999999999999886e+02,0.000000000000000000e+00,5.681034936177578487e+00,0.000000000000000000e+00,-1.000000009971576231e+00,0.000000000000000000e+00,-1.494810142193088328e-10,0.000000000000000000e+00 +4.257598916411044598e+01,2.932099999999999795e+02,0.000000000000000000e+00,5.679274693508406635e+00,0.000000000000000000e+00,-1.000000009971839354e+00,0.000000000000000000e+00,7.667198017931278594e-11,0.000000000000000000e+00 +4.257774995233423709e+01,2.932200000000000273e+02,0.000000000000000000e+00,5.677513905267058014e+00,0.000000000000000000e+00,-1.000000009971704351e+00,0.000000000000000000e+00,-1.177457684136003555e-10,0.000000000000000000e+00 +4.257951128663774654e+01,2.932300000000000182e+02,0.000000000000000000e+00,5.675752570945984843e+00,0.000000000000000000e+00,-1.000000009971911741e+00,0.000000000000000000e+00,1.048544837406919404e-10,0.000000000000000000e+00 +4.258127316752931080e+01,2.932400000000000091e+02,0.000000000000000000e+00,5.673990690036850637e+00,0.000000000000000000e+00,-1.000000009971727000e+00,0.000000000000000000e+00,-1.331692125321237901e-10,0.000000000000000000e+00 +4.258303559551805506e+01,2.932500000000000000e+02,0.000000000000000000e+00,5.672228262030531099e+00,0.000000000000000000e+00,-1.000000009971961701e+00,0.000000000000000000e+00,2.938384765575558856e-10,0.000000000000000000e+00 +4.258479857111389322e+01,2.932599999999999909e+02,0.000000000000000000e+00,5.670465286417109674e+00,0.000000000000000000e+00,-1.000000009971443671e+00,0.000000000000000000e+00,-3.449923654482241041e-10,0.000000000000000000e+00 +4.258656209482754207e+01,2.932699999999999818e+02,0.000000000000000000e+00,5.668701762685879331e+00,0.000000000000000000e+00,-1.000000009972052073e+00,0.000000000000000000e+00,2.209026649050142701e-10,0.000000000000000000e+00 +4.258832616717049291e+01,2.932800000000000296e+02,0.000000000000000000e+00,5.666937690325335453e+00,0.000000000000000000e+00,-1.000000009971662385e+00,0.000000000000000000e+00,-2.088799481367877002e-11,0.000000000000000000e+00 +4.259009078865505415e+01,2.932900000000000205e+02,0.000000000000000000e+00,5.665173068823181168e+00,0.000000000000000000e+00,-1.000000009971699244e+00,0.000000000000000000e+00,-2.246647112995204083e-10,0.000000000000000000e+00 +4.259185595979431582e+01,2.933000000000000114e+02,0.000000000000000000e+00,5.663407897666319357e+00,0.000000000000000000e+00,-1.000000009972095816e+00,0.000000000000000000e+00,1.682574028344937506e-10,0.000000000000000000e+00 +4.259362168110217084e+01,2.933100000000000023e+02,0.000000000000000000e+00,5.661642176340853538e+00,0.000000000000000000e+00,-1.000000009971798720e+00,0.000000000000000000e+00,1.018281051220724491e-11,0.000000000000000000e+00 +4.259538795309332215e+01,2.933199999999999932e+02,0.000000000000000000e+00,5.659875904332087870e+00,0.000000000000000000e+00,-1.000000009971780734e+00,0.000000000000000000e+00,1.484215737649606941e-10,0.000000000000000000e+00 +4.259715477628326852e+01,2.933299999999999841e+02,0.000000000000000000e+00,5.658109081124521822e+00,0.000000000000000000e+00,-1.000000009971518500e+00,0.000000000000000000e+00,-2.753924889425929940e-10,0.000000000000000000e+00 +4.259892215118831871e+01,2.933400000000000318e+02,0.000000000000000000e+00,5.656341706201851061e+00,0.000000000000000000e+00,-1.000000009972005222e+00,0.000000000000000000e+00,1.562414438386361925e-10,0.000000000000000000e+00 +4.260069007832557730e+01,2.933500000000000227e+02,0.000000000000000000e+00,5.654573779046963011e+00,0.000000000000000000e+00,-1.000000009971728998e+00,0.000000000000000000e+00,-2.639203096856216745e-10,0.000000000000000000e+00 +4.260245855821296601e+01,2.933600000000000136e+02,0.000000000000000000e+00,5.652805299141939521e+00,0.000000000000000000e+00,-1.000000009972195736e+00,0.000000000000000000e+00,1.676913692273103439e-10,0.000000000000000000e+00 +4.260422759136921655e+01,2.933700000000000045e+02,0.000000000000000000e+00,5.651036265968049754e+00,0.000000000000000000e+00,-1.000000009971899084e+00,0.000000000000000000e+00,3.274981320395078142e-11,0.000000000000000000e+00 +4.260599717831386357e+01,2.933799999999999955e+02,0.000000000000000000e+00,5.649266679005753744e+00,0.000000000000000000e+00,-1.000000009971841131e+00,0.000000000000000000e+00,1.848969662899708997e-10,0.000000000000000000e+00 +4.260776731956727303e+01,2.933899999999999864e+02,0.000000000000000000e+00,5.647496537734696176e+00,0.000000000000000000e+00,-1.000000009971513837e+00,0.000000000000000000e+00,-2.215811175027495365e-10,0.000000000000000000e+00 +4.260953801565060672e+01,2.934000000000000341e+02,0.000000000000000000e+00,5.645725841633707276e+00,0.000000000000000000e+00,-1.000000009971906190e+00,0.000000000000000000e+00,-4.751155233638059923e-11,0.000000000000000000e+00 +4.261130926708585065e+01,2.934100000000000250e+02,0.000000000000000000e+00,5.643954590180798370e+00,0.000000000000000000e+00,-1.000000009971990345e+00,0.000000000000000000e+00,1.477534197618793009e-10,0.000000000000000000e+00 +4.261308107439581505e+01,2.934200000000000159e+02,0.000000000000000000e+00,5.642182782853163658e+00,0.000000000000000000e+00,-1.000000009971728554e+00,0.000000000000000000e+00,-1.926831387783637370e-10,0.000000000000000000e+00 +4.261485343810412729e+01,2.934300000000000068e+02,0.000000000000000000e+00,5.640410419127176667e+00,0.000000000000000000e+00,-1.000000009972070059e+00,0.000000000000000000e+00,7.364245494405129259e-11,0.000000000000000000e+00 +4.261662635873523897e+01,2.934399999999999977e+02,0.000000000000000000e+00,5.638637498478386689e+00,0.000000000000000000e+00,-1.000000009971939496e+00,0.000000000000000000e+00,1.105541638492283505e-10,0.000000000000000000e+00 +4.261839983681441879e+01,2.934499999999999886e+02,0.000000000000000000e+00,5.636864020381520568e+00,0.000000000000000000e+00,-1.000000009971743431e+00,0.000000000000000000e+00,-6.746313967433169892e-11,0.000000000000000000e+00 +4.262017387286777392e+01,2.934599999999999795e+02,0.000000000000000000e+00,5.635089984310478251e+00,0.000000000000000000e+00,-1.000000009971863113e+00,0.000000000000000000e+00,-1.624111245409620979e-10,0.000000000000000000e+00 +4.262194846742222865e+01,2.934700000000000273e+02,0.000000000000000000e+00,5.633315389738331014e+00,0.000000000000000000e+00,-1.000000009972151327e+00,0.000000000000000000e+00,1.245843900972016178e-10,0.000000000000000000e+00 +4.262372362100553858e+01,2.934800000000000182e+02,0.000000000000000000e+00,5.631540236137320576e+00,0.000000000000000000e+00,-1.000000009971930170e+00,0.000000000000000000e+00,-3.338709848696251811e-11,0.000000000000000000e+00 +4.262549933414629066e+01,2.934900000000000091e+02,0.000000000000000000e+00,5.629764522978858210e+00,0.000000000000000000e+00,-1.000000009971989456e+00,0.000000000000000000e+00,-5.200244771595318857e-11,0.000000000000000000e+00 +4.262727560737391741e+01,2.935000000000000000e+02,0.000000000000000000e+00,5.627988249733520298e+00,0.000000000000000000e+00,-1.000000009972081827e+00,0.000000000000000000e+00,9.072563743176632212e-11,0.000000000000000000e+00 +4.262905244121866843e+01,2.935099999999999909e+02,0.000000000000000000e+00,5.626211415871048338e+00,0.000000000000000000e+00,-1.000000009971920623e+00,0.000000000000000000e+00,1.369199800603719503e-10,0.000000000000000000e+00 +4.263082983621164601e+01,2.935199999999999818e+02,0.000000000000000000e+00,5.624434020860347161e+00,0.000000000000000000e+00,-1.000000009971677262e+00,0.000000000000000000e+00,-1.683483810159757865e-10,0.000000000000000000e+00 +4.263260779288478375e+01,2.935300000000000296e+02,0.000000000000000000e+00,5.622656064169482271e+00,0.000000000000000000e+00,-1.000000009971976578e+00,0.000000000000000000e+00,4.457075186500303395e-11,0.000000000000000000e+00 +4.263438631177085369e+01,2.935400000000000205e+02,0.000000000000000000e+00,5.620877545265677178e+00,0.000000000000000000e+00,-1.000000009971897308e+00,0.000000000000000000e+00,-3.794180022966310941e-11,0.000000000000000000e+00 +4.263616539340347344e+01,2.935500000000000114e+02,0.000000000000000000e+00,5.619098463615314287e+00,0.000000000000000000e+00,-1.000000009971964809e+00,0.000000000000000000e+00,-1.050555399642959324e-10,0.000000000000000000e+00 +4.263794503831711324e+01,2.935600000000000023e+02,0.000000000000000000e+00,5.617318818683930459e+00,0.000000000000000000e+00,-1.000000009972151771e+00,0.000000000000000000e+00,1.562861058304268872e-10,0.000000000000000000e+00 +4.263972524704707467e+01,2.935699999999999932e+02,0.000000000000000000e+00,5.615538609936216119e+00,0.000000000000000000e+00,-1.000000009971873549e+00,0.000000000000000000e+00,-6.172155257818505566e-11,0.000000000000000000e+00 +4.264150602012951907e+01,2.935799999999999841e+02,0.000000000000000000e+00,5.613757836836014370e+00,0.000000000000000000e+00,-1.000000009971983461e+00,0.000000000000000000e+00,-1.624195547255641441e-10,0.000000000000000000e+00 +4.264328735810145332e+01,2.935900000000000318e+02,0.000000000000000000e+00,5.611976498846316552e+00,0.000000000000000000e+00,-1.000000009972272785e+00,0.000000000000000000e+00,1.703431145899195487e-10,0.000000000000000000e+00 +4.264506926150073696e+01,2.936000000000000227e+02,0.000000000000000000e+00,5.610194595429262243e+00,0.000000000000000000e+00,-1.000000009971969250e+00,0.000000000000000000e+00,1.362810506089132321e-10,0.000000000000000000e+00 +4.264685173086608927e+01,2.936100000000000136e+02,0.000000000000000000e+00,5.608412126046138368e+00,0.000000000000000000e+00,-1.000000009971726334e+00,0.000000000000000000e+00,-2.237835825648051147e-10,0.000000000000000000e+00 +4.264863476673707510e+01,2.936200000000000045e+02,0.000000000000000000e+00,5.606629090157374762e+00,0.000000000000000000e+00,-1.000000009972125348e+00,0.000000000000000000e+00,-2.900667657194474075e-11,0.000000000000000000e+00 +4.265041836965411903e+01,2.936299999999999955e+02,0.000000000000000000e+00,5.604845487222542388e+00,0.000000000000000000e+00,-1.000000009972177084e+00,0.000000000000000000e+00,2.049733830990058539e-10,0.000000000000000000e+00 +4.265220254015851253e+01,2.936399999999999864e+02,0.000000000000000000e+00,5.603061316700354233e+00,0.000000000000000000e+00,-1.000000009971811377e+00,0.000000000000000000e+00,-3.127741654603764074e-10,0.000000000000000000e+00 +4.265398727879240681e+01,2.936500000000000341e+02,0.000000000000000000e+00,5.601276578048661747e+00,0.000000000000000000e+00,-1.000000009972369597e+00,0.000000000000000000e+00,4.168993836732662262e-10,0.000000000000000000e+00 +4.265577258609881284e+01,2.936600000000000250e+02,0.000000000000000000e+00,5.599491270724450409e+00,0.000000000000000000e+00,-1.000000009971625303e+00,0.000000000000000000e+00,-3.440313000279039048e-10,0.000000000000000000e+00 +4.265755846262160844e+01,2.936700000000000159e+02,0.000000000000000000e+00,5.597705394183844163e+00,0.000000000000000000e+00,-1.000000009972239701e+00,0.000000000000000000e+00,-3.716391445387422345e-11,0.000000000000000000e+00 +4.265934490890554542e+01,2.936800000000000068e+02,0.000000000000000000e+00,5.595918947882094763e+00,0.000000000000000000e+00,-1.000000009972306092e+00,0.000000000000000000e+00,2.747263926076673271e-10,0.000000000000000000e+00 +4.266113192549622823e+01,2.936899999999999977e+02,0.000000000000000000e+00,5.594131931273587988e+00,0.000000000000000000e+00,-1.000000009971815151e+00,0.000000000000000000e+00,-1.874399543198422701e-10,0.000000000000000000e+00 +4.266291951294014950e+01,2.936999999999999886e+02,0.000000000000000000e+00,5.592344343811838314e+00,0.000000000000000000e+00,-1.000000009972150217e+00,0.000000000000000000e+00,2.185479807150522233e-11,0.000000000000000000e+00 +4.266470767178466872e+01,2.937099999999999795e+02,0.000000000000000000e+00,5.590556184949484475e+00,0.000000000000000000e+00,-1.000000009972111137e+00,0.000000000000000000e+00,1.267421249025662911e-10,0.000000000000000000e+00 +4.266649640257802645e+01,2.937200000000000273e+02,0.000000000000000000e+00,5.588767454138292123e+00,0.000000000000000000e+00,-1.000000009971884429e+00,0.000000000000000000e+00,-9.121024111084274924e-11,0.000000000000000000e+00 +4.266828570586932301e+01,2.937300000000000182e+02,0.000000000000000000e+00,5.586978150829149392e+00,0.000000000000000000e+00,-1.000000009972047632e+00,0.000000000000000000e+00,-1.587914695968819914e-11,0.000000000000000000e+00 +4.267007558220856112e+01,2.937400000000000091e+02,0.000000000000000000e+00,5.585188274472064229e+00,0.000000000000000000e+00,-1.000000009972076054e+00,0.000000000000000000e+00,-1.390220395621351901e-10,0.000000000000000000e+00 +4.267186603214660323e+01,2.937500000000000000e+02,0.000000000000000000e+00,5.583397824516164398e+00,0.000000000000000000e+00,-1.000000009972324966e+00,0.000000000000000000e+00,1.579458525842979130e-10,0.000000000000000000e+00 +4.267365705623521421e+01,2.937599999999999909e+02,0.000000000000000000e+00,5.581606800409693925e+00,0.000000000000000000e+00,-1.000000009972042081e+00,0.000000000000000000e+00,-1.666946835354962983e-10,0.000000000000000000e+00 +4.267544865502702578e+01,2.937699999999999818e+02,0.000000000000000000e+00,5.579815201600013097e+00,0.000000000000000000e+00,-1.000000009972340731e+00,0.000000000000000000e+00,3.392294006139459525e-10,0.000000000000000000e+00 +4.267724082907557204e+01,2.937800000000000296e+02,0.000000000000000000e+00,5.578023027533593137e+00,0.000000000000000000e+00,-1.000000009971732773e+00,0.000000000000000000e+00,-1.908636245813003988e-10,0.000000000000000000e+00 +4.267903357893526817e+01,2.937900000000000205e+02,0.000000000000000000e+00,5.576230277656018863e+00,0.000000000000000000e+00,-1.000000009972074944e+00,0.000000000000000000e+00,-2.612542601333300824e-11,0.000000000000000000e+00 +4.268082690516142463e+01,2.938000000000000114e+02,0.000000000000000000e+00,5.574436951411980701e+00,0.000000000000000000e+00,-1.000000009972121795e+00,0.000000000000000000e+00,-1.991577803744232510e-10,0.000000000000000000e+00 +4.268262080831024008e+01,2.938100000000000023e+02,0.000000000000000000e+00,5.572643048245278230e+00,0.000000000000000000e+00,-1.000000009972479065e+00,0.000000000000000000e+00,1.934017631468025502e-10,0.000000000000000000e+00 +4.268441528893880843e+01,2.938199999999999932e+02,0.000000000000000000e+00,5.570848567598814860e+00,0.000000000000000000e+00,-1.000000009972132009e+00,0.000000000000000000e+00,1.245635707374683128e-10,0.000000000000000000e+00 +4.268621034760512600e+01,2.938299999999999841e+02,0.000000000000000000e+00,5.569053508914598716e+00,0.000000000000000000e+00,-1.000000009971908410e+00,0.000000000000000000e+00,-3.259620362405542459e-10,0.000000000000000000e+00 +4.268800598486808440e+01,2.938400000000000318e+02,0.000000000000000000e+00,5.567257871633737309e+00,0.000000000000000000e+00,-1.000000009972493720e+00,0.000000000000000000e+00,2.990318391012272441e-10,0.000000000000000000e+00 +4.268980220128747050e+01,2.938500000000000227e+02,0.000000000000000000e+00,5.565461655196435764e+00,0.000000000000000000e+00,-1.000000009971956594e+00,0.000000000000000000e+00,-1.213536681233340227e-10,0.000000000000000000e+00 +4.269159899742398778e+01,2.938600000000000136e+02,0.000000000000000000e+00,5.563664859041999478e+00,0.000000000000000000e+00,-1.000000009972174642e+00,0.000000000000000000e+00,-1.265030927934731099e-10,0.000000000000000000e+00 +4.269339637383923503e+01,2.938700000000000045e+02,0.000000000000000000e+00,5.561867482608825242e+00,0.000000000000000000e+00,-1.000000009972402015e+00,0.000000000000000000e+00,3.686423263446446388e-10,0.000000000000000000e+00 +4.269519433109572759e+01,2.938799999999999955e+02,0.000000000000000000e+00,5.560069525334403906e+00,0.000000000000000000e+00,-1.000000009971739212e+00,0.000000000000000000e+00,-4.718577911917008493e-10,0.000000000000000000e+00 +4.269699286975687613e+01,2.938899999999999864e+02,0.000000000000000000e+00,5.558270986655318602e+00,0.000000000000000000e+00,-1.000000009972587867e+00,0.000000000000000000e+00,1.882130730079669888e-10,0.000000000000000000e+00 +4.269879199038701501e+01,2.939000000000000341e+02,0.000000000000000000e+00,5.556471866007236748e+00,0.000000000000000000e+00,-1.000000009972249249e+00,0.000000000000000000e+00,2.428088093320788336e-10,0.000000000000000000e+00 +4.270059169355138806e+01,2.939100000000000250e+02,0.000000000000000000e+00,5.554672162824917159e+00,0.000000000000000000e+00,-1.000000009971812265e+00,0.000000000000000000e+00,-2.136222795548538188e-10,0.000000000000000000e+00 +4.270239197981614865e+01,2.939200000000000159e+02,0.000000000000000000e+00,5.552871876542201157e+00,0.000000000000000000e+00,-1.000000009972196846e+00,0.000000000000000000e+00,9.863881936209041754e-12,0.000000000000000000e+00 +4.270419284974838092e+01,2.939300000000000068e+02,0.000000000000000000e+00,5.551071006592010804e+00,0.000000000000000000e+00,-1.000000009972179082e+00,0.000000000000000000e+00,-8.640423433672327635e-11,0.000000000000000000e+00 +4.270599430391607854e+01,2.939399999999999977e+02,0.000000000000000000e+00,5.549269552406350670e+00,0.000000000000000000e+00,-1.000000009972334736e+00,0.000000000000000000e+00,1.436728136040744611e-10,0.000000000000000000e+00 +4.270779634288815885e+01,2.939499999999999886e+02,0.000000000000000000e+00,5.547467513416302509e+00,0.000000000000000000e+00,-1.000000009972075832e+00,0.000000000000000000e+00,-2.939039564389411401e-10,0.000000000000000000e+00 +4.270959896723446292e+01,2.939599999999999795e+02,0.000000000000000000e+00,5.545664889052025259e+00,0.000000000000000000e+00,-1.000000009972605630e+00,0.000000000000000000e+00,3.430638524570582109e-10,0.000000000000000000e+00 +4.271140217752575552e+01,2.939700000000000273e+02,0.000000000000000000e+00,5.543861678742749710e+00,0.000000000000000000e+00,-1.000000009971987014e+00,0.000000000000000000e+00,-3.003602365965709209e-10,0.000000000000000000e+00 +4.271320597433373223e+01,2.939800000000000182e+02,0.000000000000000000e+00,5.542057881916782058e+00,0.000000000000000000e+00,-1.000000009972528803e+00,0.000000000000000000e+00,3.387797897528721797e-10,0.000000000000000000e+00 +4.271501035823102654e+01,2.939900000000000091e+02,0.000000000000000000e+00,5.540253498001494137e+00,0.000000000000000000e+00,-1.000000009971917514e+00,0.000000000000000000e+00,-3.604437359504414733e-10,0.000000000000000000e+00 +4.271681532979118856e+01,2.940000000000000000e+02,0.000000000000000000e+00,5.538448526423329632e+00,0.000000000000000000e+00,-1.000000009972568105e+00,0.000000000000000000e+00,1.658976747563894409e-10,0.000000000000000000e+00 +4.271862088958872050e+01,2.940099999999999909e+02,0.000000000000000000e+00,5.536642966607793426e+00,0.000000000000000000e+00,-1.000000009972268566e+00,0.000000000000000000e+00,1.201105921028358872e-10,0.000000000000000000e+00 +4.272042703819904119e+01,2.940199999999999818e+02,0.000000000000000000e+00,5.534836817979457813e+00,0.000000000000000000e+00,-1.000000009972051629e+00,0.000000000000000000e+00,-1.107311569770062312e-10,0.000000000000000000e+00 +4.272223377619852869e+01,2.940300000000000296e+02,0.000000000000000000e+00,5.533030079961954506e+00,0.000000000000000000e+00,-1.000000009972251691e+00,0.000000000000000000e+00,-1.401809184561695326e-10,0.000000000000000000e+00 +4.272404110416448475e+01,2.940400000000000205e+02,0.000000000000000000e+00,5.531222751977973751e+00,0.000000000000000000e+00,-1.000000009972505044e+00,0.000000000000000000e+00,1.484867408394789799e-10,0.000000000000000000e+00 +4.272584902267516327e+01,2.940500000000000114e+02,0.000000000000000000e+00,5.529414833449263433e+00,0.000000000000000000e+00,-1.000000009972236592e+00,0.000000000000000000e+00,5.807383943116087526e-11,0.000000000000000000e+00 +4.272765753230976316e+01,2.940600000000000023e+02,0.000000000000000000e+00,5.527606323796627308e+00,0.000000000000000000e+00,-1.000000009972131565e+00,0.000000000000000000e+00,-1.828788991899304821e-11,0.000000000000000000e+00 +4.272946663364842834e+01,2.940699999999999932e+02,0.000000000000000000e+00,5.525797222439920553e+00,0.000000000000000000e+00,-1.000000009972164650e+00,0.000000000000000000e+00,-2.298121292738646507e-10,0.000000000000000000e+00 +4.273127632727225489e+01,2.940799999999999841e+02,0.000000000000000000e+00,5.523987528798048885e+00,0.000000000000000000e+00,-1.000000009972580539e+00,0.000000000000000000e+00,9.027567185338733514e-11,0.000000000000000000e+00 +4.273308661376328388e+01,2.940900000000000318e+02,0.000000000000000000e+00,5.522177242288965893e+00,0.000000000000000000e+00,-1.000000009972417114e+00,0.000000000000000000e+00,2.539397374330498344e-10,0.000000000000000000e+00 +4.273489749370451563e+01,2.941000000000000227e+02,0.000000000000000000e+00,5.520366362329673038e+00,0.000000000000000000e+00,-1.000000009971957260e+00,0.000000000000000000e+00,-1.513822946436681810e-10,0.000000000000000000e+00 +4.273670896767990968e+01,2.941100000000000136e+02,0.000000000000000000e+00,5.518554888336215214e+00,0.000000000000000000e+00,-1.000000009972231485e+00,0.000000000000000000e+00,-1.831921183206884214e-10,0.000000000000000000e+00 +4.273852103627437771e+01,2.941200000000000045e+02,0.000000000000000000e+00,5.516742819723677194e+00,0.000000000000000000e+00,-1.000000009972563442e+00,0.000000000000000000e+00,1.898692618811747940e-11,0.000000000000000000e+00 +4.274033370007379062e+01,2.941299999999999955e+02,0.000000000000000000e+00,5.514930155906184517e+00,0.000000000000000000e+00,-1.000000009972529025e+00,0.000000000000000000e+00,3.180183586446086161e-10,0.000000000000000000e+00 +4.274214695966499278e+01,2.941399999999999864e+02,0.000000000000000000e+00,5.513116896296900826e+00,0.000000000000000000e+00,-1.000000009971952375e+00,0.000000000000000000e+00,-2.298968466983981594e-10,0.000000000000000000e+00 +4.274396081563578065e+01,2.941500000000000341e+02,0.000000000000000000e+00,5.511303040308025203e+00,0.000000000000000000e+00,-1.000000009972369375e+00,0.000000000000000000e+00,-1.371829474058404898e-10,0.000000000000000000e+00 +4.274577526857492416e+01,2.941600000000000250e+02,0.000000000000000000e+00,5.509488587350786837e+00,0.000000000000000000e+00,-1.000000009972618287e+00,0.000000000000000000e+00,1.951246785664052486e-10,0.000000000000000000e+00 +4.274759031907215956e+01,2.941700000000000159e+02,0.000000000000000000e+00,5.507673536835447692e+00,0.000000000000000000e+00,-1.000000009972264126e+00,0.000000000000000000e+00,-1.697453482025235520e-10,0.000000000000000000e+00 +4.274940596771820367e+01,2.941800000000000068e+02,0.000000000000000000e+00,5.505857888171298953e+00,0.000000000000000000e+00,-1.000000009972572323e+00,0.000000000000000000e+00,2.591797603851010111e-10,0.000000000000000000e+00 +4.275122221510473253e+01,2.941899999999999977e+02,0.000000000000000000e+00,5.504041640766655696e+00,0.000000000000000000e+00,-1.000000009972101589e+00,0.000000000000000000e+00,-2.581165491410781102e-10,0.000000000000000000e+00 +4.275303906182440983e+01,2.941999999999999886e+02,0.000000000000000000e+00,5.502224794028859556e+00,0.000000000000000000e+00,-1.000000009972570547e+00,0.000000000000000000e+00,3.094665724406886693e-10,0.000000000000000000e+00 +4.275485650847087271e+01,2.942099999999999795e+02,0.000000000000000000e+00,5.500407347364270727e+00,0.000000000000000000e+00,-1.000000009972008108e+00,0.000000000000000000e+00,-3.092422185774508927e-10,0.000000000000000000e+00 +4.275667455563873887e+01,2.942200000000000273e+02,0.000000000000000000e+00,5.498589300178272410e+00,0.000000000000000000e+00,-1.000000009972570325e+00,0.000000000000000000e+00,1.871688892135135238e-10,0.000000000000000000e+00 +4.275849320392361363e+01,2.942300000000000182e+02,0.000000000000000000e+00,5.496770651875261038e+00,0.000000000000000000e+00,-1.000000009972229931e+00,0.000000000000000000e+00,-1.973594208966544059e-10,0.000000000000000000e+00 +4.276031245392208291e+01,2.942400000000000091e+02,0.000000000000000000e+00,5.494951401858651607e+00,0.000000000000000000e+00,-1.000000009972588977e+00,0.000000000000000000e+00,3.452951806095501904e-11,0.000000000000000000e+00 +4.276213230623172024e+01,2.942500000000000000e+02,0.000000000000000000e+00,5.493131549530868796e+00,0.000000000000000000e+00,-1.000000009972526138e+00,0.000000000000000000e+00,2.345521992130419339e-10,0.000000000000000000e+00 +4.276395276145108681e+01,2.942599999999999909e+02,0.000000000000000000e+00,5.491311094293349626e+00,0.000000000000000000e+00,-1.000000009972099146e+00,0.000000000000000000e+00,-2.416684316861465602e-10,0.000000000000000000e+00 +4.276577382017973861e+01,2.942699999999999818e+02,0.000000000000000000e+00,5.489490035546539026e+00,0.000000000000000000e+00,-1.000000009972539239e+00,0.000000000000000000e+00,1.060453132179059727e-10,0.000000000000000000e+00 +4.276759548301822633e+01,2.942800000000000296e+02,0.000000000000000000e+00,5.487668372689885388e+00,0.000000000000000000e+00,-1.000000009972346060e+00,0.000000000000000000e+00,-1.660825253319300930e-10,0.000000000000000000e+00 +4.276941775056809547e+01,2.942900000000000205e+02,0.000000000000000000e+00,5.485846105121843230e+00,0.000000000000000000e+00,-1.000000009972648707e+00,0.000000000000000000e+00,1.772339182737843409e-10,0.000000000000000000e+00 +4.277124062343189337e+01,2.943000000000000114e+02,0.000000000000000000e+00,5.484023232239866097e+00,0.000000000000000000e+00,-1.000000009972325632e+00,0.000000000000000000e+00,-3.409553761606703966e-11,0.000000000000000000e+00 +4.277306410221316924e+01,2.943100000000000023e+02,0.000000000000000000e+00,5.482199753440408330e+00,0.000000000000000000e+00,-1.000000009972387804e+00,0.000000000000000000e+00,-9.653132525496142537e-11,0.000000000000000000e+00 +4.277488818751646704e+01,2.943199999999999932e+02,0.000000000000000000e+00,5.480375668118918853e+00,0.000000000000000000e+00,-1.000000009972563886e+00,0.000000000000000000e+00,1.603858186389913664e-10,0.000000000000000000e+00 +4.277671287994734683e+01,2.943299999999999841e+02,0.000000000000000000e+00,5.478550975669841172e+00,0.000000000000000000e+00,-1.000000009972271231e+00,0.000000000000000000e+00,-1.576561562292713878e-10,0.000000000000000000e+00 +4.277853818011237053e+01,2.943400000000000318e+02,0.000000000000000000e+00,5.476725675486611600e+00,0.000000000000000000e+00,-1.000000009972559001e+00,0.000000000000000000e+00,-7.515358263378515858e-11,0.000000000000000000e+00 +4.278036408861911610e+01,2.943500000000000227e+02,0.000000000000000000e+00,5.474899766961653924e+00,0.000000000000000000e+00,-1.000000009972696224e+00,0.000000000000000000e+00,3.168041116708335334e-10,0.000000000000000000e+00 +4.278219060607617763e+01,2.943600000000000136e+02,0.000000000000000000e+00,5.473073249486380298e+00,0.000000000000000000e+00,-1.000000009972117576e+00,0.000000000000000000e+00,-3.994580615409966658e-10,0.000000000000000000e+00 +4.278401773309315104e+01,2.943700000000000045e+02,0.000000000000000000e+00,5.471246122451188576e+00,0.000000000000000000e+00,-1.000000009972847437e+00,0.000000000000000000e+00,3.517021679332586177e-10,0.000000000000000000e+00 +4.278584547028065543e+01,2.943799999999999955e+02,0.000000000000000000e+00,5.469418385245455205e+00,0.000000000000000000e+00,-1.000000009972204618e+00,0.000000000000000000e+00,-1.726954788909615329e-10,0.000000000000000000e+00 +4.278767381825033311e+01,2.943899999999999864e+02,0.000000000000000000e+00,5.467590037257541447e+00,0.000000000000000000e+00,-1.000000009972520365e+00,0.000000000000000000e+00,7.369276639169369823e-11,0.000000000000000000e+00 +4.278950277761485665e+01,2.944000000000000341e+02,0.000000000000000000e+00,5.465761077874781826e+00,0.000000000000000000e+00,-1.000000009972385584e+00,0.000000000000000000e+00,-5.109436016027053266e-11,0.000000000000000000e+00 +4.279133234898790761e+01,2.944100000000000250e+02,0.000000000000000000e+00,5.463931506483488576e+00,0.000000000000000000e+00,-1.000000009972479065e+00,0.000000000000000000e+00,-9.172068035970853595e-11,0.000000000000000000e+00 +4.279316253298419781e+01,2.944200000000000159e+02,0.000000000000000000e+00,5.462101322468945419e+00,0.000000000000000000e+00,-1.000000009972646930e+00,0.000000000000000000e+00,1.421436912603902573e-10,0.000000000000000000e+00 +4.279499333021947649e+01,2.944300000000000068e+02,0.000000000000000000e+00,5.460270525215406678e+00,0.000000000000000000e+00,-1.000000009972386694e+00,0.000000000000000000e+00,-2.162963723014562726e-10,0.000000000000000000e+00 +4.279682474131052317e+01,2.944399999999999977e+02,0.000000000000000000e+00,5.458439114106095502e+00,0.000000000000000000e+00,-1.000000009972782822e+00,0.000000000000000000e+00,8.775002765776946405e-11,0.000000000000000000e+00 +4.279865676687514764e+01,2.944499999999999886e+02,0.000000000000000000e+00,5.456607088523198534e+00,0.000000000000000000e+00,-1.000000009972622061e+00,0.000000000000000000e+00,1.919190501680378146e-10,0.000000000000000000e+00 +4.280048940753220421e+01,2.944599999999999795e+02,0.000000000000000000e+00,5.454774447847867691e+00,0.000000000000000000e+00,-1.000000009972270343e+00,0.000000000000000000e+00,-2.324299012239640687e-10,0.000000000000000000e+00 +4.280232266390157747e+01,2.944700000000000273e+02,0.000000000000000000e+00,5.452941191460214831e+00,0.000000000000000000e+00,-1.000000009972696446e+00,0.000000000000000000e+00,7.301100920399394088e-11,0.000000000000000000e+00 +4.280415653660419650e+01,2.944800000000000182e+02,0.000000000000000000e+00,5.451107318739308205e+00,0.000000000000000000e+00,-1.000000009972562554e+00,0.000000000000000000e+00,-9.198956179549965551e-12,0.000000000000000000e+00 +4.280599102626203489e+01,2.944900000000000091e+02,0.000000000000000000e+00,5.449272829063174228e+00,0.000000000000000000e+00,-1.000000009972579429e+00,0.000000000000000000e+00,-9.921849386155929879e-12,0.000000000000000000e+00 +4.280782613349811783e+01,2.945000000000000000e+02,0.000000000000000000e+00,5.447437721808791267e+00,0.000000000000000000e+00,-1.000000009972597637e+00,0.000000000000000000e+00,1.548254920694714346e-11,0.000000000000000000e+00 +4.280966185893651499e+01,2.945099999999999909e+02,0.000000000000000000e+00,5.445601996352088747e+00,0.000000000000000000e+00,-1.000000009972569215e+00,0.000000000000000000e+00,1.197074878420371572e-11,0.000000000000000000e+00 +4.281149820320234767e+01,2.945199999999999818e+02,0.000000000000000000e+00,5.443765652067944494e+00,0.000000000000000000e+00,-1.000000009972547232e+00,0.000000000000000000e+00,-7.095414117949968309e-11,0.000000000000000000e+00 +4.281333516692178875e+01,2.945300000000000296e+02,0.000000000000000000e+00,5.441928688330182062e+00,0.000000000000000000e+00,-1.000000009972677573e+00,0.000000000000000000e+00,2.428785320317242875e-10,0.000000000000000000e+00 +4.281517275072207696e+01,2.945400000000000205e+02,0.000000000000000000e+00,5.440091104511568076e+00,0.000000000000000000e+00,-1.000000009972231263e+00,0.000000000000000000e+00,-1.456779113349282708e-10,0.000000000000000000e+00 +4.281701095523150258e+01,2.945500000000000114e+02,0.000000000000000000e+00,5.438252899983811339e+00,0.000000000000000000e+00,-1.000000009972499049e+00,0.000000000000000000e+00,-2.289485822786054072e-10,0.000000000000000000e+00 +4.281884978107942175e+01,2.945600000000000023e+02,0.000000000000000000e+00,5.436414074117556616e+00,0.000000000000000000e+00,-1.000000009972920045e+00,0.000000000000000000e+00,2.119713985260324939e-10,0.000000000000000000e+00 +4.282068922889624929e+01,2.945699999999999932e+02,0.000000000000000000e+00,5.434574626282385523e+00,0.000000000000000000e+00,-1.000000009972530135e+00,0.000000000000000000e+00,8.700436605723283024e-11,0.000000000000000000e+00 +4.282252929931347296e+01,2.945799999999999841e+02,0.000000000000000000e+00,5.432734555846814750e+00,0.000000000000000000e+00,-1.000000009972370041e+00,0.000000000000000000e+00,-1.167707497375872979e-10,0.000000000000000000e+00 +4.282436999296363922e+01,2.945900000000000318e+02,0.000000000000000000e+00,5.430893862178289844e+00,0.000000000000000000e+00,-1.000000009972584980e+00,0.000000000000000000e+00,-1.722026173920498404e-10,0.000000000000000000e+00 +4.282621131048038166e+01,2.946000000000000227e+02,0.000000000000000000e+00,5.429052544643184319e+00,0.000000000000000000e+00,-1.000000009972902060e+00,0.000000000000000000e+00,1.482754947692814083e-10,0.000000000000000000e+00 +4.282805325249839967e+01,2.946100000000000136e+02,0.000000000000000000e+00,5.427210602606797885e+00,0.000000000000000000e+00,-1.000000009972628945e+00,0.000000000000000000e+00,2.856046316818818974e-11,0.000000000000000000e+00 +4.282989581965346559e+01,2.946200000000000045e+02,0.000000000000000000e+00,5.425368035433354663e+00,0.000000000000000000e+00,-1.000000009972576320e+00,0.000000000000000000e+00,-3.638114580042090925e-11,0.000000000000000000e+00 +4.283173901258243887e+01,2.946299999999999955e+02,0.000000000000000000e+00,5.423524842485997866e+00,0.000000000000000000e+00,-1.000000009972643378e+00,0.000000000000000000e+00,-7.273757162943411657e-11,0.000000000000000000e+00 +4.283358283192325899e+01,2.946399999999999864e+02,0.000000000000000000e+00,5.421681023126788901e+00,0.000000000000000000e+00,-1.000000009972777493e+00,0.000000000000000000e+00,1.562603817011026148e-10,0.000000000000000000e+00 +4.283542727831494545e+01,2.946500000000000341e+02,0.000000000000000000e+00,5.419836576716704712e+00,0.000000000000000000e+00,-1.000000009972489279e+00,0.000000000000000000e+00,-1.541613648908612668e-10,0.000000000000000000e+00 +4.283727235239761200e+01,2.946600000000000250e+02,0.000000000000000000e+00,5.417991502615636001e+00,0.000000000000000000e+00,-1.000000009972773718e+00,0.000000000000000000e+00,2.093282261872710083e-11,0.000000000000000000e+00 +4.283911805481245949e+01,2.946700000000000159e+02,0.000000000000000000e+00,5.416145800182381898e+00,0.000000000000000000e+00,-1.000000009972735082e+00,0.000000000000000000e+00,1.422706504076333819e-10,0.000000000000000000e+00 +4.284096438620177594e+01,2.946800000000000068e+02,0.000000000000000000e+00,5.414299468774650848e+00,0.000000000000000000e+00,-1.000000009972472403e+00,0.000000000000000000e+00,-6.479944167180421371e-11,0.000000000000000000e+00 +4.284281134720895068e+01,2.946899999999999977e+02,0.000000000000000000e+00,5.412452507749056174e+00,0.000000000000000000e+00,-1.000000009972592085e+00,0.000000000000000000e+00,-9.133724678565618912e-11,0.000000000000000000e+00 +4.284465893847846729e+01,2.946999999999999886e+02,0.000000000000000000e+00,5.410604916461112524e+00,0.000000000000000000e+00,-1.000000009972760839e+00,0.000000000000000000e+00,5.226070995202522909e-11,0.000000000000000000e+00 +4.284650716065591070e+01,2.947099999999999795e+02,0.000000000000000000e+00,5.408756694265234977e+00,0.000000000000000000e+00,-1.000000009972664250e+00,0.000000000000000000e+00,9.836069142739549992e-11,0.000000000000000000e+00 +4.284835601438797426e+01,2.947200000000000273e+02,0.000000000000000000e+00,5.406907840514736385e+00,0.000000000000000000e+00,-1.000000009972482395e+00,0.000000000000000000e+00,-2.171839660001486292e-10,0.000000000000000000e+00 +4.285020550032244557e+01,2.947300000000000182e+02,0.000000000000000000e+00,5.405058354561823819e+00,0.000000000000000000e+00,-1.000000009972884074e+00,0.000000000000000000e+00,1.410192755149118368e-10,0.000000000000000000e+00 +4.285205561910822070e+01,2.947400000000000091e+02,0.000000000000000000e+00,5.403208235757595013e+00,0.000000000000000000e+00,-1.000000009972623172e+00,0.000000000000000000e+00,-1.246543614319892921e-10,0.000000000000000000e+00 +4.285390637139531833e+01,2.947500000000000000e+02,0.000000000000000000e+00,5.401357483452039254e+00,0.000000000000000000e+00,-1.000000009972853876e+00,0.000000000000000000e+00,2.530612228675855589e-11,0.000000000000000000e+00 +4.285575775783486563e+01,2.947599999999999909e+02,0.000000000000000000e+00,5.399506096994030280e+00,0.000000000000000000e+00,-1.000000009972807025e+00,0.000000000000000000e+00,7.673159667822958576e-11,0.000000000000000000e+00 +4.285760977907909819e+01,2.947699999999999818e+02,0.000000000000000000e+00,5.397654075731327161e+00,0.000000000000000000e+00,-1.000000009972664916e+00,0.000000000000000000e+00,3.679456297976985095e-11,0.000000000000000000e+00 +4.285946243578138137e+01,2.947800000000000296e+02,0.000000000000000000e+00,5.395801419010569866e+00,0.000000000000000000e+00,-1.000000009972596748e+00,0.000000000000000000e+00,-8.482608847913927401e-11,0.000000000000000000e+00 +4.286131572859618899e+01,2.947900000000000205e+02,0.000000000000000000e+00,5.393948126177276592e+00,0.000000000000000000e+00,-1.000000009972753956e+00,0.000000000000000000e+00,-1.808522591801350829e-11,0.000000000000000000e+00 +4.286316965817913882e+01,2.948000000000000114e+02,0.000000000000000000e+00,5.392094196575841103e+00,0.000000000000000000e+00,-1.000000009972787485e+00,0.000000000000000000e+00,-7.063984011023696521e-12,0.000000000000000000e+00 +4.286502422518695710e+01,2.948100000000000023e+02,0.000000000000000000e+00,5.390239629549530953e+00,0.000000000000000000e+00,-1.000000009972800585e+00,0.000000000000000000e+00,-3.542745941823935294e-11,0.000000000000000000e+00 +4.286687943027749981e+01,2.948199999999999932e+02,0.000000000000000000e+00,5.388384424440483933e+00,0.000000000000000000e+00,-1.000000009972866311e+00,0.000000000000000000e+00,1.739655298291001292e-10,0.000000000000000000e+00 +4.286873527410976692e+01,2.948299999999999841e+02,0.000000000000000000e+00,5.386528580589705406e+00,0.000000000000000000e+00,-1.000000009972543458e+00,0.000000000000000000e+00,-1.307282224379712917e-10,0.000000000000000000e+00 +4.287059175734389527e+01,2.948400000000000318e+02,0.000000000000000000e+00,5.384672097337066532e+00,0.000000000000000000e+00,-1.000000009972786152e+00,0.000000000000000000e+00,1.053356539272066909e-10,0.000000000000000000e+00 +4.287244888064114434e+01,2.948500000000000227e+02,0.000000000000000000e+00,5.382814974021298937e+00,0.000000000000000000e+00,-1.000000009972590531e+00,0.000000000000000000e+00,-1.220324749801215103e-10,0.000000000000000000e+00 +4.287430664466391761e+01,2.948600000000000136e+02,0.000000000000000000e+00,5.380957209979995604e+00,0.000000000000000000e+00,-1.000000009972817239e+00,0.000000000000000000e+00,-1.111175641561911376e-11,0.000000000000000000e+00 +4.287616505007577672e+01,2.948700000000000045e+02,0.000000000000000000e+00,5.379098804549604651e+00,0.000000000000000000e+00,-1.000000009972837889e+00,0.000000000000000000e+00,-4.550663500543004894e-11,0.000000000000000000e+00 +4.287802409754141308e+01,2.948799999999999955e+02,0.000000000000000000e+00,5.377239757065429338e+00,0.000000000000000000e+00,-1.000000009972922488e+00,0.000000000000000000e+00,6.554989055171757492e-11,0.000000000000000000e+00 +4.287988378772666920e+01,2.948899999999999864e+02,0.000000000000000000e+00,5.375380066861623618e+00,0.000000000000000000e+00,-1.000000009972800585e+00,0.000000000000000000e+00,1.016925170064487377e-10,0.000000000000000000e+00 +4.288174412129855284e+01,2.949000000000000341e+02,0.000000000000000000e+00,5.373519733271190368e+00,0.000000000000000000e+00,-1.000000009972611403e+00,0.000000000000000000e+00,-1.546336741835455114e-10,0.000000000000000000e+00 +4.288360509892520867e+01,2.949100000000000250e+02,0.000000000000000000e+00,5.371658755625977832e+00,0.000000000000000000e+00,-1.000000009972899173e+00,0.000000000000000000e+00,1.069894818027994781e-10,0.000000000000000000e+00 +4.288546672127594661e+01,2.949200000000000159e+02,0.000000000000000000e+00,5.369797133256676069e+00,0.000000000000000000e+00,-1.000000009972699999e+00,0.000000000000000000e+00,-9.467135794873461868e-11,0.000000000000000000e+00 +4.288732898902123480e+01,2.949300000000000068e+02,0.000000000000000000e+00,5.367934865492816954e+00,0.000000000000000000e+00,-1.000000009972876303e+00,0.000000000000000000e+00,5.494755701534323107e-11,0.000000000000000000e+00 +4.288919190283270666e+01,2.949399999999999977e+02,0.000000000000000000e+00,5.366071951662767958e+00,0.000000000000000000e+00,-1.000000009972773940e+00,0.000000000000000000e+00,-1.629982022660551366e-10,0.000000000000000000e+00 +4.289105546338316088e+01,2.949499999999999886e+02,0.000000000000000000e+00,5.364208391093732153e+00,0.000000000000000000e+00,-1.000000009973077697e+00,0.000000000000000000e+00,3.254067531981003446e-10,0.000000000000000000e+00 +4.289291967134656147e+01,2.949599999999999795e+02,0.000000000000000000e+00,5.362344183111742879e+00,0.000000000000000000e+00,-1.000000009972471071e+00,0.000000000000000000e+00,-2.149176670078011372e-10,0.000000000000000000e+00 +4.289478452739804482e+01,2.949700000000000273e+02,0.000000000000000000e+00,5.360479327041664632e+00,0.000000000000000000e+00,-1.000000009972871862e+00,0.000000000000000000e+00,-1.940132788442275411e-10,0.000000000000000000e+00 +4.289665003221391970e+01,2.949800000000000182e+02,0.000000000000000000e+00,5.358613822207184185e+00,0.000000000000000000e+00,-1.000000009973233794e+00,0.000000000000000000e+00,4.454803226382186085e-10,0.000000000000000000e+00 +4.289851618647168152e+01,2.949900000000000091e+02,0.000000000000000000e+00,5.356747667930813250e+00,0.000000000000000000e+00,-1.000000009972402459e+00,0.000000000000000000e+00,-2.753546468894326143e-10,0.000000000000000000e+00 +4.290038299084999096e+01,2.950000000000000000e+02,0.000000000000000000e+00,5.354880863533885815e+00,0.000000000000000000e+00,-1.000000009972916493e+00,0.000000000000000000e+00,3.210360495562778981e-12,0.000000000000000000e+00 +4.290225044602870241e+01,2.950099999999999909e+02,0.000000000000000000e+00,5.353013408336548373e+00,0.000000000000000000e+00,-1.000000009972910497e+00,0.000000000000000000e+00,7.226735104267903196e-11,0.000000000000000000e+00 +4.290411855268885688e+01,2.950199999999999818e+02,0.000000000000000000e+00,5.351145301657765252e+00,0.000000000000000000e+00,-1.000000009972775494e+00,0.000000000000000000e+00,-2.523721813912048494e-10,0.000000000000000000e+00 +4.290598731151267486e+01,2.950300000000000296e+02,0.000000000000000000e+00,5.349276542815311508e+00,0.000000000000000000e+00,-1.000000009973247117e+00,0.000000000000000000e+00,3.720120685301598760e-10,0.000000000000000000e+00 +4.290785672318357058e+01,2.950400000000000205e+02,0.000000000000000000e+00,5.347407131125769375e+00,0.000000000000000000e+00,-1.000000009972551673e+00,0.000000000000000000e+00,-2.677503348078282876e-10,0.000000000000000000e+00 +4.290972678838615906e+01,2.950500000000000114e+02,0.000000000000000000e+00,5.345537065904530039e+00,0.000000000000000000e+00,-1.000000009973052384e+00,0.000000000000000000e+00,1.918107428111985879e-10,0.000000000000000000e+00 +4.291159750780624904e+01,2.950600000000000023e+02,0.000000000000000000e+00,5.343666346465782979e+00,0.000000000000000000e+00,-1.000000009972693560e+00,0.000000000000000000e+00,-2.009985686982193337e-10,0.000000000000000000e+00 +4.291346888213085009e+01,2.950699999999999932e+02,0.000000000000000000e+00,5.341794972122521301e+00,0.000000000000000000e+00,-1.000000009973069703e+00,0.000000000000000000e+00,1.583465866824244268e-10,0.000000000000000000e+00 +4.291534091204817258e+01,2.950799999999999841e+02,0.000000000000000000e+00,5.339922942186531962e+00,0.000000000000000000e+00,-1.000000009972773274e+00,0.000000000000000000e+00,-1.674209924999421778e-10,0.000000000000000000e+00 +4.291721359824762771e+01,2.950900000000000318e+02,0.000000000000000000e+00,5.338050255968398439e+00,0.000000000000000000e+00,-1.000000009973086801e+00,0.000000000000000000e+00,1.766075037633133102e-10,0.000000000000000000e+00 +4.291908694141984881e+01,2.951000000000000227e+02,0.000000000000000000e+00,5.336176912777492731e+00,0.000000000000000000e+00,-1.000000009972755954e+00,0.000000000000000000e+00,-2.389881366820435314e-10,0.000000000000000000e+00 +4.292096094225667713e+01,2.951100000000000136e+02,0.000000000000000000e+00,5.334302911921977142e+00,0.000000000000000000e+00,-1.000000009973203818e+00,0.000000000000000000e+00,1.961454470432231899e-10,0.000000000000000000e+00 +4.292283560145116184e+01,2.951200000000000045e+02,0.000000000000000000e+00,5.332428252708796279e+00,0.000000000000000000e+00,-1.000000009972836112e+00,0.000000000000000000e+00,6.003067208045464817e-11,0.000000000000000000e+00 +4.292471091969757424e+01,2.951299999999999955e+02,0.000000000000000000e+00,5.330552934443679725e+00,0.000000000000000000e+00,-1.000000009972723536e+00,0.000000000000000000e+00,-2.959051300901282898e-10,0.000000000000000000e+00 +4.292658689769140778e+01,2.951399999999999864e+02,0.000000000000000000e+00,5.328676956431134037e+00,0.000000000000000000e+00,-1.000000009973278647e+00,0.000000000000000000e+00,2.375873570884249837e-10,0.000000000000000000e+00 +4.292846353612938515e+01,2.951500000000000341e+02,0.000000000000000000e+00,5.326800317974440979e+00,0.000000000000000000e+00,-1.000000009972832782e+00,0.000000000000000000e+00,-2.247295817026415043e-12,0.000000000000000000e+00 +4.293034083570944404e+01,2.951600000000000250e+02,0.000000000000000000e+00,5.324923018375658401e+00,0.000000000000000000e+00,-1.000000009972837001e+00,0.000000000000000000e+00,-1.528804963237756768e-10,0.000000000000000000e+00 +4.293221879713076561e+01,2.951700000000000159e+02,0.000000000000000000e+00,5.323045056935611363e+00,0.000000000000000000e+00,-1.000000009973124104e+00,0.000000000000000000e+00,1.457348587408448738e-10,0.000000000000000000e+00 +4.293409742109374605e+01,2.951800000000000068e+02,0.000000000000000000e+00,5.321166432953892134e+00,0.000000000000000000e+00,-1.000000009972850323e+00,0.000000000000000000e+00,-2.717533486194845538e-12,0.000000000000000000e+00 +4.293597670830003921e+01,2.951899999999999977e+02,0.000000000000000000e+00,5.319287145728858412e+00,0.000000000000000000e+00,-1.000000009972855430e+00,0.000000000000000000e+00,1.937035180920105265e-11,0.000000000000000000e+00 +4.293785665945252106e+01,2.951999999999999886e+02,0.000000000000000000e+00,5.317407194557627115e+00,0.000000000000000000e+00,-1.000000009972819015e+00,0.000000000000000000e+00,-1.745076934857297676e-10,0.000000000000000000e+00 +4.293973727525531814e+01,2.952099999999999795e+02,0.000000000000000000e+00,5.315526578736073482e+00,0.000000000000000000e+00,-1.000000009973147197e+00,0.000000000000000000e+00,3.694288917320578249e-11,0.000000000000000000e+00 +4.294161855641380043e+01,2.952200000000000273e+02,0.000000000000000000e+00,5.313645297558826641e+00,0.000000000000000000e+00,-1.000000009973077697e+00,0.000000000000000000e+00,2.218148589119416103e-11,0.000000000000000000e+00 +4.294350050363458848e+01,2.952300000000000182e+02,0.000000000000000000e+00,5.311763350319268717e+00,0.000000000000000000e+00,-1.000000009973035953e+00,0.000000000000000000e+00,1.566307467998126801e-10,0.000000000000000000e+00 +4.294538311762555338e+01,2.952400000000000091e+02,0.000000000000000000e+00,5.309880736309529503e+00,0.000000000000000000e+00,-1.000000009972741077e+00,0.000000000000000000e+00,-1.839287377656898859e-10,0.000000000000000000e+00 +4.294726639909581678e+01,2.952500000000000000e+02,0.000000000000000000e+00,5.307997454820484684e+00,0.000000000000000000e+00,-1.000000009973087467e+00,0.000000000000000000e+00,1.320045661534528561e-10,0.000000000000000000e+00 +4.294915034875576509e+01,2.952599999999999909e+02,0.000000000000000000e+00,5.306113505141750508e+00,0.000000000000000000e+00,-1.000000009972838777e+00,0.000000000000000000e+00,-2.646223447599543216e-10,0.000000000000000000e+00 +4.295103496731703530e+01,2.952699999999999818e+02,0.000000000000000000e+00,5.304228886561684675e+00,0.000000000000000000e+00,-1.000000009973337489e+00,0.000000000000000000e+00,2.621728057203023325e-10,0.000000000000000000e+00 +4.295292025549253623e+01,2.952800000000000296e+02,0.000000000000000000e+00,5.302343598367378341e+00,0.000000000000000000e+00,-1.000000009972843218e+00,0.000000000000000000e+00,-1.494065765845365553e-10,0.000000000000000000e+00 +4.295480621399644861e+01,2.952900000000000205e+02,0.000000000000000000e+00,5.300457639844658786e+00,0.000000000000000000e+00,-1.000000009973124993e+00,0.000000000000000000e+00,1.407617874983160557e-10,0.000000000000000000e+00 +4.295669284354421080e+01,2.953000000000000114e+02,0.000000000000000000e+00,5.298571010278079640e+00,0.000000000000000000e+00,-1.000000009972859427e+00,0.000000000000000000e+00,-2.214208958704798754e-10,0.000000000000000000e+00 +4.295858014485254728e+01,2.953100000000000023e+02,0.000000000000000000e+00,5.296683708950923553e+00,0.000000000000000000e+00,-1.000000009973277315e+00,0.000000000000000000e+00,1.572445755574888194e-10,0.000000000000000000e+00 +4.296046811863944725e+01,2.953199999999999932e+02,0.000000000000000000e+00,5.294795735145194193e+00,0.000000000000000000e+00,-1.000000009972980441e+00,0.000000000000000000e+00,-6.960030496840807153e-11,0.000000000000000000e+00 +4.296235676562418604e+01,2.953299999999999841e+02,0.000000000000000000e+00,5.292907088141618033e+00,0.000000000000000000e+00,-1.000000009973111892e+00,0.000000000000000000e+00,-2.468049072911736945e-12,0.000000000000000000e+00 +4.296424608652732502e+01,2.953400000000000318e+02,0.000000000000000000e+00,5.291017767219636347e+00,0.000000000000000000e+00,-1.000000009973116555e+00,0.000000000000000000e+00,1.539042954203423013e-11,0.000000000000000000e+00 +4.296613608207070456e+01,2.953500000000000227e+02,0.000000000000000000e+00,5.289127771657405219e+00,0.000000000000000000e+00,-1.000000009973087467e+00,0.000000000000000000e+00,1.409306743746815523e-10,0.000000000000000000e+00 +4.296802675297746532e+01,2.953600000000000136e+02,0.000000000000000000e+00,5.287237100731791095e+00,0.000000000000000000e+00,-1.000000009972821013e+00,0.000000000000000000e+00,-2.101464426986755652e-10,0.000000000000000000e+00 +4.296991809997202694e+01,2.953700000000000045e+02,0.000000000000000000e+00,5.285345753718368123e+00,0.000000000000000000e+00,-1.000000009973218473e+00,0.000000000000000000e+00,1.180624004835246465e-10,0.000000000000000000e+00 +4.297181012378010934e+01,2.953799999999999955e+02,0.000000000000000000e+00,5.283453729891412820e+00,0.000000000000000000e+00,-1.000000009972995096e+00,0.000000000000000000e+00,5.044598303201714239e-11,0.000000000000000000e+00 +4.297370282512873985e+01,2.953899999999999864e+02,0.000000000000000000e+00,5.281561028523904966e+00,0.000000000000000000e+00,-1.000000009972899617e+00,0.000000000000000000e+00,-2.439303634489347394e-10,0.000000000000000000e+00 +4.297559620474623898e+01,2.954000000000000341e+02,0.000000000000000000e+00,5.279667648887520492e+00,0.000000000000000000e+00,-1.000000009973361470e+00,0.000000000000000000e+00,1.497054832906155643e-10,0.000000000000000000e+00 +4.297749026336224176e+01,2.954100000000000250e+02,0.000000000000000000e+00,5.277773590252628821e+00,0.000000000000000000e+00,-1.000000009973077919e+00,0.000000000000000000e+00,-8.027522889360151402e-11,0.000000000000000000e+00 +4.297938500170768350e+01,2.954200000000000159e+02,0.000000000000000000e+00,5.275878851888292864e+00,0.000000000000000000e+00,-1.000000009973230020e+00,0.000000000000000000e+00,2.332417546682028886e-10,0.000000000000000000e+00 +4.298128042051481401e+01,2.954300000000000068e+02,0.000000000000000000e+00,5.273983433062261028e+00,0.000000000000000000e+00,-1.000000009972787929e+00,0.000000000000000000e+00,-2.132499472919130871e-10,0.000000000000000000e+00 +4.298317652051719762e+01,2.954399999999999977e+02,0.000000000000000000e+00,5.272087333040968105e+00,0.000000000000000000e+00,-1.000000009973192272e+00,0.000000000000000000e+00,-1.053574694095809364e-12,0.000000000000000000e+00 +4.298507330244972025e+01,2.954499999999999886e+02,0.000000000000000000e+00,5.270190551089527276e+00,0.000000000000000000e+00,-1.000000009973194270e+00,0.000000000000000000e+00,6.717047754290802339e-11,0.000000000000000000e+00 +4.298697076704858944e+01,2.954599999999999795e+02,0.000000000000000000e+00,5.268293086471731890e+00,0.000000000000000000e+00,-1.000000009973066817e+00,0.000000000000000000e+00,-6.632743643274422757e-11,0.000000000000000000e+00 +4.298886891505134145e+01,2.954700000000000273e+02,0.000000000000000000e+00,5.266394938450049246e+00,0.000000000000000000e+00,-1.000000009973192716e+00,0.000000000000000000e+00,3.671836192150202824e-11,0.000000000000000000e+00 +4.299076774719683414e+01,2.954800000000000182e+02,0.000000000000000000e+00,5.264496106285617039e+00,0.000000000000000000e+00,-1.000000009973122994e+00,0.000000000000000000e+00,7.738468582288057094e-11,0.000000000000000000e+00 +4.299266726422526830e+01,2.954900000000000091e+02,0.000000000000000000e+00,5.262596589238241584e+00,0.000000000000000000e+00,-1.000000009972976001e+00,0.000000000000000000e+00,-2.388477733018083058e-10,0.000000000000000000e+00 +4.299456746687816633e+01,2.955000000000000000e+02,0.000000000000000000e+00,5.260696386566393379e+00,0.000000000000000000e+00,-1.000000009973429860e+00,0.000000000000000000e+00,2.718190226578264608e-10,0.000000000000000000e+00 +4.299646835589840066e+01,2.955099999999999909e+02,0.000000000000000000e+00,5.258795497527202656e+00,0.000000000000000000e+00,-1.000000009972913162e+00,0.000000000000000000e+00,-1.543682436928808667e-10,0.000000000000000000e+00 +4.299836993203017954e+01,2.955199999999999818e+02,0.000000000000000000e+00,5.256893921376460277e+00,0.000000000000000000e+00,-1.000000009973206705e+00,0.000000000000000000e+00,-8.229217784029084761e-11,0.000000000000000000e+00 +4.300027219601906125e+01,2.955300000000000296e+02,0.000000000000000000e+00,5.254991657368607960e+00,0.000000000000000000e+00,-1.000000009973363246e+00,0.000000000000000000e+00,2.048975511556977507e-10,0.000000000000000000e+00 +4.300217514861194701e+01,2.955400000000000205e+02,0.000000000000000000e+00,5.253088704756740057e+00,0.000000000000000000e+00,-1.000000009972973336e+00,0.000000000000000000e+00,-6.193690232305269011e-11,0.000000000000000000e+00 +4.300407879055710225e+01,2.955500000000000114e+02,0.000000000000000000e+00,5.251185062792599112e+00,0.000000000000000000e+00,-1.000000009973091242e+00,0.000000000000000000e+00,-1.768817923299164779e-10,0.000000000000000000e+00 +4.300598312260414247e+01,2.955600000000000023e+02,0.000000000000000000e+00,5.249280730726569644e+00,0.000000000000000000e+00,-1.000000009973428083e+00,0.000000000000000000e+00,3.215819951679545101e-10,0.000000000000000000e+00 +4.300788814550403316e+01,2.955699999999999932e+02,0.000000000000000000e+00,5.247375707807677259e+00,0.000000000000000000e+00,-1.000000009972815462e+00,0.000000000000000000e+00,-3.035219568756408536e-10,0.000000000000000000e+00 +4.300979386000911830e+01,2.955799999999999841e+02,0.000000000000000000e+00,5.245469993283586874e+00,0.000000000000000000e+00,-1.000000009973393889e+00,0.000000000000000000e+00,1.284695328472150931e-10,0.000000000000000000e+00 +4.301170026687309900e+01,2.955900000000000318e+02,0.000000000000000000e+00,5.243563586400592946e+00,0.000000000000000000e+00,-1.000000009973148973e+00,0.000000000000000000e+00,-1.117732804743935990e-10,0.000000000000000000e+00 +4.301360736685104769e+01,2.956000000000000227e+02,0.000000000000000000e+00,5.241656486403623916e+00,0.000000000000000000e+00,-1.000000009973362136e+00,0.000000000000000000e+00,1.824966260484313414e-10,0.000000000000000000e+00 +4.301551516069941528e+01,2.956100000000000136e+02,0.000000000000000000e+00,5.239748692536232433e+00,0.000000000000000000e+00,-1.000000009973013970e+00,0.000000000000000000e+00,-2.204752774205545255e-10,0.000000000000000000e+00 +4.301742364917601691e+01,2.956200000000000045e+02,0.000000000000000000e+00,5.237840204040596248e+00,0.000000000000000000e+00,-1.000000009973434745e+00,0.000000000000000000e+00,1.345630521693001960e-10,0.000000000000000000e+00 +4.301933283304006039e+01,2.956299999999999955e+02,0.000000000000000000e+00,5.235931020157510218e+00,0.000000000000000000e+00,-1.000000009973177839e+00,0.000000000000000000e+00,2.301968264875469032e-11,0.000000000000000000e+00 +4.302124271305213199e+01,2.956399999999999864e+02,0.000000000000000000e+00,5.234021140126388083e+00,0.000000000000000000e+00,-1.000000009973133874e+00,0.000000000000000000e+00,-6.891763906435750174e-11,0.000000000000000000e+00 +4.302315328997421062e+01,2.956500000000000341e+02,0.000000000000000000e+00,5.232110563185254470e+00,0.000000000000000000e+00,-1.000000009973265547e+00,0.000000000000000000e+00,1.028159301789999359e-10,0.000000000000000000e+00 +4.302506456456966077e+01,2.956600000000000250e+02,0.000000000000000000e+00,5.230199288570743121e+00,0.000000000000000000e+00,-1.000000009973069037e+00,0.000000000000000000e+00,-1.868592093348181458e-10,0.000000000000000000e+00 +4.302697653760323959e+01,2.956700000000000159e+02,0.000000000000000000e+00,5.228287315518094225e+00,0.000000000000000000e+00,-1.000000009973426307e+00,0.000000000000000000e+00,4.202505028899739109e-11,0.000000000000000000e+00 +4.302888920984111110e+01,2.956800000000000068e+02,0.000000000000000000e+00,5.226374643261148201e+00,0.000000000000000000e+00,-1.000000009973345927e+00,0.000000000000000000e+00,7.102188352261113299e-11,0.000000000000000000e+00 +4.303080258205083197e+01,2.956899999999999977e+02,0.000000000000000000e+00,5.224461271032345699e+00,0.000000000000000000e+00,-1.000000009973210036e+00,0.000000000000000000e+00,1.574206086549988060e-10,0.000000000000000000e+00 +4.303271665500136578e+01,2.956999999999999886e+02,0.000000000000000000e+00,5.222547198062721385e+00,0.000000000000000000e+00,-1.000000009972908721e+00,0.000000000000000000e+00,-4.084246547981096940e-10,0.000000000000000000e+00 +4.303463142946309006e+01,2.957099999999999795e+02,0.000000000000000000e+00,5.220632423581901271e+00,0.000000000000000000e+00,-1.000000009973690762e+00,0.000000000000000000e+00,3.322305214489447130e-10,0.000000000000000000e+00 +4.303654690620778922e+01,2.957200000000000273e+02,0.000000000000000000e+00,5.218716946818096503e+00,0.000000000000000000e+00,-1.000000009973054382e+00,0.000000000000000000e+00,-1.912000105408453377e-11,0.000000000000000000e+00 +4.303846308600866877e+01,2.957300000000000182e+02,0.000000000000000000e+00,5.216800766998106909e+00,0.000000000000000000e+00,-1.000000009973091020e+00,0.000000000000000000e+00,-2.240273007852863892e-10,0.000000000000000000e+00 +4.304037996964034818e+01,2.957400000000000091e+02,0.000000000000000000e+00,5.214883883347308569e+00,0.000000000000000000e+00,-1.000000009973520454e+00,0.000000000000000000e+00,2.306610168562670228e-10,0.000000000000000000e+00 +4.304229755787887512e+01,2.957500000000000000e+02,0.000000000000000000e+00,5.212966295089654700e+00,0.000000000000000000e+00,-1.000000009973078141e+00,0.000000000000000000e+00,-3.126437323039334296e-10,0.000000000000000000e+00 +4.304421585150172547e+01,2.957599999999999909e+02,0.000000000000000000e+00,5.211048001447673883e+00,0.000000000000000000e+00,-1.000000009973677884e+00,0.000000000000000000e+00,3.559193751379706290e-10,0.000000000000000000e+00 +4.304613485128779615e+01,2.957699999999999818e+02,0.000000000000000000e+00,5.209129001642460288e+00,0.000000000000000000e+00,-1.000000009972994874e+00,0.000000000000000000e+00,-1.364857609584402884e-10,0.000000000000000000e+00 +4.304805455801743364e+01,2.957800000000000296e+02,0.000000000000000000e+00,5.207209294893678120e+00,0.000000000000000000e+00,-1.000000009973256887e+00,0.000000000000000000e+00,-5.746476671313689134e-11,0.000000000000000000e+00 +4.304997497247241256e+01,2.957900000000000205e+02,0.000000000000000000e+00,5.205288880419549180e+00,0.000000000000000000e+00,-1.000000009973367243e+00,0.000000000000000000e+00,-8.379595769057275201e-11,0.000000000000000000e+00 +4.305189609543594287e+01,2.958000000000000114e+02,0.000000000000000000e+00,5.203367757436855534e+00,0.000000000000000000e+00,-1.000000009973528226e+00,0.000000000000000000e+00,7.544629689007524140e-11,0.000000000000000000e+00 +4.305381792769269822e+01,2.958100000000000023e+02,0.000000000000000000e+00,5.201445925160933292e+00,0.000000000000000000e+00,-1.000000009973383230e+00,0.000000000000000000e+00,2.327230306064915682e-10,0.000000000000000000e+00 +4.305574047002878757e+01,2.958199999999999932e+02,0.000000000000000000e+00,5.199523382805669947e+00,0.000000000000000000e+00,-1.000000009972935811e+00,0.000000000000000000e+00,-2.750081206724509626e-10,0.000000000000000000e+00 +4.305766372323177649e+01,2.958299999999999841e+02,0.000000000000000000e+00,5.197600129583499928e+00,0.000000000000000000e+00,-1.000000009973464721e+00,0.000000000000000000e+00,5.331937691072267965e-11,0.000000000000000000e+00 +4.305958768809068715e+01,2.958400000000000318e+02,0.000000000000000000e+00,5.195676164705398392e+00,0.000000000000000000e+00,-1.000000009973362136e+00,0.000000000000000000e+00,8.006482717494259317e-11,0.000000000000000000e+00 +4.306151236539600546e+01,2.958500000000000227e+02,0.000000000000000000e+00,5.193751487380882992e+00,0.000000000000000000e+00,-1.000000009973208037e+00,0.000000000000000000e+00,-1.265109213312427117e-10,0.000000000000000000e+00 +4.306343775593968104e+01,2.958600000000000136e+02,0.000000000000000000e+00,5.191826096818005887e+00,0.000000000000000000e+00,-1.000000009973451620e+00,0.000000000000000000e+00,-1.763809970996354716e-11,0.000000000000000000e+00 +4.306536386051512721e+01,2.958700000000000045e+02,0.000000000000000000e+00,5.189899992223350189e+00,0.000000000000000000e+00,-1.000000009973485593e+00,0.000000000000000000e+00,1.959061798735216775e-12,0.000000000000000000e+00 +4.306729067991723525e+01,2.958799999999999955e+02,0.000000000000000000e+00,5.187973172802028188e+00,0.000000000000000000e+00,-1.000000009973481818e+00,0.000000000000000000e+00,2.475565163606931412e-10,0.000000000000000000e+00 +4.306921821494236013e+01,2.958899999999999864e+02,0.000000000000000000e+00,5.186045637757676019e+00,0.000000000000000000e+00,-1.000000009973004644e+00,0.000000000000000000e+00,-3.945153616004626098e-10,0.000000000000000000e+00 +4.307114646638835609e+01,2.959000000000000341e+02,0.000000000000000000e+00,5.184117386292451002e+00,0.000000000000000000e+00,-1.000000009973765369e+00,0.000000000000000000e+00,3.093019932835575796e-10,0.000000000000000000e+00 +4.307307543505454106e+01,2.959100000000000250e+02,0.000000000000000000e+00,5.182188417607023645e+00,0.000000000000000000e+00,-1.000000009973168735e+00,0.000000000000000000e+00,-1.801960150421022417e-10,0.000000000000000000e+00 +4.307500512174173934e+01,2.959200000000000159e+02,0.000000000000000000e+00,5.180258730900582087e+00,0.000000000000000000e+00,-1.000000009973516457e+00,0.000000000000000000e+00,1.368795718941594054e-10,0.000000000000000000e+00 +4.307693552725225317e+01,2.959300000000000068e+02,0.000000000000000000e+00,5.178328325370818774e+00,0.000000000000000000e+00,-1.000000009973252224e+00,0.000000000000000000e+00,-7.657800315412555164e-11,0.000000000000000000e+00 +4.307886665238987689e+01,2.959399999999999977e+02,0.000000000000000000e+00,5.176397200213934013e+00,0.000000000000000000e+00,-1.000000009973400106e+00,0.000000000000000000e+00,-7.011285534664901009e-12,0.000000000000000000e+00 +4.308079849795991834e+01,2.959499999999999886e+02,0.000000000000000000e+00,5.174465354624627089e+00,0.000000000000000000e+00,-1.000000009973413650e+00,0.000000000000000000e+00,-3.056239226873260224e-11,0.000000000000000000e+00 +4.308273106476917746e+01,2.959599999999999795e+02,0.000000000000000000e+00,5.172532787796095377e+00,0.000000000000000000e+00,-1.000000009973472714e+00,0.000000000000000000e+00,-4.215116107533594207e-11,0.000000000000000000e+00 +4.308466435362596059e+01,2.959700000000000273e+02,0.000000000000000000e+00,5.170599498920029014e+00,0.000000000000000000e+00,-1.000000009973554205e+00,0.000000000000000000e+00,6.578634332579494770e-11,0.000000000000000000e+00 +4.308659836534009457e+01,2.959800000000000182e+02,0.000000000000000000e+00,5.168665487186607344e+00,0.000000000000000000e+00,-1.000000009973426973e+00,0.000000000000000000e+00,1.672161434836036182e-10,0.000000000000000000e+00 +4.308853310072291265e+01,2.959900000000000091e+02,0.000000000000000000e+00,5.166730751784495368e+00,0.000000000000000000e+00,-1.000000009973103454e+00,0.000000000000000000e+00,-3.340776533011003156e-10,0.000000000000000000e+00 +4.309046856058726860e+01,2.960000000000000000e+02,0.000000000000000000e+00,5.164795291900839302e+00,0.000000000000000000e+00,-1.000000009973750048e+00,0.000000000000000000e+00,3.398012637912325493e-10,0.000000000000000000e+00 +4.309240474574753677e+01,2.960099999999999909e+02,0.000000000000000000e+00,5.162859106721260360e+00,0.000000000000000000e+00,-1.000000009973092130e+00,0.000000000000000000e+00,-2.959966097460918510e-10,0.000000000000000000e+00 +4.309434165701961916e+01,2.960199999999999818e+02,0.000000000000000000e+00,5.160922195429857418e+00,0.000000000000000000e+00,-1.000000009973665449e+00,0.000000000000000000e+00,2.525684665572437839e-10,0.000000000000000000e+00 +4.309627929522095968e+01,2.960300000000000296e+02,0.000000000000000000e+00,5.158984557209193689e+00,0.000000000000000000e+00,-1.000000009973176063e+00,0.000000000000000000e+00,-2.523590887267136190e-10,0.000000000000000000e+00 +4.309821766117052277e+01,2.960400000000000205e+02,0.000000000000000000e+00,5.157046191240302058e+00,0.000000000000000000e+00,-1.000000009973665227e+00,0.000000000000000000e+00,2.140181217009234820e-10,0.000000000000000000e+00 +4.310015675568881477e+01,2.960500000000000114e+02,0.000000000000000000e+00,5.155107096702672642e+00,0.000000000000000000e+00,-1.000000009973250226e+00,0.000000000000000000e+00,-1.030197346770213123e-10,0.000000000000000000e+00 +4.310209657959788387e+01,2.960600000000000023e+02,0.000000000000000000e+00,5.153167272774256347e+00,0.000000000000000000e+00,-1.000000009973450066e+00,0.000000000000000000e+00,-1.183136912896416547e-10,0.000000000000000000e+00 +4.310403713372133438e+01,2.960699999999999932e+02,0.000000000000000000e+00,5.151226718631454204e+00,0.000000000000000000e+00,-1.000000009973679660e+00,0.000000000000000000e+00,7.423275639499435527e-11,0.000000000000000000e+00 +4.310597841888431248e+01,2.960799999999999841e+02,0.000000000000000000e+00,5.149285433449117377e+00,0.000000000000000000e+00,-1.000000009973535553e+00,0.000000000000000000e+00,1.503532930377102440e-10,0.000000000000000000e+00 +4.310792043591352041e+01,2.960900000000000318e+02,0.000000000000000000e+00,5.147343416400542715e+00,0.000000000000000000e+00,-1.000000009973243564e+00,0.000000000000000000e+00,-2.101866357131631770e-10,0.000000000000000000e+00 +4.310986318563722364e+01,2.961000000000000227e+02,0.000000000000000000e+00,5.145400666657467426e+00,0.000000000000000000e+00,-1.000000009973651904e+00,0.000000000000000000e+00,8.808740212791005540e-11,0.000000000000000000e+00 +4.311180666888524371e+01,2.961100000000000136e+02,0.000000000000000000e+00,5.143457183390063747e+00,0.000000000000000000e+00,-1.000000009973480708e+00,0.000000000000000000e+00,2.615356142757373522e-11,0.000000000000000000e+00 +4.311375088648897957e+01,2.961200000000000045e+02,0.000000000000000000e+00,5.141512965766938947e+00,0.000000000000000000e+00,-1.000000009973429860e+00,0.000000000000000000e+00,1.027480693680581429e-12,0.000000000000000000e+00 +4.311569583928139338e+01,2.961299999999999955e+02,0.000000000000000000e+00,5.139568012955127330e+00,0.000000000000000000e+00,-1.000000009973427861e+00,0.000000000000000000e+00,-5.763127412055845069e-11,0.000000000000000000e+00 +4.311764152809702466e+01,2.961399999999999864e+02,0.000000000000000000e+00,5.137622324120087569e+00,0.000000000000000000e+00,-1.000000009973539994e+00,0.000000000000000000e+00,1.893696989894021703e-11,0.000000000000000000e+00 +4.311958795377200460e+01,2.961500000000000341e+02,0.000000000000000000e+00,5.135675898425698271e+00,0.000000000000000000e+00,-1.000000009973503134e+00,0.000000000000000000e+00,-6.625428421414737532e-11,0.000000000000000000e+00 +4.312153511714402754e+01,2.961600000000000250e+02,0.000000000000000000e+00,5.133728735034254420e+00,0.000000000000000000e+00,-1.000000009973632142e+00,0.000000000000000000e+00,9.666494199109915071e-11,0.000000000000000000e+00 +4.312348301905239367e+01,2.961700000000000159e+02,0.000000000000000000e+00,5.131780833106462048e+00,0.000000000000000000e+00,-1.000000009973443849e+00,0.000000000000000000e+00,-1.492724364420153883e-11,0.000000000000000000e+00 +4.312543166033798769e+01,2.961800000000000068e+02,0.000000000000000000e+00,5.129832191801435570e+00,0.000000000000000000e+00,-1.000000009973472936e+00,0.000000000000000000e+00,-2.173310380983370719e-10,0.000000000000000000e+00 +4.312738104184329302e+01,2.961899999999999977e+02,0.000000000000000000e+00,5.127882810276691572e+00,0.000000000000000000e+00,-1.000000009973896598e+00,0.000000000000000000e+00,3.764273464218424334e-10,0.000000000000000000e+00 +4.312933116441239179e+01,2.961999999999999886e+02,0.000000000000000000e+00,5.125932687688145251e+00,0.000000000000000000e+00,-1.000000009973162518e+00,0.000000000000000000e+00,-3.781052890450280045e-10,0.000000000000000000e+00 +4.313128202889097196e+01,2.962099999999999795e+02,0.000000000000000000e+00,5.123981823190109530e+00,0.000000000000000000e+00,-1.000000009973900150e+00,0.000000000000000000e+00,2.807973218306878586e-10,0.000000000000000000e+00 +4.313323363612633443e+01,2.962200000000000273e+02,0.000000000000000000e+00,5.122030215935282627e+00,0.000000000000000000e+00,-1.000000009973352144e+00,0.000000000000000000e+00,-1.546754078967534627e-11,0.000000000000000000e+00 +4.313518598696739303e+01,2.962300000000000182e+02,0.000000000000000000e+00,5.120077865074754264e+00,0.000000000000000000e+00,-1.000000009973382342e+00,0.000000000000000000e+00,-1.311966059413253541e-10,0.000000000000000000e+00 +4.313713908226467453e+01,2.962400000000000091e+02,0.000000000000000000e+00,5.118124769757992354e+00,0.000000000000000000e+00,-1.000000009973638582e+00,0.000000000000000000e+00,-9.489374137023716542e-11,0.000000000000000000e+00 +4.313909292287033992e+01,2.962500000000000000e+02,0.000000000000000000e+00,5.116170929132842993e+00,0.000000000000000000e+00,-1.000000009973823989e+00,0.000000000000000000e+00,3.022944304303386800e-10,0.000000000000000000e+00 +4.314104750963816315e+01,2.962599999999999909e+02,0.000000000000000000e+00,5.114216342345526023e+00,0.000000000000000000e+00,-1.000000009973233128e+00,0.000000000000000000e+00,-3.539615786938510964e-10,0.000000000000000000e+00 +4.314300284342355951e+01,2.962699999999999818e+02,0.000000000000000000e+00,5.112261008540631479e+00,0.000000000000000000e+00,-1.000000009973925241e+00,0.000000000000000000e+00,2.449653648024670610e-10,0.000000000000000000e+00 +4.314495892508357144e+01,2.962800000000000296e+02,0.000000000000000000e+00,5.110304926861109820e+00,0.000000000000000000e+00,-1.000000009973446069e+00,0.000000000000000000e+00,-4.084976298712737848e-12,0.000000000000000000e+00 +4.314691575547688984e+01,2.962900000000000205e+02,0.000000000000000000e+00,5.108348096448276365e+00,0.000000000000000000e+00,-1.000000009973454063e+00,0.000000000000000000e+00,-1.784224225190453703e-10,0.000000000000000000e+00 +4.314887333546384696e+01,2.963000000000000114e+02,0.000000000000000000e+00,5.106390516441798866e+00,0.000000000000000000e+00,-1.000000009973803339e+00,0.000000000000000000e+00,1.802815879057831030e-10,0.000000000000000000e+00 +4.315083166590641639e+01,2.963100000000000023e+02,0.000000000000000000e+00,5.104432185979696612e+00,0.000000000000000000e+00,-1.000000009973450288e+00,0.000000000000000000e+00,-8.568591908454717075e-11,0.000000000000000000e+00 +4.315279074766823442e+01,2.963199999999999932e+02,0.000000000000000000e+00,5.102473104198337772e+00,0.000000000000000000e+00,-1.000000009973618154e+00,0.000000000000000000e+00,-4.554566030740518519e-11,0.000000000000000000e+00 +4.315475058161459287e+01,2.963299999999999841e+02,0.000000000000000000e+00,5.100513270232430507e+00,0.000000000000000000e+00,-1.000000009973707416e+00,0.000000000000000000e+00,7.678631058144674936e-11,0.000000000000000000e+00 +4.315671116861244627e+01,2.963400000000000318e+02,0.000000000000000000e+00,5.098552683215022086e+00,0.000000000000000000e+00,-1.000000009973556869e+00,0.000000000000000000e+00,-1.676649158142461892e-10,0.000000000000000000e+00 +4.315867250953041179e+01,2.963500000000000227e+02,0.000000000000000000e+00,5.096591342277493553e+00,0.000000000000000000e+00,-1.000000009973885717e+00,0.000000000000000000e+00,1.605840597094623942e-10,0.000000000000000000e+00 +4.316063460523878348e+01,2.963600000000000136e+02,0.000000000000000000e+00,5.094629246549553514e+00,0.000000000000000000e+00,-1.000000009973570636e+00,0.000000000000000000e+00,1.584860148543737356e-10,0.000000000000000000e+00 +4.316259745660952518e+01,2.963700000000000045e+02,0.000000000000000000e+00,5.092666395159237247e+00,0.000000000000000000e+00,-1.000000009973259552e+00,0.000000000000000000e+00,-3.788176977389188890e-10,0.000000000000000000e+00 +4.316456106451627761e+01,2.963799999999999955e+02,0.000000000000000000e+00,5.090702787232898707e+00,0.000000000000000000e+00,-1.000000009974003401e+00,0.000000000000000000e+00,1.894488537468838699e-10,0.000000000000000000e+00 +4.316652542983437968e+01,2.963899999999999864e+02,0.000000000000000000e+00,5.088738421895205200e+00,0.000000000000000000e+00,-1.000000009973631254e+00,0.000000000000000000e+00,5.333255026794907160e-11,0.000000000000000000e+00 +4.316849055344084718e+01,2.964000000000000341e+02,0.000000000000000000e+00,5.086773298269139154e+00,0.000000000000000000e+00,-1.000000009973526449e+00,0.000000000000000000e+00,-5.952415289973337140e-11,0.000000000000000000e+00 +4.317045643621439410e+01,2.964100000000000250e+02,0.000000000000000000e+00,5.084807415475986581e+00,0.000000000000000000e+00,-1.000000009973643467e+00,0.000000000000000000e+00,-1.081633783434287073e-10,0.000000000000000000e+00 +4.317242307903543264e+01,2.964200000000000159e+02,0.000000000000000000e+00,5.082840772635335291e+00,0.000000000000000000e+00,-1.000000009973856185e+00,0.000000000000000000e+00,1.811430880866929289e-10,0.000000000000000000e+00 +4.317439048278607316e+01,2.964300000000000068e+02,0.000000000000000000e+00,5.080873368865070461e+00,0.000000000000000000e+00,-1.000000009973499804e+00,0.000000000000000000e+00,-6.024483976072464934e-11,0.000000000000000000e+00 +4.317635864835014559e+01,2.964399999999999977e+02,0.000000000000000000e+00,5.078905203281371072e+00,0.000000000000000000e+00,-1.000000009973618376e+00,0.000000000000000000e+00,-9.044502864500669153e-11,0.000000000000000000e+00 +4.317832757661317800e+01,2.964499999999999886e+02,0.000000000000000000e+00,5.076936274998701926e+00,0.000000000000000000e+00,-1.000000009973796455e+00,0.000000000000000000e+00,1.465498202235140760e-10,0.000000000000000000e+00 +4.318029726846242511e+01,2.964599999999999795e+02,0.000000000000000000e+00,5.074966583129811859e+00,0.000000000000000000e+00,-1.000000009973507797e+00,0.000000000000000000e+00,-2.026110372025913531e-10,0.000000000000000000e+00 +4.318226772478685405e+01,2.964700000000000273e+02,0.000000000000000000e+00,5.072996126785729309e+00,0.000000000000000000e+00,-1.000000009973907034e+00,0.000000000000000000e+00,7.130310893400363406e-11,0.000000000000000000e+00 +4.318423894647716565e+01,2.964800000000000182e+02,0.000000000000000000e+00,5.071024905075754319e+00,0.000000000000000000e+00,-1.000000009973766479e+00,0.000000000000000000e+00,1.230711137722506605e-10,0.000000000000000000e+00 +4.318621093442579451e+01,2.964900000000000091e+02,0.000000000000000000e+00,5.069052917107458534e+00,0.000000000000000000e+00,-1.000000009973523785e+00,0.000000000000000000e+00,-2.009117196396917753e-10,0.000000000000000000e+00 +4.318818368952690179e+01,2.965000000000000000e+02,0.000000000000000000e+00,5.067080161986677211e+00,0.000000000000000000e+00,-1.000000009973920134e+00,0.000000000000000000e+00,3.181833174292397383e-10,0.000000000000000000e+00 +4.319015721267638952e+01,2.965099999999999909e+02,0.000000000000000000e+00,5.065106638817503892e+00,0.000000000000000000e+00,-1.000000009973292192e+00,0.000000000000000000e+00,-2.894925296884899336e-10,0.000000000000000000e+00 +4.319213150477191476e+01,2.965199999999999818e+02,0.000000000000000000e+00,5.063132346702290398e+00,0.000000000000000000e+00,-1.000000009973863735e+00,0.000000000000000000e+00,1.139980598709149873e-10,0.000000000000000000e+00 +4.319410656671286830e+01,2.965300000000000296e+02,0.000000000000000000e+00,5.061157284741634399e+00,0.000000000000000000e+00,-1.000000009973638582e+00,0.000000000000000000e+00,-2.027340016236036412e-10,0.000000000000000000e+00 +4.319608239940041017e+01,2.965400000000000205e+02,0.000000000000000000e+00,5.059181452034382964e+00,0.000000000000000000e+00,-1.000000009974039150e+00,0.000000000000000000e+00,2.207410155385405935e-10,0.000000000000000000e+00 +4.319805900373745544e+01,2.965500000000000114e+02,0.000000000000000000e+00,5.057204847677621018e+00,0.000000000000000000e+00,-1.000000009973602833e+00,0.000000000000000000e+00,-1.080253900435284301e-10,0.000000000000000000e+00 +4.320003638062868134e+01,2.965600000000000023e+02,0.000000000000000000e+00,5.055227470766672226e+00,0.000000000000000000e+00,-1.000000009973816439e+00,0.000000000000000000e+00,5.129760958545157620e-11,0.000000000000000000e+00 +4.320201453098053435e+01,2.965699999999999932e+02,0.000000000000000000e+00,5.053249320395088340e+00,0.000000000000000000e+00,-1.000000009973714965e+00,0.000000000000000000e+00,1.249960078313378770e-10,0.000000000000000000e+00 +4.320399345570123728e+01,2.965799999999999841e+02,0.000000000000000000e+00,5.051270395654649192e+00,0.000000000000000000e+00,-1.000000009973467607e+00,0.000000000000000000e+00,-2.279106113605211012e-10,0.000000000000000000e+00 +4.320597315570078933e+01,2.965900000000000318e+02,0.000000000000000000e+00,5.049290695635355597e+00,0.000000000000000000e+00,-1.000000009973918802e+00,0.000000000000000000e+00,1.580846538306224362e-11,0.000000000000000000e+00 +4.320795363189096605e+01,2.966000000000000227e+02,0.000000000000000000e+00,5.047310219425423128e+00,0.000000000000000000e+00,-1.000000009973887494e+00,0.000000000000000000e+00,7.026964582612072470e-11,0.000000000000000000e+00 +4.320993488518534775e+01,2.966100000000000136e+02,0.000000000000000000e+00,5.045328966111281233e+00,0.000000000000000000e+00,-1.000000009973748272e+00,0.000000000000000000e+00,6.139178661943538209e-11,0.000000000000000000e+00 +4.321191691649929822e+01,2.966200000000000045e+02,0.000000000000000000e+00,5.043346934777565238e+00,0.000000000000000000e+00,-1.000000009973626591e+00,0.000000000000000000e+00,-1.075054058527249992e-10,0.000000000000000000e+00 +4.321389972674997892e+01,2.966299999999999955e+02,0.000000000000000000e+00,5.041364124507111910e+00,0.000000000000000000e+00,-1.000000009973839754e+00,0.000000000000000000e+00,-7.634360550210162875e-11,0.000000000000000000e+00 +4.321588331685635609e+01,2.966399999999999864e+02,0.000000000000000000e+00,5.039380534380954124e+00,0.000000000000000000e+00,-1.000000009973991189e+00,0.000000000000000000e+00,2.922742482659013299e-10,0.000000000000000000e+00 +4.321786768773920073e+01,2.966500000000000341e+02,0.000000000000000000e+00,5.037396163478317312e+00,0.000000000000000000e+00,-1.000000009973411208e+00,0.000000000000000000e+00,-2.118489457997959218e-10,0.000000000000000000e+00 +4.321985284032110286e+01,2.966600000000000250e+02,0.000000000000000000e+00,5.035411010876615023e+00,0.000000000000000000e+00,-1.000000009973831760e+00,0.000000000000000000e+00,-8.844059061992931948e-11,0.000000000000000000e+00 +4.322183877552647147e+01,2.966700000000000159e+02,0.000000000000000000e+00,5.033425075651439151e+00,0.000000000000000000e+00,-1.000000009974007398e+00,0.000000000000000000e+00,1.364644401340521571e-10,0.000000000000000000e+00 +4.322382549428153453e+01,2.966800000000000068e+02,0.000000000000000000e+00,5.031438356876560825e+00,0.000000000000000000e+00,-1.000000009973736281e+00,0.000000000000000000e+00,-5.518986486257085445e-11,0.000000000000000000e+00 +4.322581299751434614e+01,2.966899999999999977e+02,0.000000000000000000e+00,5.029450853623923301e+00,0.000000000000000000e+00,-1.000000009973845971e+00,0.000000000000000000e+00,-5.360459653357370527e-11,0.000000000000000000e+00 +4.322780128615480066e+01,2.966999999999999886e+02,0.000000000000000000e+00,5.027462564963634861e+00,0.000000000000000000e+00,-1.000000009973952553e+00,0.000000000000000000e+00,8.115653226622582688e-11,0.000000000000000000e+00 +4.322979036113463280e+01,2.967099999999999795e+02,0.000000000000000000e+00,5.025473489963966145e+00,0.000000000000000000e+00,-1.000000009973791126e+00,0.000000000000000000e+00,6.918451508969656006e-11,0.000000000000000000e+00 +4.323178022338741044e+01,2.967200000000000273e+02,0.000000000000000000e+00,5.023483627691344822e+00,0.000000000000000000e+00,-1.000000009973653459e+00,0.000000000000000000e+00,-1.398758546572441980e-10,0.000000000000000000e+00 +4.323377087384854889e+01,2.967300000000000182e+02,0.000000000000000000e+00,5.021492977210349373e+00,0.000000000000000000e+00,-1.000000009973931903e+00,0.000000000000000000e+00,8.027967054661136261e-11,0.000000000000000000e+00 +4.323576231345533216e+01,2.967400000000000091e+02,0.000000000000000000e+00,5.019501537583703765e+00,0.000000000000000000e+00,-1.000000009973772030e+00,0.000000000000000000e+00,1.638393256675040367e-11,0.000000000000000000e+00 +4.323775454314689171e+01,2.967500000000000000e+02,0.000000000000000000e+00,5.017509307872274782e+00,0.000000000000000000e+00,-1.000000009973739390e+00,0.000000000000000000e+00,-1.445001800950493781e-10,0.000000000000000000e+00 +4.323974756386422769e+01,2.967599999999999909e+02,0.000000000000000000e+00,5.015516287135064033e+00,0.000000000000000000e+00,-1.000000009974027382e+00,0.000000000000000000e+00,1.358675365615797528e-11,0.000000000000000000e+00 +4.324174137655020189e+01,2.967699999999999818e+02,0.000000000000000000e+00,5.013522474429203513e+00,0.000000000000000000e+00,-1.000000009974000292e+00,0.000000000000000000e+00,2.384529271865466289e-10,0.000000000000000000e+00 +4.324373598214955905e+01,2.967800000000000296e+02,0.000000000000000000e+00,5.011527868809952047e+00,0.000000000000000000e+00,-1.000000009973524673e+00,0.000000000000000000e+00,-1.611309386814599026e-10,0.000000000000000000e+00 +4.324573138160891972e+01,2.967900000000000205e+02,0.000000000000000000e+00,5.009532469330689075e+00,0.000000000000000000e+00,-1.000000009973846193e+00,0.000000000000000000e+00,-8.676249332490865158e-11,0.000000000000000000e+00 +4.324772757587679450e+01,2.968000000000000114e+02,0.000000000000000000e+00,5.007536275042906659e+00,0.000000000000000000e+00,-1.000000009974019388e+00,0.000000000000000000e+00,1.445465337991564634e-12,0.000000000000000000e+00 +4.324972456590357694e+01,2.968100000000000023e+02,0.000000000000000000e+00,5.005539284996208593e+00,0.000000000000000000e+00,-1.000000009974016502e+00,0.000000000000000000e+00,9.525152149784666478e-11,0.000000000000000000e+00 +4.325172235264155773e+01,2.968199999999999932e+02,0.000000000000000000e+00,5.003541498238303298e+00,0.000000000000000000e+00,-1.000000009973826209e+00,0.000000000000000000e+00,-3.088606118662459012e-11,0.000000000000000000e+00 +4.325372093704493182e+01,2.968299999999999841e+02,0.000000000000000000e+00,5.001542913814998492e+00,0.000000000000000000e+00,-1.000000009973887938e+00,0.000000000000000000e+00,6.918823814553985646e-11,0.000000000000000000e+00 +4.325572032006979128e+01,2.968400000000000318e+02,0.000000000000000000e+00,4.999543530770194977e+00,0.000000000000000000e+00,-1.000000009973749604e+00,0.000000000000000000e+00,-4.318373288890965941e-11,0.000000000000000000e+00 +4.325772050267415381e+01,2.968500000000000227e+02,0.000000000000000000e+00,4.997543348145883080e+00,0.000000000000000000e+00,-1.000000009973835979e+00,0.000000000000000000e+00,-1.343819498923407438e-10,0.000000000000000000e+00 +4.325972148581794130e+01,2.968600000000000136e+02,0.000000000000000000e+00,4.995542364982135553e+00,0.000000000000000000e+00,-1.000000009974104875e+00,0.000000000000000000e+00,3.250053366298834508e-11,0.000000000000000000e+00 +4.326172327046300836e+01,2.968700000000000045e+02,0.000000000000000000e+00,4.993540580317103128e+00,0.000000000000000000e+00,-1.000000009974039816e+00,0.000000000000000000e+00,3.470508772894239066e-11,0.000000000000000000e+00 +4.326372585757312805e+01,2.968799999999999955e+02,0.000000000000000000e+00,4.991537993187010080e+00,0.000000000000000000e+00,-1.000000009973970316e+00,0.000000000000000000e+00,1.194794920035401535e-10,0.000000000000000000e+00 +4.326572924811400611e+01,2.968899999999999864e+02,0.000000000000000000e+00,4.989534602626147120e+00,0.000000000000000000e+00,-1.000000009973730952e+00,0.000000000000000000e+00,-1.255249838466681968e-10,0.000000000000000000e+00 +4.326773344305329516e+01,2.969000000000000341e+02,0.000000000000000000e+00,4.987530407666866950e+00,0.000000000000000000e+00,-1.000000009973982529e+00,0.000000000000000000e+00,-1.107454218921969863e-12,0.000000000000000000e+00 +4.326973844336058761e+01,2.969100000000000250e+02,0.000000000000000000e+00,4.985525407339577164e+00,0.000000000000000000e+00,-1.000000009973984749e+00,0.000000000000000000e+00,8.988913237661347400e-11,0.000000000000000000e+00 +4.327174425000742275e+01,2.969200000000000159e+02,0.000000000000000000e+00,4.983519600672737582e+00,0.000000000000000000e+00,-1.000000009973804449e+00,0.000000000000000000e+00,-2.777474738577494783e-11,0.000000000000000000e+00 +4.327375086396729387e+01,2.969300000000000068e+02,0.000000000000000000e+00,4.981512986692853140e+00,0.000000000000000000e+00,-1.000000009973860182e+00,0.000000000000000000e+00,-8.306946803774047119e-11,0.000000000000000000e+00 +4.327575828621565535e+01,2.969399999999999977e+02,0.000000000000000000e+00,4.979505564424467678e+00,0.000000000000000000e+00,-1.000000009974026938e+00,0.000000000000000000e+00,-2.156061074260520221e-11,0.000000000000000000e+00 +4.327776651772993688e+01,2.969499999999999886e+02,0.000000000000000000e+00,4.977497332890159498e+00,0.000000000000000000e+00,-1.000000009974070236e+00,0.000000000000000000e+00,2.164033347584511279e-10,0.000000000000000000e+00 +4.327977555948952215e+01,2.969599999999999795e+02,0.000000000000000000e+00,4.975488291110536032e+00,0.000000000000000000e+00,-1.000000009973635473e+00,0.000000000000000000e+00,-1.844983154287626075e-10,0.000000000000000000e+00 +4.328178541247578437e+01,2.969700000000000273e+02,0.000000000000000000e+00,4.973478438104228516e+00,0.000000000000000000e+00,-1.000000009974006288e+00,0.000000000000000000e+00,-5.411236868970874392e-11,0.000000000000000000e+00 +4.328379607767207204e+01,2.969800000000000182e+02,0.000000000000000000e+00,4.971467772887883108e+00,0.000000000000000000e+00,-1.000000009974115089e+00,0.000000000000000000e+00,2.218814071032114852e-11,0.000000000000000000e+00 +4.328580755606373032e+01,2.969900000000000091e+02,0.000000000000000000e+00,4.969456294476159997e+00,0.000000000000000000e+00,-1.000000009974070458e+00,0.000000000000000000e+00,1.242474520508664249e-10,0.000000000000000000e+00 +4.328781984863809384e+01,2.970000000000000000e+02,0.000000000000000000e+00,4.967444001881725413e+00,0.000000000000000000e+00,-1.000000009973820436e+00,0.000000000000000000e+00,-1.012548621332470624e-10,0.000000000000000000e+00 +4.328983295638449391e+01,2.970099999999999909e+02,0.000000000000000000e+00,4.965430894115246296e+00,0.000000000000000000e+00,-1.000000009974024273e+00,0.000000000000000000e+00,9.305497871444118999e-11,0.000000000000000000e+00 +4.329184688029427264e+01,2.970199999999999818e+02,0.000000000000000000e+00,4.963416970185383192e+00,0.000000000000000000e+00,-1.000000009973836868e+00,0.000000000000000000e+00,-7.428153731903082138e-11,0.000000000000000000e+00 +4.329386162136077587e+01,2.970300000000000296e+02,0.000000000000000000e+00,4.961402229098787586e+00,0.000000000000000000e+00,-1.000000009973986526e+00,0.000000000000000000e+00,-6.499750327223017516e-11,0.000000000000000000e+00 +4.329587718057936740e+01,2.970400000000000205e+02,0.000000000000000000e+00,4.959386669860093022e+00,0.000000000000000000e+00,-1.000000009974117532e+00,0.000000000000000000e+00,7.267953354945037426e-12,0.000000000000000000e+00 +4.329789355894743608e+01,2.970500000000000114e+02,0.000000000000000000e+00,4.957370291471911550e+00,0.000000000000000000e+00,-1.000000009974102877e+00,0.000000000000000000e+00,3.357309849902752190e-11,0.000000000000000000e+00 +4.329991075746440288e+01,2.970600000000000023e+02,0.000000000000000000e+00,4.955353092934827508e+00,0.000000000000000000e+00,-1.000000009974035153e+00,0.000000000000000000e+00,-8.846487735069354921e-11,0.000000000000000000e+00 +4.330192877713171384e+01,2.970699999999999932e+02,0.000000000000000000e+00,4.953335073247391307e+00,0.000000000000000000e+00,-1.000000009974213677e+00,0.000000000000000000e+00,1.977550670262131207e-10,0.000000000000000000e+00 +4.330394761895285427e+01,2.970799999999999841e+02,0.000000000000000000e+00,4.951316231406113211e+00,0.000000000000000000e+00,-1.000000009973814441e+00,0.000000000000000000e+00,-7.201155519822598014e-11,0.000000000000000000e+00 +4.330596728393336292e+01,2.970900000000000318e+02,0.000000000000000000e+00,4.949296566405459785e+00,0.000000000000000000e+00,-1.000000009973959880e+00,0.000000000000000000e+00,-1.133032503367387920e-10,0.000000000000000000e+00 +4.330798777308082492e+01,2.971000000000000227e+02,0.000000000000000000e+00,4.947276077237844127e+00,0.000000000000000000e+00,-1.000000009974188808e+00,0.000000000000000000e+00,2.095968455544340776e-10,0.000000000000000000e+00 +4.331000908740488597e+01,2.971100000000000136e+02,0.000000000000000000e+00,4.945254762893623202e+00,0.000000000000000000e+00,-1.000000009973765147e+00,0.000000000000000000e+00,-2.668303150395235737e-10,0.000000000000000000e+00 +4.331203122791724525e+01,2.971200000000000045e+02,0.000000000000000000e+00,4.943232622361092510e+00,0.000000000000000000e+00,-1.000000009974304715e+00,0.000000000000000000e+00,1.249089437271183078e-10,0.000000000000000000e+00 +4.331405419563168380e+01,2.971299999999999955e+02,0.000000000000000000e+00,4.941209654626475434e+00,0.000000000000000000e+00,-1.000000009974052029e+00,0.000000000000000000e+00,1.612838350051530524e-11,0.000000000000000000e+00 +4.331607799156405036e+01,2.971399999999999864e+02,0.000000000000000000e+00,4.939185858673924123e+00,0.000000000000000000e+00,-1.000000009974019388e+00,0.000000000000000000e+00,-1.974095230752995429e-12,0.000000000000000000e+00 +4.331810261673227558e+01,2.971500000000000341e+02,0.000000000000000000e+00,4.937161233485507950e+00,0.000000000000000000e+00,-1.000000009974023385e+00,0.000000000000000000e+00,1.578628822378276492e-11,0.000000000000000000e+00 +4.332012807215637196e+01,2.971600000000000250e+02,0.000000000000000000e+00,4.935135778041209953e+00,0.000000000000000000e+00,-1.000000009973991411e+00,0.000000000000000000e+00,2.016309304319246997e-11,0.000000000000000000e+00 +4.332215435885844812e+01,2.971700000000000159e+02,0.000000000000000000e+00,4.933109491318920625e+00,0.000000000000000000e+00,-1.000000009973950554e+00,0.000000000000000000e+00,-2.484299949381554980e-10,0.000000000000000000e+00 +4.332418147786271589e+01,2.971800000000000068e+02,0.000000000000000000e+00,4.931082372294431693e+00,0.000000000000000000e+00,-1.000000009974454152e+00,0.000000000000000000e+00,2.519411465817686234e-10,0.000000000000000000e+00 +4.332620943019549031e+01,2.971899999999999977e+02,0.000000000000000000e+00,4.929054419941429011e+00,0.000000000000000000e+00,-1.000000009973943227e+00,0.000000000000000000e+00,-2.396889171512424043e-11,0.000000000000000000e+00 +4.332823821688519672e+01,2.971999999999999886e+02,0.000000000000000000e+00,4.927025633231490787e+00,0.000000000000000000e+00,-1.000000009973991855e+00,0.000000000000000000e+00,-2.308381060993279642e-11,0.000000000000000000e+00 +4.333026783896237077e+01,2.972099999999999795e+02,0.000000000000000000e+00,4.924996011134075147e+00,0.000000000000000000e+00,-1.000000009974038706e+00,0.000000000000000000e+00,1.651288878259927358e-11,0.000000000000000000e+00 +4.333229829745967265e+01,2.972200000000000273e+02,0.000000000000000000e+00,4.922965552616518359e+00,0.000000000000000000e+00,-1.000000009974005177e+00,0.000000000000000000e+00,-1.366397426487841457e-10,0.000000000000000000e+00 +4.333432959341190127e+01,2.972300000000000182e+02,0.000000000000000000e+00,4.920934256644027727e+00,0.000000000000000000e+00,-1.000000009974282733e+00,0.000000000000000000e+00,1.526455663321370271e-10,0.000000000000000000e+00 +4.333636172785598717e+01,2.972400000000000091e+02,0.000000000000000000e+00,4.918902122179674485e+00,0.000000000000000000e+00,-1.000000009973972537e+00,0.000000000000000000e+00,-1.968172652448479330e-10,0.000000000000000000e+00 +4.333839470183099252e+01,2.972500000000000000e+02,0.000000000000000000e+00,4.916869148184390248e+00,0.000000000000000000e+00,-1.000000009974372661e+00,0.000000000000000000e+00,1.061194867987331264e-10,0.000000000000000000e+00 +4.334042851637813953e+01,2.972599999999999909e+02,0.000000000000000000e+00,4.914835333616956348e+00,0.000000000000000000e+00,-1.000000009974156834e+00,0.000000000000000000e+00,-7.420926155487018749e-12,0.000000000000000000e+00 +4.334246317254079628e+01,2.972699999999999818e+02,0.000000000000000000e+00,4.912800677434002949e+00,0.000000000000000000e+00,-1.000000009974171933e+00,0.000000000000000000e+00,1.185765782534433782e-10,0.000000000000000000e+00 +4.334449867136449797e+01,2.972800000000000296e+02,0.000000000000000000e+00,4.910765178589998392e+00,0.000000000000000000e+00,-1.000000009973930570e+00,0.000000000000000000e+00,-1.414260361405623192e-10,0.000000000000000000e+00 +4.334653501389693986e+01,2.972900000000000205e+02,0.000000000000000000e+00,4.908728836037245635e+00,0.000000000000000000e+00,-1.000000009974218562e+00,0.000000000000000000e+00,9.221034147993711301e-11,0.000000000000000000e+00 +4.334857220118799148e+01,2.973000000000000114e+02,0.000000000000000000e+00,4.906691648725873378e+00,0.000000000000000000e+00,-1.000000009974030712e+00,0.000000000000000000e+00,-8.389183946453209742e-12,0.000000000000000000e+00 +4.335061023428970373e+01,2.973100000000000023e+02,0.000000000000000000e+00,4.904653615603833394e+00,0.000000000000000000e+00,-1.000000009974047810e+00,0.000000000000000000e+00,-1.940690440128907301e-10,0.000000000000000000e+00 +4.335264911425630885e+01,2.973199999999999932e+02,0.000000000000000000e+00,4.902614735616890762e+00,0.000000000000000000e+00,-1.000000009974443493e+00,0.000000000000000000e+00,2.154337721945915047e-10,0.000000000000000000e+00 +4.335468884214423468e+01,2.973299999999999841e+02,0.000000000000000000e+00,4.900575007708618536e+00,0.000000000000000000e+00,-1.000000009974004067e+00,0.000000000000000000e+00,-1.545167662918842249e-11,0.000000000000000000e+00 +4.335672941901210464e+01,2.973400000000000318e+02,0.000000000000000000e+00,4.898534430820394192e+00,0.000000000000000000e+00,-1.000000009974035597e+00,0.000000000000000000e+00,-1.939356872904865502e-10,0.000000000000000000e+00 +4.335877084592075192e+01,2.973500000000000227e+02,0.000000000000000000e+00,4.896493003891388085e+00,0.000000000000000000e+00,-1.000000009974431503e+00,0.000000000000000000e+00,1.628685302141730033e-10,0.000000000000000000e+00 +4.336081312393321241e+01,2.973600000000000136e+02,0.000000000000000000e+00,4.894450725858559892e+00,0.000000000000000000e+00,-1.000000009974098880e+00,0.000000000000000000e+00,5.227442476969306450e-11,0.000000000000000000e+00 +4.336285625411473887e+01,2.973700000000000045e+02,0.000000000000000000e+00,4.892407595656654173e+00,0.000000000000000000e+00,-1.000000009973992077e+00,0.000000000000000000e+00,-2.425780945247992619e-10,0.000000000000000000e+00 +4.336490023753281520e+01,2.973799999999999955e+02,0.000000000000000000e+00,4.890363612218189715e+00,0.000000000000000000e+00,-1.000000009974487902e+00,0.000000000000000000e+00,2.026249945696698993e-10,0.000000000000000000e+00 +4.336694507525715636e+01,2.973899999999999864e+02,0.000000000000000000e+00,4.888318774473454198e+00,0.000000000000000000e+00,-1.000000009974073567e+00,0.000000000000000000e+00,-1.921201915515261292e-11,0.000000000000000000e+00 +4.336899076835970845e+01,2.974000000000000341e+02,0.000000000000000000e+00,4.886273081350501535e+00,0.000000000000000000e+00,-1.000000009974112869e+00,0.000000000000000000e+00,2.810073791592104704e-11,0.000000000000000000e+00 +4.337103731791465577e+01,2.974100000000000250e+02,0.000000000000000000e+00,4.884226531775139435e+00,0.000000000000000000e+00,-1.000000009974055359e+00,0.000000000000000000e+00,-1.996594233277367086e-10,0.000000000000000000e+00 +4.337308472499844925e+01,2.974200000000000159e+02,0.000000000000000000e+00,4.882179124670926740e+00,0.000000000000000000e+00,-1.000000009974464144e+00,0.000000000000000000e+00,2.426129715130350376e-10,0.000000000000000000e+00 +4.337513299068977801e+01,2.974300000000000068e+02,0.000000000000000000e+00,4.880130858959164541e+00,0.000000000000000000e+00,-1.000000009973967208e+00,0.000000000000000000e+00,-2.348175780789609625e-10,0.000000000000000000e+00 +4.337718211606961205e+01,2.974399999999999977e+02,0.000000000000000000e+00,4.878081733558893518e+00,0.000000000000000000e+00,-1.000000009974448378e+00,0.000000000000000000e+00,1.705963976829151619e-10,0.000000000000000000e+00 +4.337923210222118087e+01,2.974499999999999886e+02,0.000000000000000000e+00,4.876031747386880610e+00,0.000000000000000000e+00,-1.000000009974098658e+00,0.000000000000000000e+00,-1.169312266386464542e-10,0.000000000000000000e+00 +4.338128295022998770e+01,2.974599999999999795e+02,0.000000000000000000e+00,4.873980899357619911e+00,0.000000000000000000e+00,-1.000000009974338466e+00,0.000000000000000000e+00,8.051874254282485092e-11,0.000000000000000000e+00 +4.338333466118382375e+01,2.974700000000000273e+02,0.000000000000000000e+00,4.871929188383319342e+00,0.000000000000000000e+00,-1.000000009974173265e+00,0.000000000000000000e+00,4.651678044986401188e-11,0.000000000000000000e+00 +4.338538723617276816e+01,2.974800000000000182e+02,0.000000000000000000e+00,4.869876613373898877e+00,0.000000000000000000e+00,-1.000000009974077786e+00,0.000000000000000000e+00,-8.542505646337027952e-11,0.000000000000000000e+00 +4.338744067628920220e+01,2.974900000000000091e+02,0.000000000000000000e+00,4.867823173236980772e+00,0.000000000000000000e+00,-1.000000009974253201e+00,0.000000000000000000e+00,3.523648827108995809e-11,0.000000000000000000e+00 +4.338949498262780935e+01,2.975000000000000000e+02,0.000000000000000000e+00,4.865768866877883347e+00,0.000000000000000000e+00,-1.000000009974180815e+00,0.000000000000000000e+00,-7.757399270543353404e-11,0.000000000000000000e+00 +4.339155015628557521e+01,2.975099999999999909e+02,0.000000000000000000e+00,4.863713693199615662e+00,0.000000000000000000e+00,-1.000000009974340243e+00,0.000000000000000000e+00,-6.177379124916848293e-11,0.000000000000000000e+00 +4.339360619836181598e+01,2.975199999999999818e+02,0.000000000000000000e+00,4.861657651102868627e+00,0.000000000000000000e+00,-1.000000009974467252e+00,0.000000000000000000e+00,2.397580277224580343e-10,0.000000000000000000e+00 +4.339566310995815712e+01,2.975300000000000296e+02,0.000000000000000000e+00,4.859600739486009680e+00,0.000000000000000000e+00,-1.000000009973974091e+00,0.000000000000000000e+00,-2.684671738215891764e-10,0.000000000000000000e+00 +4.339772089217856887e+01,2.975400000000000205e+02,0.000000000000000000e+00,4.857542957245076565e+00,0.000000000000000000e+00,-1.000000009974526538e+00,0.000000000000000000e+00,5.263525089417513673e-11,0.000000000000000000e+00 +4.339977954612934496e+01,2.975500000000000114e+02,0.000000000000000000e+00,4.855484303273765789e+00,0.000000000000000000e+00,-1.000000009974418180e+00,0.000000000000000000e+00,1.197806978256366870e-10,0.000000000000000000e+00 +4.340183907291913812e+01,2.975600000000000023e+02,0.000000000000000000e+00,4.853424776463432622e+00,0.000000000000000000e+00,-1.000000009974171489e+00,0.000000000000000000e+00,-9.332680975620749704e-11,0.000000000000000000e+00 +4.340389947365893875e+01,2.975699999999999932e+02,0.000000000000000000e+00,4.851364375703079546e+00,0.000000000000000000e+00,-1.000000009974363779e+00,0.000000000000000000e+00,2.003627872239672286e-11,0.000000000000000000e+00 +4.340596074946211047e+01,2.975799999999999841e+02,0.000000000000000000e+00,4.849303099879349155e+00,0.000000000000000000e+00,-1.000000009974322479e+00,0.000000000000000000e+00,2.670368745616610784e-11,0.000000000000000000e+00 +4.340802290144436881e+01,2.975900000000000318e+02,0.000000000000000000e+00,4.847240947876519712e+00,0.000000000000000000e+00,-1.000000009974267412e+00,0.000000000000000000e+00,1.272190974874753098e-10,0.000000000000000000e+00 +4.341008593072381672e+01,2.976000000000000227e+02,0.000000000000000000e+00,4.845177918576496268e+00,0.000000000000000000e+00,-1.000000009974004955e+00,0.000000000000000000e+00,-3.059704933956809393e-10,0.000000000000000000e+00 +4.341214983842092323e+01,2.976100000000000136e+02,0.000000000000000000e+00,4.843114010858804441e+00,0.000000000000000000e+00,-1.000000009974636450e+00,0.000000000000000000e+00,1.913114072786340066e-10,0.000000000000000000e+00 +4.341421462565855194e+01,2.976200000000000045e+02,0.000000000000000000e+00,4.841049223600580653e+00,0.000000000000000000e+00,-1.000000009974241433e+00,0.000000000000000000e+00,-3.815997461083422309e-11,0.000000000000000000e+00 +4.341628029356196095e+01,2.976299999999999955e+02,0.000000000000000000e+00,4.838983555676571235e+00,0.000000000000000000e+00,-1.000000009974320259e+00,0.000000000000000000e+00,6.532778766502279195e-11,0.000000000000000000e+00 +4.341834684325880289e+01,2.976399999999999864e+02,0.000000000000000000e+00,4.836917005959118221e+00,0.000000000000000000e+00,-1.000000009974185256e+00,0.000000000000000000e+00,-9.934604762201058239e-11,0.000000000000000000e+00 +4.342041427587914626e+01,2.976500000000000341e+02,0.000000000000000000e+00,4.834849573318156679e+00,0.000000000000000000e+00,-1.000000009974390647e+00,0.000000000000000000e+00,1.220628923462362253e-10,0.000000000000000000e+00 +4.342248259255546827e+01,2.976600000000000250e+02,0.000000000000000000e+00,4.832781256621204946e+00,0.000000000000000000e+00,-1.000000009974138182e+00,0.000000000000000000e+00,-6.492212679134088627e-11,0.000000000000000000e+00 +4.342455179442267621e+01,2.976700000000000159e+02,0.000000000000000000e+00,4.830712054733360183e+00,0.000000000000000000e+00,-1.000000009974272519e+00,0.000000000000000000e+00,-2.011187905687228461e-10,0.000000000000000000e+00 +4.342662188261810030e+01,2.976800000000000068e+02,0.000000000000000000e+00,4.828641966517287720e+00,0.000000000000000000e+00,-1.000000009974688853e+00,0.000000000000000000e+00,1.768014757438819783e-10,0.000000000000000000e+00 +4.342869285828151504e+01,2.976899999999999977e+02,0.000000000000000000e+00,4.826570990833215724e+00,0.000000000000000000e+00,-1.000000009974322701e+00,0.000000000000000000e+00,8.938095167010166915e-11,0.000000000000000000e+00 +4.343076472255513210e+01,2.976999999999999886e+02,0.000000000000000000e+00,4.824499126538929872e+00,0.000000000000000000e+00,-1.000000009974137516e+00,0.000000000000000000e+00,-1.926114696519264596e-10,0.000000000000000000e+00 +4.343283747658362870e+01,2.977099999999999795e+02,0.000000000000000000e+00,4.822426372489761803e+00,0.000000000000000000e+00,-1.000000009974536752e+00,0.000000000000000000e+00,2.271153562116886448e-10,0.000000000000000000e+00 +4.343491112151412636e+01,2.977200000000000273e+02,0.000000000000000000e+00,4.820352727538582904e+00,0.000000000000000000e+00,-1.000000009974065796e+00,0.000000000000000000e+00,-2.284091298447274115e-10,0.000000000000000000e+00 +4.343698565849621929e+01,2.977300000000000182e+02,0.000000000000000000e+00,4.818278190535800753e+00,0.000000000000000000e+00,-1.000000009974539639e+00,0.000000000000000000e+00,-3.081233310440879593e-11,0.000000000000000000e+00 +4.343906108868197435e+01,2.977400000000000091e+02,0.000000000000000000e+00,4.816202760329344912e+00,0.000000000000000000e+00,-1.000000009974603588e+00,0.000000000000000000e+00,2.891689613078295873e-10,0.000000000000000000e+00 +4.344113741322594535e+01,2.977500000000000000e+02,0.000000000000000000e+00,4.814126435764666034e+00,0.000000000000000000e+00,-1.000000009974003179e+00,0.000000000000000000e+00,-2.017110164295826663e-10,0.000000000000000000e+00 +4.344321463328516586e+01,2.977599999999999909e+02,0.000000000000000000e+00,4.812049215684726100e+00,0.000000000000000000e+00,-1.000000009974422177e+00,0.000000000000000000e+00,4.092315041520078347e-11,0.000000000000000000e+00 +4.344529275001917767e+01,2.977699999999999818e+02,0.000000000000000000e+00,4.809971098929986866e+00,0.000000000000000000e+00,-1.000000009974337134e+00,0.000000000000000000e+00,-1.086184610612893842e-10,0.000000000000000000e+00 +4.344737176459001660e+01,2.977800000000000296e+02,0.000000000000000000e+00,4.807892084338408978e+00,0.000000000000000000e+00,-1.000000009974562953e+00,0.000000000000000000e+00,8.262964697531690437e-11,0.000000000000000000e+00 +4.344945167816224085e+01,2.977900000000000205e+02,0.000000000000000000e+00,4.805812170745439538e+00,0.000000000000000000e+00,-1.000000009974391091e+00,0.000000000000000000e+00,-8.355429525361122620e-11,0.000000000000000000e+00 +4.345153249190291689e+01,2.978000000000000114e+02,0.000000000000000000e+00,4.803731356984007661e+00,0.000000000000000000e+00,-1.000000009974564952e+00,0.000000000000000000e+00,1.378102279675128072e-10,0.000000000000000000e+00 +4.345361420698164778e+01,2.978100000000000023e+02,0.000000000000000000e+00,4.801649641884513819e+00,0.000000000000000000e+00,-1.000000009974278070e+00,0.000000000000000000e+00,-1.418019928968484299e-10,0.000000000000000000e+00 +4.345569682457056615e+01,2.978199999999999932e+02,0.000000000000000000e+00,4.799567024274825400e+00,0.000000000000000000e+00,-1.000000009974573389e+00,0.000000000000000000e+00,2.455414188402382180e-10,0.000000000000000000e+00 +4.345778034584434124e+01,2.978299999999999841e+02,0.000000000000000000e+00,4.797483502980265158e+00,0.000000000000000000e+00,-1.000000009974061799e+00,0.000000000000000000e+00,-1.878045145121511204e-10,0.000000000000000000e+00 +4.345986477198020737e+01,2.978400000000000318e+02,0.000000000000000000e+00,4.795399076823608553e+00,0.000000000000000000e+00,-1.000000009974453263e+00,0.000000000000000000e+00,-5.696639840070694859e-11,0.000000000000000000e+00 +4.346195010415794968e+01,2.978500000000000227e+02,0.000000000000000000e+00,4.793313744625069539e+00,0.000000000000000000e+00,-1.000000009974572057e+00,0.000000000000000000e+00,-1.596494185060494073e-11,0.000000000000000000e+00 +4.346403634355991130e+01,2.978600000000000136e+02,0.000000000000000000e+00,4.791227505202298786e+00,0.000000000000000000e+00,-1.000000009974605364e+00,0.000000000000000000e+00,1.055355288750599024e-10,0.000000000000000000e+00 +4.346612349137102171e+01,2.978700000000000045e+02,0.000000000000000000e+00,4.789140357370373025e+00,0.000000000000000000e+00,-1.000000009974385096e+00,0.000000000000000000e+00,7.784108339226297714e-11,0.000000000000000000e+00 +4.346821154877878257e+01,2.978799999999999955e+02,0.000000000000000000e+00,4.787052299941787936e+00,0.000000000000000000e+00,-1.000000009974222559e+00,0.000000000000000000e+00,-1.175610685185816548e-10,0.000000000000000000e+00 +4.347030051697328190e+01,2.978899999999999864e+02,0.000000000000000000e+00,4.784963331726449276e+00,0.000000000000000000e+00,-1.000000009974468140e+00,0.000000000000000000e+00,-8.531676599368906741e-11,0.000000000000000000e+00 +4.347239039714722253e+01,2.979000000000000341e+02,0.000000000000000000e+00,4.782873451531664877e+00,0.000000000000000000e+00,-1.000000009974646442e+00,0.000000000000000000e+00,1.683287824833554267e-10,0.000000000000000000e+00 +4.347448119049589366e+01,2.979100000000000250e+02,0.000000000000000000e+00,4.780782658162138432e+00,0.000000000000000000e+00,-1.000000009974294501e+00,0.000000000000000000e+00,-1.657074861636486871e-10,0.000000000000000000e+00 +4.347657289821720639e+01,2.979200000000000159e+02,0.000000000000000000e+00,4.778690950419961503e+00,0.000000000000000000e+00,-1.000000009974641113e+00,0.000000000000000000e+00,1.399567875727021036e-10,0.000000000000000000e+00 +4.347866552151169373e+01,2.979300000000000068e+02,0.000000000000000000e+00,4.776598327104601971e+00,0.000000000000000000e+00,-1.000000009974348236e+00,0.000000000000000000e+00,-1.151831026832272274e-10,0.000000000000000000e+00 +4.348075906158251058e+01,2.979399999999999977e+02,0.000000000000000000e+00,4.774504787012901375e+00,0.000000000000000000e+00,-1.000000009974589377e+00,0.000000000000000000e+00,1.071814712465544951e-10,0.000000000000000000e+00 +4.348285351963546219e+01,2.979499999999999886e+02,0.000000000000000000e+00,4.772410328939061586e+00,0.000000000000000000e+00,-1.000000009974364890e+00,0.000000000000000000e+00,-1.750604519880589403e-10,0.000000000000000000e+00 +4.348494889687898279e+01,2.979599999999999795e+02,0.000000000000000000e+00,4.770314951674641257e+00,0.000000000000000000e+00,-1.000000009974731707e+00,0.000000000000000000e+00,2.916040089830992919e-10,0.000000000000000000e+00 +4.348704519452417117e+01,2.979700000000000273e+02,0.000000000000000000e+00,4.768218654008543389e+00,0.000000000000000000e+00,-1.000000009974120418e+00,0.000000000000000000e+00,-2.671244484289914655e-10,0.000000000000000000e+00 +4.348914241378478351e+01,2.979800000000000182e+02,0.000000000000000000e+00,4.766121434727012662e+00,0.000000000000000000e+00,-1.000000009974680637e+00,0.000000000000000000e+00,2.137748933017339317e-11,0.000000000000000000e+00 +4.349124055587724769e+01,2.979900000000000091e+02,0.000000000000000000e+00,4.764023292613619454e+00,0.000000000000000000e+00,-1.000000009974635784e+00,0.000000000000000000e+00,2.072280487259732573e-10,0.000000000000000000e+00 +4.349333962202067028e+01,2.980000000000000000e+02,0.000000000000000000e+00,4.761924226449259834e+00,0.000000000000000000e+00,-1.000000009974200799e+00,0.000000000000000000e+00,-2.455188952991167662e-10,0.000000000000000000e+00 +4.349543961343684373e+01,2.980099999999999909e+02,0.000000000000000000e+00,4.759824235012143134e+00,0.000000000000000000e+00,-1.000000009974716386e+00,0.000000000000000000e+00,1.492333327987515221e-10,0.000000000000000000e+00 +4.349754053135024634e+01,2.980199999999999818e+02,0.000000000000000000e+00,4.757723317077781289e+00,0.000000000000000000e+00,-1.000000009974402859e+00,0.000000000000000000e+00,-1.368072698596673144e-10,0.000000000000000000e+00 +4.349964237698807779e+01,2.980300000000000296e+02,0.000000000000000000e+00,4.755621471418987056e+00,0.000000000000000000e+00,-1.000000009974690407e+00,0.000000000000000000e+00,1.941910606970579628e-10,0.000000000000000000e+00 +4.350174515158023070e+01,2.980400000000000205e+02,0.000000000000000000e+00,4.753518696805858923e+00,0.000000000000000000e+00,-1.000000009974282067e+00,0.000000000000000000e+00,-1.666623732855854403e-10,0.000000000000000000e+00 +4.350384885635932619e+01,2.980500000000000114e+02,0.000000000000000000e+00,4.751414992005778437e+00,0.000000000000000000e+00,-1.000000009974632675e+00,0.000000000000000000e+00,9.094324678013922388e-11,0.000000000000000000e+00 +4.350595349256071387e+01,2.980600000000000023e+02,0.000000000000000000e+00,4.749310355783395998e+00,0.000000000000000000e+00,-1.000000009974441273e+00,0.000000000000000000e+00,-1.239106521399133646e-10,0.000000000000000000e+00 +4.350805906142247892e+01,2.980699999999999932e+02,0.000000000000000000e+00,4.747204786900628193e+00,0.000000000000000000e+00,-1.000000009974702175e+00,0.000000000000000000e+00,1.112066228032873694e-10,0.000000000000000000e+00 +4.351016556418544923e+01,2.980799999999999841e+02,0.000000000000000000e+00,4.745098284116644471e+00,0.000000000000000000e+00,-1.000000009974467918e+00,0.000000000000000000e+00,-7.733596297891091769e-11,0.000000000000000000e+00 +4.351227300209320958e+01,2.980900000000000318e+02,0.000000000000000000e+00,4.742990846187862708e+00,0.000000000000000000e+00,-1.000000009974630899e+00,0.000000000000000000e+00,4.728668323435659499e-11,0.000000000000000000e+00 +4.351438137639210879e+01,2.981000000000000227e+02,0.000000000000000000e+00,4.740882471867936765e+00,0.000000000000000000e+00,-1.000000009974531201e+00,0.000000000000000000e+00,2.789621544974092753e-11,0.000000000000000000e+00 +4.351649068833125256e+01,2.981100000000000136e+02,0.000000000000000000e+00,4.738773159907751165e+00,0.000000000000000000e+00,-1.000000009974472359e+00,0.000000000000000000e+00,-1.835069960627126392e-10,0.000000000000000000e+00 +4.351860093916254613e+01,2.981200000000000045e+02,0.000000000000000000e+00,4.736662909055410431e+00,0.000000000000000000e+00,-1.000000009974859605e+00,0.000000000000000000e+00,1.697525217107072330e-10,0.000000000000000000e+00 +4.352071213014066586e+01,2.981299999999999955e+02,0.000000000000000000e+00,4.734551718056230207e+00,0.000000000000000000e+00,-1.000000009974501225e+00,0.000000000000000000e+00,5.771536344873752138e-11,0.000000000000000000e+00 +4.352282426252309477e+01,2.981399999999999864e+02,0.000000000000000000e+00,4.732439585652731928e+00,0.000000000000000000e+00,-1.000000009974379322e+00,0.000000000000000000e+00,-1.454324746528930392e-10,0.000000000000000000e+00 +4.352493733757012251e+01,2.981500000000000341e+02,0.000000000000000000e+00,4.730326510584629496e+00,0.000000000000000000e+00,-1.000000009974686632e+00,0.000000000000000000e+00,-5.913433799207603977e-11,0.000000000000000000e+00 +4.352705135654484536e+01,2.981600000000000250e+02,0.000000000000000000e+00,4.728212491588822175e+00,0.000000000000000000e+00,-1.000000009974811643e+00,0.000000000000000000e+00,1.080320422862634578e-10,0.000000000000000000e+00 +4.352916632071318048e+01,2.981700000000000159e+02,0.000000000000000000e+00,4.726097527399387488e+00,0.000000000000000000e+00,-1.000000009974583159e+00,0.000000000000000000e+00,1.558365620588217901e-10,0.000000000000000000e+00 +4.353128223134389430e+01,2.981800000000000068e+02,0.000000000000000000e+00,4.723981616747571444e+00,0.000000000000000000e+00,-1.000000009974253423e+00,0.000000000000000000e+00,-3.042959366746856840e-10,0.000000000000000000e+00 +4.353339908970857408e+01,2.981899999999999977e+02,0.000000000000000000e+00,4.721864758361778769e+00,0.000000000000000000e+00,-1.000000009974897575e+00,0.000000000000000000e+00,1.294853774553138881e-10,0.000000000000000000e+00 +4.353551689708166350e+01,2.981999999999999886e+02,0.000000000000000000e+00,4.719746950967562249e+00,0.000000000000000000e+00,-1.000000009974623350e+00,0.000000000000000000e+00,9.274749971602364259e-11,0.000000000000000000e+00 +4.353763565474046970e+01,2.982099999999999795e+02,0.000000000000000000e+00,4.717628193287620064e+00,0.000000000000000000e+00,-1.000000009974426840e+00,0.000000000000000000e+00,-1.848879662958468810e-10,0.000000000000000000e+00 +4.353975536396516333e+01,2.982200000000000273e+02,0.000000000000000000e+00,4.715508484041780690e+00,0.000000000000000000e+00,-1.000000009974818749e+00,0.000000000000000000e+00,1.265887340996865909e-10,0.000000000000000000e+00 +4.354187602603879270e+01,2.982300000000000182e+02,0.000000000000000000e+00,4.713387821946994904e+00,0.000000000000000000e+00,-1.000000009974550297e+00,0.000000000000000000e+00,-1.115656771010330819e-10,0.000000000000000000e+00 +4.354399764224729807e+01,2.982400000000000091e+02,0.000000000000000000e+00,4.711266205717330458e+00,0.000000000000000000e+00,-1.000000009974786996e+00,0.000000000000000000e+00,1.432126292139518435e-10,0.000000000000000000e+00 +4.354612021387949738e+01,2.982500000000000000e+02,0.000000000000000000e+00,4.709143634063957862e+00,0.000000000000000000e+00,-1.000000009974483017e+00,0.000000000000000000e+00,-3.210114608926140251e-11,0.000000000000000000e+00 +4.354824374222712891e+01,2.982599999999999909e+02,0.000000000000000000e+00,4.707020105695145951e+00,0.000000000000000000e+00,-1.000000009974551185e+00,0.000000000000000000e+00,-1.705714861020996821e-10,0.000000000000000000e+00 +4.355036822858483703e+01,2.982699999999999818e+02,0.000000000000000000e+00,4.704895619316248556e+00,0.000000000000000000e+00,-1.000000009974913562e+00,0.000000000000000000e+00,2.002683552821793122e-10,0.000000000000000000e+00 +4.355249367425018647e+01,2.982800000000000296e+02,0.000000000000000000e+00,4.702770173629697403e+00,0.000000000000000000e+00,-1.000000009974487902e+00,0.000000000000000000e+00,-1.179973962140214375e-11,0.000000000000000000e+00 +4.355462008052367651e+01,2.982900000000000205e+02,0.000000000000000000e+00,4.700643767334995005e+00,0.000000000000000000e+00,-1.000000009974512993e+00,0.000000000000000000e+00,-1.191965455737201445e-10,0.000000000000000000e+00 +4.355674744870875514e+01,2.983000000000000114e+02,0.000000000000000000e+00,4.698516399128700449e+00,0.000000000000000000e+00,-1.000000009974766568e+00,0.000000000000000000e+00,-1.825740380762047642e-11,0.000000000000000000e+00 +4.355887578011180494e+01,2.983100000000000023e+02,0.000000000000000000e+00,4.696388067704423186e+00,0.000000000000000000e+00,-1.000000009974805426e+00,0.000000000000000000e+00,2.077272805071575357e-10,0.000000000000000000e+00 +4.356100507604217142e+01,2.983199999999999932e+02,0.000000000000000000e+00,4.694258771752814141e+00,0.000000000000000000e+00,-1.000000009974363113e+00,0.000000000000000000e+00,-2.989416305029706106e-10,0.000000000000000000e+00 +4.356313533781218439e+01,2.983299999999999841e+02,0.000000000000000000e+00,4.692128509961555949e+00,0.000000000000000000e+00,-1.000000009974999937e+00,0.000000000000000000e+00,1.579462521017864510e-10,0.000000000000000000e+00 +4.356526656673712949e+01,2.983400000000000318e+02,0.000000000000000000e+00,4.689997281015349628e+00,0.000000000000000000e+00,-1.000000009974663318e+00,0.000000000000000000e+00,-4.488384837392479476e-11,0.000000000000000000e+00 +4.356739876413529799e+01,2.983500000000000227e+02,0.000000000000000000e+00,4.687865083595912807e+00,0.000000000000000000e+00,-1.000000009974759019e+00,0.000000000000000000e+00,2.227558421917853135e-11,0.000000000000000000e+00 +4.356953193132797253e+01,2.983600000000000136e+02,0.000000000000000000e+00,4.685731916381962847e+00,0.000000000000000000e+00,-1.000000009974711501e+00,0.000000000000000000e+00,1.231882726714648971e-10,0.000000000000000000e+00 +4.357166606963943423e+01,2.983700000000000045e+02,0.000000000000000000e+00,4.683597778049211513e+00,0.000000000000000000e+00,-1.000000009974448600e+00,0.000000000000000000e+00,-1.630669225423356493e-10,0.000000000000000000e+00 +4.357380118039699823e+01,2.983799999999999955e+02,0.000000000000000000e+00,4.681462667270354316e+00,0.000000000000000000e+00,-1.000000009974796766e+00,0.000000000000000000e+00,1.152798323023690049e-10,0.000000000000000000e+00 +4.357593726493098529e+01,2.983899999999999864e+02,0.000000000000000000e+00,4.679326582715058969e+00,0.000000000000000000e+00,-1.000000009974550519e+00,0.000000000000000000e+00,-2.240125443438693516e-10,0.000000000000000000e+00 +4.357807432457477148e+01,2.984000000000000341e+02,0.000000000000000000e+00,4.677189523049960052e+00,0.000000000000000000e+00,-1.000000009975029247e+00,0.000000000000000000e+00,1.749947819171633829e-10,0.000000000000000000e+00 +4.358021236066475979e+01,2.984100000000000250e+02,0.000000000000000000e+00,4.675051486938643919e+00,0.000000000000000000e+00,-1.000000009974655102e+00,0.000000000000000000e+00,-4.422178031395467949e-11,0.000000000000000000e+00 +4.358235137454042274e+01,2.984200000000000159e+02,0.000000000000000000e+00,4.672912473041645143e+00,0.000000000000000000e+00,-1.000000009974749693e+00,0.000000000000000000e+00,1.016843103847267416e-10,0.000000000000000000e+00 +4.358449136754428821e+01,2.984300000000000068e+02,0.000000000000000000e+00,4.670772480016430528e+00,0.000000000000000000e+00,-1.000000009974532089e+00,0.000000000000000000e+00,-1.418779927467301213e-10,0.000000000000000000e+00 +4.358663234102196782e+01,2.984399999999999977e+02,0.000000000000000000e+00,4.668631506517393781e+00,0.000000000000000000e+00,-1.000000009974835846e+00,0.000000000000000000e+00,3.078833982063469483e-11,0.000000000000000000e+00 +4.358877429632215694e+01,2.984499999999999886e+02,0.000000000000000000e+00,4.666489551195842189e+00,0.000000000000000000e+00,-1.000000009974769899e+00,0.000000000000000000e+00,7.667649332987298366e-11,0.000000000000000000e+00 +4.359091723479663472e+01,2.984599999999999795e+02,0.000000000000000000e+00,4.664346612699990402e+00,0.000000000000000000e+00,-1.000000009974605586e+00,0.000000000000000000e+00,-1.487255149221141878e-10,0.000000000000000000e+00 +4.359306115780029245e+01,2.984700000000000273e+02,0.000000000000000000e+00,4.662202689674947997e+00,0.000000000000000000e+00,-1.000000009974924442e+00,0.000000000000000000e+00,1.843721395624849162e-10,0.000000000000000000e+00 +4.359520606669113363e+01,2.984800000000000182e+02,0.000000000000000000e+00,4.660057780762708823e+00,0.000000000000000000e+00,-1.000000009974528981e+00,0.000000000000000000e+00,-2.099488857691408697e-10,0.000000000000000000e+00 +4.359735196283029524e+01,2.984900000000000091e+02,0.000000000000000000e+00,4.657911884602144781e+00,0.000000000000000000e+00,-1.000000009974979509e+00,0.000000000000000000e+00,9.401461616106108270e-11,0.000000000000000000e+00 +4.359949884758203353e+01,2.985000000000000000e+02,0.000000000000000000e+00,4.655764999828989836e+00,0.000000000000000000e+00,-1.000000009974777671e+00,0.000000000000000000e+00,2.305346125024120727e-11,0.000000000000000000e+00 +4.360164672231375960e+01,2.985099999999999909e+02,0.000000000000000000e+00,4.653617125075836469e+00,0.000000000000000000e+00,-1.000000009974728155e+00,0.000000000000000000e+00,5.569544004692951369e-11,0.000000000000000000e+00 +4.360379558839603931e+01,2.985199999999999818e+02,0.000000000000000000e+00,4.651468258972120573e+00,0.000000000000000000e+00,-1.000000009974608473e+00,0.000000000000000000e+00,-9.006307526035349021e-11,0.000000000000000000e+00 +4.360594544720260046e+01,2.985300000000000296e+02,0.000000000000000000e+00,4.649318400144113461e+00,0.000000000000000000e+00,-1.000000009974802095e+00,0.000000000000000000e+00,-1.111847484515140542e-10,0.000000000000000000e+00 +4.360809630011034699e+01,2.985400000000000205e+02,0.000000000000000000e+00,4.647167547214910321e+00,0.000000000000000000e+00,-1.000000009975041237e+00,0.000000000000000000e+00,1.123715666943478346e-10,0.000000000000000000e+00 +4.361024814849937314e+01,2.985500000000000114e+02,0.000000000000000000e+00,4.645015698804421334e+00,0.000000000000000000e+00,-1.000000009974799431e+00,0.000000000000000000e+00,1.347009282479344414e-10,0.000000000000000000e+00 +4.361240099375295642e+01,2.985600000000000023e+02,0.000000000000000000e+00,4.642862853529361900e+00,0.000000000000000000e+00,-1.000000009974509441e+00,0.000000000000000000e+00,-9.649435985589167381e-11,0.000000000000000000e+00 +4.361455483725759308e+01,2.985699999999999932e+02,0.000000000000000000e+00,4.640709010003240209e+00,0.000000000000000000e+00,-1.000000009974717274e+00,0.000000000000000000e+00,-4.987350889699300882e-11,0.000000000000000000e+00 +4.361670968040299101e+01,2.985799999999999841e+02,0.000000000000000000e+00,4.638554166836346582e+00,0.000000000000000000e+00,-1.000000009974824744e+00,0.000000000000000000e+00,-1.423412911664774381e-10,0.000000000000000000e+00 +4.361886552458209110e+01,2.985900000000000318e+02,0.000000000000000000e+00,4.636398322635745473e+00,0.000000000000000000e+00,-1.000000009975131610e+00,0.000000000000000000e+00,1.746010348566745507e-10,0.000000000000000000e+00 +4.362102237119106007e+01,2.986000000000000227e+02,0.000000000000000000e+00,4.634241476005263038e+00,0.000000000000000000e+00,-1.000000009974755022e+00,0.000000000000000000e+00,-6.842905312484105057e-11,0.000000000000000000e+00 +4.362318022162931896e+01,2.986100000000000136e+02,0.000000000000000000e+00,4.632083625545479144e+00,0.000000000000000000e+00,-1.000000009974902682e+00,0.000000000000000000e+00,7.724254131390783970e-11,0.000000000000000000e+00 +4.362533907729955018e+01,2.986200000000000045e+02,0.000000000000000000e+00,4.629924769853712263e+00,0.000000000000000000e+00,-1.000000009974735926e+00,0.000000000000000000e+00,4.410333712162023829e-11,0.000000000000000000e+00 +4.362749893960770464e+01,2.986299999999999955e+02,0.000000000000000000e+00,4.627764907524013260e+00,0.000000000000000000e+00,-1.000000009974640669e+00,0.000000000000000000e+00,-1.538272635173909302e-10,0.000000000000000000e+00 +4.362965980996300885e+01,2.986399999999999864e+02,0.000000000000000000e+00,4.625604037147152070e+00,0.000000000000000000e+00,-1.000000009974973070e+00,0.000000000000000000e+00,7.754532678308167180e-11,0.000000000000000000e+00 +4.363182168977798625e+01,2.986500000000000341e+02,0.000000000000000000e+00,4.623442157310607037e+00,0.000000000000000000e+00,-1.000000009974805426e+00,0.000000000000000000e+00,1.077940906574456574e-11,0.000000000000000000e+00 +4.363398458046846429e+01,2.986600000000000250e+02,0.000000000000000000e+00,4.621279266598556923e+00,0.000000000000000000e+00,-1.000000009974782111e+00,0.000000000000000000e+00,-1.208781291962135221e-10,0.000000000000000000e+00 +4.363614848345356734e+01,2.986700000000000159e+02,0.000000000000000000e+00,4.619115363591866696e+00,0.000000000000000000e+00,-1.000000009975043680e+00,0.000000000000000000e+00,1.146676304241302337e-10,0.000000000000000000e+00 +4.363831340015575933e+01,2.986800000000000068e+02,0.000000000000000000e+00,4.616950446868077762e+00,0.000000000000000000e+00,-1.000000009974795434e+00,0.000000000000000000e+00,2.091344633383868678e-11,0.000000000000000000e+00 +4.364047933200083662e+01,2.986899999999999977e+02,0.000000000000000000e+00,4.614784515001399079e+00,0.000000000000000000e+00,-1.000000009974750137e+00,0.000000000000000000e+00,-1.393575686048787334e-10,0.000000000000000000e+00 +4.364264628041792804e+01,2.986999999999999886e+02,0.000000000000000000e+00,4.612617566562692950e+00,0.000000000000000000e+00,-1.000000009975052118e+00,0.000000000000000000e+00,9.381734702377079809e-11,0.000000000000000000e+00 +4.364481424683953037e+01,2.987099999999999795e+02,0.000000000000000000e+00,4.610449600119465252e+00,0.000000000000000000e+00,-1.000000009974848725e+00,0.000000000000000000e+00,5.558829247720152447e-11,0.000000000000000000e+00 +4.364698323270150127e+01,2.987200000000000273e+02,0.000000000000000000e+00,4.608280614235856554e+00,0.000000000000000000e+00,-1.000000009974728155e+00,0.000000000000000000e+00,-1.509284676348229823e-10,0.000000000000000000e+00 +4.364915323944308767e+01,2.987300000000000182e+02,0.000000000000000000e+00,4.606110607472627905e+00,0.000000000000000000e+00,-1.000000009975055670e+00,0.000000000000000000e+00,1.513687774914338195e-10,0.000000000000000000e+00 +4.365132426850691161e+01,2.987400000000000091e+02,0.000000000000000000e+00,4.603939578387150178e+00,0.000000000000000000e+00,-1.000000009974727044e+00,0.000000000000000000e+00,-4.682042147100140062e-11,0.000000000000000000e+00 +4.365349632133899860e+01,2.987500000000000000e+02,0.000000000000000000e+00,4.601767525533396075e+00,0.000000000000000000e+00,-1.000000009974828741e+00,0.000000000000000000e+00,-4.812666941691977527e-11,0.000000000000000000e+00 +4.365566939938879187e+01,2.987599999999999909e+02,0.000000000000000000e+00,4.599594447461924140e+00,0.000000000000000000e+00,-1.000000009974933324e+00,0.000000000000000000e+00,-8.732244377762531759e-11,0.000000000000000000e+00 +4.365784350410915948e+01,2.987699999999999818e+02,0.000000000000000000e+00,4.597420342719870767e+00,0.000000000000000000e+00,-1.000000009975123172e+00,0.000000000000000000e+00,1.750727538000113763e-10,0.000000000000000000e+00 +4.366001863695639429e+01,2.987800000000000296e+02,0.000000000000000000e+00,4.595245209850937762e+00,0.000000000000000000e+00,-1.000000009974742365e+00,0.000000000000000000e+00,-3.754885818330378159e-11,0.000000000000000000e+00 +4.366219479939024239e+01,2.987900000000000205e+02,0.000000000000000000e+00,4.593069047395382576e+00,0.000000000000000000e+00,-1.000000009974824078e+00,0.000000000000000000e+00,9.994688779818515078e-12,0.000000000000000000e+00 +4.366437199287390314e+01,2.988000000000000114e+02,0.000000000000000000e+00,4.590891853890003205e+00,0.000000000000000000e+00,-1.000000009974802317e+00,0.000000000000000000e+00,-6.218234884498356563e-11,0.000000000000000000e+00 +4.366655021887405042e+01,2.988100000000000023e+02,0.000000000000000000e+00,4.588713627868130196e+00,0.000000000000000000e+00,-1.000000009974937765e+00,0.000000000000000000e+00,-6.184717565007501628e-11,0.000000000000000000e+00 +4.366872947886083267e+01,2.988199999999999932e+02,0.000000000000000000e+00,4.586534367859613326e+00,0.000000000000000000e+00,-1.000000009975072546e+00,0.000000000000000000e+00,2.708984463085999975e-11,0.000000000000000000e+00 +4.367090977430788712e+01,2.988299999999999841e+02,0.000000000000000000e+00,4.584354072390810941e+00,0.000000000000000000e+00,-1.000000009975013482e+00,0.000000000000000000e+00,4.305848505795213374e-11,0.000000000000000000e+00 +4.367309110669236105e+01,2.988400000000000318e+02,0.000000000000000000e+00,4.582172739984578413e+00,0.000000000000000000e+00,-1.000000009974919557e+00,0.000000000000000000e+00,2.350301959578166435e-11,0.000000000000000000e+00 +4.367527347749491184e+01,2.988500000000000227e+02,0.000000000000000000e+00,4.579990369160255703e+00,0.000000000000000000e+00,-1.000000009974868265e+00,0.000000000000000000e+00,1.535612849641762320e-11,0.000000000000000000e+00 +4.367745688819973537e+01,2.988600000000000136e+02,0.000000000000000000e+00,4.577806958433655815e+00,0.000000000000000000e+00,-1.000000009974834736e+00,0.000000000000000000e+00,-1.094746092496611800e-10,0.000000000000000000e+00 +4.367964134029455181e+01,2.988700000000000045e+02,0.000000000000000000e+00,4.575622506317053251e+00,0.000000000000000000e+00,-1.000000009975073878e+00,0.000000000000000000e+00,8.920412321136989640e-11,0.000000000000000000e+00 +4.368182683527063404e+01,2.988799999999999955e+02,0.000000000000000000e+00,4.573437011319171575e+00,0.000000000000000000e+00,-1.000000009974878923e+00,0.000000000000000000e+00,-5.382187175937771203e-11,0.000000000000000000e+00 +4.368401337462282186e+01,2.988899999999999864e+02,0.000000000000000000e+00,4.571250471945173643e+00,0.000000000000000000e+00,-1.000000009974996606e+00,0.000000000000000000e+00,-7.643111933074909305e-11,0.000000000000000000e+00 +4.368620095984952911e+01,2.989000000000000341e+02,0.000000000000000000e+00,4.569062886696646508e+00,0.000000000000000000e+00,-1.000000009975163806e+00,0.000000000000000000e+00,1.207297558629474114e-10,0.000000000000000000e+00 +4.368838959245275078e+01,2.989100000000000250e+02,0.000000000000000000e+00,4.566874254071591643e+00,0.000000000000000000e+00,-1.000000009974899573e+00,0.000000000000000000e+00,-9.237993582232251922e-11,0.000000000000000000e+00 +4.369057927393808427e+01,2.989200000000000159e+02,0.000000000000000000e+00,4.564684572564413401e+00,0.000000000000000000e+00,-1.000000009975101856e+00,0.000000000000000000e+00,1.470680758240075698e-10,0.000000000000000000e+00 +4.369277000581474368e+01,2.989300000000000068e+02,0.000000000000000000e+00,4.562493840665903910e+00,0.000000000000000000e+00,-1.000000009974779669e+00,0.000000000000000000e+00,-1.389941839267909628e-10,0.000000000000000000e+00 +4.369496178959555266e+01,2.989399999999999977e+02,0.000000000000000000e+00,4.560302056863235087e+00,0.000000000000000000e+00,-1.000000009975084314e+00,0.000000000000000000e+00,1.179667895866580313e-10,0.000000000000000000e+00 +4.369715462679697282e+01,2.989499999999999886e+02,0.000000000000000000e+00,4.558109219639941756e+00,0.000000000000000000e+00,-1.000000009974825632e+00,0.000000000000000000e+00,-3.643572819168337270e-11,0.000000000000000000e+00 +4.369934851893911798e+01,2.989599999999999795e+02,0.000000000000000000e+00,4.555915327475914545e+00,0.000000000000000000e+00,-1.000000009974905568e+00,0.000000000000000000e+00,-6.727249186092539477e-11,0.000000000000000000e+00 +4.370154346754575414e+01,2.989700000000000273e+02,0.000000000000000000e+00,4.553720378847383010e+00,0.000000000000000000e+00,-1.000000009975053228e+00,0.000000000000000000e+00,1.688585500908585610e-11,0.000000000000000000e+00 +4.370373947414432791e+01,2.989800000000000182e+02,0.000000000000000000e+00,4.551524372226905868e+00,0.000000000000000000e+00,-1.000000009975016146e+00,0.000000000000000000e+00,3.517032180011454973e-11,0.000000000000000000e+00 +4.370593654026595942e+01,2.989900000000000091e+02,0.000000000000000000e+00,4.549327306083358557e+00,0.000000000000000000e+00,-1.000000009974938875e+00,0.000000000000000000e+00,-1.820296759005793115e-10,0.000000000000000000e+00 +4.370813466744547071e+01,2.990000000000000000e+02,0.000000000000000000e+00,4.547129178881919920e+00,0.000000000000000000e+00,-1.000000009975338999e+00,0.000000000000000000e+00,1.263091543086965320e-10,0.000000000000000000e+00 +4.371033385722139286e+01,2.990099999999999909e+02,0.000000000000000000e+00,4.544929989084058874e+00,0.000000000000000000e+00,-1.000000009975061221e+00,0.000000000000000000e+00,7.770664315553344245e-11,0.000000000000000000e+00 +4.371253411113598020e+01,2.990199999999999818e+02,0.000000000000000000e+00,4.542729735147525538e+00,0.000000000000000000e+00,-1.000000009974890247e+00,0.000000000000000000e+00,-9.461499343040589639e-11,0.000000000000000000e+00 +4.371473543073521029e+01,2.990300000000000296e+02,0.000000000000000000e+00,4.540528415526334349e+00,0.000000000000000000e+00,-1.000000009975098525e+00,0.000000000000000000e+00,3.498453438472188875e-11,0.000000000000000000e+00 +4.371693781756882657e+01,2.990400000000000205e+02,0.000000000000000000e+00,4.538326028670752521e+00,0.000000000000000000e+00,-1.000000009975021475e+00,0.000000000000000000e+00,-1.249561404470907515e-11,0.000000000000000000e+00 +4.371914127319030996e+01,2.990500000000000114e+02,0.000000000000000000e+00,4.536122573027289384e+00,0.000000000000000000e+00,-1.000000009975049009e+00,0.000000000000000000e+00,2.900798048503759765e-11,0.000000000000000000e+00 +4.372134579915692854e+01,2.990600000000000023e+02,0.000000000000000000e+00,4.533918047038681287e+00,0.000000000000000000e+00,-1.000000009974985060e+00,0.000000000000000000e+00,7.016922329374699526e-11,0.000000000000000000e+00 +4.372355139702973048e+01,2.990699999999999932e+02,0.000000000000000000e+00,4.531712449143880050e+00,0.000000000000000000e+00,-1.000000009974830295e+00,0.000000000000000000e+00,-1.481188666194686390e-10,0.000000000000000000e+00 +4.372575806837355827e+01,2.990799999999999841e+02,0.000000000000000000e+00,4.529505777778039644e+00,0.000000000000000000e+00,-1.000000009975157145e+00,0.000000000000000000e+00,3.781628726705716766e-11,0.000000000000000000e+00 +4.372796581475707001e+01,2.990900000000000318e+02,0.000000000000000000e+00,4.527298031372501974e+00,0.000000000000000000e+00,-1.000000009975073656e+00,0.000000000000000000e+00,2.754418161545902942e-11,0.000000000000000000e+00 +4.373017463775275360e+01,2.991000000000000227e+02,0.000000000000000000e+00,4.525089208354787118e+00,0.000000000000000000e+00,-1.000000009975012816e+00,0.000000000000000000e+00,-3.838227685885106692e-11,0.000000000000000000e+00 +4.373238453893691968e+01,2.991100000000000136e+02,0.000000000000000000e+00,4.522879307148577332e+00,0.000000000000000000e+00,-1.000000009975097637e+00,0.000000000000000000e+00,-8.034247591035240935e-12,0.000000000000000000e+00 +4.373459551988973715e+01,2.991200000000000045e+02,0.000000000000000000e+00,4.520668326173704621e+00,0.000000000000000000e+00,-1.000000009975115400e+00,0.000000000000000000e+00,-8.130699101106977327e-11,0.000000000000000000e+00 +4.373680758219524023e+01,2.991299999999999955e+02,0.000000000000000000e+00,4.518456263846138299e+00,0.000000000000000000e+00,-1.000000009975295256e+00,0.000000000000000000e+00,9.872460546011206683e-11,0.000000000000000000e+00 +4.373902072744132852e+01,2.991399999999999864e+02,0.000000000000000000e+00,4.516243118577970783e+00,0.000000000000000000e+00,-1.000000009975076765e+00,0.000000000000000000e+00,-6.518248223565238873e-12,0.000000000000000000e+00 +4.374123495721980959e+01,2.991500000000000341e+02,0.000000000000000000e+00,4.514028888777406046e+00,0.000000000000000000e+00,-1.000000009975091197e+00,0.000000000000000000e+00,-1.593682060353723946e-11,0.000000000000000000e+00 +4.374345027312637058e+01,2.991600000000000250e+02,0.000000000000000000e+00,4.511813572848743625e+00,0.000000000000000000e+00,-1.000000009975126503e+00,0.000000000000000000e+00,9.968147429672002188e-11,0.000000000000000000e+00 +4.374566667676063503e+01,2.991700000000000159e+02,0.000000000000000000e+00,4.509597169192367083e+00,0.000000000000000000e+00,-1.000000009974905568e+00,0.000000000000000000e+00,-1.594120101112539108e-10,0.000000000000000000e+00 +4.374788416972614868e+01,2.991800000000000068e+02,0.000000000000000000e+00,4.507379676204730679e+00,0.000000000000000000e+00,-1.000000009975259063e+00,0.000000000000000000e+00,1.636372320000741569e-10,0.000000000000000000e+00 +4.375010275363040790e+01,2.991899999999999977e+02,0.000000000000000000e+00,4.505161092278343382e+00,0.000000000000000000e+00,-1.000000009974896020e+00,0.000000000000000000e+00,-1.277442754874390354e-10,0.000000000000000000e+00 +4.375232243008485256e+01,2.991999999999999886e+02,0.000000000000000000e+00,4.502941415801759995e+00,0.000000000000000000e+00,-1.000000009975179571e+00,0.000000000000000000e+00,-5.319222469616439015e-11,0.000000000000000000e+00 +4.375454320070490155e+01,2.992099999999999795e+02,0.000000000000000000e+00,4.500720645159561606e+00,0.000000000000000000e+00,-1.000000009975297699e+00,0.000000000000000000e+00,1.174248866600554484e-10,0.000000000000000000e+00 +4.375676506710995284e+01,2.992200000000000273e+02,0.000000000000000000e+00,4.498498778732346715e+00,0.000000000000000000e+00,-1.000000009975036797e+00,0.000000000000000000e+00,-5.254042440257431502e-11,0.000000000000000000e+00 +4.375898803092341183e+01,2.992300000000000182e+02,0.000000000000000000e+00,4.496275814896716128e+00,0.000000000000000000e+00,-1.000000009975153592e+00,0.000000000000000000e+00,9.234957529312608397e-11,0.000000000000000000e+00 +4.376121209377268428e+01,2.992400000000000091e+02,0.000000000000000000e+00,4.494051752025256974e+00,0.000000000000000000e+00,-1.000000009974948201e+00,0.000000000000000000e+00,-2.179369801607746889e-10,0.000000000000000000e+00 +4.376343725728921186e+01,2.992500000000000000e+02,0.000000000000000000e+00,4.491826588486532046e+00,0.000000000000000000e+00,-1.000000009975433146e+00,0.000000000000000000e+00,2.333882912943448639e-10,0.000000000000000000e+00 +4.376566352310847208e+01,2.992599999999999909e+02,0.000000000000000000e+00,4.489600322645062036e+00,0.000000000000000000e+00,-1.000000009974913562e+00,0.000000000000000000e+00,-1.933969568031250626e-10,0.000000000000000000e+00 +4.376789089286999967e+01,2.992699999999999818e+02,0.000000000000000000e+00,4.487372952861317543e+00,0.000000000000000000e+00,-1.000000009975344328e+00,0.000000000000000000e+00,1.005364527059586668e-10,0.000000000000000000e+00 +4.377011936821739368e+01,2.992800000000000296e+02,0.000000000000000000e+00,4.485144477491696868e+00,0.000000000000000000e+00,-1.000000009975120285e+00,0.000000000000000000e+00,3.983608534145318731e-11,0.000000000000000000e+00 +4.377234895079833166e+01,2.992900000000000205e+02,0.000000000000000000e+00,4.482914894888519797e+00,0.000000000000000000e+00,-1.000000009975031467e+00,0.000000000000000000e+00,-4.877494627065492501e-12,0.000000000000000000e+00 +4.377457964226459097e+01,2.993000000000000114e+02,0.000000000000000000e+00,4.480684203400008059e+00,0.000000000000000000e+00,-1.000000009975042348e+00,0.000000000000000000e+00,-1.875408655795721946e-10,0.000000000000000000e+00 +4.377681144427206306e+01,2.993100000000000023e+02,0.000000000000000000e+00,4.478452401370272895e+00,0.000000000000000000e+00,-1.000000009975460902e+00,0.000000000000000000e+00,2.424386681308004921e-10,0.000000000000000000e+00 +4.377904435848076048e+01,2.993199999999999932e+02,0.000000000000000000e+00,4.476219487139299957e+00,0.000000000000000000e+00,-1.000000009974919557e+00,0.000000000000000000e+00,-8.975101099843537075e-11,0.000000000000000000e+00 +4.378127838655483828e+01,2.993299999999999841e+02,0.000000000000000000e+00,4.473985459042938650e+00,0.000000000000000000e+00,-1.000000009975120063e+00,0.000000000000000000e+00,-5.126069561858585026e-11,0.000000000000000000e+00 +4.378351353016260106e+01,2.993400000000000318e+02,0.000000000000000000e+00,4.471750315412880816e+00,0.000000000000000000e+00,-1.000000009975234638e+00,0.000000000000000000e+00,-9.978926722697834276e-11,0.000000000000000000e+00 +4.378574979097652431e+01,2.993500000000000227e+02,0.000000000000000000e+00,4.469514054576651851e+00,0.000000000000000000e+00,-1.000000009975457793e+00,0.000000000000000000e+00,2.095022859463238769e-10,0.000000000000000000e+00 +4.378798717067326152e+01,2.993600000000000136e+02,0.000000000000000000e+00,4.467276674857593832e+00,0.000000000000000000e+00,-1.000000009974989057e+00,0.000000000000000000e+00,-8.510799591805041272e-11,0.000000000000000000e+00 +4.379022567093367257e+01,2.993700000000000045e+02,0.000000000000000000e+00,4.465038174574853080e+00,0.000000000000000000e+00,-1.000000009975179571e+00,0.000000000000000000e+00,1.953132145773852793e-11,0.000000000000000000e+00 +4.379246529344282379e+01,2.993799999999999955e+02,0.000000000000000000e+00,4.462798552043360623e+00,0.000000000000000000e+00,-1.000000009975135828e+00,0.000000000000000000e+00,-5.648359945686277206e-11,0.000000000000000000e+00 +4.379470603989000921e+01,2.993899999999999864e+02,0.000000000000000000e+00,4.460557805573822421e+00,0.000000000000000000e+00,-1.000000009975262394e+00,0.000000000000000000e+00,6.834055290218937997e-12,0.000000000000000000e+00 +4.379694791196876480e+01,2.994000000000000341e+02,0.000000000000000000e+00,4.458315933472701609e+00,0.000000000000000000e+00,-1.000000009975247073e+00,0.000000000000000000e+00,1.108738400088388231e-11,0.000000000000000000e+00 +4.379919091137688980e+01,2.994100000000000250e+02,0.000000000000000000e+00,4.456072934042205169e+00,0.000000000000000000e+00,-1.000000009975222204e+00,0.000000000000000000e+00,-5.016496057573589617e-11,0.000000000000000000e+00 +4.380143503981643960e+01,2.994200000000000159e+02,0.000000000000000000e+00,4.453828805580267947e+00,0.000000000000000000e+00,-1.000000009975334780e+00,0.000000000000000000e+00,4.944743287693973521e-12,0.000000000000000000e+00 +4.380368029899377547e+01,2.994300000000000068e+02,0.000000000000000000e+00,4.451583546380537548e+00,0.000000000000000000e+00,-1.000000009975323678e+00,0.000000000000000000e+00,1.961085017936122945e-10,0.000000000000000000e+00 +4.380592669061954325e+01,2.994399999999999977e+02,0.000000000000000000e+00,4.449337154732360133e+00,0.000000000000000000e+00,-1.000000009974883142e+00,0.000000000000000000e+00,-3.225661029438144127e-10,0.000000000000000000e+00 +4.380817421640871601e+01,2.994499999999999886e+02,0.000000000000000000e+00,4.447089628920765314e+00,0.000000000000000000e+00,-1.000000009975608117e+00,0.000000000000000000e+00,2.545651925557942305e-10,0.000000000000000000e+00 +4.381042287808060109e+01,2.994599999999999795e+02,0.000000000000000000e+00,4.444840967226446615e+00,0.000000000000000000e+00,-1.000000009975035686e+00,0.000000000000000000e+00,-1.206056512870361067e-10,0.000000000000000000e+00 +4.381267267735884730e+01,2.994700000000000273e+02,0.000000000000000000e+00,4.442591167925755258e+00,0.000000000000000000e+00,-1.000000009975307025e+00,0.000000000000000000e+00,3.215838086365155237e-11,0.000000000000000000e+00 +4.381492361597147323e+01,2.994800000000000182e+02,0.000000000000000000e+00,4.440340229290674401e+00,0.000000000000000000e+00,-1.000000009975234638e+00,0.000000000000000000e+00,-7.611561729819805611e-11,0.000000000000000000e+00 +4.381717569565087445e+01,2.994900000000000091e+02,0.000000000000000000e+00,4.438088149588811149e+00,0.000000000000000000e+00,-1.000000009975406057e+00,0.000000000000000000e+00,1.829987204834720487e-10,0.000000000000000000e+00 +4.381942891813383056e+01,2.995000000000000000e+02,0.000000000000000000e+00,4.435834927083377011e+00,0.000000000000000000e+00,-1.000000009974993720e+00,0.000000000000000000e+00,-1.238086189868382586e-10,0.000000000000000000e+00 +4.382168328516154787e+01,2.995099999999999909e+02,0.000000000000000000e+00,4.433580560033175466e+00,0.000000000000000000e+00,-1.000000009975272830e+00,0.000000000000000000e+00,8.466292737160442592e-12,0.000000000000000000e+00 +4.382393879847964513e+01,2.995199999999999818e+02,0.000000000000000000e+00,4.431325046692581537e+00,0.000000000000000000e+00,-1.000000009975253734e+00,0.000000000000000000e+00,-1.489703054400896757e-10,0.000000000000000000e+00 +4.382619545983818199e+01,2.995300000000000296e+02,0.000000000000000000e+00,4.429068385311531131e+00,0.000000000000000000e+00,-1.000000009975589910e+00,0.000000000000000000e+00,2.603194108257072433e-10,0.000000000000000000e+00 +4.382845327099168742e+01,2.995400000000000205e+02,0.000000000000000000e+00,4.426810574135501497e+00,0.000000000000000000e+00,-1.000000009975002158e+00,0.000000000000000000e+00,-1.592378036119226933e-10,0.000000000000000000e+00 +4.383071223369915259e+01,2.995500000000000114e+02,0.000000000000000000e+00,4.424551611405499685e+00,0.000000000000000000e+00,-1.000000009975361870e+00,0.000000000000000000e+00,-6.877134701674613102e-13,0.000000000000000000e+00 +4.383297234972406642e+01,2.995600000000000023e+02,0.000000000000000000e+00,4.422291495358039448e+00,0.000000000000000000e+00,-1.000000009975363424e+00,0.000000000000000000e+00,6.667413122381191364e-11,0.000000000000000000e+00 +4.383523362083441555e+01,2.995699999999999932e+02,0.000000000000000000e+00,4.420030224225132365e+00,0.000000000000000000e+00,-1.000000009975212656e+00,0.000000000000000000e+00,-8.823180345403955682e-11,0.000000000000000000e+00 +4.383749604880271278e+01,2.995799999999999841e+02,0.000000000000000000e+00,4.417767796234268296e+00,0.000000000000000000e+00,-1.000000009975412274e+00,0.000000000000000000e+00,1.119254257165480720e-10,0.000000000000000000e+00 +4.383975963540600418e+01,2.995900000000000318e+02,0.000000000000000000e+00,4.415504209608398511e+00,0.000000000000000000e+00,-1.000000009975158921e+00,0.000000000000000000e+00,-1.288296698526244738e-10,0.000000000000000000e+00 +4.384202438242589039e+01,2.996000000000000227e+02,0.000000000000000000e+00,4.413239462565922366e+00,0.000000000000000000e+00,-1.000000009975450688e+00,0.000000000000000000e+00,1.418947346686451084e-10,0.000000000000000000e+00 +4.384429029164854086e+01,2.996100000000000136e+02,0.000000000000000000e+00,4.410973553320666873e+00,0.000000000000000000e+00,-1.000000009975129167e+00,0.000000000000000000e+00,-1.868757935005367854e-10,0.000000000000000000e+00 +4.384655736486471511e+01,2.996200000000000045e+02,0.000000000000000000e+00,4.408706480081875156e+00,0.000000000000000000e+00,-1.000000009975552828e+00,0.000000000000000000e+00,2.105677329979041889e-10,0.000000000000000000e+00 +4.384882560386977701e+01,2.996299999999999955e+02,0.000000000000000000e+00,4.406438241054184246e+00,0.000000000000000000e+00,-1.000000009975075210e+00,0.000000000000000000e+00,-9.011301971308734902e-11,0.000000000000000000e+00 +4.385109501046370895e+01,2.996399999999999864e+02,0.000000000000000000e+00,4.404168834437615310e+00,0.000000000000000000e+00,-1.000000009975279713e+00,0.000000000000000000e+00,-8.028739035988512079e-11,0.000000000000000000e+00 +4.385336558645112603e+01,2.996500000000000341e+02,0.000000000000000000e+00,4.401898258427549671e+00,0.000000000000000000e+00,-1.000000009975462012e+00,0.000000000000000000e+00,5.434442744002770909e-11,0.000000000000000000e+00 +4.385563733364129746e+01,2.996600000000000250e+02,0.000000000000000000e+00,4.399626511214717262e+00,0.000000000000000000e+00,-1.000000009975338555e+00,0.000000000000000000e+00,-2.706049925486013243e-11,0.000000000000000000e+00 +4.385791025384816066e+01,2.996700000000000159e+02,0.000000000000000000e+00,4.397353590985178862e+00,0.000000000000000000e+00,-1.000000009975400062e+00,0.000000000000000000e+00,3.729881007955211902e-11,0.000000000000000000e+00 +4.386018434889034978e+01,2.996800000000000068e+02,0.000000000000000000e+00,4.395079495920307444e+00,0.000000000000000000e+00,-1.000000009975315240e+00,0.000000000000000000e+00,-6.265301691634389152e-11,0.000000000000000000e+00 +4.386245962059118852e+01,2.996899999999999977e+02,0.000000000000000000e+00,4.392804224196773077e+00,0.000000000000000000e+00,-1.000000009975457793e+00,0.000000000000000000e+00,6.525415820996285781e-11,0.000000000000000000e+00 +4.386473607077872572e+01,2.996999999999999886e+02,0.000000000000000000e+00,4.390527773986524274e+00,0.000000000000000000e+00,-1.000000009975309245e+00,0.000000000000000000e+00,-2.973423665211005213e-11,0.000000000000000000e+00 +4.386701370128575661e+01,2.997099999999999795e+02,0.000000000000000000e+00,4.388250143456772889e+00,0.000000000000000000e+00,-1.000000009975376969e+00,0.000000000000000000e+00,7.483294229115425707e-11,0.000000000000000000e+00 +4.386929251394982288e+01,2.997200000000000273e+02,0.000000000000000000e+00,4.385971330769974585e+00,0.000000000000000000e+00,-1.000000009975206439e+00,0.000000000000000000e+00,-2.100661902309138681e-10,0.000000000000000000e+00 +4.387157251061324104e+01,2.997300000000000182e+02,0.000000000000000000e+00,4.383691334083813729e+00,0.000000000000000000e+00,-1.000000009975685389e+00,0.000000000000000000e+00,2.511307526806003411e-10,0.000000000000000000e+00 +4.387385369312311667e+01,2.997400000000000091e+02,0.000000000000000000e+00,4.381410151551182963e+00,0.000000000000000000e+00,-1.000000009975112514e+00,0.000000000000000000e+00,-1.228732897964134132e-10,0.000000000000000000e+00 +4.387613606333135863e+01,2.997500000000000000e+02,0.000000000000000000e+00,4.379127781320171664e+00,0.000000000000000000e+00,-1.000000009975392956e+00,0.000000000000000000e+00,4.570099981161491951e-12,0.000000000000000000e+00 +4.387841962309470745e+01,2.997599999999999909e+02,0.000000000000000000e+00,4.376844221534040180e+00,0.000000000000000000e+00,-1.000000009975382520e+00,0.000000000000000000e+00,-6.142121362650051031e-11,0.000000000000000000e+00 +4.388070437427474957e+01,2.997699999999999818e+02,0.000000000000000000e+00,4.374559470331209177e+00,0.000000000000000000e+00,-1.000000009975522852e+00,0.000000000000000000e+00,2.282666223880256680e-11,0.000000000000000000e+00 +4.388299031873791733e+01,2.997800000000000296e+02,0.000000000000000000e+00,4.372273525845238318e+00,0.000000000000000000e+00,-1.000000009975470672e+00,0.000000000000000000e+00,1.063069523699175132e-10,0.000000000000000000e+00 +4.388527745835553162e+01,2.997900000000000205e+02,0.000000000000000000e+00,4.369986386204810280e+00,0.000000000000000000e+00,-1.000000009975227533e+00,0.000000000000000000e+00,-1.151783966074650806e-10,0.000000000000000000e+00 +4.388756579500380184e+01,2.998000000000000114e+02,0.000000000000000000e+00,4.367698049533712101e+00,0.000000000000000000e+00,-1.000000009975491100e+00,0.000000000000000000e+00,8.902982372376183596e-11,0.000000000000000000e+00 +4.388985533056386146e+01,2.998100000000000023e+02,0.000000000000000000e+00,4.365408513950815639e+00,0.000000000000000000e+00,-1.000000009975287263e+00,0.000000000000000000e+00,-6.184232308249759812e-11,0.000000000000000000e+00 +4.389214606692176091e+01,2.998199999999999932e+02,0.000000000000000000e+00,4.363117777570063360e+00,0.000000000000000000e+00,-1.000000009975428927e+00,0.000000000000000000e+00,2.480145313694528826e-11,0.000000000000000000e+00 +4.389443800596851730e+01,2.998299999999999841e+02,0.000000000000000000e+00,4.360825838500446139e+00,0.000000000000000000e+00,-1.000000009975372084e+00,0.000000000000000000e+00,-5.848519016758467116e-11,0.000000000000000000e+00 +4.389673114960010025e+01,2.998400000000000318e+02,0.000000000000000000e+00,4.358532694845988154e+00,0.000000000000000000e+00,-1.000000009975506199e+00,0.000000000000000000e+00,-2.603351523052956224e-11,0.000000000000000000e+00 +4.389902549971747447e+01,2.998500000000000227e+02,0.000000000000000000e+00,4.356238344705726462e+00,0.000000000000000000e+00,-1.000000009975565929e+00,0.000000000000000000e+00,8.608785077664152801e-11,0.000000000000000000e+00 +4.390132105822660691e+01,2.998600000000000136e+02,0.000000000000000000e+00,4.353942786173694124e+00,0.000000000000000000e+00,-1.000000009975368309e+00,0.000000000000000000e+00,-7.821165302101014035e-11,0.000000000000000000e+00 +4.390361782703848803e+01,2.998700000000000045e+02,0.000000000000000000e+00,4.351646017338901551e+00,0.000000000000000000e+00,-1.000000009975547943e+00,0.000000000000000000e+00,1.524757523654504399e-10,0.000000000000000000e+00 +4.390591580806915317e+01,2.998799999999999955e+02,0.000000000000000000e+00,4.349348036285316077e+00,0.000000000000000000e+00,-1.000000009975197557e+00,0.000000000000000000e+00,-2.165209855265288545e-10,0.000000000000000000e+00 +4.390821500323968962e+01,2.998899999999999864e+02,0.000000000000000000e+00,4.347048841091846860e+00,0.000000000000000000e+00,-1.000000009975695381e+00,0.000000000000000000e+00,1.904416038972337034e-10,0.000000000000000000e+00 +4.391051541447626505e+01,2.999000000000000341e+02,0.000000000000000000e+00,4.344748429832320902e+00,0.000000000000000000e+00,-1.000000009975257287e+00,0.000000000000000000e+00,-8.971969921987140734e-11,0.000000000000000000e+00 +4.391281704371015593e+01,2.999100000000000250e+02,0.000000000000000000e+00,4.342446800575471499e+00,0.000000000000000000e+00,-1.000000009975463788e+00,0.000000000000000000e+00,1.523462677101959865e-11,0.000000000000000000e+00 +4.391511989287774043e+01,2.999200000000000159e+02,0.000000000000000000e+00,4.340143951384911603e+00,0.000000000000000000e+00,-1.000000009975428705e+00,0.000000000000000000e+00,-8.287867721426031064e-11,0.000000000000000000e+00 +4.391742396392054815e+01,2.999300000000000068e+02,0.000000000000000000e+00,4.337839880319120489e+00,0.000000000000000000e+00,-1.000000009975619664e+00,0.000000000000000000e+00,5.018240440182756512e-11,0.000000000000000000e+00 +4.391972925878525302e+01,2.999399999999999977e+02,0.000000000000000000e+00,4.335534585431421561e+00,0.000000000000000000e+00,-1.000000009975503978e+00,0.000000000000000000e+00,2.907299833766006799e-11,0.000000000000000000e+00 +4.392203577942370174e+01,2.999499999999999886e+02,0.000000000000000000e+00,4.333228064769965471e+00,0.000000000000000000e+00,-1.000000009975436921e+00,0.000000000000000000e+00,-1.173847294704124144e-11,0.000000000000000000e+00 +4.392434352779293505e+01,2.999599999999999795e+02,0.000000000000000000e+00,4.330920316377708801e+00,0.000000000000000000e+00,-1.000000009975464010e+00,0.000000000000000000e+00,-8.779932889286464333e-11,0.000000000000000000e+00 +4.392665250585521619e+01,2.999700000000000273e+02,0.000000000000000000e+00,4.328611338292395416e+00,0.000000000000000000e+00,-1.000000009975666737e+00,0.000000000000000000e+00,1.354253015429570755e-10,0.000000000000000000e+00 +4.392896271557803090e+01,2.999800000000000182e+02,0.000000000000000000e+00,4.326301128546536923e+00,0.000000000000000000e+00,-1.000000009975353876e+00,0.000000000000000000e+00,1.162364508098547653e-11,0.000000000000000000e+00 +4.393127415893411580e+01,2.999900000000000091e+02,0.000000000000000000e+00,4.323989685167394903e+00,0.000000000000000000e+00,-1.000000009975327009e+00,0.000000000000000000e+00,-8.842692134168151651e-11,4.323989685167394792e-01 +4.393358683790147978e+01,3.000000000000000000e+02,0.000000000000000000e+00,4.321677006176957825e+00,0.000000000000000000e+00,-1.000000009975531512e+00,1.000000000000000021e-03,-1.100667007777327466e-10,4.321677006176958269e-01 +4.393590075446343235e+01,3.000099999999999909e+02,0.000000000000000000e+00,4.319363089591923277e+00,3.649636253041848797e-06,-1.000000009975786197e+00,2.000000000000000042e-03,1.844332513664175136e-10,4.319363089591923277e-01 +4.393821591060858367e+01,3.000199999999999250e+02,3.649636253033746715e-08,4.317047933423678430e+00,1.094891605841021967e-05,-1.000000009975359205e+00,3.000000000000000062e-03,-1.081275084780377460e-10,4.317047933423678319e-01 +4.394053230833087298e+01,3.000299999999993474e+02,1.459855231122520996e-07,4.314731535678281382e+00,2.189785401473284726e-05,-1.000000009975609672e+00,4.000000000000000083e-03,1.145843179599920056e-10,4.314731535678281715e-01 +4.394284994962959701e+01,3.000399999999969509e+02,3.649640632420799799e-07,4.312413894356436295e+00,3.649647202009732920e-05,-1.000000009975344106e+00,5.000000000000000104e-03,-1.786785014805471948e-10,4.312413894356436628e-01 +4.394516883650942418e+01,3.000499999999902911e+02,7.299287833620315212e-07,4.310095007453479177e+00,5.474479927222630142e-05,-1.000000009975758442e+00,6.000000000000000125e-03,1.478616515119407599e-10,4.310095007453479399e-01 +4.394748897098040885e+01,3.000599999999753322e+02,1.277376775810844915e-06,4.307774872959352130e+00,7.664287226871102567e-05,-1.000000009975415383e+00,7.000000000000000146e-03,-6.313019920496759892e-11,4.307774872959352352e-01 +4.394981035505801259e+01,3.000699999999459351e+02,2.043805497747604996e-06,4.305453488858589139e+00,1.021907348073034059e-04,-1.000000009975561932e+00,8.000000000000000167e-03,2.896688238438810132e-11,4.305453488858592692e-01 +4.395213299076313973e+01,3.000799999998937437e+02,3.065712844042018486e-06,4.303130853130289424e+00,1.313884379862663378e-04,-1.000000009975494653e+00,9.000000000000001055e-03,-3.497082384219942714e-11,4.303130853130293643e-01 +4.395445688012214447e+01,3.000899999998074463e+02,4.379597220124435111e-06,4.300806963748101452e+00,1.642360402047825956e-04,-1.000000009975575921e+00,1.000000000000000194e-02,-3.743486253847140705e-11,4.300806963748105005e-01 +4.395678202516685218e+01,3.000999999996726046e+02,6.021957614788899263e-06,4.298481818680199851e+00,2.007336071634220555e-04,-1.000000009975662962e+00,1.100000000000000283e-02,9.334566938677368623e-11,4.298481818680203181e-01 +4.395910842793458073e+01,3.001099999994711425e+02,8.029293672942526867e-06,4.296155415889265861e+00,2.408812118646672757e-04,-1.000000009975445803e+00,1.200000000000000372e-02,-4.435812313882144871e-11,4.296155415889269524e-01 +4.396143609046816181e+01,3.001199999991810046e+02,1.043810576829447674e-05,4.293827753332466912e+00,2.846789346134977194e-04,-1.000000009975549053e+00,1.300000000000000461e-02,-1.287118737591537340e-11,4.293827753332470909e-01 +4.396376501481596222e+01,3.001299999987758156e+02,1.328489507597782551e-05,4.291498828961433532e+00,3.321268630180322255e-04,-1.000000009975579029e+00,1.400000000000000550e-02,-1.219717327376609340e-11,4.291498828961436973e-01 +4.396609520303191232e+01,3.001399999982242548e+02,1.660616364509759140e-05,4.289168640722240688e+00,3.832250919902301621e-04,-1.000000009975607451e+00,1.500000000000000638e-02,1.045720658402031789e-10,4.289168640722244019e-01 +4.396842665717551313e+01,3.001499999974899424e+02,2.043841447119822385e-05,4.286837186555385593e+00,4.379737237466506936e-04,-1.000000009975363646e+00,1.600000000000000727e-02,-1.495386308132065389e-10,4.286837186555389478e-01 +4.397075937931186473e+01,3.001599999965308143e+02,2.481815156864381736e-05,4.284504464395767265e+00,4.963728678092709738e-04,-1.000000009975712478e+00,1.700000000000000816e-02,6.326484822290334873e-11,4.284504464395771373e-01 +4.397309337151168762e+01,3.001699999952988946e+02,2.978188004290430134e-05,4.282170472172662556e+00,5.584226410063625060e-04,-1.000000009975564819e+00,1.800000000000000905e-02,-3.175781721388813194e-11,4.282170472172666109e-01 +4.397542863585134398e+01,3.001799999937397274e+02,3.536610616274093804e-05,4.279835207809709274e+00,6.241231674734261598e-04,-1.000000009975638982e+00,1.900000000000000994e-02,-4.780081018847600554e-11,4.279835207809712383e-01 +4.397776517441286614e+01,3.001899999917920923e+02,4.160733743228432692e-05,4.277498669224880423e+00,6.934745786541856791e-04,-1.000000009975750670e+00,2.000000000000001082e-02,9.478959110712348842e-11,4.277498669224883976e-01 +4.398010298928396367e+01,3.001999999893875497e+02,4.854208266299824253e-05,4.275160854330464666e+00,7.664770133016398463e-04,-1.000000009975529069e+00,2.100000000000001171e-02,7.404355942547983833e-12,4.275160854330468108e-01 +4.398244208255805177e+01,3.002099999864501001e+02,5.620685204552251270e-05,4.272821761033045007e+00,8.431306174791728140e-04,-1.000000009975511750e+00,2.200000000000001260e-02,-2.760882927745047651e-11,4.272821761033048782e-01 +4.398478245633427264e+01,3.002199999828957289e+02,6.463815722138823870e-05,4.270481387233474813e+00,9.234355445617236334e-04,-1.000000009975576365e+00,2.300000000000001349e-02,-3.413654468884643571e-11,4.270481387233479031e-01 +4.398712411271753098e+01,3.002299999786320654e+02,7.387251135459861162e-05,4.268139730826857381e+00,1.007391955237013897e-03,-1.000000009975656301e+00,2.400000000000001438e-02,-1.601642406500711340e-11,4.268139730826860934e-01 +4.398946705381849398e+01,3.002399999735578717e+02,8.394642920306851137e-05,4.265796789702523739e+00,1.095000017506834360e-03,-1.000000009975693827e+00,2.500000000000001527e-02,4.319219062641434507e-11,4.265796789702527292e-01 +4.399181128175361977e+01,3.002499999675627578e+02,9.489642718991626120e-05,4.263452561744010438e+00,1.186259906688389787e-03,-1.000000009975592574e+00,2.600000000000001615e-02,1.855486213790560202e-11,4.263452561744013880e-01 +4.399415679864519291e+01,3.002599999605266703e+02,1.067590234746006124e-04,4.261107044829037349e+00,1.281171805415702667e-03,-1.000000009975549053e+00,2.700000000000001704e-02,-3.339930081002529263e-11,4.261107044829041124e-01 +4.399650360662133153e+01,3.002699999523196652e+02,1.195707380238963724e-04,4.258760236829484569e+00,1.379735903641076018e-03,-1.000000009975627435e+00,2.800000000000001793e-02,-3.555586600807205751e-11,4.258760236829488011e-01 +4.399885170781602284e+01,3.002799999428013393e+02,1.333680926827017922e-04,4.256412135611370218e+00,1.481952398636614309e-03,-1.000000009975710924e+00,2.900000000000001882e-02,1.088770580409525596e-10,4.256412135611373770e-01 +4.400120110436913023e+01,3.002899999318204323e+02,1.481876112446709631e-04,4.254062739034828233e+00,1.587821494995803355e-03,-1.000000009975455129e+00,3.000000000000001971e-02,-1.261029893087405328e-10,4.254062739034831786e-01 +4.400355179842642173e+01,3.002999999192145424e+02,1.640658195226645151e-04,4.251712044954086167e+00,1.697343404635149201e-03,-1.000000009975751558e+00,3.100000000000002059e-02,4.106703287554197839e-11,4.251712044954090164e-01 +4.400590379213960546e+01,3.003099999048096720e+02,1.810392454190116909e-04,4.249360051217439427e+00,1.810518346795875113e-03,-1.000000009975654969e+00,3.200000000000002148e-02,-3.472254703424976949e-11,4.249360051217443424e-01 +4.400825708766633682e+01,3.003199998884197726e+02,1.991444189955771961e-04,4.247006755667232625e+00,1.927346548045678204e-03,-1.000000009975736681e+00,3.300000000000002237e-02,-1.339095410790018872e-11,4.247006755667236400e-01 +4.401061168717024685e+01,3.003299998698464606e+02,2.184178725436258317e-04,4.244652156139832933e+00,2.047828242280544820e-03,-1.000000009975768211e+00,3.400000000000002326e-02,1.443913234135113360e-10,4.244652156139837040e-01 +4.401296759282097071e+01,3.003399998488784490e+02,2.388961406534783369e-04,4.242296250465608765e+00,2.171963670726624260e-03,-1.000000009975428039e+00,3.500000000000002415e-02,-1.407316618394909058e-10,4.242296250465611984e-01 +4.401532480679416182e+01,3.003499998252913201e+02,2.606157602839514207e-04,4.239939036468906686e+00,2.299753081942162124e-03,-1.000000009975759774e+00,3.600000000000002504e-02,1.308623267679949345e-11,4.239939036468911016e-01 +4.401768333127151323e+01,3.003599997988470136e+02,2.836132708315753704e-04,4.237580511968024766e+00,2.431196731819491343e-03,-1.000000009975728910e+00,3.700000000000002592e-02,6.859393482604869526e-11,4.237580511968028207e-01 +4.402004316844080023e+01,3.003699997692934289e+02,3.079252141995820254e-04,4.235220674775193928e+00,2.566294883587084356e-03,-1.000000009975567039e+00,3.800000000000002681e-02,-9.121956644557589518e-12,4.235220674775197480e-01 +4.402240432049588748e+01,3.003799997363640841e+02,3.335881348666571268e-04,4.232859522696551302e+00,2.705047807811661667e-03,-1.000000009975588577e+00,3.900000000000002770e-02,-7.425080601320467394e-11,4.232859522696554855e-01 +4.402476678963675738e+01,3.003899996997776611e+02,3.606385799554490471e-04,4.230497053532116247e+00,2.847455782400361984e-03,-1.000000009975763993e+00,4.000000000000002859e-02,3.954701587398681249e-11,4.230497053532119578e-01 +4.402713057806952435e+01,3.003999996592376647e+02,3.891130993008280986e-04,4.228133265075767255e+00,2.993519092602970038e-03,-1.000000009975670512e+00,4.100000000000002948e-02,-1.154766041909381678e-10,4.228133265075770808e-01 +4.402949568800647739e+01,3.004099996144319107e+02,4.190482455178891038e-04,4.225768155115218860e+00,3.143238031014202946e-03,-1.000000009975943627e+00,4.200000000000003036e-02,1.469391926114490242e-10,4.225768155115222635e-01 +4.403186212166609437e+01,3.004199995650322421e+02,4.504805740696902322e-04,4.223401721431994993e+00,3.296612897576058163e-03,-1.000000009975595905e+00,4.300000000000003125e-02,-5.289099316047362923e-11,4.223401721431998546e-01 +4.403422988127306326e+01,3.004299995106940173e+02,4.834466433347217639e-04,4.221033961801408552e+00,3.453643999580217373e-03,-1.000000009975721138e+00,4.400000000000003214e-02,1.452749618556166689e-11,4.221033961801411993e-01 +4.403659896905830351e+01,3.004399994510557690e+02,5.179830146740971872e-04,4.218664873992532094e+00,3.614331651670512832e-03,-1.000000009975686721e+00,4.500000000000003303e-02,-9.367317752567788370e-12,4.218664873992535869e-01 +4.403896938725900867e+01,3.004499993857388631e+02,5.541262524984606709e-04,4.216294455768177407e+00,3.778676175845450524e-03,-1.000000009975708926e+00,4.600000000000003392e-02,1.404308155017967355e-11,4.216294455768181404e-01 +4.404134113811866058e+01,3.004599993143469874e+02,5.919129243346028845e-04,4.213922704884868864e+00,3.946677901460794030e-03,-1.000000009975675619e+00,4.700000000000003481e-02,-7.017591016430849561e-11,4.213922704884872639e-01 +4.404371422388703650e+01,3.004699992364657533e+02,6.313796008917796397e-04,4.211549619092819441e+00,4.118337165232206949e-03,-1.000000009975842152e+00,4.800000000000003569e-02,7.892681793718247367e-11,4.211549619092823660e-01 +4.404608864682026592e+01,3.004799991516623550e+02,6.725628561277249493e-04,4.209175196135904962e+00,4.293654311237955594e-03,-1.000000009975654747e+00,4.900000000000003658e-02,3.598304877422017017e-11,4.209175196135908625e-01 +4.404846440918083061e+01,3.004899990594851715e+02,7.154992673143530275e-04,4.206799433751641004e+00,4.472629690921671106e-03,-1.000000009975569260e+00,5.000000000000003747e-02,-1.274108469315135622e-10,4.206799433751644557e-01 +4.405084151323760011e+01,3.004999989594632552e+02,7.602254151031413200e-04,4.204422329671155367e+00,4.655263663095170548e-03,-1.000000009975872128e+00,5.100000000000003836e-02,-4.294418757597132372e-12,4.204422329671158587e-01 +4.405321996126586725e+01,3.005099988511060474e+02,8.067778835901880542e-04,4.202043881619163201e+00,4.841556593941337416e-03,-1.000000009975882342e+00,5.200000000000003925e-02,5.001100690344698440e-11,4.202043881619166865e-01 +4.405559975554734820e+01,3.005199987339029235e+02,8.551932603809370495e-04,4.199664087313943917e+00,5.031508857017061125e-03,-1.000000009975763327e+00,5.300000000000004013e-02,1.753123975800677853e-11,4.199664087313947913e-01 +4.405798089837022502e+01,3.005299986073227956e+02,9.055081366545636055e-04,4.197282944467313648e+00,5.225120833256240681e-03,-1.000000009975721582e+00,5.400000000000004102e-02,6.048576375226681243e-11,4.197282944467317645e-01 +4.406036339202917418e+01,3.005399984708136571e+02,9.577591072280133367e-04,4.194900450784599499e+00,5.422392910972839535e-03,-1.000000009975577475e+00,5.500000000000004191e-02,-1.060927260142210076e-10,4.194900450784602719e-01 +4.406274723882538069e+01,3.005499983238022992e+02,1.011982770619688317e-03,4.192516603964614674e+00,5.623325485864009814e-03,-1.000000009975830384e+00,5.600000000000004280e-02,3.900578653539928836e-11,4.192516603964618338e-01 +4.406513244106656657e+01,3.005599981656937416e+02,1.068215729112772074e-03,4.190131401699630942e+00,5.827918961013269471e-03,-1.000000009975737347e+00,5.700000000000004369e-02,-5.442817019295018846e-11,4.190131401699634384e-01 +4.406751900106703346e+01,3.005699979958710060e+02,1.126494588818188237e-03,4.187744841675355545e+00,6.036173746893741011e-03,-1.000000009975867243e+00,5.800000000000004458e-02,2.464145294576101467e-11,4.187744841675358765e-01 +4.406990692114766262e+01,3.005799978136946038e+02,1.186855959737183937e-03,4.185356921570901889e+00,6.248090261371451806e-03,-1.000000009975808402e+00,5.900000000000004546e-02,8.642824094320242343e-11,4.185356921570905220e-01 +4.407229620363596467e+01,3.005899976185020819e+02,1.249336455823532111e-03,4.182967639058765563e+00,6.463668929708694250e-03,-1.000000009975601900e+00,6.000000000000004635e-02,-1.892905398737490788e-10,4.182967639058768894e-01 +4.407468685086608673e+01,3.005999974096077381e+02,1.313972695045346204e-03,4.180576991804796805e+00,6.682910184567444033e-03,-1.000000009976054427e+00,6.100000000000004724e-02,1.441610401780668367e-10,4.180576991804800802e-01 +4.407707886517884788e+01,3.006099971863021096e+02,1.380801299446498057e-03,4.178184977468172079e+00,6.905814466012838264e-03,-1.000000009975709592e+00,6.200000000000004813e-02,3.757360902133765554e-11,4.178184977468146766e-01 +4.407947224892177474e+01,3.006199969478516891e+02,1.449858895207635067e-03,4.175791593701372761e+00,7.132382221516717774e-03,-1.000000009975619664e+00,6.300000000000004208e-02,-1.350020664243434113e-10,4.175791593701376758e-01 +4.408186700444910855e+01,3.006299966934984127e+02,1.521182112706786008e-03,4.173396838150152277e+00,7.362613905961224066e-03,-1.000000009975942961e+00,6.400000000000004297e-02,2.242566210136269321e-11,4.173396838150155719e-01 +4.408426313412184783e+01,3.006399964224592054e+02,1.594807586579551810e-03,4.171000708453511230e+00,7.596509981642463050e-03,-1.000000009975889226e+00,6.500000000000004385e-02,1.852296408901171054e-12,4.171000708453515005e-01 +4.408666064030776965e+01,3.006499961339257538e+02,1.670771955778872428e-03,4.168603202243672534e+00,7.834070918274220821e-03,-1.000000009975884785e+00,6.600000000000004474e-02,9.357976254938621437e-11,4.168603202243675865e-01 +4.408905952538145812e+01,3.006599958270639945e+02,1.749111863634362184e-03,4.166204317146051217e+00,8.075297192991749695e-03,-1.000000009975660298e+00,6.700000000000004563e-02,-5.180465873170867062e-12,4.166204317146054992e-01 +4.409145979172433982e+01,3.006699955010136591e+02,1.829863957911207969e-03,4.163804050779228660e+00,8.320189290355604547e-03,-1.000000009975672732e+00,6.800000000000004652e-02,-1.089120165568931201e-10,4.163804050779232324e-01 +4.409386144172468391e+01,3.006799951548879335e+02,1.913064890868622922e-03,4.161402400754923292e+00,8.568747702355548543e-03,-1.000000009975934301e+00,6.900000000000004741e-02,-8.685759348891215247e-12,4.161402400754926623e-01 +4.409626447777767311e+01,3.006899947877730028e+02,1.998751319317846904e-03,4.158999364677963939e+00,8.820972928414515246e-03,-1.000000009975955173e+00,7.000000000000004829e-02,6.833776944018972519e-11,4.158999364677967159e-01 +4.409866890228538949e+01,3.006999943987277106e+02,2.086959904679688577e-03,4.156594940146263184e+00,9.076865475392627974e-03,-1.000000009975790860e+00,7.100000000000004918e-02,7.438972819424379804e-11,4.156594940146267070e-01 +4.410107471765686427e+01,3.007099939867831040e+02,2.177727313041601283e-03,4.154189124750788054e+00,9.336425857591286806e-03,-1.000000009975611892e+00,7.200000000000005007e-02,-1.659425094097481219e-10,4.154189124750791162e-01 +4.410348192630810615e+01,3.007199935509420357e+02,2.271090215214285109e-03,4.151781916075531598e+00,9.599654596757316305e-03,-1.000000009976011350e+00,7.300000000000005096e-02,1.168022942292278965e-10,4.151781916075534817e-01 +4.410589053066212273e+01,3.007299930901787093e+02,2.367085286787808020e-03,4.149373311697483580e+00,9.866552222087163551e-03,-1.000000009975730020e+00,7.400000000000005185e-02,-1.209727242436907873e-10,4.149373311697487354e-01 +4.410830053314895594e+01,3.007399926034383952e+02,2.465749208187239302e-03,4.146963309186606494e+00,1.013711927023117250e-02,-1.000000009976021564e+00,7.500000000000005274e-02,9.346229920713446070e-11,4.146963309186609825e-01 +4.411071193620570341e+01,3.007499920896368621e+02,2.567118664727788182e-03,4.144551906105800931e+00,1.041135628529790691e-02,-1.000000009975796189e+00,7.600000000000005362e-02,-7.684299511364275773e-11,4.144551906105804484e-01 +4.411312474227655400e+01,3.007599915476600358e+02,2.671230346669440248e-03,4.142139100010882480e+00,1.068926381885853920e-02,-1.000000009975981596e+00,7.700000000000005451e-02,8.525986462859708538e-11,4.142139100010885921e-01 +4.411553895381280199e+01,3.007699909763636583e+02,2.778120949271083856e-03,4.139724888450547979e+00,1.097084242995130521e-02,-1.000000009975775761e+00,7.800000000000005540e-02,-5.037235603901679699e-11,4.139724888450551088e-01 +4.411795457327290393e+01,3.007799903745727761e+02,2.887827172844119588e-03,4.137309268966350650e+00,1.125609268508600755e-02,-1.000000009975897441e+00,7.900000000000005629e-02,-2.030254516597470363e-11,4.137309268966354314e-01 +4.412037160312247863e+01,3.007899897410813423e+02,3.000385722805546697e-03,4.134892239092667232e+00,1.154501515824859527e-02,-1.000000009975946513e+00,8.000000000000005718e-02,5.536326997230562861e-11,4.134892239092670674e-01 +4.412279004583434983e+01,3.007999890746518759e+02,3.115833309730516552e-03,4.132473796356671336e+00,1.183761043090579383e-02,-1.000000009975812620e+00,8.100000000000005806e-02,-6.744312309341701080e-11,4.132473796356674889e-01 +4.412520990388857456e+01,3.008099883740149494e+02,3.234206649404349192e-03,4.130053938278303249e+00,1.213387909200980275e-02,-1.000000009975975823e+00,8.200000000000005895e-02,1.521396227578121404e-10,4.130053938278306913e-01 +4.412763117977248584e+01,3.008199876378688487e+02,3.355542462874003869e-03,4.127632662370238847e+00,1.243382173800305218e-02,-1.000000009975607451e+00,8.300000000000005984e-02,-2.339871893360094863e-10,4.127632662370242511e-01 +4.413005387598069262e+01,3.008299868648791744e+02,3.479877476498993618e-03,4.125209966137862949e+00,1.273743897282301855e-02,-1.000000009976174331e+00,8.400000000000006073e-02,1.251229523045864885e-10,4.125209966137866613e-01 +4.413247799501513668e+01,3.008399860536783876e+02,3.607248422001743844e-03,4.122785847079233790e+00,1.304473140790710951e-02,-1.000000009975871018e+00,8.500000000000006162e-02,3.387136712039310326e-11,4.122785847079237787e-01 +4.413490353938511390e+01,3.008499852028653549e+02,3.737692036517378021e-03,4.120360302685060816e+00,1.335569966219760443e-02,-1.000000009975788862e+00,8.600000000000006251e-02,-1.052139341892259763e-11,4.120360302685064924e-01 +4.413733051160729559e+01,3.008599843110050642e+02,3.871245062642932229e-03,4.117933330438667383e+00,1.367034436214665735e-02,-1.000000009975814397e+00,8.700000000000006339e-02,-8.951632169961099021e-11,4.117933330438670603e-01 +4.413975891420577113e+01,3.008699833766280562e+02,4.007944248485983789e-03,4.115504927815963221e+00,1.398866614172136411e-02,-1.000000009976031778e+00,8.800000000000006428e-02,4.523437045531379806e-11,4.115504927815967218e-01 +4.414218874971208351e+01,3.008799823982300836e+02,4.147826347712693131e-03,4.113075092285413348e+00,1.431066564240889363e-02,-1.000000009975921866e+00,8.900000000000006517e-02,6.685254500100428396e-11,4.113075092285416456e-01 +4.414462002066523638e+01,3.008899813742718266e+02,4.290928119595243707e-03,4.110643821308008761e+00,1.463634351322167133e-02,-1.000000009975759330e+00,9.000000000000006606e-02,-1.712312027451773343e-10,4.110643821308012646e-01 +4.414705272961174387e+01,3.008999803031782108e+02,4.437286329058681700e-03,4.108211112337233573e+00,1.496570041070264048e-02,-1.000000009976175885e+00,9.100000000000006695e-02,1.114715870559579242e-10,4.108211112337237236e-01 +4.414948687910565894e+01,3.009099791833381801e+02,4.586937746727139456e-03,4.105776962819033038e+00,1.529873699893057049e-02,-1.000000009975904547e+00,9.200000000000006783e-02,7.357141582608938713e-11,4.105776962819036591e-01 +4.415192247170860895e+01,3.009199780131042417e+02,4.739919148969441373e-03,4.103341370191786908e+00,1.563545394952543452e-02,-1.000000009975725357e+00,9.300000000000006872e-02,-1.965296222539976917e-10,4.103341370191790349e-01 +4.415435950998980985e+01,3.009299767907920682e+02,4.896267317944080939e-03,4.100904331886273013e+00,1.597585194165385830e-02,-1.000000009976204307e+00,9.400000000000006961e-02,3.149344723288175014e-09,4.100904331886276455e-01 +4.415679799652612303e+01,3.009399755146799862e+02,5.056019041643563736e-03,4.098465845325636181e+00,1.631993166203461049e-02,-1.000000009968524672e+00,9.500000000000007050e-02,9.999999681947198127e-01,4.098465845325640067e-01 +4.415923793390205532e+01,3.009499741830086919e+02,5.219211113938109457e-03,4.096025907925379350e+00,1.666769380494417807e-02,-9.975600726701933096e-01,9.600000000000007139e-02,1.000000001961314444e+00,4.096025907925383014e-01 +4.416167932470982294e+01,3.009599727939807394e+02,5.385880334618699077e-03,4.093590473933763185e+00,1.701913907222239036e-02,-9.951186818576341908e-01,9.700000000000007228e-02,1.000000005504712020e+00,4.093590473933766960e-01 +4.416412216799462698e+01,3.009699713457602002e+02,5.556063509439470617e-03,4.091159554944201027e+00,1.737426817327810541e-02,-9.926758385593797973e-01,9.800000000000007316e-02,1.000000006999288926e+00,4.091159554944204246e-01 +4.416656646278823928e+01,3.009799698364722076e+02,5.729797450159445325e-03,4.088733162560262535e+00,1.773308182509497621e-02,-9.902315437486560734e-01,9.900000000000007405e-02,1.000000007773702571e+00,4.088733162560265755e-01 +4.416901220810895978e+01,3.009899682642024459e+02,5.907118974583584238e-03,4.086311308395710995e+00,1.809558075223725859e-02,-9.877857984089246646e-01,1.000000000000000749e-01,1.000000008144139363e+00,4.086311308395714770e-01 +4.417145940296155260e+01,3.009999666269969225e+02,6.088064906603159535e-03,4.083894004074379858e+00,1.846176568685569189e-02,-9.853386035364010143e-01,1.010000000000000758e-01,1.000000008309574584e+00,4.083894004074383188e-01 +4.417390804633721757e+01,3.010099649228613430e+02,6.272672076235445877e-03,4.081481261230042179e+00,1.883163736869344906e-02,-9.828899601403875419e-01,1.020000000000000767e-01,1.000000008649520433e+00,4.081481261230046065e-01 +4.417635813721353344e+01,3.010199631497609403e+02,6.460977319662707455e-03,4.079073091506278281e+00,1.920519654509213539e-02,-9.804398692428780704e-01,1.030000000000000776e-01,1.000000008836100296e+00,4.079073091506281723e-01 +4.417880967455441521e+01,3.010299613056197359e+02,6.653017479270489400e-03,4.076669506556343414e+00,1.958244397099787037e-02,-9.779883318803376246e-01,1.040000000000000785e-01,1.000000009020235670e+00,4.076669506556346856e-01 +4.418126265731005020e+01,3.010399593883204261e+02,6.848829403685191899e-03,4.074270518043030087e+00,1.996338040896741481e-02,-9.755353491025775536e-01,1.050000000000000794e-01,1.000000008944201602e+00,4.074270518043033862e-01 +4.418371708441686962e+01,3.010499573957038137e+02,7.048449947810928734e-03,4.071876137638532178e+00,2.034800662917436373e-02,-9.730809219738052462e-01,1.060000000000000803e-01,1.000000009121915445e+00,4.071876137638535398e-01 +4.418617295479749174e+01,3.010599553255683531e+02,7.251915972865660698e-03,4.069486377024305490e+00,2.073632340941542265e-02,-9.706250515707780524e-01,1.070000000000000812e-01,1.000000009217541841e+00,4.069486377024308932e-01 +4.418863026736068633e+01,3.010699531756698661e+02,7.459264346416591765e-03,4.067101247890931859e+00,2.112833153511672543e-02,-9.681677389849357995e-01,1.080000000000000820e-01,1.000000009372526089e+00,4.067101247890935745e-01 +4.419108902100130365e+01,3.010799509437209167e+02,7.670531942414823660e-03,4.064720761937977045e+00,2.152403179934022151e-02,-9.657089853212764696e-01,1.090000000000000829e-01,1.000000009176280846e+00,4.064720761937981042e-01 +4.419354921460024599e+01,3.010899486273906405e+02,7.885755641229263632e-03,4.062344930873850402e+00,2.192342500279013257e-02,-9.632487916997606314e-01,1.100000000000000838e-01,1.000000009428179570e+00,4.062344930873854065e-01 +4.419601084702441796e+01,3.010999462243040625e+02,8.104972329679771548e-03,4.059973766415660101e+00,2.232651195381947853e-02,-9.607871592523823390e-01,1.110000000000000847e-01,1.000000009349118590e+00,4.059973766415663765e-01 +4.419847391712667672e+01,3.011099437320419270e+02,8.328218901069543711e-03,4.057607280289074581e+00,2.273329346843664875e-02,-9.583240891270993211e-01,1.120000000000000856e-01,1.000000009369931053e+00,4.057607280289078355e-01 +4.420093842374578230e+01,3.011199411481400716e+02,8.555532255216718659e-03,4.055245484228173325e+00,2.314377037031205633e-02,-9.558595824849023259e-01,1.130000000000000865e-01,1.000000009663053024e+00,4.055245484228177100e-01 +4.420340436570636200e+01,3.011299384700890869e+02,8.786949298485212737e-03,4.052888389975303873e+00,2.355794349078485159e-02,-9.533936405004964643e-01,1.140000000000000874e-01,1.000000009270074264e+00,4.052888389975307093e-01 +4.420587174181884649e+01,3.011399356953339179e+02,9.022506943814749894e-03,4.050536009280936156e+00,2.397581366886969087e-02,-9.509262643651369418e-01,1.150000000000000883e-01,1.000000009750589891e+00,4.050536009280940042e-01 +4.420834055087944847e+01,3.011499328212734099e+02,9.262242110750112598e-03,4.048188353903508840e+00,2.439738175126358877e-02,-9.484574552804644343e-01,1.160000000000000892e-01,1.000000009345974883e+00,4.048188353903512393e-01 +4.421081079167008454e+01,3.011599298452598532e+02,9.506191725469573944e-03,4.045845435609289886e+00,2.482264859235282228e-02,-9.459872144667391680e-01,1.170000000000000900e-01,1.000000009687140867e+00,4.045845435609293772e-01 +4.421328246295836095e+01,3.011699267645986424e+02,9.754392720812523135e-03,4.043507266172215786e+00,2.525161505421989402e-02,-9.435155431545192428e-01,1.180000000000000909e-01,1.000000009529470768e+00,4.043507266172219339e-01 +4.421575556349750258e+01,3.011799235765477647e+02,1.000688203630626869e-02,4.041173857373750344e+00,2.568428200665057864e-02,-9.410424425918086921e-01,1.190000000000000918e-01,1.000000009557784786e+00,4.041173857373753786e-01 +4.421823009202632448e+01,3.011899202783174019e+02,1.026369661819201591e-02,4.038845221002724806e+00,2.612065032714102134e-02,-9.385679140393359265e-01,1.200000000000000927e-01,1.000000009766393694e+00,4.038845221002728136e-01 +4.422070604726917509e+01,3.011999168670694758e+02,1.052487341944999960e-02,4.036521368855188641e+00,2.656072090090490917e-02,-9.360919587723051105e-01,1.210000000000000936e-01,1.000000009463579476e+00,4.036521368855192082e-01 +4.422318342793589352e+01,3.012099133399173638e+02,1.079044939982378055e-02,4.034202312734255003e+00,2.700449462088070143e-02,-9.336145780821412110e-01,1.220000000000000945e-01,1.000000009733564177e+00,4.034202312734258555e-01 +4.422566223272176700e+01,3.012199096939252740e+02,1.106046152584368343e-02,4.031888064449940856e+00,2.745197238773893281e-02,-9.311357732721370351e-01,1.230000000000000954e-01,1.000000009671166534e+00,4.031888064449944409e-01 +4.422814246030748819e+01,3.012299059261079606e+02,1.133494677084937591e-02,4.029578635819016874e+00,2.790315510988956860e-02,-9.286555456624263627e-01,1.240000000000000963e-01,1.000000009567860726e+00,4.029578635818964472e-01 +4.423062410935910549e+01,3.012399020334302122e+02,1.161394211501157701e-02,4.027274038664844014e+00,2.835804370348945017e-02,-9.261738965870643936e-01,1.250000000000000833e-01,1.000000009751050412e+00,4.027274038664847011e-01 +4.423310717852797325e+01,3.012498980128064545e+02,1.189748454535288769e-02,4.024974284817216308e+00,2.881663909244978200e-02,-9.236908273939816727e-01,1.260000000000000842e-01,1.000000009721633720e+00,4.024974284817219861e-01 +4.423559166645072338e+01,3.012598938611002950e+02,1.218561105576773836e-02,4.022679386112202771e+00,2.927894220844369857e-02,-9.212063394470803024e-01,1.270000000000000850e-01,1.000000009739557383e+00,4.022679386112206212e-01 +4.423807757174919431e+01,3.012698895751241821e+02,1.247835864704143968e-02,4.020389354391983083e+00,2.974495399091389367e-02,-9.187204341243943029e-01,1.280000000000000859e-01,1.000000009527603595e+00,4.020389354391986636e-01 +4.424056489303042383e+01,3.012798851516388936e+02,1.277576432686833297e-02,4.018104201504686834e+00,3.021467538708031905e-02,-9.162331128194685093e-01,1.290000000000000868e-01,1.000000009851143457e+00,4.018104201504690276e-01 +4.424305362888656390e+01,3.012898805873530819e+02,1.307786510986902809e-02,4.015823939304228318e+00,3.068810735194794220e-02,-9.137443769388094994e-01,1.300000000000000877e-01,1.000000009791784494e+00,4.015823939304231649e-01 +4.424554377789487347e+01,3.012998758789229328e+02,1.338469801760672900e-02,4.013548579650146664e+00,3.116525084831458375e-02,-9.112542279061179862e-01,1.310000000000000886e-01,1.000000009618662533e+00,4.013548579650150216e-01 +4.424803533861764748e+01,3.013098710229517110e+02,1.369630007860262073e-02,4.011278134407434415e+00,3.164610684677880703e-02,-9.087626671593789229e-01,1.320000000000000895e-01,1.000000009779728138e+00,4.011278134407437745e-01 +4.425052830960218841e+01,3.013198660159891915e+02,1.401270832835033522e-02,4.009012615446372330e+00,3.213067632574789084e-02,-9.062696961504577153e-01,1.330000000000000904e-01,1.000000009760756203e+00,4.009012615446376215e-01 +4.425302268938075656e+01,3.013298608545314323e+02,1.433395980932945964e-02,4.006752034642364180e+00,3.261896027144584737e-02,-9.037753163475410467e-01,1.340000000000000913e-01,1.000000009657773026e+00,4.006752034642367954e-01 +4.425551847647053449e+01,3.013398555350202628e+02,1.466009157101810442e-02,4.004496403875764443e+00,3.311095967792153372e-02,-9.012795292336598374e-01,1.350000000000000921e-01,1.000000009889561392e+00,4.004496403875767996e-01 +4.425801566937357023e+01,3.013498500538428289e+02,1.499114066990450342e-02,4.002245735031708662e+00,3.360667554705680515e-02,-8.987823363059256332e-01,1.360000000000000930e-01,1.000000009701959680e+00,6.099708070141603156e-02 +4.426051426657675592e+01,3.013598444073310816e+02,1.532714416949764943e-02,4.000000039999944690e+00,3.410610888857476541e-02,-8.962837390785016733e-01,1.361524071352429588e-01,1.000000009732090245e+00,0.000000000000000000e+00 +4.426301426655175675e+01,3.013698385917615497e+02,1.566813914033694799e-02,3.997759330674655498e+00,3.460610888857476586e-02,-8.937837390791714132e-01,1.361524071352429588e-01,1.000000009800525724e+00,0.000000000000000000e+00 +4.426551566775499680e+01,3.013798326044452551e+02,1.601413116055888999e-02,3.995523618954289535e+00,3.510610888857476630e-02,-8.912823378514197481e-01,1.361524071352429588e-01,1.000000009837181958e+00,0.000000000000000000e+00 +4.426801846862759504e+01,3.013898264428837024e+02,1.636512014366547224e-02,3.993292916741384868e+00,3.560610888857476675e-02,-8.887795369542024204e-01,1.361524071352429588e-01,1.000000009668826628e+00,0.000000000000000000e+00 +4.427052266759533694e+01,3.013998201045784526e+02,1.672110600190944776e-02,3.991067235942392877e+00,3.610610888857476719e-02,-8.862753379622465566e-01,1.361524071352429588e-01,1.000000009797134659e+00,0.000000000000000000e+00 +4.427302826306863182e+01,3.014098135870310671e+02,1.708208864629435705e-02,3.988846588467500176e+00,3.660610888857476763e-02,-8.837697424644022082e-01,1.361524071352429588e-01,1.000000009769638876e+00,0.000000000000000000e+00 +4.427553525344247021e+01,3.014198068877431638e+02,1.744806798657453847e-02,3.986630986230453644e+00,3.710610888857476808e-02,-8.812627520660729630e-01,1.361524071352429588e-01,1.000000009808776236e+00,0.000000000000000000e+00 +4.427804363709637414e+01,3.014298000042164176e+02,1.781904393125516295e-02,3.984420441148378345e+00,3.760610888857476852e-02,-8.787543683875667089e-01,1.361524071352429588e-01,1.000000009679689938e+00,0.000000000000000000e+00 +4.428055341239436160e+01,3.014397929339526172e+02,1.819501638759224091e-02,3.982214965141598562e+00,3.810610888857476897e-02,-8.762445930652830173e-01,1.361524071352429588e-01,1.000000009819458802e+00,0.000000000000000000e+00 +4.428306457768491811e+01,3.014497856744534374e+02,1.857598526159266392e-02,3.980014570133454832e+00,3.860610888857476941e-02,-8.737334277500677926e-01,1.361524071352429588e-01,1.000000009715154681e+00,0.000000000000000000e+00 +4.428557713130093987e+01,3.014597782232207237e+02,1.896195045801421508e-02,3.977819268050124091e+00,3.910610888857476986e-02,-8.712208741096382214e-01,1.361524071352429588e-01,1.000000009806689460e+00,0.000000000000000000e+00 +4.428809107155969116e+01,3.014697705777563783e+02,1.935291188036559681e-02,3.975629070820432709e+00,3.960610888857477030e-02,-8.687069338262304319e-01,1.361524071352429588e-01,1.000000009725924288e+00,0.000000000000000000e+00 +4.429060639676279010e+01,3.014797627355623035e+02,1.974886943090645511e-02,3.973443990375674417e+00,4.010610888857477074e-02,-8.661916085986695046e-01,1.361524071352429588e-01,1.000000009774012266e+00,0.000000000000000000e+00 +4.429312310519613760e+01,3.014897546941404016e+02,2.014982301064740383e-02,3.971264038649422012e+00,4.060610888857477119e-02,-8.636749001407267867e-01,1.361524071352429588e-01,1.000000009796444322e+00,0.000000000000000000e+00 +4.429564119512988896e+01,3.014997464509927454e+02,2.055577251935005248e-02,3.969089227577342172e+00,4.110610888857477163e-02,-8.611568101823050547e-01,1.361524071352429588e-01,1.000000009745239504e+00,0.000000000000000000e+00 +4.429816066481843251e+01,3.015097380036213508e+02,2.096671785552702352e-02,3.966919569097006271e+00,4.160610888857477208e-02,-8.586373404692101419e-01,1.361524071352429588e-01,1.000000009748178931e+00,0.000000000000000000e+00 +4.430068151250031860e+01,3.015197293495284043e+02,2.138265891644198710e-02,3.964755075147700758e+00,4.210610888857477252e-02,-8.561164927627470389e-01,1.361524071352429588e-01,1.000000009758233555e+00,0.000000000000000000e+00 +4.430320373639825249e+01,3.015297204862159788e+02,2.180359559810967837e-02,3.962595757670237528e+00,4.260610888857477296e-02,-8.535942688401987333e-01,1.361524071352429588e-01,1.000000009694098635e+00,0.000000000000000000e+00 +4.430572733471903746e+01,3.015397114111863175e+02,2.222952779529592873e-02,3.960441628606762077e+00,4.310610888857477341e-02,-8.510706704949513313e-01,1.361524071352429588e-01,1.000000009857712868e+00,0.000000000000000000e+00 +4.430825230565353223e+01,3.015497021219417206e+02,2.266045540151769358e-02,3.958292699900560319e+00,4.360610888857477385e-02,-8.485456995355649124e-01,1.361524071352429588e-01,1.000000009679726576e+00,0.000000000000000000e+00 +4.431077864737662964e+01,3.015596926159844884e+02,2.309637830904307312e-02,3.956148983495866744e+00,4.410610888857477430e-02,-8.460193577880108506e-01,1.361524071352429588e-01,1.000000009809325796e+00,0.000000000000000000e+00 +4.431330635804721396e+01,3.015696828908169778e+02,2.353729640889134014e-02,3.954010491337665911e+00,4.460610888857477474e-02,-8.434916470926323573e-01,1.361524071352429588e-01,1.000000009745838359e+00,0.000000000000000000e+00 +4.431583543580811124e+01,3.015796729439416595e+02,2.398320959083297468e-02,3.951877235371500596e+00,4.510610888857477518e-02,-8.409625693070862384e-01,1.361524071352429588e-01,1.000000009718424510e+00,0.000000000000000000e+00 +4.431836587878606792e+01,3.015896627728610042e+02,2.443411774338968140e-02,3.949749227543271513e+00,4.560610888857477563e-02,-8.384321263045357853e-01,1.361524071352429588e-01,1.000000009780129595e+00,0.000000000000000000e+00 +4.432089768509170824e+01,3.015996523750775395e+02,2.489002075383442772e-02,3.947626479799040577e+00,4.610610888857477607e-02,-8.359003199741320556e-01,1.361524071352429588e-01,1.000000009740005913e+00,0.000000000000000000e+00 +4.432343085281949868e+01,3.016096417480939067e+02,2.535091850819146120e-02,3.945509004084831961e+00,4.660610888857477652e-02,-8.333671522216680172e-01,1.361524071352429588e-01,1.000000009785618094e+00,0.000000000000000000e+00 +4.432596538004770537e+01,3.016196308894127469e+02,2.581681089123634421e-02,3.943396812346430469e+00,4.710610888857477696e-02,-8.308326249686562859e-01,1.361524071352429588e-01,1.000000009721879080e+00,0.000000000000000000e+00 +4.432850126483837272e+01,3.016296197965367583e+02,2.628769778649598515e-02,3.941289916529181259e+00,4.760610888857477740e-02,-8.282967401533342100e-01,1.361524071352429588e-01,1.000000009799660861e+00,0.000000000000000000e+00 +4.433103850523727374e+01,3.016396084669686957e+02,2.676357907624866278e-02,3.939188328577786002e+00,4.810610888857477785e-02,-8.257594997295688577e-01,1.361524071352429588e-01,1.000000009679827162e+00,0.000000000000000000e+00 +4.433357709927388157e+01,3.016495968982114277e+02,2.724445464152405738e-02,3.937092060436100827e+00,4.860610888857477829e-02,-8.232209056683885695e-01,1.361524071352429588e-01,1.000000009812653579e+00,0.000000000000000000e+00 +4.433611704496133399e+01,3.016595850877678231e+02,2.773032436210327856e-02,3.935001124046929366e+00,4.910610888857477874e-02,-8.206809599560145330e-01,1.361524071352429588e-01,1.000000009713972515e+00,0.000000000000000000e+00 +4.433865834029639785e+01,3.016695730331408640e+02,2.822118811651889991e-02,3.932915531351819816e+00,4.960610888857477918e-02,-8.181396645962675240e-01,1.361524071352429588e-01,1.000000009755923180e+00,0.000000000000000000e+00 +4.434120098325943360e+01,3.016795607318335328e+02,2.871704578205498681e-02,3.930835294290854875e+00,5.010610888857477963e-02,-8.155970216084273972e-01,1.361524071352429588e-01,1.000000009720730887e+00,0.000000000000000000e+00 +4.434374497181436681e+01,3.016895481813489255e+02,2.921789723474712414e-02,3.928760424802446138e+00,5.060610888857478007e-02,-8.130530330287656371e-01,1.361524071352429588e-01,1.000000009831435666e+00,0.000000000000000000e+00 +4.434629030390865267e+01,3.016995353791901380e+02,2.972374234938245097e-02,3.926690934823123591e+00,5.110610888857478051e-02,-8.105077009094580065e-01,1.361524071352429588e-01,1.000000009654094413e+00,0.000000000000000000e+00 +4.434883697747323339e+01,3.017095223228604368e+02,3.023458099949969183e-02,3.924626836287326892e+00,5.160610888857478096e-02,-8.079610273202896265e-01,1.361524071352429588e-01,1.000000009810104284e+00,0.000000000000000000e+00 +4.435138499042252391e+01,3.017195090098630317e+02,3.075041305738918443e-02,3.922568141127191321e+00,5.210610888857478140e-02,-8.054130143460010993e-01,1.361524071352429588e-01,1.000000009715789062e+00,0.000000000000000000e+00 +4.435393434065436935e+01,3.017294954377013028e+02,3.127123839409291783e-02,3.920514861272339502e+00,5.260610888857478185e-02,-8.028636640893898058e-01,1.361524071352429588e-01,1.000000009771843112e+00,0.000000000000000000e+00 +4.435648502605000232e+01,3.017394816038785734e+02,3.179705687940456021e-02,3.918467008649664240e+00,5.310610888857478229e-02,-8.003129786688343295e-01,1.361524071352429588e-01,1.000000009721920158e+00,0.000000000000000000e+00 +4.435903704447402873e+01,3.017494675058983375e+02,3.232786838186949702e-02,3.916424595183116697e+00,5.360610888857478273e-02,-7.977609602200008698e-01,1.361524071352429588e-01,1.000000009745017460e+00,0.000000000000000000e+00 +4.436159039377438518e+01,3.017594531412641459e+02,3.286367276878485177e-02,3.914387632793489225e+00,5.410610888857478318e-02,-7.952076108947644384e-01,1.361524071352429588e-01,1.000000009771555565e+00,0.000000000000000000e+00 +4.436414507178231048e+01,3.017694385074795491e+02,3.340446990619953122e-02,3.912356133398199987e+00,5.460610888857478362e-02,-7.926529328618739934e-01,1.361524071352429588e-01,1.000000009689378633e+00,0.000000000000000000e+00 +4.436670107631232440e+01,3.017794236020482685e+02,3.395025965891425995e-02,3.910330108911074909e+00,5.510610888857478407e-02,-7.900969283070923277e-01,1.361524071352429588e-01,1.000000009749459906e+00,0.000000000000000000e+00 +4.436925840516218500e+01,3.017894084224739686e+02,3.450104189048159437e-02,3.908309571242128300e+00,5.560610888857478451e-02,-7.875395994322983428e-01,1.361524071352429588e-01,1.000000009817930913e+00,0.000000000000000000e+00 +4.437181705611286020e+01,3.017993929662604842e+02,3.505681646320597811e-02,3.906294532297344801e+00,5.610610888857478495e-02,-7.849809484565003492e-01,1.361524071352429588e-01,1.000000009648501553e+00,0.000000000000000000e+00 +4.437437702692850650e+01,3.018093772309116503e+02,3.561758323814377680e-02,3.904285003978457791e+00,5.660610888857478540e-02,-7.824209776161541452e-01,1.361524071352429588e-01,1.000000009829976610e+00,0.000000000000000000e+00 +4.437693831535642630e+01,3.018193612139314155e+02,3.618334207510329886e-02,3.902280998182726002e+00,5.710610888857478584e-02,-7.798596891630545924e-01,1.361524071352429588e-01,1.000000009684520963e+00,0.000000000000000000e+00 +4.437950091912705375e+01,3.018293449128237285e+02,3.675409283264483712e-02,3.900282526802714589e+00,5.760610888857478629e-02,-7.772970853676072212e-01,1.361524071352429588e-01,1.000000009706357496e+00,0.000000000000000000e+00 +4.438206483595391916e+01,3.018393283250927084e+02,3.732983536808070352e-02,3.898289601726066866e+00,5.810610888857478673e-02,-7.747331685158551640e-01,1.361524071352429588e-01,1.000000009799680845e+00,0.000000000000000000e+00 +4.438463006353362061e+01,3.018493114482425312e+02,3.791056953747527075e-02,3.896302234835282707e+00,5.860610888857478717e-02,-7.721679409110181469e-01,1.361524071352429588e-01,1.000000009685726887e+00,0.000000000000000000e+00 +4.438719659954578844e+01,3.018592942797773730e+02,3.849629519564499308e-02,3.894320438007492058e+00,5.910610888857478762e-02,-7.696014048739902025e-01,1.361524071352429588e-01,1.000000009778647003e+00,0.000000000000000000e+00 +4.438976444165307811e+01,3.018692768172015803e+02,3.908701219615846878e-02,3.892344223114226232e+00,5.960610888857478806e-02,-7.670335627415890700e-01,1.361524071352429588e-01,1.000000009768080789e+00,0.000000000000000000e+00 +4.439233358750112757e+01,3.018792590580194428e+02,3.968272039133644014e-02,3.890373602021192756e+00,6.010610888857478851e-02,-7.644644168684422425e-01,1.361524071352429588e-01,1.000000009697739056e+00,0.000000000000000000e+00 +4.439490403471853597e+01,3.018892409997354775e+02,4.028341963225186978e-02,3.888408586588044447e+00,6.060610888857478895e-02,-7.618939696261048944e-01,1.361524071352429588e-01,1.000000009694101299e+00,0.000000000000000000e+00 +4.439747578091683522e+01,3.018992226398541447e+02,4.088910976872994762e-02,3.886449188668149812e+00,6.110610888857478940e-02,-7.593222234028728090e-01,1.361524071352429588e-01,1.000000009763897912e+00,0.000000000000000000e+00 +4.440004882369046868e+01,3.019092039758800752e+02,4.149979064934813944e-02,3.884495420108363017e+00,6.160610888857478984e-02,-7.567491806041154456e-01,1.361524071352429588e-01,1.000000009794119515e+00,0.000000000000000000e+00 +4.440262316061676273e+01,3.019191850053178996e+02,4.211546212143623541e-02,3.882547292748792067e+00,6.210610888857479028e-02,-7.541748436526093391e-01,1.361524071352429588e-01,1.000000009685692692e+00,0.000000000000000000e+00 +4.440519878925589836e+01,3.019291657256723624e+02,4.273612403107636404e-02,3.880604818422565216e+00,6.260610888857479073e-02,-7.515992149885275531e-01,1.361524071352429588e-01,1.000000009686743407e+00,0.000000000000000000e+00 +4.440777570715089695e+01,3.019391461344482650e+02,4.336177622310305457e-02,3.878668008955596491e+00,6.310610888857479117e-02,-7.490222970685698201e-01,1.361524071352429588e-01,1.000000009788610367e+00,0.000000000000000000e+00 +4.441035391182758474e+01,3.019491262291505791e+02,4.399241854110325783e-02,3.876736876166352541e+00,6.360610888857479162e-02,-7.464440923666472161e-01,1.361524071352429588e-01,1.000000009726835337e+00,0.000000000000000000e+00 +4.441293340079457863e+01,3.019591060072842197e+02,4.462805082741640172e-02,3.874811431865616829e+00,6.410610888857479206e-02,-7.438646033745655028e-01,1.361524071352429588e-01,1.000000009714629767e+00,0.000000000000000000e+00 +4.441551417154325776e+01,3.019690854663542723e+02,4.526867292313441898e-02,3.872891687856251153e+00,6.460610888857479250e-02,-7.412838326008167611e-01,1.361524071352429588e-01,1.000000009773160059e+00,0.000000000000000000e+00 +4.441809622154774218e+01,3.019790646038658224e+02,4.591428466810178882e-02,3.870977655932959394e+00,6.510610888857479295e-02,-7.387017825710967545e-01,1.361524071352429588e-01,1.000000009665754419e+00,0.000000000000000000e+00 +4.442067954826487863e+01,3.019890434173241260e+02,4.656488590091557855e-02,3.869069347882049037e+00,6.560610888857479339e-02,-7.361184558289930457e-01,1.361524071352429588e-01,1.000000009761808695e+00,0.000000000000000000e+00 +4.442326414913419796e+01,3.019990219042344961e+02,4.722047645892547829e-02,3.867166775481190033e+00,6.610610888857479384e-02,-7.335338549344414538e-01,1.361524071352429588e-01,1.000000009705061199e+00,0.000000000000000000e+00 +4.442585002157792218e+01,3.020090000621023023e+02,4.788105617823385646e-02,3.865269950499176765e+00,6.660610888857479428e-02,-7.309479824656218705e-01,1.361524071352429588e-01,1.000000009743015283e+00,0.000000000000000000e+00 +4.442843716300092183e+01,3.020189778884329712e+02,4.854662489369578754e-02,3.863378884695684246e+00,6.710610888857479472e-02,-7.283608410174188252e-01,1.361524071352429588e-01,1.000000009728340133e+00,0.000000000000000000e+00 +4.443102557079069470e+01,3.020289553807320431e+02,4.921718243891909372e-02,3.861493589821027417e+00,6.760610888857479517e-02,-7.257724332024625413e-01,1.361524071352429588e-01,1.000000009716723204e+00,0.000000000000000000e+00 +4.443361524231737292e+01,3.020389325365051718e+02,4.989272864626439347e-02,3.859614077615916905e+00,6.810610888857479561e-02,-7.231827616506237844e-01,1.361524071352429588e-01,1.000000009765225961e+00,0.000000000000000000e+00 +4.443620617493366609e+01,3.020489093532580682e+02,5.057326334684513619e-02,3.857740359811215214e+00,6.860610888857479606e-02,-7.205918290090294054e-01,1.361524071352429588e-01,1.000000009667925571e+00,0.000000000000000000e+00 +4.443879836597486843e+01,3.020588858284965568e+02,5.125878637052765086e-02,3.855872448127692032e+00,6.910610888857479650e-02,-7.179996379427626696e-01,1.361524071352429588e-01,1.000000009747774143e+00,0.000000000000000000e+00 +4.444139181275883743e+01,3.020688619597264619e+02,5.194929754593118759e-02,3.854010354275776873e+00,6.960610888857479694e-02,-7.154061911335111157e-01,1.361524071352429588e-01,1.000000009731946360e+00,0.000000000000000000e+00 +4.444398651258596544e+01,3.020788377444537787e+02,5.264479670042795240e-02,3.852154089955314387e+00,7.010610888857479739e-02,-7.128114912811287507e-01,1.361524071352429588e-01,1.000000009741919049e+00,0.000000000000000000e+00 +4.444658246273917257e+01,3.020888131801845589e+02,5.334528366014316264e-02,3.850303666855314777e+00,7.060610888857479783e-02,-7.102155411026312981e-01,1.361524071352429588e-01,1.000000009698233994e+00,0.000000000000000000e+00 +4.444917966048387825e+01,3.020987882644249680e+02,5.405075824995508177e-02,3.848459096653706002e+00,7.110610888857479828e-02,-7.076183433327344341e-01,1.361524071352429588e-01,1.000000009714731464e+00,0.000000000000000000e+00 +4.445177810306800126e+01,3.021087629946812285e+02,5.476122029349506787e-02,3.846620391017083751e+00,7.160610888857479872e-02,-7.050199007233683979e-01,1.361524071352429588e-01,1.000000009702350479e+00,0.000000000000000000e+00 +4.445437778772192416e+01,3.021187373684596196e+02,5.547666961314760836e-02,3.844787561600461867e+00,7.210610888857479917e-02,-7.024202160442208909e-01,1.361524071352429588e-01,1.000000009697164627e+00,0.000000000000000000e+00 +4.445697871165849335e+01,3.021287113832665909e+02,5.619710603005038246e-02,3.842960620047020548e+00,7.260610888857479961e-02,-6.998192920824275465e-01,1.361524071352429588e-01,1.000000009792988420e+00,0.000000000000000000e+00 +4.445958087207300480e+01,3.021386850366085923e+02,5.692252936409428893e-02,3.841139577987854548e+00,7.310610888857480005e-02,-6.972171316424364829e-01,1.361524071352429588e-01,1.000000009681418112e+00,0.000000000000000000e+00 +4.446218426614316854e+01,3.021486583259922440e+02,5.765293943392349463e-02,3.839324447041720934e+00,7.360610888857480050e-02,-6.946137375470694542e-01,1.361524071352429588e-01,1.000000009699924641e+00,0.000000000000000000e+00 +4.446478889102911580e+01,3.021586312489242232e+02,5.838833605693549006e-02,3.837515238814783292e+00,7.410610888857480094e-02,-6.920091126358550726e-01,1.361524071352429588e-01,1.000000009715415805e+00,0.000000000000000000e+00 +4.446739474387338475e+01,3.021686038029112638e+02,5.912871904928112404e-02,3.835711964900359483e+00,7.460610888857480139e-02,-6.894032597662668183e-01,1.361524071352429588e-01,1.000000009713925442e+00,0.000000000000000000e+00 +4.447000182180089922e+01,3.021785759854602702e+02,5.987408822586464535e-02,3.833914636878665405e+00,7.510610888857480183e-02,-6.867961818134260543e-01,1.361524071352429588e-01,1.000000009732794348e+00,0.000000000000000000e+00 +4.447261012191896157e+01,3.021885477940782039e+02,6.062444340034377210e-02,3.832123266316558752e+00,7.560610888857480227e-02,-6.841878816699806798e-01,1.361524071352429588e-01,1.000000009729523409e+00,0.000000000000000000e+00 +4.447521964131722427e+01,3.021985192262720830e+02,6.137978438512970564e-02,3.830337864767282330e+00,7.610610888857480272e-02,-6.815783622463251756e-01,1.361524071352429588e-01,1.000000009710564797e+00,0.000000000000000000e+00 +4.447783037706771125e+01,3.022084902795490393e+02,6.214011099138721378e-02,3.828558443770206043e+00,7.660610888857480316e-02,-6.789676264704843645e-01,1.361524071352429588e-01,1.000000009664864686e+00,0.000000000000000000e+00 +4.448044232622478233e+01,3.022184609514163185e+02,6.290542302903463778e-02,3.826785014850568434e+00,7.710610888857480361e-02,-6.763556772881699208e-01,1.361524071352429588e-01,1.000000009758157837e+00,0.000000000000000000e+00 +4.448305548582512614e+01,3.022284312393812797e+02,6.367572030674398254e-02,3.825017589519217331e+00,7.760610888857480405e-02,-6.737425176623287326e-01,1.361524071352429588e-01,1.000000009680194868e+00,0.000000000000000000e+00 +4.448566985288775300e+01,3.022384011409513391e+02,6.445100263194092349e-02,3.823256179272350952e+00,7.810610888857480449e-02,-6.711281505743962317e-01,1.361524071352429588e-01,1.000000009750310781e+00,0.000000000000000000e+00 +4.448828542441398781e+01,3.022483706536339696e+02,6.523126981080488995e-02,3.821500795591254995e+00,7.860610888857480494e-02,-6.685125790226603693e-01,1.361524071352429588e-01,1.000000009679943069e+00,0.000000000000000000e+00 +4.449090219738745589e+01,3.022583397749368714e+02,6.601652164826909974e-02,3.819751449942043298e+00,7.910610888857480538e-02,-6.658958060238594490e-01,1.361524071352429588e-01,1.000000009675912072e+00,0.000000000000000000e+00 +4.449352016877409000e+01,3.022683085023677449e+02,6.680675794802058698e-02,3.818008153775393598e+00,7.960610888857480583e-02,-6.632778346118947121e-01,1.361524071352429588e-01,1.000000009789640654e+00,0.000000000000000000e+00 +4.449613933552210199e+01,3.022782768334343473e+02,6.760197851250027146e-02,3.816270918526285971e+00,8.010610888857480627e-02,-6.606586678382438960e-01,1.361524071352429588e-01,1.000000009657574074e+00,0.000000000000000000e+00 +4.449875969456198277e+01,3.022882447656446629e+02,6.840218314290302803e-02,3.814539755613739480e+00,8.060610888857480671e-02,-6.580383087730553582e-01,1.361524071352429588e-01,1.000000009664624434e+00,0.000000000000000000e+00 +4.450138124280650942e+01,3.022982122965066765e+02,6.920737163917770052e-02,3.812814676440545281e+00,8.110610888857480716e-02,-6.554167605031940846e-01,1.361524071352429588e-01,1.000000009777314292e+00,0.000000000000000000e+00 +4.450400397715071676e+01,3.023081794235285429e+02,7.001754380002717104e-02,3.811095692393004164e+00,8.160610888857480760e-02,-6.527940261333430305e-01,1.361524071352429588e-01,1.000000009673686741e+00,0.000000000000000000e+00 +4.450662789447191159e+01,3.023181461442184172e+02,7.083269942290840171e-02,3.809382814840660547e+00,8.210610888857480805e-02,-6.501701087867655104e-01,1.361524071352429588e-01,1.000000009709147264e+00,0.000000000000000000e+00 +4.450925299162965842e+01,3.023281124560846820e+02,7.165283830403249010e-02,3.807676055136033799e+00,8.260610888857480849e-02,-6.475450116035332826e-01,1.361524071352429588e-01,1.000000009688913005e+00,0.000000000000000000e+00 +4.451187926546577245e+01,3.023380783566357195e+02,7.247796023836472479e-02,3.805975424614353564e+00,8.310610888857480893e-02,-6.449187377419739464e-01,1.361524071352429588e-01,1.000000009705332538e+00,0.000000000000000000e+00 +4.451450671280432658e+01,3.023480438433800828e+02,7.330806501962462696e-02,3.804280934593290642e+00,8.360610888857480938e-02,-6.422912903779209870e-01,1.361524071352429588e-01,1.000000009685054092e+00,0.000000000000000000e+00 +4.451713533045163729e+01,3.023580089138263816e+02,7.414315244028600593e-02,3.802592596372689204e+00,8.410610888857480982e-02,-6.396626727051518690e-01,1.361524071352429588e-01,1.000000009709304694e+00,0.000000000000000000e+00 +4.451976511519627167e+01,3.023679735654833394e+02,7.498322229157700081e-02,3.800910421234297232e+00,8.460610888857481027e-02,-6.370328879349842488e-01,1.361524071352429588e-01,1.000000009690841463e+00,0.000000000000000000e+00 +4.452239606380904036e+01,3.023779377958598502e+02,7.582827436348016370e-02,3.799234420441497395e+00,8.510610888857481071e-02,-6.344019392967206183e-01,1.361524071352429588e-01,1.000000009694034020e+00,0.000000000000000000e+00 +4.452502817304299754e+01,3.023879016024648081e+02,7.667830844473247365e-02,3.797564605239036162e+00,8.560610888857481116e-02,-6.317698300372508458e-01,1.361524071352429588e-01,1.000000009739810958e+00,0.000000000000000000e+00 +4.452766143963343382e+01,3.023978649828072776e+02,7.753332432282541986e-02,3.795900986852753345e+00,8.610610888857481160e-02,-6.291365634211668612e-01,1.361524071352429588e-01,1.000000009676824897e+00,0.000000000000000000e+00 +4.453029586029789044e+01,3.024078279343963800e+02,7.839332178400502948e-02,3.794243576489310765e+00,8.660610888857481204e-02,-6.265021427312164048e-01,1.361524071352429588e-01,1.000000009691853542e+00,0.000000000000000000e+00 +4.453293143173615221e+01,3.024177904547414073e+02,7.925830061327195086e-02,3.792592385335919136e+00,8.710610888857481249e-02,-6.238665712674119623e-01,1.361524071352429588e-01,1.000000009668143841e+00,0.000000000000000000e+00 +4.453556815063024032e+01,3.024277525413517083e+02,8.012826059438148130e-02,3.790947424560066725e+00,8.760610888857481293e-02,-6.212298523478290146e-01,1.361524071352429588e-01,1.000000009695062975e+00,0.000000000000000000e+00 +4.453820601364443377e+01,3.024377141917368021e+02,8.100320150984362255e-02,3.789308705309245351e+00,8.810610888857481338e-02,-6.185919893080610299e-01,1.361524071352429588e-01,1.000000009747646912e+00,0.000000000000000000e+00 +4.454084501742525504e+01,3.024476754034062083e+02,8.188312314092315025e-02,3.787676238710677268e+00,8.860610888857481382e-02,-6.159529855015183353e-01,1.361524071352429588e-01,1.000000009621054842e+00,0.000000000000000000e+00 +4.454348515860147018e+01,3.024576361738696733e+02,8.276802526763966938e-02,3.786050035871040720e+00,8.910610888857481426e-02,-6.133128442999000729e-01,1.361524071352429588e-01,1.000000009757185948e+00,0.000000000000000000e+00 +4.454612643378411718e+01,3.024675965006370006e+02,8.365790766876765594e-02,3.784430107876193716e+00,8.960610888857481471e-02,-6.106715690914832351e-01,1.361524071352429588e-01,1.000000009650622523e+00,0.000000000000000000e+00 +4.454876883956647760e+01,3.024775563812181076e+02,8.455277012183649854e-02,3.782816465790901805e+00,9.010610888857481515e-02,-6.080291632836195559e-01,1.361524071352429588e-01,1.000000009693529757e+00,0.000000000000000000e+00 +4.455141237252411202e+01,3.024875158131230251e+02,8.545261240313059559e-02,3.781209120658558742e+00,9.060610888857481560e-02,-6.053856303003600781e-01,1.361524071352429588e-01,1.000000009646109023e+00,0.000000000000000000e+00 +4.455405702921483879e+01,3.024974747938618975e+02,8.635743428768938301e-02,3.779608083500912930e+00,9.110610888857481604e-02,-6.027409735841191551e-01,1.361524071352429588e-01,1.000000009716631721e+00,0.000000000000000000e+00 +4.455670280617876955e+01,3.025074333209449833e+02,8.726723554930740367e-02,3.778013365317788974e+00,9.160610888857481648e-02,-6.000951965944838484e-01,1.361524071352429588e-01,1.000000009732895823e+00,0.000000000000000000e+00 +4.455934969993828076e+01,3.025173913918826543e+02,8.818201596053433511e-02,3.776424977086811907e+00,9.210610888857481693e-02,-5.974483028092132386e-01,1.361524071352429588e-01,1.000000009649600008e+00,0.000000000000000000e+00 +4.456199770699804930e+01,3.025273490041853393e+02,8.910177529267507279e-02,3.774842929763128296e+00,9.260610888857481737e-02,-5.948002957238957000e-01,1.361524071352429588e-01,1.000000009672009416e+00,0.000000000000000000e+00 +4.456464682384504528e+01,3.025373061553636944e+02,9.002651331578979954e-02,3.773267234279127802e+00,9.310610888857481782e-02,-5.921511788512772156e-01,1.361524071352429588e-01,1.000000009684162805e+00,0.000000000000000000e+00 +4.456729704694855343e+01,3.025472628429284327e+02,9.095622979869401326e-02,3.771697901544166065e+00,9.360610888857481826e-02,-5.895009557221030372e-01,1.361524071352429588e-01,1.000000009690905411e+00,0.000000000000000000e+00 +4.456994837276017307e+01,3.025572190643903241e+02,9.189092450895859632e-02,3.770134942444284931e+00,9.410610888857481870e-02,-5.868496298847885040e-01,1.361524071352429588e-01,1.000000009689017144e+00,0.000000000000000000e+00 +4.457260079771383232e+01,3.025671748172603657e+02,9.283059721290988497e-02,3.768578367841933119e+00,9.460610888857481915e-02,-5.841972049054303673e-01,1.361524071352429588e-01,1.000000009665476863e+00,0.000000000000000000e+00 +4.457525431822579520e+01,3.025771300990496115e+02,9.377524767562969710e-02,3.767028188575686443e+00,9.510610888857481959e-02,-5.815436843678221113e-01,1.361524071352429588e-01,1.000000009658923439e+00,0.000000000000000000e+00 +4.457790893069466875e+01,3.025870849072692295e+02,9.472487566095542932e-02,3.765484415459967593e+00,9.560610888857482004e-02,-5.788890718733055163e-01,1.361524071352429588e-01,1.000000009694042236e+00,0.000000000000000000e+00 +4.458056463150143145e+01,3.025970392394305009e+02,9.567948093148008482e-02,3.763947059284765917e+00,9.610610888857482048e-02,-5.762333710407955278e-01,1.361524071352429588e-01,1.000000009717537441e+00,0.000000000000000000e+00 +4.458322141700943320e+01,3.026069930930448777e+02,9.663906324855234264e-02,3.762416130815356752e+00,9.660610888857482093e-02,-5.735765855069746566e-01,1.361524071352429588e-01,1.000000009658732258e+00,0.000000000000000000e+00 +4.458587928356440955e+01,3.026169464656239256e+02,9.760362237227664106e-02,3.760891640792019874e+00,9.710610888857482137e-02,-5.709187189263260631e-01,1.361524071352429588e-01,1.000000009616955676e+00,0.000000000000000000e+00 +4.458853822749449591e+01,3.026268993546792103e+02,9.857315806151320525e-02,3.759373599929757503e+00,9.760610888857482181e-02,-5.682597749706678192e-01,1.361524071352429588e-01,1.000000009732478157e+00,0.000000000000000000e+00 +4.459119824511024888e+01,3.026368517577225816e+02,9.954767007387811673e-02,3.757862018918013192e+00,9.810610888857482226e-02,-5.655997573290288960e-01,1.361524071352429588e-01,1.000000009620822583e+00,0.000000000000000000e+00 +4.459385933270464619e+01,3.026468036722659463e+02,1.005271581657433688e-01,3.756356908420390717e+00,9.860610888857482270e-02,-5.629386697090296154e-01,1.361524071352429588e-01,1.000000009751002894e+00,0.000000000000000000e+00 +4.459652148655312232e+01,3.026567550958212678e+02,1.015116220922369500e-01,3.754858279074368976e+00,9.910610888857482315e-02,-5.602765158345951457e-01,1.361524071352429588e-01,1.000000009624660624e+00,0.000000000000000000e+00 +4.459918470291356840e+01,3.026667060259007371e+02,1.025010616072428854e-01,3.753366141491022656e+00,9.960610888857482359e-02,-5.576132994485131222e-01,1.361524071352429588e-01,1.000000009654756550e+00,0.000000000000000000e+00 +4.460184897802636783e+01,3.026766564600166021e+02,1.034954764634012925e-01,3.751880506254735792e+00,1.001061088885748240e-01,-5.549490243099903797e-01,1.361524071352429588e-01,1.000000009659368194e+00,0.000000000000000000e+00 +4.460451430811439621e+01,3.026866063956812241e+02,1.044948664121084780e-01,3.750401383922921550e+00,1.006061088885748245e-01,-5.522836941962186996e-01,1.361524071352429588e-01,1.000000009737090467e+00,0.000000000000000000e+00 +4.460718068938304270e+01,3.026965558304071919e+02,1.054992312035169522e-01,3.748928785025737564e+00,1.011061088885748249e-01,-5.496173129016088676e-01,1.361524071352429588e-01,1.000000009576930360e+00,0.000000000000000000e+00 +4.460984811802024552e+01,3.027065047617070945e+02,1.065085705865355115e-01,3.747462720065803055e+00,1.016061088885748254e-01,-5.469498842388633708e-01,1.361524071352429588e-01,1.000000009705343640e+00,0.000000000000000000e+00 +4.461251659019648486e+01,3.027164531870936912e+02,1.075228843088293224e-01,3.746003199517912829e+00,1.021061088885748258e-01,-5.442814120367228670e-01,1.361524071352429588e-01,1.000000009673762902e+00,0.000000000000000000e+00 +4.461518610206483970e+01,3.027264011040799119e+02,1.085421721168199627e-01,3.744550233828757069e+00,1.026061088885748263e-01,-5.416119001425460100e-01,1.361524071352429588e-01,1.000000009679251400e+00,0.000000000000000000e+00 +4.461785664976097365e+01,3.027363485101787433e+02,1.095664337556854911e-01,3.743103833416633996e+00,1.031061088885748267e-01,-5.389413524205656225e-01,1.361524071352429588e-01,1.000000009626795583e+00,0.000000000000000000e+00 +4.462052822940317753e+01,3.027462954029033426e+02,1.105956689693605027e-01,3.741664008671166997e+00,1.036061088885748271e-01,-5.362697727526459790e-01,1.361524071352429588e-01,1.000000009687793678e+00,0.000000000000000000e+00 +4.462320083709238361e+01,3.027562417797669809e+02,1.116298775005361843e-01,3.740230769953019507e+00,1.041061088885748276e-01,-5.335971650375482822e-01,1.361524071352429588e-01,1.000000009675453105e+00,0.000000000000000000e+00 +4.462587446891220111e+01,3.027661876382830997e+02,1.126690590906604256e-01,3.738804127593611693e+00,1.046061088885748280e-01,-5.309235331918640277e-01,1.361524071352429588e-01,1.000000009603552842e+00,0.000000000000000000e+00 +4.462854912092892334e+01,3.027761329759651971e+02,1.137132134799378191e-01,3.737384091894834448e+00,1.051061088885748285e-01,-5.282488811494550074e-01,1.361524071352429588e-01,1.000000009682558977e+00,0.000000000000000000e+00 +4.463122478919157032e+01,3.027860777903269991e+02,1.147623404073297854e-01,3.735970673128764741e+00,1.056061088885748289e-01,-5.255732128609019727e-01,1.361524071352429588e-01,1.000000009635687359e+00,0.000000000000000000e+00 +4.463390146973189587e+01,3.027960220788822312e+02,1.158164396105546001e-01,3.734563881537382279e+00,1.061061088885748294e-01,-5.228965322947822791e-01,1.361524071352429588e-01,1.000000009689382852e+00,0.000000000000000000e+00 +4.463657915856443736e+01,3.028059658391448465e+02,1.168755108260874503e-01,3.733163727332282633e+00,1.066061088885748298e-01,-5.202188434362970959e-01,1.361524071352429588e-01,1.000000009640844789e+00,0.000000000000000000e+00 +4.463925785168651572e+01,3.028159090686289119e+02,1.179395537891605589e-01,3.731770220694393903e+00,1.071061088885748303e-01,-5.175401502883931748e-01,1.361524071352429588e-01,1.000000009661582423e+00,0.000000000000000000e+00 +4.464193754507828515e+01,3.028258517648486077e+02,1.190085682337631706e-01,3.730383371773690282e+00,1.076061088885748307e-01,-5.148604568707327855e-01,1.361524071352429588e-01,1.000000009675796164e+00,0.000000000000000000e+00 +4.464461823470275448e+01,3.028357939253182849e+02,1.200825538926416913e-01,3.729003190688908287e+00,1.081061088885748311e-01,-5.121797672203274310e-01,1.361524071352429588e-01,1.000000009606238915e+00,0.000000000000000000e+00 +4.464729991650580843e+01,3.028457355475523514e+02,1.211615104972997153e-01,3.727629687527261204e+00,1.086061088885748316e-01,-5.094980853915127561e-01,1.361524071352429588e-01,1.000000009618785324e+00,0.000000000000000000e+00 +4.464998258641625029e+01,3.028556766290654423e+02,1.222454377779980950e-01,3.726262872344153543e+00,1.091061088885748320e-01,-5.068154154552666490e-01,1.361524071352429588e-01,1.000000009749429264e+00,0.000000000000000000e+00 +4.465266624034582321e+01,3.028656171673723065e+02,1.233343354637550099e-01,3.724902755162897261e+00,1.096061088885748325e-01,-5.041317614995264318e-01,1.361524071352429588e-01,1.000000009594301131e+00,0.000000000000000000e+00 +4.465535087418925286e+01,3.028755571599877499e+02,1.244282032823460504e-01,3.723549345974427105e+00,1.101061088885748329e-01,-5.014471276303381631e-01,1.361524071352429588e-01,1.000000009602603157e+00,0.000000000000000000e+00 +4.465803648382426871e+01,3.028854966044268053e+02,1.255270409603042592e-01,3.722202654737012839e+00,1.106061088885748334e-01,-4.987615179695350509e-01,1.361524071352429588e-01,1.000000009716981886e+00,0.000000000000000000e+00 +4.466072306511163248e+01,3.028954354982046198e+02,1.266308482229202281e-01,3.720862691375977693e+00,1.111061088885748338e-01,-4.960749366560637252e-01,1.361524071352429588e-01,1.000000009557945990e+00,0.000000000000000000e+00 +4.466341061389519496e+01,3.029053738388364536e+02,1.277396247942421403e-01,3.719529465783413258e+00,1.116061088885748342e-01,-4.933873878468166274e-01,1.361524071352429588e-01,1.000000009713279958e+00,0.000000000000000000e+00 +4.466609912600189602e+01,3.029153116238377379e+02,1.288533703970758670e-01,3.718202987817892158e+00,1.121061088885748347e-01,-4.906988757139986168e-01,1.361524071352429588e-01,1.000000009644222754e+00,0.000000000000000000e+00 +4.466878859724183570e+01,3.029252488507240173e+02,1.299720847529850232e-01,3.716883267304187832e+00,1.126061088885748351e-01,-4.880094044481194659e-01,1.361524071352429588e-01,1.000000009589926186e+00,0.000000000000000000e+00 +4.467147902340828836e+01,3.029351855170110071e+02,1.310957675822910229e-01,3.715570314032986321e+00,1.131061088885748356e-01,-4.853189782558672283e-01,1.361524071352429588e-01,1.000000009703363446e+00,0.000000000000000000e+00 +4.467417040027773822e+01,3.029451216202145361e+02,1.322244186040731351e-01,3.714264137760603823e+00,1.136061088885748360e-01,-4.826276013603027493e-01,1.361524071352429588e-01,1.000000009559837366e+00,0.000000000000000000e+00 +4.467686272360992916e+01,3.029550571578505469e+02,1.333580375361686499e-01,3.712964748208703814e+00,1.141061088885748365e-01,-4.799352780023771192e-01,1.361524071352429588e-01,1.000000009686858427e+00,0.000000000000000000e+00 +4.467955598914788595e+01,3.029649921274352096e+02,1.344966240951728231e-01,3.711672155064010159e+00,1.146061088885748369e-01,-4.772420124383307538e-01,1.361524071352429588e-01,1.000000009662321165e+00,0.000000000000000000e+00 +4.468225019261797115e+01,3.029749265264846940e+02,1.356401779964390153e-01,3.710386367978027344e+00,1.151061088885748374e-01,-4.745478089422111578e-01,1.361524071352429588e-01,1.000000009582560301e+00,0.000000000000000000e+00 +4.468494532972992062e+01,3.029848603525154545e+02,1.367886989540787468e-01,3.709107396566754034e+00,1.156061088885748378e-01,-4.718526718044377954e-01,1.361524071352429588e-01,1.000000009630689135e+00,0.000000000000000000e+00 +4.468764139617686482e+01,3.029947936030440587e+02,1.379421866809618091e-01,3.707835250410400629e+00,1.161061088885748382e-01,-4.691566053315275875e-01,1.361524071352429588e-01,1.000000009646537791e+00,0.000000000000000000e+00 +4.469033838763539990e+01,3.030047262755871884e+02,1.391006408887162649e-01,3.706569939053107721e+00,1.166061088885748387e-01,-4.664596138469791486e-01,1.361524071352429588e-01,1.000000009613827734e+00,0.000000000000000000e+00 +4.469303629976559478e+01,3.030146583676616387e+02,1.402640612877285586e-01,3.705311472002662310e+00,1.171061088885748391e-01,-4.637617016908435197e-01,1.361524071352429588e-01,1.000000009656977218e+00,0.000000000000000000e+00 +4.469573512821107641e+01,3.030245898767843755e+02,1.414324475871436004e-01,3.704059858730215371e+00,1.176061088885748396e-01,-4.610628732193021162e-01,1.361524071352429588e-01,1.000000009612270979e+00,0.000000000000000000e+00 +4.469843486859902981e+01,3.030345208004725919e+02,1.426057994948648489e-01,3.702815108670000743e+00,1.181061088885748400e-01,-4.583631328054010301e-01,1.361524071352429588e-01,1.000000009634970821e+00,0.000000000000000000e+00 +4.470113551654026196e+01,3.030444511362434810e+02,1.437841167175543111e-01,3.701577231219052244e+00,1.186061088885748405e-01,-4.556624848381463089e-01,1.361524071352429588e-01,1.000000009648459365e+00,0.000000000000000000e+00 +4.470383706762925868e+01,3.030543808816145201e+02,1.449673989606326818e-01,3.700346235736923450e+00,1.191061088885748409e-01,-4.529609337230852129e-01,1.361524071352429588e-01,1.000000009585939154e+00,0.000000000000000000e+00 +4.470653951744420596e+01,3.030643100341032437e+02,1.461556459282794262e-01,3.699122131545406145e+00,1.196061088885748414e-01,-4.502584838822346058e-01,1.361524071352429588e-01,1.000000009630943376e+00,0.000000000000000000e+00 +4.470924286154704674e+01,3.030742385912273562e+02,1.473488573234327803e-01,3.697904927928249208e+00,1.201061088885748418e-01,-4.475551397533583664e-01,1.361524071352429588e-01,1.000000009607106888e+00,0.000000000000000000e+00 +4.471194709548353075e+01,3.030841665505047331e+02,1.485470328477899171e-01,3.696694634130879731e+00,1.206061088885748422e-01,-4.448509057908931474e-01,1.361524071352429588e-01,1.000000009644259391e+00,0.000000000000000000e+00 +4.471465221478326413e+01,3.030940939094533633e+02,1.497501722018069747e-01,3.695491259360121905e+00,1.211061088885748427e-01,-4.421457864650731318e-01,1.361524071352429588e-01,1.000000009568955406e+00,0.000000000000000000e+00 +4.471735821495974506e+01,3.031040206655914062e+02,1.509582750846991117e-01,3.694294812783918580e+00,1.216061088885748431e-01,-4.394397862627019147e-01,1.361524071352429588e-01,1.000000009690620084e+00,0.000000000000000000e+00 +4.472006509151042053e+01,3.031139468164371920e+02,1.521713411944405903e-01,3.693105303531051042e+00,1.221061088885748436e-01,-4.367329096857969772e-01,1.361524071352429588e-01,1.000000009586372807e+00,0.000000000000000000e+00 +4.472277283991673613e+01,3.031238723595091642e+02,1.533893702277649151e-01,3.691922740690862792e+00,1.226061088885748440e-01,-4.340251612535216963e-01,1.361524071352429588e-01,1.000000009553951630e+00,0.000000000000000000e+00 +4.472548145564419286e+01,3.031337972923259940e+02,1.546123618801648336e-01,3.690747133312978434e+00,1.231061088885748445e-01,-4.313165455001843895e-01,1.361524071352429588e-01,1.000000009699150150e+00,0.000000000000000000e+00 +4.472819093414238978e+01,3.031437216124064093e+02,1.558403158458924187e-01,3.689578490407028344e+00,1.236061088885748449e-01,-4.286070669757060525e-01,1.361524071352429588e-01,1.000000009571799575e+00,0.000000000000000000e+00 +4.473090127084508083e+01,3.031536453172693086e+02,1.570732318179592080e-01,3.688416820942372443e+00,1.241061088885748454e-01,-4.258967302470748062e-01,1.361524071352429588e-01,1.000000009614883556e+00,0.000000000000000000e+00 +4.473361246117021750e+01,3.031635684044337609e+02,1.583111094881362035e-01,3.687262133847820422e+00,1.246061088885748458e-01,-4.231855398958731529e-01,1.361524071352429588e-01,1.000000009589346650e+00,0.000000000000000000e+00 +4.473632450052001275e+01,3.031734908714190624e+02,1.595539485469540109e-01,3.686114438011359073e+00,1.251061088885748462e-01,-4.204735005200726516e-01,1.361524071352429588e-01,1.000000009600121809e+00,0.000000000000000000e+00 +4.473903738428099075e+01,3.031834127157445096e+02,1.608017486837028387e-01,3.684973742279875175e+00,1.256061088885748467e-01,-4.177606167330472631e-01,1.361524071352429588e-01,1.000000009669798962e+00,0.000000000000000000e+00 +4.474175110782405795e+01,3.031933339349296830e+02,1.620545095864326934e-01,3.683840055458881491e+00,1.261061088885748471e-01,-4.150468931637414371e-01,1.361524071352429588e-01,1.000000009556460512e+00,0.000000000000000000e+00 +4.474446566650452439e+01,3.032032545264942769e+02,1.633122309419533513e-01,3.682713386312242765e+00,1.266061088885748476e-01,-4.123323344573323057e-01,1.361524071352429588e-01,1.000000009594659511e+00,0.000000000000000000e+00 +4.474718105566219606e+01,3.032131744879581561e+02,1.645749124358344695e-01,3.681593743561900389e+00,1.271061088885748480e-01,-4.096169452736086458e-01,1.361524071352429588e-01,1.000000009608124740e+00,0.000000000000000000e+00 +4.474989727062141043e+01,3.032230938168413559e+02,1.658425537524056692e-01,3.680481135887601951e+00,1.276061088885748485e-01,-4.069007302883000388e-01,1.361524071352429588e-01,1.000000009570463755e+00,0.000000000000000000e+00 +4.475261430669109330e+01,3.032330125106639684e+02,1.671151545747566469e-01,3.679375571926627675e+00,1.281061088885748489e-01,-4.041836941926122417e-01,1.361524071352429588e-01,1.000000009662465494e+00,0.000000000000000000e+00 +4.475533215916483698e+01,3.032429305669463702e+02,1.683927145847372020e-01,3.678277060273518639e+00,1.286061088885748493e-01,-4.014658416926054629e-01,1.361524071352429588e-01,1.000000009548210667e+00,0.000000000000000000e+00 +4.475805082332094287e+01,3.032528479832090511e+02,1.696752334629573200e-01,3.677185609479807216e+00,1.291061088885748498e-01,-3.987471775105390637e-01,1.361524071352429588e-01,1.000000009634773424e+00,0.000000000000000000e+00 +4.476077029442248545e+01,3.032627647569726150e+02,1.709627108887873115e-01,3.676101228053744396e+00,1.296061088885748502e-01,-3.960277063827918886e-01,1.361524071352429588e-01,1.000000009567812320e+00,0.000000000000000000e+00 +4.476349056771737622e+01,3.032726808857578931e+02,1.722551465403578119e-01,3.675023924460033342e+00,1.301061088885748507e-01,-3.933074330618712700e-01,1.361524071352429588e-01,1.000000009550372715e+00,0.000000000000000000e+00 +4.476621163843842766e+01,3.032825963670858869e+02,1.735525400945599206e-01,3.673953707119558043e+00,1.306061088885748511e-01,-3.905863623148357888e-01,1.361524071352429588e-01,1.000000009620076291e+00,0.000000000000000000e+00 +4.476893350180339581e+01,3.032925111984776549e+02,1.748548912270452560e-01,3.672890584409116865e+00,1.311061088885748516e-01,-3.878644989236824658e-01,1.361524071352429588e-01,1.000000009646584642e+00,0.000000000000000000e+00 +4.477165615301507273e+01,3.033024253774545400e+02,1.761621996122260392e-01,3.671834564661155653e+00,1.316061088885748520e-01,-3.851418476857407791e-01,1.361524071352429588e-01,1.000000009509779408e+00,0.000000000000000000e+00 +4.477437958726133616e+01,3.033123389015379985e+02,1.774744649232751770e-01,3.670785656163500388e+00,1.321061088885748525e-01,-3.824184134135813484e-01,1.361524071352429588e-01,1.000000009635672926e+00,0.000000000000000000e+00 +4.477710379971520638e+01,3.033222517682496573e+02,1.787916868321263730e-01,3.669743867159090733e+00,1.326061088885748529e-01,-3.796942009334638990e-01,1.361524071352429588e-01,1.000000009556912595e+00,0.000000000000000000e+00 +4.477982878553492441e+01,3.033321639751112571e+02,1.801138650094741278e-01,3.668709205845718468e+00,1.331061088885748533e-01,-3.769692150877049786e-01,1.361524071352429588e-01,1.000000009586820893e+00,0.000000000000000000e+00 +4.478255453986401591e+01,3.033420755196447658e+02,1.814409991247739051e-01,3.667681680375760145e+00,1.336061088885748538e-01,-3.742434607324853779e-01,1.361524071352429588e-01,1.000000009560077396e+00,0.000000000000000000e+00 +4.478528105783134805e+01,3.033519863993723220e+02,1.827730888462422154e-01,3.666661298855916407e+00,1.341061088885748542e-01,-3.715169427390873635e-01,1.361524071352429588e-01,1.000000009607840079e+00,0.000000000000000000e+00 +4.478800833455121477e+01,3.033618966118161779e+02,1.841101338408565880e-01,3.665648069346948645e+00,1.346061088885748547e-01,-3.687896659930190446e-01,1.361524071352429588e-01,1.000000009557781899e+00,0.000000000000000000e+00 +4.479073636512338652e+01,3.033718061544988132e+02,1.854521337743558207e-01,3.664641999863418764e+00,1.351061088885748551e-01,-3.660616353947735990e-01,1.361524071352429588e-01,1.000000009588572825e+00,0.000000000000000000e+00 +4.479346514463319551e+01,3.033817150249427641e+02,1.867990883112399247e-01,3.663643098373427609e+00,1.356061088885748556e-01,-3.633328558588029833e-01,1.361524071352429588e-01,1.000000009570771509e+00,0.000000000000000000e+00 +4.479619466815158546e+01,3.033916232206709083e+02,1.881509971147702631e-01,3.662651372798356952e+00,1.361061088885748560e-01,-3.606033323142886493e-01,1.361524071352429588e-01,1.000000009541910595e+00,0.000000000000000000e+00 +4.479892493073520399e+01,3.034015307392061231e+02,1.895078598469696618e-01,3.661666831012610146e+00,1.366061088885748565e-01,-3.578730697046155762e-01,1.361524071352429588e-01,1.000000009584474547e+00,0.000000000000000000e+00 +4.480165592742646652e+01,3.034114375780715704e+02,1.908696761686224097e-01,3.660689480843354993e+00,1.371061088885748569e-01,-3.551420729871782034e-01,1.361524071352429588e-01,1.000000009585321648e+00,0.000000000000000000e+00 +4.480438765325362027e+01,3.034213437347905256e+02,1.922364457392744530e-01,3.659719330070267951e+00,1.376061088885748573e-01,-3.524103471338426719e-01,1.361524071352429588e-01,1.000000009590878536e+00,0.000000000000000000e+00 +4.480712010323081529e+01,3.034312492068864913e+02,1.936081682172334228e-01,3.658756386425277896e+00,1.381061088885748578e-01,-3.496778971304385086e-01,1.361524071352429588e-01,1.000000009506743837e+00,0.000000000000000000e+00 +4.480985327235819682e+01,3.034411539918830272e+02,1.949848432595686909e-01,3.657800657592312099e+00,1.386061088885748582e-01,-3.469447279770700443e-01,1.361524071352429588e-01,1.000000009630737097e+00,0.000000000000000000e+00 +4.481258715562196926e+01,3.034510580873039771e+02,1.963664705221115081e-01,3.656852151207042212e+00,1.391061088885748587e-01,-3.442108446869703298e-01,1.361524071352429588e-01,1.000000009520787936e+00,0.000000000000000000e+00 +4.481532174799445301e+01,3.034609614906732986e+02,1.977530496594550602e-01,3.655910874856634241e+00,1.396061088885748591e-01,-3.414762522884488005e-01,1.361524071352429588e-01,1.000000009538110302e+00,0.000000000000000000e+00 +4.481805704443419103e+01,3.034708641995151766e+02,1.991445803249545787e-01,3.654976836079494085e+00,1.401061088885748596e-01,-3.387409558226198159e-01,1.361524071352429588e-01,1.000000009596578421e+00,0.000000000000000000e+00 +4.482079303988600572e+01,3.034807662113539095e+02,2.005410621707273966e-01,3.654050042365020179e+00,1.406061088885748600e-01,-3.360049603445493527e-01,1.361524071352429588e-01,1.000000009517507449e+00,0.000000000000000000e+00 +4.482352972928107704e+01,3.034906675237140234e+02,2.019424948476530590e-01,3.653130501153353915e+00,1.411061088885748604e-01,-3.332682709234316420e-01,1.361524071352429588e-01,1.000000009619870012e+00,0.000000000000000000e+00 +4.482626710753702781e+01,3.035005681341201580e+02,2.033488780053734069e-01,3.652218219835130508e+00,1.416061088885748609e-01,-3.305308926411497650e-01,1.361524071352429588e-01,1.000000009473139828e+00,0.000000000000000000e+00 +4.482900516955798764e+01,3.035104680400971233e+02,2.047602112922926598e-01,3.651313205751234747e+00,1.421061088885748613e-01,-3.277928305942486298e-01,1.361524071352429588e-01,1.000000009613321916e+00,0.000000000000000000e+00 +4.483174391023469951e+01,3.035203672391700138e+02,2.061764943555774998e-01,3.650415466192552305e+00,1.426061088885748618e-01,-3.250540898912100407e-01,1.361524071352429588e-01,1.000000009526544442e+00,0.000000000000000000e+00 +4.483448332444456241e+01,3.035302657288639807e+02,2.075977268411571819e-01,3.649525008399729487e+00,1.431061088885748622e-01,-3.223146756552475733e-01,1.361524071352429588e-01,1.000000009541791579e+00,0.000000000000000000e+00 +4.483722340705174503e+01,3.035401635067044595e+02,2.090239083937235620e-01,3.648641839562926314e+00,1.436061088885748627e-01,-3.195745930219180408e-01,1.361524071352429588e-01,1.000000009525991107e+00,0.000000000000000000e+00 +4.483996415290724968e+01,3.035500605702169423e+02,2.104550386567312914e-01,3.647765966821577166e+00,1.441061088885748631e-01,-3.168338471403058798e-01,1.361524071352429588e-01,1.000000009591788475e+00,0.000000000000000000e+00 +4.484270555684899051e+01,3.035599569169272058e+02,2.118911172723977887e-01,3.646897397264149188e+00,1.446061088885748636e-01,-3.140924431722680876e-01,1.361524071352429588e-01,1.000000009504084852e+00,0.000000000000000000e+00 +4.484544761370189292e+01,3.035698525443611402e+02,2.133321438817034343e-01,3.646036137927903820e+00,1.451061088885748640e-01,-3.113503862933049704e-01,1.361524071352429588e-01,1.000000009564080639e+00,0.000000000000000000e+00 +4.484819031827795754e+01,3.035797474500448629e+02,2.147781181243915705e-01,3.645182195798656988e+00,1.456061088885748644e-01,-3.086076816910066634e-01,1.361524071352429588e-01,1.000000009543334789e+00,0.000000000000000000e+00 +4.485093366537635973e+01,3.035896416315046054e+02,2.162290396389686398e-01,3.644335577810544624e+00,1.461061088885748649e-01,-3.058643345664214808e-01,1.361524071352429588e-01,1.000000009508737575e+00,0.000000000000000000e+00 +4.485367764978352767e+01,3.035995350862668829e+02,2.176849080627042687e-01,3.643496290845785524e+00,1.466061088885748653e-01,-3.031203501331615757e-01,1.361524071352429588e-01,1.000000009524544708e+00,0.000000000000000000e+00 +4.485642226627322060e+01,3.036094278118582679e+02,2.191457230316313509e-01,3.642664341734447753e+00,1.471061088885748658e-01,-3.003757336173247805e-01,1.361524071352429588e-01,1.000000009532144851e+00,0.000000000000000000e+00 +4.485916750960662824e+01,3.036193198058056169e+02,2.206114841805461579e-01,3.641839737254216391e+00,1.476061088885748662e-01,-2.976304902577458500e-01,1.361524071352429588e-01,1.000000009525049638e+00,0.000000000000000000e+00 +4.486191337453245609e+01,3.036292110656359000e+02,2.220821911430084228e-01,3.641022484130161718e+00,1.481061088885748667e-01,-2.948846253057669231e-01,1.361524071352429588e-01,1.000000009546245350e+00,0.000000000000000000e+00 +4.486465985578698934e+01,3.036391015888763718e+02,2.235578435513413953e-01,3.640212589034509172e+00,1.486061088885748671e-01,-2.921381440250144235e-01,1.361524071352429588e-01,1.000000009568168702e+00,0.000000000000000000e+00 +4.486740694809421370e+01,3.036489913730543435e+02,2.250384410366320087e-01,3.639410058586411090e+00,1.491061088885748676e-01,-2.893910516915048636e-01,1.361524071352429588e-01,1.000000009490725317e+00,0.000000000000000000e+00 +4.487015464616588645e+01,3.036588804156973538e+02,2.265239832287308797e-01,3.638614899351719334e+00,1.496061088885748680e-01,-2.866433535937556454e-01,1.361524071352429588e-01,1.000000009491794239e+00,0.000000000000000000e+00 +4.487290294470162166e+01,3.036687687143331686e+02,2.280144697562524747e-01,3.637827117842758806e+00,1.501061088885748684e-01,-2.838950550319321309e-01,1.361524071352429588e-01,1.000000009554206759e+00,0.000000000000000000e+00 +4.487565183838899685e+01,3.036786562664897247e+02,2.295099002465751659e-01,3.637046720518104514e+00,1.506061088885748689e-01,-2.811461613182935082e-01,1.361524071352429588e-01,1.000000009464269590e+00,0.000000000000000000e+00 +4.487840132190362397e+01,3.036885430696951289e+02,2.310102743258413138e-01,3.636273713782358641e+00,1.511061088885748693e-01,-2.783966777776426538e-01,1.361524071352429588e-01,1.000000009572765913e+00,0.000000000000000000e+00 +4.488115138990925601e+01,3.036984291214776590e+02,2.325155916189574345e-01,3.635508103985927608e+00,1.516061088885748698e-01,-2.756466097456831132e-01,1.361524071352429588e-01,1.000000009500755516e+00,0.000000000000000000e+00 +4.488390203705787229e+01,3.037083144193658200e+02,2.340258517495942270e-01,3.634749897424804921e+00,1.521061088885748702e-01,-2.728959625709336811e-01,1.361524071352429588e-01,1.000000009488129615e+00,0.000000000000000000e+00 +4.488665325798977079e+01,3.037181989608882873e+02,2.355410543401866286e-01,3.633999100340350008e+00,1.526061088885748707e-01,-2.701447416129342805e-01,1.361524071352429588e-01,1.000000009510355614e+00,0.000000000000000000e+00 +4.488940504733365344e+01,3.037280827435739070e+02,2.370611990119340373e-01,3.633255718919073285e+00,1.531061088885748711e-01,-2.673929522428799554e-01,1.361524071352429588e-01,1.000000009511431198e+00,0.000000000000000000e+00 +4.489215739970673980e+01,3.037379657649517526e+02,2.385862853848002563e-01,3.632519759292420769e+00,1.536061088885748716e-01,-2.646405998436138218e-01,1.361524071352429588e-01,1.000000009518967392e+00,0.000000000000000000e+00 +4.489491030971484520e+01,3.037478480225510680e+02,2.401163130775137156e-01,3.631791227536560029e+00,1.541061088885748720e-01,-2.618876898093026595e-01,1.361524071352429588e-01,1.000000009524747213e+00,0.000000000000000000e+00 +4.489766377195248026e+01,3.037577295139013245e+02,2.416512817075675001e-01,3.631070129672168356e+00,1.546061088885748724e-01,-2.591342275454405208e-01,1.361524071352429588e-01,1.000000009424048208e+00,0.000000000000000000e+00 +4.490041778100295033e+01,3.037676102365321071e+02,2.431911908912194609e-01,3.630356471664222262e+00,1.551061088885748729e-01,-2.563802184690189279e-01,1.361524071352429588e-01,1.000000009540424895e+00,0.000000000000000000e+00 +4.490317233143844078e+01,3.037774901879732283e+02,2.447360402434923254e-01,3.629650259421787872e+00,1.556061088885748733e-01,-2.536256680072511704e-01,1.361524071352429588e-01,1.000000009511212928e+00,0.000000000000000000e+00 +4.490592741782012354e+01,3.037873693657547278e+02,2.462858293781737540e-01,3.628951498797816200e+00,1.561061088885748738e-01,-2.508705815993653720e-01,1.361524071352429588e-01,1.000000009514940169e+00,0.000000000000000000e+00 +4.490868303469824951e+01,3.037972477674067591e+02,2.478405579078164500e-01,3.628260195588934867e+00,1.566061088885748742e-01,-2.481149646950165100e-01,1.361524071352429588e-01,1.000000009449581118e+00,0.000000000000000000e+00 +4.491143917661226226e+01,3.038071253904597597e+02,2.494002254437383270e-01,3.627576355535245600e+00,1.571061088885748747e-01,-2.453588227549612366e-01,1.361524071352429588e-01,1.000000009457159500e+00,0.000000000000000000e+00 +4.491419583809086902e+01,3.038170022324443380e+02,2.509648315960224529e-01,3.626899984320121284e+00,1.576061088885748751e-01,-2.426021612502866909e-01,1.361524071352429588e-01,1.000000009512107546e+00,0.000000000000000000e+00 +4.491695301365215443e+01,3.038268782908912726e+02,2.525343759735173554e-01,3.626231087570006562e+00,1.581061088885748755e-01,-2.398449856627730414e-01,1.361524071352429588e-01,1.000000009536493373e+00,0.000000000000000000e+00 +4.491971069780369419e+01,3.038367535633315129e+02,2.541088581838369387e-01,3.625569670854218884e+00,1.586061088885748760e-01,-2.370873014849381177e-01,1.361524071352429588e-01,1.000000009398023026e+00,0.000000000000000000e+00 +4.492246888504262614e+01,3.038466280472962922e+02,2.556882778333606221e-01,3.624915739684750893e+00,1.591061088885748764e-01,-2.343291142200870925e-01,1.361524071352429588e-01,1.000000009549867119e+00,0.000000000000000000e+00 +4.492522756985577104e+01,3.038565017403169577e+02,2.572726345272335347e-01,3.624269299516074128e+00,1.596061088885748769e-01,-2.315704293805966318e-01,1.361524071352429588e-01,1.000000009452870042e+00,0.000000000000000000e+00 +4.492798674671973203e+01,3.038663746399250840e+02,2.588619278693665149e-01,3.623630355744948961e+00,1.601061088885748773e-01,-2.288112524905504264e-01,1.361524071352429588e-01,1.000000009441125881e+00,0.000000000000000000e+00 +4.493074641010100123e+01,3.038762467436524730e+02,2.604561574624362219e-01,3.622998913710228752e+00,1.606061088885748778e-01,-2.260515890832282271e-01,1.361524071352429588e-01,1.000000009494388165e+00,0.000000000000000000e+00 +4.493350655445604502e+01,3.038861180490310971e+02,2.620553229078852464e-01,3.622374978692672443e+00,1.611061088885748782e-01,-2.232914447019805071e-01,1.361524071352429588e-01,1.000000009469804940e+00,0.000000000000000000e+00 +4.493626717423141770e+01,3.038959885535930994e+02,2.636594238059222772e-01,3.621758555914756261e+00,1.616061088885748787e-01,-2.205308249004636900e-01,1.361524071352429588e-01,1.000000009507998389e+00,0.000000000000000000e+00 +4.493902826386387517e+01,3.039058582548709069e+02,2.652684597555220458e-01,3.621149650540486320e+00,1.621061088885748791e-01,-2.177697352417538867e-01,1.361524071352429588e-01,1.000000009390050071e+00,0.000000000000000000e+00 +4.494178981778046023e+01,3.039157271503970605e+02,2.668824303544256038e-01,3.620548267675215204e+00,1.626061088885748795e-01,-2.150081812992351293e-01,1.361524071352429588e-01,1.000000009525746636e+00,0.000000000000000000e+00 +4.494455183039862334e+01,3.039255952377043286e+02,2.685013351991403230e-01,3.619954412365457674e+00,1.631061088885748800e-01,-2.122461686547583437e-01,1.361524071352429588e-01,1.000000009437796544e+00,0.000000000000000000e+00 +4.494731429612632212e+01,3.039354625143257067e+02,2.701251738849400064e-01,3.619368089598713034e+00,1.636061088885748804e-01,-2.094837029009856411e-01,1.361524071352429588e-01,1.000000009448262617e+00,0.000000000000000000e+00 +4.495007720936212792e+01,3.039453289777943610e+02,2.717539460058649436e-01,3.618789304303282606e+00,1.641061088885748809e-01,-2.067207896390766131e-01,1.361524071352429588e-01,1.000000009454281802e+00,0.000000000000000000e+00 +4.495284056449532528e+01,3.039551946256436850e+02,2.733876511547221333e-01,3.618218061348095205e+00,1.646061088885748813e-01,-2.039574344797554228e-01,1.361524071352429588e-01,1.000000009450016547e+00,0.000000000000000000e+00 +4.495560435590602566e+01,3.039650594554072427e+02,2.750262889230853380e-01,3.617654365542531281e+00,1.651061088885748818e-01,-2.011936430429357436e-01,1.361524071352429588e-01,1.000000009466657014e+00,0.000000000000000000e+00 +4.495836857796528108e+01,3.039749234646188256e+02,2.766698589012950849e-01,3.617098221636249722e+00,1.656061088885748822e-01,-1.984294209575108159e-01,1.361524071352429588e-01,1.000000009396200706e+00,0.000000000000000000e+00 +4.496113322503518361e+01,3.039847866508124525e+02,2.783183606784588870e-01,3.616549634319016882e+00,1.661061088885748827e-01,-1.956647738616300869e-01,1.361524071352429588e-01,1.000000009512626020e+00,0.000000000000000000e+00 +4.496389829146897910e+01,3.039946490115223696e+02,2.799717938424512997e-01,3.616008608220536491e+00,1.666061088885748831e-01,-1.928997074015345592e-01,1.361524071352429588e-01,1.000000009366307063e+00,0.000000000000000000e+00 +4.496666377161115946e+01,3.040045105442829367e+02,2.816301579799140864e-01,3.615475147910284459e+00,1.671061088885748835e-01,-1.901342272334483052e-01,1.361524071352429588e-01,1.000000009524756983e+00,0.000000000000000000e+00 +4.496942965979760487e+01,3.040143712466287980e+02,2.832934526762561633e-01,3.614949257897340118e+00,1.676061088885748840e-01,-1.873683390206562771e-01,1.361524071352429588e-01,1.000000009364268028e+00,0.000000000000000000e+00 +4.497219595035566897e+01,3.040242311160947111e+02,2.849616775156538773e-01,3.614430942630227239e+00,1.681061088885748844e-01,-1.846020484366885095e-01,1.361524071352429588e-01,1.000000009448481331e+00,0.000000000000000000e+00 +4.497496263760429258e+01,3.040340901502157749e+02,2.866348320810510608e-01,3.613920206496747944e+00,1.686061088885748849e-01,-1.818353611619254739e-01,1.361524071352429588e-01,1.000000009437012283e+00,0.000000000000000000e+00 +4.497772971585411739e+01,3.040439483465272019e+02,2.883129159541590880e-01,3.613417053823827718e+00,1.691061088885748853e-01,-1.790682828859875841e-01,1.361524071352429588e-01,1.000000009418738012e+00,0.000000000000000000e+00 +4.498049717940759962e+01,3.040538057025644889e+02,2.899959287154569854e-01,3.612921488877355536e+00,1.696061088885748858e-01,-1.763008193064361795e-01,1.361524071352429588e-01,1.000000009445699112e+00,0.000000000000000000e+00 +4.498326502255913084e+01,3.040636622158632463e+02,2.916838699441915428e-01,3.612433515862029321e+00,1.701061088885748862e-01,-1.735329761287632833e-01,1.361524071352429588e-01,1.000000009415758839e+00,0.000000000000000000e+00 +4.498603323959512323e+01,3.040735178839593686e+02,2.933767392183774803e-01,3.611953138921203177e+00,1.706061088885748867e-01,-1.707647590667057957e-01,1.361524071352429588e-01,1.000000009418619440e+00,0.000000000000000000e+00 +4.498880182479415168e+01,3.040833727043889212e+02,2.950745361147975032e-01,3.611480362136735511e+00,1.711061088885748871e-01,-1.679961738416015371e-01,1.361524071352429588e-01,1.000000009386559308e+00,0.000000000000000000e+00 +4.499157077242705327e+01,3.040932266746881965e+02,2.967772602090023581e-01,3.611015189528840708e+00,1.716061088885748875e-01,-1.652272261827115729e-01,1.361524071352429588e-01,1.000000009440535020e+00,0.000000000000000000e+00 +4.499434007675703384e+01,3.041030797923937143e+02,2.984849110753110546e-01,3.610557625055941688e+00,1.721061088885748880e-01,-1.624579218265839176e-01,1.361524071352429588e-01,1.000000009425140224e+00,0.000000000000000000e+00 +4.499710973203981013e+01,3.041129320550422221e+02,3.001974882868108652e-01,3.610107672614526031e+00,1.726061088885748884e-01,-1.596882665177044580e-01,1.361524071352429588e-01,1.000000009370489717e+00,0.000000000000000000e+00 +4.499987973252368789e+01,3.041227834601705808e+02,3.019149914153575476e-01,3.609665336039002081e+00,1.731061088885748889e-01,-1.569182660078685121e-01,1.361524071352429588e-01,1.000000009432644443e+00,0.000000000000000000e+00 +4.500265007244971116e+01,3.041326340053159925e+02,3.036374200315752891e-01,3.609230619101558624e+00,1.736061088885748893e-01,-1.541479260557166719e-01,1.361524071352429588e-01,1.000000009371275089e+00,0.000000000000000000e+00 +4.500542074605174747e+01,3.041424836880158296e+02,3.053647737048569288e-01,3.608803525512027655e+00,1.741061088885748898e-01,-1.513772524277172404e-01,1.361524071352429588e-01,1.000000009416190716e+00,0.000000000000000000e+00 +4.500819174755662289e+01,3.041523325058076352e+02,3.070970520033640683e-01,3.608384058917746273e+00,1.746061088885748902e-01,-1.486062508967477547e-01,1.361524071352429588e-01,1.000000009398047451e+00,0.000000000000000000e+00 +4.501096307118424278e+01,3.041621804562292368e+02,3.088342544940271828e-01,3.607972222903424342e+00,1.751061088885748906e-01,-1.458349272430844168e-01,1.361524071352429588e-01,1.000000009383240407e+00,0.000000000000000000e+00 +4.501373471114769131e+01,3.041720275368186321e+02,3.105763807425456213e-01,3.607568020991011259e+00,1.756061088885748911e-01,-1.430632872536320710e-01,1.361524071352429588e-01,1.000000009383307020e+00,0.000000000000000000e+00 +4.501650666165335224e+01,3.041818737451140464e+02,3.123234303133878287e-01,3.607171456639566731e+00,1.761061088885748915e-01,-1.402913367219589258e-01,1.361524071352429588e-01,1.000000009411294188e+00,0.000000000000000000e+00 +4.501927891690104389e+01,3.041917190786539322e+02,3.140754027697914563e-01,3.606782533245133315e+00,1.766061088885748920e-01,-1.375190814481747070e-01,1.361524071352429588e-01,1.000000009364952147e+00,0.000000000000000000e+00 +4.502205147108411865e+01,3.042015635349769695e+02,3.158322976737633625e-01,3.606401254140611190e+00,1.771061088885748924e-01,-1.347465272391322744e-01,1.361524071352429588e-01,1.000000009372006726e+00,0.000000000000000000e+00 +4.502482431838959087e+01,3.042114071116220657e+02,3.175941145860798343e-01,3.606027622595634252e+00,1.776061088885748929e-01,-1.319736799076716427e-01,1.361524071352429588e-01,1.000000009384399036e+00,0.000000000000000000e+00 +4.502759745299825056e+01,3.042212498061282986e+02,3.193608530662866429e-01,3.605661641816450214e+00,1.781061088885748933e-01,-1.292005452729885207e-01,1.361524071352429588e-01,1.000000009350388019e+00,0.000000000000000000e+00 +4.503037086908478415e+01,3.042310916160349734e+02,3.211325126726992107e-01,3.605303314945801585e+00,1.786061088885748938e-01,-1.264271291605254255e-01,1.361524071352429588e-01,1.000000009386417643e+00,0.000000000000000000e+00 +4.503314456081788819e+01,3.042409325388816228e+02,3.229090929624026107e-01,3.604952645062808880e+00,1.791061088885748942e-01,-1.236534374013857351e-01,1.361524071352429588e-01,1.000000009371794230e+00,0.000000000000000000e+00 +4.503591852236040438e+01,3.042507725722080636e+02,3.246905934912517888e-01,3.604609635182857375e+00,1.796061088885748946e-01,-1.208794758328715080e-01,1.361524071352429588e-01,1.000000009351508901e+00,0.000000000000000000e+00 +4.503869274786942611e+01,3.042606117135542831e+02,3.264770138138716749e-01,3.604274288257484304e+00,1.801061088885748951e-01,-1.181052502979037522e-01,1.361524071352429588e-01,1.000000009361880382e+00,0.000000000000000000e+00 +4.504146723149642639e+01,3.042704499604604962e+02,3.282683534836571271e-01,3.603946607174269623e+00,1.806061088885748955e-01,-1.153307666449258917e-01,1.361524071352429588e-01,1.000000009314008231e+00,0.000000000000000000e+00 +4.504424196738737862e+01,3.042802873104671448e+02,3.300646120527732652e-01,3.603626594756728974e+00,1.811061088885748960e-01,-1.125560307281302935e-01,1.361524071352429588e-01,1.000000009396402323e+00,0.000000000000000000e+00 +4.504701694968286318e+01,3.042901237611148417e+02,3.318657890721554704e-01,3.603314253764207997e+00,1.816061088885748964e-01,-1.097810484065673414e-01,1.361524071352429588e-01,1.000000009381746047e+00,0.000000000000000000e+00 +4.504979217251821666e+01,3.042999593099445406e+02,3.336718840915094964e-01,3.603009586891781080e+00,1.821061088885748969e-01,-1.070058255451777351e-01,1.361524071352429588e-01,1.000000009260251899e+00,0.000000000000000000e+00 +4.505256763002362419e+01,3.043097939544973087e+02,3.354828966593115802e-01,3.602712596770149212e+00,1.826061088885748973e-01,-1.042303680140671263e-01,1.361524071352429588e-01,1.000000009411339263e+00,0.000000000000000000e+00 +4.505534331632426159e+01,3.043196276923144978e+02,3.372988263228085537e-01,3.602423285965541844e+00,1.831061088885748978e-01,-1.014546816873036633e-01,1.361524071352429588e-01,1.000000009276768687e+00,0.000000000000000000e+00 +4.505811922554041615e+01,3.043294605209376869e+02,3.391196726280180651e-01,3.602141656979624074e+00,1.836061088885748982e-01,-9.867877244539806358e-02,1.361524071352429588e-01,1.000000009377103760e+00,0.000000000000000000e+00 +4.506089535178759320e+01,3.043392924379086253e+02,3.409454351197285238e-01,3.601867712249398945e+00,1.841061088885748986e-01,-9.590264617218648147e-02,1.361524071352429588e-01,1.000000009351041719e+00,0.000000000000000000e+00 +4.506367168917666532e+01,3.043491234407694037e+02,3.427761133414993222e-01,3.601601454147120407e+00,1.846061088885748991e-01,-9.312630875715539880e-02,1.361524071352429588e-01,1.000000009280006541e+00,0.000000000000000000e+00 +4.506644823181396475e+01,3.043589535270622264e+02,3.446117068356609470e-01,3.601342884980201831e+00,1.851061088885748995e-01,-9.034976609408938708e-02,1.361524071352429588e-01,1.000000009341293516e+00,0.000000000000000000e+00 +4.506922497380143255e+01,3.043687826943295818e+02,3.464522151433149788e-01,3.601092006991130301e+00,1.856061088885749000e-01,-8.757302408068126653e-02,1.361524071352429588e-01,1.000000009346345697e+00,0.000000000000000000e+00 +4.507200190923673233e+01,3.043786109401141857e+02,3.482976378043343701e-01,3.600848822357384016e+00,1.861061088885749004e-01,-8.479608861942408704e-02,1.361524071352429588e-01,1.000000009258388944e+00,0.000000000000000000e+00 +4.507477903221337812e+01,3.043884382619589246e+02,3.501479743573635006e-01,3.600613333191349241e+00,1.866061088885749009e-01,-8.201896561706567557e-02,1.361524071352429588e-01,1.000000009364094833e+00,0.000000000000000000e+00 +4.507755633682084806e+01,3.043982646574070259e+02,3.520032243398181770e-01,3.600385541540240819e+00,1.871061088885749013e-01,-7.924166098358602361e-02,1.361524071352429588e-01,1.000000009293964709e+00,0.000000000000000000e+00 +4.508033381714472654e+01,3.044080901240018875e+02,3.538633872878859665e-01,3.600165449386027561e+00,1.876061088885749017e-01,-7.646418063389501252e-02,1.361524071352429588e-01,1.000000009288198655e+00,0.000000000000000000e+00 +4.508311146726681073e+01,3.044179146592871348e+02,3.557284627365261409e-01,3.599953058645354975e+00,1.881061088885749022e-01,-7.368653048601433997e-02,1.361524071352429588e-01,1.000000009274694124e+00,0.000000000000000000e+00 +4.508588928126523854e+01,3.044277382608066205e+02,3.575984502194697878e-01,3.599748371169475103e+00,1.886061088885749026e-01,-7.090871646181984289e-02,1.361524071352429588e-01,1.000000009328777528e+00,0.000000000000000000e+00 +4.508866725321463775e+01,3.044375609261044815e+02,3.594733492692200882e-01,3.599551388744176350e+00,1.891061088885749031e-01,-6.813074448650674464e-02,1.361524071352429588e-01,1.000000009327230099e+00,0.000000000000000000e+00 +4.509144537718621848e+01,3.044473826527249685e+02,3.613531594170523165e-01,3.599362113089716875e+00,1.896061088885749035e-01,-6.535262048901573084e-02,1.361524071352429588e-01,1.000000009235249010e+00,0.000000000000000000e+00 +4.509422364724791521e+01,3.044572034382127299e+02,3.632378801930138956e-01,3.599180545860758862e+00,1.901061088885749040e-01,-6.257435040166171858e-02,1.361524071352429588e-01,1.000000009278385837e+00,0.000000000000000000e+00 +4.509700205746451473e+01,3.044670232801125280e+02,3.651275111259246753e-01,3.599006688646305907e+00,1.906061088885749044e-01,-5.979594015928463985e-02,1.361524071352429588e-01,1.000000009308904536e+00,0.000000000000000000e+00 +4.509978060189777693e+01,3.044768421759694093e+02,3.670220517433769314e-01,3.598840542969644840e+00,1.911061088885749049e-01,-5.701739570016046282e-02,1.361524071352429588e-01,1.000000009265539225e+00,0.000000000000000000e+00 +4.510255927460655556e+01,3.044866601233287042e+02,3.689215015717355328e-01,3.598682110288287106e+00,1.916061088885749053e-01,-5.423872296563476969e-02,1.361524071352429588e-01,1.000000009287840275e+00,0.000000000000000000e+00 +4.510533806964694037e+01,3.044964771197358573e+02,3.708258601361379969e-01,3.598531391993913253e+00,1.921061088885749057e-01,-5.145992789943835272e-02,1.361524071352429588e-01,1.000000009255431532e+00,0.000000000000000000e+00 +4.510811698107237788e+01,3.045062931627366538e+02,3.727351269604947115e-01,3.598388389412321420e+00,1.926061088885749062e-01,-4.868101644828288360e-02,1.361524071352429588e-01,1.000000009247585808e+00,0.000000000000000000e+00 +4.511089600293378510e+01,3.045161082498770497e+02,3.746493015674889349e-01,3.598253103803376263e+00,1.931061088885749066e-01,-4.590199456117941001e-02,1.361524071352429588e-01,1.000000009255136435e+00,0.000000000000000000e+00 +4.511367512927968448e+01,3.045259223787033420e+02,3.765683834785770734e-01,3.598125536360961885e+00,1.936061088885749071e-01,-4.312286818955721884e-02,1.361524071352429588e-01,1.000000009294979675e+00,0.000000000000000000e+00 +4.511645435415634608e+01,3.045357355467619414e+02,3.784923722139886815e-01,3.598005688212936537e+00,1.941061088885749075e-01,-4.034364328706437769e-02,1.361524071352429588e-01,1.000000009179645044e+00,0.000000000000000000e+00 +4.511923367160788700e+01,3.045455477515995426e+02,3.804212672927265171e-01,3.597893560421089987e+00,1.946061088885749080e-01,-3.756432581000856280e-02,1.361524071352429588e-01,1.000000009321689420e+00,0.000000000000000000e+00 +4.512201307567642772e+01,3.045553589907631249e+02,3.823550682325668748e-01,3.597789153981101773e+00,1.951061088885749084e-01,-3.478492171556211293e-02,1.361524071352429588e-01,1.000000009181090110e+00,0.000000000000000000e+00 +4.512479256040219155e+01,3.045651692617998947e+02,3.842937745500595303e-01,3.597692469822506567e+00,1.956061088885749089e-01,-3.200543696428215235e-02,1.361524071352429588e-01,1.000000009276890367e+00,0.000000000000000000e+00 +4.512757211982364680e+01,3.045749785622572290e+02,3.862373857605278515e-01,3.597603508808654649e+00,1.961061088885749093e-01,-2.922587751703949882e-02,1.361524071352429588e-01,1.000000009174861093e+00,0.000000000000000000e+00 +4.513035174797764171e+01,3.045847868896828459e+02,3.881859013780691314e-01,3.597522271736683042e+00,1.966061088885749097e-01,-2.644624933754061158e-02,1.361524071352429588e-01,1.000000009269101264e+00,0.000000000000000000e+00 +4.513313143889951817e+01,3.045945942416246339e+02,3.901393209155544217e-01,3.597448759337481761e+00,1.971061088885749102e-01,-2.366655838989747962e-02,1.361524071352429588e-01,1.000000009229796483e+00,0.000000000000000000e+00 +4.513591118662324675e+01,3.046044006156308228e+02,3.920976438846288659e-01,3.597382972275668944e+00,1.976061088885749106e-01,-2.088681064051199632e-02,1.361524071352429588e-01,1.000000009209948582e+00,0.000000000000000000e+00 +4.513869098518154743e+01,3.046142060092497559e+02,3.940608697957116990e-01,3.597324911149562876e+00,1.981061088885749111e-01,-1.810701205660598945e-02,1.361524071352429588e-01,1.000000009212871799e+00,0.000000000000000000e+00 +4.514147082860603177e+01,3.046240104200301175e+02,3.960289981579965257e-01,3.597274576491160225e+00,1.986061088885749115e-01,-1.532716860650931365e-02,1.361524071352429588e-01,1.000000009206934548e+00,0.000000000000000000e+00 +4.514425071092731656e+01,3.046338138455207627e+02,3.980020284794512087e-01,3.597231968766115617e+00,1.991061088885749120e-01,-1.254728625962894112e-02,1.361524071352429588e-01,1.000000009182810512e+00,0.000000000000000000e+00 +4.514703062617515883e+01,3.046436162832708874e+02,3.999799602668182019e-01,3.597197088373723428e+00,1.996061088885749124e-01,-9.767370986258844603e-03,1.361524071352429588e-01,1.000000009210780139e+00,0.000000000000000000e+00 +4.514981056837858375e+01,3.046534177308298013e+02,4.019627930256145509e-01,3.597169935646902239e+00,2.001061088885749129e-01,-6.987428757230533007e-03,1.361524071352429588e-01,1.000000009210713525e+00,0.000000000000000000e+00 +4.515259053156600544e+01,3.046632181857472119e+02,4.039505262601320590e-01,3.597150510852182403e+00,2.006061088885749133e-01,-4.207465544202964453e-03,1.361524071352429588e-01,1.000000009181812421e+00,0.000000000000000000e+00 +4.515537050976536904e+01,3.046730176455729975e+02,4.059431594734374538e-01,3.597138814189694944e+00,2.011061088885749137e-01,-1.427487319313765820e-03,1.361524071352429588e-01,1.000000009145058266e+00,0.000000000000000000e+00 +4.515815049700427153e+01,3.046828161078572634e+02,4.079406921673724429e-01,3.597134845793163560e+00,2.016061088885749142e-01,1.352499945009593427e-03,1.361524071352429588e-01,1.000000009200600504e+00,0.000000000000000000e+00 +4.516093048731008253e+01,3.046926135701504563e+02,4.099431238425538804e-01,3.597138605729899297e+00,2.021061088885749146e-01,4.132490276398189874e-03,1.361524071352429588e-01,1.000000009182953065e+00,0.000000000000000000e+00 +4.516371047471008637e+01,3.047024100300031364e+02,4.119504539983738223e-01,3.597150094000798326e+00,2.026061088885749151e-01,6.912477701931496639e-03,1.361524071352429588e-01,1.000000009178145799e+00,0.000000000000000000e+00 +4.516649045323160294e+01,3.047122054849662618e+02,4.139626821329997486e-01,3.597169310540340170e+00,2.031061088885749155e-01,9.692456248964913257e-03,1.361524071352429588e-01,1.000000009121503552e+00,0.000000000000000000e+00 +4.516927041690212263e+01,3.047219999325909043e+02,4.159798077433746744e-01,3.597196255216590366e+00,2.036061088885749160e-01,1.247241994483913076e-02,1.361524071352429588e-01,1.000000009199938589e+00,0.000000000000000000e+00 +4.517205035974941296e+01,3.047317933704284769e+02,4.180018303252171497e-01,3.597230927831204461e+00,2.041061088885749164e-01,1.525236281770784436e-02,1.361524071352429588e-01,1.000000009162460790e+00,0.000000000000000000e+00 +4.517483027580168198e+01,3.047415857960306198e+02,4.200287493730215926e-01,3.597273328119436453e+00,2.046061088885749168e-01,1.803227889544869664e-02,1.361524071352429588e-01,1.000000009067300244e+00,0.000000000000000000e+00 +4.517761015908767774e+01,3.047513772069492575e+02,4.220605643800582341e-01,3.597323455750146337e+00,2.051061088885749173e-01,2.081216220665117050e-02,1.361524071352429588e-01,1.000000009224611297e+00,0.000000000000000000e+00 +4.518039000363683044e+01,3.047611676007364849e+02,4.240972748383732838e-01,3.597381310325812542e+00,2.056061088885749177e-01,2.359200678144513300e-02,1.361524071352429588e-01,1.000000009104729415e+00,0.000000000000000000e+00 +4.518316980347937317e+01,3.047709569749447382e+02,4.261388802387892083e-01,3.597446891382548806e+00,2.061061088885749182e-01,2.637180664929444918e-02,1.361524071352429588e-01,1.000000009119861533e+00,0.000000000000000000e+00 +4.518594955264646984e+01,3.047807453271266240e+02,4.281853800709046198e-01,3.597520198390117052e+00,2.066061088885749186e-01,2.915155584174339634e-02,1.361524071352429588e-01,1.000000009072651963e+00,0.000000000000000000e+00 +4.518872924517035727e+01,3.047905326548351468e+02,4.302367738230946093e-01,3.597601230751950041e+00,2.071061088885749191e-01,3.193124839085027811e-02,1.361524071352429588e-01,1.000000009190908257e+00,0.000000000000000000e+00 +4.519150887508445891e+01,3.048003189556233679e+02,4.322930609825106907e-01,3.597689987805171796e+00,2.076061088885749195e-01,3.471087833049729676e-02,1.361524071352429588e-01,1.000000009093294784e+00,0.000000000000000000e+00 +4.519428843642351268e+01,3.048101042270448033e+02,4.343542410350811345e-01,3.597786468820623806e+00,2.081061088885749200e-01,3.749043969482530186e-02,1.361524071352429588e-01,1.000000009111609467e+00,0.000000000000000000e+00 +4.519706792322370603e+01,3.048198884666530830e+02,4.364203134655109673e-01,3.597890673002889006e+00,2.086061088885749204e-01,4.026992652034392522e-02,1.361524071352429588e-01,1.000000009084082819e+00,0.000000000000000000e+00 +4.519984732952280382e+01,3.048296716720021777e+02,4.384912777572820275e-01,3.598002599490323750e+00,2.091061088885749208e-01,4.304933284468745458e-02,1.361524071352429588e-01,1.000000009102955500e+00,0.000000000000000000e+00 +4.520262664936026198e+01,3.048394538406462289e+02,4.405671333926532984e-01,3.598122247355088454e+00,2.096061088885749213e-01,4.582865270744856251e-02,1.361524071352429588e-01,1.000000009054971661e+00,0.000000000000000000e+00 +4.520540587677738387e+01,3.048492349701397757e+02,4.426478798526608527e-01,3.598249615603182683e+00,2.101061088885749217e-01,4.860788014973475152e-02,1.361524071352429588e-01,1.000000009139225821e+00,0.000000000000000000e+00 +4.520818500581741262e+01,3.048590150580374711e+02,4.447335166171180743e-01,3.598384703174481114e+00,2.106061088885749222e-01,5.138700921516395348e-02,1.361524071352429588e-01,1.000000009005129309e+00,0.000000000000000000e+00 +4.521096403052568746e+01,3.048687941018943093e+02,4.468240431646158251e-01,3.598527508942774400e+00,2.111061088885749226e-01,5.416603394846424002e-02,1.361524071352429588e-01,1.000000009132885337e+00,0.000000000000000000e+00 +4.521374294494975032e+01,3.048785720992655683e+02,4.489194589725224449e-01,3.598678031715808245e+00,2.116061088885749231e-01,5.694494839790992247e-02,1.361524071352429588e-01,1.000000009051392746e+00,0.000000000000000000e+00 +4.521652174313949502e+01,3.048883490477066971e+02,4.510197635169840291e-01,3.598836270235331369e+00,2.121061088885749235e-01,5.972374661280497460e-02,1.361524071352429588e-01,1.000000009006376978e+00,0.000000000000000000e+00 +4.521930041914726672e+01,3.048981249447734854e+02,4.531249562729244285e-01,3.599002223177138582e+00,2.126061088885749240e-01,6.250242264560205985e-02,1.361524071352429588e-01,1.000000009098405362e+00,0.000000000000000000e+00 +4.522207896702801122e+01,3.049078997880219504e+02,4.552350367140454712e-01,3.599175889151121854e+00,2.131061088885749244e-01,6.528097055162591922e-02,1.361524071352429588e-01,1.000000009053300110e+00,0.000000000000000000e+00 +4.522485738083938855e+01,3.049176735750083935e+02,4.573500043128270187e-01,3.599357266701322722e+00,2.136061088885749248e-01,6.805938438815879732e-02,1.361524071352429588e-01,1.000000008970435061e+00,0.000000000000000000e+00 +4.522763565464191515e+01,3.049274463032893436e+02,4.594698585405272429e-01,3.599546354305984242e+00,2.141061088885749253e-01,7.083765821560493448e-02,1.361524071352429588e-01,1.000000009093455100e+00,0.000000000000000000e+00 +4.523041378249906330e+01,3.049372179704216137e+02,4.615945988671825706e-01,3.599743150377608281e+00,2.146061088885749257e-01,7.361578609801766593e-02,1.361524071352429588e-01,1.000000009005321377e+00,0.000000000000000000e+00 +4.523319175847741747e+01,3.049469885739623010e+02,4.637242247616079061e-01,3.599947653263016356e+00,2.151061088885749262e-01,7.639376210139008083e-02,1.361524071352429588e-01,1.000000009009879953e+00,0.000000000000000000e+00 +4.523596957664678087e+01,3.049567581114687869e+02,4.658587356913967970e-01,3.600159861243407811e+00,2.156061088885749266e-01,7.917158029578375000e-02,1.361524071352429588e-01,1.000000009039369031e+00,0.000000000000000000e+00 +4.523874723108031048e+01,3.049665265804986802e+02,4.679981311229215457e-01,3.600379772534425982e+00,2.161061088885749271e-01,8.194923475442213168e-02,1.361524071352429588e-01,1.000000008942749430e+00,0.000000000000000000e+00 +4.524152471585463786e+01,3.049762939786098173e+02,4.701424105213333204e-01,3.600607385286223927e+00,2.166061088885749275e-01,8.472671955358490603e-02,1.361524071352429588e-01,1.000000009004569312e+00,0.000000000000000000e+00 +4.524430202504998988e+01,3.049860603033603752e+02,4.722915733505622660e-01,3.600842697583531926e+00,2.171061088885749280e-01,8.750402877394322654e-02,1.361524071352429588e-01,1.000000009024734293e+00,0.000000000000000000e+00 +4.524707915275032377e+01,3.049958255523087587e+02,4.744456190733176704e-01,3.601085707445730755e+00,2.176061088885749284e-01,9.028115649933877995e-02,1.361524071352429588e-01,1.000000008952465436e+00,0.000000000000000000e+00 +4.524985609304344791e+01,3.050055897230137134e+02,4.766045471510881315e-01,3.601336412826923628e+00,2.181061088885749288e-01,9.305809681732352123e-02,1.361524071352429588e-01,1.000000009002429247e+00,0.000000000000000000e+00 +4.525263284002114972e+01,3.050153528130341556e+02,4.787683570441416125e-01,3.601594811616011693e+00,2.186061088885749293e-01,9.583484382002151192e-02,1.361524071352429588e-01,1.000000008964513132e+00,0.000000000000000000e+00 +4.525540938777930933e+01,3.050251148199292857e+02,4.809370482115256640e-01,3.601860901636773971e+00,2.191061088885749297e-01,9.861139160307381968e-02,1.361524071352429588e-01,1.000000008895804315e+00,0.000000000000000000e+00 +4.525818573041804171e+01,3.050348757412586451e+02,4.831106201110675347e-01,3.602134680647946396e+00,2.196061088885749302e-01,1.013877342665047698e-01,1.361524071352429588e-01,1.000000009006407398e+00,0.000000000000000000e+00 +4.526096186204180327e+01,3.050446355745819460e+02,4.852890721993742273e-01,3.602416146343305314e+00,2.201061088885749306e-01,1.041638659152706869e-01,1.361524071352429588e-01,1.000000008911322347e+00,0.000000000000000000e+00 +4.526373777675952681e+01,3.050543943174592982e+02,4.874724039318327762e-01,3.602705296351754516e+00,2.206061088885749311e-01,1.069397806577314924e-01,1.361524071352429588e-01,1.000000008956663855e+00,0.000000000000000000e+00 +4.526651346868473524e+01,3.050641519674509823e+02,4.896606147626101913e-01,3.603002128237410062e+00,2.211061088885749315e-01,1.097154726078038572e-01,1.361524071352429588e-01,1.000000008952932173e+00,0.000000000000000000e+00 +4.526928893193568371e+01,3.050739085221175628e+02,4.918537041446538471e-01,3.603306639499693098e+00,2.216061088885749319e-01,1.124909358835975148e-01,1.361524071352429588e-01,1.000000008867478529e+00,0.000000000000000000e+00 +4.527206416063545191e+01,3.050836639790199456e+02,4.940516715296913719e-01,3.603618827573420891e+00,2.221061088885749324e-01,1.152661646079736479e-01,1.361524071352429588e-01,1.000000008941099416e+00,0.000000000000000000e+00 +4.527483914891209338e+01,3.050934183357192637e+02,4.962545163682309246e-01,3.603938689828901420e+00,2.226061088885749328e-01,1.180411529094263640e-01,1.361524071352429588e-01,1.000000008881722913e+00,0.000000000000000000e+00 +4.527761389089874910e+01,3.051031715897768777e+02,4.984622381095613064e-01,3.604266223572032413e+00,2.231061088885749333e-01,1.208158949207262245e-01,1.361524071352429588e-01,1.000000008903473292e+00,0.000000000000000000e+00 +4.528038838073376837e+01,3.051129237387545459e+02,5.006748362017521270e-01,3.604601426044398593e+00,2.236061088885749337e-01,1.235903847804470101e-01,1.361524071352429588e-01,1.000000008862763634e+00,0.000000000000000000e+00 +4.528316261256082953e+01,3.051226747802141972e+02,5.028923100916538047e-01,3.604944294423375162e+00,2.241061088885749342e-01,1.263646166320948616e-01,1.361524071352429588e-01,1.000000008893902947e+00,0.000000000000000000e+00 +4.528593658052906079e+01,3.051324247117180448e+02,5.051146592248979550e-01,3.605294825822230820e+00,2.246061088885749346e-01,1.291385846250007186e-01,1.361524071352429588e-01,1.000000008891006376e+00,0.000000000000000000e+00 +4.528871027879317523e+01,3.051421735308286429e+02,5.073418830458972240e-01,3.605653017290235240e+00,2.251061088885749351e-01,1.319122829137750474e-01,1.361524071352429588e-01,1.000000008797635065e+00,0.000000000000000000e+00 +4.529148370151356318e+01,3.051519212351087731e+02,5.095739809978457879e-01,3.606018865812766983e+00,2.256061088885749355e-01,1.346857056585658574e-01,1.361524071352429588e-01,1.000000008896782200e+00,0.000000000000000000e+00 +4.529425684285644849e+01,3.051616678221215011e+02,5.118109525227191314e-01,3.606392368311424068e+00,2.261061088885749359e-01,1.374588470261204898e-01,1.361524071352429588e-01,1.000000008830595366e+00,0.000000000000000000e+00 +4.529702969699397386e+01,3.051714132894301770e+02,5.140527970612742692e-01,3.606773521644139446e+00,2.266061088885749364e-01,1.402317011881284159e-01,1.361524071352429588e-01,1.000000008871793744e+00,0.000000000000000000e+00 +4.529980225810433581e+01,3.051811576345984918e+02,5.162995140530501903e-01,3.607162322605293792e+00,2.271061088885749368e-01,1.430042623230896870e-01,1.361524071352429588e-01,1.000000008770116189e+00,0.000000000000000000e+00 +4.530257452037191968e+01,3.051909008551903071e+02,5.185511029363676361e-01,3.607558767925835408e+00,2.276061088885749373e-01,1.457765246149841654e-01,1.361524071352429588e-01,1.000000008851098077e+00,0.000000000000000000e+00 +4.530534647798738490e+01,3.052006429487698256e+02,5.208075631483294332e-01,3.607962854273398356e+00,2.281061088885749377e-01,1.485484822549869299e-01,1.361524071352429588e-01,1.000000008804020846e+00,0.000000000000000000e+00 +4.530811812514782133e+01,3.052103839129015341e+02,5.230688941248204937e-01,3.608374578252427245e+00,2.286061088885749382e-01,1.513201294398230645e-01,1.361524071352429588e-01,1.000000008723409994e+00,0.000000000000000000e+00 +4.531088945605683449e+01,3.052201237451501470e+02,5.253350953005080370e-01,3.608793936404299352e+00,2.291061088885749386e-01,1.540914603730093868e-01,1.361524071352429588e-01,1.000000008879492919e+00,0.000000000000000000e+00 +4.531366046492468058e+01,3.052298624430807763e+02,5.276061661088419230e-01,3.609220925207452080e+00,2.296061088885749391e-01,1.568624692654591035e-01,1.361524071352429588e-01,1.000000008736350754e+00,0.000000000000000000e+00 +4.531643114596838018e+01,3.052396000042587048e+02,5.298821059820543189e-01,3.609655541077513963e+00,2.301061088885749395e-01,1.596331503333653923e-01,1.361524071352429588e-01,1.000000008746138924e+00,0.000000000000000000e+00 +4.531920149341183901e+01,3.052493364262495561e+02,5.321629143511603655e-01,3.610097780367431675e+00,2.306061088885749399e-01,1.624034978010565344e-01,1.361524071352429588e-01,1.000000008789086792e+00,0.000000000000000000e+00 +4.532197150148596165e+01,3.052590717066191814e+02,5.344485906459579549e-01,3.610547639367606809e+00,2.311061088885749404e-01,1.651735058995277838e-01,1.361524071352429588e-01,1.000000008695204556e+00,0.000000000000000000e+00 +4.532474116442877232e+01,3.052688058429338298e+02,5.367391342950279531e-01,3.611005114306030439e+00,2.316061088885749408e-01,1.679431688664187461e-01,1.361524071352429588e-01,1.000000008766865900e+00,0.000000000000000000e+00 +4.532751047648551435e+01,3.052785388327599208e+02,5.390345447257345324e-01,3.611470201348419451e+00,2.321061088885749413e-01,1.707124809474376281e-01,1.361524071352429588e-01,1.000000008738433088e+00,0.000000000000000000e+00 +4.533027943190878517e+01,3.052882706736642149e+02,5.413348213642250606e-01,3.611942896598358654e+00,2.326061088885749417e-01,1.734814363949034877e-01,1.361524071352429588e-01,1.000000008703884502e+00,0.000000000000000000e+00 +4.533304802495864294e+01,3.052980013632137570e+02,5.436399636354304343e-01,3.612423196097440670e+00,2.331061088885749422e-01,1.762500294688572888e-01,1.361524071352429588e-01,1.000000008713247679e+00,0.000000000000000000e+00 +4.533581624990272019e+01,3.053077308989758762e+02,5.459499709630650788e-01,3.612911095825410701e+00,2.336061088885749426e-01,1.790182544370547135e-01,1.361524071352429588e-01,1.000000008658220585e+00,0.000000000000000000e+00 +4.533858410101634462e+01,3.053174592785181858e+02,5.482648427696271698e-01,3.613406591700313086e+00,2.341061088885749430e-01,1.817861055746420318e-01,1.361524071352429588e-01,1.000000008679293062e+00,0.000000000000000000e+00 +4.534135157258263860e+01,3.053271864994085831e+02,5.505845784763987449e-01,3.613909679578638734e+00,2.346061088885749435e-01,1.845535771649585155e-01,1.361524071352429588e-01,1.000000008703867405e+00,0.000000000000000000e+00 +4.534411865889265414e+01,3.053369125592153068e+02,5.529091775034459255e-01,3.614420355255476558e+00,2.351061088885749439e-01,1.873206634990598751e-01,1.361524071352429588e-01,1.000000008621507952e+00,0.000000000000000000e+00 +4.534688535424546529e+01,3.053466374555067659e+02,5.552386392696189166e-01,3.614938614464665356e+00,2.356061088885749444e-01,1.900873588757265031e-01,1.361524071352429588e-01,1.000000008691797504e+00,0.000000000000000000e+00 +4.534965165294829603e+01,3.053563611858517675e+02,5.575729631925523400e-01,3.615464452878947466e+00,2.361061088885749448e-01,1.928536576025995930e-01,1.361524071352429588e-01,1.000000008617808911e+00,0.000000000000000000e+00 +4.535241754931661262e+01,3.053660837478194026e+02,5.599121486886652344e-01,3.615997866110127301e+00,2.366061088885749453e-01,1.956195539947533646e-01,1.361524071352429588e-01,1.000000008592076384e+00,0.000000000000000000e+00 +4.535518303767425863e+01,3.053758051389790467e+02,5.622561951731612773e-01,3.616538849709227676e+00,2.371061088885749457e-01,1.983850423761605586e-01,1.361524071352429588e-01,1.000000008660202333e+00,0.000000000000000000e+00 +4.535794811235354729e+01,3.053855253569003025e+02,5.646051020600287851e-01,3.617087399166651895e+00,2.376061088885749462e-01,2.011501170793967841e-01,1.361524071352429588e-01,1.000000008548028507e+00,0.000000000000000000e+00 +4.536071276769538230e+01,3.053952443991531709e+02,5.669588687620410461e-01,3.617643509912346733e+00,2.381061088885749466e-01,2.039147724448668597e-01,1.361524071352429588e-01,1.000000008592728307e+00,0.000000000000000000e+00 +4.536347699804937150e+01,3.054049622633078229e+02,5.693174946907564316e-01,3.618207177315964973e+00,2.386061088885749470e-01,2.066790028226050957e-01,1.361524071352429588e-01,1.000000008582920819e+00,0.000000000000000000e+00 +4.536624079777391216e+01,3.054146789469348278e+02,5.716809792565183956e-01,3.618778396687034604e+00,2.391061088885749475e-01,2.094428025708680863e-01,1.361524071352429588e-01,1.000000008573618926e+00,0.000000000000000000e+00 +4.536900416123633306e+01,3.054243944476050387e+02,5.740493218684559196e-01,3.619357163275125799e+00,2.396061088885749479e-01,2.122061660569801722e-01,1.361524071352429588e-01,1.000000008539540630e+00,0.000000000000000000e+00 +4.537176708281297977e+01,3.054341087628895366e+02,5.764225219344832896e-01,3.619943472270021889e+00,2.401061088885749484e-01,2.149690876572199483e-01,1.361524071352429588e-01,1.000000008551282793e+00,0.000000000000000000e+00 +4.537452955688932832e+01,3.054438218903597431e+02,5.788005788613005409e-01,3.620537318801891669e+00,2.406061088885749488e-01,2.177315617571931039e-01,1.361524071352429588e-01,1.000000008544478680e+00,0.000000000000000000e+00 +4.537729157786009893e+01,3.054535338275874210e+02,5.811834920543934579e-01,3.621138697941464368e+00,2.411061088885749493e-01,2.204935827515669411e-01,1.361524071352429588e-01,1.000000008437993637e+00,0.000000000000000000e+00 +4.538005314012936253e+01,3.054632445721445606e+02,5.835712609180336852e-01,3.621747604700205514e+00,2.416061088885749497e-01,2.232551450441310759e-01,1.361524071352429588e-01,1.000000008543363350e+00,0.000000000000000000e+00 +4.538281423811063320e+01,3.054729541216034931e+02,5.859638848552790602e-01,3.622364034030494562e+00,2.421061088885749502e-01,2.260162430489881524e-01,1.361524071352429588e-01,1.000000008460386836e+00,0.000000000000000000e+00 +4.538557486622698178e+01,3.054826624735367773e+02,5.883613632679736138e-01,3.622987980825807419e+00,2.426061088885749506e-01,2.287768711886942474e-01,1.361524071352429588e-01,1.000000008476606306e+00,0.000000000000000000e+00 +4.538833501891115674e+01,3.054923696255173695e+02,5.907636955567477921e-01,3.623619439920895413e+00,2.431061088885749510e-01,2.315370238962631833e-01,1.361524071352429588e-01,1.000000008462697432e+00,0.000000000000000000e+00 +4.539109469060566227e+01,3.055020755751184538e+02,5.931708811210185672e-01,3.624258406091971363e+00,2.436061088885749515e-01,2.342966956141203094e-01,1.361524071352429588e-01,1.000000008398442164e+00,0.000000000000000000e+00 +4.539385387576287911e+01,3.055117803199135551e+02,5.955829193589894377e-01,3.624904874056894322e+00,2.441061088885749519e-01,2.370558807945079838e-01,1.361524071352429588e-01,1.000000008433491461e+00,0.000000000000000000e+00 +4.539661256884516405e+01,3.055214838574765395e+02,5.979998096676508723e-01,3.625558838475356982e+00,2.446061088885749524e-01,2.398145739000578647e-01,1.361524071352429588e-01,1.000000008422481157e+00,0.000000000000000000e+00 +4.539937076432495644e+01,3.055311861853814435e+02,6.004215514427804212e-01,3.626220293949076190e+00,2.451061088885749528e-01,2.425727694030799797e-01,1.361524071352429588e-01,1.000000008393638451e+00,0.000000000000000000e+00 +4.540212845668487063e+01,3.055408873012027584e+02,6.028481440789426049e-01,3.626889235021983016e+00,2.456061088885749533e-01,2.453304617861442327e-01,1.361524071352429588e-01,1.000000008375957483e+00,0.000000000000000000e+00 +4.540488564041781672e+01,3.055505872025151461e+02,6.052795869694892472e-01,3.627565656180415932e+00,2.461061088885749537e-01,2.480876455421844040e-01,1.361524071352429588e-01,1.000000008342644575e+00,0.000000000000000000e+00 +4.540764231002707874e+01,3.055602858868936664e+02,6.077158795065595864e-01,3.628249551853315769e+00,2.466061088885749542e-01,2.508443151744456645e-01,1.361524071352429588e-01,1.000000008388615580e+00,0.000000000000000000e+00 +4.541039846002643543e+01,3.055699833519136064e+02,6.101570210810806083e-01,3.628940916412422002e+00,2.471061088885749546e-01,2.536004651969208656e-01,1.361524071352429588e-01,1.000000008264716023e+00,0.000000000000000000e+00 +4.541315408494024553e+01,3.055796795951506510e+02,6.126030110827668240e-01,3.629639744172471705e+00,2.476061088885749550e-01,2.563560901335024123e-01,1.361524071352429588e-01,1.000000008373820748e+00,0.000000000000000000e+00 +4.541590917930355431e+01,3.055893746141807128e+02,6.150538489001208253e-01,3.630346029391397611e+00,2.481061088885749555e-01,2.591111845198788011e-01,1.361524071352429588e-01,1.000000008252454053e+00,0.000000000000000000e+00 +4.541866373766219311e+01,3.055990684065800451e+02,6.175095339204331735e-01,3.631059766270532840e+00,2.486061088885749559e-01,2.618657429012463678e-01,1.361524071352429588e-01,1.000000008327612377e+00,0.000000000000000000e+00 +4.542141775457287167e+01,3.056087609699251857e+02,6.199700655297826213e-01,3.631780948954810739e+00,2.491061088885749564e-01,2.646197598348610791e-01,1.361524071352429588e-01,1.000000008222123427e+00,0.000000000000000000e+00 +4.542417122460329182e+01,3.056184523017930132e+02,6.224354431130362242e-01,3.632509571532973158e+00,2.496061088885749568e-01,2.673732298879211711e-01,1.361524071352429588e-01,1.000000008219946057e+00,0.000000000000000000e+00 +4.542692414233222564e+01,3.056281423997606908e+02,6.249056660538496732e-01,3.633245628037774289e+00,2.501061088885749295e-01,2.701261476394852257e-01,1.361524071352429588e-01,1.000000008273267404e+00,0.000000000000000000e+00 +4.542967650234962207e+01,3.056378312614056654e+02,6.273807337346671842e-01,3.633989112446191161e+00,2.506061088885749299e-01,2.728785076796549913e-01,1.361524071352429588e-01,1.000000008179590560e+00,0.000000000000000000e+00 +4.543242829925670634e+01,3.056475188843057254e+02,6.298606455367218304e-01,3.634740018679633256e+00,2.511061088885749304e-01,2.756303046092458131e-01,1.361524071352429588e-01,1.000000008229333659e+00,0.000000000000000000e+00 +4.543517952766605816e+01,3.056572052660390000e+02,6.323454008400357651e-01,3.635498340604152556e+00,2.516061088885749308e-01,2.783815330412385824e-01,1.361524071352429588e-01,1.000000008152146957e+00,0.000000000000000000e+00 +4.543793018220172542e+01,3.056668904041838459e+02,6.348349990234201101e-01,3.636264072030658934e+00,2.521061088885749313e-01,2.811321875993313402e-01,1.361524071352429588e-01,1.000000008116435080e+00,0.000000000000000000e+00 +4.544068025749931650e+01,3.056765742963190178e+02,6.373294394644754002e-01,3.637037206715132864e+00,2.526061088885749317e-01,2.838822629192406244e-01,1.361524071352429588e-01,1.000000008144811714e+00,0.000000000000000000e+00 +4.544342974820607850e+01,3.056862569400235543e+02,6.398287215395914718e-01,3.637817738358843034e+00,2.531061088885749322e-01,2.866317536483937167e-01,1.361524071352429588e-01,1.000000008116216588e+00,0.000000000000000000e+00 +4.544617864898100379e+01,3.056959383328767785e+02,6.423328446239477962e-01,3.638605660608564385e+00,2.536061088885749326e-01,2.893806544456264951e-01,1.361524071352429588e-01,1.000000008120372819e+00,0.000000000000000000e+00 +4.544892695449491526e+01,3.057056184724583545e+02,6.448418080915137018e-01,3.639400967056796610e+00,2.541061088885749331e-01,2.921289599818552296e-01,1.361524071352429588e-01,1.000000008048758993e+00,0.000000000000000000e+00 +4.545167465943056584e+01,3.057152973563482306e+02,6.473556113150482627e-01,3.640203651241985749e+00,2.546061088885749335e-01,2.948766649396232231e-01,1.361524071352429588e-01,1.000000008067414736e+00,0.000000000000000000e+00 +4.545442175848272370e+01,3.057249749821266960e+02,6.498742536661007430e-01,3.641013706648745796e+00,2.551061088885749339e-01,2.976237640139462459e-01,1.361524071352429588e-01,1.000000007971818539e+00,0.000000000000000000e+00 +4.545716824635826470e+01,3.057346513473743244e+02,6.523977345150104856e-01,3.641831126708083843e+00,2.556061088885749344e-01,3.003702519113846670e-01,1.361524071352429588e-01,1.000000008072163826e+00,0.000000000000000000e+00 +4.545991411777626467e+01,3.057443264496720303e+02,6.549260532309073568e-01,3.642655904797623911e+00,2.561061088885749348e-01,3.031161233515469178e-01,1.361524071352429588e-01,1.000000007959028547e+00,0.000000000000000000e+00 +4.546265936746807057e+01,3.057540002866010127e+02,6.574592091817117456e-01,3.643488034241836093e+00,2.566061088885749353e-01,3.058613730652021689e-01,1.361524071352429588e-01,1.000000007978144367e+00,0.000000000000000000e+00 +4.546540399017741407e+01,3.057636728557428683e+02,6.599972017341345643e-01,3.644327508312261710e+00,2.571061088885749357e-01,3.086059957964422673e-01,1.361524071352429588e-01,1.000000007936490798e+00,0.000000000000000000e+00 +4.546814798066048269e+01,3.057733441546794211e+02,6.625400302536776920e-01,3.645174320227745568e+00,2.576061088885749362e-01,3.113499863012901825e-01,1.361524071352429588e-01,1.000000007929825241e+00,0.000000000000000000e+00 +4.547089133368601921e+01,3.057830141809928364e+02,6.650876941046340862e-01,3.646028463154665555e+00,2.581061088885749366e-01,3.140933393485796921e-01,1.361524071352429588e-01,1.000000007873057983e+00,0.000000000000000000e+00 +4.547363404403539278e+01,3.057926829322656204e+02,6.676401926500877826e-01,3.646889930207165786e+00,2.586061088885749371e-01,3.168360497195454317e-01,1.361524071352429588e-01,1.000000007856766349e+00,0.000000000000000000e+00 +4.547637610650269124e+01,3.058023504060806204e+02,6.701975252519141169e-01,3.647758714447389750e+00,2.591061088885749375e-01,3.195781122083904413e-01,1.361524071352429588e-01,1.000000007854220607e+00,0.000000000000000000e+00 +4.547911751589482066e+01,3.058120166000209110e+02,6.727596912707799470e-01,3.648634808885716119e+00,2.596061088885749379e-01,3.223195216220492987e-01,1.361524071352429588e-01,1.000000007841940874e+00,0.000000000000000000e+00 +4.548185826703156209e+01,3.058216815116700218e+02,6.753266900661438754e-01,3.649518206480995008e+00,2.601061088885749384e-01,3.250602727802813785e-01,1.361524071352429588e-01,1.000000007801855606e+00,0.000000000000000000e+00 +4.548459835474567114e+01,3.058313451386116526e+02,6.778985209962561376e-01,3.650408900140785562e+00,2.606061088885749388e-01,3.278003605157693290e-01,1.361524071352429588e-01,1.000000007723602868e+00,0.000000000000000000e+00 +4.548733777388297028e+01,3.058410074784299013e+02,6.804751834181590464e-01,3.651306882721594871e+00,2.611061088885749393e-01,3.305397796742231553e-01,1.361524071352429588e-01,1.000000007784717759e+00,0.000000000000000000e+00 +4.549007651930240570e+01,3.058506685287092068e+02,6.830566766876869922e-01,3.652212147029118228e+00,2.616061088885749397e-01,3.332785251149770755e-01,1.361524071352429588e-01,1.000000007701724813e+00,0.000000000000000000e+00 +4.549281458587614679e+01,3.058603282870342923e+02,6.856430001594666646e-01,3.653124685818482043e+00,2.621061088885749402e-01,3.360165917098082988e-01,1.361524071352429588e-01,1.000000007679684222e+00,0.000000000000000000e+00 +4.549555196848967142e+01,3.058699867509902219e+02,6.882341531869171636e-01,3.654044491794484539e+00,2.626061088885749406e-01,3.387539743443559459e-01,1.361524071352429588e-01,1.000000007644715305e+00,0.000000000000000000e+00 +4.549828866204182987e+01,3.058796439181624010e+02,6.908301351222503328e-01,3.654971557611841337e+00,2.631061088885749411e-01,3.414906679174372628e-01,1.361524071352429588e-01,1.000000007661291823e+00,0.000000000000000000e+00 +4.550102466144493718e+01,3.058892997861365188e+02,6.934309453164706483e-01,3.655905875875430144e+00,2.636061088885749415e-01,3.442266673415058098e-01,1.361524071352429588e-01,1.000000007578577099e+00,0.000000000000000000e+00 +4.550375996162484427e+01,3.058989543524986061e+02,6.960365831193755515e-01,3.656847439140537670e+00,2.641061088885749419e-01,3.469619675421410920e-01,1.361524071352429588e-01,1.000000007626137055e+00,0.000000000000000000e+00 +4.550649455752101602e+01,3.059086076148350344e+02,6.986470478795556716e-01,3.657796239913106096e+00,2.646061088885749424e-01,3.496965634591672756e-01,1.361524071352429588e-01,1.000000007526269385e+00,0.000000000000000000e+00 +4.550922844408661661e+01,3.059182595707324595e+02,7.012623389443948252e-01,3.658752270649983540e+00,2.651061088885749428e-01,3.524304500453430689e-01,1.361524071352429588e-01,1.000000007445908334e+00,0.000000000000000000e+00 +4.551196161628858050e+01,3.059279102177779350e+02,7.038824556600702387e-01,3.659715523759171862e+00,2.656061088885749433e-01,3.551636222676544108e-01,1.361524071352429588e-01,1.000000007524740830e+00,0.000000000000000000e+00 +4.551469406910768356e+01,3.059375595535587991e+02,7.065073973715527700e-01,3.660685991600078903e+00,2.661061088885749437e-01,3.578960751073154700e-01,1.361524071352429588e-01,1.000000007460584817e+00,0.000000000000000000e+00 +4.551742579753862117e+01,3.059472075756626737e+02,7.091371634226070197e-01,3.661663666483771618e+00,2.666061088885749442e-01,3.606278035586363839e-01,1.361524071352429588e-01,1.000000007403988755e+00,0.000000000000000000e+00 +4.552015679659010061e+01,3.059568542816775789e+02,7.117717531557914423e-01,3.662648540673226982e+00,2.671061088885749446e-01,3.633588026303350427e-01,1.361524071352429588e-01,1.000000007425694060e+00,0.000000000000000000e+00 +4.552288706128488371e+01,3.059664996691918191e+02,7.144111659124585678e-01,3.663640606383587350e+00,2.676061088885749450e-01,3.660890673453925381e-01,1.361524071352429588e-01,1.000000007280166914e+00,0.000000000000000000e+00 +4.552561658665987920e+01,3.059761437357940395e+02,7.170554010327553351e-01,3.664639855782416245e+00,2.681061088885749455e-01,3.688185927402627406e-01,1.361524071352429588e-01,1.000000007302206617e+00,0.000000000000000000e+00 +4.552834536776622087e+01,3.059857864790732833e+02,7.197044578556228700e-01,3.665646280989952821e+00,2.686061088885749459e-01,3.715473738665289738e-01,1.361524071352429588e-01,1.000000007336209418e+00,0.000000000000000000e+00 +4.553107339966931733e+01,3.059954278966188213e+02,7.223583357187970400e-01,3.666659874079371662e+00,2.691061088885749464e-01,3.742754057896368058e-01,1.361524071352429588e-01,1.000000007215546605e+00,0.000000000000000000e+00 +4.553380067744893722e+01,3.060050679860203218e+02,7.250170339588084545e-01,3.667680627077039901e+00,2.696061088885749468e-01,3.770026835889353500e-01,1.361524071352429588e-01,1.000000007182590744e+00,0.000000000000000000e+00 +4.553652719619928035e+01,3.060147067448677376e+02,7.276805519109824649e-01,3.668708531962775243e+00,2.701061088885749473e-01,3.797292023588630938e-01,1.361524071352429588e-01,1.000000007175416039e+00,0.000000000000000000e+00 +4.553925295102904869e+01,3.060243441707513625e+02,7.303488889094396086e-01,3.669743580670107974e+00,2.706061088885749477e-01,3.824549572081871740e-01,1.361524071352429588e-01,1.000000007128097002e+00,0.000000000000000000e+00 +4.554197793706149611e+01,3.060339802612618882e+02,7.330220442870957198e-01,3.670785765086541641e+00,2.711061088885749482e-01,3.851799432600613859e-01,1.361524071352429588e-01,1.000000007093086563e+00,0.000000000000000000e+00 +4.554470214943452788e+01,3.060436150139902907e+02,7.357000173756619299e-01,3.671835077053814622e+00,2.716061088885749486e-01,3.879041556524168710e-01,1.361524071352429588e-01,1.000000007064058449e+00,0.000000000000000000e+00 +4.554742558330074331e+01,3.060532484265278299e+02,7.383828075056448892e-01,3.672891508368163471e+00,2.721061088885749490e-01,3.906275895378691354e-01,1.361524071352429588e-01,1.000000006918493556e+00,0.000000000000000000e+00 +4.555014823382750677e+01,3.060628804964661640e+02,7.410704140063472112e-01,3.673955050780586706e+00,2.726061088885749495e-01,3.933502400834682500e-01,1.361524071352429588e-01,1.000000007019175685e+00,0.000000000000000000e+00 +4.555287009619701877e+01,3.060725112213972920e+02,7.437628362058672504e-01,3.675025695997108599e+00,2.731061088885749499e-01,3.960721024720859629e-01,1.361524071352429588e-01,1.000000006898478455e+00,0.000000000000000000e+00 +4.555559116560637989e+01,3.060821405989135542e+02,7.464600734310994357e-01,3.676103435679047404e+00,2.736061088885749504e-01,3.987931719002200115e-01,1.361524071352429588e-01,1.000000006878656977e+00,0.000000000000000000e+00 +4.555831143726765475e+01,3.060917686266075748e+02,7.491621250077344918e-01,3.677188261443278261e+00,2.741061088885749508e-01,4.015134435802086288e-01,1.361524071352429588e-01,1.000000006815702225e+00,0.000000000000000000e+00 +4.556103090640793596e+01,3.061013953020723761e+02,7.518689902602595510e-01,3.678280164862502755e+00,2.746061088885749513e-01,4.042329127390251187e-01,1.361524071352429588e-01,1.000000006761264215e+00,0.000000000000000000e+00 +4.556374956826940092e+01,3.061110206229012647e+02,7.545806685119582635e-01,3.679379137465515814e+00,2.751061088885749517e-01,4.069515746188731020e-01,1.361524071352429588e-01,1.000000006785333850e+00,0.000000000000000000e+00 +4.556646741810938295e+01,3.061206445866879449e+02,7.572971590849111312e-01,3.680485170737474832e+00,2.756061088885749522e-01,4.096694244772983162e-01,1.361524071352429588e-01,1.000000006617820514e+00,0.000000000000000000e+00 +4.556918445120042804e+01,3.061302671910264053e+02,7.600184612999956180e-01,3.681598256120169665e+00,2.761061088885749526e-01,4.123864575863257498e-01,1.361524071352429588e-01,1.000000006612915771e+00,0.000000000000000000e+00 +4.557190066283035890e+01,3.061398884335109756e+02,7.627445744768860392e-01,3.682718385012290874e+00,2.766061088885749530e-01,4.151026692342168478e-01,1.361524071352429588e-01,1.000000006609233161e+00,0.000000000000000000e+00 +4.557461604830232460e+01,3.061495083117363265e+02,7.654754979340541166e-01,3.683845548769703271e+00,2.771061088885749535e-01,4.178180547241282516e-01,1.361524071352429588e-01,1.000000006533151131e+00,0.000000000000000000e+00 +4.557733060293487171e+01,3.061591268232975267e+02,7.682112309887690893e-01,3.684979738705716379e+00,2.776061088885749539e-01,4.205326093744097271e-01,1.361524071352429588e-01,1.000000006401672525e+00,0.000000000000000000e+00 +4.558004432206200107e+01,3.061687439657899859e+02,7.709517729570976030e-01,3.686120946091356210e+00,2.781061088885749544e-01,4.232463285189087543e-01,1.361524071352429588e-01,1.000000006445651346e+00,0.000000000000000000e+00 +4.558275720103321760e+01,3.061783597368093410e+02,7.736971231539042648e-01,3.687269162155638380e+00,2.786061088885749548e-01,4.259592075076082951e-01,1.361524071352429588e-01,1.000000006388620521e+00,0.000000000000000000e+00 +4.558546923521358707e+01,3.061879741339516841e+02,7.764472808928515324e-01,3.688424378085843447e+00,2.791061088885749553e-01,4.286712417053070712e-01,1.361524071352429588e-01,1.000000006232531602e+00,0.000000000000000000e+00 +4.558818041998381432e+01,3.061975871548134478e+02,7.792022454863999359e-01,3.689586585027789134e+00,2.796061088885749557e-01,4.313824264924315255e-01,1.361524071352429588e-01,1.000000006201196001e+00,0.000000000000000000e+00 +4.559089075074026454e+01,3.062071987969913494e+02,7.819620162458084112e-01,3.690755774086105223e+00,2.801061088885749562e-01,4.340927572656925748e-01,1.361524071352429588e-01,1.000000006258998653e+00,0.000000000000000000e+00 +4.559360022289504855e+01,3.062168090580824469e+02,7.847265924811341886e-01,3.691931936324510666e+00,2.806061088885749566e-01,4.368022294374366288e-01,1.361524071352429588e-01,1.000000005991647845e+00,0.000000000000000000e+00 +4.559630883187605832e+01,3.062264179356841964e+02,7.874959735012333484e-01,3.693115062766089363e+00,2.811061088885749570e-01,4.395108384346739783e-01,1.361524071352429588e-01,1.000000006121559259e+00,0.000000000000000000e+00 +4.559901657312701673e+01,3.062360254273943951e+02,7.902701586137605982e-01,3.694305144393563722e+00,2.816061088885749575e-01,4.422185797022113452e-01,1.361524071352429588e-01,1.000000005907816458e+00,0.000000000000000000e+00 +4.560172344210755568e+01,3.062456315308111812e+02,7.930491471251696067e-01,3.695502172149577103e+00,2.821061088885749579e-01,4.449254486987407886e-01,1.361524071352429588e-01,1.000000005933399994e+00,0.000000000000000000e+00 +4.560442943429323748e+01,3.062552362435329769e+02,7.958329383407133362e-01,3.696706136936966036e+00,2.826061088885749584e-01,4.476314409004764627e-01,1.361524071352429588e-01,1.000000005806047865e+00,0.000000000000000000e+00 +4.560713454517561871e+01,3.062648395631586595e+02,7.986215315644439317e-01,3.697917029619042673e+00,2.831061088885749588e-01,4.503365517985654098e-01,1.361524071352429588e-01,1.000000005736315867e+00,0.000000000000000000e+00 +4.560983877026230715e+01,3.062744414872873335e+02,8.014149260992131651e-01,3.699134841019870557e+00,2.836061088885749593e-01,4.530407769007693264e-01,1.361524071352429588e-01,1.000000005630255817e+00,0.000000000000000000e+00 +4.561254210507700435e+01,3.062840420135185582e+02,8.042131212466724355e-01,3.700359561924545293e+00,2.841061088885749597e-01,4.557441117306901268e-01,1.361524071352429588e-01,1.000000005638336686e+00,0.000000000000000000e+00 +4.561524454515955540e+01,3.062936411394522338e+02,8.070161163072728794e-01,3.701591183079473435e+00,2.846061088885749601e-01,4.584465518284795427e-01,1.361524071352429588e-01,1.000000005488953736e+00,0.000000000000000000e+00 +4.561794608606599155e+01,3.063032388626885449e+02,8.098239105802658155e-01,3.702829695192653592e+00,2.851061088885749606e-01,4.611480927497463300e-01,1.361524071352429588e-01,1.000000005403039571e+00,0.000000000000000000e+00 +4.562064672336858706e+01,3.063128351808280740e+02,8.126365033637026336e-01,3.704075088933954873e+00,2.856061088885749610e-01,4.638487300669346669e-01,1.361524071352429588e-01,1.000000005366906697e+00,0.000000000000000000e+00 +4.562334645265590183e+01,3.063224300914716878e+02,8.154538939544352383e-01,3.705327354935399331e+00,2.861061088885749615e-01,4.665484593687364567e-01,1.361524071352429588e-01,1.000000005194454644e+00,0.000000000000000000e+00 +4.562604526953281692e+01,3.063320235922207075e+02,8.182760816481159383e-01,3.706586483791443065e+00,2.866061088885749619e-01,4.692472762596718305e-01,1.361524071352429588e-01,1.000000005200509801e+00,0.000000000000000000e+00 +4.562874316962059851e+01,3.063416156806767390e+02,8.211030657391977794e-01,3.707852466059256447e+00,2.871061088885749624e-01,4.719451763614863071e-01,1.361524071352429588e-01,1.000000004983580215e+00,0.000000000000000000e+00 +4.563144014855693342e+01,3.063512063544417856e+02,8.239348455209348776e-01,3.709125292259008333e+00,2.876061088885749628e-01,4.746421553112620262e-01,1.361524071352429588e-01,1.000000005014150428e+00,0.000000000000000000e+00 +4.563413620199596465e+01,3.063607956111181920e+02,8.267714202853821970e-01,3.710404952874145401e+00,2.881061088885749633e-01,4.773382087638136650e-01,1.361524071352429588e-01,1.000000004806088860e+00,0.000000000000000000e+00 +4.563683132560834821e+01,3.063703834483085870e+02,8.296127893233961048e-01,3.711691438351678141e+00,2.886061088885749637e-01,4.800333323891513015e-01,1.361524071352429588e-01,1.000000004751009142e+00,0.000000000000000000e+00 +4.563952551508128863e+01,3.063799698636160542e+02,8.324589519246343716e-01,3.712984739102460185e+00,2.891061088885749641e-01,4.827275218748890984e-01,1.361524071352429588e-01,1.000000004592919156e+00,0.000000000000000000e+00 +4.564221876611856743e+01,3.063895548546439613e+02,8.353099073775562822e-01,3.714284845501474308e+00,2.896061088885749646e-01,4.854207729245409997e-01,1.361524071352429588e-01,1.000000004531320208e+00,0.000000000000000000e+00 +4.564491107444061413e+01,3.063991384189960741e+02,8.381656549694230796e-01,3.715591747888113971e+00,2.901061088885749650e-01,4.881130812587886059e-01,1.361524071352429588e-01,1.000000004427899380e+00,0.000000000000000000e+00 +4.564760243578452048e+01,3.064087205542765560e+02,8.410261939862978542e-01,3.716905436566468435e+00,2.906061088885749655e-01,4.908044426146110917e-01,1.361524071352429588e-01,1.000000004175747303e+00,0.000000000000000000e+00 +4.565029284590408309e+01,3.064183012580897980e+02,8.438915237130458769e-01,3.718225901805605638e+00,2.911061088885749659e-01,4.934948527454093292e-01,1.361524071352429588e-01,1.000000004193130954e+00,0.000000000000000000e+00 +4.565298230056985318e+01,3.064278805280406459e+02,8.467616434333347097e-01,3.719553133839855530e+00,2.916061088885749664e-01,4.961843074224571160e-01,1.361524071352429588e-01,1.000000004014303112e+00,0.000000000000000000e+00 +4.565567079556916497e+01,3.064374583617342864e+02,8.496365524296344285e-01,3.720887122869097396e+00,2.921061088885749668e-01,4.988728024325605470e-01,1.361524071352429588e-01,1.000000003825758821e+00,0.000000000000000000e+00 +4.565835832670617123e+01,3.064470347567762474e+02,8.525162499832178442e-01,3.722227859059040966e+00,2.926061088885749673e-01,5.015603335798496376e-01,1.361524071352429588e-01,1.000000003732710807e+00,0.000000000000000000e+00 +4.566104488980188592e+01,3.064566097107724545e+02,8.554007353741605035e-01,3.723575332541512406e+00,2.931061088885749677e-01,5.042468966855954138e-01,1.361524071352429588e-01,1.000000003576121621e+00,0.000000000000000000e+00 +4.566373048069421969e+01,3.064661832213291746e+02,8.582900078813411326e-01,3.724929533414739868e+00,2.936061088885749681e-01,5.069324875875352854e-01,1.361524071352429588e-01,1.000000003365154155e+00,0.000000000000000000e+00 +4.566641509523800835e+01,3.064757552860530154e+02,8.611840667824416373e-01,3.726290451743637266e+00,2.941061088885749686e-01,5.096171021403599344e-01,1.361524071352429588e-01,1.000000003280682614e+00,0.000000000000000000e+00 +4.566909872930505543e+01,3.064853259025509260e+02,8.640829113539472139e-01,3.727658077560089378e+00,2.946061088885749690e-01,5.123007362162080858e-01,1.361524071352429588e-01,1.000000003060295573e+00,0.000000000000000000e+00 +4.567178137878414645e+01,3.064948950684303099e+02,8.669865408711467936e-01,3.729032400863238284e+00,2.951061088885749695e-01,5.149833857035098772e-01,1.361524071352429588e-01,1.000000002863849824e+00,0.000000000000000000e+00 +4.567446303958111287e+01,3.065044627812988551e+02,8.698949546081330420e-01,3.730413411619766695e+00,2.956061088885749699e-01,5.176650465081528152e-01,1.361524071352429588e-01,1.000000002659327647e+00,0.000000000000000000e+00 +4.567714370761883202e+01,3.065140290387645905e+02,8.728081518378025816e-01,3.731801099764184393e+00,2.961061088885749704e-01,5.203457145529986061e-01,1.361524071352429588e-01,1.000000002533237398e+00,0.000000000000000000e+00 +4.567982337883727695e+01,3.065235938384359997e+02,8.757261318318559917e-01,3.733195455199113333e+00,2.966061088885749708e-01,5.230253857782319882e-01,1.361524071352429588e-01,1.000000002322186221e+00,0.000000000000000000e+00 +4.568250204919354474e+01,3.065331571779218507e+02,8.786488938607983634e-01,3.734596467795573638e+00,2.971061088885749712e-01,5.257040561407213541e-01,1.361524071352429588e-01,1.000000001985551501e+00,0.000000000000000000e+00 +4.568517971466188499e+01,3.065427190548313661e+02,8.815764371939391886e-01,3.736004127393267815e+00,2.976061088885749717e-01,5.283817216143777973e-01,1.361524071352429588e-01,1.000000001918306625e+00,0.000000000000000000e+00 +4.568785637123372112e+01,3.065522794667740527e+02,8.845087610993926930e-01,3.737418423800865863e+00,2.981061088885749721e-01,5.310583781913501555e-01,1.361524071352429588e-01,1.000000001589750998e+00,0.000000000000000000e+00 +4.569053201491769300e+01,3.065618384113597585e+02,8.874458648440778363e-01,3.738839346796293484e+00,2.986061088885749726e-01,5.337340218795748603e-01,1.361524071352429588e-01,1.000000001280522577e+00,0.000000000000000000e+00 +4.569320664173967117e+01,3.065713958861987862e+02,8.903877476937187563e-01,3.740266886127013635e+00,2.991061088885749730e-01,5.364086487049756213e-01,1.361524071352429588e-01,1.000000001156354124e+00,0.000000000000000000e+00 +4.569588024774278523e+01,3.065809518889017795e+02,8.933344089128447685e-01,3.741701031510313857e+00,2.996061088885749735e-01,5.390822547111818741e-01,1.361524071352429588e-01,1.000000000709437398e+00,0.000000000000000000e+00 +4.569855282898745941e+01,3.065905064170797232e+02,8.962858477647904776e-01,3.743141772633592712e+00,3.001061088885749739e-01,5.417548359577540884e-01,1.361524071352429588e-01,1.000000000562929259e+00,0.000000000000000000e+00 +4.570122438155143385e+01,3.066000594683439999e+02,8.992420635116963323e-01,3.744589099154641332e+00,3.006061088885749744e-01,5.444263885232326627e-01,1.361524071352429588e-01,1.000000000173311143e+00,0.000000000000000000e+00 +4.570389490152978595e+01,3.066096110403063335e+02,9.022030554145082926e-01,3.746043000701932968e+00,3.011061088885749748e-01,5.470969085020443989e-01,1.361524071352429588e-01,9.999999997596031864e-01,0.000000000000000000e+00 +4.570656438503494456e+01,3.066191611305788456e+02,9.051688227329783842e-01,3.747503466874904099e+00,3.016061088885749752e-01,5.497663920065642973e-01,1.361524071352429588e-01,9.999999995606555503e-01,0.000000000000000000e+00 +4.570923282819674682e+01,3.066287097367739989e+02,9.081393647256649215e-01,3.748970487244240868e+00,3.021061088885749757e-01,5.524348351671908297e-01,1.361524071352429588e-01,9.999999990872574518e-01,0.000000000000000000e+00 +4.571190022716241685e+01,3.066382568565045972e+02,9.111146806499323958e-01,3.750444051352165520e+00,3.026061088885749761e-01,5.551022341304254759e-01,1.361524071352429588e-01,9.999999986216152603e-01,0.000000000000000000e+00 +4.571456657809662261e+01,3.066478024873839558e+02,9.140947697619516976e-01,3.751924148712717511e+00,3.031061088885749766e-01,5.577685850609535034e-01,1.361524071352429588e-01,9.999999982840633850e-01,0.000000000000000000e+00 +4.571723187718147585e+01,3.066573466270255608e+02,9.170796313167006719e-01,3.753410768812039944e+00,3.036061088885749770e-01,5.604338841412325189e-01,1.361524071352429588e-01,9.999999977842730647e-01,0.000000000000000000e+00 +4.571989612061656771e+01,3.066668892730434663e+02,9.200692645679640069e-01,3.754903901108664677e+00,3.041061088885749775e-01,5.630981275704183275e-01,1.361524071352429588e-01,9.999999972984333629e-01,0.000000000000000000e+00 +4.572255930461897577e+01,3.066764304230519542e+02,9.230636687683333452e-01,3.756403535033794316e+00,3.046061088885749779e-01,5.657613115656283664e-01,1.361524071352429588e-01,9.999999967210080332e-01,0.000000000000000000e+00 +4.572522142542328538e+01,3.066859700746657609e+02,9.260628431692076168e-01,3.757909659991587326e+00,3.051061088885749784e-01,5.684234323612100681e-01,1.361524071352429588e-01,9.999999961674640447e-01,0.000000000000000000e+00 +4.572788247928162519e+01,3.066955082254999638e+02,9.290667870207932610e-01,3.759422265359440907e+00,3.056061088885749788e-01,5.710844862093478191e-01,1.361524071352429588e-01,9.999999954746588982e-01,0.000000000000000000e+00 +4.573054246246365295e+01,3.067050448731700385e+02,9.320754995721043379e-01,3.760941340488275220e+00,3.061061088885749792e-01,5.737444693793390948e-01,1.361524071352429588e-01,9.999999948306579345e-01,0.000000000000000000e+00 +4.573320137125660523e+01,3.067145800152918582e+02,9.350889800709627497e-01,3.762466874702815378e+00,3.066061088885749797e-01,5.764033781585460314e-01,1.361524071352429588e-01,9.999999940225972050e-01,0.000000000000000000e+00 +4.573585920196529031e+01,3.067241136494815805e+02,9.381072277639983525e-01,3.763998857301875667e+00,3.071061088885749801e-01,5.790612088513453770e-01,1.361524071352429588e-01,9.999999933188288281e-01,0.000000000000000000e+00 +4.573851595091211664e+01,3.067336457733558177e+02,9.411302418966491778e-01,3.765537277558640650e+00,3.076061088885749806e-01,5.817179577804235668e-01,1.361524071352429588e-01,9.999999922759288395e-01,0.000000000000000000e+00 +4.574117161443710700e+01,3.067431763845315231e+02,9.441580217131618769e-01,3.767082124720949388e+00,3.081061088885749810e-01,5.843736212849003353e-01,1.361524071352429588e-01,9.999999913130517282e-01,0.000000000000000000e+00 +4.574382618889789853e+01,3.067527054806260480e+02,9.471905664565913874e-01,3.768633388011574326e+00,3.086061088885749815e-01,5.870281957226347602e-01,1.361524071352429588e-01,9.999999902044384159e-01,0.000000000000000000e+00 +4.574647967066978538e+01,3.067622330592571416e+02,9.502278753688014890e-01,3.770191056628505955e+00,3.091061088885749819e-01,5.896816774685258444e-01,1.361524071352429588e-01,9.999999889612855020e-01,0.000000000000000000e+00 +4.574913205614569023e+01,3.067717591180428940e+02,9.532699476904651359e-01,3.771755119745232587e+00,3.096061088885749824e-01,5.923340629151550019e-01,1.361524071352429588e-01,9.999999875197191912e-01,0.000000000000000000e+00 +4.575178334173622119e+01,3.067812836546017934e+02,9.563167826610641242e-01,3.773325566511021467e+00,3.101061088885749828e-01,5.949853484725993180e-01,1.361524071352429588e-01,9.999999859312481698e-01,0.000000000000000000e+00 +4.575443352386965756e+01,3.067908066665527258e+02,9.593683795188897578e-01,3.774902386051198988e+00,3.106061088885749832e-01,5.976355305687492958e-01,1.361524071352429588e-01,9.999999841127562572e-01,0.000000000000000000e+00 +4.575708259899195696e+01,3.068003281515149183e+02,9.624247375010428485e-01,3.776485567467431359e+00,3.111061088885749837e-01,6.002846056489630211e-01,1.361524071352429588e-01,9.999999819735935214e-01,0.000000000000000000e+00 +4.575973056356678370e+01,3.068098481071079959e+02,9.654858558434339377e-01,3.778075099838003936e+00,3.116061088885749841e-01,6.029325701760569478e-01,1.361524071352429588e-01,9.999999795446605777e-01,0.000000000000000000e+00 +4.576237741407550885e+01,3.068193665309519815e+02,9.685517337807834082e-01,3.779670972218100111e+00,3.121061088885749846e-01,6.055794206306377436e-01,1.361524071352429588e-01,9.999999766636010756e-01,0.000000000000000000e+00 +4.576502314701721019e+01,3.068288834206672391e+02,9.716223705466218163e-01,3.781273173640080643e+00,3.126061088885749850e-01,6.082251535105999141e-01,1.361524071352429588e-01,9.999999731023424543e-01,0.000000000000000000e+00 +4.576766775890870775e+01,3.068383987738745873e+02,9.746977653732900038e-01,3.782881693113761212e+00,3.131061088885749855e-01,6.108697653309611564e-01,1.361524071352429588e-01,9.999999688228004002e-01,0.000000000000000000e+00 +4.577031124628453540e+01,3.068479125881951290e+02,9.777779174919393190e-01,3.784496519626689093e+00,3.136061088885749859e-01,6.135132526243733952e-01,1.361524071352429588e-01,9.999999635347123217e-01,0.000000000000000000e+00 +4.577295360569698346e+01,3.068574248612504789e+02,9.808628261325317288e-01,3.786117642144420703e+00,3.141061088885749863e-01,6.161556119404637544e-01,1.361524071352429588e-01,9.999999565680589564e-01,0.000000000000000000e+00 +4.577559483371607030e+01,3.068669355906625356e+02,9.839524905238400398e-01,3.787745049610796944e+00,3.146061088885749868e-01,6.187968398448393526e-01,1.361524071352429588e-01,9.999999475107984592e-01,0.000000000000000000e+00 +4.577823492692958496e+01,3.068764447740535957e+02,9.870469098934481211e-01,3.789378730948215424e+00,3.151061088885749872e-01,6.214369329197773073e-01,1.361524071352429588e-01,9.999999346164825109e-01,0.000000000000000000e+00 +4.578087388194305873e+01,3.068859524090464106e+02,9.901460834677512368e-01,3.791018675057904019e+00,3.156061088885749877e-01,6.240758877607104349e-01,1.361524071352429588e-01,9.999999153744290048e-01,0.000000000000000000e+00 +4.578351169537980070e+01,3.068954584932640159e+02,9.932500104719560463e-01,3.792664870820184664e+00,3.161061088885749881e-01,6.267137009742239639e-01,1.361524071352429588e-01,9.999998832470438082e-01,0.000000000000000000e+00 +4.578614836388086928e+01,3.069049630243299589e+02,9.963586901300807153e-01,3.794317307094731362e+00,3.166061088885749886e-01,6.293503691674534606e-01,1.361524071352429588e-01,9.999998190164022249e-01,0.000000000000000000e+00 +4.578878388410510070e+01,3.069144659998680709e+02,9.994721216649553597e-01,3.795975972720799785e+00,3.171061088885749890e-01,6.319858889146990899e-01,1.361524071352429588e-01,9.999996263793252682e-01,0.000000000000000000e+00 +4.579141825272910182e+01,3.069239674175025812e+02,1.002590304298222268e+00,3.797640856517368491e+00,3.176061088885749895e-01,6.346202565544462049e-01,1.361524071352429588e-01,-8.921718892017822533e-01,0.000000000000000000e+00 +4.579405146644725733e+01,3.069334672748581738e+02,1.005713237250335679e+00,3.799311947282745461e+00,3.181061088885749899e-01,6.322709772968495567e-01,1.361524071352429588e-01,-9.999996228816463439e-01,0.000000000000000000e+00 +4.579668352197172254e+01,3.069429655695598740e+02,1.008840919740562336e+00,3.800976119601496617e+00,3.186061088885749903e-01,6.296389227649840103e-01,1.361524071352429588e-01,-9.999998156100287083e-01,0.000000000000000000e+00 +4.579931442510958561e+01,3.069524622992331047e+02,1.011973350986981490e+00,3.802632638619119376e+00,3.191061088885749908e-01,6.270080201122336661e-01,1.361524071352429588e-01,-9.999998798597871108e-01,0.000000000000000000e+00 +4.580194418216222374e+01,3.069619574615036868e+02,1.015110530206485562e+00,3.804281517382070099e+00,3.196061088885749912e-01,6.243782633755352585e-01,1.361524071352429588e-01,-9.999999117948348282e-01,0.000000000000000000e+00 +4.580457279940684856e+01,3.069714510539978392e+02,1.018252456614779700e+00,3.805922768852348259e+00,3.201061088885749917e-01,6.217496463627675274e-01,1.361524071352429588e-01,-9.999999312341238955e-01,0.000000000000000000e+00 +4.580720028309670511e+01,3.069809430743421217e+02,1.021399129426382446e+00,3.807556405907338348e+00,3.206061088885749921e-01,6.191221628535956700e-01,1.361524071352429588e-01,-9.999999439945885804e-01,0.000000000000000000e+00 +4.580982663946124234e+01,3.069904335201636059e+02,1.024550547854625515e+00,3.809182441340176695e+00,3.211061088885749926e-01,6.164958066361457822e-01,1.361524071352429588e-01,-9.999999531703885891e-01,0.000000000000000000e+00 +4.581245187470633340e+01,3.069999223890895905e+02,1.027706711111654236e+00,3.810800887860210651e+00,3.216061088885749930e-01,6.138705715139903818e-01,1.361524071352429588e-01,-9.999999600288207446e-01,0.000000000000000000e+00 +4.581507599501444616e+01,3.070094096787479430e+02,1.030867618408427777e+00,3.812411758093471992e+00,3.221061088885749935e-01,6.112464513107689346e-01,1.361524071352429588e-01,-9.999999654288322937e-01,0.000000000000000000e+00 +4.581769900654481376e+01,3.070188953867668147e+02,1.034033268954719587e+00,3.814015064583158310e+00,3.226061088885749939e-01,6.086234398710788085e-01,1.361524071352429588e-01,-9.999999696315147180e-01,0.000000000000000000e+00 +4.582032091543365482e+01,3.070283795107747551e+02,1.037203661959116952e+00,3.815610819790112629e+00,3.231061088885749943e-01,6.060015310618622753e-01,1.361524071352429588e-01,-9.999999731451586493e-01,0.000000000000000000e+00 +4.582294172779432273e+01,3.070378620484007115e+02,1.040378796629021441e+00,3.817199036093302578e+00,3.236061088885749948e-01,6.033807187715769516e-01,1.361524071352429588e-01,-9.999999761500100171e-01,0.000000000000000000e+00 +4.582556144971750456e+01,3.070473429972740860e+02,1.043558672170649571e+00,3.818779725790293345e+00,3.241061088885749952e-01,6.007609969108760328e-01,1.361524071352429588e-01,-9.999999784391654378e-01,0.000000000000000000e+00 +4.582818008727139869e+01,3.070568223550246216e+02,1.046743287789032362e+00,3.820352901097718412e+00,3.246061088885749957e-01,5.981423594134429589e-01,1.361524071352429588e-01,-9.999999807193453716e-01,0.000000000000000000e+00 +4.583079764650189247e+01,3.070663001192825163e+02,1.049932642688016005e+00,3.821918574151748516e+00,3.251061088885749961e-01,5.955248002334205815e-01,1.361524071352429588e-01,-9.999999824160739070e-01,0.000000000000000000e+00 +4.583341413343273274e+01,3.070757762876783090e+02,1.053126736070261860e+00,3.823476757008549942e+00,3.256061088885749966e-01,5.929083133485893997e-01,1.361524071352429588e-01,-9.999999841416217228e-01,0.000000000000000000e+00 +4.583602955406571056e+01,3.070852508578429365e+02,1.056325567137246457e+00,3.825027461644747273e+00,3.261061088885749970e-01,5.902928927570856299e-01,1.361524071352429588e-01,-9.999999854318328829e-01,0.000000000000000000e+00 +4.583864391438083885e+01,3.070947238274077904e+02,1.059529135089262164e+00,3.826570699957873689e+00,3.266061088885749975e-01,5.876785324800437582e-01,1.361524071352429588e-01,-9.999999867643047935e-01,0.000000000000000000e+00 +4.584125722033650874e+01,3.071041951940046033e+02,1.062737439125416961e+00,3.828106483766824386e+00,3.271061088885749979e-01,5.850652265589606493e-01,1.361524071352429588e-01,-9.999999878109411267e-01,0.000000000000000000e+00 +4.584386947786968136e+01,3.071136649552655626e+02,1.065950478443634886e+00,3.829634824812299332e+00,3.276061088885749983e-01,5.824529690576307761e-01,1.361524071352429588e-01,-9.999999888739010689e-01,0.000000000000000000e+00 +4.584648069289603711e+01,3.071231331088231968e+02,1.069168252240656036e+00,3.831155734757247355e+00,3.281061088885749988e-01,5.798417540603290066e-01,1.361524071352429588e-01,-9.999999897857331232e-01,0.000000000000000000e+00 +4.584909087131016037e+01,3.071325996523104891e+02,1.072390759712037012e+00,3.832669225187301798e+00,3.286061088885749992e-01,5.772315756728688685e-01,1.361524071352429588e-01,-9.999999906315544251e-01,0.000000000000000000e+00 +4.585170001898569581e+01,3.071420645833608205e+02,1.075618000052151135e+00,3.834175307611215278e+00,3.291061088885749997e-01,5.746224280217754332e-01,1.361524071352429588e-01,-9.999999912984515182e-01,0.000000000000000000e+00 +4.585430814177553316e+01,3.071515278996079132e+02,1.078849972454188233e+00,3.835673993461288678e+00,3.296061088885750001e-01,5.720143052546360352e-01,1.361524071352429588e-01,-9.999999920689633948e-01,0.000000000000000000e+00 +4.585691524551194220e+01,3.071609895986859442e+02,1.082086676110155077e+00,3.837165294093797474e+00,3.301061088885750006e-01,5.694072015389040065e-01,1.361524071352429588e-01,-9.999999926473355227e-01,0.000000000000000000e+00 +4.585952133600676461e+01,3.071704496782294882e+02,1.085328110210875829e+00,3.838649220789411398e+00,3.306061088885750010e-01,5.668011110632433791e-01,1.361524071352429588e-01,-9.999999932755053722e-01,0.000000000000000000e+00 +4.586212641905156318e+01,3.071799081358735748e+02,1.088574273945992044e+00,3.840125784753614102e+00,3.311061088885750014e-01,5.641960280359646918e-01,1.361524071352429588e-01,-9.999999937585228871e-01,0.000000000000000000e+00 +4.586473050041777810e+01,3.071893649692535178e+02,1.091825166503962885e+00,3.841594997117115273e+00,3.316061088885750019e-01,5.615919466860026521e-01,1.361524071352429588e-01,-9.999999943203905506e-01,0.000000000000000000e+00 +4.586733358585689757e+01,3.071988201760051993e+02,1.095080787072065132e+00,3.843056868936261861e+00,3.321061088885750023e-01,5.589888612616650265e-01,1.361524071352429588e-01,-9.999999948240726466e-01,0.000000000000000000e+00 +4.586993568110061403e+01,3.072082737537647290e+02,1.098341134836393618e+00,3.844511411193442640e+00,3.326061088885750028e-01,5.563867660314144592e-01,1.361524071352429588e-01,-9.999999951038145429e-01,0.000000000000000000e+00 +4.587253679186098054e+01,3.072177257001687281e+02,1.101606208981861457e+00,3.845958634797491449e+00,3.331061088885750032e-01,5.537856552837853163e-01,1.361524071352429588e-01,-9.999999956929284117e-01,0.000000000000000000e+00 +4.587513692383055286e+01,3.072271760128542724e+02,1.104876008692200040e+00,3.847398550584086863e+00,3.336061088885750037e-01,5.511855233254092656e-01,1.361524071352429588e-01,-9.999999959254418647e-01,0.000000000000000000e+00 +4.587773608268257419e+01,3.072366246894587221e+02,1.108150533149959704e+00,3.848831169316143441e+00,3.341061088885750041e-01,5.485863644839795716e-01,1.361524071352429588e-01,-9.999999964366121930e-01,0.000000000000000000e+00 +4.588033427407109599e+01,3.072460717276199489e+02,1.111429781536509065e+00,3.850256501684207411e+00,3.346061088885750046e-01,5.459881731047139253e-01,1.361524071352429588e-01,-9.999999966054151646e-01,0.000000000000000000e+00 +4.588293150363116268e+01,3.072555171249761656e+02,1.114713753032036347e+00,3.851674558306839913e+00,3.351061088885750050e-01,5.433909435534671761e-01,1.361524071352429588e-01,-9.999999969927578780e-01,0.000000000000000000e+00 +4.588552777697892537e+01,3.072649608791660398e+02,1.118002446815548501e+00,3.853085349731005138e+00,3.356061088885750054e-01,5.407946702135089101e-01,1.361524071352429588e-01,-9.999999973071002080e-01,0.000000000000000000e+00 +4.588812309971183367e+01,3.072744029878285801e+02,1.121295862064872084e+00,3.854488886432446915e+00,3.361061088885750059e-01,5.381993474875876871e-01,1.361524071352429588e-01,-9.999999975276793185e-01,0.000000000000000000e+00 +4.589071747740875651e+01,3.072838434486033066e+02,1.124593997956653268e+00,3.855885178816067516e+00,3.366061088885750063e-01,5.356049697970782786e-01,1.361524071352429588e-01,-9.999999979108737946e-01,0.000000000000000000e+00 +4.589331091563013842e+01,3.072932822591300805e+02,1.127896853666358279e+00,3.857274237216301138e+00,3.371061088885750068e-01,5.330115315811148058e-01,1.361524071352429588e-01,-9.999999980046698767e-01,0.000000000000000000e+00 +4.589590341991814171e+01,3.073027194170492180e+02,1.131204428368272952e+00,3.858656071897482054e+00,3.376061088885750072e-01,5.304190272982812759e-01,1.361524071352429588e-01,-9.999999983699627837e-01,0.000000000000000000e+00 +4.589849499579680980e+01,3.073121549200014329e+02,1.134516721235503844e+00,3.860030693054214090e+00,3.381061088885750077e-01,5.278274514238390225e-01,1.361524071352429588e-01,-9.999999986046052003e-01,0.000000000000000000e+00 +4.590108564877218811e+01,3.073215887656278937e+02,1.137833731439977569e+00,3.861398110811729900e+00,3.386061088885750081e-01,5.252367984520789346e-01,1.361524071352429588e-01,-9.999999986680725428e-01,0.000000000000000000e+00 +4.590367538433247319e+01,3.073310209515700535e+02,1.141155458152441904e+00,3.862758335226253337e+00,3.391061088885750086e-01,5.226470628952397668e-01,1.361524071352429588e-01,-9.999999990207378842e-01,0.000000000000000000e+00 +4.590626420794817619e+01,3.073404514754699335e+02,1.144481900542464903e+00,3.864111376285356059e+00,3.396061088885750090e-01,5.200582392820686239e-01,1.361524071352429588e-01,-9.999999991708766744e-01,0.000000000000000000e+00 +4.590885212507224367e+01,3.073498803349698392e+02,1.147813057778436008e+00,3.865457243908307472e+00,3.401061088885750094e-01,5.174703221601449910e-01,1.361524071352429588e-01,-9.999999993351619265e-01,0.000000000000000000e+00 +4.591143914114019964e+01,3.073593075277125877e+02,1.151148929027566048e+00,3.866795947946427781e+00,3.406061088885750099e-01,5.148833060939057571e-01,1.361524071352429588e-01,-9.999999995156687582e-01,0.000000000000000000e+00 +4.591402526157029484e+01,3.073687330513413940e+02,1.154489513455887240e+00,3.868127498183433044e+00,3.411061088885750103e-01,5.122971856650614386e-01,1.361524071352429588e-01,-9.999999996370148025e-01,0.000000000000000000e+00 +4.591661049176363463e+01,3.073781569034998711e+02,1.157834810228253408e+00,3.869451904335778458e+00,3.416061088885750108e-01,5.097119554726579072e-01,1.361524071352429588e-01,-9.999999999488013991e-01,0.000000000000000000e+00 +4.591919483710432814e+01,3.073875790818320297e+02,1.161184818508340433e+00,3.870769176052998972e+00,3.421061088885750112e-01,5.071276101320987273e-01,1.361524071352429588e-01,-9.999999999668531814e-01,0.000000000000000000e+00 +4.592177830295960916e+01,3.073969995839823923e+02,1.164539537458646024e+00,3.872079322918044575e+00,3.426061088885750117e-01,5.045441442769051932e-01,1.361524071352429588e-01,-1.000000000139623202e+00,0.000000000000000000e+00 +4.592436089467998528e+01,3.074064184075957655e+02,1.167898966240490832e+00,3.873382354447617359e+00,3.431061088885750121e-01,5.019615525561704761e-01,1.361524071352429588e-01,-1.000000000322890159e+00,0.000000000000000000e+00 +4.592694261759936580e+01,3.074158355503174676e+02,1.171263104014017342e+00,3.874678280092499261e+00,3.436061088885750125e-01,4.993798296359567290e-01,1.361524071352429588e-01,-1.000000000382343490e+00,0.000000000000000000e+00 +4.592952347703520388e+01,3.074252510097932145e+02,1.174631949938191422e+00,3.875967109237880681e+00,3.441061088885750130e-01,4.967989701991353813e-01,1.361524071352429588e-01,-1.000000000597910166e+00,0.000000000000000000e+00 +4.593210347828861018e+01,3.074346647836691204e+02,1.178005503170801438e+00,3.877248851203686009e+00,3.446061088885750134e-01,4.942189689441852662e-01,1.361524071352429588e-01,-1.000000000734493355e+00,0.000000000000000000e+00 +4.593468262664450918e+01,3.074440768695917541e+02,1.181383762868459142e+00,3.878523515244893360e+00,3.451061088885750139e-01,4.916398205863901638e-01,1.361524071352429588e-01,-1.000000000712488957e+00,0.000000000000000000e+00 +4.593726092737175293e+01,3.074534872652080821e+02,1.184766728186599671e+00,3.879791110551854771e+00,3.456061088885750143e-01,4.890615198573062816e-01,1.361524071352429588e-01,-1.000000000946533740e+00,0.000000000000000000e+00 +4.593983838572326306e+01,3.074628959681655260e+02,1.188154398279481549e+00,3.881051646250612386e+00,3.461061088885750148e-01,4.864840615033582116e-01,1.361524071352429588e-01,-1.000000001013316098e+00,0.000000000000000000e+00 +4.594241500693613744e+01,3.074723029761119051e+02,1.191546772300187573e+00,3.882305131403208431e+00,3.466061088885750152e-01,4.839074402878704162e-01,1.361524071352429588e-01,-1.000000001192244081e+00,0.000000000000000000e+00 +4.594499079623180648e+01,3.074817082866954934e+02,1.194943849400623925e+00,3.883551575007997858e+00,3.471061088885750157e-01,4.813316509891276684e-01,1.361524071352429588e-01,-1.000000001198732447e+00,0.000000000000000000e+00 +4.594756575881614680e+01,3.074911118975649629e+02,1.198345628731521506e+00,3.884790985999953428e+00,3.476061088885750161e-01,4.787566884017010471e-01,1.361524071352429588e-01,-1.000000001326083687e+00,0.000000000000000000e+00 +4.595013989987960201e+01,3.075005138063693835e+02,1.201752109442435490e+00,3.886023373250971691e+00,3.481061088885750165e-01,4.761825473348331172e-01,1.361524071352429588e-01,-1.000000001377673975e+00,0.000000000000000000e+00 +4.595271322459731778e+01,3.075099140107582798e+02,1.205163290681745769e+00,3.887248745570172304e+00,3.486061088885750170e-01,4.736092226135741878e-01,1.361524071352429588e-01,-1.000000001608974731e+00,0.000000000000000000e+00 +4.595528573812925544e+01,3.075193125083815744e+02,1.208579171596656954e+00,3.888467111704197787e+00,3.491061088885750174e-01,4.710367090774940646e-01,1.361524071352429588e-01,-1.000000001523507986e+00,0.000000000000000000e+00 +4.595785744562034125e+01,3.075287092968897014e+02,1.211999751333199038e+00,3.889678480337507516e+00,3.496061088885750179e-01,4.684650015824929348e-01,1.361524071352429588e-01,-1.000000001756078616e+00,0.000000000000000000e+00 +4.596042835220055167e+01,3.075381043739333791e+02,1.215425029036226956e+00,3.890882860092673923e+00,3.501061088885750183e-01,4.658940949977684598e-01,1.361524071352429588e-01,-1.000000001726428778e+00,0.000000000000000000e+00 +4.596299846298506253e+01,3.075474977371638943e+02,1.218855003849421248e+00,3.892080259530668496e+00,3.506061088885750188e-01,4.633239842088185956e-01,1.361524071352429588e-01,-1.000000001791688797e+00,0.000000000000000000e+00 +4.596556778307436986e+01,3.075568893842329317e+02,1.222289674915288282e+00,3.893270687151153098e+00,3.511061088885750192e-01,4.607546641149100619e-01,1.361524071352429588e-01,-1.000000001974266750e+00,0.000000000000000000e+00 +4.596813631755438934e+01,3.075662793127925738e+02,1.225729041375160255e+00,3.894454151392762409e+00,3.516061088885750197e-01,4.581861296298188058e-01,1.361524071352429588e-01,-1.000000002031300461e+00,0.000000000000000000e+00 +4.597070407149659843e+01,3.075756675204953012e+02,1.229173102369195636e+00,3.895630660633385922e+00,3.521061088885750201e-01,4.556183756823916076e-01,1.361524071352429588e-01,-1.000000001996470322e+00,0.000000000000000000e+00 +4.597327104995815006e+01,3.075850540049940491e+02,1.232621857036379165e+00,3.896800223190449053e+00,3.526061088885750205e-01,4.530513972157166336e-01,1.361524071352429588e-01,-1.000000002184492587e+00,0.000000000000000000e+00 +4.597583725798197918e+01,3.075944387639422644e+02,1.236075304514522077e+00,3.897962847321189805e+00,3.531061088885750210e-01,4.504851891862843294e-01,1.361524071352429588e-01,-1.000000002115499553e+00,0.000000000000000000e+00 +4.597840270059692358e+01,3.076038217949936779e+02,1.239533443940262769e+00,3.899118541222931000e+00,3.536061088885750214e-01,4.479197465659096045e-01,1.361524071352429588e-01,-1.000000002339089811e+00,0.000000000000000000e+00 +4.598096738281785889e+01,3.076132030958025894e+02,1.242996274449066130e+00,3.900267313033355165e+00,3.541061088885750219e-01,4.453550643389736496e-01,1.361524071352429588e-01,-1.000000002278710109e+00,0.000000000000000000e+00 +4.598353130964579094e+01,3.076225826640236392e+02,1.246463795175224876e+00,3.901409170830770101e+00,3.546061088885750223e-01,4.427911375051972742e-01,1.361524071352429588e-01,-1.000000002394861864e+00,0.000000000000000000e+00 +4.598609448606798367e+01,3.076319604973119795e+02,1.249936005251858662e+00,3.902544122634379331e+00,3.551061088885750228e-01,4.402279610768660700e-01,1.361524071352429588e-01,-1.000000002364971330e+00,0.000000000000000000e+00 +4.598865691705806569e+01,3.076413365933231034e+02,1.253412903810914969e+00,3.903672176404543226e+00,3.556061088885750232e-01,4.376655300807241744e-01,1.361524071352429588e-01,-1.000000002573459223e+00,0.000000000000000000e+00 +4.599121860757615110e+01,3.076507109497130159e+02,1.256894489983169105e+00,3.904793340043042793e+00,3.561061088885750237e-01,4.351038395560487548e-01,1.361524071352429588e-01,-1.000000002491404860e+00,0.000000000000000000e+00 +4.599377956256893896e+01,3.076600835641381195e+02,1.260380762898224649e+00,3.905907621393336360e+00,3.566061088885750241e-01,4.325428845568774494e-01,1.361524071352429588e-01,-1.000000002574484625e+00,0.000000000000000000e+00 +4.599633978696984826e+01,3.076694544342552717e+02,1.263871721684513449e+00,3.907015028240819809e+00,3.571061088885750245e-01,4.299826601493740297e-01,1.361524071352429588e-01,-1.000000002641592500e+00,0.000000000000000000e+00 +4.599889928569911035e+01,3.076788235577217279e+02,1.267367365469295626e+00,3.908115568313077937e+00,3.576061088885750250e-01,4.274231614133482959e-01,1.361524071352429588e-01,-1.000000002690203837e+00,0.000000000000000000e+00 +4.600145806366388967e+01,3.076881909321952548e+02,1.270867693378660457e+00,3.909209249280137577e+00,3.581061088885750254e-01,4.248643834416880316e-01,1.361524071352429588e-01,-1.000000002764052764e+00,0.000000000000000000e+00 +4.600401612575837618e+01,3.076975565553339607e+02,1.274372704537525935e+00,3.910296078754717186e+00,3.586061088885750259e-01,4.223063213401307969e-01,1.361524071352429588e-01,-1.000000002752487349e+00,0.000000000000000000e+00 +4.600657347686392029e+01,3.077069204247964649e+02,1.277882398069639214e+00,3.911376064292473753e+00,3.591061088885750263e-01,4.197489702275497003e-01,1.361524071352429588e-01,-1.000000002800782495e+00,0.000000000000000000e+00 +4.600913012184911821e+01,3.077162825382417850e+02,1.281396773097577046e+00,3.912449213392248382e+00,3.596061088885750268e-01,4.171923252351902867e-01,1.361524071352429588e-01,-1.000000002837816870e+00,0.000000000000000000e+00 +4.601168606556993979e+01,3.077256428933293932e+02,1.284915828742745569e+00,3.913515533496307874e+00,3.601061088885750272e-01,4.146363815071162362e-01,1.361524071352429588e-01,-1.000000002918350894e+00,0.000000000000000000e+00 +4.601424131286982089e+01,3.077350014877192166e+02,1.288439564125380965e+00,3.914575031990585430e+00,3.606061088885750276e-01,4.120811341997803745e-01,1.361524071352429588e-01,-1.000000002954067435e+00,0.000000000000000000e+00 +4.601679586857977000e+01,3.077443583190715799e+02,1.291967978364549463e+00,3.915627716204918229e+00,3.611061088885750281e-01,4.095265784822838540e-01,1.361524071352429588e-01,-1.000000002920238718e+00,0.000000000000000000e+00 +4.601934973751848901e+01,3.077537133850473197e+02,1.295501070578147340e+00,3.916673593413283694e+00,3.616061088885750285e-01,4.069727095361077018e-01,1.361524071352429588e-01,-1.000000002994976489e+00,0.000000000000000000e+00 +4.602190292449245845e+01,3.077630666833076134e+02,1.299038839882901808e+00,3.917712670834033073e+00,3.621061088885750290e-01,4.044195225544897077e-01,1.361524071352429588e-01,-1.000000003085393496e+00,0.000000000000000000e+00 +4.602445543429605834e+01,3.077724182115142071e+02,1.302581285394370347e+00,3.918744955630121485e+00,3.626061088885750294e-01,4.018670127430121197e-01,1.361524071352429588e-01,-1.000000003033976403e+00,0.000000000000000000e+00 +4.602700727171166761e+01,3.077817679673291309e+02,1.306128406226941596e+00,3.919770454909337509e+00,3.631061088885750299e-01,3.993151753196624298e-01,1.361524071352429588e-01,-1.000000003099038137e+00,0.000000000000000000e+00 +4.602955844150975651e+01,3.077911159484150403e+02,1.309680201493835572e+00,3.920789175724531006e+00,3.636061088885750303e-01,3.967640055136688604e-01,1.361524071352429588e-01,-1.000000003138957538e+00,0.000000000000000000e+00 +4.603210894844900025e+01,3.078004621524348750e+02,1.313236670307103227e+00,3.921801125073836047e+00,3.641061088885750308e-01,3.942134985664184632e-01,1.361524071352429588e-01,-1.000000003160405049e+00,0.000000000000000000e+00 +4.603465879727638566e+01,3.078098065770520861e+02,1.316797811777627558e+00,3.922806309900894295e+00,3.646061088885750312e-01,3.916636497309766152e-01,1.361524071352429588e-01,-1.000000003184394970e+00,0.000000000000000000e+00 +4.603720799272729636e+01,3.078191492199305799e+02,1.320363625015123166e+00,3.923804737095075268e+00,3.651061088885750316e-01,3.891144542719490729e-01,1.361524071352429588e-01,-1.000000003249197800e+00,0.000000000000000000e+00 +4.603975653952562652e+01,3.078284900787347169e+02,1.323934109128136694e+00,3.924796413491694391e+00,3.656061088885750321e-01,3.865659074653372551e-01,1.361524071352429588e-01,-1.000000003138955318e+00,0.000000000000000000e+00 +4.604230444238388031e+01,3.078378291511292559e+02,1.327509263224047054e+00,3.925781345872228822e+00,3.661061088885750325e-01,3.840180045990856383e-01,1.361524071352429588e-01,-1.000000003343900490e+00,0.000000000000000000e+00 +4.604485170600326427e+01,3.078471664347794672e+02,1.331089086409065869e+00,3.926759540964532835e+00,3.666061088885750330e-01,3.814707409711829977e-01,1.361524071352429588e-01,-1.000000003215819833e+00,0.000000000000000000e+00 +4.604739833507379387e+01,3.078565019273509620e+02,1.334673577788237475e+00,3.927731005443046541e+00,3.671061088885750334e-01,3.789241118924638330e-01,1.361524071352429588e-01,-1.000000003365159706e+00,0.000000000000000000e+00 +4.604994433427438594e+01,3.078658356265099201e+02,1.338262736465438918e+00,3.928695745929009941e+00,3.676061088885750339e-01,3.763781126833037338e-01,1.361524071352429588e-01,-1.000000003336590115e+00,0.000000000000000000e+00 +4.605248970827295807e+01,3.078751675299229191e+02,1.341856561543380622e+00,3.929653768990666762e+00,3.681061088885750343e-01,3.738327386762358429e-01,1.361524071352429588e-01,-1.000000003254149172e+00,0.000000000000000000e+00 +4.605503446172653526e+01,3.078844976352569347e+02,1.345455052123606166e+00,3.930605081143473178e+00,3.686061088885750348e-01,3.712879852143780579e-01,1.361524071352429588e-01,-1.000000003413564764e+00,0.000000000000000000e+00 +4.605757859928132802e+01,3.078938259401795108e+02,1.349058207306493173e+00,3.931549688850300761e+00,3.691061088885750352e-01,3.687438476508997920e-01,1.361524071352429588e-01,-1.000000003392716552e+00,0.000000000000000000e+00 +4.606012212557284613e+01,3.079031524423585324e+02,1.352666026191252646e+00,3.932487598521636318e+00,3.696061088885750356e-01,3.662003213507523669e-01,1.361524071352429588e-01,-1.000000003425495665e+00,0.000000000000000000e+00 +4.606266504522598382e+01,3.079124771394623394e+02,1.356278507875929851e+00,3.933418816515784400e+00,3.701061088885750361e-01,3.636574016889041472e-01,1.361524071352429588e-01,-1.000000003375253854e+00,0.000000000000000000e+00 +4.606520736285511930e+01,3.079218000291597832e+02,1.359895651457404542e+00,3.934343349139063584e+00,3.706061088885750365e-01,3.611150840511880289e-01,1.361524071352429588e-01,-1.000000003423341832e+00,0.000000000000000000e+00 +4.606774908306420713e+01,3.079311211091201699e+02,1.363517456031390962e+00,3.935261202646003209e+00,3.711061088885750370e-01,3.585733638333982731e-01,1.361524071352429588e-01,-1.000000003453506592e+00,0.000000000000000000e+00 +4.607029021044687767e+01,3.079404403770132035e+02,1.367143920692437620e+00,3.936172383239536110e+00,3.716061088885750374e-01,3.560322364419531427e-01,1.361524071352429588e-01,-1.000000003465678411e+00,0.000000000000000000e+00 +4.607283074958652236e+01,3.079497578305090997e+02,1.370775044533928622e+00,3.937076897071191350e+00,3.721061088885750379e-01,3.534916972935059354e-01,1.361524071352429588e-01,-1.000000003441290142e+00,0.000000000000000000e+00 +4.607537070505638610e+01,3.079590734672784720e+02,1.374410826648083006e+00,3.937974750241284294e+00,3.726061088885750383e-01,3.509517418148989654e-01,1.361524071352429588e-01,-1.000000003482705235e+00,0.000000000000000000e+00 +4.607791008141967382e+01,3.079683872849923887e+02,1.378051266125955188e+00,3.938865948799104899e+00,3.731061088885750388e-01,3.484123654427639383e-01,1.361524071352429588e-01,-1.000000003471410048e+00,0.000000000000000000e+00 +4.608044888322963573e+01,3.079776992813224297e+02,1.381696362057435401e+00,3.939750498743103346e+00,3.736061088885750392e-01,3.458735636239909650e-01,1.361524071352429588e-01,-1.000000003551769767e+00,0.000000000000000000e+00 +4.608298711502963840e+01,3.079870094539405727e+02,1.385346113531249701e+00,3.940628406021075225e+00,3.741061088885750396e-01,3.433353318149695577e-01,1.361524071352429588e-01,-1.000000003513531244e+00,0.000000000000000000e+00 +4.608552478135329267e+01,3.079963178005192503e+02,1.389000519634960185e+00,3.941499676530343166e+00,3.746061088885750401e-01,3.407976654823978713e-01,1.361524071352429588e-01,-1.000000003482494071e+00,0.000000000000000000e+00 +4.608806188672451754e+01,3.080056243187314067e+02,1.392659579454965213e+00,3.942364316117938916e+00,3.751061088885750405e-01,3.382605601023391251e-01,1.361524071352429588e-01,-1.000000003509493585e+00,0.000000000000000000e+00 +4.609059843565763259e+01,3.080149290062504406e+02,1.396323292076500078e+00,3.943222330580781421e+00,3.756061088885750410e-01,3.357240111603220223e-01,1.361524071352429588e-01,-1.000000003503041857e+00,0.000000000000000000e+00 +4.609313443265745747e+01,3.080242318607501488e+02,1.399991656583636557e+00,3.944073725665853569e+00,3.761061088885750414e-01,3.331880141516122551e-01,1.361524071352429588e-01,-1.000000003645520774e+00,0.000000000000000000e+00 +4.609566988221939710e+01,3.080335328799048398e+02,1.403664672059283580e+00,3.944918507070378055e+00,3.766061088885750419e-01,3.306525645804288538e-01,1.361524071352429588e-01,-1.000000003428061834e+00,0.000000000000000000e+00 +4.609820478882952699e+01,3.080428320613892197e+02,1.407342337585187231e+00,3.945756680441989683e+00,3.771061088885750423e-01,3.281176579616082445e-01,1.361524071352429588e-01,-1.000000003587121711e+00,0.000000000000000000e+00 +4.610073915696468561e+01,3.080521294028785064e+02,1.411024652241931188e+00,3.946588251378910339e+00,3.776061088885750427e-01,3.255832898173589007e-01,1.361524071352429588e-01,-1.000000003549589067e+00,0.000000000000000000e+00 +4.610327299109255961e+01,3.080614249020483726e+02,1.414711615108936726e+00,3.947413225430114192e+00,3.781061088885750432e-01,3.230494556804934803e-01,1.361524071352429588e-01,-1.000000003577169005e+00,0.000000000000000000e+00 +4.610580629567176203e+01,3.080707185565749455e+02,1.418403225264463163e+00,3.948231608095499556e+00,3.786061088885750436e-01,3.205161510922255319e-01,1.361524071352429588e-01,-1.000000003454536213e+00,0.000000000000000000e+00 +4.610833907515194596e+01,3.080800103641348073e+02,1.422099481785608077e+00,3.949043404826053649e+00,3.791061088885750441e-01,3.179833716032914870e-01,1.361524071352429588e-01,-1.000000003598510379e+00,0.000000000000000000e+00 +4.611087133397386140e+01,3.080893003224050517e+02,1.425800383748307310e+00,3.949848621024018680e+00,3.796061088885750445e-01,3.154511127722631203e-01,1.361524071352429588e-01,-1.000000003605968635e+00,0.000000000000000000e+00 +4.611340307656945470e+01,3.080985884290631134e+02,1.429505930227335408e+00,3.950647262043052166e+00,3.801061088885750450e-01,3.129193701675384021e-01,1.361524071352429588e-01,-1.000000003501638313e+00,0.000000000000000000e+00 +4.611593430736196098e+01,3.081078746817869956e+02,1.433216120296305629e+00,3.951439333188390801e+00,3.806061088885750454e-01,3.103881393661722110e-01,1.361524071352429588e-01,-1.000000003532844461e+00,0.000000000000000000e+00 +4.611846503076596804e+01,3.081171590782551561e+02,1.436930953027670599e+00,3.952224839717009885e+00,3.811061088885750459e-01,3.078574159532280197e-01,1.361524071352429588e-01,-1.000000003547216076e+00,0.000000000000000000e+00 +4.612099525118751586e+01,3.081264416161464510e+02,1.440650427492722097e+00,3.953003786837779643e+00,3.816061088885750463e-01,3.053271955227050971e-01,1.361524071352429588e-01,-1.000000003549075034e+00,0.000000000000000000e+00 +4.612352497302418186e+01,3.081357222931403044e+02,1.444374542761591718e+00,3.953776179711622429e+00,3.821061088885750467e-01,3.027974736770576158e-01,1.361524071352429588e-01,-1.000000003492675704e+00,0.000000000000000000e+00 +4.612605420066516615e+01,3.081450011069165384e+02,1.448103297903250430e+00,3.954542023451667276e+00,3.826061088885750472e-01,3.002682460272375065e-01,1.361524071352429588e-01,-1.000000003562164119e+00,0.000000000000000000e+00 +4.612858293849136970e+01,3.081542780551554301e+02,1.451836691985509464e+00,3.955301323123403101e+00,3.831061088885750476e-01,2.977395081920296560e-01,1.361524071352429588e-01,-1.000000003548003891e+00,0.000000000000000000e+00 +4.613111119087546541e+01,3.081635531355377111e+02,1.455574724075020532e+00,3.956054083744828809e+00,3.836061088885750481e-01,2.952112557989646224e-01,1.361524071352429588e-01,-1.000000003473573651e+00,0.000000000000000000e+00 +4.613363896218200466e+01,3.081728263457446246e+02,1.459317393237275384e+00,3.956800310286604283e+00,3.841061088885750485e-01,2.926834844836468941e-01,1.361524071352429588e-01,-1.000000003527655501e+00,0.000000000000000000e+00 +4.613616625676748129e+01,3.081820976834579255e+02,1.463064698536606922e+00,3.957540007672198268e+00,3.846061088885750490e-01,2.901561898892547342e-01,1.361524071352429588e-01,-1.000000003509942781e+00,0.000000000000000000e+00 +4.613869307898042393e+01,3.081913671463597097e+02,1.466816639036188752e+00,3.958273180778033584e+00,3.851061088885750494e-01,2.876293676674419042e-01,1.361524071352429588e-01,-1.000000003458064946e+00,0.000000000000000000e+00 +4.614121943316147423e+01,3.082006347321326416e+02,1.470573213798035850e+00,3.958999834433633236e+00,3.856061088885750499e-01,2.851030134776547653e-01,1.361524071352429588e-01,-1.000000003510473467e+00,0.000000000000000000e+00 +4.614374532364346493e+01,3.082099004384598402e+02,1.474334421883004564e+00,3.959719973421763406e+00,3.861061088885750503e-01,2.825771229867966583e-01,1.361524071352429588e-01,-1.000000003420595807e+00,0.000000000000000000e+00 +4.614627075475150519e+01,3.082191642630248225e+02,1.478100262350792837e+00,3.960433602478574233e+00,3.866061088885750507e-01,2.800516918701198565e-01,1.361524071352429588e-01,-1.000000003463486609e+00,0.000000000000000000e+00 +4.614879573080305164e+01,3.082284262035116740e+02,1.481870734259940425e+00,3.961140726293741476e+00,3.871061088885750512e-01,2.775267158098277398e-01,1.361524071352429588e-01,-1.000000003462339082e+00,0.000000000000000000e+00 +4.615132025610800071e+01,3.082376862576049348e+02,1.485645836667829567e+00,3.961841349510603294e+00,3.876061088885750516e-01,2.750021904961361119e-01,1.361524071352429588e-01,-1.000000003416929628e+00,0.000000000000000000e+00 +4.615384433496876682e+01,3.082469444229895430e+02,1.489425568630684760e+00,3.962535476726298356e+00,3.881061088885750521e-01,2.724781116267476211e-01,1.361524071352429588e-01,-1.000000003435397522e+00,0.000000000000000000e+00 +4.615636797168034633e+01,3.082562006973510051e+02,1.493209929203572761e+00,3.963223112491901290e+00,3.886061088885750525e-01,2.699544749064990978e-01,1.361524071352429588e-01,-1.000000003387049752e+00,0.000000000000000000e+00 +4.615889117053041701e+01,3.082654550783752256e+02,1.496998917440403698e+00,3.963904261312555910e+00,3.891061088885750530e-01,2.674312760478855244e-01,1.361524071352429588e-01,-1.000000003392303105e+00,0.000000000000000000e+00 +4.616141393579939489e+01,3.082747075637486205e+02,1.500792532393930401e+00,3.964578927647608442e+00,3.896061088885750534e-01,2.649085107703478270e-01,1.361524071352429588e-01,-1.000000003335274945e+00,0.000000000000000000e+00 +4.616393627176054082e+01,3.082839581511580036e+02,1.504590773115749069e+00,3.965247115910737641e+00,3.901061088885750539e-01,2.623861748007909611e-01,1.361524071352429588e-01,-1.000000003354048150e+00,0.000000000000000000e+00 +4.616645818268001022e+01,3.082932068382908142e+02,1.508393638656299718e+00,3.965908830470084911e+00,3.906061088885750543e-01,2.598642638728654308e-01,1.361524071352429588e-01,-1.000000003283415984e+00,0.000000000000000000e+00 +4.616897967281693838e+01,3.083024536228348325e+02,1.512201128064865951e+00,3.966564075648381316e+00,3.911061088885750547e-01,2.573427737276547944e-01,1.361524071352429588e-01,-1.000000003354631017e+00,0.000000000000000000e+00 +4.617150074642353985e+01,3.083116985024784071e+02,1.516013240389575412e+00,3.967212855723075027e+00,3.916061088885750552e-01,2.548217001125987480e-01,1.361524071352429588e-01,-1.000000003288646910e+00,0.000000000000000000e+00 +4.617402140774514407e+01,3.083209414749102848e+02,1.519829974677399997e+00,3.967855174926454787e+00,3.921061088885750556e-01,2.523010387827029910e-01,1.361524071352429588e-01,-1.000000003205571142e+00,0.000000000000000000e+00 +4.617654166102030899e+01,3.083301825378197236e+02,1.523651329974156088e+00,3.968491037445775138e+00,3.926061088885750561e-01,2.497807854994563148e-01,1.361524071352429588e-01,-1.000000003276928284e+00,0.000000000000000000e+00 +4.617906151048088503e+01,3.083394216888964365e+02,1.527477305324504986e+00,3.969120447423377662e+00,3.931061088885750565e-01,2.472609360306250725e-01,1.361524071352429588e-01,-1.000000003167374363e+00,0.000000000000000000e+00 +4.618158096035207194e+01,3.083486589258306481e+02,1.531307899771952918e+00,3.969743408956810438e+00,3.936061088885750570e-01,2.447414861514546347e-01,1.361524071352429588e-01,-1.000000003224832401e+00,0.000000000000000000e+00 +4.618410001485253247e+01,3.083578942463130943e+02,1.535143112358851258e+00,3.970359926098949277e+00,3.941061088885750574e-01,2.422224316428721325e-01,1.361524071352429588e-01,-1.000000003152761163e+00,0.000000000000000000e+00 +4.618661867819442790e+01,3.083671276480349093e+02,1.538982942126396747e+00,3.970970002858113190e+00,3.946061088885750578e-01,2.397037682930349689e-01,1.361524071352429588e-01,-1.000000003130797177e+00,0.000000000000000000e+00 +4.618913695458352464e+01,3.083763591286877386e+02,1.542827388114632159e+00,3.971573643198182513e+00,3.951061088885750583e-01,2.371854918960562830e-01,1.361524071352429588e-01,-1.000000003116218839e+00,0.000000000000000000e+00 +4.619165484821924395e+01,3.083855886859637394e+02,1.546676449362445860e+00,3.972170851038712591e+00,3.956061088885750587e-01,2.346675982524904780e-01,1.361524071352429588e-01,-1.000000003055112163e+00,0.000000000000000000e+00 +4.619417236329475429e+01,3.083948163175554669e+02,1.550530124907572693e+00,3.972761630255047471e+00,3.961061088885750592e-01,2.321500831692870082e-01,1.361524071352429588e-01,-1.000000003023562511e+00,0.000000000000000000e+00 +4.619668950399704244e+01,3.084040420211560445e+02,1.554388413786593537e+00,3.973345984678432252e+00,3.966061088885750596e-01,2.296329424593890334e-01,1.361524071352429588e-01,-1.000000003018882699e+00,0.000000000000000000e+00 +4.619920627450697737e+01,3.084132657944590505e+02,1.558251315034936413e+00,3.973923918096123220e+00,3.971061088885750601e-01,2.271161719418580416e-01,1.361524071352429588e-01,-1.000000002960504064e+00,0.000000000000000000e+00 +4.620172267899938845e+01,3.084224876351585749e+02,1.562118827686876044e+00,3.974495434251497095e+00,3.976061088885750605e-01,2.245997674419963619e-01,1.361524071352429588e-01,-1.000000002901517915e+00,0.000000000000000000e+00 +4.620423872164314361e+01,3.084317075409491054e+02,1.565990950775534296e+00,3.975060536844159387e+00,3.981061088885750610e-01,2.220837247909375756e-01,1.361524071352429588e-01,-1.000000002959835488e+00,0.000000000000000000e+00 +4.620675440660122746e+01,3.084409255095256981e+02,1.569867683332880404e+00,3.975619229530050536e+00,3.986061088885750614e-01,2.195680398254106214e-01,1.361524071352429588e-01,-1.000000002828055568e+00,0.000000000000000000e+00 +4.620926973803078397e+01,3.084501415385838072e+02,1.573749024389731188e+00,3.976171515921550270e+00,3.991061088885750618e-01,2.170527083887371367e-01,1.361524071352429588e-01,-1.000000002827053924e+00,0.000000000000000000e+00 +4.621178472008323013e+01,3.084593556258195122e+02,1.577634972975751282e+00,3.976717399587583301e+00,3.996061088885750623e-01,2.145377263291785574e-01,1.361524071352429588e-01,-1.000000002784366959e+00,0.000000000000000000e+00 +4.621429935690429858e+01,3.084685677689292334e+02,1.581525528119453794e+00,3.977256884053719688e+00,4.001061088885750627e-01,2.120230895011050443e-01,1.361524071352429588e-01,-1.000000002736936233e+00,0.000000000000000000e+00 +4.621681365263412289e+01,3.084777779656099597e+02,1.585420688848199866e+00,3.977789972802276974e+00,4.006061088885750632e-01,2.095087937643969056e-01,1.361524071352429588e-01,-1.000000002651564301e+00,0.000000000000000000e+00 +4.621932761140730150e+01,3.084869862135590779e+02,1.589320454188199339e+00,3.978316669272419670e+00,4.011061088885750636e-01,2.069948349845494029e-01,1.361524071352429588e-01,-1.000000002706729063e+00,0.000000000000000000e+00 +4.622184123735297590e+01,3.084961925104746001e+02,1.593224823164510751e+00,3.978836976860257835e+00,4.016061088885750641e-01,2.044812090320693165e-01,1.361524071352429588e-01,-1.000000002591130865e+00,0.000000000000000000e+00 +4.622435453459489452e+01,3.085053968540549363e+02,1.597133794801042006e+00,3.979350898918943003e+00,4.021061088885750645e-01,2.019679117836350735e-01,1.361524071352429588e-01,-1.000000002488324435e+00,0.000000000000000000e+00 +4.622686750725149807e+01,3.085145992419990080e+02,1.601047368120550374e+00,3.979858438758765882e+00,4.026061088885750650e-01,1.994549391207819655e-01,1.361524071352429588e-01,-1.000000002586139969e+00,0.000000000000000000e+00 +4.622938015943596213e+01,3.085237996720061915e+02,1.604965542144642265e+00,3.980359599647249613e+00,4.031061088885750654e-01,1.969422869298210754e-01,1.361524071352429588e-01,-1.000000002373955033e+00,0.000000000000000000e+00 +4.623189249525629663e+01,3.085329981417763747e+02,1.608888315893774346e+00,3.980854384809241697e+00,4.036061088885750658e-01,1.944299511035239292e-01,1.361524071352429588e-01,-1.000000002472666960e+00,0.000000000000000000e+00 +4.623440451881540270e+01,3.085421946490099572e+02,1.612815688387253310e+00,3.981342797427009028e+00,4.041061088885750663e-01,1.919179275382093541e-01,1.361524071352429588e-01,-1.000000002243532027e+00,0.000000000000000000e+00 +4.623691623421113661e+01,3.085513891914077931e+02,1.616747658643235885e+00,3.981824840640324492e+00,4.046061088885750667e-01,1.894062121368382534e-01,1.361524071352429588e-01,-1.000000002322508408e+00,0.000000000000000000e+00 +4.623942764553640217e+01,3.085605817666713051e+02,1.620684225678729495e+00,3.982300517546560226e+00,4.051061088885750672e-01,1.868948008057418897e-01,1.361524071352429588e-01,-1.000000002227967588e+00,0.000000000000000000e+00 +4.624193875687918620e+01,3.085697723725023138e+02,1.624625388509592483e+00,3.982769831200771549e+00,4.056061088885750676e-01,1.843836894573596397e-01,1.361524071352429588e-01,-1.000000002121544940e+00,0.000000000000000000e+00 +4.624444957232266518e+01,3.085789610066031514e+02,1.628571146150534110e+00,3.983232784615786670e+00,4.061061088885750681e-01,1.818728740085541196e-01,1.361524071352429588e-01,-1.000000002175595260e+00,0.000000000000000000e+00 +4.624696009594524071e+01,3.085881476666766616e+02,1.632521497615115003e+00,3.983689380762291066e+00,4.066061088885750685e-01,1.793623503805155117e-01,1.361524071352429588e-01,-1.000000001939693961e+00,0.000000000000000000e+00 +4.624947033182063194e+01,3.085973323504261998e+02,1.636476441915747371e+00,3.984139622568910521e+00,4.071061088885750689e-01,1.768521145002563411e-01,1.361524071352429588e-01,-1.000000001962233709e+00,0.000000000000000000e+00 +4.625198028401792527e+01,3.086065150555555761e+02,1.640435978063695233e+00,3.984583512922296844e+00,4.076061088885750694e-01,1.743421622980354524e-01,1.361524071352429588e-01,-1.000000001888669221e+00,0.000000000000000000e+00 +4.625448995660166673e+01,3.086156957797691121e+02,1.644400105069074414e+00,3.985021054667206020e+00,4.081061088885750698e-01,1.718324897095563908e-01,1.361524071352429588e-01,-1.000000001801160554e+00,0.000000000000000000e+00 +4.625699935363189752e+01,3.086248745207716411e+02,1.648368821940853213e+00,3.985452250606580815e+00,4.086061088885750703e-01,1.693230926748030274e-01,1.361524071352429588e-01,-1.000000001726312204e+00,0.000000000000000000e+00 +4.625950847916426056e+01,3.086340512762685080e+02,1.652342127686852402e+00,3.985877103501629382e+00,4.091061088885750707e-01,1.668139671381111411e-01,1.361524071352429588e-01,-1.000000001706268016e+00,0.000000000000000000e+00 +4.626201733725002896e+01,3.086432260439654556e+02,1.656320021313745672e+00,3.986295616071902970e+00,4.096061088885750712e-01,1.643051090480617538e-01,1.361524071352429588e-01,-1.000000001517347803e+00,0.000000000000000000e+00 +4.626452593193620544e+01,3.086523988215688519e+02,1.660302501827059629e+00,3.986707790995372314e+00,4.101061088885750716e-01,1.617965143580805121e-01,1.361524071352429588e-01,-1.000000001446992970e+00,0.000000000000000000e+00 +4.626703426726556501e+01,3.086615696067854628e+02,1.664289568231174021e+00,3.987113630908504458e+00,4.106061088885750721e-01,1.592881790250880725e-01,1.361524071352429588e-01,-1.000000001447811426e+00,0.000000000000000000e+00 +4.626954234727674731e+01,3.086707383973226229e+02,1.668281219529322401e+00,3.987513138406335145e+00,4.111061088885750725e-01,1.567800990102730663e-01,1.361524071352429588e-01,-1.000000001279254258e+00,0.000000000000000000e+00 +4.627205017600429926e+01,3.086799051908881211e+02,1.672277454723591905e+00,3.987906316042542088e+00,4.116061088885750729e-01,1.542722702795095158e-01,1.361524071352429588e-01,-1.000000001214406131e+00,0.000000000000000000e+00 +4.627455775747876032e+01,3.086890699851902582e+02,1.676278272814923920e+00,3.988293166329518247e+00,4.121061088885750734e-01,1.517646888020018625e-01,1.361524071352429588e-01,-1.000000001122918425e+00,0.000000000000000000e+00 +4.627706509572671933e+01,3.086982327779377897e+02,1.680283672803113859e+00,3.988673691738440663e+00,4.126061088885750738e-01,1.492573505512302112e-01,1.361524071352429588e-01,-1.000000000895215235e+00,0.000000000000000000e+00 +4.627957219477087136e+01,3.087073935668400964e+02,1.684293653686811609e+00,3.989047894699340624e+00,4.131061088885750743e-01,1.467502515048317302e-01,1.361524071352429588e-01,-1.000000001008644279e+00,0.000000000000000000e+00 +4.628207905863011007e+01,3.087165523496069568e+02,1.688308214463521972e+00,3.989415777601172497e+00,4.136061088885750747e-01,1.442433876430629924e-01,1.361524071352429588e-01,-1.000000000690886681e+00,0.000000000000000000e+00 +4.628458569131957745e+01,3.087257091239486613e+02,1.692327354129604888e+00,3.989777342791877679e+00,4.141061088885750752e-01,1.417367549518668279e-01,1.361524071352429588e-01,-1.000000000676586120e+00,0.000000000000000000e+00 +4.628709209685072068e+01,3.087348638875760116e+02,1.696351071680275435e+00,3.990132592578455206e+00,4.146061088885750756e-01,1.392303494190286761e-01,1.361524071352429588e-01,-1.000000000593350702e+00,0.000000000000000000e+00 +4.628959827923137738e+01,3.087440166382003213e+02,1.700379366109604273e+00,3.990481529227021706e+00,4.151061088885750761e-01,1.367241670368859741e-01,1.361524071352429588e-01,-1.000000000375580234e+00,0.000000000000000000e+00 +4.629210424246582534e+01,3.087531673735334152e+02,1.704412236410517867e+00,3.990824154962877124e+00,4.156061088885750765e-01,1.342182038014934631e-01,1.361524071352429588e-01,-1.000000000265553357e+00,0.000000000000000000e+00 +4.629460999055486781e+01,3.087623160912875733e+02,1.708449681574798484e+00,3.991160471970567336e+00,4.161061088885750769e-01,1.317124557117862749e-01,1.361524071352429588e-01,-1.000000000177551751e+00,0.000000000000000000e+00 +4.629711552749586900e+01,3.087714627891756436e+02,1.712491700593084865e+00,3.991490482393943662e+00,4.166061088885750774e-01,1.292069187703367150e-01,1.361524071352429588e-01,-9.999999999811939322e-01,0.000000000000000000e+00 +4.629962085728285359e+01,3.087806074649109860e+02,1.716538292454872439e+00,3.991814188336223257e+00,4.171061088885750778e-01,1.267015889834010034e-01,1.361524071352429588e-01,-9.999999998559402359e-01,0.000000000000000000e+00 +4.630212598390653511e+01,3.087897501162073581e+02,1.720589456148513108e+00,3.992131591860048623e+00,4.176061088885750783e-01,1.241964623600780443e-01,1.361524071352429588e-01,-9.999999996547298542e-01,0.000000000000000000e+00 +4.630463091135441545e+01,3.087988907407791430e+02,1.724645190661216132e+00,3.992442694987544005e+00,4.181061088885750787e-01,1.216915349130626989e-01,1.361524071352429588e-01,-9.999999996124336876e-01,0.000000000000000000e+00 +4.630713564361082746e+01,3.088080293363411784e+02,1.728705494979047907e+00,3.992747499700372682e+00,4.186061088885750792e-01,1.191868026576243939e-01,1.361524071352429588e-01,-9.999999992845199914e-01,0.000000000000000000e+00 +4.630964018465699894e+01,3.088171659006088134e+02,1.732770368086932189e+00,3.993046007939790698e+00,4.191061088885750796e-01,1.166822616132443952e-01,1.361524071352429588e-01,-9.999999992466027665e-01,0.000000000000000000e+00 +4.631214453847113077e+01,3.088263004312979092e+02,1.736839808968650756e+00,3.993338221606703708e+00,4.196061088885750801e-01,1.141779078009963061e-01,1.361524071352429588e-01,-9.999999989711982895e-01,0.000000000000000000e+00 +4.631464870902846087e+01,3.088354329261248381e+02,1.740913816606843634e+00,3.993624142561716273e+00,4.201061088885750805e-01,1.116737372462446171e-01,1.361524071352429588e-01,-9.999999987397042434e-01,0.000000000000000000e+00 +4.631715270030130682e+01,3.088445633828064842e+02,1.744992389983008652e+00,3.993903772625186921e+00,4.206061088885750809e-01,1.091697459765547940e-01,1.361524071352429588e-01,-9.999999986519232387e-01,0.000000000000000000e+00 +4.631965651625915115e+01,3.088536917990601864e+02,1.749075528077502772e+00,3.994177113577277005e+00,4.211061088885750814e-01,1.066659300220842016e-01,1.361524071352429588e-01,-9.999999984137467601e-01,0.000000000000000000e+00 +4.632216016086870525e+01,3.088628181726039088e+02,1.753163229869541206e+00,3.994444167157999548e+00,4.216061088885750818e-01,1.041622854165045464e-01,1.361524071352429588e-01,-9.999999981168684604e-01,0.000000000000000000e+00 +4.632466363809395204e+01,3.088719425011560133e+02,1.757255494337198742e+00,3.994704935067269425e+00,4.221061088885750823e-01,1.016588081959721168e-01,1.361524071352429588e-01,-9.999999978851819016e-01,0.000000000000000000e+00 +4.632716695189623124e+01,3.088810647824354305e+02,1.761352320457409082e+00,3.994959418964949993e+00,4.226061088885750827e-01,9.915549439898364847e-02,1.361524071352429588e-01,-9.999999977335611856e-01,0.000000000000000000e+00 +4.632967010623430326e+01,3.088901850141616023e+02,1.765453707205965950e+00,3.995207620470898391e+00,4.231061088885750832e-01,9.665234006658582344e-02,1.361524071352429588e-01,-9.999999973555122601e-01,0.000000000000000000e+00 +4.633217310506439190e+01,3.088993031940544256e+02,1.769559653557522427e+00,3.995449541165010388e+00,4.236061088885750836e-01,9.414934124311630237e-02,1.361524071352429588e-01,-9.999999971159888590e-01,0.000000000000000000e+00 +4.633467595234026959e+01,3.089084193198344224e+02,1.773670158485592063e+00,3.995685182587266127e+00,4.241061088885750840e-01,9.164649397445975842e-02,1.361524071352429588e-01,-9.999999968468655798e-01,0.000000000000000000e+00 +4.633717865201330000e+01,3.089175333892225126e+02,1.777785220962548651e+00,3.995914546237770537e+00,4.246061088885750845e-01,8.914379430931909654e-02,1.361524071352429588e-01,-9.999999964852471779e-01,0.000000000000000000e+00 +4.633968120803252333e+01,3.089266453999401847e+02,1.781904839959626674e+00,3.996137633576795967e+00,4.251061088885750849e-01,8.664123829888897843e-02,1.361524071352429588e-01,-9.999999961448593488e-01,0.000000000000000000e+00 +4.634218362434470606e+01,3.089357553497094386e+02,1.786029014446921304e+00,3.996354446024823037e+00,4.256061088885750854e-01,8.413882199635087933e-02,1.361524071352429588e-01,-9.999999959037922936e-01,0.000000000000000000e+00 +4.634468590489440487e+01,3.089448632362527860e+02,1.790157743393389067e+00,3.996564984962579281e+00,4.261061088885750858e-01,8.163654145689949737e-02,1.361524071352429588e-01,-9.999999953791989249e-01,0.000000000000000000e+00 +4.634718805362403060e+01,3.089539690572932500e+02,1.794291025766847625e+00,3.996769251731076888e+00,4.266061088885750863e-01,7.913439273883339509e-02,1.361524071352429588e-01,-9.999999950753687417e-01,0.000000000000000000e+00 +4.634969007447391220e+01,3.089630728105544222e+02,1.798428860533976437e+00,3.996967247631652231e+00,4.271061088885750867e-01,7.663237190127253351e-02,1.361524071352429588e-01,-9.999999946108327764e-01,0.000000000000000000e+00 +4.635219197138235359e+01,3.089721744937602921e+02,1.802571246660316762e+00,3.997158973925998726e+00,4.276061088885750872e-01,7.413047500631206321e-02,1.361524071352429588e-01,-9.999999941373338697e-01,0.000000000000000000e+00 +4.635469374828570466e+01,3.089812741046354745e+02,1.806718183110272102e+00,3.997344431836204137e+00,4.281061088885750876e-01,7.162869811762570538e-02,1.361524071352429588e-01,-9.999999937018485552e-01,0.000000000000000000e+00 +4.635719540911841818e+01,3.089903716409050958e+02,1.810869668847108427e+00,3.997523622544783439e+00,4.286061088885750880e-01,6.912703730066555030e-02,1.361524071352429588e-01,-9.999999931048560997e-01,0.000000000000000000e+00 +4.635969695781311373e+01,3.089994671002947371e+02,1.815025702832954391e+00,3.997696547194711236e+00,4.291061088885750885e-01,6.662548862321641951e-02,1.361524071352429588e-01,-9.999999926103182446e-01,0.000000000000000000e+00 +4.636219839830064160e+01,3.090085604805305479e+02,1.819186284028801337e+00,3.997863206889454624e+00,4.296061088885750889e-01,6.412404815417420412e-02,1.361524071352429588e-01,-9.999999918815112299e-01,0.000000000000000000e+00 +4.636469973451013971e+01,3.090176517793391326e+02,1.823351411394504185e+00,3.998023602693002054e+00,4.301061088885750894e-01,6.162271196498637221e-02,1.361524071352429588e-01,-9.999999913297568099e-01,0.000000000000000000e+00 +4.636720097036909038e+01,3.090267409944477208e+02,1.827521083888780984e+00,3.998177735629894869e+00,4.306061088885750898e-01,5.912147612771874450e-02,1.361524071352429588e-01,-9.999999905532513944e-01,0.000000000000000000e+00 +4.636970210980341278e+01,3.090358281235839968e+02,1.831695300469213805e+00,3.998325606685253053e+00,4.311061088885750903e-01,5.662033671702742382e-02,1.361524071352429588e-01,-9.999999897568919716e-01,0.000000000000000000e+00 +4.637220315673747706e+01,3.090449131644762133e+02,1.835874060092248294e+00,3.998467216804804991e+00,4.316061088885750907e-01,5.411928980857935029e-02,1.361524071352429588e-01,-9.999999889008196474e-01,0.000000000000000000e+00 +4.637470411509421098e+01,3.090539961148530779e+02,1.840057361713194783e+00,3.998602566894912336e+00,4.321061088885750912e-01,5.161833147960266654e-02,1.361524071352429588e-01,-9.999999879135494929e-01,0.000000000000000000e+00 +4.637720498879513542e+01,3.090630769724438096e+02,1.844245204286227624e+00,3.998731657822595320e+00,4.326061088885750916e-01,4.911745780890402341e-02,1.361524071352429588e-01,-9.999999869052728085e-01,0.000000000000000000e+00 +4.637970578176043546e+01,3.090721557349782529e+02,1.848437586764386520e+00,3.998854490415557184e+00,4.331061088885750920e-01,4.661666487635251349e-02,1.361524071352429588e-01,-9.999999855999955889e-01,0.000000000000000000e+00 +4.638220649790901717e+01,3.090812324001867069e+02,1.852634508099575639e+00,3.998971065462206376e+00,4.336061088885750925e-01,4.411594876378379521e-02,1.361524071352429588e-01,-9.999999844719564823e-01,0.000000000000000000e+00 +4.638470714115857163e+01,3.090903069657999822e+02,1.856835967242564722e+00,3.999081383711680093e+00,4.341061088885750929e-01,4.161530555306235113e-02,1.361524071352429588e-01,-9.999999828284602543e-01,0.000000000000000000e+00 +4.638720771542563170e+01,3.090993794295494581e+02,1.861041963142988864e+00,3.999185445873862044e+00,4.346061088885750934e-01,3.911473132893809185e-02,1.361524071352429588e-01,-9.999999812246042064e-01,0.000000000000000000e+00 +4.638970822462565025e+01,3.091084497891670253e+02,1.865252494749349399e+00,3.999283252619406426e+00,4.351061088885750938e-01,3.661422217586456085e-02,1.361524071352429588e-01,-9.999999792619294059e-01,0.000000000000000000e+00 +4.639220867267304982e+01,3.091175180423850861e+02,1.869467561009013234e+00,3.999374804579753029e+00,4.356061088885750943e-01,3.411377418032195824e-02,1.361524071352429588e-01,-9.999999770800054311e-01,0.000000000000000000e+00 +4.639470906348127244e+01,3.091265841869365545e+02,1.873687160868213963e+00,3.999460102347147217e+00,4.361061088885750947e-01,3.161338342941037022e-02,1.361524071352429588e-01,-9.999999744332835894e-01,0.000000000000000000e+00 +4.639720940096285773e+01,3.091356482205549128e+02,1.877911293272051640e+00,3.999539146474655471e+00,4.366061088885750952e-01,2.911304601175137771e-02,1.361524071352429588e-01,-9.999999713305006699e-01,0.000000000000000000e+00 +4.639970968902949977e+01,3.091447101409741549e+02,1.882139957164493005e+00,3.999611937476182266e+00,4.371061088885750956e-01,2.661275801679091266e-02,1.361524071352429588e-01,-9.999999678217782462e-01,0.000000000000000000e+00 +4.640220993159211105e+01,3.091537699459287865e+02,1.886373151488372368e+00,3.999678475826484281e+00,4.376061088885750960e-01,2.411251553463452171e-02,1.361524071352429588e-01,-9.999999631462240801e-01,0.000000000000000000e+00 +4.640471013256087218e+01,3.091628276331538814e+02,1.890610875185390949e+00,3.999738761961183275e+00,4.381061088885750965e-01,2.161231465801384186e-02,1.361524071352429588e-01,-9.999999575791066464e-01,0.000000000000000000e+00 +4.640721029584531010e+01,3.091718832003850252e+02,1.894853127196117981e+00,3.999792796276782969e+00,4.386061088885750969e-01,1.911215147963471472e-02,1.361524071352429588e-01,-9.999999503717992289e-01,0.000000000000000000e+00 +4.640971042535434776e+01,3.091809366453583152e+02,1.899099906459990272e+00,3.999840579130678364e+00,4.391061088885750974e-01,1.661202209467594476e-02,1.361524071352429588e-01,-9.999999406042852090e-01,0.000000000000000000e+00 +4.641221052499636102e+01,3.091899879658103600e+02,1.903351211915313312e+00,3.999882110841170402e+00,4.396061088885750978e-01,1.411192260115656967e-02,1.361524071352429588e-01,-9.999999271853136085e-01,0.000000000000000000e+00 +4.641471059867925675e+01,3.091990371594783369e+02,1.907607042499260608e+00,3.999917391687480617e+00,4.401061088885750983e-01,1.161184910030277871e-02,1.361524071352429588e-01,-9.999999069340608226e-01,0.000000000000000000e+00 +4.641721065031051552e+01,3.092080842240999914e+02,1.911867397147874570e+00,3.999946421909765792e+00,4.406061088885750987e-01,9.111797701710814060e-03,1.361524071352429588e-01,-9.999998730169812333e-01,0.000000000000000000e+00 +4.641971068379726972e+01,3.092171291574135239e+02,1.916132274796066515e+00,3.999969201709144606e+00,4.411061088885750991e-01,6.611764532417677663e-03,1.361524071352429588e-01,-9.999998054266197034e-01,0.000000000000000000e+00 +4.642221070304634623e+01,3.092261719571577032e+02,1.920401674377617107e+00,3.999985731247746035e+00,4.416061088885750996e-01,4.111745769774879239e-03,1.361524071352429588e-01,-9.999996024144747198e-01,0.000000000000000000e+00 +4.642471071196435162e+01,3.092352126210718097e+02,1.924675594825176361e+00,3.999996010648839029e+00,4.421061088885751000e-01,1.611737845740266904e-03,1.361524071352429588e-01,-6.447442116591992622e-01,0.000000000000000000e+00 +4.642721071445770065e+01,3.092442511468956923e+02,1.928954035070264306e+00,4.000000039997472001e+00,4.426061088885751005e-01,-1.242909787529309855e-07,1.361524071352429588e-01,4.971880784365459519e-05,0.000000000000000000e+00 +4.642971071443270148e+01,3.092532875323697112e+02,1.933236994043270984e+00,4.000000039686744557e+00,4.431061088885751009e-01,6.039613313883998619e-12,1.361524071352429588e-01,-2.415845349522858496e-09,0.000000000000000000e+00 +4.643221071440789416e+01,3.092623217752347955e+02,1.937524470673456456e+00,4.000000039686759656e+00,4.436061088885751014e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.643471071438308684e+01,3.092713538732323855e+02,1.941816463888951683e+00,4.000000039686759656e+00,4.441061088885751018e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.643721071435827952e+01,3.092803838241044332e+02,1.946112972616758530e+00,4.000000039686759656e+00,4.446061088885751023e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.643971071433347220e+01,3.092894116255934591e+02,1.950413995782749543e+00,4.000000039686759656e+00,4.451061088885751027e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.644221071430866488e+01,3.092984372754425522e+02,1.954719532311669283e+00,4.000000039686759656e+00,4.456061088885751031e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.644471071428385756e+01,3.093074607713952560e+02,1.959029581127133435e+00,4.000000039686759656e+00,4.461061088885751036e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.644721071425905023e+01,3.093164821111956826e+02,1.963344141151629918e+00,4.000000039686759656e+00,4.466061088885751040e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.644971071423424291e+01,3.093255012925885126e+02,1.967663211306518667e+00,4.000000039686759656e+00,4.471061088885751045e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.645221071420943559e+01,3.093345183133189948e+02,1.971986790512032073e+00,4.000000039686759656e+00,4.476061088885751049e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.645471071418462827e+01,3.093435331711328331e+02,1.976314877687275429e+00,4.000000039686759656e+00,4.481061088885751054e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.645721071415982095e+01,3.093525458637762995e+02,1.980647471750227151e+00,4.000000039686759656e+00,4.486061088885751058e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.645971071413501363e+01,3.093615563889962345e+02,1.984984571617738558e+00,4.000000039686759656e+00,4.491061088885751063e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.646221071411020631e+01,3.093705647445399904e+02,1.989326176205534757e+00,4.000000039686759656e+00,4.496061088885751067e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.646471071408539899e+01,3.093795709281555446e+02,1.993672284428214647e+00,4.000000039686759656e+00,4.501061088885751071e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.646721071406059167e+01,3.093885749375912724e+02,1.998022895199251137e+00,4.000000039686759656e+00,4.506061088885751076e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.646971071403578435e+01,3.093975767705962312e+02,2.002378007430991591e+00,4.000000039686759656e+00,4.511061088885751080e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.647221071401097703e+01,3.094065764249199333e+02,2.006737620034658054e+00,4.000000039686759656e+00,4.516061088885751085e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.647471071398616971e+01,3.094155738983124593e+02,2.011101731920347024e+00,4.000000039686759656e+00,4.521061088885751089e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.647721071396136239e+01,3.094245691885244582e+02,2.015470341997030790e+00,4.000000039686759656e+00,4.526061088885751094e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.647971071393655507e+01,3.094335622933070908e+02,2.019843449172557204e+00,4.000000039686759656e+00,4.531061088885751098e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.648221071391174775e+01,3.094425532104120862e+02,2.024221052353649242e+00,4.000000039686759656e+00,4.536061088885751102e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.648471071388694043e+01,3.094515419375917418e+02,2.028603150445905889e+00,4.000000039686759656e+00,4.541061088885751107e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.648721071386213310e+01,3.094605284725988099e+02,2.032989742353803031e+00,4.000000039686759656e+00,4.546061088885751111e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.648971071383732578e+01,3.094695128131867250e+02,2.037380826980692117e+00,4.000000039686759656e+00,4.551061088885751116e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.649221071381251846e+01,3.094784949571093762e+02,2.041776403228802828e+00,4.000000039686759656e+00,4.556061088885751120e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.649471071378771114e+01,3.094874749021212210e+02,2.046176469999240410e+00,4.000000039686759656e+00,4.561061088885751125e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.649721071376290382e+01,3.094964526459772856e+02,2.050581026191988787e+00,4.000000039686759656e+00,4.566061088885751129e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.649971071373809650e+01,3.095054281864331074e+02,2.054990070705908334e+00,4.000000039686759656e+00,4.571061088885751134e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.650221071371328918e+01,3.095144015212448494e+02,2.059403602438738545e+00,4.000000039686759656e+00,4.576061088885751138e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.650471071368848186e+01,3.095233726481691292e+02,2.063821620287096259e+00,4.000000039686759656e+00,4.581061088885751142e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.650721071366367454e+01,3.095323415649631897e+02,2.068244123146476987e+00,4.000000039686759656e+00,4.586061088885751147e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.650971071363886722e+01,3.095413082693847855e+02,2.072671109911254916e+00,4.000000039686759656e+00,4.591061088885751151e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.651221071361405990e+01,3.095502727591922394e+02,2.077102579474683353e+00,4.000000039686759656e+00,4.596061088885751156e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.651471071358925258e+01,3.095592350321444428e+02,2.081538530728895164e+00,4.000000039686759656e+00,4.601061088885751160e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.651721071356444526e+01,3.095681950860008556e+02,2.085978962564902339e+00,4.000000039686759656e+00,4.606061088885751165e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.651971071353963794e+01,3.095771529185214490e+02,2.090423873872597316e+00,4.000000039686759656e+00,4.611061088885751169e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.652221071351483062e+01,3.095861085274667630e+02,2.094873263540752095e+00,4.000000039686759656e+00,4.616061088885751174e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.652471071349002329e+01,3.095950619105978490e+02,2.099327130457019130e+00,4.000000039686759656e+00,4.621061088885751178e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.652721071346521597e+01,3.096040130656763836e+02,2.103785473507931769e+00,4.000000039686759656e+00,4.626061088885751182e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.652971071344040865e+01,3.096129619904646120e+02,2.108248291578904254e+00,4.000000039686759656e+00,4.631061088885751187e-01,0.000000000000000000e+00,1.361524071352429588e-01,-9.947598498035375109e-10,0.000000000000000000e+00 +4.653221071341560133e+01,3.096219086827252909e+02,2.112715583554232168e+00,4.000000039686759656e+00,4.636061088885751191e-01,-2.486899599834597004e-12,1.361524071352429588e-01,4.728917795706043145e-05,0.000000000000000000e+00 +4.653471071339079401e+01,3.096308531402217454e+02,2.117187348317092876e+00,4.000000039686753439e+00,4.641061088885751196e-01,1.182204568200798648e-07,1.361524071352429588e-01,-6.226300161337212646e-01,0.000000000000000000e+00 +4.653721071336598669e+01,3.096397953607178692e+02,2.121663584749544640e+00,4.000000039982304578e+00,4.646061088885751200e-01,-1.556456804433630717e-03,1.361524071352429588e-01,-9.999970095018867466e-01,0.000000000000000000e+00 +4.653971071334099463e+01,3.096487353419780675e+02,2.126144291732528835e+00,3.999996148840332388e+00,4.651061088885751205e-01,-4.056449303199482180e-03,1.361524071352429588e-01,-9.999984635107874720e-01,0.000000000000000000e+00 +4.654221071574797008e+01,3.096576730817673706e+02,2.130629468145868177e+00,3.999986007707310609e+00,4.656061088885751209e-01,-6.556447868949862555e-03,1.361524071352429588e-01,-9.999989461686454861e-01,0.000000000000000000e+00 +4.654471072449318569e+01,3.096666085778513207e+02,2.135119112868268942e+00,3.999969616530300698e+00,4.661061088885751214e-01,-9.056453979575782368e-03,1.361524071352429588e-01,-9.999991858710240988e-01,0.000000000000000000e+00 +4.654721074348299936e+01,3.096755418279960850e+02,2.139613224777320077e+00,3.999946975223371393e+00,4.666061088885751218e-01,-1.155647093405068847e-02,1.361524071352429588e-01,-9.999993282724214394e-01,0.000000000000000000e+00 +4.654971077662392531e+01,3.096844728299683425e+02,2.144111802749493645e+00,3.999918083663044133e+00,4.671061088885751222e-01,-1.405650239563419578e-02,1.361524071352429588e-01,-9.999994220104649889e-01,0.000000000000000000e+00 +4.655221082782268383e+01,3.096934015815353405e+02,2.148614845660144823e+00,3.999882941687379567e+00,4.676061088885751227e-01,-1.655655214938986722e-02,1.361524071352429588e-01,-9.999994874858274541e-01,0.000000000000000000e+00 +4.655471090098627229e+01,3.097023280804648380e+02,2.153122352383513238e+00,3.999841549095669357e+00,4.681061088885751231e-01,-1.905662403165342758e-02,1.361524071352429588e-01,-9.999995356202221464e-01,0.000000000000000000e+00 +4.655721100002200785e+01,3.097112523245252760e+02,2.157634321792722076e+00,3.999793905648303394e+00,4.686061088885751236e-01,-2.155672190639627492e-02,1.361524071352429588e-01,-9.999995716222351838e-01,0.000000000000000000e+00 +4.655971112883761265e+01,3.097201743114855503e+02,2.162150752759778971e+00,3.999740011066695189e+00,4.691061088885751240e-01,-2.405684965100353401e-02,1.361524071352429588e-01,-9.999995993924200022e-01,0.000000000000000000e+00 +4.656221129134125647e+01,3.097290940391152390e+02,2.166671644155576448e+00,3.999679865033241910e+00,4.696061088885751245e-01,-2.655701115306508681e-02,1.361524071352429588e-01,-9.999996206707043589e-01,0.000000000000000000e+00 +4.656471149144162780e+01,3.097380115051843177e+02,2.171196994849891482e+00,3.999613467191291516e+00,4.701061088885751249e-01,-2.905721030503494867e-02,1.361524071352429588e-01,-9.999996373808752725e-01,0.000000000000000000e+00 +4.656721173304798356e+01,3.097469267074635013e+02,2.175726803711386381e+00,3.999540817145122329e+00,4.706061088885751253e-01,-3.155745100475216419e-02,1.361524071352429588e-01,-9.999996497833559816e-01,0.000000000000000000e+00 +4.656971202007022015e+01,3.097558396437239026e+02,2.180261069607609237e+00,3.999461914459920386e+00,4.711061088885751258e-01,-3.405773715134325502e-02,1.361524071352429588e-01,-9.999996593167875814e-01,0.000000000000000000e+00 +4.657221235641893031e+01,3.097647503117373731e+02,2.184799791404993030e+00,3.999376758661766118e+00,4.716061088885751262e-01,-3.655807264822927977e-02,1.361524071352429588e-01,-9.999996656853131771e-01,0.000000000000000000e+00 +4.657471274600546707e+01,3.097736587092761624e+02,2.189342967968857856e+00,3.999285349237612586e+00,4.721061088885751267e-01,-3.905846139885032348e-02,1.361524071352429588e-01,-9.999996698419931773e-01,0.000000000000000000e+00 +4.657721319274200766e+01,3.097825648341132592e+02,2.193890598163409589e+00,3.999187685635273493e+00,4.726061088885751271e-01,-4.155890730984945769e-02,1.361524071352429588e-01,-9.999996712894100304e-01,0.000000000000000000e+00 +4.657971370054161042e+01,3.097914686840220497e+02,2.198442680851740327e+00,3.999083767263402311e+00,4.731061088885751276e-01,-4.405941428750724531e-02,1.361524071352429588e-01,-9.999996707786829031e-01,0.000000000000000000e+00 +4.658221427331827158e+01,3.098003702567766027e+02,2.202999214895829727e+00,3.998973593491479406e+00,4.736061088885751280e-01,-4.655998624092493737e-02,1.361524071352429588e-01,-9.999996677523128596e-01,0.000000000000000000e+00 +4.658471491498698924e+01,3.098092695501515550e+02,2.207560199156544112e+00,3.998857163649790269e+00,4.741061088885751285e-01,-4.906062707881359009e-02,1.361524071352429588e-01,-9.999996622617801645e-01,0.000000000000000000e+00 +4.658721562946384154e+01,3.098181665619220553e+02,2.212125632493637806e+00,3.998734477029410872e+00,4.746061088885751289e-01,-5.156134071107814493e-02,1.361524071352429588e-01,-9.999996541860167731e-01,0.000000000000000000e+00 +4.658971642066602215e+01,3.098270612898638774e+02,2.216695513765752246e+00,3.998605532882188118e+00,4.751061088885751293e-01,-5.406213104844732886e-02,1.361524071352429588e-01,-9.999996429473291260e-01,0.000000000000000000e+00 +4.659221729251191135e+01,3.098359537317533068e+02,2.221269841830416869e+00,3.998470330420720309e+00,4.756061088885751298e-01,-5.656300200139309509e-02,1.361524071352429588e-01,-9.999996282923001578e-01,0.000000000000000000e+00 +4.659471824892114711e+01,3.098448438853672542e+02,2.225848615544050002e+00,3.998328868818339377e+00,4.761061088885751302e-01,-5.906395748100291831e-02,1.361524071352429588e-01,-9.999996089426297363e-01,0.000000000000000000e+00 +4.659721929381467476e+01,3.098537317484831419e+02,2.230431833761958416e+00,3.998181147209090014e+00,4.766061088885751307e-01,-6.156500139647795578e-02,1.361524071352429588e-01,-9.999995842280564595e-01,0.000000000000000000e+00 +4.659972043111481099e+01,3.098626173188790744e+02,2.235019495338337325e+00,3.998027164687714130e+00,4.771061088885751311e-01,-6.406613765671494154e-02,1.361524071352429588e-01,-9.999995518145082807e-01,0.000000000000000000e+00 +4.660222166474532202e+01,3.098715005943336109e+02,2.239611599126271280e+00,3.997866920309630423e+00,4.776061088885751316e-01,-6.656737016620595249e-02,1.361524071352429588e-01,-9.999995094080939007e-01,0.000000000000000000e+00 +4.660472299863145196e+01,3.098803815726259359e+02,2.244208143977734604e+00,3.997700413090923277e+00,4.781061088885751320e-01,-6.906870282519962656e-02,1.361524071352429588e-01,-9.999994519871279186e-01,0.000000000000000000e+00 +4.660722443670000814e+01,3.098892602515358021e+02,2.248809128743590957e+00,3.997527642008330329e+00,4.786061088885751325e-01,-7.157013952293844739e-02,1.361524071352429588e-01,-9.999993717324598963e-01,0.000000000000000000e+00 +4.660972598287943214e+01,3.098981366288435311e+02,2.253414552273594218e+00,3.997348605999246018e+00,4.791061088885751329e-01,-7.407168413072023894e-02,1.361524071352429588e-01,-9.999992532039039261e-01,0.000000000000000000e+00 +4.661222764109982819e+01,3.099070107023300693e+02,2.258024413416388487e+00,3.997163303961741576e+00,4.796061088885751333e-01,-7.657334048289102246e-02,1.361524071352429588e-01,-9.999990631988017187e-01,0.000000000000000000e+00 +4.661472941529306269e+01,3.099158824697768750e+02,2.262638711019508531e+00,3.996971734754631633e+00,4.801061088885751338e-01,-7.907511233246160287e-02,1.361524071352429588e-01,-9.999987126664043879e-01,0.000000000000000000e+00 +4.661723130939279969e+01,3.099247519289659749e+02,2.267257443929379779e+00,3.996773897197650971e+00,4.806061088885751342e-01,-8.157700321142673239e-02,1.361524071352429588e-01,-9.999978618107761008e-01,0.000000000000000000e+00 +4.661973332733457198e+01,3.099336190776800208e+02,2.271880610991319216e+00,3.996569790071979877e+00,4.811061088885751347e-01,-8.407901580341230197e-02,1.361524071352429588e-01,-9.999928785442298018e-01,0.000000000000000000e+00 +4.662223547305584503e+01,3.099424839137022332e+02,2.276508211049534935e+00,3.996359412122338473e+00,4.816061088885751351e-01,-8.658114370576583396e-02,1.361524071352429588e-01,9.999951334547151349e-01,0.000000000000000000e+00 +4.662473775049607383e+01,3.099513464348164575e+02,2.281140242947127028e+00,3.996142762079694322e+00,4.821061088885751356e-01,-8.407887844298345126e-02,1.361524071352429588e-01,9.999982567829638347e-01,0.000000000000000000e+00 +4.662724016359675261e+01,3.099602066388069943e+02,2.285776705526088026e+00,3.995932361992788451e+00,4.826061088885751360e-01,-8.157646970455655067e-02,1.361524071352429588e-01,9.999989636149098082e-01,0.000000000000000000e+00 +4.662974270845840152e+01,3.099690645234588260e+02,2.290417597627301571e+00,3.995728213217697888e+00,4.831061088885751365e-01,-7.907392743650823452e-02,1.361524071352429588e-01,9.999992752012403230e-01,0.000000000000000000e+00 +4.663224538117946594e+01,3.099779200865574467e+02,2.295062918090545079e+00,3.995530317056555258e+00,4.836061088885751369e-01,-7.657125652937975258e-02,1.361524071352429588e-01,9.999994502478698477e-01,0.000000000000000000e+00 +4.663474817785637327e+01,3.099867733258889757e+02,2.299712665754488405e+00,3.995338674770167131e+00,4.841061088885751373e-01,-7.406846122839313984e-02,1.361524071352429588e-01,9.999995619344620446e-01,0.000000000000000000e+00 +4.663725109458359697e+01,3.099956242392401577e+02,2.304366839456694738e+00,3.995153287579598977e+00,4.846061088885751378e-01,-7.156554559761250933e-02,1.361524071352429588e-01,9.999996392191733419e-01,0.000000000000000000e+00 +4.663975412745372040e+01,3.100044728243981922e+02,2.309025438033620592e+00,3.994974156666599718e+00,4.851061088885751382e-01,-6.906251363053370063e-02,1.361524071352429588e-01,9.999996957102703643e-01,0.000000000000000000e+00 +4.664225727255750087e+01,3.100133190791509605e+02,2.313688460320616258e+00,3.994801283173750495e+00,4.856061088885751387e-01,-6.655936928843195211e-02,1.361524071352429588e-01,9.999997388877832627e-01,0.000000000000000000e+00 +4.664476052598392641e+01,3.100221630012869127e+02,2.318355905151926244e+00,3.994634668204518402e+00,4.861061088885751391e-01,-6.405611651563491993e-02,1.361524071352429588e-01,9.999997726578457868e-01,0.000000000000000000e+00 +4.664726388382027267e+01,3.100310045885950672e+02,2.323027771360689275e+00,3.994474312823272921e+00,4.866061088885751396e-01,-6.155275924840497570e-02,1.361524071352429588e-01,9.999997998344138939e-01,0.000000000000000000e+00 +4.664976734215217391e+01,3.100398438388650106e+02,2.327704057778938740e+00,3.994320218055281035e+00,4.871061088885751400e-01,-5.904930141761066675e-02,1.361524071352429588e-01,9.999998221396394493e-01,0.000000000000000000e+00 +4.665227089706367281e+01,3.100486807498868984e+02,2.332384763237603575e+00,3.994172384886696570e+00,4.876061088885751404e-01,-5.654574695139786417e-02,1.361524071352429588e-01,9.999998407709812520e-01,0.000000000000000000e+00 +4.665477454463728435e+01,3.100575153194515678e+02,2.337069886566506938e+00,3.994030814264543761e+00,4.881061088885751409e-01,-5.404209977644162249e-02,1.361524071352429588e-01,9.999998565429308872e-01,0.000000000000000000e+00 +4.665727828095405982e+01,3.100663475453503679e+02,2.341759426594367977e+00,3.993895507096698605e+00,4.886061088885751413e-01,-5.153836381884343426e-02,1.361524071352429588e-01,9.999998699577801187e-01,0.000000000000000000e+00 +4.665978210209365074e+01,3.100751774253752160e+02,2.346453382148801836e+00,3.993766464251868875e+00,4.891061088885751418e-01,-4.903454300485144551e-02,1.361524071352429588e-01,9.999998815597525015e-01,0.000000000000000000e+00 +4.666228600413437277e+01,3.100840049573186548e+02,2.351151752056320099e+00,3.993643686559573247e+00,4.896061088885751422e-01,-4.653064126069406115e-02,1.361524071352429588e-01,9.999998916514007963e-01,0.000000000000000000e+00 +4.666478998315324844e+01,3.100928301389737953e+02,2.355854535142329897e+00,3.993527174810121760e+00,4.901061088885751427e-01,-4.402666251312362805e-02,1.361524071352429588e-01,9.999999005768390736e-01,0.000000000000000000e+00 +4.666729403522608521e+01,3.101016529681343172e+02,2.360561730231135247e+00,3.993416929754595834e+00,4.906061088885751431e-01,-4.152261068925094945e-02,1.361524071352429588e-01,9.999999083674157019e-01,0.000000000000000000e+00 +4.666979815642752527e+01,3.101104734425945253e+02,2.365273336145937932e+00,3.993312952104829616e+00,4.911061088885751436e-01,-3.901848971726702003e-02,1.361524071352429588e-01,9.999999153081762238e-01,0.000000000000000000e+00 +4.667230234283113077e+01,3.101192915601493496e+02,2.369989351708836178e+00,3.993215242533390441e+00,4.916061088885751440e-01,-3.651430352574629862e-02,1.361524071352429588e-01,9.999999217251283046e-01,0.000000000000000000e+00 +4.667480659050941227e+01,3.101281073185942319e+02,2.374709775740825979e+00,3.993123801673561957e+00,4.921061088885751444e-01,-3.401005604348259631e-02,1.361524071352429588e-01,9.999999271354015340e-01,0.000000000000000000e+00 +4.667731089553391399e+01,3.101369207157251822e+02,2.379434607061801543e+00,3.993038630119328580e+00,4.926061088885751449e-01,-3.150575120145317903e-02,1.361524071352429588e-01,9.999999322298290805e-01,0.000000000000000000e+00 +4.667981525397527065e+01,3.101457317493389496e+02,2.384163844490555295e+00,3.992959728425355959e+00,4.931061088885751453e-01,-2.900139292981796305e-02,1.361524071352429588e-01,9.999999368900500674e-01,0.000000000000000000e+00 +4.668231966190325721e+01,3.101545404172326812e+02,2.388897486844777873e+00,3.992887097106979866e+00,4.936061088885751458e-01,-2.649698515988434255e-02,1.361524071352429588e-01,9.999999410381296139e-01,0.000000000000000000e+00 +4.668482411538686705e+01,3.101633467172042629e+02,2.393635532941058131e+00,3.992820736640191104e+00,4.941061088885751462e-01,-2.399253182394435815e-02,1.361524071352429588e-01,9.999999447780478778e-01,0.000000000000000000e+00 +4.668732861049435456e+01,3.101721506470520922e+02,2.398377981594885355e+00,3.992760647461621737e+00,4.946061088885751467e-01,-2.148803685475746128e-02,1.361524071352429588e-01,9.999999482539222440e-01,0.000000000000000000e+00 +4.668983314329332046e+01,3.101809522045751919e+02,2.403124831620647051e+00,3.992706829968533544e+00,4.951061088885751471e-01,-1.898350418538829326e-02,1.361524071352429588e-01,9.999999515083276558e-01,0.000000000000000000e+00 +4.669233770985076148e+01,3.101897513875732102e+02,2.407876081831630266e+00,3.992659284518807805e+00,4.956061088885751476e-01,-1.647893774939928127e-02,1.361524071352429588e-01,9.999999544114024363e-01,0.000000000000000000e+00 +4.669484230623312015e+01,3.101985481938463067e+02,2.412631731040022931e+00,3.992618011430935532e+00,4.961061088885751480e-01,-1.397434148122078668e-02,1.361524071352429588e-01,9.999999572271188741e-01,0.000000000000000000e+00 +4.669734692850637003e+01,3.102073426211953233e+02,2.417391778056912965e+00,3.992583010984007696e+00,4.966061088885751484e-01,-1.146971931510296257e-02,1.361524071352429588e-01,9.999999595513110462e-01,0.000000000000000000e+00 +4.669985157273605836e+01,3.102161346674216134e+02,2.422156221692288280e+00,3.992554283417709016e+00,4.971061088885751489e-01,-8.965075186727402071e-03,1.361524071352429588e-01,9.999999620813950774e-01,0.000000000000000000e+00 +4.670235623498736999e+01,3.102249243303272124e+02,2.426925060755038110e+00,3.992531828932308624e+00,4.976061088885751493e-01,-6.460413030386288023e-03,1.361524071352429588e-01,9.999999641386254634e-01,0.000000000000000000e+00 +4.670486091132521267e+01,3.102337116077146675e+02,2.431698294052953013e+00,3.992515647688658742e+00,4.981061088885751498e-01,-3.955736782367377108e-03,1.361524071352429588e-01,9.999999661457255051e-01,0.000000000000000000e+00 +4.670736559781423836e+01,3.102424964973871511e+02,2.436475920392724426e+00,3.992505739808185794e+00,4.986061088885751502e-01,-1.451050378133384366e-03,1.361524071352429588e-01,9.999999680694594550e-01,0.000000000000000000e+00 +4.670987029051894268e+01,3.102512789971484608e+02,2.441257938579945552e+00,3.992502105372889520e+00,4.991061088885751507e-01,1.053642246597827695e-03,1.361524071352429588e-01,9.999999698453521102e-01,0.000000000000000000e+00 +4.671237498550370759e+01,3.102600591048029628e+02,2.446044347419112253e+00,3.992504744425340313e+00,4.996061088885751511e-01,3.558337155836841653e-03,1.361524071352429588e-01,9.999999714484644198e-01,0.000000000000000000e+00 +4.671487967883286530e+01,3.102688368181555916e+02,2.450835145713622154e+00,3.992513656968677438e+00,5.001061088885750960e-01,6.063030413483549985e-03,1.361524071352429588e-01,9.999999730349607985e-01,0.000000000000000000e+00 +4.671738436657076221e+01,3.102776121350119638e+02,2.455630332265775539e+00,3.992528842966608593e+00,5.006061088885750410e-01,8.567718083842610147e-03,1.361524071352429588e-01,9.999999744466057106e-01,0.000000000000000000e+00 +4.671988904478182292e+01,3.102863850531782646e+02,2.460429905876776235e+00,3.992550302343411683e+00,5.011061088885749859e-01,1.107239623089781300e-02,1.361524071352429588e-01,9.999999758478679279e-01,0.000000000000000000e+00 +4.672239370953059989e+01,3.102951555704612474e+02,2.465233865346730724e+00,3.992578034983935709e+00,5.016061088885749308e-01,1.357706091918219581e-02,1.361524071352429588e-01,9.999999771596492781e-01,0.000000000000000000e+00 +4.672489835688185167e+01,3.103039236846682911e+02,2.470042209474649031e+00,3.992612040733604761e+00,5.021061088885748758e-01,1.608170821322981933e-02,1.361524071352429588e-01,9.999999782716828545e-01,0.000000000000000000e+00 +4.672740298290059968e+01,3.103126893936073429e+02,2.474854937058445170e+00,3.992652319398421579e+00,5.026061088885748207e-01,1.858633417755953254e-02,1.361524071352429588e-01,9.999999794673265496e-01,0.000000000000000000e+00 +4.672990758365219222e+01,3.103214526950869754e+02,2.479672046894937143e+00,3.992698870744971984e+00,5.031061088885747656e-01,2.109093487772267100e-02,1.361524071352429588e-01,9.999999805741532910e-01,0.000000000000000000e+00 +4.673241215520234704e+01,3.103302135869163862e+02,2.484493537779847827e+00,3.992751694500432880e+00,5.036061088885747106e-01,2.359550637922328345e-02,1.361524071352429588e-01,9.999999816011094778e-01,0.000000000000000000e+00 +4.673491669361723666e+01,3.103389720669053418e+02,2.489319408507804088e+00,3.992810790352578465e+00,5.041061088885746555e-01,2.610004474803418947e-02,1.361524071352429588e-01,9.999999825262444464e-01,0.000000000000000000e+00 +4.673742119496354519e+01,3.103477281328642334e+02,2.494149657872338555e+00,3.992876157949788674e+00,5.046061088885746004e-01,2.860454605058136354e-02,1.361524071352429588e-01,9.999999835092031608e-01,0.000000000000000000e+00 +4.673992565530852517e+01,3.103564817826040212e+02,2.498984284665888733e+00,3.992947796901058499e+00,5.051061088885745454e-01,3.110900635426048014e-02,1.361524071352429588e-01,9.999999843249199882e-01,0.000000000000000000e+00 +4.674243007072005440e+01,3.103652330139362903e+02,2.503823287679798337e+00,3.993025706776009542e+00,5.056061088885744903e-01,3.361342172653512816e-02,1.361524071352429588e-01,9.999999851425485087e-01,0.000000000000000000e+00 +4.674493443726671416e+01,3.103739818246732511e+02,2.508666665704316401e+00,3.993109887104900224e+00,5.061061088885744352e-01,3.611778823598581212e-02,1.361524071352429588e-01,9.999999860299777499e-01,0.000000000000000000e+00 +4.674743875101783175e+01,3.103827282126277396e+02,2.513514417528598610e+00,3.993200337378639553e+00,5.066061088885743802e-01,3.862210195211798064e-02,1.361524071352429588e-01,9.999999866707339757e-01,0.000000000000000000e+00 +4.674994300804355163e+01,3.103914721756131030e+02,2.518366541940706860e+00,3.993297057048801335e+00,5.071061088885743251e-01,4.112635894446109441e-02,1.361524071352429588e-01,9.999999874262450739e-01,0.000000000000000000e+00 +4.675244720441490642e+01,3.104002137114433708e+02,2.523223037727610141e+00,3.993400045527637054e+00,5.076061088885742700e-01,4.363055528432788904e-02,1.361524071352429588e-01,9.999999881322482187e-01,0.000000000000000000e+00 +4.675495133620385957e+01,3.104089528179331410e+02,2.528083903675184096e+00,3.993509302188094079e+00,5.081061088885742150e-01,4.613468704355944139e-02,1.361524071352429588e-01,9.999999887362241990e-01,0.000000000000000000e+00 +4.675745539948336926e+01,3.104176894928976367e+02,2.532949138568212799e+00,3.993624826363831648e+00,5.086061088885741599e-01,4.863875029486653540e-02,1.361524071352429588e-01,9.999999894392799238e-01,0.000000000000000000e+00 +4.675995939032747373e+01,3.104264237341527064e+02,2.537818741190387417e+00,3.993746617349238637e+00,5.091061088885741048e-01,5.114274111252622296e-02,1.361524071352429588e-01,9.999999899172367090e-01,0.000000000000000000e+00 +4.676246330481131963e+01,3.104351555395148239e+02,2.542692710324307104e+00,3.993874674399453983e+00,5.096061088885740498e-01,5.364665557112791722e-02,1.361524071352429588e-01,9.999999905957595026e-01,0.000000000000000000e+00 +4.676496713901124735e+01,3.104438849068009745e+02,2.547571044751479885e+00,3.994008996730384897e+00,5.101061088885739947e-01,5.615048974751234850e-02,1.361524071352429588e-01,9.999999910922666713e-01,0.000000000000000000e+00 +4.676747088900484783e+01,3.104526118338288256e+02,2.552453743252322216e+00,3.994149583518730839e+00,5.106061088885739396e-01,5.865423971880909942e-02,1.361524071352429588e-01,9.999999916328331517e-01,0.000000000000000000e+00 +4.676997455087101230e+01,3.104613363184166701e+02,2.557340804606159423e+00,3.994296433902003507e+00,5.111061088885738846e-01,6.115790156402187150e-02,1.361524071352429588e-01,9.999999920606936765e-01,0.000000000000000000e+00 +4.677247812068999622e+01,3.104700583583833691e+02,2.562232227591226152e+00,3.994449546978551702e+00,5.116061088885738295e-01,6.366147136313114741e-02,1.361524071352429588e-01,9.999999926158056329e-01,0.000000000000000000e+00 +4.677498159454349747e+01,3.104787779515484658e+02,2.567128010984666808e+00,3.994608921807584867e+00,5.121061088885737744e-01,6.616494519814858366e-02,1.361524071352429588e-01,9.999999930848729734e-01,0.000000000000000000e+00 +4.677748496851470605e+01,3.104874950957320152e+02,2.572028153562535113e+00,3.994774557409200177e+00,5.126061088885737194e-01,6.866831915204334169e-02,1.361524071352429588e-01,9.999999935101182569e-01,0.000000000000000000e+00 +4.677998823868835387e+01,3.104962097887546975e+02,2.576932654099795883e+00,3.994946452764407852e+00,5.131061088885736643e-01,7.117158930944282591e-02,1.361524071352429588e-01,9.999999939061818832e-01,0.000000000000000000e+00 +4.678249140115079285e+01,3.105049220284378748e+02,2.581841511370323694e+00,3.995124606815159130e+00,5.136061088885736092e-01,7.367475175662457909e-02,1.361524071352429588e-01,9.999999943312730677e-01,0.000000000000000000e+00 +4.678499445199004469e+01,3.105136318126035349e+02,2.586754724146904660e+00,3.995309018464375139e+00,5.141061088885735542e-01,7.617780258168621588e-02,1.361524071352429588e-01,9.999999946747903934e-01,0.000000000000000000e+00 +4.678749738729587193e+01,3.105223391390741767e+02,2.591672291201235545e+00,3.995499686575977094e+00,5.146061088885734991e-01,7.868073787418368437e-02,1.361524071352429588e-01,9.999999951538887100e-01,0.000000000000000000e+00 +4.679000020315982766e+01,3.105310440056729817e+02,2.596594211303924205e+00,3.995696609974916491e+00,5.151061088885734440e-01,8.118355372601236686e-02,1.361524071352429588e-01,9.999999954630367505e-01,0.000000000000000000e+00 +4.679250289567532661e+01,3.105397464102236995e+02,2.601520483224490921e+00,3.995899787447208418e+00,5.156061088885733890e-01,8.368624623015950836e-02,1.361524071352429588e-01,9.999999957668835870e-01,0.000000000000000000e+00 +4.679500546093770197e+01,3.105484463505507620e+02,2.606451105731367957e+00,3.996109217739962638e+00,5.161061088885733339e-01,8.618881148194160180e-02,1.361524071352429588e-01,9.999999962043851776e-01,0.000000000000000000e+00 +4.679750789504426223e+01,3.105571438244791693e+02,2.611386077591899557e+00,3.996324899561418675e+00,5.166061088885732788e-01,8.869124557900050221e-02,1.361524071352429588e-01,9.999999963926875512e-01,0.000000000000000000e+00 +4.680001019409434804e+01,3.105658388298346040e+02,2.616325397572342393e+00,3.996546831580981785e+00,5.171061088885732238e-01,9.119354462005803408e-02,1.361524071352429588e-01,9.999999968458413990e-01,0.000000000000000000e+00 +4.680251235418940325e+01,3.105745313644432599e+02,2.621269064437866891e+00,3.996775012429256702e+00,5.176061088885731687e-01,9.369570470722071720e-02,1.361524071352429588e-01,9.999999971312246716e-01,0.000000000000000000e+00 +4.680501437143303178e+01,3.105832214261320132e+02,2.626217076952556351e+00,3.997009440698088056e+00,5.181061088885731136e-01,9.619772194367111340e-02,1.361524071352429588e-01,9.999999973592695879e-01,0.000000000000000000e+00 +4.680751624193105442e+01,3.105919090127283653e+02,2.631169433879407382e+00,3.997250114940595900e+00,5.186061088885730586e-01,9.869959243508685809e-02,1.361524071352429588e-01,9.999999976165631077e-01,0.000000000000000000e+00 +4.681001796179157282e+01,3.106005941220603859e+02,2.636126133980331243e+00,3.997497033671215672e+00,5.191061088885730035e-01,1.012013122896409795e-01,1.361524071352429588e-01,9.999999979662137495e-01,0.000000000000000000e+00 +4.681251952712501918e+01,3.106092767519568270e+02,2.641087176016152505e+00,3.997750195365739057e+00,5.196061088885729484e-01,1.037028776180030504e-01,1.361524071352429588e-01,9.999999982352869576e-01,0.000000000000000000e+00 +4.681502093404424159e+01,3.106179569002470657e+02,2.646052558746610828e+00,3.998009598461355729e+00,5.201061088885728934e-01,1.062042845328085433e-01,1.361524071352429588e-01,9.999999984410454790e-01,0.000000000000000000e+00 +4.681752217866452526e+01,3.106266345647609910e+02,2.651022280930360520e+00,3.998275241356694654e+00,5.206061088885728383e-01,1.087055291491944020e-01,1.361524071352429588e-01,9.999999986494437776e-01,0.000000000000000000e+00 +4.682002325710369206e+01,3.106353097433292305e+02,2.655996341324971421e+00,3.998547122411867605e+00,5.211061088885727832e-01,1.112066075849804381e-01,1.361524071352429588e-01,9.999999990466718058e-01,0.000000000000000000e+00 +4.682252416548212182e+01,3.106439824337829805e+02,2.660974738686928021e+00,3.998825239948514021e+00,5.216061088885727282e-01,1.137075159610295011e-01,1.361524071352429588e-01,9.999999990874520739e-01,0.000000000000000000e+00 +4.682502489992285177e+01,3.106526526339540624e+02,2.665957471771631226e+00,3.999109592249847633e+00,5.221061088885726731e-01,1.162082503994775473e-01,1.361524071352429588e-01,9.999999994127060088e-01,0.000000000000000000e+00 +4.682752545655160503e+01,3.106613203416749229e+02,2.670944539333397927e+00,3.999400177560699543e+00,5.226061088885726180e-01,1.187088070267594692e-01,1.361524071352429588e-01,9.999999997197682733e-01,0.000000000000000000e+00 +4.683002583149685449e+01,3.106699855547786342e+02,2.675935940125460988e+00,3.999696994087569735e+00,5.231061088885725630e-01,1.212091819713084911e-01,1.361524071352429588e-01,9.999999996147759251e-01,0.000000000000000000e+00 +4.683252602088989391e+01,3.106786482710988935e+02,2.680931672899970142e+00,4.000000039998673707e+00,5.236061088885725079e-01,1.237093713633874298e-01,1.361524071352429588e-01,9.999999996788415668e-01,-4.000000039998676815e-01 +4.683502602086489475e+01,3.106873084884700802e+02,2.685931736407992432e+00,4.000309313423989543e+00,5.241061088885724528e-01,1.262093713375853632e-01,1.351524071352429579e-01,9.999999992663257675e-01,-4.000309313423992541e-01 +4.683752582755895588e+01,3.106959662047270854e+02,2.690936129399511767e+00,4.000624812455312096e+00,5.246023912616116780e-01,1.287091780298093568e-01,1.341524071352429570e-01,9.999999989209188422e-01,-4.000624812455315649e-01 +4.684002543711216049e+01,3.107046214363259651e+02,2.695944818446542435e+00,4.000946535146300498e+00,5.250949570186089765e-01,1.312087875803165105e-01,1.331524071352429561e-01,9.999999984578404888e-01,-4.000946535146304162e-01 +4.684252484566764707e+01,3.107132741997662606e+02,2.700957770156498849e+00,4.001274479512534121e+00,5.255838071626407482e-01,1.337081961319513401e-01,1.321524071352429552e-01,9.999999982435041623e-01,-4.001274479512537674e-01 +4.684502404937166631e+01,3.107219245115906006e+02,2.705974951171957077e+00,4.001608643531564979e+00,5.260689426889491038e-01,1.362073998315818935e-01,1.311524071352429544e-01,9.999999979165337116e-01,-4.001608643531568421e-01 +4.684752304437363080e+01,3.107305723883843029e+02,2.710996328170417247e+00,4.001949025142974570e+00,5.265503645849500813e-01,1.387063948283389914e-01,1.301524071352429535e-01,9.999999975255816631e-01,-4.001949025142977900e-01 +4.685002182682617189e+01,3.107392178467751478e+02,2.716021867864064188e+00,4.002295622248427165e+00,5.270280738302417500e-01,1.412051772746992506e-01,1.291524071352429526e-01,9.999999969612393125e-01,-4.002295622248430718e-01 +4.685252039288521075e+01,3.107478609034328088e+02,2.721051536999527620e+00,4.002648432711726656e+00,5.275020713966123154e-01,1.437037433261481312e-01,1.281524071352429517e-01,9.999999965256578527e-01,-4.002648432711730098e-01 +4.685501873871000811e+01,3.107565015750686825e+02,2.726085302357642348e+00,4.003007454358873396e+00,5.279723582480480015e-01,1.462020891422661228e-01,1.271524071352429508e-01,9.999999962217892557e-01,-4.003007454358877282e-01 +4.685751686046322106e+01,3.107651398784354910e+02,2.731123130753206674e+00,4.003372684978124596e+00,5.284389353407408230e-01,1.487002108860387695e-01,1.261524071352429499e-01,9.999999956114841160e-01,-4.003372684978127594e-01 +4.686001475431095997e+01,3.107737758303267697e+02,2.736164989034742590e+00,4.003744122320053833e+00,5.289018036230969111e-01,1.511981047228124209e-01,1.251524071352429490e-01,9.999999950968445628e-01,-4.003744122320057608e-01 +4.686251241642284526e+01,3.107824094475767538e+02,2.741210844084252862e+00,4.004121764097608782e+00,5.293609640357436197e-01,1.536957668224507301e-01,1.241524071352429481e-01,9.999999944978215094e-01,-4.004121764097612335e-01 +4.686500984297207140e+01,3.107910407470598102e+02,2.746260662816978115e+00,4.004505607986175164e+00,5.298164175115377406e-01,1.561931933579376874e-01,1.231524071352429472e-01,9.999999939067064636e-01,-4.004505607986179050e-01 +4.686750703013546371e+01,3.107996697456902666e+02,2.751314412181156133e+00,4.004895651623638031e+00,5.302681649755730531e-01,1.586903805061150030e-01,1.221524071352429464e-01,9.999999934041460259e-01,-4.004895651623641695e-01 +4.687000397409352814e+01,3.108082964604218432e+02,2.756372059157775833e+00,4.005291892610445714e+00,5.307162073451876516e-01,1.611873244477099176e-01,1.211524071352429455e-01,9.999999923472745467e-01,-4.005291892610449156e-01 +4.687250067103050810e+01,3.108169209082474822e+02,2.761433570760335687e+00,4.005694328509674662e+00,5.311605455299717171e-01,1.636840213655855469e-01,1.201524071352429446e-01,9.999999919349684685e-01,-4.005694328509678548e-01 +4.687499711713445549e+01,3.108255431061989498e+02,2.766498914034597689e+00,4.006102956847090724e+00,5.316011804317748446e-01,1.661804674493959910e-01,1.191524071352429437e-01,9.999999909340308024e-01,-4.006102956847094609e-01 +4.687749330859725916e+01,3.108341630713463815e+02,2.771568056058343110e+00,4.006517775111222868e+00,5.320381129447134816e-01,1.686766588895707020e-01,1.181524071352429428e-01,9.999999900970449884e-01,-4.006517775111226309e-01 +4.687998924161473724e+01,3.108427808207981116e+02,2.776640963941126916e+00,4.006938780753422691e+00,5.324713439551781446e-01,1.711725918823284454e-01,1.171524071352429419e-01,9.999999891705266819e-01,-4.006938780753426244e-01 +4.688248491238665849e+01,3.108513963717001616e+02,2.781717604824032186e+00,4.007365971187937248e+00,5.329008743418406358e-01,1.736682626272218755e-01,1.161524071352429410e-01,9.999999880355205928e-01,-4.007365971187940579e-01 +4.688498031711682046e+01,3.108600097412360128e+02,2.786797945879423200e+00,4.007799343791976554e+00,5.333267049756614808e-01,1.761636673275294995e-01,1.151524071352429401e-01,9.999999869938324126e-01,-4.007799343791980107e-01 +4.688747545201310629e+01,3.108686209466261516e+02,2.791881954310698521e+00,4.008238895905782861e+00,5.337488367198967021e-01,1.786588021913614877e-01,1.141524071352429393e-01,9.999999856275715304e-01,-4.008238895905786303e-01 +4.688997031328752030e+01,3.108772300051277284e+02,2.796969597352044090e+00,4.008684624832703491e+00,5.341672704301051455e-01,1.811536634299194537e-01,1.131524071352429384e-01,9.999999840834942200e-01,-4.008684624832707377e-01 +4.689246489715626609e+01,3.108858369340343870e+02,2.802060842268185414e+00,4.009136527839260111e+00,5.345820069541552533e-01,1.836482472589609505e-01,1.121524071352429375e-01,9.999999827890875270e-01,-4.009136527839263775e-01 +4.689495919983978922e+01,3.108944417506756395e+02,2.807155656354138440e+00,4.009594602155222454e+00,5.349930471322320580e-01,1.861425498995548378e-01,1.111524071352429366e-01,9.999999808826340875e-01,-4.009594602155225895e-01 +4.689745321756283403e+01,3.109030444724167523e+02,2.812254006934961748e+00,4.010058844973684700e+00,5.354003917968441773e-01,1.886365675749206161e-01,1.101524071352429357e-01,9.999999789261311278e-01,-4.010058844973688474e-01 +4.689994694655450047e+01,3.109116451166582920e+02,2.817355861365506975e+00,4.010529253451134757e+00,5.358040417728302529e-01,1.911302965140347088e-01,1.091524071352429348e-01,9.999999767650276095e-01,-4.010529253451138310e-01 +4.690244038304830099e+01,3.109202437008357833e+02,2.822461187030168350e+00,4.011005824707533307e+00,5.362039978773659454e-01,1.936237329498979032e-01,1.081524071352429339e-01,9.999999739565058610e-01,-4.011005824707536971e-01 +4.690493352328220311e+01,3.109288402424194260e+02,2.827569951342634003e+00,4.011488555826389302e+00,5.366002609199707063e-01,1.961168731188714098e-01,1.071524071352429330e-01,9.999999713422759173e-01,-4.011488555826392965e-01 +4.690742636349870764e+01,3.109374347589136960e+02,2.832682121745633719e+00,4.011977443854834569e+00,5.369928317025139952e-01,1.986097132639338958e-01,1.061524071352429321e-01,9.999999676197335319e-01,-4.011977443854837788e-01 +4.690991889994486996e+01,3.109460272678570618e+02,2.837797665710689810e+00,4.012472485803707301e+00,5.373817110192220525e-01,2.011022496293898842e-01,1.051524071352429313e-01,9.999999637728618218e-01,-4.012472485803710853e-01 +4.691241112887239240e+01,3.109546177868215295e+02,2.842916550737863979e+00,4.012973678647623110e+00,5.377668996566844495e-01,2.035944784666240404e-01,1.041524071352429304e-01,9.999999586420643682e-01,-4.012973678647626108e-01 +4.691490304653763843e+01,3.109632063334124155e+02,2.848038744355505969e+00,4.013481019325061183e+00,5.381483983938601945e-01,2.060863960288121521e-01,1.031524071352429295e-01,9.999999527848341119e-01,-4.013481019325064736e-01 +4.691739464920172509e+01,3.109717929252679482e+02,2.853164214120001763e+00,4.013994504738437996e+00,5.385262080020842834e-01,2.085779985752544974e-01,1.021524071352429286e-01,9.999999451874089784e-01,-4.013994504738441216e-01 +4.691988593313053713e+01,3.109803775800589847e+02,2.858292927615520007e+00,4.014514131754192583e+00,5.389003292450740279e-01,2.110692823675141272e-01,1.011524071352429277e-01,9.999999356968132247e-01,-4.014514131754196025e-01 +4.692237689459481231e+01,3.109889603154886117e+02,2.863424852453760217e+00,4.015039897202862917e+00,5.392707628789349394e-01,2.135602436716155794e-01,1.001524071352429268e-01,9.999999227319117390e-01,-4.015039897202866137e-01 +4.692486752987018406e+01,3.109975411492918056e+02,2.868559956273696976e+00,4.015571797879168514e+00,5.396375096521672798e-01,2.160508787545410980e-01,9.915240713524292593e-02,9.999999047140878394e-01,-4.015571797879171623e-01 +4.692735783523722404e+01,3.110061200992352610e+02,2.873698206741328143e+00,4.016109830542085035e+00,5.400005703056718342e-01,2.185411838842918342e-01,9.815240713524292504e-02,9.999998776324638960e-01,-4.016109830542088921e-01 +4.692984780698151326e+01,3.110146971831167662e+02,2.878839571549419496e+00,4.016653991914919786e+00,5.403599455727561285e-01,2.210311553238863691e-01,9.715240713524292415e-02,9.999998327476581350e-01,-4.016653991914923560e-01 +4.693233744139367047e+01,3.110232724187650888e+02,2.883984018417250272e+00,4.017204278685372998e+00,5.407156361791403132e-01,2.235207893196463902e-01,9.615240713524292326e-02,9.999997425357970426e-01,-4.017204278685376773e-01 +4.693482673476943035e+01,3.110318458240395785e+02,2.889131515090357372e+00,4.017760687505570694e+00,5.410676428429629370e-01,2.260100820545009048e-01,9.515240713524292238e-02,9.999994721839073897e-01,-4.017760687505574357e-01 +4.693731568340967897e+01,3.110404174168298255e+02,2.894282029340280893e+00,4.018323214991982084e+00,5.414159662747869417e-01,2.284990293810395534e-01,9.415240713524292149e-02,7.533818181847299345e-01,-4.018323214991985637e-01 +4.693980428362050361e+01,3.110489872150552628e+02,2.899435528964307007e+00,4.018891857724673500e+00,5.417606071776054355e-01,2.303738955326072868e-01,9.315240713524292060e-02,-9.999994660761267751e-01,-4.018891857724676830e-01 +4.694229253171326377e+01,3.110575552366650527e+02,2.904591981785212162e+00,4.019465085130854654e+00,5.421015662468472440e-01,2.278856487683803833e-01,9.215240713524291971e-02,-9.999997366199639970e-01,-4.019465085130857762e-01 +4.694478042494985459e+01,3.110661214996375179e+02,2.909751355651007287e+00,4.020032040295141051e+00,5.424388441703825725e-01,2.253977561870534607e-01,9.115240713524291882e-02,-9.999998267494819570e-01,-4.020032040295144493e-01 +4.694726796731264074e+01,3.110746860219798577e+02,2.914913618434679776e+00,4.020592726762133751e+00,5.427724416285286679e-01,2.229102142552332744e-01,9.015240713524291793e-02,-9.999998716156430767e-01,-4.020592726762137192e-01 +4.694975516277848016e+01,3.110832488217279206e+02,2.920078738033935917e+00,4.021147148036319230e+00,5.431023592940553701e-01,2.204230191087082902e-01,8.915240713524291705e-02,-9.999998989213002565e-01,-4.021147148036322561e-01 +4.695224201531877384e+01,3.110918099169458060e+02,2.925246682370943319e+00,4.021695307581329537e+00,5.434285978321903299e-01,2.179361668197796476e-01,8.815240713524291616e-02,-9.999999166692894459e-01,-4.021695307581333312e-01 +4.695472852889953685e+01,3.111003693257255236e+02,2.930417419392073786e+00,4.022237208819866794e+00,5.437511579006247819e-01,2.154496534462175539e-01,8.715240713524291527e-02,-9.999999296569684892e-01,-4.022237208819869902e-01 +4.695721470748146231e+01,3.111089270661867090e+02,2.935590917067643524e+00,4.022772855133748493e+00,5.440700401495184302e-01,2.129634750391753428e-01,8.615240713524291438e-02,-9.999999393283206528e-01,-4.022772855133752157e-01 +4.695970055501999241e+01,3.111174831564762258e+02,2.940767143391654681e+00,4.023302249863971447e+00,5.443852452215051096e-01,2.104776276514657707e-01,8.515240713524291349e-02,-9.999999466447220264e-01,-4.023302249863974778e-01 +4.696218607546537527e+01,3.111260376147679381e+02,2.945946066381536887e+00,4.023825396310795277e+00,5.446967737516975605e-01,2.079921073386964969e-01,8.415240713524291261e-02,-9.999999529485147365e-01,-4.023825396310798941e-01 +4.696467127276274311e+01,3.111345904592623128e+02,2.951127654077887019e+00,4.024342297733827678e+00,5.450046263676930902e-01,2.055069101582588098e-01,8.315240713524291172e-02,-9.999999575183237122e-01,-4.024342297733831120e-01 +4.696715615085216911e+01,3.111431417081860786e+02,2.956311874544209406e+00,4.024852957352106131e+00,5.453088036895781254e-01,2.030220321743918810e-01,8.215240713524291083e-02,-9.999999618841597382e-01,-4.024852957352109684e-01 +4.696964071366873839e+01,3.111516913797919983e+02,2.961498695866656039e+00,4.025357378344191162e+00,5.456093063299335411e-01,2.005374694525227930e-01,8.115240713524290994e-02,-9.999999650816662200e-01,-4.025357378344194825e-01 +4.697212496514260494e+01,3.111602394923584143e+02,2.966688086153765891e+00,4.025855563848244500e+00,5.459061348938395453e-01,1.980532180653999663e-01,8.015240713524290905e-02,-9.999999682563120995e-01,-4.025855563848247942e-01 +4.697460890919906973e+01,3.111687860641890211e+02,2.971880013536204679e+00,4.026347516962121453e+00,5.461992899788805644e-01,1.955692740877863489e-01,7.915240713524290816e-02,-9.999999706352848960e-01,-4.026347516962124895e-01 +4.697709254975863047e+01,3.111773311136124676e+02,2.977074446166502408e+00,4.026833240743449061e+00,5.464887721751501282e-01,1.930856336011604335e-01,7.815240713524290728e-02,-9.999999729825952421e-01,-4.026833240743452613e-01 +4.697957589073705265e+01,3.111858746589821294e+02,2.982271352218793137e+00,4.027312738209714915e+00,5.467745820652554212e-01,1.906022926898343628e-01,7.715240713524290639e-02,-9.999999748644760045e-01,-4.027312738209718468e-01 +4.698205893604543348e+01,3.111944167186757113e+02,2.987470699888553405e+00,4.027786012338345323e+00,5.470567202243221683e-01,1.881192474438646844e-01,7.615240713524290550e-02,-9.999999768104790299e-01,-4.027786012338349098e-01 +4.698454168959027299e+01,3.112029573110949627e+02,2.992672457392339336e+00,4.028253066066789678e+00,5.473351872199992973e-01,1.856364939565960659e-01,7.515240713524290461e-02,-9.999999780090740309e-01,-4.028253066066793120e-01 +4.698702415527353082e+01,3.112114964546653368e+02,2.997876592967524623e+00,4.028713902292597737e+00,5.476099836124636022e-01,1.831540283279272097e-01,7.415240713524290372e-02,-9.999999797670117152e-01,-4.028713902292601068e-01 +4.698950633699269019e+01,3.112200341678355926e+02,3.003083074872038072e+00,4.029168523873503993e+00,5.478811099544238505e-01,1.806718466589882777e-01,7.315240713524290284e-02,-9.999999808983176530e-01,-4.029168523873507546e-01 +4.699198823864082186e+01,3.112285704690776811e+02,3.008291871384100702e+00,4.029616933627497843e+00,5.481485667911257798e-01,1.781899450582655753e-01,7.215240713524290195e-02,-9.999999820488320035e-01,-4.029616933627501174e-01 +4.699446986410664096e+01,3.112371053768862339e+02,3.013502950801962843e+00,4.030059134332907966e+00,5.484123546603560939e-01,1.757083196369910449e-01,7.115240713524290106e-02,-9.999999829584241828e-01,-4.030059134332911186e-01 +4.699695121727459224e+01,3.112456389097783358e+02,3.018716281443639460e+00,4.030495128728474263e+00,5.486724740924470156e-01,1.732269665113279067e-01,7.015240713524290017e-02,-9.999999841920609311e-01,-4.030495128728477927e-01 +4.699943230202487854e+01,3.112541710862931268e+02,3.023931831646648583e+00,4.030924919513424243e+00,5.489289256102803938e-01,1.707458818002603185e-01,6.915240713524289928e-02,-9.999999849766758597e-01,-4.030924919513427795e-01 +4.700191312223356022e+01,3.112627019249916316e+02,3.029149569767744410e+00,4.031348509347543185e+00,5.491817097292921446e-01,1.682650616288506595e-01,6.815240713524289839e-02,-9.999999856544663501e-01,-4.031348509347547071e-01 +4.700439368177258359e+01,3.112712314444562480e+02,3.034369464182656184e+00,4.031765900851251416e+00,5.494308269574762482e-01,1.657845021254096829e-01,6.715240713524289751e-02,-9.999999865296793633e-01,-4.031765900851255191e-01 +4.700687398450987331e+01,3.112797596632905766e+02,3.039591483285820850e+00,4.032177096605673583e+00,5.496762777953888568e-01,1.633041994215286286e-01,6.615240713524289662e-02,-9.999999871473973512e-01,-4.032177096605676914e-01 +4.700935403430937498e+01,3.112882866001190791e+02,3.044815595490120153e+00,4.032582099152707045e+00,5.499180627361524021e-01,1.608241496539001003e-01,6.515240713524289573e-02,-9.999999878821544952e-01,-4.032582099152710597e-01 +4.701183383503112623e+01,3.112968122735866814e+02,3.050041769226614630e+00,4.032980910995093815e+00,5.501561822654593703e-01,1.583443489621987055e-01,6.415240713524289484e-02,-9.999999883503294384e-01,-4.032980910995097590e-01 +4.701431339053131353e+01,3.113053367023585452e+02,3.055269972944278489e+00,4.033373534596486287e+00,5.503906368615764100e-01,1.558647934908994614e-01,6.315240713524289395e-02,-9.999999891441007094e-01,-4.033373534596489951e-01 +4.701679270466232907e+01,3.113138599051197275e+02,3.060500175109734489e+00,4.033759972381516512e+00,5.506214269953482177e-01,1.533854793867964195e-01,6.215240713524289307e-02,-9.999999893761262193e-01,-4.033759972381519843e-01 +4.701927178127285600e+01,3.113223819005748965e+02,3.065732344206987481e+00,4.034140226735858370e+00,5.508485531302010907e-01,1.509064028026095572e-01,6.115240713524289218e-02,-9.999999901479517117e-01,-4.034140226735861701e-01 +4.702175062420789686e+01,3.113309027074479332e+02,3.070966448737158849e+00,4.034514300006297738e+00,5.510720157221469240e-01,1.484275598919924388e-01,6.015240713524289129e-02,-9.999999903599272599e-01,-4.034514300006301069e-01 +4.702422923730885884e+01,3.113394223444816475e+02,3.076202457218219610e+00,4.034882194500789332e+00,5.512918152197866517e-01,1.459489468149279545e-01,5.915240713524289040e-02,-9.999999909030934386e-01,-4.034882194500792885e-01 +4.702670762441359642e+01,3.113479408304375511e+02,3.081440338184724848e+00,4.035243912488525986e+00,5.515079520643141331e-01,1.434705597327325666e-01,5.815240713524288951e-02,-9.999999913353959657e-01,-4.035243912488529205e-01 +4.702918578935650373e+01,3.113564581840954020e+02,3.086680060187546371e+00,4.035599456199994606e+00,5.517204266895193721e-01,1.409923948112998537e-01,5.715240713524288863e-02,-9.999999917613850986e-01,-4.035599456199998047e-01 +4.703166373596853589e+01,3.113649744242530346e+02,3.091921591793605817e+00,4.035948827827039231e+00,5.519292395217920699e-01,1.385144482196849214e-01,5.615240713524288774e-02,-9.999999919653488334e-01,-4.035948827827042229e-01 +4.703414146807729423e+01,3.113734895697259617e+02,3.097164901585606867e+00,4.036292029522919655e+00,5.521343909801254002e-01,1.360367161308374262e-01,5.515240713524288685e-02,-9.999999924245092098e-01,-4.036292029522922653e-01 +4.703661898950707609e+01,3.113820036393470332e+02,3.102409958161769676e+00,4.036629063402370932e+00,5.523358814761190061e-01,1.335591947198241924e-01,5.415240713524288596e-02,-9.999999925735184592e-01,-4.036629063402374373e-01 +4.703909630407894582e+01,3.113905166519662657e+02,3.107656730135561318e+00,4.036959931541657554e+00,5.525337114139824424e-01,1.310818801663520827e-01,5.315240713524288507e-02,-9.999999931200713732e-01,-4.036959931541660995e-01 +4.704157341561078454e+01,3.113990286264503311e+02,3.112905186135428881e+00,4.037284635978632963e+00,5.527278811905382838e-01,1.286047686515539024e-01,5.215240713524288418e-02,-9.999999932958684168e-01,-4.037284635978636849e-01 +4.704405032791736119e+01,3.114075395816824425e+02,3.118155294804531241e+00,4.037603178712790175e+00,5.529183911952255670e-01,1.261278563615848558e-01,5.115240713524288330e-02,-9.999999936070552709e-01,-4.037603178712793617e-01 +4.704652704481037517e+01,3.114160495365618431e+02,3.123407024800470833e+00,4.037915561705320400e+00,5.531052418101028989e-01,1.236511394844056061e-01,5.015240713524288241e-02,-9.999999938083827811e-01,-4.037915561705323619e-01 +4.704900357009852740e+01,3.114245585100037488e+02,3.128660344795025861e+00,4.038221786879162778e+00,5.532884334098511214e-01,1.211746142115837643e-01,4.915240713524288152e-02,-9.999999940617821936e-01,-4.038221786879166442e-01 +4.705147990758759136e+01,3.114330665209387803e+02,3.133915223473880740e+00,4.038521856119057674e+00,5.534679663617768641e-01,1.186982767372257580e-01,4.815240713524288063e-02,-9.999999943578092854e-01,-4.038521856119061670e-01 +4.705395606108044859e+01,3.114415735883127923e+02,3.139171629536357866e+00,4.038815771271596411e+00,5.536438410258150977e-01,1.162221232583418029e-01,4.715240713524287974e-02,-9.999999945159443460e-01,-4.038815771271599964e-01 +4.705643203437715982e+01,3.114500797310865892e+02,3.144429531695148050e+00,4.039103534145271013e+00,5.538160577545323537e-01,1.137461499752100980e-01,4.615240713524287886e-02,-9.999999947646475151e-01,-4.039103534145274677e-01 +4.705890783127502885e+01,3.114585849682355843e+02,3.149688898676042736e+00,4.039385146510523938e+00,5.539846168931291670e-01,1.112703530903048910e-01,4.515240713524287797e-02,-9.999999948725166732e-01,-4.039385146510527380e-01 +4.706138345556865232e+01,3.114670893187493448e+02,3.154949699217663106e+00,4.039660610099794269e+00,5.541495187794430732e-01,1.087947288093759485e-01,4.415240713524287708e-02,-9.999999953080662696e-01,-4.039660610099797822e-01 +4.706385891104998365e+01,3.114755928016315920e+02,3.160211902071190959e+00,4.039929926607565669e+00,5.543107637439514956e-01,1.063192733396567669e-01,4.315240713524287619e-02,-9.999999952110847357e-01,-4.039929926607569444e-01 +4.706633420150839697e+01,3.114840954358995759e+02,3.165475476000100041e+00,4.040193097690409019e+00,5.544683521097739654e-01,1.038439828930949604e-01,4.215240713524287530e-02,-9.999999954368449240e-01,-4.040193097690412127e-01 +4.706880933073073692e+01,3.114925972405839616e+02,3.170740389779885149e+00,4.040450124967032153e+00,5.546222841926751190e-01,1.013688536820468583e-01,4.115240713524287441e-02,-9.999999958027515623e-01,-4.040450124967036039e-01 +4.707128430250138251e+01,3.115010982347284880e+02,3.176006612197792123e+00,4.040701010018318051e+00,5.547725603010670303e-01,9.889388192178806547e-02,4.015240713524287353e-02,-9.999999958130529887e-01,-4.040701010018321604e-01 +4.707375912060230405e+01,3.115095984373896272e+02,3.181274112052548286e+00,4.040945754387368360e+00,5.549191807360115414e-01,9.641906383122976487e-02,3.915240713524287264e-02,-9.999999958193723781e-01,-4.040945754387371691e-01 +4.707623378881311993e+01,3.115180978676362429e+02,3.186542858154092439e+00,4.041184359579547802e+00,5.550621457912231493e-01,9.394439563076296962e-02,3.815240713524287175e-02,-9.999999962964962741e-01,-4.041184359579551577e-01 +4.707870831091115349e+01,3.115265965445494203e+02,3.191812819323302630e+00,4.041416827062522366e+00,5.552014557530707828e-01,9.146987354189559105e-02,3.715240713524287086e-02,-9.999999962469161563e-01,-4.041416827062525585e-01 +4.708118269067149697e+01,3.115350944872220680e+02,3.197083964391727928e+00,4.041643158266295721e+00,5.553371109005805772e-01,8.899549379083744605e-02,3.615240713524286997e-02,-9.999999962472071457e-01,-4.041643158266299274e-01 +4.708365693186707546e+01,3.115435917147585769e+02,3.202356262201315751e+00,4.041863354583253631e+00,5.554691115054378736e-01,8.652125260454684996e-02,3.515240713524286909e-02,-9.999999967081328878e-01,-4.041863354583256629e-01 +4.708613103826868240e+01,3.115520882462745362e+02,3.207629681604142302e+00,4.042077417368197700e+00,5.555974578319893276e-01,8.404714621108308470e-02,3.415240713524286820e-02,-9.999999964237087369e-01,-4.042077417368201142e-01 +4.708860501364506490e+01,3.115605841008965058e+02,3.212904191462140346e+00,4.042285347938379125e+00,5.557221501372453520e-01,8.157317084354841208e-02,3.315240713524286731e-02,-9.999999969245602083e-01,-4.042285347938382456e-01 +4.709107886176295921e+01,3.115690792977616752e+02,3.218179760646829202e+00,4.042487147573541328e+00,5.558431886708816716e-01,7.909932273325957774e-02,3.215240713524286642e-02,-9.999999968191819466e-01,-4.042487147573544659e-01 +4.709355258638716890e+01,3.115775738560174091e+02,3.223456358039042513e+00,4.042682817515944826e+00,5.559605736752418759e-01,7.662559811691931067e-02,3.115240713524286553e-02,-9.999999970183242048e-01,-4.042682817515948490e-01 +4.709602619128060041e+01,3.115860677948212469e+02,3.228733952528657802e+00,4.042872358970408975e+00,5.560743053853389739e-01,7.415199323086302252e-02,3.015240713524286464e-02,-9.999999969621328200e-01,-4.042872358970412972e-01 +4.709849968020434119e+01,3.115945611333402780e+02,3.234012513014323797e+00,4.043055773104338613e+00,5.561843840288573926e-01,7.167850431463911043e-02,2.915240713524286376e-02,-9.999999970877760935e-01,-4.043055773104342054e-01 +4.710097305691769520e+01,3.116030538907510845e+02,3.239292008403189982e+00,4.043233061047758703e+00,5.562908098261548639e-01,6.920512760848510081e-02,2.815240713524286287e-02,-9.999999973783738616e-01,-4.043233061047762367e-01 +4.710344632517826824e+01,3.116115460862392865e+02,3.244572407610634368e+00,4.043404223893341864e+00,5.563935829902640906e-01,6.673185935439332472e-02,2.715240713524286198e-02,-9.999999973629214445e-01,-4.043404223893345417e-01 +4.710591948874200341e+01,3.116200377389993150e+02,3.249853679559991271e+00,4.043569262696437683e+00,5.564927037268946330e-01,6.425869579717659319e-02,2.615240713524286109e-02,-9.999999972782545044e-01,-4.043569262696440902e-01 +4.710839255136325221e+01,3.116285288682340706e+02,3.255135793182279524e+00,4.043728178475103796e+00,5.565881722344342419e-01,6.178563318266010879e-02,2.515240713524286020e-02,-9.999999974886838450e-01,-4.043728178475107238e-01 +4.711086551679481715e+01,3.116370194931546393e+02,3.260418717415930701e+00,4.043880972210131652e+00,5.566799887039507455e-01,5.931266775730902746e-02,2.415240713524285932e-02,-9.999999976148004066e-01,-4.043880972210135427e-01 +4.711333838878801572e+01,3.116455096329799517e+02,3.265702421206516437e+00,4.044027644845070490e+00,5.567681533191933818e-01,5.683979577001049138e-02,2.315240713524285843e-02,-9.999999976954900838e-01,-4.044027644845074043e-01 +4.711581117109274430e+01,3.116539993069365551e+02,3.270986873506477099e+00,4.044168197286254873e+00,5.568526662565944640e-01,5.436701347098196746e-02,2.215240713524285754e-02,-9.999999976072840857e-01,-4.044168197286258648e-01 +4.711828386745752795e+01,3.116624885342582729e+02,3.276272043274848667e+00,4.044302630402828669e+00,5.569335276852706018e-01,5.189431711211561077e-02,2.115240713524285665e-02,-9.999999977908807791e-01,-4.044302630402832333e-01 +4.712075648162957719e+01,3.116709773341858636e+02,3.281557899476990503e+00,4.044430945026769031e+00,5.570107377670240334e-01,4.942170294552621079e-02,2.015240713524285576e-02,-9.999999977987722444e-01,-4.044430945026772362e-01 +4.712322901735485203e+01,3.116794657259667360e+02,3.286844411084312689e+00,4.044553141952905939e+00,5.570842966563442911e-01,4.694916722569046630e-02,1.915240713524285487e-02,-9.999999978933282740e-01,-4.044553141952909603e-01 +4.712570147837811874e+01,3.116879537288547226e+02,3.292131547074003350e+00,4.044669221938946180e+00,5.571542045004089783e-01,4.447670620763476135e-02,1.815240713524285399e-02,-9.999999978848227444e-01,-4.044669221938949621e-01 +4.712817386844298539e+01,3.116964413621096810e+02,3.297419276428756429e+00,4.044779185705491997e+00,5.572204614390851019e-01,4.200431614799611524e-02,1.715240713524285310e-02,-9.999999980033882352e-01,-4.044779185705495439e-01 +4.713064619129198718e+01,3.117049286449972669e+02,3.302707568136498573e+00,4.044883033936061523e+00,5.572830676049304044e-01,3.953199330392726668e-02,1.615240713524285221e-02,-9.999999980273691635e-01,-4.044883033936065297e-01 +4.713311845066663608e+01,3.117134155967885363e+02,3.307996391190116459e+00,4.044980767277105649e+00,5.573420231231940303e-01,3.705973393415688127e-02,1.515240713524285132e-02,-9.999999980099981700e-01,-4.044980767277109313e-01 +4.713559065030745643e+01,3.117219022367597745e+02,3.313285714587184128e+00,4.045072386338026682e+00,5.573973281118179690e-01,3.458753429825316833e-02,1.415240713524285043e-02,-9.999999979890058510e-01,-4.045072386338030568e-01 +4.713806279395407728e+01,3.117303885841920419e+02,3.318575507329689422e+00,4.045157891691194330e+00,5.574489826814376103e-01,3.211539065660551362e-02,1.315240713524284955e-02,-9.999999982773922769e-01,-4.045157891691197882e-01 +4.714053488534525371e+01,3.117388746583710031e+02,3.323865738423761762e+00,4.045237283871960798e+00,5.574969869353828544e-01,2.964329926968732945e-02,1.215240713524284866e-02,-9.999999981555912631e-01,-4.045237283871964684e-01 +4.714300692821894501e+01,3.117473604785866428e+02,3.329156376879398582e+00,4.045310563378673230e+00,5.575413409696788891e-01,2.717125640055203378e-02,1.115240713524284777e-02,-9.999999981969158735e-01,-4.045310563378676783e-01 +4.714547892631237147e+01,3.117558460641327542e+02,3.334447391710192221e+00,4.045377730672691463e+00,5.575820448730469669e-01,2.469925831158032228e-02,1.015240713524284688e-02,-9.999999980876718153e-01,-4.045377730672695127e-01 +4.714795088336206419e+01,3.117643314343068823e+02,3.339738751933056360e+00,4.045438786178396917e+00,5.576190987269050714e-01,2.222730126661635192e-02,9.152407135242845992e-03,-9.999999983713954155e-01,-4.045438786178400248e-01 +4.715042280310391476e+01,3.117728166084098689e+02,3.345030426567954684e+00,4.045493730283205913e+00,5.576525026053685830e-01,1.975538152879215137e-02,8.152407135242845104e-03,-9.999999982686635924e-01,-4.045493730283205580e-01 +4.715289468927324634e+01,3.117813016057456821e+02,3.350322384637625106e+00,4.045542563337576780e+00,5.576822565752509453e-01,1.728349536374139406e-02,7.152407135242845083e-03,-9.999999981482038391e-01,-4.045542563337576336e-01 +4.715536654560486340e+01,3.117897864456209618e+02,3.355614595167307979e+00,4.045585285655024066e+00,5.577083606960641093e-01,1.481163903670474832e-02,6.152407135242845063e-03,-9.999999985095563426e-01,-4.045585285655023955e-01 +4.715783837583310145e+01,3.117982711473448489e+02,3.360907027184472984e+00,4.045621897512124754e+00,5.577308150200189774e-01,1.233980881215011871e-02,5.152407135242845042e-03,-9.999999980933546029e-01,-4.045621897512124976e-01 +4.716031018369189809e+01,3.118067557302286446e+02,3.366199649718544684e+00,4.045652399148522704e+00,5.577496195920258470e-01,9.868000958063928574e-03,4.152407135242845021e-03,-9.999999985331133878e-01,-4.045652399148522704e-01 +4.716278197291484275e+01,3.118152402135854118e+02,3.371492431800630740e+00,4.045676790766942865e+00,5.577647744496949667e-01,7.396211738743997156e-03,3.152407135242845000e-03,-9.999999981044729314e-01,-4.045676790766942754e-01 +4.716525374723522646e+01,3.118237246167298622e+02,3.376785342463246575e+00,4.045695072533186831e+00,5.577762796233366460e-01,4.924437423043157187e-03,2.152407135242844979e-03,-9.999999985576232264e-01,-4.045695072533186942e-01 +4.716772551038611283e+01,3.118322089589779011e+02,3.382078350740043593e+00,4.045707244576147943e+00,5.577841351359613675e-01,2.452674275724495059e-03,1.152407135242844959e-03,-9.999999981394998017e-01,-4.045707244576147721e-01 +4.717019726610037367e+01,3.118406932596464003e+02,3.387371425665534730e+00,4.045713306987804181e+00,5.577883410032803413e-01,-1.908143393577174096e-05,1.524071352428449377e-04,-9.999999985717216155e-01,-4.045713306987804292e-01 +4.717266901811075996e+01,3.118491775380528566e+02,3.392664536274822229e+00,4.045713259823231489e+00,5.577888972337052831e-01,-2.490833440793276034e-03,-8.475928647571550831e-04,-9.999999980726475002e-01,-4.045713259823231489e-01 +4.717514077014996587e+01,3.118576618135151080e+02,3.397957651603322304e+00,4.045707103100594892e+00,5.577858038283486364e-01,-4.962585475232662510e-03,-1.847592864757155104e-03,-9.999999984807507181e-01,-4.045707103100595337e-01 +4.717761252595065713e+01,3.118661461053510493e+02,3.403250740686494247e+00,4.045694836801160044e+00,5.577790607810235723e-01,-7.434341272171989499e-03,-2.847592864757155125e-03,-9.999999982766140105e-01,-4.045694836801159711e-01 +4.718008428924556341e+01,3.118746304328783481e+02,3.408543772559564200e+00,4.045676460869281676e+00,5.577686680782438788e-01,-9.906104562819218959e-03,-3.847592864757155146e-03,-9.999999983979158680e-01,-4.045676460869281899e-01 +4.718255606376750677e+01,3.118831148154141033e+02,3.413836716257254267e+00,4.045651975212411600e+00,5.577546256992240714e-01,-1.237787908080192727e-02,-4.847592864757155166e-03,-9.999999983142981996e-01,-4.045651975212411489e-01 +4.718502785324946558e+01,3.118915992722745614e+02,3.419129540813507173e+00,4.045621379701090703e+00,5.577369336158789492e-01,-1.484966855859504511e-02,-5.847592864757155187e-03,-9.999999982079431637e-01,-4.045621379701090925e-01 +4.718749966142463848e+01,3.119000838227747749e+02,3.424422215261213598e+00,4.045584674168948958e+00,5.577155917928234841e-01,-1.732147672933846694e-02,-6.847592864757155208e-03,-9.999999982466556414e-01,-4.045584674168949402e-01 +4.718997149202649410e+01,3.119085684862283756e+02,3.429714708631939502e+00,4.045541858412700087e+00,5.576906001873724872e-01,-1.979330732685791530e-02,-7.847592864757155229e-03,-9.999999982930867226e-01,-4.045541858412703418e-01 +4.719244334878882086e+01,3.119170532819472328e+02,3.435006989955651235e+00,4.045492932192135349e+00,5.576619587495404984e-01,-2.226516408496706165e-02,-8.847592864757156117e-03,-9.999999980500570151e-01,-4.045492932192139013e-01 +4.719491523544580502e+01,3.119255382292411696e+02,3.440299028260442871e+00,4.045437895230118208e+00,5.576296674220408978e-01,-2.473705073712884409e-02,-9.847592864757157005e-03,-9.999999983687227756e-01,-4.045437895230121761e-01 +4.719738715573205923e+01,3.119340233474176216e+02,3.445590792572263528e+00,4.045376747212579005e+00,5.575937261402860168e-01,-2.720897101935045373e-02,-1.084759286475715789e-02,-9.999999981959412088e-01,-4.045376747212582891e-01 +4.719985911338270057e+01,3.119425086557813529e+02,3.450882251914643373e+00,4.045309487788501634e+00,5.575541348323863611e-01,-2.968092866553255493e-02,-1.184759286475715878e-02,-9.999999980628123675e-01,-4.045309487788505409e-01 +4.720233111213340038e+01,3.119509941736342284e+02,3.456173375308420059e+00,4.045236116569920881e+00,5.575108934191498333e-01,-3.215292741144184369e-02,-1.284759286475715967e-02,-9.999999980495249963e-01,-4.045236116569924656e-01 +4.720480315572043395e+01,3.119594799202748732e+02,3.461464131771466501e+00,4.045156633131909096e+00,5.574640018140814002e-01,-3.462497099365294956e-02,-1.384759286475716056e-02,-9.999999980759957108e-01,-4.045156633131912205e-01 +4.720727524788074447e+01,3.119679659149982172e+02,3.466754490318415982e+00,4.045071037012564652e+00,5.574134599233824261e-01,-3.709706314920876297e-02,-1.484759286475716145e-02,-9.999999980471229177e-01,-4.045071037012568094e-01 +4.720974739235199991e+01,3.119764521770954389e+02,3.472044419960390815e+00,4.044979327713000394e+00,5.573592676459495632e-01,-3.956920761563983979e-02,-1.584759286475716233e-02,-9.999999978526603606e-01,-4.044979327713003614e-01 +4.721221959287264980e+01,3.119849387258535671e+02,3.477333889704728342e+00,4.044881504697331209e+00,5.573014248733743070e-01,-4.204140813098351803e-02,-1.684759286475716322e-02,-9.999999980936359334e-01,-4.044881504697335206e-01 +4.721469185318197503e+01,3.119934255805550833e+02,3.482622868554707374e+00,4.044777567392660700e+00,5.572399314899419975e-01,-4.451366843559895203e-02,-1.784759286475716411e-02,-9.999999977571680798e-01,-4.044777567392663919e-01 +4.721716417702015178e+01,3.120019127604777509e+02,3.487911325509276406e+00,4.044667515189062534e+00,5.571747873726308198e-01,-4.698599226823380048e-02,-1.884759286475716500e-02,-9.999999978491485031e-01,-4.044667515189065976e-01 +4.721963656812830834e+01,3.120104002848942741e+02,3.493199229562780062e+00,4.044551347439570677e+00,5.571059923911110268e-01,-4.945838337107184152e-02,-1.984759286475716589e-02,-9.999999977612827884e-01,-4.044551347439573896e-01 +4.722210903024856776e+01,3.120188881730719572e+02,3.498486549704685533e+00,4.044429063460156293e+00,5.570335464077436072e-01,-5.193084548579895293e-02,-2.084759286475716678e-02,-9.999999975958879794e-01,-4.044429063460159846e-01 +4.722458156712413313e+01,3.120273764442724769e+02,3.503773254919310798e+00,4.044300662529713541e+00,5.569574492775793972e-01,-5.440338235541671702e-02,-2.184759286475716766e-02,-9.999999977296749609e-01,-4.044300662529716761e-01 +4.722705418249930887e+01,3.120358651177515412e+02,3.509059314185551059e+00,4.044166143890040033e+00,5.568777008483579705e-01,-5.687599772497772821e-02,-2.284759286475716855e-02,-9.999999975060785973e-01,-4.044166143890043363e-01 +4.722952688011958600e+01,3.120443542127584919e+02,3.514344696476606966e+00,4.044025506745814624e+00,5.567943009605060833e-01,-5.934869533908759126e-02,-2.384759286475716944e-02,-9.999999975594733304e-01,-4.044025506745818066e-01 +4.723199966373168479e+01,3.120528437485362474e+02,3.519629370759710607e+00,4.043878750264580546e+00,5.567072494471367872e-01,-6.182147894515382242e-02,-2.484759286475717033e-02,-9.999999973453662649e-01,-4.043878750264583988e-01 +4.723447253708362581e+01,3.120613337443207342e+02,3.524913305995854618e+00,4.043725873576719643e+00,5.566165461340479848e-01,-6.429435229052783696e-02,-2.584759286475717122e-02,-9.999999973190709657e-01,-4.043725873576723417e-01 +4.723694550392476543e+01,3.120698242193407168e+02,3.530196471139518177e+00,4.043566875775432834e+00,5.565221908397207651e-01,-6.676731912503425237e-02,-2.684759286475717210e-02,-9.999999973376901830e-01,-4.043566875775436720e-01 +4.723941856800586692e+01,3.120783151928175130e+02,3.535478835138395670e+00,4.043401755916713469e+00,5.564241833753182931e-01,-6.924038319954871346e-02,-2.784759286475717299e-02,-9.999999970956943152e-01,-4.043401755916717355e-01 +4.724189173307915723e+01,3.120868066839645962e+02,3.540760366933124015e+00,4.043230513019323347e+00,5.563225235446842554e-01,-7.171354826565275176e-02,-2.884759286475717388e-02,-9.999999969959769697e-01,-4.043230513019326344e-01 +4.724436500289837682e+01,3.120952987119874251e+02,3.546041035457010437e+00,4.043053146064768733e+00,5.562172111443409728e-01,-7.418681807744297030e-02,-2.984759286475717477e-02,-9.999999969877334527e-01,-4.043053146064771730e-01 +4.724683838121885060e+01,3.121037912960830454e+02,3.551320809635760245e+00,4.042869653997271051e+00,5.561082459634881792e-01,-7.666019639046629808e-02,-3.084759286475717566e-02,-9.999999970019523010e-01,-4.042869653997274160e-01 +4.724931187179753067e+01,3.121122844554398057e+02,3.556599658387205487e+00,4.042680035723739351e+00,5.559956277840011341e-01,-7.913368696173225803e-02,-3.184759286475717655e-02,-9.999999965156595172e-01,-4.042680035723743015e-01 +4.725178547839306731e+01,3.121207782092370167e+02,3.561877550621032729e+00,4.042484290113741885e+00,5.558793563804288462e-01,-8.160729354864740270e-02,-3.284759286475717743e-02,-9.999999968741331013e-01,-4.042484290113745327e-01 +4.725425920476584452e+01,3.121292725766447802e+02,3.567154455238510380e+00,4.042282415999479461e+00,5.557594315199922974e-01,-8.408101991369407169e-02,-3.384759286475717832e-02,-9.999999963552679283e-01,-4.042282415999483014e-01 +4.725673305467806529e+01,3.121377675768235349e+02,3.572430341132218690e+00,4.042074412175746367e+00,5.556358529625826659e-01,-8.655486981690033166e-02,-3.484759286475717921e-02,-9.999999964107779693e-01,-4.042074412175749587e-01 +4.725920703189379424e+01,3.121462632289237717e+02,3.577705177185776630e+00,4.041860277399909052e+00,5.555086204607592171e-01,-8.902884702374869175e-02,-3.584759286475718010e-02,-9.999999962954790877e-01,-4.041860277399912382e-01 +4.726168114017900734e+01,3.121547595520858067e+02,3.582978932273571004e+00,4.041640010391864379e+00,5.553777337597476382e-01,-9.150295529979916853e-02,-3.684759286475718099e-02,-9.999999961149331762e-01,-4.041640010391868154e-01 +4.726415538330167010e+01,3.121632565654394966e+02,3.588251575260485993e+00,4.041413609834010323e+00,5.552431925974375959e-01,-9.397719841285162579e-02,-3.784759286475718187e-02,-9.999999959542426042e-01,-4.041413609834013654e-01 +4.726662976503178015e+01,3.121717542881037843e+02,3.593523075001630929e+00,4.041181074371210435e+00,5.551049967043809596e-01,-9.645158013295306032e-02,-3.884759286475718276e-02,-9.999999957326132227e-01,-4.041181074371213433e-01 +4.726910428914143125e+01,3.121802527391865283e+02,3.598793400342068960e+00,4.040942402610757433e+00,5.549631458037893594e-01,-9.892610423204507841e-02,-3.984759286475718365e-02,-9.999999957831989805e-01,-4.040942402610760431e-01 +4.727157895940487009e+01,3.121887519377841613e+02,3.604062520116547486e+00,4.040697593122336784e+00,5.548176396115322984e-01,-1.014007744850462661e-01,-4.084759286475718454e-02,-9.999999955474303537e-01,-4.040697593122339892e-01 +4.727405377959854604e+01,3.121972519029814066e+02,3.609330403149226374e+00,4.040446644437986734e+00,5.546684778361347101e-01,-1.038755946677036579e-01,-4.184759286475718543e-02,-9.999999951700558887e-01,-4.040446644437989954e-01 +4.727652875350118933e+01,3.122057526538508796e+02,3.614597018253407068e+00,4.040189555052062786e+00,5.545156601787744055e-01,-1.063505685583913118e-01,-4.284759286475718632e-02,-9.999999952083726829e-01,-4.040189555052066672e-01 +4.727900388489384653e+01,3.122142542094528608e+02,3.619862334231263024e+00,4.039926323421196841e+00,5.543591863332800740e-01,-1.088256999391898211e-01,-4.384759286475718720e-02,-9.999999950369878876e-01,-4.039926323421200727e-01 +4.728147917755995877e+01,3.122227565888350114e+02,3.625126319873568370e+00,4.039656947964252787e+00,5.541990559861285082e-01,-1.113009925930175809e-01,-4.484759286475718809e-02,-9.999999947324572647e-01,-4.039656947964256339e-01 +4.728395463528540432e+01,3.122312598110319755e+02,3.630388943959428794e+00,4.039381427062288310e+00,5.540352688164422723e-01,-1.137764503054265464e-01,-4.584759286475718898e-02,-9.999999943476892694e-01,-4.039381427062292418e-01 +4.728643026185856968e+01,3.122397638950652095e+02,3.635650175256010197e+00,4.039099759058511374e+00,5.538678244959871488e-01,-1.162520768646023578e-01,-4.684759286475718987e-02,-9.999999944911848182e-01,-4.039099759058514816e-01 +4.728890606107040639e+01,3.122482688599424705e+02,3.640909982518270027e+00,4.038811942258235810e+00,5.536967226891693628e-01,-1.187278760627986374e-01,-4.784759286475719076e-02,-9.999999940081002459e-01,-4.038811942258239140e-01 +4.729138203671447371e+01,3.122567747246577596e+02,3.646168334488686824e+00,4.038517974928832466e+00,5.535219630530328061e-01,-1.212038516920302539e-01,-4.884759286475719164e-02,-9.999999938922669029e-01,-4.038517974928835796e-01 +4.729385819258701673e+01,3.122652815081908670e+02,3.651425199896991103e+00,4.038217855299690129e+00,5.533435452372567065e-01,-1.236800075494519091e-01,-4.984759286475719253e-02,-9.999999935182944943e-01,-4.038217855299693904e-01 +4.729633453248702324e+01,3.122737892295070310e+02,3.656680547459895791e+00,4.037911581562162233e+00,5.531614688841522964e-01,-1.261563474334081725e-01,-5.084759286475719342e-02,-9.999999933938981123e-01,-4.037911581562165786e-01 +4.729881106021627346e+01,3.122822979075566536e+02,3.661934345880826225e+00,4.037599151869522451e+00,5.529757336286602598e-01,-1.286328751462983699e-01,-5.184759286475719431e-02,-9.999999928418104034e-01,-4.037599151869526448e-01 +4.730128777957940400e+01,3.122908075612751304e+02,3.667186563849652803e+00,4.037280564336912292e+00,5.527863390983478453e-01,-1.311095944917013978e-01,-5.284759286475719520e-02,-9.999999928955316530e-01,-4.037280564336915845e-01 +4.730376469438397180e+01,3.122993182095822817e+02,3.672437170042420540e+00,4.036955817041294914e+00,5.525932849134056468e-01,-1.335865092786720498e-01,-5.384759286475719609e-02,-9.999999922446661804e-01,-4.036955817041298356e-01 +4.730624180844050386e+01,3.123078298713823528e+02,3.677686133121081280e+00,4.036624908021397395e+00,5.523965706866446057e-01,-1.360636233159952801e-01,-5.484759286475719697e-02,-9.999999920120630215e-01,-4.036624908021401170e-01 +4.730871912556256831e+01,3.123163425655634455e+02,3.682933421733225021e+00,4.036287835277666325e+00,5.521961960234931244e-01,-1.385409404182727511e-01,-5.584759286475719786e-02,-9.999999918444195668e-01,-4.036287835277669878e-01 +4.731119664956682414e+01,3.123248563109973475e+02,3.688179004511812131e+00,4.035944596772207404e+00,5.519921605219935135e-01,-1.410184644023263489e-01,-5.684759286475719875e-02,-9.999999912151352754e-01,-4.035944596772210735e-01 +4.731367438427309224e+01,3.123333711265391344e+02,3.693422850074903785e+00,4.035595190428733048e+00,5.517844637727991053e-01,-1.434961990868284520e-01,-5.784759286475719964e-02,-9.999999908702226215e-01,-4.035595190428736267e-01 +4.731615233350440519e+01,3.123418870310269426e+02,3.698664927025395954e+00,4.035239614132509978e+00,5.515731053591709232e-01,-1.459741482955150271e-01,-5.884759286475720053e-02,-9.999999903681709990e-01,-4.035239614132513086e-01 +4.731863050108706403e+01,3.123504040432815714e+02,3.703905203950750291e+00,4.034877865730297941e+00,5.513580848569740178e-01,-1.484523158543036014e-01,-5.984759286475720141e-02,-9.999999901046905393e-01,-4.034877865730301383e-01 +4.732110889085071648e+01,3.123589221821063120e+02,3.709143649422727229e+00,4.034509943030294643e+00,5.511394018346744694e-01,-1.509307055934281938e-01,-6.084759286475720230e-02,-9.999999895765876445e-01,-4.034509943030298307e-01 +4.732358750662839952e+01,3.123674414662864365e+02,3.714380231997119530e+00,4.034135843802074461e+00,5.509170558533357243e-01,-1.534093213452721316e-01,-6.184759286475720319e-02,-9.999999889719189961e-01,-4.034135843802078014e-01 +4.732606635225660341e+01,3.123759619145890269e+02,3.719614920213483611e+00,4.033755565776531604e+00,5.506910464666149307e-01,-1.558881669461417430e-01,-6.284759286475720408e-02,-9.999999883016832403e-01,-4.033755565776535046e-01 +4.732854543157534977e+01,3.123844835457626914e+02,3.724847682594873977e+00,4.033369106645817936e+00,5.504613732207594978e-01,-1.583672462358883815e-01,-6.384759286475720497e-02,-9.999999879771940270e-01,-4.033369106645821600e-01 +4.733102474842823426e+01,3.123930063785371090e+02,3.730078487647576324e+00,4.032976464063280808e+00,5.502280356546036533e-01,-1.608465630589618889e-01,-6.484759286475720585e-02,-9.999999870756838272e-01,-4.032976464063284250e-01 +4.733350430666248343e+01,3.124015304316228026e+02,3.735307303860841088e+00,4.032577635643397329e+00,5.499910332995642248e-01,-1.633261212611641644e-01,-6.584759286475720674e-02,-9.999999866628177525e-01,-4.032577635643401215e-01 +4.733598411012903284e+01,3.124100557237108546e+02,3.740534099706617432e+00,4.032172618961715749e+00,5.497503656796373095e-01,-1.658059246946404497e-01,-6.684759286475720763e-02,-9.999999856023762401e-01,-4.032172618961719079e-01 +4.733846416268257684e+01,3.124185822734725093e+02,3.745758843639287239e+00,4.031761411554783514e+00,5.495060323113943879e-01,-1.682859772124810083e-01,-6.784759286475720852e-02,-9.999999848889921106e-01,-4.031761411554786734e-01 +4.734094446818163959e+01,3.124271100995589450e+02,3.750981504095399544e+00,4.031344010920087761e+00,5.492580327039781052e-01,-1.707662826740667383e-01,-6.884759286475720941e-02,-9.999999841810585099e-01,-4.031344010920091536e-01 +4.734342503048863193e+01,3.124356392206008195e+02,3.756202049493405415e+00,4.030920414515981598e+00,5.490063663590987186e-01,-1.732468449418173018e-01,-6.984759286475721030e-02,-9.999999829559296227e-01,-4.030920414515985484e-01 +4.734590585346990110e+01,3.124441696552081567e+02,3.761420448233391944e+00,4.030490619761617488e+00,5.487510327710297675e-01,-1.757276678808035730e-01,-7.084759286475721118e-02,-9.999999820965308484e-01,-4.030490619761620819e-01 +4.734838694099581602e+01,3.124527014219698913e+02,3.766636668696818901e+00,4.030054624036880639e+00,5.484920314266042984e-01,-1.782087553622965226e-01,-7.184759286475721207e-02,-9.999999808597740403e-01,-4.030054624036883970e-01 +4.735086829694080990e+01,3.124612345394535851e+02,3.771850679246252280e+00,4.029612424682312621e+00,5.482293618052104245e-01,-1.806901112597956993e-01,-7.284759286475721296e-02,-9.999999797620601205e-01,-4.029612424682316174e-01 +4.735334992518345132e+01,3.124697690262050855e+02,3.777062448225101399e+00,4.029164018999043861e+00,5.479630233787873284e-01,-1.831717394522164588e-01,-7.384759286475721385e-02,-9.999999781259578668e-01,-4.029164018999047414e-01 +4.735583182960651527e+01,3.124783049007481850e+02,3.782271943957354665e+00,4.028709404248717263e+00,5.476930156118210435e-01,-1.856536438209901718e-01,-7.484759286475721474e-02,-9.999999765314570022e-01,-4.028709404248720372e-01 +4.735831401409702579e+01,3.124868421815844499e+02,3.787479134747314014e+00,4.028248577653418039e+00,5.474193379613400134e-01,-1.881358282532474280e-01,-7.584759286475721562e-02,-9.999999750840657953e-01,-4.028248577653422147e-01 +4.736079648254633412e+01,3.124953808871927095e+02,3.792683988879334223e+00,4.027781536395594664e+00,5.471419898769106505e-01,-1.906182966407037882e-01,-7.684759286475721651e-02,-9.999999728385583486e-01,-4.027781536395598216e-01 +4.736327923885018265e+01,3.125039210360288848e+02,3.797886474617556907e+00,4.027308277617981602e+00,5.468609708006330061e-01,-1.931010528771143764e-01,-7.784759286475721740e-02,-9.999999706803818222e-01,-4.027308277617984711e-01 +4.736576228690875467e+01,3.125124626465255346e+02,3.803086560205649391e+00,4.026828798423527367e+00,5.465762801671363302e-01,-1.955841008628818045e-01,-7.884759286475721829e-02,-9.999999681540671093e-01,-4.026828798423531253e-01 +4.736824563062674542e+01,3.125210057370916843e+02,3.808284213866540924e+00,4.026343095875310141e+00,5.462879174035744079e-01,-1.980674445017908125e-01,-7.984759286475721918e-02,-9.999999651920631338e-01,-4.026343095875313804e-01 +4.737072927391344024e+01,3.125295503261123713e+02,3.813479403802161105e+00,4.025851166996460506e+00,5.459958819296208965e-01,-2.005510877020349469e-01,-8.084759286475722007e-02,-9.999999618255139833e-01,-4.025851166996464170e-01 +4.737321322068275720e+01,3.125380964319484747e+02,3.818672098193177433e+00,4.025353008770080621e+00,5.457001731574647740e-01,-2.030350343765255916e-01,-8.184759286475722095e-02,-9.999999574636171396e-01,-4.025353008770084506e-01 +4.737569747485331106e+01,3.125466440729361466e+02,3.823862265198732846e+00,4.024848618139161616e+00,5.454007904918054539e-01,-2.055192884414110965e-01,-8.284759286475722184e-02,-9.999999529079961480e-01,-4.024848618139165168e-01 +4.737818204034850567e+01,3.125551932673868123e+02,3.829049872956185041e+00,4.024337992006503661e+00,5.450977333298481220e-01,-2.080038538195999875e-01,-8.384759286475722273e-02,-9.999999467538336351e-01,-4.024337992006507547e-01 +4.738066692109656231e+01,3.125637440335864881e+02,3.834234889580845351e+00,4.023821127234626260e+00,5.447910010612987408e-01,-2.104887344353437995e-01,-8.484759286475722362e-02,-9.999999391311098496e-01,-4.023821127234629702e-01 +4.738315212103060503e+01,3.125722963897958380e+02,3.839417283165717176e+00,4.023298020645690976e+00,5.444805930683590534e-01,-2.129739342181143635e-01,-8.584759286475722451e-02,-9.999999296887001066e-01,-4.023298020645694195e-01 +4.738563764408872458e+01,3.125808503542495487e+02,3.844597021781236190e+00,4.022768669021413501e+00,5.441665087257219202e-01,-2.154594571014731563e-01,-8.684759286475722539e-02,-9.999999167320038351e-01,-4.022768669021416499e-01 +4.738812349421404235e+01,3.125894059451561020e+02,3.849774073475008773e+00,4.022233069102977510e+00,5.438487474005657685e-01,-2.179453070197963638e-01,-8.784759286475722628e-02,-9.999998988046032711e-01,-4.022233069102981173e-01 +4.739060967535476721e+01,3.125979631806974908e+02,3.854948406271553996e+00,4.021691217590955603e+00,5.435273084525499288e-01,-2.204314879089302182e-01,-8.884759286475722717e-02,-9.999998716707123592e-01,-4.021691217590959155e-01 +4.739309619146427366e+01,3.126065220790288777e+02,3.860119988172042493e+00,4.021143111145227600e+00,5.432021912338091951e-01,-2.229180036993436975e-01,-8.984759286475722806e-02,-9.999998265957232846e-01,-4.021143111145231153e-01 +4.739558304650115872e+01,3.126150826582781974e+02,3.865288787154037564e+00,4.020588746384914813e+00,5.428733950889487181e-01,-2.254048583050006493e-01,-9.084759286475722895e-02,-9.999997364281349999e-01,-4.020588746384918255e-01 +4.739807024442932004e+01,3.126236449365459293e+02,3.870454771171237152e+00,4.020028119888340967e+00,5.425409193550385645e-01,-2.278920555776072498e-01,-9.184759286475722984e-02,-9.999994660766632348e-01,-4.020028119888344187e-01 +4.740055778921800567e+01,3.126322089319046995e+02,3.875617908153214053e+00,4.019461228193105917e+00,5.422047633616084994e-01,-2.303795990381351799e-01,-9.284759286475723072e-02,7.671713648424505205e-01,-4.019461228193109692e-01 +4.740304568484189218e+01,3.126407746623990533e+02,3.880778166005157903e+00,4.018888067796826391e+00,5.418649264306423241e-01,-2.284709567567732025e-01,-9.384759286475723161e-02,9.999994719927515208e-01,-4.018888067796829722e-01 +4.740553393528114157e+01,3.126493421460448872e+02,3.885935512607618492e+00,4.018319574838320030e+00,5.415214078765726580e-01,-2.259827076313354888e-01,-9.484759286475723250e-02,9.999997423826144649e-01,-4.018319574838323804e-01 +4.740802253774636199e+01,3.126579114008294482e+02,3.891089915816246414e+00,4.017757193715010722e+00,5.411742070062752763e-01,-2.234941058072188735e-01,-9.584759286475723339e-02,9.999998325866314985e-01,-4.017757193715014163e-01 +4.741051148855096642e+01,3.126664824447107662e+02,3.896241343461537721e+00,4.017200927880537620e+00,5.408233231190634482e-01,-2.210051554192986323e-01,-9.684759286475723428e-02,9.999998775269969276e-01,-4.017200927880540950e-01 +4.741300078400308138e+01,3.126750552956173692e+02,3.901389763348575457e+00,4.016650780752258676e+00,5.404687555066821636e-01,-2.185158602720564114e-01,-9.784759286475723516e-02,9.999999049199918000e-01,-4.016650780752262229e-01 +4.741549042040561091e+01,3.126836299714479992e+02,3.906535143256774756e+00,4.016106755711995824e+00,5.401105034533025817e-01,-2.160262241062438915e-01,-9.884759286475723605e-02,9.999999225418926274e-01,-4.016106755711999488e-01 +4.741798039405627918e+01,3.126922064900712712e+02,3.911677450939625711e+00,4.015568856106117579e+00,5.397485662355162583e-01,-2.135362506484426992e-01,-9.984759286475723694e-02,9.999999357314520720e-01,-4.015568856106120910e-01 +4.742047070124770158e+01,3.127007848693252754e+02,3.916816654124438024e+00,4.015037085245499071e+00,5.393829431223290394e-01,-2.110459436170719350e-01,-1.008475928647572378e-01,9.999999451028067643e-01,-4.015037085245502513e-01 +4.742296133826740601e+01,3.127093651270172927e+02,3.921952720512086099e+00,4.014511446405467865e+00,5.390136333751552877e-01,-2.085553067340961408e-01,-1.018475928647572387e-01,9.999999528494710743e-01,-4.014511446405471529e-01 +4.742545230139791101e+01,3.127179472809235108e+02,3.927085617776754134e+00,4.013991942825721360e+00,5.386406362478117771e-01,-2.060643437210379625e-01,-1.028475928647572396e-01,9.999999585917680456e-01,-4.013991942825724801e-01 +4.742794358691677559e+01,3.127265313487886260e+02,3.932215313565681214e+00,4.013478577710254847e+00,5.382639509865118077e-01,-2.035730583053333154e-01,-1.038475928647572405e-01,9.999999636715234397e-01,-4.013478577710258288e-01 +4.743043519109663464e+01,3.127351173483255025e+02,3.937341775498906848e+00,4.012971354227274468e+00,5.378835768298589892e-01,-2.010814542159898577e-01,-1.048475928647572414e-01,9.999999677163133871e-01,-4.012971354227278242e-01 +4.743292711020527008e+01,3.127437052972148308e+02,3.942464971169018728e+00,4.012470275509121720e+00,5.374995130088409123e-01,-1.985895351878041448e-01,-1.058475928647572423e-01,9.999999712148011088e-01,-4.012470275509125162e-01 +4.743541934050565345e+01,3.127522952131048442e+02,3.947584868140898262e+00,4.011975344652188191e+00,5.371117587468230425e-01,-1.960973049591629713e-01,-1.068475928647572432e-01,9.999999740854338404e-01,-4.011975344652191633e-01 +4.743791187825599565e+01,3.127608871136109201e+02,3.952701433951467447e+00,4.011486564716836511e+00,5.367203132595425030e-01,-1.936047672734107494e-01,-1.078475928647572440e-01,9.999999766766277665e-01,-4.011486564716839620e-01 +4.744040471970982509e+01,3.127694810163152397e+02,3.957814636109437512e+00,4.011003938727318641e+00,5.363251757551015242e-01,-1.911119258777242702e-01,-1.088475928647572449e-01,9.999999789083708901e-01,-4.011003938727322193e-01 +4.744289786111600904e+01,3.127780769387665600e+02,3.962924442095056676e+00,4.010527469671697709e+00,5.359263454339611155e-01,-1.886187845241267258e-01,-1.098475928647572458e-01,9.999999808432242787e-01,-4.010527469671700818e-01 +4.744539129871882466e+01,3.127866748984797596e+02,3.968030819359857908e+00,4.010057160501768081e+00,5.355238214889342929e-01,-1.861253469690784257e-01,-1.108475928647572467e-01,9.999999826856040830e-01,-4.010057160501771523e-01 +4.744788502875800873e+01,3.127952749129354402e+02,3.973133735326407567e+00,4.009593014132977196e+00,5.351176031051798621e-01,-1.836316169730689007e-01,-1.118475928647572476e-01,9.999999843522381360e-01,-4.009593014132981081e-01 +4.745037904746882162e+01,3.128038769995798134e+02,3.978233157388056274e+00,4.009135033444349183e+00,5.347076894601956454e-01,-1.811375983012799007e-01,-1.128475928647572485e-01,9.999999854720575954e-01,-4.009135033444352625e-01 +4.745287335108208993e+01,3.128124811758241322e+02,3.983329052908687107e+00,4.008683221278407594e+00,5.342940797238115991e-01,-1.786432947242488911e-01,-1.138475928647572494e-01,9.999999869555405985e-01,-4.008683221278411257e-01 +4.745536793582426327e+01,3.128210874590444064e+02,3.988421389222466029e+00,4.008237580441097236e+00,5.338767730581833737e-01,-1.761487100146179041e-01,-1.148475928647572503e-01,9.999999881387634515e-01,-4.008237580441100789e-01 +4.745786279791747120e+01,3.128296958665811189e+02,3.993510133633593195e+00,4.007798113701714904e+00,5.334557686177852087e-01,-1.736538479510056077e-01,-1.158475928647572512e-01,9.999999890670471236e-01,-4.007798113701718234e-01 +4.746035793357957289e+01,3.128383064157388844e+02,3.998595253416052930e+00,4.007364823792831210e+00,5.330310655494032712e-01,-1.711587123161833757e-01,-1.168475928647572520e-01,9.999999900656230123e-01,-4.007364823792834985e-01 +4.746285333902422821e+01,3.128469191237859945e+02,4.003676715813366371e+00,4.006937713410217761e+00,5.326026629921283284e-01,-1.686633068963215576e-01,-1.178475928647572529e-01,9.999999910254118163e-01,-4.006937713410220758e-01 +4.746534901046093324e+01,3.128555340079541907e+02,4.008754488038342778e+00,4.006516785212776988e+00,5.321705600773491973e-01,-1.661676354820176560e-01,-1.188475928647572538e-01,9.999999918308197788e-01,-4.006516785212780873e-01 +4.746784494409508426e+01,3.128641510854382091e+02,4.013828537272832619e+00,4.006102041822470206e+00,5.317347559287453063e-01,-1.636717018682571634e-01,-1.198475928647572547e-01,9.999999925013489666e-01,-4.006102041822473536e-01 +4.747034113612804163e+01,3.128727703733956105e+02,4.018898830667480659e+00,4.005693485824246558e+00,5.312952496622795895e-01,-1.611755098540207376e-01,-1.208475928647572556e-01,9.999999931909251405e-01,-4.005693485824249889e-01 +4.747283758275716536e+01,3.128813918889461547e+02,4.023965335341476823e+00,4.005291119765973740e+00,5.308520403861913817e-01,-1.586790632418927094e-01,-1.218475928647572565e-01,9.999999940445202240e-01,-4.005291119765976848e-01 +4.747533428017590040e+01,3.128900156491717439e+02,4.029028018382314613e+00,4.004894946158370495e+00,5.304051272009890905e-01,-1.561823658380272206e-01,-1.228475928647572574e-01,9.999999943428968807e-01,-4.004894946158374380e-01 +4.747783122457380500e+01,3.128986416711157972e+02,4.034086846845541530e+00,4.004504967474940003e+00,5.299545091994426471e-01,-1.536854214542497377e-01,-1.238475928647572583e-01,9.999999952087690325e-01,-4.004504967474943888e-01 +4.748032841213661470e+01,3.129072699717831938e+02,4.039141787754515711e+00,4.004121186151898826e+00,5.295001854665765118e-01,-1.511882339034016642e-01,-1.248475928647572591e-01,9.999999956172910265e-01,-4.004121186151846645e-01 +4.748282583904631338e+01,3.129159005681396479e+02,4.044192808100161685e+00,4.003743604588118288e+00,5.290421550796616801e-01,-1.486908070046460695e-01,-1.258475928647572462e-01,9.999999960991607928e-01,-4.003743604588121952e-01 +4.748532350148117587e+01,3.129245334771114813e+02,4.049239874840726117e+00,4.003372225145053420e+00,5.285804171082085778e-01,-1.461931445795267293e-01,-1.268475928647572470e-01,9.999999966033027432e-01,-4.003372225145056529e-01 +4.748782139561582483e+01,3.129331687155853388e+02,4.054282954901533564e+00,4.003007050146682566e+00,5.281149706139590672e-01,-1.436952504533639541e-01,-1.278475928647572479e-01,9.999999970661078708e-01,-4.003007050146686341e-01 +4.749031951762128756e+01,3.129418063004076771e+02,4.059322015174744003e+00,4.002648081879444319e+00,5.276458146508791192e-01,-1.411971284552289152e-01,-1.288475928647572488e-01,9.999999975530677876e-01,-4.002648081879447428e-01 +4.749281786366506708e+01,3.129504462483844804e+02,4.064357022519110352e+00,4.002295322592175353e+00,5.271729482651505982e-01,-1.386987824175639761e-01,-1.298475928647572497e-01,9.999999976891299491e-01,-4.002295322592178684e-01 +4.749531642991117764e+01,3.129590885762809762e+02,4.069387943759736004e+00,4.001948774496050021e+00,5.266963704951640457e-01,-1.362002161772260245e-01,-1.308475928647572506e-01,9.999999982229955675e-01,-4.001948774496053018e-01 +4.749781521252022287e+01,3.129677333008211804e+02,4.074414745687833239e+00,4.001608439764518188e+00,5.262160803715102420e-01,-1.337014335726212921e-01,-1.318475928647572515e-01,9.999999986079716185e-01,-4.001608439764521852e-01 +4.750031420764943846e+01,3.129763804386874995e+02,4.079437395060484306e+00,4.001274320533251050e+00,5.257320769169724350e-01,-1.312024384468842564e-01,-1.328475928647572524e-01,9.999999989932082389e-01,-4.001274320533254603e-01 +4.750281341145275604e+01,3.129850300065205602e+02,4.084455858600398059e+00,4.000946418900079848e+00,5.252443591465185690e-01,-1.287032346460812715e-01,-1.338475928647572533e-01,9.999999990851443643e-01,-4.000946418900083179e-01 +4.750531282008086720e+01,3.129936820209186408e+02,4.089470102995672818e+00,4.000624736924939917e+00,5.247529260672928464e-01,-1.262038260202590356e-01,-1.348475928647572541e-01,9.999999997110425864e-01,-4.000624736924943692e-01 +4.750781242968126605e+01,3.130023364984374439e+02,4.094480094899555667e+00,4.000309276629812949e+00,5.242577766786077342e-01,-1.237042164205851419e-01,-1.358475928647572550e-01,9.999999996906461242e-01,-1.219351353873109750e-01 +4.751031223639832035e+01,3.130109934555896416e+02,4.099485800930203538e+00,4.000000039998677259e+00,5.237589099719357488e-01,-1.212044097043076252e-01,-1.361524071352429588e-01,9.999999996031530003e-01,0.000000000000000000e+00 +4.751281223637332118e+01,3.130196529088445914e+02,4.104487187670446069e+00,3.999697028977446500e+00,5.232589099719358039e-01,-1.187044097302989154e-01,-1.361524071352429588e-01,9.999999994408306225e-01,0.000000000000000000e+00 +4.751531242574455405e+01,3.130283148617103848e+02,4.109484244059068203e+00,3.999400245473920368e+00,5.227589099719358590e-01,-1.162042203604643498e-01,-1.361524071352429588e-01,9.999999991772114960e-01,0.000000000000000000e+00 +4.751781280064734858e+01,3.130369793120215149e+02,4.114476968846806137e+00,3.999109691357732643e+00,5.222589099719359140e-01,-1.137038454597304182e-01,-1.361524071352429588e-01,9.999999989797045963e-01,0.000000000000000000e+00 +4.752031335721412830e+01,3.130456462576118497e+02,4.119465360785477870e+00,3.998825368460300123e+00,5.217589099719359691e-01,-1.112032888955012538e-01,-1.361524071352429588e-01,9.999999986408527608e-01,0.000000000000000000e+00 +4.752281409157448877e+01,3.130543156963146885e+02,4.124449418627985864e+00,3.998547278574773767e+00,5.212589099719360242e-01,-1.087025545385370967e-01,-1.361524071352429588e-01,9.999999984301478628e-01,0.000000000000000000e+00 +4.752531499985524732e+01,3.130629876259627054e+02,4.129429141128316161e+00,3.998275423455988520e+00,5.207589099719360792e-01,-1.062016462617026563e-01,-1.361524071352429588e-01,9.999999982413225741e-01,0.000000000000000000e+00 +4.752781607818049991e+01,3.130716620443878355e+02,4.134404527041537492e+00,3.998009804820417123e+00,5.202589099719361343e-01,-1.037005679408476294e-01,-1.361524071352429588e-01,9.999999979470106659e-01,0.000000000000000000e+00 +4.753031732267168508e+01,3.130803389494215594e+02,4.139375575123803941e+00,3.997750424346122600e+00,5.197589099719361894e-01,-1.011993234548003301e-01,-1.361524071352429588e-01,9.999999976823311654e-01,0.000000000000000000e+00 +4.753281872944763364e+01,3.130890183388945616e+02,4.144342284132353171e+00,3.997497283672711621e+00,5.192589099719362444e-01,-9.869791668465185963e-02,-1.361524071352429588e-01,9.999999973473439052e-01,0.000000000000000000e+00 +4.753532029462463981e+01,3.130977002106370719e+02,4.149304652825508199e+00,3.997250384401290546e+00,5.187589099719362995e-01,-9.619635151428458653e-02,-1.361524071352429588e-01,9.999999971035807844e-01,0.000000000000000000e+00 +4.753782201431651089e+01,3.131063845624785813e+02,4.154262679962676508e+00,3.997009728094421011e+00,5.182589099719363546e-01,-9.369463182965852288e-02,-1.361524071352429588e-01,9.999999967348900398e-01,0.000000000000000000e+00 +4.754032388463463832e+01,3.131150713922480122e+02,4.159216364304351821e+00,3.996775316276078183e+00,5.177589099719364096e-01,-9.119276151969647748e-02,-1.361524071352429588e-01,9.999999964985105683e-01,0.000000000000000000e+00 +4.754282590168805456e+01,3.131237606977736618e+02,4.164165704612113217e+00,3.996547150431607687e+00,5.172589099719364647e-01,-8.869074447503998149e-02,-1.361524071352429588e-01,9.999999962023174982e-01,0.000000000000000000e+00 +4.754532806158348279e+01,3.131324524768832021e+02,4.169110699648625129e+00,3.996325232007686523e+00,5.167589099719365198e-01,-8.618858458911364540e-02,-1.361524071352429588e-01,9.999999957720353549e-01,0.000000000000000000e+00 +4.754783036042540800e+01,3.131411467274036795e+02,4.174051348177639120e+00,3.996109562412282212e+00,5.162589099719365748e-01,-8.368628575777040113e-02,-1.361524071352429588e-01,9.999999953926402840e-01,0.000000000000000000e+00 +4.755033279431612669e+01,3.131498434471615155e+02,4.178987648963992996e+00,3.995900143014613715e+00,5.157589099719366299e-01,-8.118385187858270791e-02,-1.361524071352429588e-01,9.999999952241940271e-01,0.000000000000000000e+00 +4.755283535935581796e+01,3.131585426339825631e+02,4.183919600773611691e+00,3.995696975145115015e+00,5.152589099719366850e-01,-7.868128685084463392e-02,-1.361524071352429588e-01,9.999999946216147073e-01,0.000000000000000000e+00 +4.755533805164259320e+01,3.131672442856919929e+02,4.188847202373507272e+00,3.995500060095399597e+00,5.147589099719367400e-01,-7.617859457752654273e-02,-1.361524071352429588e-01,9.999999943324183738e-01,0.000000000000000000e+00 +4.755784086727257431e+01,3.131759484001144642e+02,4.193770452531778936e+00,3.995309399118220917e+00,5.142589099719367951e-01,-7.367577896172965157e-02,-1.361524071352429588e-01,9.999999939437471674e-01,0.000000000000000000e+00 +4.756034380233993630e+01,3.131846549750738973e+02,4.198689350017613897e+00,3.995124993427442650e+00,5.137589099719368502e-01,-7.117284390952956230e-02,-1.361524071352429588e-01,9.999999935128448536e-01,0.000000000000000000e+00 +4.756284685293696413e+01,3.131933640083936439e+02,4.203603893601289165e+00,3.994946844198002722e+00,5.132589099719369052e-01,-6.866979332873925090e-02,-1.361524071352429588e-01,9.999999929995833092e-01,0.000000000000000000e+00 +4.756535001515413086e+01,3.132020754978964305e+02,4.208514082054167993e+00,3.994774952565881332e+00,5.127589099719369603e-01,-6.616663112909217104e-02,-1.361524071352429588e-01,9.999999926204108380e-01,0.000000000000000000e+00 +4.756785328508015454e+01,3.132107894414044154e+02,4.213419914148703427e+00,3.994609319628069422e+00,5.122589099719370154e-01,-6.366336122153930244e-02,-1.361524071352429588e-01,9.999999921394376878e-01,0.000000000000000000e+00 +4.757035665880204789e+01,3.132195058367390743e+02,4.218321388658437421e+00,3.994449946442539812e+00,5.117589099719370704e-01,-6.115998751932066879e-02,-1.361524071352429588e-01,9.999999915768419401e-01,0.000000000000000000e+00 +4.757286013240518940e+01,3.132282246817213718e+02,4.223218504358000835e+00,3.994296834028216558e+00,5.112589099719371255e-01,-5.865651393726353802e-02,-1.361524071352429588e-01,9.999999911376159512e-01,0.000000000000000000e+00 +4.757536370197338016e+01,3.132369459741715332e+02,4.228111260023115214e+00,3.994149983364946976e+00,5.107589099719371806e-01,-5.615294439125880638e-02,-1.361524071352429588e-01,9.999999905028136293e-01,0.000000000000000000e+00 +4.757786736358890778e+01,3.132456697119092723e+02,4.232999654430591896e+00,3.994009395393475881e+00,5.102589099719372356e-01,-5.364928279951170637e-02,-1.361524071352429588e-01,9.999999899629119504e-01,0.000000000000000000e+00 +4.758037111333259617e+01,3.132543958927536778e+02,4.237883686358332014e+00,3.993875071015417610e+00,5.097589099719372907e-01,-5.114553308095503431e-02,-1.361524071352429588e-01,9.999999894256264010e-01,0.000000000000000000e+00 +4.758287494728388367e+01,3.132631245145231560e+02,4.242763354585328273e+00,3.993747011093232935e+00,5.092589099719373458e-01,-4.864169915614630774e-02,-1.361524071352429588e-01,9.999999886991666198e-01,0.000000000000000000e+00 +4.758537886152087282e+01,3.132718555750355449e+02,4.247638657891663172e+00,3.993625216450204629e+00,5.087589099719374008e-01,-4.613778494745578163e-02,-1.361524071352429588e-01,9.999999882002640339e-01,0.000000000000000000e+00 +4.758788285212039426e+01,3.132805890721081141e+02,4.252509595058510783e+00,3.993509687870413494e+00,5.082589099719374559e-01,-4.363379437748154260e-02,-1.361524071352429588e-01,9.999999873248709426e-01,0.000000000000000000e+00 +4.759038691515807074e+01,3.132893250035575079e+02,4.257376164868136748e+00,3.993400426098719258e+00,5.077589099719375110e-01,-4.112973137154419395e-02,-1.361524071352429588e-01,9.999999867852920055e-01,0.000000000000000000e+00 +4.759289104670837389e+01,3.132980633671996884e+02,4.262238366103899168e+00,3.993297431840736156e+00,5.072589099719375660e-01,-3.862559985432936771e-02,-1.361524071352429588e-01,9.999999859185798590e-01,0.000000000000000000e+00 +4.759539524284469536e+01,3.133068041608501062e+02,4.267096197550246828e+00,3.993200705762817826e+00,5.067589099719376211e-01,-3.612140375327003994e-02,-1.361524071352429588e-01,9.999999852359955366e-01,0.000000000000000000e+00 +4.759789949963939648e+01,3.133155473823235297e+02,4.271949657992722749e+00,3.993110248492034664e+00,5.062589099719376762e-01,-3.361714699554474439e-02,-1.361524071352429588e-01,9.999999842274607254e-01,0.000000000000000000e+00 +4.760040381316386515e+01,3.133242930294341591e+02,4.276798746217961522e+00,3.993026060616159612e+00,5.057589099719377312e-01,-3.111283351057371818e-02,-1.361524071352429588e-01,9.999999835565838158e-01,0.000000000000000000e+00 +4.760290817948860109e+01,3.133330410999956257e+02,4.281643461013691088e+00,3.992948142683648616e+00,5.052589099719377863e-01,-2.860846722701814587e-02,-1.361524071352429588e-01,9.999999825113715657e-01,0.000000000000000000e+00 +4.760541259468325137e+01,3.133417915918208791e+02,4.286483801168732732e+00,3.992876495203629528e+00,5.047589099719378414e-01,-2.610405207616353293e-02,-1.361524071352429588e-01,9.999999815531688263e-01,0.000000000000000000e+00 +4.760791705481669567e+01,3.133505445027223004e+02,4.291319765473001979e+00,3.992811118645883450e+00,5.042589099719378964e-01,-2.359959198891966106e-02,-1.361524071352429588e-01,9.999999805463415381e-01,0.000000000000000000e+00 +4.761042155595708181e+01,3.133592998305116453e+02,4.296151352717506811e+00,3.992752013440834524e+00,5.037589099719379515e-01,-2.109509089725399716e-02,-1.361524071352429588e-01,9.999999795370368982e-01,0.000000000000000000e+00 +4.761292609417191102e+01,3.133680575730001010e+02,4.300978561694351221e+00,3.992699179979537050e+00,5.032589099719380066e-01,-1.859055273367477001e-02,-1.361524071352429588e-01,9.999999782574748863e-01,0.000000000000000000e+00 +4.761543066552808767e+01,3.133768177279982297e+02,4.305801391196732553e+00,3.992652618613664828e+00,5.027589099719380616e-01,-1.608598143195551569e-02,-1.361524071352429588e-01,9.999999771169751916e-01,0.000000000000000000e+00 +4.761793526609197613e+01,3.133855802933159680e+02,4.310619840018944160e+00,3.992612329655499614e+00,5.022589099719381167e-01,-1.358138092537751820e-02,-1.361524071352429588e-01,9.999999757859800997e-01,0.000000000000000000e+00 +4.762043989192947890e+01,3.133943452667626843e+02,4.315433906956372745e+00,3.992578313377924903e+00,5.017589099719381718e-01,-1.107675514851862511e-02,-1.361524071352429588e-01,9.999999745410540486e-01,0.000000000000000000e+00 +4.762294453910608638e+01,3.134031126461471786e+02,4.320243590805502798e+00,3.992550570014416156e+00,5.012589099719382268e-01,-8.572108035673384543e-03,-1.361524071352429588e-01,9.999999729905587609e-01,0.000000000000000000e+00 +4.762544920368694790e+01,3.134118824292775685e+02,4.325048890363912157e+00,3.992529099759035915e+00,5.007589099719382819e-01,-6.067443522464856590e-03,-1.361524071352429588e-01,9.999999714196328160e-01,0.000000000000000000e+00 +4.762795388173690725e+01,3.134206546139614034e+02,4.329849804430277338e+00,3.992513902766425815e+00,5.002589099719383370e-01,-3.562765544087725684e-03,-1.361524071352429588e-01,9.999999697990610281e-01,0.000000000000000000e+00 +4.763045856932060218e+01,3.134294291980056641e+02,4.334646331804369090e+00,3.992504979151803912e+00,4.997589099719383365e-01,-1.058078036033820515e-03,-1.361524071352429588e-01,9.999999680684147352e-01,0.000000000000000000e+00 +4.763296326250250701e+01,3.134382061792166496e+02,4.339438471287055066e+00,3.992502328990961136e+00,4.992589099719383361e-01,1.446615065891532301e-03,-1.361524071352429588e-01,9.999999662068130846e-01,0.000000000000000000e+00 +4.763546795734698946e+01,3.134469855554002038e+02,4.344226221680301592e+00,3.992505952320258622e+00,4.987589099719383356e-01,3.951309825730399058e-03,-1.361524071352429588e-01,9.999999640913311838e-01,0.000000000000000000e+00 +4.763797264991837466e+01,3.134557673243614317e+02,4.349009581787170120e+00,3.992515849136626382e+00,4.982589099719383352e-01,6.456002307178492459e-03,-1.361524071352429588e-01,9.999999619925133976e-01,0.000000000000000000e+00 +4.764047733628102321e+01,3.134645514839048701e+02,4.353788550411820779e+00,3.992532019397562415e+00,4.977589099719383348e-01,8.960688574632537373e-03,-1.361524071352429588e-01,9.999999596541377933e-01,0.000000000000000000e+00 +4.764298201249937392e+01,3.134733380318344871e+02,4.358563126359511486e+00,3.992554463021135369e+00,4.972589099719383343e-01,1.146536469193272859e-02,-1.361524071352429588e-01,9.999999571426897438e-01,0.000000000000000000e+00 +4.764548667463801479e+01,3.134821269659536824e+02,4.363333308436598834e+00,3.992583179885984990e+00,4.967589099719383339e-01,1.397002672323285379e-02,-1.361524071352429588e-01,9.999999543518713896e-01,0.000000000000000000e+00 +4.764799131876174698e+01,3.134909182840651738e+02,4.368099095450537206e+00,3.992618169831325670e+00,4.962589099719383334e-01,1.647467073262936718e-02,-1.361524071352429588e-01,9.999999514981784410e-01,0.000000000000000000e+00 +4.765049594093562746e+01,3.134997119839711672e+02,4.372860486209879660e+00,3.992659432656950003e+00,4.957589099719383330e-01,1.897929278503170114e-02,-1.361524071352429588e-01,9.999999482714477805e-01,0.000000000000000000e+00 +4.765300053722506135e+01,3.135085080634732435e+02,4.377617479524277933e+00,3.992706968123235445e+00,4.952589099719383325e-01,2.148388894490499412e-02,-1.361524071352429588e-01,9.999999448260129542e-01,0.000000000000000000e+00 +4.765550510369583748e+01,3.135173065203723581e+02,4.382370074204484212e+00,3.992760775951148755e+00,4.947589099719383321e-01,2.398845527749528944e-02,-1.361524071352429588e-01,9.999999409312473331e-01,0.000000000000000000e+00 +4.765800963641420651e+01,3.135261073524688982e+02,4.387118269062350251e+00,3.992820855822254433e+00,4.942589099719383317e-01,2.649298784792715813e-02,-1.361524071352429588e-01,9.999999367504036618e-01,0.000000000000000000e+00 +4.766051413144693782e+01,3.135349105575626822e+02,4.391862062910826481e+00,3.992887207378721826e+00,4.937589099719383312e-01,2.899748272225196807e-02,-1.361524071352429588e-01,9.999999323451370659e-01,0.000000000000000000e+00 +4.766301858486137633e+01,3.135437161334529037e+02,4.396601454563965561e+00,3.992959830223335782e+00,4.932589099719383308e-01,3.150193596725515965e-02,-1.361524071352429588e-01,9.999999270383744809e-01,0.000000000000000000e+00 +4.766552299272551352e+01,3.135525240779381306e+02,4.401336442836918827e+00,3.993038723919507760e+00,4.927589099719383303e-01,3.400634364866787773e-02,-1.361524071352429588e-01,9.999999216801003232e-01,0.000000000000000000e+00 +4.766802735110803724e+01,3.135613343888164195e+02,4.406067026545939846e+00,3.993123887991283372e+00,4.922589099719383299e-01,3.651070183505309569e-02,-1.361524071352429588e-01,9.999999152489114085e-01,0.000000000000000000e+00 +4.767053165607840981e+01,3.135701470638851447e+02,4.410793204508381748e+00,3.993215321923360595e+00,4.917589099719383294e-01,3.901500659318058589e-02,-1.361524071352429588e-01,9.999999083215975748e-01,0.000000000000000000e+00 +4.767303590370690358e+01,3.135789621009411690e+02,4.415514975542700782e+00,3.993313025161097318e+00,4.912589099719383290e-01,4.151925399209104722e-02,-1.361524071352429588e-01,9.999999005242440342e-01,0.000000000000000000e+00 +4.767554009006469329e+01,3.135877794977807298e+02,4.420232338468454536e+00,3.993416997110529998e+00,4.907589099719383285e-01,4.402344010077683528e-02,-1.361524071352429588e-01,9.999998915236482100e-01,0.000000000000000000e+00 +4.767804421122389869e+01,3.135965992521994963e+02,4.424945292106301942e+00,3.993527237138387420e+00,4.902589099719383281e-01,4.652756098834556764e-02,-1.361524071352429588e-01,9.999998815232511440e-01,0.000000000000000000e+00 +4.768054826325764850e+01,3.136054213619925122e+02,4.429653835278004159e+00,3.993643744572105803e+00,4.897589099719383277e-01,4.903161272542552740e-02,-1.361524071352429588e-01,9.999998698468971492e-01,0.000000000000000000e+00 +4.768305224224015149e+01,3.136142458249542528e+02,4.434357966806425466e+00,3.993766518699848334e+00,4.892589099719383272e-01,5.153559138202460504e-02,-1.361524071352429588e-01,9.999998563553885722e-01,0.000000000000000000e+00 +4.768555614424673195e+01,3.136230726388786252e+02,4.439057685515533258e+00,3.993895558770520271e+00,4.887589099719383268e-01,5.403949302893643752e-02,-1.361524071352429588e-01,9.999998405968102411e-01,0.000000000000000000e+00 +4.768805996535392921e+01,3.136319018015589108e+02,4.443752990230398048e+00,3.994030863993788483e+00,4.882589099719383263e-01,5.654331373701887431e-02,-1.361524071352429588e-01,9.999998220191265164e-01,0.000000000000000000e+00 +4.769056370163953318e+01,3.136407333107877662e+02,4.448443879777193466e+00,3.994172433540100098e+00,4.877589099719383259e-01,5.904704957700481621e-02,-1.361524071352429588e-01,9.999997996160744362e-01,0.000000000000000000e+00 +4.769306734918264823e+01,3.136495671643573928e+02,4.453130352983197149e+00,3.994320266540701603e+00,4.872589099719383254e-01,6.155069661842650641e-02,-1.361524071352429588e-01,9.999997724232131402e-01,0.000000000000000000e+00 +4.769557090406375721e+01,3.136584033600593102e+02,4.457812408676791627e+00,3.994474362087656161e+00,4.867589099719383250e-01,6.405425092978188351e-02,-1.361524071352429588e-01,9.999997383842624821e-01,0.000000000000000000e+00 +4.769807436236478537e+01,3.136672418956844126e+02,4.462490045687461659e+00,3.994634719233862263e+00,4.862589099719383245e-01,6.655770857586282285e-02,-1.361524071352429588e-01,9.999996952721328380e-01,0.000000000000000000e+00 +4.770057772016915720e+01,3.136760827690231395e+02,4.467163262845798677e+00,3.994801336993066609e+00,4.857589099719383241e-01,6.906106561738957483e-02,-1.361524071352429588e-01,9.999996385627786255e-01,0.000000000000000000e+00 +4.770308097356186039e+01,3.136849259778651913e+02,4.471832058983499003e+00,3.994974214339876983e+00,4.852589099719383237e-01,7.156431810532302984e-02,-1.361524071352429588e-01,9.999995609379598305e-01,0.000000000000000000e+00 +4.770558411862950976e+01,3.136937715199998138e+02,4.476496432933362968e+00,3.995153350209761811e+00,4.847589099719383232e-01,7.406746207393359593e-02,-1.361524071352429588e-01,9.999994485978134229e-01,0.000000000000000000e+00 +4.770808715146039702e+01,3.137026193932156275e+02,4.481156383529296683e+00,3.995338743499033285e+00,4.842589099719383228e-01,7.657049352464201375e-02,-1.361524071352429588e-01,9.999992727499020795e-01,0.000000000000000000e+00 +4.771059006814456183e+01,3.137114695953006844e+02,4.485811909606312931e+00,3.995530393064790964e+00,4.837589099719383223e-01,7.907340838856197207e-02,-1.361524071352429588e-01,9.999989583336458265e-01,0.000000000000000000e+00 +4.771309286477385569e+01,3.137203221240424114e+02,4.490463010000530275e+00,3.995728297724772560e+00,4.832589099719383219e-01,8.157620241077585821e-02,-1.361524071352429588e-01,9.999982423913481577e-01,0.000000000000000000e+00 +4.771559553744199178e+01,3.137291769772276666e+02,4.495109683549173951e+00,3.995932456256916065e+00,4.827589099719383214e-01,8.407887068018937704e-02,-1.361524071352429588e-01,9.999950219446477329e-01,0.000000000000000000e+00 +4.771809808224460170e+01,3.137380341526427401e+02,4.499751929090574976e+00,3.996142867397746379e+00,4.822589099719383210e-01,8.658140302499624241e-02,-1.361524071352429588e-01,-9.999931011930357494e-01,0.000000000000000000e+00 +4.772060049527932790e+01,3.137468936480733532e+02,4.504389745464172812e+00,3.996359529829240920e+00,4.817589099719383205e-01,8.407900725393557817e-02,-1.361524071352429588e-01,-9.999978821398877171e-01,0.000000000000000000e+00 +4.772310277264585920e+01,3.137557554613046022e+02,4.509023131510512705e+00,3.996569918826092582e+00,4.812589099719383201e-01,8.157673518688104974e-02,-1.361524071352429588e-01,-9.999987200302010715e-01,0.000000000000000000e+00 +4.772560491828652118e+01,3.137646195901210717e+02,4.513652086071248348e+00,3.996774035698420047e+00,4.807589099719383197e-01,7.907459274888779810e-02,-1.361524071352429588e-01,-9.999990668459693977e-01,0.000000000000000000e+00 +4.772810693614159305e+01,3.137734860323066641e+02,4.518276607989140992e+00,3.996971881741360200e+00,4.802589099719383192e-01,7.657257722858525073e-02,-1.361524071352429588e-01,-9.999992556715696645e-01,0.000000000000000000e+00 +4.773060883014932188e+01,3.137823547856448272e+02,4.522896696108060333e+00,3.997163458213484954e+00,4.797589099719383188e-01,7.407068508308459198e-02,-1.361524071352429588e-01,-9.999993734390050237e-01,0.000000000000000000e+00 +4.773311060424601493e+01,3.137912258479183834e+02,4.527512349272984515e+00,3.997348766334750003e+00,4.792589099719383183e-01,7.156891255390723794e-02,-1.361524071352429588e-01,-9.999994531590897795e-01,0.000000000000000000e+00 +4.773561226236606814e+01,3.138000992169095298e+02,4.532123566330000131e+00,3.997527807285984114e+00,4.787589099719383179e-01,6.906725580185953117e-02,-1.361524071352429588e-01,-9.999995103674684804e-01,0.000000000000000000e+00 +4.773811380844206553e+01,3.138089748903999521e+02,4.536730346126303104e+00,3.997700582208715048e+00,4.782589099719383174e-01,6.656571095070215605e-02,-1.361524071352429588e-01,-9.999995526251361788e-01,0.000000000000000000e+00 +4.774061524640480769e+01,3.138178528661707105e+02,4.541332687510197808e+00,3.997867092205103834e+00,4.777589099719383170e-01,6.406427410704379488e-02,-1.361524071352429588e-01,-9.999995848376316276e-01,0.000000000000000000e+00 +4.774311658018338278e+01,3.138267331420022970e+02,4.545930589331099725e+00,3.998027338337927894e+00,4.772589099719383166e-01,6.156294136692495866e-02,-1.361524071352429588e-01,-9.999996096087110375e-01,0.000000000000000000e+00 +4.774561781370525182e+01,3.138356157156746917e+02,4.550524050439532786e+00,3.998181321630579710e+00,4.767589099719383161e-01,5.906170882151561691e-02,-1.361524071352429588e-01,-9.999996286591833483e-01,0.000000000000000000e+00 +4.774811895089627711e+01,3.138445005849671929e+02,4.555113069687132032e+00,3.998329043067078814e+00,4.762589099719383157e-01,5.656057255926287552e-02,-1.361524071352429588e-01,-9.999996434656018840e-01,0.000000000000000000e+00 +4.775061999568080751e+01,3.138533877476586440e+02,4.559697645926642728e+00,3.998470503592088221e+00,4.757589099719383152e-01,5.405952866644080784e-02,-1.361524071352429588e-01,-9.999996545503833101e-01,0.000000000000000000e+00 +4.775312095198172813e+01,3.138622772015272062e+02,4.564277778011921249e+00,3.998605704110931303e+00,4.752589099719383148e-01,5.155857322947555305e-02,-1.361524071352429588e-01,-9.999996626886871187e-01,0.000000000000000000e+00 +4.775562182372052433e+01,3.138711689443505293e+02,4.568853464797934194e+00,3.998734645489613548e+00,4.747589099719383143e-01,4.905770233425175986e-02,-1.361524071352429588e-01,-9.999996680565982343e-01,0.000000000000000000e+00 +4.775812261481734566e+01,3.138800629739056944e+02,4.573424705140760160e+00,3.998857328554841661e+00,4.742589099719383139e-01,4.655691206754938860e-02,-1.361524071352429588e-01,-9.999996710122781574e-01,0.000000000000000000e+00 +4.776062332919106979e+01,3.138889592879691577e+02,4.577991497897588857e+00,3.998973754094045319e+00,4.737589099719383134e-01,4.405619851652687463e-02,-1.361524071352429588e-01,-9.999996716701435862e-01,0.000000000000000000e+00 +4.776312397075935934e+01,3.138978578843168634e+02,4.582553841926721994e+00,3.999083922855396711e+00,4.732589099719383130e-01,4.155555776926923156e-02,-1.361524071352429588e-01,-9.999996701139871602e-01,0.000000000000000000e+00 +4.776562454343872588e+01,3.139067587607241876e+02,4.587111736087573277e+00,3.999187835547830527e+00,4.727589099719383126e-01,3.905498591480318499e-02,-1.361524071352429588e-01,-9.999996659710805869e-01,0.000000000000000000e+00 +4.776812505114459384e+01,3.139156619149658809e+02,4.591665179240669303e+00,3.999285492841063050e+00,4.722589099719383121e-01,3.655447904417730154e-02,-1.361524071352429588e-01,-9.999996594776130454e-01,0.000000000000000000e+00 +4.777062549779135026e+01,3.139245673448161824e+02,4.596214170247649555e+00,3.999376895365613027e+00,4.717589099719383117e-01,3.405403324887795041e-02,-1.361524071352429588e-01,-9.999996501294552420e-01,0.000000000000000000e+00 +4.777312588729242293e+01,3.139334750480487060e+02,4.600758707971266404e+00,3.999462043712817660e+00,4.712589099719383112e-01,3.155364462261911473e-02,-1.361524071352429588e-01,-9.999996375345424626e-01,0.000000000000000000e+00 +4.777562622356033017e+01,3.139423850224365538e+02,4.605298791275385994e+00,3.999540938434852144e+00,4.707589099719383108e-01,2.905330926100079675e-02,-1.361524071352429588e-01,-9.999996209868657893e-01,0.000000000000000000e+00 +4.777812651050673765e+01,3.139512972657522027e+02,4.609834419024986474e+00,3.999613580044747430e+00,4.702589099719383103e-01,2.655302326223265424e-02,-1.361524071352429588e-01,-9.999995996796826603e-01,0.000000000000000000e+00 +4.778062675204254361e+01,3.139602117757675614e+02,4.614365590086161539e+00,3.999679969016408876e+00,4.697589099719383099e-01,2.405278272732454259e-02,-1.361524071352429588e-01,-9.999995718531345945e-01,0.000000000000000000e+00 +4.778312695207791450e+01,3.139691285502540836e+02,4.618892303326117776e+00,3.999740105784634459e+00,4.692589099719383094e-01,2.155258376240822699e-02,-1.361524071352429588e-01,-9.999995358599611528e-01,0.000000000000000000e+00 +4.778562711452235590e+01,3.139780475869825409e+02,4.623414557613177323e+00,3.999793990745137862e+00,4.687589099719383090e-01,1.905242247839452480e-02,-1.361524071352429588e-01,-9.999994878211108107e-01,0.000000000000000000e+00 +4.778812724328476946e+01,3.139869688837231365e+02,4.627932351816776979e+00,3.999841624254569794e+00,4.682589099719383086e-01,1.655229499649184602e-02,-1.361524071352429588e-01,-9.999994222651032993e-01,0.000000000000000000e+00 +4.779062734227353104e+01,3.139958924382455621e+02,4.632445684807468211e+00,3.999883006630552185e+00,4.677589099719383081e-01,1.405219745212602823e-02,-1.361524071352429588e-01,-9.999993286466283271e-01,0.000000000000000000e+00 +4.779312741539652620e+01,3.140048182483189976e+02,4.636954555456917149e+00,3.999918138151721259e+00,4.672589099719383077e-01,1.155212600756391761e-02,-1.361524071352429588e-01,-9.999991863017578808e-01,0.000000000000000000e+00 +4.779562746656122840e+01,3.140137463117118841e+02,4.641458962637906360e+00,3.999947019057801256e+00,4.667589099719383072e-01,9.052076877148871811e-03,-1.361524071352429588e-01,-9.999989466845886632e-01,0.000000000000000000e+00 +4.779812749967475582e+01,3.140226766261922648e+02,4.645958905224334856e+00,3.999969649549740325e+00,4.662589099719383068e-01,6.552046396944808358e-03,-1.361524071352429588e-01,-9.999984641606941560e-01,0.000000000000000000e+00 +4.780062751864392823e+01,3.140316091895275576e+02,4.650454382091216310e+00,3.999986029790019604e+00,4.657589099719383063e-01,4.052031267396863541e-03,-1.361524071352429588e-01,-9.999970108496183396e-01,0.000000000000000000e+00 +4.780312752737533799e+01,3.140405439994846120e+02,4.654945392114681724e+00,3.999996159903568049e+00,4.652589099719383059e-01,1.552030008887184424e-03,-1.361524071352429588e-01,-6.208586966924765083e-01,0.000000000000000000e+00 +4.780562752977539986e+01,3.140494810538297656e+02,4.659431934171978540e+00,4.000000039982315236e+00,4.647589099719383054e-01,-1.182229437284152384e-07,-1.361524071352429588e-01,4.729003061534868552e-05,0.000000000000000000e+00 +4.780812752975040780e+01,3.140584203503287313e+02,4.663914007141470641e+00,4.000000039686757880e+00,4.642589099719383050e-01,2.131628228429653652e-12,-1.361524071352429588e-01,-8.526512998316027241e-10,0.000000000000000000e+00 +4.781062752972560048e+01,3.140673618867466530e+02,4.668391609902641015e+00,4.000000039686763209e+00,4.637589099719383046e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.781312752970079316e+01,3.140763056608481634e+02,4.672864741336088201e+00,4.000000039686763209e+00,4.632589099719383041e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.781562752967598584e+01,3.140852516703973265e+02,4.677333400323528956e+00,4.000000039686763209e+00,4.627589099719383037e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.781812752965117852e+01,3.140941999131576381e+02,4.681797585747799140e+00,4.000000039686763209e+00,4.622589099719383032e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.782062752962637120e+01,3.141031503868920254e+02,4.686257296492852831e+00,4.000000039686763209e+00,4.617589099719383028e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.782312752960156388e+01,3.141121030893629040e+02,4.690712531443762323e+00,4.000000039686763209e+00,4.612589099719383023e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.782562752957675656e+01,3.141210580183320644e+02,4.695163289486718128e+00,4.000000039686763209e+00,4.607589099719383019e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.782812752955194924e+01,3.141300151715607853e+02,4.699609569509030749e+00,4.000000039686763209e+00,4.602589099719383015e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.783062752952714192e+01,3.141389745468097772e+02,4.704051370399130683e+00,4.000000039686763209e+00,4.597589099719383010e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.783312752950233460e+01,3.141479361418392386e+02,4.708488691046568420e+00,4.000000039686763209e+00,4.592589099719383006e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.783562752947752728e+01,3.141568999544087433e+02,4.712921530342012666e+00,4.000000039686763209e+00,4.587589099719383001e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.783812752945271995e+01,3.141658659822772961e+02,4.717349887177253898e+00,4.000000039686763209e+00,4.582589099719382997e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.784062752942791263e+01,3.141748342232034474e+02,4.721773760445203472e+00,4.000000039686763209e+00,4.577589099719382992e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.784312752940310531e+01,3.141838046749450655e+02,4.726193149039892738e+00,4.000000039686763209e+00,4.572589099719382988e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.784562752937829799e+01,3.141927773352596205e+02,4.730608051856473928e+00,4.000000039686763209e+00,4.567589099719382983e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.784812752935349067e+01,3.142017522019039006e+02,4.735018467791221930e+00,4.000000039686763209e+00,4.562589099719382979e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.785062752932868335e+01,3.142107292726341825e+02,4.739424395741533402e+00,4.000000039686763209e+00,4.557589099719382975e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.785312752930387603e+01,3.142197085452062311e+02,4.743825834605924996e+00,4.000000039686763209e+00,4.552589099719382970e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.785562752927906871e+01,3.142286900173751860e+02,4.748222783284037796e+00,4.000000039686763209e+00,4.547589099719382966e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.785812752925426139e+01,3.142376736868957323e+02,4.752615240676634656e+00,4.000000039686763209e+00,4.542589099719382961e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.786062752922945407e+01,3.142466595515219296e+02,4.757003205685601976e+00,4.000000039686763209e+00,4.537589099719382957e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.786312752920464675e+01,3.142556476090072692e+02,4.761386677213947038e+00,4.000000039686763209e+00,4.532589099719382952e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.786562752917983943e+01,3.142646378571047876e+02,4.765765654165803333e+00,4.000000039686763209e+00,4.527589099719382948e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.786812752915503211e+01,3.142736302935668959e+02,4.770140135446426122e+00,4.000000039686763209e+00,4.522589099719382943e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.787062752913022479e+01,3.142826249161455507e+02,4.774510119962195098e+00,4.000000039686763209e+00,4.517589099719382939e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.787312752910541747e+01,3.142916217225920263e+02,4.778875606620613503e+00,4.000000039686763209e+00,4.512589099719382935e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.787562752908061015e+01,3.143006207106571424e+02,4.783236594330310787e+00,4.000000039686763209e+00,4.507589099719382930e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.787812752905580282e+01,3.143096218780911499e+02,4.787593082001039058e+00,4.000000039686763209e+00,4.502589099719382926e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.788062752903099550e+01,3.143186252226437318e+02,4.791945068543677522e+00,4.000000039686763209e+00,4.497589099719382921e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.788312752900618818e+01,3.143276307420640592e+02,4.796292552870228931e+00,4.000000039686763209e+00,4.492589099719382917e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.788562752898138086e+01,3.143366384341007915e+02,4.800635533893822249e+00,4.000000039686763209e+00,4.487589099719382912e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.788812752895657354e+01,3.143456482965019632e+02,4.804974010528711759e+00,4.000000039686763209e+00,4.482589099719382908e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.789062752893176622e+01,3.143546603270151536e+02,4.809307981690278844e+00,4.000000039686763209e+00,4.477589099719382904e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.789312752890695890e+01,3.143636745233873171e+02,4.813637446295031097e+00,4.000000039686763209e+00,4.472589099719382899e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.789562752888215158e+01,3.143726908833649532e+02,4.817962403260601434e+00,4.000000039686763209e+00,4.467589099719382895e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.789812752885734426e+01,3.143817094046939360e+02,4.822282851505751644e+00,4.000000039686763209e+00,4.462589099719382890e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.790062752883253694e+01,3.143907300851196283e+02,4.826598789950368840e+00,4.000000039686763209e+00,4.457589099719382886e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.790312752880772962e+01,3.143997529223868810e+02,4.830910217515469007e+00,4.000000039686763209e+00,4.452589099719382881e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.790562752878292230e+01,3.144087779142399199e+02,4.835217133123195232e+00,4.000000039686763209e+00,4.447589099719382877e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.790812752875811498e+01,3.144178050584225730e+02,4.839519535696818586e+00,4.000000039686763209e+00,4.442589099719382872e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.791062752873330766e+01,3.144268343526780427e+02,4.843817424160738128e+00,4.000000039686763209e+00,4.437589099719382868e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.791312752870850034e+01,3.144358657947489633e+02,4.848110797440481790e+00,4.000000039686763209e+00,4.432589099719382864e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.791562752868369301e+01,3.144448993823775140e+02,4.852399654462706380e+00,4.000000039686763209e+00,4.427589099719382859e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.791812752865888569e+01,3.144539351133053060e+02,4.856683994155198469e+00,4.000000039686763209e+00,4.422589099719382855e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.792062752863407837e+01,3.144629729852733817e+02,4.860963815446871727e+00,4.000000039686763209e+00,4.417589099719382850e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.792312752860927105e+01,3.144720129960222721e+02,4.865239117267772251e+00,4.000000039686763209e+00,4.412589099719382846e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.792562752858446373e+01,3.144810551432919965e+02,4.869509898549073235e+00,4.000000039686763209e+00,4.407589099719382841e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.792812752855965641e+01,3.144900994248220059e+02,4.873776158223080301e+00,4.000000039686763209e+00,4.402589099719382837e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.793062752853484909e+01,3.144991458383512395e+02,4.878037895223228837e+00,4.000000039686763209e+00,4.397589099719382832e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.793312752851004177e+01,3.145081943816180683e+02,4.882295108484083990e+00,4.000000039686763209e+00,4.392589099719382828e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.793562752848523445e+01,3.145172450523603516e+02,4.886547796941342447e+00,4.000000039686763209e+00,4.387589099719382824e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.793812752846042713e+01,3.145262978483154370e+02,4.890795959531832438e+00,4.000000039686763209e+00,4.382589099719382819e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.794062752843561981e+01,3.145353527672201608e+02,4.895039595193512838e+00,4.000000039686763209e+00,4.377589099719382815e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.794312752841081249e+01,3.145444098068107337e+02,4.899278702865474955e+00,4.000000039686763209e+00,4.372589099719382810e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.794562752838600517e+01,3.145534689648229687e+02,4.903513281487942521e+00,4.000000039686763209e+00,4.367589099719382806e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.794812752836119785e+01,3.145625302389919966e+02,4.907743330002269921e+00,4.000000039686763209e+00,4.362589099719382801e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.795062752833639053e+01,3.145715936270525503e+02,4.911968847350945744e+00,4.000000039686763209e+00,4.357589099719382797e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.795312752831158321e+01,3.145806591267387375e+02,4.916189832477590116e+00,4.000000039686763209e+00,4.352589099719382792e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.795562752828677588e+01,3.145897267357842111e+02,4.920406284326957369e+00,4.000000039686763209e+00,4.347589099719382788e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.795812752826196856e+01,3.145987964519221123e+02,4.924618201844934262e+00,4.000000039686763209e+00,4.342589099719382784e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.796062752823716124e+01,3.146078682728849572e+02,4.928825583978541758e+00,4.000000039686763209e+00,4.337589099719382779e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.796312752821235392e+01,3.146169421964048070e+02,4.933028429675934134e+00,4.000000039686763209e+00,4.332589099719382775e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.796562752818754660e+01,3.146260182202131546e+02,4.937226737886399874e+00,4.000000039686763209e+00,4.327589099719382770e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.796812752816273928e+01,3.146350963420410380e+02,4.941420507560361663e+00,4.000000039686763209e+00,4.322589099719382766e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.797062752813793196e+01,3.146441765596188702e+02,4.945609737649377280e+00,4.000000039686763209e+00,4.317589099719382761e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.797312752811312464e+01,3.146532588706766660e+02,4.949794427106139594e+00,4.000000039686763209e+00,4.312589099719382757e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.797562752808831732e+01,3.146623432729438150e+02,4.953974574884476567e+00,4.000000039686763209e+00,4.307589099719382753e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.797812752806351000e+01,3.146714297641491953e+02,4.958150179939350366e+00,4.000000039686763209e+00,4.302589099719382748e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.798062752803870268e+01,3.146805183420212302e+02,4.962321241226860025e+00,4.000000039686763209e+00,4.297589099719382744e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.798312752801389536e+01,3.146896090042877177e+02,4.966487757704240558e+00,4.000000039686763209e+00,4.292589099719382739e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.798562752798908804e+01,3.146987017486760578e+02,4.970649728329862960e+00,4.000000039686763209e+00,4.287589099719382735e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.798812752796428072e+01,3.147077965729130256e+02,4.974807152063234206e+00,4.000000039686763209e+00,4.282589099719382730e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.799062752793947340e+01,3.147168934747249409e+02,4.978960027864998139e+00,4.000000039686763209e+00,4.277589099719382726e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.799312752791466608e+01,3.147259924518375556e+02,4.983108354696936360e+00,4.000000039686763209e+00,4.272589099719382721e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.799562752788985875e+01,3.147350935019761096e+02,4.987252131521967335e+00,4.000000039686763209e+00,4.267589099719382717e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.799812752786505143e+01,3.147441966228653314e+02,4.991391357304146403e+00,4.000000039686763209e+00,4.262589099719382713e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.800062752784024411e+01,3.147533018122294948e+02,4.995526031008667545e+00,4.000000039686763209e+00,4.257589099719382708e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.800312752781543679e+01,3.147624090677922482e+02,4.999656151601861609e+00,4.000000039686763209e+00,4.252589099719382704e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.800562752779062947e+01,3.147715183872768421e+02,5.003781718051198979e+00,4.000000039686763209e+00,4.247589099719382699e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.800812752776582215e+01,3.147806297684059018e+02,5.007902729325287794e+00,4.000000039686763209e+00,4.242589099719382695e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.801062752774101483e+01,3.147897432089015979e+02,5.012019184393875726e+00,4.000000039686763209e+00,4.237589099719382690e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.801312752771620751e+01,3.147988587064855324e+02,5.016131082227849092e+00,4.000000039686763209e+00,4.232589099719382686e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.801562752769140019e+01,3.148079762588788526e+02,5.020238421799232853e+00,4.000000039686763209e+00,4.227589099719382681e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.801812752766659287e+01,3.148170958638021943e+02,5.024341202081192392e+00,4.000000039686763209e+00,4.222589099719382677e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.802062752764178555e+01,3.148262175189756249e+02,5.028439422048032625e+00,4.000000039686763209e+00,4.217589099719382673e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.802312752761697823e+01,3.148353412221187568e+02,5.032533080675198889e+00,4.000000039686763209e+00,4.212589099719382668e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.802562752759217091e+01,3.148444669709506911e+02,5.036622176939276052e+00,4.000000039686763209e+00,4.207589099719382664e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.802812752756736359e+01,3.148535947631899035e+02,5.040706709817990294e+00,4.000000039686763209e+00,4.202589099719382659e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.803062752754255627e+01,3.148627245965545285e+02,5.044786678290209103e+00,4.000000039686763209e+00,4.197589099719382655e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.803312752751774894e+01,3.148718564687620756e+02,5.048862081335939500e+00,4.000000039686763209e+00,4.192589099719382650e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.803562752749294162e+01,3.148809903775295425e+02,5.052932917936330703e+00,4.000000039686763209e+00,4.187589099719382646e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.803812752746813430e+01,3.148901263205735290e+02,5.056999187073674129e+00,4.000000039686763209e+00,4.182589099719382641e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.804062752744332698e+01,3.148992642956100099e+02,5.061060887731402502e+00,4.000000039686763209e+00,4.177589099719382637e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.804312752741851966e+01,3.149084043003544480e+02,5.065118018894090746e+00,4.000000039686763209e+00,4.172589099719382633e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.804562752739371234e+01,3.149175463325219084e+02,5.069170579547455091e+00,4.000000039686763209e+00,4.167589099719382628e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.804812752736890502e+01,3.149266903898268311e+02,5.073218568678356633e+00,4.000000039686763209e+00,4.162589099719382624e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.805062752734409770e+01,3.149358364699832578e+02,5.077261985274796885e+00,4.000000039686763209e+00,4.157589099719382619e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.805312752731929038e+01,3.149449845707046052e+02,5.081300828325923113e+00,4.000000039686763209e+00,4.152589099719382615e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.805562752729448306e+01,3.149541346897038920e+02,5.085335096822023893e+00,4.000000039686763209e+00,4.147589099719382610e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.805812752726967574e+01,3.149632868246935686e+02,5.089364789754531770e+00,4.000000039686763209e+00,4.142589099719382606e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.806062752724486842e+01,3.149724409733856305e+02,5.093389906116024157e+00,4.000000039686763209e+00,4.137589099719382602e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.806312752722006110e+01,3.149815971334915048e+02,5.097410444900221549e+00,4.000000039686763209e+00,4.132589099719382597e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.806562752719525378e+01,3.149907553027221638e+02,5.101426405101989303e+00,4.000000039686763209e+00,4.127589099719382593e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.806812752717044646e+01,3.149999154787880684e+02,5.105437785717337640e+00,4.000000039686763209e+00,4.122589099719382588e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.807062752714563914e+01,3.150090776593992246e+02,5.109444585743420753e+00,4.000000039686763209e+00,4.117589099719382584e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.807312752712083181e+01,3.150182418422650130e+02,5.113446804178539473e+00,4.000000039686763209e+00,4.112589099719382579e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.807562752709602449e+01,3.150274080250944166e+02,5.117444440022138608e+00,4.000000039686763209e+00,4.107589099719382575e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.807812752707121717e+01,3.150365762055959067e+02,5.121437492274809600e+00,4.000000039686763209e+00,4.102589099719382570e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.808062752704640985e+01,3.150457463814773860e+02,5.125425959938289644e+00,4.000000039686763209e+00,4.097589099719382566e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.808312752702160253e+01,3.150549185504463594e+02,5.129409842015461685e+00,4.000000039686763209e+00,4.092589099719382562e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.808562752699679521e+01,3.150640927102097635e+02,5.133389137510355305e+00,4.000000039686763209e+00,4.087589099719382557e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.808812752697198789e+01,3.150732688584740799e+02,5.137363845428145837e+00,4.000000039686763209e+00,4.082589099719382553e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.809062752694718057e+01,3.150824469929452221e+02,5.141333964775157028e+00,4.000000039686763209e+00,4.077589099719382548e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.809312752692237325e+01,3.150916271113287053e+02,5.145299494558859266e+00,4.000000039686763209e+00,4.072589099719382544e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.809562752689756593e+01,3.151008092113294765e+02,5.149260433787869573e+00,4.000000039686763209e+00,4.067589099719382539e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.809812752687275861e+01,3.151099932906520280e+02,5.153216781471953389e+00,4.000000039686763209e+00,4.062589099719382535e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.810062752684795129e+01,3.151191793470003404e+02,5.157168536622023680e+00,4.000000039686763209e+00,4.057589099719382530e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.810312752682314397e+01,3.151283673780778827e+02,5.161115698250141826e+00,4.000000039686763209e+00,4.052589099719382526e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.810562752679833665e+01,3.151375573815876123e+02,5.165058265369517621e+00,4.000000039686763209e+00,4.047589099719382522e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.810812752677352933e+01,3.151467493552320889e+02,5.168996236994509275e+00,4.000000039686763209e+00,4.042589099719382517e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.811062752674872200e+01,3.151559432967133034e+02,5.172929612140623412e+00,4.000000039686763209e+00,4.037589099719382513e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.811312752672391468e+01,3.151651392037327355e+02,5.176858389824516848e+00,4.000000039686763209e+00,4.032589099719382508e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.811562752669910736e+01,3.151743370739914667e+02,5.180782569063994814e+00,4.000000039686763209e+00,4.027589099719382504e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.811812752667430004e+01,3.151835369051900102e+02,5.184702148878012729e+00,4.000000039686763209e+00,4.022589099719382499e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.812062752664949272e+01,3.151927386950283676e+02,5.188617128286675317e+00,4.000000039686763209e+00,4.017589099719382495e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.812312752662468540e+01,3.152019424412061426e+02,5.192527506311238383e+00,4.000000039686763209e+00,4.012589099719382491e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.812562752659987808e+01,3.152111481414223704e+02,5.196433281974107032e+00,4.000000039686763209e+00,4.007589099719382486e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.812812752657507076e+01,3.152203557933756315e+02,5.200334454298837450e+00,4.000000039686763209e+00,4.002589099719382482e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.813062752655026344e+01,3.152295653947640517e+02,5.204231022310136012e+00,4.000000039686763209e+00,3.997589099719382477e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.813312752652545612e+01,3.152387769432851883e+02,5.208122985033861951e+00,4.000000039686763209e+00,3.992589099719382473e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.813562752650064880e+01,3.152479904366361438e+02,5.212010341497023802e+00,4.000000039686763209e+00,3.987589099719382468e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.813812752647584148e+01,3.152572058725135662e+02,5.215893090727782067e+00,4.000000039686763209e+00,3.982589099719382464e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.814062752645103416e+01,3.152664232486135916e+02,5.219771231755450103e+00,4.000000039686763209e+00,3.977589099719382459e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.814312752642622684e+01,3.152756425626319015e+02,5.223644763610492348e+00,4.000000039686763209e+00,3.972589099719382455e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.814562752640141952e+01,3.152848638122636089e+02,5.227513685324526094e+00,4.000000039686763209e+00,3.967589099719382451e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.814812752637661220e+01,3.152940869952034859e+02,5.231377995930321489e+00,4.000000039686763209e+00,3.962589099719382446e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.815062752635180487e+01,3.153033121091456792e+02,5.235237694461799762e+00,4.000000039686763209e+00,3.957589099719382442e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.815312752632699755e+01,3.153125391517838807e+02,5.239092779954036772e+00,4.000000039686763209e+00,3.952589099719382437e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.815562752630219023e+01,3.153217681208113845e+02,5.242943251443261232e+00,4.000000039686763209e+00,3.947589099719382433e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.815812752627738291e+01,3.153309990139209162e+02,5.246789107966855603e+00,4.000000039686763209e+00,3.942589099719382428e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.816062752625257559e+01,3.153402318288048036e+02,5.250630348563355199e+00,4.000000039686763209e+00,3.937589099719382424e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.816312752622776827e+01,3.153494665631548060e+02,5.254466972272449965e+00,4.000000039686763209e+00,3.932589099719382419e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.816562752620296095e+01,3.153587032146622278e+02,5.258298978134984480e+00,4.000000039686763209e+00,3.927589099719382415e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.816812752617815363e+01,3.153679417810179189e+02,5.262126365192957067e+00,4.000000039686763209e+00,3.922589099719382411e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.817062752615334631e+01,3.153771822599122174e+02,5.265949132489520679e+00,4.000000039686763209e+00,3.917589099719382406e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.817312752612853899e+01,3.153864246490350638e+02,5.269767279068983790e+00,4.000000039686763209e+00,3.912589099719382402e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.817562752610373167e+01,3.153956689460758298e+02,5.273580803976809506e+00,4.000000039686763209e+00,3.907589099719382397e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.817812752607892435e+01,3.154049151487234326e+02,5.277389706259617341e+00,4.000000039686763209e+00,3.902589099719382393e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.818062752605411703e+01,3.154141632546662777e+02,5.281193984965181443e+00,4.000000039686763209e+00,3.897589099719382388e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.818312752602930971e+01,3.154234132615923727e+02,5.284993639142431476e+00,4.000000039686763209e+00,3.892589099719382384e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.818562752600450239e+01,3.154326651671892705e+02,5.288788667841454405e+00,4.000000039686763209e+00,3.887589099719382379e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.818812752597969506e+01,3.154419189691439556e+02,5.292579070113493600e+00,4.000000039686763209e+00,3.882589099719382375e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.819062752595488774e+01,3.154511746651429576e+02,5.296364845010947953e+00,4.000000039686763209e+00,3.877589099719382371e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.819312752593008042e+01,3.154604322528723515e+02,5.300145991587373651e+00,4.000000039686763209e+00,3.872589099719382366e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.819562752590527310e+01,3.154696917300177574e+02,5.303922508897484178e+00,4.000000039686763209e+00,3.867589099719382362e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.819812752588046578e+01,3.154789530942643410e+02,5.307694395997150316e+00,4.000000039686763209e+00,3.862589099719382357e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.820062752585565846e+01,3.154882163432966991e+02,5.311461651943400142e+00,4.000000039686763209e+00,3.857589099719382353e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.820312752583085114e+01,3.154974814747990308e+02,5.315224275794419917e+00,4.000000039686763209e+00,3.852589099719382348e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.820562752580604382e+01,3.155067484864550806e+02,5.318982266609553200e+00,4.000000039686763209e+00,3.847589099719382344e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.820812752578123650e+01,3.155160173759480813e+02,5.322735623449302622e+00,4.000000039686763209e+00,3.842589099719382340e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.821062752575642918e+01,3.155252881409608108e+02,5.326484345375328999e+00,4.000000039686763209e+00,3.837589099719382335e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.821312752573162186e+01,3.155345607791755924e+02,5.330228431450452220e+00,4.000000039686763209e+00,3.832589099719382331e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.821562752570681454e+01,3.155438352882742379e+02,5.333967880738650358e+00,4.000000039686763209e+00,3.827589099719382326e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.821812752568200722e+01,3.155531116659381610e+02,5.337702692305061447e+00,4.000000039686763209e+00,3.822589099719382322e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.822062752565719990e+01,3.155623899098482070e+02,5.341432865215981707e+00,4.000000039686763209e+00,3.817589099719382317e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.822312752563239258e+01,3.155716700176848803e+02,5.345158398538869093e+00,4.000000039686763209e+00,3.812589099719382313e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.822562752560758526e+01,3.155809519871281168e+02,5.348879291342339748e+00,4.000000039686763209e+00,3.807589099719382308e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.822812752558277793e+01,3.155902358158574543e+02,5.352595542696170661e+00,4.000000039686763209e+00,3.802589099719382304e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.823062752555797061e+01,3.155995215015518625e+02,5.356307151671298783e+00,4.000000039686763209e+00,3.797589099719382300e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.823312752553316329e+01,3.156088090418899696e+02,5.360014117339821915e+00,4.000000039686763209e+00,3.792589099719382295e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.823562752550835597e+01,3.156180984345498928e+02,5.363716438774998707e+00,4.000000039686763209e+00,3.787589099719382291e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.823812752548354865e+01,3.156273896772092939e+02,5.367414115051249546e+00,4.000000039686763209e+00,3.782589099719382286e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.824062752545874133e+01,3.156366827675453806e+02,5.371107145244154779e+00,4.000000039686763209e+00,3.777589099719382282e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.824312752543393401e+01,3.156459777032348484e+02,5.374795528430456493e+00,4.000000039686763209e+00,3.772589099719382277e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.824562752540912669e+01,3.156552744819539384e+02,5.378479263688059397e+00,4.000000039686763209e+00,3.767589099719382273e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.824812752538431937e+01,3.156645731013784939e+02,5.382158350096029054e+00,4.000000039686763209e+00,3.762589099719382268e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.825062752535951205e+01,3.156738735591838463e+02,5.385832786734594535e+00,4.000000039686763209e+00,3.757589099719382264e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.825312752533470473e+01,3.156831758530448724e+02,5.389502572685146653e+00,4.000000039686763209e+00,3.752589099719382260e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.825562752530989741e+01,3.156924799806360511e+02,5.393167707030238844e+00,4.000000039686763209e+00,3.747589099719382255e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.825812752528509009e+01,3.157017859396312929e+02,5.396828188853587172e+00,4.000000039686763209e+00,3.742589099719382251e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.826062752526028277e+01,3.157110937277041103e+02,5.400484017240072099e+00,4.000000039686763209e+00,3.737589099719382246e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.826312752523547545e+01,3.157204033425275611e+02,5.404135191275735828e+00,4.000000039686763209e+00,3.732589099719382242e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.826562752521066813e+01,3.157297147817742484e+02,5.407781710047784962e+00,4.000000039686763209e+00,3.727589099719382237e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.826812752518586080e+01,3.157390280431163205e+02,5.411423572644589619e+00,4.000000039686763209e+00,3.722589099719382233e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.827062752516105348e+01,3.157483431242254710e+02,5.415060778155684318e+00,4.000000039686763209e+00,3.717589099719382228e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.827312752513624616e+01,3.157576600227729386e+02,5.418693325671767980e+00,4.000000039686763209e+00,3.712589099719382224e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.827562752511143884e+01,3.157669787364294507e+02,5.422321214284703927e+00,4.000000039686763209e+00,3.707589099719382220e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.827812752508663152e+01,3.157762992628653365e+02,5.425944443087519886e+00,4.000000039686763209e+00,3.702589099719382215e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.828062752506182420e+01,3.157856215997505274e+02,5.429563011174407983e+00,4.000000039686763209e+00,3.697589099719382211e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.828312752503701688e+01,3.157949457447543864e+02,5.433176917640726522e+00,4.000000039686763209e+00,3.692589099719382206e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.828562752501220956e+01,3.158042716955458786e+02,5.436786161582999100e+00,4.000000039686763209e+00,3.687589099719382202e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.828812752498740224e+01,3.158135994497935144e+02,5.440390742098914600e+00,4.000000039686763209e+00,3.682589099719382197e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.829062752496259492e+01,3.158229290051653493e+02,5.443990658287328088e+00,4.000000039686763209e+00,3.677589099719382193e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.829312752493778760e+01,3.158322603593290410e+02,5.447585909248260805e+00,4.000000039686763209e+00,3.672589099719382189e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.829562752491298028e+01,3.158415935099516787e+02,5.451176494082900170e+00,4.000000039686763209e+00,3.667589099719382184e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.829812752488817296e+01,3.158509284547000107e+02,5.454762411893598895e+00,4.000000039686763209e+00,3.662589099719382180e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.830062752486336564e+01,3.158602651912403303e+02,5.458343661783878531e+00,4.000000039686763209e+00,3.657589099719382175e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.830312752483855832e+01,3.158696037172384194e+02,5.461920242858425922e+00,4.000000039686763209e+00,3.652589099719382171e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.830562752481375099e+01,3.158789440303596621e+02,5.465492154223096755e+00,4.000000039686763209e+00,3.647589099719382166e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.830812752478894367e+01,3.158882861282689873e+02,5.469059394984912004e+00,4.000000039686763209e+00,3.642589099719382162e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.831062752476413635e+01,3.158976300086308697e+02,5.472621964252062376e+00,4.000000039686763209e+00,3.637589099719382157e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.831312752473932903e+01,3.159069756691093289e+02,5.476179861133905646e+00,4.000000039686763209e+00,3.632589099719382153e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.831562752471452171e+01,3.159163231073679299e+02,5.479733084740967541e+00,4.000000039686763209e+00,3.627589099719382149e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.831812752468971439e+01,3.159256723210698397e+02,5.483281634184941744e+00,4.000000039686763209e+00,3.622589099719382144e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.832062752466490707e+01,3.159350233078777137e+02,5.486825508578690780e+00,4.000000039686763209e+00,3.617589099719382140e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.832312752464009975e+01,3.159443760654538664e+02,5.490364707036246905e+00,4.000000039686763209e+00,3.612589099719382135e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.832562752461529243e+01,3.159537305914600438e+02,5.493899228672809443e+00,4.000000039686763209e+00,3.607589099719382131e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.832812752459048511e+01,3.159630868835576507e+02,5.497429072604749223e+00,4.000000039686763209e+00,3.602589099719382126e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.833062752456567779e+01,3.159724449394076373e+02,5.500954237949604142e+00,4.000000039686763209e+00,3.597589099719382122e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.833312752454087047e+01,3.159818047566704422e+02,5.504474723826083604e+00,4.000000039686763209e+00,3.592589099719382117e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.833562752451606315e+01,3.159911663330061629e+02,5.507990529354065856e+00,4.000000039686763209e+00,3.587589099719382113e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.833812752449125583e+01,3.160005296660743852e+02,5.511501653654599764e+00,4.000000039686763209e+00,3.582589099719382109e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.834062752446644851e+01,3.160098947535342404e+02,5.515008095849903924e+00,4.000000039686763209e+00,3.577589099719382104e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.834312752444164119e+01,3.160192615930445186e+02,5.518509855063367553e+00,4.000000039686763209e+00,3.572589099719382100e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.834562752441683386e+01,3.160286301822634414e+02,5.522006930419551374e+00,4.000000039686763209e+00,3.567589099719382095e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.834812752439202654e+01,3.160380005188488894e+02,5.525499321044186729e+00,4.000000039686763209e+00,3.562589099719382091e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.835062752436721922e+01,3.160473726004582886e+02,5.528987026064175581e+00,4.000000039686763209e+00,3.557589099719382086e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.835312752434241190e+01,3.160567464247486100e+02,5.532470044607592286e+00,4.000000039686763209e+00,3.552589099719382082e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.835562752431760458e+01,3.160661219893764269e+02,5.535948375803681820e+00,4.000000039686763209e+00,3.547589099719382078e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.835812752429279726e+01,3.160754992919978008e+02,5.539422018782861556e+00,4.000000039686763209e+00,3.542589099719382073e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.836062752426798994e+01,3.160848783302684524e+02,5.542890972676720374e+00,4.000000039686763209e+00,3.537589099719382069e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.836312752424318262e+01,3.160942591018435905e+02,5.546355236618019546e+00,4.000000039686763209e+00,3.532589099719382064e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.836562752421837530e+01,3.161036416043780264e+02,5.549814809740693633e+00,4.000000039686763209e+00,3.527589099719382060e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.836812752419356798e+01,3.161130258355261731e+02,5.553269691179849588e+00,4.000000039686763209e+00,3.522589099719382055e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.837062752416876066e+01,3.161224117929419322e+02,5.556719880071766759e+00,4.000000039686763209e+00,3.517589099719382051e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.837312752414395334e+01,3.161317994742788073e+02,5.560165375553897782e+00,4.000000039686763209e+00,3.512589099719382046e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.837562752411914602e+01,3.161411888771899044e+02,5.563606176764869460e+00,4.000000039686763209e+00,3.507589099719382042e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.837812752409433870e+01,3.161505799993278174e+02,5.567042282844480994e+00,4.000000039686763209e+00,3.502589099719382038e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.838062752406953138e+01,3.161599728383448564e+02,5.570473692933705756e+00,4.000000039686763209e+00,3.497589099719382033e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.838312752404472405e+01,3.161693673918927630e+02,5.573900406174691291e+00,4.000000039686763209e+00,3.492589099719382029e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.838562752401991673e+01,3.161787636576228806e+02,5.577322421710759315e+00,4.000000039686763209e+00,3.487589099719382024e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.838812752399510941e+01,3.161881616331861551e+02,5.580739738686406604e+00,4.000000039686763209e+00,3.482589099719382020e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.839062752397030209e+01,3.161975613162330774e+02,5.584152356247303217e+00,4.000000039686763209e+00,3.477589099719382015e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.839312752394549477e+01,3.162069627044137974e+02,5.587560273540295164e+00,4.000000039686763209e+00,3.472589099719382011e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.839562752392068745e+01,3.162163657953778966e+02,5.590963489713402623e+00,4.000000039686763209e+00,3.467589099719382006e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.839812752389588013e+01,3.162257705867746154e+02,5.594362003915822612e+00,4.000000039686763209e+00,3.462589099719382002e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.840062752387107281e+01,3.162351770762527963e+02,5.597755815297925430e+00,4.000000039686763209e+00,3.457589099719381998e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.840312752384626549e+01,3.162445852614607702e+02,5.601144923011259102e+00,4.000000039686763209e+00,3.452589099719381993e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.840562752382145817e+01,3.162539951400465270e+02,5.604529326208545825e+00,4.000000039686763209e+00,3.447589099719381989e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.840812752379665085e+01,3.162634067096575450e+02,5.607909024043685520e+00,4.000000039686763209e+00,3.442589099719381984e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.841062752377184353e+01,3.162728199679409613e+02,5.611284015671753167e+00,4.000000039686763209e+00,3.437589099719381980e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.841312752374703621e+01,3.162822349125434584e+02,5.614654300249001473e+00,4.000000039686763209e+00,3.432589099719381975e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.841562752372222889e+01,3.162916515411113210e+02,5.618019876932859091e+00,4.000000039686763209e+00,3.427589099719381971e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.841812752369742157e+01,3.163010698512903787e+02,5.621380744881932401e+00,4.000000039686763209e+00,3.422589099719381966e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.842062752367261425e+01,3.163104898407260634e+02,5.624736903256003728e+00,4.000000039686763209e+00,3.417589099719381962e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.842312752364780692e+01,3.163199115070633525e+02,5.628088351216034013e+00,4.000000039686763209e+00,3.412589099719381958e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.842562752362299960e+01,3.163293348479468250e+02,5.631435087924160143e+00,4.000000039686763209e+00,3.407589099719381953e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.842812752359819228e+01,3.163387598610206624e+02,5.634777112543699396e+00,4.000000039686763209e+00,3.402589099719381949e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.843062752357338496e+01,3.163481865439286480e+02,5.638114424239144995e+00,4.000000039686763209e+00,3.397589099719381944e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.843312752354857764e+01,3.163576148943140538e+02,5.641447022176168780e+00,4.000000039686763209e+00,3.392589099719381940e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.843562752352377032e+01,3.163670449098198105e+02,5.644774905521621200e+00,4.000000039686763209e+00,3.387589099719381935e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.843812752349896300e+01,3.163764765880884511e+02,5.648098073443532208e+00,4.000000039686763209e+00,3.382589099719381931e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.844062752347415568e+01,3.163859099267619968e+02,5.651416525111109479e+00,4.000000039686763209e+00,3.377589099719381927e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.844312752344934836e+01,3.163953449234821278e+02,5.654730259694740191e+00,4.000000039686763209e+00,3.372589099719381922e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.844562752342454104e+01,3.164047815758901265e+02,5.658039276365990133e+00,4.000000039686763209e+00,3.367589099719381918e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.844812752339973372e+01,3.164142198816268206e+02,5.661343574297605485e+00,4.000000039686763209e+00,3.362589099719381913e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.845062752337492640e+01,3.164236598383326395e+02,5.664643152663511927e+00,4.000000039686763209e+00,3.357589099719381909e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.845312752335011908e+01,3.164331014436475584e+02,5.667938010638815527e+00,4.000000039686763209e+00,3.352589099719381904e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.845562752332531176e+01,3.164425446952112111e+02,5.671228147399800967e+00,4.000000039686763209e+00,3.347589099719381900e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.845812752330050444e+01,3.164519895906627198e+02,5.674513562123934207e+00,4.000000039686763209e+00,3.342589099719381895e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.846062752327569711e+01,3.164614361276409227e+02,5.677794253989861595e+00,4.000000039686763209e+00,3.337589099719381891e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.846312752325088979e+01,3.164708843037842030e+02,5.681070222177409867e+00,4.000000039686763209e+00,3.332589099719381887e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.846562752322608247e+01,3.164803341167304893e+02,5.684341465867587040e+00,4.000000039686763209e+00,3.327589099719381882e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.846812752320127515e+01,3.164897855641173123e+02,5.687607984242583292e+00,4.000000039686763209e+00,3.322589099719381878e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.847062752317646783e+01,3.164992386435818048e+02,5.690869776485768305e+00,4.000000039686763209e+00,3.317589099719381873e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.847312752315166051e+01,3.165086933527607584e+02,5.694126841781693926e+00,4.000000039686763209e+00,3.312589099719381869e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.847562752312685319e+01,3.165181496892904534e+02,5.697379179316093278e+00,4.000000039686763209e+00,3.307589099719381864e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.847812752310204587e+01,3.165276076508067717e+02,5.700626788275882539e+00,4.000000039686763209e+00,3.302589099719381860e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.848062752307723855e+01,3.165370672349452548e+02,5.703869667849160052e+00,4.000000039686763209e+00,3.297589099719381855e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.848312752305243123e+01,3.165465284393410457e+02,5.707107817225205437e+00,4.000000039686763209e+00,3.292589099719381851e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.848562752302762391e+01,3.165559912616287761e+02,5.710341235594481368e+00,4.000000039686763209e+00,3.287589099719381847e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.848812752300281659e+01,3.165654556994427935e+02,5.713569922148633573e+00,4.000000039686763209e+00,3.282589099719381842e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.849062752297800927e+01,3.165749217504169337e+02,5.716793876080489945e+00,4.000000039686763209e+00,3.277589099719381838e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.849312752295320195e+01,3.165843894121847484e+02,5.720013096584062318e+00,4.000000039686763209e+00,3.272589099719381833e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.849562752292839463e+01,3.165938586823792775e+02,5.723227582854545581e+00,4.000000039686763209e+00,3.267589099719381829e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.849812752290358731e+01,3.166033295586332201e+02,5.726437334088317677e+00,4.000000039686763209e+00,3.262589099719381824e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.850062752287877998e+01,3.166128020385788204e+02,5.729642349482941377e+00,4.000000039686763209e+00,3.257589099719381820e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.850312752285397266e+01,3.166222761198480384e+02,5.732842628237162508e+00,4.000000039686763209e+00,3.252589099719381815e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.850562752282916534e+01,3.166317518000722657e+02,5.736038169550911725e+00,4.000000039686763209e+00,3.247589099719381811e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.850812752280435802e+01,3.166412290768826665e+02,5.739228972625303626e+00,4.000000039686763209e+00,3.242589099719381807e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.851062752277955070e+01,3.166507079479098365e+02,5.742415036662637640e+00,4.000000039686763209e+00,3.237589099719381802e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.851312752275474338e+01,3.166601884107840874e+02,5.745596360866397134e+00,4.000000039686763209e+00,3.232589099719381798e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.851562752272993606e+01,3.166696704631353327e+02,5.748772944441251198e+00,4.000000039686763209e+00,3.227589099719381793e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.851812752270512874e+01,3.166791541025930314e+02,5.751944786593054637e+00,4.000000039686763209e+00,3.222589099719381789e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.852062752268032142e+01,3.166886393267863014e+02,5.755111886528846199e+00,4.000000039686763209e+00,3.217589099719381784e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.852312752265551410e+01,3.166981261333438056e+02,5.758274243456851238e+00,4.000000039686763209e+00,3.212589099719381780e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.852562752263070678e+01,3.167076145198938661e+02,5.761431856586480826e+00,4.000000039686763209e+00,3.207589099719381776e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.852812752260589946e+01,3.167171044840644072e+02,5.764584725128331755e+00,4.000000039686763209e+00,3.202589099719381771e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.853062752258109214e+01,3.167265960234828981e+02,5.767732848294186532e+00,4.000000039686763209e+00,3.197589099719381767e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.853312752255628482e+01,3.167360891357764672e+02,5.770876225297014273e+00,4.000000039686763209e+00,3.192589099719381762e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.853562752253147750e+01,3.167455838185718449e+02,5.774014855350970699e+00,4.000000039686763209e+00,3.187589099719381758e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.853812752250667018e+01,3.167550800694953068e+02,5.777148737671398138e+00,4.000000039686763209e+00,3.182589099719381753e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.854062752248186285e+01,3.167645778861728445e+02,5.780277871474826412e+00,4.000000039686763209e+00,3.177589099719381749e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.854312752245705553e+01,3.167740772662299946e+02,5.783402255978972839e+00,4.000000039686763209e+00,3.172589099719381744e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.854562752243224821e+01,3.167835782072918960e+02,5.786521890402740453e+00,4.000000039686763209e+00,3.167589099719381740e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.854812752240744089e+01,3.167930807069833463e+02,5.789636773966220673e+00,4.000000039686763209e+00,3.162589099719381736e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.855062752238263357e+01,3.168025847629286886e+02,5.792746905890692410e+00,4.000000039686763209e+00,3.157589099719381731e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.855312752235782625e+01,3.168120903727519249e+02,5.795852285398622961e+00,4.000000039686763209e+00,3.152589099719381727e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.855562752233301893e+01,3.168215975340766590e+02,5.798952911713667113e+00,4.000000039686763209e+00,3.147589099719381722e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.855812752230821161e+01,3.168311062445260973e+02,5.802048784060668929e+00,4.000000039686763209e+00,3.142589099719381718e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.856062752228340429e+01,3.168406165017230478e+02,5.805139901665659963e+00,4.000000039686763209e+00,3.137589099719381713e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.856312752225859697e+01,3.168501283032899778e+02,5.808226263755861041e+00,4.000000039686763209e+00,3.132589099719381709e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.856562752223378965e+01,3.168596416468488997e+02,5.811307869559682260e+00,4.000000039686763209e+00,3.127589099719381704e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.856812752220898233e+01,3.168691565300214847e+02,5.814384718306721211e+00,4.000000039686763209e+00,3.122589099719381700e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.857062752218417501e+01,3.168786729504290065e+02,5.817456809227765646e+00,4.000000039686763209e+00,3.117589099719381696e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.857312752215936769e+01,3.168881909056923973e+02,5.820524141554793474e+00,4.000000039686763209e+00,3.112589099719381691e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.857562752213456037e+01,3.168977103934321349e+02,5.823586714520970986e+00,4.000000039686763209e+00,3.107589099719381687e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.857812752210975304e+01,3.169072314112683557e+02,5.826644527360655523e+00,4.000000039686763209e+00,3.102589099719381682e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.858062752208494572e+01,3.169167539568207985e+02,5.829697579309393696e+00,4.000000039686763209e+00,3.097589099719381678e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.858312752206013840e+01,3.169262780277088041e+02,5.832745869603923161e+00,4.000000039686763209e+00,3.092589099719381673e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.858562752203533108e+01,3.169358036215514289e+02,5.835789397482169960e+00,4.000000039686763209e+00,3.087589099719381669e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.858812752201052376e+01,3.169453307359672181e+02,5.838828162183252957e+00,4.000000039686763209e+00,3.082589099719381664e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.859062752198571644e+01,3.169548593685743754e+02,5.841862162947481174e+00,4.000000039686763209e+00,3.077589099719381660e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.859312752196090912e+01,3.169643895169908205e+02,5.844891399016354683e+00,4.000000039686763209e+00,3.072589099719381656e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.859562752193610180e+01,3.169739211788339617e+02,5.847915869632563712e+00,4.000000039686763209e+00,3.067589099719381651e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.859812752191129448e+01,3.169834543517208658e+02,5.850935574039991316e+00,4.000000039686763209e+00,3.062589099719381647e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.860062752188648716e+01,3.169929890332682589e+02,5.853950511483710706e+00,4.000000039686763209e+00,3.057589099719381642e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.860312752186167984e+01,3.170025252210924691e+02,5.856960681209987918e+00,4.000000039686763209e+00,3.052589099719381638e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.860562752183687252e+01,3.170120629128094834e+02,5.859966082466280035e+00,4.000000039686763209e+00,3.047589099719381633e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.860812752181206520e+01,3.170216021060348339e+02,5.862966714501237853e+00,4.000000039686763209e+00,3.042589099719381629e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.861062752178725788e+01,3.170311427983837689e+02,5.865962576564702324e+00,4.000000039686763209e+00,3.037589099719381625e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.861312752176245056e+01,3.170406849874710815e+02,5.868953667907708116e+00,4.000000039686763209e+00,3.032589099719381620e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.861562752173764324e+01,3.170502286709112241e+02,5.871939987782482717e+00,4.000000039686763209e+00,3.027589099719381616e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.861812752171283591e+01,3.170597738463182509e+02,5.874921535442446441e+00,4.000000039686763209e+00,3.022589099719381611e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.862062752168802859e+01,3.170693205113059321e+02,5.877898310142211535e+00,4.000000039686763209e+00,3.017589099719381607e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.862312752166322127e+01,3.170788686634875830e+02,5.880870311137584849e+00,4.000000039686763209e+00,3.012589099719381602e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.862562752163841395e+01,3.170884183004761212e+02,5.883837537685566943e+00,4.000000039686763209e+00,3.007589099719381598e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.862812752161360663e+01,3.170979694198841798e+02,5.886799989044350312e+00,4.000000039686763209e+00,3.002589099719381593e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.863062752158879931e+01,3.171075220193239375e+02,5.889757664473322052e+00,4.000000039686763209e+00,2.997589099719381589e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.863312752156399199e+01,3.171170760964072883e+02,5.892710563233062970e+00,4.000000039686763209e+00,2.992589099719381585e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.863562752153918467e+01,3.171266316487457289e+02,5.895658684585349363e+00,4.000000039686763209e+00,2.987589099719381580e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.863812752151437735e+01,3.171361886739503007e+02,5.898602027793150349e+00,4.000000039686763209e+00,2.982589099719381576e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.864062752148957003e+01,3.171457471696318180e+02,5.901540592120630535e+00,4.000000039686763209e+00,2.977589099719381571e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.864312752146476271e+01,3.171553071334005836e+02,5.904474376833148241e+00,4.000000039686763209e+00,2.972589099719381567e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.864562752143995539e+01,3.171648685628666726e+02,5.907403381197258163e+00,4.000000039686763209e+00,2.967589099719381562e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.864812752141514807e+01,3.171744314556397057e+02,5.910327604480708708e+00,4.000000039686763209e+00,2.962589099719381558e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.865062752139034075e+01,3.171839958093289624e+02,5.913247045952443770e+00,4.000000039686763209e+00,2.957589099719381553e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.865312752136553343e+01,3.171935616215433242e+02,5.916161704882602734e+00,4.000000039686763209e+00,2.952589099719381549e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.865562752134072610e+01,3.172031288898913886e+02,5.919071580542522248e+00,4.000000039686763209e+00,2.947589099719381545e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.865812752131591878e+01,3.172126976119812980e+02,5.921976672204731784e+00,4.000000039686763209e+00,2.942589099719381540e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.866062752129111146e+01,3.172222677854209110e+02,5.924876979142959854e+00,4.000000039686763209e+00,2.937589099719381536e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.866312752126630414e+01,3.172318394078176311e+02,5.927772500632128683e+00,4.000000039686763209e+00,2.932589099719381531e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.866562752124149682e+01,3.172414124767785779e+02,5.930663235948358647e+00,4.000000039686763209e+00,2.927589099719381527e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.866812752121668950e+01,3.172509869899105297e+02,5.933549184368965612e+00,4.000000039686763209e+00,2.922589099719381522e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.867062752119188218e+01,3.172605629448198101e+02,5.936430345172462708e+00,4.000000039686763209e+00,2.917589099719381518e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.867312752116707486e+01,3.172701403391124018e+02,5.939306717638559441e+00,4.000000039686763209e+00,2.912589099719381514e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.867562752114226754e+01,3.172797191703940030e+02,5.942178301048162581e+00,4.000000039686763209e+00,2.907589099719381509e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.867812752111746022e+01,3.172892994362699142e+02,5.945045094683377052e+00,4.000000039686763209e+00,2.902589099719381505e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.868062752109265290e+01,3.172988811343450379e+02,5.947907097827504153e+00,4.000000039686763209e+00,2.897589099719381500e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.868312752106784558e+01,3.173084642622239926e+02,5.950764309765042448e+00,4.000000039686763209e+00,2.892589099719381496e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.868562752104303826e+01,3.173180488175109417e+02,5.953616729781689543e+00,4.000000039686763209e+00,2.887589099719381491e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.868812752101823094e+01,3.173276347978097647e+02,5.956464357164340306e+00,4.000000039686763209e+00,2.882589099719381487e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.869062752099342362e+01,3.173372222007239998e+02,5.959307191201087761e+00,4.000000039686763209e+00,2.877589099719381482e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.869312752096861630e+01,3.173468110238567306e+02,5.962145231181223970e+00,4.000000039686763209e+00,2.872589099719381478e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.869562752094380897e+01,3.173564012648108132e+02,5.964978476395238260e+00,4.000000039686763209e+00,2.867589099719381474e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.869812752091900165e+01,3.173659929211886492e+02,5.967806926134819889e+00,4.000000039686763209e+00,2.862589099719381469e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.870062752089419433e+01,3.173755859905923558e+02,5.970630579692856266e+00,4.000000039686763209e+00,2.857589099719381465e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.870312752086938701e+01,3.173851804706236521e+02,5.973449436363433840e+00,4.000000039686763209e+00,2.852589099719381460e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.870562752084457969e+01,3.173947763588839166e+02,5.976263495441838991e+00,4.000000039686763209e+00,2.847589099719381456e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.870812752081977237e+01,3.174043736529741864e+02,5.979072756224556251e+00,4.000000039686763209e+00,2.842589099719381451e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.871062752079496505e+01,3.174139723504951007e+02,5.981877218009270969e+00,4.000000039686763209e+00,2.837589099719381447e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.871312752077015773e+01,3.174235724490470147e+02,5.984676880094867535e+00,4.000000039686763209e+00,2.832589099719381442e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.871562752074535041e+01,3.174331739462298856e+02,5.987471741781430268e+00,4.000000039686763209e+00,2.827589099719381438e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.871812752072054309e+01,3.174427768396433862e+02,5.990261802370243416e+00,4.000000039686763209e+00,2.822589099719381434e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.872062752069573577e+01,3.174523811268867348e+02,5.993047061163792932e+00,4.000000039686763209e+00,2.817589099719381429e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.872312752067092845e+01,3.174619868055589222e+02,5.995827517465762924e+00,4.000000039686763209e+00,2.812589099719381425e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.872562752064612113e+01,3.174715938732584846e+02,5.998603170581040089e+00,4.000000039686763209e+00,2.807589099719381420e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.872812752062131381e+01,3.174812023275836737e+02,6.001374019815711058e+00,4.000000039686763209e+00,2.802589099719381416e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.873062752059650649e+01,3.174908121661323435e+02,6.004140064477063277e+00,4.000000039686763209e+00,2.797589099719381411e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.873312752057169916e+01,3.175004233865020637e+02,6.006901303873585896e+00,4.000000039686763209e+00,2.792589099719381407e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.873562752054689184e+01,3.175100359862900063e+02,6.009657737314968884e+00,4.000000039686763209e+00,2.787589099719381402e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.873812752052208452e+01,3.175196499630930589e+02,6.012409364112103916e+00,4.000000039686763209e+00,2.782589099719381398e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.874062752049727720e+01,3.175292653145077111e+02,6.015156183577084370e+00,4.000000039686763209e+00,2.777589099719381394e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.874312752047246988e+01,3.175388820381301116e+02,6.017898195023205332e+00,4.000000039686763209e+00,2.772589099719381389e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.874562752044766256e+01,3.175485001315560680e+02,6.020635397764964480e+00,4.000000039686763209e+00,2.767589099719381385e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.874812752042285524e+01,3.175581195923811038e+02,6.023367791118060310e+00,4.000000039686763209e+00,2.762589099719381380e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.875062752039804792e+01,3.175677404182002874e+02,6.026095374399394800e+00,4.000000039686763209e+00,2.757589099719381376e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.875312752037324060e+01,3.175773626066084603e+02,6.028818146927072519e+00,4.000000039686763209e+00,2.752589099719381371e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.875562752034843328e+01,3.175869861552000657e+02,6.031536108020399745e+00,4.000000039686763209e+00,2.747589099719381367e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.875812752032362596e+01,3.175966110615692060e+02,6.034249256999887123e+00,4.000000039686763209e+00,2.742589099719381363e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.876062752029881864e+01,3.176062373233096991e+02,6.036957593187246118e+00,4.000000039686763209e+00,2.737589099719381358e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.876312752027401132e+01,3.176158649380149086e+02,6.039661115905393451e+00,4.000000039686763209e+00,2.732589099719381354e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.876562752024920400e+01,3.176254939032779703e+02,6.042359824478448438e+00,4.000000039686763209e+00,2.727589099719381349e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.876812752022439668e+01,3.176351242166916791e+02,6.045053718231733875e+00,4.000000039686763209e+00,2.722589099719381345e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.877062752019958936e+01,3.176447558758484320e+02,6.047742796491776929e+00,4.000000039686763209e+00,2.717589099719381340e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.877312752017478203e+01,3.176543888783402849e+02,6.050427058586307361e+00,4.000000039686763209e+00,2.712589099719381336e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.877562752014997471e+01,3.176640232217590096e+02,6.053106503844260189e+00,4.000000039686763209e+00,2.707589099719381331e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.877812752012516739e+01,3.176736589036959799e+02,6.055781131595773026e+00,4.000000039686763209e+00,2.702589099719381327e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.878062752010036007e+01,3.176832959217423422e+02,6.058450941172189630e+00,4.000000039686763209e+00,2.697589099719381323e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.878312752007555275e+01,3.176929342734887882e+02,6.061115931906058130e+00,4.000000039686763209e+00,2.692589099719381318e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.878562752005074543e+01,3.177025739565257823e+02,6.063776103131130135e+00,4.000000039686763209e+00,2.687589099719381314e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.878812752002593811e+01,3.177122149684433339e+02,6.066431454182363403e+00,4.000000039686763209e+00,2.682589099719381309e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.879062752000113079e+01,3.177218573068312253e+02,6.069081984395919172e+00,4.000000039686763209e+00,2.677589099719381305e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.879312751997632347e+01,3.177315009692788976e+02,6.071727693109165713e+00,4.000000039686763209e+00,2.672589099719381300e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.879562751995151615e+01,3.177411459533753941e+02,6.074368579660675671e+00,4.000000039686763209e+00,2.667589099719381296e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.879812751992670883e+01,3.177507922567095306e+02,6.077004643390227834e+00,4.000000039686763209e+00,2.662589099719381291e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.880062751990190151e+01,3.177604398768696683e+02,6.079635883638806249e+00,4.000000039686763209e+00,2.657589099719381287e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.880312751987709419e+01,3.177700888114439408e+02,6.082262299748600221e+00,4.000000039686763209e+00,2.652589099719381283e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.880562751985228687e+01,3.177797390580200840e+02,6.084883891063006089e+00,4.000000039686763209e+00,2.647589099719381278e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.880812751982747955e+01,3.177893906141855496e+02,6.087500656926626341e+00,4.000000039686763209e+00,2.642589099719381274e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.881062751980267223e+01,3.177990434775274480e+02,6.090112596685268720e+00,4.000000039686763209e+00,2.637589099719381269e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.881312751977786490e+01,3.178086976456325488e+02,6.092719709685948892e+00,4.000000039686763209e+00,2.632589099719381265e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.881562751975305758e+01,3.178183531160873372e+02,6.095321995276888671e+00,4.000000039686763209e+00,2.627589099719381260e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.881812751972825026e+01,3.178280098864779006e+02,6.097919452807516905e+00,4.000000039686763209e+00,2.622589099719381256e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.882062751970344294e+01,3.178376679543900991e+02,6.100512081628468586e+00,4.000000039686763209e+00,2.617589099719381251e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.882312751967863562e+01,3.178473273174093947e+02,6.103099881091586631e+00,4.000000039686763209e+00,2.612589099719381247e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.882562751965382830e+01,3.178569879731209653e+02,6.105682850549920992e+00,4.000000039686763209e+00,2.607589099719381243e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.882812751962902098e+01,3.178666499191096477e+02,6.108260989357730431e+00,4.000000039686763209e+00,2.602589099719381238e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.883062751960421366e+01,3.178763131529598809e+02,6.110834296870478966e+00,4.000000039686763209e+00,2.597589099719381234e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.883312751957940634e+01,3.178859776722559332e+02,6.113402772444840316e+00,4.000000039686763209e+00,2.592589099719381229e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.883562751955459902e+01,3.178956434745816750e+02,6.115966415438695236e+00,4.000000039686763209e+00,2.587589099719381225e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.883812751952979170e+01,3.179053105575206359e+02,6.118525225211133289e+00,4.000000039686763209e+00,2.582589099719381220e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.884062751950498438e+01,3.179149789186560042e+02,6.121079201122451963e+00,4.000000039686763209e+00,2.577589099719381216e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.884312751948017706e+01,3.179246485555707409e+02,6.123628342534157554e+00,4.000000039686763209e+00,2.572589099719381212e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.884562751945536974e+01,3.179343194658474658e+02,6.126172648808965171e+00,4.000000039686763209e+00,2.567589099719381207e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.884812751943056242e+01,3.179439916470684011e+02,6.128712119310796957e+00,4.000000039686763209e+00,2.562589099719381203e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.885062751940575509e+01,3.179536650968154845e+02,6.131246753404786531e+00,4.000000039686763209e+00,2.557589099719381198e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.885312751938094777e+01,3.179633398126703696e+02,6.133776550457274546e+00,4.000000039686763209e+00,2.552589099719381194e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.885562751935614045e+01,3.179730157922144258e+02,6.136301509835812240e+00,4.000000039686763209e+00,2.547589099719381189e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.885812751933133313e+01,3.179826930330286245e+02,6.138821630909159666e+00,4.000000039686763209e+00,2.542589099719381185e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.886062751930652581e+01,3.179923715326936531e+02,6.141336913047286572e+00,4.000000039686763209e+00,2.537589099719381180e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.886312751928171849e+01,3.180020512887898576e+02,6.143847355621372408e+00,4.000000039686763209e+00,2.532589099719381176e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.886562751925691117e+01,3.180117322988973569e+02,6.146352958003806322e+00,4.000000039686763209e+00,2.527589099719381172e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.886812751923210385e+01,3.180214145605958720e+02,6.148853719568188048e+00,4.000000039686763209e+00,2.522589099719381167e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.887062751920729653e+01,3.180310980714648394e+02,6.151349639689327020e+00,4.000000039686763209e+00,2.517589099719381163e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.887312751918248921e+01,3.180407828290833550e+02,6.153840717743243260e+00,4.000000039686763209e+00,2.512589099719381158e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.887562751915768189e+01,3.180504688310302299e+02,6.156326953107166489e+00,4.000000039686763209e+00,2.507589099719381154e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.887812751913287457e+01,3.180601560748839916e+02,6.158808345159538788e+00,4.000000039686763209e+00,2.502589099719381149e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.888062751910806725e+01,3.180698445582228260e+02,6.161284893280011943e+00,4.000000039686763209e+00,2.497589099719381145e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.888312751908325993e+01,3.180795342786246351e+02,6.163756596849449210e+00,4.000000039686763209e+00,2.492589099719381140e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.888562751905845261e+01,3.180892252336669230e+02,6.166223455249924434e+00,4.000000039686763209e+00,2.487589099719381136e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.888812751903364529e+01,3.180989174209270232e+02,6.168685467864722938e+00,4.000000039686763209e+00,2.482589099719381132e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.889062751900883796e+01,3.181086108379818143e+02,6.171142634078342404e+00,4.000000039686763209e+00,2.477589099719381127e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.889312751898403064e+01,3.181183054824080045e+02,6.173594953276490216e+00,4.000000039686763209e+00,2.472589099719381123e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.889562751895922332e+01,3.181280013517819043e+02,6.176042424846087009e+00,4.000000039686763209e+00,2.467589099719381118e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.889812751893441600e+01,3.181376984436795965e+02,6.178485048175264893e+00,4.000000039686763209e+00,2.462589099719381114e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.890062751890960868e+01,3.181473967556767661e+02,6.180922822653368343e+00,4.000000039686763209e+00,2.457589099719381109e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.890312751888480136e+01,3.181570962853488140e+02,6.183355747670953306e+00,4.000000039686763209e+00,2.452589099719381105e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.890562751885999404e+01,3.181667970302708568e+02,6.185783822619788985e+00,4.000000039686763209e+00,2.447589099719381101e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.890812751883518672e+01,3.181764989880177268e+02,6.188207046892856056e+00,4.000000039686763209e+00,2.442589099719381096e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.891062751881037940e+01,3.181862021561639722e+02,6.190625419884348446e+00,4.000000039686763209e+00,2.437589099719381092e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.891312751878557208e+01,3.181959065322837432e+02,6.193038940989673335e+00,4.000000039686763209e+00,2.432589099719381087e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.891562751876076476e+01,3.182056121139509628e+02,6.195447609605451156e+00,4.000000039686763209e+00,2.427589099719381083e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.891812751873595744e+01,3.182153188987392696e+02,6.197851425129513814e+00,4.000000039686763209e+00,2.422589099719381078e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.892062751871115012e+01,3.182250268842219043e+02,6.200250386960907356e+00,4.000000039686763209e+00,2.417589099719381074e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.892312751868634280e+01,3.182347360679719372e+02,6.202644494499891969e+00,4.000000039686763209e+00,2.412589099719381069e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.892562751866153548e+01,3.182444464475620407e+02,6.205033747147940204e+00,4.000000039686763209e+00,2.407589099719381065e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.892812751863672815e+01,3.182541580205646028e+02,6.207418144307738750e+00,4.000000039686763209e+00,2.402589099719381061e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.893062751861192083e+01,3.182638707845517843e+02,6.209797685383188437e+00,4.000000039686763209e+00,2.397589099719381056e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.893312751858711351e+01,3.182735847370953479e+02,6.212172369779405123e+00,4.000000039686763209e+00,2.392589099719381052e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.893562751856230619e+01,3.182832998757668292e+02,6.214542196902716142e+00,4.000000039686763209e+00,2.387589099719381047e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.893812751853749887e+01,3.182930161981374226e+02,6.216907166160665632e+00,4.000000039686763209e+00,2.382589099719381043e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.894062751851269155e+01,3.183027337017780383e+02,6.219267276962010982e+00,4.000000039686763209e+00,2.377589099719381038e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.894312751848788423e+01,3.183124523842593021e+02,6.221622528716724609e+00,4.000000039686763209e+00,2.372589099719381034e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.894562751846307691e+01,3.183221722431515559e+02,6.223972920835993961e+00,4.000000039686763209e+00,2.367589099719381029e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.894812751843826959e+01,3.183318932760248572e+02,6.226318452732220621e+00,4.000000039686763209e+00,2.362589099719381025e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.895062751841346227e+01,3.183416154804489224e+02,6.228659123819021204e+00,4.000000039686763209e+00,2.357589099719381021e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.895312751838865495e+01,3.183513388539931839e+02,6.230994933511229128e+00,4.000000039686763209e+00,2.352589099719381016e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.895562751836384763e+01,3.183610633942268464e+02,6.233325881224891063e+00,4.000000039686763209e+00,2.347589099719381012e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.895812751833904031e+01,3.183707890987187739e+02,6.235651966377270483e+00,4.000000039686763209e+00,2.342589099719381007e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.896062751831423299e+01,3.183805159650374890e+02,6.237973188386845891e+00,4.000000039686763209e+00,2.337589099719381003e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.896312751828942567e+01,3.183902439907512871e+02,6.240289546673311705e+00,4.000000039686763209e+00,2.332589099719380998e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.896562751826461835e+01,3.183999731734281795e+02,6.242601040657578260e+00,4.000000039686763209e+00,2.327589099719380994e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.896812751823981102e+01,3.184097035106358931e+02,6.244907669761772695e+00,4.000000039686763209e+00,2.322589099719380989e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.897062751821500370e+01,3.184194349999418137e+02,6.247209433409237178e+00,4.000000039686763209e+00,2.317589099719380985e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.897312751819019638e+01,3.184291676389130998e+02,6.249506331024530681e+00,4.000000039686763209e+00,2.312589099719380981e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.897562751816538906e+01,3.184389014251165122e+02,6.251798362033428980e+00,4.000000039686763209e+00,2.307589099719380976e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.897812751814058174e+01,3.184486363561186977e+02,6.254085525862924655e+00,4.000000039686763209e+00,2.302589099719380972e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.898062751811577442e+01,3.184583724294858484e+02,6.256367821941227092e+00,4.000000039686763209e+00,2.297589099719380967e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.898312751809096710e+01,3.184681096427839861e+02,6.258645249697761592e+00,4.000000039686763209e+00,2.292589099719380963e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.898562751806615978e+01,3.184778479935788482e+02,6.260917808563171150e+00,4.000000039686763209e+00,2.287589099719380958e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.898812751804135246e+01,3.184875874794357742e+02,6.263185497969316451e+00,4.000000039686763209e+00,2.282589099719380954e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.899062751801654514e+01,3.184973280979199330e+02,6.265448317349274987e+00,4.000000039686763209e+00,2.277589099719380950e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.899312751799173782e+01,3.185070698465961527e+02,6.267706266137341942e+00,4.000000039686763209e+00,2.272589099719380945e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.899562751796693050e+01,3.185168127230289770e+02,6.269959343769030191e+00,4.000000039686763209e+00,2.267589099719380941e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.899812751794212318e+01,3.185265567247827221e+02,6.272207549681070304e+00,4.000000039686763209e+00,2.262589099719380936e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.900062751791731586e+01,3.185363018494213634e+02,6.274450883311410543e+00,4.000000039686763209e+00,2.257589099719380932e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.900312751789250854e+01,3.185460480945086488e+02,6.276689344099217749e+00,4.000000039686763209e+00,2.252589099719380927e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.900562751786770121e+01,3.185557954576079851e+02,6.278922931484877346e+00,4.000000039686763209e+00,2.247589099719380923e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.900812751784289389e+01,3.185655439362825518e+02,6.281151644909991560e+00,4.000000039686763209e+00,2.242589099719380918e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.901062751781808657e+01,3.185752935280952443e+02,6.283375483817382090e+00,4.000000039686763209e+00,2.237589099719380914e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.901312751779327925e+01,3.185850442306086165e+02,6.285594447651090100e+00,4.000000039686763209e+00,2.232589099719380910e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.901562751776847193e+01,3.185947960413850524e+02,6.287808535856373560e+00,4.000000039686763209e+00,2.227589099719380905e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.901812751774366461e+01,3.186045489579865375e+02,6.290017747879711685e+00,4.000000039686763209e+00,2.222589099719380901e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.902062751771885729e+01,3.186143029779748872e+02,6.292222083168800495e+00,4.000000039686763209e+00,2.217589099719380896e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.902312751769404997e+01,3.186240580989115756e+02,6.294421541172556367e+00,4.000000039686763209e+00,2.212589099719380892e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.902562751766924265e+01,3.186338143183578495e+02,6.296616121341115146e+00,4.000000039686763209e+00,2.207589099719380887e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.902812751764443533e+01,3.186435716338746147e+02,6.298805823125831260e+00,4.000000039686763209e+00,2.202589099719380883e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.903062751761962801e+01,3.186533300430225495e+02,6.300990645979279492e+00,4.000000039686763209e+00,2.197589099719380878e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.903312751759482069e+01,3.186630895433621049e+02,6.303170589355254094e+00,4.000000039686763209e+00,2.192589099719380874e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.903562751757001337e+01,3.186728501324533340e+02,6.305345652708769677e+00,4.000000039686763209e+00,2.187589099719380870e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.903812751754520605e+01,3.186826118078561194e+02,6.307515835496059431e+00,4.000000039686763209e+00,2.182589099719380865e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.904062751752039873e+01,3.186923745671300594e+02,6.309681137174578680e+00,4.000000039686763209e+00,2.177589099719380861e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.904312751749559141e+01,3.187021384078344681e+02,6.311841557203001329e+00,4.000000039686763209e+00,2.172589099719380856e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.904562751747078408e+01,3.187119033275283755e+02,6.313997095041223417e+00,4.000000039686763209e+00,2.167589099719380852e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.904812751744597676e+01,3.187216693237705272e+02,6.316147750150359563e+00,4.000000039686763209e+00,2.162589099719380847e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.905062751742116944e+01,3.187314363941194415e+02,6.318293521992745632e+00,4.000000039686763209e+00,2.157589099719380843e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.905312751739636212e+01,3.187412045361333526e+02,6.320434410031939620e+00,4.000000039686763209e+00,2.152589099719380838e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.905562751737155480e+01,3.187509737473702103e+02,6.322570413732718997e+00,4.000000039686763209e+00,2.147589099719380834e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.905812751734674748e+01,3.187607440253877371e+02,6.324701532561083361e+00,4.000000039686763209e+00,2.142589099719380830e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.906062751732194016e+01,3.187705153677433145e+02,6.326827765984252672e+00,4.000000039686763209e+00,2.137589099719380825e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.906312751729713284e+01,3.187802877719941534e+02,6.328949113470668131e+00,4.000000039686763209e+00,2.132589099719380821e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.906562751727232552e+01,3.187900612356971237e+02,6.331065574489993963e+00,4.000000039686763209e+00,2.127589099719380816e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.906812751724751820e+01,3.187998357564089247e+02,6.333177148513113863e+00,4.000000039686763209e+00,2.122589099719380812e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.907062751722271088e+01,3.188096113316858577e+02,6.335283835012134546e+00,4.000000039686763209e+00,2.117589099719380807e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.907312751719790356e+01,3.188193879590840538e+02,6.337385633460384859e+00,4.000000039686763209e+00,2.112589099719380803e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.907562751717309624e+01,3.188291656361593596e+02,6.339482543332414899e+00,4.000000039686763209e+00,2.107589099719380799e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.907812751714828892e+01,3.188389443604673374e+02,6.341574564103997780e+00,4.000000039686763209e+00,2.102589099719380794e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.908062751712348160e+01,3.188487241295633225e+02,6.343661695252127863e+00,4.000000039686763209e+00,2.097589099719380790e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.908312751709867428e+01,3.188585049410023657e+02,6.345743936255021644e+00,4.000000039686763209e+00,2.092589099719380785e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.908562751707386695e+01,3.188682867923392337e+02,6.347821286592119527e+00,4.000000039686763209e+00,2.087589099719380781e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.908812751704905963e+01,3.188780696811285225e+02,6.349893745744084050e+00,4.000000039686763209e+00,2.082589099719380776e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.909062751702425231e+01,3.188878536049244872e+02,6.351961313192800773e+00,4.000000039686763209e+00,2.077589099719380772e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.909312751699944499e+01,3.188976385612811555e+02,6.354023988421377389e+00,4.000000039686763209e+00,2.072589099719380767e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.909562751697463767e+01,3.189074245477522709e+02,6.356081770914144613e+00,4.000000039686763209e+00,2.067589099719380763e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.909812751694983035e+01,3.189172115618913494e+02,6.358134660156657958e+00,4.000000039686763209e+00,2.062589099719380759e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.910062751692502303e+01,3.189269996012516231e+02,6.360182655635694182e+00,4.000000039686763209e+00,2.057589099719380754e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.910312751690021571e+01,3.189367886633860394e+02,6.362225756839254842e+00,4.000000039686763209e+00,2.052589099719380750e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.910562751687540839e+01,3.189465787458474324e+02,6.364263963256564516e+00,4.000000039686763209e+00,2.047589099719380745e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.910812751685060107e+01,3.189563698461881813e+02,6.366297274378071691e+00,4.000000039686763209e+00,2.042589099719380741e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.911062751682579375e+01,3.189661619619606086e+02,6.368325689695448766e+00,4.000000039686763209e+00,2.037589099719380736e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.911312751680098643e+01,3.189759550907166386e+02,6.370349208701591159e+00,4.000000039686763209e+00,2.032589099719380732e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.911562751677617911e+01,3.189857492300079684e+02,6.372367830890619977e+00,4.000000039686763209e+00,2.027589099719380727e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.911812751675137179e+01,3.189955443773860679e+02,6.374381555757879347e+00,4.000000039686763209e+00,2.022589099719380723e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.912062751672656447e+01,3.190053405304021794e+02,6.376390382799938195e+00,4.000000039686763209e+00,2.017589099719380719e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.912312751670175714e+01,3.190151376866072610e+02,6.378394311514590242e+00,4.000000039686763209e+00,2.012589099719380714e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.912562751667694982e+01,3.190249358435519866e+02,6.380393341400852236e+00,4.000000039686763209e+00,2.007589099719380710e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.912812751665214250e+01,3.190347349987868597e+02,6.382387471958967495e+00,4.000000039686763209e+00,2.002589099719380705e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.913062751662733518e+01,3.190445351498620994e+02,6.384376702690403249e+00,4.000000039686763209e+00,1.997589099719380701e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.913312751660252786e+01,3.190543362943276406e+02,6.386361033097851525e+00,4.000000039686763209e+00,1.992589099719380696e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.913562751657772054e+01,3.190641384297331911e+02,6.388340462685230037e+00,4.000000039686763209e+00,1.987589099719380692e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.913812751655291322e+01,3.190739415536282308e+02,6.390314990957681296e+00,4.000000039686763209e+00,1.982589099719380688e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.914062751652810590e+01,3.190837456635619560e+02,6.392284617421573500e+00,4.000000039686763209e+00,1.977589099719380683e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.914312751650329858e+01,3.190935507570833920e+02,6.394249341584499646e+00,4.000000039686763209e+00,1.972589099719380679e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.914562751647849126e+01,3.191033568317412232e+02,6.396209162955278416e+00,4.000000039686763209e+00,1.967589099719380674e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.914812751645368394e+01,3.191131638850839067e+02,6.398164081043955065e+00,4.000000039686763209e+00,1.962589099719380670e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.915062751642887662e+01,3.191229719146597290e+02,6.400114095361799649e+00,4.000000039686763209e+00,1.957589099719380665e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.915312751640406930e+01,3.191327809180166923e+02,6.402059205421308796e+00,4.000000039686763209e+00,1.952589099719380661e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.915562751637926198e+01,3.191425908927025148e+02,6.403999410736205711e+00,4.000000039686763209e+00,1.947589099719380656e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.915812751635445466e+01,3.191524018362646871e+02,6.405934710821438394e+00,4.000000039686763209e+00,1.942589099719380652e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.916062751632964734e+01,3.191622137462504725e+02,6.407865105193181421e+00,4.000000039686763209e+00,1.937589099719380648e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.916312751630484001e+01,3.191720266202069070e+02,6.409790593368836831e+00,4.000000039686763209e+00,1.932589099719380643e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.916562751628003269e+01,3.191818404556807991e+02,6.411711174867032348e+00,4.000000039686763209e+00,1.927589099719380639e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.916812751625522537e+01,3.191916552502186732e+02,6.413626849207623160e+00,4.000000039686763209e+00,1.922589099719380634e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.917062751623041805e+01,3.192014710013668264e+02,6.415537615911690139e+00,4.000000039686763209e+00,1.917589099719380630e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.917312751620561073e+01,3.192112877066713281e+02,6.417443474501541623e+00,4.000000039686763209e+00,1.912589099719380625e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.917562751618080341e+01,3.192211053636780207e+02,6.419344424500712520e+00,4.000000039686763209e+00,1.907589099719380621e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.917812751615599609e+01,3.192309239699324621e+02,6.421240465433966094e+00,4.000000039686763209e+00,1.902589099719380616e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.918062751613118877e+01,3.192407435229799830e+02,6.423131596827292178e+00,4.000000039686763209e+00,1.897589099719380612e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.918312751610638145e+01,3.192505640203657435e+02,6.425017818207907183e+00,4.000000039686763209e+00,1.892589099719380608e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.918562751608157413e+01,3.192603854596345627e+02,6.426899129104256758e+00,4.000000039686763209e+00,1.887589099719380603e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.918812751605676681e+01,3.192702078383311459e+02,6.428775529046012238e+00,4.000000039686763209e+00,1.882589099719380599e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.919062751603195949e+01,3.192800311539998575e+02,6.430647017564074197e+00,4.000000039686763209e+00,1.877589099719380594e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.919312751600715217e+01,3.192898554041848342e+02,6.432513594190570672e+00,4.000000039686763209e+00,1.872589099719380590e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.919562751598234485e+01,3.192996805864300995e+02,6.434375258458857161e+00,4.000000039686763209e+00,1.867589099719380585e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.919812751595753753e+01,3.193095066982792787e+02,6.436232009903517515e+00,4.000000039686763209e+00,1.862589099719380581e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.920062751593273020e+01,3.193193337372758833e+02,6.438083848060363934e+00,4.000000039686763209e+00,1.857589099719380576e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.920312751590792288e+01,3.193291617009631409e+02,6.439930772466436970e+00,4.000000039686763209e+00,1.852589099719380572e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.920562751588311556e+01,3.193389905868840515e+02,6.441772782660005525e+00,4.000000039686763209e+00,1.847589099719380568e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.920812751585830824e+01,3.193488203925814446e+02,6.443609878180567740e+00,4.000000039686763209e+00,1.842589099719380563e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.921062751583350092e+01,3.193586511155978087e+02,6.445442058568849220e+00,4.000000039686763209e+00,1.837589099719380559e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.921312751580869360e+01,3.193684827534755186e+02,6.447269323366804805e+00,4.000000039686763209e+00,1.832589099719380554e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.921562751578388628e+01,3.193783153037566080e+02,6.449091672117617691e+00,4.000000039686763209e+00,1.827589099719380550e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.921812751575907896e+01,3.193881487639829970e+02,6.450909104365701197e+00,4.000000039686763209e+00,1.822589099719380545e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.922062751573427164e+01,3.193979831316962645e+02,6.452721619656697882e+00,4.000000039686763209e+00,1.817589099719380541e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.922312751570946432e+01,3.194078184044378759e+02,6.454529217537477770e+00,4.000000039686763209e+00,1.812589099719380537e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.922562751568465700e+01,3.194176545797489553e+02,6.456331897556142785e+00,4.000000039686763209e+00,1.807589099719380532e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.922812751565984968e+01,3.194274916551705132e+02,6.458129659262021427e+00,4.000000039686763209e+00,1.802589099719380528e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.923062751563504236e+01,3.194373296282432193e+02,6.459922502205674100e+00,4.000000039686763209e+00,1.797589099719380523e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.923312751561023504e+01,3.194471684965076292e+02,6.461710425938890445e+00,4.000000039686763209e+00,1.792589099719380519e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.923562751558542772e+01,3.194570082575040146e+02,6.463493430014689345e+00,4.000000039686763209e+00,1.787589099719380514e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.923812751556062040e+01,3.194668489087724197e+02,6.465271513987318919e+00,4.000000039686763209e+00,1.782589099719380510e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.924062751553581307e+01,3.194766904478526612e+02,6.467044677412259190e+00,4.000000039686763209e+00,1.777589099719380505e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.924312751551100575e+01,3.194865328722843856e+02,6.468812919846218534e+00,4.000000039686763209e+00,1.772589099719380501e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.924562751548619843e+01,3.194963761796070116e+02,6.470576240847137228e+00,4.000000039686763209e+00,1.767589099719380497e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.924812751546139111e+01,3.195062203673596741e+02,6.472334639974184789e+00,4.000000039686763209e+00,1.762589099719380492e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.925062751543658379e+01,3.195160654330813372e+02,6.474088116787760860e+00,4.000000039686763209e+00,1.757589099719380488e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.925312751541177647e+01,3.195259113743107378e+02,6.475836670849496990e+00,4.000000039686763209e+00,1.752589099719380483e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.925562751538696915e+01,3.195357581885863851e+02,6.477580301722253964e+00,4.000000039686763209e+00,1.747589099719380479e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.925812751536216183e+01,3.195456058734466183e+02,6.479319008970124472e+00,4.000000039686763209e+00,1.742589099719380474e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.926062751533735451e+01,3.195554544264294918e+02,6.481052792158431330e+00,4.000000039686763209e+00,1.737589099719380470e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.926312751531254719e+01,3.195653038450728332e+02,6.482781650853729261e+00,4.000000039686763209e+00,1.732589099719380465e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.926562751528773987e+01,3.195751541269142990e+02,6.484505584623803109e+00,4.000000039686763209e+00,1.727589099719380461e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.926812751526293255e+01,3.195850052694913188e+02,6.486224593037669628e+00,4.000000039686763209e+00,1.722589099719380457e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.927062751523812523e+01,3.195948572703411514e+02,6.487938675665577470e+00,4.000000039686763209e+00,1.717589099719380452e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.927312751521331791e+01,3.196047101270007147e+02,6.489647832079004530e+00,4.000000039686763209e+00,1.712589099719380448e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.927562751518851059e+01,3.196145638370068696e+02,6.491352061850663269e+00,4.000000039686763209e+00,1.707589099719380443e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.927812751516370326e+01,3.196244183978961360e+02,6.493051364554495386e+00,4.000000039686763209e+00,1.702589099719380439e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.928062751513889594e+01,3.196342738072049201e+02,6.494745739765675374e+00,4.000000039686763209e+00,1.697589099719380434e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.928312751511408862e+01,3.196441300624693440e+02,6.496435187060608740e+00,4.000000039686763209e+00,1.692589099719380430e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.928562751508928130e+01,3.196539871612253592e+02,6.498119706016934671e+00,4.000000039686763209e+00,1.687589099719380425e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.928812751506447398e+01,3.196638451010086897e+02,6.499799296213523370e+00,4.000000039686763209e+00,1.682589099719380421e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.929062751503966666e+01,3.196737038793548322e+02,6.501473957230476941e+00,4.000000039686763209e+00,1.677589099719380417e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.929312751501485934e+01,3.196835634937991131e+02,6.503143688649130283e+00,4.000000039686763209e+00,1.672589099719380412e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.929562751499005202e+01,3.196934239418765742e+02,6.504808490052050196e+00,4.000000039686763209e+00,1.667589099719380408e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.929812751496524470e+01,3.197032852211222007e+02,6.506468361023036273e+00,4.000000039686763209e+00,1.662589099719380403e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.930062751494043738e+01,3.197131473290705799e+02,6.508123301147121786e+00,4.000000039686763209e+00,1.657589099719380399e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.930312751491563006e+01,3.197230102632562421e+02,6.509773310010571024e+00,4.000000039686763209e+00,1.652589099719380394e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.930562751489082274e+01,3.197328740212134335e+02,6.511418387200881952e+00,4.000000039686763209e+00,1.647589099719380390e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.930812751486601542e+01,3.197427386004762297e+02,6.513058532306784443e+00,4.000000039686763209e+00,1.642589099719380386e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.931062751484120810e+01,3.197526039985784791e+02,6.514693744918242935e+00,4.000000039686763209e+00,1.637589099719380381e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.931312751481640078e+01,3.197624702130538026e+02,6.516324024626454658e+00,4.000000039686763209e+00,1.632589099719380377e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.931562751479159346e+01,3.197723372414356504e+02,6.517949371023849636e+00,4.000000039686763209e+00,1.627589099719380372e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.931812751476678613e+01,3.197822050812573025e+02,6.519569783704090682e+00,4.000000039686763209e+00,1.622589099719380368e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.932062751474197881e+01,3.197920737300517544e+02,6.521185262262075177e+00,4.000000039686763209e+00,1.617589099719380363e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.932312751471717149e+01,3.198019431853518881e+02,6.522795806293932408e+00,4.000000039686763209e+00,1.612589099719380359e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.932562751469236417e+01,3.198118134446903014e+02,6.524401415397028003e+00,4.000000039686763209e+00,1.607589099719380354e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.932812751466755685e+01,3.198216845055994781e+02,6.526002089169958609e+00,4.000000039686763209e+00,1.602589099719380350e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.933062751464274953e+01,3.198315563656116183e+02,6.527597827212556325e+00,4.000000039686763209e+00,1.597589099719380346e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.933312751461794221e+01,3.198414290222587510e+02,6.529188629125886045e+00,4.000000039686763209e+00,1.592589099719380341e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.933562751459313489e+01,3.198513024730727352e+02,6.530774494512247230e+00,4.000000039686763209e+00,1.587589099719380337e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.933812751456832757e+01,3.198611767155852021e+02,6.532355422975173909e+00,4.000000039686763209e+00,1.582589099719380332e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.934062751454352025e+01,3.198710517473276127e+02,6.533931414119434677e+00,4.000000039686763209e+00,1.577589099719380328e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.934312751451871293e+01,3.198809275658311435e+02,6.535502467551030925e+00,4.000000039686763209e+00,1.572589099719380323e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.934562751449390561e+01,3.198908041686269144e+02,6.537068582877199496e+00,4.000000039686763209e+00,1.567589099719380319e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.934812751446909829e+01,3.199006815532457040e+02,6.538629759706410915e+00,4.000000039686763209e+00,1.562589099719380314e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.935062751444429097e+01,3.199105597172182343e+02,6.540185997648372052e+00,4.000000039686763209e+00,1.557589099719380310e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.935312751441948365e+01,3.199204386580749429e+02,6.541737296314022565e+00,4.000000039686763209e+00,1.552589099719380306e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.935562751439467633e+01,3.199303183733460401e+02,6.543283655315538461e+00,4.000000039686763209e+00,1.547589099719380301e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.935812751436986900e+01,3.199401988605616793e+02,6.544825074266330311e+00,4.000000039686763209e+00,1.542589099719380297e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.936062751434506168e+01,3.199500801172516731e+02,6.546361552781042370e+00,4.000000039686763209e+00,1.537589099719380292e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.936312751432025436e+01,3.199599621409457768e+02,6.547893090475555233e+00,4.000000039686763209e+00,1.532589099719380288e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.936562751429544704e+01,3.199698449291734050e+02,6.549419686966984955e+00,4.000000039686763209e+00,1.527589099719380283e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.936812751427063972e+01,3.199797284794639154e+02,6.550941341873682155e+00,4.000000039686763209e+00,1.522589099719380279e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.937062751424583240e+01,3.199896127893463813e+02,6.552458054815232913e+00,4.000000039686763209e+00,1.517589099719380275e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.937312751422102508e+01,3.199994978563497625e+02,6.553969825412459649e+00,4.000000039686763209e+00,1.512589099719380270e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.937562751419621776e+01,3.200093836780027914e+02,6.555476653287419353e+00,4.000000039686763209e+00,1.507589099719380266e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.937812751417141044e+01,3.200192702518339729e+02,6.556978538063405360e+00,4.000000039686763209e+00,1.502589099719380261e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.938062751414660312e+01,3.200291575753716984e+02,6.558475479364945571e+00,4.000000039686763209e+00,1.497589099719380257e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.938312751412179580e+01,3.200390456461441318e+02,6.559967476817805121e+00,4.000000039686763209e+00,1.492589099719380252e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.938562751409698848e+01,3.200489344616792664e+02,6.561454530048984601e+00,4.000000039686763209e+00,1.487589099719380248e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.938812751407218116e+01,3.200588240195048684e+02,6.562936638686720947e+00,4.000000039686763209e+00,1.482589099719380243e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.939062751404737384e+01,3.200687143171485900e+02,6.564413802360487438e+00,4.000000039686763209e+00,1.477589099719380239e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.939312751402256652e+01,3.200786053521377994e+02,6.565886020700992809e+00,4.000000039686763209e+00,1.472589099719380235e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.939562751399775919e+01,3.200884971219997510e+02,6.567353293340182141e+00,4.000000039686763209e+00,1.467589099719380230e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.939812751397295187e+01,3.200983896242615288e+02,6.568815619911237746e+00,4.000000039686763209e+00,1.462589099719380226e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.940062751394814455e+01,3.201082828564499891e+02,6.570273000048577394e+00,4.000000039686763209e+00,1.457589099719380221e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.940312751392333723e+01,3.201181768160918750e+02,6.571725433387856086e+00,4.000000039686763209e+00,1.452589099719380217e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.940562751389852991e+01,3.201280715007136450e+02,6.573172919565966055e+00,4.000000039686763209e+00,1.447589099719380212e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.940812751387372259e+01,3.201379669078416441e+02,6.574615458221035880e+00,4.000000039686763209e+00,1.442589099719380208e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.941062751384891527e+01,3.201478630350019898e+02,6.576053048992430483e+00,4.000000039686763209e+00,1.437589099719380203e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.941312751382410795e+01,3.201577598797206861e+02,6.577485691520752020e+00,4.000000039686763209e+00,1.432589099719380199e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.941562751379930063e+01,3.201676574395235093e+02,6.578913385447839879e+00,4.000000039686763209e+00,1.427589099719380195e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.941812751377449331e+01,3.201775557119360656e+02,6.580336130416770679e+00,4.000000039686763209e+00,1.422589099719380190e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.942062751374968599e+01,3.201874546944837903e+02,6.581753926071858274e+00,4.000000039686763209e+00,1.417589099719380186e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.942312751372487867e+01,3.201973543846919483e+02,6.583166772058653748e+00,4.000000039686763209e+00,1.412589099719380181e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.942562751370007135e+01,3.202072547800856341e+02,6.584574668023946309e+00,4.000000039686763209e+00,1.407589099719380177e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.942812751367526403e+01,3.202171558781897147e+02,6.585977613615760617e+00,4.000000039686763209e+00,1.402589099719380172e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.943062751365045671e+01,3.202270576765288865e+02,6.587375608483361233e+00,4.000000039686763209e+00,1.397589099719380168e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.943312751362564939e+01,3.202369601726277892e+02,6.588768652277249060e+00,4.000000039686763209e+00,1.392589099719380163e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.943562751360084206e+01,3.202468633640107214e+02,6.590156744649163123e+00,4.000000039686763209e+00,1.387589099719380159e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.943812751357603474e+01,3.202567672482019248e+02,6.591539885252080566e+00,4.000000039686763209e+00,1.382589099719380155e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.944062751355122742e+01,3.202666718227254137e+02,6.592918073740216656e+00,4.000000039686763209e+00,1.377589099719380150e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.944312751352642010e+01,3.202765770851050320e+02,6.594291309769023890e+00,4.000000039686763209e+00,1.372589099719380146e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.944562751350161278e+01,3.202864830328645098e+02,6.595659592995192888e+00,4.000000039686763209e+00,1.367589099719380141e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.944812751347680546e+01,3.202963896635272931e+02,6.597022923076653278e+00,4.000000039686763209e+00,1.362589099719380137e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.945062751345199814e+01,3.203062969746167710e+02,6.598381299672571920e+00,4.000000039686763209e+00,1.357589099719380132e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.945312751342719082e+01,3.203162049636561051e+02,6.599734722443355572e+00,4.000000039686763209e+00,1.352589099719380128e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.945562751340238350e+01,3.203261136281682866e+02,6.601083191050648225e+00,4.000000039686763209e+00,1.347589099719380124e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.945812751337757618e+01,3.203360229656761931e+02,6.602426705157332876e+00,4.000000039686763209e+00,1.342589099719380119e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.946062751335276886e+01,3.203459329737024177e+02,6.603765264427530646e+00,4.000000039686763209e+00,1.337589099719380115e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.946312751332796154e+01,3.203558436497694970e+02,6.605098868526601663e+00,4.000000039686763209e+00,1.332589099719380110e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.946562751330315422e+01,3.203657549913997968e+02,6.606427517121145065e+00,4.000000039686763209e+00,1.327589099719380106e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.946812751327834690e+01,3.203756669961154557e+02,6.607751209878998999e+00,4.000000039686763209e+00,1.322589099719380101e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.947062751325353958e+01,3.203855796614384417e+02,6.609069946469239731e+00,4.000000039686763209e+00,1.317589099719380097e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.947312751322873225e+01,3.203954929848906090e+02,6.610383726562183426e+00,4.000000039686763209e+00,1.312589099719380092e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.947562751320392493e+01,3.204054069639936415e+02,6.611692549829385257e+00,4.000000039686763209e+00,1.307589099719380088e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.947812751317911761e+01,3.204153215962690524e+02,6.612996415943639406e+00,4.000000039686763209e+00,1.302589099719380084e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.948062751315431029e+01,3.204252368792381276e+02,6.614295324578979063e+00,4.000000039686763209e+00,1.297589099719380079e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.948312751312950297e+01,3.204351528104220961e+02,6.615589275410676429e+00,4.000000039686763209e+00,1.292589099719380075e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.948562751310469565e+01,3.204450693873419596e+02,6.616878268115245376e+00,4.000000039686763209e+00,1.287589099719380070e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.948812751307988833e+01,3.204549866075185491e+02,6.618162302370436123e+00,4.000000039686763209e+00,1.282589099719380066e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.949062751305508101e+01,3.204649044684726391e+02,6.619441377855241448e+00,4.000000039686763209e+00,1.277589099719380061e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.949312751303027369e+01,3.204748229677246627e+02,6.620715494249891364e+00,4.000000039686763209e+00,1.272589099719380057e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.949562751300546637e+01,3.204847421027950531e+02,6.621984651235857555e+00,4.000000039686763209e+00,1.267589099719380052e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.949812751298065905e+01,3.204946618712040163e+02,6.623248848495850716e+00,4.000000039686763209e+00,1.262589099719380048e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.950062751295585173e+01,3.205045822704716443e+02,6.624508085713821437e+00,4.000000039686763209e+00,1.257589099719380044e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.950312751293104441e+01,3.205145032981178019e+02,6.625762362574960207e+00,4.000000039686763209e+00,1.252589099719380039e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.950562751290623709e+01,3.205244249516622403e+02,6.627011678765698299e+00,4.000000039686763209e+00,1.247589099719380035e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.950812751288142977e+01,3.205343472286245401e+02,6.628256033973705996e+00,4.000000039686763209e+00,1.242589099719380030e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.951062751285662245e+01,3.205442701265241112e+02,6.629495427887895254e+00,4.000000039686763209e+00,1.237589099719380026e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.951312751283181512e+01,3.205541936428802501e+02,6.630729860198417036e+00,4.000000039686763209e+00,1.232589099719380021e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.951562751280700780e+01,3.205641177752120825e+02,6.631959330596663094e+00,4.000000039686763209e+00,1.227589099719380017e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.951812751278220048e+01,3.205740425210385638e+02,6.633183838775266850e+00,4.000000039686763209e+00,1.222589099719380012e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.952062751275739316e+01,3.205839678778785355e+02,6.634403384428099848e+00,4.000000039686763209e+00,1.217589099719380008e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.952312751273258584e+01,3.205938938432506120e+02,6.635617967250277083e+00,4.000000039686763209e+00,1.212589099719380004e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.952562751270777852e+01,3.206038204146733506e+02,6.636827586938151669e+00,4.000000039686763209e+00,1.207589099719379999e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.952812751268297120e+01,3.206137475896650813e+02,6.638032243189319281e+00,4.000000039686763209e+00,1.202589099719379995e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.953062751265816388e+01,3.206236753657440204e+02,6.639231935702616383e+00,4.000000039686763209e+00,1.197589099719379990e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.953312751263335656e+01,3.206336037404282138e+02,6.640426664178119331e+00,4.000000039686763209e+00,1.192589099719379986e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.953562751260854924e+01,3.206435327112355935e+02,6.641616428317145271e+00,4.000000039686763209e+00,1.187589099719379981e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.953812751258374192e+01,3.206534622756838644e+02,6.642801227822253907e+00,4.000000039686763209e+00,1.182589099719379977e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.954062751255893460e+01,3.206633924312906743e+02,6.643981062397245729e+00,4.000000039686763209e+00,1.177589099719379973e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.954312751253412728e+01,3.206733231755735005e+02,6.645155931747162015e+00,4.000000039686763209e+00,1.172589099719379968e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.954562751250931996e+01,3.206832545060495931e+02,6.646325835578284824e+00,4.000000039686763209e+00,1.167589099719379964e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.954812751248451264e+01,3.206931864202362021e+02,6.647490773598138780e+00,4.000000039686763209e+00,1.162589099719379959e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.955062751245970531e+01,3.207031189156502933e+02,6.648650745515488403e+00,4.000000039686763209e+00,1.157589099719379955e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.955312751243489799e+01,3.207130519898087755e+02,6.649805751040341661e+00,4.000000039686763209e+00,1.152589099719379950e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.955562751241009067e+01,3.207229856402283303e+02,6.650955789883947311e+00,4.000000039686763209e+00,1.147589099719379946e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.955812751238528335e+01,3.207329198644255825e+02,6.652100861758794892e+00,4.000000039686763209e+00,1.142589099719379941e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.956062751236047603e+01,3.207428546599169863e+02,6.653240966378616505e+00,4.000000039686763209e+00,1.137589099719379937e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.956312751233566871e+01,3.207527900242188252e+02,6.654376103458386815e+00,4.000000039686763209e+00,1.132589099719379933e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.956562751231086139e+01,3.207627259548472693e+02,6.655506272714321270e+00,4.000000039686763209e+00,1.127589099719379928e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.956812751228605407e+01,3.207726624493183181e+02,6.656631473863876991e+00,4.000000039686763209e+00,1.122589099719379924e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.957062751226124675e+01,3.207825995051478571e+02,6.657751706625754551e+00,4.000000039686763209e+00,1.117589099719379919e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.957312751223643943e+01,3.207925371198516018e+02,6.658866970719894418e+00,4.000000039686763209e+00,1.112589099719379915e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.957562751221163211e+01,3.208024752909451536e+02,6.659977265867482288e+00,4.000000039686763209e+00,1.107589099719379910e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.957812751218682479e+01,3.208124140159440003e+02,6.661082591790942864e+00,4.000000039686763209e+00,1.102589099719379906e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.958062751216201747e+01,3.208223532923634593e+02,6.662182948213945188e+00,4.000000039686763209e+00,1.097589099719379901e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.958312751213721015e+01,3.208322931177186774e+02,6.663278334861400864e+00,4.000000039686763209e+00,1.092589099719379897e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.958562751211240283e+01,3.208422334895247445e+02,6.664368751459462281e+00,4.000000039686763209e+00,1.087589099719379893e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.958812751208759551e+01,3.208521744052965232e+02,6.665454197735526165e+00,4.000000039686763209e+00,1.082589099719379888e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.959062751206278818e+01,3.208621158625488192e+02,6.666534673418230028e+00,4.000000039686763209e+00,1.077589099719379884e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.959312751203798086e+01,3.208720578587962677e+02,6.667610178237455720e+00,4.000000039686763209e+00,1.072589099719379879e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.959562751201317354e+01,3.208820003915533334e+02,6.668680711924326765e+00,4.000000039686763209e+00,1.067589099719379875e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.959812751198836622e+01,3.208919434583344241e+02,6.669746274211209247e+00,4.000000039686763209e+00,1.062589099719379870e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.960062751196355890e+01,3.209018870566537203e+02,6.670806864831713590e+00,4.000000039686763209e+00,1.057589099719379866e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.960312751193875158e+01,3.209118311840253455e+02,6.671862483520691001e+00,4.000000039686763209e+00,1.052589099719379861e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.960562751191394426e+01,3.209217758379633096e+02,6.672913130014237915e+00,4.000000039686763209e+00,1.047589099719379857e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.960812751188913694e+01,3.209317210159813953e+02,6.673958804049692439e+00,4.000000039686763209e+00,1.042589099719379853e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.961062751186432962e+01,3.209416667155933283e+02,6.674999505365635244e+00,4.000000039686763209e+00,1.037589099719379848e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.961312751183952230e+01,3.209516129343127204e+02,6.676035233701892224e+00,4.000000039686763209e+00,1.032589099719379844e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.961562751181471498e+01,3.209615596696529565e+02,6.677065988799530061e+00,4.000000039686763209e+00,1.027589099719379839e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.961812751178990766e+01,3.209715069191273642e+02,6.678091770400860661e+00,4.000000039686763209e+00,1.022589099719379835e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.962062751176510034e+01,3.209814546802491577e+02,6.679112578249438492e+00,4.000000039686763209e+00,1.017589099719379830e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.962312751174029302e+01,3.209914029505313806e+02,6.680128412090062362e+00,4.000000039686763209e+00,1.012589099719379826e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.962562751171548570e+01,3.210013517274869628e+02,6.681139271668772750e+00,4.000000039686763209e+00,1.007589099719379822e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.962812751169067838e+01,3.210113010086287204e+02,6.682145156732855362e+00,4.000000039686763209e+00,1.002589099719379817e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.963062751166587105e+01,3.210212507914693560e+02,6.683146067030838466e+00,4.000000039686763209e+00,9.975890997193798126e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.963312751164106373e+01,3.210312010735214017e+02,6.684142002312494668e+00,4.000000039686763209e+00,9.925890997193798082e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.963562751161625641e+01,3.210411518522972756e+02,6.685132962328840911e+00,4.000000039686763209e+00,9.875890997193798038e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.963812751159144909e+01,3.210511031253092824e+02,6.686118946832135812e+00,4.000000039686763209e+00,9.825890997193797993e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.964062751156664177e+01,3.210610548900696131e+02,6.687099955575884103e+00,4.000000039686763209e+00,9.775890997193797949e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.964312751154183445e+01,3.210710071440902880e+02,6.688075988314833964e+00,4.000000039686763209e+00,9.725890997193797904e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.964562751151702713e+01,3.210809598848833275e+02,6.689047044804976139e+00,4.000000039686763209e+00,9.675890997193797860e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.964812751149221981e+01,3.210909131099604679e+02,6.690013124803547484e+00,4.000000039686763209e+00,9.625890997193797816e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.965062751146741249e+01,3.211008668168334452e+02,6.690974228069027419e+00,4.000000039686763209e+00,9.575890997193797771e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.965312751144260517e+01,3.211108210030138252e+02,6.691930354361140587e+00,4.000000039686763209e+00,9.525890997193797727e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.965562751141779785e+01,3.211207756660130599e+02,6.692881503440855084e+00,4.000000039686763209e+00,9.475890997193797682e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.965812751139299053e+01,3.211307308033424874e+02,6.693827675070383343e+00,4.000000039686763209e+00,9.425890997193797638e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.966062751136818321e+01,3.211406864125132756e+02,6.694768869013183021e+00,4.000000039686763209e+00,9.375890997193797594e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.966312751134337589e+01,3.211506424910365922e+02,6.695705085033955228e+00,4.000000039686763209e+00,9.325890997193797549e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.966562751131856857e+01,3.211605990364233776e+02,6.696636322898646299e+00,4.000000039686763209e+00,9.275890997193797505e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.966812751129376124e+01,3.211705560461845153e+02,6.697562582374446905e+00,4.000000039686763209e+00,9.225890997193797460e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.967062751126895392e+01,3.211805135178307751e+02,6.698483863229792057e+00,4.000000039686763209e+00,9.175890997193797416e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.967312751124414660e+01,3.211904714488727564e+02,6.699400165234361104e+00,4.000000039686763209e+00,9.125890997193797372e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.967562751121933928e+01,3.212004298368209447e+02,6.700311488159079509e+00,4.000000039686763209e+00,9.075890997193797327e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.967812751119453196e+01,3.212103886791857690e+02,6.701217831776115297e+00,4.000000039686763209e+00,9.025890997193797283e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.968062751116972464e+01,3.212203479734775442e+02,6.702119195858883494e+00,4.000000039686763209e+00,8.975890997193797238e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.968312751114491732e+01,3.212303077172064150e+02,6.703015580182042576e+00,4.000000039686763209e+00,8.925890997193797194e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.968562751112011000e+01,3.212402679078824690e+02,6.703906984521497137e+00,4.000000039686763209e+00,8.875890997193797149e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.968812751109530268e+01,3.212502285430156803e+02,6.704793408654395215e+00,4.000000039686763209e+00,8.825890997193797105e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.969062751107049536e+01,3.212601896201158524e+02,6.705674852359130966e+00,4.000000039686763209e+00,8.775890997193797061e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.969312751104568804e+01,3.212701511366927321e+02,6.706551315415343772e+00,4.000000039686763209e+00,8.725890997193797016e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.969562751102088072e+01,3.212801130902558953e+02,6.707422797603918241e+00,4.000000039686763209e+00,8.675890997193796972e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.969812751099607340e+01,3.212900754783149182e+02,6.708289298706983317e+00,4.000000039686763209e+00,8.625890997193796927e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.970062751097126608e+01,3.213000382983791496e+02,6.709150818507914060e+00,4.000000039686763209e+00,8.575890997193796883e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.970312751094645876e+01,3.213100015479579383e+02,6.710007356791329869e+00,4.000000039686763209e+00,8.525890997193796839e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.970562751092165144e+01,3.213199652245604625e+02,6.710858913343096255e+00,4.000000039686763209e+00,8.475890997193796794e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.970812751089684411e+01,3.213299293256957299e+02,6.711705487950324844e+00,4.000000039686763209e+00,8.425890997193796750e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.971062751087203679e+01,3.213398938488728049e+02,6.712547080401371602e+00,4.000000039686763209e+00,8.375890997193796705e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.971312751084722947e+01,3.213498587916005249e+02,6.713383690485837718e+00,4.000000039686763209e+00,8.325890997193796661e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.971562751082242215e+01,3.213598241513876701e+02,6.714215317994571386e+00,4.000000039686763209e+00,8.275890997193796617e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.971812751079761483e+01,3.213697899257428503e+02,6.715041962719666024e+00,4.000000039686763209e+00,8.225890997193796572e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.972062751077280751e+01,3.213797561121746753e+02,6.715863624454460279e+00,4.000000039686763209e+00,8.175890997193796528e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.972312751074800019e+01,3.213897227081915844e+02,6.716680302993538021e+00,4.000000039686763209e+00,8.125890997193796483e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.972562751072319287e+01,3.213996897113019031e+02,6.717491998132730124e+00,4.000000039686763209e+00,8.075890997193796439e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.972812751069838555e+01,3.214096571190139002e+02,6.718298709669113578e+00,4.000000039686763209e+00,8.025890997193796395e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.973062751067357823e+01,3.214196249288357308e+02,6.719100437401009707e+00,4.000000039686763209e+00,7.975890997193796350e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.973312751064877091e+01,3.214295931382754361e+02,6.719897181127985952e+00,4.000000039686763209e+00,7.925890997193796306e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.973562751062396359e+01,3.214395617448409439e+02,6.720688940650857646e+00,4.000000039686763209e+00,7.875890997193796261e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.973812751059915627e+01,3.214495307460401250e+02,6.721475715771684456e+00,4.000000039686763209e+00,7.825890997193796217e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.974062751057434895e+01,3.214595001393807365e+02,6.722257506293772167e+00,4.000000039686763209e+00,7.775890997193796172e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.974312751054954163e+01,3.214694699223704220e+02,6.723034312021673564e+00,4.000000039686763209e+00,7.725890997193796128e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.974562751052473430e+01,3.214794400925167110e+02,6.723806132761186660e+00,4.000000039686763209e+00,7.675890997193796084e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.974812751049992698e+01,3.214894106473270767e+02,6.724572968319357358e+00,4.000000039686763209e+00,7.625890997193796039e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.975062751047511966e+01,3.214993815843088782e+02,6.725334818504475898e+00,4.000000039686763209e+00,7.575890997193795995e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.975312751045031234e+01,3.215093529009694180e+02,6.726091683126079523e+00,4.000000039686763209e+00,7.525890997193795950e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.975562751042550502e+01,3.215193245948158278e+02,6.726843561994952481e+00,4.000000039686763209e+00,7.475890997193795906e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.975812751040069770e+01,3.215292966633551828e+02,6.727590454923125129e+00,4.000000039686763209e+00,7.425890997193795862e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.976062751037589038e+01,3.215392691040945010e+02,6.728332361723874833e+00,4.000000039686763209e+00,7.375890997193795817e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.976312751035108306e+01,3.215492419145406302e+02,6.729069282211724179e+00,4.000000039686763209e+00,7.325890997193795773e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.976562751032627574e+01,3.215592150922004180e+02,6.729801216202442760e+00,4.000000039686763209e+00,7.275890997193795728e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.976812751030146842e+01,3.215691886345805415e+02,6.730528163513048057e+00,4.000000039686763209e+00,7.225890997193795684e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.977062751027666110e+01,3.215791625391875641e+02,6.731250123961802778e+00,4.000000039686763209e+00,7.175890997193795640e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.977312751025185378e+01,3.215891368035281062e+02,6.731967097368216635e+00,4.000000039686763209e+00,7.125890997193795595e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.977562751022704646e+01,3.215991114251085037e+02,6.732679083553046340e+00,4.000000039686763209e+00,7.075890997193795551e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.977812751020223914e+01,3.216090864014351496e+02,6.733386082338294720e+00,4.000000039686763209e+00,7.025890997193795506e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.978062751017743182e+01,3.216190617300143231e+02,6.734088093547213383e+00,4.000000039686763209e+00,6.975890997193795462e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.978312751015262450e+01,3.216290374083521897e+02,6.734785117004298272e+00,4.000000039686763209e+00,6.925890997193795418e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.978562751012781717e+01,3.216390134339548013e+02,6.735477152535294110e+00,4.000000039686763209e+00,6.875890997193795373e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.978812751010300985e+01,3.216489898043281528e+02,6.736164199967192623e+00,4.000000039686763209e+00,6.825890997193795329e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.979062751007820253e+01,3.216589665169781824e+02,6.736846259128230763e+00,4.000000039686763209e+00,6.775890997193795284e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.979312751005339521e+01,3.216689435694106578e+02,6.737523329847895148e+00,4.000000039686763209e+00,6.725890997193795240e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.979562751002858789e+01,3.216789209591313465e+02,6.738195411956916736e+00,4.000000039686763209e+00,6.675890997193795195e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.979812751000378057e+01,3.216888986836459026e+02,6.738862505287276150e+00,4.000000039686763209e+00,6.625890997193795151e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.980062750997897325e+01,3.216988767404599230e+02,6.739524609672199240e+00,4.000000039686763209e+00,6.575890997193795107e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.980312750995416593e+01,3.217088551270788344e+02,6.740181724946159747e+00,4.000000039686763209e+00,6.525890997193795062e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.980562750992935861e+01,3.217188338410080632e+02,6.740833850944879302e+00,4.000000039686763209e+00,6.475890997193795018e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.980812750990455129e+01,3.217288128797529794e+02,6.741480987505326539e+00,4.000000039686763209e+00,6.425890997193794973e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.981062750987974397e+01,3.217387922408187819e+02,6.742123134465717094e+00,4.000000039686763209e+00,6.375890997193794929e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.981312750985493665e+01,3.217487719217106132e+02,6.742760291665514494e+00,4.000000039686763209e+00,6.325890997193794885e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.981562750983012933e+01,3.217587519199335588e+02,6.743392458945429269e+00,4.000000039686763209e+00,6.275890997193794840e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.981812750980532201e+01,3.217687322329926474e+02,6.744019636147419838e+00,4.000000039686763209e+00,6.225890997193794796e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.982062750978051469e+01,3.217787128583927938e+02,6.744641823114691626e+00,4.000000039686763209e+00,6.175890997193794751e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.982312750975570737e+01,3.217886937936387994e+02,6.745259019691697944e+00,4.000000039686763209e+00,6.125890997193794707e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.982562750973090004e+01,3.217986750362354655e+02,6.745871225724139109e+00,4.000000039686763209e+00,6.075890997193794663e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.982812750970609272e+01,3.218086565836874797e+02,6.746478441058964215e+00,4.000000039686763209e+00,6.025890997193794618e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.983062750968128540e+01,3.218186384334994727e+02,6.747080665544369360e+00,4.000000039686763209e+00,5.975890997193794574e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.983312750965647808e+01,3.218286205831759617e+02,6.747677899029798532e+00,4.000000039686763209e+00,5.925890997193794529e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.983562750963167076e+01,3.218386030302214067e+02,6.748270141365942720e+00,4.000000039686763209e+00,5.875890997193794485e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.983812750960686344e+01,3.218485857721402112e+02,6.748857392404742583e+00,4.000000039686763209e+00,5.825890997193794441e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.984062750958205612e+01,3.218585688064366650e+02,6.749439651999384004e+00,4.000000039686763209e+00,5.775890997193794396e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.984312750955724880e+01,3.218685521306150576e+02,6.750016920004303422e+00,4.000000039686763209e+00,5.725890997193794352e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.984562750953244148e+01,3.218785357421795084e+02,6.750589196275182502e+00,4.000000039686763209e+00,5.675890997193794307e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.984812750950763416e+01,3.218885196386341363e+02,6.751156480668953463e+00,4.000000039686763209e+00,5.625890997193794263e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.985062750948282684e+01,3.218985038174829469e+02,6.751718773043793753e+00,4.000000039686763209e+00,5.575890997193794218e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.985312750945801952e+01,3.219084882762299458e+02,6.752276073259131373e+00,4.000000039686763209e+00,5.525890997193794174e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.985562750943321220e+01,3.219184730123789677e+02,6.752828381175641326e+00,4.000000039686763209e+00,5.475890997193794130e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.985812750940840488e+01,3.219284580234338478e+02,6.753375696655246507e+00,4.000000039686763209e+00,5.425890997193794085e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.986062750938359756e+01,3.219384433068983071e+02,6.753918019561117703e+00,4.000000039686763209e+00,5.375890997193794041e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.986312750935879023e+01,3.219484288602760671e+02,6.754455349757674476e+00,4.000000039686763209e+00,5.325890997193793996e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.986562750933398291e+01,3.219584146810707352e+02,6.754987687110583394e+00,4.000000039686763209e+00,5.275890997193793952e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.986812750930917559e+01,3.219684007667858054e+02,6.755515031486761579e+00,4.000000039686763209e+00,5.225890997193793908e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.987062750928436827e+01,3.219783871149248284e+02,6.756037382754372267e+00,4.000000039686763209e+00,5.175890997193793863e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.987312750925956095e+01,3.219883737229911276e+02,6.756554740782827473e+00,4.000000039686763209e+00,5.125890997193793819e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.987562750923475363e+01,3.219983605884881399e+02,6.757067105442787103e+00,4.000000039686763209e+00,5.075890997193793774e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.987812750920994631e+01,3.220083477089191319e+02,6.757574476606160729e+00,4.000000039686763209e+00,5.025890997193793730e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.988062750918513899e+01,3.220183350817872565e+02,6.758076854146105816e+00,4.000000039686763209e+00,4.975890997193793686e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.988312750916033167e+01,3.220283227045957233e+02,6.758574237937027718e+00,4.000000039686763209e+00,4.925890997193793641e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.988562750913552435e+01,3.220383105748476282e+02,6.759066627854580567e+00,4.000000039686763209e+00,4.875890997193793597e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.988812750911071703e+01,3.220482986900460105e+02,6.759554023775666387e+00,4.000000039686763209e+00,4.825890997193793552e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.989062750908590971e+01,3.220582870476938524e+02,6.760036425578436869e+00,4.000000039686763209e+00,4.775890997193793508e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.989312750906110239e+01,3.220682756452940225e+02,6.760513833142291595e+00,4.000000039686763209e+00,4.725890997193793464e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.989562750903629507e+01,3.220782644803493895e+02,6.760986246347878037e+00,4.000000039686763209e+00,4.675890997193793419e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.989812750901148775e+01,3.220882535503627651e+02,6.761453665077093333e+00,4.000000039686763209e+00,4.625890997193793375e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.990062750898668043e+01,3.220982428528368473e+02,6.761916089213082515e+00,4.000000039686763209e+00,4.575890997193793330e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.990312750896187310e+01,3.221082323852743343e+02,6.762373518640240277e+00,4.000000039686763209e+00,4.525890997193793286e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.990562750893706578e+01,3.221182221451778105e+02,6.762825953244208321e+00,4.000000039686763209e+00,4.475890997193793241e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.990812750891225846e+01,3.221282121300498602e+02,6.763273392911878901e+00,4.000000039686763209e+00,4.425890997193793197e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.991062750888745114e+01,3.221382023373930110e+02,6.763715837531391273e+00,4.000000039686763209e+00,4.375890997193793153e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.991312750886264382e+01,3.221481927647096768e+02,6.764153286992134362e+00,4.000000039686763209e+00,4.325890997193793108e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.991562750883783650e+01,3.221581834095022714e+02,6.764585741184746759e+00,4.000000039686763209e+00,4.275890997193793064e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.991812750881302918e+01,3.221681742692730950e+02,6.765013200001114058e+00,4.000000039686763209e+00,4.225890997193793019e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.992062750878822186e+01,3.221781653415244477e+02,6.765435663334371519e+00,4.000000039686763209e+00,4.175890997193792975e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.992312750876341454e+01,3.221881566237585730e+02,6.765853131078904070e+00,4.000000039686763209e+00,4.125890997193792931e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.992562750873860722e+01,3.221981481134776573e+02,6.766265603130343642e+00,4.000000039686763209e+00,4.075890997193792886e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.992812750871379990e+01,3.222081398081838302e+02,6.766673079385572720e+00,4.000000039686763209e+00,4.025890997193792842e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.993062750868899258e+01,3.222181317053791645e+02,6.767075559742722568e+00,4.000000039686763209e+00,3.975890997193792797e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.993312750866418526e+01,3.222281238025656762e+02,6.767473044101173230e+00,4.000000039686763209e+00,3.925890997193792753e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.993562750863937794e+01,3.222381160972453245e+02,6.767865532361552638e+00,4.000000039686763209e+00,3.875890997193792709e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.993812750861457062e+01,3.222481085869200683e+02,6.768253024425739284e+00,4.000000039686763209e+00,3.825890997193792664e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.994062750858976329e+01,3.222581012690918101e+02,6.768635520196860433e+00,4.000000039686763209e+00,3.775890997193792620e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.994312750856495597e+01,3.222680941412623383e+02,6.769013019579292134e+00,4.000000039686763209e+00,3.725890997193792575e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.994562750854014865e+01,3.222780872009334416e+02,6.769385522478659212e+00,4.000000039686763209e+00,3.675890997193792531e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.994812750851534133e+01,3.222880804456068518e+02,6.769753028801836159e+00,4.000000039686763209e+00,3.625890997193792487e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.995062750849053401e+01,3.222980738727842436e+02,6.770115538456946247e+00,4.000000039686763209e+00,3.575890997193792442e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.995312750846572669e+01,3.223080674799672920e+02,6.770473051353362415e+00,4.000000039686763209e+00,3.525890997193792398e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.995562750844091937e+01,3.223180612646575582e+02,6.770825567401705491e+00,4.000000039686763209e+00,3.475890997193792353e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.995812750841611205e+01,3.223280552243566035e+02,6.771173086513847750e+00,4.000000039686763209e+00,3.425890997193792309e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.996062750839130473e+01,3.223380493565659890e+02,6.771515608602908465e+00,4.000000039686763209e+00,3.375890997193792264e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.996312750836649741e+01,3.223480436587871623e+02,6.771853133583257467e+00,4.000000039686763209e+00,3.325890997193792220e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.996562750834169009e+01,3.223580381285215140e+02,6.772185661370513365e+00,4.000000039686763209e+00,3.275890997193792176e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.996812750831688277e+01,3.223680327632704348e+02,6.772513191881544437e+00,4.000000039686763209e+00,3.225890997193792131e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.997062750829207545e+01,3.223780275605352585e+02,6.772835725034467735e+00,4.000000039686763209e+00,3.175890997193792087e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.997312750826726813e+01,3.223880225178173191e+02,6.773153260748650872e+00,4.000000039686763209e+00,3.125890997193792042e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.997562750824246081e+01,3.223980176326178366e+02,6.773465798944709348e+00,4.000000039686763209e+00,3.075890997193791998e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.997812750821765349e+01,3.224080129024380881e+02,6.773773339544508332e+00,4.000000039686763209e+00,3.025890997193791954e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.998062750819284616e+01,3.224180083247792368e+02,6.774075882471162657e+00,4.000000039686763209e+00,2.975890997193791909e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.998312750816803884e+01,3.224280038971423892e+02,6.774373427649036827e+00,4.000000039686763209e+00,2.925890997193791865e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.998562750814323152e+01,3.224379996170287086e+02,6.774665975003744123e+00,4.000000039686763209e+00,2.875890997193791820e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.998812750811842420e+01,3.224479954819391878e+02,6.774953524462148380e+00,4.000000039686763209e+00,2.825890997193791776e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.999062750809361688e+01,3.224579914893749333e+02,6.775236075952362214e+00,4.000000039686763209e+00,2.775890997193791732e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.999312750806880956e+01,3.224679876368369378e+02,6.775513629403747018e+00,4.000000039686763209e+00,2.725890997193791687e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.999562750804400224e+01,3.224779839218261372e+02,6.775786184746914742e+00,4.000000039686763209e+00,2.675890997193791643e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +4.999812750801919492e+01,3.224879803418434676e+02,6.776053741913727002e+00,4.000000039686763209e+00,2.625890997193791598e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.000062750799438760e+01,3.224979768943898080e+02,6.776316300837294193e+00,4.000000039686763209e+00,2.575890997193791554e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.000312750796958028e+01,3.225079735769660374e+02,6.776573861451976377e+00,4.000000039686763209e+00,2.525890997193791510e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.000562750794477296e+01,3.225179703870729782e+02,6.776826423693384172e+00,4.000000039686763209e+00,2.475890997193791465e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.000812750791996564e+01,3.225279673222114525e+02,6.777073987498376084e+00,4.000000039686763209e+00,2.425890997193791421e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.001062750789515832e+01,3.225379643798821689e+02,6.777316552805062067e+00,4.000000039686763209e+00,2.375890997193791376e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.001312750787035100e+01,3.225479615575858929e+02,6.777554119552799961e+00,4.000000039686763209e+00,2.325890997193791332e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.001562750784554368e+01,3.225579588528233899e+02,6.777786687682198163e+00,4.000000039686763209e+00,2.275890997193791288e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.001812750782073635e+01,3.225679562630952546e+02,6.778014257135115628e+00,4.000000039686763209e+00,2.225890997193791243e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.002062750779592903e+01,3.225779537859021957e+02,6.778236827854659197e+00,4.000000039686763209e+00,2.175890997193791199e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.002312750777112171e+01,3.225879514187447512e+02,6.778454399785186268e+00,4.000000039686763209e+00,2.125890997193791154e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.002562750774631439e+01,3.225979491591235728e+02,6.778666972872303909e+00,4.000000039686763209e+00,2.075890997193791110e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.002812750772150707e+01,3.226079470045392554e+02,6.778874547062867961e+00,4.000000039686763209e+00,2.025890997193791065e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.003062750769669975e+01,3.226179449524922802e+02,6.779077122304985714e+00,4.000000039686763209e+00,1.975890997193791021e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.003312750767189243e+01,3.226279430004831852e+02,6.779274698548014122e+00,4.000000039686763209e+00,1.925890997193790977e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.003562750764708511e+01,3.226379411460124516e+02,6.779467275742558030e+00,4.000000039686763209e+00,1.875890997193790932e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.003812750762227779e+01,3.226479393865805037e+02,6.779654853840473727e+00,4.000000039686763209e+00,1.825890997193790888e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.004062750759747047e+01,3.226579377196878227e+02,6.779837432794866281e+00,4.000000039686763209e+00,1.775890997193790843e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.004312750757266315e+01,3.226679361428348329e+02,6.780015012560090426e+00,4.000000039686763209e+00,1.725890997193790799e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.004562750754785583e+01,3.226779346535219588e+02,6.780187593091752341e+00,4.000000039686763209e+00,1.675890997193790755e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.004812750752304851e+01,3.226879332492495109e+02,6.780355174346706093e+00,4.000000039686763209e+00,1.625890997193790710e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.005062750749824119e+01,3.226979319275178568e+02,6.780517756283057196e+00,4.000000039686763209e+00,1.575890997193790666e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.005312750747343387e+01,3.227079306858273640e+02,6.780675338860159940e+00,4.000000039686763209e+00,1.525890997193790621e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.005562750744862655e+01,3.227179295216782862e+02,6.780827922038618283e+00,4.000000039686763209e+00,1.475890997193790577e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.005812750742381922e+01,3.227279284325709341e+02,6.780975505780286738e+00,4.000000039686763209e+00,1.425890997193790533e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.006062750739901190e+01,3.227379274160056184e+02,6.781118090048268598e+00,4.000000039686763209e+00,1.375890997193790488e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.006312750737420458e+01,3.227479264694825360e+02,6.781255674806918599e+00,4.000000039686763209e+00,1.325890997193790444e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.006562750734939726e+01,3.227579255905019409e+02,6.781388260021840253e+00,4.000000039686763209e+00,1.275890997193790399e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.006812750732458994e+01,3.227679247765640866e+02,6.781515845659887631e+00,4.000000039686763209e+00,1.225890997193790355e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.007062750729978262e+01,3.227779240251691135e+02,6.781638431689163582e+00,4.000000039686763209e+00,1.175890997193790311e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.007312750727497530e+01,3.227879233338172753e+02,6.781756018079022397e+00,4.000000039686763209e+00,1.125890997193790266e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.007562750725016798e+01,3.227979227000087121e+02,6.781868604800067146e+00,4.000000039686763209e+00,1.075890997193790222e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.007812750722536066e+01,3.228079221212435641e+02,6.781976191824151456e+00,4.000000039686763209e+00,1.025890997193790177e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.008062750720055334e+01,3.228179215950220282e+02,6.782078779124377732e+00,4.000000039686763209e+00,9.758909971937901329e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.008312750717574602e+01,3.228279211188441877e+02,6.782176366675099821e+00,4.000000039686763209e+00,9.258909971937900885e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.008562750715093870e+01,3.228379206902101828e+02,6.782268954451921239e+00,4.000000039686763209e+00,8.758909971937900441e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.008812750712613138e+01,3.228479203066200967e+02,6.782356542431694280e+00,4.000000039686763209e+00,8.258909971937899996e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.009062750710132406e+01,3.228579199655740695e+02,6.782439130592521792e+00,4.000000039686763209e+00,7.758909971937899552e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.009312750707651674e+01,3.228679196645721845e+02,6.782516718913757181e+00,4.000000039686763209e+00,7.258909971937899108e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.009562750705170942e+01,3.228779194011144682e+02,6.782589307376003518e+00,4.000000039686763209e+00,6.758909971937898664e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.009812750702690209e+01,3.228879191727010038e+02,6.782656895961113541e+00,4.000000039686763209e+00,6.258909971937898220e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.010062750700209477e+01,3.228979189768318747e+02,6.782719484652189657e+00,4.000000039686763209e+00,5.758909971937897776e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.010312750697728745e+01,3.229079188110071073e+02,6.782777073433585713e+00,4.000000039686763209e+00,5.258909971937897332e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.010562750695248013e+01,3.229179186727267279e+02,6.782829662290903450e+00,4.000000039686763209e+00,4.758909971937896888e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.010812750692767281e+01,3.229279185594908199e+02,6.782877251210996050e+00,4.000000039686763209e+00,4.258909971937896444e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.011062750690286549e+01,3.229379184687994098e+02,6.782919840181966364e+00,4.000000039686763209e+00,3.758909971937896433e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.011312750687805817e+01,3.229479183981524670e+02,6.782957429193166909e+00,4.000000039686763209e+00,3.258909971937896423e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.011562750685325085e+01,3.229579183450500182e+02,6.782990018235200758e+00,4.000000039686763209e+00,2.758909971937896412e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.011812750682844353e+01,3.229679183069921464e+02,6.783017607299920648e+00,4.000000039686763209e+00,2.258909971937896402e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.012062750680363621e+01,3.229779182814787646e+02,6.783040196380428988e+00,4.000000039686763209e+00,1.758909971937896392e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.012312750677882889e+01,3.229879182660099559e+02,6.783057785471078738e+00,4.000000039686763209e+00,1.258909971937896381e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.012562750675402157e+01,3.229979182580856900e+02,6.783070374567472527e+00,4.000000039686763209e+00,7.589099719378963708e-04,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.012812750672921425e+01,3.230079182552059933e+02,6.783077963666463539e+00,4.000000039686763209e+00,2.589099719378963604e-04,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.013062750670440693e+01,3.230179182548708354e+02,6.783080552766153737e+00,4.000000039686763209e+00,-2.410900280621036500e-04,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.013312750667959961e+01,3.230279182545801859e+02,6.783078141865896526e+00,4.000000039686763209e+00,-7.410900280621036604e-04,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.013562750665479228e+01,3.230379182518341281e+02,6.783070730966294093e+00,4.000000039686763209e+00,-1.241090028062103671e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.013812750662998496e+01,3.230479182441326316e+02,6.783058320069199176e+00,4.000000039686763209e+00,-1.741090028062103681e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.014062750660517764e+01,3.230579182289756659e+02,6.783040909177715072e+00,4.000000039686763209e+00,-2.241090028062103692e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.014312750658037032e+01,3.230679182038632575e+02,6.783018498296193854e+00,4.000000039686763209e+00,-2.741090028062103702e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.014562750655556300e+01,3.230779181662954329e+02,6.782991087430239041e+00,4.000000039686763209e+00,-3.241090028062103712e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.014812750653075568e+01,3.230879181137721616e+02,6.782958676586702929e+00,4.000000039686763209e+00,-3.741090028062103723e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.015062750650594836e+01,3.230979180437934701e+02,6.782921265773687480e+00,4.000000039686763209e+00,-4.241090028062104167e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.015312750648114104e+01,3.231079179538593849e+02,6.782878855000546103e+00,4.000000039686763209e+00,-4.741090028062104611e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.015562750645633372e+01,3.231179178414699322e+02,6.782831444277881872e+00,4.000000039686763209e+00,-5.241090028062105055e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.015812750643152640e+01,3.231279177041251387e+02,6.782779033617546638e+00,4.000000039686763209e+00,-5.741090028062105499e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.016062750640671908e+01,3.231379175393250307e+02,6.782721623032643699e+00,4.000000039686763209e+00,-6.241090028062105943e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.016312750638191176e+01,3.231479173445696347e+02,6.782659212537526017e+00,4.000000039686763209e+00,-6.741090028062106387e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.016562750635710444e+01,3.231579171173590339e+02,6.782591802147795335e+00,4.000000039686763209e+00,-7.241090028062106831e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.016812750633229712e+01,3.231679168551932548e+02,6.782519391880304838e+00,4.000000039686763209e+00,-7.741090028062107276e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.017062750630748980e+01,3.231779165555723807e+02,6.782441981753156490e+00,4.000000039686763209e+00,-8.241090028062107720e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.017312750628268248e+01,3.231879162159964949e+02,6.782359571785702812e+00,4.000000039686763209e+00,-8.741090028062108164e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.017562750625787515e+01,3.231979158339656806e+02,6.782272161998546878e+00,4.000000039686763209e+00,-9.241090028062108608e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.017812750623306783e+01,3.232079154069800211e+02,6.782179752413541429e+00,4.000000039686763209e+00,-9.741090028062109052e-03,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.018062750620826051e+01,3.232179149325395997e+02,6.782082343053787987e+00,4.000000039686763209e+00,-1.024109002806210950e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.018312750618345319e+01,3.232279144081445565e+02,6.781979933943639516e+00,4.000000039686763209e+00,-1.074109002806210994e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.018562750615864587e+01,3.232379138312950317e+02,6.781872525108697758e+00,4.000000039686763209e+00,-1.124109002806211038e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.018812750613383855e+01,3.232479131994911654e+02,6.781760116575815012e+00,4.000000039686763209e+00,-1.174109002806211083e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.019062750610903123e+01,3.232579125102330977e+02,6.781642708373094131e+00,4.000000039686763209e+00,-1.224109002806211127e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.019312750608422391e+01,3.232679117610210255e+02,6.781520300529885859e+00,4.000000039686763209e+00,-1.274109002806211172e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.019562750605941659e+01,3.232779109493551459e+02,6.781392893076793271e+00,4.000000039686763209e+00,-1.324109002806211216e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.019812750603460927e+01,3.232879100727356558e+02,6.781260486045668223e+00,4.000000039686763209e+00,-1.374109002806211260e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.020062750600980195e+01,3.232979091286627522e+02,6.781123079469612236e+00,4.000000039686763209e+00,-1.424109002806211305e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.020312750598499463e+01,3.233079081146366889e+02,6.780980673382976498e+00,4.000000039686763209e+00,-1.474109002806211349e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.020562750596018731e+01,3.233179070281576628e+02,6.780833267821362753e+00,4.000000039686763209e+00,-1.524109002806211394e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.020812750593537999e+01,3.233279058667260415e+02,6.780680862821622412e+00,4.000000039686763209e+00,-1.574109002806211438e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.021062750591057267e+01,3.233379046278420219e+02,6.780523458421856553e+00,4.000000039686763209e+00,-1.624109002806211483e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.021312750588576534e+01,3.233479033090059716e+02,6.780361054661416809e+00,4.000000039686763209e+00,-1.674109002806211527e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.021562750586095802e+01,3.233579019077182011e+02,6.780193651580903591e+00,4.000000039686763209e+00,-1.724109002806211571e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.021812750583615070e+01,3.233679004214790780e+02,6.780021249222168755e+00,4.000000039686763209e+00,-1.774109002806211616e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.022062750581134338e+01,3.233778988477889698e+02,6.779843847628312048e+00,4.000000039686763209e+00,-1.824109002806211660e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.022312750578653606e+01,3.233878971841483008e+02,6.779661446843683770e+00,4.000000039686763209e+00,-1.874109002806211705e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.022562750576172874e+01,3.233978954280574385e+02,6.779474046913883889e+00,4.000000039686763209e+00,-1.924109002806211749e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.022812750573692142e+01,3.234078935770168073e+02,6.779281647885762929e+00,4.000000039686763209e+00,-1.974109002806211793e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.023062750571211410e+01,3.234178916285268883e+02,6.779084249807420193e+00,4.000000039686763209e+00,-2.024109002806211838e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.023312750568730678e+01,3.234278895800882196e+02,6.778881852728205537e+00,4.000000039686763209e+00,-2.074109002806211882e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.023562750566249946e+01,3.234378874292012256e+02,6.778674456698718487e+00,4.000000039686763209e+00,-2.124109002806211927e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.023812750563769214e+01,3.234478851733665010e+02,6.778462061770807345e+00,4.000000039686763209e+00,-2.174109002806211971e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.024062750561288482e+01,3.234578828100846408e+02,6.778244667997570971e+00,4.000000039686763209e+00,-2.224109002806212015e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.024312750558807750e+01,3.234678803368561830e+02,6.778022275433358779e+00,4.000000039686763209e+00,-2.274109002806212060e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.024562750556327018e+01,3.234778777511817225e+02,6.777794884133768072e+00,4.000000039686763209e+00,-2.324109002806212104e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.024812750553846286e+01,3.234878750505619678e+02,6.777562494155646711e+00,4.000000039686763209e+00,-2.374109002806212149e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.025062750551365554e+01,3.234978722324975706e+02,6.777325105557092222e+00,4.000000039686763209e+00,-2.424109002806212193e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.025312750548884821e+01,3.235078692944892396e+02,6.777082718397451799e+00,4.000000039686763209e+00,-2.474109002806212237e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.025562750546404089e+01,3.235178662340376832e+02,6.776835332737322304e+00,4.000000039686763209e+00,-2.524109002806212282e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.025812750543923357e+01,3.235278630486436668e+02,6.776582948638549375e+00,4.000000039686763209e+00,-2.574109002806212326e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.026062750541442625e+01,3.235378597358080128e+02,6.776325566164230096e+00,4.000000039686763209e+00,-2.624109002806212371e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.026312750538961893e+01,3.235478562930315434e+02,6.776063185378709441e+00,4.000000039686763209e+00,-2.674109002806212415e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.026562750536481161e+01,3.235578527178151376e+02,6.775795806347582939e+00,4.000000039686763209e+00,-2.724109002806212460e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.026812750534000429e+01,3.235678490076596745e+02,6.775523429137695786e+00,4.000000039686763209e+00,-2.774109002806212504e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.027062750531519697e+01,3.235778451600660333e+02,6.775246053817141956e+00,4.000000039686763209e+00,-2.824109002806212548e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.027312750529038965e+01,3.235878411725352635e+02,6.774963680455265091e+00,4.000000039686763209e+00,-2.874109002806212593e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.027562750526558233e+01,3.235978370425683011e+02,6.774676309122658502e+00,4.000000039686763209e+00,-2.924109002806212637e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.027812750524077501e+01,3.236078327676661957e+02,6.774383939891164275e+00,4.000000039686763209e+00,-2.974109002806212682e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.028062750521596769e+01,3.236178283453299969e+02,6.774086572833875941e+00,4.000000039686763209e+00,-3.024109002806212726e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.028312750519116037e+01,3.236278237730608112e+02,6.773784208025134923e+00,4.000000039686763209e+00,-3.074109002806212770e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.028562750516635305e+01,3.236378190483598019e+02,6.773476845540532310e+00,4.000000039686763209e+00,-3.124109002806212815e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.028812750514154573e+01,3.236478141687281891e+02,6.773164485456908857e+00,4.000000039686763209e+00,-3.174109002806212859e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.029062750511673840e+01,3.236578091316671362e+02,6.772847127852354099e+00,4.000000039686763209e+00,-3.224109002806212904e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.029312750509193108e+01,3.236678039346779201e+02,6.772524772806208126e+00,4.000000039686763209e+00,-3.274109002806212948e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.029562750506712376e+01,3.236777985752618179e+02,6.772197420399058920e+00,4.000000039686763209e+00,-3.324109002806212992e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.029812750504231644e+01,3.236877930509202201e+02,6.771865070712745016e+00,4.000000039686763209e+00,-3.374109002806213037e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.030062750501750912e+01,3.236977873591544608e+02,6.771527723830353729e+00,4.000000039686763209e+00,-3.424109002806213081e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.030312750499270180e+01,3.237077814974659873e+02,6.771185379836222040e+00,4.000000039686763209e+00,-3.474109002806213126e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.030562750496789448e+01,3.237177754633562472e+02,6.770838038815935711e+00,4.000000039686763209e+00,-3.524109002806213170e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.030812750494308716e+01,3.237277692543267449e+02,6.770485700856330169e+00,4.000000039686763209e+00,-3.574109002806213214e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.031062750491827984e+01,3.237377628678790416e+02,6.770128366045490509e+00,4.000000039686763209e+00,-3.624109002806213259e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.031312750489347252e+01,3.237477563015147553e+02,6.769766034472749716e+00,4.000000039686763209e+00,-3.674109002806213303e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.031562750486866520e+01,3.237577495527355040e+02,6.769398706228690443e+00,4.000000039686763209e+00,-3.724109002806213348e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.031812750484385788e+01,3.237677426190429628e+02,6.769026381405145010e+00,4.000000039686763209e+00,-3.774109002806213392e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.032062750481905056e+01,3.237777354979389202e+02,6.768649060095194514e+00,4.000000039686763209e+00,-3.824109002806213436e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.032312750479424324e+01,3.237877281869251078e+02,6.768266742393169721e+00,4.000000039686763209e+00,-3.874109002806213481e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.032562750476943592e+01,3.237977206835033712e+02,6.767879428394649288e+00,4.000000039686763209e+00,-3.924109002806213525e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.032812750474462860e+01,3.238077129851755558e+02,6.767487118196462426e+00,4.000000039686763209e+00,-3.974109002806213570e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.033062750471982127e+01,3.238177050894436206e+02,6.767089811896686236e+00,4.000000039686763209e+00,-4.024109002806213614e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.033312750469501395e+01,3.238276969938095249e+02,6.766687509594647487e+00,4.000000039686763209e+00,-4.074109002806213659e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.033562750467020663e+01,3.238376886957753413e+02,6.766280211390921728e+00,4.000000039686763209e+00,-4.124109002806213703e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.033812750464539931e+01,3.238476801928430859e+02,6.765867917387333286e+00,4.000000039686763209e+00,-4.174109002806213747e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.034062750462059199e+01,3.238576714825148883e+02,6.765450627686956153e+00,4.000000039686763209e+00,-4.224109002806213792e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.034312750459578467e+01,3.238676625622929350e+02,6.765028342394112215e+00,4.000000039686763209e+00,-4.274109002806213836e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.034562750457097735e+01,3.238776534296794694e+02,6.764601061614373023e+00,4.000000039686763209e+00,-4.324109002806213881e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.034812750454617003e+01,3.238876440821767346e+02,6.764168785454558908e+00,4.000000039686763209e+00,-4.374109002806213925e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.035062750452136271e+01,3.238976345172871447e+02,6.763731514022738978e+00,4.000000039686763209e+00,-4.424109002806213969e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.035312750449655539e+01,3.239076247325129998e+02,6.763289247428231121e+00,4.000000039686763209e+00,-4.474109002806214014e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.035562750447174807e+01,3.239176147253568274e+02,6.762841985781601117e+00,4.000000039686763209e+00,-4.524109002806214058e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.035812750444694075e+01,3.239276044933210983e+02,6.762389729194665300e+00,4.000000039686763209e+00,-4.574109002806214103e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.036062750442213343e+01,3.239375940339083400e+02,6.761932477780487893e+00,4.000000039686763209e+00,-4.624109002806214147e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.036312750439732611e+01,3.239475833446211936e+02,6.761470231653381013e+00,4.000000039686763209e+00,-4.674109002806214191e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.036562750437251879e+01,3.239575724229623575e+02,6.761002990928906442e+00,4.000000039686763209e+00,-4.724109002806214236e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.036812750434771147e+01,3.239675612664345294e+02,6.760530755723874741e+00,4.000000039686763209e+00,-4.774109002806214280e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.037062750432290414e+01,3.239775498725404645e+02,6.760053526156344361e+00,4.000000039686763209e+00,-4.824109002806214325e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.037312750429809682e+01,3.239875382387830882e+02,6.759571302345623423e+00,4.000000039686763209e+00,-4.874109002806214369e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.037562750427328950e+01,3.239975263626652691e+02,6.759084084412267046e+00,4.000000039686763209e+00,-4.924109002806214413e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.037812750424848218e+01,3.240075142416899325e+02,6.758591872478080020e+00,4.000000039686763209e+00,-4.974109002806214458e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.038062750422367486e+01,3.240175018733601746e+02,6.758094666666115025e+00,4.000000039686763209e+00,-5.024109002806214502e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.038312750419886754e+01,3.240274892551790913e+02,6.757592467100673517e+00,4.000000039686763209e+00,-5.074109002806214547e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.038562750417406022e+01,3.240374763846497785e+02,6.757085273907305734e+00,4.000000039686763209e+00,-5.124109002806214591e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.038812750414925290e+01,3.240474632592755029e+02,6.756573087212809803e+00,4.000000039686763209e+00,-5.174109002806214636e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.039062750412444558e+01,3.240574498765595308e+02,6.756055907145232631e+00,4.000000039686763209e+00,-5.224109002806214680e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.039312750409963826e+01,3.240674362340051857e+02,6.755533733833869015e+00,4.000000039686763209e+00,-5.274109002806214724e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.039562750407483094e+01,3.240774223291159046e+02,6.755006567409261642e+00,4.000000039686763209e+00,-5.324109002806214769e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.039812750405002362e+01,3.240874081593951814e+02,6.754474408003202868e+00,4.000000039686763209e+00,-5.374109002806214813e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.040062750402521630e+01,3.240973937223465668e+02,6.753937255748732937e+00,4.000000039686763209e+00,-5.424109002806214858e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.040312750400040898e+01,3.241073790154736116e+02,6.753395110780139099e+00,4.000000039686763209e+00,-5.474109002806214902e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.040562750397560166e+01,3.241173640362800370e+02,6.752847973232957379e+00,4.000000039686763209e+00,-5.524109002806214946e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.040812750395079433e+01,3.241273487822695643e+02,6.752295843243973472e+00,4.000000039686763209e+00,-5.574109002806214991e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.041062750392598701e+01,3.241373332509460283e+02,6.751738720951218298e+00,4.000000039686763209e+00,-5.624109002806215035e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.041312750390117969e+01,3.241473174398132642e+02,6.751176606493973331e+00,4.000000039686763209e+00,-5.674109002806215080e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.041562750387637237e+01,3.241573013463752773e+02,6.750609500012767050e+00,4.000000039686763209e+00,-5.724109002806215124e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.041812750385156505e+01,3.241672849681360731e+02,6.750037401649376712e+00,4.000000039686763209e+00,-5.774109002806215168e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.042062750382675773e+01,3.241772683025997708e+02,6.749460311546825686e+00,4.000000039686763209e+00,-5.824109002806215213e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.042312750380195041e+01,3.241872513472704895e+02,6.748878229849387012e+00,4.000000039686763209e+00,-5.874109002806215257e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.042562750377714309e+01,3.241972340996524622e+02,6.748291156702581617e+00,4.000000039686763209e+00,-5.924109002806215302e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.042812750375233577e+01,3.242072165572500353e+02,6.747699092253177433e+00,4.000000039686763209e+00,-5.974109002806215346e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.043062750372752845e+01,3.242171987175676122e+02,6.747102036649190282e+00,4.000000039686763209e+00,-6.024109002806215390e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.043312750370272113e+01,3.242271805781096532e+02,6.746499990039883876e+00,4.000000039686763209e+00,-6.074109002806215435e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.043562750367791381e+01,3.242371621363806184e+02,6.745892952575770707e+00,4.000000039686763209e+00,-6.124109002806215479e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.043812750365310649e+01,3.242471433898851956e+02,6.745280924408609380e+00,4.000000039686763209e+00,-6.174109002806215524e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.044062750362829917e+01,3.242571243361280153e+02,6.744663905691407280e+00,4.000000039686763209e+00,-6.224109002806215568e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.044312750360349185e+01,3.242671049726138790e+02,6.744041896578418793e+00,4.000000039686763209e+00,-6.274109002806214919e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.044562750357868453e+01,3.242770852968476447e+02,6.743414897225147087e+00,4.000000039686763209e+00,-6.324109002806214963e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.044812750355387720e+01,3.242870653063342274e+02,6.742782907788340552e+00,4.000000039686763209e+00,-6.374109002806215007e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.045062750352906988e+01,3.242970449985785990e+02,6.742145928425998136e+00,4.000000039686763209e+00,-6.424109002806215052e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.045312750350426256e+01,3.243070243710858449e+02,6.741503959297363124e+00,4.000000039686763209e+00,-6.474109002806215096e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.045562750347945524e+01,3.243170034213611075e+02,6.740857000562929358e+00,4.000000039686763209e+00,-6.524109002806215141e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.045812750345464792e+01,3.243269821469096428e+02,6.740205052384435014e+00,4.000000039686763209e+00,-6.574109002806215185e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.046062750342984060e+01,3.243369605452367637e+02,6.739548114924867939e+00,4.000000039686763209e+00,-6.624109002806215230e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.046312750340503328e+01,3.243469386138478399e+02,6.738886188348462092e+00,4.000000039686763209e+00,-6.674109002806215274e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.046562750338022596e+01,3.243569163502484116e+02,6.738219272820700212e+00,4.000000039686763209e+00,-6.724109002806215318e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.046812750335541864e+01,3.243668937519440192e+02,6.737547368508310264e+00,4.000000039686763209e+00,-6.774109002806215363e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.047062750333061132e+01,3.243768708164402597e+02,6.736870475579268103e+00,4.000000039686763209e+00,-6.824109002806215407e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.047312750330580400e+01,3.243868475412429575e+02,6.736188594202797475e+00,4.000000039686763209e+00,-6.874109002806215452e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.047562750328099668e+01,3.243968239238578803e+02,6.735501724549368241e+00,4.000000039686763209e+00,-6.924109002806215496e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.047812750325618936e+01,3.244067999617909095e+02,6.734809866790698152e+00,4.000000039686763209e+00,-6.974109002806215540e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.048062750323138204e+01,3.244167756525480968e+02,6.734113021099751961e+00,4.000000039686763209e+00,-7.024109002806215585e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.048312750320657472e+01,3.244267509936354941e+02,6.733411187650740537e+00,4.000000039686763209e+00,-7.074109002806215629e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.048562750318176739e+01,3.244367259825592669e+02,6.732704366619122638e+00,4.000000039686763209e+00,-7.124109002806215674e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.048812750315696007e+01,3.244467006168256376e+02,6.731992558181603137e+00,4.000000039686763209e+00,-7.174109002806215718e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.049062750313215275e+01,3.244566748939409990e+02,6.731275762516133909e+00,4.000000039686763209e+00,-7.224109002806215762e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.049312750310734543e+01,3.244666488114117442e+02,6.730553979801914721e+00,4.000000039686763209e+00,-7.274109002806215807e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.049562750308253811e+01,3.244766223667444365e+02,6.729827210219390565e+00,4.000000039686763209e+00,-7.324109002806215851e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.049812750305773079e+01,3.244865955574456393e+02,6.729095453950254324e+00,4.000000039686763209e+00,-7.374109002806215896e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.050062750303292347e+01,3.244965683810220867e+02,6.728358711177444107e+00,4.000000039686763209e+00,-7.424109002806215940e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.050312750300811615e+01,3.245065408349805693e+02,6.727616982085146802e+00,4.000000039686763209e+00,-7.474109002806215984e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.050562750298330883e+01,3.245165129168279350e+02,6.726870266858793634e+00,4.000000039686763209e+00,-7.524109002806216029e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.050812750295850151e+01,3.245264846240712018e+02,6.726118565685064610e+00,4.000000039686763209e+00,-7.574109002806216073e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.051062750293369419e+01,3.245364559542174447e+02,6.725361878751884070e+00,4.000000039686763209e+00,-7.624109002806216118e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.051312750290888687e+01,3.245464269047737957e+02,6.724600206248424250e+00,4.000000039686763209e+00,-7.674109002806216162e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.051562750288407955e+01,3.245563974732475572e+02,6.723833548365102608e+00,4.000000039686763209e+00,-7.724109002806216207e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.051812750285927223e+01,3.245663676571460883e+02,6.723061905293584495e+00,4.000000039686763209e+00,-7.774109002806216251e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.052062750283446491e+01,3.245763374539768051e+02,6.722285277226779598e+00,4.000000039686763209e+00,-7.824109002806216295e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.052312750280965759e+01,3.245863068612472944e+02,6.721503664358845498e+00,4.000000039686763209e+00,-7.874109002806216340e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.052562750278485026e+01,3.245962758764651994e+02,6.720717066885185886e+00,4.000000039686763209e+00,-7.924109002806216384e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.052812750276004294e+01,3.246062444971382206e+02,6.719925485002449683e+00,4.000000039686763209e+00,-7.974109002806216429e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.053062750273523562e+01,3.246162127207742287e+02,6.719128918908531922e+00,4.000000039686763209e+00,-8.024109002806216473e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.053312750271042830e+01,3.246261805448812083e+02,6.718327368802574640e+00,4.000000039686763209e+00,-8.074109002806216517e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.053562750268562098e+01,3.246361479669671439e+02,6.717520834884965986e+00,4.000000039686763209e+00,-8.124109002806216562e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.053812750266081366e+01,3.246461149845402474e+02,6.716709317357338449e+00,4.000000039686763209e+00,-8.174109002806216606e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.054062750263600634e+01,3.246560815951087307e+02,6.715892816422571521e+00,4.000000039686763209e+00,-8.224109002806216651e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.054312750261119902e+01,3.246660477961809192e+02,6.715071332284790806e+00,4.000000039686763209e+00,-8.274109002806216695e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.054562750258639170e+01,3.246760135852653093e+02,6.714244865149367136e+00,4.000000039686763209e+00,-8.324109002806216739e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.054812750256158438e+01,3.246859789598703969e+02,6.713413415222917457e+00,4.000000039686763209e+00,-8.374109002806216784e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.055062750253677706e+01,3.246959439175048487e+02,6.712576982713303941e+00,4.000000039686763209e+00,-8.424109002806216828e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.055312750251196974e+01,3.247059084556774451e+02,6.711735567829634874e+00,4.000000039686763209e+00,-8.474109002806216873e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.055562750248716242e+01,3.247158725718970800e+02,6.710889170782263768e+00,4.000000039686763209e+00,-8.524109002806216917e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.055812750246235510e+01,3.247258362636727043e+02,6.710037791782790251e+00,4.000000039686763209e+00,-8.574109002806216961e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.056062750243754778e+01,3.247357995285133825e+02,6.709181431044059174e+00,4.000000039686763209e+00,-8.624109002806217006e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.056312750241274045e+01,3.247457623639282929e+02,6.708320088780159729e+00,4.000000039686763209e+00,-8.674109002806217050e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.056562750238793313e+01,3.247557247674267273e+02,6.707453765206428109e+00,4.000000039686763209e+00,-8.724109002806217095e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.056812750236312581e+01,3.247656867365180915e+02,6.706582460539445734e+00,4.000000039686763209e+00,-8.774109002806217139e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.057062750233831849e+01,3.247756482687119046e+02,6.705706174997038360e+00,4.000000039686763209e+00,-8.824109002806217184e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.057312750231351117e+01,3.247856093615177429e+02,6.704824908798276972e+00,4.000000039686763209e+00,-8.874109002806217228e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.057562750228870385e+01,3.247955700124454097e+02,6.703938662163478668e+00,4.000000039686763209e+00,-8.924109002806217272e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.057812750226389653e+01,3.248055302190046518e+02,6.703047435314204883e+00,4.000000039686763209e+00,-8.974109002806217317e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.058062750223908921e+01,3.248154899787055001e+02,6.702151228473262279e+00,4.000000039686763209e+00,-9.024109002806217361e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.058312750221428189e+01,3.248254492890579286e+02,6.701250041864702744e+00,4.000000039686763209e+00,-9.074109002806217406e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.058562750218947457e+01,3.248354081475721955e+02,6.700343875713822506e+00,4.000000039686763209e+00,-9.124109002806217450e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.058812750216466725e+01,3.248453665517585591e+02,6.699432730247163903e+00,4.000000039686763209e+00,-9.174109002806217494e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.059062750213985993e+01,3.248553244991273914e+02,6.698516605692512726e+00,4.000000039686763209e+00,-9.224109002806217539e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.059312750211505261e+01,3.248652819871892348e+02,6.697595502278899993e+00,4.000000039686763209e+00,-9.274109002806217583e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.059562750209024529e+01,3.248752390134546886e+02,6.696669420236601944e+00,4.000000039686763209e+00,-9.324109002806217628e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.059812750206543797e+01,3.248851955754345227e+02,6.695738359797138273e+00,4.000000039686763209e+00,-9.374109002806217672e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.060062750204063065e+01,3.248951516706395637e+02,6.694802321193274786e+00,4.000000039686763209e+00,-9.424109002806217716e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.060312750201582332e+01,3.249051072965808089e+02,6.693861304659020739e+00,4.000000039686763209e+00,-9.474109002806217761e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.060562750199101600e+01,3.249150624507693692e+02,6.692915310429630615e+00,4.000000039686763209e+00,-9.524109002806217805e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.060812750196620868e+01,3.249250171307164123e+02,6.691964338741603235e+00,4.000000039686763209e+00,-9.574109002806217850e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.061062750194140136e+01,3.249349713339333334e+02,6.691008389832680869e+00,4.000000039686763209e+00,-9.624109002806217894e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.061312750191659404e+01,3.249449250579315276e+02,6.690047463941851014e+00,4.000000039686763209e+00,-9.674109002806217938e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.061562750189178672e+01,3.249548783002225605e+02,6.689081561309345503e+00,4.000000039686763209e+00,-9.724109002806217983e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.061812750186697940e+01,3.249648310583181683e+02,6.688110682176639621e+00,4.000000039686763209e+00,-9.774109002806218027e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.062062750184217208e+01,3.249747833297301440e+02,6.687134826786452990e+00,4.000000039686763209e+00,-9.824109002806218072e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.062312750181736476e+01,3.249847351119703944e+02,6.686153995382749571e+00,4.000000039686763209e+00,-9.874109002806218116e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.062562750179255744e+01,3.249946864025509967e+02,6.685168188210737661e+00,4.000000039686763209e+00,-9.924109002806218160e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.062812750176775012e+01,3.250046371989841418e+02,6.684177405516868120e+00,4.000000039686763209e+00,-9.974109002806218205e-02,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.063062750174294280e+01,3.250145874987820775e+02,6.683181647548837923e+00,4.000000039686763209e+00,-1.002410900280621825e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.063312750171813548e+01,3.250245372994572790e+02,6.682180914555585716e+00,4.000000039686763209e+00,-1.007410900280621829e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.063562750169332816e+01,3.250344865985222782e+02,6.681175206787294485e+00,4.000000039686763209e+00,-1.012410900280621834e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.063812750166852084e+01,3.250444353934897777e+02,6.680164524495391554e+00,4.000000039686763209e+00,-1.017410900280621838e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.064062750164371352e+01,3.250543836818725367e+02,6.679148867932547695e+00,4.000000039686763209e+00,-1.022410900280621843e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.064312750161890619e+01,3.250643314611834853e+02,6.678128237352676244e+00,4.000000039686763209e+00,-1.027410900280621847e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.064562750159409887e+01,3.250742787289357238e+02,6.677102633010935762e+00,4.000000039686763209e+00,-1.032410900280621852e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.064812750156929155e+01,3.250842254826423527e+02,6.676072055163726482e+00,4.000000039686763209e+00,-1.037410900280621856e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.065062750154448423e+01,3.250941717198167566e+02,6.675036504068693866e+00,4.000000039686763209e+00,-1.042410900280621860e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.065312750151967691e+01,3.251041174379723770e+02,6.673995979984725047e+00,4.000000039686763209e+00,-1.047410900280621865e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.065562750149486959e+01,3.251140626346227691e+02,6.672950483171950609e+00,4.000000039686763209e+00,-1.052410900280621869e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.065812750147006227e+01,3.251240073072816017e+02,6.671900013891745473e+00,4.000000039686763209e+00,-1.057410900280621874e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.066062750144525495e+01,3.251339514534627142e+02,6.670844572406727124e+00,4.000000039686763209e+00,-1.062410900280621878e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.066312750142044763e+01,3.251438950706801165e+02,6.669784158980755606e+00,4.000000039686763209e+00,-1.067410900280621883e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.066562750139564031e+01,3.251538381564478755e+02,6.668718773878934414e+00,4.000000039686763209e+00,-1.072410900280621887e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.066812750137083299e+01,3.251637807082802283e+02,6.667648417367609603e+00,4.000000039686763209e+00,-1.077410900280621892e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.067062750134602567e+01,3.251737227236915260e+02,6.666573089714369793e+00,4.000000039686763209e+00,-1.082410900280621896e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.067312750132121835e+01,3.251836642001962332e+02,6.665492791188047939e+00,4.000000039686763209e+00,-1.087410900280621900e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.067562750129641103e+01,3.251936051353090420e+02,6.664407522058717781e+00,4.000000039686763209e+00,-1.092410900280621905e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.067812750127160371e+01,3.252035455265447013e+02,6.663317282597697400e+00,4.000000039686763209e+00,-1.097410900280621909e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.068062750124679638e+01,3.252134853714180736e+02,6.662222073077545659e+00,4.000000039686763209e+00,-1.102410900280621914e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.068312750122198906e+01,3.252234246674442488e+02,6.661121893772065761e+00,4.000000039686763209e+00,-1.107410900280621918e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.068562750119718174e+01,3.252333634121383739e+02,6.660016744956301693e+00,4.000000039686763209e+00,-1.112410900280621923e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.068812750117237442e+01,3.252433016030157660e+02,6.658906626906541781e+00,4.000000039686763209e+00,-1.117410900280621927e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.069062750114756710e+01,3.252532392375919130e+02,6.657791539900315136e+00,4.000000039686763209e+00,-1.122410900280621932e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.069312750112275978e+01,3.252631763133823597e+02,6.656671484216393431e+00,4.000000039686763209e+00,-1.127410900280621936e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.069562750109795246e+01,3.252731128279028212e+02,6.655546460134790010e+00,4.000000039686763209e+00,-1.132410900280621940e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.069812750107314514e+01,3.252830487786692402e+02,6.654416467936761670e+00,4.000000039686763209e+00,-1.137410900280621945e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.070062750104833782e+01,3.252929841631975592e+02,6.653281507904805991e+00,4.000000039686763209e+00,-1.142410900280621949e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.070312750102353050e+01,3.253029189790040050e+02,6.652141580322663117e+00,4.000000039686763209e+00,-1.147410900280621954e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.070562750099872318e+01,3.253128532236048045e+02,6.650996685475314862e+00,4.000000039686763209e+00,-1.152410900280621958e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.070812750097391586e+01,3.253227868945164118e+02,6.649846823648984717e+00,4.000000039686763209e+00,-1.157410900280621963e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.071062750094910854e+01,3.253327199892554518e+02,6.648691995131138732e+00,4.000000039686763209e+00,-1.162410900280621967e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.071312750092430122e+01,3.253426525053386058e+02,6.647532200210483744e+00,4.000000039686763209e+00,-1.167410900280621971e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.071562750089949390e+01,3.253525844402827829e+02,6.646367439176968261e+00,4.000000039686763209e+00,-1.172410900280621976e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.071812750087468658e+01,3.253625157916049488e+02,6.645197712321783357e+00,4.000000039686763209e+00,-1.177410900280621980e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.072062750084987925e+01,3.253724465568222968e+02,6.644023019937359997e+00,4.000000039686763209e+00,-1.182410900280621985e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.072312750082507193e+01,3.253823767334521335e+02,6.642843362317370826e+00,4.000000039686763209e+00,-1.187410900280621989e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.072562750080026461e+01,3.253923063190118796e+02,6.641658739756731045e+00,4.000000039686763209e+00,-1.192410900280621994e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.072812750077545729e+01,3.254022353110191830e+02,6.640469152551595755e+00,4.000000039686763209e+00,-1.197410900280621998e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.073062750075064997e+01,3.254121637069918052e+02,6.639274600999362619e+00,4.000000039686763209e+00,-1.202410900280622003e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.073312750072584265e+01,3.254220915044476214e+02,6.638075085398669195e+00,4.000000039686763209e+00,-1.207410900280622007e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.073562750070103533e+01,3.254320187009046776e+02,6.636870606049393828e+00,4.000000039686763209e+00,-1.212410900280622011e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.073812750067622801e+01,3.254419452938811901e+02,6.635661163252656536e+00,4.000000039686763209e+00,-1.217410900280622016e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.074062750065142069e+01,3.254518712808954888e+02,6.634446757310818121e+00,4.000000039686763209e+00,-1.222410900280622020e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.074312750062661337e+01,3.254617966594661311e+02,6.633227388527480173e+00,4.000000039686763209e+00,-1.227410900280622025e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.074562750060180605e+01,3.254717214271117314e+02,6.632003057207485064e+00,4.000000039686763209e+00,-1.232410900280622029e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.074812750057699873e+01,3.254816455813510743e+02,6.630773763656915065e+00,4.000000039686763209e+00,-1.237410900280622034e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.075062750055219141e+01,3.254915691197031720e+02,6.629539508183094121e+00,4.000000039686763209e+00,-1.242410900280622038e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.075312750052738409e+01,3.255014920396870934e+02,6.628300291094585184e+00,4.000000039686763209e+00,-1.247410900280622043e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.075562750050257677e+01,3.255114143388221351e+02,6.627056112701193769e+00,4.000000039686763209e+00,-1.252410900280621908e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.075812750047776944e+01,3.255213360146277068e+02,6.625806973313963510e+00,4.000000039686763209e+00,-1.257410900280621913e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.076062750045296212e+01,3.255312570646234462e+02,6.624552873245179718e+00,4.000000039686763209e+00,-1.262410900280621917e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.076312750042815480e+01,3.255411774863290475e+02,6.623293812808366710e+00,4.000000039686763209e+00,-1.267410900280621922e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.076562750040334748e+01,3.255510972772643754e+02,6.622029792318290475e+00,4.000000039686763209e+00,-1.272410900280621926e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.076812750037854016e+01,3.255610164349495221e+02,6.620760812090956016e+00,4.000000039686763209e+00,-1.277410900280621930e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.077062750035373284e+01,3.255709349569046935e+02,6.619486872443608227e+00,4.000000039686763209e+00,-1.282410900280621935e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.077312750032892552e+01,3.255808528406502091e+02,6.618207973694731905e+00,4.000000039686763209e+00,-1.287410900280621939e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.077562750030411820e+01,3.255907700837066727e+02,6.616924116164051739e+00,4.000000039686763209e+00,-1.292410900280621944e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.077812750027931088e+01,3.256006866835947449e+02,6.615635300172532318e+00,4.000000039686763209e+00,-1.297410900280621948e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.078062750025450356e+01,3.256106026378352567e+02,6.614341526042377239e+00,4.000000039686763209e+00,-1.302410900280621953e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.078312750022969624e+01,3.256205179439492667e+02,6.613042794097029997e+00,4.000000039686763209e+00,-1.307410900280621957e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.078562750020488892e+01,3.256304325994578903e+02,6.611739104661173982e+00,4.000000039686763209e+00,-1.312410900280621961e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.078812750018008160e+01,3.256403466018825270e+02,6.610430458060731596e+00,4.000000039686763209e+00,-1.317410900280621966e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.079062750015527428e+01,3.256502599487446332e+02,6.609116854622864246e+00,4.000000039686763209e+00,-1.322410900280621970e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.079312750013046696e+01,3.256601726375658359e+02,6.607798294675972350e+00,4.000000039686763209e+00,-1.327410900280621975e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.079562750010565964e+01,3.256700846658680462e+02,6.606474778549696225e+00,4.000000039686763209e+00,-1.332410900280621979e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.079812750008085231e+01,3.256799960311731752e+02,6.605146306574915194e+00,4.000000039686763209e+00,-1.337410900280621984e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.080062750005604499e+01,3.256899067310034752e+02,6.603812879083747589e+00,4.000000039686763209e+00,-1.342410900280621988e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.080312750003123767e+01,3.256998167628811984e+02,6.602474496409549864e+00,4.000000039686763209e+00,-1.347410900280621993e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.080562750000643035e+01,3.257097261243288813e+02,6.601131158886917483e+00,4.000000039686763209e+00,-1.352410900280621997e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.080812749998162303e+01,3.257196348128691170e+02,6.599782866851684915e+00,4.000000039686763209e+00,-1.357410900280622001e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.081062749995681571e+01,3.257295428260247832e+02,6.598429620640924753e+00,4.000000039686763209e+00,-1.362410900280622006e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.081312749993200839e+01,3.257394501613188709e+02,6.597071420592948598e+00,4.000000039686763209e+00,-1.367410900280622010e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.081562749990720107e+01,3.257493568162745419e+02,6.595708267047307061e+00,4.000000039686763209e+00,-1.372410900280622015e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.081812749988239375e+01,3.257592627884151284e+02,6.594340160344787982e+00,4.000000039686763209e+00,-1.377410900280622019e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.082062749985758643e+01,3.257691680752641901e+02,6.592967100827419102e+00,4.000000039686763209e+00,-1.382410900280622024e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.082312749983277911e+01,3.257790726743453433e+02,6.591589088838464505e+00,4.000000039686763209e+00,-1.387410900280622028e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.082562749980797179e+01,3.257889765831824320e+02,6.590206124722426395e+00,4.000000039686763209e+00,-1.392410900280622033e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.082812749978316447e+01,3.257988797992995273e+02,6.588818208825046874e+00,4.000000039686763209e+00,-1.397410900280622037e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.083062749975835715e+01,3.258087823202208142e+02,6.587425341493304387e+00,4.000000039686763209e+00,-1.402410900280622041e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.083312749973354983e+01,3.258186841434706480e+02,6.586027523075416390e+00,4.000000039686763209e+00,-1.407410900280622046e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.083562749970874250e+01,3.258285852665735547e+02,6.584624753920836682e+00,4.000000039686763209e+00,-1.412410900280622050e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.083812749968393518e+01,3.258384856870542876e+02,6.583217034380258070e+00,4.000000039686763209e+00,-1.417410900280622055e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.084062749965912786e+01,3.258483854024377138e+02,6.581804364805610597e+00,4.000000039686763209e+00,-1.422410900280622059e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.084312749963432054e+01,3.258582844102489275e+02,6.580386745550061534e+00,4.000000039686763209e+00,-1.427410900280622064e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.084562749960951322e+01,3.258681827080131370e+02,6.578964176968015387e+00,4.000000039686763209e+00,-1.432410900280622068e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.084812749958470590e+01,3.258780802932558345e+02,6.577536659415113895e+00,4.000000039686763209e+00,-1.437410900280622073e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.085062749955989858e+01,3.258879771635025691e+02,6.576104193248236918e+00,4.000000039686763209e+00,-1.442410900280622077e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.085312749953509126e+01,3.258978733162791173e+02,6.574666778825501545e+00,4.000000039686763209e+00,-1.447410900280622081e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.085562749951028394e+01,3.259077687491114830e+02,6.573224416506260326e+00,4.000000039686763209e+00,-1.452410900280622086e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.085812749948547662e+01,3.259176634595257838e+02,6.571777106651104816e+00,4.000000039686763209e+00,-1.457410900280622090e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.086062749946066930e+01,3.259275574450483646e+02,6.570324849621862029e+00,4.000000039686763209e+00,-1.462410900280622095e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.086312749943586198e+01,3.259374507032056840e+02,6.568867645781596210e+00,4.000000039686763209e+00,-1.467410900280622099e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.086562749941105466e+01,3.259473432315244850e+02,6.567405495494607948e+00,4.000000039686763209e+00,-1.472410900280622104e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.086812749938624734e+01,3.259572350275316239e+02,6.565938399126435066e+00,4.000000039686763209e+00,-1.477410900280622108e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.087062749936144002e+01,3.259671260887541280e+02,6.564466357043851730e+00,4.000000039686763209e+00,-1.482410900280622112e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.087312749933663270e+01,3.259770164127192515e+02,6.562989369614868451e+00,4.000000039686763209e+00,-1.487410900280622117e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.087562749931182537e+01,3.259869059969543628e+02,6.561507437208732085e+00,4.000000039686763209e+00,-1.492410900280622121e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.087812749928701805e+01,3.259967948389871140e+02,6.560020560195925832e+00,4.000000039686763209e+00,-1.497410900280622126e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.088062749926221073e+01,3.260066829363452712e+02,6.558528738948169234e+00,4.000000039686763209e+00,-1.502410900280622130e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.088312749923740341e+01,3.260165702865568278e+02,6.557031973838417294e+00,4.000000039686763209e+00,-1.507410900280622135e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.088562749921259609e+01,3.260264568871499478e+02,6.555530265240861354e+00,4.000000039686763209e+00,-1.512410900280622139e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.088812749918778877e+01,3.260363427356529655e+02,6.554023613530928216e+00,4.000000039686763209e+00,-1.517410900280622144e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.089062749916298145e+01,3.260462278295944429e+02,6.552512019085281025e+00,4.000000039686763209e+00,-1.522410900280622148e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.089312749913817413e+01,3.260561121665031123e+02,6.550995482281818383e+00,4.000000039686763209e+00,-1.527410900280622152e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.089562749911336681e+01,3.260659957439078767e+02,6.549474003499674346e+00,4.000000039686763209e+00,-1.532410900280622157e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.089812749908855949e+01,3.260758785593378093e+02,6.547947583119218429e+00,4.000000039686763209e+00,-1.537410900280622161e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.090062749906375217e+01,3.260857606103222111e+02,6.546416221522055601e+00,4.000000039686763209e+00,-1.542410900280622166e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.090312749903894485e+01,3.260956418943906101e+02,6.544879919091027176e+00,4.000000039686763209e+00,-1.547410900280622170e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.090562749901413753e+01,3.261055224090726483e+02,6.543338676210208149e+00,4.000000039686763209e+00,-1.552410900280622175e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.090812749898933021e+01,3.261154021518982518e+02,6.541792493264908970e+00,4.000000039686763209e+00,-1.557410900280622179e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.091062749896452289e+01,3.261252811203974034e+02,6.540241370641675545e+00,4.000000039686763209e+00,-1.562410900280622184e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.091312749893971557e+01,3.261351593121004271e+02,6.538685308728289236e+00,4.000000039686763209e+00,-1.567410900280622188e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.091562749891490824e+01,3.261450367245377606e+02,6.537124307913765087e+00,4.000000039686763209e+00,-1.572410900280622192e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.091812749889010092e+01,3.261549133552400122e+02,6.535558368588352707e+00,4.000000039686763209e+00,-1.577410900280622197e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.092062749886529360e+01,3.261647892017380741e+02,6.533987491143537163e+00,4.000000039686763209e+00,-1.582410900280622201e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.092312749884048628e+01,3.261746642615629526e+02,6.532411675972038090e+00,4.000000039686763209e+00,-1.587410900280622206e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.092562749881567896e+01,3.261845385322459379e+02,6.530830923467809690e+00,4.000000039686763209e+00,-1.592410900280622210e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.092812749879087164e+01,3.261944120113183772e+02,6.529245234026038958e+00,4.000000039686763209e+00,-1.597410900280622215e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.093062749876606432e+01,3.262042846963119587e+02,6.527654608043149231e+00,4.000000039686763209e+00,-1.602410900280622219e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.093312749874125700e+01,3.262141565847584843e+02,6.526059045916796642e+00,4.000000039686763209e+00,-1.607410900280622224e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.093562749871644968e+01,3.262240276741899834e+02,6.524458548045871886e+00,4.000000039686763209e+00,-1.612410900280622228e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.093812749869164236e+01,3.262338979621387125e+02,6.522853114830499344e+00,4.000000039686763209e+00,-1.617410900280622232e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.094062749866683504e+01,3.262437674461370989e+02,6.521242746672037072e+00,4.000000039686763209e+00,-1.622410900280622237e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.094312749864202772e+01,3.262536361237177402e+02,6.519627443973076808e+00,4.000000039686763209e+00,-1.627410900280622241e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.094562749861722040e+01,3.262635039924134617e+02,6.518007207137444858e+00,4.000000039686763209e+00,-1.632410900280622246e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.094812749859241308e+01,3.262733710497573156e+02,6.516382036570200320e+00,4.000000039686763209e+00,-1.637410900280622250e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.095062749856760576e+01,3.262832372932825820e+02,6.514751932677635970e+00,4.000000039686763209e+00,-1.642410900280622255e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.095312749854279843e+01,3.262931027205226542e+02,6.513116895867277378e+00,4.000000039686763209e+00,-1.647410900280622259e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.095562749851799111e+01,3.263029673290111532e+02,6.511476926547883792e+00,4.000000039686763209e+00,-1.652410900280622263e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.095812749849318379e+01,3.263128311162819273e+02,6.509832025129447253e+00,4.000000039686763209e+00,-1.657410900280622268e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.096062749846837647e+01,3.263226940798691089e+02,6.508182192023193480e+00,4.000000039686763209e+00,-1.662410900280622272e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.096312749844356915e+01,3.263325562173068874e+02,6.506527427641580985e+00,4.000000039686763209e+00,-1.667410900280622277e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.096562749841876183e+01,3.263424175261297364e+02,6.504867732398301072e+00,4.000000039686763209e+00,-1.672410900280622281e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.096812749839395451e+01,3.263522780038722999e+02,6.503203106708276948e+00,4.000000039686763209e+00,-1.677410900280622286e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.097062749836914719e+01,3.263621376480695062e+02,6.501533550987664611e+00,4.000000039686763209e+00,-1.682410900280622290e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.097312749834433987e+01,3.263719964562564542e+02,6.499859065653853740e+00,4.000000039686763209e+00,-1.687410900280622295e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.097562749831953255e+01,3.263818544259684131e+02,6.498179651125465917e+00,4.000000039686763209e+00,-1.692410900280622299e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.097812749829472523e+01,3.263917115547408798e+02,6.496495307822353737e+00,4.000000039686763209e+00,-1.697410900280622303e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.098062749826991791e+01,3.264015678401095784e+02,6.494806036165603480e+00,4.000000039686763209e+00,-1.702410900280622308e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.098312749824511059e+01,3.264114232796104602e+02,6.493111836577533325e+00,4.000000039686763209e+00,-1.707410900280622312e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.098562749822030327e+01,3.264212778707796474e+02,6.491412709481693355e+00,4.000000039686763209e+00,-1.712410900280622317e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.098812749819549595e+01,3.264311316111534893e+02,6.489708655302864670e+00,4.000000039686763209e+00,-1.717410900280622321e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.099062749817068863e+01,3.264409844982685627e+02,6.487999674467061162e+00,4.000000039686763209e+00,-1.722410900280622326e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.099312749814588130e+01,3.264508365296616716e+02,6.486285767401527735e+00,4.000000039686763209e+00,-1.727410900280622330e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.099562749812107398e+01,3.264606877028697909e+02,6.484566934534742089e+00,4.000000039686763209e+00,-1.732410900280622335e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.099812749809626666e+01,3.264705380154301224e+02,6.482843176296411158e+00,4.000000039686763209e+00,-1.737410900280622339e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.100062749807145934e+01,3.264803874648800388e+02,6.481114493117475561e+00,4.000000039686763209e+00,-1.742410900280622343e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.100312749804665202e+01,3.264902360487572537e+02,6.479380885430105153e+00,4.000000039686763209e+00,-1.747410900280622348e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.100562749802184470e+01,3.265000837645995944e+02,6.477642353667702579e+00,4.000000039686763209e+00,-1.752410900280622352e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.100812749799703738e+01,3.265099306099451155e+02,6.475898898264900616e+00,4.000000039686763209e+00,-1.757410900280622357e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.101062749797223006e+01,3.265197765823320992e+02,6.474150519657563052e+00,4.000000039686763209e+00,-1.762410900280622361e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.101312749794742274e+01,3.265296216792990549e+02,6.472397218282783804e+00,4.000000039686763209e+00,-1.767410900280622366e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.101562749792261542e+01,3.265394658983847194e+02,6.470638994578888692e+00,4.000000039686763209e+00,-1.772410900280622370e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.101812749789780810e+01,3.265493092371280568e+02,6.468875848985434551e+00,4.000000039686763209e+00,-1.777410900280622374e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.102062749787300078e+01,3.265591516930682019e+02,6.467107781943206568e+00,4.000000039686763209e+00,-1.782410900280622379e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.102312749784819346e+01,3.265689932637445736e+02,6.465334793894221832e+00,4.000000039686763209e+00,-1.787410900280622383e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.102562749782338614e+01,3.265788339466967614e+02,6.463556885281727560e+00,4.000000039686763209e+00,-1.792410900280622388e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.102812749779857882e+01,3.265886737394645820e+02,6.461774056550201095e+00,4.000000039686763209e+00,-1.797410900280622392e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.103062749777377149e+01,3.265985126395881366e+02,6.459986308145349021e+00,4.000000039686763209e+00,-1.802410900280622397e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.103312749774896417e+01,3.266083506446076399e+02,6.458193640514108935e+00,4.000000039686763209e+00,-1.807410900280622401e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.103562749772415685e+01,3.266181877520636476e+02,6.456396054104646787e+00,4.000000039686763209e+00,-1.812410900280622406e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.103812749769934953e+01,3.266280239594968293e+02,6.454593549366360428e+00,4.000000039686763209e+00,-1.817410900280622410e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.104062749767454221e+01,3.266378592644481387e+02,6.452786126749875173e+00,4.000000039686763209e+00,-1.822410900280622414e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.104312749764973489e+01,3.266476936644587568e+02,6.450973786707047353e+00,4.000000039686763209e+00,-1.827410900280622419e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.104562749762492757e+01,3.266575271570700920e+02,6.449156529690961648e+00,4.000000039686763209e+00,-1.832410900280622423e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.104812749760012025e+01,3.266673597398237803e+02,6.447334356155931978e+00,4.000000039686763209e+00,-1.837410900280622428e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.105062749757531293e+01,3.266771914102616847e+02,6.445507266557502390e+00,4.000000039686763209e+00,-1.842410900280622432e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.105312749755050561e+01,3.266870221659258391e+02,6.443675261352444394e+00,4.000000039686763209e+00,-1.847410900280622437e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.105562749752569829e+01,3.266968520043586182e+02,6.441838340998759627e+00,4.000000039686763209e+00,-1.852410900280622441e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.105812749750089097e+01,3.267066809231025104e+02,6.439996505955678963e+00,4.000000039686763209e+00,-1.857410900280622446e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.106062749747608365e+01,3.267165089197002885e+02,6.438149756683659852e+00,4.000000039686763209e+00,-1.862410900280622450e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.106312749745127633e+01,3.267263359916950094e+02,6.436298093644390761e+00,4.000000039686763209e+00,-1.867410900280622454e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.106562749742646901e+01,3.267361621366298436e+02,6.434441517300786728e+00,4.000000039686763209e+00,-1.872410900280622459e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.106812749740166169e+01,3.267459873520483029e+02,6.432580028116992032e+00,4.000000039686763209e+00,-1.877410900280622463e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.107062749737685436e+01,3.267558116354940125e+02,6.430713626558379303e+00,4.000000039686763209e+00,-1.882410900280622468e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.107312749735204704e+01,3.267656349845109389e+02,6.428842313091548633e+00,4.000000039686763209e+00,-1.887410900280622472e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.107562749732723972e+01,3.267754573966432758e+02,6.426966088184327575e+00,4.000000039686763209e+00,-1.892410900280622477e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.107812749730243240e+01,3.267852788694353876e+02,6.425084952305773811e+00,4.000000039686763209e+00,-1.897410900280622481e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.108062749727762508e+01,3.267950994004319227e+02,6.423198905926169822e+00,4.000000039686763209e+00,-1.902410900280622486e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.108312749725281776e+01,3.268049189871777571e+02,6.421307949517028213e+00,4.000000039686763209e+00,-1.907410900280622490e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.108562749722801044e+01,3.268147376272179940e+02,6.419412083551088166e+00,4.000000039686763209e+00,-1.912410900280622494e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.108812749720320312e+01,3.268245553180979073e+02,6.417511308502315437e+00,4.000000039686763209e+00,-1.917410900280622499e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.109062749717839580e+01,3.268343720573631686e+02,6.415605624845904131e+00,4.000000039686763209e+00,-1.922410900280622503e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.109312749715358848e+01,3.268441878425595064e+02,6.413695033058274930e+00,4.000000039686763209e+00,-1.927410900280622508e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.109562749712878116e+01,3.268540026712330473e+02,6.411779533617075977e+00,4.000000039686763209e+00,-1.932410900280622512e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.109812749710397384e+01,3.268638165409300314e+02,6.409859127001182877e+00,4.000000039686763209e+00,-1.937410900280622517e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.110062749707916652e+01,3.268736294491970398e+02,6.407933813690696034e+00,4.000000039686763209e+00,-1.942410900280622521e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.110312749705435920e+01,3.268834413935808243e+02,6.406003594166944204e+00,4.000000039686763209e+00,-1.947410900280622525e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.110562749702955188e+01,3.268932523716283640e+02,6.404068468912482714e+00,4.000000039686763209e+00,-1.952410900280622530e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.110812749700474455e+01,3.269030623808869791e+02,6.402128438411092581e+00,4.000000039686763209e+00,-1.957410900280622534e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.111062749697993723e+01,3.269128714189041034e+02,6.400183503147781394e+00,4.000000039686763209e+00,-1.962410900280622539e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.111312749695512991e+01,3.269226794832275118e+02,6.398233663608782429e+00,4.000000039686763209e+00,-1.967410900280622543e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.111562749693032259e+01,3.269324865714052066e+02,6.396278920281556424e+00,4.000000039686763209e+00,-1.972410900280622548e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.111812749690551527e+01,3.269422926809853607e+02,6.394319273654788915e+00,4.000000039686763209e+00,-1.977410900280622552e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.112062749688070795e+01,3.269520978095164878e+02,6.392354724218391127e+00,4.000000039686763209e+00,-1.982410900280622557e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.112312749685590063e+01,3.269619019545472725e+02,6.390385272463500854e+00,4.000000039686763209e+00,-1.987410900280622561e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.112562749683109331e+01,3.269717051136267401e+02,6.388410918882480694e+00,4.000000039686763209e+00,-1.992410900280622565e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.112812749680628599e+01,3.269815072843040298e+02,6.386431663968918926e+00,4.000000039686763209e+00,-1.997410900280622570e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.113062749678147867e+01,3.269913084641286787e+02,6.384447508217630407e+00,4.000000039686763209e+00,-2.002410900280622574e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.113312749675667135e+01,3.270011086506503375e+02,6.382458452124653014e+00,4.000000039686763209e+00,-2.007410900280622579e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.113562749673186403e+01,3.270109078414189412e+02,6.380464496187251200e+00,4.000000039686763209e+00,-2.012410900280622583e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.113812749670705671e+01,3.270207060339847089e+02,6.378465640903913325e+00,4.000000039686763209e+00,-2.017410900280622588e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.114062749668224939e+01,3.270305032258981441e+02,6.376461886774353438e+00,4.000000039686763209e+00,-2.022410900280622592e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.114312749665744207e+01,3.270402994147098639e+02,6.374453234299510385e+00,4.000000039686763209e+00,-2.027410900280622597e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.114562749663263475e+01,3.270500945979708831e+02,6.372439683981546921e+00,4.000000039686763209e+00,-2.032410900280622601e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.114812749660782742e+01,3.270598887732323874e+02,6.370421236323850600e+00,4.000000039686763209e+00,-2.037410900280622605e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.115062749658302010e+01,3.270696819380458464e+02,6.368397891831033775e+00,4.000000039686763209e+00,-2.042410900280622610e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.115312749655821278e+01,3.270794740899629574e+02,6.366369651008932706e+00,4.000000039686763209e+00,-2.047410900280622614e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.115562749653340546e+01,3.270892652265356446e+02,6.364336514364606678e+00,4.000000039686763209e+00,-2.052410900280622619e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.115812749650859814e+01,3.270990553453161738e+02,6.362298482406340661e+00,4.000000039686763209e+00,-2.057410900280622623e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.116062749648379082e+01,3.271088444438570377e+02,6.360255555643641756e+00,4.000000039686763209e+00,-2.062410900280622628e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.116312749645898350e+01,3.271186325197108999e+02,6.358207734587242754e+00,4.000000039686763209e+00,-2.067410900280622632e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.116562749643417618e+01,3.271284195704307649e+02,6.356155019749098578e+00,4.000000039686763209e+00,-2.072410900280622637e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.116812749640936886e+01,3.271382055935698645e+02,6.354097411642387172e+00,4.000000039686763209e+00,-2.077410900280622641e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.117062749638456154e+01,3.271479905866817148e+02,6.352034910781511279e+00,4.000000039686763209e+00,-2.082410900280622645e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.117312749635975422e+01,3.271577745473200594e+02,6.349967517682095774e+00,4.000000039686763209e+00,-2.087410900280622650e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.117562749633494690e+01,3.271675574730388689e+02,6.347895232860989445e+00,4.000000039686763209e+00,-2.092410900280622654e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.117812749631013958e+01,3.271773393613924554e+02,6.345818056836263210e+00,4.000000039686763209e+00,-2.097410900280622659e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.118062749628533226e+01,3.271871202099353582e+02,6.343735990127211011e+00,4.000000039686763209e+00,-2.102410900280622663e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.118312749626052494e+01,3.271969000162223438e+02,6.341649033254348922e+00,4.000000039686763209e+00,-2.107410900280622668e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.118562749623571762e+01,3.272066787778084631e+02,6.339557186739416927e+00,4.000000039686763209e+00,-2.112410900280622672e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.118812749621091029e+01,3.272164564922489944e+02,6.337460451105376258e+00,4.000000039686763209e+00,-2.117410900280622676e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.119062749618610297e+01,3.272262331570995570e+02,6.335358826876411165e+00,4.000000039686763209e+00,-2.122410900280622681e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.119312749616129565e+01,3.272360087699159408e+02,6.333252314577927145e+00,4.000000039686763209e+00,-2.127410900280622685e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.119562749613648833e+01,3.272457833282542765e+02,6.331140914736552716e+00,4.000000039686763209e+00,-2.132410900280622690e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.119812749611168101e+01,3.272555568296709225e+02,6.329024627880137643e+00,4.000000039686763209e+00,-2.137410900280622694e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.120062749608687369e+01,3.272653292717225213e+02,6.326903454537753824e+00,4.000000039686763209e+00,-2.142410900280622699e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.120312749606206637e+01,3.272751006519659427e+02,6.324777395239694400e+00,4.000000039686763209e+00,-2.147410900280622703e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.120562749603725905e+01,3.272848709679583408e+02,6.322646450517474648e+00,4.000000039686763209e+00,-2.152410900280622708e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.120812749601245173e+01,3.272946402172570970e+02,6.320510620903830201e+00,4.000000039686763209e+00,-2.157410900280622712e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.121062749598764441e+01,3.273044083974199339e+02,6.318369906932718827e+00,4.000000039686763209e+00,-2.162410900280622716e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.121312749596283709e+01,3.273141755060048013e+02,6.316224309139318649e+00,4.000000039686763209e+00,-2.167410900280622721e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.121562749593802977e+01,3.273239415405699333e+02,6.314073828060029037e+00,4.000000039686763209e+00,-2.172410900280622725e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.121812749591322245e+01,3.273337064986738483e+02,6.311918464232470605e+00,4.000000039686763209e+00,-2.177410900280622730e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.122062749588841513e+01,3.273434703778752350e+02,6.309758218195484325e+00,4.000000039686763209e+00,-2.182410900280622734e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.122312749586360781e+01,3.273532331757331804e+02,6.307593090489131527e+00,4.000000039686763209e+00,-2.187410900280622739e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.122562749583880048e+01,3.273629948898069983e+02,6.305423081654693895e+00,4.000000039686763209e+00,-2.192410900280622743e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.122812749581399316e+01,3.273727555176562305e+02,6.303248192234673475e+00,4.000000039686763209e+00,-2.197410900280622748e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.123062749578918584e+01,3.273825150568407025e+02,6.301068422772793554e+00,4.000000039686763209e+00,-2.202410900280622752e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.123312749576437852e+01,3.273922735049205244e+02,6.298883773813995113e+00,4.000000039686763209e+00,-2.207410900280622756e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.123562749573957120e+01,3.274020308594561470e+02,6.296694245904441267e+00,4.000000039686763209e+00,-2.212410900280622761e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.123812749571476388e+01,3.274117871180081352e+02,6.294499839591514601e+00,4.000000039686763209e+00,-2.217410900280622765e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.124062749568995656e+01,3.274215422781375082e+02,6.292300555423815389e+00,4.000000039686763209e+00,-2.222410900280622770e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.124312749566514924e+01,3.274312963374054561e+02,6.290096393951165155e+00,4.000000039686763209e+00,-2.227410900280622774e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.124562749564034192e+01,3.274410492933734531e+02,6.287887355724604888e+00,4.000000039686763209e+00,-2.232410900280622779e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.124812749561553460e+01,3.274508011436032575e+02,6.285673441296393271e+00,4.000000039686763209e+00,-2.237410900280622783e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.125062749559072728e+01,3.274605518856569120e+02,6.283454651220009346e+00,4.000000039686763209e+00,-2.242410900280622787e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.125312749556591996e+01,3.274703015170967433e+02,6.281230986050150733e+00,4.000000039686763209e+00,-2.247410900280622792e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.125562749554111264e+01,3.274800500354853057e+02,6.279002446342732746e+00,4.000000039686763209e+00,-2.252410900280622796e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.125812749551630532e+01,3.274897974383854944e+02,6.276769032654891056e+00,4.000000039686763209e+00,-2.257410900280622801e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.126062749549149800e+01,3.274995437233604889e+02,6.274530745544979027e+00,4.000000039686763209e+00,-2.262410900280622805e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.126312749546669068e+01,3.275092888879736961e+02,6.272287585572568602e+00,4.000000039686763209e+00,-2.267410900280622810e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.126562749544188335e+01,3.275190329297888070e+02,6.270039553298449420e+00,4.000000039686763209e+00,-2.272410900280622814e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.126812749541707603e+01,3.275287758463697969e+02,6.267786649284629696e+00,4.000000039686763209e+00,-2.277410900280622819e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.127062749539226871e+01,3.275385176352809822e+02,6.265528874094336231e+00,4.000000039686763209e+00,-2.282410900280622823e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.127312749536746139e+01,3.275482582940869065e+02,6.263266228292011739e+00,4.000000039686763209e+00,-2.287410900280622827e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.127562749534265407e+01,3.275579978203523979e+02,6.260998712443317515e+00,4.000000039686763209e+00,-2.292410900280622832e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.127812749531784675e+01,3.275677362116425684e+02,6.258726327115133437e+00,4.000000039686763209e+00,-2.297410900280622836e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.128062749529303943e+01,3.275774734655228144e+02,6.256449072875555295e+00,4.000000039686763209e+00,-2.302410900280622841e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.128312749526823211e+01,3.275872095795588166e+02,6.254166950293896576e+00,4.000000039686763209e+00,-2.307410900280622845e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.128562749524342479e+01,3.275969445513165965e+02,6.251879959940687570e+00,4.000000039686763209e+00,-2.312410900280622850e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.128812749521861747e+01,3.276066783783623464e+02,6.249588102387676258e+00,4.000000039686763209e+00,-2.317410900280622854e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.129062749519381015e+01,3.276164110582626563e+02,6.247291378207827428e+00,4.000000039686763209e+00,-2.322410900280622859e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.129312749516900283e+01,3.276261425885843437e+02,6.244989787975321782e+00,4.000000039686763209e+00,-2.327410900280622863e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.129562749514419551e+01,3.276358729668945102e+02,6.242683332265556828e+00,4.000000039686763209e+00,-2.332410900280622867e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.129812749511938819e+01,3.276456021907605418e+02,6.240372011655145990e+00,4.000000039686763209e+00,-2.337410900280622872e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.130062749509458087e+01,3.276553302577501654e+02,6.238055826721920383e+00,4.000000039686763209e+00,-2.342410900280622876e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.130312749506977354e+01,3.276650571654313921e+02,6.235734778044925264e+00,4.000000039686763209e+00,-2.347410900280622881e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.130562749504496622e+01,3.276747829113724606e+02,6.233408866204423582e+00,4.000000039686763209e+00,-2.352410900280622885e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.130812749502015890e+01,3.276845074931419504e+02,6.231078091781893313e+00,4.000000039686763209e+00,-2.357410900280622890e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.131062749499535158e+01,3.276942309083086684e+02,6.228742455360027463e+00,4.000000039686763209e+00,-2.362410900280622894e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.131312749497054426e+01,3.277039531544418196e+02,6.226401957522734953e+00,4.000000039686763209e+00,-2.367410900280622899e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.131562749494573694e+01,3.277136742291108362e+02,6.224056598855140621e+00,4.000000039686763209e+00,-2.372410900280622903e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.131812749492092962e+01,3.277233941298854347e+02,6.221706379943584331e+00,4.000000039686763209e+00,-2.377410900280622907e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.132062749489612230e+01,3.277331128543356158e+02,6.219351301375620977e+00,4.000000039686763209e+00,-2.382410900280622912e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.132312749487131498e+01,3.277428304000317212e+02,6.216991363740019594e+00,4.000000039686763209e+00,-2.387410900280622916e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.132562749484650766e+01,3.277525467645443769e+02,6.214626567626765130e+00,4.000000039686763209e+00,-2.392410900280622921e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.132812749482170034e+01,3.277622619454444930e+02,6.212256913627055788e+00,4.000000039686763209e+00,-2.397410900280622925e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.133062749479689302e+01,3.277719759403032640e+02,6.209882402333305684e+00,4.000000039686763209e+00,-2.402410900280622930e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.133312749477208570e+01,3.277816887466921685e+02,6.207503034339142189e+00,4.000000039686763209e+00,-2.407410900280622934e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.133562749474727838e+01,3.277914003621830261e+02,6.205118810239407701e+00,4.000000039686763209e+00,-2.412410900280622938e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.133812749472247106e+01,3.278011107843479408e+02,6.202729730630157867e+00,4.000000039686763209e+00,-2.417410900280622943e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.134062749469766374e+01,3.278108200107593007e+02,6.200335796108663367e+00,4.000000039686763209e+00,-2.422410900280622947e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.134312749467285641e+01,3.278205280389897780e+02,6.197937007273407239e+00,4.000000039686763209e+00,-2.427410900280622952e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.134562749464804909e+01,3.278302348666123862e+02,6.195533364724086667e+00,4.000000039686763209e+00,-2.432410900280622956e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.134812749462324177e+01,3.278399404912004229e+02,6.193124869061612081e+00,4.000000039686763209e+00,-2.437410900280622961e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.135062749459843445e+01,3.278496449103274699e+02,6.190711520888108055e+00,4.000000039686763209e+00,-2.442410900280622965e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.135312749457362713e+01,3.278593481215674501e+02,6.188293320806910636e+00,4.000000039686763209e+00,-2.447410900280622970e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.135562749454881981e+01,3.278690501224945137e+02,6.185870269422570900e+00,4.000000039686763209e+00,-2.452410900280622974e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.135812749452401249e+01,3.278787509106832090e+02,6.183442367340851398e+00,4.000000039686763209e+00,-2.457410900280622978e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.136062749449920517e+01,3.278884504837083114e+02,6.181009615168727045e+00,4.000000039686763209e+00,-2.462410900280622983e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.136312749447439785e+01,3.278981488391449375e+02,6.178572013514386008e+00,4.000000039686763209e+00,-2.467410900280622987e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.136562749444959053e+01,3.279078459745684881e+02,6.176129562987228816e+00,4.000000039686763209e+00,-2.472410900280622992e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.136812749442478321e+01,3.279175418875546484e+02,6.173682264197868363e+00,4.000000039686763209e+00,-2.477410900280622996e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.137062749439997589e+01,3.279272365756795011e+02,6.171230117758129019e+00,4.000000039686763209e+00,-2.482410900280623001e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.137312749437516857e+01,3.279369300365193567e+02,6.168773124281047515e+00,4.000000039686763209e+00,-2.487410900280623005e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.137562749435036125e+01,3.279466222676508096e+02,6.166311284380872948e+00,4.000000039686763209e+00,-2.492410900280623010e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.137812749432555393e+01,3.279563132666508523e+02,6.163844598673064112e+00,4.000000039686763209e+00,-2.497410900280623014e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.138062749430074660e+01,3.279660030310967045e+02,6.161373067774293055e+00,4.000000039686763209e+00,-2.502410900280622741e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.138312749427593928e+01,3.279756915585659272e+02,6.158896692302442410e+00,4.000000039686763209e+00,-2.507410900280622745e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.138562749425113196e+01,3.279853788466364222e+02,6.156415472876605399e+00,4.000000039686763209e+00,-2.512410900280622750e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.138812749422632464e+01,3.279950648928863757e+02,6.153929410117087606e+00,4.000000039686763209e+00,-2.517410900280622754e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.139062749420151732e+01,3.280047496948942012e+02,6.151438504645404315e+00,4.000000039686763209e+00,-2.522410900280622759e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.139312749417671000e+01,3.280144332502387670e+02,6.148942757084282285e+00,4.000000039686763209e+00,-2.527410900280622763e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.139562749415190268e+01,3.280241155564991686e+02,6.146442168057657973e+00,4.000000039686763209e+00,-2.532410900280622768e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.139812749412709536e+01,3.280337966112547861e+02,6.143936738190679314e+00,4.000000039686763209e+00,-2.537410900280622772e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.140062749410228804e+01,3.280434764120853970e+02,6.141426468109703052e+00,4.000000039686763209e+00,-2.542410900280622776e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.140312749407748072e+01,3.280531549565710634e+02,6.138911358442296518e+00,4.000000039686763209e+00,-2.547410900280622781e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.140562749405267340e+01,3.280628322422921315e+02,6.136391409817237630e+00,4.000000039686763209e+00,-2.552410900280622785e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.140812749402786608e+01,3.280725082668292885e+02,6.133866622864513118e+00,4.000000039686763209e+00,-2.557410900280622790e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.141062749400305876e+01,3.280821830277635058e+02,6.131336998215320300e+00,4.000000039686763209e+00,-2.562410900280622794e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.141312749397825144e+01,3.280918565226760961e+02,6.128802536502065301e+00,4.000000039686763209e+00,-2.567410900280622799e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.141562749395344412e+01,3.281015287491487129e+02,6.126263238358363061e+00,4.000000039686763209e+00,-2.572410900280622803e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.141812749392863680e+01,3.281111997047632940e+02,6.123719104419038217e+00,4.000000039686763209e+00,-2.577410900280622807e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.142062749390382947e+01,3.281208693871020614e+02,6.121170135320124217e+00,4.000000039686763209e+00,-2.582410900280622812e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.142312749387902215e+01,3.281305377937476351e+02,6.118616331698863320e+00,4.000000039686763209e+00,-2.587410900280622816e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.142562749385421483e+01,3.281402049222829191e+02,6.116057694193706595e+00,4.000000039686763209e+00,-2.592410900280622821e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.142812749382940751e+01,3.281498707702911020e+02,6.113494223444313036e+00,4.000000039686763209e+00,-2.597410900280622825e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.143062749380460019e+01,3.281595353353557130e+02,6.110925920091551333e+00,4.000000039686763209e+00,-2.602410900280622830e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.143312749377979287e+01,3.281691986150606226e+02,6.108352784777496325e+00,4.000000039686763209e+00,-2.607410900280622834e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.143562749375498555e+01,3.281788606069900425e+02,6.105774818145431659e+00,4.000000039686763209e+00,-2.612410900280622839e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.143812749373017823e+01,3.281885213087284683e+02,6.103192020839849796e+00,4.000000039686763209e+00,-2.617410900280622843e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.144062749370537091e+01,3.281981807178606800e+02,6.100604393506449341e+00,4.000000039686763209e+00,-2.622410900280622847e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.144312749368056359e+01,3.282078388319718556e+02,6.098011936792137710e+00,4.000000039686763209e+00,-2.627410900280622852e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.144562749365575627e+01,3.282174956486474571e+02,6.095414651345028467e+00,4.000000039686763209e+00,-2.632410900280622856e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.144812749363094895e+01,3.282271511654732876e+02,6.092812537814443097e+00,4.000000039686763209e+00,-2.637410900280622861e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.145062749360614163e+01,3.282368053800354915e+02,6.090205596850910119e+00,4.000000039686763209e+00,-2.642410900280622865e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.145312749358133431e+01,3.282464582899204970e+02,6.087593829106165089e+00,4.000000039686763209e+00,-2.647410900280622870e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.145562749355652699e+01,3.282561098927150169e+02,6.084977235233149706e+00,4.000000039686763209e+00,-2.652410900280622874e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.145812749353171967e+01,3.282657601860062186e+02,6.082355815886012707e+00,4.000000039686763209e+00,-2.657410900280622879e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.146062749350691234e+01,3.282754091673815537e+02,6.079729571720108083e+00,4.000000039686763209e+00,-2.662410900280622883e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.146312749348210502e+01,3.282850568344287012e+02,6.077098503391997752e+00,4.000000039686763209e+00,-2.667410900280622887e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.146562749345729770e+01,3.282947031847357948e+02,6.074462611559448000e+00,4.000000039686763209e+00,-2.672410900280622892e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.146812749343249038e+01,3.283043482158912525e+02,6.071821896881432146e+00,4.000000039686763209e+00,-2.677410900280622896e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.147062749340768306e+01,3.283139919254837764e+02,6.069176360018128769e+00,4.000000039686763209e+00,-2.682410900280622901e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.147312749338287574e+01,3.283236343111024667e+02,6.066526001630922593e+00,4.000000039686763209e+00,-2.687410900280622905e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.147562749335806842e+01,3.283332753703367075e+02,6.063870822382402714e+00,4.000000039686763209e+00,-2.692410900280622910e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.147812749333326110e+01,3.283429151007762243e+02,6.061210822936363485e+00,4.000000039686763209e+00,-2.697410900280622914e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.148062749330845378e+01,3.283525535000111404e+02,6.058546003957805404e+00,4.000000039686763209e+00,-2.702410900280622919e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.148312749328364646e+01,3.283621905656318063e+02,6.055876366112933340e+00,4.000000039686763209e+00,-2.707410900280622923e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.148562749325883914e+01,3.283718262952289706e+02,6.053201910069156533e+00,4.000000039686763209e+00,-2.712410900280622927e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.148812749323403182e+01,3.283814606863937229e+02,6.050522636495088591e+00,4.000000039686763209e+00,-2.717410900280622932e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.149062749320922450e+01,3.283910937367174370e+02,6.047838546060548381e+00,4.000000039686763209e+00,-2.722410900280622936e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.149312749318441718e+01,3.284007254437918846e+02,6.045149639436558253e+00,4.000000039686763209e+00,-2.727410900280622941e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.149562749315960986e+01,3.284103558052090648e+02,6.042455917295344925e+00,4.000000039686763209e+00,-2.732410900280622945e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.149812749313480253e+01,3.284199848185614314e+02,6.039757380310338597e+00,4.000000039686763209e+00,-2.737410900280622950e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.150062749310999521e+01,3.284296124814417794e+02,6.037054029156173840e+00,4.000000039686763209e+00,-2.742410900280622954e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.150312749308518789e+01,3.284392387914431310e+02,6.034345864508688706e+00,4.000000039686763209e+00,-2.747410900280622958e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.150562749306038057e+01,3.284488637461589065e+02,6.031632887044923841e+00,4.000000039686763209e+00,-2.752410900280622963e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.150812749303557325e+01,3.284584873431829237e+02,6.028915097443123372e+00,4.000000039686763209e+00,-2.757410900280622967e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.151062749301076593e+01,3.284681095801092283e+02,6.026192496382735797e+00,4.000000039686763209e+00,-2.762410900280622972e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.151312749298595861e+01,3.284777304545322636e+02,6.023465084544410431e+00,4.000000039686763209e+00,-2.767410900280622976e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.151562749296115129e+01,3.284873499640468708e+02,6.020732862610000069e+00,4.000000039686763209e+00,-2.772410900280622981e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.151812749293634397e+01,3.284969681062481186e+02,6.017995831262560991e+00,4.000000039686763209e+00,-2.777410900280622985e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.152062749291153665e+01,3.285065848787314735e+02,6.015253991186350291e+00,4.000000039686763209e+00,-2.782410900280622990e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.152312749288672933e+01,3.285162002790927431e+02,6.012507343066828547e+00,4.000000039686763209e+00,-2.787410900280622994e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.152562749286192201e+01,3.285258143049280761e+02,6.009755887590657153e+00,4.000000039686763209e+00,-2.792410900280622998e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.152812749283711469e+01,3.285354269538339622e+02,6.006999625445700097e+00,4.000000039686763209e+00,-2.797410900280623003e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.153062749281230737e+01,3.285450382234072890e+02,6.004238557321023073e+00,4.000000039686763209e+00,-2.802410900280623007e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.153312749278750005e+01,3.285546481112451715e+02,6.001472683906893479e+00,4.000000039686763209e+00,-2.807410900280623012e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.153562749276269273e+01,3.285642566149451795e+02,5.998702005894779532e+00,4.000000039686763209e+00,-2.812410900280623016e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.153812749273788540e+01,3.285738637321051669e+02,5.995926523977350264e+00,4.000000039686763209e+00,-2.817410900280623021e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.154062749271307808e+01,3.285834694603233856e+02,5.993146238848476415e+00,4.000000039686763209e+00,-2.822410900280623025e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.154312749268827076e+01,3.285930737971983717e+02,5.990361151203229539e+00,4.000000039686763209e+00,-2.827410900280623030e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.154562749266346344e+01,3.286026767403290592e+02,5.987571261737881123e+00,4.000000039686763209e+00,-2.832410900280623034e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.154812749263865612e+01,3.286122782873147230e+02,5.984776571149903468e+00,4.000000039686763209e+00,-2.837410900280623038e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.155062749261384880e+01,3.286218784357549225e+02,5.981977080137968805e+00,4.000000039686763209e+00,-2.842410900280623043e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.155312749258904148e+01,3.286314771832496717e+02,5.979172789401951071e+00,4.000000039686763209e+00,-2.847410900280623047e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.155562749256423416e+01,3.286410745273992688e+02,5.976363699642922356e+00,4.000000039686763209e+00,-2.852410900280623052e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.155812749253942684e+01,3.286506704658043532e+02,5.973549811563154677e+00,4.000000039686763209e+00,-2.857410900280623056e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.156062749251461952e+01,3.286602649960659619e+02,5.970731125866119982e+00,4.000000039686763209e+00,-2.862410900280623061e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.156312749248981220e+01,3.286698581157854733e+02,5.967907643256490147e+00,4.000000039686763209e+00,-2.867410900280623065e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.156562749246500488e+01,3.286794498225646066e+02,5.965079364440136089e+00,4.000000039686763209e+00,-2.872410900280623069e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.156812749244019756e+01,3.286890401140054223e+02,5.962246290124126880e+00,4.000000039686763209e+00,-2.877410900280623074e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.157062749241539024e+01,3.286986289877103786e+02,5.959408421016731516e+00,4.000000039686763209e+00,-2.882410900280623078e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.157312749239058292e+01,3.287082164412822181e+02,5.956565757827417151e+00,4.000000039686763209e+00,-2.887410900280623083e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.157562749236577559e+01,3.287178024723240810e+02,5.953718301266849089e+00,4.000000039686763209e+00,-2.892410900280623087e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.157812749234096827e+01,3.287273870784394489e+02,5.950866052046892563e+00,4.000000039686763209e+00,-2.897410900280623092e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.158062749231616095e+01,3.287369702572322012e+02,5.948009010880609182e+00,4.000000039686763209e+00,-2.902410900280623096e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.158312749229135363e+01,3.287465520063065583e+02,5.945147178482258710e+00,4.000000039686763209e+00,-2.907410900280623101e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.158562749226654631e+01,3.287561323232670247e+02,5.942280555567299949e+00,4.000000039686763209e+00,-2.912410900280623105e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.158812749224173899e+01,3.287657112057185600e+02,5.939409142852388079e+00,4.000000039686763209e+00,-2.917410900280623109e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.159062749221693167e+01,3.287752886512664645e+02,5.936532941055376433e+00,4.000000039686763209e+00,-2.922410900280623114e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.159312749219212435e+01,3.287848646575163229e+02,5.933651950895315608e+00,4.000000039686763209e+00,-2.927410900280623118e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.159562749216731703e+01,3.287944392220741747e+02,5.930766173092453464e+00,4.000000039686763209e+00,-2.932410900280623123e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.159812749214250971e+01,3.288040123425463435e+02,5.927875608368234239e+00,4.000000039686763209e+00,-2.937410900280623127e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.160062749211770239e+01,3.288135840165396075e+02,5.924980257445298548e+00,4.000000039686763209e+00,-2.942410900280623132e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.160312749209289507e+01,3.288231542416609727e+02,5.922080121047485157e+00,4.000000039686763209e+00,-2.947410900280623136e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.160562749206808775e+01,3.288327230155179564e+02,5.919175199899827433e+00,4.000000039686763209e+00,-2.952410900280623141e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.160812749204328043e+01,3.288422903357183031e+02,5.916265494728555119e+00,4.000000039686763209e+00,-2.957410900280623145e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.161062749201847311e+01,3.288518561998702125e+02,5.913351006261095222e+00,4.000000039686763209e+00,-2.962410900280623149e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.161312749199366579e+01,3.288614206055822251e+02,5.910431735226069350e+00,4.000000039686763209e+00,-2.967410900280623154e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.161562749196885846e+01,3.288709835504632224e+02,5.907507682353296374e+00,4.000000039686763209e+00,-2.972410900280623158e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.161812749194405114e+01,3.288805450321224839e+02,5.904578848373787991e+00,4.000000039686763209e+00,-2.977410900280623163e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.162062749191924382e+01,3.288901050481696302e+02,5.901645234019754049e+00,4.000000039686763209e+00,-2.982410900280623167e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.162312749189443650e+01,3.288996635962146797e+02,5.898706840024597220e+00,4.000000039686763209e+00,-2.987410900280623172e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.162562749186962918e+01,3.289092206738679351e+02,5.895763667122916551e+00,4.000000039686763209e+00,-2.992410900280623176e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.162812749184482186e+01,3.289187762787402107e+02,5.892815716050504804e+00,4.000000039686763209e+00,-2.997410900280623181e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.163062749182001454e+01,3.289283304084425481e+02,5.889862987544349338e+00,4.000000039686763209e+00,-3.002410900280623185e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.163312749179520722e+01,3.289378830605864437e+02,5.886905482342633000e+00,4.000000039686763209e+00,-3.007410900280623189e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.163562749177039990e+01,3.289474342327836780e+02,5.883943201184732352e+00,4.000000039686763209e+00,-3.012410900280623194e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.163812749174559258e+01,3.289569839226465433e+02,5.880976144811216777e+00,4.000000039686763209e+00,-3.017410900280623198e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.164062749172078526e+01,3.289665321277875591e+02,5.878004313963851146e+00,4.000000039686763209e+00,-3.022410900280623203e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.164312749169597794e+01,3.289760788458196998e+02,5.875027709385592267e+00,4.000000039686763209e+00,-3.027410900280623207e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.164562749167117062e+01,3.289856240743562239e+02,5.872046331820592435e+00,4.000000039686763209e+00,-3.032410900280623212e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.164812749164636330e+01,3.289951678110109015e+02,5.869060182014194993e+00,4.000000039686763209e+00,-3.037410900280623216e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.165062749162155598e+01,3.290047100533977869e+02,5.866069260712937883e+00,4.000000039686763209e+00,-3.042410900280623220e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.165312749159674865e+01,3.290142507991312755e+02,5.863073568664550983e+00,4.000000039686763209e+00,-3.047410900280623225e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.165562749157194133e+01,3.290237900458262175e+02,5.860073106617957883e+00,4.000000039686763209e+00,-3.052410900280623229e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.165812749154713401e+01,3.290333277910978040e+02,5.857067875323274109e+00,4.000000039686763209e+00,-3.057410900280623234e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.166062749152232669e+01,3.290428640325615675e+02,5.854057875531807120e+00,4.000000039686763209e+00,-3.062410900280623238e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.166312749149751937e+01,3.290523987678334947e+02,5.851043107996056314e+00,4.000000039686763209e+00,-3.067410900280623243e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.166562749147271205e+01,3.290619319945298571e+02,5.848023573469714798e+00,4.000000039686763209e+00,-3.072410900280623247e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.166812749144790473e+01,3.290714637102673805e+02,5.844999272707664950e+00,4.000000039686763209e+00,-3.077410900280623252e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.167062749142309741e+01,3.290809939126631321e+02,5.841970206465982862e+00,4.000000039686763209e+00,-3.082410900280623256e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.167312749139829009e+01,3.290905225993345198e+02,5.838936375501934783e+00,4.000000039686763209e+00,-3.087410900280623260e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.167562749137348277e+01,3.291000497678994066e+02,5.835897780573978011e+00,4.000000039686763209e+00,-3.092410900280623265e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.167812749134867545e+01,3.291095754159759963e+02,5.832854422441761777e+00,4.000000039686763209e+00,-3.097410900280623269e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.168062749132386813e+01,3.291190995411828908e+02,5.829806301866125473e+00,4.000000039686763209e+00,-3.102410900280623274e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.168312749129906081e+01,3.291286221411390329e+02,5.826753419609099538e+00,4.000000039686763209e+00,-3.107410900280623278e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.168562749127425349e+01,3.291381432134637635e+02,5.823695776433903681e+00,4.000000039686763209e+00,-3.112410900280623283e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.168812749124944617e+01,3.291476627557768779e+02,5.820633373104949548e+00,4.000000039686763209e+00,-3.117410900280623287e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.169062749122463885e+01,3.291571807656984561e+02,5.817566210387837167e+00,4.000000039686763209e+00,-3.122410900280623292e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.169312749119983152e+01,3.291666972408489755e+02,5.814494289049357612e+00,4.000000039686763209e+00,-3.127410900280623296e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.169562749117502420e+01,3.291762121788493118e+02,5.811417609857491229e+00,4.000000039686763209e+00,-3.132410900280623300e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.169812749115021688e+01,3.291857255773207385e+02,5.808336173581407635e+00,4.000000039686763209e+00,-3.137410900280623305e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.170062749112540956e+01,3.291952374338849268e+02,5.805249980991466607e+00,4.000000039686763209e+00,-3.142410900280623309e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.170312749110060224e+01,3.292047477461638891e+02,5.802159032859215415e+00,4.000000039686763209e+00,-3.147410900280623314e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.170562749107579492e+01,3.292142565117800928e+02,5.799063329957391488e+00,4.000000039686763209e+00,-3.152410900280623318e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.170812749105098760e+01,3.292237637283562890e+02,5.795962873059920639e+00,4.000000039686763209e+00,-3.157410900280623323e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.171062749102618028e+01,3.292332693935156840e+02,5.792857662941917063e+00,4.000000039686763209e+00,-3.162410900280623327e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.171312749100137296e+01,3.292427735048818818e+02,5.789747700379682449e+00,4.000000039686763209e+00,-3.167410900280623332e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.171562749097656564e+01,3.292522760600788843e+02,5.786632986150708646e+00,4.000000039686763209e+00,-3.172410900280623336e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.171812749095175832e+01,3.292617770567309776e+02,5.783513521033673221e+00,4.000000039686763209e+00,-3.177410900280623340e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.172062749092695100e+01,3.292712764924629596e+02,5.780389305808443012e+00,4.000000039686763209e+00,-3.182410900280623345e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.172312749090214368e+01,3.292807743648999690e+02,5.777260341256071463e+00,4.000000039686763209e+00,-3.187410900280623349e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.172562749087733636e+01,3.292902706716675425e+02,5.774126628158799512e+00,4.000000039686763209e+00,-3.192410900280623354e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.172812749085252904e+01,3.292997654103916148e+02,5.770988167300055594e+00,4.000000039686763209e+00,-3.197410900280623358e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.173062749082772172e+01,3.293092585786984614e+02,5.767844959464455634e+00,4.000000039686763209e+00,-3.202410900280623363e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.173312749080291439e+01,3.293187501742148129e+02,5.764697005437800392e+00,4.000000039686763209e+00,-3.207410900280623367e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.173562749077810707e+01,3.293282401945677975e+02,5.761544306007079008e+00,4.000000039686763209e+00,-3.212410900280623371e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.173812749075329975e+01,3.293377286373848278e+02,5.758386861960466341e+00,4.000000039686763209e+00,-3.217410900280623376e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.174062749072849243e+01,3.293472155002938848e+02,5.755224674087323855e+00,4.000000039686763209e+00,-3.222410900280623380e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.174312749070368511e+01,3.293567007809231768e+02,5.752057743178197846e+00,4.000000039686763209e+00,-3.227410900280623385e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.174562749067887779e+01,3.293661844769014237e+02,5.748886070024821215e+00,4.000000039686763209e+00,-3.232410900280623389e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.174812749065407047e+01,3.293756665858577435e+02,5.745709655420111694e+00,4.000000039686763209e+00,-3.237410900280623394e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.175062749062926315e+01,3.293851471054215381e+02,5.742528500158173621e+00,4.000000039686763209e+00,-3.242410900280623398e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.175312749060445583e+01,3.293946260332227212e+02,5.739342605034295275e+00,4.000000039686763209e+00,-3.247410900280623403e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.175562749057964851e+01,3.294041033668915475e+02,5.736151970844950654e+00,4.000000039686763209e+00,-3.252410900280623407e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.175812749055484119e+01,3.294135791040586696e+02,5.732956598387798586e+00,4.000000039686763209e+00,-3.257410900280623411e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.176062749053003387e+01,3.294230532423551381e+02,5.729756488461681840e+00,4.000000039686763209e+00,-3.262410900280623416e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.176312749050522655e+01,3.294325257794124582e+02,5.726551641866628017e+00,4.000000039686763209e+00,-3.267410900280623420e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.176562749048041923e+01,3.294419967128624762e+02,5.723342059403848658e+00,4.000000039686763209e+00,-3.272410900280623425e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.176812749045561191e+01,3.294514660403374364e+02,5.720127741875739247e+00,4.000000039686763209e+00,-3.277410900280623429e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.177062749043080458e+01,3.294609337594700378e+02,5.716908690085879208e+00,4.000000039686763209e+00,-3.282410900280623434e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.177312749040599726e+01,3.294703998678933772e+02,5.713684904839031908e+00,4.000000039686763209e+00,-3.287410900280623438e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.177562749038118994e+01,3.294798643632408925e+02,5.710456386941143769e+00,4.000000039686763209e+00,-3.292410900280623443e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.177812749035638262e+01,3.294893272431464766e+02,5.707223137199343377e+00,4.000000039686763209e+00,-3.297410900280623447e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.178062749033157530e+01,3.294987885052443630e+02,5.703985156421943259e+00,4.000000039686763209e+00,-3.302410900280623451e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.178312749030676798e+01,3.295082481471692972e+02,5.700742445418438997e+00,4.000000039686763209e+00,-3.307410900280623456e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.178562749028196066e+01,3.295177061665563087e+02,5.697495004999508339e+00,4.000000039686763209e+00,-3.312410900280623460e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.178812749025715334e+01,3.295271625610409387e+02,5.694242835977011197e+00,4.000000039686763209e+00,-3.317410900280623465e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.179062749023234602e+01,3.295366173282590694e+02,5.690985939163989649e+00,4.000000039686763209e+00,-3.322410900280623469e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.179312749020753870e+01,3.295460704658470377e+02,5.687724315374668826e+00,4.000000039686763209e+00,-3.327410900280623474e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.179562749018273138e+01,3.295555219714415216e+02,5.684457965424453363e+00,4.000000039686763209e+00,-3.332410900280623478e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.179812749015792406e+01,3.295649718426796539e+02,5.681186890129931832e+00,4.000000039686763209e+00,-3.337410900280623482e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.180062749013311674e+01,3.295744200771989654e+02,5.677911090308872311e+00,4.000000039686763209e+00,-3.342410900280623487e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.180312749010830942e+01,3.295838666726374413e+02,5.674630566780225038e+00,4.000000039686763209e+00,-3.347410900280623491e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.180562749008350210e+01,3.295933116266334082e+02,5.671345320364120646e+00,4.000000039686763209e+00,-3.352410900280623496e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.180812749005869478e+01,3.296027549368255904e+02,5.668055351881871040e+00,4.000000039686763209e+00,-3.357410900280623500e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.181062749003388745e+01,3.296121966008531672e+02,5.664760662155967630e+00,4.000000039686763209e+00,-3.362410900280623505e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.181312749000908013e+01,3.296216366163557723e+02,5.661461252010083101e+00,4.000000039686763209e+00,-3.367410900280623509e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.181562748998427281e+01,3.296310749809733807e+02,5.658157122269070527e+00,4.000000039686763209e+00,-3.372410900280623514e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.181812748995946549e+01,3.296405116923463652e+02,5.654848273758962485e+00,4.000000039686763209e+00,-3.377410900280623518e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.182062748993465817e+01,3.296499467481156103e+02,5.651534707306970162e+00,4.000000039686763209e+00,-3.382410900280623522e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.182312748990985085e+01,3.296593801459222846e+02,5.648216423741486025e+00,4.000000039686763209e+00,-3.387410900280623527e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.182562748988504353e+01,3.296688118834080683e+02,5.644893423892080264e+00,4.000000039686763209e+00,-3.392410900280623531e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.182812748986023621e+01,3.296782419582150396e+02,5.641565708589502570e+00,4.000000039686763209e+00,-3.397410900280623536e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.183062748983542889e+01,3.296876703679856746e+02,5.638233278665683024e+00,4.000000039686763209e+00,-3.402410900280623540e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.183312748981062157e+01,3.296970971103628472e+02,5.634896134953727653e+00,4.000000039686763209e+00,-3.407410900280623545e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.183562748978581425e+01,3.297065221829898860e+02,5.631554278287922877e+00,4.000000039686763209e+00,-3.412410900280623549e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.183812748976100693e+01,3.297159455835105177e+02,5.628207709503733724e+00,4.000000039686763209e+00,-3.417410900280623554e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.184062748973619961e+01,3.297253673095689237e+02,5.624856429437801175e+00,4.000000039686763209e+00,-3.422410900280623558e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.184312748971139229e+01,3.297347873588096263e+02,5.621500438927945709e+00,4.000000039686763209e+00,-3.427410900280623562e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.184562748968658497e+01,3.297442057288776596e+02,5.618139738813165529e+00,4.000000039686763209e+00,-3.432410900280623567e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.184812748966177764e+01,3.297536224174183985e+02,5.614774329933634789e+00,4.000000039686763209e+00,-3.437410900280623571e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.185062748963697032e+01,3.297630374220776730e+02,5.611404213130705365e+00,4.000000039686763209e+00,-3.442410900280623576e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.185312748961216300e+01,3.297724507405017675e+02,5.608029389246907748e+00,4.000000039686763209e+00,-3.447410900280623580e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.185562748958735568e+01,3.297818623703373078e+02,5.604649859125946598e+00,4.000000039686763209e+00,-3.452410900280623585e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.185812748956254836e+01,3.297912723092314309e+02,5.601265623612705191e+00,4.000000039686763209e+00,-3.457410900280623589e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.186062748953774104e+01,3.298006805548316152e+02,5.597876683553241861e+00,4.000000039686763209e+00,-3.462410900280623594e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.186312748951293372e+01,3.298100871047857936e+02,5.594483039794792667e+00,4.000000039686763209e+00,-3.467410900280623598e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.186562748948812640e+01,3.298194919567423540e+02,5.591084693185767840e+00,4.000000039686763209e+00,-3.472410900280623602e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.186812748946331908e+01,3.298288951083500820e+02,5.587681644575753559e+00,4.000000039686763209e+00,-3.477410900280623607e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.187062748943851176e+01,3.298382965572581611e+02,5.584273894815512840e+00,4.000000039686763209e+00,-3.482410900280623611e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.187312748941370444e+01,3.298476963011162866e+02,5.580861444756981982e+00,4.000000039686763209e+00,-3.487410900280623616e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.187562748938889712e+01,3.298570943375744946e+02,5.577444295253274120e+00,4.000000039686763209e+00,-3.492410900280623620e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.187812748936408980e+01,3.298664906642832193e+02,5.574022447158676563e+00,4.000000039686763209e+00,-3.497410900280623625e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.188062748933928248e+01,3.298758852788934632e+02,5.570595901328651678e+00,4.000000039686763209e+00,-3.502410900280623629e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.188312748931447516e+01,3.298852781790565132e+02,5.567164658619836004e+00,4.000000039686763209e+00,-3.507410900280623633e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.188562748928966784e+01,3.298946693624241675e+02,5.563728719890039365e+00,4.000000039686763209e+00,-3.512410900280623638e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.188812748926486051e+01,3.299040588266486225e+02,5.560288085998246643e+00,4.000000039686763209e+00,-3.517410900280623642e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.189062748924005319e+01,3.299134465693825291e+02,5.556842757804616895e+00,4.000000039686763209e+00,-3.522410900280623647e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.189312748921524587e+01,3.299228325882789363e+02,5.553392736170481570e+00,4.000000039686763209e+00,-3.527410900280623651e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.189562748919043855e+01,3.299322168809913478e+02,5.549938021958346290e+00,4.000000039686763209e+00,-3.532410900280623656e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.189812748916563123e+01,3.299415994451737220e+02,5.546478616031889963e+00,4.000000039686763209e+00,-3.537410900280623660e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.190062748914082391e+01,3.299509802784803583e+02,5.543014519255963890e+00,4.000000039686763209e+00,-3.542410900280623665e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.190312748911601659e+01,3.299603593785660678e+02,5.539545732496591768e+00,4.000000039686763209e+00,-3.547410900280623669e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.190562748909120927e+01,3.299697367430861163e+02,5.536072256620970578e+00,4.000000039686763209e+00,-3.552410900280623673e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.190812748906640195e+01,3.299791123696961108e+02,5.532594092497468807e+00,4.000000039686763209e+00,-3.557410900280623678e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.191062748904159463e+01,3.299884862560521697e+02,5.529111240995628229e+00,4.000000039686763209e+00,-3.562410900280623682e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.191312748901678731e+01,3.299978583998108093e+02,5.525623702986161234e+00,4.000000039686763209e+00,-3.567410900280623687e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.191562748899197999e+01,3.300072287986290007e+02,5.522131479340952609e+00,4.000000039686763209e+00,-3.572410900280623691e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.191812748896717267e+01,3.300165974501641131e+02,5.518634570933057759e+00,4.000000039686763209e+00,-3.577410900280623696e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.192062748894236535e+01,3.300259643520740269e+02,5.515132978636704486e+00,4.000000039686763209e+00,-3.582410900280623700e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.192312748891755803e+01,3.300353295020170208e+02,5.511626703327290322e+00,4.000000039686763209e+00,-3.587410900280623705e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.192562748889275070e+01,3.300446928976517711e+02,5.508115745881384306e+00,4.000000039686763209e+00,-3.592410900280623709e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.192812748886794338e+01,3.300540545366374658e+02,5.504600107176725210e+00,4.000000039686763209e+00,-3.597410900280623713e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.193062748884313606e+01,3.300634144166336910e+02,5.501079788092223311e+00,4.000000039686763209e+00,-3.602410900280623718e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.193312748881832874e+01,3.300727725353004303e+02,5.497554789507957729e+00,4.000000039686763209e+00,-3.607410900280623722e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.193562748879352142e+01,3.300821288902981792e+02,5.494025112305179093e+00,4.000000039686763209e+00,-3.612410900280623727e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.193812748876871410e+01,3.300914834792878878e+02,5.490490757366305985e+00,4.000000039686763209e+00,-3.617410900280623731e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.194062748874390678e+01,3.301008362999308474e+02,5.486951725574927607e+00,4.000000039686763209e+00,-3.622410900280623736e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.194312748871909946e+01,3.301101873498889177e+02,5.483408017815801117e+00,4.000000039686763209e+00,-3.627410900280623740e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.194562748869429214e+01,3.301195366268242992e+02,5.479859634974854288e+00,4.000000039686763209e+00,-3.632410900280623745e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.194812748866948482e+01,3.301288841283996476e+02,5.476306577939181963e+00,4.000000039686763209e+00,-3.637410900280623749e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.195062748864467750e+01,3.301382298522781298e+02,5.472748847597048716e+00,4.000000039686763209e+00,-3.642410900280623753e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.195312748861987018e+01,3.301475737961233108e+02,5.469186444837887073e+00,4.000000039686763209e+00,-3.647410900280623758e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.195562748859506286e+01,3.301569159575991534e+02,5.465619370552298406e+00,4.000000039686763209e+00,-3.652410900280623762e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.195812748857025554e+01,3.301662563343701891e+02,5.462047625632050263e+00,4.000000039686763209e+00,-3.657410900280623767e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.196062748854544822e+01,3.301755949241012900e+02,5.458471210970079923e+00,4.000000039686763209e+00,-3.662410900280623771e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.196312748852064090e+01,3.301849317244577833e+02,5.454890127460489957e+00,4.000000039686763209e+00,-3.667410900280623776e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.196562748849583357e+01,3.301942667331055077e+02,5.451304375998551777e+00,4.000000039686763209e+00,-3.672410900280623780e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.196812748847102625e+01,3.302035999477106998e+02,5.447713957480702973e+00,4.000000039686763209e+00,-3.677410900280623784e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.197062748844621893e+01,3.302129313659400509e+02,5.444118872804548204e+00,4.000000039686763209e+00,-3.682410900280623789e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.197312748842141161e+01,3.302222609854607072e+02,5.440519122868859192e+00,4.000000039686763209e+00,-3.687410900280623793e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.197562748839660429e+01,3.302315888039402694e+02,5.436914708573572952e+00,4.000000039686763209e+00,-3.692410900280623798e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.197812748837179697e+01,3.302409148190467931e+02,5.433305630819792675e+00,4.000000039686763209e+00,-3.697410900280623802e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.198062748834698965e+01,3.302502390284487888e+02,5.429691890509788621e+00,4.000000039686763209e+00,-3.702410900280623807e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.198312748832218233e+01,3.302595614298151645e+02,5.426073488546995449e+00,4.000000039686763209e+00,-3.707410900280623811e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.198562748829737501e+01,3.302688820208153402e+02,5.422450425836013110e+00,4.000000039686763209e+00,-3.712410900280623816e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.198812748827256769e+01,3.302782007991191335e+02,5.418822703282607733e+00,4.000000039686763209e+00,-3.717410900280623820e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.199062748824776037e+01,3.302875177623968739e+02,5.415190321793709849e+00,4.000000039686763209e+00,-3.722410900280623824e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.199312748822295305e+01,3.302968329083193453e+02,5.411553282277415278e+00,4.000000039686763209e+00,-3.727410900280623829e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.199562748819814573e+01,3.303061462345577297e+02,5.407911585642983354e+00,4.000000039686763209e+00,-3.732410900280623833e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.199812748817333841e+01,3.303154577387837207e+02,5.404265232800837815e+00,4.000000039686763209e+00,-3.737410900280623838e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.200062748814853109e+01,3.303247674186694098e+02,5.400614224662567686e+00,4.000000039686763209e+00,-3.742410900280623842e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.200312748812372377e+01,3.303340752718874000e+02,5.396958562140924620e+00,4.000000039686763209e+00,-3.747410900280623847e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.200562748809891644e+01,3.303433812961107492e+02,5.393298246149824671e+00,4.000000039686763209e+00,-3.752410900280623851e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.200812748807410912e+01,3.303526854890129130e+02,5.389633277604345629e+00,4.000000039686763209e+00,-3.757410900280623856e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.201062748804930180e+01,3.303619878482678587e+02,5.385963657420730577e+00,4.000000039686763209e+00,-3.762410900280623860e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.201312748802449448e+01,3.303712883715500084e+02,5.382289386516384333e+00,4.000000039686763209e+00,-3.767410900280623864e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.201562748799968716e+01,3.303805870565341820e+02,5.378610465809875230e+00,4.000000039686763209e+00,-3.772410900280623869e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.201812748797487984e+01,3.303898839008957680e+02,5.374926896220932449e+00,4.000000039686763209e+00,-3.777410900280623873e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.202062748795007252e+01,3.303991789023104957e+02,5.371238678670448685e+00,4.000000039686763209e+00,-3.782410900280623878e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.202312748792526520e+01,3.304084720584546631e+02,5.367545814080478372e+00,4.000000039686763209e+00,-3.787410900280623882e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.202562748790045788e+01,3.304177633670049659e+02,5.363848303374237680e+00,4.000000039686763209e+00,-3.792410900280623887e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.202812748787565056e+01,3.304270528256386115e+02,5.360146147476104517e+00,4.000000039686763209e+00,-3.797410900280623891e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.203062748785084324e+01,3.304363404320332052e+02,5.356439347311617638e+00,4.000000039686763209e+00,-3.802410900280623895e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.203312748782603592e+01,3.304456261838668070e+02,5.352727903807476650e+00,4.000000039686763209e+00,-3.807410900280623900e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.203562748780122860e+01,3.304549100788180453e+02,5.349011817891542897e+00,4.000000039686763209e+00,-3.812410900280623904e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.203812748777642128e+01,3.304641921145658898e+02,5.345291090492837682e+00,4.000000039686763209e+00,-3.817410900280623909e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.204062748775161396e+01,3.304734722887898783e+02,5.341565722541542272e+00,4.000000039686763209e+00,-3.822410900280623913e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.204312748772680663e+01,3.304827505991699468e+02,5.337835714968999667e+00,4.000000039686763209e+00,-3.827410900280623918e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.204562748770199931e+01,3.304920270433864857e+02,5.334101068707711057e+00,4.000000039686763209e+00,-3.832410900280623922e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.204812748767719199e+01,3.305013016191204542e+02,5.330361784691338478e+00,4.000000039686763209e+00,-3.837410900280623927e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.205062748765238467e+01,3.305105743240531524e+02,5.326617863854702151e+00,4.000000039686763209e+00,-3.842410900280623931e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.205312748762757735e+01,3.305198451558664487e+02,5.322869307133783146e+00,4.000000039686763209e+00,-3.847410900280623935e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.205562748760277003e+01,3.305291141122426097e+02,5.319116115465719830e+00,4.000000039686763209e+00,-3.852410900280623940e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.205812748757796271e+01,3.305383811908643565e+02,5.315358289788810531e+00,4.000000039686763209e+00,-3.857410900280623944e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.206062748755315539e+01,3.305476463894149788e+02,5.311595831042511762e+00,4.000000039686763209e+00,-3.862410900280623949e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.206312748752834807e+01,3.305569097055781640e+02,5.307828740167438220e+00,4.000000039686763209e+00,-3.867410900280623953e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.206562748750354075e+01,3.305661711370380544e+02,5.304057018105362786e+00,4.000000039686763209e+00,-3.872410900280623958e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.206812748747873343e+01,3.305754306814793040e+02,5.300280665799214752e+00,4.000000039686763209e+00,-3.877410900280623962e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.207062748745392611e+01,3.305846883365870781e+02,5.296499684193083368e+00,4.000000039686763209e+00,-3.882410900280623967e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.207312748742911879e+01,3.305939441000468832e+02,5.292714074232213406e+00,4.000000039686763209e+00,-3.887410900280623971e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.207562748740431147e+01,3.306031979695448513e+02,5.288923836863007821e+00,4.000000039686763209e+00,-3.892410900280623975e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.207812748737950415e+01,3.306124499427674550e+02,5.285128973033025979e+00,4.000000039686763209e+00,-3.897410900280623980e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.208062748735469683e+01,3.306217000174017357e+02,5.281329483690983650e+00,4.000000039686763209e+00,-3.902410900280623984e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.208312748732988950e+01,3.306309481911351895e+02,5.277525369786753018e+00,4.000000039686763209e+00,-3.907410900280623989e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.208562748730508218e+01,3.306401944616557103e+02,5.273716632271362670e+00,4.000000039686763209e+00,-3.912410900280623993e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.208812748728027486e+01,3.306494388266517603e+02,5.269903272096996716e+00,4.000000039686763209e+00,-3.917410900280623998e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.209062748725546754e+01,3.306586812838122569e+02,5.266085290216994785e+00,4.000000039686763209e+00,-3.922410900280624002e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.209312748723066022e+01,3.306679218308266286e+02,5.262262687585852916e+00,4.000000039686763209e+00,-3.927410900280624007e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.209562748720585290e+01,3.306771604653846452e+02,5.258435465159221778e+00,4.000000039686763209e+00,-3.932410900280624011e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.209812748718104558e+01,3.306863971851767019e+02,5.254603623893907560e+00,4.000000039686763209e+00,-3.937410900280624015e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.210062748715623826e+01,3.306956319878936483e+02,5.250767164747869309e+00,4.000000039686763209e+00,-3.942410900280624020e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.210312748713143094e+01,3.307048648712267322e+02,5.246926088680222477e+00,4.000000039686763209e+00,-3.947410900280624024e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.210562748710662362e+01,3.307140958328677698e+02,5.243080396651236263e+00,4.000000039686763209e+00,-3.952410900280624029e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.210812748708181630e+01,3.307233248705089750e+02,5.239230089622332720e+00,4.000000039686763209e+00,-3.957410900280624033e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.211062748705700898e+01,3.307325519818431303e+02,5.235375168556089420e+00,4.000000039686763209e+00,-3.962410900280624038e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.211312748703220166e+01,3.307417771645634730e+02,5.231515634416236793e+00,4.000000039686763209e+00,-3.967410900280624042e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.211562748700739434e+01,3.307510004163636381e+02,5.227651488167657234e+00,4.000000039686763209e+00,-3.972410900280624046e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.211812748698258702e+01,3.307602217349378861e+02,5.223782730776388661e+00,4.000000039686763209e+00,-3.977410900280624051e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.212062748695777969e+01,3.307694411179808185e+02,5.219909363209619180e+00,4.000000039686763209e+00,-3.982410900280624055e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.212312748693297237e+01,3.307786585631876619e+02,5.216031386435691530e+00,4.000000039686763209e+00,-3.987410900280624060e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.212562748690816505e+01,3.307878740682539842e+02,5.212148801424099531e+00,4.000000039686763209e+00,-3.992410900280624064e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.212812748688335773e+01,3.307970876308759784e+02,5.208261609145489857e+00,4.000000039686763209e+00,-3.997410900280624069e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.213062748685855041e+01,3.308062992487501788e+02,5.204369810571660260e+00,4.000000039686763209e+00,-4.002410900280624073e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.213312748683374309e+01,3.308155089195737446e+02,5.200473406675559573e+00,4.000000039686763209e+00,-4.007410900280624078e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.213562748680893577e+01,3.308247166410442333e+02,5.196572398431289486e+00,4.000000039686763209e+00,-4.012410900280624082e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.213812748678412845e+01,3.308339224108597136e+02,5.192666786814101876e+00,4.000000039686763209e+00,-4.017410900280624086e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.214062748675932113e+01,3.308431262267187662e+02,5.188756572800400590e+00,4.000000039686763209e+00,-4.022410900280624091e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.214312748673451381e+01,3.308523280863204263e+02,5.184841757367737891e+00,4.000000039686763209e+00,-4.027410900280624095e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.214562748670970649e+01,3.308615279873641839e+02,5.180922341494818006e+00,4.000000039686763209e+00,-4.032410900280624100e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.214812748668489917e+01,3.308707259275500974e+02,5.176998326161494468e+00,4.000000039686763209e+00,-4.037410900280624104e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.215062748666009185e+01,3.308799219045786799e+02,5.173069712348771887e+00,4.000000039686763209e+00,-4.042410900280624109e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.215312748663528453e+01,3.308891159161509563e+02,5.169136501038803289e+00,4.000000039686763209e+00,-4.047410900280624113e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.215562748661047721e+01,3.308983079599684061e+02,5.165198693214891890e+00,4.000000039686763209e+00,-4.052410900280624118e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.215812748658566989e+01,3.309074980337330203e+02,5.161256289861488433e+00,4.000000039686763209e+00,-4.057410900280624122e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.216062748656086256e+01,3.309166861351473017e+02,5.157309291964194742e+00,4.000000039686763209e+00,-4.062410900280624126e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.216312748653605524e+01,3.309258722619142077e+02,5.153357700509760164e+00,4.000000039686763209e+00,-4.067410900280624131e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.216562748651124792e+01,3.309350564117372073e+02,5.149401516486082464e+00,4.000000039686763209e+00,-4.072410900280624135e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.216812748648644060e+01,3.309442385823202244e+02,5.145440740882207820e+00,4.000000039686763209e+00,-4.077410900280624140e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.217062748646163328e+01,3.309534187713677511e+02,5.141475374688329936e+00,4.000000039686763209e+00,-4.082410900280624144e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.217312748643682596e+01,3.309625969765847344e+02,5.137505418895790044e+00,4.000000039686763209e+00,-4.087410900280624149e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.217562748641201864e+01,3.309717731956766329e+02,5.133530874497077789e+00,4.000000039686763209e+00,-4.092410900280624153e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.217812748638721132e+01,3.309809474263494167e+02,5.129551742485828569e+00,4.000000039686763209e+00,-4.097410900280624158e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.218062748636240400e+01,3.309901196663094538e+02,5.125568023856825306e+00,4.000000039686763209e+00,-4.102410900280624162e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.218312748633759668e+01,3.309992899132637376e+02,5.121579719605998449e+00,4.000000039686763209e+00,-4.107410900280624166e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.218562748631278936e+01,3.310084581649197162e+02,5.117586830730423308e+00,4.000000039686763209e+00,-4.112410900280624171e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.218812748628798204e+01,3.310176244189852923e+02,5.113589358228321835e+00,4.000000039686763209e+00,-4.117410900280624175e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.219062748626317472e+01,3.310267886731689373e+02,5.109587303099062616e+00,4.000000039686763209e+00,-4.122410900280624180e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.219312748623836740e+01,3.310359509251795771e+02,5.105580666343159990e+00,4.000000039686763209e+00,-4.127410900280624184e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.219562748621356008e+01,3.310451111727266493e+02,5.101569448962272268e+00,4.000000039686763209e+00,-4.132410900280624189e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.219812748618875275e+01,3.310542694135200463e+02,5.097553651959203513e+00,4.000000039686763209e+00,-4.137410900280624193e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.220062748616394543e+01,3.310634256452702857e+02,5.093533276337903537e+00,4.000000039686763209e+00,-4.142410900280624197e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.220312748613913811e+01,3.310725798656882262e+02,5.089508323103466125e+00,4.000000039686763209e+00,-4.147410900280624202e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.220562748611433079e+01,3.310817320724853516e+02,5.085478793262129926e+00,4.000000039686763209e+00,-4.152410900280624206e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.220812748608952347e+01,3.310908822633736577e+02,5.081444687821276673e+00,4.000000039686763209e+00,-4.157410900280624211e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.221062748606471615e+01,3.311000304360655377e+02,5.077406007789433851e+00,4.000000039686763209e+00,-4.162410900280624215e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.221312748603990883e+01,3.311091765882739537e+02,5.073362754176270251e+00,4.000000039686763209e+00,-4.167410900280624220e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.221562748601510151e+01,3.311183207177123791e+02,5.069314927992599529e+00,4.000000039686763209e+00,-4.172410900280624224e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.221812748599029419e+01,3.311274628220947989e+02,5.065262530250378425e+00,4.000000039686763209e+00,-4.177410900280624229e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.222062748596548687e+01,3.311366028991356529e+02,5.061205561962706767e+00,4.000000039686763209e+00,-4.182410900280624233e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.222312748594067955e+01,3.311457409465499495e+02,5.057144024143825689e+00,4.000000039686763209e+00,-4.187410900280624237e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.222562748591587223e+01,3.311548769620531516e+02,5.053077917809120301e+00,4.000000039686763209e+00,-4.192410900280624242e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.222812748589106491e+01,3.311640109433612906e+02,5.049007243975117021e+00,4.000000039686763209e+00,-4.197410900280624246e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.223062748586625759e+01,3.311731428881908528e+02,5.044932003659483577e+00,4.000000039686763209e+00,-4.202410900280624251e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.223312748584145027e+01,3.311822727942588358e+02,5.040852197881030783e+00,4.000000039686763209e+00,-4.207410900280624255e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.223562748581664295e+01,3.311914006592827491e+02,5.036767827659709873e+00,4.000000039686763209e+00,-4.212410900280624260e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.223812748579183562e+01,3.312005264809806704e+02,5.032678894016613391e+00,4.000000039686763209e+00,-4.217410900280624264e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.224062748576702830e+01,3.312096502570711323e+02,5.028585397973975191e+00,4.000000039686763209e+00,-4.222410900280624269e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.224312748574222098e+01,3.312187719852731789e+02,5.024487340555168657e+00,4.000000039686763209e+00,-4.227410900280624273e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.224562748571741366e+01,3.312278916633063659e+02,5.020384722784708487e+00,4.000000039686763209e+00,-4.232410900280624277e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.224812748569260634e+01,3.312370092888908175e+02,5.016277545688248907e+00,4.000000039686763209e+00,-4.237410900280624282e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.225062748566779902e+01,3.312461248597471126e+02,5.012165810292583679e+00,4.000000039686763209e+00,-4.242410900280624286e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.225312748564299170e+01,3.312552383735963417e+02,5.008049517625646985e+00,4.000000039686763209e+00,-4.247410900280624291e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.225562748561818438e+01,3.312643498281601637e+02,5.003928668716512540e+00,4.000000039686763209e+00,-4.252410900280624295e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.225812748559337706e+01,3.312734592211606355e+02,4.999803264595391816e+00,4.000000039686763209e+00,-4.257410900280624300e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.226062748556856974e+01,3.312825665503204959e+02,4.995673306293636706e+00,4.000000039686763209e+00,-4.262410900280624304e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.226312748554376242e+01,3.312916718133628819e+02,4.991538794843735971e+00,4.000000039686763209e+00,-4.267410900280624309e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.226562748551895510e+01,3.313007750080114420e+02,4.987399731279317905e+00,4.000000039686763209e+00,-4.272410900280624313e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.226812748549414778e+01,3.313098761319903929e+02,4.983256116635147670e+00,4.000000039686763209e+00,-4.277410900280624317e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.227062748546934046e+01,3.313189751830244631e+02,4.979107951947129962e+00,4.000000039686763209e+00,-4.282410900280624322e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.227312748544453314e+01,3.313280721588388928e+02,4.974955238252304568e+00,4.000000039686763209e+00,-4.287410900280624326e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.227562748541972582e+01,3.313371670571594905e+02,4.970797976588850808e+00,4.000000039686763209e+00,-4.292410900280624331e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.227812748539491849e+01,3.313462598757124624e+02,4.966636167996083984e+00,4.000000039686763209e+00,-4.297410900280624335e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.228062748537011117e+01,3.313553506122246404e+02,4.962469813514456263e+00,4.000000039686763209e+00,-4.302410900280624340e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.228312748534530385e+01,3.313644392644233108e+02,4.958298914185556683e+00,4.000000039686763209e+00,-4.307410900280624344e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.228562748532049653e+01,3.313735258300363284e+02,4.954123471052109373e+00,4.000000039686763209e+00,-4.312410900280624348e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.228812748529568921e+01,3.313826103067920030e+02,4.949943485157975331e+00,4.000000039686763209e+00,-4.317410900280624353e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.229062748527088189e+01,3.313916926924192694e+02,4.945758957548150647e+00,4.000000039686763209e+00,-4.322410900280624357e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.229312748524607457e+01,3.314007729846475172e+02,4.941569889268767390e+00,4.000000039686763209e+00,-4.327410900280624362e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.229562748522126725e+01,3.314098511812067045e+02,4.937376281367092723e+00,4.000000039686763209e+00,-4.332410900280624366e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.229812748519645993e+01,3.314189272798272441e+02,4.933178134891528899e+00,4.000000039686763209e+00,-4.337410900280624371e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.230062748517165261e+01,3.314280012782401172e+02,4.928975450891611487e+00,4.000000039686763209e+00,-4.342410900280624375e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.230312748514684529e+01,3.314370731741768168e+02,4.924768230418012926e+00,4.000000039686763209e+00,-4.347410900280624380e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.230562748512203797e+01,3.314461429653694040e+02,4.920556474522537194e+00,4.000000039686763209e+00,-4.352410900280624384e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.230812748509723065e+01,3.314552106495503949e+02,4.916340184258123358e+00,4.000000039686763209e+00,-4.357410900280624388e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.231062748507242333e+01,3.314642762244528740e+02,4.912119360678844693e+00,4.000000039686763209e+00,-4.362410900280624393e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.231312748504761601e+01,3.314733396878104372e+02,4.907894004839906010e+00,4.000000039686763209e+00,-4.367410900280624397e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.231562748502280868e+01,3.314824010373572492e+02,4.903664117797647215e+00,4.000000039686763209e+00,-4.372410900280624402e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.231812748499800136e+01,3.314914602708279858e+02,4.899429700609539751e+00,4.000000039686763209e+00,-4.377410900280624406e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.232062748497319404e+01,3.315005173859577781e+02,4.895190754334187488e+00,4.000000039686763209e+00,-4.382410900280624411e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.232312748494838672e+01,3.315095723804823820e+02,4.890947280031327615e+00,4.000000039686763209e+00,-4.387410900280624415e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.232562748492357940e+01,3.315186252521380652e+02,4.886699278761827969e+00,4.000000039686763209e+00,-4.392410900280624420e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.232812748489877208e+01,3.315276759986616071e+02,4.882446751587689704e+00,4.000000039686763209e+00,-4.397410900280624424e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.233062748487396476e+01,3.315367246177902985e+02,4.878189699572043736e+00,4.000000039686763209e+00,-4.402410900280624428e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.233312748484915744e+01,3.315457711072619986e+02,4.873928123779153410e+00,4.000000039686763209e+00,-4.407410900280624433e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.233562748482435012e+01,3.315548154648150785e+02,4.869662025274412720e+00,4.000000039686763209e+00,-4.412410900280624437e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.233812748479954280e+01,3.315638576881884205e+02,4.865391405124346313e+00,4.000000039686763209e+00,-4.417410900280624442e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.234062748477473548e+01,3.315728977751215325e+02,4.861116264396609488e+00,4.000000039686763209e+00,-4.422410900280624446e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.234312748474992816e+01,3.315819357233543769e+02,4.856836604159986415e+00,4.000000039686763209e+00,-4.427410900280624451e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.234562748472512084e+01,3.315909715306274279e+02,4.852552425484392806e+00,4.000000039686763209e+00,-4.432410900280624455e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.234812748470031352e+01,3.316000051946817280e+02,4.848263729440873249e+00,4.000000039686763209e+00,-4.437410900280624459e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.235062748467550620e+01,3.316090367132588881e+02,4.843970517101602091e+00,4.000000039686763209e+00,-4.442410900280624464e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.235312748465069888e+01,3.316180660841010308e+02,4.839672789539881670e+00,4.000000039686763209e+00,-4.447410900280624468e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.235562748462589155e+01,3.316270933049508471e+02,4.835370547830144083e+00,4.000000039686763209e+00,-4.452410900280624473e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.235812748460108423e+01,3.316361183735514828e+02,4.831063793047950305e+00,4.000000039686763209e+00,-4.457410900280624477e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.236062748457627691e+01,3.316451412876466520e+02,4.826752526269988408e+00,4.000000039686763209e+00,-4.462410900280624482e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.236312748455146959e+01,3.316541620449806942e+02,4.822436748574075338e+00,4.000000039686763209e+00,-4.467410900280624486e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.236562748452666227e+01,3.316631806432983467e+02,4.818116461039155141e+00,4.000000039686763209e+00,-4.472410900280624491e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.236812748450185495e+01,3.316721970803450290e+02,4.813791664745299848e+00,4.000000039686763209e+00,-4.477410900280624495e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.237062748447704763e+01,3.316812113538666154e+02,4.809462360773708589e+00,4.000000039686763209e+00,-4.482410900280624499e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.237312748445224031e+01,3.316902234616094916e+02,4.805128550206707594e+00,4.000000039686763209e+00,-4.487410900280624504e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.237562748442743299e+01,3.316992334013206687e+02,4.800790234127749301e+00,4.000000039686763209e+00,-4.492410900280624508e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.237812748440262567e+01,3.317082411707476695e+02,4.796447413621412359e+00,4.000000039686763209e+00,-4.497410900280624513e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.238062748437781835e+01,3.317172467676385281e+02,4.792100089773402516e+00,4.000000039686763209e+00,-4.502410900280624517e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.238312748435301103e+01,3.317262501897418474e+02,4.787748263670549953e+00,4.000000039686763209e+00,-4.507410900280624522e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.238562748432820371e+01,3.317352514348067984e+02,4.783391936400811950e+00,4.000000039686763209e+00,-4.512410900280624526e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.238812748430339639e+01,3.317442505005830071e+02,4.779031109053269333e+00,4.000000039686763209e+00,-4.517410900280624531e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.239062748427858907e+01,3.317532473848207815e+02,4.774665782718130025e+00,4.000000039686763209e+00,-4.522410900280624535e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.239312748425378174e+01,3.317622420852708842e+02,4.770295958486724608e+00,4.000000039686763209e+00,-4.527410900280624539e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.239562748422897442e+01,3.317712345996845897e+02,4.765921637451509874e+00,4.000000039686763209e+00,-4.532410900280624544e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.239812748420416710e+01,3.317802249258137977e+02,4.761542820706065271e+00,4.000000039686763209e+00,-4.537410900280624548e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.240062748417935978e+01,3.317892130614109760e+02,4.757159509345095572e+00,4.000000039686763209e+00,-4.542410900280624553e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.240312748415455246e+01,3.317981990042290477e+02,4.752771704464429092e+00,4.000000039686763209e+00,-4.547410900280624557e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.240562748412974514e+01,3.318071827520215038e+02,4.748379407161015919e+00,4.000000039686763209e+00,-4.552410900280624562e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.240812748410493782e+01,3.318161643025424041e+02,4.743982618532930573e+00,4.000000039686763209e+00,-4.557410900280624566e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.241062748408013050e+01,3.318251436535464336e+02,4.739581339679371119e+00,4.000000039686763209e+00,-4.562410900280624571e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.241312748405532318e+01,3.318341208027886751e+02,4.735175571700656505e+00,4.000000039686763209e+00,-4.567410900280624575e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.241562748403051586e+01,3.318430957480248935e+02,4.730765315698228335e+00,4.000000039686763209e+00,-4.572410900280624579e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.241812748400570854e+01,3.318520684870113087e+02,4.726350572774650871e+00,4.000000039686763209e+00,-4.577410900280624584e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.242062748398090122e+01,3.318610390175047655e+02,4.721931344033610145e+00,4.000000039686763209e+00,-4.582410900280624588e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.242312748395609390e+01,3.318700073372626207e+02,4.717507630579913069e+00,4.000000039686763209e+00,-4.587410900280624593e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.242562748393128658e+01,3.318789734440427992e+02,4.713079433519488326e+00,4.000000039686763209e+00,-4.592410900280624597e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.242812748390647926e+01,3.318879373356037945e+02,4.708646753959384590e+00,4.000000039686763209e+00,-4.597410900280624602e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.243062748388167194e+01,3.318968990097046117e+02,4.704209593007772305e+00,4.000000039686763209e+00,-4.602410900280624606e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.243312748385686461e+01,3.319058584641048242e+02,4.699767951773941022e+00,4.000000039686763209e+00,-4.607410900280624610e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.243562748383205729e+01,3.319148156965646308e+02,4.695321831368302057e+00,4.000000039686763209e+00,-4.612410900280624615e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.243812748380724997e+01,3.319237707048446282e+02,4.690871232902384946e+00,4.000000039686763209e+00,-4.617410900280624619e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.244062748378244265e+01,3.319327234867061520e+02,4.686416157488839218e+00,4.000000039686763209e+00,-4.622410900280624624e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.244312748375763533e+01,3.319416740399109358e+02,4.681956606241433505e+00,4.000000039686763209e+00,-4.627410900280624628e-01,0.000000000000000000e+00,-1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.244562748373282801e+01,3.319506223622213952e+02,4.677492580275055545e+00,4.000000039686763209e+00,-4.632410900280624633e-01,0.000000000000000000e+00,-1.361524071352429588e-01,-9.947598498035393721e-10,0.000000000000000000e+00 +5.244812748370802069e+01,3.319595684514004006e+02,4.673024080705712180e+00,4.000000039686763209e+00,-4.637410900280624637e-01,-2.486899599834599427e-12,-1.361524071352429588e-01,4.728917795706051954e-05,0.000000000000000000e+00 +5.245062748368321337e+01,3.319685123052114477e+02,4.668551108650527581e+00,4.000000039686756992e+00,-4.642410900280624642e-01,1.182204568200799707e-07,-1.361524071352429588e-01,-6.226300161337222638e-01,0.000000000000000000e+00 +5.245312748365840605e+01,3.319774539214186007e+02,4.664073665227745913e+00,4.000000039982308131e+00,-4.647410900280624646e-01,-1.556456804433632019e-03,-1.361524071352429588e-01,-9.999970095018885230e-01,0.000000000000000000e+00 +5.245562748363341399e+01,3.319863932977864351e+02,4.659591751556726891e+00,3.999996148840335941e+00,-4.652410900280624650e-01,-4.056449303199485650e-03,-1.361524071352429588e-01,-9.999984635107894704e-01,0.000000000000000000e+00 +5.245812748604038944e+01,3.319953304320800953e+02,4.655105368757949336e+00,3.999986007707314162e+00,-4.657410900280624655e-01,-6.556447868949868626e-03,-1.361524071352429588e-01,-9.999989461686473735e-01,0.000000000000000000e+00 +5.246062749478560505e+01,3.320042653220652937e+02,4.650614517953009397e+00,3.999969616530304251e+00,-4.662410900280624659e-01,-9.056453979575791041e-03,-1.361524071352429588e-01,-9.999991858710256531e-01,0.000000000000000000e+00 +5.246312751377541872e+01,3.320131979655083114e+02,4.646119200264618776e+00,3.999946975223374945e+00,-4.667410900280624664e-01,-1.155647093405069888e-02,-1.361524071352429588e-01,-9.999993282724229937e-01,0.000000000000000000e+00 +5.246562754691634467e+01,3.320221283601759978e+02,4.641619416816608279e+00,3.999918083663047685e+00,-4.672410900280624668e-01,-1.405650239563420792e-02,-1.361524071352429588e-01,-9.999994220104665432e-01,0.000000000000000000e+00 +5.246812759811510318e+01,3.320310565038357709e+02,4.637115168733922488e+00,3.999882941687383120e+00,-4.677410900280624673e-01,-1.655655214938988110e-02,-1.361524071352429588e-01,-9.999994874858296745e-01,0.000000000000000000e+00 +5.247062767127869165e+01,3.320399823942555599e+02,4.632606457142624201e+00,3.999841549095672910e+00,-4.682410900280624677e-01,-1.905662403165344493e-02,-1.361524071352429588e-01,-9.999995356202230345e-01,0.000000000000000000e+00 +5.247312777031442721e+01,3.320489060292039198e+02,4.628093283169890881e+00,3.999793905648306946e+00,-4.687410900280624682e-01,-2.155672190639629227e-02,-1.361524071352429588e-01,-9.999995716222375153e-01,0.000000000000000000e+00 +5.247562789913003201e+01,3.320578274064499738e+02,4.623575647944015543e+00,3.999740011066698742e+00,-4.692410900280624686e-01,-2.405684965100355482e-02,-1.361524071352429588e-01,-9.999995993924208904e-01,0.000000000000000000e+00 +5.247812806163367583e+01,3.320667465237632996e+02,4.619053552594407641e+00,3.999679865033245463e+00,-4.697410900280624690e-01,-2.655701115306510762e-02,-1.361524071352429588e-01,-9.999996206707065793e-01,0.000000000000000000e+00 +5.248062826173404716e+01,3.320756633789141574e+02,4.614526998251590406e+00,3.999613467191295069e+00,-4.702410900280624695e-01,-2.905721030503497296e-02,-1.361524071352429588e-01,-9.999996373808774930e-01,0.000000000000000000e+00 +5.248312850334040292e+01,3.320845779696733189e+02,4.609995986047202621e+00,3.999540817145125882e+00,-4.707410900280624699e-01,-3.155745100475219195e-02,-1.361524071352429588e-01,-9.999996497833596454e-01,0.000000000000000000e+00 +5.248562879036263951e+01,3.320934902938121809e+02,4.605460517113997732e+00,3.999461914459923939e+00,-4.712410900280624704e-01,-3.405773715134328972e-02,-1.361524071352429588e-01,-9.999996593167913561e-01,0.000000000000000000e+00 +5.248812912671134967e+01,3.321024003491025951e+02,4.600920592585842961e+00,3.999376758661769671e+00,-4.717410900280624708e-01,-3.655807264822932140e-02,-1.361524071352429588e-01,-9.999996656853115118e-01,0.000000000000000000e+00 +5.249062951629788643e+01,3.321113081333170953e+02,4.596376213597719307e+00,3.999285349237616138e+00,-4.722410900280624713e-01,-3.905846139885035817e-02,-1.361524071352429588e-01,-9.999996698419968411e-01,0.000000000000000000e+00 +5.249312996303442702e+01,3.321202136442287269e+02,4.591827381285721543e+00,3.999187685635277045e+00,-4.727410900280624717e-01,-4.155890730984949932e-02,-1.361524071352429588e-01,-9.999996712894109185e-01,0.000000000000000000e+00 +5.249563047083402978e+01,3.321291168796111037e+02,4.587274096787057331e+00,3.999083767263405864e+00,-4.732410900280624722e-01,-4.405941428750728694e-02,-1.361524071352429588e-01,-9.999996707786836803e-01,0.000000000000000000e+00 +5.249813104361069094e+01,3.321380178372384080e+02,4.582716361240048109e+00,3.998973593491482958e+00,-4.737410900280624726e-01,-4.655998624092497901e-02,-1.361524071352429588e-01,-9.999996677523165234e-01,0.000000000000000000e+00 +5.250063168527940860e+01,3.321469165148854472e+02,4.578154175784127311e+00,3.998857163649793822e+00,-4.742410900280624730e-01,-4.906062707881363866e-02,-1.361524071352429588e-01,-9.999996622617782771e-01,0.000000000000000000e+00 +5.250313239975626090e+01,3.321558129103274837e+02,4.573587541559841263e+00,3.998734477029414425e+00,-4.747410900280624735e-01,-5.156134071107818656e-02,-1.361524071352429588e-01,-9.999996541860204369e-01,0.000000000000000000e+00 +5.250563319095844150e+01,3.321647070213404618e+02,4.569016459708849176e+00,3.998605532882191671e+00,-4.752410900280624739e-01,-5.406213104844737743e-02,-1.361524071352429588e-01,-9.999996429473300141e-01,0.000000000000000000e+00 +5.250813406280433071e+01,3.321735988457008375e+02,4.564440931373920485e+00,3.998470330420723862e+00,-4.757410900280624744e-01,-5.656300200139314366e-02,-1.361524071352429588e-01,-9.999996282923038216e-01,0.000000000000000000e+00 +5.251063501921356647e+01,3.321824883811856921e+02,4.559860957698938400e+00,3.998328868818342929e+00,-4.762410900280624748e-01,-5.906395748100297383e-02,-1.361524071352429588e-01,-9.999996089426277379e-01,0.000000000000000000e+00 +5.251313606410709411e+01,3.321913756255726184e+02,4.555276539828895466e+00,3.998181147209093567e+00,-4.767410900280624753e-01,-6.156500139647800435e-02,-1.361524071352429588e-01,-9.999995842280600122e-01,0.000000000000000000e+00 +5.251563720140723035e+01,3.322002605766397778e+02,4.550687678909896228e+00,3.998027164687717683e+00,-4.772410900280624757e-01,-6.406613765671499705e-02,-1.361524071352429588e-01,-9.999995518145091689e-01,0.000000000000000000e+00 +5.251813843503774137e+01,3.322091432321659568e+02,4.546094376089156341e+00,3.997866920309633976e+00,-4.777410900280624761e-01,-6.656737016620600800e-02,-1.361524071352429588e-01,-9.999995094080947888e-01,0.000000000000000000e+00 +5.252063976892387132e+01,3.322180235899305103e+02,4.541496632515001686e+00,3.997700413090926830e+00,-4.782410900280624766e-01,-6.906870282519968207e-02,-1.361524071352429588e-01,-9.999994519871288068e-01,0.000000000000000000e+00 +5.252314120699242750e+01,3.322269016477133050e+02,4.536894449336867474e+00,3.997527642008333881e+00,-4.787410900280624770e-01,-7.157013952293850290e-02,-1.361524071352429588e-01,-9.999993717324663356e-01,0.000000000000000000e+00 +5.252564275317185150e+01,3.322357774032948896e+02,4.532287827705300032e+00,3.997348605999249571e+00,-4.792410900280624775e-01,-7.407168413072030833e-02,-1.361524071352429588e-01,-9.999992532039050364e-01,0.000000000000000000e+00 +5.252814441139224755e+01,3.322446508544562676e+02,4.527676768771954130e+00,3.997163303961745129e+00,-4.797410900280624779e-01,-7.657334048289109185e-02,-1.361524071352429588e-01,-9.999990631988026069e-01,0.000000000000000000e+00 +5.253064618558548204e+01,3.322535219989790676e+02,4.523061273689594763e+00,3.996971734754635186e+00,-4.802410900280624784e-01,-7.907511233246167226e-02,-1.361524071352429588e-01,-9.999987126664052761e-01,0.000000000000000000e+00 +5.253314807968521905e+01,3.322623908346455437e+02,4.518441343612095373e+00,3.996773897197654524e+00,-4.807410900280624788e-01,-8.157700321142680178e-02,-1.361524071352429588e-01,-9.999978618107825401e-01,0.000000000000000000e+00 +5.253565009762699134e+01,3.322712573592384615e+02,4.513816979694438736e+00,3.996569790071983430e+00,-4.812410900280624793e-01,-8.407901580341238523e-02,-1.361524071352429588e-01,-9.999928785442252499e-01,0.000000000000000000e+00 +5.253815224334826439e+01,3.322801215705412119e+02,4.509188183092716073e+00,3.996359412122342025e+00,-4.817410900280624797e-01,-8.658114370576590335e-02,-1.361524071352429588e-01,9.999951334547159121e-01,0.000000000000000000e+00 +5.254065452078849319e+01,3.322889834663377542e+02,4.504554954964126168e+00,3.996142762079697874e+00,-4.822410900280624801e-01,-8.407887844298352065e-02,-1.361524071352429588e-01,9.999982567829646118e-01,0.000000000000000000e+00 +5.254315693388917197e+01,3.322978430444125593e+02,4.499917296466976246e+00,3.995932361992792003e+00,-4.827410900280624806e-01,-8.157646970455662006e-02,-1.361524071352429588e-01,9.999989636149050343e-01,0.000000000000000000e+00 +5.254565947875082088e+01,3.323067003025507802e+02,4.495275208760681096e+00,3.995728213217701441e+00,-4.832410900280624810e-01,-7.907392743650831779e-02,-1.361524071352429588e-01,9.999992752012524244e-01,0.000000000000000000e+00 +5.254816215147188529e+01,3.323155552385380815e+02,4.490628693005762173e+00,3.995530317056558811e+00,-4.837410900280624815e-01,-7.657125652937980809e-02,-1.361524071352429588e-01,9.999994502478650737e-01,0.000000000000000000e+00 +5.255066494814879263e+01,3.323244078501607532e+02,4.485977750363848493e+00,3.995338674770170684e+00,-4.842410900280624819e-01,-7.406846122839320923e-02,-1.361524071352429588e-01,9.999995619344629327e-01,0.000000000000000000e+00 +5.255316786487601632e+01,3.323332581352055968e+02,4.481322381997675741e+00,3.995153287579602530e+00,-4.847410900280624824e-01,-7.156554559761257872e-02,-1.361524071352429588e-01,9.999996392191797812e-01,0.000000000000000000e+00 +5.255567089774613976e+01,3.323421060914600957e+02,4.476662589071085385e+00,3.994974156666603271e+00,-4.852410900280624828e-01,-6.906251363053375614e-02,-1.361524071352429588e-01,9.999996957102712525e-01,0.000000000000000000e+00 +5.255817404284992023e+01,3.323509517167122453e+02,4.471998372749026451e+00,3.994801283173754047e+00,-4.857410900280624833e-01,-6.655936928843200762e-02,-1.361524071352429588e-01,9.999997388877841509e-01,0.000000000000000000e+00 +5.256067729627634577e+01,3.323597950087506092e+02,4.467329734197552860e+00,3.994634668204521954e+00,-4.862410900280624837e-01,-6.405611651563497544e-02,-1.361524071352429588e-01,9.999997726578465640e-01,0.000000000000000000e+00 +5.256318065411269203e+01,3.323686359653643763e+02,4.462656674583824312e+00,3.994474312823276474e+00,-4.867410900280624841e-01,-6.155275924840503121e-02,-1.361524071352429588e-01,9.999997998344175576e-01,0.000000000000000000e+00 +5.256568411244459327e+01,3.323774745843433038e+02,4.457979195076105405e+00,3.994320218055284588e+00,-4.872410900280624846e-01,-5.904930141761071533e-02,-1.361524071352429588e-01,9.999998221396403375e-01,0.000000000000000000e+00 +5.256818766735609216e+01,3.323863108634777745e+02,4.453297296843766517e+00,3.994172384886700122e+00,-4.877410900280624850e-01,-5.654574695139791274e-02,-1.361524071352429588e-01,9.999998407709849157e-01,0.000000000000000000e+00 +5.257069131492970371e+01,3.323951448005586826e+02,4.448610981057281144e+00,3.994030814264547313e+00,-4.882410900280624855e-01,-5.404209977644166413e-02,-1.361524071352429588e-01,9.999998565429262243e-01,0.000000000000000000e+00 +5.257319505124647918e+01,3.324039763933775475e+02,4.443920248888229452e+00,3.993895507096702158e+00,-4.887410900280624859e-01,-5.153836381884348977e-02,-1.361524071352429588e-01,9.999998699577867800e-01,0.000000000000000000e+00 +5.257569887238607009e+01,3.324128056397264572e+02,4.439225101509293836e+00,3.993766464251872428e+00,-4.892410900280624864e-01,-4.903454300485148715e-02,-1.361524071352429588e-01,9.999998815597533897e-01,0.000000000000000000e+00 +5.257820277442679213e+01,3.324216325373981249e+02,4.434525540094260698e+00,3.993643686559576800e+00,-4.897410900280624868e-01,-4.653064126069410278e-02,-1.361524071352429588e-01,9.999998916514015734e-01,0.000000000000000000e+00 +5.258070675344566780e+01,3.324304570841858322e+02,4.429821565818020446e+00,3.993527174810125313e+00,-4.902410900280624872e-01,-4.402666251312366968e-02,-1.361524071352429588e-01,9.999999005768399618e-01,0.000000000000000000e+00 +5.258321080551850457e+01,3.324392792778834291e+02,4.425113179856567491e+00,3.993416929754599387e+00,-4.907410900280624877e-01,-4.152261068925099108e-02,-1.361524071352429588e-01,9.999999083674193656e-01,0.000000000000000000e+00 +5.258571492671994463e+01,3.324480991162853911e+02,4.420400383386997589e+00,3.993312952104833169e+00,-4.912410900280624881e-01,-3.901848971726705473e-02,-1.361524071352429588e-01,9.999999153081770009e-01,0.000000000000000000e+00 +5.258821911312355013e+01,3.324569165971867051e+02,4.415683177587509611e+00,3.993215242533393994e+00,-4.917410900280624886e-01,-3.651430352574633331e-02,-1.361524071352429588e-01,9.999999217251319683e-01,0.000000000000000000e+00 +5.259072336080183163e+01,3.324657317183830401e+02,4.410961563637405547e+00,3.993123801673565509e+00,-4.922410900280624890e-01,-3.401005604348262407e-02,-1.361524071352429588e-01,9.999999271353996466e-01,0.000000000000000000e+00 +5.259322766582633335e+01,3.324745444776706336e+02,4.406235542717088727e+00,3.993038630119332133e+00,-4.927410900280624895e-01,-3.150575120145321373e-02,-1.361524071352429588e-01,9.999999322298342985e-01,0.000000000000000000e+00 +5.259573202426769001e+01,3.324833548728462347e+02,4.401505116008064711e+00,3.992959728425359511e+00,-4.932410900280624899e-01,-2.900139292981798733e-02,-1.361524071352429588e-01,9.999999368900522878e-01,0.000000000000000000e+00 +5.259823643219567657e+01,3.324921629017072746e+02,4.396770284692939512e+00,3.992887097106983418e+00,-4.937410900280624904e-01,-2.649698515988436337e-02,-1.361524071352429588e-01,9.999999410381305021e-01,0.000000000000000000e+00 +5.260074088567928641e+01,3.325009685620517530e+02,4.392031049955421373e+00,3.992820736640194657e+00,-4.942410900280624908e-01,-2.399253182394437897e-02,-1.361524071352429588e-01,9.999999447780500983e-01,0.000000000000000000e+00 +5.260324538078677392e+01,3.325097718516782948e+02,4.387287412980318990e+00,3.992760647461625290e+00,-4.947410900280624912e-01,-2.148803685475747863e-02,-1.361524071352429588e-01,9.999999482539231321e-01,0.000000000000000000e+00 +5.260574991358573982e+01,3.325185727683860364e+02,4.382539374953540623e+00,3.992706829968537097e+00,-4.952410900280624917e-01,-1.898350418538831061e-02,-1.361524071352429588e-01,9.999999515083298762e-01,0.000000000000000000e+00 +5.260825448014318084e+01,3.325273713099747397e+02,4.377786937062096762e+00,3.992659284518811358e+00,-4.957410900280624921e-01,-1.647893774939929515e-02,-1.361524071352429588e-01,9.999999544114039907e-01,0.000000000000000000e+00 +5.261075907652553951e+01,3.325361674742447917e+02,4.373030100494096573e+00,3.992618011430939085e+00,-4.962410900280624926e-01,-1.397434148122079882e-02,-1.361524071352429588e-01,9.999999572271204284e-01,0.000000000000000000e+00 +5.261326369879878939e+01,3.325449612589970911e+02,4.368268866438749676e+00,3.992583010984011249e+00,-4.967410900280624930e-01,-1.146971931510297298e-02,-1.361524071352429588e-01,9.999999595513126005e-01,0.000000000000000000e+00 +5.261576834302847772e+01,3.325537526620332756e+02,4.363503236086363479e+00,3.992554283417712568e+00,-4.972410900280624935e-01,-8.965075186727410744e-03,-1.361524071352429588e-01,9.999999620813972978e-01,0.000000000000000000e+00 +5.261827300527978934e+01,3.325625416811554373e+02,4.358733210628346733e+00,3.992531828932312177e+00,-4.977410900280624939e-01,-6.460413030386293227e-03,-1.361524071352429588e-01,9.999999641386266847e-01,0.000000000000000000e+00 +5.262077768161763203e+01,3.325713283141663510e+02,4.353958791257205085e+00,3.992515647688662295e+00,-4.982410900280624944e-01,-3.955736782367381445e-03,-1.361524071352429588e-01,9.999999661457279476e-01,0.000000000000000000e+00 +5.262328236810665771e+01,3.325801125588693594e+02,4.349179979166542864e+00,3.992505739808189347e+00,-4.987410900280624948e-01,-1.451050378133385667e-03,-1.361524071352429588e-01,9.999999680694610094e-01,0.000000000000000000e+00 +5.262578706081136204e+01,3.325888944130683740e+02,4.344396775551063961e+00,3.992502105372893073e+00,-4.992410900280624952e-01,1.053642246597828562e-03,-1.361524071352429588e-01,9.999999698453538866e-01,0.000000000000000000e+00 +5.262829175579612695e+01,3.325976738745679313e+02,4.339609181606569166e+00,3.992504744425343866e+00,-4.997410900280624957e-01,3.558337155836844689e-03,-1.361524071352429588e-01,9.999999714484660851e-01,0.000000000000000000e+00 +5.263079644912528465e+01,3.326064509411731933e+02,4.334817198529956173e+00,3.992513656968680991e+00,-5.002410900280624961e-01,6.063030413483555189e-03,-1.361524071352429588e-01,9.999999730349630189e-01,0.000000000000000000e+00 +5.263330113686318157e+01,3.326152256106898903e+02,4.330020827519221349e+00,3.992528842966612146e+00,-5.007410900280624411e-01,8.567718083842618820e-03,-1.361524071352429588e-01,9.999999744466067098e-01,0.000000000000000000e+00 +5.263580581507424228e+01,3.326239978809243780e+02,4.325220069773457077e+00,3.992550302343415236e+00,-5.012410900280623860e-01,1.107239623089782167e-02,-1.361524071352429588e-01,9.999999758478701484e-01,0.000000000000000000e+00 +5.263831047982301925e+01,3.326327677496835236e+02,4.320414926492853525e+00,3.992578034983939261e+00,-5.017410900280623309e-01,1.357706091918220795e-02,-1.361524071352429588e-01,9.999999771596522757e-01,0.000000000000000000e+00 +5.264081512717427103e+01,3.326415352147749331e+02,4.315605398878695986e+00,3.992612040733608314e+00,-5.022410900280622759e-01,1.608170821322983668e-02,-1.361524071352429588e-01,9.999999782716824104e-01,0.000000000000000000e+00 +5.264331975319301904e+01,3.326503002740066677e+02,4.310791488133366656e+00,3.992652319398425131e+00,-5.027410900280622208e-01,1.858633417755954642e-02,-1.361524071352429588e-01,9.999999794673302134e-01,0.000000000000000000e+00 +5.264582435394461157e+01,3.326590629251875271e+02,4.305973195460342851e+00,3.992698870744975537e+00,-5.032410900280621657e-01,2.109093487772269182e-02,-1.361524071352429588e-01,9.999999805741541792e-01,0.000000000000000000e+00 +5.264832892549476639e+01,3.326678231661268228e+02,4.301150522064197013e+00,3.992751694500436432e+00,-5.037410900280621107e-01,2.359550637922330427e-02,-1.361524071352429588e-01,9.999999816011102549e-01,0.000000000000000000e+00 +5.265083346390965602e+01,3.326765809946344916e+02,4.296323469150598484e+00,3.992810790352582018e+00,-5.042410900280620556e-01,2.610004474803421029e-02,-1.361524071352429588e-01,9.999999825262466668e-01,0.000000000000000000e+00 +5.265333796525596455e+01,3.326853364085210387e+02,4.291492037926309955e+00,3.992876157949792226e+00,-5.047410900280620005e-01,2.860454605058138783e-02,-1.361524071352429588e-01,9.999999835092053813e-01,0.000000000000000000e+00 +5.265584242560094452e+01,3.326940894055976514e+02,4.286656229599190127e+00,3.992947796901062052e+00,-5.052410900280619455e-01,3.110900635426050789e-02,-1.361524071352429588e-01,9.999999843249236520e-01,0.000000000000000000e+00 +5.265834684101247376e+01,3.327028399836760855e+02,4.281816045378190161e+00,3.993025706776013095e+00,-5.057410900280618904e-01,3.361342172653516286e-02,-1.361524071352429588e-01,9.999999851425466213e-01,0.000000000000000000e+00 +5.266085120755913351e+01,3.327115881405686650e+02,4.276971486473356343e+00,3.993109887104903777e+00,-5.062410900280618353e-01,3.611778823598583987e-02,-1.361524071352429588e-01,9.999999860299786381e-01,0.000000000000000000e+00 +5.266335552131025111e+01,3.327203338740883964e+02,4.272122554095828306e+00,3.993200337378643106e+00,-5.067410900280617803e-01,3.862210195211800839e-02,-1.361524071352429588e-01,9.999999866707375284e-01,0.000000000000000000e+00 +5.266585977833597099e+01,3.327290771820487976e+02,4.267269249457839031e+00,3.993297057048804888e+00,-5.072410900280617252e-01,4.112635894446112911e-02,-1.361524071352429588e-01,9.999999874262487376e-01,0.000000000000000000e+00 +5.266836397470732578e+01,3.327378180622640684e+02,4.262411573772714846e+00,3.993400045527640607e+00,-5.077410900280616701e-01,4.363055528432793068e-02,-1.361524071352429588e-01,9.999999881322463313e-01,0.000000000000000000e+00 +5.267086810649627893e+01,3.327465565125490343e+02,4.257549528254874538e+00,3.993509302188097632e+00,-5.082410900280616151e-01,4.613468704355947608e-02,-1.361524071352429588e-01,9.999999887362278628e-01,0.000000000000000000e+00 +5.267337216977578862e+01,3.327552925307190321e+02,4.252683114119829355e+00,3.993624826363835201e+00,-5.087410900280615600e-01,4.863875029486657703e-02,-1.361524071352429588e-01,9.999999894392808120e-01,0.000000000000000000e+00 +5.267587616061989308e+01,3.327640261145900240e+02,4.247812332584183004e+00,3.993746617349242189e+00,-5.092410900280615049e-01,5.114274111252626459e-02,-1.361524071352429588e-01,9.999999899172403728e-01,0.000000000000000000e+00 +5.267838007510373899e+01,3.327727572619786542e+02,4.242937184865630762e+00,3.993874674399457536e+00,-5.097410900280614499e-01,5.364665557112796579e-02,-1.361524071352429588e-01,9.999999905957603907e-01,0.000000000000000000e+00 +5.268088390930366671e+01,3.327814859707021355e+02,4.238057672182959479e+00,3.994008996730388450e+00,-5.102410900280613948e-01,5.615048974751239708e-02,-1.361524071352429588e-01,9.999999910922702240e-01,0.000000000000000000e+00 +5.268338765929726719e+01,3.327902122385783059e+02,4.233173795756047575e+00,3.994149583518734392e+00,-5.107410900280613397e-01,5.865423971880915494e-02,-1.361524071352429588e-01,9.999999916328339289e-01,0.000000000000000000e+00 +5.268589132116343166e+01,3.327989360634255718e+02,4.228285556805864154e+00,3.994296433902007060e+00,-5.112410900280612847e-01,6.115790156402192701e-02,-1.361524071352429588e-01,9.999999920606945647e-01,0.000000000000000000e+00 +5.268839489098241557e+01,3.328076574430630217e+02,4.223392956554468114e+00,3.994449546978555254e+00,-5.117410900280612296e-01,6.366147136313120292e-02,-1.361524071352429588e-01,9.999999926158065211e-01,0.000000000000000000e+00 +5.269089836483591682e+01,3.328163763753102558e+02,4.218495996225009925e+00,3.994608921807588420e+00,-5.122410900280611745e-01,6.616494519814863917e-02,-1.361524071352429588e-01,9.999999930848738616e-01,0.000000000000000000e+00 +5.269340173880712541e+01,3.328250928579875563e+02,4.213594677041729852e+00,3.994774557409203730e+00,-5.127410900280611195e-01,6.866831915204339720e-02,-1.361524071352429588e-01,9.999999935101246962e-01,0.000000000000000000e+00 +5.269590500898077323e+01,3.328338068889158308e+02,4.208689000229957955e+00,3.994946452764411404e+00,-5.132410900280610644e-01,7.117158930944289530e-02,-1.361524071352429588e-01,9.999999939061828824e-01,0.000000000000000000e+00 +5.269840817144321221e+01,3.328425184659164984e+02,4.203778967016113199e+00,3.995124606815162682e+00,-5.137410900280610093e-01,7.367475175662464848e-02,-1.361524071352429588e-01,9.999999943312739559e-01,0.000000000000000000e+00 +5.270091122228246405e+01,3.328512275868117172e+02,4.198864578627703459e+00,3.995309018464378692e+00,-5.142410900280609543e-01,7.617780258168628527e-02,-1.361524071352429588e-01,9.999999946747912816e-01,0.000000000000000000e+00 +5.270341415758829129e+01,3.328599342494242137e+02,4.193945836293326401e+00,3.995499686575980647e+00,-5.147410900280608992e-01,7.868073787418375376e-02,-1.361524071352429588e-01,9.999999951538895981e-01,0.000000000000000000e+00 +5.270591697345224702e+01,3.328686384515773398e+02,4.189022741242666825e+00,3.995696609974920044e+00,-5.152410900280608441e-01,8.118355372601243625e-02,-1.361524071352429588e-01,9.999999954630431898e-01,0.000000000000000000e+00 +5.270841966596774597e+01,3.328773401910950156e+02,4.184095294706499324e+00,3.995899787447211970e+00,-5.157410900280607891e-01,8.368624623015959163e-02,-1.361524071352429588e-01,9.999999957668790351e-01,0.000000000000000000e+00 +5.271092223123012133e+01,3.328860394658017867e+02,4.179163497916684733e+00,3.996109217739966191e+00,-5.162410900280607340e-01,8.618881148194167119e-02,-1.361524071352429588e-01,9.999999962043860657e-01,0.000000000000000000e+00 +5.271342466533668158e+01,3.328947362735228808e+02,4.174227352106172795e+00,3.996324899561422228e+00,-5.167410900280606789e-01,8.869124557900057160e-02,-1.361524071352429588e-01,9.999999963926938795e-01,0.000000000000000000e+00 +5.271592696438676739e+01,3.329034306120840370e+02,4.169286858508999494e+00,3.996546831580985337e+00,-5.172410900280606239e-01,9.119354462005811734e-02,-1.361524071352429588e-01,9.999999968458423982e-01,0.000000000000000000e+00 +5.271842912448182261e+01,3.329121224793117335e+02,4.164342018360288833e+00,3.996775012429260254e+00,-5.177410900280605688e-01,9.369570470722080047e-02,-1.361524071352429588e-01,9.999999971312254488e-01,0.000000000000000000e+00 +5.272093114172545114e+01,3.329208118730329602e+02,4.159392832896250169e+00,3.997009440698091609e+00,-5.182410900280605137e-01,9.619772194367119666e-02,-1.361524071352429588e-01,9.999999973592815783e-01,0.000000000000000000e+00 +5.272343301222347378e+01,3.329294987910753889e+02,4.154439303354179991e+00,3.997250114940599452e+00,-5.187410900280604586e-01,9.869959243508696911e-02,-1.361524071352429588e-01,9.999999976165642179e-01,0.000000000000000000e+00 +5.272593473208399217e+01,3.329381832312672600e+02,4.149481430972461027e+00,3.997497033671219224e+00,-5.192410900280604036e-01,1.012013122896410905e-01,-1.361524071352429588e-01,9.999999979662037575e-01,0.000000000000000000e+00 +5.272843629741743854e+01,3.329468651914374959e+02,4.144519216990560473e+00,3.997750195365742609e+00,-5.197410900280603485e-01,1.037028776180031336e-01,-1.361524071352429588e-01,9.999999982352933969e-01,0.000000000000000000e+00 +5.273093770433666094e+01,3.329555446694155876e+02,4.139552662649032655e+00,3.998009598461359282e+00,-5.202410900280602934e-01,1.062042845328086405e-01,-1.361524071352429588e-01,9.999999984410463671e-01,0.000000000000000000e+00 +5.273343894895694461e+01,3.329642216630317080e+02,4.134581769189516365e+00,3.998275241356698206e+00,-5.207410900280602384e-01,1.087055291491944992e-01,-1.361524071352429588e-01,9.999999986494446658e-01,0.000000000000000000e+00 +5.273594002739611142e+01,3.329728961701165986e+02,4.129606537854733972e+00,3.998547122411871158e+00,-5.212410900280601833e-01,1.112066075849805352e-01,-1.361524071352429588e-01,9.999999990466725830e-01,0.000000000000000000e+00 +5.273844093577454117e+01,3.329815681885015692e+02,4.124626969888494088e+00,3.998825239948517574e+00,-5.217410900280601282e-01,1.137075159610295982e-01,-1.361524071352429588e-01,9.999999990874585132e-01,0.000000000000000000e+00 +5.274094167021527113e+01,3.329902377160186688e+02,4.119643066535688014e+00,3.999109592249851186e+00,-5.222410900280600732e-01,1.162082503994776583e-01,-1.361524071352429588e-01,9.999999994127068970e-01,0.000000000000000000e+00 +5.274344222684402439e+01,3.329989047505005146e+02,4.114654829042292405e+00,3.999400177560703096e+00,-5.227410900280600181e-01,1.187088070267595802e-01,-1.361524071352429588e-01,9.999999997197691615e-01,0.000000000000000000e+00 +5.274594260178927385e+01,3.330075692897803492e+02,4.109662258655365719e+00,3.999696994087573287e+00,-5.232410900280599630e-01,1.212091819713086022e-01,-1.361524071352429588e-01,9.999999996147768133e-01,0.000000000000000000e+00 +5.274844279118231327e+01,3.330162313316920404e+02,4.104665356623050876e+00,4.000000039998677259e+00,-5.237410900280599080e-01,1.237093713633875408e-01,-1.361524071352429588e-01,9.999999996788424550e-01,4.000000039998680701e-01 +5.275094279115731410e+01,3.330248908740700244e+02,4.099664124194573489e+00,4.000309313423993096e+00,-5.242410900280598529e-01,1.262093713375854742e-01,-1.351524071352429579e-01,9.999999992663266557e-01,4.000309313423996427e-01 +5.275344259785137524e+01,3.330335479147494766e+02,4.094658562620241860e+00,4.000624812455315649e+00,-5.247373724010990781e-01,1.287091780298094679e-01,-1.341524071352429570e-01,9.999999989209197304e-01,4.000624812455318979e-01 +5.275594220740457985e+01,3.330422024701909436e+02,4.089648705325819478e+00,4.000946535146304051e+00,-5.252299381580963766e-01,1.312087875803166215e-01,-1.331524071352429561e-01,9.999999984578413770e-01,4.000946535146307492e-01 +5.275844161596006643e+01,3.330508545568984573e+02,4.084634585701665266e+00,4.001274479512537674e+00,-5.257187883021281483e-01,1.337081961319514511e-01,-1.321524071352429552e-01,9.999999982435050505e-01,4.001274479512541005e-01 +5.276094081966408567e+01,3.330595041914191938e+02,4.079616237102969833e+00,4.001608643531568532e+00,-5.262039238284365039e-01,1.362073998315820045e-01,-1.311524071352429544e-01,9.999999979165345998e-01,4.001608643531571752e-01 +5.276343981466605015e+01,3.330681513903429618e+02,4.074593692849994397e+00,4.001949025142978122e+00,-5.266853457244374814e-01,1.387063948283391024e-01,-1.301524071352429535e-01,9.999999975255824403e-01,4.001949025142981231e-01 +5.276593859711859125e+01,3.330767961703019751e+02,4.069566986228308814e+00,4.002295622248430718e+00,-5.271630549697291501e-01,1.412051772746993616e-01,-1.291524071352429526e-01,9.999999969612513029e-01,4.002295622248434603e-01 +5.276843716317763011e+01,3.330854385479704547e+02,4.064536150489032273e+00,4.002648432711730209e+00,-5.276370525360997155e-01,1.437037433261482700e-01,-1.281524071352429517e-01,9.999999965256587409e-01,4.002648432711733428e-01 +5.277093550900242747e+01,3.330940785400642312e+02,4.059501218849074888e+00,4.003007454358876949e+00,-5.281073393875354016e-01,1.462020891422662616e-01,-1.271524071352429508e-01,9.999999962217901439e-01,4.003007454358880612e-01 +5.277343363075564042e+01,3.331027161633405171e+02,4.054462224491376610e+00,4.003372684978128149e+00,-5.285739164802282231e-01,1.487002108860389082e-01,-1.261524071352429499e-01,9.999999956114850042e-01,4.003372684978131479e-01 +5.277593152460337933e+01,3.331113514345973954e+02,4.049419200565148813e+00,4.003744122320057386e+00,-5.290367847625843112e-01,1.511981047228125596e-01,-1.251524071352429490e-01,9.999999950968453399e-01,4.003744122320060939e-01 +5.277842918671526462e+01,3.331199843706734782e+02,4.044372180186115884e+00,4.004121764097612335e+00,-5.294959451752310198e-01,1.536957668224508688e-01,-1.241524071352429481e-01,9.999999944978222866e-01,4.004121764097615666e-01 +5.278092661326449075e+01,3.331286149884476231e+02,4.039321196436757688e+00,4.004505607986178717e+00,-5.299513986510251407e-01,1.561931933579378262e-01,-1.231524071352429472e-01,9.999999939067073518e-01,4.004505607986182381e-01 +5.278342380042788307e+01,3.331372433048385915e+02,4.034266282366554712e+00,4.004895651623641584e+00,-5.304031461150604532e-01,1.586903805061151418e-01,-1.221524071352429464e-01,9.999999934041469141e-01,4.004895651623645025e-01 +5.278592074438594750e+01,3.331458693368045942e+02,4.029207470992228757e+00,4.005291892610449267e+00,-5.308511884846750517e-01,1.611873244477100564e-01,-1.211524071352429455e-01,9.999999923472754348e-01,4.005291892610452487e-01 +5.278841744132292746e+01,3.331544931013430642e+02,4.024144795297987187e+00,4.005694328509678215e+00,-5.312955266694591172e-01,1.636840213655856857e-01,-1.201524071352429446e-01,9.999999919349692457e-01,4.005694328509681879e-01 +5.279091388742687485e+01,3.331631146154901444e+02,4.019078288235768959e+00,4.006102956847094276e+00,-5.317361615712622447e-01,1.661804674493961298e-01,-1.191524071352429437e-01,9.999999909340316906e-01,4.006102956847097940e-01 +5.279341007888967852e+01,3.331717338963205179e+02,4.014007982725488866e+00,4.006517775111226420e+00,-5.321730940842008817e-01,1.686766588895708407e-01,-1.181524071352429428e-01,9.999999900970569788e-01,4.006517775111229640e-01 +5.279590601190715660e+01,3.331803509609468392e+02,4.008933911655281790e+00,4.006938780753426244e+00,-5.326063250946655447e-01,1.711725918823286119e-01,-1.171524071352429419e-01,9.999999891705275701e-01,4.006938780753429574e-01 +5.279840168267907785e+01,3.331889658265196204e+02,4.003856107881749615e+00,4.007365971187940801e+00,-5.330358554813280358e-01,1.736682626272220420e-01,-1.161524071352429410e-01,9.999999880355213699e-01,4.007365971187944464e-01 +5.280089708740923982e+01,3.331975785102267764e+02,3.998774604230209029e+00,4.007799343791980107e+00,-5.334616861151488809e-01,1.761636673275296661e-01,-1.151524071352429401e-01,9.999999869938333008e-01,4.007799343791983437e-01 +5.280339222230552565e+01,3.332061890292931707e+02,3.993689433494936214e+00,4.008238895905786414e+00,-5.338838178593841022e-01,1.786588021913616542e-01,-1.141524071352429393e-01,9.999999856275613164e-01,4.008238895905789634e-01 +5.280588708357993966e+01,3.332147974009805012e+02,3.988600628439415541e+00,4.008684624832707044e+00,-5.343022515695925456e-01,1.811536634299195925e-01,-1.131524071352429384e-01,9.999999840834949971e-01,4.008684624832710708e-01 +5.280838166744868545e+01,3.332234036425866748e+02,3.983508221796587367e+00,4.009136527839263664e+00,-5.347169880936426534e-01,1.836482472589610893e-01,-1.121524071352429375e-01,9.999999827890995174e-01,4.009136527839267106e-01 +5.281087597013220858e+01,3.332320077714457511e+02,3.978412246269095842e+00,4.009594602155226006e+00,-5.351280282717194581e-01,1.861425498995550043e-01,-1.111524071352429366e-01,9.999999808826348646e-01,4.009594602155229226e-01 +5.281336998785525338e+01,3.332406098049273169e+02,3.973312734529538481e+00,4.010058844973688252e+00,-5.355353729363315773e-01,1.886365675749207826e-01,-1.101524071352429357e-01,9.999999789261319050e-01,4.010058844973691805e-01 +5.281586371684691983e+01,3.332492097604363721e+02,3.968209719220714415e+00,4.010529253451138310e+00,-5.359390229123176530e-01,1.911302965140348753e-01,-1.091524071352429348e-01,9.999999767650284976e-01,4.010529253451142195e-01 +5.281835715334072034e+01,3.332578076554128756e+02,3.963103232955875743e+00,4.011005824707536860e+00,-5.363389790168533455e-01,1.936237329498980697e-01,-1.081524071352429339e-01,9.999999739565067491e-01,4.011005824707540302e-01 +5.282085029357462247e+01,3.332664035073314039e+02,3.957993308318975778e+00,4.011488555826392854e+00,-5.367352420594581064e-01,1.961168731188715764e-01,-1.071524071352429330e-01,9.999999713422768055e-01,4.011488555826396296e-01 +5.282334313379112700e+01,3.332749973337008100e+02,3.952879977864921290e+00,4.011977443854838121e+00,-5.371278128420013953e-01,1.986097132639340623e-01,-1.061524071352429321e-01,9.999999676197344201e-01,4.011977443854841674e-01 +5.282583567023728932e+01,3.332835891520639393e+02,3.947763274119822974e+00,4.012472485803710853e+00,-5.375166921587094526e-01,2.011022496293900508e-01,-1.051524071352429313e-01,9.999999637728627100e-01,4.012472485803714739e-01 +5.282832789916481175e+01,3.332921789799971748e+02,3.942643229581246800e+00,4.012973678647626663e+00,-5.379018807961718496e-01,2.035944784666242069e-01,-1.041524071352429304e-01,9.999999586420763587e-01,4.012973678647629994e-01 +5.283081981683005779e+01,3.333007668351102666e+02,3.937519876718465817e+00,4.013481019325064736e+00,-5.382833795333475946e-01,2.060863960288123464e-01,-1.031524071352429295e-01,9.999999527848350001e-01,4.013481019325068067e-01 +5.283331141949414445e+01,3.333093527350458203e+02,3.932393247972713279e+00,4.013994504738441549e+00,-5.386611891415716835e-01,2.085779985752546917e-01,-1.021524071352429286e-01,9.999999451873987644e-01,4.013994504738444546e-01 +5.283580270342295648e+01,3.333179366974790128e+02,3.927263375757434893e+00,4.014514131754196136e+00,-5.390353103845614280e-01,2.110692823675142937e-01,-1.011524071352429277e-01,9.999999356968363173e-01,4.014514131754199355e-01 +5.283829366488723167e+01,3.333265187401173648e+02,3.922130292458541945e+00,4.015039897202866470e+00,-5.394057440184223395e-01,2.135602436716158015e-01,-1.001524071352429268e-01,9.999999227319127382e-01,4.015039897202870023e-01 +5.284078430016260342e+01,3.333350988807002295e+02,3.916994030434664875e+00,4.015571797879172067e+00,-5.397724907916546799e-01,2.160508787545413201e-01,-9.915240713524292593e-02,9.999999047140777364e-01,4.015571797879176064e-01 +5.284327460552964340e+01,3.333436771369986218e+02,3.911854622017407301e+00,4.016109830542088588e+00,-5.401355514451592343e-01,2.185411838842920285e-01,-9.815240713524292504e-02,9.999998776324647842e-01,4.016109830542092252e-01 +5.284576457727393262e+01,3.333522535268147067e+02,3.906712099511600922e+00,4.016653991914923338e+00,-5.404949267122435286e-01,2.210311553238865634e-01,-9.715240713524292415e-02,9.999998327476590232e-01,4.016653991914926891e-01 +5.284825421168608983e+01,3.333608280679815721e+02,3.901566495195559980e+00,4.017204278685376551e+00,-5.408506173186277133e-01,2.235207893196465845e-01,-9.615240713524292326e-02,9.999997425357979308e-01,4.017204278685380103e-01 +5.285074350506184970e+01,3.333694007783630013e+02,3.896417841321336617e+00,4.017760687505574246e+00,-5.412026239824503371e-01,2.260100820545010991e-01,-9.515240713524292238e-02,9.999994721839081668e-01,4.017760687505578243e-01 +5.285323245370209833e+01,3.333779716758528480e+02,3.891266170114975775e+00,4.018323214991985637e+00,-5.415509474142743418e-01,2.284990293810397477e-01,-9.415240713524292149e-02,7.533818181847306006e-01,4.018323214991988968e-01 +5.285572105391292297e+01,3.333865407783749788e+02,3.886111513776771886e+00,4.018891857724677052e+00,-5.418955883170928356e-01,2.303738955326074811e-01,-9.315240713524292060e-02,-9.999994660761276632e-01,4.018891857724680161e-01 +5.285820930200568313e+01,3.333951081038828193e+02,3.880953904481525107e+00,4.019465085130858206e+00,-5.422365473863346441e-01,2.278856487683805776e-01,-9.215240713524291971e-02,-9.999997366199648852e-01,4.019465085130861648e-01 +5.286069719524227395e+01,3.334036736703590691e+02,3.875793374378798006e+00,4.020032040295144604e+00,-5.425738253098699726e-01,2.253977561870536550e-01,-9.115240713524291882e-02,-9.999998267494828452e-01,4.020032040295147824e-01 +5.286318473760506009e+01,3.334122374958152477e+02,3.870629955593172244e+00,4.020592726762137303e+00,-5.429074227680160680e-01,2.229102142552334687e-01,-9.015240713524291793e-02,-9.999998716156439649e-01,4.020592726762141078e-01 +5.286567193307089951e+01,3.334207995982915804e+02,3.865463680224506593e+00,4.021147148036322783e+00,-5.432373404335427702e-01,2.204230191087084845e-01,-8.915240713524291705e-02,-9.999998989213011447e-01,4.021147148036325891e-01 +5.286815878561119320e+01,3.334293599958564300e+02,3.860294580348194504e+00,4.021695307581333090e+00,-5.435635789716777300e-01,2.179361668197798418e-01,-8.815240713524291616e-02,-9.999999166692791208e-01,4.021695307581336642e-01 +5.287064529919195621e+01,3.334379187066061832e+02,3.855122688015422128e+00,4.022237208819870347e+00,-5.438861390401121820e-01,2.154496534462177759e-01,-8.715240713524291527e-02,-9.999999296569918039e-01,4.022237208819874343e-01 +5.287313147777388167e+01,3.334464757486647954e+02,3.849948035253427214e+00,4.022772855133752046e+00,-5.442050212890058303e-01,2.129634750391755094e-01,-8.615240713524291438e-02,-9.999999393283103277e-01,4.022772855133755487e-01 +5.287561732531241177e+01,3.334550311401834506e+02,3.844770654065757576e+00,4.023302249863975000e+00,-5.445202263609925097e-01,2.104776276514659650e-01,-8.515240713524291349e-02,-9.999999467885192228e-01,4.023302249863978108e-01 +5.287810284575779463e+01,3.334635848993403329e+02,3.839590576432530433e+00,4.023825396310798830e+00,-5.448317548911849606e-01,2.079921073383392827e-01,-8.415240713524291261e-02,-9.999999526608969180e-01,4.023825396310802827e-01 +5.288058804305516247e+01,3.334721370443401725e+02,3.834407834310692209e+00,4.024342297733830343e+00,-5.451396075071804903e-01,2.055069101586163849e-01,-8.315240713524291172e-02,-9.999999578060135841e-01,4.024342297733833895e-01 +5.288307292114458846e+01,3.334806875934140749e+02,3.829222459634277431e+00,4.024852957352109684e+00,-5.454437848290655255e-01,2.030220321740345835e-01,-8.215240713524291083e-02,-9.999999617403089180e-01,4.024852957352113014e-01 +5.288555748396115774e+01,3.334892365648190662e+02,3.824034484314670301e+00,4.025357378344193826e+00,-5.457442874694209412e-01,2.005374694525229040e-01,-8.115240713524290994e-02,-9.999999650816555619e-01,4.025357378344197046e-01 +5.288804173543502429e+01,3.334977839768378090e+02,3.818843940240864043e+00,4.025855563848247165e+00,-5.460411160333269454e-01,1.980532180654001051e-01,-8.015240713524290905e-02,-9.999999682563127656e-01,4.025855563848250718e-01 +5.289052567949148909e+01,3.335063298477782610e+02,3.813650859279722916e+00,4.026347516962124118e+00,-5.463342711183679645e-01,1.955692740877864877e-01,-7.915240713524290816e-02,-9.999999706353079887e-01,4.026347516962127671e-01 +5.289300932005104983e+01,3.335148741959734480e+02,3.808455273276241559e+00,4.026833240743451725e+00,-5.466237533146375283e-01,1.930856336011605168e-01,-7.815240713524290728e-02,-9.999999729825733708e-01,4.026833240743454834e-01 +5.289549266102947200e+01,3.335234170397810090e+02,3.803257214053808344e+00,4.027312738209717580e+00,-5.469095632047428213e-01,1.906022926898345016e-01,-7.715240713524290639e-02,-9.999999748644878839e-01,4.027312738209721243e-01 +5.289797570633785284e+01,3.335319583975829119e+02,3.798056713414466490e+00,4.027786012338347987e+00,-5.471917013638095684e-01,1.881192474438647955e-01,-7.615240713524290550e-02,-9.999999766663665302e-01,4.027786012338351318e-01 +5.290045845988269235e+01,3.335404982877852262e+02,3.792853803139175195e+00,4.028253066066792343e+00,-5.474701683594866974e-01,1.856364939569539740e-01,-7.515240713524290461e-02,-9.999999782973230111e-01,4.028253066066795895e-01 +5.290294092556595018e+01,3.335490367288176117e+02,3.787648514988073423e+00,4.028713902292601290e+00,-5.477449647519510023e-01,1.831540283275695513e-01,-7.415240713524290372e-02,-9.999999796228663529e-01,4.028713902292604399e-01 +5.290542310728510955e+01,3.335575737391332609e+02,3.782440880700741914e+00,4.029168523873506658e+00,-5.480160910939112506e-01,1.806718466589884164e-01,-7.315240713524290284e-02,-9.999999808983184302e-01,4.029168523873510321e-01 +5.290790500893324122e+01,3.335661093372083315e+02,3.777230931996466090e+00,4.029616933627500508e+00,-5.482835479306131798e-01,1.781899450582657141e-01,-7.215240713524290195e-02,-9.999999820488326696e-01,4.029616933627503950e-01 +5.291038663439906031e+01,3.335746435415417182e+02,3.772018700574498951e+00,4.030059134332910631e+00,-5.485473357998434940e-01,1.757083196369911837e-01,-7.115240713524290106e-02,-9.999999829584360622e-01,4.030059134332914517e-01 +5.291286798756701160e+01,3.335831763706547690e+02,3.766804218114325309e+00,4.030495128728476928e+00,-5.488074552319344157e-01,1.732269665113280177e-01,-7.015240713524290017e-02,-9.999999841920502730e-01,4.030495128728480148e-01 +5.291534907231729790e+01,3.335917078430909442e+02,3.761587516275925136e+00,4.030924919513426907e+00,-5.490639067497677939e-01,1.707458818002604573e-01,-6.915240713524289928e-02,-9.999999849766989524e-01,4.030924919513430571e-01 +5.291782989252597957e+01,3.336002379774154747e+02,3.756368626700037794e+00,4.031348509347545850e+00,-5.493166908687795447e-01,1.682650616288507428e-01,-6.815240713524289839e-02,-9.999999856544556920e-01,4.031348509347549292e-01 +5.292031045206500295e+01,3.336087667922150786e+02,3.751147581008425824e+00,4.031765900851254081e+00,-5.495658080969636483e-01,1.657845021254097939e-01,-6.715240713524289751e-02,-9.999999865296800294e-01,4.031765900851257967e-01 +5.292279075480229267e+01,3.336172943060976195e+02,3.745924410804140958e+00,4.032177096605676248e+00,-5.498112589348762569e-01,1.633041994215287396e-01,-6.615240713524289662e-02,-9.999999871473980173e-01,4.032177096605679689e-01 +5.292527080460179434e+01,3.336258205376918227e+02,3.740699147671787017e+00,4.032582099152709709e+00,-5.500530438756398022e-01,1.608241496539002113e-01,-6.515240713524289573e-02,-9.999999878821552723e-01,4.032582099152713373e-01 +5.292775060532354559e+01,3.336343455056468770e+02,3.735471823177786810e+00,4.032980910995096480e+00,-5.502911634049467704e-01,1.583443489621988165e-01,-6.415240713524289484e-02,-9.999999884948080897e-01,4.032980910995100365e-01 +5.293023016082373289e+01,3.336428692286322075e+02,3.730242468870645922e+00,4.033373534596488952e+00,-5.505256180010638101e-01,1.558647934905413313e-01,-6.315240713524289395e-02,-9.999999888551285299e-01,4.033373534596492727e-01 +5.293270947495474843e+01,3.336513917253371346e+02,3.725011116281219614e+00,4.033759972381518288e+00,-5.507564081348356178e-01,1.533854793871547439e-01,-6.215240713524289307e-02,-9.999999896651495801e-01,4.033759972381521508e-01 +5.293518855156527536e+01,3.336599130144705327e+02,3.719777796922977497e+00,4.034140226735861035e+00,-5.509835342696884908e-01,1.509064028022513715e-01,-6.115240713524289218e-02,-9.999999898588685099e-01,4.034140226735864476e-01 +5.293766739450031622e+01,3.336684331147605462e+02,3.714542542292270877e+00,4.034514300006299514e+00,-5.512069968616343241e-01,1.484275598923508466e-01,-6.015240713524289129e-02,-9.999999906490720791e-01,4.034514300006303289e-01 +5.294014600760127820e+01,3.336769520449542483e+02,3.709305383868598316e+00,4.034882194500791996e+00,-5.514267963592740518e-01,1.459489468145696855e-01,-5.915240713524289040e-02,-9.999999907585144232e-01,4.034882194500795660e-01 +5.294262439470601578e+01,3.336854698238174137e+02,3.704066353114872090e+00,4.035243912488527762e+00,-5.516429332038015332e-01,1.434705597327326221e-01,-5.815240713524288951e-02,-9.999999913353965209e-01,4.035243912488531426e-01 +5.294510255964892309e+01,3.336939864701340639e+02,3.698825481477685528e+00,4.035599456199996382e+00,-5.518554078290067721e-01,1.409923948112999093e-01,-5.715240713524288863e-02,-9.999999916167129355e-01,4.035599456199999713e-01 +5.294758050626095525e+01,3.337025020027062396e+02,3.693582800387579024e+00,4.035948827827041008e+00,-5.520642206612794700e-01,1.385144482200434679e-01,-5.615240713524288774e-02,-9.999999922546972675e-01,4.035948827827044449e-01 +5.295005823836971359e+01,3.337110164403536601e+02,3.688338341259308706e+00,4.036292029522922320e+00,-5.522693721196128003e-01,1.360367161304790462e-01,-5.515240713524288685e-02,-9.999999921351262477e-01,4.036292029522925984e-01 +5.295253575979949545e+01,3.337195298019134952e+02,3.683092135492112451e+00,4.036629063402372708e+00,-5.524708626156064062e-01,1.335591947201827667e-01,-5.415240713524288596e-02,-9.999999928629602630e-01,4.036629063402376039e-01 +5.295501307437136518e+01,3.337280421062399114e+02,3.677844214469978557e+00,4.036959931541660218e+00,-5.526686925534698425e-01,1.310818801659936195e-01,-5.315240713524288507e-02,-9.999999929753394801e-01,4.036959931541663771e-01 +5.295749018590320389e+01,3.337365533722038435e+02,3.672594609561912637e+00,4.037284635978634739e+00,-5.528628623300256839e-01,1.286047686515539579e-01,-5.215240713524288418e-02,-9.999999932958687499e-01,4.037284635978637959e-01 +5.295996709820978054e+01,3.337450636186927682e+02,3.667343352122206745e+00,4.037603178712791951e+00,-5.530533723347129671e-01,1.261278563615849113e-01,-5.115240713524288330e-02,-9.999999936070558260e-01,4.037603178712795282e-01 +5.296244381510279453e+01,3.337535728646101916e+02,3.662090473490706710e+00,4.037915561705322176e+00,-5.532402229495902990e-01,1.236511394844056616e-01,-5.015240713524288241e-02,-9.999999938083888873e-01,4.037915561705325840e-01 +5.296492034039094676e+01,3.337620811288754226e+02,3.656836004993081701e+00,4.038221786879164554e+00,-5.534234145493385215e-01,1.211746142115838060e-01,-4.915240713524288152e-02,-9.999999940617825267e-01,4.038221786879168107e-01 +5.296739667788001071e+01,3.337705884304234587e+02,3.651579977941091126e+00,4.038521856119059450e+00,-5.536029475012642642e-01,1.186982767372257996e-01,-4.815240713524288063e-02,-9.999999943578039563e-01,4.038521856119062781e-01 +5.296987283137286795e+01,3.337790947882043042e+02,3.646322423632855525e+00,4.038815771271598187e+00,-5.537788221653024978e-01,1.162221232583418584e-01,-4.715240713524287974e-02,-9.999999945159504522e-01,4.038815771271602184e-01 +5.297234880466957918e+01,3.337876002211830269e+02,3.641063373353123467e+00,4.039103534145272789e+00,-5.539510388940197538e-01,1.137461499752101396e-01,-4.615240713524287886e-02,-9.999999947646421861e-01,4.039103534145276342e-01 +5.297482460156744821e+01,3.337961047483391894e+02,3.635802858373542890e+00,4.039385146510525715e+00,-5.541195980326165671e-01,1.112703530903049465e-01,-4.515240713524287797e-02,-9.999999948725283305e-01,4.039385146510529601e-01 +5.297730022586107168e+01,3.338046083886666224e+02,3.630540909952928885e+00,4.039660610099796045e+00,-5.542844999189304733e-01,1.087947288093759762e-01,-4.415240713524287708e-02,-9.999999953080609405e-01,4.039660610099799487e-01 +5.297977568134240300e+01,3.338131111611732535e+02,3.625277559337533706e+00,4.039929926607567445e+00,-5.544457448834388957e-01,1.063192733396568085e-01,-4.315240713524287619e-02,-9.999999952110795176e-01,4.039929926607571109e-01 +5.298225097180081633e+01,3.338216130848805392e+02,3.620012837761316771e+00,4.040193097690410795e+00,-5.546033332492613654e-01,1.038439828930950160e-01,-4.215240713524287530e-02,-9.999999954368510302e-01,4.040193097690414348e-01 +5.298472610102315628e+01,3.338301141788234077e+02,3.614746776446214671e+00,4.040450124967033929e+00,-5.547572653321625191e-01,1.013688536820468999e-01,-4.115240713524287441e-02,-9.999999958027518954e-01,4.040450124967037149e-01 +5.298720107279380187e+01,3.338386144620498044e+02,3.609479406602409846e+00,4.040701010018319828e+00,-5.549075414405544304e-01,9.889388192178810710e-02,-4.015240713524287353e-02,-9.999999958130478817e-01,4.040701010018323269e-01 +5.298967589089472341e+01,3.338471139536203509e+02,3.604210759428602806e+00,4.040945754387370137e+00,-5.550541618754989415e-01,9.641906383122982038e-02,-3.915240713524287264e-02,-9.999999959644222391e-01,4.040945754387373912e-01 +5.299215055910553929e+01,3.338556126726082312e+02,3.598940866112280812e+00,4.041184359579549579e+00,-5.551971269307105494e-01,9.394439563040407615e-02,-3.815240713524287175e-02,-9.999999960063976623e-01,4.041184359579552687e-01 +5.299462508120357285e+01,3.338641106380986230e+02,3.593669757829989209e+00,4.041416827062523254e+00,-5.553364368925581829e-01,9.146987354225455391e-02,-3.715240713524287086e-02,-9.999999963919713464e-01,4.041416827062526695e-01 +5.299709946096391633e+01,3.338726078691886983e+02,3.588397465747601878e+00,4.041643158266297498e+00,-5.554720920400679773e-01,8.899549379083748768e-02,-3.615240713524286997e-02,-9.999999963922986401e-01,4.041643158266300939e-01 +5.299957370215949481e+01,3.338811043849869975e+02,3.583124021020592576e+00,4.041863354583255408e+00,-5.556040926449252737e-01,8.652125260418790098e-02,-3.515240713524286909e-02,-9.999999964179407952e-01,4.041863354583258849e-01 +5.300204780856110176e+01,3.338896002046134299e+02,3.577849454794304496e+00,4.042077417368198589e+00,-5.557324389714767277e-01,8.404714621144210307e-02,-3.415240713524286820e-02,-9.999999967139280299e-01,4.042077417368202252e-01 +5.300452178393748426e+01,3.338980953471986481e+02,3.572573798204222939e+00,4.042285347938380902e+00,-5.558571312767327521e-01,8.157317084318943534e-02,-3.315240713524286731e-02,-9.999999967794463984e-01,4.042285347938384676e-01 +5.300699563205537856e+01,3.339065898318840482e+02,3.567297082376244877e+00,4.042487147573542217e+00,-5.559781698103690717e-01,7.909932273325959162e-02,-3.215240713524286642e-02,-9.999999968191820576e-01,4.042487147573545769e-01 +5.300946935667958826e+01,3.339150836778213147e+02,3.562019338426952064e+00,4.042682817515945715e+00,-5.560955548147292760e-01,7.662559811691932454e-02,-3.115240713524286553e-02,-9.999999968731622113e-01,4.042682817515949045e-01 +5.301194296157301977e+01,3.339235769041720232e+02,3.556740597463880604e+00,4.042872358970409863e+00,-5.562092865248263740e-01,7.415199323122211028e-02,-3.015240713524286464e-02,-9.999999972524710179e-01,4.042872358970413527e-01 +5.301441645049676055e+01,3.339320695301075830e+02,3.551460890585794061e+00,4.043055773104340389e+00,-5.563193651683447927e-01,7.167850431428005042e-02,-2.915240713524286376e-02,-9.999999969426009994e-01,4.043055773104343720e-01 +5.301688982721011456e+01,3.339405615748087257e+02,3.546180248882954356e+00,4.043233061047759591e+00,-5.564257909656422640e-01,6.920512760848511469e-02,-2.815240713524286287e-02,-9.999999973783684215e-01,4.043233061047763477e-01 +5.301936309547068760e+01,3.339490530574652780e+02,3.540898703437393991e+00,4.043404223893342753e+00,-5.565285641297514907e-01,6.673185935439335248e-02,-2.715240713524286198e-02,-9.999999973629217775e-01,4.043404223893346527e-01 +5.302183625903442277e+01,3.339575439972758204e+02,3.535616285323187391e+00,4.043569262696438571e+00,-5.566276848663820331e-01,6.425869579717662095e-02,-2.615240713524286109e-02,-9.999999972782632751e-01,4.043569262696442568e-01 +5.302430932165567157e+01,3.339660344134475167e+02,3.530333025606723130e+00,4.043728178475104684e+00,-5.567231533739216420e-01,6.178563318266011573e-02,-2.515240713524286020e-02,-9.999999974886811804e-01,4.043728178475107793e-01 +5.302678228708723651e+01,3.339745243251956026e+02,3.525048955346976154e+00,4.043880972210132541e+00,-5.568149698434381456e-01,5.931266775730904134e-02,-2.415240713524285932e-02,-9.999999976148006287e-01,4.043880972210135982e-01 +5.302925515908043508e+01,3.339830137517432149e+02,3.519764105595780013e+00,4.044027644845071379e+00,-5.569031344586807819e-01,5.683979577001050526e-02,-2.315240713524285843e-02,-9.999999976954929704e-01,4.044027644845074598e-01 +5.303172794138516366e+01,3.339915027123211075e+02,3.514478507398099083e+00,4.044168197286255761e+00,-5.569876473960818641e-01,5.436701347098197440e-02,-2.215240713524285754e-02,-9.999999976072814212e-01,4.044168197286259203e-01 +5.303420063774994730e+01,3.339999912261672534e+02,3.509192191792301241e+00,4.044302630402829557e+00,-5.570685088247580019e-01,5.189431711211562465e-02,-2.115240713524285665e-02,-9.999999977908837767e-01,4.044302630402832888e-01 +5.303667325192199655e+01,3.340084793125266174e+02,3.503905189810429643e+00,4.044430945026769919e+00,-5.571457189065114335e-01,4.942170294552621773e-02,-2.015240713524285576e-02,-9.999999977987724664e-01,4.044430945026773472e-01 +5.303914578764727139e+01,3.340169669906508148e+02,3.498617532478475844e+00,4.044553141952906827e+00,-5.572192777958316912e-01,4.694916722569047324e-02,-1.915240713524285487e-02,-9.999999978933256095e-01,4.044553141952910713e-01 +5.304161824867053809e+01,3.340254542797978274e+02,3.493329250816652465e+00,4.044669221938947068e+00,-5.572891856398963784e-01,4.447670620763477523e-02,-1.815240713524285399e-02,-9.999999978848228555e-01,4.044669221938950177e-01 +5.304409063873540475e+01,3.340339411992317196e+02,3.488040375839665419e+00,4.044779185705492885e+00,-5.573554425785725019e-01,4.200431614799612912e-02,-1.715240713524285310e-02,-9.999999980033914548e-01,4.044779185705496549e-01 +5.304656296158440654e+01,3.340424277682223533e+02,3.482750938556987474e+00,4.044883033936062411e+00,-5.574180487444178045e-01,3.953199330392727362e-02,-1.615240713524285221e-02,-9.999999980273693856e-01,4.044883033936065853e-01 +5.304903522095905544e+01,3.340509140060449340e+02,3.477460969973130478e+00,4.044980767277106537e+00,-5.574770042626814304e-01,3.705973393415688821e-02,-1.515240713524285132e-02,-9.999999980099982810e-01,4.044980767277109868e-01 +5.305150742059987579e+01,3.340593999319799536e+02,3.472170501087918026e+00,4.045072386338027570e+00,-5.575323092513053691e-01,3.458753429825317527e-02,-1.415240713524285043e-02,-9.999999981343382638e-01,4.045072386338031123e-01 +5.305397956424649664e+01,3.340678855653126789e+02,3.466879562896759470e+00,4.045157891691195218e+00,-5.575839638209250104e-01,3.211539065624623851e-02,-1.315240713524284955e-02,-9.999999981320599751e-01,4.045157891691198437e-01 +5.305645165563767307e+01,3.340763709253329239e+02,3.461588186390921695e+00,4.045237283871960798e+00,-5.576319680748702545e-01,2.964329926968732945e-02,-1.215240713524284866e-02,-9.999999980102489694e-01,4.045237283871964684e-01 +5.305892369851136436e+01,3.340848560313348230e+02,3.456296402557803571e+00,4.045310563378673230e+00,-5.576763221091662892e-01,2.717125640091132624e-02,-1.115240713524284777e-02,-9.999999983422593886e-01,4.045310563378676783e-01 +5.306139569660479083e+01,3.340933409026164327e+02,3.451004242381208176e+00,4.045377730672692351e+00,-5.577170260125343670e-01,2.469925831158032575e-02,-1.015240713524284688e-02,-9.999999982330249892e-01,4.045377730672695682e-01 +5.306386765365448355e+01,3.341018255584794474e+02,3.445711736841616357e+00,4.045438786178397805e+00,-5.577540798663924715e-01,2.222730126625704905e-02,-9.152407135242845992e-03,-9.999999982260419085e-01,4.045438786178400803e-01 +5.306633957339633412e+01,3.341103100182289154e+02,3.440418916916459402e+00,4.045493730283205913e+00,-5.577874837448559830e-01,1.975538152879215137e-02,-8.152407135242845104e-03,-9.999999981233022028e-01,4.045493730283205580e-01 +5.306881145956566570e+01,3.341187943011728976e+02,3.435125813580393039e+00,4.045542563337576780e+00,-5.578172377147383454e-01,1.728349536410071080e-02,-7.152407135242845083e-03,-9.999999984389300600e-01,4.045542563337576336e-01 +5.307128331589728276e+01,3.341272784266222970e+02,3.429832457805570556e+00,4.045585285655024954e+00,-5.578433418355515094e-01,1.481163903634543158e-02,-6.152407135242845063e-03,-9.999999982188243486e-01,4.045585285655024510e-01 +5.307375514612552081e+01,3.341357624138904043e+02,3.424538880561915910e+00,4.045621897512124754e+00,-5.578657961595063774e-01,1.233980881250944239e-02,-5.152407135242845042e-03,-9.999999983840928142e-01,4.045621897512124976e-01 +5.307622695398431745e+01,3.341442462822926700e+02,3.419245112817397292e+00,4.045652399148523592e+00,-5.578846007315132471e-01,9.868000957704603157e-03,-4.152407135242845021e-03,-9.999999982423710687e-01,4.045652399148523259e-01 +5.307869874320726211e+01,3.341527300511464205e+02,3.413951185538300237e+00,4.045676790766942865e+00,-5.578997555891823668e-01,7.396211739103326042e-03,-3.152407135242845000e-03,-9.999999983952186922e-01,4.045676790766942754e-01 +5.308117051752764581e+01,3.341612137397704601e+02,3.408657129689501630e+00,4.045695072533187719e+00,-5.579112607628240461e-01,4.924437422683828301e-03,-2.152407135242844979e-03,-9.999999984122499574e-01,4.045695072533187497e-01 +5.308364228067853219e+01,3.341696973674849005e+02,3.403362976234742820e+00,4.045707244576147943e+00,-5.579191162754487676e-01,2.452674275724495059e-03,-1.152407135242844959e-03,-9.999999981394998017e-01,4.045707244576147721e-01 +5.308611403639279303e+01,3.341781809536108199e+02,3.398068756136902735e+00,4.045713306987804181e+00,-5.579233221427677414e-01,-1.908143393577174096e-05,-1.524071352428449377e-04,-9.999999985717216155e-01,4.045713306987804292e-01 +5.308858578840317932e+01,3.341866645174698647e+02,3.392774500358271883e+00,4.045713259823231489e+00,-5.579238783731926832e-01,-2.490833440793276034e-03,8.475928647571550831e-04,-9.999999982180223235e-01,4.045713259823231489e-01 +5.309105754044238523e+01,3.341951480783840793e+02,3.387480239860825471e+00,4.045707103100594892e+00,-5.579207849678360365e-01,-4.962585475591993131e-03,1.847592864757155104e-03,-9.999999981900010715e-01,4.045707103100595337e-01 +5.309352929624307649e+01,3.342036316556755651e+02,3.382186005606496959e+00,4.045694836801159155e+00,-5.579140419205109724e-01,-7.434341271812658011e-03,2.847592864757155125e-03,-9.999999985673618808e-01,4.045694836801159155e-01 +5.309600105953798277e+01,3.342121152686661389e+02,3.376891828557452069e+00,4.045676460869281676e+00,-5.579036492177312789e-01,-9.906104563178547845e-03,3.847592864757155146e-03,-9.999999981071702182e-01,4.045676460869281899e-01 +5.309847283405992613e+01,3.342205989366770496e+02,3.371597739676361449e+00,4.045651975212410711e+00,-5.578896068387114715e-01,-1.237787908044259838e-02,4.847592864757155166e-03,-9.999999984596700253e-01,4.045651975212410933e-01 +5.310094462354188494e+01,3.342290826790286928e+02,3.366303769926674683e+00,4.045621379701090703e+00,-5.578719147553663493e-01,-1.484966855859504511e-02,5.847592864757155187e-03,-9.999999982079431637e-01,4.045621379701090925e-01 +5.310341643171705783e+01,3.342375665150403847e+02,3.361009950272892954e+00,4.045584674168948958e+00,-5.578505729323108842e-01,-1.732147672933846694e-02,6.847592864757155208e-03,-9.999999982466556414e-01,4.045584674168949402e-01 +5.310588826231891346e+01,3.342460504640299064e+02,3.355716311680843944e+00,4.045541858412700087e+00,-5.578255813268598873e-01,-1.979330732685791530e-02,7.847592864757155229e-03,-9.999999982930867226e-01,4.045541858412703418e-01 +5.310836011908124021e+01,3.342545345453132768e+02,3.350422885117954053e+00,4.045492932192135349e+00,-5.577969398890278985e-01,-2.226516408496706165e-02,8.847592864757156117e-03,-9.999999981954155182e-01,4.045492932192139013e-01 +5.311083200573822438e+01,3.342630187782045255e+02,3.345129701553521961e+00,4.045437895230118208e+00,-5.577646485615282979e-01,-2.473705073748815389e-02,9.847592864757157005e-03,-9.999999982233633844e-01,4.045437895230121761e-01 +5.311330392602447859e+01,3.342715031820152944e+02,3.339836791958992190e+00,4.045376747212578117e+00,-5.577287072797734169e-01,-2.720897101935044679e-02,1.084759286475715789e-02,-9.999999980505906993e-01,4.045376747212581225e-01 +5.311577588367511993e+01,3.342799877760545542e+02,3.334544187308228658e+00,4.045309487788500746e+00,-5.576891159718737612e-01,-2.968092866517324860e-02,1.184759286475715878e-02,-9.999999982081625438e-01,4.045309487788503744e-01 +5.311824788242581974e+01,3.342884725796282623e+02,3.329251918577788238e+00,4.045236116569920881e+00,-5.576458745586372334e-01,-3.215292741144184369e-02,1.284759286475715967e-02,-9.999999980495249963e-01,4.045236116569924656e-01 +5.312071992601285331e+01,3.342969576120392503e+02,3.323960016747192991e+00,4.045156633131909096e+00,-5.575989829535688003e-01,-3.462497099365294956e-02,1.384759286475716056e-02,-9.999999982213281235e-01,4.045156633131912205e-01 +5.312319201817316383e+01,3.343054428925866546e+02,3.318668512799204606e+00,4.045071037012564652e+00,-5.575484410628698262e-01,-3.709706314956803808e-02,1.484759286475716145e-02,-9.999999977564669740e-01,4.045071037012568094e-01 +5.312566416264441926e+01,3.343139284405658600e+02,3.313377437720096186e+00,4.044979327712999506e+00,-5.574942487854369633e-01,-3.956920761528057162e-02,1.584759286475716233e-02,-9.999999981433010943e-01,4.044979327713003059e-01 +5.312813636316506916e+01,3.343224142752679882e+02,3.308086822499927582e+00,4.044881504697331209e+00,-5.574364060128617071e-01,-4.204140813134277233e-02,1.684759286475716322e-02,-9.999999979483190637e-01,4.044881504697335206e-01 +5.313060862347439439e+01,3.343309004159797837e+02,3.302796698132815845e+00,4.044777567392659812e+00,-5.573749126294293976e-01,-4.451366843559894509e-02,1.784759286475716411e-02,-9.999999977571679688e-01,4.044777567392663364e-01 +5.313308094731257114e+01,3.343393868819831596e+02,3.297507095617210560e+00,4.044667515189061646e+00,-5.573097685121182199e-01,-4.698599226823379355e-02,1.884759286475716500e-02,-9.999999978491482810e-01,4.044667515189064866e-01 +5.313555333842072770e+01,3.343478736925550265e+02,3.292218045956165628e+00,4.044551347439569788e+00,-5.572409735305984269e-01,-4.945838337107183458e-02,1.984759286475716589e-02,-9.999999977612825663e-01,4.044551347439573341e-01 +5.313802580054098712e+01,3.343563608669668952e+02,3.286929580157612829e+00,4.044429063460155405e+00,-5.571685275472310073e-01,-5.193084548579894599e-02,2.084759286475716678e-02,-9.999999975958878684e-01,4.044429063460159290e-01 +5.314049833741655249e+01,3.343648484244845918e+02,3.281641729234633598e+00,4.044300662529712653e+00,-5.570924304170667973e-01,-5.440338235541671008e-02,2.184759286475716766e-02,-9.999999977296747389e-01,4.044300662529716206e-01 +5.314297095279172822e+01,3.343733363843679740e+02,3.276354524205733476e+00,4.044166143890039145e+00,-5.570126819878453706e-01,-5.687599772497772127e-02,2.284759286475716855e-02,-9.999999975060784863e-01,4.044166143890042808e-01 +5.314544365041200535e+01,3.343818247658707037e+02,3.271067996095113450e+00,4.044025506745813736e+00,-5.569292820999934834e-01,-5.934869533908758432e-02,2.384759286475716944e-02,-9.999999975594731083e-01,4.044025506745817511e-01 +5.314791643402410415e+01,3.343903135882397351e+02,3.265782175932943066e+00,4.043878750264579658e+00,-5.568422305866241873e-01,-6.182147894515381548e-02,2.484759286475717033e-02,-9.999999973453632673e-01,4.043878750264583433e-01 +5.315038930737604517e+01,3.343988028707152580e+02,3.260497094755633984e+00,4.043725873576718755e+00,-5.567515272735353848e-01,-6.429435229052782308e-02,2.584759286475717122e-02,-9.999999974642984624e-01,4.043725873576722307e-01 +5.315286227421718479e+01,3.344072926325302433e+02,3.255212783606110438e+00,4.043566875775431946e+00,-5.566571719792081652e-01,-6.676731912539338176e-02,2.684759286475717210e-02,-9.999999970472458477e-01,4.043566875775435054e-01 +5.315533533829828627e+01,3.344157828929101584e+02,3.249929273534083229e+00,4.043401755916711693e+00,-5.565591645148056932e-01,-6.924038319918955631e-02,2.784759286475717299e-02,-9.999999972409099325e-01,4.043401755916715135e-01 +5.315780850337157659e+01,3.344242736710727399e+02,3.244646595596321959e+00,4.043230513019322458e+00,-5.564575046841716555e-01,-7.171354826565273788e-02,2.884759286475717388e-02,-9.999999971411698274e-01,4.043230513019325789e-01 +5.316028177319079617e+01,3.344327649862275962e+02,3.239364780856926807e+00,4.043053146064767844e+00,-5.563521922838283729e-01,-7.418681807780205806e-02,2.984759286475717477e-02,-9.999999968425410390e-01,4.043053146064771175e-01 +5.316275515151126996e+01,3.344412568575759224e+02,3.234083860387600318e+00,4.042869653997269275e+00,-5.562432271029755793e-01,-7.666019639046627032e-02,3.084759286475717566e-02,-9.999999968567830910e-01,4.042869653997273049e-01 +5.316522864208995003e+01,3.344497493043102736e+02,3.228803865267920514e+00,4.042680035723737575e+00,-5.561306089234885341e-01,-7.913368696137315639e-02,3.184759286475717655e-02,-9.999999968059775091e-01,4.042680035723740795e-01 +5.316770224868548667e+01,3.344582423456142237e+02,3.223524826585612235e+00,4.042484290113740997e+00,-5.560143375199162463e-01,-8.160729354900643495e-02,3.284759286475717743e-02,-9.999999965838396454e-01,4.042484290113744771e-01 +5.317017597505826387e+01,3.344667360006620243e+02,3.218246775436818474e+00,4.042282415999477685e+00,-5.558944126594796975e-01,-8.408101991333499781e-02,3.384759286475717832e-02,-9.999999965004096047e-01,4.042282415999480794e-01 +5.317264982497048464e+01,3.344752302886182633e+02,3.212969742926372607e+00,4.042074412175745479e+00,-5.557708341020700660e-01,-8.655486981690031778e-02,3.484759286475717921e-02,-9.999999965558844517e-01,4.042074412175749032e-01 +5.317512380218621360e+01,3.344837252286376952e+02,3.207693760168070618e+00,4.041860277399908163e+00,-5.556436016002466172e-01,-8.902884702410766848e-02,3.584759286475718010e-02,-9.999999960052753378e-01,4.041860277399911827e-01 +5.317759791047142670e+01,3.344922208398648991e+02,3.202418858284941550e+00,4.041640010391862603e+00,-5.555127148992350383e-01,-9.150295529944015016e-02,3.684759286475718099e-02,-9.999999962600293335e-01,4.041640010391865934e-01 +5.318007215359408946e+01,3.345007171414338245e+02,3.197145068409518842e+00,4.041413609834009435e+00,-5.553781737369249960e-01,-9.397719841285161191e-02,3.784759286475718187e-02,-9.999999959542423822e-01,4.041413609834013099e-01 +5.318254653532419951e+01,3.345092141524676776e+02,3.191872421684112116e+00,4.041181074371209547e+00,-5.552399778438683597e-01,-9.645158013295304644e-02,3.884759286475718276e-02,-9.999999958776484288e-01,4.041181074371212878e-01 +5.318502105943385061e+01,3.345177118920784665e+02,3.186600949261078952e+00,4.040942402610756545e+00,-5.550981269432767595e-01,-9.892610423240395801e-02,3.984759286475718365e-02,-9.999999956381663280e-01,4.040942402610759876e-01 +5.318749572969728945e+01,3.345262103793668871e+02,3.181330682303093571e+00,4.040697593122335007e+00,-5.549526207510196985e-01,-1.014007744850462384e-01,4.084759286475718454e-02,-9.999999955474244695e-01,4.040697593122338782e-01 +5.318997054989096540e+01,3.345347096334218122e+02,3.176061651983420386e+00,4.040446644437984958e+00,-5.548034589756221102e-01,-1.038755946677036163e-01,4.184759286475718543e-02,-9.999999951700500045e-01,4.040446644437988843e-01 +5.319244552379360869e+01,3.345432096733201206e+02,3.170793889486183126e+00,4.040189555052061010e+00,-5.546506413182618056e-01,-1.063505685583912563e-01,4.284759286475718632e-02,-9.999999952083721277e-01,4.040189555052064452e-01 +5.319492065518626589e+01,3.345517105181262991e+02,3.165527426006634837e+00,4.039926323421195065e+00,-5.544941674727674741e-01,-1.088256999391897656e-01,4.384759286475718720e-02,-9.999999950369873325e-01,4.039926323421198506e-01 +5.319739594785237813e+01,3.345602121868922154e+02,3.160262292751430113e+00,4.039656947964251010e+00,-5.543340371256159083e-01,-1.113009925930175253e-01,4.484759286475718809e-02,-9.999999947324511584e-01,4.039656947964254119e-01 +5.319987140557782368e+01,3.345687146986567200e+02,3.154998520938894213e+00,4.039381427062286534e+00,-5.541702499559296724e-01,-1.137764503054264770e-01,4.584759286475718898e-02,-9.999999943476999276e-01,4.039381427062290197e-01 +5.320234703215098904e+01,3.345772180724454756e+02,3.149736141799292621e+00,4.039099759058509598e+00,-5.540028056354745489e-01,-1.162520768646023162e-01,4.684759286475718987e-02,-9.999999944911844851e-01,4.039099759058513150e-01 +5.320482283136282575e+01,3.345857223272705028e+02,3.144475186575102388e+00,4.038811942258234033e+00,-5.538317038286567628e-01,-1.187278760627985957e-01,4.784759286475719076e-02,-9.999999940080998018e-01,4.038811942258237475e-01 +5.320729880700689307e+01,3.345942274821300089e+02,3.139215686521280801e+00,4.038517974928830689e+00,-5.536569441925202062e-01,-1.212038516920302123e-01,4.884759286475719164e-02,-9.999999938922553566e-01,4.038517974928834131e-01 +5.320977496287943609e+01,3.346027335560079337e+02,3.133957672905534952e+00,4.038217855299688352e+00,-5.534785263767441066e-01,-1.236800075494518397e-01,4.984759286475719253e-02,-9.999999935182996014e-01,4.038217855299691683e-01 +5.321225130277944260e+01,3.346112405678737787e+02,3.128701177008592182e+00,4.037911581562160457e+00,-5.532964500236396965e-01,-1.261563474334081170e-01,5.084759286475719342e-02,-9.999999933938977792e-01,4.037911581562164121e-01 +5.321472783050869282e+01,3.346197485366822093e+02,3.123446230124468315e+00,4.037599151869520675e+00,-5.531107147681476599e-01,-1.286328751462983144e-01,5.184759286475719431e-02,-9.999999929865990289e-01,4.037599151869524228e-01 +5.321720454987182336e+01,3.346282574813727706e+02,3.118192863560737216e+00,4.037280564336910516e+00,-5.529213202378352454e-01,-1.311095944920599443e-01,5.284759286475719520e-02,-9.999999926059870425e-01,4.037280564336914179e-01 +5.321968146467639116e+01,3.346367674208696030e+02,3.112941108638799470e+00,4.036955817041292249e+00,-5.527282660528930469e-01,-1.335865092783134200e-01,5.384759286475719609e-02,-9.999999923894090648e-01,4.036955817041295580e-01 +5.322215857873292322e+01,3.346452783740811014e+02,3.107690996694151497e+00,4.036624908021395619e+00,-5.525315518261320058e-01,-1.360636233159951969e-01,5.484759286475719697e-02,-9.999999921567719330e-01,4.036624908021398950e-01 +5.322463589585498767e+01,3.346537903598996309e+02,3.102442559076652895e+00,4.036287835277664549e+00,-5.523311771629805245e-01,-1.385409404186311588e-01,5.584759286475719786e-02,-9.999999915550357166e-01,4.036287835277667657e-01 +5.322711341985924349e+01,3.346623033972012422e+02,3.097195827150796443e+00,4.035944596772204740e+00,-5.521271416614809135e-01,-1.410184644019678024e-01,5.684759286475719875e-02,-9.999999913598195400e-01,4.035944596772207960e-01 +5.322959115456551160e+01,3.346708175048452176e+02,3.091950832295975005e+00,4.035595190428731271e+00,-5.519194449122865054e-01,-1.434961990868283965e-01,5.784759286475719964e-02,-9.999999908702222884e-01,4.035595190428735157e-01 +5.323206910379682455e+01,3.346793327016738999e+02,3.086707605906750196e+00,4.035239614132508201e+00,-5.517080864986583233e-01,-1.459741482955149716e-01,5.884759286475720053e-02,-9.999999905127744393e-01,4.035239614132511976e-01 +5.323454727137948339e+01,3.346878490065124083e+02,3.081466179393118843e+00,4.034877865730296165e+00,-5.514930659964614179e-01,-1.484523158546618982e-01,5.984759286475720141e-02,-9.999999899600768849e-01,4.034877865730299717e-01 +5.323702566114313584e+01,3.346963664381681838e+02,3.076226584180782098e+00,4.034509943030291979e+00,-5.512743829741618695e-01,-1.509307055934280828e-01,6.084759286475720230e-02,-9.999999895765868674e-01,4.034509943030295531e-01 +5.323950427692081888e+01,3.347048850154308184e+02,3.070988851711411893e+00,4.034135843802071797e+00,-5.510520369928231244e-01,-1.534093213452720206e-01,6.184759286475720319e-02,-9.999999888273988224e-01,4.034135843802075239e-01 +5.324198312254902277e+01,3.347134047570716575e+02,3.065753013442918284e+00,4.033755565776528940e+00,-5.508260276061023308e-01,-1.558881669457833907e-01,6.284759286475720408e-02,-9.999999885907054908e-01,4.033755565776532825e-01 +5.324446220186776912e+01,3.347219256818434587e+02,3.060519100849715457e+00,4.033369106645816160e+00,-5.505963543602468979e-01,-1.583672462362465394e-01,6.384759286475720497e-02,-9.999999878326903957e-01,4.033369106645819380e-01 +5.324694151872065362e+01,3.347304478084802213e+02,3.055287145422989070e+00,4.032976464063278144e+00,-5.503630167940910534e-01,-1.608465630589617779e-01,6.484759286475720585e-02,-9.999999870756831610e-01,4.032976464063281474e-01 +5.324942107695490279e+01,3.347389711556967313e+02,3.050057178670963154e+00,4.032577635643394665e+00,-5.501260144390516249e-01,-1.633261212611640534e-01,6.584759286475720674e-02,-9.999999865183982761e-01,4.032577635643398439e-01 +5.325190088042145220e+01,3.347474957421882777e+02,3.044829232119165674e+00,4.032172618961713084e+00,-5.498853468191247096e-01,-1.658059246942822085e-01,6.684759286475720763e-02,-9.999999858911839956e-01,4.032172618961716304e-01 +5.325438093297499620e+01,3.347560215866303679e+02,3.039603337310693654e+00,4.031761411554781738e+00,-5.496410134508817880e-01,-1.682859772128390274e-01,6.784759286475720852e-02,-9.999999847446022772e-01,4.031761411554785624e-01 +5.325686123847405895e+01,3.347645487076784434e+02,3.034379525806480515e+00,4.031344010920085097e+00,-5.493930138434655053e-01,-1.707662826740666273e-01,6.884759286475720941e-02,-9.999999841810578438e-01,4.031344010920088206e-01 +5.325934180078105129e+01,3.347730771239674823e+02,3.029157829185560313e+00,4.030920414515978933e+00,-5.491413474985861187e-01,-1.732468449418171907e-01,6.984759286475721030e-02,-9.999999829559289566e-01,4.030920414515982708e-01 +5.326182262376232046e+01,3.347816068541117147e+02,3.023938279045332855e+00,4.030490619761614823e+00,-5.488860139105171676e-01,-1.757276678808034620e-01,7.084759286475721118e-02,-9.999999820965301822e-01,4.030490619761618043e-01 +5.326430371128823538e+01,3.347901379167043387e+02,3.018720907001829712e+00,4.030054624036877975e+00,-5.486270125660916985e-01,-1.782087553622964116e-01,7.184759286475721207e-02,-9.999999810040011150e-01,4.030054624036881195e-01 +5.326678506723322926e+01,3.347986703303171794e+02,3.013505744689977561e+00,4.029612424682309957e+00,-5.483643429446978246e-01,-1.806901112601534687e-01,7.284759286475721296e-02,-9.999999794736244008e-01,4.029612424682313399e-01 +5.326926669547587068e+01,3.348072041135004042e+02,3.008292823763864199e+00,4.029164018999040309e+00,-5.480980045182747284e-01,-1.831717394518584396e-01,7.384759286475721385e-02,-9.999999782701528561e-01,4.029164018999044083e-01 +5.327174859989893463e+01,3.348157392847820688e+02,3.003082175897000550e+00,4.028709404248714598e+00,-5.478279967513084436e-01,-1.856536438209900330e-01,7.484759286475721474e-02,-9.999999766756023645e-01,4.028709404248717596e-01 +5.327423078438944515e+01,3.348242758626680029e+02,2.997873832782586234e+00,4.028248577653415374e+00,-5.475543191008274135e-01,-1.881358282536050863e-01,7.584759286475721562e-02,-9.999999747958171481e-01,4.028248577653418816e-01 +5.327671325283875348e+01,3.348328138656413557e+02,2.992667826133772913e+00,4.027781536395591111e+00,-5.472769710163980506e-01,-1.906182966403458801e-01,7.684759286475721651e-02,-9.999999729826702932e-01,4.027781536395594886e-01 +5.327919600914260201e+01,3.348413533121622550e+02,2.987464187683926742e+00,4.027308277617978938e+00,-5.469959519401204062e-01,-1.931010528771142654e-01,7.784759286475721740e-02,-9.999999706803701649e-01,4.027308277617982490e-01 +5.328167905720117403e+01,3.348498942206676361e+02,2.982262949186892609e+00,4.026828798423524702e+00,-5.467112613066237303e-01,-1.955841008628816657e-01,7.884759286475721829e-02,-9.999999682980669213e-01,4.026828798423527922e-01 +5.328416240091916478e+01,3.348584366095707310e+02,2.977064142417255255e+00,4.026343095875307476e+00,-5.464228985430618080e-01,-1.980674445021482766e-01,7.984759286475721918e-02,-9.999999650480680957e-01,4.026343095875311029e-01 +5.328664604420585960e+01,3.348669804972609541e+02,2.971867799170603952e+00,4.025851166996456953e+00,-5.461308630691082966e-01,-2.005510877020347804e-01,8.084759286475722007e-02,-9.999999616815697934e-01,4.025851166996460839e-01 +5.328912999097517655e+01,3.348755259021033908e+02,2.966673951263792297e+00,4.025353008770077068e+00,-5.458351542969521741e-01,-2.030350343761678777e-01,8.184759286475722095e-02,-9.999999577514558924e-01,4.025353008770081176e-01 +5.329161424514573042e+01,3.348840728424385702e+02,2.961482630535201999e+00,4.024848618139158951e+00,-5.455357716312928540e-01,-2.055192884417684496e-01,8.284759286475722184e-02,-9.999999527640991426e-01,4.024848618139162393e-01 +5.329409881064092502e+01,3.348926213365821241e+02,2.956293868845003114e+00,4.024337992006500109e+00,-5.452327144693355221e-01,-2.080038538195998210e-01,8.384759286475722273e-02,-9.999999466099995793e-01,4.024337992006503661e-01 +5.329658369138898166e+01,3.349011714028245024e+02,2.951107698075416508e+00,4.023821127234622708e+00,-5.449259822007861409e-01,-2.104887344349862244e-01,8.484759286475722362e-02,-9.999999394187274460e-01,4.023821127234625816e-01 +5.329906889132302439e+01,3.349097230594305188e+02,2.945924150130973196e+00,4.023298020645688311e+00,-5.446155742078464534e-01,-2.129739342184715778e-01,8.584759286475722451e-02,-9.999999295449034653e-01,4.023298020645691975e-01 +5.330155441438114394e+01,3.349182763246392369e+02,2.940743256938775918e+00,4.022768669021409949e+00,-5.443014898652093203e-01,-2.154594571014729620e-01,8.684759286475722539e-02,-9.999999167320140492e-01,4.022768669021413168e-01 +5.330404026450646171e+01,3.349268312166635155e+02,2.935565050448759816e+00,4.022233069102973957e+00,-5.439837285400531686e-01,-2.179453070197961972e-01,8.784759286475722628e-02,-9.999998988045912807e-01,4.022233069102977843e-01 +5.330652644564718656e+01,3.349353877536896107e+02,2.930389562633951783e+00,4.021691217590952050e+00,-5.436622895920373288e-01,-2.204314879089300239e-01,8.884759286475722717e-02,-9.999998716707114710e-01,4.021691217590955825e-01 +5.330901296175669302e+01,3.349439459538770052e+02,2.925216825490730255e+00,4.021143111145224047e+00,-5.433371723732965952e-01,-2.229180036993435032e-01,8.984759286475722806e-02,-9.999998265957223964e-01,4.021143111145227267e-01 +5.331149981679357808e+01,3.349525058353579539e+02,2.920046871039084113e+00,4.020588746384911261e+00,-5.430083762284361182e-01,-2.254048583050004551e-01,9.084759286475722895e-02,-9.999997364281230094e-01,4.020588746384914369e-01 +5.331398701472173940e+01,3.349610674162372561e+02,2.914879731322872924e+00,4.020028119888337415e+00,-5.426759004945259646e-01,-2.278920555776070278e-01,9.184759286475722984e-02,-9.999994660766623467e-01,4.020028119888340856e-01 +5.331647455951042502e+01,3.349696307145919150e+02,2.909715438410083621e+00,4.019461228193102365e+00,-5.423397445010958995e-01,-2.303795990381349579e-01,9.284759286475723072e-02,7.671713648424387522e-01,4.019461228193105806e-01 +5.331896245513431154e+01,3.349781957484707391e+02,2.904554024393090295e+00,4.018888067796822838e+00,-5.419999075701297242e-01,-2.284709567567730082e-01,9.384759286475723161e-02,9.999994719927506326e-01,4.018888067796826391e-01 +5.332145070557356092e+01,3.349867625358940586e+02,2.899395521388911323e+00,4.018319574838316477e+00,-5.416563890160600581e-01,-2.259827076313352945e-01,9.484759286475723250e-02,9.999997423826136878e-01,4.018319574838319919e-01 +5.332393930803878135e+01,3.349953310948533272e+02,2.894239961539467831e+00,4.017757193715007169e+00,-5.413091881457626764e-01,-2.234941058072186792e-01,9.584759286475723339e-02,9.999998325866307214e-01,4.017757193715010833e-01 +5.332642825884338578e+01,3.350039014433110083e+02,2.889087377011839930e+00,4.017200927880534067e+00,-5.409583042585508483e-01,-2.210051554192984380e-01,9.684759286475723428e-02,9.999998776703066250e-01,4.017200927880537620e-01 +5.332891755429550074e+01,3.350124735991999501e+02,2.883937799998523399e+00,4.016650780752255123e+00,-5.406037366461695637e-01,-2.185158602716994747e-01,9.784759286475723516e-02,9.999999046334089314e-01,4.016650780752258898e-01 +5.333140719069803026e+01,3.350210475804232146e+02,2.878791262717687705e+00,4.016106755711993159e+00,-5.402454845927899818e-01,-2.160262241066004396e-01,9.884759286475723605e-02,9.999999226851523648e-01,4.016106755711996712e-01 +5.333389716434869854e+01,3.350296234048537940e+02,2.873647797413430016e+00,4.015568856106114026e+00,-5.398835473750036584e-01,-2.135362506484425327e-01,9.984759286475723694e-02,9.999999357314622861e-01,4.015568856106117024e-01 +5.333638747154012094e+01,3.350382010903341552e+02,2.868507436356032336e+00,4.015037085245495518e+00,-5.395179242618164395e-01,-2.110459436170717407e-01,1.008475928647572378e-01,9.999999451028058761e-01,4.015037085245499182e-01 +5.333887810855982536e+01,3.350467806546759562e+02,2.863370211842216406e+00,4.014511446405464312e+00,-5.391486145146426878e-01,-2.085553067340959466e-01,1.018475928647572387e-01,9.999999528494701861e-01,4.014511446405468198e-01 +5.334136907169033037e+01,3.350553621156597046e+02,2.858236156195398614e+00,4.013991942825717807e+00,-5.387756173872991772e-01,-2.060643437210377682e-01,1.028475928647572396e-01,9.999999585917671574e-01,4.013991942825720916e-01 +5.334386035720919494e+01,3.350639454910344739e+02,2.853105301765944457e+00,4.013478577710251294e+00,-5.383989321259992078e-01,-2.035730583053331211e-01,1.038475928647572405e-01,9.999999636715225515e-01,4.013478577710254958e-01 +5.334635196138905400e+01,3.350725307985174481e+02,2.847977680931423006e+00,4.012971354227270915e+00,-5.380185579693463893e-01,-2.010814542159896634e-01,1.048475928647572414e-01,9.999999677163013967e-01,4.012971354227274912e-01 +5.334884388049768944e+01,3.350811180557937519e+02,2.842853326096859590e+00,4.012470275509118167e+00,-5.376344941483283124e-01,-1.985895351878039783e-01,1.058475928647572423e-01,9.999999712148002207e-01,4.012470275509121831e-01 +5.335133611079807281e+01,3.350897072805159951e+02,2.837732269694990705e+00,4.011975344652184639e+00,-5.372467398863104426e-01,-1.960973049591628048e-01,1.068475928647572432e-01,9.999999740854329522e-01,4.011975344652188302e-01 +5.335382864854841500e+01,3.350982984903039323e+02,2.832614544186515815e+00,4.011486564716832959e+00,-5.368552943990299031e-01,-1.936047672734105829e-01,1.078475928647572440e-01,9.999999766766268783e-01,4.011486564716836289e-01 +5.335632149000224445e+01,3.351068917027441216e+02,2.827500182060350475e+00,4.011003938727315088e+00,-5.364601568945889243e-01,-1.911119258777241037e-01,1.088475928647572449e-01,9.999999789083700019e-01,4.011003938727318863e-01 +5.335881463140842840e+01,3.351154869353896970e+02,2.822389215833877696e+00,4.010527469671694156e+00,-5.360613265734485156e-01,-1.886187845241265593e-01,1.098475928647572458e-01,9.999999808432233905e-01,4.010527469671697487e-01 +5.336130806901124402e+01,3.351240842057599139e+02,2.817281678053199734e+00,4.010057160501764528e+00,-5.356588026284216930e-01,-1.861253469690782592e-01,1.108475928647572467e-01,9.999999826856144081e-01,4.010057160501768192e-01 +5.336380179905042809e+01,3.351326835313398647e+02,2.812177601293389895e+00,4.009593014132973643e+00,-5.352525842446672621e-01,-1.836316169730687065e-01,1.118475928647572476e-01,9.999999843522260345e-01,4.009593014132976641e-01 +5.336629581776124098e+01,3.351412849295800811e+02,2.807077018158742998e+00,4.009135033444345630e+00,-5.348426705996830455e-01,-1.811375983012797342e-01,1.128475928647572485e-01,9.999999854720456050e-01,4.009135033444349294e-01 +5.336879012137450928e+01,3.351498884178961930e+02,2.801979961283025400e+00,4.008683221278404041e+00,-5.344290608632989992e-01,-1.786432947242487523e-01,1.138475928647572494e-01,9.999999869555397103e-01,4.008683221278407927e-01 +5.337128470611668263e+01,3.351584940136687010e+02,2.796886463329725014e+00,4.008237580441093684e+00,-5.340117541976707738e-01,-1.761487100146177653e-01,1.148475928647572503e-01,9.999999881387625633e-01,4.008237580441097458e-01 +5.337377956820989056e+01,3.351671017342424648e+02,2.791796556992301337e+00,4.007798113701711351e+00,-5.335907497572726088e-01,-1.736538479510054689e-01,1.158475928647572512e-01,9.999999890670462355e-01,4.007798113701714349e-01 +5.337627470387199224e+01,3.351757115969265328e+02,2.786710274994433245e+00,4.007364823792827657e+00,-5.331660466888906713e-01,-1.711587123161832369e-01,1.168475928647572520e-01,9.999999900656222351e-01,4.007364823792831099e-01 +5.337877010931664756e+01,3.351843236189935737e+02,2.781627650090269022e+00,4.006937713410214208e+00,-5.327376441316157285e-01,-1.686633068963214188e-01,1.178475928647572529e-01,9.999999910254110391e-01,4.006937713410217428e-01 +5.338126578075335260e+01,3.351929378176798195e+02,2.776548715064672379e+00,4.006516785212773435e+00,-5.323055412168365974e-01,-1.661676354820175172e-01,1.188475928647572538e-01,9.999999918308190017e-01,4.006516785212776988e-01 +5.338376171438750362e+01,3.352015542101844403e+02,2.771473502733472039e+00,4.006102041822466653e+00,-5.318697370682327064e-01,-1.636717018682570246e-01,1.198475928647572547e-01,9.999999925013480784e-01,4.006102041822470206e-01 +5.338625790642046098e+01,3.352101728136693168e+02,2.766402045943708199e+00,4.005693485824243005e+00,-5.314302308017669896e-01,-1.611755098540205988e-01,1.208475928647572556e-01,9.999999931909242523e-01,4.005693485824246558e-01 +5.338875435304958472e+01,3.352187936452587564e+02,2.761334377573877674e+00,4.005291119765970187e+00,-5.309870215256787818e-01,-1.586790632418925706e-01,1.218475928647572565e-01,9.999999940445193358e-01,4.005291119765973518e-01 +5.339125105046831976e+01,3.352274167220390382e+02,2.756270530534182583e+00,4.004894946158366942e+00,-5.305401083404764906e-01,-1.561823658380270818e-01,1.228475928647572574e-01,9.999999943429070948e-01,4.004894946158370495e-01 +5.339374799486622436e+01,3.352360420610581286e+02,2.751210537766774156e+00,4.004504967474936450e+00,-5.300894903389300472e-01,-1.536854214542495711e-01,1.238475928647572583e-01,9.999999952087568200e-01,4.004504967474939447e-01 +5.339624518242903406e+01,3.352446696793252272e+02,2.746154432245997867e+00,4.004121186151895273e+00,-5.296351666060639118e-01,-1.511882339034015255e-01,1.248475928647572591e-01,9.999999956172790361e-01,4.004121186151843315e-01 +5.339874260933873273e+01,3.352532995938105955e+02,2.741102246978639023e+00,4.003743604588114735e+00,-5.291771362191490802e-01,-1.486908070046459585e-01,1.258475928647572462e-01,9.999999960991711179e-01,4.003743604588118621e-01 +5.340124027177359523e+01,3.352619318214449891e+02,2.736054015004166562e+00,4.003372225145049867e+00,-5.287153982476959779e-01,-1.461931445795265905e-01,1.268475928647572470e-01,9.999999966032907528e-01,4.003372225145053198e-01 +5.340373816590824418e+01,3.352705663791194866e+02,2.731009769394975972e+00,4.003007050146679013e+00,-5.282499517534464673e-01,-1.436952504533638431e-01,1.278475928647572479e-01,9.999999970661069826e-01,4.003007050146682455e-01 +5.340623628791370692e+01,3.352792032836850353e+02,2.725969543256632655e+00,4.002648081879440767e+00,-5.277807957903665192e-01,-1.411971284552288042e-01,1.288475928647572488e-01,9.999999975530780016e-01,4.002648081879444097e-01 +5.340873463395748644e+01,3.352878425519521102e+02,2.720933369728115725e+00,4.002295322592171800e+00,-5.273079294046379983e-01,-1.386987824175638373e-01,1.298475928647572497e-01,9.999999976891179587e-01,4.002295322592174798e-01 +5.341123320020359699e+01,3.352964842006903723e+02,2.715901281982058268e+00,4.001948774496046468e+00,-5.268313516346514458e-01,-1.362002161772259134e-01,1.308475928647572506e-01,9.999999982229946793e-01,4.001948774496049688e-01 +5.341373198281264223e+01,3.353051282466283283e+02,2.710873313224989367e+00,4.001608439764514635e+00,-5.263510615109976420e-01,-1.337014335726211811e-01,1.318475928647572515e-01,9.999999986079818326e-01,4.001608439764518521e-01 +5.341623097794185782e+01,3.353137747064529322e+02,2.705849496697575685e+00,4.001274320533247497e+00,-5.258670580564598351e-01,-1.312024384468841176e-01,1.328475928647572524e-01,9.999999989931961375e-01,4.001274320533250717e-01 +5.341873018174517540e+01,3.353224235968092444e+02,2.700829865674861274e+00,4.000946418900076296e+00,-5.253793402860059691e-01,-1.287032346460811605e-01,1.338475928647572533e-01,9.999999990851323739e-01,4.000946418900079848e-01 +5.342122959037328656e+01,3.353310749343000907e+02,2.695814453466507388e+00,4.000624736924936364e+00,-5.248879072067802465e-01,-1.262038260202589524e-01,1.348475928647572541e-01,9.999999997110472494e-01,4.000624736924940361e-01 +5.342372919997368541e+01,3.353397287354856076e+02,2.690803293417032283e+00,4.000309276629809396e+00,-5.243927578180951343e-01,-1.237042164205850447e-01,1.358475928647572550e-01,9.999999996906507871e-01,1.219351353873108640e-01 +5.342622900669073971e+01,3.353483850168830145e+02,2.685796418906049254e+00,4.000000039998673707e+00,-5.238938911114231489e-01,-1.212044097043075142e-01,1.361524071352429588e-01,9.999999996031465610e-01,0.000000000000000000e+00 +5.342872900666574054e+01,3.353570437949662164e+02,2.680793863348505113e+00,3.999697028977442947e+00,-5.233938911114232040e-01,-1.187044097302988183e-01,1.361524071352429588e-01,9.999999994408297344e-01,0.000000000000000000e+00 +5.343122919603697341e+01,3.353657050732447260e+02,2.675795637805141514e+00,3.999400245473916815e+00,-5.228938911114232591e-01,-1.162042203604642526e-01,1.361524071352429588e-01,9.999999991772106078e-01,0.000000000000000000e+00 +5.343372957093976794e+01,3.353743688495532638e+02,2.670801743525514915e+00,3.999109691357729091e+00,-5.223938911114233141e-01,-1.137038454597303211e-01,1.361524071352429588e-01,9.999999989797037081e-01,0.000000000000000000e+00 +5.343623012750654766e+01,3.353830351217258112e+02,2.665812181758099086e+00,3.998825368460296570e+00,-5.218938911114233692e-01,-1.112032888955011567e-01,1.361524071352429588e-01,9.999999986408574237e-01,0.000000000000000000e+00 +5.343873086186690813e+01,3.353917038875958951e+02,2.660826953750284218e+00,3.998547278574770214e+00,-5.213938911114234243e-01,-1.087025545385369857e-01,1.361524071352429588e-01,9.999999984301413125e-01,0.000000000000000000e+00 +5.344123177014766668e+01,3.354003751449962465e+02,2.655846060748376924e+00,3.998275423455984967e+00,-5.208938911114234793e-01,-1.062016462617025592e-01,1.361524071352429588e-01,9.999999982413161348e-01,0.000000000000000000e+00 +5.344373284847291927e+01,3.354090488917590847e+02,2.650869503997601129e+00,3.998009804820413571e+00,-5.203938911114235344e-01,-1.037005679408475461e-01,1.361524071352429588e-01,9.999999979470097777e-01,0.000000000000000000e+00 +5.344623409296410443e+01,3.354177251257160037e+02,2.645897284742095401e+00,3.997750424346119047e+00,-5.198938911114235895e-01,-1.011993234548002468e-01,1.361524071352429588e-01,9.999999976823359393e-01,0.000000000000000000e+00 +5.344873549974005300e+01,3.354264038446979157e+02,2.640929404224914734e+00,3.997497283672708068e+00,-5.193938911114236445e-01,-9.869791668465176249e-02,1.361524071352429588e-01,9.999999973473372439e-01,0.000000000000000000e+00 +5.345123706491705917e+01,3.354350850465351641e+02,2.635965863688029209e+00,3.997250384401286993e+00,-5.188938911114236996e-01,-9.619635151428450326e-02,1.361524071352429588e-01,9.999999971035800073e-01,0.000000000000000000e+00 +5.345373878460893025e+01,3.354437687290574104e+02,2.631006664372324000e+00,3.997009728094417458e+00,-5.183938911114237547e-01,-9.369463182965843961e-02,1.361524071352429588e-01,9.999999967348836005e-01,0.000000000000000000e+00 +5.345624065492705768e+01,3.354524548900937475e+02,2.626051807517598924e+00,3.996775316276074630e+00,-5.178938911114238097e-01,-9.119276151969640809e-02,1.361524071352429588e-01,9.999999964985152312e-01,0.000000000000000000e+00 +5.345874267198047392e+01,3.354611435274726432e+02,2.621101294362568446e+00,3.996547150431604134e+00,-5.173938911114238648e-01,-8.869074447503989822e-02,1.361524071352429588e-01,9.999999962023166100e-01,0.000000000000000000e+00 +5.346124483187590215e+01,3.354698346390219399e+02,2.616155126144860343e+00,3.996325232007682970e+00,-5.168938911114239199e-01,-8.618858458911356213e-02,1.361524071352429588e-01,9.999999957720288046e-01,0.000000000000000000e+00 +5.346374713071782736e+01,3.354785282225688547e+02,2.611213304101017041e+00,3.996109562412278660e+00,-5.163938911114239749e-01,-8.368628575777033174e-02,1.361524071352429588e-01,9.999999953926393959e-01,0.000000000000000000e+00 +5.346624956460854605e+01,3.354872242759399796e+02,2.606275829466493832e+00,3.995900143014610162e+00,-5.158938911114240300e-01,-8.118385187858263852e-02,1.361524071352429588e-01,9.999999952241931389e-01,0.000000000000000000e+00 +5.346875212964823731e+01,3.354959227969613380e+02,2.601342703475659324e+00,3.995696975145111463e+00,-5.153938911114240851e-01,-7.868128685084456453e-02,1.361524071352429588e-01,9.999999946216139302e-01,0.000000000000000000e+00 +5.347125482193501256e+01,3.355046237834582712e+02,2.596413927361794993e+00,3.995500060095396044e+00,-5.148938911114241401e-01,-7.617859457752647334e-02,1.361524071352429588e-01,9.999999943324174856e-01,0.000000000000000000e+00 +5.347375763756499367e+01,3.355133272332554952e+02,2.591489502357094743e+00,3.995309399118217364e+00,-5.143938911114241952e-01,-7.367577896172958218e-02,1.361524071352429588e-01,9.999999939437408392e-01,0.000000000000000000e+00 +5.347626057263235566e+01,3.355220331441772146e+02,2.586569429692664901e+00,3.995124993427439097e+00,-5.138938911114242503e-01,-7.117284390952950679e-02,1.361524071352429588e-01,9.999999935128496276e-01,0.000000000000000000e+00 +5.347876362322938348e+01,3.355307415140468947e+02,2.581653710598523332e+00,3.994946844197999170e+00,-5.133938911114243053e-01,-6.866979332873918151e-02,1.361524071352429588e-01,9.999999929995768699e-01,0.000000000000000000e+00 +5.348126678544655022e+01,3.355394523406874896e+02,2.576742346303600328e+00,3.994774952565877779e+00,-5.128938911114243604e-01,-6.616663112909211553e-02,1.361524071352429588e-01,9.999999926204099499e-01,0.000000000000000000e+00 +5.348377005537257389e+01,3.355481656219212709e+02,2.571835338035736385e+00,3.994609319628065869e+00,-5.123938911114244155e-01,-6.366336122153924693e-02,1.361524071352429588e-01,9.999999921394423508e-01,0.000000000000000000e+00 +5.348627342909446725e+01,3.355568813555699421e+02,2.566932687021683979e+00,3.994449946442536259e+00,-5.118938911114244705e-01,-6.115998751932059940e-02,1.361524071352429588e-01,9.999999915768326142e-01,0.000000000000000000e+00 +5.348877690269760876e+01,3.355655995394545243e+02,2.562034394487105793e+00,3.994296834028213006e+00,-5.113938911114245256e-01,-5.865651393726348944e-02,1.361524071352429588e-01,9.999999911376150630e-01,0.000000000000000000e+00 +5.349128047226579952e+01,3.355743201713955273e+02,2.557140461656574715e+00,3.994149983364943424e+00,-5.108938911114245807e-01,-5.615294439125875781e-02,1.361524071352429588e-01,9.999999905028155167e-01,0.000000000000000000e+00 +5.349378413388132714e+01,3.355830432492127784e+02,2.552250889753574281e+00,3.994009395393472328e+00,-5.103938911114246357e-01,-5.364928279951165085e-02,1.361524071352429588e-01,9.999999899629081757e-01,0.000000000000000000e+00 +5.349628788362501552e+01,3.355917687707254800e+02,2.547365680000496901e+00,3.993875071015414058e+00,-5.098938911114246908e-01,-5.114553308095498574e-02,1.361524071352429588e-01,9.999999894256256239e-01,0.000000000000000000e+00 +5.349879171757630303e+01,3.356004967337522658e+02,2.542484833618645634e+00,3.993747011093229382e+00,-5.093938911114247459e-01,-4.864169915614625916e-02,1.361524071352429588e-01,9.999999886991629561e-01,0.000000000000000000e+00 +5.350129563181329218e+01,3.356092271361111443e+02,2.537608351828231523e+00,3.993625216450201076e+00,-5.088938911114248009e-01,-4.613778494745573999e-02,1.361524071352429588e-01,9.999999882002604812e-01,0.000000000000000000e+00 +5.350379962241281362e+01,3.356179599756194989e+02,2.532736235848375372e+00,3.993509687870409941e+00,-5.083938911114248560e-01,-4.363379437748150791e-02,1.361524071352429588e-01,9.999999873248700544e-01,0.000000000000000000e+00 +5.350630368545049009e+01,3.356266952500941443e+02,2.527868486897105527e+00,3.993400426098715705e+00,-5.078938911114249111e-01,-4.112973137154415926e-02,1.361524071352429588e-01,9.999999867852938928e-01,0.000000000000000000e+00 +5.350880781700079325e+01,3.356354329573512700e+02,2.523005106191359648e+00,3.993297431840732603e+00,-5.073938911114249661e-01,-3.862559985432932608e-02,1.361524071352429588e-01,9.999999859185733087e-01,0.000000000000000000e+00 +5.351131201313711472e+01,3.356441730952064404e+02,2.518146094946982938e+00,3.993200705762814273e+00,-5.068938911114250212e-01,-3.612140375327001218e-02,1.361524071352429588e-01,9.999999851651831806e-01,0.000000000000000000e+00 +5.351381626993181584e+01,3.356529156614745943e+02,2.513291454378728140e+00,3.993110248492031111e+00,-5.063938911114250763e-01,-3.361714699572204701e-02,1.361524071352429588e-01,9.999999843690771106e-01,0.000000000000000000e+00 +5.351632058345628451e+01,3.356616606539701024e+02,2.508441185700255538e+00,3.993026060616155615e+00,-5.058938911114251313e-01,-3.111283351039636699e-02,1.361524071352429588e-01,9.999999834857757897e-01,0.000000000000000000e+00 +5.351882494978102045e+01,3.356704080705067099e+02,2.503595290124132067e+00,3.992948142683645063e+00,-5.053938911114251864e-01,-2.860846722701812159e-02,1.361524071352429588e-01,9.999999825113721208e-01,0.000000000000000000e+00 +5.352132936497567073e+01,3.356791579088975936e+02,2.498753768861831315e+00,3.992876495203625975e+00,-5.048938911114252415e-01,-2.610405207616350517e-02,1.361524071352429588e-01,9.999999815531636083e-01,0.000000000000000000e+00 +5.352383382510911503e+01,3.356879101669553052e+02,2.493916623123733967e+00,3.992811118645879898e+00,-5.043938911114252965e-01,-2.359959198891964371e-02,1.361524071352429588e-01,9.999999805463406499e-01,0.000000000000000000e+00 +5.352633832624950116e+01,3.356966648424917139e+02,2.489083854119126471e+00,3.992752013440830972e+00,-5.038938911114253516e-01,-2.109509089725397982e-02,1.361524071352429588e-01,9.999999794662407515e-01,0.000000000000000000e+00 +5.352884286446433038e+01,3.357054219333182346e+02,2.484255463056201041e+00,3.992699179979533497e+00,-5.033938911114254067e-01,-1.859055273385206222e-02,1.361524071352429588e-01,9.999999783990611846e-01,0.000000000000000000e+00 +5.353134743582050703e+01,3.357141814372455428e+02,2.479431451142055209e+00,3.992652618613660831e+00,-5.028938911114254617e-01,-1.608598143177819226e-02,1.361524071352429588e-01,9.999999770461801551e-01,0.000000000000000000e+00 +5.353385203638439549e+01,3.357229433520837460e+02,2.474611819582691830e+00,3.992612329655496062e+00,-5.023938911114255168e-01,-1.358138092537750606e-02,1.361524071352429588e-01,9.999999757859785454e-01,0.000000000000000000e+00 +5.353635666222189826e+01,3.357317076756423830e+02,2.469796569583019075e+00,3.992578313377921351e+00,-5.018938911114255719e-01,-1.107675514851861470e-02,1.361524071352429588e-01,9.999999745410517171e-01,0.000000000000000000e+00 +5.353886130939850574e+01,3.357404744057303674e+02,2.464985702346849106e+00,3.992550570014412603e+00,-5.013938911114256269e-01,-8.572108035673377605e-03,1.361524071352429588e-01,9.999999729197679432e-01,0.000000000000000000e+00 +5.354136597397936725e+01,3.357492435401560442e+02,2.460179219076898960e+00,3.992529099759032363e+00,-5.008938911114256820e-01,-6.067443522642154870e-03,1.361524071352429588e-01,9.999999715612091222e-01,0.000000000000000000e+00 +5.354387065202932661e+01,3.357580150767271334e+02,2.455377120974789218e+00,3.992513902766421818e+00,-5.003938911114257371e-01,-3.562765543910418730e-03,1.361524071352429588e-01,9.999999697282703215e-01,0.000000000000000000e+00 +5.354637533961302154e+01,3.357667890132507296e+02,2.450579409241044893e+00,3.992504979151800359e+00,-4.998938911114257366e-01,-1.058078036033819648e-03,1.361524071352429588e-01,9.999999680684129588e-01,0.000000000000000000e+00 +5.354888003279492636e+01,3.357755653475333588e+02,2.445786085075093208e+00,3.992502328990957583e+00,-4.993938911114257362e-01,1.446615065891531000e-03,1.361524071352429588e-01,9.999999662068114192e-01,0.000000000000000000e+00 +5.355138472763940882e+01,3.357843440773809220e+02,2.440997149675265820e+00,3.992505952320255069e+00,-4.988938911114257357e-01,3.951309825730395589e-03,1.361524071352429588e-01,9.999999640913292964e-01,0.000000000000000000e+00 +5.355388942021079401e+01,3.357931252005987517e+02,2.436212604238796153e+00,3.992515849136622830e+00,-4.983938911114257353e-01,6.456002307178486388e-03,1.361524071352429588e-01,9.999999619925121763e-01,0.000000000000000000e+00 +5.355639410657344257e+01,3.358019087149915549e+02,2.431432449961820730e+00,3.992532019397558862e+00,-4.978938911114257349e-01,8.960688574632530434e-03,1.361524071352429588e-01,9.999999596541355729e-01,0.000000000000000000e+00 +5.355889878279179328e+01,3.358106946183634705e+02,2.426656688039377840e+00,3.992554463021131816e+00,-4.973938911114257344e-01,1.146536469193271818e-02,1.361524071352429588e-01,9.999999571426881895e-01,0.000000000000000000e+00 +5.356140344493043415e+01,3.358194829085179549e+02,2.421885319665407987e+00,3.992583179885981437e+00,-4.968938911114257340e-01,1.397002672323284164e-02,1.361524071352429588e-01,9.999999543518698353e-01,0.000000000000000000e+00 +5.356390808905416634e+01,3.358282735832580101e+02,2.417118346032753440e+00,3.992618169831322117e+00,-4.963938911114257335e-01,1.647467073262935330e-02,1.361524071352429588e-01,9.999999514981748883e-01,0.000000000000000000e+00 +5.356641271122804682e+01,3.358370666403859559e+02,2.412355768333157346e+00,3.992659432656946450e+00,-4.958938911114257331e-01,1.897929278503168032e-02,1.361524071352429588e-01,9.999999482714481136e-01,0.000000000000000000e+00 +5.356891730751748071e+01,3.358458620777035435e+02,2.407597587757264179e+00,3.992706968123231892e+00,-4.953938911114257326e-01,2.148388894490497678e-02,1.361524071352429588e-01,9.999999448260107338e-01,0.000000000000000000e+00 +5.357142187398825683e+01,3.358546598930118421e+02,2.402843805494619289e+00,3.992760775951145202e+00,-4.948938911114257322e-01,2.398845527749526862e-02,1.361524071352429588e-01,9.999999409312464449e-01,0.000000000000000000e+00 +5.357392640670662587e+01,3.358634600841114661e+02,2.398094422733668019e+00,3.992820855822250881e+00,-4.943938911114257317e-01,2.649298784792713732e-02,1.361524071352429588e-01,9.999999367503999981e-01,0.000000000000000000e+00 +5.357643090173935718e+01,3.358722626488023479e+02,2.393349440661756145e+00,3.992887207378718273e+00,-4.938938911114257313e-01,2.899748272225194032e-02,1.361524071352429588e-01,9.999999322743329255e-01,0.000000000000000000e+00 +5.357893535515379568e+01,3.358810675848838514e+02,2.388608860465128991e+00,3.992959830223332229e+00,-4.933938911114257309e-01,3.150193596707780846e-02,1.361524071352429588e-01,9.999999271799798750e-01,0.000000000000000000e+00 +5.358143976301793288e+01,3.358898748901547151e+02,2.383872683328931430e+00,3.993038723919503763e+00,-4.928938911114257304e-01,3.400634364884516647e-02,1.361524071352429588e-01,9.999999215384846041e-01,0.000000000000000000e+00 +5.358394412140045659e+01,3.358986845624131661e+02,2.379140910437208323e+00,3.993123887991279819e+00,-4.923938911114257300e-01,3.651070183487573062e-02,1.361524071352429588e-01,9.999999153905309024e-01,0.000000000000000000e+00 +5.358644842637082917e+01,3.359074965994567492e+02,2.374413542972902302e+00,3.993215321923356598e+00,-4.918938911114257295e-01,3.901500659335788157e-02,1.361524071352429588e-01,9.999999082507846637e-01,0.000000000000000000e+00 +5.358895267399932294e+01,3.359163109990824410e+02,2.369690582117855548e+00,3.993313025161093766e+00,-4.913938911114257291e-01,4.151925399209101253e-02,1.361524071352429588e-01,9.999999005242431460e-01,0.000000000000000000e+00 +5.359145686035711265e+01,3.359251277590867062e+02,2.364972029052808011e+00,3.993416997110526445e+00,-4.908938911114257286e-01,4.402344010077680059e-02,1.361524071352429588e-01,9.999998915236445463e-01,0.000000000000000000e+00 +5.359396098151631804e+01,3.359339468772652708e+02,2.360257884957397856e+00,3.993527237138383867e+00,-4.903938911114257282e-01,4.652756098834552601e-02,1.361524071352429588e-01,9.999998815232502558e-01,0.000000000000000000e+00 +5.359646503355006786e+01,3.359427683514134060e+02,2.355548151010161462e+00,3.993643744572102250e+00,-4.898938911114257277e-01,4.903161272542548577e-02,1.361524071352429588e-01,9.999998698468934855e-01,0.000000000000000000e+00 +5.359896901253257084e+01,3.359515921793257576e+02,2.350842828388532091e+00,3.993766518699844781e+00,-4.893938911114257273e-01,5.153559138202455647e-02,1.361524071352429588e-01,9.999998563553876840e-01,0.000000000000000000e+00 +5.360147291453915130e+01,3.359604183587963462e+02,2.346141918268840332e+00,3.993895558770516718e+00,-4.888938911114257269e-01,5.403949302893638895e-02,1.361524071352429588e-01,9.999998405968093529e-01,0.000000000000000000e+00 +5.360397673564634857e+01,3.359692468876186240e+02,2.341445421826313655e+00,3.994030863993784930e+00,-4.883938911114257264e-01,5.654331373701882574e-02,1.361524071352429588e-01,9.999998220191200771e-01,0.000000000000000000e+00 +5.360648047193195254e+01,3.359780777635854179e+02,2.336753340235076415e+00,3.994172433540096545e+00,-4.878938911114257260e-01,5.904704957700475376e-02,1.361524071352429588e-01,9.999997996160789882e-01,0.000000000000000000e+00 +5.360898411947506759e+01,3.359869109844890431e+02,2.332065674668148514e+00,3.994320266540698050e+00,-4.873938911114257255e-01,6.155069661842645784e-02,1.361524071352429588e-01,9.999997724232094765e-01,0.000000000000000000e+00 +5.361148767435617657e+01,3.359957465481212466e+02,2.327382426297446738e+00,3.994474362087652608e+00,-4.868938911114257251e-01,6.405425092978182799e-02,1.361524071352429588e-01,9.999997383842615939e-01,0.000000000000000000e+00 +5.361399113265720473e+01,3.360045844522730931e+02,2.322703596293782979e+00,3.994634719233858711e+00,-4.863938911114257246e-01,6.655770857586276734e-02,1.361524071352429588e-01,9.999996952721320609e-01,0.000000000000000000e+00 +5.361649449046157656e+01,3.360134246947350789e+02,2.318029185826864680e+00,3.994801336993063057e+00,-4.858938911114257242e-01,6.906106561738951932e-02,1.361524071352429588e-01,9.999996385627721862e-01,0.000000000000000000e+00 +5.361899774385427975e+01,3.360222672732971887e+02,2.313359196065294388e+00,3.994974214339873431e+00,-4.853938911114257238e-01,7.156431810532296045e-02,1.361524071352429588e-01,9.999995609379644934e-01,0.000000000000000000e+00 +5.362150088892192912e+01,3.360311121857487251e+02,2.308693628176569757e+00,3.995153350209758258e+00,-4.848938911114257233e-01,7.406746207393354042e-02,1.361524071352429588e-01,9.999994485978015435e-01,0.000000000000000000e+00 +5.362400392175281638e+01,3.360399594298785360e+02,2.304032483327082659e+00,3.995338743499029732e+00,-4.843938911114257229e-01,7.657049352464193048e-02,1.361524071352429588e-01,9.999992727499009693e-01,0.000000000000000000e+00 +5.362650683843698118e+01,3.360488090034747302e+02,2.299375762682119184e+00,3.995530393064787411e+00,-4.838938911114257224e-01,7.907340838856188880e-02,1.361524071352429588e-01,9.999989583336503784e-01,0.000000000000000000e+00 +5.362900963506627505e+01,3.360576609043249618e+02,2.294723467405859640e+00,3.995728297724769007e+00,-4.833938911114257220e-01,8.157620241077578882e-02,1.361524071352429588e-01,9.999982423913472696e-01,0.000000000000000000e+00 +5.363151230773441114e+01,3.360665151302162599e+02,2.290075598661377665e+00,3.995932456256912513e+00,-4.828938911114257215e-01,8.407887068018930765e-02,1.361524071352429588e-01,9.999950219446468447e-01,0.000000000000000000e+00 +5.363401485253702106e+01,3.360753716789350278e+02,2.285432157610640225e+00,3.996142867397742826e+00,-4.823938911114257211e-01,8.658140302499617302e-02,1.361524071352429588e-01,-9.999931011930348612e-01,0.000000000000000000e+00 +5.363651726557174726e+01,3.360842305482671577e+02,2.280793145414508061e+00,3.996359529829237367e+00,-4.818938911114257206e-01,8.407900725393550878e-02,1.361524071352429588e-01,-9.999978821398869400e-01,0.000000000000000000e+00 +5.363901954293827856e+01,3.360930917359979730e+02,2.276158563232733911e+00,3.996569918826089030e+00,-4.813938911114257202e-01,8.157673518688098036e-02,1.361524071352429588e-01,-9.999987200302002943e-01,0.000000000000000000e+00 +5.364152168857894054e+01,3.361019552399121153e+02,2.271528412223963400e+00,3.996774035698416494e+00,-4.808938911114257198e-01,7.907459274888772871e-02,1.361524071352429588e-01,-9.999990668459686205e-01,0.000000000000000000e+00 +5.364402370643401241e+01,3.361108210577937143e+02,2.266902693545734149e+00,3.996971881741356647e+00,-4.803938911114257193e-01,7.657257722858518134e-02,1.361524071352429588e-01,-9.999992556715687764e-01,0.000000000000000000e+00 +5.364652560044174123e+01,3.361196891874263315e+02,2.262281408354475776e+00,3.997163458213481402e+00,-4.798938911114257189e-01,7.407068508308452259e-02,1.361524071352429588e-01,-9.999993734389983624e-01,0.000000000000000000e+00 +5.364902737453843429e+01,3.361285596265929598e+02,2.257664557805509453e+00,3.997348766334746450e+00,-4.793938911114257184e-01,7.156891255390718243e-02,1.361524071352429588e-01,-9.999994531590888913e-01,0.000000000000000000e+00 +5.365152903265848749e+01,3.361374323730759670e+02,2.253052143053047907e+00,3.997527807285980561e+00,-4.788938911114257180e-01,6.906725580185947566e-02,1.361524071352429588e-01,-9.999995103674731434e-01,0.000000000000000000e+00 +5.365403057873448489e+01,3.361463074246571523e+02,2.248444165250194970e+00,3.997700582208711495e+00,-4.783938911114257175e-01,6.656571095070208666e-02,1.361524071352429588e-01,-9.999995526251297395e-01,0.000000000000000000e+00 +5.365653201669722705e+01,3.361551847791177465e+02,2.243840625548944701e+00,3.997867092205100281e+00,-4.778938911114257171e-01,6.406427410704373937e-02,1.361524071352429588e-01,-9.999995848376280749e-01,0.000000000000000000e+00 +5.365903335047580214e+01,3.361640644342384121e+02,2.239241525100182262e+00,3.998027338337924341e+00,-4.773938911114257166e-01,6.156294136692491009e-02,1.361524071352429588e-01,-9.999996096087130359e-01,0.000000000000000000e+00 +5.366153458399767118e+01,3.361729463877992430e+02,2.234646865053683040e+00,3.998181321630576157e+00,-4.768938911114257162e-01,5.906170882151556140e-02,1.361524071352429588e-01,-9.999996286591825712e-01,0.000000000000000000e+00 +5.366403572118869647e+01,3.361818306375797647e+02,2.230056646558111755e+00,3.998329043067075261e+00,-4.763938911114257158e-01,5.656057255926282001e-02,1.361524071352429588e-01,-9.999996434655982203e-01,0.000000000000000000e+00 +5.366653676597322686e+01,3.361907171813589343e+02,2.225470870761022901e+00,3.998470503592084668e+00,-4.758938911114257153e-01,5.405952866644075927e-02,1.361524071352429588e-01,-9.999996545503796463e-01,0.000000000000000000e+00 +5.366903772227414748e+01,3.361996060169150837e+02,2.220889538808860308e+00,3.998605704110927750e+00,-4.753938911114257149e-01,5.155857322947551141e-02,1.361524071352429588e-01,-9.999996626886862305e-01,0.000000000000000000e+00 +5.367153859401294369e+01,3.362084971420259762e+02,2.216312651846957138e+00,3.998734645489609996e+00,-4.748938911114257144e-01,4.905770233425171822e-02,1.361524071352429588e-01,-9.999996680565945706e-01,0.000000000000000000e+00 +5.367403938510976502e+01,3.362173905544688637e+02,2.211740211019534996e+00,3.998857328554838109e+00,-4.743938911114257140e-01,4.655691206754935391e-02,1.361524071352429588e-01,-9.999996710122800447e-01,0.000000000000000000e+00 +5.367654009948348914e+01,3.362262862520204294e+02,2.207172217469703934e+00,3.998973754094041766e+00,-4.738938911114257135e-01,4.405619851652683300e-02,1.361524071352429588e-01,-9.999996716701399224e-01,0.000000000000000000e+00 +5.367904074105177870e+01,3.362351842324566746e+02,2.202608672339462892e+00,3.999083922855393158e+00,-4.733938911114257131e-01,4.155555776926919687e-02,1.361524071352429588e-01,-9.999996701139862720e-01,0.000000000000000000e+00 +5.368154131373114524e+01,3.362440844935531459e+02,2.198049576769697477e+00,3.999187835547826975e+00,-4.728938911114257126e-01,3.905498591480315029e-02,1.361524071352429588e-01,-9.999996659710796987e-01,0.000000000000000000e+00 +5.368404182143701320e+01,3.362529870330848212e+02,2.193494931900181744e+00,3.999285492841059497e+00,-4.723938911114257122e-01,3.655447904417726684e-02,1.361524071352429588e-01,-9.999996594776119352e-01,0.000000000000000000e+00 +5.368654226808376961e+01,3.362618918488259965e+02,2.188944738869577300e+00,3.999376895365609474e+00,-4.718938911114257118e-01,3.405403324887791572e-02,1.361524071352429588e-01,-9.999996501294515783e-01,0.000000000000000000e+00 +5.368904265758484229e+01,3.362707989385505130e+02,2.184398998815431980e+00,3.999462043712814108e+00,-4.713938911114257113e-01,3.155364462261908698e-02,1.361524071352429588e-01,-9.999996375345402422e-01,0.000000000000000000e+00 +5.369154299385274953e+01,3.362797083000315297e+02,2.179857712874180731e+00,3.999540938434848591e+00,-4.708938911114257109e-01,2.905330926100077246e-02,1.361524071352429588e-01,-9.999996209868649011e-01,0.000000000000000000e+00 +5.369404328079915700e+01,3.362886199310417510e+02,2.175320882181145166e+00,3.999613580044743877e+00,-4.703938911114257104e-01,2.655302326223262996e-02,1.361524071352429588e-01,-9.999995996796803288e-01,0.000000000000000000e+00 +5.369654352233496297e+01,3.362975338293533127e+02,2.170788507870532680e+00,3.999679969016405323e+00,-4.698938911114257100e-01,2.405278272732452177e-02,1.361524071352429588e-01,-9.999995718531337063e-01,0.000000000000000000e+00 +5.369904372237033385e+01,3.363064499927376687e+02,2.166260591075437336e+00,3.999740105784630906e+00,-4.693938911114257095e-01,2.155258376240820617e-02,1.361524071352429588e-01,-9.999995358599576001e-01,0.000000000000000000e+00 +5.370154388481477525e+01,3.363153684189658179e+02,2.161737132927837646e+00,3.999793990745134309e+00,-4.688938911114257091e-01,1.905242247839451092e-02,1.361524071352429588e-01,-9.999994878211112548e-01,0.000000000000000000e+00 +5.370404401357718882e+01,3.363242891058081341e+02,2.157218134558598788e+00,3.999841624254566241e+00,-4.683938911114257087e-01,1.655229499649182867e-02,1.361524071352429588e-01,-9.999994222651004128e-01,0.000000000000000000e+00 +5.370654411256595040e+01,3.363332120510344794e+02,2.152703597097469945e+00,3.999883006630548632e+00,-4.678938911114257082e-01,1.405219745212601609e-02,1.361524071352429588e-01,-9.999993286466267728e-01,0.000000000000000000e+00 +5.370904418568894556e+01,3.363421372524140907e+02,2.148193521673085638e+00,3.999918138151717706e+00,-4.673938911114257078e-01,1.155212600756390720e-02,1.361524071352429588e-01,-9.999991863017556604e-01,0.000000000000000000e+00 +5.371154423685364776e+01,3.363510647077156364e+02,2.143687909412964387e+00,3.999947019057797704e+00,-4.668938911114257073e-01,9.052076877148864872e-03,1.361524071352429588e-01,-9.999989466845874420e-01,0.000000000000000000e+00 +5.371404426996717518e+01,3.363599944147073302e+02,2.139186761443509610e+00,3.999969649549736772e+00,-4.663938911114257069e-01,6.552046396944802287e-03,1.361524071352429588e-01,-9.999984641606922686e-01,0.000000000000000000e+00 +5.371654428893634758e+01,3.363689263711567037e+02,2.134690078890007836e+00,3.999986029790016051e+00,-4.658938911114257064e-01,4.052031267396860072e-03,1.361524071352429588e-01,-9.999970108496167853e-01,0.000000000000000000e+00 +5.371904429766775735e+01,3.363778605748307200e+02,2.130197862876630044e+00,3.999996159903564497e+00,-4.653938911114257060e-01,1.552030008887182906e-03,1.361524071352429588e-01,-6.208586966924752870e-01,0.000000000000000000e+00 +5.372154430006781922e+01,3.363867970234958875e+02,2.125710114526430328e+00,4.000000039982311684e+00,-4.648938911114257055e-01,-1.182229437284151325e-07,1.361524071352429588e-01,4.729003061534860420e-05,0.000000000000000000e+00 +5.372404430004282716e+01,3.363957357149180893e+02,2.121226834961345453e+00,4.000000039686754327e+00,-4.643938911114257051e-01,2.131628228429651632e-12,1.361524071352429588e-01,-8.526512998316011731e-10,0.000000000000000000e+00 +5.372654430001801984e+01,3.364046766468626402e+02,2.116748025302195302e+00,4.000000039686759656e+00,-4.638938911114257047e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.372904429999321252e+01,3.364136198170942862e+02,2.112273686668682426e+00,4.000000039686759656e+00,-4.633938911114257042e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.373154429996840520e+01,3.364225652233772621e+02,2.107803820179391607e+00,4.000000039686759656e+00,-4.628938911114257038e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.373404429994359788e+01,3.364315128634752341e+02,2.103338426951788964e+00,4.000000039686759656e+00,-4.623938911114257033e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.373654429991879056e+01,3.364404627351513000e+02,2.098877508102223288e+00,4.000000039686759656e+00,-4.618938911114257029e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.373904429989398324e+01,3.364494148361679322e+02,2.094421064745923822e+00,4.000000039686759656e+00,-4.613938911114257024e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.374154429986917592e+01,3.364583691642871486e+02,2.089969097997001590e+00,4.000000039686759656e+00,-4.608938911114257020e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.374404429984436860e+01,3.364673257172703416e+02,2.085521608968448071e+00,4.000000039686759656e+00,-4.603938911114257015e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.374654429981956127e+01,3.364762844928783920e+02,2.081078598772136079e+00,4.000000039686759656e+00,-4.598938911114257011e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.374904429979475395e+01,3.364852454888716125e+02,2.076640068518817550e+00,4.000000039686759656e+00,-4.593938911114257007e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.375154429976994663e+01,3.364942087030097468e+02,2.072206019318125314e+00,4.000000039686759656e+00,-4.588938911114257002e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.375404429974513931e+01,3.365031741330519708e+02,2.067776452278571320e+00,4.000000039686759656e+00,-4.583938911114256998e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.375654429972033199e+01,3.365121417767569483e+02,2.063351368507547523e+00,4.000000039686759656e+00,-4.578938911114256993e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.375904429969552467e+01,3.365211116318827749e+02,2.058930769111324999e+00,4.000000039686759656e+00,-4.573938911114256989e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.376154429967071735e+01,3.365300836961869777e+02,2.054514655195053496e+00,4.000000039686759656e+00,-4.568938911114256984e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.376404429964591003e+01,3.365390579674265155e+02,2.050103027862761440e+00,4.000000039686759656e+00,-4.563938911114256980e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.376654429962110271e+01,3.365480344433578352e+02,2.045695888217355485e+00,4.000000039686759656e+00,-4.558938911114256975e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.376904429959629539e+01,3.365570131217368726e+02,2.041293237360620516e+00,4.000000039686759656e+00,-4.553938911114256971e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.377154429957148807e+01,3.365659940003188808e+02,2.036895076393219206e+00,4.000000039686759656e+00,-4.548938911114256967e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.377404429954668075e+01,3.365749770768586586e+02,2.032501406414692013e+00,4.000000039686759656e+00,-4.543938911114256962e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.377654429952187343e+01,3.365839623491104931e+02,2.028112228523456295e+00,4.000000039686759656e+00,-4.538938911114256958e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.377904429949706611e+01,3.365929498148279890e+02,2.023727543816806751e+00,4.000000039686759656e+00,-4.533938911114256953e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.378154429947225879e+01,3.366019394717642967e+02,2.019347353390914090e+00,4.000000039686759656e+00,-4.528938911114256949e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.378404429944745146e+01,3.366109313176720548e+02,2.014971658340826366e+00,4.000000039686759656e+00,-4.523938911114256944e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.378654429942264414e+01,3.366199253503032764e+02,2.010600459760466752e+00,4.000000039686759656e+00,-4.518938911114256940e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.378904429939783682e+01,3.366289215674094066e+02,2.006233758742635320e+00,4.000000039686759656e+00,-4.513938911114256936e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.379154429937302950e+01,3.366379199667414355e+02,2.001871556379007266e+00,4.000000039686759656e+00,-4.508938911114256931e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.379404429934822218e+01,3.366469205460497847e+02,1.997513853760132907e+00,4.000000039686759656e+00,-4.503938911114256927e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.379654429932341486e+01,3.366559233030842506e+02,1.993160651975438125e+00,4.000000039686759656e+00,-4.498938911114256922e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.379904429929860754e+01,3.366649282355941750e+02,1.988811952113223036e+00,4.000000039686759656e+00,-4.493938911114256918e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.380154429927380022e+01,3.366739353413283311e+02,1.984467755260662880e+00,4.000000039686759656e+00,-4.488938911114256913e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.380404429924899290e+01,3.366829446180349237e+02,1.980128062503806685e+00,4.000000039686759656e+00,-4.483938911114256909e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.380654429922418558e+01,3.366919560634616460e+02,1.975792874927577714e+00,4.000000039686759656e+00,-4.478938911114256904e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.380904429919937826e+01,3.367009696753556227e+02,1.971462193615772795e+00,4.000000039686759656e+00,-4.473938911114256900e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.381154429917457094e+01,3.367099854514634671e+02,1.967136019651062329e+00,4.000000039686759656e+00,-4.468938911114256896e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.381404429914976362e+01,3.367190033895312240e+02,1.962814354114989612e+00,4.000000039686759656e+00,-4.463938911114256891e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.381654429912495630e+01,3.367280234873044265e+02,1.958497198087971070e+00,4.000000039686759656e+00,-4.458938911114256887e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.381904429910014898e+01,3.367370457425280392e+02,1.954184552649295803e+00,4.000000039686759656e+00,-4.453938911114256882e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.382154429907534166e+01,3.367460701529465155e+02,1.949876418877124928e+00,4.000000039686759656e+00,-4.448938911114256878e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.382404429905053433e+01,3.367550967163037399e+02,1.945572797848492019e+00,4.000000039686759656e+00,-4.443938911114256873e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.382654429902572701e+01,3.367641254303430856e+02,1.941273690639302441e+00,4.000000039686759656e+00,-4.438938911114256869e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.382904429900091969e+01,3.367731562928073572e+02,1.936979098324332682e+00,4.000000039686759656e+00,-4.433938911114256864e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.383154429897611237e+01,3.367821893014387911e+02,1.932689021977231025e+00,4.000000039686759656e+00,-4.428938911114256860e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.383404429895130505e+01,3.367912244539792255e+02,1.928403462670516433e+00,4.000000039686759656e+00,-4.423938911114256856e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.383654429892649773e+01,3.368002617481698167e+02,1.924122421475578770e+00,4.000000039686759656e+00,-4.418938911114256851e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.383904429890169041e+01,3.368093011817512661e+02,1.919845899462678140e+00,4.000000039686759656e+00,-4.413938911114256847e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.384154429887688309e+01,3.368183427524637068e+02,1.915573897700945105e+00,4.000000039686759656e+00,-4.408938911114256842e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.384404429885207577e+01,3.368273864580467034e+02,1.911306417258380241e+00,4.000000039686759656e+00,-4.403938911114256838e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.384654429882726845e+01,3.368364322962393658e+02,1.907043459201853475e+00,4.000000039686759656e+00,-4.398938911114256833e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.384904429880246113e+01,3.368454802647802353e+02,1.902785024597104302e+00,4.000000039686759656e+00,-4.393938911114256829e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.385154429877765381e+01,3.368545303614073418e+02,1.898531114508741346e+00,4.000000039686759656e+00,-4.388938911114256824e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.385404429875284649e+01,3.368635825838581468e+02,1.894281730000242137e+00,4.000000039686759656e+00,-4.383938911114256820e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.385654429872803917e+01,3.368726369298696000e+02,1.890036872133952883e+00,4.000000039686759656e+00,-4.378938911114256816e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.385904429870323185e+01,3.368816933971780827e+02,1.885796541971088036e+00,4.000000039686759656e+00,-4.373938911114256811e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.386154429867842452e+01,3.368907519835195217e+02,1.881560740571729839e+00,4.000000039686759656e+00,-4.368938911114256807e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.386404429865361720e+01,3.368998126866292182e+02,1.877329468994828998e+00,4.000000039686759656e+00,-4.363938911114256802e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.386654429862880988e+01,3.369088755042420757e+02,1.873102728298203123e+00,4.000000039686759656e+00,-4.358938911114256798e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.386904429860400256e+01,3.369179404340923156e+02,1.868880519538537399e+00,4.000000039686759656e+00,-4.353938911114256793e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.387154429857919524e+01,3.369270074739137613e+02,1.864662843771384138e+00,4.000000039686759656e+00,-4.348938911114256789e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.387404429855438792e+01,3.369360766214396108e+02,1.860449702051162113e+00,4.000000039686759656e+00,-4.343938911114256785e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.387654429852958060e+01,3.369451478744025508e+02,1.856241095431156785e+00,4.000000039686759656e+00,-4.338938911114256780e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.387904429850477328e+01,3.369542212305348130e+02,1.852037024963519629e+00,4.000000039686759656e+00,-4.333938911114256776e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.388154429847996596e+01,3.369632966875680609e+02,1.847837491699268364e+00,4.000000039686759656e+00,-4.328938911114256771e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.388404429845515864e+01,3.369723742432334461e+02,1.843642496688286281e+00,4.000000039686759656e+00,-4.323938911114256767e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.388654429843035132e+01,3.369814538952615521e+02,1.839452040979322245e+00,4.000000039686759656e+00,-4.318938911114256762e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.388904429840554400e+01,3.369905356413824506e+02,1.835266125619990030e+00,4.000000039686759656e+00,-4.313938911114256758e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.389154429838073668e+01,3.369996194793257018e+02,1.831084751656768539e+00,4.000000039686759656e+00,-4.308938911114256753e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.389404429835592936e+01,3.370087054068204111e+02,1.826907920135001140e+00,4.000000039686759656e+00,-4.303938911114256749e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.389654429833112204e+01,3.370177934215950586e+02,1.822735632098895664e+00,4.000000039686759656e+00,-4.298938911114256745e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.389904429830631472e+01,3.370268835213776129e+02,1.818567888591524184e+00,4.000000039686759656e+00,-4.293938911114256740e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.390154429828150739e+01,3.370359757038955877e+02,1.814404690654822572e+00,4.000000039686759656e+00,-4.288938911114256736e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.390404429825670007e+01,3.370450699668759285e+02,1.810246039329590273e+00,4.000000039686759656e+00,-4.283938911114256731e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.390654429823189275e+01,3.370541663080450121e+02,1.806091935655490088e+00,4.000000039686759656e+00,-4.278938911114256727e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.390904429820708543e+01,3.370632647251288176e+02,1.801942380671047728e+00,4.000000039686759656e+00,-4.273938911114256722e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.391154429818227811e+01,3.370723652158527557e+02,1.797797375413652254e+00,4.000000039686759656e+00,-4.268938911114256718e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.391404429815747079e+01,3.370814677779416684e+02,1.793656920919554754e+00,4.000000039686759656e+00,-4.263938911114256713e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.391654429813266347e+01,3.370905724091198863e+02,1.789521018223868776e+00,4.000000039686759656e+00,-4.258938911114256709e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.391904429810785615e+01,3.370996791071112852e+02,1.785389668360570115e+00,4.000000039686759656e+00,-4.253938911114256705e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.392154429808304883e+01,3.371087878696392295e+02,1.781262872362496141e+00,4.000000039686759656e+00,-4.248938911114256700e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.392404429805824151e+01,3.371178986944264580e+02,1.777140631261345805e+00,4.000000039686759656e+00,-4.243938911114256696e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.392654429803343419e+01,3.371270115791953117e+02,1.773022946087679408e+00,4.000000039686759656e+00,-4.238938911114256691e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.392904429800862687e+01,3.371361265216675633e+02,1.768909817870918388e+00,4.000000039686759656e+00,-4.233938911114256687e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.393154429798381955e+01,3.371452435195644739e+02,1.764801247639344650e+00,4.000000039686759656e+00,-4.228938911114256682e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.393404429795901223e+01,3.371543625706067928e+02,1.760697236420100564e+00,4.000000039686759656e+00,-4.223938911114256678e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.393654429793420491e+01,3.371634836725147579e+02,1.756597785239188969e+00,4.000000039686759656e+00,-4.218938911114256674e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.393904429790939759e+01,3.371726068230080955e+02,1.752502895121472726e+00,4.000000039686759656e+00,-4.213938911114256669e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.394154429788459026e+01,3.371817320198060202e+02,1.748412567090674496e+00,4.000000039686759656e+00,-4.208938911114256665e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.394404429785978294e+01,3.371908592606271782e+02,1.744326802169376078e+00,4.000000039686759656e+00,-4.203938911114256660e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.394654429783497562e+01,3.371999885431898178e+02,1.740245601379018625e+00,4.000000039686759656e+00,-4.198938911114256656e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.394904429781016830e+01,3.372091198652116191e+02,1.736168965739902426e+00,4.000000039686759656e+00,-4.193938911114256651e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.395154429778536098e+01,3.372182532244097501e+02,1.732096896271186237e+00,4.000000039686759656e+00,-4.188938911114256647e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.395404429776055366e+01,3.372273886185008678e+02,1.728029393990887508e+00,4.000000039686759656e+00,-4.183938911114256642e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.395654429773574634e+01,3.372365260452011171e+02,1.723966459915881932e+00,4.000000039686759656e+00,-4.178938911114256638e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.395904429771093902e+01,3.372456655022261316e+02,1.719908095061902786e+00,4.000000039686759656e+00,-4.173938911114256634e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.396154429768613170e+01,3.372548069872910332e+02,1.715854300443541369e+00,4.000000039686759656e+00,-4.168938911114256629e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.396404429766132438e+01,3.372639504981104892e+02,1.711805077074246340e+00,4.000000039686759656e+00,-4.163938911114256625e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.396654429763651706e+01,3.372730960323985983e+02,1.707760425966323492e+00,4.000000039686759656e+00,-4.158938911114256620e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.396904429761170974e+01,3.372822435878690044e+02,1.703720348130935536e+00,4.000000039686759656e+00,-4.153938911114256616e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.397154429758690242e+01,3.372913931622347832e+02,1.699684844578101872e+00,4.000000039686759656e+00,-4.148938911114256611e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.397404429756209510e+01,3.373005447532085554e+02,1.695653916316698373e+00,4.000000039686759656e+00,-4.143938911114256607e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.397654429753728778e+01,3.373096983585024304e+02,1.691627564354457158e+00,4.000000039686759656e+00,-4.138938911114256602e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.397904429751248045e+01,3.373188539758280058e+02,1.687605789697966152e+00,4.000000039686759656e+00,-4.133938911114256598e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.398154429748767313e+01,3.373280116028963675e+02,1.683588593352669083e+00,4.000000039686759656e+00,-4.128938911114256594e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.398404429746286581e+01,3.373371712374181470e+02,1.679575976322864816e+00,4.000000039686759656e+00,-4.123938911114256589e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.398654429743805849e+01,3.373463328771034071e+02,1.675567939611707802e+00,4.000000039686759656e+00,-4.118938911114256585e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.398904429741325117e+01,3.373554965196616990e+02,1.671564484221207181e+00,4.000000039686759656e+00,-4.113938911114256580e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.399154429738844385e+01,3.373646621628021762e+02,1.667565611152226568e+00,4.000000039686759656e+00,-4.108938911114256576e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.399404429736363653e+01,3.373738298042333668e+02,1.663571321404484493e+00,4.000000039686759656e+00,-4.103938911114256571e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.399654429733882921e+01,3.373829994416634008e+02,1.659581615976553071e+00,4.000000039686759656e+00,-4.098938911114256567e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.399904429731402189e+01,3.373921710727998402e+02,1.655596495865858886e+00,4.000000039686759656e+00,-4.093938911114256562e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.400154429728921457e+01,3.374013446953498487e+02,1.651615962068681887e+00,4.000000039686759656e+00,-4.088938911114256558e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.400404429726440725e+01,3.374105203070199650e+02,1.647640015580155382e+00,4.000000039686759656e+00,-4.083938911114256554e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.400654429723959993e+01,3.374196979055162728e+02,1.643668657394266042e+00,4.000000039686759656e+00,-4.078938911114256549e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.400904429721479261e+01,3.374288774885444013e+02,1.639701888503853455e+00,4.000000039686759656e+00,-4.073938911114256545e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.401154429718998529e+01,3.374380590538094111e+02,1.635739709900609906e+00,4.000000039686759656e+00,-4.068938911114256540e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.401404429716517797e+01,3.374472425990159650e+02,1.631782122575079930e+00,4.000000039686759656e+00,-4.063938911114256536e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.401654429714037065e+01,3.374564281218681572e+02,1.627829127516660312e+00,4.000000039686759656e+00,-4.058938911114256531e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.401904429711556332e+01,3.374656156200696273e+02,1.623880725713599649e+00,4.000000039686759656e+00,-4.053938911114256527e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.402154429709075600e+01,3.374748050913234465e+02,1.619936918152998562e+00,4.000000039686759656e+00,-4.048938911114256523e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.402404429706594868e+01,3.374839965333322880e+02,1.615997705820808816e+00,4.000000039686759656e+00,-4.043938911114256518e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.402654429704114136e+01,3.374931899437982565e+02,1.612063089701833540e+00,4.000000039686759656e+00,-4.038938911114256514e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.402904429701633404e+01,3.375023853204230591e+02,1.608133070779726781e+00,4.000000039686759656e+00,-4.033938911114256509e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.403154429699152672e+01,3.375115826609078340e+02,1.604207650036993282e+00,4.000000039686759656e+00,-4.028938911114256505e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.403404429696671940e+01,3.375207819629532082e+02,1.600286828454988042e+00,4.000000039686759656e+00,-4.023938911114256500e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.403654429694191208e+01,3.375299832242593538e+02,1.596370607013916532e+00,4.000000039686759656e+00,-4.018938911114256496e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.403904429691710476e+01,3.375391864425259882e+02,1.592458986692834033e+00,4.000000039686759656e+00,-4.013938911114256491e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.404154429689229744e+01,3.375483916154523172e+02,1.588551968469645859e+00,4.000000039686759656e+00,-4.008938911114256487e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.404404429686749012e+01,3.375575987407370349e+02,1.584649553321106241e+00,4.000000039686759656e+00,-4.003938911114256483e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.404654429684268280e+01,3.375668078160783807e+02,1.580751742222819001e+00,4.000000039686759656e+00,-3.998938911114256478e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.404904429681787548e+01,3.375760188391740257e+02,1.576858536149236878e+00,4.000000039686759656e+00,-3.993938911114256474e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.405154429679306816e+01,3.375852318077212431e+02,1.572969936073661534e+00,4.000000039686759656e+00,-3.988938911114256469e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.405404429676826084e+01,3.375944467194167942e+02,1.569085942968242886e+00,4.000000039686759656e+00,-3.983938911114256465e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.405654429674345351e+01,3.376036635719569858e+02,1.565206557803979104e+00,4.000000039686759656e+00,-3.978938911114256460e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.405904429671864619e+01,3.376128823630375564e+02,1.561331781550716613e+00,4.000000039686759656e+00,-3.973938911114256456e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.406154429669383887e+01,3.376221030903538463e+02,1.557461615177149428e+00,4.000000039686759656e+00,-3.968938911114256451e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.406404429666903155e+01,3.376313257516006274e+02,1.553596059650818928e+00,4.000000039686759656e+00,-3.963938911114256447e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.406654429664422423e+01,3.376405503444722740e+02,1.549735115938114083e+00,4.000000039686759656e+00,-3.958938911114256443e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.406904429661941691e+01,3.376497768666625916e+02,1.545878785004271005e+00,4.000000039686759656e+00,-3.953938911114256438e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.407154429659460959e+01,3.376590053158649880e+02,1.542027067813372065e+00,4.000000039686759656e+00,-3.948938911114256434e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.407404429656980227e+01,3.376682356897723594e+02,1.538179965328346777e+00,4.000000039686759656e+00,-3.943938911114256429e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.407654429654499495e+01,3.376774679860770902e+02,1.534337478510970687e+00,4.000000039686759656e+00,-3.938938911114256425e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.407904429652018763e+01,3.376867022024711105e+02,1.530499608321865379e+00,4.000000039686759656e+00,-3.933938911114256420e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.408154429649538031e+01,3.376959383366458951e+02,1.526666355720498469e+00,4.000000039686759656e+00,-3.928938911114256416e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.408404429647057299e+01,3.377051763862923508e+02,1.522837721665183164e+00,4.000000039686759656e+00,-3.923938911114256411e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.408654429644576567e+01,3.377144163491009863e+02,1.519013707113077816e+00,4.000000039686759656e+00,-3.918938911114256407e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.408904429642095835e+01,3.377236582227618555e+02,1.515194313020186145e+00,4.000000039686759656e+00,-3.913938911114256403e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.409154429639615103e+01,3.377329020049644441e+02,1.511379540341356575e+00,4.000000039686759656e+00,-3.908938911114256398e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.409404429637134371e+01,3.377421476933978397e+02,1.507569390030282230e+00,4.000000039686759656e+00,-3.903938911114256394e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.409654429634653638e+01,3.377513952857505615e+02,1.503763863039500936e+00,4.000000039686759656e+00,-3.898938911114256389e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.409904429632172906e+01,3.377606447797107876e+02,1.499962960320394112e+00,4.000000039686759656e+00,-3.893938911114256385e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.410154429629692174e+01,3.377698961729660709e+02,1.496166682823187433e+00,4.000000039686759656e+00,-3.888938911114256380e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.410404429627211442e+01,3.377791494632036233e+02,1.492375031496950388e+00,4.000000039686759656e+00,-3.883938911114256376e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.410654429624730710e+01,3.377884046481100881e+02,1.488588007289595838e+00,4.000000039686759656e+00,-3.878938911114256372e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.410904429622249978e+01,3.377976617253717109e+02,1.484805611147879567e+00,4.000000039686759656e+00,-3.873938911114256367e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.411154429619769246e+01,3.378069206926741685e+02,1.481027844017400952e+00,4.000000039686759656e+00,-3.868938911114256363e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.411404429617288514e+01,3.378161815477027403e+02,1.477254706842601406e+00,4.000000039686759656e+00,-3.863938911114256358e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.411654429614807782e+01,3.378254442881421937e+02,1.473486200566765492e+00,4.000000039686759656e+00,-3.858938911114256354e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.411904429612327050e+01,3.378347089116768984e+02,1.469722326132019585e+00,4.000000039686759656e+00,-3.853938911114256349e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.412154429609846318e+01,3.378439754159906556e+02,1.465963084479332323e+00,4.000000039686759656e+00,-3.848938911114256345e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.412404429607365586e+01,3.378532437987668118e+02,1.462208476548513936e+00,4.000000039686759656e+00,-3.843938911114256340e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.412654429604884854e+01,3.378625140576883155e+02,1.458458503278216467e+00,4.000000039686759656e+00,-3.838938911114256336e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.412904429602404122e+01,3.378717861904376036e+02,1.454713165605933334e+00,4.000000039686759656e+00,-3.833938911114256332e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.413154429599923390e+01,3.378810601946966585e+02,1.450972464467998879e+00,4.000000039686759656e+00,-3.828938911114256327e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.413404429597442657e+01,3.378903360681469508e+02,1.447236400799588374e+00,4.000000039686759656e+00,-3.823938911114256323e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.413654429594961925e+01,3.378996138084694962e+02,1.443504975534717794e+00,4.000000039686759656e+00,-3.818938911114256318e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.413904429592481193e+01,3.379088934133448561e+02,1.439778189606243375e+00,4.000000039686759656e+00,-3.813938911114256314e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.414154429590000461e+01,3.379181748804531935e+02,1.436056043945861393e+00,4.000000039686759656e+00,-3.808938911114256309e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.414404429587519729e+01,3.379274582074741033e+02,1.432338539484108608e+00,4.000000039686759656e+00,-3.803938911114256305e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.414654429585038997e+01,3.379367433920867256e+02,1.428625677150360707e+00,4.000000039686759656e+00,-3.798938911114256300e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.414904429582558265e+01,3.379460304319698025e+02,1.424917457872833637e+00,4.000000039686759656e+00,-3.793938911114256296e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.415154429580077533e+01,3.379553193248015646e+02,1.421213882578582055e+00,4.000000039686759656e+00,-3.788938911114256292e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.415404429577596801e+01,3.379646100682597876e+02,1.417514952193499544e+00,4.000000039686759656e+00,-3.783938911114256287e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.415654429575116069e+01,3.379739026600217926e+02,1.413820667642319062e+00,4.000000039686759656e+00,-3.778938911114256283e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.415904429572635337e+01,3.379831970977643891e+02,1.410131029848611384e+00,4.000000039686759656e+00,-3.773938911114256278e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.416154429570154605e+01,3.379924933791639887e+02,1.406446039734786213e+00,4.000000039686759656e+00,-3.768938911114256274e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.416404429567673873e+01,3.380017915018965482e+02,1.402765698222090851e+00,4.000000039686759656e+00,-3.763938911114256269e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.416654429565193141e+01,3.380110914636375128e+02,1.399090006230610861e+00,4.000000039686759656e+00,-3.758938911114256265e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.416904429562712409e+01,3.380203932620619298e+02,1.395418964679268958e+00,4.000000039686759656e+00,-3.753938911114256261e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.417154429560231677e+01,3.380296968948443350e+02,1.391752574485825678e+00,4.000000039686759656e+00,-3.748938911114256256e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.417404429557750944e+01,3.380390023596588094e+02,1.388090836566878483e+00,4.000000039686759656e+00,-3.743938911114256252e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.417654429555270212e+01,3.380483096541789791e+02,1.384433751837861992e+00,4.000000039686759656e+00,-3.738938911114256247e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.417904429552789480e+01,3.380576187760780158e+02,1.380781321213047308e+00,4.000000039686759656e+00,-3.733938911114256243e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.418154429550308748e+01,3.380669297230286361e+02,1.377133545605542020e+00,4.000000039686759656e+00,-3.728938911114256238e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.418404429547828016e+01,3.380762424927031020e+02,1.373490425927289982e+00,4.000000039686759656e+00,-3.723938911114256234e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.418654429545347284e+01,3.380855570827732777e+02,1.369851963089071090e+00,4.000000039686759656e+00,-3.718938911114256229e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.418904429542866552e+01,3.380948734909104587e+02,1.366218158000501059e+00,4.000000039686759656e+00,-3.713938911114256225e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.419154429540385820e+01,3.381041917147855429e+02,1.362589011570031206e+00,4.000000039686759656e+00,-3.708938911114256221e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.419404429537905088e+01,3.381135117520689732e+02,1.358964524704947996e+00,4.000000039686759656e+00,-3.703938911114256216e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.419654429535424356e+01,3.381228336004307948e+02,1.355344698311373053e+00,4.000000039686759656e+00,-3.698938911114256212e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.419904429532943624e+01,3.381321572575404844e+02,1.351729533294263152e+00,4.000000039686759656e+00,-3.693938911114256207e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.420154429530462892e+01,3.381414827210671774e+02,1.348119030557409559e+00,4.000000039686759656e+00,-3.688938911114256203e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.420404429527982160e+01,3.381508099886794412e+02,1.344513191003437802e+00,4.000000039686759656e+00,-3.683938911114256198e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.420654429525501428e+01,3.381601390580455018e+02,1.340912015533807899e+00,4.000000039686759656e+00,-3.678938911114256194e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.420904429523020696e+01,3.381694699268330737e+02,1.337315505048813469e+00,4.000000039686759656e+00,-3.673938911114256189e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.421154429520539964e+01,3.381788025927094736e+02,1.333723660447582171e+00,4.000000039686759656e+00,-3.668938911114256185e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.421404429518059231e+01,3.381881370533415065e+02,1.330136482628075267e+00,4.000000039686759656e+00,-3.663938911114256181e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.421654429515578499e+01,3.381974733063955796e+02,1.326553972487087174e+00,4.000000039686759656e+00,-3.658938911114256176e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.421904429513097767e+01,3.382068113495376451e+02,1.322976130920245463e+00,4.000000039686759656e+00,-3.653938911114256172e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.422154429510617035e+01,3.382161511804331440e+02,1.319402958822010419e+00,4.000000039686759656e+00,-3.648938911114256167e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.422404429508136303e+01,3.382254927967471190e+02,1.315834457085675036e+00,4.000000039686759656e+00,-3.643938911114256163e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.422654429505655571e+01,3.382348361961442151e+02,1.312270626603364576e+00,4.000000039686759656e+00,-3.638938911114256158e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.422904429503174839e+01,3.382441813762885090e+02,1.308711468266036793e+00,4.000000039686759656e+00,-3.633938911114256154e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.423154429500694107e+01,3.382535283348437929e+02,1.305156982963481260e+00,4.000000039686759656e+00,-3.628938911114256149e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.423404429498213375e+01,3.382628770694732907e+02,1.301607171584319378e+00,4.000000039686759656e+00,-3.623938911114256145e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.423654429495732643e+01,3.382722275778397716e+02,1.298062035016003923e+00,4.000000039686759656e+00,-3.618938911114256141e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.423904429493251911e+01,3.382815798576056636e+02,1.294521574144818832e+00,4.000000039686759656e+00,-3.613938911114256136e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.424154429490771179e+01,3.382909339064328833e+02,1.290985789855879640e+00,4.000000039686759656e+00,-3.608938911114256132e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.424404429488290447e+01,3.383002897219829492e+02,1.287454683033132152e+00,4.000000039686759656e+00,-3.603938911114256127e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.424654429485809715e+01,3.383096473019168684e+02,1.283928254559353110e+00,4.000000039686759656e+00,-3.598938911114256123e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.424904429483328983e+01,3.383190066438952499e+02,1.280406505316149524e+00,4.000000039686759656e+00,-3.593938911114256118e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.425154429480848250e+01,3.383283677455782481e+02,1.276889436183958892e+00,4.000000039686759656e+00,-3.588938911114256114e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.425404429478367518e+01,3.383377306046256194e+02,1.273377048042048321e+00,4.000000039686759656e+00,-3.583938911114256110e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.425654429475886786e+01,3.383470952186966088e+02,1.269869341768514959e+00,4.000000039686759656e+00,-3.578938911114256105e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.425904429473406054e+01,3.383564615854500630e+02,1.266366318240285116e+00,4.000000039686759656e+00,-3.573938911114256101e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.426154429470925322e+01,3.383658297025444313e+02,1.262867978333114927e+00,4.000000039686759656e+00,-3.568938911114256096e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.426404429468444590e+01,3.383751995676376509e+02,1.259374322921589240e+00,4.000000039686759656e+00,-3.563938911114256092e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.426654429465963858e+01,3.383845711783873185e+02,1.255885352879121841e+00,4.000000039686759656e+00,-3.558938911114256087e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.426904429463483126e+01,3.383939445324504618e+02,1.252401069077955231e+00,4.000000039686759656e+00,-3.553938911114256083e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.427154429461002394e+01,3.384033196274837678e+02,1.248921472389160403e+00,4.000000039686759656e+00,-3.548938911114256078e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.427404429458521662e+01,3.384126964611434687e+02,1.245446563682636398e+00,4.000000039686759656e+00,-3.543938911114256074e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.427654429456040930e+01,3.384220750310853418e+02,1.241976343827110529e+00,4.000000039686759656e+00,-3.538938911114256070e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.427904429453560198e+01,3.384314553349647099e+02,1.238510813690137713e+00,4.000000039686759656e+00,-3.533938911114256065e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.428154429451079466e+01,3.384408373704365545e+02,1.235049974138100470e+00,4.000000039686759656e+00,-3.528938911114256061e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.428404429448598734e+01,3.384502211351553456e+02,1.231593826036208483e+00,4.000000039686759656e+00,-3.523938911114256056e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.428654429446118002e+01,3.384596066267751553e+02,1.228142370248499038e+00,4.000000039686759656e+00,-3.518938911114256052e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.428904429443637270e+01,3.384689938429496010e+02,1.224695607637835915e+00,4.000000039686759656e+00,-3.513938911114256047e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.429154429441156537e+01,3.384783827813319022e+02,1.221253539065909832e+00,4.000000039686759656e+00,-3.508938911114256043e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.429404429438675805e+01,3.384877734395747666e+02,1.217816165393237782e+00,4.000000039686759656e+00,-3.503938911114256038e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.429654429436195073e+01,3.384971658153305611e+02,1.214383487479163248e+00,4.000000039686759656e+00,-3.498938911114256034e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.429904429433714341e+01,3.385065599062511978e+02,1.210955506181855545e+00,4.000000039686759656e+00,-3.493938911114256030e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.430154429431233609e+01,3.385159557099881340e+02,1.207532222358310259e+00,4.000000039686759656e+00,-3.488938911114256025e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.430404429428752877e+01,3.385253532241924859e+02,1.204113636864348136e+00,4.000000039686759656e+00,-3.483938911114256021e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.430654429426272145e+01,3.385347524465148012e+02,1.200699750554615530e+00,4.000000039686759656e+00,-3.478938911114256016e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.430904429423791413e+01,3.385441533746052869e+02,1.197290564282583958e+00,4.000000039686759656e+00,-3.473938911114256012e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.431154429421310681e+01,3.385535560061137517e+02,1.193886078900550096e+00,4.000000039686759656e+00,-3.468938911114256007e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.431404429418829949e+01,3.385629603386894928e+02,1.190486295259635341e+00,4.000000039686759656e+00,-3.463938911114256003e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.431654429416349217e+01,3.385723663699814097e+02,1.187091214209785361e+00,4.000000039686759656e+00,-3.458938911114255998e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.431904429413868485e+01,3.385817740976380605e+02,1.183700836599770545e+00,4.000000039686759656e+00,-3.453938911114255994e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.432154429411387753e+01,3.385911835193074921e+02,1.180315163277185331e+00,4.000000039686759656e+00,-3.448938911114255990e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.432404429408907021e+01,3.386005946326372964e+02,1.176934195088447987e+00,4.000000039686759656e+00,-3.443938911114255985e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.432654429406426289e+01,3.386100074352747811e+02,1.173557932878800392e+00,4.000000039686759656e+00,-3.438938911114255981e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.432904429403945556e+01,3.386194219248666855e+02,1.170186377492308250e+00,4.000000039686759656e+00,-3.433938911114255976e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.433154429401464824e+01,3.386288380990594078e+02,1.166819529771860209e+00,4.000000039686759656e+00,-3.428938911114255972e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.433404429398984092e+01,3.386382559554988916e+02,1.163457390559168303e+00,4.000000039686759656e+00,-3.423938911114255967e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.433654429396503360e+01,3.386476754918306824e+02,1.160099960694767507e+00,4.000000039686759656e+00,-3.418938911114255963e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.433904429394022628e+01,3.386570967056998711e+02,1.156747241018015071e+00,4.000000039686759656e+00,-3.413938911114255959e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.434154429391541896e+01,3.386665195947512075e+02,1.153399232367090743e+00,4.000000039686759656e+00,-3.408938911114255954e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.434404429389061164e+01,3.386759441566289297e+02,1.150055935578996991e+00,4.000000039686759656e+00,-3.403938911114255950e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.434654429386580432e+01,3.386853703889768781e+02,1.146717351489557668e+00,4.000000039686759656e+00,-3.398938911114255945e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.434904429384099700e+01,3.386947982894385518e+02,1.143383480933419127e+00,4.000000039686759656e+00,-3.393938911114255941e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.435154429381618968e+01,3.387042278556569386e+02,1.140054324744048664e+00,4.000000039686759656e+00,-3.388938911114255936e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.435404429379138236e+01,3.387136590852746281e+02,1.136729883753735404e+00,4.000000039686759656e+00,-3.383938911114255932e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.435654429376657504e+01,3.387230919759338690e+02,1.133410158793589639e+00,4.000000039686759656e+00,-3.378938911114255927e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.435904429374176772e+01,3.387325265252763984e+02,1.130095150693542605e+00,4.000000039686759656e+00,-3.373938911114255923e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.436154429371696040e+01,3.387419627309436123e+02,1.126784860282346257e+00,4.000000039686759656e+00,-3.368938911114255919e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.436404429369215308e+01,3.387514005905763952e+02,1.123479288387573272e+00,4.000000039686759656e+00,-3.363938911114255914e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.436654429366734576e+01,3.387608401018153472e+02,1.120178435835616604e+00,4.000000039686759656e+00,-3.358938911114255910e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.436904429364253843e+01,3.387702812623005570e+02,1.116882303451689262e+00,4.000000039686759656e+00,-3.353938911114255905e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.437154429361773111e+01,3.387797240696717722e+02,1.113590892059824311e+00,4.000000039686759656e+00,-3.348938911114255901e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.437404429359292379e+01,3.387891685215682287e+02,1.110304202482874647e+00,4.000000039686759656e+00,-3.343938911114255896e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.437654429356811647e+01,3.387986146156288783e+02,1.107022235542512778e+00,4.000000039686759656e+00,-3.338938911114255892e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.437904429354330915e+01,3.388080623494921610e+02,1.103744992059230157e+00,4.000000039686759656e+00,-3.333938911114255887e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.438154429351850183e+01,3.388175117207961193e+02,1.100472472852337846e+00,4.000000039686759656e+00,-3.328938911114255883e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.438404429349369451e+01,3.388269627271784543e+02,1.097204678739965633e+00,4.000000039686759656e+00,-3.323938911114255879e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.438654429346888719e+01,3.388364153662764124e+02,1.093941610539061804e+00,4.000000039686759656e+00,-3.318938911114255874e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.438904429344407987e+01,3.388458696357268423e+02,1.090683269065393590e+00,4.000000039686759656e+00,-3.313938911114255870e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.439154429341927255e+01,3.388553255331661376e+02,1.087429655133546280e+00,4.000000039686759656e+00,-3.308938911114255865e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.439404429339446523e+01,3.388647830562303511e+02,1.084180769556923440e+00,4.000000039686759656e+00,-3.303938911114255861e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.439654429336965791e+01,3.388742422025550809e+02,1.080936613147746250e+00,4.000000039686759656e+00,-3.298938911114255856e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.439904429334485059e+01,3.388837029697755838e+02,1.077697186717053945e+00,4.000000039686759656e+00,-3.293938911114255852e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.440154429332004327e+01,3.388931653555266053e+02,1.074462491074703152e+00,4.000000039686759656e+00,-3.288938911114255848e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.440404429329523595e+01,3.389026293574426063e+02,1.071232527029367665e+00,4.000000039686759656e+00,-3.283938911114255843e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.440654429327042862e+01,3.389120949731575365e+02,1.068007295388538447e+00,4.000000039686759656e+00,-3.278938911114255839e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.440904429324562130e+01,3.389215622003050044e+02,1.064786796958523407e+00,4.000000039686759656e+00,-3.273938911114255834e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.441154429322081398e+01,3.389310310365182204e+02,1.061571032544447180e+00,4.000000039686759656e+00,-3.268938911114255830e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.441404429319600666e+01,3.389405014794299973e+02,1.058360002950250900e+00,4.000000039686759656e+00,-3.263938911114255825e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.441654429317119934e+01,3.389499735266726930e+02,1.055153708978691984e+00,4.000000039686759656e+00,-3.258938911114255821e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.441904429314639202e+01,3.389594471758783243e+02,1.051952151431343685e+00,4.000000039686759656e+00,-3.253938911114255816e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.442154429312158470e+01,3.389689224246784534e+02,1.048755331108595534e+00,4.000000039686759656e+00,-3.248938911114255812e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.442404429309677738e+01,3.389783992707042444e+02,1.045563248809652679e+00,4.000000039686759656e+00,-3.243938911114255808e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.442654429307197006e+01,3.389878777115865205e+02,1.042375905332535435e+00,4.000000039686759656e+00,-3.238938911114255803e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.442904429304716274e+01,3.389973577449556501e+02,1.039193301474079956e+00,4.000000039686759656e+00,-3.233938911114255799e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.443154429302235542e+01,3.390068393684416606e+02,1.036015438029936897e+00,4.000000039686759656e+00,-3.228938911114255794e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.443404429299754810e+01,3.390163225796741244e+02,1.032842315794572308e+00,4.000000039686759656e+00,-3.223938911114255790e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.443654429297274078e+01,3.390258073762822164e+02,1.029673935561266740e+00,4.000000039686759656e+00,-3.218938911114255785e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.443904429294793346e+01,3.390352937558947701e+02,1.026510298122115028e+00,4.000000039686759656e+00,-3.213938911114255781e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.444154429292312614e+01,3.390447817161401645e+02,1.023351404268026732e+00,4.000000039686759656e+00,-3.208938911114255776e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.444404429289831882e+01,3.390542712546464372e+02,1.020197254788725028e+00,4.000000039686759656e+00,-3.203938911114255772e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.444654429287351149e+01,3.390637623690412283e+02,1.017047850472747594e+00,4.000000039686759656e+00,-3.198938911114255768e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.444904429284870417e+01,3.390732550569517230e+02,1.013903192107445284e+00,4.000000039686759656e+00,-3.193938911114255763e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.445154429282389685e+01,3.390827493160047084e+02,1.010763280478982784e+00,4.000000039686759656e+00,-3.188938911114255759e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.445404429279908953e+01,3.390922451438266876e+02,1.007628116372337956e+00,4.000000039686759656e+00,-3.183938911114255754e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.445654429277428221e+01,3.391017425380436521e+02,1.004497700571301610e+00,4.000000039686759656e+00,-3.178938911114255750e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.445904429274947489e+01,3.391112414962813091e+02,1.001372033858477950e+00,4.000000039686759656e+00,-3.173938911114255745e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.446154429272466757e+01,3.391207420161648542e+02,9.982511170152835733e-01,4.000000039686759656e+00,-3.168938911114255741e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.446404429269986025e+01,3.391302440953191990e+02,9.951349508219475837e-01,4.000000039686759656e+00,-3.163938911114255736e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.446654429267505293e+01,3.391397477313688000e+02,9.920235360575115902e-01,4.000000039686759656e+00,-3.158938911114255732e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.446904429265024561e+01,3.391492529219377730e+02,9.889168734998292631e-01,4.000000039686759656e+00,-3.153938911114255728e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.447154429262543829e+01,3.391587596646498355e+02,9.858149639255662233e-01,4.000000039686759656e+00,-3.148938911114255723e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.447404429260063097e+01,3.391682679571282506e+02,9.827178081101998197e-01,4.000000039686759656e+00,-3.143938911114255719e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.447654429257582365e+01,3.391777777969959971e+02,9.796254068280190186e-01,4.000000039686759656e+00,-3.138938911114255714e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.447904429255101633e+01,3.391872891818755988e+02,9.765377608521241815e-01,4.000000039686759656e+00,-3.133938911114255710e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.448154429252620901e+01,3.391968021093891821e+02,9.734548709544266210e-01,4.000000039686759656e+00,-3.128938911114255705e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.448404429250140169e+01,3.392063165771585318e+02,9.703767379056489339e-01,4.000000039686759656e+00,-3.123938911114255701e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.448654429247659436e+01,3.392158325828050351e+02,9.673033624753243354e-01,4.000000039686759656e+00,-3.118938911114255697e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.448904429245178704e+01,3.392253501239496813e+02,9.642347454317966582e-01,4.000000039686759656e+00,-3.113938911114255692e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.449154429242697972e+01,3.392348691982131186e+02,9.611708875422201315e-01,4.000000039686759656e+00,-3.108938911114255688e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.449404429240217240e+01,3.392443898032155403e+02,9.581117895725592692e-01,4.000000039686759656e+00,-3.103938911114255683e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.449654429237736508e+01,3.392539119365767988e+02,9.550574522875885375e-01,4.000000039686759656e+00,-3.098938911114255679e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.449904429235255776e+01,3.392634355959163486e+02,9.520078764508921321e-01,4.000000039686759656e+00,-3.093938911114255674e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.450154429232775044e+01,3.392729607788533031e+02,9.489630628248640898e-01,4.000000039686759656e+00,-3.088938911114255670e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.450404429230294312e+01,3.392824874830063777e+02,9.459230121707078442e-01,4.000000039686759656e+00,-3.083938911114255665e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.450654429227813580e+01,3.392920157059938902e+02,9.428877252484358928e-01,4.000000039686759656e+00,-3.078938911114255661e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.450904429225332848e+01,3.393015454454337601e+02,9.398572028168701298e-01,4.000000039686759656e+00,-3.073938911114255657e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.451154429222852116e+01,3.393110766989435660e+02,9.368314456336410689e-01,4.000000039686759656e+00,-3.068938911114255652e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.451404429220371384e+01,3.393206094641404889e+02,9.338104544551879549e-01,4.000000039686759656e+00,-3.063938911114255648e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.451654429217890652e+01,3.393301437386413681e+02,9.307942300367585409e-01,4.000000039686759656e+00,-3.058938911114255643e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.451904429215409920e+01,3.393396795200625888e+02,9.277827731324089777e-01,4.000000039686759656e+00,-3.053938911114255639e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.452154429212929188e+01,3.393492168060202516e+02,9.247760844950034809e-01,4.000000039686759656e+00,-3.048938911114255634e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.452404429210448455e+01,3.393587555941300025e+02,9.217741648762142193e-01,4.000000039686759656e+00,-3.043938911114255630e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.452654429207967723e+01,3.393682958820071462e+02,9.187770150265209823e-01,4.000000039686759656e+00,-3.038938911114255625e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.452904429205486991e+01,3.393778376672665900e+02,9.157846356952112910e-01,4.000000039686759656e+00,-3.033938911114255621e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.453154429203006259e+01,3.393873809475228995e+02,9.127970276303799535e-01,4.000000039686759656e+00,-3.028938911114255617e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.453404429200525527e+01,3.393969257203902998e+02,9.098141915789289547e-01,4.000000039686759656e+00,-3.023938911114255612e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.453654429198044795e+01,3.394064719834825610e+02,9.068361282865673445e-01,4.000000039686759656e+00,-3.018938911114255608e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.453904429195564063e+01,3.394160197344131120e+02,9.038628384978109054e-01,4.000000039686759656e+00,-3.013938911114255603e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.454154429193083331e+01,3.394255689707950410e+02,9.008943229559820409e-01,4.000000039686759656e+00,-3.008938911114255599e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.454404429190602599e+01,3.394351196902410379e+02,8.979305824032095540e-01,4.000000039686759656e+00,-3.003938911114255594e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.454654429188121867e+01,3.394446718903633951e+02,8.949716175804286467e-01,4.000000039686759656e+00,-2.998938911114255590e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.454904429185641135e+01,3.394542255687740635e+02,8.920174292273805872e-01,4.000000039686759656e+00,-2.993938911114255585e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.455154429183160403e+01,3.394637807230846533e+02,8.890680180826123769e-01,4.000000039686759656e+00,-2.988938911114255581e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.455404429180679671e+01,3.394733373509063767e+02,8.861233848834767501e-01,4.000000039686759656e+00,-2.983938911114255577e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.455654429178198939e+01,3.394828954498500480e+02,8.831835303661320635e-01,4.000000039686759656e+00,-2.978938911114255572e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.455904429175718207e+01,3.394924550175261402e+02,8.802484552655418515e-01,4.000000039686759656e+00,-2.973938911114255568e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.456154429173237475e+01,3.395020160515447856e+02,8.773181603154749375e-01,4.000000039686759656e+00,-2.968938911114255563e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.456404429170756742e+01,3.395115785495157184e+02,8.743926462485049900e-01,4.000000039686759656e+00,-2.963938911114255559e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.456654429168276010e+01,3.395211425090483317e+02,8.714719137960105222e-01,4.000000039686759656e+00,-2.958938911114255554e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.456904429165795278e+01,3.395307079277515641e+02,8.685559636881746703e-01,4.000000039686759656e+00,-2.953938911114255550e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.457154429163314546e+01,3.395402748032341265e+02,8.656447966539848604e-01,4.000000039686759656e+00,-2.948938911114255546e-01,0.000000000000000000e+00,1.361524071352429588e-01,0.000000000000000000e+00,0.000000000000000000e+00 +5.457404429160833814e+01,3.395498431331042752e+02,8.627384134212329192e-01,4.000000039686759656e+00,-2.943938911114255541e-01,0.000000000000000000e+00,1.361524071352429588e-01,-1.278976949747405430e-09,0.000000000000000000e+00 +5.457654429158353082e+01,3.395594129149699825e+02,8.598368147165146302e-01,4.000000039686759656e+00,-2.938938911114255537e-01,-3.197442342644482093e-12,1.361524071352429588e-01,4.954884601016413940e-05,0.000000000000000000e+00 +5.457904429155872350e+01,3.395689841464387086e+02,8.569400012652296228e-01,4.000000039686751663e+00,-2.933938911114255532e-01,1.238689163540469824e-07,1.361524071352429588e-01,-6.168131206813017853e-01,0.000000000000000000e+00 +5.458154429153391618e+01,3.395785568251177438e+02,8.540479737915812608e-01,4.000000039996423951e+00,-2.928938911114255528e-01,-1.541908917487332456e-03,1.361524071352429588e-01,-9.999994315022114888e-01,0.000000000000000000e+00 +5.458404429150891701e+01,3.395881309486138662e+02,8.511607330185764209e-01,3.999996185224168777e+00,-2.923938911114255523e-01,-4.041907471245110607e-03,1.361524071352429588e-01,-9.999997190552153414e-01,0.000000000000000000e+00 +5.458654429389315510e+01,3.395977065145335132e+02,8.482782796680252702e-01,3.999986080445853798e+00,-2.918938911114255519e-01,-6.541909153119647435e-03,1.361524071352429588e-01,-9.999998149961043525e-01,0.000000000000000000e+00 +5.458904430259291019e+01,3.396072835204828380e+02,8.454006144605411555e-01,3.999969725616058014e+00,-2.913938911114255514e-01,-9.041917390359914541e-03,1.361524071352429588e-01,-9.999998628074915352e-01,0.000000000000000000e+00 +5.459154432151454017e+01,3.396168619640675956e+02,8.425277381155402701e-01,3.999947120651494270e+00,-2.908938911114255510e-01,-1.154193596900922152e-02,1.361524071352429588e-01,-9.999998915465478921e-01,0.000000000000000000e+00 +5.459404435456456639e+01,3.396264418428931435e+02,8.396596513512417648e-01,3.999918265430110420e+00,-2.903938911114255506e-01,-1.404196874790173896e-02,1.361524071352429588e-01,-9.999999107729347081e-01,0.000000000000000000e+00 +5.459654440564971623e+01,3.396360231545645547e+02,8.367963548846673039e-01,3.999883159790904585e+00,-2.898938911114255501e-01,-1.654201960997955453e-02,1.361524071352429588e-01,-9.999999243331754162e-01,0.000000000000000000e+00 +5.459904447867697996e+01,3.396456058966864475e+02,8.339378494316409540e-01,3.999841803533861206e+00,-2.893938911114255497e-01,-1.904209244807078191e-02,1.361524071352429588e-01,-9.999999346948423851e-01,0.000000000000000000e+00 +5.460154457755368185e+01,3.396551900668631561e+02,8.310841357067891844e-01,3.999794196419921732e+00,-2.888938911114255492e-01,-2.154219116150325394e-02,1.361524071352429588e-01,-9.999999426623119581e-01,0.000000000000000000e+00 +5.460404470618753692e+01,3.396647756626986734e+02,8.282352144235403113e-01,3.999740338170962861e+00,-2.883938911114255488e-01,-2.404231965200753426e-02,1.361524071352429588e-01,-9.999999489398457841e-01,0.000000000000000000e+00 +5.460654486848671496e+01,3.396743626817965946e+02,8.253910862941246096e-01,3.999680228469784105e+00,-2.878938911114255483e-01,-2.654248182352773530e-02,1.361524071352429588e-01,-9.999999542025018728e-01,0.000000000000000000e+00 +5.460904506835989736e+01,3.396839511217601171e+02,8.225517520295740903e-01,3.999613866960094910e+00,-2.873938911114255479e-01,-2.904268158220965970e-02,1.361524071352429588e-01,-9.999999585277293823e-01,0.000000000000000000e+00 +5.461154530971634813e+01,3.396935409801921537e+02,8.197172123397223897e-01,3.999541253246500894e+00,-2.868938911114255474e-01,-3.154292283496783894e-02,1.361524071352429588e-01,-9.999999621767434732e-01,0.000000000000000000e+00 +5.461404559646595658e+01,3.397031322546952765e+02,8.168874679332044364e-01,3.999462386894492738e+00,-2.863938911114255470e-01,-3.404320949000615160e-02,1.361524071352429588e-01,-9.999999653812748912e-01,0.000000000000000000e+00 +5.461654593251931544e+01,3.397127249428716027e+02,8.140625195174562290e-01,3.999377267430432870e+00,-2.858938911114255466e-01,-3.654354545680531946e-02,1.361524071352429588e-01,-9.999999680592946971e-01,0.000000000000000000e+00 +5.461904632178777064e+01,3.397223190423230221e+02,8.112423677987148363e-01,3.999285894341541248e+00,-2.853938911114255461e-01,-3.904393464539963887e-02,1.361524071352429588e-01,-9.999999704542362755e-01,0.000000000000000000e+00 +5.462154676818349941e+01,3.397319145506509699e+02,8.084270134820182863e-01,3.999188267075882042e+00,-2.848938911114255457e-01,-4.154438096725200646e-02,1.361524071352429588e-01,-9.999999724244771349e-01,0.000000000000000000e+00 +5.462404727561955298e+01,3.397415114654565400e+02,8.056164572712050109e-01,3.999084385042347201e+00,-2.843938911114255452e-01,-4.404488833435241807e-02,1.361524071352429588e-01,-9.999999744376035782e-01,0.000000000000000000e+00 +5.462654784800992047e+01,3.397511097843405423e+02,8.028106998689141793e-01,3.998974247610641353e+00,-2.838938911114255448e-01,-4.654546066080262473e-02,1.361524071352429588e-01,-9.999999760786675296e-01,0.000000000000000000e+00 +5.462904848926960710e+01,3.397607095049034456e+02,8.000097419765850315e-01,3.998857854111261823e+00,-2.833938911114255443e-01,-4.904610186067071692e-02,1.361524071352429588e-01,-9.999999774705830013e-01,0.000000000000000000e+00 +5.463154920331467679e+01,3.397703106247452638e+02,7.972135842944571005e-01,3.998735203835483087e+00,-2.828938911114255439e-01,-5.154681584939745792e-02,1.361524071352429588e-01,-9.999999789186845289e-01,0.000000000000000000e+00 +5.463404999406231610e+01,3.397799131414657268e+02,7.944222275215696571e-01,3.998606296035336793e+00,-2.823938911114255434e-01,-5.404760654431396694e-02,1.361524071352429588e-01,-9.999999800583946330e-01,0.000000000000000000e+00 +5.463655086543089823e+01,3.397895170526641664e+02,7.916356723557620434e-01,3.998471129923589551e+00,-2.818938911114255430e-01,-5.654847786302795443e-02,1.361524071352429588e-01,-9.999999812042976721e-01,0.000000000000000000e+00 +5.463905182134006111e+01,3.397991223559396872e+02,7.888539194936728949e-01,3.998329704673723839e+00,-2.813938911114255426e-01,-5.904943372518371703e-02,1.361524071352429588e-01,-9.999999822136871330e-01,0.000000000000000000e+00 +5.464155286571074299e+01,3.398087290488908820e+02,7.860769696307405852e-01,3.998182019419913580e+00,-2.808938911114255421e-01,-6.155047805138014888e-02,1.361524071352429588e-01,-9.999999831964326846e-01,0.000000000000000000e+00 +5.464405400246525346e+01,3.398183371291161166e+02,7.833048234612024485e-01,3.998028073257001491e+00,-2.803938911114255417e-01,-6.405161476386408981e-02,1.361524071352429588e-01,-9.999999840177364874e-01,0.000000000000000000e+00 +5.464655523552734451e+01,3.398279465942133584e+02,7.805374816780950020e-01,3.997867865240473773e+00,-2.798938911114255412e-01,-6.655284778598012652e-02,1.361524071352429588e-01,-9.999999847948545240e-01,0.000000000000000000e+00 +5.464905656882226026e+01,3.398375574417802909e+02,7.777749449732537235e-01,3.997701394386435236e+00,-2.793938911114255408e-01,-6.905418104286280279e-02,1.361524071352429588e-01,-9.999999855417837091e-01,0.000000000000000000e+00 +5.465155800627680094e+01,3.398471696694141428e+02,7.750172140373127183e-01,3.997528659671581774e+00,-2.788938911114255403e-01,-7.155561846124022796e-02,1.361524071352429588e-01,-9.999999861691210024e-01,0.000000000000000000e+00 +5.465405955181939390e+01,3.398567832747118587e+02,7.722642895597047197e-01,3.997349660033172380e+00,-2.783938911114255399e-01,-7.405716396923735234e-02,1.361524071352429588e-01,-9.999999869804687691e-01,0.000000000000000000e+00 +5.465656120938015050e+01,3.398663982552700986e+02,7.695161722286608663e-01,3.997164394369000728e+00,-2.778938911114255395e-01,-7.655882149742108955e-02,1.361524071352429588e-01,-9.999999873948216544e-01,0.000000000000000000e+00 +5.465906298289091581e+01,3.398760146086850682e+02,7.667728627312104805e-01,3.996972861537363197e+00,-2.773938911114255390e-01,-7.906059497664943980e-02,1.361524071352429588e-01,-9.999999880041542388e-01,0.000000000000000000e+00 +5.466156487628534677e+01,3.398856323325526887e+02,7.640343617531809572e-01,3.996775060357031339e+00,-2.768938911114255386e-01,-8.156248834106803736e-02,1.361524071352429588e-01,-9.999999885151734658e-01,0.000000000000000000e+00 +5.466406689349896908e+01,3.398952514244684835e+02,7.613006699791974308e-01,3.996570989607215907e+00,-2.763938911114255381e-01,-8.406450552595770565e-02,1.361524071352429588e-01,-9.999999890263492341e-01,0.000000000000000000e+00 +5.466656903846924820e+01,3.399048718820277486e+02,7.585717880926828860e-01,3.996360648027535323e+00,-2.758938911114255377e-01,-8.656665046877687342e-02,1.361524071352429588e-01,-9.999999894598781136e-01,0.000000000000000000e+00 +5.466907131513563201e+01,3.399144937028253253e+02,7.558477167758578252e-01,3.996144034317980598e+00,-2.753938911114255372e-01,-8.906892710878293318e-02,1.361524071352429588e-01,-9.999999899160064709e-01,0.000000000000000000e+00 +5.467157372743962185e+01,3.399241168844557706e+02,7.531284567097399352e-01,3.995921147138880247e+00,-2.748938911114255368e-01,-9.157133938754023761e-02,1.361524071352429588e-01,-9.999999903180601946e-01,0.000000000000000000e+00 +5.467407627932485070e+01,3.399337414245133004e+02,7.504140085741443089e-01,3.995691985110862987e+00,-2.743938911114255363e-01,-9.407389124853997309e-02,1.361524071352429588e-01,-9.999999906248618897e-01,0.000000000000000000e+00 +5.467657897473712580e+01,3.399433673205917898e+02,7.477043730476830019e-01,3.995456546814820431e+00,-2.738938911114255359e-01,-9.657658663735162186e-02,1.361524071352429588e-01,-9.999999910429341332e-01,0.000000000000000000e+00 +5.467908181762449971e+01,3.399529945702847158e+02,7.449995508077648099e-01,3.995214830791868454e+00,-2.733938911114255355e-01,-9.907942950230565204e-02,1.361524071352429588e-01,-9.999999913172132882e-01,0.000000000000000000e+00 +5.468158481193732712e+01,3.399626231711853279e+02,7.422995425305952688e-01,3.994966835543305894e+00,-2.728938911114255350e-01,-1.015824237934011554e-01,1.361524071352429588e-01,-9.999999917230779634e-01,0.000000000000000000e+00 +5.468408796162834307e+01,3.399722531208864211e+02,7.396043488911764330e-01,3.994712559530575025e+00,-2.723938911114255346e-01,-1.040855734636964292e-01,1.361524071352429588e-01,-9.999999920026285682e-01,0.000000000000000000e+00 +5.468659127065270553e+01,3.399818844169805629e+02,7.369139705633067639e-01,3.994452001175217593e+00,-2.718938911114255341e-01,-1.065888824680372576e-01,1.361524071352429588e-01,-9.999999922857982781e-01,0.000000000000000000e+00 +5.468909474296807360e+01,3.399915170570599230e+02,7.342284082195807970e-01,3.994185158858833073e+00,-2.713938911114255337e-01,-1.090923547640908486e-01,1.361524071352429588e-01,-9.999999925935760814e-01,0.000000000000000000e+00 +5.469159838253466432e+01,3.400011510387162730e+02,7.315476625313891423e-01,3.993912030923033374e+00,-2.708938911114255332e-01,-1.115959943121364456e-01,1.361524071352429588e-01,-9.999999927669394051e-01,0.000000000000000000e+00 +5.469410219331531664e+01,3.400107863595411573e+02,7.288717341689181506e-01,3.993632615669397090e+00,-2.703938911114255328e-01,-1.140998050746780262e-01,1.361524071352429588e-01,-9.999999930330262243e-01,0.000000000000000000e+00 +5.469660617927555535e+01,3.400204230171257791e+02,7.262006238011499137e-01,3.993346911359423768e+00,-2.698938911114255323e-01,-1.166037910174746450e-01,1.361524071352429588e-01,-9.999999932962060356e-01,0.000000000000000000e+00 +5.469911034438366215e+01,3.400300610090609439e+02,7.235343320958620428e-01,3.993054916214484606e+00,-2.693938911114255319e-01,-1.191079561087959593e-01,1.361524071352429588e-01,-9.999999934919293620e-01,0.000000000000000000e+00 +5.470161469261072540e+01,3.400397003329371728e+02,7.208728597196273347e-01,3.992756628415774056e+00,-2.688938911114255315e-01,-1.216123043195637549e-01,1.361524071352429588e-01,-9.999999937277169737e-01,0.000000000000000000e+00 +5.470411922793071824e+01,3.400493409863445891e+02,7.182162073378139944e-01,3.992452046104260077e+00,-2.683938911114255310e-01,-1.241168396238467309e-01,1.361524071352429588e-01,-9.999999938577880387e-01,0.000000000000000000e+00 +5.470662395432054836e+01,3.400589829668730886e+02,7.155643756145850798e-01,3.992141167380632183e+00,-2.678938911114255306e-01,-1.266215659982901365e-01,1.361524071352429588e-01,-9.999999941905844958e-01,0.000000000000000000e+00 +5.470912887576012906e+01,3.400686262721121125e+02,7.129173652128985017e-01,3.991823990305249925e+00,-2.673938911114255301e-01,-1.291264874233175874e-01,1.361524071352429588e-01,-9.999999942139667919e-01,0.000000000000000000e+00 +5.471163399623244317e+01,3.400782708996508745e+02,7.102751767945068018e-01,3.991500512898087383e+00,-2.668938911114255297e-01,-1.316316078811399226e-01,1.361524071352429588e-01,-9.999999945057429507e-01,0.000000000000000000e+00 +5.471413931972362121e+01,3.400879168470782474e+02,7.076378110199571525e-01,3.991170733138681648e+00,-2.663938911114255292e-01,-1.341369313585498713e-01,1.361524071352429588e-01,-9.999999946099760173e-01,0.000000000000000000e+00 +5.471664485022296986e+01,3.400975641119827060e+02,7.050052685485909132e-01,3.990834648966073317e+00,-2.658938911114255288e-01,-1.366424618443969896e-01,1.361524071352429588e-01,-9.999999947347160134e-01,0.000000000000000000e+00 +5.471915059172308560e+01,3.401072126919524408e+02,7.023775500385437409e-01,3.990492258278752313e+00,-2.653938911114255284e-01,-1.391482033313157507e-01,1.361524071352429588e-01,-9.999999949022586598e-01,0.000000000000000000e+00 +5.472165654821986891e+01,3.401168625845753013e+02,6.997546561467451465e-01,3.990143558934598378e+00,-2.648938911114255279e-01,-1.416541598153250592e-01,1.361524071352429588e-01,-9.999999950901029555e-01,0.000000000000000000e+00 +5.472416272371263091e+01,3.401265137874387960e+02,6.971365875289187164e-01,3.989788548750821562e+00,-2.643938911114255275e-01,-1.441603352957809836e-01,1.361524071352429588e-01,-9.999999952304443607e-01,0.000000000000000000e+00 +5.472666912220413593e+01,3.401361662981301492e+02,6.945233448395815579e-01,3.989427225503901830e+00,-2.638938911114255270e-01,-1.466667337753283229e-01,1.361524071352429588e-01,-9.999999952801826852e-01,0.000000000000000000e+00 +5.472917574770066551e+01,3.401458201142362441e+02,6.919149287320442987e-01,3.989059586929527779e+00,-2.633938911114255266e-01,-1.491733592600277547e-01,1.361524071352429588e-01,-9.999999954322760232e-01,0.000000000000000000e+00 +5.473168260421210363e+01,3.401554752333435658e+02,6.893113398584109763e-01,3.988685630722534015e+00,-2.628938911114255261e-01,-1.516802157600130041e-01,1.361524071352429588e-01,-9.999999955496714499e-01,0.000000000000000000e+00 +5.473418969575197934e+01,3.401651316530384292e+02,6.867125788695787048e-01,3.988305354536835878e+00,-2.623938911114255257e-01,-1.541873072887292584e-01,1.361524071352429588e-01,-9.999999956594151085e-01,0.000000000000000000e+00 +5.473669702633754497e+01,3.401747893709066375e+02,6.841186464152377855e-01,3.987918755985365049e+00,-2.618938911114255252e-01,-1.566946378634102577e-01,1.361524071352429588e-01,-9.999999958105306730e-01,0.000000000000000000e+00 +5.473920459998984001e+01,3.401844483845338232e+02,6.815295431438713747e-01,3.987525832640002932e+00,-2.613938911114255248e-01,-1.592022115051993647e-01,1.361524071352429588e-01,-9.999999958615197748e-01,0.000000000000000000e+00 +5.474171242073375510e+01,3.401941086915052210e+02,6.789452697027552608e-01,3.987126582031512712e+00,-2.608938911114255244e-01,-1.617100322387379219e-01,1.361524071352429588e-01,-9.999999959034819863e-01,0.000000000000000000e+00 +5.474422049259810308e+01,3.402037702894057247e+02,6.763658267379577538e-01,3.986721001649471408e+00,-2.603938911114255239e-01,-1.642181040928147595e-01,1.361524071352429588e-01,-9.999999960471862570e-01,0.000000000000000000e+00 +5.474672881961568294e+01,3.402134331758200005e+02,6.737912148943395740e-01,3.986309088942199264e+00,-2.598938911114255235e-01,-1.667264311004820754e-01,1.361524071352429588e-01,-9.999999961403738258e-01,0.000000000000000000e+00 +5.474923740582334375e+01,3.402230973483322600e+02,6.712214348155536303e-01,3.985890841316687805e+00,-2.593938911114255230e-01,-1.692350172984623535e-01,1.361524071352429588e-01,-9.999999961903425216e-01,0.000000000000000000e+00 +5.475174625526205574e+01,3.402327628045264873e+02,6.686564871440450197e-01,3.985466256138528340e+00,-2.588938911114255226e-01,-1.717438667276153241e-01,1.361524071352429588e-01,-9.999999962926077179e-01,0.000000000000000000e+00 +5.475425537197696713e+01,3.402424295419863256e+02,6.660963725210505837e-01,3.985035330731838243e+00,-2.583938911114255221e-01,-1.742529834332263161e-01,1.361524071352429588e-01,-9.999999963479238030e-01,0.000000000000000000e+00 +5.475676476001748938e+01,3.402520975582950769e+02,6.635410915865990189e-01,3.984598062379185457e+00,-2.578938911114255217e-01,-1.767623714645848165e-01,1.361524071352429588e-01,-9.999999963437765649e-01,0.000000000000000000e+00 +5.475927442343734697e+01,3.402617668510357021e+02,6.609906449795105443e-01,3.984154448321512998e+00,-2.573938911114255212e-01,-1.792720348752694093e-01,1.361524071352429588e-01,-9.999999965648420641e-01,0.000000000000000000e+00 +5.476178436629466262e+01,3.402714374177909349e+02,6.584450333373967901e-01,3.983704485758061686e+00,-2.568938911114255208e-01,-1.817819777239612633e-01,1.361524071352429588e-01,-9.999999964644494810e-01,0.000000000000000000e+00 +5.476429459265199995e+01,3.402811092561431110e+02,6.559042572966605755e-01,3.983248171846289765e+00,-2.563938911114255204e-01,-1.842922040724253585e-01,1.361524071352429588e-01,-9.999999965668578961e-01,0.000000000000000000e+00 +5.476680510657646295e+01,3.402907823636742819e+02,6.533683174924959092e-01,3.982785503701796515e+00,-2.558938911114255199e-01,-1.868027179882664202e-01,1.361524071352429588e-01,-9.999999966338442015e-01,0.000000000000000000e+00 +5.476931591213973149e+01,3.403004567379661580e+02,6.508372145588878777e-01,3.982316478398237880e+00,-2.553938911114255195e-01,-1.893135235430832564e-01,1.361524071352429588e-01,-9.999999967211333773e-01,0.000000000000000000e+00 +5.477182701341815374e+01,3.403101323766001656e+02,6.483109491286120907e-01,3.981841092967245643e+00,-2.548938911114255190e-01,-1.918246248132750020e-01,1.361524071352429588e-01,-9.999999966841711663e-01,0.000000000000000000e+00 +5.477433841449281005e+01,3.403198092771573897e+02,6.457895218332349030e-01,3.981359344398343492e+00,-2.543938911114255186e-01,-1.943360258796067996e-01,1.361524071352429588e-01,-9.999999966704345988e-01,0.000000000000000000e+00 +5.477685011944957694e+01,3.403294874372185745e+02,6.432729333031130814e-01,3.980871229638863085e+00,-2.538938911114255181e-01,-1.968477308280119353e-01,1.361524071352429588e-01,-9.999999968365113068e-01,0.000000000000000000e+00 +5.477936213237919816e+01,3.403391668543642368e+02,6.407611841673938047e-01,3.980376745593857013e+00,-2.533938911114255177e-01,-1.993597437496839320e-01,1.361524071352429588e-01,-9.999999968547419460e-01,0.000000000000000000e+00 +5.478187445737734862e+01,3.403488475261744384e+02,6.382542750540143306e-01,3.979875889126010424e+00,-2.528938911114255172e-01,-2.018720687399294111e-01,1.361524071352429588e-01,-9.999999967570875059e-01,0.000000000000000000e+00 +5.478438709854470545e+01,3.403585294502290708e+02,6.357522065897018848e-01,3.979368657055554426e+00,-2.523938911114255168e-01,-2.043847098991407596e-01,1.361524071352429588e-01,-9.999999968632342640e-01,0.000000000000000000e+00 +5.478690005998703327e+01,3.403682126241076276e+02,6.332549793999736609e-01,3.978855046160175934e+00,-2.518938911114255164e-01,-2.068976713335889117e-01,1.361524071352429588e-01,-9.999999969357155072e-01,0.000000000000000000e+00 +5.478941334581524103e+01,3.403778970453893749e+02,6.307625941091363764e-01,3.978335053174924418e+00,-2.513938911114255159e-01,-2.094109571540934134e-01,1.361524071352429588e-01,-9.999999968123142180e-01,0.000000000000000000e+00 +5.479192696014543884e+01,3.403875827116531241e+02,6.282750513402862724e-01,3.977808674792120858e+00,-2.508938911114255155e-01,-2.119245714762814370e-01,1.361524071352429588e-01,-9.999999969669974842e-01,0.000000000000000000e+00 +5.479444090709903747e+01,3.403972696204775161e+02,6.257923517153091142e-01,3.977275907661264931e+00,-2.503938911114255150e-01,-2.144385184222573071e-01,1.361524071352429588e-01,-9.999999968221714441e-01,0.000000000000000000e+00 +5.479695519080279809e+01,3.404069577694407940e+02,6.233144958548798575e-01,3.976736748388936871e+00,-2.498938911114255146e-01,-2.169528021180298638e-01,1.361524071352429588e-01,-9.999999969964239455e-01,0.000000000000000000e+00 +5.479946981538891038e+01,3.404166471561209732e+02,6.208414843784623161e-01,3.976191193538704649e+00,-2.493938911114255141e-01,-2.194674266965905285e-01,1.361524071352429588e-01,-9.999999969147739254e-01,0.000000000000000000e+00 +5.480198478499506365e+01,3.404263377780956148e+02,6.183733179043094941e-01,3.975639239631022281e+00,-2.488938911114255137e-01,-2.219823962949835083e-01,1.361524071352429588e-01,-9.999999968447687015e-01,0.000000000000000000e+00 +5.480450010376451075e+01,3.404360296329421658e+02,6.159099970494629206e-01,3.975080883143134347e+00,-2.483938911114255133e-01,-2.244977150564956281e-01,1.361524071352429588e-01,-9.999999969819642898e-01,0.000000000000000000e+00 +5.480701577584615336e+01,3.404457227182375618e+02,6.134515224297527602e-01,3.974516120508973849e+00,-2.478938911114255128e-01,-2.270133871305472506e-01,1.361524071352429588e-01,-9.999999968878243717e-01,0.000000000000000000e+00 +5.480953180539460590e+01,3.404554170315586248e+02,6.109978946597977023e-01,3.973944948119059184e+00,-2.473938911114255124e-01,-2.295294166711690786e-01,1.361524071352429588e-01,-9.999999968922673732e-01,0.000000000000000000e+00 +5.481204819657026661e+01,3.404651125704817218e+02,6.085491143530046276e-01,3.973367362320393781e+00,-2.468938911114255119e-01,-2.320458078390074397e-01,1.361524071352429588e-01,-9.999999968292435648e-01,0.000000000000000000e+00 +5.481456495353938863e+01,3.404748093325829927e+02,6.061051821215687196e-01,3.972783359416359517e+00,-2.463938911114255115e-01,-2.345625648001489760e-01,1.361524071352429588e-01,-9.999999969476239814e-01,0.000000000000000000e+00 +5.481708208047415809e+01,3.404845073154381794e+02,6.036660985764729093e-01,3.972192935666611913e+00,-2.458938911114255110e-01,-2.370796917272375293e-01,1.361524071352429588e-01,-9.999999967884365404e-01,0.000000000000000000e+00 +5.481959958155277235e+01,3.404942065166228531e+02,6.012318643274880969e-01,3.971596087286971333e+00,-2.453938911114255106e-01,-2.395971927977655069e-01,1.361524071352429588e-01,-9.999999967957230451e-01,0.000000000000000000e+00 +5.482211746095949678e+01,3.405039069337121873e+02,5.988024799831728195e-01,3.970992810449317290e+00,-2.448938911114255101e-01,-2.421150721964201447e-01,1.361524071352429588e-01,-9.999999967735360151e-01,0.000000000000000000e+00 +5.482463572288475007e+01,3.405136085642811281e+02,5.963779461508731394e-01,3.970383101281475646e+00,-2.443938911114255097e-01,-2.446333341135460693e-01,1.361524071352429588e-01,-9.999999967257364730e-01,0.000000000000000000e+00 +5.482715437152517524e+01,3.405233114059042236e+02,5.939582634367225333e-01,3.969766955867108482e+00,-2.438938911114255093e-01,-2.471519827457220875e-01,1.361524071352429588e-01,-9.999999967845715210e-01,0.000000000000000000e+00 +5.482967341108371073e+01,3.405330154561557947e+02,5.915434324456416704e-01,3.969144370245601294e+00,-2.433938911114255088e-01,-2.496710222961587289e-01,1.361524071352429588e-01,-9.999999965795146606e-01,0.000000000000000000e+00 +5.483219284576967567e+01,3.405427207126097642e+02,5.891334537813383010e-01,3.968515340411947978e+00,-2.428938911114255084e-01,-2.521904569735061719e-01,1.361524071352429588e-01,-9.999999967057343619e-01,0.000000000000000000e+00 +5.483471267979883379e+01,3.405524271728398844e+02,5.867283280463070350e-01,3.967879862316637585e+00,-2.423938911114255079e-01,-2.547102909943617655e-01,1.361524071352429588e-01,-9.999999965536097157e-01,0.000000000000000000e+00 +5.483723291739346450e+01,3.405621348344195098e+02,5.843280558418293413e-01,3.967237931865533529e+00,-2.418938911114255075e-01,-2.572305285803096475e-01,1.361524071352429588e-01,-9.999999964764746396e-01,0.000000000000000000e+00 +5.483975356278245528e+01,3.405718436949217107e+02,5.819326377679732154e-01,3.966589544919759014e+00,-2.413938911114255070e-01,-2.597511739604223546e-01,1.361524071352429588e-01,-9.999999965296613169e-01,0.000000000000000000e+00 +5.484227462020136556e+01,3.405815537519193299e+02,5.795420744235931787e-01,3.965934697295574907e+00,-2.408938911114255066e-01,-2.622722313705857511e-01,1.361524071352429588e-01,-9.999999963304863071e-01,0.000000000000000000e+00 +5.484479609389250498e+01,3.405912650029848123e+02,5.771563664063300569e-01,3.965273384764258058e+00,-2.403938911114255061e-01,-2.647937050524706293e-01,1.361524071352429588e-01,-9.999999964538113240e-01,0.000000000000000000e+00 +5.484731798810499726e+01,3.406009774456903187e+02,5.747755143126108690e-01,3.964605603051980953e+00,-2.398938911114255057e-01,-2.673155992560231620e-01,1.361524071352429588e-01,-9.999999961955232664e-01,0.000000000000000000e+00 +5.484984030709488678e+01,3.406106910776077825e+02,5.723995187376486049e-01,3.963931347839683816e+00,-2.393938911114255053e-01,-2.698379182363164763e-01,1.361524071352429588e-01,-9.999999962250807339e-01,0.000000000000000000e+00 +5.485236305512518840e+01,3.406204058963087959e+02,5.700283802754421147e-01,3.963250614762953372e+00,-2.388938911114255048e-01,-2.723606662570915438e-01,1.361524071352429588e-01,-9.999999961401643267e-01,0.000000000000000000e+00 +5.485488623646596551e+01,3.406301218993646103e+02,5.676620995187759977e-01,3.962563399411891396e+00,-2.383938911114255044e-01,-2.748838475881312804e-01,1.361524071352429588e-01,-9.999999960014189782e-01,0.000000000000000000e+00 +5.485740985539442960e+01,3.406398390843462494e+02,5.653006770592204910e-01,3.961869697330988593e+00,-2.378938911114255039e-01,-2.774074665065057732e-01,1.361524071352429588e-01,-9.999999959815779604e-01,0.000000000000000000e+00 +5.485993391619499704e+01,3.406495574488244529e+02,5.629441134871311370e-01,3.961169504018994036e+00,-2.373938911114255035e-01,-2.799315272969332136e-01,1.361524071352429588e-01,-9.999999958064216266e-01,0.000000000000000000e+00 +5.486245842315938148e+01,3.406592769903695626e+02,5.605924093916488937e-01,3.960462814928782382e+00,-2.368938911114255030e-01,-2.824560342507301258e-01,1.361524071352429588e-01,-9.999999957991264621e-01,0.000000000000000000e+00 +5.486498338058665780e+01,3.406689977065517496e+02,5.582455653606996915e-01,3.959749625467222423e+00,-2.363938911114255026e-01,-2.849809916673978760e-01,1.361524071352429588e-01,-9.999999956936937995e-01,0.000000000000000000e+00 +5.486750879278334736e+01,3.406787195949407874e+02,5.559035819809945433e-01,3.959029930995040303e+00,-2.358938911114255021e-01,-2.875064038532142985e-01,1.361524071352429588e-01,-9.999999955398483076e-01,0.000000000000000000e+00 +5.487003466406351038e+01,3.406884426531062218e+02,5.535664598380293233e-01,3.958303726826684965e+00,-2.353938911114255017e-01,-2.900322751221099948e-01,1.361524071352429588e-01,-9.999999953525809948e-01,0.000000000000000000e+00 +5.487256099874880277e+01,3.406981668786173145e+02,5.512341995160845443e-01,3.957571008230190035e+00,-2.348938911114255013e-01,-2.925586097956603404e-01,1.361524071352429588e-01,-9.999999953893721205e-01,0.000000000000000000e+00 +5.487508780116856855e+01,3.407078922690429863e+02,5.489068015982252469e-01,3.956831770427034378e+00,-2.343938911114255008e-01,-2.950854122037782634e-01,1.361524071352429588e-01,-9.999999951744273918e-01,0.000000000000000000e+00 +5.487761507565992503e+01,3.407176188219519304e+02,5.465842666663008886e-01,3.956086008591999548e+00,-2.338938911114255004e-01,-2.976126866829419404e-01,1.361524071352429588e-01,-9.999999950279656602e-01,0.000000000000000000e+00 +5.488014282656784104e+01,3.407273465349124422e+02,5.442665953009452329e-01,3.955333717853030340e+00,-2.333938911114254999e-01,-3.001404375782867895e-01,1.361524071352429588e-01,-9.999999948816031825e-01,0.000000000000000000e+00 +5.488267105824520087e+01,3.407370754054926465e+02,5.419537880815761266e-01,3.954574893291088689e+00,-2.328938911114254995e-01,-3.026686692427047465e-01,1.361524071352429588e-01,-9.999999947639341968e-01,0.000000000000000000e+00 +5.488519977505291081e+01,3.407468054312602703e+02,5.396458455863952786e-01,3.953809529940008449e+00,-2.323938911114254990e-01,-3.051973860371708924e-01,1.361524071352429588e-01,-9.999999946599064105e-01,0.000000000000000000e+00 +5.488772898135996314e+01,3.407565366097828701e+02,5.373427683923883702e-01,3.953037622786347960e+00,-2.318938911114254986e-01,-3.077265923307150319e-01,1.361524071352429588e-01,-9.999999943702468919e-01,0.000000000000000000e+00 +5.489025868154352850e+01,3.407662689386276043e+02,5.350445570753247226e-01,3.952259166769241272e+00,-2.313938911114254982e-01,-3.102562925000379446e-01,1.361524071352429588e-01,-9.999999942736191860e-01,0.000000000000000000e+00 +5.489278887998903400e+01,3.407760024153614040e+02,5.327512122097570746e-01,3.951474156780248936e+00,-2.308938911114254977e-01,-3.127864909310559827e-01,1.361524071352429588e-01,-9.999999940751800320e-01,0.000000000000000000e+00 +5.489531958109025567e+01,3.407857370375509163e+02,5.304627343690215824e-01,3.950682587663203460e+00,-2.303938911114254973e-01,-3.153171920172804787e-01,1.361524071352429588e-01,-9.999999939156599682e-01,0.000000000000000000e+00 +5.489785078924938233e+01,3.407954728027624469e+02,5.281791241252378200e-01,3.949884454214057428e+00,-2.298938911114254968e-01,-3.178484001610031862e-01,1.361524071352429588e-01,-9.999999936757275609e-01,0.000000000000000000e+00 +5.490038250887711513e+01,3.408052097085621313e+02,5.259003820493082237e-01,3.949079751180727182e+00,-2.293938911114254964e-01,-3.203801197727220718e-01,1.361524071352429588e-01,-9.999999933904102356e-01,0.000000000000000000e+00 +5.490291474439274566e+01,3.408149477525156499e+02,5.236265087109184257e-01,3.948268473262936507e+00,-2.288938911114254959e-01,-3.229123552716162693e-01,1.361524071352429588e-01,-9.999999933161020094e-01,0.000000000000000000e+00 +5.490544750022424836e+01,3.408246869321885697e+02,5.213575046785366984e-01,3.947450615112057637e+00,-2.283938911114254955e-01,-3.254451110861915630e-01,1.361524071352429588e-01,-9.999999930289173999e-01,0.000000000000000000e+00 +5.490798078080835865e+01,3.408344272451460597e+02,5.190933705194139547e-01,3.946626171330949173e+00,-2.278938911114254950e-01,-3.279783916526427534e-01,1.361524071352429588e-01,-9.999999926693484698e-01,0.000000000000000000e+00 +5.491051459059065820e+01,3.408441686889530047e+02,5.168341067995838589e-01,3.945795136473796649e+00,-2.273938911114254946e-01,-3.305122014163683897e-01,1.361524071352429588e-01,-9.999999925934391909e-01,0.000000000000000000e+00 +5.491304893402566734e+01,3.408539112611741189e+02,5.145797140838621608e-01,3.944957505045947777e+00,-2.268938911114254942e-01,-3.330465448326033751e-01,1.361524071352429588e-01,-9.999999921265947389e-01,0.000000000000000000e+00 +5.491558381557691604e+01,3.408636549593737186e+02,5.123301929358471396e-01,3.944113271503744578e+00,-2.263938911114254937e-01,-3.355814263638936534e-01,1.361524071352429588e-01,-9.999999919816915384e-01,0.000000000000000000e+00 +5.491811923971705056e+01,3.408733997811158929e+02,5.100855439179190487e-01,3.943262430254360407e+00,-2.258938911114254933e-01,-3.381168504836994937e-01,1.361524071352429588e-01,-9.999999915613512202e-01,0.000000000000000000e+00 +5.492065521092791158e+01,3.408831457239643896e+02,5.078457675912402269e-01,3.942404975655626309e+00,-2.253938911114254928e-01,-3.406528216731616321e-01,1.361524071352429588e-01,-9.999999913053938538e-01,0.000000000000000000e+00 +5.492319173370061947e+01,3.408928927854827862e+02,5.056108645157546544e-01,3.941540902015864045e+00,-2.248938911114254924e-01,-3.431893444238186541e-01,1.361524071352429588e-01,-9.999999908930773396e-01,0.000000000000000000e+00 +5.492572881253567374e+01,3.409026409632342620e+02,5.033808352501880634e-01,3.940670203593710674e+00,-2.243938911114254919e-01,-3.457264232357666334e-01,1.361524071352429588e-01,-9.999999906216825440e-01,0.000000000000000000e+00 +5.492826645194302415e+01,3.409123902547818261e+02,5.011556803520477166e-01,3.939792874597946248e+00,-2.238938911114254915e-01,-3.482640626193154731e-01,1.361524071352429588e-01,-9.999999901630653998e-01,0.000000000000000000e+00 +5.493080465644217014e+01,3.409221406576881463e+02,4.989354003776224622e-01,3.938908909187315732e+00,-2.233938911114254910e-01,-3.508022670934913267e-01,1.361524071352429588e-01,-9.999999897336134813e-01,0.000000000000000000e+00 +5.493334343056225322e+01,3.409318921695156064e+02,4.967199958819821792e-01,3.938018301470353144e+00,-2.228938911114254906e-01,-3.533410411875079760e-01,1.361524071352429588e-01,-9.999999893339502899e-01,0.000000000000000000e+00 +5.493588277884214222e+01,3.409416447878263057e+02,4.945094674189780548e-01,3.937121045505200367e+00,-2.223938911114254902e-01,-3.558803894403095858e-01,1.361524071352429588e-01,-9.999999888159301076e-01,0.000000000000000000e+00 +5.493842270583052567e+01,3.409513985101821163e+02,4.923038155412421402e-01,3.936217135299425518e+00,-2.218938911114254897e-01,-3.584203164002834896e-01,1.361524071352429588e-01,-9.999999883627114228e-01,0.000000000000000000e+00 +5.494096321608599709e+01,3.409611533341446261e+02,4.901030408001874061e-01,3.935306564809840424e+00,-2.213938911114254893e-01,-3.609608266261926657e-01,1.361524071352429588e-01,-9.999999877982402863e-01,0.000000000000000000e+00 +5.494350431417716862e+01,3.409709092572750819e+02,4.879071437460075211e-01,3.934389327942314107e+00,-2.208938911114254888e-01,-3.635019246863550046e-01,1.361524071352429588e-01,-9.999999872729247175e-01,0.000000000000000000e+00 +5.494604600468272793e+01,3.409806662771345600e+02,4.857161249276767401e-01,3.933465418551586712e+00,-2.203938911114254884e-01,-3.660436151595647947e-01,1.361524071352429588e-01,-9.999999865055720916e-01,0.000000000000000000e+00 +5.494858829219155893e+01,3.409904243912837387e+02,4.835299848929497379e-01,3.932534830441079432e+00,-2.198938911114254879e-01,-3.685859026340884692e-01,1.361524071352429588e-01,-9.999999860178517830e-01,0.000000000000000000e+00 +5.495113118130282714e+01,3.410001835972831259e+02,4.813487241883615542e-01,3.931597557362705331e+00,-2.193938911114254875e-01,-3.711287917097986777e-01,1.361524071352429588e-01,-9.999999852084585639e-01,0.000000000000000000e+00 +5.495367467662606487e+01,3.410099438926929452e+02,4.791723433592273151e-01,3.930653593016673053e+00,-2.188938911114254871e-01,-3.736722869954129389e-01,1.361524071352429588e-01,-9.999999844119552561e-01,0.000000000000000000e+00 +5.495621878278127781e+01,3.410197052750730791e+02,4.770008429496422342e-01,3.929702931051295867e+00,-2.183938911114254866e-01,-3.762163931109673287e-01,1.361524071352429588e-01,-9.999999836595303560e-01,0.000000000000000000e+00 +5.495876350439903035e+01,3.410294677419831828e+02,4.748342235024814451e-01,3.928745565062792711e+00,-2.178938911114254862e-01,-3.787611146871400214e-01,1.361524071352429588e-01,-9.999999827463647017e-01,0.000000000000000000e+00 +5.496130884612055212e+01,3.410392312909826842e+02,4.726724855593997243e-01,3.927781488595089243e+00,-2.173938911114254857e-01,-3.813064563647459160e-01,1.361524071352429588e-01,-9.999999816408736697e-01,0.000000000000000000e+00 +5.496385481259782324e+01,3.410489959196306700e+02,4.705156296608316024e-01,3.926810695139618446e+00,-2.168938911114254853e-01,-3.838524227952729850e-01,1.361524071352429588e-01,-9.999999806187113149e-01,0.000000000000000000e+00 +5.496640140849366674e+01,3.410587616254859427e+02,4.683636563459910307e-01,3.925833178135118118e+00,-2.163938911114254848e-01,-3.863990186417609607e-01,1.361524071352429588e-01,-9.999999795069860475e-01,0.000000000000000000e+00 +5.496894863848186219e+01,3.410685284061071343e+02,4.662165661528712701e-01,3.924848930967424376e+00,-2.158938911114254844e-01,-3.889462485777563927e-01,1.361524071352429588e-01,-9.999999780933931381e-01,0.000000000000000000e+00 +5.497149650724723102e+01,3.410782962590525358e+02,4.640743596182449471e-01,3.923857946969266042e+00,-2.153938911114254839e-01,-3.914941172873092623e-01,1.361524071352429588e-01,-9.999999766027175552e-01,0.000000000000000000e+00 +5.497404501948573596e+01,3.410880651818801539e+02,4.619370372776636091e-01,3.922860219420057248e+00,-2.148938911114254835e-01,-3.940426294661844020e-01,1.361524071352429588e-01,-9.999999751459252018e-01,0.000000000000000000e+00 +5.497659417990458053e+01,3.410978351721478248e+02,4.598045996654578915e-01,3.921855741545685170e+00,-2.143938911114254831e-01,-3.965917898216705373e-01,1.361524071352429588e-01,-9.999999731723909768e-01,0.000000000000000000e+00 +5.497914399322230850e+01,3.411076062274129868e+02,4.576770473147371288e-01,3.920844506518296413e+00,-2.138938911114254826e-01,-3.991416030709928342e-01,1.361524071352429588e-01,-9.999999712436551391e-01,0.000000000000000000e+00 +5.498169446416890338e+01,3.411173783452329076e+02,4.555543807573894100e-01,3.919826507456085629e+00,-2.133938911114254822e-01,-4.016920739442477739e-01,1.361524071352429588e-01,-9.999999689126097824e-01,0.000000000000000000e+00 +5.498424559748589502e+01,3.411271515231645708e+02,4.534366005240814124e-01,3.918801737423074805e+00,-2.128938911114254817e-01,-4.042432071819317962e-01,1.361524071352429588e-01,-9.999999661562477549e-01,0.000000000000000000e+00 +5.498679739792645194e+01,3.411369257587646189e+02,4.513237071442581239e-01,3.917770189428896987e+00,-2.123938911114254813e-01,-4.067950075361232987e-01,1.361524071352429588e-01,-9.999999632351909140e-01,0.000000000000000000e+00 +5.498934987025548082e+01,3.411467010495895238e+02,4.492157011461428984e-01,3.916731856428575131e+00,-2.118938911114254808e-01,-4.093474797713080870e-01,1.361524071352429588e-01,-9.999999595324736701e-01,0.000000000000000000e+00 +5.499190301924973312e+01,3.411564773931954733e+02,4.471125830567372339e-01,3.915686731322296943e+00,-2.113938911114254804e-01,-4.119006286622416413e-01,1.361524071352429588e-01,-9.999999553915002171e-01,0.000000000000000000e+00 +5.499445684969791870e+01,3.411662547871384277e+02,4.450143534018206615e-01,3.914634806955193280e+00,-2.108938911114254799e-01,-4.144544589965028503e-01,1.361524071352429588e-01,-9.999999503414138680e-01,0.000000000000000000e+00 +5.499701136640079113e+01,3.411760332289739495e+02,4.429210127059505231e-01,3.913576076117108116e+00,-2.103938911114254795e-01,-4.170089755725183145e-01,1.361524071352429588e-01,-9.999999439812931046e-01,0.000000000000000000e+00 +5.499956657417125427e+01,3.411858127162574874e+02,4.408325614924620273e-01,3.912510531542371606e+00,-2.098938911114254791e-01,-4.195641831998437876e-01,1.361524071352429588e-01,-9.999999363165011923e-01,0.000000000000000000e+00 +5.500212247783448305e+01,3.411955932465441492e+02,4.387490002834679714e-01,3.911438165909570497e+00,-2.093938911114254786e-01,-4.221200867003061519e-01,1.361524071352429588e-01,-9.999999262606976691e-01,0.000000000000000000e+00 +5.500467908222801583e+01,3.412053748173888152e+02,4.366703295998586309e-01,3.910358971841313647e+00,-2.088938911114254782e-01,-4.246766909053176775e-01,1.361524071352429588e-01,-9.999999129262587827e-01,0.000000000000000000e+00 +5.500723639220186101e+01,3.412151574263460816e+02,4.345965499613016481e-01,3.909272941904002430e+00,-2.083938911114254777e-01,-4.272340006564870896e-01,1.361524071352429588e-01,-9.999998942640578870e-01,0.000000000000000000e+00 +5.500979441261860359e+01,3.412249410709703170e+02,4.325276618862419764e-01,3.908180068607597590e+00,-2.078938911114254773e-01,-4.297920208027524724e-01,1.361524071352429588e-01,-9.999998661828689572e-01,0.000000000000000000e+00 +5.501235314835351176e+01,3.412347257488155492e+02,4.304636658919015479e-01,3.907080344405391426e+00,-2.073938911114254768e-01,-4.323507561952574241e-01,1.361524071352429588e-01,-9.999998194360526504e-01,0.000000000000000000e+00 +5.501491260429465058e+01,3.412445114574356921e+02,4.284045624942793840e-01,3.905973761693791069e+00,-2.068938911114254764e-01,-4.349102116742520341e-01,1.361524071352429588e-01,-9.999997258865627181e-01,0.000000000000000000e+00 +5.501747278534298857e+01,3.412542981943842619e+02,4.263503522081513730e-01,3.904860312812133305e+00,-2.063938911114254759e-01,-4.374703920208115604e-01,1.361524071352429588e-01,-9.999994452180647198e-01,0.000000000000000000e+00 +5.502003369641250430e+01,3.412640859572146042e+02,4.243010355470699935e-01,3.903739990042621066e+00,-2.058938911114254755e-01,-4.400313016695818202e-01,1.361524071352429588e-01,-5.906885044666913137e-02,0.000000000000000000e+00 +5.502259534243030004e+01,3.412738747434797233e+02,4.222566130233644799e-01,3.902612785610994006e+00,-2.053938911114254751e-01,-4.401826151551042621e-01,1.361524071352429588e-01,9.999994519574871843e-01,0.000000000000000000e+00 +5.502515772833670127e+01,3.412836645507325102e+02,4.202170851481403790e-01,3.901484867881676699e+00,-2.048938911114254746e-01,-4.376202306529970998e-01,1.361524071352429588e-01,9.999997326464810099e-01,0.000000000000000000e+00 +5.502772085502785160e+01,3.412934553765254577e+02,4.181824524312797164e-01,3.900363191787901140e+00,-2.043938911114254742e-01,-4.350571046471042869e-01,1.361524071352429588e-01,9.999998261652119913e-01,0.000000000000000000e+00 +5.503028471882932138e+01,3.413032472184108315e+02,4.161527153814406077e-01,3.899247764625725310e+00,-2.038938911114254737e-01,-4.324932412913258251e-01,1.361524071352429588e-01,9.999998730259659352e-01,0.000000000000000000e+00 +5.503284931605515595e+01,3.413130400739407264e+02,4.141278745060573141e-01,3.898138593658917461e+00,-2.033938911114254733e-01,-4.299286443911287114e-01,1.361524071352429588e-01,9.999999009538383943e-01,0.000000000000000000e+00 +5.503541464300793962e+01,3.413228339406668965e+02,4.121079303113400760e-01,3.897035686119687092e+00,-2.028938911114254728e-01,-4.273633176924306887e-01,1.361524071352429588e-01,9.999999197343978352e-01,0.000000000000000000e+00 +5.503798069597882403e+01,3.413326288161409252e+02,4.100928833022748909e-01,3.895939049208676508e+00,-2.023938911114254724e-01,-4.247972649275146284e-01,1.361524071352429588e-01,9.999999329988995544e-01,0.000000000000000000e+00 +5.504054747124755664e+01,3.413424246979140548e+02,4.080827339826235134e-01,3.894848690094835142e+00,-2.018938911114254720e-01,-4.222304898307583931e-01,1.361524071352429588e-01,9.999999430928750987e-01,0.000000000000000000e+00 +5.504311496508253754e+01,3.413522215835373004e+02,4.060774828549232884e-01,3.893764615915253913e+00,-2.013938911114254715e-01,-4.196629961418866794e-01,1.361524071352429588e-01,9.999999508768271372e-01,0.000000000000000000e+00 +5.504568317374084074e+01,3.413620194705614495e+02,4.040771304204869852e-01,3.892686833774991584e+00,-2.008938911114254711e-01,-4.170947876097390039e-01,1.361524071352429588e-01,9.999999570083334399e-01,0.000000000000000000e+00 +5.504825209346827108e+01,3.413718183565370623e+02,4.020816771794026856e-01,3.891615350746891799e+00,-2.003938911114254706e-01,-4.145258679927489864e-01,1.361524071352429588e-01,9.999999621424831009e-01,0.000000000000000000e+00 +5.505082172049939260e+01,3.413816182390143581e+02,4.000911236305336738e-01,3.890550173871399231e+00,-1.998938911114254702e-01,-4.119562410589088786e-01,1.361524071352429588e-01,9.999999663928049731e-01,0.000000000000000000e+00 +5.505339205105756406e+01,3.413914191155434423e+02,3.981054702715183247e-01,3.889491310156376169e+00,-1.993938911114254697e-01,-4.093859105871192616e-01,1.361524071352429588e-01,9.999999699360181404e-01,0.000000000000000000e+00 +5.505596308135499584e+01,3.414012209836740226e+02,3.961247175987699931e-01,3.888438766576916006e+00,-1.988938911114254693e-01,-4.068148803669853764e-01,1.361524071352429588e-01,9.999999730102807627e-01,0.000000000000000000e+00 +5.505853480759277119e+01,3.414110238409556928e+02,3.941488661074768474e-01,3.887392550075157605e+00,-1.983938911114254688e-01,-4.042431541986172827e-01,1.361524071352429588e-01,9.999999757119997223e-01,0.000000000000000000e+00 +5.506110722596091733e+01,3.414208276849377057e+02,3.921779162916017025e-01,3.886352667560100560e+00,-1.978938911114254684e-01,-4.016707358929520466e-01,1.361524071352429588e-01,9.999999779948109957e-01,0.000000000000000000e+00 +5.506368033263841255e+01,3.414306325131690869e+02,3.902118686438820205e-01,3.885319125907420013e+00,-1.973938911114254680e-01,-3.990976292720785912e-01,1.361524071352429588e-01,9.999999800704960640e-01,0.000000000000000000e+00 +5.506625412379325724e+01,3.414404383231986344e+02,3.882507236558297437e-01,3.884291931959281019e+00,-1.968938911114254675e-01,-3.965238381685307067e-01,1.361524071352429588e-01,9.999999818707248078e-01,0.000000000000000000e+00 +5.506882859558249521e+01,3.414502451125749189e+02,3.862944818177310724e-01,3.883271092524155144e+00,-1.963938911114254671e-01,-3.939493664259644534e-01,1.361524071352429588e-01,9.999999834482439232e-01,0.000000000000000000e+00 +5.507140374415227768e+01,3.414600528788462270e+02,3.843431436186464656e-01,3.882256614376635717e+00,-1.958938911114254666e-01,-3.913742178988029452e-01,1.361524071352429588e-01,9.999999850413214819e-01,0.000000000000000000e+00 +5.507397956563789876e+01,3.414698616195606178e+02,3.823967095464104737e-01,3.881248504257254428e+00,-1.953938911114254662e-01,-3.887983964517142677e-01,1.361524071352429588e-01,9.999999862026667241e-01,0.000000000000000000e+00 +5.507655605616383099e+01,3.414796713322659230e+02,3.804551800876315726e-01,3.880246768872299690e+00,-1.948938911114254657e-01,-3.862219059613326566e-01,1.361524071352429588e-01,9.999999874709107894e-01,0.000000000000000000e+00 +5.507913321184378219e+01,3.414894820145096901e+02,3.785185557276921076e-01,3.879251414893631011e+00,-1.943938911114254653e-01,-3.836447503136738435e-01,1.361524071352429588e-01,9.999999886288326589e-01,0.000000000000000000e+00 +5.508171102878073100e+01,3.414992936638392962e+02,3.765868369507481828e-01,3.878262448958500475e+00,-1.938938911114254648e-01,-3.810669334060366453e-01,1.361524071352429588e-01,9.999999895053450771e-01,0.000000000000000000e+00 +5.508428950306699079e+01,3.415091062778017772e+02,3.746600242397294944e-01,3.877279877669369768e+00,-1.933938911114254644e-01,-3.784884591468387072e-01,1.361524071352429588e-01,9.999999905080017015e-01,0.000000000000000000e+00 +5.508686863078423102e+01,3.415189198539439985e+02,3.727381180763392199e-01,3.876303707593728110e+00,-1.928938911114254640e-01,-3.759093314540782327e-01,1.361524071352429588e-01,9.999999913519360684e-01,0.000000000000000000e+00 +5.508944840800354825e+01,3.415287343898125414e+02,3.708211189410538511e-01,3.875333945263914615e+00,-1.923938911114254635e-01,-3.733295542570724268e-01,1.361524071352429588e-01,9.999999921271691683e-01,0.000000000000000000e+00 +5.509202883078549462e+01,3.415385498829538165e+02,3.689090273131231945e-01,3.874370597176936659e+00,-1.918938911114254631e-01,-3.707491314954436401e-01,1.361524071352429588e-01,9.999999928296255947e-01,0.000000000000000000e+00 +5.509460989518013463e+01,3.415483663309139502e+02,3.670018436705701492e-01,3.873413669794291359e+00,-1.913938911114254626e-01,-3.681680671193143239e-01,1.361524071352429588e-01,9.999999935593888445e-01,0.000000000000000000e+00 +5.509719159722708781e+01,3.415581837312387847e+02,3.650995684901905958e-01,3.872463169541787043e+00,-1.908938911114254622e-01,-3.655863650889900063e-01,1.361524071352429588e-01,9.999999941195333308e-01,0.000000000000000000e+00 +5.509977393295558556e+01,3.415680020814739919e+02,3.632022022475532852e-01,3.871519102809366064e+00,-1.903938911114254617e-01,-3.630040293756774394e-01,1.361524071352429588e-01,9.999999948139423056e-01,0.000000000000000000e+00 +5.510235689838451378e+01,3.415778213791650160e+02,3.613097454169998390e-01,3.870581475950926276e+00,-1.898938911114254613e-01,-3.604210639601425070e-01,1.361524071352429588e-01,9.999999952468942022e-01,0.000000000000000000e+00 +5.510494048952246970e+01,3.415876416218569602e+02,3.594221984716444163e-01,3.869650295284146502e+00,-1.893938911114254608e-01,-3.578374728344674849e-01,1.361524071352429588e-01,9.999999958527686639e-01,0.000000000000000000e+00 +5.510752470236779743e+01,3.415974628070948143e+02,3.575395618833737688e-01,3.868725567090308015e+00,-1.888938911114254604e-01,-3.552532599998569629e-01,1.361524071352429588e-01,9.999999962307855039e-01,0.000000000000000000e+00 +5.511010953290865189e+01,3.416072849324232834e+02,3.556618361228470193e-01,3.867807297614122231e+00,-1.883938911114254600e-01,-3.526684294687451593e-01,1.361524071352429588e-01,9.999999968061779043e-01,0.000000000000000000e+00 +5.511269497712304144e+01,3.416171079953868457e+02,3.537890216594955506e-01,3.866895493063553513e+00,-1.878938911114254595e-01,-3.500829852626105021e-01,1.361524071352429588e-01,9.999999972330977371e-01,0.000000000000000000e+00 +5.511528103097889186e+01,3.416269319935296949e+02,3.519211189615230606e-01,3.865990159609648202e+00,-1.873938911114254591e-01,-3.474969314139174092e-01,1.361524071352429588e-01,9.999999975233440086e-01,0.000000000000000000e+00 +5.511786769043407475e+01,3.416367569243958542e+02,3.500581284959051187e-01,3.865091303386359201e+00,-1.868938911114254586e-01,-3.449102719651403470e-01,1.361524071352429588e-01,9.999999980435391178e-01,0.000000000000000000e+00 +5.512045495143648566e+01,3.416465827855291195e+02,3.482000507283893875e-01,3.864198930490373662e+00,-1.863938911114254582e-01,-3.423230109677936617e-01,1.361524071352429588e-01,9.999999983195597686e-01,0.000000000000000000e+00 +5.512304280992407257e+01,3.416564095744730025e+02,3.463468861234952900e-01,3.863313046980943799e+00,-1.858938911114254577e-01,-3.397351524845538817e-01,1.361524071352429588e-01,9.999999987601132512e-01,0.000000000000000000e+00 +5.512563126182491402e+01,3.416662372887707875e+02,3.444986351445140094e-01,3.862433658879712794e+00,-1.853938911114254573e-01,-3.371467005869226985e-01,1.361524071352429588e-01,9.999999989967024439e-01,0.000000000000000000e+00 +5.512822030305724752e+01,3.416760659259655313e+02,3.426552982535082115e-01,3.861560772170547384e+00,-1.848938911114254569e-01,-3.345576593571847890e-01,1.361524071352429588e-01,9.999999992747885535e-01,0.000000000000000000e+00 +5.513080992952954773e+01,3.416858954836001203e+02,3.408168759113121560e-01,3.860694392799365993e+00,-1.843938911114254564e-01,-3.319680328867649077e-01,1.361524071352429588e-01,9.999999997224475745e-01,0.000000000000000000e+00 +5.513340013714055488e+01,3.416957259592171567e+02,3.389833685775313632e-01,3.859834526673971755e+00,-1.838938911114254560e-01,-3.293778252764770764e-01,1.361524071352429588e-01,9.999999998862225681e-01,0.000000000000000000e+00 +5.513599092177935290e+01,3.417055573503590153e+02,3.371547767105427251e-01,3.858981179663885541e+00,-1.833938911114254555e-01,-3.267870406379762005e-01,1.361524071352429588e-01,1.000000000185661930e+00,0.000000000000000000e+00 +5.513858227932540501e+01,3.417153896545678435e+02,3.353311007674941724e-01,3.858134357600175868e+00,-1.828938911114254551e-01,-3.241956830914416998e-01,1.361524071352429588e-01,1.000000000455515181e+00,0.000000000000000000e+00 +5.514117420564863181e+01,3.417252228693855614e+02,3.335123412043046742e-01,3.857294066275295474e+00,-1.823938911114254546e-01,-3.216037567670367303e-01,1.361524071352429588e-01,1.000000000738638484e+00,0.000000000000000000e+00 +5.514376669660943975e+01,3.417350569923538615e+02,3.316984984756641275e-01,3.856460311442914790e+00,-1.818938911114254542e-01,-3.190112658043130489e-01,1.361524071352429588e-01,1.000000000887399487e+00,0.000000000000000000e+00 +5.514635974805880636e+01,3.417448920210142091e+02,3.298895730350331901e-01,3.855633098817757620e+00,-1.813938911114254537e-01,-3.164182143526484414e-01,1.361524071352429588e-01,1.000000001157012708e+00,0.000000000000000000e+00 +5.514895335583830871e+01,3.417547279529078992e+02,3.280855653346431700e-01,3.854812434075436389e+00,-1.808938911114254533e-01,-3.138246065701453813e-01,1.361524071352429588e-01,1.000000001411103678e+00,0.000000000000000000e+00 +5.515154751578020154e+01,3.417645647855758853e+02,3.262864758254960806e-01,3.853998322852290936e+00,-1.803938911114254529e-01,-3.112304466245890411e-01,1.361524071352429588e-01,1.000000001582899811e+00,0.000000000000000000e+00 +5.515414222370747410e+01,3.417744025165590074e+02,3.244923049573641971e-01,3.853190770745225535e+00,-1.798938911114254524e-01,-3.086357386932093161e-01,1.361524071352429588e-01,1.000000001739353550e+00,0.000000000000000000e+00 +5.515673747543389283e+01,3.417842411433977645e+02,3.227030531787902778e-01,3.852389783311547244e+00,-1.793938911114254520e-01,-3.060404869622758151e-01,1.361524071352429588e-01,1.000000002013653022e+00,0.000000000000000000e+00 +5.515933326676407233e+01,3.417940806636325988e+02,3.209187209370872318e-01,3.851595366068806037e+00,-1.788938911114254515e-01,-3.034446956268672668e-01,1.361524071352429588e-01,1.000000002208059957e+00,0.000000000000000000e+00 +5.516192959349353231e+01,3.418039210748035543e+02,3.191393086783381183e-01,3.850807524494636258e+00,-1.783938911114254511e-01,-3.008483688916714915e-01,1.361524071352429588e-01,1.000000002254391118e+00,0.000000000000000000e+00 +5.516452645140876143e+01,3.418137623744505618e+02,3.173648168473960363e-01,3.850026264026596756e+00,-1.778938911114254506e-01,-2.982515109705900502e-01,1.361524071352429588e-01,1.000000002606881377e+00,0.000000000000000000e+00 +5.516712383628726002e+01,3.418236045601132673e+02,3.155952458878839018e-01,3.849251590062012784e+00,-1.773938911114254502e-01,-2.956541260853217112e-01,1.361524071352429588e-01,1.000000002594930937e+00,0.000000000000000000e+00 +5.516972174389761818e+01,3.418334476293311468e+02,3.138305962421944484e-01,3.848483507957822347e+00,-1.768938911114254497e-01,-2.930562184682235505e-01,1.361524071352429588e-01,1.000000002857326153e+00,0.000000000000000000e+00 +5.517232016999956556e+01,3.418432915796434486e+02,3.120708683514900605e-01,3.847722023030415883e+00,-1.763938911114254493e-01,-2.904577923588494426e-01,1.361524071352429588e-01,1.000000002971427104e+00,0.000000000000000000e+00 +5.517491911034404950e+01,3.418531364085891369e+02,3.103160626557027180e-01,3.846967140555485720e+00,-1.758938911114254489e-01,-2.878588520066463485e-01,1.361524071352429588e-01,1.000000003162354600e+00,0.000000000000000000e+00 +5.517751856067326344e+01,3.418629821137070621e+02,3.085661795935338292e-01,3.846218865767869310e+00,-1.753938911114254484e-01,-2.852594016692099887e-01,1.361524071352429588e-01,1.000000003314917230e+00,0.000000000000000000e+00 +5.518011851672074641e+01,3.418728286925357338e+02,3.068212196024541205e-01,3.845477203861397797e+00,-1.748938911114254480e-01,-2.826594456131074073e-01,1.361524071352429588e-01,1.000000003367081725e+00,0.000000000000000000e+00 +5.518271897421141858e+01,3.418826761426135477e+02,3.050811831187036360e-01,3.844742159988743246e+00,-1.743938911114254475e-01,-2.800589881136767989e-01,1.361524071352429588e-01,1.000000003504945445e+00,0.000000000000000000e+00 +5.518531992886165938e+01,3.418925244614786720e+02,3.033460705772914601e-01,3.844013739261267215e+00,-1.738938911114254471e-01,-2.774580334543196858e-01,1.361524071352429588e-01,1.000000003767392620e+00,0.000000000000000000e+00 +5.518792137637935724e+01,3.419023736466689911e+02,3.016158824119957171e-01,3.843291946748871979e+00,-1.733938911114254466e-01,-2.748565859268205513e-01,1.361524071352429588e-01,1.000000003716873920e+00,0.000000000000000000e+00 +5.519052331246398069e+01,3.419122236957221617e+02,2.998906190553634610e-01,3.842576787479851763e+00,-1.728938911114254462e-01,-2.722546498325230657e-01,1.361524071352429588e-01,1.000000003947046467e+00,0.000000000000000000e+00 +5.519312573280664935e+01,3.419220746061757268e+02,2.981702809387105080e-01,3.841868266440741753e+00,-1.723938911114254458e-01,-2.696522294795835606e-01,1.361524071352429588e-01,1.000000004047445268e+00,0.000000000000000000e+00 +5.519572863309017663e+01,3.419319263755669454e+02,2.964548684921213817e-01,3.841166388576175095e+00,-1.718938911114254453e-01,-2.670493291855193796e-01,1.361524071352429588e-01,1.000000004176517798e+00,0.000000000000000000e+00 +5.519833200898916203e+01,3.419417790014329057e+02,2.947443821444491463e-01,3.840471158788734130e+00,-1.713938911114254449e-01,-2.644459532756640585e-01,1.361524071352429588e-01,1.000000004207752147e+00,0.000000000000000000e+00 +5.520093585617002674e+01,3.419516324813104120e+02,2.930388223233154066e-01,3.839782581938806505e+00,-1.708938911114254444e-01,-2.618421060838441172e-01,1.361524071352429588e-01,1.000000004448852620e+00,0.000000000000000000e+00 +5.520354017029109883e+01,3.419614868127360978e+02,2.913381894551101414e-01,3.839100662844440404e+00,-1.703938911114254440e-01,-2.592377919511831830e-01,1.361524071352429588e-01,1.000000004396179865e+00,0.000000000000000000e+00 +5.520614494700268438e+01,3.419713419932464262e+02,2.896424839649915373e-01,3.838425406281203767e+00,-1.698938911114254435e-01,-2.566330152281491306e-01,1.361524071352429588e-01,1.000000004566731437e+00,0.000000000000000000e+00 +5.520875018194710293e+01,3.419811980203775761e+02,2.879517062768859326e-01,3.837756816982039076e+00,-1.693938911114254431e-01,-2.540277802718299838e-01,1.361524071352429588e-01,1.000000004663563757e+00,0.000000000000000000e+00 +5.521135587075879414e+01,3.419910548916654989e+02,2.862658568134877624e-01,3.837094899637126133e+00,-1.688938911114254426e-01,-2.514220914479874391e-01,1.361524071352429588e-01,1.000000004752961136e+00,0.000000000000000000e+00 +5.521396200906435325e+01,3.420009126046460324e+02,2.845849359962593916e-01,3.836439658893740390e+00,-1.683938911114254422e-01,-2.488159531300440097e-01,1.361524071352429588e-01,1.000000004869994186e+00,0.000000000000000000e+00 +5.521656859248260929e+01,3.420107711568547302e+02,2.829089442454310044e-01,3.835791099356114842e+00,-1.678938911114254418e-01,-2.462093696990971248e-01,1.361524071352429588e-01,1.000000004952153576e+00,0.000000000000000000e+00 +5.521917561662468898e+01,3.420206305458269185e+02,2.812378819800005481e-01,3.835149225585302801e+00,-1.673938911114254413e-01,-2.436023455441059526e-01,1.361524071352429588e-01,1.000000005033973016e+00,0.000000000000000000e+00 +5.522178307709409495e+01,3.420304907690978098e+02,2.795717496177335670e-01,3.834514042099041120e+00,-1.668938911114254409e-01,-2.409948850615706017e-01,1.361524071352429588e-01,1.000000005049726415e+00,0.000000000000000000e+00 +5.522439096948676962e+01,3.420403518242022756e+02,2.779105475751631471e-01,3.833885553371615185e+00,-1.663938911114254404e-01,-2.383869926557252994e-01,1.361524071352429588e-01,1.000000005223933508e+00,0.000000000000000000e+00 +5.522699928939115921e+01,3.420502137086751304e+02,2.762542762675897490e-01,3.833263763833724358e+00,-1.658938911114254400e-01,-2.357786727377128577e-01,1.361524071352429588e-01,1.000000005286405313e+00,0.000000000000000000e+00 +5.522960803238827765e+01,3.420600764200508479e+02,2.746029361090812637e-01,3.832648677872350529e+00,-1.653938911114254395e-01,-2.331699297268059190e-01,1.361524071352429588e-01,1.000000005320070606e+00,0.000000000000000000e+00 +5.523221719405178476e+01,3.420699399558637879e+02,2.729565275124726798e-01,3.832040299830624441e+00,-1.648938911114254391e-01,-2.305607680494167755e-01,1.361524071352429588e-01,1.000000005432689187e+00,0.000000000000000000e+00 +5.523482676994806440e+01,3.420798043136480260e+02,2.713150508893661383e-01,3.831438634007695576e+00,-1.643938911114254386e-01,-2.279511921389627827e-01,1.361524071352429588e-01,1.000000005495034205e+00,0.000000000000000000e+00 +5.523743675563626709e+01,3.420896694909375242e+02,2.696785066501307671e-01,3.830843684658603365e+00,-1.638938911114254382e-01,-2.253412064364147260e-01,1.361524071352429588e-01,1.000000005596108910e+00,0.000000000000000000e+00 +5.524004714666841664e+01,3.420995354852659602e+02,2.680468952039026242e-01,3.830255455994147962e+00,-1.633938911114254378e-01,-2.227308153896570275e-01,1.361524071352429588e-01,1.000000005585488738e+00,0.000000000000000000e+00 +5.524265793858944562e+01,3.421094022941668413e+02,2.664202169585845881e-01,3.829673952180763674e+00,-1.628938911114254373e-01,-2.201200234540420242e-01,1.361524071352429588e-01,1.000000005723770125e+00,0.000000000000000000e+00 +5.524526912693729486e+01,3.421192699151734473e+02,2.647984723208462454e-01,3.829099177340391957e+00,-1.623938911114254369e-01,-2.175088350912459390e-01,1.361524071352429588e-01,1.000000005769068334e+00,0.000000000000000000e+00 +5.524788070724296318e+01,3.421291383458188875e+02,2.631816616961236699e-01,3.828531135550358400e+00,-1.618938911114254364e-01,-2.148972547705093883e-01,1.361524071352429588e-01,1.000000005887996091e+00,0.000000000000000000e+00 +5.525049267503059269e+01,3.421390075836360438e+02,2.615697854886195328e-01,3.827969830843247490e+00,-1.613938911114254360e-01,-2.122852869674990983e-01,1.361524071352429588e-01,1.000000005807728520e+00,0.000000000000000000e+00 +5.525310502581753980e+01,3.421488776261576277e+02,2.599628441013028812e-01,3.827415267206781380e+00,-1.608938911114254355e-01,-2.096729361653835999e-01,1.361524071352429588e-01,1.000000006051563251e+00,0.000000000000000000e+00 +5.525571775511443207e+01,3.421587484709161231e+02,2.583608379359090823e-01,3.826867448583696873e+00,-1.603938911114254351e-01,-2.070602068526812556e-01,1.361524071352429588e-01,1.000000005920439250e+00,0.000000000000000000e+00 +5.525833085842526060e+01,3.421686201154437867e+02,2.567637673929396569e-01,3.826326378871629075e+00,-1.598938911114254346e-01,-2.044471035263809577e-01,1.361524071352429588e-01,1.000000006159175614e+00,0.000000000000000000e+00 +5.526094433124745109e+01,3.421784925572727616e+02,2.551716328716622240e-01,3.825792061922987930e+00,-1.593938911114254342e-01,-2.018336306880966491e-01,1.361524071352429588e-01,1.000000006093365590e+00,0.000000000000000000e+00 +5.526355816907192064e+01,3.421883657939349064e+02,2.535844347701103896e-01,3.825264501544845874e+00,-1.588938911114254338e-01,-1.992197928477025537e-01,1.361524071352429588e-01,1.000000006164413202e+00,0.000000000000000000e+00 +5.526617236738316308e+01,3.421982398229619093e+02,2.520021734850836914e-01,3.824743701498817039e+00,-1.583938911114254333e-01,-1.966055945203435962e-01,1.361524071352429588e-01,1.000000006302727895e+00,0.000000000000000000e+00 +5.526878692165933415e+01,3.422081146418852313e+02,2.504248494121474322e-01,3.824229665500945341e+00,-1.578938911114254329e-01,-1.939910402276968648e-01,1.361524071352429588e-01,1.000000006252089513e+00,0.000000000000000000e+00 +5.527140182737229424e+01,3.422179902482362195e+02,2.488524629456326520e-01,3.823722397221590352e+00,-1.573938911114254324e-01,-1.913761344983855028e-01,1.361524071352429588e-01,1.000000006412800069e+00,0.000000000000000000e+00 +5.527401707998772196e+01,3.422278666395459936e+02,2.472850144786359339e-01,3.823221900285313168e+00,-1.568938911114254320e-01,-1.887608818661875576e-01,1.361524071352429588e-01,1.000000006346654535e+00,0.000000000000000000e+00 +5.527663267496515687e+01,3.422377438133453893e+02,2.457225044030193761e-01,3.822728178270768051e+00,-1.563938911114254315e-01,-1.861452868721537868e-01,1.361524071352429588e-01,1.000000006464365487e+00,0.000000000000000000e+00 +5.527924860775808469e+01,3.422476217671651284e+02,2.441649331094105091e-01,3.822241234710589630e+00,-1.558938911114254311e-01,-1.835293540623124109e-01,1.361524071352429588e-01,1.000000006466111202e+00,0.000000000000000000e+00 +5.528186487381402969e+01,3.422575004985357623e+02,2.426123009872021286e-01,3.821761073091287209e+00,-1.553938911114254307e-01,-1.809130879894520760e-01,1.361524071352429588e-01,1.000000006573825484e+00,0.000000000000000000e+00 +5.528448146857459733e+01,3.422673800049875581e+02,2.410646084245522680e-01,3.821287696853135518e+00,-1.548938911114254302e-01,-1.782964932116813117e-01,1.361524071352429588e-01,1.000000006621700299e+00,0.000000000000000000e+00 +5.528709838747558081e+01,3.422772602840506693e+02,2.395218558083840599e-01,3.820821109390070358e+00,-1.543938911114254298e-01,-1.756795742933669191e-01,1.361524071352429588e-01,1.000000006574071953e+00,0.000000000000000000e+00 +5.528971562594702505e+01,3.422871413332550219e+02,2.379840435243856522e-01,3.820361314049582901e+00,-1.538938911114254293e-01,-1.730623358047172766e-01,1.361524071352429588e-01,1.000000006718820611e+00,0.000000000000000000e+00 +5.529233317941329773e+01,3.422970231501303715e+02,2.364511719570100978e-01,3.819908314132616223e+00,-1.533938911114254289e-01,-1.704447823208589119e-01,1.361524071352429588e-01,1.000000006758609672e+00,0.000000000000000000e+00 +5.529495104329317456e+01,3.423069057322062463e+02,2.349232414894752985e-01,3.819462112893465378e+00,-1.528938911114254284e-01,-1.678269184232913103e-01,1.361524071352429588e-01,1.000000006717735701e+00,0.000000000000000000e+00 +5.529756921299991035e+01,3.423167890770120039e+02,2.334002525037638387e-01,3.819022713539674818e+00,-1.523938911114254280e-01,-1.652087486989680665e-01,1.361524071352429588e-01,1.000000006811032405e+00,0.000000000000000000e+00 +5.530018768394132422e+01,3.423266731820767745e+02,2.318822053806229855e-01,3.818590119231939362e+00,-1.518938911114254275e-01,-1.625902777397205401e-01,1.361524071352429588e-01,1.000000006924608664e+00,0.000000000000000000e+00 +5.530280645151987073e+01,3.423365580449295749e+02,2.303691004995644942e-01,3.818164333084007822e+00,-1.513938911114254271e-01,-1.599715101430407849e-01,1.361524071352429588e-01,1.000000006809638409e+00,0.000000000000000000e+00 +5.530542551113271799e+01,3.423464436630991941e+02,2.288609382388645808e-01,3.817745358162585756e+00,-1.508938911114254267e-01,-1.573524505123571615e-01,1.361524071352429588e-01,1.000000006987517231e+00,0.000000000000000000e+00 +5.530804485817183291e+01,3.423563300341141939e+02,2.273577189755638106e-01,3.817333197487238650e+00,-1.503938911114254262e-01,-1.547331034549389583e-01,1.361524071352429588e-01,1.000000006936192509e+00,0.000000000000000000e+00 +5.531066448802405233e+01,3.423662171555030227e+02,2.258594430854669877e-01,3.816927854030301770e+00,-1.498938911114254258e-01,-1.521134735845507957e-01,1.361524071352429588e-01,1.000000007031343507e+00,0.000000000000000000e+00 +5.531328439607116110e+01,3.423761050247938442e+02,2.243661109431430711e-01,3.816529330716784241e+00,-1.493938911114254253e-01,-1.494935655190225421e-01,1.361524071352429588e-01,1.000000006991995649e+00,0.000000000000000000e+00 +5.531590457768997027e+01,3.423859936395147656e+02,2.228777229219250922e-01,3.816137630424280669e+00,-1.488938911114254249e-01,-1.468733838818905013e-01,1.361524071352429588e-01,1.000000007109028255e+00,0.000000000000000000e+00 +5.531852502825240947e+01,3.423958829971935529e+02,2.213942793939100429e-01,3.815752755982879663e+00,-1.483938911114254244e-01,-1.442529333008200076e-01,1.361524071352429588e-01,1.000000007144560943e+00,0.000000000000000000e+00 +5.532114574312559085e+01,3.424057730953579153e+02,2.199157807299587930e-01,3.815374710175077677e+00,-1.478938911114254240e-01,-1.416322184089114089e-01,1.361524071352429588e-01,1.000000007107354483e+00,0.000000000000000000e+00 +5.532376671767190146e+01,3.424156639315353345e+02,2.184422272996960068e-01,3.815003495735690642e+00,-1.473938911114254235e-01,-1.390112438439742026e-01,1.361524071352429588e-01,1.000000007251579781e+00,0.000000000000000000e+00 +5.532638794724906717e+01,3.424255555032530651e+02,2.169736194715100319e-01,3.814639115351768694e+00,-1.468938911114254231e-01,-1.363900142478038369e-01,1.361524071352429588e-01,1.000000007171097050e+00,0.000000000000000000e+00 +5.532900942721023796e+01,3.424354478080382478e+02,2.155099576125528438e-01,3.814281571662514025e+00,-1.463938911114254227e-01,-1.337685342678323064e-01,1.361524071352429588e-01,1.000000007220689824e+00,0.000000000000000000e+00 +5.533163115290408740e+01,3.424453408434177959e+02,2.140512420887398515e-01,3.813930867259195612e+00,-1.458938911114254222e-01,-1.311468085550532570e-01,1.361524071352429588e-01,1.000000007351640630e+00,0.000000000000000000e+00 +5.533425311967486238e+01,3.424552346069184523e+02,2.125974732647499810e-01,3.813587004685070614e+00,-1.453938911114254218e-01,-1.285248417649990094e-01,1.361524071352429588e-01,1.000000007305116068e+00,0.000000000000000000e+00 +5.533687532286249677e+01,3.424651290960667325e+02,2.111486515040253975e-01,3.813249986435304439e+00,-1.448938911114254213e-01,-1.259026385582107666e-01,1.361524071352429588e-01,1.000000007321916184e+00,0.000000000000000000e+00 +5.533949775780266123e+01,3.424750243083890382e+02,2.097047771687715334e-01,3.812919814956890807e+00,-1.443938911114254209e-01,-1.232802035988475736e-01,1.361524071352429588e-01,1.000000007366318000e+00,0.000000000000000000e+00 +5.534212041982686259e+01,3.424849202414116007e+02,2.082658506199569770e-01,3.812596492648576696e+00,-1.438938911114254204e-01,-1.206575415553300806e-01,1.361524071352429588e-01,1.000000007383945011e+00,0.000000000000000000e+00 +5.534474330426251498e+01,3.424948168926604239e+02,2.068318722173133617e-01,3.812280021860786849e+00,-1.433938911114254200e-01,-1.180346571003080547e-01,1.361524071352429588e-01,1.000000007494459719e+00,0.000000000000000000e+00 +5.534736640643303929e+01,3.425047142596613412e+02,2.054028423193352548e-01,3.811970404895549613e+00,-1.428938911114254195e-01,-1.154115549101222549e-01,1.361524071352429588e-01,1.000000007474593389e+00,0.000000000000000000e+00 +5.534998972165793418e+01,3.425146123399400153e+02,2.039787612832801578e-01,3.811667644006425437e+00,-1.423938911114254191e-01,-1.127882396656220976e-01,1.361524071352429588e-01,1.000000007467298113e+00,0.000000000000000000e+00 +5.535261324525284010e+01,3.425245111310218817e+02,2.025596294651682838e-01,3.811371741398434487e+00,-1.418938911114254187e-01,-1.101647160511230045e-01,1.361524071352429588e-01,1.000000007464681762e+00,0.000000000000000000e+00 +5.535523697252966002e+01,3.425344106304323191e+02,2.011454472197826138e-01,3.811082699227988257e+00,-1.413938911114254182e-01,-1.075409887547198184e-01,1.361524071352429588e-01,1.000000007629927579e+00,0.000000000000000000e+00 +5.535786089879660210e+01,3.425443108356963648e+02,1.997362149006686738e-01,3.810800519602821623e+00,-1.408938911114254178e-01,-1.049170624677554925e-01,1.361524071352429588e-01,1.000000007522615197e+00,0.000000000000000000e+00 +5.536048501935829336e+01,3.425542117443390566e+02,1.983319328601345632e-01,3.810525204581927561e+00,-1.403938911114254173e-01,-1.022929418863222778e-01,1.361524071352429588e-01,1.000000007645990063e+00,0.000000000000000000e+00 +5.536310932951585073e+01,3.425641133538850909e+02,1.969326014492507881e-01,3.810256756175489201e+00,-1.398938911114254169e-01,-9.966863170870279842e-02,1.361524071352429588e-01,1.000000007640456046e+00,0.000000000000000000e+00 +5.536573382456695214e+01,3.425740156618591072e+02,1.955382210178501778e-01,3.809995176344819878e+00,-1.393938911114254164e-01,-9.704413663755122321e-02,1.361524071352429588e-01,1.000000007572759309e+00,0.000000000000000000e+00 +5.536835849980593594e+01,3.425839186657855180e+02,1.941487919145278296e-01,3.809740467002298736e+00,-1.388938911114254160e-01,-9.441946137869138000e-02,1.361524071352429588e-01,1.000000007741723485e+00,0.000000000000000000e+00 +5.537098335052387910e+01,3.425938223631885649e+02,1.927643144866409974e-01,3.809492630011310776e+00,-1.383938911114254156e-01,-9.179461064042422624e-02,1.361524071352429588e-01,1.000000007710777350e+00,0.000000000000000000e+00 +5.537360837200868957e+01,3.426037267515923759e+02,1.913847890803090646e-01,3.809251667186190016e+00,-1.378938911114254151e-01,-8.916958913537459397e-02,1.361524071352429588e-01,1.000000007725506235e+00,0.000000000000000000e+00 +5.537623355954516313e+01,3.426136318285207949e+02,1.900102160404133489e-01,3.809017580292159089e+00,-1.373938911114254147e-01,-8.654440157861706395e-02,1.361524071352429588e-01,1.000000007746133956e+00,0.000000000000000000e+00 +5.537885890841510417e+01,3.426235375914975521e+02,1.886405957105971309e-01,3.808790371045275069e+00,-1.368938911114254142e-01,-8.391905268834118359e-02,1.361524071352429588e-01,1.000000007769272115e+00,0.000000000000000000e+00 +5.538148441389737542e+01,3.426334440380462638e+02,1.872759284332654595e-01,3.808570041112374849e+00,-1.363938911114254138e-01,-8.129354718567201321e-02,1.361524071352429588e-01,1.000000007762942511e+00,0.000000000000000000e+00 +5.538411007126800456e+01,3.426433511656902624e+02,1.859162145495851792e-01,3.808356592111022287e+00,-1.358938911114254133e-01,-7.866788979466110554e-02,1.361524071352429588e-01,1.000000007859220830e+00,0.000000000000000000e+00 +5.538673587580025526e+01,3.426532589719527664e+02,1.845614543994847090e-01,3.808150025609456701e+00,-1.353938911114254129e-01,-7.604208524177151485e-02,1.361524071352429588e-01,1.000000007838521610e+00,0.000000000000000000e+00 +5.538936182276472664e+01,3.426631674543568806e+02,1.832116483216541247e-01,3.807950343126544013e+00,-1.348938911114254124e-01,-7.341613825671679250e-02,1.361524071352429588e-01,1.000000007837522187e+00,0.000000000000000000e+00 +5.539198790742941725e+01,3.426730766104254258e+02,1.818667966535449099e-01,3.807757546131727011e+00,-1.343938911114254120e-01,-7.079005357144102506e-02,1.361524071352429588e-01,1.000000007962200232e+00,0.000000000000000000e+00 +5.539461412505983162e+01,3.426829864376811088e+02,1.805268997313699830e-01,3.807571636044979613e+00,-1.338938911114254116e-01,-6.816383592011474035e-02,1.361524071352429588e-01,1.000000007836711502e+00,0.000000000000000000e+00 +5.539724047091905135e+01,3.426928969336465229e+02,1.791919578901035592e-01,3.807392614236762451e+00,-1.333938911114254111e-01,-6.553749004031551861e-02,1.361524071352429588e-01,1.000000007955042847e+00,0.000000000000000000e+00 +5.539986694026781322e+01,3.427028080958440341e+02,1.778619714634810944e-01,3.807220482027976693e+00,-1.328938911114254107e-01,-6.291102067065870718e-02,1.361524071352429588e-01,1.000000007942178026e+00,0.000000000000000000e+00 +5.540249352836461583e+01,3.427127199217958378e+02,1.765369407839992022e-01,3.807055240689925402e+00,-1.323938911114254102e-01,-6.028443255299468367e-02,1.361524071352429588e-01,1.000000007970094140e+00,0.000000000000000000e+00 +5.540512023046579060e+01,3.427226324090239586e+02,1.752168661829155427e-01,3.806896891444270459e+00,-1.318938911114254098e-01,-5.765773043088712191e-02,1.361524071352429588e-01,1.000000007984770622e+00,0.000000000000000000e+00 +5.540774704182557997e+01,3.427325455550503079e+02,1.739017479902487395e-01,3.806745435462994820e+00,-1.313938911114254093e-01,-5.503091905012133522e-02,1.361524071352429588e-01,1.000000008027711829e+00,0.000000000000000000e+00 +5.541037395769624396e+01,3.427424593573965694e+02,1.725915865347783518e-01,3.806600873868364765e+00,-1.308938911114254089e-01,-5.240400315836802464e-02,1.361524071352429588e-01,1.000000007978088190e+00,0.000000000000000000e+00 +5.541300097332813124e+01,3.427523738135843132e+02,1.712863821440447354e-01,3.806463207732894372e+00,-1.303938911114254084e-01,-4.977698750552427692e-02,1.361524071352429588e-01,1.000000008131567864e+00,0.000000000000000000e+00 +5.541562808396975726e+01,3.427622889211348820e+02,1.699861351443489876e-01,3.806332438079310432e+00,-1.298938911114254080e-01,-4.714987684253389016e-02,1.361524071352429588e-01,1.000000007977356109e+00,0.000000000000000000e+00 +5.541825528486791086e+01,3.427722046775695617e+02,1.686908458607528360e-01,3.806208565880521810e+00,-1.293938911114254076e-01,-4.452267592342037256e-02,1.361524071352429588e-01,1.000000008128198115e+00,0.000000000000000000e+00 +5.542088257126772533e+01,3.427821210804093539e+02,1.674005146170785829e-01,3.806091592059584805e+00,-1.288938911114254071e-01,-4.189538950224954567e-02,1.361524071352429588e-01,1.000000008132446494e+00,0.000000000000000000e+00 +5.542350993841277074e+01,3.427920381271752035e+02,1.661151417359090499e-01,3.805981517489677834e+00,-1.283938911114254067e-01,-3.926802233584008456e-02,1.361524071352429588e-01,1.000000008082290837e+00,0.000000000000000000e+00 +5.542613738154512504e+01,3.428019558153878279e+02,1.648347275385874666e-01,3.805878342994070351e+00,-1.278938911114254062e-01,-3.664057918224888216e-02,1.361524071352429588e-01,1.000000008163028697e+00,0.000000000000000000e+00 +5.542876489590548772e+01,3.428118741425678309e+02,1.635592723452173602e-01,3.805782069346097085e+00,-1.273938911114254058e-01,-3.401306480044041791e-02,1.361524071352429588e-01,1.000000008138232532e+00,0.000000000000000000e+00 +5.543139247673323666e+01,3.428217931062356456e+02,1.622887764746625272e-01,3.805692697269134506e+00,-1.268938911114254053e-01,-3.138548395130879437e-02,1.361524071352429588e-01,1.000000008121414652e+00,0.000000000000000000e+00 +5.543402011926653472e+01,3.428317127039114780e+02,1.610232402445469224e-01,3.805610227436575954e+00,-1.263938911114254049e-01,-2.875784139667218742e-02,1.361524071352429588e-01,1.000000008254150474e+00,0.000000000000000000e+00 +5.543664781874240788e+01,3.428416329331154202e+02,1.597626639712546037e-01,3.805534660471810771e+00,-1.258938911114254044e-01,-2.613014189911291862e-02,1.361524071352429588e-01,1.000000008191339829e+00,0.000000000000000000e+00 +5.543927557039682341e+01,3.428515537913674507e+02,1.585070479699296209e-01,3.805465996948205198e+00,-1.253938911114254040e-01,-2.350239022317007070e-02,1.361524071352429588e-01,1.000000008258717932e+00,0.000000000000000000e+00 +5.544190336946480357e+01,3.428614752761873774e+02,1.572563925544759600e-01,3.805404237389081512e+00,-1.248938911114254036e-01,-2.087459113349046658e-02,1.361524071352429588e-01,1.000000008166372467e+00,0.000000000000000000e+00 +5.544453121118047534e+01,3.428713973850947809e+02,1.560106980375574881e-01,3.805349382267703362e+00,-1.243938911114254031e-01,-1.824674939636011448e-02,1.361524071352429588e-01,1.000000008294813503e+00,0.000000000000000000e+00 +5.544715909077718408e+01,3.428813201156091850e+02,1.547699647305978143e-01,3.805301432007258455e+00,-1.238938911114254027e-01,-1.561886977785610121e-02,1.361524071352429588e-01,1.000000008280024888e+00,0.000000000000000000e+00 +5.544978700348756462e+01,3.428912434652498291e+02,1.535341929437802899e-01,3.805260386980847453e+00,-1.233938911114254022e-01,-1.299095704571667960e-02,1.361524071352429588e-01,1.000000008299499532e+00,0.000000000000000000e+00 +5.545241494454364073e+01,3.429011674315359528e+02,1.523033829860478139e-01,3.805226247511469317e+00,-1.228938911114254018e-01,-1.036301596783182309e-02,1.361524071352429588e-01,1.000000008300439225e+00,0.000000000000000000e+00 +5.545504290917689616e+01,3.429110920119865114e+02,1.510775351651028886e-01,3.805199013872011982e+00,-1.223938911114254013e-01,-7.735051312761927200e-03,1.361524071352429588e-01,1.000000008256885398e+00,0.000000000000000000e+00 +5.545767089261838123e+01,3.429210172041204032e+02,1.498566497874074810e-01,3.805178686285243028e+00,-1.218938911114254009e-01,-5.107067849580780583e-03,1.361524071352429588e-01,1.000000008362536663e+00,0.000000000000000000e+00 +5.546029889009877678e+01,3.429309430054562995e+02,1.486407271581828837e-01,3.805165264923802138e+00,-1.213938911114254005e-01,-2.479070347211781780e-03,1.361524071352429588e-01,1.000000008387674555e+00,0.000000000000000000e+00 +5.546292689684849364e+01,3.429408694135127575e+02,1.474297675814097985e-01,3.805158749910196647e+00,-1.208938911114254000e-01,1.489364245458684702e-04,1.361524071352429588e-01,1.000000008322136980e+00,0.000000000000000000e+00 +5.546555490809775790e+01,3.429507964258081643e+02,1.462237713598280864e-01,3.805159141316795779e+00,-1.203938911114253996e-01,2.776947695680712785e-03,1.361524071352429588e-01,1.000000008375279359e+00,0.000000000000000000e+00 +5.546818291907669618e+01,3.429607240398607928e+02,1.450227387949367952e-01,3.805166439165827974e+00,-1.198938911114253991e-01,5.404958696632499587e-03,1.361524071352429588e-01,1.000000008332956325e+00,0.000000000000000000e+00 +5.547081092501542798e+01,3.429706522531887458e+02,1.438266701869940489e-01,3.805180643429381337e+00,-1.193938911114253987e-01,8.032964657265793951e-03,1.361524071352429588e-01,1.000000008457743172e+00,0.000000000000000000e+00 +5.547343892114414388e+01,3.429805810633099554e+02,1.426355658350170197e-01,3.805201754029402750e+00,-1.188938911114253982e-01,1.066096080820937500e-02,1.361524071352429588e-01,1.000000008460132594e+00,0.000000000000000000e+00 +5.547606690269319074e+01,3.429905104677421832e+02,1.414494260367817891e-01,3.805229770837701864e+00,-1.183938911114253978e-01,1.328894237949193070e-02,1.361524071352429588e-01,1.000000008334489321e+00,0.000000000000000000e+00 +5.547869486489317126e+01,3.430004404640031339e+02,1.402682510888232648e-01,3.805264693675952881e+00,-1.178938911114253973e-01,1.591690460137464361e-02,1.361524071352429588e-01,1.000000008552025976e+00,0.000000000000000000e+00 +5.548132280297501495e+01,3.430103710496102849e+02,1.390920412864352085e-01,3.805306522315699880e+00,-1.173938911114253969e-01,1.854484270569087268e-02,1.361524071352429588e-01,1.000000008388988615e+00,0.000000000000000000e+00 +5.548395071217007057e+01,3.430203022220809999e+02,1.379207969236700693e-01,3.805355256478367032e+00,-1.168938911114253965e-01,2.117275192279237384e-02,1.361524071352429588e-01,1.000000008434583476e+00,0.000000000000000000e+00 +5.548657858771019846e+01,3.430302339789324719e+02,1.367545182933389003e-01,3.805410895835262153e+00,-1.163938911114253960e-01,2.380062748508619472e-02,1.361524071352429588e-01,1.000000008533357576e+00,0.000000000000000000e+00 +5.548920642482784871e+01,3.430401663176817237e+02,1.355932056870113867e-01,3.805473440007590913e+00,-1.158938911114253956e-01,2.642846462516424202e-02,1.361524071352429588e-01,1.000000008492653469e+00,0.000000000000000000e+00 +5.549183421875616062e+01,3.430500992358457211e+02,1.344368593950156510e-01,3.805542888566467497e+00,-1.153938911114253951e-01,2.905625857579199542e-02,1.361524071352429588e-01,1.000000008468591606e+00,0.000000000000000000e+00 +5.549446196472902670e+01,3.430600327309412592e+02,1.332854797064382812e-01,3.805619241032926592e+00,-1.148938911114253947e-01,3.168400457091146566e-02,1.361524071352429588e-01,1.000000008580417710e+00,0.000000000000000000e+00 +5.549708965798119920e+01,3.430699668004849059e+02,1.321390669091241921e-01,3.805702496877939378e+00,-1.143938911114253942e-01,3.431169784563065789e-02,1.361524071352429588e-01,1.000000008460427914e+00,0.000000000000000000e+00 +5.549971729374836826e+01,3.430799014419931723e+02,1.309976212896765413e-01,3.805792655522430845e+00,-1.138938911114253938e-01,3.693933363503035944e-02,1.361524071352429588e-01,1.000000008604799318e+00,0.000000000000000000e+00 +5.550234486726724725e+01,3.430898366529823988e+02,1.298611431334567579e-01,3.805889716337295337e+00,-1.133938911114253933e-01,3.956690717652043554e-02,1.361524071352429588e-01,1.000000008508587390e+00,0.000000000000000000e+00 +5.550497237377566506e+01,3.430997724309687555e+02,1.287296327245843752e-01,3.805993678643419642e+00,-1.128938911114253929e-01,4.219441370729549307e-02,1.361524071352429588e-01,1.000000008595531176e+00,0.000000000000000000e+00 +5.550759980851264430e+01,3.431097087734683555e+02,1.276030903459369759e-01,3.806104541711700762e+00,-1.123938911114253925e-01,4.482184846686126239e-02,1.361524071352429588e-01,1.000000008545929298e+00,0.000000000000000000e+00 +5.551022716671849366e+01,3.431196456779970845e+02,1.264815162791501635e-01,3.806222304763071662e+00,-1.118938911114253920e-01,4.744920669516732026e-02,1.361524071352429588e-01,1.000000008583375566e+00,0.000000000000000000e+00 +5.551285444363489319e+01,3.431295831420707145e+02,1.253649108046174521e-01,3.806346966968523482e+00,-1.113938911114253916e-01,5.007648363412063597e-02,1.361524071352429588e-01,1.000000008638789240e+00,0.000000000000000000e+00 +5.551548163450497952e+01,3.431395211632048472e+02,1.242532742014901964e-01,3.806478527449133065e+00,-1.108938911114253911e-01,5.270367452690258303e-02,1.361524071352429588e-01,1.000000008607989654e+00,0.000000000000000000e+00 +5.551810873457342410e+01,3.431494597389150272e+02,1.231466067476775367e-01,3.806616985276090048e+00,-1.103938911114253907e-01,5.533077461796267332e-02,1.361524071352429588e-01,1.000000008609361446e+00,0.000000000000000000e+00 +5.552073573908653259e+01,3.431593988667165718e+02,1.220449087198463289e-01,3.806762339470725287e+00,-1.098938911114253902e-01,5.795777915368911792e-02,1.361524071352429588e-01,1.000000008598161294e+00,0.000000000000000000e+00 +5.552336264329232307e+01,3.431693385441247415e+02,1.209481803934210897e-01,3.806914589004542382e+00,-1.093938911114253898e-01,6.058468338206602494e-02,1.361524071352429588e-01,1.000000008688568087e+00,0.000000000000000000e+00 +5.552598944244061130e+01,3.431792787686545694e+02,1.198564220425838850e-01,3.807073732799249655e+00,-1.088938911114253894e-01,6.321148255317654563e-02,1.361524071352429588e-01,1.000000008639187810e+00,0.000000000000000000e+00 +5.552861613178309597e+01,3.431892195378210317e+02,1.187696339402742884e-01,3.807239769726794787e+00,-1.083938911114253889e-01,6.583817191835443505e-02,1.361524071352429588e-01,1.000000008690078435e+00,0.000000000000000000e+00 +5.553124270657345107e+01,3.431991608491389343e+02,1.176878163581893261e-01,3.807412698609398571e+00,-1.078938911114253885e-01,6.846474673153421509e-02,1.361524071352429588e-01,1.000000008597732082e+00,0.000000000000000000e+00 +5.553386916206740409e+01,3.432091027001229122e+02,1.166109695667833929e-01,3.807592518219593547e+00,-1.073938911114253880e-01,7.109120224806639299e-02,1.361524071352429588e-01,1.000000008729717393e+00,0.000000000000000000e+00 +5.553649549352282122e+01,3.432190450882875439e+02,1.155390938352681834e-01,3.807779227280260859e+00,-1.068938911114253876e-01,7.371753372640775515e-02,1.361524071352429588e-01,1.000000008713251676e+00,0.000000000000000000e+00 +5.553912169619979267e+01,3.432289880111472371e+02,1.144721894316126226e-01,3.807972824464672890e+00,-1.063938911114253871e-01,7.634373642626204881e-02,1.361524071352429588e-01,1.000000008723162637e+00,0.000000000000000000e+00 +5.554174776536072500e+01,3.432389314662162292e+02,1.134102566225427960e-01,3.808173308396532342e+00,-1.058938911114253867e-01,7.896980561010330524e-02,1.361524071352429588e-01,1.000000008645401728e+00,0.000000000000000000e+00 +5.554437369627041932e+01,3.432488754510086437e+02,1.123532956735419086e-01,3.808380677650016644e+00,-1.053938911114253862e-01,8.159573654250212860e-02,1.361524071352429588e-01,1.000000008785826733e+00,0.000000000000000000e+00 +5.554699948419616362e+01,3.432588199630385475e+02,1.113013068488501872e-01,3.808594930749821916e+00,-1.048938911114253858e-01,8.422152449131317664e-02,1.361524071352429588e-01,1.000000008711490196e+00,0.000000000000000000e+00 +5.554962512440779676e+01,3.432687649998197799e+02,1.102542904114648392e-01,3.808816066171211379e+00,-1.043938911114253854e-01,8.684716472581985314e-02,1.361524071352429588e-01,1.000000008732358836e+00,0.000000000000000000e+00 +5.555225061217782212e+01,3.432787105588660665e+02,1.092122466231399691e-01,3.809044082340060200e+00,-1.038938911114253849e-01,8.947265251876965197e-02,1.361524071352429588e-01,1.000000008742602864e+00,0.000000000000000000e+00 +5.555487594278146446e+01,3.432886566376910196e+02,1.081751757443865092e-01,3.809278977632907015e+00,-1.033938911114253845e-01,9.209798314536681019e-02,1.361524071352429588e-01,1.000000008736323442e+00,0.000000000000000000e+00 +5.555750111149678361e+01,3.432986032338081372e+02,1.071430780344721778e-01,3.809520750377004106e+00,-1.028938911114253840e-01,9.472315188361901672e-02,1.361524071352429588e-01,1.000000008808176410e+00,0.000000000000000000e+00 +5.556012611360473130e+01,3.433085503447307474e+02,1.061159537514214102e-01,3.809769398850369804e+00,-1.023938911114253836e-01,9.734815401468553675e-02,1.361524071352429588e-01,1.000000008831723131e+00,0.000000000000000000e+00 +5.556275094438924356e+01,3.433184979679721209e+02,1.050938031520152610e-01,3.810024921281843113e+00,-1.018938911114253831e-01,9.997298482238083095e-02,1.361524071352429588e-01,1.000000008717702782e+00,0.000000000000000000e+00 +5.556537559913734015e+01,3.433284461010453015e+02,1.040766264917913630e-01,3.810287315851138334e+00,-1.013938911114253827e-01,1.025976395933560908e-01,1.361524071352429588e-01,1.000000008801525730e+00,0.000000000000000000e+00 +5.556800007313918144e+01,3.433383947414632757e+02,1.030644240250438992e-01,3.810556580688901462e+00,-1.008938911114253822e-01,1.052221136182975580e-01,1.361524071352429588e-01,1.000000008812407026e+00,0.000000000000000000e+00 +5.557062436168817499e+01,3.433483438867389168e+02,1.020571960048234639e-01,3.810832713876771027e+00,-1.003938911114253818e-01,1.078464021904190079e-01,1.361524071352429588e-01,1.000000008840981947e+00,0.000000000000000000e+00 +5.557324846008104657e+01,3.433582935343848703e+02,1.010549426829370628e-01,3.811115713447436271e+00,-9.989389111142538136e-02,1.104705006064937434e-01,1.361524071352429588e-01,1.000000008759649006e+00,0.000000000000000000e+00 +5.557587236361793259e+01,3.433682436819137820e+02,1.000576643099480162e-01,3.811405577384699317e+00,-9.939389111142538091e-02,1.130944041663651256e-01,1.361524071352429588e-01,1.000000008868214385e+00,0.000000000000000000e+00 +5.557849606760245109e+01,3.433781943268380701e+02,9.906536113517591668e-02,3.811702303623537347e+00,-9.889389111142538047e-02,1.157181081741511242e-01,1.361524071352429588e-01,1.000000008862531375e+00,0.000000000000000000e+00 +5.558111956734179415e+01,3.433881454666700961e+02,9.807803340669656034e-02,3.812005890050169210e+00,-9.839389111142538002e-02,1.183416079367424906e-01,1.361524071352429588e-01,1.000000008802646390e+00,0.000000000000000000e+00 +5.558374285814679894e+01,3.433980970989220509e+02,9.709568137134186316e-02,3.812316334502119375e+00,-9.789389111142537958e-02,1.209648987648410945e-01,1.361524071352429588e-01,1.000000008920228556e+00,0.000000000000000000e+00 +5.558636593533205428e+01,3.434080492211060687e+02,9.611830527469983343e-02,3.812633634768285873e+00,-9.739389111142537914e-02,1.235879759734925809e-01,1.361524071352429588e-01,1.000000008780203231e+00,0.000000000000000000e+00 +5.558898879421595041e+01,3.434180018307341129e+02,9.514590536111448837e-02,3.812957788589010910e+00,-9.689389111142537869e-02,1.262108348804197311e-01,1.361524071352429588e-01,1.000000008895011394e+00,0.000000000000000000e+00 +5.559161143012079265e+01,3.434279549253180335e+02,9.417848187368579871e-02,3.813288793656148368e+00,-9.639389111142537825e-02,1.288334708085899782e-01,1.361524071352429588e-01,1.000000008918067618e+00,0.000000000000000000e+00 +5.559423383837285826e+01,3.434379085023695097e+02,9.321603505426963310e-02,3.813626647613139298e+00,-9.589389111142537780e-02,1.314558790840441860e-01,1.361524071352429588e-01,1.000000008870902013e+00,0.000000000000000000e+00 +5.559685601430249591e+01,3.434478625594001642e+02,9.225856514347768877e-02,3.813971348055082977e+00,-9.539389111142537736e-02,1.340780550369439772e-01,1.361524071352429588e-01,1.000000008885904235e+00,0.000000000000000000e+00 +5.559947795324419673e+01,3.434578170939215056e+02,9.130607238067744991e-02,3.814322892528811959e+00,-9.489389111142537692e-02,1.366999940019439364e-01,1.361524071352429588e-01,1.000000008884116109e+00,0.000000000000000000e+00 +5.560209965053667958e+01,3.434677721034449291e+02,9.035855700399209045e-02,3.814681278532969344e+00,-9.439389111142537647e-02,1.393216913177187377e-01,1.361524071352429588e-01,1.000000008963577436e+00,0.000000000000000000e+00 +5.560472110152296921e+01,3.434777275854816025e+02,8.941601925030044640e-02,3.815046503518086052e+00,-9.389389111142537603e-02,1.419431423275083481e-01,1.361524071352429588e-01,1.000000008883282554e+00,0.000000000000000000e+00 +5.560734230155048863e+01,3.434876835375426936e+02,8.847845935523696026e-02,3.815418564886660757e+00,-9.339389111142537558e-02,1.445643423783101456e-01,1.361524071352429588e-01,1.000000008903972004e+00,0.000000000000000000e+00 +5.560996324597111595e+01,3.434976399571392562e+02,8.754587755319159781e-02,3.815797459993238938e+00,-9.289389111142537514e-02,1.471852868222749133e-01,1.361524071352429588e-01,1.000000008949073704e+00,0.000000000000000000e+00 +5.561258393014129098e+01,3.435075968417821173e+02,8.661827407730980644e-02,3.816183186144496808e+00,-9.239389111142537470e-02,1.498059710159030666e-01,1.361524071352429588e-01,1.000000008928411344e+00,0.000000000000000000e+00 +5.561520434942207913e+01,3.435175541889821034e+02,8.569564915949245965e-02,3.816575740599324362e+00,-9.189389111142537425e-02,1.524263903200893389e-01,1.361524071352429588e-01,1.000000008933229489e+00,0.000000000000000000e+00 +5.561782449917926385e+01,3.435275119962498707e+02,8.477800303039577379e-02,3.816975120568909752e+00,-9.139389111142537381e-02,1.550465401006782540e-01,1.361524071352429588e-01,1.000000008978437549e+00,0.000000000000000000e+00 +5.562044437478341052e+01,3.435374702610959616e+02,8.386533591943126642e-02,3.817381323216826328e+00,-9.089389111142537336e-02,1.576664157283438339e-01,1.361524071352429588e-01,1.000000008938674911e+00,0.000000000000000000e+00 +5.562306397160995175e+01,3.435474289810308051e+02,8.295764805476571468e-02,3.817794345659120570e+00,-9.039389111142537292e-02,1.602860125783016898e-01,1.361524071352429588e-01,1.000000009002240953e+00,0.000000000000000000e+00 +5.562568328503927972e+01,3.435573881535647160e+02,8.205493966332108591e-02,3.818214184964400459e+00,-8.989389111142537248e-02,1.629053260312100515e-01,1.361524071352429588e-01,1.000000008960136411e+00,0.000000000000000000e+00 +5.562830231045681018e+01,3.435673477762078960e+02,8.115721097077448210e-02,3.818640838153927408e+00,-8.939389111142537203e-02,1.655243514722080922e-01,1.361524071352429588e-01,1.000000008983673139e+00,0.000000000000000000e+00 +5.563092104325306764e+01,3.435773078464704327e+02,8.026446220155805666e-02,3.819074302201706850e+00,-8.889389111142537159e-02,1.681430842919909296e-01,1.361524071352429588e-01,1.000000008978148003e+00,0.000000000000000000e+00 +5.563353947882375650e+01,3.435872683618623569e+02,7.937669357885900057e-02,3.819514574034582832e+00,-8.839389111142537114e-02,1.707615198861914541e-01,1.361524071352429588e-01,1.000000008972204979e+00,0.000000000000000000e+00 +5.563615761256985337e+01,3.435972293198934722e+02,7.849390532461947290e-02,3.819961650532332165e+00,-8.789389111142537070e-02,1.733796536557817014e-01,1.361524071352429588e-01,1.000000008989323508e+00,0.000000000000000000e+00 +5.563877543989767815e+01,3.436071907180735820e+02,7.761609765953651763e-02,3.820415528527760785e+00,-8.739389111142537026e-02,1.759974810071373574e-01,1.361524071352429588e-01,1.000000009048922056e+00,0.000000000000000000e+00 +5.564139295621895798e+01,3.436171525539123763e+02,7.674327080306204973e-02,3.820876204806801457e+00,-8.689389111142536981e-02,1.786149973521048984e-01,1.361524071352429588e-01,1.000000008972650845e+00,0.000000000000000000e+00 +5.564401015695093378e+01,3.436271148249193175e+02,7.587542497340278580e-02,3.821343676108612808e+00,-8.639389111142536937e-02,1.812321981075614985e-01,1.361524071352429588e-01,1.000000009098807485e+00,0.000000000000000000e+00 +5.564662703751640294e+01,3.436370775286038679e+02,7.501256038752017463e-02,3.821817939125678354e+00,-8.589389111142536892e-02,1.838490786968445256e-01,1.361524071352429588e-01,1.000000008921433814e+00,0.000000000000000000e+00 +5.564924359334383297e+01,3.436470406624753764e+02,7.415467726113036950e-02,3.822298990503910421e+00,-8.539389111142536848e-02,1.864656345476190524e-01,1.361524071352429588e-01,1.000000009102106180e+00,0.000000000000000000e+00 +5.565185981986741126e+01,3.436570042240430212e+02,7.330177580870413101e-02,3.822786826842749619e+00,-8.489389111142536803e-02,1.890818610950097678e-01,1.361524071352429588e-01,1.000000009005885371e+00,0.000000000000000000e+00 +5.565447571252713033e+01,3.436669682108159236e+02,7.245385624346682707e-02,3.823281444695273645e+00,-8.439389111142536759e-02,1.916977537782849905e-01,1.361524071352429588e-01,1.000000009037992355e+00,0.000000000000000000e+00 +5.565709126676885887e+01,3.436769326203030914e+02,7.161091877739834965e-02,3.823782840568298536e+00,-8.389389111142536715e-02,1.943133080436542648e-01,1.361524071352429588e-01,1.000000009087705255e+00,0.000000000000000000e+00 +5.565970647804443416e+01,3.436868974500134186e+02,7.077296362123304541e-02,3.824291010922488354e+00,-8.339389111142536670e-02,1.969285193429943792e-01,1.361524071352429588e-01,1.000000008983414679e+00,0.000000000000000000e+00 +5.566232134181171176e+01,3.436968626974557424e+02,6.993999098445971563e-02,3.824805952172462664e+00,-8.289389111142536626e-02,1.995433831337658781e-01,1.361524071352429588e-01,1.000000009143428903e+00,0.000000000000000000e+00 +5.566493585353467211e+01,3.437068283601386725e+02,6.911200107532150527e-02,3.825327660686904885e+00,-8.239389111142536581e-02,2.021578948806309339e-01,1.361524071352429588e-01,1.000000009018148672e+00,0.000000000000000000e+00 +5.566755000868346315e+01,3.437167944355708755e+02,6.828899410081588905e-02,3.825856132788675978e+00,-8.189389111142536537e-02,2.047720500529974785e-01,1.361524071352429588e-01,1.000000009104973442e+00,0.000000000000000000e+00 +5.567016380273449982e+01,3.437267609212607908e+02,6.747097026669460207e-02,3.826391364754922808e+00,-8.139389111142536493e-02,2.073858441278313147e-01,1.361524071352429588e-01,1.000000009000259871e+00,0.000000000000000000e+00 +5.567277723117052091e+01,3.437367278147167440e+02,6.665792977746359815e-02,3.826933352817194933e+00,-8.089389111142536448e-02,2.099992725873749688e-01,1.361524071352429588e-01,1.000000009155326941e+00,0.000000000000000000e+00 +5.567539028948068136e+01,3.437466951134471174e+02,6.584987283638300826e-02,3.827482093161556520e+00,-8.039389111142536404e-02,2.126123309214564272e-01,1.361524071352429588e-01,1.000000009057181005e+00,0.000000000000000000e+00 +5.567800297316060210e+01,3.437566628149600092e+02,6.504679964546705717e-02,3.828037581928705357e+00,-7.989389111142536359e-02,2.152250146250427876e-01,1.361524071352429588e-01,1.000000009115410426e+00,0.000000000000000000e+00 +5.568061527771246944e+01,3.437666309167635177e+02,6.424871040548403578e-02,3.828599815214086544e+00,-7.939389111142536315e-02,2.178373192007245496e-01,1.361524071352429588e-01,1.000000009102632648e+00,0.000000000000000000e+00 +5.568322719864509196e+01,3.437765994163656273e+02,6.345560531595624554e-02,3.829168789068013723e+00,-7.889389111142536271e-02,2.204492401571244153e-01,1.361524071352429588e-01,1.000000009131285061e+00,0.000000000000000000e+00 +5.568583873147397867e+01,3.437865683112742090e+02,6.266748457515995685e-02,3.829744499495787213e+00,-7.839389111142536226e-02,2.230607730098579100e-01,1.361524071352429588e-01,1.000000009069187401e+00,0.000000000000000000e+00 +5.568844987172141003e+01,3.437965375989970198e+02,6.188434838012536049e-02,3.830326942457815687e+00,-7.789389111142536182e-02,2.256719132809669737e-01,1.361524071352429588e-01,1.000000009126871259e+00,0.000000000000000000e+00 +5.569106061491650195e+01,3.438065072770417601e+02,6.110619692663649127e-02,3.830916113869737405e+00,-7.739389111142536137e-02,2.282826564998870766e-01,1.361524071352429588e-01,1.000000009077042229e+00,0.000000000000000000e+00 +5.569367095659529809e+01,3.438164773429159595e+02,6.033303040923121419e-02,3.831512009602545010e+00,-7.689389111142536093e-02,2.308929982023758543e-01,1.361524071352429588e-01,1.000000009233283027e+00,0.000000000000000000e+00 +5.569628089230081969e+01,3.438264477941271480e+02,5.956484902120114805e-02,3.832114625482708536e+00,-7.639389111142536049e-02,2.335029339319966424e-01,1.361524071352429588e-01,1.000000009017176561e+00,0.000000000000000000e+00 +5.569889041758315074e+01,3.438364186281827415e+02,5.880165295459164471e-02,3.832723957292303307e+00,-7.589389111142536004e-02,2.361124592378614495e-01,1.361524071352429588e-01,1.000000009176370552e+00,0.000000000000000000e+00 +5.570149952799950910e+01,3.438463898425899856e+02,5.804344240020171269e-02,3.833340000769132949e+00,-7.539389111142535960e-02,2.387215696781626040e-01,1.361524071352429588e-01,1.000000009177663296e+00,0.000000000000000000e+00 +5.570410821911430332e+01,3.438563614348560691e+02,5.729021754758398255e-02,3.833962751606862618e+00,-7.489389111142535915e-02,2.413302608169006769e-01,1.361524071352429588e-01,1.000000009164359271e+00,0.000000000000000000e+00 +5.570671648649921792e+01,3.438663334024881237e+02,5.654197858504466517e-02,3.834592205455144676e+00,-7.439389111142535871e-02,2.439385282257200416e-01,1.361524071352429588e-01,1.000000009109995869e+00,0.000000000000000000e+00 +5.570932432573327731e+01,3.438763057429931678e+02,5.579872569964350326e-02,3.835228357919750142e+00,-7.389389111142535826e-02,2.465463674835357277e-01,1.361524071352429588e-01,1.000000009145884494e+00,0.000000000000000000e+00 +5.571193173240290974e+01,3.438862784538781057e+02,5.506045907719370885e-02,3.835871204562700143e+00,-7.339389111142535782e-02,2.491537741770143144e-01,1.361524071352429588e-01,1.000000009170610493e+00,0.000000000000000000e+00 +5.571453870210202552e+01,3.438962515326497282e+02,5.432717890226193558e-02,3.836520740902399584e+00,-7.289389111142535738e-02,2.517607439000361103e-01,1.361524071352429588e-01,1.000000009177745897e+00,0.000000000000000000e+00 +5.571714523043208089e+01,3.439062249768147694e+02,5.359888535816822314e-02,3.837176962413770376e+00,-7.239389111142535693e-02,2.543672722540116782e-01,1.361524071352429588e-01,1.000000009126610356e+00,0.000000000000000000e+00 +5.571975131300214201e+01,3.439161987838799064e+02,5.287557862698594874e-02,3.837839864528386435e+00,-7.189389111142535649e-02,2.569733548478609908e-01,1.361524071352429588e-01,1.000000009205179952e+00,0.000000000000000000e+00 +5.572235694542897022e+01,3.439261729513516457e+02,5.215725888954179934e-02,3.838509442634609581e+00,-7.139389111142535604e-02,2.595789872986773439e-01,1.361524071352429588e-01,1.000000009242992594e+00,0.000000000000000000e+00 +5.572496212333707177e+01,3.439361474767364939e+02,5.144392632541570226e-02,3.839185692077728085e+00,-7.089389111142535560e-02,2.621841652308609105e-01,1.361524071352429588e-01,1.000000009104339505e+00,0.000000000000000000e+00 +5.572756684235877600e+01,3.439461223575407871e+02,5.073558111294079048e-02,3.839868608160093899e+00,-7.039389111142535516e-02,2.647888842762768924e-01,1.361524071352429588e-01,1.000000009213924956e+00,0.000000000000000000e+00 +5.573017109813428505e+01,3.439560975912708045e+02,5.003222342920336796e-02,3.840558186141261210e+00,-6.989389111142535471e-02,2.673931400757821875e-01,1.361524071352429588e-01,1.000000009183283467e+00,0.000000000000000000e+00 +5.573277488631176624e+01,3.439660731754327685e+02,4.933385345004285411e-02,3.841254421238129879e+00,-6.939389111142535427e-02,2.699969282771738643e-01,1.361524071352429588e-01,1.000000009252604460e+00,0.000000000000000000e+00 +5.573537820254739472e+01,3.439760491075327309e+02,4.864047135005173522e-02,3.841957308625084444e+00,-6.889389111142535382e-02,2.726002445368926885e-01,1.361524071352429588e-01,1.000000009178678262e+00,0.000000000000000000e+00 +5.573798104250543872e+01,3.439860253850767435e+02,4.795207730257553674e-02,3.842666843434138446e+00,-6.839389111142535338e-02,2.752030845188302988e-01,1.361524071352429588e-01,1.000000009153479308e+00,0.000000000000000000e+00 +5.574058340185831639e+01,3.439960020055707446e+02,4.726867147971276772e-02,3.843383020755076540e+00,-6.789389111142535294e-02,2.778054438955276373e-01,1.361524071352429588e-01,1.000000009281618585e+00,0.000000000000000000e+00 +5.574318527628665265e+01,3.440059789665205585e+02,4.659025405231487921e-02,3.844105835635600599e+00,-6.739389111142535249e-02,2.804073183480123577e-01,1.361524071352429588e-01,1.000000009187944183e+00,0.000000000000000000e+00 +5.574578666147935735e+01,3.440159562654319529e+02,4.591682518998622259e-02,3.844835283081476263e+00,-6.689389111142535205e-02,2.830087035646152716e-01,1.361524071352429588e-01,1.000000009199431661e+00,0.000000000000000000e+00 +5.574838755313367500e+01,3.440259338998105818e+02,4.524838506108400799e-02,3.845571358056677269e+00,-6.639389111142535160e-02,2.856095952428615581e-01,1.361524071352429588e-01,1.000000009231928777e+00,0.000000000000000000e+00 +5.575098794695527005e+01,3.440359118671620990e+02,4.458493383271826954e-02,3.846314055483535554e+00,-6.589389111142535116e-02,2.882099890884649573e-01,1.361524071352429588e-01,1.000000009250143096e+00,0.000000000000000000e+00 +5.575358783865827661e+01,3.440458901649919312e+02,4.392647167075180298e-02,3.847063370242889579e+00,-6.539389111142535072e-02,2.908098808155185067e-01,1.361524071352429588e-01,1.000000009269694345e+00,0.000000000000000000e+00 +5.575618722396535532e+01,3.440558687908055617e+02,4.327299873980015171e-02,3.847819297174233988e+00,-6.489389111142535027e-02,2.934092661466901064e-01,1.361524071352429588e-01,1.000000009161043257e+00,0.000000000000000000e+00 +5.575878609860776436e+01,3.440658477421083035e+02,4.262451520323154441e-02,3.848581831075870596e+00,-6.439389111142534983e-02,2.960081408129079938e-01,1.361524071352429588e-01,1.000000009308575688e+00,0.000000000000000000e+00 +5.576138445832543056e+01,3.440758270164054693e+02,4.198102122316686030e-02,3.849350966705059385e+00,-6.389389111142534938e-02,2.986065005547587359e-01,1.361524071352429588e-01,1.000000009231286846e+00,0.000000000000000000e+00 +5.576398229886699198e+01,3.440858066112022016e+02,4.134251696047959446e-02,3.850126698778173928e+00,-6.339389111142534894e-02,3.012043411203002563e-01,1.361524071352429588e-01,1.000000009228011688e+00,0.000000000000000000e+00 +5.576657961598987612e+01,3.440957865240035858e+02,4.070900257479580925e-02,3.850909021970851942e+00,-6.289389111142534849e-02,3.038016582671498877e-01,1.361524071352429588e-01,1.000000009261120759e+00,0.000000000000000000e+00 +5.576917640546034960e+01,3.441057667523146506e+02,4.008047822449409270e-02,3.851697930918152046e+00,-6.239389111142534805e-02,3.063984477616711888e-01,1.361524071352429588e-01,1.000000009286677649e+00,0.000000000000000000e+00 +5.577177266305358927e+01,3.441157472936403678e+02,3.945694406670553073e-02,3.852493420214709197e+00,-6.189389111142534761e-02,3.089947053790184084e-01,1.361524071352429588e-01,1.000000009189918826e+00,0.000000000000000000e+00 +5.577436838455373191e+01,3.441257281454855956e+02,3.883840025731365858e-02,3.853295484414891003e+00,-6.139389111142534716e-02,3.115904269030130846e-01,1.361524071352429588e-01,1.000000009314182536e+00,0.000000000000000000e+00 +5.577696356575393821e+01,3.441357093053550784e+02,3.822484695095443308e-02,3.854104118032954496e+00,-6.089389111142534672e-02,3.141856081273931012e-01,1.361524071352429588e-01,1.000000009276009516e+00,0.000000000000000000e+00 +5.577955820245646379e+01,3.441456907707535606e+02,3.761628430101617016e-02,3.854919315543206881e+00,-6.039389111142534627e-02,3.167802448539857041e-01,1.361524071352429588e-01,1.000000009284819802e+00,0.000000000000000000e+00 +5.578215229047269474e+01,3.441556725391856730e+02,3.701271245963953099e-02,3.855741071380162310e+00,-5.989389111142534583e-02,3.193743328943054460e-01,1.361524071352429588e-01,1.000000009221520436e+00,0.000000000000000000e+00 +5.578474582562323292e+01,3.441656546081559895e+02,3.641413157771747344e-02,3.856569379938703523e+00,-5.939389111142534539e-02,3.219678680687604322e-01,1.361524071352429588e-01,1.000000009365769271e+00,0.000000000000000000e+00 +5.578733880373793141e+01,3.441756369751689704e+02,3.582054180489521039e-02,3.857404235574242168e+00,-5.889389111142534494e-02,3.245608462077448353e-01,1.361524071352429588e-01,1.000000009209027541e+00,0.000000000000000000e+00 +5.578993122065596566e+01,3.441856196377290189e+02,3.523194328957018895e-02,3.858245632602882669e+00,-5.839389111142534450e-02,3.271532631496528176e-01,1.361524071352429588e-01,1.000000009305307858e+00,0.000000000000000000e+00 +5.579252307222588314e+01,3.441956025933404817e+02,3.464833617889202799e-02,3.859093565301581652e+00,-5.789389111142534405e-02,3.297451147436911145e-01,1.361524071352429588e-01,1.000000009357108643e+00,0.000000000000000000e+00 +5.579511435430567445e+01,3.442055858395075916e+02,3.406972061876251123e-02,3.859948027908315371e+00,-5.739389111142534361e-02,3.323363968477283104e-01,1.361524071352429588e-01,1.000000009207399954e+00,0.000000000000000000e+00 +5.579770506276280884e+01,3.442155693737345814e+02,3.349609675383551782e-02,3.860809014622242241e+00,-5.689389111142534317e-02,3.349271053287160571e-01,1.361524071352429588e-01,1.000000009371276422e+00,0.000000000000000000e+00 +5.580029519347430522e+01,3.442255531935255704e+02,3.292746472751701542e-02,3.861676519603867153e+00,-5.639389111142534272e-02,3.375172360644865255e-01,1.361524071352429588e-01,1.000000009250753275e+00,0.000000000000000000e+00 +5.580288474232678908e+01,3.442355372963845639e+02,3.236382468196500467e-02,3.862550536975211113e+00,-5.589389111142534228e-02,3.401067849409246113e-01,1.361524071352429588e-01,1.000000009320237693e+00,0.000000000000000000e+00 +5.580547370521653505e+01,3.442455216798155675e+02,3.180517675808949146e-02,3.863431060819974228e+00,-5.539389111142534183e-02,3.426957478548010583e-01,1.361524071352429588e-01,1.000000009340868967e+00,0.000000000000000000e+00 +5.580806207804953800e+01,3.442555063413224730e+02,3.125152109555245916e-02,3.864318085183706675e+00,-5.489389111142534139e-02,3.452841207119800582e-01,1.361524071352429588e-01,1.000000009288734892e+00,0.000000000000000000e+00 +5.581064985674154855e+01,3.442654912784091152e+02,3.070285783276781658e-02,3.865211604073975682e+00,-5.439389111142534095e-02,3.478718994280305399e-01,1.361524071352429588e-01,1.000000009290720193e+00,0.000000000000000000e+00 +5.581323703721815122e+01,3.442754764885792724e+02,3.015918710690138060e-02,3.866111611460534725e+00,-5.389389111142534050e-02,3.504590799286704250e-01,1.361524071352429588e-01,1.000000009360813236e+00,0.000000000000000000e+00 +5.581582361541479287e+01,3.442854619693366089e+02,2.962050905387082766e-02,3.867018101275494502e+00,-5.339389111142534006e-02,3.530456581495279300e-01,1.361524071352429588e-01,1.000000009268597001e+00,0.000000000000000000e+00 +5.581840958727686086e+01,3.442954477181847892e+02,2.908682380834566941e-02,3.867931067413493906e+00,-5.289389111142533961e-02,3.556316300355626958e-01,1.361524071352429588e-01,1.000000009403974044e+00,0.000000000000000000e+00 +5.582099494875971146e+01,3.443054337326273640e+02,2.855813150374721110e-02,3.868850503731870116e+00,-5.239389111142533917e-02,3.582169915427228513e-01,1.361524071352429588e-01,1.000000009317777883e+00,0.000000000000000000e+00 +5.582357969582873380e+01,3.443154200101678271e+02,2.803443227224853077e-02,3.869776404050833563e+00,-5.189389111142533872e-02,3.608017386358275957e-01,1.361524071352429588e-01,1.000000009317498995e+00,0.000000000000000000e+00 +5.582616382445940673e+01,3.443254065483096156e+02,2.751572624477443066e-02,3.870708762153638016e+00,-5.139389111142533828e-02,3.633858672905754816e-01,1.361524071352429588e-01,1.000000009272944412e+00,0.000000000000000000e+00 +5.582874733063734141e+01,3.443353933445560529e+02,2.700201355100141642e-02,3.871647571786756448e+00,-5.089389111142533784e-02,3.659693734924643338e-01,1.361524071352429588e-01,1.000000009415747293e+00,0.000000000000000000e+00 +5.583133021035833110e+01,3.443453803964105191e+02,2.649329431935765894e-02,3.872592826660054666e+00,-5.039389111142533739e-02,3.685522532377771276e-01,1.361524071352429588e-01,1.000000009342529861e+00,0.000000000000000000e+00 +5.583391245962842220e+01,3.443553677013761671e+02,2.598956867702295961e-02,3.873544520446968065e+00,-4.989389111142533695e-02,3.711345025319922053e-01,1.361524071352429588e-01,1.000000009347796537e+00,0.000000000000000000e+00 +5.583649407446393553e+01,3.443653552569562066e+02,2.549083674992872958e-02,3.874502646784674820e+00,-4.939389111142533650e-02,3.737161173916360712e-01,1.361524071352429588e-01,1.000000009360584308e+00,0.000000000000000000e+00 +5.583907505089153034e+01,3.443753430606537904e+02,2.499709866275794806e-02,3.875467199274274410e+00,-4.889389111142533606e-02,3.762970938433890522e-01,1.361524071352429588e-01,1.000000009278521063e+00,0.000000000000000000e+00 +5.584165538494825398e+01,3.443853311099719008e+02,2.450835453894513460e-02,3.876438171480964368e+00,-4.839389111142533562e-02,3.788774279240536558e-01,1.361524071352429588e-01,1.000000009436546211e+00,0.000000000000000000e+00 +5.584423507268159170e+01,3.443953194024135769e+02,2.402460450067631786e-02,3.877415556934217467e+00,-4.789389111142533517e-02,3.814571156817317399e-01,1.361524071352429588e-01,1.000000009341076135e+00,0.000000000000000000e+00 +5.584681411014950214e+01,3.444053079354817442e+02,2.354584866888900438e-02,3.878399349127962470e+00,-4.739389111142533473e-02,3.840361531737351841e-01,1.361524071352429588e-01,1.000000009339258700e+00,0.000000000000000000e+00 +5.584939249342048839e+01,3.444152967066792144e+02,2.307208716327214734e-02,3.879389541520759987e+00,-4.689389111142533428e-02,3.866145364688027830e-01,1.361524071352429588e-01,1.000000009353181118e+00,0.000000000000000000e+00 +5.585197021857362643e+01,3.444252857135088561e+02,2.260332010226612232e-02,3.880386127535984553e+00,-4.639389111142533384e-02,3.891922616460510853e-01,1.361524071352429588e-01,1.000000009415217272e+00,0.000000000000000000e+00 +5.585454728169861482e+01,3.444352749534733675e+02,2.213954760306269254e-02,3.881389100562004479e+00,-4.589389111142533340e-02,3.917693247953057956e-01,1.361524071352429588e-01,1.000000009335091367e+00,0.000000000000000000e+00 +5.585712367889583163e+01,3.444452644240755035e+02,2.168076978160498117e-02,3.882398453952363049e+00,-4.539389111142533295e-02,3.943457220165745847e-01,1.361524071352429588e-01,1.000000009437798987e+00,0.000000000000000000e+00 +5.585969940627636987e+01,3.444552541228178484e+02,2.122698675258744005e-02,3.883414181025958811e+00,-4.489389111142533251e-02,3.969214494214208799e-01,1.361524071352429588e-01,1.000000009293416481e+00,0.000000000000000000e+00 +5.586227445996208019e+01,3.444652440472029866e+02,2.077819862945582546e-02,3.884436275067229882e+00,-4.439389111142533206e-02,3.994965031310646619e-01,1.361524071352429588e-01,1.000000009459437678e+00,0.000000000000000000e+00 +5.586484883608563479e+01,3.444752341947334457e+02,2.033440552440716337e-02,3.885464729326333799e+00,-4.389389111142533162e-02,4.020708792789707831e-01,1.361524071352429588e-01,1.000000009339274021e+00,0.000000000000000000e+00 +5.586742253079054876e+01,3.444852245629116396e+02,1.989560754838972864e-02,3.886499537019334483e+00,-4.339389111142533118e-02,4.046445740079219200e-01,1.361524071352429588e-01,1.000000009394503175e+00,0.000000000000000000e+00 +5.586999554023124404e+01,3.444952151492400390e+02,1.946180481110301383e-02,3.887540691328382092e+00,-4.289389111142533073e-02,4.072175834727871369e-01,1.361524071352429588e-01,1.000000009404413470e+00,0.000000000000000000e+00 +5.587256786057307778e+01,3.445052059512209439e+02,1.903299742099770139e-02,3.888588185401900432e+00,-4.239389111142533029e-02,4.097899038388093662e-01,1.361524071352429588e-01,1.000000009338424922e+00,0.000000000000000000e+00 +5.587513948799239216e+01,3.445151969663567115e+02,1.860918548527563596e-02,3.889642012354770362e+00,-4.189389111142532984e-02,4.123615312821383161e-01,1.361524071352429588e-01,1.000000009425743519e+00,0.000000000000000000e+00 +5.587771041867656407e+01,3.445251881921495851e+02,1.819036910988980002e-02,3.890702165268514978e+00,-4.139389111142532940e-02,4.149324619905413458e-01,1.361524071352429588e-01,1.000000009418070768e+00,0.000000000000000000e+00 +5.588028064882403356e+01,3.445351796261016943e+02,1.777654839954428273e-02,3.891768637191487024e+00,-4.089389111142532895e-02,4.175026921622179699e-01,1.361524071352429588e-01,1.000000009396740719e+00,0.000000000000000000e+00 +5.588285017464436066e+01,3.445451712657152257e+02,1.736772345769426254e-02,3.892841421139053626e+00,-4.039389111142532851e-02,4.200722180066895350e-01,1.361524071352429588e-01,1.000000009371885712e+00,0.000000000000000000e+00 +5.588541899235825383e+01,3.445551631084922519e+02,1.696389438654596904e-02,3.893920510093783705e+00,-3.989389111142532807e-02,4.226410357446576116e-01,1.361524071352429588e-01,1.000000009485703112e+00,0.000000000000000000e+00 +5.588798709819761967e+01,3.445651551519348459e+02,1.656506128705667255e-02,3.895005897005635376e+00,-3.939389111142532762e-02,4.252091416083841890e-01,1.361524071352429588e-01,1.000000009340387574e+00,0.000000000000000000e+00 +5.589055448840559848e+01,3.445751473935449667e+02,1.617122425893464249e-02,3.896097574792144691e+00,-3.889389111142532718e-02,4.277765318403454753e-01,1.361524071352429588e-01,1.000000009414254043e+00,0.000000000000000000e+00 +5.589312115923661395e+01,3.445851398308245734e+02,1.578238340063913350e-02,3.897195536338611266e+00,-3.839389111142532673e-02,4.303432026955218981e-01,1.361524071352429588e-01,1.000000009446842864e+00,0.000000000000000000e+00 +5.589568710695639453e+01,3.445951324612755684e+02,1.539853880938036115e-02,3.898299774498290127e+00,-3.789389111142532629e-02,4.329091504395407575e-01,1.361524071352429588e-01,1.000000009383074540e+00,0.000000000000000000e+00 +5.589825232784203024e+01,3.446051252823997402e+02,1.501969058111946899e-02,3.899410282092579116e+00,-3.739389111142532585e-02,4.354743713492430501e-01,1.361524071352429588e-01,1.000000009443397397e+00,0.000000000000000000e+00 +5.590081681818200110e+01,3.446151182916989342e+02,1.464583881056851292e-02,3.900527051911208076e+00,-3.689389111142532540e-02,4.380388617134289841e-01,1.361524071352429588e-01,1.000000009382379540e+00,0.000000000000000000e+00 +5.590338057427621976e+01,3.446251114866748821e+02,1.427698359119043345e-02,3.901650076712430248e+00,-3.639389111142532496e-02,4.406026178317012376e-01,1.361524071352429588e-01,1.000000009435933812e+00,0.000000000000000000e+00 +5.590594359243607414e+01,3.446351048648292590e+02,1.391312501519903315e-02,3.902779349223211014e+00,-3.589389111142532451e-02,4.431656360157372188e-01,1.361524071352429588e-01,1.000000009444572235e+00,0.000000000000000000e+00 +5.590850586898444874e+01,3.446450984236637396e+02,1.355426317355895582e-02,3.903914862139420183e+00,-3.539389111142532407e-02,4.457279125883126247e-01,1.361524071352429588e-01,1.000000009463227757e+00,0.000000000000000000e+00 +5.591106740025578148e+01,3.446550921606799420e+02,1.320039815598565876e-02,3.905056608126022066e+00,-3.489389111142532363e-02,4.482894438838880835e-01,1.361524071352429588e-01,1.000000009424619307e+00,0.000000000000000000e+00 +5.591362818259609213e+01,3.446650860733794275e+02,1.285153005094539364e-02,3.906204579817267319e+00,-3.439389111142532318e-02,4.508502262483324863e-01,1.361524071352429588e-01,1.000000009411645241e+00,0.000000000000000000e+00 +5.591618821236301073e+01,3.446750801592637572e+02,1.250765894565518573e-02,3.907358769816884347e+00,-3.389389111142532274e-02,4.534102560393436510e-01,1.361524071352429588e-01,1.000000009388304578e+00,0.000000000000000000e+00 +5.591874748592582023e+01,3.446850744158343787e+02,1.216878492608280959e-02,3.908519170698272038e+00,-3.339389111142532229e-02,4.559695296261793152e-01,1.361524071352429588e-01,1.000000009540079615e+00,0.000000000000000000e+00 +5.592130599966549198e+01,3.446950688405926826e+02,1.183490807694676829e-02,3.909685775004692054e+00,-3.289389111142532185e-02,4.585280433902589881e-01,1.361524071352429588e-01,1.000000009325478167e+00,0.000000000000000000e+00 +5.592386374997472132e+01,3.447050634310401165e+02,1.150602848171627252e-02,3.910858575249462898e+00,-3.239389111142532141e-02,4.610857937233385773e-01,1.361524071352429588e-01,1.000000009513572818e+00,0.000000000000000000e+00 +5.592642073325795593e+01,3.447150581846780142e+02,1.118214622261121984e-02,3.912037563916149541e+00,-3.189389111142532096e-02,4.636427770308972907e-01,1.361524071352429588e-01,1.000000009470910944e+00,0.000000000000000000e+00 +5.592897694593143143e+01,3.447250530990077095e+02,1.086326138060217210e-02,3.913222733458761926e+00,-3.139389111142532052e-02,4.661989897285838125e-01,1.361524071352429588e-01,1.000000009402586931e+00,0.000000000000000000e+00 +5.593153238442321395e+01,3.447350481715304227e+02,1.054937403541033811e-02,3.914414076301944601e+00,-3.089389111142532007e-02,4.687544282443943389e-01,1.361524071352429588e-01,1.000000009472216345e+00,0.000000000000000000e+00 +5.593408704517322150e+01,3.447450433997474306e+02,1.024048426550755279e-02,3.915611584841172110e+00,-3.039389111142531963e-02,4.713090890185987480e-01,1.361524071352429588e-01,1.000000009462713058e+00,0.000000000000000000e+00 +5.593664092463325943e+01,3.447550387811598966e+02,9.936592148116258141e-03,3.916815251442944401e+00,-2.989389111142531918e-02,4.738629685028001304e-01,1.361524071352429588e-01,1.000000009458021033e+00,0.000000000000000000e+00 +5.593919401926704893e+01,3.447650343132689841e+02,9.637697759209480630e-03,3.918025068444979997e+00,-2.939389111142531874e-02,4.764160631607358698e-01,1.361524071352429588e-01,1.000000009436499360e+00,0.000000000000000000e+00 +5.594174632555026960e+01,3.447750299935758562e+02,9.343801173510817362e-03,3.919241028156411399e+00,-2.889389111142531830e-02,4.789683694680392789e-01,1.361524071352429588e-01,1.000000009476904372e+00,0.000000000000000000e+00 +5.594429783997057370e+01,3.447850258195815627e+02,9.054902464494411773e-03,3.920463122857980043e+00,-2.839389111142531785e-02,4.815198839125267583e-01,1.361524071352429588e-01,1.000000009487103991e+00,0.000000000000000000e+00 +5.594684855902764298e+01,3.447950217887870963e+02,8.771001704384939757e-03,3.921691344802232138e+00,-2.789389111142531741e-02,4.840706029937921206e-01,1.361524071352429588e-01,1.000000009410020763e+00,0.000000000000000000e+00 +5.594939847923318155e+01,3.448050178986935066e+02,8.492098964157590579e-03,3.922925686213713625e+00,-2.739389111142531696e-02,4.866205232233262734e-01,1.361524071352429588e-01,1.000000009498816622e+00,0.000000000000000000e+00 +5.595194759711097987e+01,3.448150141468017864e+02,8.218194313538047802e-03,3.924166139289165578e+00,-2.689389111142531652e-02,4.891696411253377841e-01,1.361524071352429588e-01,1.000000009498395181e+00,0.000000000000000000e+00 +5.595449590919692184e+01,3.448250105306128717e+02,7.949287821002471929e-03,3.925412696197721818e+00,-2.639389111142531608e-02,4.917179532354859495e-01,1.361524071352429588e-01,1.000000009466843087e+00,0.000000000000000000e+00 +5.595704341203902743e+01,3.448350070476276414e+02,7.685379553777485669e-03,3.926665349081103429e+00,-2.589389111142531563e-02,4.942654561017080783e-01,1.361524071352429588e-01,1.000000009435391135e+00,0.000000000000000000e+00 +5.595959010219746688e+01,3.448450036953469748e+02,7.426469577840153977e-03,3.927924090053815487e+00,-2.539389111142531519e-02,4.968121462841790792e-01,1.361524071352429588e-01,1.000000009478479113e+00,0.000000000000000000e+00 +5.596213597624460334e+01,3.448550004712716941e+02,7.172557957917970184e-03,3.929188911203343793e+00,-2.489389111142531474e-02,4.993580203554490726e-01,1.361524071352429588e-01,1.000000009509654397e+00,0.000000000000000000e+00 +5.596468103076501421e+01,3.448649973729026215e+02,6.923644757488836912e-03,3.930459804590352046e+00,-2.439389111142531430e-02,5.019030749000609193e-01,1.361524071352429588e-01,1.000000009488309249e+00,0.000000000000000000e+00 +5.596722526235550532e+01,3.448749943977405223e+02,6.679730038781053064e-03,3.931736762248878136e+00,-2.389389111142531386e-02,5.044473065146939383e-01,1.361524071352429588e-01,1.000000009490190189e+00,0.000000000000000000e+00 +5.596976866762516067e+01,3.448849915432861621e+02,6.440813862773297344e-03,3.933019776186530869e+00,-2.339389111142531341e-02,5.069907118084863162e-01,1.361524071352429588e-01,1.000000009434311998e+00,0.000000000000000000e+00 +5.597231124319534956e+01,3.448949888070402494e+02,6.206896289194612643e-03,3.934308838384687590e+00,-2.289389111142531297e-02,5.095332874026622383e-01,1.361524071352429588e-01,1.000000009496506470e+00,0.000000000000000000e+00 +5.597485298569976209e+01,3.449049861865034359e+02,5.977977376524390429e-03,3.935603940798690914e+00,-2.239389111142531252e-02,5.120750299312103460e-01,1.361524071352429588e-01,1.000000009492624686e+00,0.000000000000000000e+00 +5.597739389178442337e+01,3.449149836791764301e+02,5.754057181992358605e-03,3.936905075358047235e+00,-2.189389111142531208e-02,5.146159360399934490e-01,1.361524071352429588e-01,1.000000009567232562e+00,0.000000000000000000e+00 +5.597993395810773620e+01,3.449249812825598269e+02,5.535135761578564156e-03,3.938212233966623010e+00,-2.139389111142531164e-02,5.171560023876086154e-01,1.361524071352429588e-01,1.000000009438229975e+00,0.000000000000000000e+00 +5.598247318134048811e+01,3.449349789941542213e+02,5.321213170013361013e-03,3.939525408502843273e+00,-2.089389111142531119e-02,5.196952256443273521e-01,1.361524071352429588e-01,1.000000009431281311e+00,0.000000000000000000e+00 +5.598501155816588692e+01,3.449449768114602080e+02,5.112289460777396169e-03,3.940844590819887472e+00,-2.039389111142531075e-02,5.222336024936629073e-01,1.361524071352429588e-01,1.000000009586318850e+00,0.000000000000000000e+00 +5.598754908527956786e+01,3.449549747319783251e+02,4.908364686101595806e-03,3.942169772745889311e+00,-1.989389111142531030e-02,5.247711296316672769e-01,1.361524071352429588e-01,1.000000009451147198e+00,0.000000000000000000e+00 +5.599008575938962906e+01,3.449649727532090537e+02,4.709438896967152281e-03,3.943500946084134817e+00,-1.939389111142530986e-02,5.273078037657054074e-01,1.361524071352429588e-01,1.000000009531450740e+00,0.000000000000000000e+00 +5.599262157721666000e+01,3.449749708726529320e+02,4.515512143105511987e-03,3.944838102613257291e+00,-1.889389111142530941e-02,5.298436216169080115e-01,1.361524071352429588e-01,1.000000009498684728e+00,0.000000000000000000e+00 +5.599515653549374861e+01,3.449849690878104411e+02,4.326584472998362338e-03,3.946181234087438483e+00,-1.839389111142530897e-02,5.323785799180769107e-01,1.361524071352429588e-01,1.000000009502961973e+00,0.000000000000000000e+00 +5.599769063096650967e+01,3.449949673961820054e+02,4.142655933877620496e-03,3.947530332236604433e+00,-1.789389111142530853e-02,5.349126754149204910e-01,1.361524071352429588e-01,1.000000009552761249e+00,0.000000000000000000e+00 +5.600022386039310618e+01,3.450049657952680491e+02,3.963726571725419492e-03,3.948885388766624427e+00,-1.739389111142530808e-02,5.374459048657153071e-01,1.361524071352429588e-01,1.000000009447125748e+00,0.000000000000000000e+00 +5.600275622054426350e+01,3.450149642825689398e+02,3.789796431274099122e-03,3.950246395359509055e+00,-1.689389111142530764e-02,5.399782650407961571e-01,1.361524071352429588e-01,1.000000009538059009e+00,0.000000000000000000e+00 +5.600528770820329783e+01,3.450249628555851018e+02,3.620865556006193364e-03,3.951613343673606948e+00,-1.639389111142530719e-02,5.425097527239766126e-01,1.361524071352429588e-01,1.000000009486571528e+00,0.000000000000000000e+00 +5.600781832016613038e+01,3.450349615118168458e+02,3.456933988154420843e-03,3.952986225343805060e+00,-1.589389111142530675e-02,5.450403647108187366e-01,1.361524071352429588e-01,1.000000009579282256e+00,0.000000000000000000e+00 +5.601034805324131582e+01,3.450449602487645393e+02,3.298001768701672252e-03,3.954365031981724510e+00,-1.539389111142530631e-02,5.475700978102360228e-01,1.361524071352429588e-01,1.000000009482283403e+00,0.000000000000000000e+00 +5.601287690425004229e+01,3.450549590639284929e+02,3.144068937381001676e-03,3.955749755175920424e+00,-1.489389111142530586e-02,5.500989488429418595e-01,1.361524071352429588e-01,1.000000009491709418e+00,0.000000000000000000e+00 +5.601540487002616686e+01,3.450649579548090173e+02,2.995135532675615754e-03,3.957140386492077777e+00,-1.439389111142530542e-02,5.526269146430616841e-01,1.361524071352429588e-01,1.000000009563084991e+00,0.000000000000000000e+00 +5.601793194741622983e+01,3.450749569189064232e+02,2.851201591818865438e-03,3.958536917473211236e+00,-1.389389111142530497e-02,5.551539920572889919e-01,1.361524071352429588e-01,1.000000009520753075e+00,0.000000000000000000e+00 +5.602045813327946178e+01,3.450849559537209075e+02,2.712267150794234714e-03,3.959939339639862776e+00,-1.339389111142530453e-02,5.576801779445714757e-01,1.361524071352429588e-01,1.000000009476446294e+00,0.000000000000000000e+00 +5.602298342448781199e+01,3.450949550567527240e+02,2.578332244335333669e-03,3.961347644490298414e+00,-1.289389111142530409e-02,5.602054691768543204e-01,1.361524071352429588e-01,1.000000009553024816e+00,0.000000000000000000e+00 +5.602550781792596979e+01,3.451049542255021265e+02,2.449396905925888077e-03,3.962761823500706715e+00,-1.239389111142530364e-02,5.627298626391243896e-01,1.361524071352429588e-01,1.000000009606928808e+00,0.000000000000000000e+00 +5.602803131049135743e+01,3.451149534574692552e+02,2.325461167799731596e-03,3.964181868125397301e+00,-1.189389111142530320e-02,5.652533552287535290e-01,1.361524071352429588e-01,1.000000009437677306e+00,0.000000000000000000e+00 +5.603055389909416562e+01,3.451249527501543639e+02,2.206525060940798394e-03,3.965607769796997584e+00,-1.139389111142530275e-02,5.677759438553711124e-01,1.361524071352429588e-01,1.000000009557748148e+00,0.000000000000000000e+00 +5.603307558065736771e+01,3.451349521010575927e+02,2.092588615083114043e-03,3.967039519926649049e+00,-1.089389111142530231e-02,5.702976254426778135e-01,1.361524071352429588e-01,1.000000009518860145e+00,0.000000000000000000e+00 +5.603559635211673395e+01,3.451449515076791386e+02,1.983651858710789879e-03,3.968477109904207989e+00,-1.039389111142530187e-02,5.728183969260366437e-01,1.361524071352429588e-01,1.000000009588263294e+00,0.000000000000000000e+00 +5.603811621042083146e+01,3.451549509675191416e+02,1.879714819058014331e-03,3.969920531098440009e+00,-9.893891111425301421e-03,5.753382552542919415e-01,1.361524071352429588e-01,1.000000009493362541e+00,0.000000000000000000e+00 +5.604063515253104555e+01,3.451649504780777420e+02,1.780777522109046850e-03,3.971369774857218982e+00,-9.393891111425300977e-03,5.778571973884224500e-01,1.361524071352429588e-01,1.000000009540951806e+00,0.000000000000000000e+00 +5.604315317542161523e+01,3.451749500368550230e+02,1.686839992598211180e-03,3.972824832507722448e+00,-8.893891111425300533e-03,5.803752203030146939e-01,1.361524071352429588e-01,1.000000009570056969e+00,0.000000000000000000e+00 +5.604567027607961194e+01,3.451849496413511247e+02,1.597902254009889080e-03,3.974285695356630566e+00,-8.393891111425300089e-03,5.828923209850974674e-01,1.361524071352429588e-01,1.000000009512278742e+00,0.000000000000000000e+00 +5.604818645150496792e+01,3.451949492890661304e+02,1.513964328578514679e-03,3.975752354690321955e+00,-7.893891111425299645e-03,5.854084964343879705e-01,1.361524071352429588e-01,1.000000009533732248e+00,0.000000000000000000e+00 +5.605070169871049757e+01,3.452049489775001803e+02,1.435026237288569055e-03,3.977224801775069984e+00,-7.393891111425299201e-03,5.879237436638941050e-01,1.361524071352429588e-01,1.000000009616251795e+00,0.000000000000000000e+00 +5.605321601472189030e+01,3.452149487041533007e+02,1.361087999874574603e-03,3.978703027857240393e+00,-6.893891111425298757e-03,5.904380596994622810e-01,1.361524071352429588e-01,1.000000009486898156e+00,0.000000000000000000e+00 +5.605572939657773190e+01,3.452249484665255750e+02,1.292149634821090258e-03,3.980187024163487575e+00,-6.393891111425298313e-03,5.929514415791484749e-01,1.361524071352429588e-01,1.000000009533642986e+00,0.000000000000000000e+00 +5.605824184132951871e+01,3.452349482621170296e+02,1.228211159362706945e-03,3.981676781900949091e+00,-5.893891111425297868e-03,5.954638863548906702e-01,1.361524071352429588e-01,1.000000009611893947e+00,0.000000000000000000e+00 +5.606075334604166471e+01,3.452449480884277477e+02,1.169272589484043022e-03,3.983172292257444180e+00,-5.393891111425297424e-03,5.979753910911803638e-01,1.361524071352429588e-01,1.000000009536788026e+00,0.000000000000000000e+00 +5.606326390779151581e+01,3.452549479429578128e+02,1.115333939919740816e-03,3.984673546401668709e+00,-4.893891111425296980e-03,6.004859528649720835e-01,1.361524071352429588e-01,1.000000009507793441e+00,0.000000000000000000e+00 +5.606577352366934264e+01,3.452649478232071942e+02,1.066395224154462499e-03,3.986180535483389686e+00,-4.393891111425296536e-03,6.029955687666582742e-01,1.361524071352429588e-01,1.000000009617081798e+00,0.000000000000000000e+00 +5.606828219077836906e+01,3.452749477266759754e+02,1.022456454422886619e-03,3.987693250633641995e+00,-3.893891111425296526e-03,6.055042358998086183e-01,1.361524071352429588e-01,1.000000009568139836e+00,0.000000000000000000e+00 +5.607078990623477210e+01,3.452849476508641260e+02,9.835176417097054972e-04,3.989211682964924233e+00,-3.393891111425296515e-03,6.080119513802038078e-01,1.361524071352429588e-01,1.000000009523421607e+00,0.000000000000000000e+00 +5.607329666716768912e+01,3.452949475932716723e+02,9.495787957496219789e-04,3.990735823571391894e+00,-2.893891111425296505e-03,6.105187123369956170e-01,1.361524071352429588e-01,1.000000009541723633e+00,0.000000000000000000e+00 +5.607580247071923907e+01,3.453049475513986977e+02,9.206399250273473696e-04,3.992265663529053210e+00,-2.393891111425296495e-03,6.130245159124545484e-01,1.361524071352429588e-01,1.000000009578727367e+00,0.000000000000000000e+00 +5.607830731404450830e+01,3.453149475227451148e+02,8.967010367775992688e-04,3.993801193895964108e+00,-1.893891111425296484e-03,6.155293592617189224e-01,1.361524071352429588e-01,1.000000009558972058e+00,0.000000000000000000e+00 +5.608081119431157902e+01,3.453249475048110071e+02,8.777621369850996174e-04,3.995342405712422273e+00,-1.393891111425296474e-03,6.180332395527242673e-01,1.361524071352429588e-01,1.000000009589316008e+00,0.000000000000000000e+00 +5.608331410870152212e+01,3.453349474950963440e+02,8.638232303845732891e-04,3.996889290001160777e+00,-8.938911114252964633e-04,6.205361539666667259e-01,1.361524071352429588e-01,1.000000009606272888e+00,0.000000000000000000e+00 +5.608581605440840434e+01,3.453449474911011521e+02,8.548843204607467884e-04,3.998441837767542584e+00,-3.938911114252964529e-04,6.230380996975828367e-01,1.361524071352429588e-01,1.000000009518562827e+00,0.000000000000000000e+00 +5.608831702863930246e+01,3.453549474903254008e+02,8.509454094483476011e-04,4.000000039999753731e+00,1.061088885747035575e-04,6.255390739522862509e-01,1.361524071352429588e-01,1.000000009563288605e+00,-4.000000039999757617e-01 +5.609081702861430330e+01,3.453649474902691168e+02,8.520064983321034343e-04,4.001563887668996067e+00,6.061088885747035679e-04,6.280390739511946263e-01,1.351524071352429579e-01,1.000000009597514117e+00,-4.001563887668999064e-01 +5.609331605156651079e+01,3.453749474884322694e+02,8.580675868467421089e-04,4.003133371729681755e+00,1.102391261613891666e-03,6.305380969273841618e-01,1.341524071352429570e-01,1.000000009453454686e+00,-4.003133371729685197e-01 +5.609581409474204605e+01,3.453849474823559262e+02,8.690914972300492394e-04,4.004708483119625129e+00,1.594957018611155080e-03,6.330361401265328647e-01,1.331524071352429561e-01,1.000000009652274313e+00,-4.004708483119628348e-01 +5.609831115540005442e+01,3.453949474696364632e+02,8.850410606538419061e-04,4.006289212760234086e+00,2.083807162642880954e-03,6.355332008086459483e-01,1.321524071352429552e-01,1.000000009625340303e+00,-4.006289212760237861e-01 +5.610080723081271969e+01,3.454049474479252240e+02,9.058791171995799613e-04,4.007875551556705496e+00,2.568942688951201050e-03,6.380292762453375621e-01,1.311524071352429544e-01,1.000000009423425595e+00,-4.007875551556708826e-01 +5.610330231826524994e+01,3.454149474149278944e+02,9.315685158330157560e-04,4.009467490398213485e+00,3.050364584952167286e-03,6.405243637213821062e-01,1.301524071352429535e-01,1.000000009577601823e+00,-4.009467490398216927e-01 +5.610579641505589876e+01,3.454249473684043323e+02,9.620721143778912868e-04,4.011065020158101291e+00,3.528073830243861134e-03,6.430184605359151595e-01,1.291524071352429526e-01,1.000000009530342071e+00,-4.011065020158104399e-01 +5.610828951849594404e+01,3.454349473061678850e+02,9.973527794886907858e-04,4.012668131694075768e+00,4.002071396614434277e-03,6.455115639997202059e-01,1.281524071352429517e-01,1.000000009634137044e+00,-4.012668131694079321e-01 +5.611078162590971630e+01,3.454449472260851053e+02,1.037373386622456560e-03,4.014276815848394797e+00,4.472358248050083140e-03,6.480036714375011497e-01,1.271524071352429508e-01,1.000000009439138138e+00,-4.014276815848398239e-01 +5.611327273463458454e+01,3.454549471260753535e+02,1.082096820009677621e-03,4.015891063448060017e+00,4.938935340742954885e-03,6.504947801858842471e-01,1.261524071352429499e-01,1.000000009552872271e+00,-4.015891063448063236e-01 +5.611576284202097042e+01,3.454649470041101722e+02,1.131485972624258259e-03,4.017510865305004231e+00,5.401803623098990099e-03,6.529848875960545529e-01,1.251524071352429490e-01,1.000000009495408460e+00,-4.017510865305007894e-01 +5.611825194543232698e+01,3.454749468582131158e+02,1.185503746152575351e-03,4.019136212216285031e+00,5.860964035745694356e-03,6.554739910310479756e-01,1.241524071352429481e-01,1.000000009561284209e+00,-4.019136212216288251e-01 +5.612074004224517410e+01,3.454849466864591250e+02,1.244113050961631649e-03,4.020767094964271315e+00,6.316417511539842988e-03,6.579620878676810669e-01,1.231524071352429472e-01,1.000000009530832568e+00,-4.020767094964274868e-01 +5.612322712984906303e+01,3.454949464869741291e+02,1.307276806066315052e-03,4.022403504316834244e+00,6.768164975575125149e-03,6.604491754952714899e-01,1.221524071352429464e-01,1.000000009532073797e+00,-4.022403504316837686e-01 +5.612571320564659771e+01,3.455049462579347050e+02,1.374957939095769899e-03,4.024045431027534647e+00,7.216207345189714142e-03,6.629352513165034377e-01,1.211524071352429455e-01,1.000000009467533868e+00,-4.024045431027538089e-01 +5.612819826705343473e+01,3.455149459975675654e+02,1.447119386258890290e-03,4.025692865835812206e+00,7.660545529973775310e-03,6.654203127468665269e-01,1.201524071352429446e-01,1.000000009590131134e+00,-4.025692865835815981e-01 +5.613068231149826914e+01,3.455249457041492178e+02,1.523724092308941912e-03,4.027345799467172860e+00,8.101180431776908858e-03,6.679043572155259900e-01,1.191524071352429437e-01,1.000000009353188224e+00,-4.027345799467176302e-01 +5.613316533642285577e+01,3.455349453760053962e+02,1.604735010507321721e-03,4.029004222633377985e+00,8.538112944715525038e-03,6.703873821633352659e-01,1.181524071352429428e-01,1.000000009571006876e+00,-4.029004222633381094e-01 +5.613564733928198081e+01,3.455449450115107197e+02,1.690115102586462609e-03,4.030668126032628251e+00,8.971343955180151666e-03,6.728693850462148518e-01,1.171524071352429419e-01,1.000000009539151691e+00,-4.030668126032631582e-01 +5.613812831754347599e+01,3.455549446090883521e+02,1.779827338711891752e-03,4.032337500349755466e+00,9.400874341842677465e-03,6.753503633313793220e-01,1.161524071352429410e-01,1.000000009484745878e+00,-4.032337500349758574e-01 +5.614060826868822573e+01,3.455649441672094326e+02,1.873834697443450435e-03,4.034012336256404652e+00,9.826704975663534680e-03,6.778303144996483676e-01,1.151524071352429401e-01,1.000000009414348634e+00,-4.034012336256407871e-01 +5.614308719021013871e+01,3.455749436843926787e+02,1.972100165695682503e-03,4.035692624411221452e+00,1.024883671989880451e-02,6.803092360448966813e-01,1.141524071352429393e-01,1.000000009548838165e+00,-4.035692624411225116e-01 +5.614556507961616205e+01,3.455849431592039878e+02,2.074586738697401650e-03,4.037378355460037760e+00,1.066727043010726877e-02,6.827871254745822016e-01,1.131524071352429384e-01,1.000000009456078143e+00,-4.037378355460041202e-01 +5.614804193442628133e+01,3.455949425902560961e+02,2.181257419950441423e-03,4.039069520036058236e+00,1.108200695415739040e-02,6.852639803081246317e-01,1.121524071352429375e-01,1.000000009497936215e+00,-4.039069520036062122e-01 +5.615051775217351349e+01,3.456049419762080106e+02,2.292075221187601410e-03,4.040766108760042385e+00,1.149304713223423327e-02,6.877397980788695353e-01,1.111524071352429366e-01,1.000000009529983913e+00,-4.040766108760045494e-01 +5.615299253040389260e+01,3.456149413157646109e+02,2.407003162329792410e-03,4.042468112240491074e+00,1.190039179684630744e-02,6.902145763328300099e-01,1.101524071352429357e-01,1.000000009335289652e+00,-4.042468112240494849e-01 +5.615546626667646990e+01,3.456249406076763648e+02,2.526004271442390797e-03,4.044175521073829493e+00,1.230404177283236228e-02,6.926883126285037218e-01,1.091524071352429348e-01,1.000000009496664788e+00,-4.044175521073833379e-01 +5.615793895856332796e+01,3.456349398507387036e+02,2.649041584690810074e-03,4.045888325844589239e+00,1.270399787736810511e-02,6.951610045388467718e-01,1.081524071352429339e-01,1.000000009511295529e+00,-4.045888325844592681e-01 +5.616041060364955229e+01,3.456449390437917373e+02,2.776078146295296589e-03,4.047606517125594827e+00,1.310026091997285730e-02,6.976326496485830697e-01,1.071524071352429330e-01,1.000000009532697298e+00,-4.047606517125598158e-01 +5.616288119953323843e+01,3.456549381857198000e+02,2.907077008484957627e-03,4.049330085478143104e+00,1.349283170251615316e-02,7.001032455558227063e-01,1.061524071352429321e-01,1.000000009209353280e+00,-4.049330085478146657e-01 +5.616535074382548487e+01,3.456649372754510523e+02,3.042001231451030123e-03,4.051059021452186215e+00,1.388171101922426078e-02,7.025727898708085117e-01,1.051524071352429313e-01,1.000000009578876581e+00,-4.051059021452189657e-01 +5.616781923415037170e+01,3.456749363119570262e+02,3.180813883299396082e-03,4.052793315586511014e+00,1.426689965668665079e-02,7.050412802193406492e-01,1.041524071352429304e-01,1.000000009427329806e+00,-4.052793315586514233e-01 +5.617028666814498195e+01,3.456849352942521705e+02,3.323478040002354663e-03,4.054532958408926469e+00,1.464839839386239580e-02,7.075087142372104010e-01,1.031524071352429295e-01,1.000000009514359745e+00,-4.054532958408930132e-01 +5.617275304345937315e+01,3.456949342213934528e+02,3.469956785349656569e-03,4.056277940436436857e+00,1.502620800208650555e-02,7.099750895750662760e-01,1.021524071352429286e-01,1.000000009222014485e+00,-4.056277940436440743e-01 +5.617521835775657735e+01,3.457049330924800756e+02,3.620213210898810298e-03,4.058028252175426509e+00,1.540032924507619624e-02,7.124404038950076234e-01,1.011524071352429277e-01,1.000000009621296870e+00,-4.058028252175429618e-01 +5.617768260871260111e+01,3.457149319066527937e+02,3.774210415924666735e-03,4.059783884121835662e+00,1.577076287893710432e-02,7.149046548747419738e-01,1.001524071352429268e-01,1.000000009234113696e+00,-4.059783884121839215e-01 +5.618014579401641129e+01,3.457249306630937440e+02,3.931911507368288615e-03,4.061544826761346094e+00,1.613750965216942737e-02,7.173678402012939603e-01,9.915240713524292593e-02,1.000000009591458738e+00,-4.061544826761349647e-01 +5.618260791136991372e+01,3.457349293610259338e+02,4.093279599785116553e-03,4.063311070569550765e+00,1.650057030567399913e-02,7.198299575784123938e-01,9.815240713524292504e-02,1.000000009235104903e+00,-4.063311070569554095e-01 +5.618506895848797456e+01,3.457449279997127292e+02,4.258277815292432940e-03,4.065082606012141220e+00,1.685994557275832112e-02,7.222910047191988259e-01,9.715240713524292415e-02,1.000000009575078952e+00,-4.065082606012144772e-01 +5.618752893309838470e+01,3.457549265784575709e+02,4.426869283516139328e-03,4.066859423545076346e+00,1.721563617914249888e-02,7.247509793531610178e-01,9.615240713524292326e-02,1.000000009175343596e+00,-4.066859423545079455e-01 +5.618998783294185984e+01,3.457649250966035197e+02,4.599017141536846862e-03,4.068641513614768002e+00,1.756764284296514350e-02,7.272098792191997729e-01,9.515240713524292238e-02,1.000000009622330488e+00,-4.068641513614771887e-01 +5.619244565577204753e+01,3.457749235535328580e+02,4.774684533835289735e-03,4.070428866658248879e+00,1.791596627478919332e-02,7.296677020730345520e-01,9.415240713524292149e-02,1.000000009211528651e+00,-4.070428866658252209e-01 +5.619490239935548459e+01,3.457849219486665220e+02,4.953834612237076850e-03,4.072221473103358136e+00,1.826060717760768712e-02,7.321244456791020649e-01,9.315240713524292060e-02,1.000000009414201196e+00,-4.072221473103361244e-01 +5.619735806147161838e+01,3.457949202814639875e+02,5.136430535856774740e-03,4.074019323368906598e+00,1.860156624684944707e-02,7.345801078183523680e-01,9.215240713524291971e-02,1.000000009290779701e+00,-4.074019323368909817e-01 +5.619981263991277842e+01,3.458049185514225314e+02,5.322435471041340842e-03,4.075822407864860608e+00,1.893884417038473739e-02,7.370346862823147216e-01,9.115240713524291882e-02,1.000000009464160344e+00,-4.075822407864864716e-01 +5.620226613248416925e+01,3.458149167580770609e+02,5.511812591312912311e-03,4.077630716992510784e+00,1.927244162853082241e-02,7.394881788769246400e-01,9.015240713524291793e-02,1.000000009322110639e+00,-4.077630716992514115e-01 +5.620471853700386333e+01,3.458249149009994881e+02,5.704525077310952999e-03,4.079444241144649652e+00,1.960235929405748992e-02,7.419405834194813254e-01,8.915240713524291705e-02,1.000000009376488697e+00,-4.079444241144653538e-01 +5.620716985130279397e+01,3.458349129797985597e+02,5.900536116733772450e-03,4.081262970705741289e+00,1.992859783219249128e-02,7.443918977413946925e-01,8.815240713524291616e-02,1.000000009347120189e+00,-4.081262970705744619e-01 +5.620962007322472687e+01,3.458449109941192319e+02,6.099808904279416938e-03,4.083086896052097181e+00,2.025115790062693988e-02,7.468421196862310429e-01,8.715240713524291527e-02,1.000000009342130181e+00,-4.083086896052101067e-01 +5.621206920062626722e+01,3.458549089436423287e+02,6.302306641585950740e-03,4.084916007552046757e+00,2.057004014952062282e-02,7.492912471106535355e-01,8.615240713524291438e-02,1.000000009268725565e+00,-4.084916007552050199e-01 +5.621451723137683842e+01,3.458649068280841448e+02,6.507992537171122457e-03,4.086750295566109692e+00,2.088524522150727800e-02,7.517392778839178114e-01,8.515240713524291349e-02,1.000000009277286939e+00,-4.086750295566112801e-01 +5.621696416335867497e+01,3.458749046471961037e+02,6.716829806371431982e-03,4.088589750447166438e+00,2.119677375169977743e-02,7.541862098884550836e-01,8.415240713524291261e-02,1.000000009317917549e+00,-4.088589750447170212e-01 +5.621940999446680109e+01,3.458849024007641333e+02,6.928781671280603328e-03,4.090434362540629643e+00,2.150462636769528285e-02,7.566320410193689838e-01,8.315240713524291172e-02,1.000000009437793880e+00,-4.090434362540633639e-01 +5.622185472260901662e+01,3.458949000886084377e+02,7.143811360687471988e-03,4.092284122184613793e+00,2.180880368958030419e-02,7.590767691846601606e-01,8.215240713524291083e-02,1.000000009186509553e+00,-4.092284122184617345e-01 +5.622429834570590401e+01,3.459048977105831000e+02,7.361882110013289425e-03,4.094139019710104854e+00,2.210930632993572328e-02,7.615203923039969292e-01,8.115240713524290994e-02,1.000000009401866174e+00,-4.094139019710107963e-01 +5.622674086169079288e+01,3.459148952665755132e+02,7.582957161248458575e-03,4.095999045441126363e+00,2.240613489384174484e-02,7.639629083118502084e-01,8.015240713524290905e-02,1.000000009086389863e+00,-4.095999045441129915e-01 +5.622918226850975287e+01,3.459248927565060967e+02,7.806999762888701226e-03,4.097864189694912618e+00,2.269928997888278482e-02,7.664043151529953413e-01,7.915240713524290816e-02,1.000000009427257641e+00,-4.097864189694916393e-01 +5.623162256412158655e+01,3.459348901803278977e+02,8.033973169870669423e-03,4.099734442782070332e+00,2.298877217515229651e-02,7.688446107878336155e-01,7.815240713524290728e-02,1.000000009178447113e+00,-4.099734442782074217e-01 +5.623406174649780098e+01,3.459448875380260233e+02,8.263840643507007824e-03,4.101609795006752712e+00,2.327458206525754095e-02,7.712837931864375829e-01,7.715240713524290639e-02,1.000000009282860036e+00,-4.101609795006755932e-01 +5.623649981362260775e+01,3.459548848296174128e+02,8.496565451420867027e-03,4.103490236666818447e+00,2.355672022432428805e-02,7.737218603338786860e-01,7.615240713524290550e-02,1.000000009293086523e+00,-4.103490236666821889e-01 +5.623893676349290160e+01,3.459648820551503832e+02,8.732110867479887795e-03,4.105375758054003121e+00,2.383518722000146570e-02,7.761588102268199840e-01,7.515240713524290461e-02,1.000000009162314019e+00,-4.105375758054006230e-01 +5.624137259411823919e+01,3.459748792147041172e+02,8.970440171729650997e-03,4.107266349454081755e+00,2.410998361246573241e-02,7.785946408744787162e-01,7.415240713524290372e-02,1.000000009246318378e+00,-4.107266349454085641e-01 +5.624380730352083901e+01,3.459848763083883796e+02,9.211516650326606256e-03,4.109162001147033116e+00,2.438110995442600848e-02,7.810293502995911963e-01,7.315240713524290284e-02,1.000000009256865052e+00,-4.109162001147037002e-01 +5.624624088973554592e+01,3.459948733363430051e+02,9.455303595470490596e-03,4.111062703407205809e+00,2.464856679112792728e-02,7.834629365368281917e-01,7.215240713524290195e-02,1.000000009309280458e+00,-4.111062703407209473e-01 +5.624867335080983821e+01,3.460048702987375577e+02,9.701764305336235336e-03,4.112968446503479925e+00,2.491235466035823798e-02,7.858953976337618164e-01,7.115240713524290106e-02,1.000000009023564340e+00,-4.112968446503483255e-01 +5.625110468480378501e+01,3.460148671957709894e+02,9.950862084005371658e-03,4.114879220699430462e+00,2.517247409244913886e-02,7.883267316496443966e-01,7.015240713524290017e-02,1.000000009177260951e+00,-4.114879220699433904e-01 +5.625353488979004624e+01,3.460248640276710148e+02,1.020256024139694351e-02,4.116795016253487205e+00,2.542892561028255519e-02,7.907569366582066772e-01,6.915240713524289928e-02,1.000000009302909998e+00,-3.125661034381806425e-01 +5.625596396385385844e+01,3.460348607946939410e+02,1.045682209319793998e-02,4.118715823419100808e+00,2.568170972929435109e-02,7.931860107446132568e-01,6.839316092015533532e-02,1.000000009188940941e+00,0.000000000000000000e+00 +5.625839190509300636e+01,3.460448574971240987e+02,1.071361096079323852e-02,4.120641632444900893e+00,2.593170972929435131e-02,7.956139520060688808e-01,6.839316092015533532e-02,1.000000009032397053e+00,0.000000000000000000e+00 +5.626081871161780867e+01,3.460548541350446499e+02,1.097289899594539563e-02,4.122572433574855033e+00,2.618170972929435153e-02,7.980407585527936609e-01,6.839316092015533532e-02,1.000000009290968883e+00,0.000000000000000000e+00 +5.626324438155111807e+01,3.460648507078308285e+02,1.123468618244890908e-02,4.124508217048429515e+00,2.643170972929435175e-02,8.004664285086368070e-01,6.839316092015533532e-02,1.000000009021950964e+00,0.000000000000000000e+00 +5.626566891302827145e+01,3.460748472148578117e+02,1.149897250394208044e-02,4.126448973100750983e+00,2.668170972929435197e-02,8.028909600076613584e-01,6.839316092015533532e-02,1.000000009052276706e+00,0.000000000000000000e+00 +5.626809230419708996e+01,3.460848436555008334e+02,1.176575794390701500e-02,4.128394691962759211e+00,2.693170972929435220e-02,8.053143511984188763e-01,6.839316092015533532e-02,1.000000009263203093e+00,0.000000000000000000e+00 +5.627051455321787188e+01,3.460948400291350708e+02,1.203504248566962184e-02,4.130345363861369634e+00,2.718170972929435242e-02,8.077366002416366264e-01,6.839316092015533532e-02,1.000000009039685889e+00,0.000000000000000000e+00 +5.627293565826334998e+01,3.461048363351358148e+02,1.230682611239961727e-02,4.132300979019629672e+00,2.743170972929435264e-02,8.101577053089978886e-01,6.839316092015533532e-02,1.000000009089365705e+00,0.000000000000000000e+00 +5.627535561751868443e+01,3.461148325728782424e+02,1.258110880711052482e-02,4.134261527656871493e+00,2.768170972929435286e-02,8.125776645863267422e-01,6.839316092015533532e-02,1.000000009172124615e+00,0.000000000000000000e+00 +5.627777442918144857e+01,3.461248287417376446e+02,1.285789055265967699e-02,4.136226999988871889e+00,2.793170972929435308e-02,8.149964762712732513e-01,6.839316092015533532e-02,1.000000009006951185e+00,0.000000000000000000e+00 +5.628019209146159341e+01,3.461348248410891983e+02,1.313717133174821354e-02,4.138197386228005925e+00,2.818170972929435331e-02,8.174141385731963361e-01,6.839316092015533532e-02,1.000000009033908732e+00,0.000000000000000000e+00 +5.628260860258145470e+01,3.461448208703081946e+02,1.341895112692108663e-02,4.140172676583399713e+00,2.843170972929435353e-02,8.198306497148879490e-01,6.839316092015533532e-02,1.000000009046604799e+00,0.000000000000000000e+00 +5.628502396077570324e+01,3.461548168287698672e+02,1.370322992056705914e-02,4.142152861261086727e+00,2.868170972929435375e-02,8.222460079309897862e-01,6.839316092015533532e-02,1.000000008952385055e+00,0.000000000000000000e+00 +5.628743816429135194e+01,3.461648127158494503e+02,1.399000769491870640e-02,4.144137930464159680e+00,2.893170972929435397e-02,8.246602114682487494e-01,6.839316092015533532e-02,1.000000009077741003e+00,0.000000000000000000e+00 +5.628985121138770609e+01,3.461748085309222347e+02,1.427928443205241787e-02,4.146127874392922408e+00,2.918170972929435419e-02,8.270732585865084863e-01,6.839316092015533532e-02,1.000000009102268717e+00,0.000000000000000000e+00 +5.629226310033637048e+01,3.461848042733634543e+02,1.457106011388839724e-02,4.148122683245043518e+00,2.943170972929435442e-02,8.294851475571271004e-01,6.839316092015533532e-02,1.000000008819809105e+00,0.000000000000000000e+00 +5.629467382942121390e+01,3.461947999425483999e+02,1.486533472219066405e-02,4.150122347215705609e+00,2.968170972929435464e-02,8.318958766632332802e-01,6.839316092015533532e-02,1.000000009057607109e+00,0.000000000000000000e+00 +5.629708339693835484e+01,3.462047955378523056e+02,1.516210823856705553e-02,4.152126856497754481e+00,2.993170972929435486e-02,8.343054442021963224e-01,6.839316092015533532e-02,1.000000008772152560e+00,0.000000000000000000e+00 +5.629949180119612606e+01,3.462147910586505191e+02,1.546138064446922825e-02,4.154136201281853680e+00,3.018170972929435508e-02,8.367138484810955346e-01,6.839316092015533532e-02,1.000000009178688254e+00,0.000000000000000000e+00 +5.630189904051507455e+01,3.462247865043182742e+02,1.576315192119265643e-02,4.156150371756627493e+00,3.043170972929435530e-02,8.391210878221410097e-01,6.839316092015533532e-02,1.000000008699730047e+00,0.000000000000000000e+00 +5.630430511322792597e+01,3.462347818742308050e+02,1.606742204987663541e-02,4.158169358108816382e+00,3.068170972929435553e-02,8.415271605559268009e-01,6.839316092015533532e-02,1.000000009094677011e+00,0.000000000000000000e+00 +5.630671001767957051e+01,3.462447771677634591e+02,1.637419101150427991e-02,4.160193150523415540e+00,3.093170972929435575e-02,8.439320650294412918e-01,6.839316092015533532e-02,1.000000008712727650e+00,0.000000000000000000e+00 +5.630911375222702731e+01,3.462547723842915275e+02,1.668345878690253095e-02,4.162221739183832092e+00,3.118170972929435597e-02,8.463357995978396664e-01,6.839316092015533532e-02,1.000000008939041951e+00,0.000000000000000000e+00 +5.631151631523943735e+01,3.462647675231903008e+02,1.699522535674215587e-02,4.164255114272021885e+00,3.143170972929435619e-02,8.487383626317234198e-01,6.839316092015533532e-02,1.000000008819149411e+00,0.000000000000000000e+00 +5.631391770509802797e+01,3.462747625838350700e+02,1.730949070153774139e-02,4.166293265968643134e+00,3.168170972929435641e-02,8.511397525114929863e-01,6.839316092015533532e-02,1.000000008902257154e+00,0.000000000000000000e+00 +5.631631792019610572e+01,3.462847575656011827e+02,1.762625480164770400e-02,4.168336184453195870e+00,3.193170972929435664e-02,8.535399676309386452e-01,6.839316092015533532e-02,1.000000008625182124e+00,0.000000000000000000e+00 +5.631871695893902086e+01,3.462947524678639297e+02,1.794551763727428653e-02,4.170383859904169377e+00,3.218170972929435686e-02,8.559390063945463423e-01,6.839316092015533532e-02,1.000000008933559892e+00,0.000000000000000000e+00 +5.632111481974414602e+01,3.463047472899986019e+02,1.826727918846356505e-02,4.172436282499182525e+00,3.243170972929435708e-02,8.583368672210951456e-01,6.839316092015533532e-02,1.000000008732591539e+00,0.000000000000000000e+00 +5.632351150104086202e+01,3.463147420313805469e+02,1.859153943510543847e-02,4.174493442415132094e+00,3.268170972929435730e-02,8.607335485387391794e-01,6.839316092015533532e-02,1.000000008747513380e+00,0.000000000000000000e+00 +5.632590700127051520e+01,3.463247366913851124e+02,1.891829835693364589e-02,4.176555329828328667e+00,3.293170972929435752e-02,8.631290487893491514e-01,6.839316092015533532e-02,1.000000008588275646e+00,0.000000000000000000e+00 +5.632830131888641745e+01,3.463347312693876461e+02,1.924755593352574928e-02,4.178621934914642289e+00,3.318170972929435775e-02,8.655233664258148440e-01,6.839316092015533532e-02,1.000000008761209980e+00,0.000000000000000000e+00 +5.633069445235380357e+01,3.463447257647634387e+02,1.957931214430315425e-02,4.180693247849641025e+00,3.343170972929435797e-02,8.679164999141681935e-01,6.839316092015533532e-02,1.000000008810460139e+00,0.000000000000000000e+00 +5.633308640014981705e+01,3.463547201768878381e+02,1.991356696853109620e-02,4.182769258808733959e+00,3.368170972929435819e-02,8.703084477312552636e-01,6.839316092015533532e-02,1.000000008400607099e+00,0.000000000000000000e+00 +5.633547716076348166e+01,3.463647145051361917e+02,2.025032038531865072e-02,4.184849957967307965e+00,3.393170972929435841e-02,8.726992083650020327e-01,6.839316092015533532e-02,1.000000008718454181e+00,0.000000000000000000e+00 +5.633786673269567302e+01,3.463747087488839043e+02,2.058957237361872666e-02,4.186935335500864497e+00,3.418170972929435864e-02,8.750887803180289470e-01,6.839316092015533532e-02,1.000000008588108225e+00,0.000000000000000000e+00 +5.634025511445911150e+01,3.463847029075062665e+02,2.093132291222807653e-02,4.189025381585164354e+00,3.443170972929435886e-02,8.774771621019775703e-01,6.839316092015533532e-02,1.000000008510674387e+00,0.000000000000000000e+00 +5.634264230457831246e+01,3.463946969803786828e+02,2.127557197978729303e-02,4.191120086396358246e+00,3.468170972929435908e-02,8.798643522414946183e-01,6.839316092015533532e-02,1.000000008645961724e+00,0.000000000000000000e+00 +5.634502830158957920e+01,3.464046909668765579e+02,2.162231955478080905e-02,4.193219440111126239e+00,3.493170972929435930e-02,8.822503492733901886e-01,6.839316092015533532e-02,1.000000008341604740e+00,0.000000000000000000e+00 +5.634741310404096737e+01,3.464146848663751825e+02,2.197156561553689769e-02,4.195323432906814531e+00,3.518170972929435952e-02,8.846351517446748858e-01,6.839316092015533532e-02,1.000000008474320357e+00,0.000000000000000000e+00 +5.634979671049227790e+01,3.464246786782500180e+02,2.232331014022768262e-02,4.197432054961566905e+00,3.543170972929435975e-02,8.870187582161822570e-01,6.839316092015533532e-02,1.000000008484878355e+00,0.000000000000000000e+00 +5.635217911951500014e+01,3.464346724018764121e+02,2.267755310686913467e-02,4.199545296454464172e+00,3.568170972929435997e-02,8.894011672591179973e-01,6.839316092015533532e-02,1.000000008406780827e+00,0.000000000000000000e+00 +5.635456032969231188e+01,3.464446660366297692e+02,2.303429449332106485e-02,4.201663147565654732e+00,3.593170972929436019e-02,8.917823774564482830e-01,6.839316092015533532e-02,1.000000008399526408e+00,0.000000000000000000e+00 +5.635694033961904381e+01,3.464546595818854371e+02,2.339353427728713478e-02,4.203785598476487806e+00,3.618170972929436041e-02,8.941623874031735530e-01,6.839316092015533532e-02,1.000000008121224138e+00,0.000000000000000000e+00 +5.635931914790165820e+01,3.464646530370188771e+02,2.375527243631486013e-02,4.205912639369646655e+00,3.643170972929436063e-02,8.965411957051089287e-01,6.839316092015533532e-02,1.000000008454643874e+00,0.000000000000000000e+00 +5.636169675315822047e+01,3.464746464014054936e+02,2.411950894779560720e-02,4.208044260429278260e+00,3.668170972929436086e-02,8.989188009817713487e-01,6.839316092015533532e-02,1.000000008211114455e+00,0.000000000000000000e+00 +5.636407315401836371e+01,3.464846396744206913e+02,2.448624378896459286e-02,4.210180451841129212e+00,3.693170972929436108e-02,9.012952018614263094e-01,6.839316092015533532e-02,1.000000008054880540e+00,0.000000000000000000e+00 +5.636644834912327440e+01,3.464946328554398747e+02,2.485547693690089155e-02,4.212321203792669166e+00,3.718170972929436130e-02,9.036703969854680274e-01,6.839316092015533532e-02,1.000000008307851962e+00,0.000000000000000000e+00 +5.636882233712565693e+01,3.465046259438385050e+02,2.522720836852742829e-02,4.214466506473224072e+00,3.743170972929436152e-02,9.060443850075767802e-01,6.839316092015533532e-02,1.000000007999995999e+00,0.000000000000000000e+00 +5.637119511668971938e+01,3.465146189389919869e+02,2.560143806061099259e-02,4.216616350074106734e+00,3.768170972929436174e-02,9.084171645906249370e-01,6.839316092015533532e-02,1.000000008022394304e+00,0.000000000000000000e+00 +5.637356668649113800e+01,3.465246118402757816e+02,2.597816598976222455e-02,4.218770724788739379e+00,3.793170972929436197e-02,9.107887344110683348e-01,6.839316092015533532e-02,1.000000007974348293e+00,0.000000000000000000e+00 +5.637593704521702165e+01,3.465346046470652936e+02,2.635739213243563223e-02,4.220929620812785998e+00,3.818170972929436219e-02,9.131590931558527524e-01,6.839316092015533532e-02,1.000000007897916543e+00,0.000000000000000000e+00 +5.637830619156589762e+01,3.465445973587359845e+02,2.673911646492958122e-02,4.223093028344276689e+00,3.843170972929436241e-02,9.155282395234374260e-01,6.839316092015533532e-02,1.000000007963616655e+00,0.000000000000000000e+00 +5.638067412424767610e+01,3.465545899746633154e+02,2.712333896338629813e-02,4.225260937583733778e+00,3.868170972929436263e-02,9.178961722240714938e-01,6.839316092015533532e-02,1.000000007836597815e+00,0.000000000000000000e+00 +5.638304084198362887e+01,3.465645824942228046e+02,2.751005960379188098e-02,4.227433338734297941e+00,3.893170972929436285e-02,9.202628899785694205e-01,6.839316092015533532e-02,1.000000007626145049e+00,0.000000000000000000e+00 +5.638540634350635372e+01,3.465745749167898566e+02,2.789927836197628533e-02,4.229610222001850772e+00,3.918170972929436308e-02,9.226283915193354002e-01,6.839316092015533532e-02,1.000000007730088347e+00,0.000000000000000000e+00 +5.638777062755976033e+01,3.465845672417399328e+02,2.829099521361334163e-02,4.231791577595139131e+00,3.943170972929436330e-02,9.249926755910170550e-01,6.839316092015533532e-02,1.000000007563185633e+00,0.000000000000000000e+00 +5.639013369289902045e+01,3.465945594684485513e+02,2.868521013422074828e-02,4.233977395725900372e+00,3.968170972929436352e-02,9.273557409481523184e-01,6.839316092015533532e-02,1.000000007621995923e+00,0.000000000000000000e+00 +5.639249553829056794e+01,3.466045515962911736e+02,2.908192309916007162e-02,4.236167666608981364e+00,3.993170972929436374e-02,9.297175863576990773e-01,6.839316092015533532e-02,1.000000007259219226e+00,0.000000000000000000e+00 +5.639485616251203481e+01,3.466145436246433178e+02,2.948113408363674942e-02,4.238362380462462831e+00,4.018170972929436396e-02,9.320782105963041353e-01,6.839316092015533532e-02,1.000000007390049239e+00,0.000000000000000000e+00 +5.639721556435225835e+01,3.466245355528804453e+02,2.988284306270009780e-02,4.240561527507776596e+00,4.043170972929436419e-02,9.344376124539643946e-01,6.839316092015533532e-02,1.000000007306584227e+00,0.000000000000000000e+00 +5.639957374261123135e+01,3.466345273803780742e+02,3.028705001124330429e-02,4.242765097969830812e+00,4.068170972929436441e-02,9.367957907301661669e-01,6.839316092015533532e-02,1.000000007066373264e+00,0.000000000000000000e+00 +5.640193069610007370e+01,3.466445191065117228e+02,3.069375490400343479e-02,4.244973082077125426e+00,4.093170972929436463e-02,9.391527442356639721e-01,6.839316092015533532e-02,1.000000006857374002e+00,0.000000000000000000e+00 +5.640428642364101108e+01,3.466545107306569093e+02,3.110295771556143354e-02,4.247185470061871193e+00,4.118170972929436485e-02,9.415084717927585389e-01,6.839316092015533532e-02,1.000000007158622140e+00,0.000000000000000000e+00 +5.640664092406734653e+01,3.466645022521891519e+02,3.151465842034213011e-02,4.249402252160108695e+00,4.143170972929436507e-02,9.438629722359521690e-01,6.839316092015533532e-02,1.000000006495567861e+00,0.000000000000000000e+00 +5.640899419622342492e+01,3.466744936704840256e+02,3.192885699261422544e-02,4.251623418611828242e+00,4.168170972929436530e-02,9.462162444073198841e-01,6.839316092015533532e-02,1.000000006889794957e+00,0.000000000000000000e+00 +5.641134623896461164e+01,3.466844849849169918e+02,3.234555340649030580e-02,4.253848959661078233e+00,4.193170972929436552e-02,9.485682871647104220e-01,6.839316092015533532e-02,1.000000006161630983e+00,0.000000000000000000e+00 +5.641369705115724997e+01,3.466944761948636256e+02,3.276474763592684969e-02,4.256078865556092161e+00,4.218170972929436574e-02,9.509190993718305007e-01,6.839316092015533532e-02,1.000000006435846522e+00,0.000000000000000000e+00 +5.641604663167863976e+01,3.467044672996995018e+02,3.318643965472421742e-02,4.258313126549391647e+00,4.243170972929436596e-02,9.532686799083396334e-01,6.839316092015533532e-02,1.000000006111588791e+00,0.000000000000000000e+00 +5.641839497941700898e+01,3.467144582988001389e+02,3.361062943652665808e-02,4.260551732897912558e+00,4.268170972929436618e-02,9.556170276610609360e-01,6.839316092015533532e-02,1.000000005806887193e+00,0.000000000000000000e+00 +5.642074209327148537e+01,3.467244491915411118e+02,3.403731695482230951e-02,4.262794674863109812e+00,4.293170972929436641e-02,9.579641415291672013e-01,6.839316092015533532e-02,1.000000005628111532e+00,0.000000000000000000e+00 +5.642308797215206084e+01,3.467344399772979955e+02,3.446650218294320528e-02,4.265041942711073730e+00,4.318170972929436663e-02,9.603100204229476633e-01,6.839316092015533532e-02,1.000000005327588148e+00,0.000000000000000000e+00 +5.642543261497957019e+01,3.467444306554463651e+02,3.489818509406526770e-02,4.267293526712642837e+00,4.343170972929436685e-02,9.626546632629473521e-01,6.839316092015533532e-02,1.000000005110907253e+00,0.000000000000000000e+00 +5.642777602068564846e+01,3.467544212253617957e+02,3.533236566120830785e-02,4.269549417143513992e+00,4.368170972929436707e-02,9.649980689810003787e-01,6.839316092015533532e-02,1.000000004829828759e+00,0.000000000000000000e+00 +5.643011818821270253e+01,3.467644116864198622e+02,3.576904385723604640e-02,4.271809604284354300e+00,4.393170972929436729e-02,9.673402365193699559e-01,6.839316092015533532e-02,1.000000004303703394e+00,0.000000000000000000e+00 +5.643245911651390401e+01,3.467744020379961967e+02,3.620821965485609972e-02,4.274074078420910361e+00,4.418170972929436752e-02,9.696811648306429277e-01,6.839316092015533532e-02,1.000000003968998685e+00,0.000000000000000000e+00 +5.643479880455311815e+01,3.467843922794663740e+02,3.664989302661997295e-02,4.276342829844116622e+00,4.443170972929436774e-02,9.720208528791440816e-01,6.839316092015533532e-02,1.000000003258217030e+00,0.000000000000000000e+00 +5.643713725130491099e+01,3.467943824102060262e+02,3.709406394492308773e-02,4.278615848850206405e+00,4.468170972929436796e-02,9.743592996385557203e-01,6.839316092015533532e-02,1.000000002870110816e+00,0.000000000000000000e+00 +5.643947445575449962e+01,3.468043724295907850e+02,3.754073238200475449e-02,4.280893125740816707e+00,4.493170972929436818e-02,9.766965040948493160e-01,6.839316092015533532e-02,1.000000002010081879e+00,0.000000000000000000e+00 +5.644181041689771661e+01,3.468143623369962256e+02,3.798989830994820016e-02,4.283174650823099228e+00,4.518170972929436841e-02,9.790324652427628838e-01,6.839316092015533532e-02,1.000000001151206019e+00,0.000000000000000000e+00 +5.644414513374100295e+01,3.468243521317979798e+02,3.844156170068055434e-02,4.285460414409822505e+00,4.543170972929436863e-02,9.813671820887337471e-01,6.839316092015533532e-02,1.000000000084614538e+00,0.000000000000000000e+00 +5.644647860530134409e+01,3.468343418133717364e+02,3.889572252597285618e-02,4.287750406819480276e+00,4.568170972929436885e-02,9.837006536492739484e-01,6.839316092015533532e-02,9.999999984042725609e-01,0.000000000000000000e+00 +5.644881083060626992e+01,3.468443313810930704e+02,3.935238075744005443e-02,4.290044618376395391e+00,4.593170972929436907e-02,9.860328789504804181e-01,6.839316092015533532e-02,9.999999968144783757e-01,0.000000000000000000e+00 +5.645114180869381215e+01,3.468543208343377273e+02,3.981153636654100741e-02,4.292343039410821959e+00,4.618170972929436929e-02,9.883638570305940396e-01,6.839316092015533532e-02,9.999999938621506601e-01,0.000000000000000000e+00 +5.645347153861245459e+01,3.468643101724812823e+02,4.027318932457848999e-02,4.294645660259052811e+00,4.643170972929436952e-02,9.906935869349388080e-01,6.839316092015533532e-02,9.999999898568752155e-01,0.000000000000000000e+00 +5.645580001942113313e+01,3.468742993948994240e+02,4.073733960269919352e-02,4.296952471263514539e+00,4.668170972929436974e-02,9.930220677200021218e-01,6.839316092015533532e-02,9.999999829432840714e-01,0.000000000000000000e+00 +5.645812725018918599e+01,3.468842885009678412e+02,4.120398717189372589e-02,4.299263462772871414e+00,4.693170972929436996e-02,9.953492984483635064e-01,6.839316092015533532e-02,9.999999690879678438e-01,0.000000000000000000e+00 +5.646045322999633242e+01,3.468942774900622226e+02,4.167313200299661152e-02,4.301578625142116863e+00,4.718170972929437018e-02,9.976752781836063511e-01,6.839316092015533532e-02,9.999999261143563967e-01,0.000000000000000000e+00 +5.646277795793261589e+01,3.469042663615582569e+02,4.214477406668630521e-02,4.303897948732652523e+00,4.743170972929437040e-02,1.000000005948128656e+00,6.839316092015533532e-02,1.663537065600766720e-06,0.000000000000000000e+00 +5.646510143309841112e+01,3.469142551148315761e+02,4.261891333348517136e-02,4.306221423912268698e+00,4.768170972929437063e-02,1.000000009813315716e+00,6.839316092015533532e-02,-1.759358752017841888e-11,0.000000000000000000e+00 +5.646742365460436019e+01,3.469242437492579256e+02,4.309554977375951168e-02,4.308543645441009318e+00,4.793170972929437085e-02,1.000000009813274859e+00,6.839316092015533532e-02,-2.688295729067310526e-11,0.000000000000000000e+00 +5.646974462447792575e+01,3.469342322642130512e+02,4.357468335771954443e-02,4.310864615337348660e+00,4.818170972929437107e-02,1.000000009813212465e+00,6.839316092015533532e-02,-2.522233147098410322e-10,0.000000000000000000e+00 +5.647206434474109926e+01,3.469442206590726414e+02,4.405631405541941825e-02,4.313184335623287069e+00,4.843170972929437129e-02,1.000000009812627377e+00,6.839316092015533532e-02,-3.907494792031010528e-11,0.000000000000000000e+00 +5.647438281741044364e+01,3.469542089332124419e+02,4.454044183675721913e-02,4.315502808315384797e+00,4.868170972929437151e-02,1.000000009812536783e+00,6.839316092015533532e-02,-2.013249877979156078e-10,0.000000000000000000e+00 +5.647670004449710746e+01,3.469641970860081415e+02,4.502706667147496344e-02,4.317820035424785985e+00,4.893170972929437174e-02,1.000000009812070267e+00,6.839316092015533532e-02,-4.688280868687045283e-11,0.000000000000000000e+00 +5.647901602800683207e+01,3.469741851168354856e+02,4.551618852915859104e-02,4.320136018957234647e+00,4.918170972929437196e-02,1.000000009811961688e+00,6.839316092015533532e-02,-1.890707167132512424e-10,0.000000000000000000e+00 +5.648133076993998714e+01,3.469841730250702767e+02,4.600780737923799296e-02,4.322450760913098655e+00,4.943170972929437218e-02,1.000000009811524038e+00,6.839316092015533532e-02,-6.459298345294939816e-11,0.000000000000000000e+00 +5.648364427229157769e+01,3.469941608100882036e+02,4.650192319098699067e-02,4.324764263287386612e+00,4.968170972929437240e-02,1.000000009811374602e+00,6.839316092015533532e-02,-8.508174470006901223e-11,0.000000000000000000e+00 +5.648595653705127262e+01,3.470041484712650686e+02,4.699853593352334297e-02,4.327076528069770944e+00,4.993170972929437262e-02,1.000000009811177870e+00,6.839316092015533532e-02,-1.484442177150446011e-10,0.000000000000000000e+00 +5.648826756620343303e+01,3.470141360079766173e+02,4.749764557580875290e-02,4.329387557244605667e+00,5.018170972929437285e-02,1.000000009810834811e+00,6.839316092015533532e-02,-1.333346886655710389e-10,0.000000000000000000e+00 +5.649057736172711230e+01,3.470241234195986522e+02,4.799925208664887477e-02,4.331697352790946809e+00,5.043170972929437307e-02,1.000000009810526835e+00,6.839316092015533532e-02,-2.338208796500660668e-10,0.000000000000000000e+00 +5.649288592559609157e+01,3.470341107055069756e+02,4.850335543469329325e-02,4.334005916682572845e+00,5.068170972929437329e-02,1.000000009809987045e+00,6.839316092015533532e-02,4.051462478667751148e-11,0.000000000000000000e+00 +5.649519325977888684e+01,3.470440978650773332e+02,4.900995558843555117e-02,4.336313250888003346e+00,5.093170972929437351e-02,1.000000009810080526e+00,6.839316092015533532e-02,-3.036844552118003954e-10,0.000000000000000000e+00 +5.649749936623878455e+01,3.470540848976855841e+02,4.951905251621314258e-02,4.338619357370521179e+00,5.118170972929437373e-02,1.000000009809380197e+00,6.839316092015533532e-02,9.460264147471368778e-11,0.000000000000000000e+00 +5.649980424693384151e+01,3.470640718027075309e+02,5.003064618620751275e-02,4.340924238088186726e+00,5.143170972929437396e-02,1.000000009809598245e+00,6.839316092015533532e-02,-3.930697776804686408e-10,0.000000000000000000e+00 +5.650210790381692050e+01,3.470740585795189190e+02,5.054473656644405122e-02,4.343227894993864524e+00,5.168170972929437418e-02,1.000000009808692747e+00,6.839316092015533532e-02,1.334716205707910545e-10,0.000000000000000000e+00 +5.650441033883570441e+01,3.470840452274956647e+02,5.106132362479211262e-02,4.345530330035233924e+00,5.193170972929437440e-02,1.000000009809000057e+00,6.839316092015533532e-02,-2.574357376280201875e-10,0.000000000000000000e+00 +5.650671155393271761e+01,3.470940317460135702e+02,5.158040732896500280e-02,4.347831545154818400e+00,5.218170972929437462e-02,1.000000009808407642e+00,6.839316092015533532e-02,-1.309099401154408427e-10,0.000000000000000000e+00 +5.650901155104533302e+01,3.471040181344484381e+02,5.210198764651999270e-02,4.350131542289994435e+00,5.243170972929437484e-02,1.000000009808106549e+00,6.839316092015533532e-02,-4.501202296907396539e-11,0.000000000000000000e+00 +5.651131033210580767e+01,3.471140043921761844e+02,5.262606454485831142e-02,4.352430323373018162e+00,5.268170972929437507e-02,1.000000009808003076e+00,6.839316092015533532e-02,-2.074933092961887844e-10,0.000000000000000000e+00 +5.651360789904129689e+01,3.471239905185726116e+02,5.315263799122515315e-02,4.354727890331041351e+00,5.293170972929437529e-02,1.000000009807526347e+00,6.839316092015533532e-02,-1.358556086720222425e-10,0.000000000000000000e+00 +5.651590425377386140e+01,3.471339765130136357e+02,5.368170795270967716e-02,4.357024245086129177e+00,5.318170972929437551e-02,1.000000009807214374e+00,6.839316092015533532e-02,-1.717230365689354689e-10,0.000000000000000000e+00 +5.651819939822050287e+01,3.471439623748751160e+02,5.421327439624501476e-02,4.359319389555281532e+00,5.343170972929437573e-02,1.000000009806820245e+00,6.839316092015533532e-02,3.407230997617325698e-11,0.000000000000000000e+00 +5.652049333429317812e+01,3.471539481035329118e+02,5.474733728860825543e-02,4.361613325650449902e+00,5.368170972929437595e-02,1.000000009806898404e+00,6.839316092015533532e-02,-3.346073205206480012e-10,0.000000000000000000e+00 +5.652278606389879911e+01,3.471639336983629391e+02,5.528389659642047455e-02,4.363906055278557794e+00,5.393170972929437618e-02,1.000000009806131240e+00,6.839316092015533532e-02,-5.048395157025994538e-11,0.000000000000000000e+00 +5.652507758893928269e+01,3.471739191587410573e+02,5.582295228614671950e-02,4.366197580341514950e+00,5.418170972929437640e-02,1.000000009806015555e+00,6.839316092015533532e-02,-6.524671850737994713e-11,0.000000000000000000e+00 +5.652736791131155059e+01,3.471839044840432393e+02,5.636450432409600281e-02,4.368487902736242212e+00,5.443170972929437662e-02,1.000000009805866119e+00,6.839316092015533532e-02,-1.326958865220535447e-10,0.000000000000000000e+00 +5.652965703290754362e+01,3.471938896736453444e+02,5.690855267642132287e-02,4.370777024354684848e+00,5.468170972929437684e-02,1.000000009805562362e+00,6.839316092015533532e-02,-1.579015633496066415e-10,0.000000000000000000e+00 +5.653194495561425725e+01,3.472038747269233454e+02,5.745509730911965707e-02,4.373064947083832088e+00,5.493170972929437706e-02,1.000000009805201096e+00,6.839316092015533532e-02,-1.998349854725695490e-10,0.000000000000000000e+00 +5.653423168131374155e+01,3.472138596432531585e+02,5.800413818803196869e-02,4.375351672805735781e+00,5.518170972929437729e-02,1.000000009804744128e+00,6.839316092015533532e-02,3.954099560736633368e-11,0.000000000000000000e+00 +5.653651721188312251e+01,3.472238444220106999e+02,5.855567527884320694e-02,4.377637203397528154e+00,5.543170972929437751e-02,1.000000009804834500e+00,6.839316092015533532e-02,-3.165904065897284697e-10,0.000000000000000000e+00 +5.653880154919463763e+01,3.472338290625719424e+02,5.910970854708229999e-02,4.379921540731441354e+00,5.568170972929437773e-02,1.000000009804111301e+00,6.839316092015533532e-02,-8.772292291991412691e-11,0.000000000000000000e+00 +5.654108469511563584e+01,3.472438135643128589e+02,5.966623795812216885e-02,4.382204686674820771e+00,5.593170972929437795e-02,1.000000009803911016e+00,6.839316092015533532e-02,-1.187114788191064087e-10,0.000000000000000000e+00 +5.654336665150859176e+01,3.472537979266094226e+02,6.022526347717972045e-02,4.384486643090149016e+00,5.618170972929437818e-02,1.000000009803640122e+00,6.839316092015533532e-02,-4.770402861873741786e-11,0.000000000000000000e+00 +5.654564742023114121e+01,3.472637821488376062e+02,6.078678506931586845e-02,4.386767411835059249e+00,5.643170972929437840e-02,1.000000009803531320e+00,6.839316092015533532e-02,-3.490049946065502537e-10,0.000000000000000000e+00 +5.654792700313608833e+01,3.472737662303733828e+02,6.135080269943550546e-02,4.389046994762354714e+00,5.668170972929437862e-02,1.000000009802735734e+00,6.839316092015533532e-02,5.584252900090079704e-11,0.000000000000000000e+00 +5.655020540207141977e+01,3.472837501705927252e+02,6.191731633228753778e-02,4.391325393720023840e+00,5.693170972929437884e-02,1.000000009802862966e+00,6.839316092015533532e-02,-3.027592698212771874e-10,0.000000000000000000e+00 +5.655248261888033312e+01,3.472937339688716634e+02,6.248632593246485761e-02,4.393602610551263332e+00,5.718170972929437906e-02,1.000000009802173517e+00,6.839316092015533532e-02,2.907215752455175553e-11,0.000000000000000000e+00 +5.655475865540125113e+01,3.473037176245862270e+02,6.305783146440437081e-02,4.395878647094487945e+00,5.743170972929437929e-02,1.000000009802239687e+00,6.839316092015533532e-02,-2.185445666845655385e-10,0.000000000000000000e+00 +5.655703351346782171e+01,3.473137011371124458e+02,6.363183289238698304e-02,4.398153505183355350e+00,5.768170972929437951e-02,1.000000009801742529e+00,6.839316092015533532e-02,-7.226738305189790081e-11,0.000000000000000000e+00 +5.655930719490896053e+01,3.473236845058262929e+02,6.420833018053759278e-02,4.400427186646776789e+00,5.793170972929437973e-02,1.000000009801578216e+00,6.839316092015533532e-02,-2.589291457824929251e-10,0.000000000000000000e+00 +5.656157970154885106e+01,3.473336677301038549e+02,6.478732329282513303e-02,4.402699693308939288e+00,5.818170972929437995e-02,1.000000009800989798e+00,6.839316092015533532e-02,5.640727269805041423e-11,0.000000000000000000e+00 +5.656385103520696589e+01,3.473436508093211614e+02,6.536881219306252266e-02,4.404971026989318972e+00,5.843170972929438017e-02,1.000000009801117917e+00,6.839316092015533532e-02,-3.403788178851303535e-10,0.000000000000000000e+00 +5.656612119769810221e+01,3.473536337428542424e+02,6.595279684490670813e-02,4.407241189502702383e+00,5.868170972929438040e-02,1.000000009800345202e+00,6.839316092015533532e-02,-6.605577868944055999e-11,0.000000000000000000e+00 +5.656839019083236053e+01,3.473636165300792413e+02,6.653927721185866340e-02,4.409510182659197142e+00,5.893170972929438062e-02,1.000000009800195322e+00,6.839316092015533532e-02,-1.332565915079612392e-10,0.000000000000000000e+00 +5.657065801641519442e+01,3.473735991703721879e+02,6.712825325726334835e-02,4.411778008264255924e+00,5.918170972929438084e-02,1.000000009799893119e+00,6.839316092015533532e-02,-1.617338594527125936e-10,0.000000000000000000e+00 +5.657292467624741050e+01,3.473835816631091689e+02,6.771972494430976430e-02,4.414044668118688008e+00,5.943170972929438106e-02,1.000000009799526524e+00,6.839316092015533532e-02,-1.003637559760747570e-10,0.000000000000000000e+00 +5.657519017212519685e+01,3.473935640076662708e+02,6.831369223603094010e-02,4.416310164018677931e+00,5.968170972929438128e-02,1.000000009799299150e+00,6.839316092015533532e-02,-2.289742669466490733e-10,0.000000000000000000e+00 +5.657745450584013014e+01,3.474035462034195803e+02,6.891015509530390437e-02,4.418574497755802355e+00,5.993170972929438151e-02,1.000000009798780676e+00,6.839316092015533532e-02,-1.205797252655101148e-10,0.000000000000000000e+00 +5.657971767917919692e+01,3.474135282497452408e+02,6.950911348484974106e-02,4.420837671117045176e+00,6.018170972929438173e-02,1.000000009798507783e+00,6.839316092015533532e-02,-2.562036432255496131e-11,0.000000000000000000e+00 +5.658197969392480076e+01,3.474235101460193391e+02,7.011056736723354776e-02,4.423099685884816168e+00,6.043170972929438195e-02,1.000000009798449829e+00,6.839316092015533532e-02,-1.810057153292125251e-10,0.000000000000000000e+00 +5.658424055185479773e+01,3.474334918916180754e+02,7.071451670486446350e-02,4.425360543836966087e+00,6.068170972929438217e-02,1.000000009798040601e+00,6.839316092015533532e-02,-2.881063635336019621e-10,0.000000000000000000e+00 +5.658650025474248935e+01,3.474434734859175364e+02,7.132096145999564096e-02,4.427620246746801769e+00,6.093170972929438239e-02,1.000000009797389566e+00,6.839316092015533532e-02,-3.224663738106039057e-11,0.000000000000000000e+00 +5.658875880435666517e+01,3.474534549282938656e+02,7.192990159472430201e-02,4.429878796383103889e+00,6.118170972929438262e-02,1.000000009797316736e+00,6.839316092015533532e-02,-1.288556200243343997e-10,0.000000000000000000e+00 +5.659101620246158859e+01,3.474634362181232632e+02,7.254133707099166828e-02,4.432136194510144733e+00,6.143170972929438284e-02,1.000000009797025857e+00,6.839316092015533532e-02,-2.351091181448324988e-10,0.000000000000000000e+00 +5.659327245081703950e+01,3.474734173547818727e+02,7.315526785058303061e-02,4.434392442887700625e+00,6.168170972929438306e-02,1.000000009796495393e+00,6.839316092015533532e-02,7.975526636314706044e-12,0.000000000000000000e+00 +5.659552755117831424e+01,3.474833983376458946e+02,7.377169389512772124e-02,4.436647543271069694e+00,6.193170972929438328e-02,1.000000009796513378e+00,6.839316092015533532e-02,-2.489432735918393961e-10,0.000000000000000000e+00 +5.659778150529625407e+01,3.474933791660914721e+02,7.439061516609909996e-02,4.438901497411089636e+00,6.218170972929438350e-02,1.000000009795952272e+00,6.839316092015533532e-02,-2.692752441230593955e-10,0.000000000000000000e+00 +5.660003431491724513e+01,3.475033598394948626e+02,7.501203162481459574e-02,4.441154307054149264e+00,6.243170972929438373e-02,1.000000009795345646e+00,6.839316092015533532e-02,2.958403060562819187e-13,0.000000000000000000e+00 +5.660228598178324688e+01,3.475133403572322095e+02,7.563594323243567896e-02,4.443405973942208043e+00,6.268170972929437701e-02,1.000000009795346312e+00,6.839316092015533532e-02,-7.409623773281465962e-11,0.000000000000000000e+00 +5.660453650763180633e+01,3.475233207186797699e+02,7.626234994996787531e-02,4.445656499812812079e+00,6.293170972929437723e-02,1.000000009795179556e+00,6.839316092015533532e-02,-2.375044502966799886e-10,0.000000000000000000e+00 +5.660678589419606510e+01,3.475333009232138011e+02,7.689125173826076576e-02,4.447905886399106556e+00,6.318170972929437745e-02,1.000000009794645317e+00,6.839316092015533532e-02,-2.196496915763204834e-10,0.000000000000000000e+00 +5.660903414320478788e+01,3.475432809702105033e+02,7.752264855800798660e-02,4.450154135429852609e+00,6.343170972929437768e-02,1.000000009794151490e+00,6.839316092015533532e-02,-8.656042599667460132e-11,0.000000000000000000e+00 +5.661128125638236952e+01,3.475532608590461336e+02,7.815654036974724328e-02,4.452401248629444197e+00,6.368170972929437790e-02,1.000000009793956979e+00,6.839316092015533532e-02,-2.434011186852756007e-10,0.000000000000000000e+00 +5.661352723544884924e+01,3.475632405890968926e+02,7.879292713386029656e-02,4.454647227717923208e+00,6.393170972929437812e-02,1.000000009793410305e+00,6.839316092015533532e-02,-2.551956390098251587e-11,0.000000000000000000e+00 +5.661577208211993195e+01,3.475732201597390940e+02,7.943180881057296250e-02,4.456892074410992777e+00,6.418170972929437834e-02,1.000000009793353017e+00,6.839316092015533532e-02,-1.626949812723415480e-10,0.000000000000000000e+00 +5.661801579810700247e+01,3.475831995703490520e+02,8.007318535995515407e-02,4.459135790420035939e+00,6.443170972929437856e-02,1.000000009792987976e+00,6.839316092015533532e-02,-1.388158116937019512e-10,0.000000000000000000e+00 +5.662025838511713260e+01,3.475931788203030237e+02,8.071705674192082569e-02,4.461378377452127175e+00,6.468170972929437879e-02,1.000000009792676670e+00,6.839316092015533532e-02,-3.050134372667456387e-10,0.000000000000000000e+00 +5.662249984485310250e+01,3.476031579089772663e+02,8.136342291622801481e-02,4.463619837210050179e+00,6.493170972929437901e-02,1.000000009791992994e+00,6.839316092015533532e-02,6.154871987423683725e-11,0.000000000000000000e+00 +5.662474017901342904e+01,3.476131368357481506e+02,8.201228384247884196e-02,4.465860171392311173e+00,6.518170972929437923e-02,1.000000009792130884e+00,6.839316092015533532e-02,-2.490949835406982431e-10,0.000000000000000000e+00 +5.662697938929235164e+01,3.476231155999919338e+02,8.266363948011949681e-02,4.468099381693157568e+00,6.543170972929437945e-02,1.000000009791573108e+00,6.839316092015533532e-02,-1.328445147682963503e-10,0.000000000000000000e+00 +5.662921747737986777e+01,3.476330942010849867e+02,8.331748978844025211e-02,4.470337469802586838e+00,6.568170972929437967e-02,1.000000009791275790e+00,6.839316092015533532e-02,-2.425949391637321568e-10,0.000000000000000000e+00 +5.663145444496174719e+01,3.476430726384036234e+02,8.397383472657546366e-02,4.472574437406366954e+00,6.593170972929437990e-02,1.000000009790733113e+00,6.839316092015533532e-02,-1.545280753268831039e-10,0.000000000000000000e+00 +5.663369029371953900e+01,3.476530509113242147e+02,8.463267425350357032e-02,4.474810286186047925e+00,6.618170972929438012e-02,1.000000009790387612e+00,6.839316092015533532e-02,-1.411916232079229806e-10,0.000000000000000000e+00 +5.663592502533059303e+01,3.476630290192230746e+02,8.529400832804709398e-02,4.477045017818978678e+00,6.643170972929438034e-02,1.000000009790072086e+00,6.839316092015533532e-02,-1.073631987590250555e-10,0.000000000000000000e+00 +5.663815864146806689e+01,3.476730069614766307e+02,8.595783690887266737e-02,4.479278633978320379e+00,6.668170972929438056e-02,1.000000009789832278e+00,6.839316092015533532e-02,-1.219379176577422031e-10,0.000000000000000000e+00 +5.664039114380095441e+01,3.476829847374612541e+02,8.662415995449100625e-02,4.481511136333061529e+00,6.693170972929438078e-02,1.000000009789560051e+00,6.839316092015533532e-02,-2.413106271605441747e-10,0.000000000000000000e+00 +5.664262253399407854e+01,3.476929623465533155e+02,8.729297742325690945e-02,4.483742526548032181e+00,6.718170972929438101e-02,1.000000009789021593e+00,6.839316092015533532e-02,-1.522258391138274026e-10,0.000000000000000000e+00 +5.664485281370813397e+01,3.477029397881291857e+02,8.796428927336930048e-02,4.485972806283918146e+00,6.743170972929438123e-02,1.000000009788682087e+00,6.839316092015533532e-02,-6.245459592912931564e-11,0.000000000000000000e+00 +5.664708198459967292e+01,3.477129170615652924e+02,8.863809546287118590e-02,4.488201977197276982e+00,6.768170972929438145e-02,1.000000009788542865e+00,6.839316092015533532e-02,-3.475078068523741662e-10,0.000000000000000000e+00 +5.664931004832114070e+01,3.477228941662380635e+02,8.931439594964966922e-02,4.490430040940551315e+00,6.793170972929438167e-02,1.000000009787768596e+00,6.839316092015533532e-02,6.141986708606283107e-11,0.000000000000000000e+00 +5.665153700652087565e+01,3.477328711015239264e+02,8.999319069143597860e-02,4.492656999162081277e+00,6.818170972929438189e-02,1.000000009787905375e+00,6.839316092015533532e-02,-2.589692364957044063e-10,0.000000000000000000e+00 +5.665376286084313051e+01,3.477428478667993659e+02,9.067447964580543918e-02,4.494882853506124043e+00,6.843170972929438212e-02,1.000000009787328947e+00,6.839316092015533532e-02,-2.138852196479051739e-10,0.000000000000000000e+00 +5.665598761292809371e+01,3.477528244614407527e+02,9.135826277017748687e-02,4.497107605612860937e+00,6.868170972929438234e-02,1.000000009786853106e+00,6.839316092015533532e-02,-1.270166388587136963e-10,0.000000000000000000e+00 +5.665821126441188937e+01,3.477628008848246282e+02,9.204454002181568228e-02,4.499331257118416971e+00,6.893170972929438256e-02,1.000000009786570665e+00,6.839316092015533532e-02,-1.319747997697502079e-10,0.000000000000000000e+00 +5.666043381692659153e+01,3.477727771363274201e+02,9.273331135782769685e-02,4.501553809654873284e+00,6.918170972929438278e-02,1.000000009786277344e+00,6.839316092015533532e-02,-1.698228207525882445e-10,0.000000000000000000e+00 +5.666265527210025965e+01,3.477827532153256129e+02,9.342457673516532668e-02,4.503775264850280458e+00,6.943170972929438300e-02,1.000000009785900090e+00,6.839316092015533532e-02,-1.692065986908336312e-10,0.000000000000000000e+00 +5.666487563155692442e+01,3.477927291211956913e+02,9.411833611062447869e-02,4.505995624328672733e+00,6.968170972929438323e-02,1.000000009785524391e+00,6.839316092015533532e-02,-2.259201297091038601e-10,0.000000000000000000e+00 +5.666709489691661616e+01,3.478027048533141965e+02,9.481458944084519835e-02,4.508214889710082218e+00,6.993170972929438345e-02,1.000000009785023014e+00,6.839316092015533532e-02,-2.436494348846260859e-10,0.000000000000000000e+00 +5.666931306979537908e+01,3.478126804110576131e+02,9.551333668231164198e-02,4.510433062610552213e+00,7.018170972929438367e-02,1.000000009784482558e+00,6.839316092015533532e-02,6.780272306688636981e-11,0.000000000000000000e+00 +5.667153015180528541e+01,3.478226557938024825e+02,9.621457779135211830e-02,4.512650144642151417e+00,7.043170972929438389e-02,1.000000009784632882e+00,6.839316092015533532e-02,-2.543100411834094030e-10,0.000000000000000000e+00 +5.667374614455444259e+01,3.478326310009253461e+02,9.691831272413904685e-02,4.514866137412989033e+00,7.068170972929438411e-02,1.000000009784069332e+00,6.839316092015533532e-02,-3.541838392235894122e-10,0.000000000000000000e+00 +5.667596104964700743e+01,3.478426060318027453e+02,9.762454143668899964e-02,4.517081042527223644e+00,7.093170972929438434e-02,1.000000009783284849e+00,6.839316092015533532e-02,9.708976842862320830e-11,0.000000000000000000e+00 +5.667817486868320742e+01,3.478525808858112782e+02,9.833326388486268721e-02,4.519294861585080980e+00,7.118170972929438456e-02,1.000000009783499788e+00,6.839316092015533532e-02,-3.734971326623186324e-10,0.000000000000000000e+00 +5.668038760325934788e+01,3.478625555623274863e+02,9.904448002436495868e-02,4.521507596182869015e+00,7.143170972929438478e-02,1.000000009782673338e+00,6.839316092015533532e-02,3.644434215331630260e-11,0.000000000000000000e+00 +5.668259925496782614e+01,3.478725300607279678e+02,9.975818981074480174e-02,4.523719247912984187e+00,7.168170972929438500e-02,1.000000009782753940e+00,6.839316092015533532e-02,-3.049563187898800468e-10,0.000000000000000000e+00 +5.668480982539715285e+01,3.478825043803892640e+02,1.004743931993953565e-01,4.525929818363933599e+00,7.193170972929438522e-02,1.000000009782079813e+00,6.839316092015533532e-02,-2.953572439106455596e-10,0.000000000000000000e+00 +5.668701931613194489e+01,3.478924785206880301e+02,1.011930901455539017e-01,4.528139309120340350e+00,7.218170972929438545e-02,1.000000009781427224e+00,6.839316092015533532e-02,9.189802982003649289e-11,0.000000000000000000e+00 +5.668922772875296801e+01,3.479024524810008643e+02,1.019142806043018962e-01,4.530347721762962188e+00,7.243170972929438567e-02,1.000000009781630173e+00,6.839316092015533532e-02,-3.813515772766648822e-10,0.000000000000000000e+00 +5.669143506483712258e+01,3.479124262607044216e+02,1.026379645305649235e-01,4.532555057868704829e+00,7.268170972929438589e-02,1.000000009780788401e+00,6.839316092015533532e-02,-2.626780726497317043e-11,0.000000000000000000e+00 +5.669364132595746497e+01,3.479223998591753002e+02,1.033641418791127337e-01,4.534761319010629066e+00,7.293170972929438611e-02,1.000000009780730448e+00,6.839316092015533532e-02,-2.414592446650651699e-10,0.000000000000000000e+00 +5.669584651368324302e+01,3.479323732757901553e+02,1.040928126045592567e-01,4.536966506757972084e+00,7.318170972929438634e-02,1.000000009780197985e+00,6.839316092015533532e-02,-2.238462654794706832e-10,0.000000000000000000e+00 +5.669805062957986763e+01,3.479423465099256987e+02,1.048239766613625612e-01,4.539170622676153677e+00,7.343170972929438656e-02,1.000000009779704602e+00,6.839316092015533532e-02,-7.226631152287948589e-11,0.000000000000000000e+00 +5.670025367520896253e+01,3.479523195609585287e+02,1.055576340038248961e-01,4.541373668326793123e+00,7.368170972929438678e-02,1.000000009779545396e+00,6.839316092015533532e-02,-2.392903589707335894e-10,0.000000000000000000e+00 +5.670245565212835714e+01,3.479622924282654139e+02,1.062937845860926905e-01,4.543575645267721619e+00,7.393170972929438700e-02,1.000000009779018484e+00,6.839316092015533532e-02,-2.520173394832962684e-10,0.000000000000000000e+00 +5.670465656189210790e+01,3.479722651112229528e+02,1.070324283621565259e-01,4.545776555052992940e+00,7.418170972929438722e-02,1.000000009778463816e+00,6.839316092015533532e-02,9.891778560593272414e-12,0.000000000000000000e+00 +5.670685640605050537e+01,3.479822376092079139e+02,1.077735652858511639e-01,4.547976399232898537e+00,7.443170972929438745e-02,1.000000009778485577e+00,6.839316092015533532e-02,-2.410520597566396743e-10,0.000000000000000000e+00 +5.670905518615008845e+01,3.479922099215970093e+02,1.085171953108555465e-01,4.550175179353980859e+00,7.468170972929438767e-02,1.000000009777955556e+00,6.839316092015533532e-02,-3.120945974771515779e-10,0.000000000000000000e+00 +5.671125290373365857e+01,3.480021820477669507e+02,1.092633183906927957e-01,4.552372896959042237e+00,7.493170972929438789e-02,1.000000009777269661e+00,6.839316092015533532e-02,-4.872199835435649458e-11,0.000000000000000000e+00 +5.671344956034030105e+01,3.480121539870945071e+02,1.100119344787302139e-01,4.554569553587160868e+00,7.518170972929438811e-02,1.000000009777162635e+00,6.839316092015533532e-02,-2.056008674964959138e-10,0.000000000000000000e+00 +5.671564515750537794e+01,3.480221257389564471e+02,1.107630435281793113e-01,4.556765150773704143e+00,7.543170972929438833e-02,1.000000009776711218e+00,6.839316092015533532e-02,-2.388871882747326800e-10,0.000000000000000000e+00 +5.671783969676055648e+01,3.480320973027294826e+02,1.115166454920957645e-01,4.558959690050337521e+00,7.568170972929438856e-02,1.000000009776186971e+00,6.839316092015533532e-02,-1.440492089819585043e-10,0.000000000000000000e+00 +5.672003317963381619e+01,3.480420686777904393e+02,1.122727403233794441e-01,4.561153172945039636e+00,7.593170972929438878e-02,1.000000009775871002e+00,6.839316092015533532e-02,-2.758811233483602296e-10,0.000000000000000000e+00 +5.672222560764945598e+01,3.480520398635160859e+02,1.130313279747744287e-01,4.563345600982114725e+00,7.618170972929438900e-02,1.000000009775266152e+00,6.839316092015533532e-02,-5.400709224997395950e-11,0.000000000000000000e+00 +5.672441698232812257e+01,3.480620108592831912e+02,1.137924083988689911e-01,4.565536975682203291e+00,7.643170972929438922e-02,1.000000009775147802e+00,6.839316092015533532e-02,-1.808535091600183002e-10,0.000000000000000000e+00 +5.672660730518680339e+01,3.480719816644686375e+02,1.145559815480956117e-01,4.567727298562297200e+00,7.668170972929438944e-02,1.000000009774751675e+00,6.839316092015533532e-02,-2.389547563244669898e-10,0.000000000000000000e+00 +5.672879657773885498e+01,3.480819522784491937e+02,1.153220473747309655e-01,4.569916571135748562e+00,7.693170972929438967e-02,1.000000009774228538e+00,6.839316092015533532e-02,-1.689517657097687868e-10,0.000000000000000000e+00 +5.673098480149400302e+01,3.480919227006016854e+02,1.160906058308959349e-01,4.572104794912283943e+00,7.718170972929438989e-02,1.000000009773858833e+00,6.839316092015533532e-02,-8.588686776213699157e-11,0.000000000000000000e+00 +5.673317197795835654e+01,3.481018929303029950e+02,1.168616568685556106e-01,4.574291971398016798e+00,7.743170972929439011e-02,1.000000009773670984e+00,6.839316092015533532e-02,-4.664079951734943167e-10,0.000000000000000000e+00 +5.673535810863442919e+01,3.481118629669300049e+02,1.176352004395193190e-01,4.576478102095459022e+00,7.768170972929439033e-02,1.000000009772651355e+00,6.839316092015533532e-02,8.241238226956808826e-11,0.000000000000000000e+00 +5.673754319502114640e+01,3.481218328098595407e+02,1.184112364954405805e-01,4.578663188503530712e+00,7.793170972929439055e-02,1.000000009772831433e+00,6.839316092015533532e-02,-3.819619642621622433e-10,0.000000000000000000e+00 +5.673972723861385248e+01,3.481318024584685418e+02,1.191897649878171372e-01,4.580847232117578827e+00,7.818170972929439078e-02,1.000000009771997211e+00,6.839316092015533532e-02,-7.150581469558620112e-11,0.000000000000000000e+00 +5.674191024090431767e+01,3.481417719121338337e+02,1.199707858679909533e-01,4.583030234429379846e+00,7.843170972929439100e-02,1.000000009771841114e+00,6.839316092015533532e-02,-1.652642711727672659e-10,0.000000000000000000e+00 +5.674409220338077375e+01,3.481517411702323557e+02,1.207542990871482425e-01,4.585212196927160200e+00,7.868170972929439122e-02,1.000000009771480514e+00,6.839316092015533532e-02,-1.555689851807584683e-10,0.000000000000000000e+00 +5.674627312752790687e+01,3.481617102321410471e+02,1.215403045963194123e-01,4.587393121095602488e+00,7.893170972929439144e-02,1.000000009771141229e+00,6.839316092015533532e-02,-2.703380040577958640e-10,0.000000000000000000e+00 +5.674845301482686466e+01,3.481716790972368472e+02,1.223288023463791202e-01,4.589573008415859690e+00,7.918170972929439166e-02,1.000000009770551923e+00,6.839316092015533532e-02,-3.528089321832729525e-10,0.000000000000000000e+00 +5.675063186675528470e+01,3.481816477648966952e+02,1.231197922880462731e-01,4.591751860365565818e+00,7.943170972929439189e-02,1.000000009769783205e+00,6.839316092015533532e-02,-4.822583732251112793e-11,0.000000000000000000e+00 +5.675280968478728738e+01,3.481916162344975305e+02,1.239132743718839857e-01,4.593929678418848361e+00,7.968170972929439211e-02,1.000000009769678178e+00,6.839316092015533532e-02,-1.143484233858133734e-10,0.000000000000000000e+00 +5.675498647039351141e+01,3.482015845054163492e+02,1.247092485482996227e-01,4.596106464046341600e+00,7.993170972929439233e-02,1.000000009769429266e+00,6.839316092015533532e-02,-1.765535314124415881e-10,0.000000000000000000e+00 +5.675716222504110675e+01,3.482115525770300906e+02,1.255077147675447979e-01,4.598282218715194603e+00,8.018170972929439255e-02,1.000000009769045128e+00,6.839316092015533532e-02,-4.111662675835534176e-10,0.000000000000000000e+00 +5.675933695019374881e+01,3.482215204487158076e+02,1.263086729797154029e-01,4.600456943889084549e+00,8.043170972929439277e-02,1.000000009768150955e+00,6.839316092015533532e-02,-4.484414169708257939e-11,0.000000000000000000e+00 +5.676151064731165974e+01,3.482314881198504395e+02,1.271121231347515090e-01,4.602630641028227387e+00,8.068170972929439300e-02,1.000000009768053477e+00,6.839316092015533532e-02,-1.722051974380481294e-10,0.000000000000000000e+00 +5.676368331785160137e+01,3.482414555898110393e+02,1.279180651824375070e-01,4.604803311589392933e+00,8.093170972929439322e-02,1.000000009767679332e+00,6.839316092015533532e-02,-3.766785860980298300e-10,0.000000000000000000e+00 +5.676585496326691072e+01,3.482514228579746600e+02,1.287264990724020230e-01,4.606974957025911088e+00,8.118170972929439344e-02,1.000000009766861320e+00,6.839316092015533532e-02,-3.958831725479122914e-11,0.000000000000000000e+00 +5.676802558500748574e+01,3.482613899237183546e+02,1.295374247541179191e-01,4.609145578787685160e+00,8.143170972929439366e-02,1.000000009766775388e+00,6.839316092015533532e-02,-2.286355820893357071e-10,0.000000000000000000e+00 +5.677019518451981384e+01,3.482713567864191191e+02,1.303508421769023484e-01,4.611315178321206076e+00,8.168170972929439388e-02,1.000000009766279341e+00,6.839316092015533532e-02,-1.173409634870581867e-10,0.000000000000000000e+00 +5.677236376324698597e+01,3.482813234454540634e+02,1.311667512899167276e-01,4.613483757069558600e+00,8.193170972929439411e-02,1.000000009766024878e+00,6.839316092015533532e-02,-3.774910971543770408e-10,0.000000000000000000e+00 +5.677453132262869673e+01,3.482912899002002973e+02,1.319851520421667368e-01,4.615651316472436427e+00,8.218170972929439433e-02,1.000000009765206643e+00,6.839316092015533532e-02,-1.600863298885078934e-10,0.000000000000000000e+00 +5.677669786410125141e+01,3.483012561500348738e+02,1.328060443825023196e-01,4.617817857966150186e+00,8.243170972929439455e-02,1.000000009764859810e+00,6.839316092015533532e-02,-1.179165773171025311e-10,0.000000000000000000e+00 +5.677886338909759445e+01,3.483112221943349596e+02,1.336294282596177108e-01,4.619983382983642528e+00,8.268170972929439477e-02,1.000000009764604458e+00,6.839316092015533532e-02,-3.277566420186225509e-10,0.000000000000000000e+00 +5.678102789904730940e+01,3.483211880324776075e+02,1.344553036220514364e-01,4.622147892954496129e+00,8.293170972929439499e-02,1.000000009763895026e+00,6.839316092015533532e-02,-9.760331756591358655e-11,0.000000000000000000e+00 +5.678319139537663318e+01,3.483311536638399843e+02,1.352836704181862582e-01,4.624311389304944342e+00,8.318170972929439522e-02,1.000000009763683861e+00,6.839316092015533532e-02,-2.422229209957463701e-10,0.000000000000000000e+00 +5.678535387950846314e+01,3.483411190877992567e+02,1.361145285962492568e-01,4.626473873457885411e+00,8.343170972929439544e-02,1.000000009763160058e+00,6.839316092015533532e-02,-2.392543419223661657e-10,0.000000000000000000e+00 +5.678751535286236418e+01,3.483510843037325344e+02,1.369478781043118043e-01,4.628635346832889574e+00,8.368170972929439566e-02,1.000000009762642916e+00,6.839316092015533532e-02,-1.253871478454043906e-10,0.000000000000000000e+00 +5.678967581685459720e+01,3.483610493110170410e+02,1.377837188902895638e-01,4.630795810846212390e+00,8.393170972929439588e-02,1.000000009762372022e+00,6.839316092015533532e-02,-3.082673192470895722e-10,0.000000000000000000e+00 +5.679183527289811195e+01,3.483710141090299430e+02,1.386220509019424896e-01,4.632955266910805392e+00,8.418170972929439611e-02,1.000000009761706332e+00,6.839316092015533532e-02,-4.392646022412880266e-11,0.000000000000000000e+00 +5.679399372240256127e+01,3.483809786971484641e+02,1.394628740868747996e-01,4.635113716436324971e+00,8.443170972929439633e-02,1.000000009761611519e+00,6.839316092015533532e-02,-4.838278573552825728e-10,0.000000000000000000e+00 +5.679615116677432241e+01,3.483909430747497709e+02,1.403061883925350861e-01,4.637271160829146588e+00,8.468170972929439655e-02,1.000000009760567687e+00,6.839316092015533532e-02,9.050896366533266565e-11,0.000000000000000000e+00 +5.679830760741649698e+01,3.484009072412111436e+02,1.411519937662161772e-01,4.639427601492370101e+00,8.493170972929439677e-02,1.000000009760762865e+00,6.839316092015533532e-02,-4.092825158947640525e-10,0.000000000000000000e+00 +5.680046304572892524e+01,3.484108711959098059e+02,1.420002901550552477e-01,4.641583039825838419e+00,8.518170972929439699e-02,1.000000009759880681e+00,6.839316092015533532e-02,-2.439521263945589687e-10,0.000000000000000000e+00 +5.680261748310820025e+01,3.484208349382229812e+02,1.428510775060337634e-01,4.643737477226138388e+00,8.543170972929439722e-02,1.000000009759355102e+00,6.839316092015533532e-02,-1.469341516246391344e-10,0.000000000000000000e+00 +5.680477092094766789e+01,3.484307984675279499e+02,1.437043557659775095e-01,4.645890915086619444e+00,8.568170972929439744e-02,1.000000009759038688e+00,6.839316092015533532e-02,-7.840122097015524191e-11,0.000000000000000000e+00 +5.680692336063744108e+01,3.484407617832019923e+02,1.445601248815566175e-01,4.648043354797400717e+00,8.593170972929439766e-02,1.000000009758869934e+00,6.839316092015533532e-02,-3.733007861562098219e-10,0.000000000000000000e+00 +5.680907480356442818e+01,3.484507248846223888e+02,1.454183847992855105e-01,4.650194797745381692e+00,8.618170972929439788e-02,1.000000009758066799e+00,6.839316092015533532e-02,-2.056840928046099986e-10,0.000000000000000000e+00 +5.681122525111231170e+01,3.484606877711664765e+02,1.462791354655229303e-01,4.652345245314251088e+00,8.643170972929439810e-02,1.000000009757624486e+00,6.839316092015533532e-02,-2.748887939003901694e-10,0.000000000000000000e+00 +5.681337470466159090e+01,3.484706504422115927e+02,1.471423768264719656e-01,4.654494698884501069e+00,8.668170972929439833e-02,1.000000009757033625e+00,6.839316092015533532e-02,-1.193698779203078086e-10,0.000000000000000000e+00 +5.681552316558956051e+01,3.484806128971350176e+02,1.480081088281800517e-01,4.656643159833434353e+00,8.693170972929439855e-02,1.000000009756777164e+00,6.839316092015533532e-02,-2.291305199395774331e-10,0.000000000000000000e+00 +5.681767063527035333e+01,3.484905751353140886e+02,1.488763314165389151e-01,4.658790629535176642e+00,8.718170972929439877e-02,1.000000009756285113e+00,6.839316092015533532e-02,-3.165445533776543343e-10,0.000000000000000000e+00 +5.681981711507491895e+01,3.485005371561261995e+02,1.497470445372846570e-01,4.660937109360684616e+00,8.743170972929439899e-02,1.000000009755605657e+00,6.839316092015533532e-02,-8.258788793446716351e-11,0.000000000000000000e+00 +5.682196260637105922e+01,3.485104989589487445e+02,1.506202481359976975e-01,4.663082600677757483e+00,8.768170972929439921e-02,1.000000009755428465e+00,6.839316092015533532e-02,-3.777184193703422155e-10,0.000000000000000000e+00 +5.682410711052342833e+01,3.485204605431590608e+02,1.514959421581028309e-01,4.665227104851048523e+00,8.793170972929439944e-02,1.000000009754618446e+00,6.839316092015533532e-02,-1.129118475226596414e-10,0.000000000000000000e+00 +5.682625062889353984e+01,3.485304219081345991e+02,1.523741265488691710e-01,4.667370623242071304e+00,8.818170972929439966e-02,1.000000009754376418e+00,6.839316092015533532e-02,-1.207364602979102736e-10,0.000000000000000000e+00 +5.682839316283978093e+01,3.485403830532527536e+02,1.532548012534101778e-01,4.669513157209214782e+00,8.843170972929439988e-02,1.000000009754117736e+00,6.839316092015533532e-02,-4.535139053104121314e-10,0.000000000000000000e+00 +5.683053471371742660e+01,3.485503439778909183e+02,1.541379662166837139e-01,4.671654708107749521e+00,8.868170972929440010e-02,1.000000009753146513e+00,6.839316092015533532e-02,8.402257364464376520e-12,0.000000000000000000e+00 +5.683267528287863968e+01,3.485603046814266008e+02,1.550236213834919330e-01,4.673795277289837458e+00,8.893170972929440032e-02,1.000000009753164498e+00,6.839316092015533532e-02,-5.123574294603179047e-10,0.000000000000000000e+00 +5.683481487167247792e+01,3.485702651632371953e+02,1.559117666984814188e-01,4.675934866104547005e+00,8.918170972929440055e-02,1.000000009752068264e+00,6.839316092015533532e-02,-1.012309457249379272e-10,0.000000000000000000e+00 +5.683695348144492954e+01,3.485802254227002095e+02,1.568024021061430739e-01,4.678073475897854827e+00,8.943170972929440077e-02,1.000000009751851771e+00,6.839316092015533532e-02,-1.317123558539296940e-10,0.000000000000000000e+00 +5.683909111353889188e+01,3.485901854591930942e+02,1.576955275508122034e-01,4.680211108012664489e+00,8.968170972929440099e-02,1.000000009751570218e+00,6.839316092015533532e-02,-2.231195949976158907e-10,0.000000000000000000e+00 +5.684122776929419985e+01,3.486001452720934140e+02,1.585911429766684311e-01,4.682347763788810013e+00,8.993170972929440121e-02,1.000000009751093488e+00,6.839316092015533532e-02,-3.738725453358196505e-10,0.000000000000000000e+00 +5.684336345004763302e+01,3.486101048607786197e+02,1.594892483277358386e-01,4.684483444563067422e+00,9.018170972929440143e-02,1.000000009750295016e+00,6.839316092015533532e-02,-1.833809618104684331e-10,0.000000000000000000e+00 +5.684549815713291565e+01,3.486200642246262760e+02,1.603898435478827988e-01,4.686618151669164511e+00,9.043170972929440166e-02,1.000000009749903551e+00,6.839316092015533532e-02,-2.162446337365625372e-10,0.000000000000000000e+00 +5.684763189188073795e+01,3.486300233630138905e+02,1.612929285808221425e-01,4.688751886437792393e+00,9.068170972929440188e-02,1.000000009749442142e+00,6.839316092015533532e-02,-2.501792280698026208e-10,0.000000000000000000e+00 +5.684976465561876324e+01,3.486399822753190278e+02,1.621985033701110468e-01,4.690884650196612604e+00,9.093170972929440210e-02,1.000000009748908569e+00,6.839316092015533532e-02,-2.477932211157383322e-10,0.000000000000000000e+00 +5.685189644967163503e+01,3.486499409609192526e+02,1.631065678591510637e-01,4.693016444270267762e+00,9.118170972929440232e-02,1.000000009748380325e+00,6.839316092015533532e-02,-1.637074661153501751e-10,0.000000000000000000e+00 +5.685402727536098411e+01,3.486598994191921292e+02,1.640171219911882028e-01,4.695147269980391336e+00,9.143170972929440254e-02,1.000000009748031493e+00,6.839316092015533532e-02,-3.351740767817847774e-10,0.000000000000000000e+00 +5.685615713400544990e+01,3.486698576495152793e+02,1.649301657093127926e-01,4.697277128645617417e+00,9.168170972929440277e-02,1.000000009747317620e+00,6.839316092015533532e-02,-3.077907885592083125e-10,0.000000000000000000e+00 +5.685828602692067335e+01,3.486798156512663240e+02,1.658456989564596196e-01,4.699406021581588710e+00,9.193170972929440299e-02,1.000000009746662366e+00,6.839316092015533532e-02,-9.599995331688452395e-12,0.000000000000000000e+00 +5.686041395541931109e+01,3.486897734238228281e+02,1.667637216754078722e-01,4.701533950100968084e+00,9.218170972929440321e-02,1.000000009746641938e+00,6.839316092015533532e-02,-5.383651431472168156e-10,0.000000000000000000e+00 +5.686254092081106393e+01,3.486997309665624698e+02,1.676842338087811135e-01,4.703660915513448337e+00,9.243170972929440343e-02,1.000000009745496854e+00,6.839316092015533532e-02,-3.864363359840030283e-11,0.000000000000000000e+00 +5.686466692440265547e+01,3.487096882788629273e+02,1.686072352990473366e-01,4.705786919125756640e+00,9.268170972929440365e-02,1.000000009745414697e+00,6.839316092015533532e-02,-1.808712547958598628e-10,0.000000000000000000e+00 +5.686679196749786058e+01,3.487196453601018789e+02,1.695327260885189369e-01,4.707911962241672299e+00,9.293170972929440388e-02,1.000000009745030338e+00,6.839316092015533532e-02,-4.679060237709748027e-10,0.000000000000000000e+00 +5.686891605139751960e+01,3.487296022096569459e+02,1.704607061193527673e-01,4.710036046162028534e+00,9.318170972929440410e-02,1.000000009744036467e+00,6.839316092015533532e-02,2.510011423326489765e-12,0.000000000000000000e+00 +5.687103917739952408e+01,3.487395588269058635e+02,1.713911753335500554e-01,4.712159172184724021e+00,9.343170972929440432e-02,1.000000009744041796e+00,6.839316092015533532e-02,-4.205117967839379431e-10,0.000000000000000000e+00 +5.687316134679885948e+01,3.487495152112263099e+02,1.723241336729564865e-01,4.714281341604736220e+00,9.368170972929440454e-02,1.000000009743149398e+00,6.839316092015533532e-02,-2.266280297774482037e-10,0.000000000000000000e+00 +5.687528256088757672e+01,3.487594713619960771e+02,1.732595810792621482e-01,4.716402555714123146e+00,9.393170972929440476e-02,1.000000009742668672e+00,6.839316092015533532e-02,-2.628601872798885500e-10,0.000000000000000000e+00 +5.687740282095483479e+01,3.487694272785928433e+02,1.741975174940015858e-01,4.718522815802039361e+00,9.418170972929440499e-02,1.000000009742111340e+00,6.839316092015533532e-02,-1.843991660657537512e-10,0.000000000000000000e+00 +5.687952212828689369e+01,3.487793829603944005e+02,1.751379428585537745e-01,4.720642123154741299e+00,9.443170972929440521e-02,1.000000009741720541e+00,6.839316092015533532e-02,-2.310217625963295383e-10,0.000000000000000000e+00 +5.688164048416711438e+01,3.487893384067784837e+02,1.760808571141421475e-01,4.722760479055597926e+00,9.468170972929440543e-02,1.000000009741231155e+00,6.839316092015533532e-02,-2.388855418209134977e-10,0.000000000000000000e+00 +5.688375788987598725e+01,3.487992936171228848e+02,1.770262602018345399e-01,4.724877884785098736e+00,9.493170972929440565e-02,1.000000009740725337e+00,6.839316092015533532e-02,-4.319283209244295887e-10,0.000000000000000000e+00 +5.688587434669113918e+01,3.488092485908054527e+02,1.779741520625432727e-01,4.726994341620863516e+00,9.518170972929440588e-02,1.000000009739811180e+00,6.839316092015533532e-02,-3.463691850524608056e-11,0.000000000000000000e+00 +5.688798985588731938e+01,3.488192033272039794e+02,1.789245326370250966e-01,4.729109850837650342e+00,9.543170972929440610e-02,1.000000009739737905e+00,6.839316092015533532e-02,-4.453360986068072314e-10,0.000000000000000000e+00 +5.689010441873644197e+01,3.488291578256962566e+02,1.798774018658812202e-01,4.731224413707368015e+00,9.568170972929440632e-02,1.000000009738796214e+00,6.839316092015533532e-02,-2.766079339198479546e-10,0.000000000000000000e+00 +5.689221803650757181e+01,3.488391120856601333e+02,1.808327596895573375e-01,4.733338031499078724e+00,9.593170972929440654e-02,1.000000009738211570e+00,6.839316092015533532e-02,-1.170827560923453958e-10,0.000000000000000000e+00 +5.689433071046693158e+01,3.488490661064735150e+02,1.817906060483435726e-01,4.735450705479013145e+00,9.618170972929440676e-02,1.000000009737964213e+00,6.839316092015533532e-02,-3.508793034830641195e-10,0.000000000000000000e+00 +5.689644244187793021e+01,3.488590198875142505e+02,1.827509408823745352e-01,4.737562436910576658e+00,9.643170972929440699e-02,1.000000009737223250e+00,6.839316092015533532e-02,-1.598964273009445893e-10,0.000000000000000000e+00 +5.689855323200115578e+01,3.488689734281601886e+02,1.837137641316292924e-01,4.739673227054356452e+00,9.668170972929440721e-02,1.000000009736885742e+00,6.839316092015533532e-02,-3.100425988589646238e-10,0.000000000000000000e+00 +5.690066308209438972e+01,3.488789267277892918e+02,1.846790757359313695e-01,4.741783077168133964e+00,9.693170972929440743e-02,1.000000009736231599e+00,6.839316092015533532e-02,-1.660403350965766150e-10,0.000000000000000000e+00 +5.690277199341261394e+01,3.488888797857794657e+02,1.856468756349488325e-01,4.743891988506890200e+00,9.718170972929440765e-02,1.000000009735881434e+00,6.839316092015533532e-02,-4.800141571254167827e-10,0.000000000000000000e+00 +5.690487996720801789e+01,3.488988326015086159e+02,1.866171637681941498e-01,4.745999962322817289e+00,9.743170972929440787e-02,1.000000009734869577e+00,6.839316092015533532e-02,-1.993834415062683231e-10,0.000000000000000000e+00 +5.690698700473001281e+01,3.489087851743547048e+02,1.875899400750243584e-01,4.748106999865323807e+00,9.768170972929440810e-02,1.000000009734449469e+00,6.839316092015533532e-02,-6.167605526122198750e-11,0.000000000000000000e+00 +5.690909310722523884e+01,3.489187375036956951e+02,1.885652044946408978e-01,4.750213102381048103e+00,9.793170972929440832e-02,1.000000009734319573e+00,6.839316092015533532e-02,-5.992086967638140941e-10,0.000000000000000000e+00 +5.691119827593756497e+01,3.489286895889096058e+02,1.895429569660897484e-01,4.752318271113863624e+00,9.818170972929440854e-02,1.000000009733058137e+00,6.839316092015533532e-02,6.869525380748531196e-11,0.000000000000000000e+00 +5.691330251210810331e+01,3.489386414293743996e+02,1.905231974282614038e-01,4.754422507304885137e+00,9.843170972929440876e-02,1.000000009733202688e+00,6.839316092015533532e-02,-5.797870719108296052e-10,0.000000000000000000e+00 +5.691540581697523038e+01,3.489485930244680389e+02,1.915059258198908154e-01,4.756525812192485603e+00,9.868170972929440898e-02,1.000000009731983219e+00,6.839316092015533532e-02,-4.404190931249255750e-11,0.000000000000000000e+00 +5.691750819177457998e+01,3.489585443735685999e+02,1.924911420795574757e-01,4.758628187012293509e+00,9.893170972929440921e-02,1.000000009731890627e+00,6.839316092015533532e-02,-4.327947123794996003e-10,0.000000000000000000e+00 +5.691960963773905036e+01,3.489684954760541586e+02,1.934788461456853625e-01,4.760729632997212413e+00,9.918170972929440943e-02,1.000000009730981132e+00,6.839316092015533532e-02,-2.316093678155637835e-10,0.000000000000000000e+00 +5.692171015609881835e+01,3.489784463313027345e+02,1.944690379565429672e-01,4.762830151377420052e+00,9.943170972929440965e-02,1.000000009730494632e+00,6.839316092015533532e-02,-1.287051419713041103e-10,0.000000000000000000e+00 +5.692380974808135363e+01,3.489883969386924036e+02,1.954617174502432941e-01,4.764929743380383442e+00,9.968170972929440987e-02,1.000000009730224404e+00,6.839316092015533532e-02,-4.046953054543937103e-10,0.000000000000000000e+00 +5.692590841491141163e+01,3.489983472976012422e+02,1.964568845647438888e-01,4.767028410230864210e+00,9.993170972929441009e-02,1.000000009729375083e+00,6.839316092015533532e-02,-3.238988396449303859e-10,0.000000000000000000e+00 +5.692800615781106188e+01,3.490082974074073263e+02,1.974545392378468101e-01,4.769126153150925695e+00,1.001817097292944103e-01,1.000000009728695627e+00,6.839316092015533532e-02,-3.529509455469267313e-10,0.000000000000000000e+00 +5.693010297799968100e+01,3.490182472674887890e+02,1.984546814071986298e-01,4.771222973359944497e+00,1.004317097292944105e-01,1.000000009727955552e+00,6.839316092015533532e-02,-1.434460529454587566e-10,0.000000000000000000e+00 +5.693219887669396684e+01,3.490281968772238201e+02,1.994573110102904612e-01,4.773318872074616692e+00,1.006817097292944108e-01,1.000000009727654904e+00,6.839316092015533532e-02,-1.484905474086537004e-10,0.000000000000000000e+00 +5.693429385510793850e+01,3.490381462359904958e+02,2.004624279844579582e-01,4.775413850508967606e+00,1.009317097292944110e-01,1.000000009727343819e+00,6.839316092015533532e-02,-6.126730506981385294e-10,0.000000000000000000e+00 +5.693638791445295766e+01,3.490480953431670059e+02,2.014700322668813159e-01,4.777507909874358027e+00,1.011817097292944112e-01,1.000000009726060846e+00,6.839316092015533532e-02,5.070718913468981063e-11,0.000000000000000000e+00 +5.693848105593773568e+01,3.490580441981315403e+02,2.024801237945852705e-01,4.779601051379491317e+00,1.014317097292944114e-01,1.000000009726166983e+00,6.839316092015533532e-02,-6.166063683757902987e-10,0.000000000000000000e+00 +5.694057328076832647e+01,3.490679928002622887e+02,2.034927025044390714e-01,4.781693276230428502e+00,1.016817097292944116e-01,1.000000009724876904e+00,6.839316092015533532e-02,1.911148549907875547e-12,0.000000000000000000e+00 +5.694266459014814785e+01,3.490779411489374979e+02,2.045077683331565921e-01,4.783784585630585617e+00,1.019317097292944119e-01,1.000000009724880901e+00,6.839316092015533532e-02,-5.411978079858455219e-10,0.000000000000000000e+00 +5.694475498527798862e+01,3.490878892435353578e+02,2.055253212172961919e-01,4.785874980780753241e+00,1.021817097292944121e-01,1.000000009723749583e+00,6.839316092015533532e-02,-1.636523687765203319e-11,0.000000000000000000e+00 +5.694684446735600858e+01,3.490978370834341149e+02,2.065453610932608264e-01,4.787964462879093830e+00,1.024317097292944123e-01,1.000000009723715388e+00,6.839316092015533532e-02,-4.547056954903069418e-10,0.000000000000000000e+00 +5.694893303757776692e+01,3.491077846680120160e+02,2.075678878972979924e-01,4.790053033121159487e+00,1.026817097292944125e-01,1.000000009722765704e+00,6.839316092015533532e-02,-4.227831597404609430e-10,0.000000000000000000e+00 +5.695102069713620097e+01,3.491177319966473647e+02,2.085929015654997831e-01,4.792140692699891069e+00,1.029317097292944128e-01,1.000000009721883076e+00,6.839316092015533532e-02,-1.065133055842568895e-10,0.000000000000000000e+00 +5.695310744722165452e+01,3.491276790687184644e+02,2.096204020338028329e-01,4.794227442805632400e+00,1.031817097292944130e-01,1.000000009721660810e+00,6.839316092015533532e-02,-2.980690547683855657e-10,0.000000000000000000e+00 +5.695519328902188505e+01,3.491376258836036186e+02,2.106503892379883724e-01,4.796313284626137374e+00,1.034317097292944132e-01,1.000000009721039085e+00,6.839316092015533532e-02,-3.553889944729031638e-10,0.000000000000000000e+00 +5.695727822372205651e+01,3.491475724406811310e+02,2.116828631136821737e-01,4.798398219346574400e+00,1.036817097292944134e-01,1.000000009720298122e+00,6.839316092015533532e-02,-2.394085107686850198e-10,0.000000000000000000e+00 +5.695936225250476070e+01,3.491575187393293618e+02,2.127178235963546604e-01,4.800482248149537057e+00,1.039317097292944136e-01,1.000000009719799188e+00,6.839316092015533532e-02,-5.193168009617231264e-10,0.000000000000000000e+00 +5.696144537655003148e+01,3.491674647789266146e+02,2.137552706213207698e-01,4.802565372215052086e+00,1.041817097292944139e-01,1.000000009718717386e+00,6.839316092015533532e-02,-1.195416162114842694e-10,0.000000000000000000e+00 +5.696352759703533053e+01,3.491774105588513066e+02,2.147952041237400633e-01,4.804647592720584726e+00,1.044317097292944141e-01,1.000000009718468474e+00,6.839316092015533532e-02,-2.092085156074633953e-10,0.000000000000000000e+00 +5.696560891513556868e+01,3.491873560784818551e+02,2.158376240386167266e-01,4.806728910841051139e+00,1.046817097292944143e-01,1.000000009718033045e+00,6.839316092015533532e-02,-5.184983342424638023e-10,0.000000000000000000e+00 +5.696768933202312013e+01,3.491973013371966204e+02,2.168825303007994865e-01,4.808809327748821083e+00,1.049317097292944145e-01,1.000000009716954352e+00,6.839316092015533532e-02,-1.532250190132601939e-10,0.000000000000000000e+00 +5.696976884886782244e+01,3.492072463343740196e+02,2.179299228449817216e-01,4.810888844613726789e+00,1.051817097292944148e-01,1.000000009716635718e+00,6.839316092015533532e-02,-4.702356880323859451e-10,0.000000000000000000e+00 +5.697184746683697654e+01,3.492171910693925270e+02,2.189798016057013796e-01,4.812967462603074509e+00,1.054317097292944150e-01,1.000000009715658278e+00,6.839316092015533532e-02,-1.502583003003526481e-10,0.000000000000000000e+00 +5.697392518709536091e+01,3.492271355416305596e+02,2.200321665173410601e-01,4.815045182881646291e+00,1.056817097292944152e-01,1.000000009715346083e+00,6.839316092015533532e-02,-3.328278908989582661e-10,0.000000000000000000e+00 +5.697600201080525295e+01,3.492370797504665916e+02,2.210870175141279315e-01,4.817122006611713303e+00,1.059317097292944154e-01,1.000000009714654858e+00,6.839316092015533532e-02,-3.000272747698730357e-10,0.000000000000000000e+00 +5.697807793912641472e+01,3.492470236952790970e+02,2.221443545301338418e-01,4.819197934953038498e+00,1.061817097292944156e-01,1.000000009714032023e+00,6.839316092015533532e-02,-3.562286005167318060e-10,0.000000000000000000e+00 +5.698015297321610717e+01,3.492569673754466066e+02,2.232041774992752081e-01,4.821272969062887270e+00,1.064317097292944159e-01,1.000000009713292837e+00,6.839316092015533532e-02,-3.871064148371106372e-10,0.000000000000000000e+00 +5.698222711422910436e+01,3.492669107903476515e+02,2.242664863553130716e-01,4.823347110096033674e+00,1.066817097292944161e-01,1.000000009712489923e+00,6.839316092015533532e-02,-2.708554456594762668e-10,0.000000000000000000e+00 +5.698430036331770054e+01,3.492768539393607625e+02,2.253312810318531534e-01,4.825420359204768417e+00,1.069317097292944163e-01,1.000000009711928373e+00,6.839316092015533532e-02,-2.921867485639362872e-10,0.000000000000000000e+00 +5.698637272163171019e+01,3.492867968218644705e+02,2.263985614623457987e-01,4.827492717538906852e+00,1.071817097292944165e-01,1.000000009711322857e+00,6.839316092015533532e-02,-3.168591716350423742e-10,0.000000000000000000e+00 +5.698844419031848219e+01,3.492967394372373633e+02,2.274683275800859494e-01,4.829564186245795199e+00,1.074317097292944168e-01,1.000000009710666493e+00,6.839316092015533532e-02,-4.096486525875006349e-10,0.000000000000000000e+00 +5.699051477052289982e+01,3.493066817848580285e+02,2.285405793182132550e-01,4.831634766470318532e+00,1.076817097292944170e-01,1.000000009709818283e+00,6.839316092015533532e-02,-2.149968219457347496e-10,0.000000000000000000e+00 +5.699258446338739503e+01,3.493166238641050541e+02,2.296153166097119613e-01,4.833704459354907890e+00,1.079317097292944172e-01,1.000000009709373305e+00,6.839316092015533532e-02,-4.065652812642903913e-10,0.000000000000000000e+00 +5.699465327005194837e+01,3.493265656743570844e+02,2.306925393874109942e-01,4.835773266039549156e+00,1.081817097292944174e-01,1.000000009708532200e+00,6.839316092015533532e-02,-4.080277984586164037e-10,0.000000000000000000e+00 +5.699672119165411033e+01,3.493365072149927073e+02,2.317722475839839313e-01,4.837841187661787501e+00,1.084317097292944176e-01,1.000000009707688431e+00,6.839316092015533532e-02,-4.962880392644355394e-11,0.000000000000000000e+00 +5.699878822932899425e+01,3.493464484853906242e+02,2.328544411319490026e-01,4.839908225356737148e+00,1.086817097292944179e-01,1.000000009707585846e+00,6.839316092015533532e-02,-6.117053001626470774e-10,0.000000000000000000e+00 +5.700085438420929052e+01,3.493563894849294797e+02,2.339391199636691177e-01,4.841974380257089372e+00,1.089317097292944181e-01,1.000000009706321968e+00,6.839316092015533532e-02,-2.482485071733901813e-10,0.000000000000000000e+00 +5.700291965742526656e+01,3.493663302129879753e+02,2.350262840113518659e-01,4.844039653493114272e+00,1.091817097292944183e-01,1.000000009705809267e+00,6.839316092015533532e-02,-2.267349772281043071e-10,0.000000000000000000e+00 +5.700498405010478820e+01,3.493762706689448123e+02,2.361159332070494887e-01,4.846104046192675874e+00,1.094317097292944185e-01,1.000000009705341197e+00,6.839316092015533532e-02,-5.615911517393617630e-10,0.000000000000000000e+00 +5.700704756337331958e+01,3.493862108521787491e+02,2.372080674826588798e-01,4.848167559481233901e+00,1.096817097292944188e-01,1.000000009704182347e+00,6.839316092015533532e-02,-7.104962372345400717e-12,0.000000000000000000e+00 +5.700911019835392324e+01,3.493961507620684870e+02,2.383026867699216955e-01,4.850230194481850887e+00,1.099317097292944190e-01,1.000000009704167692e+00,6.839316092015533532e-02,-6.513499121446882929e-10,0.000000000000000000e+00 +5.701117195616726718e+01,3.494060903979927843e+02,2.393997910004241891e-01,4.852291952315204604e+00,1.101817097292944192e-01,1.000000009702824766e+00,6.839316092015533532e-02,-1.903810415924348643e-10,0.000000000000000000e+00 +5.701323283793165331e+01,3.494160297593303994e+02,2.404993801055973768e-01,4.854352834099586289e+00,1.104317097292944194e-01,1.000000009702432413e+00,6.839316092015533532e-02,-2.832676148759307867e-10,0.000000000000000000e+00 +5.701529284476299608e+01,3.494259688454601473e+02,2.416014540167169267e-01,4.856412840950917520e+00,1.106817097292944196e-01,1.000000009701848880e+00,6.839316092015533532e-02,-4.938798439447823259e-10,0.000000000000000000e+00 +5.701735197777485098e+01,3.494359076557608432e+02,2.427060126649032146e-01,4.858471973982750214e+00,1.109317097292944199e-01,1.000000009700831916e+00,6.839316092015533532e-02,-3.777948809988183353e-10,0.000000000000000000e+00 +5.701941023807840736e+01,3.494458461896112453e+02,2.438130559811213238e-01,4.860530234306275510e+00,1.111817097292944201e-01,1.000000009700054315e+00,6.839316092015533532e-02,-3.220495474558476734e-10,0.000000000000000000e+00 +5.702146762678250980e+01,3.494557844463902825e+02,2.449225838961810453e-01,4.862587623030332651e+00,1.114317097292944203e-01,1.000000009699391734e+00,6.839316092015533532e-02,-2.891466989057896265e-10,0.000000000000000000e+00 +5.702352414499364386e+01,3.494657224254767698e+02,2.460345963407369052e-01,4.864644141261414312e+00,1.116817097292944205e-01,1.000000009698797099e+00,6.839316092015533532e-02,-2.348285202536340779e-10,0.000000000000000000e+00 +5.702557979381596454e+01,3.494756601262495792e+02,2.471490932452881095e-01,4.866699790103673706e+00,1.119317097292944208e-01,1.000000009698314374e+00,6.839316092015533532e-02,-5.298301590989831871e-10,0.000000000000000000e+00 +5.702763457435129624e+01,3.494855975480875827e+02,2.482660745401785996e-01,4.868754570658931691e+00,1.121817097292944210e-01,1.000000009697225689e+00,6.839316092015533532e-02,-2.754593585682964508e-10,0.000000000000000000e+00 +5.702968848769913279e+01,3.494955346903697659e+02,2.493855401555970519e-01,4.870808484026682095e+00,1.124317097292944212e-01,1.000000009696659919e+00,6.839316092015533532e-02,-4.618161903290104155e-10,0.000000000000000000e+00 +5.703174153495664456e+01,3.495054715524750009e+02,2.505074900215768507e-01,4.872861531304102378e+00,1.126817097292944214e-01,1.000000009695711789e+00,6.839316092015533532e-02,-1.767975930577959360e-10,0.000000000000000000e+00 +5.703379371721869973e+01,3.495154081337822163e+02,2.516319240679961711e-01,4.874913713586056296e+00,1.129317097292944216e-01,1.000000009695348968e+00,6.839316092015533532e-02,-6.105008353213338274e-10,0.000000000000000000e+00 +5.703584503557785723e+01,3.495253444336703978e+02,2.527588422245778399e-01,4.876965031965104558e+00,1.131817097292944219e-01,1.000000009694096637e+00,6.839316092015533532e-02,-2.046688132398621464e-10,0.000000000000000000e+00 +5.703789549112438095e+01,3.495352804515185312e+02,2.538882444208895306e-01,4.879015487531506601e+00,1.134317097292944221e-01,1.000000009693676972e+00,6.839316092015533532e-02,-3.492749629918984655e-10,0.000000000000000000e+00 +5.703994508494623972e+01,3.495452161867056589e+02,2.550201305863435408e-01,4.881065081373233916e+00,1.136817097292944223e-01,1.000000009692961100e+00,6.839316092015533532e-02,-3.173407882752960756e-10,0.000000000000000000e+00 +5.704199381812912151e+01,3.495551516386107664e+02,2.561545006501970145e-01,4.883113814575970935e+00,1.139317097292944225e-01,1.000000009692310954e+00,6.839316092015533532e-02,-6.440558321903215100e-10,0.000000000000000000e+00 +5.704404169175642636e+01,3.495650868066128396e+02,2.572913545415518310e-01,4.885161688223124798e+00,1.141817097292944228e-01,1.000000009690992009e+00,6.839316092015533532e-02,-1.643356552540450318e-10,0.000000000000000000e+00 +5.704608870690929479e+01,3.495750216900909777e+02,2.584306921893546050e-01,4.887208703395829801e+00,1.144317097292944230e-01,1.000000009690655611e+00,6.839316092015533532e-02,-2.488313900902791088e-10,0.000000000000000000e+00 +5.704813486466659356e+01,3.495849562884242232e+02,2.595725135223967417e-01,4.889254861172958933e+00,1.146817097292944232e-01,1.000000009690146463e+00,6.839316092015533532e-02,-5.691972057493238063e-10,0.000000000000000000e+00 +5.705018016610493703e+01,3.495948906009917323e+02,2.607168184693144375e-01,4.891300162631124770e+00,1.149317097292944234e-01,1.000000009688982283e+00,6.839316092015533532e-02,-3.636218647182554763e-10,0.000000000000000000e+00 +5.705222461229869424e+01,3.496048246271725475e+02,2.618636069585885684e-01,4.893344608844687471e+00,1.151817097292944236e-01,1.000000009688238878e+00,6.839316092015533532e-02,-3.520392096202759701e-10,0.000000000000000000e+00 +5.705426820431997470e+01,3.496147583663457681e+02,2.630128789185449123e-01,4.895388200885764540e+00,1.154317097292944239e-01,1.000000009687519453e+00,6.839316092015533532e-02,-3.980574001892482918e-10,0.000000000000000000e+00 +5.705631094323865682e+01,3.496246918178906071e+02,2.641646342773539269e-01,4.897430939824234386e+00,1.156817097292944241e-01,1.000000009686706326e+00,6.839316092015533532e-02,-3.598365823060587648e-10,0.000000000000000000e+00 +5.705835283012238790e+01,3.496346249811861640e+02,2.653188729630309162e-01,4.899472826727743424e+00,1.159317097292944243e-01,1.000000009685971580e+00,6.839316092015533532e-02,-5.155565247130849132e-10,0.000000000000000000e+00 +5.706039386603659125e+01,3.496445578556116516e+02,2.664755949034359750e-01,4.901513862661713183e+00,1.161817097292944245e-01,1.000000009684919311e+00,6.839316092015533532e-02,-2.846047564477678166e-10,0.000000000000000000e+00 +5.706243405204446617e+01,3.496544904405462830e+02,2.676348000262739890e-01,4.903554048689345635e+00,1.164317097292944247e-01,1.000000009684338664e+00,6.839316092015533532e-02,-3.602864750343447634e-10,0.000000000000000000e+00 +5.706447338920700219e+01,3.496644227353692145e+02,2.687964882590946347e-01,4.905593385871632073e+00,1.166817097292944250e-01,1.000000009683603919e+00,6.839316092015533532e-02,-3.632683918537858282e-10,0.000000000000000000e+00 +5.706651187858298613e+01,3.496743547394597158e+02,2.699606595292923794e-01,4.907631875267356669e+00,1.169317097292944252e-01,1.000000009682863400e+00,6.839316092015533532e-02,-3.358496023414313075e-10,0.000000000000000000e+00 +5.706854952122900215e+01,3.496842864521970000e+02,2.711273137641065367e-01,4.909669517933104466e+00,1.171817097292944254e-01,1.000000009682179059e+00,6.839316092015533532e-02,-5.280762304075805890e-10,0.000000000000000000e+00 +5.707058631819944594e+01,3.496942178729603938e+02,2.722964508906212111e-01,4.911706314923267591e+00,1.174317097292944256e-01,1.000000009681103474e+00,6.839316092015533532e-02,-5.425823993819469230e-10,0.000000000000000000e+00 +5.707262227054651760e+01,3.497041490011291671e+02,2.734680708357653534e-01,4.913742267290050592e+00,1.176817097292944259e-01,1.000000009679998803e+00,6.839316092015533532e-02,-1.889733171488742508e-10,0.000000000000000000e+00 +5.707465737932024297e+01,3.497140798360825897e+02,2.746421735263127051e-01,4.915777376083478423e+00,1.179317097292944261e-01,1.000000009679614221e+00,6.839316092015533532e-02,-3.445934465838971604e-10,0.000000000000000000e+00 +5.707669164556848074e+01,3.497240103771999884e+02,2.758187588888817987e-01,4.917811642351403556e+00,1.181817097292944263e-01,1.000000009678913226e+00,6.839316092015533532e-02,-5.943611995755368936e-10,0.000000000000000000e+00 +5.707872507033690113e+01,3.497339406238607467e+02,2.769978268499361240e-01,4.919845067139508643e+00,1.184317097292944265e-01,1.000000009677704638e+00,6.839316092015533532e-02,-3.017277999770433837e-10,0.000000000000000000e+00 +5.708075765466903562e+01,3.497438705754441912e+02,2.781793773357839061e-01,4.921877651491314509e+00,1.186817097292944267e-01,1.000000009677091350e+00,6.839316092015533532e-02,-5.430502725336592461e-10,0.000000000000000000e+00 +5.708278939960624854e+01,3.497538002313297056e+02,2.793634102725782165e-01,4.923909396448189035e+00,1.189317097292944270e-01,1.000000009675988011e+00,6.839316092015533532e-02,-2.402040554016309579e-10,0.000000000000000000e+00 +5.708482030618775838e+01,3.497637295908966735e+02,2.805499255863170283e-01,4.925940303049348934e+00,1.191817097292944272e-01,1.000000009675500179e+00,6.839316092015533532e-02,-4.598244681468402129e-10,0.000000000000000000e+00 +5.708685037545063778e+01,3.497736586535245351e+02,2.817389232028431056e-01,4.927970372331870408e+00,1.194317097292944274e-01,1.000000009674566703e+00,6.839316092015533532e-02,-5.425188544188366236e-10,0.000000000000000000e+00 +5.708887960842982778e+01,3.497835874185927310e+02,2.829304030478441145e-01,4.929999605330690926e+00,1.196817097292944276e-01,1.000000009673465806e+00,6.839316092015533532e-02,-2.514479534242352379e-10,0.000000000000000000e+00 +5.709090800615813066e+01,3.497935158854806446e+02,2.841243650468525672e-01,4.932028003078618106e+00,1.199317097292944279e-01,1.000000009672955770e+00,6.839316092015533532e-02,-4.245819821932129147e-10,0.000000000000000000e+00 +5.709293556966623839e+01,3.498034440535678300e+02,2.853208091252458223e-01,4.934055566606336818e+00,1.201817097292944281e-01,1.000000009672094903e+00,6.839316092015533532e-02,-5.996111632996843213e-10,0.000000000000000000e+00 +5.709496229998271133e+01,3.498133719222337277e+02,2.865197352082461402e-01,4.936082296942411851e+00,1.204317097292944283e-01,1.000000009670879653e+00,6.839316092015533532e-02,-3.069981272249154598e-10,0.000000000000000000e+00 +5.709698819813400661e+01,3.498232994908578917e+02,2.877211432209206832e-01,4.938108195113295906e+00,1.206817097292944285e-01,1.000000009670257706e+00,6.839316092015533532e-02,-3.699524475722584596e-10,0.000000000000000000e+00 +5.709901326514446396e+01,3.498332267588198192e+02,2.889250330881814044e-01,4.940133262143337589e+00,1.209317097292944287e-01,1.000000009669508527e+00,6.839316092015533532e-02,-5.251003615454087453e-10,0.000000000000000000e+00 +5.710103750203633410e+01,3.498431537254990076e+02,2.901314047347851588e-01,4.942157499054784076e+00,1.211817097292944290e-01,1.000000009668445600e+00,6.839316092015533532e-02,-5.028192453664153418e-10,0.000000000000000000e+00 +5.710306090982977167e+01,3.498530803902751245e+02,2.913402580853337587e-01,4.944180906867788217e+00,1.214317097292944292e-01,1.000000009667428191e+00,6.839316092015533532e-02,-2.438277534134360515e-10,0.000000000000000000e+00 +5.710508348954284941e+01,3.498630067525276672e+02,2.925515930642738627e-01,4.946203486600415644e+00,1.216817097292944294e-01,1.000000009666935030e+00,6.839316092015533532e-02,-5.533123551669326692e-10,0.000000000000000000e+00 +5.710710524219154394e+01,3.498729328116362467e+02,2.937654095958970313e-01,4.948225239268650988e+00,1.219317097292944296e-01,1.000000009665816370e+00,6.839316092015533532e-02,-4.934381692035641604e-10,0.000000000000000000e+00 +5.710912616878975712e+01,3.498828585669805307e+02,2.949817076043397823e-01,4.950246165886400540e+00,1.221817097292944299e-01,1.000000009664819167e+00,6.839316092015533532e-02,-4.237321375886632697e-10,0.000000000000000000e+00 +5.711114627034933733e+01,3.498927840179401301e+02,2.962004870135834245e-01,4.952266267465502025e+00,1.224317097292944301e-01,1.000000009663963185e+00,6.839316092015533532e-02,-2.643496112450420575e-10,0.000000000000000000e+00 +5.711316554788005107e+01,3.499027091638947127e+02,2.974217477474542792e-01,4.954285545015729042e+00,1.226817097292944303e-01,1.000000009663429390e+00,6.839316092015533532e-02,-8.014027263012387352e-10,0.000000000000000000e+00 +5.711518400238961135e+01,3.499126340042239462e+02,2.986454897296235145e-01,4.956303999544797279e+00,1.229317097292944305e-01,1.000000009661811795e+00,6.839316092015533532e-02,-2.006248987200845802e-10,0.000000000000000000e+00 +5.711720163488368485e+01,3.499225585383075554e+02,2.998717128836072554e-01,4.958321632058367179e+00,1.231817097292944307e-01,1.000000009661407008e+00,6.839316092015533532e-02,-5.464107002396562409e-10,0.000000000000000000e+00 +5.711921844636589185e+01,3.499324827655252079e+02,3.011004171327665846e-01,4.960338443560057264e+00,1.234317097292944310e-01,1.000000009660305000e+00,6.839316092015533532e-02,-2.102603888499954144e-10,0.000000000000000000e+00 +5.712123443783779919e+01,3.499424066852566853e+02,3.023316024003074864e-01,4.962354435051441470e+00,1.236817097292944312e-01,1.000000009659881117e+00,6.839316092015533532e-02,-8.333397659109132381e-10,0.000000000000000000e+00 +5.712324961029895576e+01,3.499523302968817120e+02,3.035652686092809027e-01,4.964369607532061579e+00,1.239317097292944314e-01,1.000000009658201794e+00,6.839316092015533532e-02,-3.359845416052769702e-10,0.000000000000000000e+00 +5.712526396474686408e+01,3.499622535997801265e+02,3.048014156825826770e-01,4.966383961999426333e+00,1.241817097292944316e-01,1.000000009657525002e+00,6.839316092015533532e-02,-3.504567354369698228e-10,0.000000000000000000e+00 +5.712727750217701583e+01,3.499721765933316533e+02,3.060400435429536103e-01,4.968397499449025645e+00,1.244317097292944319e-01,1.000000009656819344e+00,6.839316092015533532e-02,-5.363786890715519237e-10,0.000000000000000000e+00 +5.712929022358288478e+01,3.499820992769161307e+02,3.072811521129794610e-01,4.970410220874329710e+00,1.246817097292944321e-01,1.000000009655739763e+00,6.839316092015533532e-02,-5.471910452546896878e-10,0.000000000000000000e+00 +5.713130212995592672e+01,3.499920216499133971e+02,3.085247413150909446e-01,4.972422127266796110e+00,1.249317097292944323e-01,1.000000009654638866e+00,6.839316092015533532e-02,-2.489744387765085723e-10,0.000000000000000000e+00 +5.713331322228559372e+01,3.500019437117032908e+02,3.097708110715637342e-01,4.974433219615876922e+00,1.251817097292944325e-01,1.000000009654138156e+00,6.839316092015533532e-02,-6.017566929298844187e-10,0.000000000000000000e+00 +5.713532350155933415e+01,3.500118654616656499e+02,3.110193613045184602e-01,4.976443498909024932e+00,1.254317097292944327e-01,1.000000009652928457e+00,6.839316092015533532e-02,-5.840989988400015836e-10,0.000000000000000000e+00 +5.713733296876260681e+01,3.500217868991804266e+02,3.122703919359207658e-01,4.978452966131695412e+00,1.256817097292944330e-01,1.000000009651754729e+00,6.839316092015533532e-02,-4.863929936811275314e-10,0.000000000000000000e+00 +5.713934162487888102e+01,3.500317080236274592e+02,3.135239028875811962e-01,4.980461622267355892e+00,1.259317097292944332e-01,1.000000009650777733e+00,6.839316092015533532e-02,-3.750054791386814958e-10,0.000000000000000000e+00 +5.714134947088963656e+01,3.500416288343867564e+02,3.147798940811553647e-01,4.982469468297490600e+00,1.261817097292944334e-01,1.000000009650024779e+00,6.839316092015533532e-02,-5.318130543520380023e-10,0.000000000000000000e+00 +5.714335650777438502e+01,3.500515493308382133e+02,3.160383654381437868e-01,4.984476505201605789e+00,1.264317097292944336e-01,1.000000009648957411e+00,6.839316092015533532e-02,-5.729779954372896329e-10,0.000000000000000000e+00 +5.714536273651065557e+01,3.500614695123618390e+02,3.172993168798919905e-01,4.986482733957234181e+00,1.266817097292944339e-01,1.000000009647807886e+00,6.839316092015533532e-02,-3.285126453456380717e-10,0.000000000000000000e+00 +5.714736815807401626e+01,3.500713893783375852e+02,3.185627483275905170e-01,4.988488155539942071e+00,1.269317097292944341e-01,1.000000009647149080e+00,6.839316092015533532e-02,-5.077544985575576053e-10,0.000000000000000000e+00 +5.714937277343807409e+01,3.500813089281454609e+02,3.198286597022749200e-01,4.990492770923335542e+00,1.271817097292944343e-01,1.000000009646131227e+00,6.839316092015533532e-02,-7.109646564416953113e-10,0.000000000000000000e+00 +5.715137658357447492e+01,3.500912281611655317e+02,3.210970509248257665e-01,4.992496581079063134e+00,1.274317097292944345e-01,1.000000009644706589e+00,6.839316092015533532e-02,-3.107285077411562266e-10,0.000000000000000000e+00 +5.715337958945291774e+01,3.501011470767778064e+02,3.223679219159685805e-01,4.994499586976822947e+00,1.276817097292944347e-01,1.000000009644084198e+00,6.839316092015533532e-02,-4.452641775667830149e-10,0.000000000000000000e+00 +5.715538179204115465e+01,3.501110656743624077e+02,3.236412725962738990e-01,4.996501789584370634e+00,1.279317097292944350e-01,1.000000009643192689e+00,6.839316092015533532e-02,-6.997277598876611919e-10,0.000000000000000000e+00 +5.715738319230500508e+01,3.501209839532993442e+02,3.249171028861573274e-01,4.998503189867520291e+00,1.281817097292944352e-01,1.000000009641792253e+00,6.839316092015533532e-02,-4.303046112123260016e-10,0.000000000000000000e+00 +5.715938379120834867e+01,3.501309019129687954e+02,3.261954127058794839e-01,5.000503788790151560e+00,1.284317097292944354e-01,1.000000009640931387e+00,6.839316092015533532e-02,-5.419544589343401046e-10,0.000000000000000000e+00 +5.716138358971313238e+01,3.501408195527508838e+02,3.274762019755459996e-01,5.002503587314217626e+00,1.286817097292944356e-01,1.000000009639847587e+00,6.839316092015533532e-02,-6.029308046593755784e-10,0.000000000000000000e+00 +5.716338258877939182e+01,3.501507368720257318e+02,3.287594706151075186e-01,5.004502586399746988e+00,1.289317097292944359e-01,1.000000009638642329e+00,6.839316092015533532e-02,-3.983733736721693361e-10,0.000000000000000000e+00 +5.716538078936523704e+01,3.501606538701734621e+02,3.300452185443597530e-01,5.006500787004850572e+00,1.291817097292944361e-01,1.000000009637846299e+00,6.839316092015533532e-02,-3.761879399816073760e-10,0.000000000000000000e+00 +5.716737819242686669e+01,3.501705705465743108e+02,3.313334456829434838e-01,5.008498190085727941e+00,1.294317097292944363e-01,1.000000009637094900e+00,6.839316092015533532e-02,-7.569020672831487083e-10,0.000000000000000000e+00 +5.716937479891856810e+01,3.501804869006085141e+02,3.326241519503445043e-01,5.010494796596670852e+00,1.296817097292944365e-01,1.000000009635583664e+00,6.839316092015533532e-02,-4.204339062749711549e-10,0.000000000000000000e+00 +5.717137060979273144e+01,3.501904029316562514e+02,3.339173372658936767e-01,5.012490607490067696e+00,1.299317097292944367e-01,1.000000009634744558e+00,6.839316092015533532e-02,-6.919499219552205962e-10,0.000000000000000000e+00 +5.717336562599985683e+01,3.502003186390977589e+02,3.352130015487669312e-01,5.014485623716413265e+00,1.301817097292944370e-01,1.000000009633364106e+00,6.839316092015533532e-02,-4.398085942920422226e-10,0.000000000000000000e+00 +5.717535984848854014e+01,3.502102340223133865e+02,3.365111447179852666e-01,5.016479846224308758e+00,1.304317097292944372e-01,1.000000009632487030e+00,6.839316092015533532e-02,-5.363343205015979390e-10,0.000000000000000000e+00 +5.717735327820550140e+01,3.502201490806833704e+02,3.378117666924146945e-01,5.018473275960471547e+00,1.306817097292944374e-01,1.000000009631417885e+00,6.839316092015533532e-02,-5.084664591194528495e-10,0.000000000000000000e+00 +5.717934591609557771e+01,3.502300638135880035e+02,3.391148673907663502e-01,5.020465913869736951e+00,1.309317097292944376e-01,1.000000009630404696e+00,6.839316092015533532e-02,-5.494688368626639632e-10,0.000000000000000000e+00 +5.718133776310172323e+01,3.502399782204076359e+02,3.404204467315964378e-01,5.022457760895065348e+00,1.311817097292944378e-01,1.000000009629310238e+00,6.839316092015533532e-02,-6.245174035915371857e-10,0.000000000000000000e+00 +5.718332882016503049e+01,3.502498923005226175e+02,3.417285046333062293e-01,5.024448817977546611e+00,1.314317097292944381e-01,1.000000009628066788e+00,6.839316092015533532e-02,-4.690199968577246934e-10,0.000000000000000000e+00 +5.718531908822473042e+01,3.502598060533132980e+02,3.430390410141421764e-01,5.026439086056405436e+00,1.316817097292944383e-01,1.000000009627133313e+00,6.839316092015533532e-02,-7.113981122968910348e-10,0.000000000000000000e+00 +5.718730856821817810e+01,3.502697194781600842e+02,3.443520557921956882e-01,5.028428566069007566e+00,1.319317097292944385e-01,1.000000009625718000e+00,6.839316092015533532e-02,-4.045207878637493737e-10,0.000000000000000000e+00 +5.718929726108088829e+01,3.502796325744433830e+02,3.456675488854033529e-01,5.030417258950862447e+00,1.321817097292944387e-01,1.000000009624913533e+00,6.839316092015533532e-02,-6.173531950142456096e-10,0.000000000000000000e+00 +5.719128516774652127e+01,3.502895453415436009e+02,3.469855202115468829e-01,5.032405165635632116e+00,1.324317097292944390e-01,1.000000009623686292e+00,6.839316092015533532e-02,-6.173736752965034511e-10,0.000000000000000000e+00 +5.719327228914689698e+01,3.502994577788412585e+02,3.483059696882530587e-01,5.034392287055132087e+00,1.326817097292944392e-01,1.000000009622459496e+00,6.839316092015533532e-02,-5.660841249454581352e-10,0.000000000000000000e+00 +5.719525862621198797e+01,3.503093698857167624e+02,3.496288972329937850e-01,5.036378624139339344e+00,1.329317097292944394e-01,1.000000009621335062e+00,6.839316092015533532e-02,-6.207687195968752895e-10,0.000000000000000000e+00 +5.719724417986994069e+01,3.503192816615506331e+02,3.509543027630860901e-01,5.038364177816396783e+00,1.331817097292944396e-01,1.000000009620102492e+00,6.839316092015533532e-02,-4.834082381576154579e-10,0.000000000000000000e+00 +5.719922895104706839e+01,3.503291931057233910e+02,3.522821861956921263e-01,5.040348949012617652e+00,1.334317097292944398e-01,1.000000009619143038e+00,6.839316092015533532e-02,-7.538811912632724164e-10,0.000000000000000000e+00 +5.720121294066785822e+01,3.503391042176155565e+02,3.536125474478191699e-01,5.042332938652491769e+00,1.336817097292944401e-01,1.000000009617647345e+00,6.839316092015533532e-02,-4.480730546704786406e-10,0.000000000000000000e+00 +5.720319614965497834e+01,3.503490149966077070e+02,3.549453864363196764e-01,5.044316147658688188e+00,1.339317097292944403e-01,1.000000009616758723e+00,6.839316092015533532e-02,-6.077462847907896759e-10,0.000000000000000000e+00 +5.720517857892929214e+01,3.503589254420803627e+02,3.562807030778911699e-01,5.046298576952064074e+00,1.341817097292944405e-01,1.000000009615553909e+00,6.839316092015533532e-02,-4.655691518359500799e-10,0.000000000000000000e+00 +5.720716022940983692e+01,3.503688355534141579e+02,3.576184972890763536e-01,5.048280227451665603e+00,1.344317097292944407e-01,1.000000009614631313e+00,6.839316092015533532e-02,-8.303948623158850668e-10,0.000000000000000000e+00 +5.720914110201385938e+01,3.503787453299897265e+02,3.589587689862631104e-01,5.050261100074735943e+00,1.346817097292944410e-01,1.000000009612986407e+00,6.839316092015533532e-02,-4.712052335545733689e-10,0.000000000000000000e+00 +5.721112119765680859e+01,3.503886547711877029e+02,3.603015180856845023e-01,5.052241195736717039e+00,1.349317097292944412e-01,1.000000009612053375e+00,6.839316092015533532e-02,-6.416826989677830616e-10,0.000000000000000000e+00 +5.721310051725232881e+01,3.503985638763887209e+02,3.616467445034186601e-01,5.054220515351259380e+00,1.351817097292944414e-01,1.000000009610783280e+00,6.839316092015533532e-02,-5.537242669438472476e-10,0.000000000000000000e+00 +5.721507906171227376e+01,3.504084726449734717e+02,3.629944481553889490e-01,5.056199059830221998e+00,1.354317097292944416e-01,1.000000009609687712e+00,6.839316092015533532e-02,-7.747764588092645489e-10,0.000000000000000000e+00 +5.721705683194672787e+01,3.504183810763227029e+02,3.643446289573638586e-01,5.058176830083680464e+00,1.356817097292944418e-01,1.000000009608155382e+00,6.839316092015533532e-02,-5.055257082321828145e-10,0.000000000000000000e+00 +5.721903382886398504e+01,3.504282891698170488e+02,3.656972868249571129e-01,5.060153827019929551e+00,1.359317097292944421e-01,1.000000009607155960e+00,6.839316092015533532e-02,-5.322397784411548367e-10,0.000000000000000000e+00 +5.722101005337056279e+01,3.504381969248373139e+02,3.670524216736276157e-01,5.062130051545491227e+00,1.361817097292944423e-01,1.000000009606104134e+00,6.839316092015533532e-02,-7.289261057923937425e-10,0.000000000000000000e+00 +5.722298550637120940e+01,3.504481043407642460e+02,3.684100334186794501e-01,5.064105504565116433e+00,1.364317097292944425e-01,1.000000009604664175e+00,6.839316092015533532e-02,-7.369693183916175679e-10,0.000000000000000000e+00 +5.722496018876891810e+01,3.504580114169786498e+02,3.697701219752618229e-01,5.066080186981790412e+00,1.366817097292944427e-01,1.000000009603208895e+00,6.839316092015533532e-02,-4.200360818760186328e-10,0.000000000000000000e+00 +5.722693410146491289e+01,3.504679181528613299e+02,3.711326872583692316e-01,5.068054099696738923e+00,1.369317097292944430e-01,1.000000009602379780e+00,6.839316092015533532e-02,-7.777183759883712074e-10,0.000000000000000000e+00 +5.722890724535866269e+01,3.504778245477930909e+02,3.724977291828413528e-01,5.070027243609433576e+00,1.371817097292944432e-01,1.000000009600845230e+00,6.839316092015533532e-02,-7.543799487181160532e-10,0.000000000000000000e+00 +5.723087962134788853e+01,3.504877306011547944e+02,3.738652476633630983e-01,5.071999619617592714e+00,1.374317097292944434e-01,1.000000009599357309e+00,6.839316092015533532e-02,-4.280724786679728471e-10,0.000000000000000000e+00 +5.723285123032856347e+01,3.504976363123273586e+02,3.752352426144645037e-01,5.073971228617190299e+00,1.376817097292944436e-01,1.000000009598513317e+00,6.839316092015533532e-02,-7.880902318330661579e-10,0.000000000000000000e+00 +5.723482207319491977e+01,3.505075416806916451e+02,3.766077139505208948e-01,5.075942071502460351e+00,1.379317097292944438e-01,1.000000009596960115e+00,6.839316092015533532e-02,-7.636004614048712600e-10,0.000000000000000000e+00 +5.723679215083944882e+01,3.505174467056285152e+02,3.779826615857528327e-01,5.077912149165897837e+00,1.381817097292944441e-01,1.000000009595455763e+00,6.839316092015533532e-02,-4.197768117851693737e-10,0.000000000000000000e+00 +5.723876146415292254e+01,3.505273513865189443e+02,3.793600854342261131e-01,5.079881462498267553e+00,1.384317097292944443e-01,1.000000009594629091e+00,6.839316092015533532e-02,-7.359940777451877859e-10,0.000000000000000000e+00 +5.724073001402437910e+01,3.505372557227439074e+02,3.807399854098517111e-01,5.081850012388608562e+00,1.386817097292944445e-01,1.000000009593180250e+00,6.839316092015533532e-02,-8.545353345783308583e-10,0.000000000000000000e+00 +5.724269780134113006e+01,3.505471597136843798e+02,3.821223614263858925e-01,5.083817799724235087e+00,1.389317097292944447e-01,1.000000009591498706e+00,6.839316092015533532e-02,-3.704834221339701407e-10,0.000000000000000000e+00 +5.724466482698877456e+01,3.505570633587213365e+02,3.835072133974301023e-01,5.085784825390744501e+00,1.391817097292944450e-01,1.000000009590769956e+00,6.839316092015533532e-02,-9.405698844373480191e-10,0.000000000000000000e+00 +5.724663109185119225e+01,3.505669666572358096e+02,3.848945412364311869e-01,5.087751090272023546e+00,1.394317097292944452e-01,1.000000009588920546e+00,6.839316092015533532e-02,-5.446320729119198037e-10,0.000000000000000000e+00 +5.724859659681057167e+01,3.505768696086088880e+02,3.862843448566810611e-01,5.089716595250246556e+00,1.396817097292944454e-01,1.000000009587850069e+00,6.839316092015533532e-02,-8.325771662589202121e-10,0.000000000000000000e+00 +5.725056134274737474e+01,3.505867722122216037e+02,3.876766241713170968e-01,5.091681341205887890e+00,1.399317097292944456e-01,1.000000009586214267e+00,6.839316092015533532e-02,-6.931588259580689689e-10,0.000000000000000000e+00 +5.725252533054037940e+01,3.505966744674549886e+02,3.890713790933217897e-01,5.093645329017720158e+00,1.401817097292944458e-01,1.000000009584852911e+00,6.839316092015533532e-02,-6.194577177216509710e-10,0.000000000000000000e+00 +5.725448856106666540e+01,3.506065763736902454e+02,3.904686095355229258e-01,5.095608559562823103e+00,1.404317097292944461e-01,1.000000009583636773e+00,6.839316092015533532e-02,-6.415335048242366899e-10,0.000000000000000000e+00 +5.725645103520162138e+01,3.506164779303084629e+02,3.918683154105936373e-01,5.097571033716586264e+00,1.406817097292944463e-01,1.000000009582377780e+00,6.839316092015533532e-02,-7.855303735036645907e-10,0.000000000000000000e+00 +5.725841275381895201e+01,3.506263791366907867e+02,3.932704966310522909e-01,5.099532752352713416e+00,1.409317097292944465e-01,1.000000009580836791e+00,6.839316092015533532e-02,-8.424488590620213464e-10,0.000000000000000000e+00 +5.726037371779067797e+01,3.506362799922183626e+02,3.946751531092625997e-01,5.101493716343227014e+00,1.411817097292944467e-01,1.000000009579184779e+00,6.839316092015533532e-02,-5.976437311134144549e-10,0.000000000000000000e+00 +5.726233392798715016e+01,3.506461804962724500e+02,3.960822847574335115e-01,5.103453926558473519e+00,1.414317097292944470e-01,1.000000009578013271e+00,6.839316092015533532e-02,-7.590136164045947863e-10,0.000000000000000000e+00 +5.726429338527703550e+01,3.506560806482342514e+02,3.974918914876192644e-01,5.105413383867128729e+00,1.416817097292944472e-01,1.000000009576526017e+00,6.839316092015533532e-02,-6.414075698550950087e-10,0.000000000000000000e+00 +5.726625209052734533e+01,3.506659804474849693e+02,3.989039732117194981e-01,5.107372089136199556e+00,1.419317097292944474e-01,1.000000009575269688e+00,6.839316092015533532e-02,-7.136667380821327729e-10,0.000000000000000000e+00 +5.726821004460342834e+01,3.506758798934058632e+02,4.003185298414790871e-01,5.109330043231031127e+00,1.421817097292944476e-01,1.000000009573872362e+00,6.839316092015533532e-02,-9.774844856309208889e-10,0.000000000000000000e+00 +5.727016724836897055e+01,3.506857789853782492e+02,4.017355612884881966e-01,5.111287247015309454e+00,1.424317097292944478e-01,1.000000009571959225e+00,6.839316092015533532e-02,-5.024351744106597523e-10,0.000000000000000000e+00 +5.727212370268600239e+01,3.506956777227834436e+02,4.031550674641823928e-01,5.113243701351065873e+00,1.426817097292944481e-01,1.000000009570976234e+00,6.839316092015533532e-02,-9.057967320509076059e-10,0.000000000000000000e+00 +5.727407940841490586e+01,3.507055761050027627e+02,4.045770482798425327e-01,5.115199407098685036e+00,1.429317097292944483e-01,1.000000009569204762e+00,6.839316092015533532e-02,-7.849530603833757217e-10,0.000000000000000000e+00 +5.727603436641441448e+01,3.507154741314175794e+02,4.060015036465948746e-01,5.117154365116903136e+00,1.431817097292944485e-01,1.000000009567670212e+00,6.839316092015533532e-02,-5.887977643234297911e-10,0.000000000000000000e+00 +5.727798857754163464e+01,3.507253718014092101e+02,4.074284334754109116e-01,5.119108576262817678e+00,1.434317097292944487e-01,1.000000009566519577e+00,6.839316092015533532e-02,-9.975419793591397327e-10,0.000000000000000000e+00 +5.727994204265201716e+01,3.507352691143590846e+02,4.088578376771074829e-01,5.121062041391890141e+00,1.436817097292944490e-01,1.000000009564570913e+00,6.839316092015533532e-02,-5.920901557827112146e-10,0.000000000000000000e+00 +5.728189476259939994e+01,3.507451660696486329e+02,4.102897161623468847e-01,5.123014761357947755e+00,1.439317097292944492e-01,1.000000009563414727e+00,6.839316092015533532e-02,-7.430396835859135394e-10,0.000000000000000000e+00 +5.728384673823597950e+01,3.507550626666592848e+02,4.117240688416367034e-01,5.124966737013193274e+00,1.441817097292944494e-01,1.000000009561964331e+00,6.839316092015533532e-02,-9.549854431026785650e-10,0.000000000000000000e+00 +5.728579797041233235e+01,3.507649589047725271e+02,4.131608956253299270e-01,5.126917969208204084e+00,1.444317097292944496e-01,1.000000009560100933e+00,6.839316092015533532e-02,-7.267574168118334014e-10,0.000000000000000000e+00 +5.728774845997742204e+01,3.507748547833697899e+02,4.146001964236248338e-01,5.128868458791938423e+00,1.446817097292944498e-01,1.000000009558683400e+00,6.839316092015533532e-02,-9.537764654151121726e-10,0.000000000000000000e+00 +5.728969820777858502e+01,3.507847503018326165e+02,4.160419711465651038e-01,5.130818206611741594e+00,1.449317097292944501e-01,1.000000009556823777e+00,6.839316092015533532e-02,-6.599794015938313996e-10,0.000000000000000000e+00 +5.729164721466156607e+01,3.507946454595425507e+02,4.174862197040398737e-01,5.132767213513346860e+00,1.451817097292944503e-01,1.000000009555537472e+00,6.839316092015533532e-02,-7.339689046542908046e-10,0.000000000000000000e+00 +5.729359548147048287e+01,3.508045402558811361e+02,4.189329420057835707e-01,5.134715480340883431e+00,1.454317097292944505e-01,1.000000009554107505e+00,6.839316092015533532e-02,-8.930684271548670305e-10,0.000000000000000000e+00 +5.729554300904786857e+01,3.508144346902299162e+02,4.203821379613760789e-01,5.136663007936877356e+00,1.456817097292944507e-01,1.000000009552368230e+00,6.839316092015533532e-02,-8.491531054775081924e-10,0.000000000000000000e+00 +5.729748979823465049e+01,3.508243287619704915e+02,4.218338074802426285e-01,5.138609797142256852e+00,1.459317097292944510e-01,1.000000009550715108e+00,6.839316092015533532e-02,-7.790751975741933668e-10,0.000000000000000000e+00 +5.729943584987016436e+01,3.508342224704845194e+02,4.232879504716539065e-01,5.140555848796357630e+00,1.461817097292944512e-01,1.000000009549198987e+00,6.839316092015533532e-02,-8.558462328672763761e-10,0.000000000000000000e+00 +5.730138116479215427e+01,3.508441158151536001e+02,4.247445668447259459e-01,5.142501163736926451e+00,1.464317097292944514e-01,1.000000009547534097e+00,6.839316092015533532e-02,-7.801219215208972489e-10,0.000000000000000000e+00 +5.730332574383678690e+01,3.508540087953594480e+02,4.262036565084202366e-01,5.144445742800124677e+00,1.466817097292944516e-01,1.000000009546017088e+00,6.839316092015533532e-02,-9.524467570957692779e-10,0.000000000000000000e+00 +5.730526958783863734e+01,3.508639014104837202e+02,4.276652193715436701e-01,5.146389586820533601e+00,1.469317097292944518e-01,1.000000009544165680e+00,6.839316092015533532e-02,-8.303061957501522169e-10,0.000000000000000000e+00 +5.730721269763071746e+01,3.508737936599081308e+02,4.291292553427485945e-01,5.148332696631157113e+00,1.471817097292944521e-01,1.000000009542552304e+00,6.839316092015533532e-02,-8.069562908001723272e-10,0.000000000000000000e+00 +5.730915507404445464e+01,3.508836855430144510e+02,4.305957643305327598e-01,5.150275073063427911e+00,1.474317097292944523e-01,1.000000009540984891e+00,6.839316092015533532e-02,-1.038151722660303000e-09,0.000000000000000000e+00 +5.731109671790971305e+01,3.508935770591843948e+02,4.320647462432393171e-01,5.152216716947210173e+00,1.476817097292944525e-01,1.000000009538969170e+00,6.839316092015533532e-02,-7.328604454129601059e-10,0.000000000000000000e+00 +5.731303763005479368e+01,3.509034682077997331e+02,4.335362009890569301e-01,5.154157629110803107e+00,1.479317097292944527e-01,1.000000009537546752e+00,6.839316092015533532e-02,-7.995750143730412374e-02,0.000000000000000000e+00 +5.731497781130643432e+01,3.509133589882422939e+02,4.350101284760196640e-01,5.156097810380948054e+00,1.481817097292944529e-01,9.998448774923300864e-01,6.839316092015533532e-02,-9.999997704246778030e-01,0.000000000000000000e+00 +5.731691726248982377e+01,3.509232493998939049e+02,4.364865286120070409e-01,5.158036960711803509e+00,1.484317097292944532e-01,9.979054267541936918e-01,6.839316092015533532e-02,-9.999998902039377580e-01,0.000000000000000000e+00 +5.731885598454167763e+01,3.509331394421363939e+02,4.379654013047440397e-01,5.159971621968314714e+00,1.486817097292944534e-01,9.959667049152056695e-01,6.839316092015533532e-02,-9.999999297597081949e-01,0.000000000000000000e+00 +5.732079397969603463e+01,3.509430291143516456e+02,4.394467464618011521e-01,5.161901800616342406e+00,1.489317097292944536e-01,9.940287098969728952e-01,6.839316092015533532e-02,-9.999999497001741400e-01,0.000000000000000000e+00 +5.732273125018010518e+01,3.509529184159216015e+02,4.409305639905942709e-01,5.163827503096343641e+00,1.491817097292944538e-01,9.920914395103476169e-01,6.839316092015533532e-02,-9.999999618568127246e-01,0.000000000000000000e+00 +5.732466779821429270e+01,3.509628073462281463e+02,4.424168537983848570e-01,5.165748735823260773e+00,1.494317097292944541e-01,9.901548915500271164e-01,6.839316092015533532e-02,-9.999999696098851310e-01,0.000000000000000000e+00 +5.732660362601223625e+01,3.509726959046531647e+02,4.439056157922797730e-01,5.167665505186593400e+00,1.496817097292944543e-01,9.882190638109132896e-01,6.839316092015533532e-02,-9.999999752080414028e-01,0.000000000000000000e+00 +5.732853873578084603e+01,3.509825840905787118e+02,4.453968498792313935e-01,5.169577817550501386e+00,1.499317097292944545e-01,9.862839540902775815e-01,6.839316092015533532e-02,-9.999999797636539567e-01,0.000000000000000000e+00 +5.733047312972033893e+01,3.509924719033867291e+02,4.468905559660375504e-01,5.171485679253911449e+00,1.501817097292944547e-01,9.843495601899310277e-01,6.839316092015533532e-02,-9.999999827745441605e-01,0.000000000000000000e+00 +5.733240681002425987e+01,3.510023593424592150e+02,4.483867339593416435e-01,5.173389096610627291e+00,1.504317097292944549e-01,9.824158799193152269e-01,6.839316092015533532e-02,-9.999999856851338187e-01,0.000000000000000000e+00 +5.733433977887953858e+01,3.510122464071782247e+02,4.498853837656325849e-01,5.175288075909445062e+00,1.506817097292944552e-01,9.804829110917041568e-01,6.839316092015533532e-02,-9.999999878507712658e-01,0.000000000000000000e+00 +5.733627203846650389e+01,3.510221330969258133e+02,4.513865052912446885e-01,5.177182623414260831e+00,1.509317097292944554e-01,9.785506515282110795e-01,6.839316092015533532e-02,-9.999999893875052281e-01,0.000000000000000000e+00 +5.733820359095892627e+01,3.510320194110840930e+02,4.528900984423578913e-01,5.179072745364185160e+00,1.511817097292944556e-01,9.766190990562837460e-01,6.839316092015533532e-02,-9.999999911778417738e-01,0.000000000000000000e+00 +5.734013443852405345e+01,3.510419053490351189e+02,4.543961631249976429e-01,5.180958447973654124e+00,1.514317097292944558e-01,9.746882515081913834e-01,6.839316092015533532e-02,-9.999999922505860006e-01,0.000000000000000000e+00 +5.734206458332263168e+01,3.510517909101610599e+02,4.559046992450349056e-01,5.182839737432536786e+00,1.516817097292944561e-01,9.727581067245718582e-01,6.839316092015533532e-02,-9.999999935940402374e-01,0.000000000000000000e+00 +5.734399402750894836e+01,3.510616760938440279e+02,4.574157067081861539e-01,5.184716619906248880e+00,1.519317097292944563e-01,9.708286625506151735e-01,6.839316092015533532e-02,-9.999999945823082603e-01,0.000000000000000000e+00 +5.734592277323086762e+01,3.510715608994662489e+02,4.589291854200134302e-01,5.186589101535858504e+00,1.521817097292944565e-01,9.688999168391467798e-01,6.839316092015533532e-02,-9.999999953608864622e-01,0.000000000000000000e+00 +5.734785082262985156e+01,3.510814453264098915e+02,4.604451352859242896e-01,5.188457188438197143e+00,1.524317097292944567e-01,9.669718674491059041e-01,6.839316092015533532e-02,-9.999999963718385620e-01,0.000000000000000000e+00 +5.734977817784101006e+01,3.510913293740571817e+02,4.619635562111719107e-01,5.190320886705967141e+00,1.526817097292944569e-01,9.650445122449419211e-01,6.839316092015533532e-02,-9.999999966818292618e-01,0.000000000000000000e+00 +5.735170484099311494e+01,3.511012130417903450e+02,4.634844481008549288e-01,5.192180202407847389e+00,1.529317097292944572e-01,9.631178490992332586e-01,6.839316092015533532e-02,-9.999999975699299659e-01,0.000000000000000000e+00 +5.735363081420863551e+01,3.511110963289916640e+02,4.650078108599176585e-01,5.194035141588603466e+00,1.531817097292944574e-01,9.611918758883917224e-01,6.839316092015533532e-02,-9.999999979841892594e-01,0.000000000000000000e+00 +5.735555609960378831e+01,3.511209792350434782e+02,4.665336443931498711e-01,5.195885710269188884e+00,1.534317097292944576e-01,9.592665904971220403e-01,6.839316092015533532e-02,-9.999999986110561512e-01,0.000000000000000000e+00 +5.735748069928854420e+01,3.511308617593280701e+02,4.680619486051870171e-01,5.197731914446854340e+00,1.536817097292944578e-01,9.573419908150415658e-01,6.839316092015533532e-02,-9.999999992434713825e-01,0.000000000000000000e+00 +5.735940461536667101e+01,3.511407439012277791e+02,4.695927234005100592e-01,5.199573760095249852e+00,1.539317097292944581e-01,9.554180747383697048e-01,6.839316092015533532e-02,-9.999999992586228181e-01,0.000000000000000000e+00 +5.736132784993576905e+01,3.511506256601250016e+02,4.711259686834455840e-01,5.201411253164529569e+00,1.541817097292944583e-01,9.534948401706956345e-01,6.839316092015533532e-02,-1.000000000021212587e+00,0.000000000000000000e+00 +5.736325040508729955e+01,3.511605070354020768e+02,4.726616843581657457e-01,5.203244399581457458e+00,1.544317097292944585e-01,9.515722850191243865e-01,6.839316092015533532e-02,-1.000000000323536531e+00,0.000000000000000000e+00 +5.736517228290660597e+01,3.511703880264414579e+02,4.741998703286883221e-01,5.205073205249505008e+00,1.546817097292944587e-01,9.496504071991934692e-01,6.839316092015533532e-02,-1.000000000466821248e+00,0.000000000000000000e+00 +5.736709348547296372e+01,3.511802686326255412e+02,4.757405264988767146e-01,5.206897676048957813e+00,1.549317097292944589e-01,9.477292046319398811e-01,6.839316092015533532e-02,-1.000000001065093791e+00,0.000000000000000000e+00 +5.736901401485958729e+01,3.511901488533368365e+02,4.772836527724398925e-01,5.208717817837015929e+00,1.551817097292944592e-01,9.458086752432696143e-01,6.839316092015533532e-02,-1.000000000878526585e+00,0.000000000000000000e+00 +5.737093387313367998e+01,3.512000286879577970e+02,4.788292490529324485e-01,5.210533636447892469e+00,1.554317097292944594e-01,9.438888169674880535e-01,6.839316092015533532e-02,-1.000000001871750532e+00,0.000000000000000000e+00 +5.737285306235646232e+01,3.512099081358709327e+02,4.803773152437546545e-01,5.212345137692918406e+00,1.556817097292944596e-01,9.419696277411164775e-01,6.839316092015533532e-02,-1.000000001504713021e+00,0.000000000000000000e+00 +5.737477158458317916e+01,3.512197871964588103e+02,4.819278512481523502e-01,5.214152327360634942e+00,1.559317097292944598e-01,9.400511055115096104e-01,6.839316092015533532e-02,-1.000000002135445820e+00,0.000000000000000000e+00 +5.737668944186317077e+01,3.512296658691039966e+02,4.834808569692170543e-01,5.215955211216901866e+00,1.561817097292944601e-01,9.381332482274251650e-01,6.839316092015533532e-02,-1.000000002097966245e+00,0.000000000000000000e+00 +5.737860663623985857e+01,3.512395441531890015e+02,4.850363323098859092e-01,5.217753795004987261e+00,1.564317097292944603e-01,9.362160538467152460e-01,6.839316092015533532e-02,-1.000000002459565218e+00,0.000000000000000000e+00 +5.738052316975080913e+01,3.512494220480965055e+02,4.865942771729416805e-01,5.219548084445671421e+00,1.566817097292944605e-01,9.342995203310540120e-01,6.839316092015533532e-02,-1.000000002434693336e+00,0.000000000000000000e+00 +5.738243904442773413e+01,3.512592995532091322e+02,4.881546914610128129e-01,5.221338085237340110e+00,1.569317097292944607e-01,9.323836456494609681e-01,6.839316092015533532e-02,-1.000000003011035421e+00,0.000000000000000000e+00 +5.738435426229655434e+01,3.512691766679095053e+02,4.897175750765734303e-01,5.223123803056084036e+00,1.571817097292944609e-01,9.304684277748735965e-01,6.839316092015533532e-02,-1.000000002838139057e+00,0.000000000000000000e+00 +5.738626882537739959e+01,3.512790533915803053e+02,4.912829279219433354e-01,5.224905243555791223e+00,1.574317097292944612e-01,9.285538646885974634e-01,6.839316092015533532e-02,-1.000000003311972252e+00,0.000000000000000000e+00 +5.738818273568464434e+01,3.512889297236042694e+02,4.928507498992878988e-01,5.226682412368247377e+00,1.576817097292944614e-01,9.266399543750174495e-01,6.839316092015533532e-02,-1.000000003248159741e+00,0.000000000000000000e+00 +5.739009599522693605e+01,3.512988056633640781e+02,4.944210409106183368e-01,5.228455315103225587e+00,1.579317097292944616e-01,9.247266948265095987e-01,6.839316092015533532e-02,-1.000000003243545210e+00,0.000000000000000000e+00 +5.739200860600723786e+01,3.513086812102425256e+02,4.959938008577913782e-01,5.230223957348584918e+00,1.581817097292944618e-01,9.228140840400027578e-01,6.839316092015533532e-02,-1.000000003741488452e+00,0.000000000000000000e+00 +5.739392057002284275e+01,3.513185563636224060e+02,4.975690296425095971e-01,5.231988344670361890e+00,1.584317097292944621e-01,9.209021200172452515e-01,6.839316092015533532e-02,-1.000000003814708105e+00,0.000000000000000000e+00 +5.739583188926540203e+01,3.513284311228864567e+02,4.991467271663211358e-01,5.233748482612861963e+00,1.586817097292944623e-01,9.189908007673975865e-01,6.839316092015533532e-02,-1.000000003839607521e+00,0.000000000000000000e+00 +5.739774256572095368e+01,3.513383054874175855e+02,5.007268933306199266e-01,5.235504376698755458e+00,1.589317097292944625e-01,9.170801243045111351e-01,6.839316092015533532e-02,-1.000000004039946155e+00,0.000000000000000000e+00 +5.739965260136995795e+01,3.513481794565985865e+02,5.023095280366456361e-01,5.237256032429168151e+00,1.591817097292944627e-01,9.151700886477928121e-01,6.839316092015533532e-02,-1.000000004244780971e+00,0.000000000000000000e+00 +5.740156199818731153e+01,3.513580530298123676e+02,5.038946311854834992e-01,5.239003455283771871e+00,1.594317097292944629e-01,9.132606918223316050e-01,6.839316092015533532e-02,-1.000000003887132172e+00,0.000000000000000000e+00 +5.740347075814239730e+01,3.513679262064417799e+02,5.054822026780646516e-01,5.240746650720875977e+00,1.596817097292944632e-01,9.113519318598265473e-01,6.839316092015533532e-02,-1.000000004688190947e+00,0.000000000000000000e+00 +5.740537888319908433e+01,3.513777989858697879e+02,5.070722424151657970e-01,5.242485624177519732e+00,1.599317097292944634e-01,9.094438067941917891e-01,6.839316092015533532e-02,-1.000000004318386759e+00,0.000000000000000000e+00 +5.740728637531577760e+01,3.513876713674793564e+02,5.086647502974095403e-01,5.244220381069555792e+00,1.601817097292944636e-01,9.075363146692605465e-01,6.839316092015533532e-02,-1.000000004446358837e+00,0.000000000000000000e+00 +5.740919323644543226e+01,3.513975433506534500e+02,5.102597262252640542e-01,5.245950926791747904e+00,1.604317097292944638e-01,9.056294535311281146e-01,6.839316092015533532e-02,-1.000000004642156659e+00,0.000000000000000000e+00 +5.741109946853558199e+01,3.514074149347750904e+02,5.118571700990434126e-01,5.247677266717853506e+00,1.606817097292944641e-01,9.037232214321295753e-01,6.839316092015533532e-02,-1.000000004817836796e+00,0.000000000000000000e+00 +5.741300507352836746e+01,3.514172861192272421e+02,5.134570818189073682e-01,5.249399406200713436e+00,1.609317097292944643e-01,9.018176164301602293e-01,6.839316092015533532e-02,-1.000000004983856661e+00,0.000000000000000000e+00 +5.741491005336057185e+01,3.514271569033929836e+02,5.150594612848613529e-01,5.251117350572339859e+00,1.611817097292944645e-01,8.999126365884613232e-01,6.839316092015533532e-02,-1.000000004761526951e+00,0.000000000000000000e+00 +5.741681440996362795e+01,3.514370272866554501e+02,5.166643083967568106e-01,5.252831105144003310e+00,1.614317097292944647e-01,8.980082799763347001e-01,6.839316092015533532e-02,-1.000000004852888758e+00,0.000000000000000000e+00 +5.741871814526366791e+01,3.514468972683976631e+02,5.182716230542906422e-01,5.254540675206320621e+00,1.616817097292944649e-01,8.961045446670581338e-01,6.839316092015533532e-02,-1.000000005328433916e+00,0.000000000000000000e+00 +5.742062126118152321e+01,3.514567668480027578e+02,5.198814051570057604e-01,5.256246066029338415e+00,1.619317097292944652e-01,8.942014287390628313e-01,6.839316092015533532e-02,-1.000000004890165384e+00,0.000000000000000000e+00 +5.742252375963277444e+01,3.514666360248539263e+02,5.214936546042907572e-01,5.257947282862618366e+00,1.621817097292944654e-01,8.922989302785111487e-01,6.839316092015533532e-02,-1.000000005287564164e+00,0.000000000000000000e+00 +5.742442564252775838e+01,3.514765047983343038e+02,5.231083712953800147e-01,5.259644330935326906e+00,1.624317097292944656e-01,8.903970473734715840e-01,6.839316092015533532e-02,-1.000000005432535310e+00,0.000000000000000000e+00 +5.742632691177161064e+01,3.514863731678271392e+02,5.247255551293538156e-01,5.261337215456313388e+00,1.626817097292944658e-01,8.884957781192923676e-01,6.839316092015533532e-02,-1.000000005323318231e+00,0.000000000000000000e+00 +5.742822756926427985e+01,3.514962411327156246e+02,5.263452060051381221e-01,5.263025941614198011e+00,1.629317097292944660e-01,8.865951206165084697e-01,6.839316092015533532e-02,-1.000000005312538187e+00,0.000000000000000000e+00 +5.743012761690054901e+01,3.515061086923830089e+02,5.279673238215047970e-01,5.264710514577455314e+00,1.631817097292944663e-01,8.846950729701428262e-01,6.839316092015533532e-02,-1.000000005616223042e+00,0.000000000000000000e+00 +5.743202705657008522e+01,3.515159758462125978e+02,5.295919084770713825e-01,5.266390939494495882e+00,1.634317097292944665e-01,8.827956332899413727e-01,6.839316092015533532e-02,-1.000000005575140127e+00,0.000000000000000000e+00 +5.743392589015743255e+01,3.515258425935876971e+02,5.312189598703014326e-01,5.268067221493748065e+00,1.636817097292944667e-01,8.808967996920104016e-01,6.839316092015533532e-02,-1.000000005625196531e+00,0.000000000000000000e+00 +5.743582411954205469e+01,3.515357089338916126e+02,5.328484778995041804e-01,5.269739365683742349e+00,1.639317097292944669e-01,8.789985702967111347e-01,6.839316092015533532e-02,-1.000000005575442552e+00,0.000000000000000000e+00 +5.743772174659836338e+01,3.515455748665077067e+02,5.344804624628347600e-01,5.271407377153191298e+00,1.641817097292944672e-01,8.771009432298254582e-01,6.839316092015533532e-02,-1.000000005840606221e+00,0.000000000000000000e+00 +5.743961877319572551e+01,3.515554403908193422e+02,5.361149134582942066e-01,5.273071260971071261e+00,1.644317097292944674e-01,8.752039166213817500e-01,6.839316092015533532e-02,-1.000000005715520057e+00,0.000000000000000000e+00 +5.744151520119851284e+01,3.515653055062099384e+02,5.377518307837292344e-01,5.274731022186701423e+00,1.646817097292944676e-01,8.733074886077550891e-01,6.839316092015533532e-02,-1.000000005843482143e+00,0.000000000000000000e+00 +5.744341103246610203e+01,3.515751702120629147e+02,5.393912143368325696e-01,5.276386665829826406e+00,1.649317097292944678e-01,8.714116573290846546e-01,6.839316092015533532e-02,-1.000000005749025700e+00,0.000000000000000000e+00 +5.744530626885291724e+01,3.515850345077617476e+02,5.410330640151427284e-01,5.278038196910693536e+00,1.651817097292944680e-01,8.695164209313712700e-01,6.839316092015533532e-02,-1.000000006061724456e+00,0.000000000000000000e+00 +5.744720091220844438e+01,3.515948983926899132e+02,5.426773797160441282e-01,5.279685620420133674e+00,1.654317097292944683e-01,8.676217775643584318e-01,6.839316092015533532e-02,-1.000000006045149714e+00,0.000000000000000000e+00 +5.744909496437725949e+01,3.516047618662308878e+02,5.443241613367669762e-01,5.281328941329637594e+00,1.656817097292944685e-01,8.657277253840970355e-01,6.839316092015533532e-02,-1.000000006070120406e+00,0.000000000000000000e+00 +5.745098842719904297e+01,3.516146249277682614e+02,5.459734087743874920e-01,5.282968164591436810e+00,1.659317097292944687e-01,8.638342625508231842e-01,6.839316092015533532e-02,-1.000000005884778886e+00,0.000000000000000000e+00 +5.745288130250861514e+01,3.516244875766855102e+02,5.476251219258276848e-01,5.284603295138579959e+00,1.661817097292944689e-01,8.619413872301139312e-01,6.839316092015533532e-02,-1.000000006349351933e+00,0.000000000000000000e+00 +5.745477359213595747e+01,3.516343498123662812e+02,5.492793006878554651e-01,5.286234337885010959e+00,1.664317097292944692e-01,8.600490975907586488e-01,6.839316092015533532e-02,-1.000000005965545835e+00,0.000000000000000000e+00 +5.745666529790623400e+01,3.516442116341941642e+02,5.509359449570846445e-01,5.287861297725642729e+00,1.666817097292944694e-01,8.581573918091991438e-01,6.839316092015533532e-02,-1.000000006333905178e+00,0.000000000000000000e+00 +5.745855642163981258e+01,3.516540730415528060e+02,5.525950546299750465e-01,5.289484179536438901e+00,1.669317097292944696e-01,8.562662680636424772e-01,6.839316092015533532e-02,-1.000000006200701064e+00,0.000000000000000000e+00 +5.746044696515229333e+01,3.516639340338258535e+02,5.542566296028321737e-01,5.291102988174483990e+00,1.671817097292944698e-01,8.543757245394375532e-01,6.839316092015533532e-02,-1.000000006422039567e+00,0.000000000000000000e+00 +5.746233693025452993e+01,3.516737946103970103e+02,5.559206697718077628e-01,5.292717728478063322e+00,1.674317097292944700e-01,8.524857594250615511e-01,6.839316092015533532e-02,-1.000000005991218854e+00,0.000000000000000000e+00 +5.746422631875265097e+01,3.516836547706499800e+02,5.575871750328991183e-01,5.294328405266734983e+00,1.676817097292944703e-01,8.505963709156184605e-01,6.839316092015533532e-02,-1.000000006763769766e+00,0.000000000000000000e+00 +5.746611513244808833e+01,3.516935145139685233e+02,5.592561452819497791e-01,5.295935023341407977e+00,1.679317097292944705e-01,8.487075572074076479e-01,6.839316092015533532e-02,-1.000000006242758754e+00,0.000000000000000000e+00 +5.746800337313758433e+01,3.517033738397364004e+02,5.609275804146490740e-01,5.297537587484409727e+00,1.681817097292944707e-01,8.468193165061238536e-01,6.839316092015533532e-02,-1.000000006290083343e+00,0.000000000000000000e+00 +5.746989104261323433e+01,3.517132327473373721e+02,5.626014803265323438e-01,5.299136102459568676e+00,1.684317097292944709e-01,8.449316470186007955e-01,6.839316092015533532e-02,-1.000000006657123519e+00,0.000000000000000000e+00 +5.747177814266249385e+01,3.517230912361553123e+02,5.642778449129808305e-01,5.300730573012280900e+00,1.686817097292944712e-01,8.430445469567756644e-01,6.839316092015533532e-02,-1.000000006474928593e+00,0.000000000000000000e+00 +5.747366467506822119e+01,3.517329493055740386e+02,5.659566740692216769e-01,5.302321003869583826e+00,1.689317097292944714e-01,8.411580145388364294e-01,6.839316092015533532e-02,-1.000000006501623684e+00,0.000000000000000000e+00 +5.747555064160867033e+01,3.517428069549774250e+02,5.676379676903281490e-01,5.303907399740231732e+00,1.691817097292944716e-01,8.392720479861289773e-01,6.839316092015533532e-02,-1.000000006629067295e+00,0.000000000000000000e+00 +5.747743604405753359e+01,3.517526641837493457e+02,5.693217256712194141e-01,5.305489765314765016e+00,1.694317097292944718e-01,8.373866455247699347e-01,6.839316092015533532e-02,-1.000000006631152294e+00,0.000000000000000000e+00 +5.747932088418395580e+01,3.517625209912737319e+02,5.710079479066605401e-01,5.307068105265582147e+00,1.696817097292944720e-01,8.355018053858467297e-01,6.839316092015533532e-02,-1.000000006414518250e+00,0.000000000000000000e+00 +5.748120516375256983e+01,3.517723773769345144e+02,5.726966342912626073e-01,5.308642424247011604e+00,1.699317097292944723e-01,8.336175258051450321e-01,6.839316092015533532e-02,-1.000000006770563665e+00,0.000000000000000000e+00 +5.748308888452350374e+01,3.517822333401157380e+02,5.743877847194828190e-01,5.310212726895382929e+00,1.701817097292944725e-01,8.317338050214601042e-01,6.839316092015533532e-02,-1.000000006874286251e+00,0.000000000000000000e+00 +5.748497204825239493e+01,3.517920888802013337e+02,5.760813990856241684e-01,5.311779017829094229e+00,1.704317097292944727e-01,8.298506412796208265e-01,6.839316092015533532e-02,-1.000000006535474384e+00,0.000000000000000000e+00 +5.748685465669043992e+01,3.518019439965753463e+02,5.777774772838357720e-01,5.313341301648685011e+00,1.706817097292944729e-01,8.279680328292712277e-01,6.839316092015533532e-02,-1.000000006703069211e+00,0.000000000000000000e+00 +5.748873671158439436e+01,3.518117986886218773e+02,5.794760192081127581e-01,5.314899582936906342e+00,1.709317097292944732e-01,8.260859779227046618e-01,6.839316092015533532e-02,-1.000000006960860555e+00,0.000000000000000000e+00 +5.749061821467658717e+01,3.518216529557249714e+02,5.811770247522962674e-01,5.316453866258786576e+00,1.711817097292944734e-01,8.242044748174131019e-01,6.839316092015533532e-02,-1.000000006778101191e+00,0.000000000000000000e+00 +5.749249916770497038e+01,3.518315067972687302e+02,5.828804938100735633e-01,5.318004156161701523e+00,1.714317097292944736e-01,8.223235217762804306e-01,6.839316092015533532e-02,-1.000000006767050920e+00,0.000000000000000000e+00 +5.749437957240311192e+01,3.518413602126372552e+02,5.845864262749776996e-01,5.319550457175444613e+00,1.716817097292944738e-01,8.204431170654108429e-01,6.839316092015533532e-02,-1.000000006927228346e+00,0.000000000000000000e+00 +5.749625943050023835e+01,3.518512132012147617e+02,5.862948220403878530e-01,5.321092773812292620e+00,1.719317097292944740e-01,8.185632589552610527e-01,6.839316092015533532e-02,-1.000000006644517603e+00,0.000000000000000000e+00 +5.749813874372124189e+01,3.518610657623854650e+02,5.880056809995294342e-01,5.322631110567073165e+00,1.721817097292944743e-01,8.166839457217726084e-01,6.839316092015533532e-02,-1.000000007206108599e+00,0.000000000000000000e+00 +5.750001751378669468e+01,3.518709178955335233e+02,5.897190030454736442e-01,5.324165471917233994e+00,1.724317097292944745e-01,8.148051756427776571e-01,6.839316092015533532e-02,-1.000000006771613492e+00,0.000000000000000000e+00 +5.750189574241289847e+01,3.518807696000432088e+02,5.914347880711379180e-01,5.325695862322905150e+00,1.726817097292944747e-01,8.129269470038553713e-01,6.839316092015533532e-02,-1.000000006914341766e+00,0.000000000000000000e+00 +5.750377343131187047e+01,3.518906208752987368e+02,5.931530359692857024e-01,5.327222286226971804e+00,1.729317097292944749e-01,8.110492580918975403e-01,6.839316092015533532e-02,-1.000000007086895071e+00,0.000000000000000000e+00 +5.750565058219139303e+01,3.519004717206844361e+02,5.948737466325264567e-01,5.328744748055134650e+00,1.731817097292944752e-01,8.091721071990723990e-01,6.839316092015533532e-02,-1.000000006884693482e+00,0.000000000000000000e+00 +5.750752719675501368e+01,3.519103221355846358e+02,5.965969199533157630e-01,5.330263252215977410e+00,1.734317097292944754e-01,8.072954926225350825e-01,6.839316092015533532e-02,-1.000000007057887164e+00,0.000000000000000000e+00 +5.750940327670206642e+01,3.519201721193837216e+02,5.983225558239553266e-01,5.331777803101033442e+00,1.736817097292944756e-01,8.054194126622401528e-01,6.839316092015533532e-02,-1.000000007241699018e+00,0.000000000000000000e+00 +5.751127882372770728e+01,3.519300216714660223e+02,6.000506541365928648e-01,5.333288405084847916e+00,1.739317097292944758e-01,8.035438656230141641e-01,6.839316092015533532e-02,-1.000000006965099608e+00,0.000000000000000000e+00 +5.751315383952292848e+01,3.519398707912159239e+02,6.017812147832222180e-01,5.334795062525043541e+00,1.741817097292944760e-01,8.016688498147340747e-01,6.839316092015533532e-02,-1.000000006914704143e+00,0.000000000000000000e+00 +5.751502832577456559e+01,3.519497194780179257e+02,6.035142376556834609e-01,5.336297779762386284e+00,1.744317097292944763e-01,7.997943635501363335e-01,6.839316092015533532e-02,-1.000000007168894367e+00,0.000000000000000000e+00 +5.751690228416532591e+01,3.519595677312564135e+02,6.052497226456625690e-01,5.337796561120846661e+00,1.746817097292944765e-01,7.979204051459383162e-01,6.839316092015533532e-02,-1.000000007196182095e+00,0.000000000000000000e+00 +5.751877571637382403e+01,3.519694155503158868e+02,6.069876696446917519e-01,5.339291410907662794e+00,1.749317097292944767e-01,7.960469729239613157e-01,6.839316092015533532e-02,-1.000000007120410261e+00,0.000000000000000000e+00 +5.752064862407456758e+01,3.519792629345809019e+02,6.087280785441493425e-01,5.340782333413405247e+00,1.751817097292944769e-01,7.941740652098824294e-01,6.839316092015533532e-02,-1.000000006962935117e+00,0.000000000000000000e+00 +5.752252100893800701e+01,3.519891098834359582e+02,6.104709492352596856e-01,5.342269332912039204e+00,1.754317097292944772e-01,7.923016803334071989e-01,6.839316092015533532e-02,-1.000000007404386659e+00,0.000000000000000000e+00 +5.752439287263053558e+01,3.519989563962656121e+02,6.122162816090934712e-01,5.343752413660986633e+00,1.756817097292944774e-01,7.904298166270161685e-01,6.839316092015533532e-02,-1.000000007249739475e+00,0.000000000000000000e+00 +5.752626421681452484e+01,3.520088024724544766e+02,6.139640755565674013e-01,5.345231579901185803e+00,1.759317097292944776e-01,7.885584724294569803e-01,6.839316092015533532e-02,-1.000000006976907718e+00,0.000000000000000000e+00 +5.752813504314833892e+01,3.520186481113871650e+02,6.157143309684443011e-01,5.346706835857157003e+00,1.761817097292944778e-01,7.866876460825928952e-01,6.839316092015533532e-02,-1.000000007473021313e+00,0.000000000000000000e+00 +5.753000535328633447e+01,3.520284933124483473e+02,6.174670477353333409e-01,5.348178185737062051e+00,1.764317097292944780e-01,7.848173359306193086e-01,6.839316092015533532e-02,-1.000000006986754730e+00,0.000000000000000000e+00 +5.753187514887891041e+01,3.520383380750226934e+02,6.192222257476895919e-01,5.349645633732762029e+00,1.766817097292944783e-01,7.829475403249799292e-01,6.839316092015533532e-02,-1.000000007477248154e+00,0.000000000000000000e+00 +5.753374443157250795e+01,3.520481823984948733e+02,6.209798648958144707e-01,5.351109184019883891e+00,1.769317097292944785e-01,7.810782576174083447e-01,6.839316092015533532e-02,-1.000000007248524891e+00,0.000000000000000000e+00 +5.753561320300962478e+01,3.520580262822496138e+02,6.227399650698555167e-01,5.352568840757873758e+00,1.771817097292944787e-01,7.792094861667437922e-01,6.839316092015533532e-02,-1.000000007302585647e+00,0.000000000000000000e+00 +5.753748146482885772e+01,3.520678697256716987e+02,6.245025261598065036e-01,5.354024608090062642e+00,1.774317097292944789e-01,7.773412243338684302e-01,6.839316092015533532e-02,-1.000000007273178948e+00,0.000000000000000000e+00 +5.753934921866489560e+01,3.520777127281459116e+02,6.262675480555073282e-01,5.355476490143722401e+00,1.776817097292944791e-01,7.754734704842463078e-01,6.839316092015533532e-02,-1.000000007461186557e+00,0.000000000000000000e+00 +5.754121646614855479e+01,3.520875552890570930e+02,6.280350306466441213e-01,5.356924491030126134e+00,1.779317097292944794e-01,7.736062229866583762e-01,6.839316092015533532e-02,-1.000000007052018969e+00,0.000000000000000000e+00 +5.754308320890677919e+01,3.520973974077900266e+02,6.298049738227492478e-01,5.358368614844605915e+00,1.781817097292944796e-01,7.717394802152669486e-01,6.839316092015533532e-02,-1.000000007684502590e+00,0.000000000000000000e+00 +5.754494944856269001e+01,3.521072390837296098e+02,6.315773774732013068e-01,5.359808865666614075e+00,1.784317097292944798e-01,7.698732405450170457e-01,6.839316092015533532e-02,-1.000000007078361897e+00,0.000000000000000000e+00 +5.754681518673556440e+01,3.521170803162607399e+02,6.333522414872250206e-01,5.361245247559775606e+00,1.786817097292944800e-01,7.680075023589334471e-01,6.839316092015533532e-02,-1.000000007704599403e+00,0.000000000000000000e+00 +5.754868042504089232e+01,3.521269211047683143e+02,6.351295657538913453e-01,5.362677764571953887e+00,1.789317097292944803e-01,7.661422640392356875e-01,6.839316092015533532e-02,-1.000000007092808785e+00,0.000000000000000000e+00 +5.755054516509036233e+01,3.521367614486373441e+02,6.369093501621175824e-01,5.364106420735299530e+00,1.791817097292944805e-01,7.642775239765393636e-01,6.839316092015533532e-02,-1.000000007784709766e+00,0.000000000000000000e+00 +5.755240940849189712e+01,3.521466013472527266e+02,6.386915946006671563e-01,5.365531220066316109e+00,1.794317097292944807e-01,7.624132805604894036e-01,6.839316092015533532e-02,-1.000000007121216727e+00,0.000000000000000000e+00 +5.755427315684967482e+01,3.521564407999995296e+02,6.404762989581498367e-01,5.366952166565908122e+00,1.796817097292944809e-01,7.605495321894402139e-01,6.839316092015533532e-02,-1.000000007461577800e+00,0.000000000000000000e+00 +5.755613641176412898e+01,3.521662798062627644e+02,6.422634631230216273e-01,5.368369264219446713e+00,1.799317097292944811e-01,7.586862772610821759e-01,6.839316092015533532e-02,-1.000000007495019938e+00,0.000000000000000000e+00 +5.755799917483198413e+01,3.521761183654274987e+02,6.440530869835846550e-01,5.369782516996817634e+00,1.801817097292944814e-01,7.568235141792649667e-01,6.839316092015533532e-02,-1.000000007609722630e+00,0.000000000000000000e+00 +5.755986144764626289e+01,3.521859564768788005e+02,6.458451704279875027e-01,5.371191928852481645e+00,1.804317097292944816e-01,7.549612413508134390e-01,6.839316092015533532e-02,-1.000000007334618024e+00,0.000000000000000000e+00 +5.756172323179630723e+01,3.521957941400017944e+02,6.476397133442249876e-01,5.372597503725528689e+00,1.806817097292944818e-01,7.530994571871105769e-01,6.839316092015533532e-02,-1.000000007646322242e+00,0.000000000000000000e+00 +5.756358452886779986e+01,3.522056313541816621e+02,6.494367156201381608e-01,5.373999245539734737e+00,1.809317097292944820e-01,7.512381601013845556e-01,6.839316092015533532e-02,-1.000000007381668166e+00,0.000000000000000000e+00 +5.756544534044277128e+01,3.522154681188035283e+02,6.512361771434143076e-01,5.375397158203613301e+00,1.811817097292944823e-01,7.493773485126750122e-01,6.839316092015533532e-02,-1.000000007595575058e+00,0.000000000000000000e+00 +5.756730566809962824e+01,3.522253044332526315e+02,6.530380978015871696e-01,5.376791245610474057e+00,1.814317097292944825e-01,7.475170208416871409e-01,6.839316092015533532e-02,-1.000000007459278972e+00,0.000000000000000000e+00 +5.756916551341316080e+01,3.522351402969142100e+02,6.548424774820366112e-01,5.378181511638473467e+00,1.816817097292944827e-01,7.456571755142799018e-01,6.839316092015533532e-02,-1.000000007595531537e+00,0.000000000000000000e+00 +5.757102487795457080e+01,3.522449757091735023e+02,6.566493160719890643e-01,5.379567960150671624e+00,1.819317097292944829e-01,7.437978109587484177e-01,6.839316092015533532e-02,-1.000000007512520384e+00,0.000000000000000000e+00 +5.757288376329147184e+01,3.522548106694158037e+02,6.584586134585169725e-01,5.380950594995083769e+00,1.821817097292944831e-01,7.419389256078799955e-01,6.839316092015533532e-02,-1.000000007659222812e+00,0.000000000000000000e+00 +5.757474217098793190e+01,3.522646451770264093e+02,6.602703695285392360e-01,5.382329420004735354e+00,1.824317097292944834e-01,7.400805178971878728e-01,6.839316092015533532e-02,-1.000000007626755449e+00,0.000000000000000000e+00 +5.757660010260445915e+01,3.522744792313906714e+02,6.620845841688212108e-01,5.383704438997713559e+00,1.826817097292944836e-01,7.382225862664890670e-01,6.839316092015533532e-02,-1.000000007434370231e+00,0.000000000000000000e+00 +5.757845755969804458e+01,3.522843128318939421e+02,6.639012572659743761e-01,5.385075655777221471e+00,1.829317097292944838e-01,7.363651291590915804e-01,6.839316092015533532e-02,-1.000000007530584600e+00,0.000000000000000000e+00 +5.758031454382216907e+01,3.522941459779216302e+02,6.657203887064567782e-01,5.386443074131630482e+00,1.831817097292944840e-01,7.345081450209806073e-01,6.839316092015533532e-02,-1.000000007764528576e+00,0.000000000000000000e+00 +5.758217105652681767e+01,3.523039786688592017e+02,6.675419783765725867e-01,5.387806697834530922e+00,1.834317097292944843e-01,7.326516323019155452e-01,6.839316092015533532e-02,-1.000000007642494637e+00,0.000000000000000000e+00 +5.758402709935850083e+01,3.523138109040920654e+02,6.693660261624725383e-01,5.389166530644784459e+00,1.836817097292944845e-01,7.307955894560494992e-01,6.839316092015533532e-02,-1.000000007617166009e+00,0.000000000000000000e+00 +5.758588267386026160e+01,3.523236426830057439e+02,6.711925319501536036e-01,5.390522576306577385e+00,1.839317097292944847e-01,7.289400149401558116e-01,6.839316092015533532e-02,-1.000000007542351632e+00,0.000000000000000000e+00 +5.758773778157170398e+01,3.523334740049857601e+02,6.730214956254592096e-01,5.391874838549470361e+00,1.841817097292944849e-01,7.270849072147235193e-01,6.839316092015533532e-02,-1.000000007705010852e+00,0.000000000000000000e+00 +5.758959242402900003e+01,3.523433048694176364e+02,6.748529170740791283e-01,5.393223321088449929e+00,1.844317097292944851e-01,7.252302647431374538e-01,6.839316092015533532e-02,-1.000000007792784418e+00,0.000000000000000000e+00 +5.759144660276491123e+01,3.523531352756868955e+02,6.766867961815494770e-01,5.394568027623978246e+00,1.846817097292944854e-01,7.233760859927738096e-01,6.839316092015533532e-02,-1.000000007410632552e+00,0.000000000000000000e+00 +5.759330031930880978e+01,3.523629652231792306e+02,6.785231328332528289e-01,5.395908961842044604e+00,1.849317097292944856e-01,7.215223694351367012e-01,6.839316092015533532e-02,-1.000000007890914366e+00,0.000000000000000000e+00 +5.759515357518668566e+01,3.523727947112802212e+02,6.803619269144181025e-01,5.397246127414216943e+00,1.851817097292944858e-01,7.196691135426400709e-01,6.839316092015533532e-02,-1.000000007641413724e+00,0.000000000000000000e+00 +5.759700637192115380e+01,3.523826237393755036e+02,6.822031783101206726e-01,5.398579527997687144e+00,1.854317097292944860e-01,7.178163167940128098e-01,6.839316092015533532e-02,-1.000000007574020744e+00,0.000000000000000000e+00 +5.759885871103149668e+01,3.523924523068507710e+02,6.840468869052823697e-01,5.399909167235326102e+00,1.856817097292944863e-01,7.159639776696414826e-01,6.839316092015533532e-02,-1.000000008004385599e+00,0.000000000000000000e+00 +5.760071059403365723e+01,3.524022804130917734e+02,6.858930525846714810e-01,5.401235048755729906e+00,1.859317097292944865e-01,7.141120946526603452e-01,6.839316092015533532e-02,-1.000000007354639342e+00,0.000000000000000000e+00 +5.760256202244026014e+01,3.524121080574842040e+02,6.877416752329025273e-01,5.402557176173267806e+00,1.861817097292944867e-01,7.122606662324418858e-01,6.839316092015533532e-02,-1.000000007852795525e+00,0.000000000000000000e+00 +5.760441299776063317e+01,3.524219352394138696e+02,6.895927547344365971e-01,5.403875553088136385e+00,1.864317097292944869e-01,7.104096908975336966e-01,6.839316092015533532e-02,-1.000000007761845833e+00,0.000000000000000000e+00 +5.760626352150082141e+01,3.524317619582665770e+02,6.914462909735813456e-01,5.405190183086400424e+00,1.866817097292944871e-01,7.085591671429842808e-01,6.839316092015533532e-02,-1.000000007857203110e+00,0.000000000000000000e+00 +5.760811359516359431e+01,3.524415882134281333e+02,6.933022838344906624e-01,5.406501069740047072e+00,1.869317097292944874e-01,7.067090934656762302e-01,6.839316092015533532e-02,-1.000000007539633140e+00,0.000000000000000000e+00 +5.760996322024846705e+01,3.524514140042844019e+02,6.951607332011650042e-01,5.407808216607031149e+00,1.871817097292944876e-01,7.048594683668547578e-01,6.839316092015533532e-02,-1.000000007949094716e+00,0.000000000000000000e+00 +5.761181239825172895e+01,3.524612393302213036e+02,6.970216389574512839e-01,5.409111627231324881e+00,1.874317097292944878e-01,7.030102903488951727e-01,6.839316092015533532e-02,-1.000000007811441050e+00,0.000000000000000000e+00 +5.761366113066642924e+01,3.524710641906247020e+02,6.988850009870428703e-01,5.410411305142961425e+00,1.876817097292944880e-01,7.011615579197526538e-01,6.839316092015533532e-02,-1.000000007592766860e+00,0.000000000000000000e+00 +5.761550941898241973e+01,3.524808885848805744e+02,7.007508191734796998e-01,5.411707253858086375e+00,1.879317097292944883e-01,6.993132695897282813e-01,6.839316092015533532e-02,-1.000000007683943704e+00,0.000000000000000000e+00 +5.761735726468635477e+01,3.524907125123748983e+02,7.026190934001480537e-01,5.412999476879003069e+00,1.881817097292944885e-01,6.974654238715937149e-01,6.839316092015533532e-02,-1.000000008140045749e+00,0.000000000000000000e+00 +5.761920466926171258e+01,3.525005359724937080e+02,7.044898235502808914e-01,5.414287977694217879e+00,1.884317097292944887e-01,6.956180192811971530e-01,6.839316092015533532e-02,-1.000000007638267796e+00,0.000000000000000000e+00 +5.762105163418880949e+01,3.525103589646229807e+02,7.063630095069575177e-01,5.415572759778486400e+00,1.886817097292944889e-01,6.937710543399933094e-01,6.839316092015533532e-02,-1.000000007643887967e+00,0.000000000000000000e+00 +5.762289816094480699e+01,3.525201814881488076e+02,7.082386511531038042e-01,5.416853826592864074e+00,1.889317097292944891e-01,6.919245275698778785e-01,6.839316092015533532e-02,-1.000000007985989203e+00,0.000000000000000000e+00 +5.762474425100374731e+01,3.525300035424572798e+02,7.101167483714921902e-01,5.418131181584747047e+00,1.891817097292944894e-01,6.900784374961957957e-01,6.839316092015533532e-02,-1.000000007636948629e+00,0.000000000000000000e+00 +5.762658990583653917e+01,3.525398251269344883e+02,7.119973010447415707e-01,5.419404828187918355e+00,1.894317097292944896e-01,6.882327826493073175e-01,6.839316092015533532e-02,-1.000000008101182614e+00,0.000000000000000000e+00 +5.762843512691100045e+01,3.525496462409666378e+02,7.138803090553174080e-01,5.420674769822596772e+00,1.896817097292944898e-01,6.863875615598993285e-01,6.839316092015533532e-02,-1.000000007681112191e+00,0.000000000000000000e+00 +5.763027991569185104e+01,3.525594668839398764e+02,7.157657722855316207e-01,5.421941009895476782e+00,1.899317097292944900e-01,6.845427727648802918e-01,6.839316092015533532e-02,-1.000000007735116769e+00,0.000000000000000000e+00 +5.763212427364074131e+01,3.525692870552404088e+02,7.176536906175429165e-01,5.423203551799779198e+00,1.901817097292944903e-01,6.826984148017264387e-01,6.839316092015533532e-02,-1.000000007984790162e+00,0.000000000000000000e+00 +5.763396820221625916e+01,3.525791067542544965e+02,7.195440639333562372e-01,5.424462398915291139e+00,1.904317097292944905e-01,6.808544862114876972e-01,6.839316092015533532e-02,-1.000000007816427061e+00,0.000000000000000000e+00 +5.763581170287394428e+01,3.525889259803684013e+02,7.214368921148234248e-01,5.425717554608411319e+00,1.906817097292944907e-01,6.790109855393908767e-01,6.839316092015533532e-02,-1.000000007851125972e+00,0.000000000000000000e+00 +5.763765477706631657e+01,3.525987447329683846e+02,7.233321750436425557e-01,5.426969022232196238e+00,1.909317097292944909e-01,6.771679113325483890e-01,6.839316092015533532e-02,-1.000000007854144002e+00,0.000000000000000000e+00 +5.763949742624286898e+01,3.526085630114408218e+02,7.252299126013584951e-01,5.428216805126401923e+00,1.911817097292944911e-01,6.753252621415219981e-01,6.839316092015533532e-02,-1.000000007780932787e+00,0.000000000000000000e+00 +5.764133965185009600e+01,3.526183808151720314e+02,7.271301046693626757e-01,5.429460906617528337e+00,1.914317097292944914e-01,6.734830365199577784e-01,6.839316092015533532e-02,-1.000000008039608312e+00,0.000000000000000000e+00 +5.764318145533150783e+01,3.526281981435484454e+02,7.290327511288930973e-01,5.430701330018862905e+00,1.916817097292944916e-01,6.716412330237381267e-01,6.839316092015533532e-02,-1.000000007920331058e+00,0.000000000000000000e+00 +5.764502283812763750e+01,3.526380149959564392e+02,7.309378518610344377e-01,5.431938078630522249e+00,1.919317097292944918e-01,6.697998502130269038e-01,6.839316092015533532e-02,-1.000000007690323045e+00,0.000000000000000000e+00 +5.764686380167604796e+01,3.526478313717825017e+02,7.328454067467177202e-01,5.433171155739497493e+00,1.921817097292944920e-01,6.679588866504554412e-01,6.839316092015533532e-02,-1.000000008071860957e+00,0.000000000000000000e+00 +5.764870434741137473e+01,3.526576472704130651e+02,7.347554156667208680e-01,5.434400564619696006e+00,1.924317097292944923e-01,6.661183409002714439e-01,6.839316092015533532e-02,-1.000000007882797748e+00,0.000000000000000000e+00 +5.765054447676531169e+01,3.526674626912346753e+02,7.366678785016683717e-01,5.435626308531981365e+00,1.926817097292944925e-01,6.642782115318306424e-01,6.839316092015533532e-02,-1.000000007706716376e+00,0.000000000000000000e+00 +5.765238419116663238e+01,3.526772776336338211e+02,7.385827951320312890e-01,5.436848390724219549e+00,1.929317097292944927e-01,6.624384971163325142e-01,6.839316092015533532e-02,-1.000000008059616752e+00,0.000000000000000000e+00 +5.765422349204121133e+01,3.526870920969971053e+02,7.405001654381272447e-01,5.438066814431318896e+00,1.931817097292944929e-01,6.605991962269317508e-01,6.839316092015533532e-02,-1.000000008076901814e+00,0.000000000000000000e+00 +5.765606238081202406e+01,3.526969060807111305e+02,7.424199893001206529e-01,5.439281582875270082e+00,1.934317097292944931e-01,6.587603074412641257e-01,6.839316092015533532e-02,-1.000000007612588115e+00,0.000000000000000000e+00 +5.765790085889918259e+01,3.527067195841624994e+02,7.443422665980224950e-01,5.440492699265190524e+00,1.936817097292944934e-01,6.569218293401102304e-01,6.839316092015533532e-02,-1.000000008030078158e+00,0.000000000000000000e+00 +5.765973892771992837e+01,3.527165326067378714e+02,7.462669972116904304e-01,5.441700166797366123e+00,1.939317097292944936e-01,6.550837605046072598e-01,6.839316092015533532e-02,-1.000000007998201212e+00,0.000000000000000000e+00 +5.766157658868864644e+01,3.527263451478239631e+02,7.481941810208289079e-01,5.442903988655287684e+00,1.941817097292944938e-01,6.532460995211893939e-01,6.839316092015533532e-02,-1.000000007958140813e+00,0.000000000000000000e+00 +5.766341384321690100e+01,3.527361572068074338e+02,7.501238179049888322e-01,5.444104168009696210e+00,1.944317097292944940e-01,6.514088449783158596e-01,6.839316092015533532e-02,-1.000000008022122078e+00,0.000000000000000000e+00 +5.766525069271342119e+01,3.527459687830750568e+02,7.520559077435678974e-01,5.445300708018621982e+00,1.946817097292944942e-01,6.495719954670624574e-01,6.839316092015533532e-02,-1.000000007709496819e+00,0.000000000000000000e+00 +5.766708713858412949e+01,3.527557798760136052e+02,7.539904504158104759e-01,5.446493611827424530e+00,1.949317097292944945e-01,6.477355495821971454e-01,6.839316092015533532e-02,-1.000000008053986811e+00,0.000000000000000000e+00 +5.766892318223215597e+01,3.527655904850099091e+02,7.559274458008077291e-01,5.447682882568834373e+00,1.951817097292944947e-01,6.458995059193854971e-01,6.839316092015533532e-02,-1.000000007917035028e+00,0.000000000000000000e+00 +5.767075882505784534e+01,3.527754006094507986e+02,7.578668937774973857e-01,5.448868523362989436e+00,1.954317097292944949e-01,6.440638630791666319e-01,6.839316092015533532e-02,-1.000000007938302460e+00,0.000000000000000000e+00 +5.767259406845877123e+01,3.527852102487231036e+02,7.598087942246639637e-01,5.450050537317478572e+00,1.956817097292944951e-01,6.422286196636747269e-01,6.839316092015533532e-02,-1.000000008166705534e+00,0.000000000000000000e+00 +5.767442891382975034e+01,3.527950194022137680e+02,7.617531470209386590e-01,5.451228927527378865e+00,1.959317097292944954e-01,6.403937742777108255e-01,6.839316092015533532e-02,-1.000000007794600299e+00,0.000000000000000000e+00 +5.767626336256286379e+01,3.528048280693097354e+02,7.636999520447994572e-01,5.452403697075294708e+00,1.961817097292944956e-01,6.385593255303011473e-01,6.839316092015533532e-02,-1.000000008061365575e+00,0.000000000000000000e+00 +5.767809741604745000e+01,3.528146362493978927e+02,7.656492091745711326e-01,5.453574849031399552e+00,1.964317097292944958e-01,6.367252720309284353e-01,6.839316092015533532e-02,-1.000000008031286525e+00,0.000000000000000000e+00 +5.767993107567014022e+01,3.528244439418652973e+02,7.676009182884250270e-01,5.454742386453470537e+00,1.966817097292944960e-01,6.348916123935093303e-01,6.839316092015533532e-02,-1.000000007760584175e+00,0.000000000000000000e+00 +5.768176434281485854e+01,3.528342511460989499e+02,7.695550792643792715e-01,5.455906312386930246e+00,1.969317097292944962e-01,6.330583452345615036e-01,6.839316092015533532e-02,-1.000000008300389931e+00,0.000000000000000000e+00 +5.768359721886283609e+01,3.528440578614858509e+02,7.715116919802988971e-01,5.457066629864884888e+00,1.971817097292944965e-01,6.312254691713673482e-01,6.839316092015533532e-02,-1.000000007730870166e+00,0.000000000000000000e+00 +5.768542970519263235e+01,3.528538640874131147e+02,7.734707563138955022e-01,5.458223341908158943e+00,1.974317097292944967e-01,6.293929828274070770e-01,6.839316092015533532e-02,-1.000000008035600185e+00,0.000000000000000000e+00 +5.768726180318012808e+01,3.528636698232678555e+02,7.754322721427276965e-01,5.459376451525339569e+00,1.976817097292944969e-01,6.275608848251915672e-01,6.839316092015533532e-02,-1.000000007963120607e+00,0.000000000000000000e+00 +5.768909351419855369e+01,3.528734750684372443e+02,7.773962393442006569e-01,5.460525961712807685e+00,1.979317097292944971e-01,6.257291737921784058e-01,6.839316092015533532e-02,-1.000000008051460387e+00,0.000000000000000000e+00 +5.769092483961851059e+01,3.528832798223083955e+02,7.793626577955664603e-01,5.461671875454779723e+00,1.981817097292944974e-01,6.238978483574801892e-01,6.839316092015533532e-02,-1.000000008248181915e+00,0.000000000000000000e+00 +5.769275578080795697e+01,3.528930840842685370e+02,7.813315273739238620e-01,5.462814195723343147e+00,1.984317097292944976e-01,6.220669071529338900e-01,6.839316092015533532e-02,-1.000000007644326949e+00,0.000000000000000000e+00 +5.769458633913224332e+01,3.529028878537048968e+02,7.833028479562186286e-01,5.463952925478493761e+00,1.986817097292944978e-01,6.202363488146561687e-01,6.839316092015533532e-02,-1.000000008185648159e+00,0.000000000000000000e+00 +5.769641651595411247e+01,3.529126911300047595e+02,7.852766194192432048e-01,5.465088067668175675e+00,1.989317097292944980e-01,6.184061719778048971e-01,6.839316092015533532e-02,-1.000000008046418198e+00,0.000000000000000000e+00 +5.769824631263372083e+01,3.529224939125554101e+02,7.872528416396368245e-01,5.466219625228311507e+00,1.991817097292944982e-01,6.165763752834707567e-01,6.839316092015533532e-02,-1.000000007991386886e+00,0.000000000000000000e+00 +5.770007573052864558e+01,3.529322962007441902e+02,7.892315144938856220e-01,5.467347601082845010e+00,1.994317097292944985e-01,6.147469573739230420e-01,6.839316092015533532e-02,-1.000000007930327062e+00,0.000000000000000000e+00 +5.770190477099389881e+01,3.529420979939584413e+02,7.912126378583226316e-01,5.468471998143774826e+00,1.996817097292944987e-01,6.129179168941623068e-01,6.839316092015533532e-02,-1.000000008244529281e+00,0.000000000000000000e+00 +5.770373343538194177e+01,3.529518992915855620e+02,7.931962116091275661e-01,5.469592819311190901e+00,1.999317097292944989e-01,6.110892524910457313e-01,6.839316092015533532e-02,-1.000000007927561496e+00,0.000000000000000000e+00 +5.770556172504267778e+01,3.529617000930129507e+02,7.951822356223270383e-01,5.470710067473309124e+00,2.001817097292944991e-01,6.092609628158126567e-01,6.839316092015533532e-02,-1.000000007773119926e+00,0.000000000000000000e+00 +5.770738964132350191e+01,3.529715003976280627e+02,7.971707097737945613e-01,5.471823745506510406e+00,2.004317097292944994e-01,6.074330465207804508e-01,6.839316092015533532e-02,-1.000000008252126538e+00,0.000000000000000000e+00 +5.770921718556927971e+01,3.529813002048183534e+02,7.991616339392505486e-01,5.472933856275373543e+00,2.006817097292944996e-01,6.056055022599234894e-01,6.839316092015533532e-02,-1.000000008180766953e+00,0.000000000000000000e+00 +5.771104435912236852e+01,3.529910995139713918e+02,8.011550079942622027e-01,5.474040402632708968e+00,2.009317097292944998e-01,6.037783286918853021e-01,6.839316092015533532e-02,-1.000000007912519973e+00,0.000000000000000000e+00 +5.771287116332264588e+01,3.530008983244746901e+02,8.031508318142437375e-01,5.475143387419597829e+00,2.011817097292945000e-01,6.019515244771564966e-01,6.839316092015533532e-02,-1.000000008009495733e+00,0.000000000000000000e+00 +5.771469759950748823e+01,3.530106966357158171e+02,8.051491052744560450e-01,5.476242813465425741e+00,2.014317097292945002e-01,6.001250882776822948e-01,6.839316092015533532e-02,-1.000000008178453026e+00,0.000000000000000000e+00 +5.771652366901182063e+01,3.530204944470823989e+02,8.071498282500070287e-01,5.477338683587915646e+00,2.016817097292945005e-01,5.982990187584134034e-01,6.839316092015533532e-02,-1.000000008068046675e+00,0.000000000000000000e+00 +5.771834937316810255e+01,3.530302917579620612e+02,8.091530006158516031e-01,5.478431000593163347e+00,2.019317097292945007e-01,5.964733145873998277e-01,6.839316092015533532e-02,-1.000000007802639646e+00,0.000000000000000000e+00 +5.772017471330634919e+01,3.530400885677424867e+02,8.111586222467914720e-01,5.479519767275673026e+00,2.021817097292945009e-01,5.946479744349102425e-01,6.839316092015533532e-02,-1.000000008250176542e+00,0.000000000000000000e+00 +5.772199969075413861e+01,3.530498848758113581e+02,8.131666930174752395e-01,5.480604986418391000e+00,2.024317097292945011e-01,5.928229969720634207e-01,6.839316092015533532e-02,-1.000000008089210635e+00,0.000000000000000000e+00 +5.772382430683663301e+01,3.530596806815564150e+02,8.151772128023985209e-01,5.481686660792736809e+00,2.026817097292945014e-01,5.909983808748126011e-01,6.839316092015533532e-02,-1.000000008075165869e+00,0.000000000000000000e+00 +5.772564856287657165e+01,3.530694759843653969e+02,8.171901814759037208e-01,5.482764793158641403e+00,2.029317097292945016e-01,5.891741248201431969e-01,6.839316092015533532e-02,-1.000000007840850413e+00,0.000000000000000000e+00 +5.772747246019430634e+01,3.530792707836261002e+02,8.192055989121804771e-01,5.483839386264578231e+00,2.031817097292945018e-01,5.873502274881098328e-01,6.839316092015533532e-02,-1.000000008298362220e+00,0.000000000000000000e+00 +5.772929600010779438e+01,3.530890650787263780e+02,8.212234649852651058e-01,5.484910442847597878e+00,2.034317097292945020e-01,5.855266875594914433e-01,6.839316092015533532e-02,-1.000000007901186372e+00,0.000000000000000000e+00 +5.773111918393261988e+01,3.530988588690540837e+02,8.232437795690409343e-01,5.485977965633358266e+00,2.036817097292945022e-01,5.837035037202635834e-01,6.839316092015533532e-02,-1.000000008253025374e+00,0.000000000000000000e+00 +5.773294201298199368e+01,3.531086521539970704e+02,8.252665425372383012e-01,5.487041957336162845e+00,2.039317097292945025e-01,5.818806746558424781e-01,6.839316092015533532e-02,-1.000000007963614657e+00,0.000000000000000000e+00 +5.773476448856678900e+01,3.531184449329433050e+02,8.272917537634345564e-01,5.488102420658988123e+00,2.041817097292945027e-01,5.800581990565323309e-01,6.839316092015533532e-02,-1.000000007993868456e+00,0.000000000000000000e+00 +5.773658661199552711e+01,3.531282372052806977e+02,8.293194131210540609e-01,5.489159358293520974e+00,2.044317097292945029e-01,5.782360756132278734e-01,6.839316092015533532e-02,-1.000000008449161593e+00,0.000000000000000000e+00 +5.773840838457439872e+01,3.531380289703972153e+02,8.313495204833680763e-01,5.490212772920187945e+00,2.046817097292945031e-01,5.764143030189630146e-01,6.839316092015533532e-02,-1.000000007774487942e+00,0.000000000000000000e+00 +5.774022980760727819e+01,3.531478202276809384e+02,8.333820757234948751e-01,5.491262667208187231e+00,2.049317097292945034e-01,5.745928799719239866e-01,6.839316092015533532e-02,-1.000000008108452132e+00,0.000000000000000000e+00 +5.774205088239572348e+01,3.531576109765198908e+02,8.354170787143997412e-01,5.492309043815525982e+00,2.051817097292945036e-01,5.727718051687096246e-01,6.839316092015533532e-02,-1.000000008056614265e+00,0.000000000000000000e+00 +5.774387161023901172e+01,3.531674012163020961e+02,8.374545293288949699e-01,5.493351905389045164e+00,2.054317097292945038e-01,5.709510773107558945e-01,6.839316092015533532e-02,-1.000000008045186961e+00,0.000000000000000000e+00 +5.774569199243411077e+01,3.531771909464157488e+02,8.394944274396399786e-01,5.494391254564455984e+00,2.056817097292945040e-01,5.691306951010085546e-01,6.839316092015533532e-02,-1.000000008180231159e+00,0.000000000000000000e+00 +5.774751203027573609e+01,3.531869801662489294e+02,8.415367729191410850e-01,5.495427093966370080e+00,2.059317097292945042e-01,5.673106572444953644e-01,6.839316092015533532e-02,-1.000000008246946903e+00,0.000000000000000000e+00 +5.774933172505632228e+01,3.531967688751898322e+02,8.435815656397516182e-01,5.496459426208330612e+00,2.061817097292945045e-01,5.654909624488990705e-01,6.839316092015533532e-02,-1.000000007977776439e+00,0.000000000000000000e+00 +5.775115107806606574e+01,3.532065570726266515e+02,8.456288054736721405e-01,5.497488253892844234e+00,2.064317097292945047e-01,5.636716094246421171e-01,6.839316092015533532e-02,-1.000000008126401996e+00,0.000000000000000000e+00 +5.775297009059291042e+01,3.532163447579476383e+02,8.476784922929501143e-01,5.498513579611413071e+00,2.066817097292945049e-01,5.618525968830176964e-01,6.839316092015533532e-02,-1.000000008053266720e+00,0.000000000000000000e+00 +5.775478876392256922e+01,3.532261319305410439e+02,8.497306259694802355e-01,5.499535405944563138e+00,2.069317097292945051e-01,5.600339235387137293e-01,6.839316092015533532e-02,-1.000000007871858498e+00,0.000000000000000000e+00 +5.775660709933853809e+01,3.532359185897952329e+02,8.517852063750039893e-01,5.500553735461877203e+00,2.071817097292945054e-01,5.582155881084318594e-01,6.839316092015533532e-02,-1.000000008450904421e+00,0.000000000000000000e+00 +5.775842509812210324e+01,3.532457047350984567e+02,8.538422333811102050e-01,5.501568570722024987e+00,2.074317097292945056e-01,5.563975893095037817e-01,6.839316092015533532e-02,-1.000000007920841760e+00,0.000000000000000000e+00 +5.776024276155234816e+01,3.532554903658391368e+02,8.559017068592346122e-01,5.502579914272790695e+00,2.076817097292945058e-01,5.545799258648589358e-01,6.839316092015533532e-02,-1.000000008123558048e+00,0.000000000000000000e+00 +5.776206009090617499e+01,3.532652754814056379e+02,8.579636266806601741e-01,5.503587768651109435e+00,2.079317097292945060e-01,5.527625964962663563e-01,6.839316092015533532e-02,-1.000000008162407639e+00,0.000000000000000000e+00 +5.776387708745830452e+01,3.532750600811864388e+02,8.600279927165168647e-01,5.504592136383091194e+00,2.081817097292945062e-01,5.509455999293023654e-01,6.839316092015533532e-02,-1.000000008166192389e+00,0.000000000000000000e+00 +5.776569375248129745e+01,3.532848441645699609e+02,8.620948048377818917e-01,5.505593019984053704e+00,2.084317097292945065e-01,5.491289348914758506e-01,6.839316092015533532e-02,-1.000000007943860458e+00,0.000000000000000000e+00 +5.776751008724554737e+01,3.532946277309446828e+02,8.641640629152793629e-01,5.506590421958551751e+00,2.086817097292945067e-01,5.473126001127988083e-01,6.839316092015533532e-02,-1.000000008331969559e+00,0.000000000000000000e+00 +5.776932609301930910e+01,3.533044107796991398e+02,8.662357668196807303e-01,5.507584344800407372e+00,2.089317097292945069e-01,5.454965943239094006e-01,6.839316092015533532e-02,-1.000000007962946968e+00,0.000000000000000000e+00 +5.777114177106869874e+01,3.533141933102219241e+02,8.683099164215045684e-01,5.508574790992736503e+00,2.091817097292945071e-01,5.436809162600645395e-01,6.839316092015533532e-02,-1.000000008112973182e+00,0.000000000000000000e+00 +5.777295712265770788e+01,3.533239753219016279e+02,8.703865115911163519e-01,5.509561763007982726e+00,2.094317097292945073e-01,5.418655646563282913e-01,6.839316092015533532e-02,-1.000000008123784978e+00,0.000000000000000000e+00 +5.777477214904821778e+01,3.533337568141268434e+02,8.724655521987290108e-01,5.510545263307942143e+00,2.096817097292945076e-01,5.400505382510741859e-01,6.839316092015533532e-02,-1.000000008096341153e+00,0.000000000000000000e+00 +5.777658685150000650e+01,3.533435377862862197e+02,8.745470381144024863e-01,5.511525294343794457e+00,2.099317097292945078e-01,5.382358357845962171e-01,6.839316092015533532e-02,-1.000000008082589265e+00,0.000000000000000000e+00 +5.777840123127074889e+01,3.533533182377684625e+02,8.766309692080439531e-01,5.512501858556131396e+00,2.101817097292945080e-01,5.364214559991875575e-01,6.839316092015533532e-02,-1.000000008086608494e+00,0.000000000000000000e+00 +5.778021528961605213e+01,3.533630981679623346e+02,8.787173453494075970e-01,5.513474958374985135e+00,2.104317097292945082e-01,5.346073976392171634e-01,6.839316092015533532e-02,-1.000000008333980617e+00,0.000000000000000000e+00 +5.778202902778943439e+01,3.533728775762565419e+02,8.808061664080950592e-01,5.514444596219856720e+00,2.106817097292945085e-01,5.327936594507177714e-01,6.839316092015533532e-02,-1.000000007921926448e+00,0.000000000000000000e+00 +5.778384244704236750e+01,3.533826564620399040e+02,8.828974322535548813e-01,5.515410774499743596e+00,2.109317097292945087e-01,5.309802401834221586e-01,6.839316092015533532e-02,-1.000000008060460299e+00,0.000000000000000000e+00 +5.778565554862425557e+01,3.533924348247011835e+02,8.849911427550830600e-01,5.516373495613170697e+00,2.111817097292945089e-01,5.291671385869211042e-01,6.839316092015533532e-02,-1.000000008291829445e+00,0.000000000000000000e+00 +5.778746833378247061e+01,3.534022126636292569e+02,8.870872977818226035e-01,5.517332761948214426e+00,2.114317097292945091e-01,5.273543534136780897e-01,6.839316092015533532e-02,-1.000000008110305982e+00,0.000000000000000000e+00 +5.778928080376234533e+01,3.534119899782130574e+02,8.891858972027638641e-01,5.518288575882531966e+00,2.116817097292945093e-01,5.255418834191055710e-01,6.839316092015533532e-02,-1.000000008044175548e+00,0.000000000000000000e+00 +5.779109295980719452e+01,3.534217667678414614e+02,8.912869408867444276e-01,5.519240939783390587e+00,2.119317097292945096e-01,5.237297273596804859e-01,6.839316092015533532e-02,-1.000000008304909205e+00,0.000000000000000000e+00 +5.779290480315832212e+01,3.534315430319034022e+02,8.933904287024490021e-01,5.520189856007693407e+00,2.121817097292945098e-01,5.219178839935089131e-01,6.839316092015533532e-02,-1.000000007974987115e+00,0.000000000000000000e+00 +5.779471633505502126e+01,3.534413187697879266e+02,8.954963605184096398e-01,5.521135326902006035e+00,2.124317097292945100e-01,5.201063520823615560e-01,6.839316092015533532e-02,-1.000000007984324313e+00,0.000000000000000000e+00 +5.779652755673460263e+01,3.534510939808839680e+02,8.976047362030055154e-01,5.522077354802586768e+00,2.126817097292945102e-01,5.182951303883165384e-01,6.839316092015533532e-02,-1.000000008405585117e+00,0.000000000000000000e+00 +5.779833846943239450e+01,3.534608686645806301e+02,8.997155556244632590e-01,5.523015942035410575e+00,2.129317097292945105e-01,5.164842176753030589e-01,6.839316092015533532e-02,-1.000000007910191391e+00,0.000000000000000000e+00 +5.780014907438174987e+01,3.534706428202670168e+02,9.018288186508566229e-01,5.523951090916195739e+00,2.131817097292945107e-01,5.146736127116287030e-01,6.839316092015533532e-02,-1.000000008103918425e+00,0.000000000000000000e+00 +5.780195937281405349e+01,3.534804164473321748e+02,9.039445251501065925e-01,5.524882803750434945e+00,2.134317097292945109e-01,5.128633142646559229e-01,6.839316092015533532e-02,-1.000000008379416938e+00,0.000000000000000000e+00 +5.780376936595874326e+01,3.534901895451653218e+02,9.060626749899816090e-01,5.525811082833416599e+00,2.136817097292945111e-01,5.110533211047999513e-01,6.839316092015533532e-02,-1.000000007812618552e+00,0.000000000000000000e+00 +5.780557905504331018e+01,3.534999621131555614e+02,9.081832680380972356e-01,5.526735930450253242e+00,2.139317097292945113e-01,5.092436320060914623e-01,6.839316092015533532e-02,-1.000000008416490616e+00,0.000000000000000000e+00 +5.780738844129331966e+01,3.535097341506921680e+02,9.103063041619164908e-01,5.527657348875910870e+00,2.141817097292945116e-01,5.074342457408514973e-01,6.839316092015533532e-02,-1.000000007820187831e+00,0.000000000000000000e+00 +5.780919752593241157e+01,3.535195056571643590e+02,9.124317832287495156e-01,5.528575340375228464e+00,2.144317097292945118e-01,5.056251610876149050e-01,6.839316092015533532e-02,-1.000000008219399161e+00,0.000000000000000000e+00 +5.781100631018230018e+01,3.535292766319614657e+02,9.145597051057540172e-01,5.529489907202951748e+00,2.146817097292945120e-01,5.038163768228579587e-01,6.839316092015533532e-02,-1.000000008238358218e+00,0.000000000000000000e+00 +5.781281479526280975e+01,3.535390470744727622e+02,9.166900696599347143e-01,5.530401051603751839e+00,2.149317097292945122e-01,5.020078917274503061e-01,6.839316092015533532e-02,-1.000000008084424463e+00,0.000000000000000000e+00 +5.781462298239186026e+01,3.535488169840875798e+02,9.188228767581438916e-01,5.531308775812255440e+00,2.151817097292945125e-01,5.001997045837811573e-01,6.839316092015533532e-02,-1.000000008193237422e+00,0.000000000000000000e+00 +5.781643087278548876e+01,3.535585863601953065e+02,9.209581262670811785e-01,5.532213082053069719e+00,2.154317097292945127e-01,4.983918141753372888e-01,6.839316092015533532e-02,-1.000000008141173957e+00,0.000000000000000000e+00 +5.781823846765786357e+01,3.535683552021853870e+02,9.230958180532934376e-01,5.533113972540806280e+00,2.156817097292945129e-01,4.965842192882472528e-01,6.839316092015533532e-02,-1.000000008004232832e+00,0.000000000000000000e+00 +5.782004576822127717e+01,3.535781235094472663e+02,9.252359519831748758e-01,5.534011449480107814e+00,2.159317097292945131e-01,4.947769187103684407e-01,6.839316092015533532e-02,-1.000000008086928238e+00,0.000000000000000000e+00 +5.782185277568616755e+01,3.535878912813703892e+02,9.273785279229671552e-01,5.534905515065672965e+00,2.161817097292945133e-01,4.929699112308648101e-01,6.839316092015533532e-02,-1.000000008106716409e+00,0.000000000000000000e+00 +5.782365949126112525e+01,3.535976585173443141e+02,9.295235457387592826e-01,5.535796171482280315e+00,2.164317097292945136e-01,4.911631956412584876e-01,6.839316092015533532e-02,-1.000000008281437536e+00,0.000000000000000000e+00 +5.782546591615290765e+01,3.536074252167585428e+02,9.316710052964876088e-01,5.536683420904814135e+00,2.166817097292945138e-01,4.893567707345161666e-01,6.839316092015533532e-02,-1.000000007969818139e+00,0.000000000000000000e+00 +5.782727205156643890e+01,3.536171913790026906e+02,9.338209064619359401e-01,5.537567265498288371e+00,2.169317097292945140e-01,4.875506353065917065e-01,6.839316092015533532e-02,-1.000000008393167494e+00,0.000000000000000000e+00 +5.782907789870482418e+01,3.536269570034663730e+02,9.359732491007355382e-01,5.538447707417873289e+00,2.171817097292945142e-01,4.857447881530525535e-01,6.839316092015533532e-02,-1.000000008007275509e+00,0.000000000000000000e+00 +5.783088345876935676e+01,3.536367220895392052e+02,9.381280330783648980e-01,5.539324748808915899e+00,2.174317097292945145e-01,4.839392280740651975e-01,6.839316092015533532e-02,-1.000000007949000347e+00,0.000000000000000000e+00 +5.783268873295952517e+01,3.536464866366108595e+02,9.402852582601499698e-01,5.540198391806969269e+00,2.176817097292945147e-01,4.821339538695441074e-01,6.839316092015533532e-02,-1.000000008223773662e+00,0.000000000000000000e+00 +5.783449372247304154e+01,3.536562506440711218e+02,9.424449245112642704e-01,5.541068638537812951e+00,2.179317097292945149e-01,4.803289643411860488e-01,6.839316092015533532e-02,-1.000000007976849403e+00,0.000000000000000000e+00 +5.783629842850582037e+01,3.536660141113096643e+02,9.446070316967286606e-01,5.541935491117476964e+00,2.181817097292945151e-01,4.785242582940132938e-01,6.839316092015533532e-02,-1.000000008493085346e+00,0.000000000000000000e+00 +5.783810285225200687e+01,3.536757770377163297e+02,9.467715796814113460e-01,5.542798951652268435e+00,2.184317097292945153e-01,4.767198345325027731e-01,6.839316092015533532e-02,-1.000000007742293251e+00,0.000000000000000000e+00 +5.783990699490398413e+01,3.536855394226809040e+02,9.489385683300282093e-01,5.543659022238791145e+00,2.186817097292945156e-01,4.749156918665592420e-01,6.839316092015533532e-02,-1.000000008290850007e+00,0.000000000000000000e+00 +5.784171085765237308e+01,3.536953012655932866e+02,9.511079975071423664e-01,5.544515704963975722e+00,2.189317097292945158e-01,4.731118291032123668e-01,6.839316092015533532e-02,-1.000000008298335130e+00,0.000000000000000000e+00 +5.784351444168606093e+01,3.537050625658433205e+02,9.532798670771645000e-01,5.545369001905094741e+00,2.191817097292945160e-01,4.713082450545585944e-01,6.839316092015533532e-02,-1.000000007792574586e+00,0.000000000000000000e+00 +5.784531774819218697e+01,3.537148233228209051e+02,9.554541769043528587e-01,5.546218915129792038e+00,2.194317097292945162e-01,4.695049385343810777e-01,6.839316092015533532e-02,-1.000000008399863471e+00,0.000000000000000000e+00 +5.784712077835616384e+01,3.537245835359159969e+02,9.576309268528130358e-01,5.547065446696105795e+00,2.196817097292945165e-01,4.677019083552586554e-01,6.839316092015533532e-02,-1.000000007881570285e+00,0.000000000000000000e+00 +5.784892353336168469e+01,3.537343432045186091e+02,9.598101167864980798e-01,5.547908598652486312e+00,2.199317097292945167e-01,4.658991533355262282e-01,6.839316092015533532e-02,-1.000000008056246559e+00,0.000000000000000000e+00 +5.785072601439073736e+01,3.537441023280187551e+02,9.619917465692087166e-01,5.548748373037826198e+00,2.201817097292945169e-01,4.640966722919503962e-01,6.839316092015533532e-02,-1.000000008516743755e+00,0.000000000000000000e+00 +5.785252822262360439e+01,3.537538609058065049e+02,9.641758160645930165e-01,5.549584771881477252e+00,2.204317097292945171e-01,4.622944640437337549e-01,6.839316092015533532e-02,-1.000000007720811546e+00,0.000000000000000000e+00 +5.785433015923887723e+01,3.537636189372719286e+02,9.663623251361467270e-01,5.550417797203274439e+00,2.206817097292945173e-01,4.604925274145509895e-01,6.839316092015533532e-02,-1.000000008188574485e+00,0.000000000000000000e+00 +5.785613182541345623e+01,3.537733764218051533e+02,9.685512736472129403e-01,5.551247451013563428e+00,2.209317097292945176e-01,4.586908612252193485e-01,6.839316092015533532e-02,-1.000000008297889931e+00,0.000000000000000000e+00 +5.785793322232257196e+01,3.537831333587963059e+02,9.707426614609824256e-01,5.552073735313214797e+00,2.211817097292945178e-01,4.568894643011544576e-01,6.839316092015533532e-02,-1.000000008027443155e+00,0.000000000000000000e+00 +5.785973435113979235e+01,3.537928897476356269e+02,9.729364884404934077e-01,5.552896652093651575e+00,2.214317097292945180e-01,4.550883354694765237e-01,6.839316092015533532e-02,-1.000000008137993612e+00,0.000000000000000000e+00 +5.786153521303702263e+01,3.538026455877133003e+02,9.751327544486316778e-01,5.553716203336871438e+00,2.216817097292945182e-01,4.532874735575931902e-01,6.839316092015533532e-02,-1.000000007982019712e+00,0.000000000000000000e+00 +5.786333580918451247e+01,3.538124008784196235e+02,9.773314593481307044e-01,5.554532391015466253e+00,2.219317097292945185e-01,4.514868773957274040e-01,6.839316092015533532e-02,-1.000000008242161620e+00,0.000000000000000000e+00 +5.786513614075088441e+01,3.538221556191448940e+02,9.795326030015713004e-01,5.555345217092646060e+00,2.221817097292945187e-01,4.496865458145133387e-01,6.839316092015533532e-02,-1.000000007918196765e+00,0.000000000000000000e+00 +5.786693620890312673e+01,3.538319098092794093e+02,9.817361852713820669e-01,5.556154683522258608e+00,2.224317097292945189e-01,4.478864776480177556e-01,6.839316092015533532e-02,-1.000000008163169030e+00,0.000000000000000000e+00 +5.786873601480660056e+01,3.538416634482135237e+02,9.839422060198391717e-01,5.556960792248814229e+00,2.226817097292945191e-01,4.460866717298548889e-01,6.839316092015533532e-02,-1.000000008172996502e+00,0.000000000000000000e+00 +5.787053555962504703e+01,3.538514165353376484e+02,9.861506651090662379e-01,5.557763545207503597e+00,2.229317097292945193e-01,4.442871268967010234e-01,6.839316092015533532e-02,-1.000000008201473500e+00,0.000000000000000000e+00 +5.787233484452060850e+01,3.538611690700422514e+02,9.883615624010345657e-01,5.558562944324221711e+00,2.231817097292945196e-01,4.424878419863816914e-01,6.839316092015533532e-02,-1.000000007915091693e+00,0.000000000000000000e+00 +5.787413387065382864e+01,3.538709210517177439e+02,9.905748977575631331e-01,5.559358991515588322e+00,2.234317097292945198e-01,4.406888158389200005e-01,6.839316092015533532e-02,-1.000000008040220489e+00,0.000000000000000000e+00 +5.787593263918366659e+01,3.538806724797546508e+02,9.927906710403184842e-01,5.560151688688970140e+00,2.236817097292945200e-01,4.388900472946213327e-01,6.839316092015533532e-02,-1.000000008441945809e+00,0.000000000000000000e+00 +5.787773115126748991e+01,3.538904233535435537e+02,9.950088821108147297e-01,5.560941037742499482e+00,2.239317097292945202e-01,4.370915351956146666e-01,6.839316092015533532e-02,-1.000000007848516281e+00,0.000000000000000000e+00 +5.787952940806110291e+01,3.539001736724749776e+02,9.972295308304137684e-01,5.561727040565095592e+00,2.241817097292945205e-01,4.352932783878883383e-01,6.839316092015533532e-02,-1.000000007971218130e+00,0.000000000000000000e+00 +5.788132741071873966e+01,3.539099234359395041e+02,9.994526170603249549e-01,5.562509699036489508e+00,2.244317097292945207e-01,4.334952757159168391e-01,6.839316092015533532e-02,-1.000000008287199371e+00,0.000000000000000000e+00 +5.788312516039308520e+01,3.539196726433278286e+02,1.001678140661605543e+00,5.563289015027239159e+00,2.246817097292945209e-01,4.316975260266706083e-01,6.839316092015533532e-02,-1.000000007960465176e+00,0.000000000000000000e+00 +5.788492265823527561e+01,3.539294212940305897e+02,1.003906101495160019e+00,5.564064990398751576e+00,2.249317097292945211e-01,4.299000281701700343e-01,6.839316092015533532e-02,-1.000000008316665356e+00,0.000000000000000000e+00 +5.788671990539490508e+01,3.539391693874384828e+02,1.006136499421740993e+00,5.564837627003305975e+00,2.251817097292945213e-01,4.281027809955912922e-01,6.839316092015533532e-02,-1.000000007895220921e+00,0.000000000000000000e+00 +5.788851690302004016e+01,3.539489169229422600e+02,1.008369334301948639e+00,5.565606926684069755e+00,2.254317097292945216e-01,4.263057833562662324e-01,6.839316092015533532e-02,-1.000000008223223658e+00,0.000000000000000000e+00 +5.789031365225722681e+01,3.539586638999327306e+02,1.010604605996230809e+00,5.566372891275123358e+00,2.256817097292945218e-01,4.245090341043045723e-01,6.839316092015533532e-02,-1.000000008040872412e+00,0.000000000000000000e+00 +5.789211015425149043e+01,3.539684103178007035e+02,1.012842314364883034e+00,5.567135522601475373e+00,2.259317097292945220e-01,4.227125320955938403e-01,6.839316092015533532e-02,-1.000000007976828531e+00,0.000000000000000000e+00 +5.789390641014635719e+01,3.539781561759369879e+02,1.015082459268048520e+00,5.567894822479086514e+00,2.261817097292945222e-01,4.209162761863977642e-01,6.839316092015533532e-02,-1.000000008073393509e+00,0.000000000000000000e+00 +5.789570242108385401e+01,3.539879014737325065e+02,1.017325040565718153e+00,5.568650792714887388e+00,2.264317097292945224e-01,4.191202652344018231e-01,6.839316092015533532e-02,-1.000000008061208812e+00,0.000000000000000000e+00 +5.789749818820451566e+01,3.539976462105781820e+02,1.019570058117730493e+00,5.569403435106798028e+00,2.266817097292945227e-01,4.173244980992648068e-01,6.839316092015533532e-02,-1.000000008184929623e+00,0.000000000000000000e+00 +5.789929371264739899e+01,3.540073903858649373e+02,1.021817511783772225e+00,5.570152751443748329e+00,2.269317097292945229e-01,4.155289736416875046e-01,6.839316092015533532e-02,-1.000000008102753579e+00,0.000000000000000000e+00 +5.790108899555008293e+01,3.540171339989837520e+02,1.024067401423377266e+00,5.570898743505696693e+00,2.271817097292945231e-01,4.137336907244577033e-01,6.839316092015533532e-02,-1.000000007987393191e+00,0.000000000000000000e+00 +5.790288403804868267e+01,3.540268770493257193e+02,1.026319726895927653e+00,5.571641413063650461e+00,2.274317097292945233e-01,4.119386482115182102e-01,6.839316092015533532e-02,-1.000000007976087124e+00,0.000000000000000000e+00 +5.790467884127786391e+01,3.540366195362818189e+02,1.028574488060652881e+00,5.572380761879684563e+00,2.276817097292945236e-01,4.101438449680226417e-01,6.839316092015533532e-02,-1.000000008170561339e+00,0.000000000000000000e+00 +5.790647340637083573e+01,3.540463614592432009e+02,1.030831684776630564e+00,5.573116791706960171e+00,2.279317097292945238e-01,4.083492798603912677e-01,6.839316092015533532e-02,-1.000000008085440317e+00,0.000000000000000000e+00 +5.790826773445936482e+01,3.540561028176009586e+02,1.033091316902785772e+00,5.573849504289743351e+00,2.281817097292945240e-01,4.065549517573565641e-01,6.839316092015533532e-02,-1.000000008027043696e+00,0.000000000000000000e+00 +5.791006182667378255e+01,3.540658436107462990e+02,1.035353384297891477e+00,5.574578901363425487e+00,2.284317097292945242e-01,4.047608595285344113e-01,6.839316092015533532e-02,-1.000000007990913486e+00,0.000000000000000000e+00 +5.791185568414300633e+01,3.540755838380703722e+02,1.037617886820568547e+00,5.575304984654541052e+00,2.286817097292945244e-01,4.029670020449739321e-01,6.839316092015533532e-02,-1.000000007937349444e+00,0.000000000000000000e+00 +5.791364930799453248e+01,3.540853234989644420e+02,1.039884824329285751e+00,5.576027755880786252e+00,2.289317097292945247e-01,4.011733781792127806e-01,6.839316092015533532e-02,-1.000000008344223756e+00,0.000000000000000000e+00 +5.791544269935444333e+01,3.540950625928197724e+02,1.042154196682359313e+00,5.576747216751037683e+00,2.291817097292945249e-01,3.993799868043410028e-01,6.839316092015533532e-02,-1.000000007720973194e+00,0.000000000000000000e+00 +5.791723585934741436e+01,3.541048011190276839e+02,1.044426003737953357e+00,5.577463368965369206e+00,2.294317097292945251e-01,3.975868267975233294e-01,6.839316092015533532e-02,-1.000000008409433150e+00,0.000000000000000000e+00 +5.791902878909674257e+01,3.541145390769794972e+02,1.046700245354080128e+00,5.578176214215075035e+00,2.296817097292945253e-01,3.957938970331187356e-01,6.839316092015533532e-02,-1.000000007744412001e+00,0.000000000000000000e+00 +5.792082148972432520e+01,3.541242764660665898e+02,1.048976921388599326e+00,5.578885754182680401e+00,2.299317097292945256e-01,3.940011963916508764e-01,6.839316092015533532e-02,-1.000000008275798713e+00,0.000000000000000000e+00 +5.792261396235069526e+01,3.541340132856803962e+02,1.051256031699218774e+00,5.579591990541968194e+00,2.301817097292945258e-01,3.922087237504499613e-01,6.839316092015533532e-02,-1.000000007821493231e+00,0.000000000000000000e+00 +5.792440620809500018e+01,3.541437495352123506e+02,1.053537576143494192e+00,5.580294924957988734e+00,2.304317097292945260e-01,3.904164779921281969e-01,6.839316092015533532e-02,-1.000000008034664045e+00,0.000000000000000000e+00 +5.792619822807503027e+01,3.541534852140539442e+02,1.055821554578828980e+00,5.580994559087084639e+00,2.306817097292945262e-01,3.886244579976971814e-01,6.839316092015533532e-02,-1.000000008323267187e+00,0.000000000000000000e+00 +5.792799002340722581e+01,3.541632203215967252e+02,1.058107966862474436e+00,5.581690894576903261e+00,2.309317097292945264e-01,3.868326626505846355e-01,6.839316092015533532e-02,-1.000000007783823142e+00,0.000000000000000000e+00 +5.792978159520668413e+01,3.541729548572321846e+02,1.060396812851529980e+00,5.582383933066416226e+00,2.311817097292945267e-01,3.850410908371841301e-01,6.839316092015533532e-02,-1.000000007969375826e+00,0.000000000000000000e+00 +5.793157294458714546e+01,3.541826888203519843e+02,1.062688092402942486e+00,5.583073676185939860e+00,2.314317097292945269e-01,3.832497414424461124e-01,6.839316092015533532e-02,-1.000000008185998990e+00,0.000000000000000000e+00 +5.793336407266103549e+01,3.541924222103476723e+02,1.064981805373507173e+00,5.583760125557147624e+00,2.316817097292945271e-01,3.814586133538962476e-01,6.839316092015533532e-02,-1.000000007705466931e+00,0.000000000000000000e+00 +5.793515498053944413e+01,3.542021550266109671e+02,1.067277951619866938e+00,5.584443282793089658e+00,2.319317097292945273e-01,3.796677054616885982e-01,6.839316092015533532e-02,-1.000000008258543183e+00,0.000000000000000000e+00 +5.793694566933214674e+01,3.542118872685335873e+02,1.069576530998512576e+00,5.585123149498212314e+00,2.321817097292945276e-01,3.778770166541940978e-01,6.839316092015533532e-02,-1.000000007942505542e+00,0.000000000000000000e+00 +5.793873614014761841e+01,3.542216189355071947e+02,1.071877543365783003e+00,5.585799727268369708e+00,2.324317097292945278e-01,3.760865458245001292e-01,6.839316092015533532e-02,-1.000000008145199626e+00,0.000000000000000000e+00 +5.794052639409302685e+01,3.542313500269236215e+02,1.074180988577864815e+00,5.586473017690846810e+00,2.326817097292945280e-01,3.742962918645103554e-01,6.839316092015533532e-02,-1.000000007728020224e+00,0.000000000000000000e+00 +5.794231643227423945e+01,3.542410805421746431e+02,1.076486866490792726e+00,5.587143022344371879e+00,2.329317097292945282e-01,3.725062536694608295e-01,6.839316092015533532e-02,-1.000000008291034526e+00,0.000000000000000000e+00 +5.794410625579585172e+01,3.542508104806521487e+02,1.078795176960449353e+00,5.587809742799136892e+00,2.331817097292945284e-01,3.707164301330097556e-01,6.839316092015533532e-02,-1.000000007797808177e+00,0.000000000000000000e+00 +5.794589586576116602e+01,3.542605398417479705e+02,1.081105919842565211e+00,5.588473180616809088e+00,2.334317097292945287e-01,3.689268201537392877e-01,6.839316092015533532e-02,-1.000000008060809797e+00,0.000000000000000000e+00 +5.794768526327221991e+01,3.542702686248540545e+02,1.083419094992719156e+00,5.589133337350554065e+00,2.336817097292945289e-01,3.671374226282591025e-01,6.839316092015533532e-02,-1.000000007809634939e+00,0.000000000000000000e+00 +5.794947444942979331e+01,3.542799968293622896e+02,1.085734702266337504e+00,5.589790214545046432e+00,2.339317097292945291e-01,3.653482364567163243e-01,6.839316092015533532e-02,-1.000000008238024707e+00,0.000000000000000000e+00 +5.795126342533339425e+01,3.542897244546647357e+02,1.088052741518694910e+00,5.590443813736490242e+00,2.341817097292945293e-01,3.635592605383787257e-01,6.839316092015533532e-02,-1.000000007732664287e+00,0.000000000000000000e+00 +5.795305219208129444e+01,3.542994515001533955e+02,1.090373212604913711e+00,5.591094136452631425e+00,2.344317097292945296e-01,3.617704937766494933e-01,6.839316092015533532e-02,-1.000000008255979234e+00,0.000000000000000000e+00 +5.795484075077051500e+01,3.543091779652202717e+02,1.092696115379964583e+00,5.591741184212779103e+00,2.346817097292945298e-01,3.599819350726630729e-01,6.839316092015533532e-02,-1.000000007852220429e+00,0.000000000000000000e+00 +5.795662910249684785e+01,3.543189038492575378e+02,1.095021449698666327e+00,5.592384958527815364e+00,2.349317097292945300e-01,3.581935833322865137e-01,6.839316092015533532e-02,-1.000000007865227580e+00,0.000000000000000000e+00 +5.795841724835486275e+01,3.543286291516573101e+02,1.097349215415685197e+00,5.593025460900217460e+00,2.351817097292945302e-01,3.564054374602103614e-01,6.839316092015533532e-02,-1.000000007941163727e+00,0.000000000000000000e+00 +5.796020518943790023e+01,3.543383538718117052e+02,1.099679412385536015e+00,5.593662692824069360e+00,2.354317097292945304e-01,3.546174963629777910e-01,6.839316092015533532e-02,-1.000000007972123850e+00,0.000000000000000000e+00 +5.796199292683808579e+01,3.543480780091130100e+02,1.102012040462581499e+00,5.594296655785078620e+00,2.356817097292945307e-01,3.528297589485373531e-01,6.839316092015533532e-02,-1.000000008096536996e+00,0.000000000000000000e+00 +5.796378046164635833e+01,3.543578015629533979e+02,1.104347099501032270e+00,5.594927351260592374e+00,2.359317097292945309e-01,3.510422241257952769e-01,6.839316092015533532e-02,-1.000000007587126927e+00,0.000000000000000000e+00 +5.796556779495243461e+01,3.543675245327251560e+02,1.106684589354947290e+00,5.595554780719612431e+00,2.361817097292945311e-01,3.492548908061556268e-01,6.839316092015533532e-02,-1.000000008187785561e+00,0.000000000000000000e+00 +5.796735492784485899e+01,3.543772469178206279e+02,1.109024509878233422e+00,5.596178945622813039e+00,2.364317097292945313e-01,3.474677578990961746e-01,6.839316092015533532e-02,-1.000000007996553864e+00,0.000000000000000000e+00 +5.796914186141098924e+01,3.543869687176321577e+02,1.111366860924645650e+00,5.596799847422550656e+00,2.366817097292945316e-01,3.456808243186774710e-01,6.839316092015533532e-02,-1.000000007860629703e+00,0.000000000000000000e+00 +5.797092859673699650e+01,3.543966899315521459e+02,1.113711642347786857e+00,5.597417487562885263e+00,2.369317097292945318e-01,3.438940889786221144e-01,6.839316092015533532e-02,-1.000000008040662136e+00,0.000000000000000000e+00 +5.797271513490790085e+01,3.544064105589729934e+02,1.116058854001108269e+00,5.598031867479592805e+00,2.371817097292945320e-01,3.421075507933561410e-01,6.839316092015533532e-02,-1.000000007653066847e+00,0.000000000000000000e+00 +5.797450147700754286e+01,3.544161305992871576e+02,1.118408495737909236e+00,5.598642988600179393e+00,2.374317097292945322e-01,3.403212086800460612e-01,6.839316092015533532e-02,-1.000000008009938712e+00,0.000000000000000000e+00 +5.797628762411861203e+01,3.544258500518871529e+02,1.120760567411337227e+00,5.599250852343899076e+00,2.376817097292945324e-01,3.385350615546692254e-01,6.839316092015533532e-02,-1.000000007887701159e+00,0.000000000000000000e+00 +5.797807357732266098e+01,3.544355689161654936e+02,1.123115068874387612e+00,5.599855460121764494e+00,2.379317097292945327e-01,3.367491083365363180e-01,6.839316092015533532e-02,-1.000000007980718975e+00,0.000000000000000000e+00 +5.797985933770008415e+01,3.544452871915147512e+02,1.125471999979904103e+00,5.600456813336565531e+00,2.381817097292945329e-01,3.349633479448583251e-01,6.839316092015533532e-02,-1.000000007839044969e+00,0.000000000000000000e+00 +5.798164490633016044e+01,3.544550048773275535e+02,1.127831360580578535e+00,5.601054913382881750e+00,2.384317097292945331e-01,3.331777793007832389e-01,6.839316092015533532e-02,-1.000000008096745496e+00,0.000000000000000000e+00 +5.798343028429103185e+01,3.544647219729965286e+02,1.130193150528950863e+00,5.601649761647098380e+00,2.386817097292945333e-01,3.313924013254532785e-01,6.839316092015533532e-02,-1.000000007685813541e+00,0.000000000000000000e+00 +5.798521547265972487e+01,3.544744384779143616e+02,1.132557369677409165e+00,5.602241359507418750e+00,2.389317097292945336e-01,3.296072129430368536e-01,6.839316092015533532e-02,-1.000000007737041230e+00,0.000000000000000000e+00 +5.798700047251215750e+01,3.544841543914737372e+02,1.134924017878189861e+00,5.602829708333882053e+00,2.391817097292945338e-01,3.278222130767958764e-01,6.839316092015533532e-02,-1.000000008237359239e+00,0.000000000000000000e+00 +5.798878528492313222e+01,3.544938697130674541e+02,1.137293094983377273e+00,5.603414809488374004e+00,2.394317097292945340e-01,3.260374006511211897e-01,6.839316092015533532e-02,-1.000000007469878049e+00,0.000000000000000000e+00 +5.799056991096635727e+01,3.545035844420883109e+02,1.139664600844904063e+00,5.603996664324641053e+00,2.396817097292945342e-01,3.242527745945662510e-01,6.839316092015533532e-02,-1.000000008149679820e+00,0.000000000000000000e+00 +5.799235435171445374e+01,3.545132985779291062e+02,1.142038535314551240e+00,5.604575274188309919e+00,2.399317097292945344e-01,3.224683338319302983e-01,6.839316092015533532e-02,-1.000000007663450319e+00,0.000000000000000000e+00 +5.799413860823894851e+01,3.545230121199827522e+02,1.144414898243947931e+00,5.605150640416892927e+00,2.401817097292945347e-01,3.206840772937606387e-01,6.839316092015533532e-02,-1.000000008109766414e+00,0.000000000000000000e+00 +5.799592268161030262e+01,3.545327250676421045e+02,1.146793689484571388e+00,5.605722764339810205e+00,2.404317097292945349e-01,3.189000039079374349e-01,6.839316092015533532e-02,-1.000000007651995038e+00,0.000000000000000000e+00 +5.799770657289790421e+01,3.545424374203001321e+02,1.149174908887747204e+00,5.606291647278396795e+00,2.406817097292945351e-01,3.171161126066883162e-01,6.839316092015533532e-02,-1.000000007772380739e+00,0.000000000000000000e+00 +5.799949028317006849e+01,3.545521491773498042e+02,1.151558556304649095e+00,5.606857290545922190e+00,2.409317097292945353e-01,3.153324023206602322e-01,6.839316092015533532e-02,-1.000000007970595739e+00,0.000000000000000000e+00 +5.800127381349406619e+01,3.545618603381841467e+02,1.153944631586299119e+00,5.607419695447599217e+00,2.411817097292945355e-01,3.135488719824496284e-01,6.839316092015533532e-02,-1.000000007716552508e+00,0.000000000000000000e+00 +5.800305716493610930e+01,3.545715709021961857e+02,1.156333134583567679e+00,5.607978863280599136e+00,2.414317097292945358e-01,3.117655205266482987e-01,6.839316092015533532e-02,-1.000000007847103856e+00,0.000000000000000000e+00 +5.800484033856136534e+01,3.545812808687790607e+02,1.158724065147173077e+00,5.608534795334066736e+00,2.416817097292945360e-01,3.099823468873986743e-01,6.839316092015533532e-02,-1.000000007774017652e+00,0.000000000000000000e+00 +5.800662333543397153e+01,3.545909902373258547e+02,1.161117423127682402e+00,5.609087492889130999e+00,2.419317097292945362e-01,3.081993500009285181e-01,6.839316092015533532e-02,-1.000000007997161156e+00,0.000000000000000000e+00 +5.800840615661704192e+01,3.546006990072297071e+02,1.163513208375510644e+00,5.609636957218920195e+00,2.421817097292945364e-01,3.064165288036038159e-01,6.839316092015533532e-02,-1.000000007590389650e+00,0.000000000000000000e+00 +5.801018880317265314e+01,3.546104071778838716e+02,1.165911420740921356e+00,5.610183189588573427e+00,2.424317097292945367e-01,3.046338822344644148e-01,6.839316092015533532e-02,-1.000000007834627613e+00,0.000000000000000000e+00 +5.801197127616187288e+01,3.546201147486815444e+02,1.168312060074026215e+00,5.610726191255256623e+00,2.426817097292945369e-01,3.028514092312825645e-01,6.839316092015533532e-02,-1.000000007746105979e+00,0.000000000000000000e+00 +5.801375357664475274e+01,3.546298217190160358e+02,1.170715126224785241e+00,5.611265963468171414e+00,2.429317097292945371e-01,3.010691087345934158e-01,6.839316092015533532e-02,-1.000000007710025507e+00,0.000000000000000000e+00 +5.801553570568035667e+01,3.546395280882806560e+02,1.173120619043006796e+00,5.611802507468571122e+00,2.431817097292945373e-01,2.992869796852479225e-01,6.839316092015533532e-02,-1.000000008083292258e+00,0.000000000000000000e+00 +5.801731766432674675e+01,3.546492338558687720e+02,1.175528538378347587e+00,5.612335824489772307e+00,2.434317097292945375e-01,2.975050210244568061e-01,6.839316092015533532e-02,-1.000000007516236744e+00,0.000000000000000000e+00 +5.801909945364098320e+01,3.546589390211737509e+02,1.177938884080312665e+00,5.612865915757166313e+00,2.436817097292945378e-01,2.957232316968248509e-01,6.839316092015533532e-02,-1.000000007707408267e+00,0.000000000000000000e+00 +5.802088107467916700e+01,3.546686435835890165e+02,1.180351655998255422e+00,5.613392782488236143e+00,2.439317097292945380e-01,2.939416106449125321e-01,6.839316092015533532e-02,-1.000000007810110780e+00,0.000000000000000000e+00 +5.802266252849640438e+01,3.546783475425080496e+02,1.182766853981377597e+00,5.613916425892563566e+00,2.441817097292945382e-01,2.921601568137647265e-01,6.839316092015533532e-02,-1.000000007788206302e+00,0.000000000000000000e+00 +5.802444381614683522e+01,3.546880508973243309e+02,1.185184477878729270e+00,5.614436847171844214e+00,2.444317097292945384e-01,2.903788691494596508e-01,6.839316092015533532e-02,-1.000000007577505956e+00,0.000000000000000000e+00 +5.802622493868364728e+01,3.546977536474314547e+02,1.187604527539209087e+00,5.614954047519900016e+00,2.446817097292945387e-01,2.885977465991521607e-01,6.839316092015533532e-02,-1.000000007926059142e+00,0.000000000000000000e+00 +5.802800589715906199e+01,3.547074557922229587e+02,1.190027002811563817e+00,5.615468028122691635e+00,2.449317097292945389e-01,2.868167881096205241e-01,6.839316092015533532e-02,-1.000000007313638362e+00,0.000000000000000000e+00 +5.802978669262435574e+01,3.547171573310924373e+02,1.192451903544388792e+00,5.615978790158328238e+00,2.451817097292945391e-01,2.850359926312996395e-01,6.839316092015533532e-02,-1.000000008113125949e+00,0.000000000000000000e+00 +5.803156732612986701e+01,3.547268582634335417e+02,1.194879229586127689e+00,5.616486334797084368e+00,2.454317097292945393e-01,2.832553591113412539e-01,6.839316092015533532e-02,-1.000000007628154775e+00,0.000000000000000000e+00 +5.803334779872498927e+01,3.547365585886400368e+02,1.197308980785072752e+00,5.616990663201404388e+00,2.456817097292945395e-01,2.814748865026345803e-01,6.839316092015533532e-02,-1.000000007616206776e+00,0.000000000000000000e+00 +5.803512811145819938e+01,3.547462583061055739e+02,1.199741156989364343e+00,5.617491776525922909e+00,2.459317097292945398e-01,2.796945737558687584e-01,6.839316092015533532e-02,-1.000000007566467675e+00,0.000000000000000000e+00 +5.803690826537703629e+01,3.547559574152239747e+02,1.202175758046991616e+00,5.617989675917471004e+00,2.461817097292945400e-01,2.779144198235653507e-01,6.839316092015533532e-02,-1.000000007781066902e+00,0.000000000000000000e+00 +5.803868826152812943e+01,3.547656559153890043e+02,1.204612783805791842e+00,5.618484362515089536e+00,2.464317097292945402e-01,2.761344236586244505e-01,6.839316092015533532e-02,-1.000000007413699432e+00,0.000000000000000000e+00 +5.804046810095719877e+01,3.547753538059945413e+02,1.207052234113451084e+00,5.618975837450039812e+00,2.466817097292945404e-01,2.743545842163623849e-01,6.839316092015533532e-02,-1.000000008113679062e+00,0.000000000000000000e+00 +5.804224778470905477e+01,3.547850510864344074e+02,1.209494108817503522e+00,5.619464101845817794e+00,2.469317097292945407e-01,2.725749004500632733e-01,6.839316092015533532e-02,-1.000000007297274118e+00,0.000000000000000000e+00 +5.804402731382762681e+01,3.547947477561025948e+02,1.211938407765332126e+00,5.619949156818160318e+00,2.471817097292945409e-01,2.707953713185063949e-01,6.839316092015533532e-02,-1.000000007681672409e+00,0.000000000000000000e+00 +5.804580668935594190e+01,3.548044438143930392e+02,1.214385130804168211e+00,5.620431003475064635e+00,2.474317097292945411e-01,2.690159957765257959e-01,6.839316092015533532e-02,-1.000000007469775909e+00,0.000000000000000000e+00 +5.804758591233613885e+01,3.548141392606996760e+02,1.216834277781091656e+00,5.620909642916791071e+00,2.476817097292945413e-01,2.672367727830374240e-01,6.839316092015533532e-02,-1.000000007923130374e+00,0.000000000000000000e+00 +5.804936498380948962e+01,3.548238340944166112e+02,1.219285848543030681e+00,5.621385076235879907e+00,2.479317097292945415e-01,2.654577012955900428e-01,6.839316092015533532e-02,-1.000000007470277064e+00,0.000000000000000000e+00 +5.805114390481639219e+01,3.548335283149378938e+02,1.221739842936762077e+00,5.621857304517158482e+00,2.481817097292945418e-01,2.636787802753992604e-01,6.839316092015533532e-02,-1.000000007600017726e+00,0.000000000000000000e+00 +5.805292267639637771e+01,3.548432219216576300e+02,1.224196260808911196e+00,5.622326328837757181e+00,2.484317097292945420e-01,2.619000086818966677e-01,6.839316092015533532e-02,-1.000000007529077140e+00,0.000000000000000000e+00 +5.805470129958811754e+01,3.548529149139699825e+02,1.226655102005951958e+00,5.622792150267115652e+00,2.486817097292945422e-01,2.601213854767654987e-01,6.839316092015533532e-02,-1.000000007570359672e+00,0.000000000000000000e+00 +5.805647977542943750e+01,3.548626072912691711e+02,1.229116366374206848e+00,5.623254769866996128e+00,2.489317097292945424e-01,2.583429096219842513e-01,6.839316092015533532e-02,-1.000000007448503370e+00,0.000000000000000000e+00 +5.805825810495731076e+01,3.548722990529493586e+02,1.231580053759846693e+00,5.623714188691493199e+00,2.491817097292945427e-01,2.565645800808666332e-01,6.839316092015533532e-02,-1.000000007704199501e+00,0.000000000000000000e+00 +5.806003628920787207e+01,3.548819901984048784e+02,1.234046164008891111e+00,5.624170407787045356e+00,2.494317097292945429e-01,2.547863958166039500e-01,6.839316092015533532e-02,-1.000000007447351624e+00,0.000000000000000000e+00 +5.806181432921643193e+01,3.548916807270299500e+02,1.236514696967208282e+00,5.624623428192443875e+00,2.496817097292945431e-01,2.530083557948030748e-01,6.839316092015533532e-02,-1.000000007446728345e+00,0.000000000000000000e+00 +5.806359222601746239e+01,3.549013706382189639e+02,1.238985652480514732e+00,5.625073250938846137e+00,2.499317097292945433e-01,2.512304589805303134e-01,6.839316092015533532e-02,-1.000000007602194430e+00,0.000000000000000000e+00 +5.806536998064462551e+01,3.549110599313663101e+02,1.241459030394375773e+00,5.625519877049783624e+00,2.501817097292945435e-01,2.494527043398502286e-01,6.839316092015533532e-02,-1.000000007506344435e+00,0.000000000000000000e+00 +5.806714759413076621e+01,3.549207486058663790e+02,1.243934830554205506e+00,5.625963307541172576e+00,2.504317097292945160e-01,2.476750908403654861e-01,6.839316092015533532e-02,-1.000000007568511595e+00,0.000000000000000000e+00 +5.806892506750791938e+01,3.549304366611136743e+02,1.246413052805266153e+00,5.626403543421325537e+00,2.506817097292944885e-01,2.458976174497586042e-01,6.839316092015533532e-02,-1.000000007328806451e+00,0.000000000000000000e+00 +5.807070240180732412e+01,3.549401240965026432e+02,1.248893696992668945e+00,5.626840585690960239e+00,2.509317097292944609e-01,2.441202831373308069e-01,6.839316092015533532e-02,-1.000000007425854376e+00,0.000000000000000000e+00 +5.807247959805941662e+01,3.549498109114278463e+02,1.251376762961373679e+00,5.627274435343211145e+00,2.511817097292944334e-01,2.423430868720432285e-01,6.839316092015533532e-02,-1.000000007628944809e+00,0.000000000000000000e+00 +5.807425665729384434e+01,3.549594971052838446e+02,1.253862250556188718e+00,5.627705093363637445e+00,2.514317097292944059e-01,2.405660276240558781e-01,6.839316092015533532e-02,-1.000000007399990842e+00,0.000000000000000000e+00 +5.807603358053948028e+01,3.549691826774652554e+02,1.256350159621770990e+00,5.628132560730233713e+00,2.516817097292943783e-01,2.387891043652674572e-01,6.839316092015533532e-02,-1.000000007300158256e+00,0.000000000000000000e+00 +5.807781036882442294e+01,3.549788676273667534e+02,1.258840490002626211e+00,5.628556838413441454e+00,2.519317097292943508e-01,2.370123160673557050e-01,6.839316092015533532e-02,-1.000000007302431770e+00,0.000000000000000000e+00 +5.807958702317598920e+01,3.549885519543830128e+02,1.261333241543108885e+00,5.628977927376157098e+00,2.521817097292943233e-01,2.352356617028164842e-01,6.839316092015533532e-02,-1.000000007635508226e+00,0.000000000000000000e+00 +5.808136354462073569e+01,3.549982356579087082e+02,1.263828414087421859e+00,5.629395828573741767e+00,2.524317097292942957e-01,2.334591402445032882e-01,6.839316092015533532e-02,-1.000000007376752320e+00,0.000000000000000000e+00 +5.808313993418446586e+01,3.550079187373386844e+02,1.266326007479616989e+00,5.629810542954030161e+00,2.526817097292942682e-01,2.316827506676663873e-01,6.839316092015533532e-02,-1.000000007266387270e+00,0.000000000000000000e+00 +5.808491619289222996e+01,3.550176011920677297e+02,1.268826021563594475e+00,5.630222071457342992e+00,2.529317097292942407e-01,2.299064919469925028e-01,6.839316092015533532e-02,-1.000000007175023242e+00,0.000000000000000000e+00 +5.808669232176833219e+01,3.550272830214906890e+02,1.271328456183103528e+00,5.630630415016494084e+00,2.531817097292942131e-01,2.281303630581435760e-01,6.839316092015533532e-02,-1.000000007510956745e+00,0.000000000000000000e+00 +5.808846832183633779e+01,3.550369642250024071e+02,1.273833311181742145e+00,5.631035574556800150e+00,2.534317097292941856e-01,2.263543629767956200e-01,6.839316092015533532e-02,-1.000000007530862156e+00,0.000000000000000000e+00 +5.809024419411908013e+01,3.550466448019978429e+02,1.276340586402956667e+00,5.631437550996088781e+00,2.536817097292941581e-01,2.245784906806779224e-01,6.839316092015533532e-02,-1.000000007028858162e+00,0.000000000000000000e+00 +5.809201993963866784e+01,3.550563247518720118e+02,1.278850281690042445e+00,5.631836345244709996e+00,2.539317097292941305e-01,2.228027451486121746e-01,6.839316092015533532e-02,-1.000000007464207030e+00,0.000000000000000000e+00 +5.809379555941647766e+01,3.550660040740198724e+02,1.281362396886143618e+00,5.632231958205546007e+00,2.541817097292941030e-01,2.210271253575495920e-01,6.839316092015533532e-02,-1.000000007172444638e+00,0.000000000000000000e+00 +5.809557105447318293e+01,3.550756827678364402e+02,1.283876931834252888e+00,5.632624390774015666e+00,2.544317097292940755e-01,2.192516302881117041e-01,6.839316092015533532e-02,-1.000000007280946068e+00,0.000000000000000000e+00 +5.809734642582873931e+01,3.550853608327167876e+02,1.286393886377211970e+00,5.633013643838088669e+00,2.546817097292940479e-01,2.174762589196268803e-01,6.839316092015533532e-02,-1.000000007201797825e+00,0.000000000000000000e+00 +5.809912167450241327e+01,3.550950382680561006e+02,1.288913260357711144e+00,5.633399718278290891e+00,2.549317097292940204e-01,2.157010102331698709e-01,6.839316092015533532e-02,-1.000000007167325178e+00,0.000000000000000000e+00 +5.810089680151276070e+01,3.551047150732495084e+02,1.291435053618289475e+00,5.633782614967715041e+00,2.551817097292939929e-01,2.139258832100994212e-01,6.839316092015533532e-02,-1.000000007385065892e+00,0.000000000000000000e+00 +5.810267180787765540e+01,3.551143912476921969e+02,1.293959266001334818e+00,5.634162334772028657e+00,2.554317097292939653e-01,2.121508768320963245e-01,6.839316092015533532e-02,-1.000000006909973704e+00,0.000000000000000000e+00 +5.810444669461428191e+01,3.551240667907794091e+02,1.296485897349084038e+00,5.634538878549482099e+00,2.556817097292939378e-01,2.103759900832031793e-01,6.839316092015533532e-02,-1.000000007591616891e+00,0.000000000000000000e+00 +5.810622146273915689e+01,3.551337417019064446e+02,1.299014947503622786e+00,5.634912247150920095e+00,2.559317097292939103e-01,2.086012219448581118e-01,6.839316092015533532e-02,-1.000000006743415160e+00,0.000000000000000000e+00 +5.810799611326810776e+01,3.551434159804686033e+02,1.301546416306885279e+00,5.635282441419784405e+00,2.561817097292938827e-01,2.068265714039397019e-01,6.839316092015533532e-02,-1.000000007575917227e+00,0.000000000000000000e+00 +5.810977064721630825e+01,3.551530896258612415e+02,1.304080303600654522e+00,5.635649462192130699e+00,2.564317097292938552e-01,2.050520374422950542e-01,6.839316092015533532e-02,-1.000000006788558382e+00,0.000000000000000000e+00 +5.811154506559827126e+01,3.551627626374797728e+02,1.306616609226562753e+00,5.636013310296626777e+00,2.566817097292938277e-01,2.032776190482887269e-01,6.839316092015533532e-02,-1.000000007261295121e+00,0.000000000000000000e+00 +5.811331936942784893e+01,3.551724350147196105e+02,1.309155333026090995e+00,5.636373986554571225e+00,2.569317097292938001e-01,2.015033152058290922e-01,6.839316092015533532e-02,-1.000000007054329787e+00,0.000000000000000000e+00 +5.811509355971824675e+01,3.551821067569762249e+02,1.311696474840568838e+00,5.636731491779892522e+00,2.571817097292937726e-01,1.997291249029148341e-01,6.839316092015533532e-02,-1.000000007024391735e+00,0.000000000000000000e+00 +5.811686763748203077e+01,3.551917778636451430e+02,1.314240034511175104e+00,5.637085826779163256e+00,2.574317097292937451e-01,1.979550471266668388e-01,6.839316092015533532e-02,-1.000000006875237712e+00,0.000000000000000000e+00 +5.811864160373113464e+01,3.552014483341219488e+02,1.316786011878937179e+00,5.637436992351605447e+00,2.576817097292937175e-01,1.961810808653679516e-01,6.839316092015533532e-02,-1.000000007415318359e+00,0.000000000000000000e+00 +5.812041545947685250e+01,3.552111181678022263e+02,1.319334406784731462e+00,5.637784989289099435e+00,2.579317097292936900e-01,1.944072251064973278e-01,6.839316092015533532e-02,-1.000000006606067027e+00,0.000000000000000000e+00 +5.812218920572986036e+01,3.552207873640816160e+02,1.321885219069283135e+00,5.638129818376189206e+00,2.581817097292936625e-01,1.926334788417747301e-01,6.839316092015533532e-02,-1.000000007183432293e+00,0.000000000000000000e+00 +5.812396284350020892e+01,3.552304559223557590e+02,1.324438448573166616e+00,5.638471480390096602e+00,2.584317097292936349e-01,1.908598410586854477e-01,6.839316092015533532e-02,-1.000000007060256380e+00,0.000000000000000000e+00 +5.812573637379734492e+01,3.552401238420204095e+02,1.326994095136805107e+00,5.638809976100720434e+00,2.586817097292936074e-01,1.890863107490294848e-01,6.839316092015533532e-02,-1.000000006665780372e+00,0.000000000000000000e+00 +5.812750979763010406e+01,3.552497911224712652e+02,1.329552158600470602e+00,5.639145306270650693e+00,2.589317097292935799e-01,1.873128869044521083e-01,6.839316092015533532e-02,-1.000000007252779710e+00,0.000000000000000000e+00 +5.812928311600671805e+01,3.552594577631041943e+02,1.332112638804284099e+00,5.639477471655174767e+00,2.591817097292935523e-01,1.855395685149777429e-01,6.839316092015533532e-02,-1.000000006660875407e+00,0.000000000000000000e+00 +5.813105632993482885e+01,3.552691237633150081e+02,1.334675535588215611e+00,5.639806473002280995e+00,2.594317097292935248e-01,1.837663545750568561e-01,6.839316092015533532e-02,-1.000000006942317832e+00,0.000000000000000000e+00 +5.813282944042148870e+01,3.552787891224995178e+02,1.337240848792084158e+00,5.640132311052672875e+00,2.596817097292934973e-01,1.819932440760897163e-01,6.839316092015533532e-02,-1.000000006735890956e+00,0.000000000000000000e+00 +5.813460244847316005e+01,3.552884538400537053e+02,1.339808578255557769e+00,5.640454986539769955e+00,2.599317097292934697e-01,1.802202360124734726e-01,6.839316092015533532e-02,-1.000000007199060237e+00,0.000000000000000000e+00 +5.813637535509573695e+01,3.552981179153734956e+02,1.342378723818153041e+00,5.640774500189719376e+00,2.601817097292934422e-01,1.784473293771303426e-01,6.839316092015533532e-02,-1.000000006357232962e+00,0.000000000000000000e+00 +5.813814816129454499e+01,3.553077813478549274e+02,1.344951285319236245e+00,5.641090852721399429e+00,2.604317097292934147e-01,1.766745231670547589e-01,6.839316092015533532e-02,-1.000000007016137449e+00,0.000000000000000000e+00 +5.813992086807432713e+01,3.553174441368939824e+02,1.347526262598021995e+00,5.641404044846432875e+00,2.606817097292933871e-01,1.749018163748326249e-01,6.839316092015533532e-02,-1.000000006588164014e+00,0.000000000000000000e+00 +5.814169347643928631e+01,3.553271062818868131e+02,1.350103655493574362e+00,5.641714077269185168e+00,2.609317097292933596e-01,1.731292079981968657e-01,6.839316092015533532e-02,-1.000000006984229195e+00,0.000000000000000000e+00 +5.814346598739305705e+01,3.553367677822294581e+02,1.352683463844806200e+00,5.642020950686779557e+00,2.611817097292933321e-01,1.713566970320468952e-01,6.839316092015533532e-02,-1.000000006416777554e+00,0.000000000000000000e+00 +5.814523840193873383e+01,3.553464286373181267e+02,1.355265687490479598e+00,5.642324665789097971e+00,2.614317097292933045e-01,1.695842824749987654e-01,6.839316092015533532e-02,-1.000000006749926840e+00,0.000000000000000000e+00 +5.814701072107886404e+01,3.553560888465489711e+02,1.357850326269205432e+00,5.642625223258793454e+00,2.616817097292932770e-01,1.678119633229067376e-01,6.839316092015533532e-02,-1.000000006714279577e+00,0.000000000000000000e+00 +5.814878294581546214e+01,3.553657484093182575e+02,1.360437380019443809e+00,5.642922623771291057e+00,2.619317097292932495e-01,1.660397385744114829e-01,6.839316092015533532e-02,-1.000000006430540989e+00,0.000000000000000000e+00 +5.815055507715000971e+01,3.553754073250222518e+02,1.363026848579503847e+00,5.643216867994798491e+00,2.621817097292932219e-01,1.642676072284703637e-01,6.839316092015533532e-02,-1.000000006844550926e+00,0.000000000000000000e+00 +5.815232711608346250e+01,3.553850655930572771e+02,1.365618731787543894e+00,5.643507956590312347e+00,2.624317097292931944e-01,1.624955682828895243e-01,6.839316092015533532e-02,-1.000000006333215952e+00,0.000000000000000000e+00 +5.815409906361625758e+01,3.553947232128196561e+02,1.368213029481571308e+00,5.643795890211621646e+00,2.626817097292931669e-01,1.607236207388704763e-01,6.839316092015533532e-02,-1.000000006644306660e+00,0.000000000000000000e+00 +5.815587092074832753e+01,3.554043801837058254e+02,1.370809741499442236e+00,5.644080669505319392e+00,2.629317097292931393e-01,1.589517635950310481e-01,6.839316092015533532e-02,-1.000000006390700857e+00,0.000000000000000000e+00 +5.815764268847907914e+01,3.554140365051122217e+02,1.373408867678862277e+00,5.644362295110803451e+00,2.631817097292931118e-01,1.571799958529545571e-01,6.839316092015533532e-02,-1.000000006708167577e+00,0.000000000000000000e+00 +5.815941436780743601e+01,3.554236921764353383e+02,1.376010407857386264e+00,5.644640767660287217e+00,2.634317097292930843e-01,1.554083165127138066e-01,6.839316092015533532e-02,-1.000000006162636401e+00,0.000000000000000000e+00 +5.816118595973181016e+01,3.554333471970716687e+02,1.378614361872417593e+00,5.644916087778802272e+00,2.636817097292930567e-01,1.536367245774184487e-01,6.839316092015533532e-02,-1.000000006409635267e+00,0.000000000000000000e+00 +5.816295746525013755e+01,3.554430015664177631e+02,1.381220729561209337e+00,5.645188256084209044e+00,2.639317097292930292e-01,1.518652190477355057e-01,6.839316092015533532e-02,-1.000000006534693675e+00,0.000000000000000000e+00 +5.816472888535986385e+01,3.554526552838702287e+02,1.383829510760863579e+00,5.645457273187197700e+00,2.641817097292930017e-01,1.500937989264367611e-01,6.839316092015533532e-02,-1.000000006166070765e+00,0.000000000000000000e+00 +5.816650022105794449e+01,3.554623083488257294e+02,1.386440705308331189e+00,5.645723139691297021e+00,2.644317097292929741e-01,1.483224632174313662e-01,6.839316092015533532e-02,-1.000000006324255564e+00,0.000000000000000000e+00 +5.816827147334088011e+01,3.554719607606809291e+02,1.389054313040412714e+00,5.645985856192881513e+00,2.646817097292929466e-01,1.465512109232940119e-01,6.839316092015533532e-02,-1.000000006025253629e+00,0.000000000000000000e+00 +5.817004264320469531e+01,3.554816125188326055e+02,1.391670333793757708e+00,5.646245423281174070e+00,2.649317097292929191e-01,1.447800410488098433e-01,6.839316092015533532e-02,-1.000000006526969409e+00,0.000000000000000000e+00 +5.817181373164494573e+01,3.554912636226774794e+02,1.394288767404864959e+00,5.646501841538254851e+00,2.651817097292928915e-01,1.430089525969978348e-01,6.839316092015533532e-02,-1.000000005949806425e+00,0.000000000000000000e+00 +5.817358473965674648e+01,3.555009140716123284e+02,1.396909613710082265e+00,5.646755111539063066e+00,2.654317097292928640e-01,1.412379445746620443e-01,6.839316092015533532e-02,-1.000000006355423077e+00,0.000000000000000000e+00 +5.817535566823475079e+01,3.555105638650340438e+02,1.399532872545606654e+00,5.647005233851408512e+00,2.656817097292928365e-01,1.394670159854056457e-01,6.839316092015533532e-02,-1.000000005818211024e+00,0.000000000000000000e+00 +5.817712651837316429e+01,3.555202130023395171e+02,1.402158543747484387e+00,5.647252209035970694e+00,2.659317097292928089e-01,1.376961658366867569e-01,6.839316092015533532e-02,-1.000000006354484050e+00,0.000000000000000000e+00 +5.817889729106576624e+01,3.555298614829256394e+02,1.404786627151611178e+00,5.647496037646310363e+00,2.661817097292927814e-01,1.359253931328319176e-01,6.839316092015533532e-02,-1.000000005709451578e+00,0.000000000000000000e+00 +5.818066798730589539e+01,3.555395093061894158e+02,1.407417122593731751e+00,5.647736720228868634e+00,2.664317097292927539e-01,1.341546968825938768e-01,6.839316092015533532e-02,-1.000000006137452102e+00,0.000000000000000000e+00 +5.818243860808646417e+01,3.555491564715278514e+02,1.410050029909440283e+00,5.647974257322979419e+00,2.666817097292927263e-01,1.323840760911612902e-01,6.839316092015533532e-02,-1.000000005621068500e+00,0.000000000000000000e+00 +5.818420915439995866e+01,3.555588029783379511e+02,1.412685348934179963e+00,5.648208649460867647e+00,2.669317097292926988e-01,1.306135297677170903e-01,6.839316092015533532e-02,-1.000000006086462889e+00,0.000000000000000000e+00 +5.818597962723845285e+01,3.555684488260168905e+02,1.415323079503243209e+00,5.648439897167660817e+00,2.671817097292926713e-01,1.288430569184502439e-01,6.839316092015533532e-02,-1.000000006037183420e+00,0.000000000000000000e+00 +5.818775002759360149e+01,3.555780940139617314e+02,1.417963221451772116e+00,5.648668000961388103e+00,2.674317097292926437e-01,1.270726565526100749e-01,6.839316092015533532e-02,-1.000000005370718981e+00,0.000000000000000000e+00 +5.818952035645666854e+01,3.555877385415697063e+02,1.420605774614757566e+00,5.648892961352990127e+00,2.676817097292926162e-01,1.253023276800324659e-01,6.839316092015533532e-02,-1.000000005945854253e+00,0.000000000000000000e+00 +5.819129061481851295e+01,3.555973824082379906e+02,1.423250738827040118e+00,5.649114778846324292e+00,2.679317097292925887e-01,1.235320693076622095e-01,6.839316092015533532e-02,-1.000000005631313194e+00,0.000000000000000000e+00 +5.819306080366959577e+01,3.556070256133638736e+02,1.425898113923309563e+00,5.649333453938163885e+00,2.681817097292925611e-01,1.217618804466110705e-01,6.839316092015533532e-02,-1.000000005390583313e+00,0.000000000000000000e+00 +5.819483092399999435e+01,3.556166681563446446e+02,1.428547899738104920e+00,5.649548987118209631e+00,2.684317097292925336e-01,1.199917601066734785e-01,6.839316092015533532e-02,-1.000000005881608534e+00,0.000000000000000000e+00 +5.819660097679939526e+01,3.556263100365776495e+02,1.431200096105814445e+00,5.649761378869091466e+00,2.686817097292925061e-01,1.182217072968620164e-01,6.839316092015533532e-02,-1.000000005188485863e+00,0.000000000000000000e+00 +5.819837096305711555e+01,3.556359512534602345e+02,1.433854702860676067e+00,5.649970629666371202e+00,2.689317097292924785e-01,1.164517210299576694e-01,6.839316092015533532e-02,-1.000000005625171662e+00,0.000000000000000000e+00 +5.820014088376210282e+01,3.556455918063898594e+02,1.436511719836776724e+00,5.650176739978553186e+00,2.691817097292924510e-01,1.146818003150172072e-01,6.839316092015533532e-02,-1.000000005230806455e+00,0.000000000000000000e+00 +5.820191073990292807e+01,3.556552316947639838e+02,1.439171146868052809e+00,5.650379710267081634e+00,2.694317097292924235e-01,1.129119441649340111e-01,6.839316092015533532e-02,-1.000000005424295901e+00,0.000000000000000000e+00 +5.820368053246781415e+01,3.556648709179801244e+02,1.441832983788290168e+00,5.650579540986351290e+00,2.696817097292923959e-01,1.111421515904505025e-01,6.839316092015533532e-02,-1.000000005050435847e+00,0.000000000000000000e+00 +5.820545026244462150e+01,3.556745094754357979e+02,1.444497230431124102e+00,5.650776232583707426e+00,2.699317097292923684e-01,1.093724216047084058e-01,6.839316092015533532e-02,-1.000000005200188724e+00,0.000000000000000000e+00 +5.820721993082086243e+01,3.556841473665285775e+02,1.447163886630039142e+00,5.650969785499453835e+00,2.701817097292923409e-01,1.076027532192679187e-01,6.839316092015533532e-02,-1.000000005240829770e+00,0.000000000000000000e+00 +5.820898953858370106e+01,3.556937845906561506e+02,1.449832952218369275e+00,5.651160200166853720e+00,2.704317097292923133e-01,1.058331454471526656e-01,6.839316092015533532e-02,-1.000000005084497490e+00,0.000000000000000000e+00 +5.821075908671997468e+01,3.557034211472162042e+02,1.452504427029297940e+00,5.651347477012135911e+00,2.706817097292922858e-01,1.040635973018798205e-01,6.839316092015533532e-02,-1.000000004621075078e+00,0.000000000000000000e+00 +5.821252857621618659e+01,3.557130570356063686e+02,1.455178310895858029e+00,5.651531616454499307e+00,2.709317097292922583e-01,1.022941077974939134e-01,6.839316092015533532e-02,-1.000000005136664649e+00,0.000000000000000000e+00 +5.821429800805849908e+01,3.557226922552245014e+02,1.457854603650931669e+00,5.651712618906117314e+00,2.711817097292922307e-01,1.005246759460907413e-01,6.839316092015533532e-02,-1.000000004774866058e+00,0.000000000000000000e+00 +5.821606738323276886e+01,3.557323268054683467e+02,1.460533305127250658e+00,5.651890484772137846e+00,2.714317097292922032e-01,9.875530076337238339e-02,6.839316092015533532e-02,-1.000000004777534368e+00,0.000000000000000000e+00 +5.821783670272452582e+01,3.557419606857357053e+02,1.463214415157396031e+00,5.652065214450693098e+00,2.716817097292921757e-01,9.698598126315943757e-02,6.839316092015533532e-02,-1.000000004378555962e+00,0.000000000000000000e+00 +5.821960596751900141e+01,3.557515938954245485e+02,1.465897933573798495e+00,5.652236808332899543e+00,2.719317097292921481e-01,9.521671646093839148e-02,6.839316092015533532e-02,-1.000000004775917883e+00,0.000000000000000000e+00 +5.822137517860110734e+01,3.557612264339327339e+02,1.468583860208737990e+00,5.652405266802864148e+00,2.721817097292921206e-01,9.344750537038101768e-02,6.839316092015533532e-02,-1.000000004308052137e+00,0.000000000000000000e+00 +5.822314433695547109e+01,3.557708583006582330e+02,1.471272194894344354e+00,5.652570590237684378e+00,2.724317097292920931e-01,9.167834700839810891e-02,6.839316092015533532e-02,-1.000000004128874798e+00,0.000000000000000000e+00 +5.822491344356641463e+01,3.557804894949990739e+02,1.473962937462596434e+00,5.652732779007457076e+00,2.726817097292920655e-01,8.990924039015271707e-02,6.839316092015533532e-02,-1.000000004519157493e+00,0.000000000000000000e+00 +5.822668249941797569e+01,3.557901200163533417e+02,1.476656087745322976e+00,5.652891833475278460e+00,2.729317097292920380e-01,8.814018453059951907e-02,6.839316092015533532e-02,-1.000000004034852452e+00,0.000000000000000000e+00 +5.822845150549390780e+01,3.557997498641190646e+02,1.479351645574202179e+00,5.653047753997246794e+00,2.731817097292920105e-01,8.637117844753057494e-02,6.839316092015533532e-02,-1.000000004047936208e+00,0.000000000000000000e+00 +5.823022046277768737e+01,3.558093790376944412e+02,1.482049610780761473e+00,5.653200540922470374e+00,2.734317097292919829e-01,8.460222115658810882e-02,6.839316092015533532e-02,-1.000000003921845959e+00,0.000000000000000000e+00 +5.823198937225252791e+01,3.558190075364775566e+02,1.484749983196378187e+00,5.653350194593066647e+00,2.736817097292919554e-01,8.283331167481219892e-02,6.839316092015533532e-02,-1.000000003565703732e+00,0.000000000000000000e+00 +5.823375823490136582e+01,3.558286353598667233e+02,1.487452762652278881e+00,5.653496715344167534e+00,2.739317097292919279e-01,8.106444901966991523e-02,6.839316092015533532e-02,-1.000000004002209453e+00,0.000000000000000000e+00 +5.823552705170687460e+01,3.558382625072601400e+02,1.490157948979540015e+00,5.653640103503922987e+00,2.741817097292919003e-01,7.929563220708009397e-02,6.839316092015533532e-02,-1.000000003393510584e+00,0.000000000000000000e+00 +5.823729582365148616e+01,3.558478889780561190e+02,1.492865542009087276e+00,5.653780359393500987e+00,2.744317097292918728e-01,7.752686025646769730e-02,6.839316092015533532e-02,-1.000000003286368955e+00,0.000000000000000000e+00 +5.823906455171736951e+01,3.558575147716530296e+02,1.495575541571696254e+00,5.653917483327096427e+00,2.746817097292918453e-01,7.575813218477153721e-02,6.839316092015533532e-02,-1.000000003218671996e+00,0.000000000000000000e+00 +5.824083323688645919e+01,3.558671398874492411e+02,1.498287947497991990e+00,5.654051475611929334e+00,2.749317097292918177e-01,7.398944700999213198e-02,6.839316092015533532e-02,-1.000000003274196470e+00,0.000000000000000000e+00 +5.824260188014044104e+01,3.558767643248432364e+02,1.501002759618448978e+00,5.654182336548249310e+00,2.751817097292917902e-01,7.222080375022066345e-02,6.839316092015533532e-02,-1.000000002663159027e+00,0.000000000000000000e+00 +5.824437048246077353e+01,3.558863880832334416e+02,1.503719977763391391e+00,5.654310066429338200e+00,2.754317097292917627e-01,7.045220142517849560e-02,6.839316092015533532e-02,-1.000000003129493109e+00,0.000000000000000000e+00 +5.824613904482868776e+01,3.558960111620183397e+02,1.506439601762993297e+00,5.654434665541515415e+00,2.756817097292917351e-01,6.868363905173054118e-02,6.839316092015533532e-02,-1.000000002420067258e+00,0.000000000000000000e+00 +5.824790756822518745e+01,3.559056335605965273e+02,1.509161631447278218e+00,5.654556134164135273e+00,2.759317097292917076e-01,6.691511565094897251e-02,6.839316092015533532e-02,-1.000000002235450269e+00,0.000000000000000000e+00 +5.824967605363107026e+01,3.559152552783666010e+02,1.511886066646119131e+00,5.654674472569596766e+00,2.761817097292916801e-01,6.514663024111534695e-02,6.839316092015533532e-02,-1.000000002550780698e+00,0.000000000000000000e+00 +5.825144450202690649e+01,3.559248763147272143e+02,1.514612907189238911e+00,5.654789681023340897e+00,2.764317097292916525e-01,6.337818184076673966e-02,6.839316092015533532e-02,-1.000000001615473755e+00,0.000000000000000000e+00 +5.825321291439307458e+01,3.559344966690770775e+02,1.517342152906210107e+00,5.654901759783853343e+00,2.766817097292916250e-01,6.160976947174207075e-02,6.839316092015533532e-02,-1.000000001917260573e+00,0.000000000000000000e+00 +5.825498129170974693e+01,3.559441163408148441e+02,1.520073803626454723e+00,5.655010709102672450e+00,2.769317097292915975e-01,5.984139215168145925e-02,6.839316092015533532e-02,-1.000000001662171956e+00,0.000000000000000000e+00 +5.825674963495689695e+01,3.559537353293393380e+02,1.522807859179244661e+00,5.655116529224383903e+00,2.771817097292915699e-01,5.807304890159263600e-02,6.839316092015533532e-02,-1.000000001306629915e+00,0.000000000000000000e+00 +5.825851794511431336e+01,3.559633536340493265e+02,1.525544319393701276e+00,5.655219220386628720e+00,2.774317097292915424e-01,5.630473874186586042e-02,6.839316092015533532e-02,-1.000000001001448258e+00,0.000000000000000000e+00 +5.826028622316160011e+01,3.559729712543437472e+02,1.528283184098796044e+00,5.655318782820104140e+00,2.776817097292915149e-01,5.453646069280893710e-02,6.839316092015533532e-02,-1.000000000875876038e+00,0.000000000000000000e+00 +5.826205447007818350e+01,3.559825881896214241e+02,1.531024453123349893e+00,5.655415216748565399e+00,2.779317097292914873e-01,5.276821377467992569e-02,6.839316092015533532e-02,-1.000000000185335081e+00,0.000000000000000000e+00 +5.826382268684331223e+01,3.559922044392812950e+02,1.533768126296033429e+00,5.655508522388827508e+00,2.781817097292914598e-01,5.099999700922683288e-02,6.839316092015533532e-02,-1.000000000152154511e+00,0.000000000000000000e+00 +5.826559087443606444e+01,3.560018200027224111e+02,1.536514203445367155e+00,5.655598699950769692e+00,2.784317097292914323e-01,4.923180941620422524e-02,6.839316092015533532e-02,-9.999999999886396429e-01,0.000000000000000000e+00 +5.826735903383536908e+01,3.560114348793437671e+02,1.539262684399721248e+00,5.655685749637333615e+00,2.786817097292914047e-01,4.746365001692198077e-02,6.839316092015533532e-02,-9.999999994535989645e-01,0.000000000000000000e+00 +5.826912716601998454e+01,3.560210490685444142e+02,1.542013568987315564e+00,5.655769671644527818e+00,2.789317097292913772e-01,4.569551783327347599e-02,6.839316092015533532e-02,-9.999999988525096750e-01,0.000000000000000000e+00 +5.827089527196852003e+01,3.560306625697234608e+02,1.544766857036219854e+00,5.655850466161430390e+00,2.791817097292913497e-01,4.392741188676356490e-02,6.839316092015533532e-02,-9.999999987534659018e-01,0.000000000000000000e+00 +5.827266335265944974e+01,3.560402753822800719e+02,1.547522548374353546e+00,5.655928133370189848e+00,2.794317097292913221e-01,4.215933119803885742e-02,6.839316092015533532e-02,-9.999999979983796861e-01,0.000000000000000000e+00 +5.827443140907109154e+01,3.560498875056134693e+02,1.550280642829485966e+00,5.656002673446025142e+00,2.796817097292912946e-01,4.039127478993433801e-02,6.839316092015533532e-02,-9.999999973964300848e-01,0.000000000000000000e+00 +5.827619944218164250e+01,3.560594989391228751e+02,1.553041140229236339e+00,5.656074086557230984e+00,2.799317097292912671e-01,3.862324168398963836e-02,6.839316092015533532e-02,-9.999999974512705503e-01,0.000000000000000000e+00 +5.827796745296915759e+01,3.560691096822075679e+02,1.555804040401073562e+00,5.656142372865176959e+00,2.801817097292912395e-01,3.685523090098386662e-02,6.839316092015533532e-02,-9.999999960877949956e-01,0.000000000000000000e+00 +5.827973544241157100e+01,3.560787197342669401e+02,1.558569343172316213e+00,5.656207532524307524e+00,2.804317097292912120e-01,3.508724146548945072e-02,6.839316092015533532e-02,-9.999999957556552355e-01,0.000000000000000000e+00 +5.828150341148669611e+01,3.560883290947002706e+02,1.561337048370132985e+00,5.656269565682150002e+00,2.806817097292911845e-01,3.331927239786691697e-02,6.839316092015533532e-02,-9.999999949050720760e-01,0.000000000000000000e+00 +5.828327136117223972e+01,3.560979377629070086e+02,1.564107155821542250e+00,5.656328472479308367e+00,2.809317097292911569e-01,3.155132272133046728e-02,6.839316092015533532e-02,-9.999999942379705908e-01,0.000000000000000000e+00 +5.828503929244579496e+01,3.561075457382866603e+02,1.566879665353412276e+00,5.656384253049469457e+00,2.811817097292911294e-01,2.978339145796158813e-02,6.839316092015533532e-02,-9.999999930140444082e-01,0.000000000000000000e+00 +5.828680720628485545e+01,3.561171530202386748e+02,1.569654576792461453e+00,5.656436907519402091e+00,2.814317097292911019e-01,2.801547763125343191e-02,6.839316092015533532e-02,-9.999999921765466704e-01,0.000000000000000000e+00 +5.828857510366680827e+01,3.561267596081626152e+02,1.572431889965257623e+00,5.656486436008960617e+00,2.816817097292910743e-01,2.624758026312899728e-02,6.839316092015533532e-02,-9.999999906581055198e-01,0.000000000000000000e+00 +5.829034298556896232e+01,3.561363655014580445e+02,1.575211604698218526e+00,5.656532838631083138e+00,2.819317097292910468e-01,2.447969837749033178e-02,6.839316092015533532e-02,-9.999999893591559053e-01,0.000000000000000000e+00 +5.829211085296852701e+01,3.561459706995246393e+02,1.577993720817612244e+00,5.656576115491795953e+00,2.821817097292910193e-01,2.271183099673423911e-02,6.839316092015533532e-02,-9.999999877378290547e-01,0.000000000000000000e+00 +5.829387870684264072e+01,3.561555752017620193e+02,1.580778238149556536e+00,5.656616266690211781e+00,2.824317097292909917e-01,2.094397714429670904e-02,6.839316092015533532e-02,-9.999999857992090124e-01,0.000000000000000000e+00 +5.829564654816836367e+01,3.561651790075699751e+02,1.583565156520019057e+00,5.656653292318532422e+00,2.826817097292909642e-01,1.917613584368055984e-02,6.839316092015533532e-02,-9.999999832427671764e-01,0.000000000000000000e+00 +5.829741437792267789e+01,3.561747821163481831e+02,1.586354475754817361e+00,5.656687192462049651e+00,2.829317097292909367e-01,1.740830611899030905e-02,6.839316092015533532e-02,-9.999999803149849376e-01,0.000000000000000000e+00 +5.829918219708250859e+01,3.561843845274964906e+02,1.589146195679618900e+00,5.656717967199146990e+00,2.831817097292909091e-01,1.564048699395974643e-02,6.839316092015533532e-02,-9.999999766725566896e-01,0.000000000000000000e+00 +5.830095000662471705e+01,3.561939862404147448e+02,1.591940316119941246e+00,5.656745616601299709e+00,2.834317097292908816e-01,1.387267749298917892e-02,6.839316092015533532e-02,-9.999999722349880438e-01,0.000000000000000000e+00 +5.830271780752611477e+01,3.562035872545028496e+02,1.594736836901151866e+00,5.656770140733076602e+00,2.836817097292908540e-01,1.210487664067542296e-02,6.839316092015533532e-02,-9.999999660477787433e-01,0.000000000000000000e+00 +5.830448560076345643e+01,3.562131875691607661e+02,1.597535757848468352e+00,5.656791539652140877e+00,2.839317097292908265e-01,1.033708346335147042e-02,6.839316092015533532e-02,-9.999999568508199932e-01,0.000000000000000000e+00 +5.830625338731346829e+01,3.562227871837883981e+02,1.600337078786957967e+00,5.656809813409253707e+00,2.841817097292907990e-01,8.569296989621321206e-03,6.839316092015533532e-02,-9.999999442152458506e-01,0.000000000000000000e+00 +5.830802116815281977e+01,3.562323860977858203e+02,1.603140799541538319e+00,5.656824962048278671e+00,2.844317097292907714e-01,6.801516248885113546e-03,6.839316092015533532e-02,-9.999999220065629579e-01,0.000000000000000000e+00 +5.830978894425815895e+01,3.562419843105531072e+02,1.605946919936976691e+00,5.656836985606183532e+00,2.846817097292907439e-01,5.033740281420012383e-03,6.839316092015533532e-02,-9.999998786687338548e-01,0.000000000000000000e+00 +5.831155671660610551e+01,3.562515818214903902e+02,1.608755439797890707e+00,5.656845884113059775e+00,2.849317097292907164e-01,3.265968147958799462e-03,6.839316092015533532e-02,-9.999997474863293601e-01,0.000000000000000000e+00 +5.831332448617325781e+01,3.562611786299977439e+02,1.611566358948747668e+00,5.656851657592159022e+00,2.851817097292906888e-01,1.498199027193509352e-03,6.839316092015533532e-02,-8.475796472399770298e-01,0.000000000000000000e+00 +5.831509225393619289e+01,3.562707747354754702e+02,1.614379677213865216e+00,5.656854306060101756e+00,2.854317097292906613e-01,-1.249497176150875558e-07,6.839316092015533532e-02,7.074817318038487590e-05,0.000000000000000000e+00 +5.831686002087148069e+01,3.562803701373237573e+02,1.617195394417411114e+00,5.656854305839219776e+00,2.856817097292906338e-01,1.165636652937517381e-10,6.839316092015533532e-02,-6.593836719213610888e-08,0.000000000000000000e+00 +5.831862778780683954e+01,3.562899648349428503e+02,1.620013510383402799e+00,5.656854305839425834e+00,2.859317097292906062e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.832039555474219839e+01,3.562995588277331649e+02,1.622834024935708275e+00,5.656854305839425834e+00,2.861817097292905787e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.832216332167755724e+01,3.563091521150950030e+02,1.625656937898045218e+00,5.656854305839425834e+00,2.864317097292905512e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.832393108861291608e+01,3.563187446964288370e+02,1.628482249093981649e+00,5.656854305839425834e+00,2.866817097292905236e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.832569885554827493e+01,3.563283365711350825e+02,1.631309958346935485e+00,5.656854305839425834e+00,2.869317097292904961e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.832746662248363378e+01,3.563379277386143258e+02,1.634140065480174986e+00,5.656854305839425834e+00,2.871817097292904686e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.832923438941899263e+01,3.563475181982670392e+02,1.636972570316818532e+00,5.656854305839425834e+00,2.874317097292904410e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.833100215635435148e+01,3.563571079494938658e+02,1.639807472679834621e+00,5.656854305839425834e+00,2.876817097292904135e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.833276992328971033e+01,3.563666969916953917e+02,1.642644772392041652e+00,5.656854305839425834e+00,2.879317097292903860e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.833453769022506918e+01,3.563762853242723736e+02,1.645484469276108364e+00,5.656854305839425834e+00,2.881817097292903584e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.833630545716042803e+01,3.563858729466255113e+02,1.648326563154553837e+00,5.656854305839425834e+00,2.884317097292903309e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.833807322409578688e+01,3.563954598581555615e+02,1.651171053849747272e+00,5.656854305839425834e+00,2.886817097292903034e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.833984099103114573e+01,3.564050460582633377e+02,1.654017941183907991e+00,5.656854305839425834e+00,2.889317097292902758e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.834160875796650458e+01,3.564146315463497103e+02,1.656867224979105435e+00,5.656854305839425834e+00,2.891817097292902483e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.834337652490186343e+01,3.564242163218156065e+02,1.659718905057259386e+00,5.656854305839425834e+00,2.894317097292902208e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.834514429183722228e+01,3.564338003840619535e+02,1.662572981240139747e+00,5.656854305839425834e+00,2.896817097292901932e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.834691205877258113e+01,3.564433837324897922e+02,1.665429453349366984e+00,5.656854305839425834e+00,2.899317097292901657e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.834867982570793998e+01,3.564529663665001067e+02,1.668288321206411462e+00,5.656854305839425834e+00,2.901817097292901382e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.835044759264329883e+01,3.564625482854940515e+02,1.671149584632593887e+00,5.656854305839425834e+00,2.904317097292901106e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.835221535957865768e+01,3.564721294888726675e+02,1.674013243449085309e+00,5.656854305839425834e+00,2.906817097292900831e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.835398312651401653e+01,3.564817099760371661e+02,1.676879297476907116e+00,5.656854305839425834e+00,2.909317097292900556e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.835575089344937538e+01,3.564912897463888157e+02,1.679747746536931041e+00,5.656854305839425834e+00,2.911817097292900280e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.835751866038473423e+01,3.565008687993288277e+02,1.682618590449878715e+00,5.656854305839425834e+00,2.914317097292900005e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.835928642732009308e+01,3.565104471342585271e+02,1.685491829036322775e+00,5.656854305839425834e+00,2.916817097292899730e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.836105419425545193e+01,3.565200247505792390e+02,1.688367462116685536e+00,5.656854305839425834e+00,2.919317097292899454e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.836282196119081078e+01,3.565296016476924024e+02,1.691245489511239875e+00,5.656854305839425834e+00,2.921817097292899179e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.836458972812616963e+01,3.565391778249994559e+02,1.694125911040109234e+00,5.656854305839425834e+00,2.924317097292898904e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.836635749506152848e+01,3.565487532819018952e+02,1.697008726523267397e+00,5.656854305839425834e+00,2.926817097292898628e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.836812526199688733e+01,3.565583280178012160e+02,1.699893935780538268e+00,5.656854305839425834e+00,2.929317097292898353e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.836989302893224618e+01,3.565679020320990276e+02,1.702781538631596092e+00,5.656854305839425834e+00,2.931817097292898078e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.837166079586760503e+01,3.565774753241969393e+02,1.705671534895965902e+00,5.656854305839425834e+00,2.934317097292897802e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.837342856280296388e+01,3.565870478934966172e+02,1.708563924393022848e+00,5.656854305839425834e+00,2.936817097292897527e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.837519632973832273e+01,3.565966197393997845e+02,1.711458706941992647e+00,5.656854305839425834e+00,2.939317097292897252e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.837696409667368158e+01,3.566061908613082210e+02,1.714355882361951355e+00,5.656854305839425834e+00,2.941817097292896976e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.837873186360904043e+01,3.566157612586237065e+02,1.717255450471825595e+00,5.656854305839425834e+00,2.944317097292896701e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.838049963054439928e+01,3.566253309307480777e+02,1.720157411090392108e+00,5.656854305839425834e+00,2.946817097292896426e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.838226739747975813e+01,3.566348998770832850e+02,1.723061764036278642e+00,5.656854305839425834e+00,2.949317097292896150e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.838403516441511698e+01,3.566444680970312220e+02,1.725968509127963069e+00,5.656854305839425834e+00,2.951817097292895875e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.838580293135047583e+01,3.566540355899938959e+02,1.728877646183773820e+00,5.656854305839425834e+00,2.954317097292895600e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.838757069828583468e+01,3.566636023553733139e+02,1.731789175021889671e+00,5.656854305839425834e+00,2.956817097292895324e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.838933846522119353e+01,3.566731683925715402e+02,1.734703095460340183e+00,5.656854305839425834e+00,2.959317097292895049e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.839110623215655238e+01,3.566827337009907524e+02,1.737619407317005260e+00,5.656854305839425834e+00,2.961817097292894774e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.839287399909191123e+01,3.566922982800330715e+02,1.740538110409615591e+00,5.656854305839425834e+00,2.964317097292894498e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.839464176602727008e+01,3.567018621291007321e+02,1.743459204555752207e+00,5.656854305839425834e+00,2.966817097292894223e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.839640953296262893e+01,3.567114252475960257e+02,1.746382689572846481e+00,5.656854305839425834e+00,2.969317097292893948e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.839817729989798778e+01,3.567209876349211868e+02,1.749308565278180794e+00,5.656854305839425834e+00,2.971817097292893672e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.839994506683334663e+01,3.567305492904786206e+02,1.752236831488887869e+00,5.656854305839425834e+00,2.974317097292893397e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.840171283376870548e+01,3.567401102136707323e+02,1.755167488021951216e+00,5.656854305839425834e+00,2.976817097292893122e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.840348060070406433e+01,3.567496704038999269e+02,1.758100534694204686e+00,5.656854305839425834e+00,2.979317097292892846e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.840524836763942318e+01,3.567592298605687233e+02,1.761035971322332694e+00,5.656854305839425834e+00,2.981817097292892571e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.840701613457478203e+01,3.567687885830796404e+02,1.763973797722870662e+00,5.656854305839425834e+00,2.984317097292892296e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.840878390151014088e+01,3.567783465708352537e+02,1.766914013712204357e+00,5.656854305839425834e+00,2.986817097292892020e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.841055166844549973e+01,3.567879038232381959e+02,1.769856619106570328e+00,5.656854305839425834e+00,2.989317097292891745e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.841231943538085858e+01,3.567974603396910993e+02,1.772801613722055691e+00,5.656854305839425834e+00,2.991817097292891470e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.841408720231621743e+01,3.568070161195967103e+02,1.775748997374598348e+00,5.656854305839425834e+00,2.994317097292891194e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.841585496925157628e+01,3.568165711623578318e+02,1.778698769879986763e+00,5.656854305839425834e+00,2.996817097292890919e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.841762273618693513e+01,3.568261254673772100e+02,1.781650931053860187e+00,5.656854305839425834e+00,2.999317097292890644e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.841939050312229398e+01,3.568356790340577618e+02,1.784605480711708658e+00,5.656854305839425834e+00,3.001817097292890368e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.842115827005765283e+01,3.568452318618023469e+02,1.787562418668872555e+00,5.656854305839425834e+00,3.004317097292890093e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.842292603699301168e+01,3.568547839500139389e+02,1.790521744740543486e+00,5.656854305839425834e+00,3.006817097292889818e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.842469380392837053e+01,3.568643352980955115e+02,1.793483458741763403e+00,5.656854305839425834e+00,3.009317097292889542e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.842646157086372938e+01,3.568738859054500949e+02,1.796447560487425266e+00,5.656854305839425834e+00,3.011817097292889267e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.842822933779908823e+01,3.568834357714807766e+02,1.799414049792272818e+00,5.656854305839425834e+00,3.014317097292888992e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.842999710473444708e+01,3.568929848955907005e+02,1.802382926470900371e+00,5.656854305839425834e+00,3.016817097292888716e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.843176487166980593e+01,3.569025332771830676e+02,1.805354190337753240e+00,5.656854305839425834e+00,3.019317097292888441e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.843353263860516478e+01,3.569120809156610790e+02,1.808327841207127307e+00,5.656854305839425834e+00,3.021817097292888166e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.843530040554052363e+01,3.569216278104280491e+02,1.811303878893169461e+00,5.656854305839425834e+00,3.024317097292887890e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.843706817247588248e+01,3.569311739608872358e+02,1.814282303209877156e+00,5.656854305839425834e+00,3.026817097292887615e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.843883593941124133e+01,3.569407193664420674e+02,1.817263113971099076e+00,5.656854305839425834e+00,3.029317097292887340e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.844060370634660018e+01,3.569502640264959155e+02,1.820246310990534466e+00,5.656854305839425834e+00,3.031817097292887064e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.844237147328195903e+01,3.569598079404522082e+02,1.823231894081733584e+00,5.656854305839425834e+00,3.034317097292886789e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.844413924021731788e+01,3.569693511077144876e+02,1.826219863058097470e+00,5.656854305839425834e+00,3.036817097292886514e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.844590700715267673e+01,3.569788935276863526e+02,1.829210217732878174e+00,5.656854305839425834e+00,3.039317097292886238e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.844767477408803558e+01,3.569884351997713452e+02,1.832202957919178310e+00,5.656854305839425834e+00,3.041817097292885963e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.844944254102339443e+01,3.569979761233731210e+02,1.835198083429951721e+00,5.656854305839425834e+00,3.044317097292885688e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.845121030795875328e+01,3.570075162978953358e+02,1.838195594078003037e+00,5.656854305839425834e+00,3.046817097292885412e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.845297807489411213e+01,3.570170557227418158e+02,1.841195489675987895e+00,5.656854305839425834e+00,3.049317097292885137e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.845474584182947098e+01,3.570265943973162734e+02,1.844197770036412720e+00,5.656854305839425834e+00,3.051817097292884862e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.845651360876482983e+01,3.570361323210225919e+02,1.847202434971635165e+00,5.656854305839425834e+00,3.054317097292884586e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.845828137570018868e+01,3.570456694932645973e+02,1.850209484293863449e+00,5.656854305839425834e+00,3.056817097292884311e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.846004914263554753e+01,3.570552059134462297e+02,1.853218917815157241e+00,5.656854305839425834e+00,3.059317097292884036e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.846181690957090638e+01,3.570647415809714857e+02,1.856230735347426775e+00,5.656854305839425834e+00,3.061817097292883760e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.846358467650626523e+01,3.570742764952443622e+02,1.859244936702433515e+00,5.656854305839425834e+00,3.064317097292883485e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.846535244344162408e+01,3.570838106556689695e+02,1.862261521691789712e+00,5.656854305839425834e+00,3.066817097292883210e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.846712021037698293e+01,3.570933440616493613e+02,1.865280490126959068e+00,5.656854305839425834e+00,3.069317097292882934e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.846888797731234177e+01,3.571028767125897616e+02,1.868301841819255849e+00,5.656854305839425834e+00,3.071817097292882659e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.847065574424770062e+01,3.571124086078943378e+02,1.871325576579845773e+00,5.656854305839425834e+00,3.074317097292882384e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.847242351118305947e+01,3.571219397469673709e+02,1.874351694219745346e+00,5.656854305839425834e+00,3.076817097292882108e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.847419127811841832e+01,3.571314701292131417e+02,1.877380194549822079e+00,5.656854305839425834e+00,3.079317097292881833e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.847595904505377717e+01,3.571409997540360450e+02,1.880411077380794715e+00,5.656854305839425834e+00,3.081817097292881558e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.847772681198913602e+01,3.571505286208404186e+02,1.883444342523233228e+00,5.656854305839425834e+00,3.084317097292881282e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.847949457892449487e+01,3.571600567290307708e+02,1.886479989787558598e+00,5.656854305839425834e+00,3.086817097292881007e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.848126234585985372e+01,3.571695840780115532e+02,1.889518018984042591e+00,5.656854305839425834e+00,3.089317097292880732e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.848303011279521257e+01,3.571791106671872740e+02,1.892558429922808649e+00,5.656854305839425834e+00,3.091817097292880456e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.848479787973057142e+01,3.571886364959626121e+02,1.895601222413831000e+00,5.656854305839425834e+00,3.094317097292880181e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.848656564666593027e+01,3.571981615637421328e+02,1.898646396266935099e+00,5.656854305839425834e+00,3.096817097292879906e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.848833341360128912e+01,3.572076858699305149e+02,1.901693951291797635e+00,5.656854305839425834e+00,3.099317097292879630e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.849010118053664797e+01,3.572172094139325509e+02,1.904743887297946303e+00,5.656854305839425834e+00,3.101817097292879355e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.849186894747200682e+01,3.572267321951529766e+02,1.907796204094760251e+00,5.656854305839425834e+00,3.104317097292879080e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.849363671440736567e+01,3.572362542129966414e+02,1.910850901491469633e+00,5.656854305839425834e+00,3.106817097292878804e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.849540448134272452e+01,3.572457754668683947e+02,1.913907979297155837e+00,5.656854305839425834e+00,3.109317097292878529e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.849717224827808337e+01,3.572552959561731427e+02,1.916967437320751477e+00,5.656854305839425834e+00,3.111817097292878254e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.849894001521344222e+01,3.572648156803159054e+02,1.920029275371040400e+00,5.656854305839425834e+00,3.114317097292877978e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.850070778214880107e+01,3.572743346387016459e+02,1.923093493256657682e+00,5.656854305839425834e+00,3.116817097292877703e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.850247554908415992e+01,3.572838528307354409e+02,1.926160090786089851e+00,5.656854305839425834e+00,3.119317097292877428e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.850424331601951877e+01,3.572933702558224240e+02,1.929229067767674444e+00,5.656854305839425834e+00,3.121817097292877152e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.850601108295487762e+01,3.573028869133677858e+02,1.932300424009600670e+00,5.656854305839425834e+00,3.124317097292876877e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.850777884989023647e+01,3.573124028027766599e+02,1.935374159319908527e+00,5.656854305839425834e+00,3.126817097292876602e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.850954661682559532e+01,3.573219179234543503e+02,1.938450273506489463e+00,5.656854305839425834e+00,3.129317097292876326e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.851131438376095417e+01,3.573314322748061613e+02,1.941528766377086601e+00,5.656854305839425834e+00,3.131817097292876051e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.851308215069631302e+01,3.573409458562374539e+02,1.944609637739293850e+00,5.656854305839425834e+00,3.134317097292875776e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.851484991763167187e+01,3.573504586671535890e+02,1.947692887400557016e+00,5.656854305839425834e+00,3.136817097292875500e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.851661768456703072e+01,3.573599707069600413e+02,1.950778515168172911e+00,5.656854305839425834e+00,3.139317097292875225e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.851838545150238957e+01,3.573694819750623424e+02,1.953866520849289801e+00,5.656854305839425834e+00,3.141817097292874950e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.852015321843774842e+01,3.573789924708659669e+02,1.956956904250907181e+00,5.656854305839425834e+00,3.144317097292874674e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.852192098537310727e+01,3.573885021937765600e+02,1.960049665179876222e+00,5.656854305839425834e+00,3.146817097292874399e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.852368875230846612e+01,3.573980111431997670e+02,1.963144803442899544e+00,5.656854305839425834e+00,3.149317097292874124e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.852545651924382497e+01,3.574075193185412331e+02,1.966242318846530779e+00,5.656854305839425834e+00,3.151817097292873848e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.852722428617918382e+01,3.574170267192067172e+02,1.969342211197175230e+00,5.656854305839425834e+00,3.154317097292873573e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.852899205311454267e+01,3.574265333446020350e+02,1.972444480301089653e+00,5.656854305839425834e+00,3.156817097292873298e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.853075982004990152e+01,3.574360391941330022e+02,1.975549125964382258e+00,5.656854305839425834e+00,3.159317097292873022e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.853252758698526037e+01,3.574455442672054915e+02,1.978656147993012704e+00,5.656854305839425834e+00,3.161817097292872747e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.853429535392061922e+01,3.574550485632254890e+02,1.981765546192792105e+00,5.656854305839425834e+00,3.164317097292872472e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.853606312085597807e+01,3.574645520815989244e+02,1.984877320369383025e+00,5.656854305839425834e+00,3.166817097292872196e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.853783088779133692e+01,3.574740548217318405e+02,1.987991470328299481e+00,5.656854305839425834e+00,3.169317097292871921e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.853959865472669577e+01,3.574835567830302807e+02,1.991107995874907388e+00,5.656854305839425834e+00,3.171817097292871646e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.854136642166205462e+01,3.574930579649004017e+02,1.994226896814423666e+00,5.656854305839425834e+00,3.174317097292871370e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.854313418859741347e+01,3.575025583667484170e+02,1.997348172951917133e+00,5.656854305839425834e+00,3.176817097292871095e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.854490195553277232e+01,3.575120579879804836e+02,2.000471824092307838e+00,5.656854305839425834e+00,3.179317097292870820e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.854666972246813117e+01,3.575215568280029288e+02,2.003597850040367945e+00,5.656854305839425834e+00,3.181817097292870544e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.854843748940349002e+01,3.575310548862220799e+02,2.006726250600720629e+00,5.656854305839425834e+00,3.184317097292870269e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.855020525633884887e+01,3.575405521620442642e+02,2.009857025577840517e+00,5.656854305839425834e+00,3.186817097292869994e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.855197302327420772e+01,3.575500486548759227e+02,2.012990174776054797e+00,5.656854305839425834e+00,3.189317097292869718e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.855374079020956657e+01,3.575595443641234965e+02,2.016125697999541444e+00,5.656854305839425834e+00,3.191817097292869443e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.855550855714492542e+01,3.575690392891935403e+02,2.019263595052330107e+00,5.656854305839425834e+00,3.194317097292869168e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.855727632408028427e+01,3.575785334294926088e+02,2.022403865738302109e+00,5.656854305839425834e+00,3.196817097292868892e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.855904409101564312e+01,3.575880267844273703e+02,2.025546509861190891e+00,5.656854305839425834e+00,3.199317097292868617e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.856081185795100197e+01,3.575975193534044365e+02,2.028691527224580682e+00,5.656854305839425834e+00,3.201817097292868342e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.856257962488636082e+01,3.576070111358305326e+02,2.031838917631908270e+00,5.656854305839425834e+00,3.204317097292868066e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.856434739182171967e+01,3.576165021311123837e+02,2.034988680886461676e+00,5.656854305839425834e+00,3.206817097292867791e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.856611515875707852e+01,3.576259923386568289e+02,2.038140816791381038e+00,5.656854305839425834e+00,3.209317097292867516e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.856788292569243737e+01,3.576354817578707639e+02,2.041295325149657280e+00,5.656854305839425834e+00,3.211817097292867240e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.856965069262779622e+01,3.576449703881610844e+02,2.044452205764133890e+00,5.656854305839425834e+00,3.214317097292866965e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.857141845956315507e+01,3.576544582289347431e+02,2.047611458437506027e+00,5.656854305839425834e+00,3.216817097292866690e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.857318622649851392e+01,3.576639452795986927e+02,2.050773082972320083e+00,5.656854305839425834e+00,3.219317097292866414e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.857495399343387277e+01,3.576734315395600561e+02,2.053937079170974567e+00,5.656854305839425834e+00,3.221817097292866139e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.857672176036923162e+01,3.576829170082259566e+02,2.057103446835720106e+00,5.656854305839425834e+00,3.224317097292865864e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.857848952730459047e+01,3.576924016850035173e+02,2.060272185768658115e+00,5.656854305839425834e+00,3.226817097292865588e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.858025729423994932e+01,3.577018855692999750e+02,2.063443295771743013e+00,5.656854305839425834e+00,3.229317097292865313e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.858202506117530817e+01,3.577113686605225666e+02,2.066616776646780007e+00,5.656854305839425834e+00,3.231817097292865038e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.858379282811066702e+01,3.577208509580785858e+02,2.069792628195426865e+00,5.656854305839425834e+00,3.234317097292864762e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.858556059504602587e+01,3.577303324613753830e+02,2.072970850219192585e+00,5.656854305839425834e+00,3.236817097292864487e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.858732836198138472e+01,3.577398131698204224e+02,2.076151442519438284e+00,5.656854305839425834e+00,3.239317097292864212e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.858909612891674357e+01,3.577492930828211115e+02,2.079334404897377198e+00,5.656854305839425834e+00,3.241817097292863936e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.859086389585210242e+01,3.577587721997849712e+02,2.082519737154073791e+00,5.656854305839425834e+00,3.244317097292863661e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.859263166278746127e+01,3.577682505201195227e+02,2.085707439090445092e+00,5.656854305839425834e+00,3.246817097292863386e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.859439942972282012e+01,3.577777280432324005e+02,2.088897510507259803e+00,5.656854305839425834e+00,3.249317097292863110e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.859616719665817897e+01,3.577872047685312964e+02,2.092089951205138298e+00,5.656854305839425834e+00,3.251817097292862835e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.859793496359353782e+01,3.577966806954238450e+02,2.095284760984553074e+00,5.656854305839425834e+00,3.254317097292862559e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.859970273052889667e+01,3.578061558233178516e+02,2.098481939645828298e+00,5.656854305839425834e+00,3.256817097292862284e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.860147049746425552e+01,3.578156301516211215e+02,2.101681486989140701e+00,5.656854305839425834e+00,3.259317097292862009e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.860323826439961437e+01,3.578251036797414599e+02,2.104883402814518245e+00,5.656854305839425834e+00,3.261817097292861733e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.860500603133497322e+01,3.578345764070868427e+02,2.108087686921841453e+00,5.656854305839425834e+00,3.264317097292861458e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.860677379827033207e+01,3.578440483330651887e+02,2.111294339110842522e+00,5.656854305839425834e+00,3.266817097292861183e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.860854156520569092e+01,3.578535194570844737e+02,2.114503359181105768e+00,5.656854305839425834e+00,3.269317097292860907e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.861030933214104977e+01,3.578629897785527874e+02,2.117714746932067182e+00,5.656854305839425834e+00,3.271817097292860632e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.861207709907640862e+01,3.578724592968782190e+02,2.120928502163014873e+00,5.656854305839425834e+00,3.274317097292860357e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.861384486601176746e+01,3.578819280114689150e+02,2.124144624673089510e+00,5.656854305839425834e+00,3.276817097292860081e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.861561263294712631e+01,3.578913959217330785e+02,2.127363114261283439e+00,5.656854305839425834e+00,3.279317097292859806e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.861738039988248516e+01,3.579008630270790263e+02,2.130583970726441123e+00,5.656854305839425834e+00,3.281817097292859531e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.861914816681784401e+01,3.579103293269150186e+02,2.133807193867258700e+00,5.656854305839425834e+00,3.284317097292859255e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.862091593375320286e+01,3.579197948206493720e+02,2.137032783482284870e+00,5.656854305839425834e+00,3.286817097292858980e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.862268370068856171e+01,3.579292595076905741e+02,2.140260739369920451e+00,5.656854305839425834e+00,3.289317097292858705e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.862445146762392056e+01,3.579387233874469985e+02,2.143491061328417935e+00,5.656854305839425834e+00,3.291817097292858429e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.862621923455927941e+01,3.579481864593271894e+02,2.146723749155882377e+00,5.656854305839425834e+00,3.294317097292858154e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.862798700149463826e+01,3.579576487227397479e+02,2.149958802650270506e+00,5.656854305839425834e+00,3.296817097292857879e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.862975476842999711e+01,3.579671101770932182e+02,2.153196221609392058e+00,5.656854305839425834e+00,3.299317097292857603e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.863152253536535596e+01,3.579765708217963152e+02,2.156436005830907998e+00,5.656854305839425834e+00,3.301817097292857328e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.863329030230071481e+01,3.579860306562576966e+02,2.159678155112331410e+00,5.656854305839425834e+00,3.304317097292857053e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.863505806923607366e+01,3.579954896798861341e+02,2.162922669251028385e+00,5.656854305839425834e+00,3.306817097292856777e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.863682583617143251e+01,3.580049478920904562e+02,2.166169548044217130e+00,5.656854305839425834e+00,3.309317097292856502e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.863859360310679136e+01,3.580144052922795481e+02,2.169418791288967086e+00,5.656854305839425834e+00,3.311817097292856227e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.864036137004215021e+01,3.580238618798622952e+02,2.172670398782201140e+00,5.656854305839425834e+00,3.314317097292855951e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.864212913697750906e+01,3.580333176542476394e+02,2.175924370320693413e+00,5.656854305839425834e+00,3.316817097292855676e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.864389690391286791e+01,3.580427726148446368e+02,2.179180705701070586e+00,5.656854305839425834e+00,3.319317097292855401e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.864566467084822676e+01,3.580522267610623430e+02,2.182439404719811904e+00,5.656854305839425834e+00,3.321817097292855125e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.864743243778358561e+01,3.580616800923098140e+02,2.185700467173248729e+00,5.656854305839425834e+00,3.324317097292854850e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.864920020471894446e+01,3.580711326079962760e+02,2.188963892857564542e+00,5.656854305839425834e+00,3.326817097292854575e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.865096797165430331e+01,3.580805843075309554e+02,2.192229681568795385e+00,5.656854305839425834e+00,3.329317097292854299e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.865273573858966216e+01,3.580900351903230785e+02,2.195497833102829421e+00,5.656854305839425834e+00,3.331817097292854024e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.865450350552502101e+01,3.580994852557819854e+02,2.198768347255407374e+00,5.656854305839425834e+00,3.334317097292853749e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.865627127246037986e+01,3.581089345033170730e+02,2.202041223822121641e+00,5.656854305839425834e+00,3.336817097292853473e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.865803903939573871e+01,3.581183829323377381e+02,2.205316462598417626e+00,5.656854305839425834e+00,3.339317097292853198e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.865980680633109756e+01,3.581278305422534345e+02,2.208594063379592853e+00,5.656854305839425834e+00,3.341817097292852923e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.866157457326645641e+01,3.581372773324737295e+02,2.211874025960797407e+00,5.656854305839425834e+00,3.344317097292852647e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.866334234020181526e+01,3.581467233024081338e+02,2.215156350137033936e+00,5.656854305839425834e+00,3.346817097292852372e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.866511010713717411e+01,3.581561684514663284e+02,2.218441035703156761e+00,5.656854305839425834e+00,3.349317097292852097e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.866687787407253296e+01,3.581656127790579944e+02,2.221728082453873210e+00,5.656854305839425834e+00,3.351817097292851821e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.866864564100789181e+01,3.581750562845928130e+02,2.225017490183742730e+00,5.656854305839425834e+00,3.354317097292851546e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.867041340794325066e+01,3.581844989674806357e+02,2.228309258687177330e+00,5.656854305839425834e+00,3.356817097292851271e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.867218117487860951e+01,3.581939408271312573e+02,2.231603387758441581e+00,5.656854305839425834e+00,3.359317097292850995e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.867394894181396836e+01,3.582033818629545294e+02,2.234899877191652173e+00,5.656854305839425834e+00,3.361817097292850720e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.867571670874932721e+01,3.582128220743604174e+02,2.238198726780778802e+00,5.656854305839425834e+00,3.364317097292850445e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.867748447568468606e+01,3.582222614607589435e+02,2.241499936319643282e+00,5.656854305839425834e+00,3.366817097292850169e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.867925224262004491e+01,3.582317000215601297e+02,2.244803505601919991e+00,5.656854305839425834e+00,3.369317097292849894e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.868102000955540376e+01,3.582411377561739982e+02,2.248109434421135866e+00,5.656854305839425834e+00,3.371817097292849619e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.868278777649076261e+01,3.582505746640107418e+02,2.251417722570670410e+00,5.656854305839425834e+00,3.374317097292849343e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.868455554342612146e+01,3.582600107444805531e+02,2.254728369843755686e+00,5.656854305839425834e+00,3.376817097292849068e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.868632331036148031e+01,3.582694459969936815e+02,2.258041376033475878e+00,5.656854305839425834e+00,3.379317097292848793e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.868809107729683916e+01,3.582788804209604336e+02,2.261356740932768172e+00,5.656854305839425834e+00,3.381817097292848517e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.868985884423219801e+01,3.582883140157911726e+02,2.264674464334422765e+00,5.656854305839425834e+00,3.384317097292848242e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.869162661116755686e+01,3.582977467808962615e+02,2.267994546031081526e+00,5.656854305839425834e+00,3.386817097292847967e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.869339437810291571e+01,3.583071787156861205e+02,2.271316985815239331e+00,5.656854305839425834e+00,3.389317097292847691e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.869516214503827456e+01,3.583166098195713403e+02,2.274641783479244062e+00,5.656854305839425834e+00,3.391817097292847416e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.869692991197363341e+01,3.583260400919623976e+02,2.277968938815295274e+00,5.656854305839425834e+00,3.394317097292847141e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.869869767890899226e+01,3.583354695322699399e+02,2.281298451615446421e+00,5.656854305839425834e+00,3.396817097292846865e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.870046544584435111e+01,3.583448981399046147e+02,2.284630321671602626e+00,5.656854305839425834e+00,3.399317097292846590e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.870223321277970996e+01,3.583543259142771262e+02,2.287964548775522022e+00,5.656854305839425834e+00,3.401817097292846315e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.870400097971506881e+01,3.583637528547982924e+02,2.291301132718815303e+00,5.656854305839425834e+00,3.404317097292846039e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.870576874665042766e+01,3.583731789608788745e+02,2.294640073292946170e+00,5.656854305839425834e+00,3.406817097292845764e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.870753651358578651e+01,3.583826042319297471e+02,2.297981370289230441e+00,5.656854305839425834e+00,3.409317097292845489e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.870930428052114536e+01,3.583920286673618421e+02,2.301325023498837385e+00,5.656854305839425834e+00,3.411817097292845213e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.871107204745650421e+01,3.584014522665861477e+02,2.304671032712788836e+00,5.656854305839425834e+00,3.414317097292844938e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.871283981439186306e+01,3.584108750290136527e+02,2.308019397721958743e+00,5.656854305839425834e+00,3.416817097292844663e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.871460758132722191e+01,3.584202969540554591e+02,2.311370118317074951e+00,5.656854305839425834e+00,3.419317097292844387e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.871637534826258076e+01,3.584297180411226691e+02,2.314723194288716979e+00,5.656854305839425834e+00,3.421817097292844112e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.871814311519793961e+01,3.584391382896264986e+02,2.318078625427317352e+00,5.656854305839425834e+00,3.424317097292843837e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.871991088213329846e+01,3.584485576989781634e+02,2.321436411523162047e+00,5.656854305839425834e+00,3.426817097292843561e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.872167864906865731e+01,3.584579762685889932e+02,2.324796552366389601e+00,5.656854305839425834e+00,3.429317097292843286e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.872344641600401616e+01,3.584673939978702606e+02,2.328159047746990673e+00,5.656854305839425834e+00,3.431817097292843011e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.872521418293937501e+01,3.584768108862334088e+02,2.331523897454809813e+00,5.656854305839425834e+00,3.434317097292842735e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.872698194987473386e+01,3.584862269330898243e+02,2.334891101279543246e+00,5.656854305839425834e+00,3.436817097292842460e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.872874971681009271e+01,3.584956421378510640e+02,2.338260659010741538e+00,5.656854305839425834e+00,3.439317097292842185e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.873051748374545156e+01,3.585050564999286848e+02,2.341632570437806926e+00,5.656854305839425834e+00,3.441817097292841909e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.873228525068081041e+01,3.585144700187342437e+02,2.345006835349994656e+00,5.656854305839425834e+00,3.444317097292841634e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.873405301761616926e+01,3.585238826936794112e+02,2.348383453536413423e+00,5.656854305839425834e+00,3.446817097292841359e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.873582078455152811e+01,3.585332945241758580e+02,2.351762424786024930e+00,5.656854305839425834e+00,3.449317097292841083e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.873758855148688696e+01,3.585427055096354252e+02,2.355143748887642996e+00,5.656854305839425834e+00,3.451817097292840808e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.873935631842224581e+01,3.585521156494698403e+02,2.358527425629935337e+00,5.656854305839425834e+00,3.454317097292840533e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.874112408535760466e+01,3.585615249430910580e+02,2.361913454801421786e+00,5.656854305839425834e+00,3.456817097292840257e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.874289185229296351e+01,3.585709333899109197e+02,2.365301836190475626e+00,5.656854305839425834e+00,3.459317097292839982e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.874465961922832236e+01,3.585803409893414369e+02,2.368692569585323149e+00,5.656854305839425834e+00,3.461817097292839707e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.874642738616368121e+01,3.585897477407946212e+02,2.372085654774043206e+00,5.656854305839425834e+00,3.464317097292839431e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.874819515309904006e+01,3.585991536436825413e+02,2.375481091544568102e+00,5.656854305839425834e+00,3.466817097292839156e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.874996292003439891e+01,3.586085586974173793e+02,2.378878879684683145e+00,5.656854305839425834e+00,3.469317097292838881e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.875173068696975776e+01,3.586179629014112606e+02,2.382279018982026653e+00,5.656854305839425834e+00,3.471817097292838605e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.875349845390511661e+01,3.586273662550764243e+02,2.385681509224089503e+00,5.656854305839425834e+00,3.474317097292838330e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.875526622084047546e+01,3.586367687578252230e+02,2.389086350198216468e+00,5.656854305839425834e+00,3.476817097292838055e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.875703398777583431e+01,3.586461704090699527e+02,2.392493541691604886e+00,5.656854305839425834e+00,3.479317097292837779e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.875880175471119315e+01,3.586555712082230229e+02,2.395903083491305097e+00,5.656854305839425834e+00,3.481817097292837504e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.876056952164655200e+01,3.586649711546968433e+02,2.399314975384220894e+00,5.656854305839425834e+00,3.484317097292837229e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.876233728858191085e+01,3.586743702479039939e+02,2.402729217157109076e+00,5.656854305839425834e+00,3.486817097292836953e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.876410505551726970e+01,3.586837684872569412e+02,2.406145808596579450e+00,5.656854305839425834e+00,3.489317097292836678e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.876587282245262855e+01,3.586931658721683789e+02,2.409564749489095270e+00,5.656854305839425834e+00,3.491817097292836403e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.876764058938798740e+01,3.587025624020509440e+02,2.412986039620972800e+00,5.656854305839425834e+00,3.494317097292836127e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.876940835632334625e+01,3.587119580763173303e+02,2.416409678778380865e+00,5.656854305839425834e+00,3.496817097292835852e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.877117612325870510e+01,3.587213528943802885e+02,2.419835666747342628e+00,5.656854305839425834e+00,3.499317097292835577e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.877294389019406395e+01,3.587307468556526828e+02,2.423264003313733372e+00,5.656854305839425834e+00,3.501817097292835301e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.877471165712942280e+01,3.587401399595473777e+02,2.426694688263282274e+00,5.656854305839425834e+00,3.504317097292835026e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.877647942406478165e+01,3.587495322054773510e+02,2.430127721381571515e+00,5.656854305839425834e+00,3.506817097292834751e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.877824719100014050e+01,3.587589235928555240e+02,2.433563102454036287e+00,5.656854305839425834e+00,3.509317097292834475e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.878001495793549935e+01,3.587683141210949316e+02,2.437000831265965672e+00,5.656854305839425834e+00,3.511817097292834200e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.878178272487085820e+01,3.587777037896087222e+02,2.440440907602501319e+00,5.656854305839425834e+00,3.514317097292833925e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.878355049180621705e+01,3.587870925978099876e+02,2.443883331248638768e+00,5.656854305839425834e+00,3.516817097292833649e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.878531825874157590e+01,3.587964805451119901e+02,2.447328101989226123e+00,5.656854305839425834e+00,3.519317097292833374e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.878708602567693475e+01,3.588058676309279349e+02,2.450775219608965383e+00,5.656854305839425834e+00,3.521817097292833099e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.878885379261229360e+01,3.588152538546711412e+02,2.454224683892411996e+00,5.656854305839425834e+00,3.524317097292832823e-01,0.000000000000000000e+00,6.839316092015533532e-02,-1.136868399864498811e-08,0.000000000000000000e+00 +5.879062155954765245e+01,3.588246392157549280e+02,2.457676494623973973e+00,5.656854305839425834e+00,3.526817097292832548e-01,-2.009718367133724172e-11,6.839316092015533532e-02,6.337728690434578046e-05,0.000000000000000000e+00 +5.879238932648301130e+01,3.588340237135927850e+02,2.461130651587913665e+00,5.656854305839390307e+00,3.529317097292832273e-01,1.120161750585234533e-07,6.839316092015533532e-02,-6.018556849369615103e-01,0.000000000000000000e+00 +5.879415709341837015e+01,3.588434073475981450e+02,2.464587154568345984e+00,5.656854306037408797e+00,3.531817097292831997e-01,-1.063828563513700715e-03,6.839316092015533532e-02,-9.999915936716446963e-01,0.000000000000000000e+00 +5.879592486035366505e+01,3.588527901171844974e+02,2.468046003349239292e+00,5.656852425436449394e+00,3.534317097292831722e-01,-2.831580638380434660e-03,6.839316092015533532e-02,-9.999955363138058884e-01,0.000000000000000000e+00 +5.879769262787664985e+01,3.588621720217654456e+02,2.471507197714415849e+00,5.656847419860158155e+00,3.536817097292831447e-01,-4.599340270604978902e-03,6.839316092015533532e-02,-9.999968264281712260e-01,0.000000000000000000e+00 +5.879946039696388027e+01,3.588715530607546498e+02,2.474970737447550917e+00,5.656839289288606132e+00,3.539317097292831171e-01,-6.367103747691818874e-03,6.839316092015533532e-02,-9.999974500772063069e-01,0.000000000000000000e+00 +5.880122816859191914e+01,3.588809332335657700e+02,2.478436622332173211e+00,5.656828033703248160e+00,3.541817097292830896e-01,-8.134870868053062365e-03,6.839316092015533532e-02,-9.999978025427666006e-01,0.000000000000000000e+00 +5.880299594373735772e+01,3.588903125396125233e+02,2.481904852151664898e+00,5.656813653080716264e+00,3.544317097292830621e-01,-9.902642128881221362e-03,6.839316092015533532e-02,-9.999980147645762818e-01,0.000000000000000000e+00 +5.880476372337679436e+01,3.588996909783087403e+02,2.485375426689261591e+00,5.656796147391584206e+00,3.546817097292830345e-01,-1.167041825885851807e-02,6.839316092015533532e-02,-9.999981426282377184e-01,0.000000000000000000e+00 +5.880653150848685584e+01,3.589090685490682517e+02,2.488848345728052358e+00,5.656775516599958031e+00,3.549317097292830070e-01,-1.343820008548373378e-02,6.839316092015533532e-02,-9.999982095977180130e-01,0.000000000000000000e+00 +5.880829930004419026e+01,3.589184452513050019e+02,2.492323609050980160e+00,5.656751760663301098e+00,3.551817097292829795e-01,-1.520598847776339323e-02,6.839316092015533532e-02,-9.999982291683776614e-01,0.000000000000000000e+00 +5.881006709902549545e+01,3.589278210844328783e+02,2.495801216440840520e+00,5.656724879532360362e+00,3.554317097292829519e-01,-1.697378432859478897e-02,6.839316092015533532e-02,-9.999982025935350016e-01,0.000000000000000000e+00 +5.881183490640749767e+01,3.589371960478659389e+02,2.499281167680283300e+00,5.656694873151123737e+00,3.556817097292829244e-01,-1.874158853312984235e-02,6.839316092015533532e-02,-9.999981268426498815e-01,0.000000000000000000e+00 +5.881360272316697291e+01,3.589465701410182419e+02,2.502763462551811369e+00,5.656661741456815662e+00,3.559317097292828969e-01,-2.050940198120714680e-02,6.839316092015533532e-02,-9.999979883492942090e-01,0.000000000000000000e+00 +5.881537055028074690e+01,3.589559433633039021e+02,2.506248100837781490e+00,5.656625484379905977e+00,3.561817097292828693e-01,-2.227722553873129688e-02,6.839316092015533532e-02,-9.999977584649994977e-01,0.000000000000000000e+00 +5.881713838872570221e+01,3.589653157141370912e+02,2.509735082320403876e+00,5.656586101844151671e+00,3.564317097292828418e-01,-2.404506002101472473e-02,6.839316092015533532e-02,-9.999973755569590006e-01,0.000000000000000000e+00 +5.881890623947877828e+01,3.589746871929319809e+02,2.513224406781741749e+00,5.656543593766685696e+00,3.566817097292828143e-01,-2.581290613446987278e-02,6.839316092015533532e-02,-9.999966864698404123e-01,0.000000000000000000e+00 +5.882067410351699266e+01,3.589840577991029136e+02,2.516716074003712666e+00,5.656497960058208818e+00,3.569317097292827867e-01,-2.758076431481131310e-02,6.839316092015533532e-02,-9.999952035632213576e-01,0.000000000000000000e+00 +5.882244198181741979e+01,3.589934275320642314e+02,2.520210083768087195e+00,5.656449200623467455e+00,3.571817097292827592e-01,-2.934863413572243174e-02,6.839316092015533532e-02,-9.999901220698573789e-01,0.000000000000000000e+00 +5.882420987535721935e+01,3.590027963912303335e+02,2.523706435856489794e+00,5.656397315362776901e+00,3.574317097292827317e-01,-3.111651021239547274e-02,6.839316092015533532e-02,9.999496962156090296e-01,0.000000000000000000e+00 +5.882597778511363629e+01,3.590121643760156189e+02,2.527205130050398818e+00,5.656342304180786762e+00,3.576817097292827041e-01,-2.934868938852982015e-02,6.839316092015533532e-02,9.999935601395280038e-01,0.000000000000000000e+00 +5.882774571206399372e+01,3.590215314858346005e+02,2.530706166131145185e+00,5.656290417841859153e+00,3.579317097292826766e-01,-2.758077382337669956e-02,6.839316092015533532e-02,9.999967240926388445e-01,0.000000000000000000e+00 +5.882951365523191356e+01,3.590308977201018479e+02,2.534209543879914595e+00,5.656241656601212142e+00,3.581817097292826491e-01,-2.581283644707383154e-02,6.839316092015533532e-02,9.999978717949041807e-01,0.000000000000000000e+00 +5.883128161364088982e+01,3.590402630782319875e+02,2.537715263077746197e+00,5.656196020579955963e+00,3.584317097292826215e-01,-2.404488180067388542e-02,6.839316092015533532e-02,9.999984599835520793e-01,0.000000000000000000e+00 +5.883304958631433124e+01,3.590496275596397027e+02,2.541223323505532150e+00,5.656153509885996300e+00,3.586817097292825940e-01,-2.227691184994184254e-02,6.839316092015533532e-02,9.999988149185008446e-01,0.000000000000000000e+00 +5.883481757227555420e+01,3.590589911637396767e+02,2.544733724944018505e+00,5.656114124618586203e+00,3.589317097292825665e-01,-2.050892798392640881e-02,6.839316092015533532e-02,9.999990508409557499e-01,0.000000000000000000e+00 +5.883658557054781113e+01,3.590683538899466498e+02,2.548246467173805652e+00,5.656077864869344829e+00,3.591817097292825389e-01,-1.874093138978344744e-02,6.839316092015533532e-02,9.999992177459984255e-01,0.000000000000000000e+00 +5.883835358015427630e+01,3.590777157376755326e+02,2.551761549975346988e+00,5.656044730722613600e+00,3.594317097292825114e-01,-1.697292316635157575e-02,6.839316092015533532e-02,9.999993417359006598e-01,0.000000000000000000e+00 +5.884012160011806714e+01,3.590870767063411222e+02,2.555278973128949804e+00,5.656014722255611638e+00,3.596817097292824839e-01,-1.520490436638684967e-02,6.839316092015533532e-02,9.999994366718073513e-01,0.000000000000000000e+00 +5.884188962946223711e+01,3.590964367953584429e+02,2.558798736414774844e+00,5.655987839538516582e+00,3.599317097292824563e-01,-1.343687601819858884e-02,6.839316092015533532e-02,9.999995115621879149e-01,0.000000000000000000e+00 +5.884365766720978996e+01,3.591057960041424053e+02,2.562320839612837631e+00,5.655964082634507228e+00,3.601817097292824288e-01,-1.166883913422293341e-02,6.839316092015533532e-02,9.999995719839215313e-01,0.000000000000000000e+00 +5.884542571238367969e+01,3.591151543321081476e+02,2.565845282503006253e+00,5.655943451599791061e+00,3.604317097292824013e-01,-9.900794717084186389e-03,6.839316092015533532e-02,9.999996212191013534e-01,0.000000000000000000e+00 +5.884719376400682478e+01,3.591245117786706942e+02,2.569372064865003136e+00,5.655925946483621125e+00,3.606817097292823737e-01,-8.132743763646435586e-03,6.839316092015533532e-02,9.999996625281812879e-01,0.000000000000000000e+00 +5.884896182110209395e+01,3.591338683432452399e+02,2.572901186478404156e+00,5.655911567328305800e+00,3.609317097292823462e-01,-6.364687265046242715e-03,6.839316092015533532e-02,9.999996974452968201e-01,0.000000000000000000e+00 +5.885072988269233463e+01,3.591432240252470365e+02,2.576432647122639530e+00,5.655900314169218568e+00,3.611817097292823187e-01,-4.596626209739346040e-03,6.839316092015533532e-02,9.999997263466098296e-01,0.000000000000000000e+00 +5.885249794780036581e+01,3.591525788240912789e+02,2.579966446576992922e+00,5.655892187034802454e+00,3.614317097292822911e-01,-2.828561585542557419e-03,6.839316092015533532e-02,9.999997518597727453e-01,0.000000000000000000e+00 +5.885426601544899228e+01,3.591619327391933325e+02,2.583502584620601450e+00,5.655887185946570916e+00,3.616817097292822636e-01,-1.060494375647526473e-03,6.839316092015533532e-02,9.999997740338967267e-01,0.000000000000000000e+00 +5.885603408466099040e+01,3.591712857699685628e+02,2.587041061032457012e+00,5.655885310919115838e+00,3.619317097292822361e-01,7.075744368256778284e-04,6.839316092015533532e-02,9.999997934649050846e-01,0.000000000000000000e+00 +5.885780215445913655e+01,3.591806379158324489e+02,2.590581875591404515e+00,5.655886561960107528e+00,3.621817097292822085e-01,2.475643869800794351e-03,6.839316092015533532e-02,9.999998095908213536e-01,0.000000000000000000e+00 +5.885957022386619286e+01,3.591899891762004131e+02,2.594125028076143202e+00,5.655890939070296497e+00,3.624317097292821810e-01,4.243712940203544538e-03,6.839316092015533532e-02,9.999998252376929297e-01,0.000000000000000000e+00 +5.886133829190493572e+01,3.591993395504880482e+02,2.597670518265226214e+00,5.655898442243511681e+00,3.626817097292821535e-01,6.011780669957313139e-03,6.839316092015533532e-02,9.999998380960017919e-01,0.000000000000000000e+00 +5.886310635759814147e+01,3.592086890381109470e+02,2.601218345937060139e+00,5.655909071466669324e+00,3.629317097292821259e-01,7.779846076908528141e-03,6.839316092015533532e-02,9.999998503807537853e-01,0.000000000000000000e+00 +5.886487441996860071e+01,3.592180376384847591e+02,2.604768510869905906e+00,5.655922826719765872e+00,3.631817097292820984e-01,9.547908182831736645e-03,6.839316092015533532e-02,9.999998603078625870e-01,0.000000000000000000e+00 +5.886664247803911820e+01,3.592273853510252479e+02,2.608321012841877895e+00,5.655939707975885078e+00,3.634317097292820709e-01,1.131596600636435891e-02,6.839316092015533532e-02,9.999998703336819839e-01,0.000000000000000000e+00 +5.886841053083252007e+01,3.592367321751481199e+02,2.611875851630945267e+00,5.655959715201192672e+00,3.636817097292820433e-01,1.308401857050945326e-02,6.839316092015533532e-02,9.999998791995924341e-01,0.000000000000000000e+00 +5.887017857737166082e+01,3.592460781102691953e+02,2.615433027014930190e+00,5.655982848354944359e+00,3.639317097292820158e-01,1.485206489607282521e-02,6.839316092015533532e-02,9.999998867620595311e-01,0.000000000000000000e+00 +5.887194661667943762e+01,3.592554231558044080e+02,2.618992538771509171e+00,5.656009107389482260e+00,3.641817097292819883e-01,1.662010400363997734e-02,6.839316092015533532e-02,9.999998939926943997e-01,0.000000000000000000e+00 +5.887371464777877605e+01,3.592647673111696349e+02,2.622554386678213056e+00,5.656038492250234917e+00,3.644317097292819607e-01,1.838813491555313373e-02,6.839316092015533532e-02,9.999999004210934350e-01,0.000000000000000000e+00 +5.887548266969264432e+01,3.592741105757808668e+02,2.626118570512426142e+00,5.656071002875720843e+00,3.646817097292819332e-01,2.015615665336709800e-02,6.839316092015533532e-02,9.999999066920066682e-01,0.000000000000000000e+00 +5.887725068144407459e+01,3.592834529490542081e+02,2.629685090051387064e+00,5.656106639197547636e+00,3.649317097292819057e-01,2.192416823982627772e-02,6.839316092015533532e-02,9.999999122922879069e-01,0.000000000000000000e+00 +5.887901868205614164e+01,3.592927944304057064e+02,2.633253945072187907e+00,5.656145401140414641e+00,3.651817097292818781e-01,2.369216869682289756e-02,6.839316092015533532e-02,9.999999166873956291e-01,0.000000000000000000e+00 +5.888078667055197712e+01,3.593021350192515229e+02,2.636825135351775540e+00,5.656187288622112064e+00,3.654317097292818506e-01,2.546015704536459465e-02,6.839316092015533532e-02,9.999999221629016777e-01,0.000000000000000000e+00 +5.888255464595479083e+01,3.593114747150079324e+02,2.640398660666950725e+00,5.656232301553520081e+00,3.656817097292818231e-01,2.722813231056573843e-02,6.839316092015533532e-02,9.999999261525444050e-01,0.000000000000000000e+00 +5.888432260728785650e+01,3.593208135170911532e+02,2.643974520794368122e+00,5.656280439838616836e+00,3.659317097292817955e-01,2.899609351307485053e-02,6.839316092015533532e-02,9.999999300467745655e-01,0.000000000000000000e+00 +5.888609055357453315e+01,3.593301514249175170e+02,2.647552715510536281e+00,5.656331703374471331e+00,3.661817097292817680e-01,3.076403967607540049e-02,6.839316092015533532e-02,9.999999340781527968e-01,0.000000000000000000e+00 +5.888785848383824373e+01,3.593394884379033556e+02,2.651133244591818094e+00,5.656386092051248760e+00,3.664317097292817405e-01,3.253196982324405018e-02,6.839316092015533532e-02,9.999999373212363762e-01,0.000000000000000000e+00 +5.888962639710251779e+01,3.593488245554651712e+02,2.654716107814430792e+00,5.656443605752212278e+00,3.666817097292817129e-01,3.429988297670878011e-02,6.839316092015533532e-02,9.999999408184357952e-01,0.000000000000000000e+00 +5.889139429239097012e+01,3.593581597770194094e+02,2.658301304954445055e+00,5.656504244353721234e+00,3.669317097292816854e-01,3.606777816053330366e-02,6.839316092015533532e-02,9.999999433174491248e-01,0.000000000000000000e+00 +5.889316216872730791e+01,3.593674941019826861e+02,2.661888835787785901e+00,5.656568007725235603e+00,3.671817097292816579e-01,3.783565439666561336e-02,6.839316092015533532e-02,9.999999466706750439e-01,0.000000000000000000e+00 +5.889493002513535203e+01,3.593768275297715604e+02,2.665478700090233133e+00,5.656634895729313328e+00,3.674317097292816303e-01,3.960351071043213128e-02,6.839316092015533532e-02,9.999999490148021586e-01,0.000000000000000000e+00 +5.889669786063902990e+01,3.593861600598027053e+02,2.669070897637420003e+00,5.656704908221617423e+00,3.676817097292816028e-01,4.137134612397418143e-02,6.839316092015533532e-02,9.999999518755151584e-01,0.000000000000000000e+00 +5.889846567426237556e+01,3.593954916914927935e+02,2.672665428204834104e+00,5.656778045050911530e+00,3.679317097292815752e-01,4.313915966224464438e-02,6.839316092015533532e-02,9.999999536310493209e-01,0.000000000000000000e+00 +5.890023346502955093e+01,3.594048224242586684e+02,2.676262291567817364e+00,5.656854306059066140e+00,3.681817097292815477e-01,4.490695034744917463e-02,6.839316092015533532e-02,9.999999509328285630e-01,-5.656854306059071469e-01 +5.890200123196483872e+01,3.594141522575171166e+02,2.679861487501566053e+00,5.656933691081055038e+00,3.684317097292815202e-01,4.667471719599913110e-02,6.739316092015533444e-02,9.999999472320381111e-01,-5.656933691081059701e-01 +5.890376897409265666e+01,3.594234811906850382e+02,2.683463015781129890e+00,5.657016199944946422e+00,3.686780432191787971e-01,4.844245923053751984e-02,6.639316092015533355e-02,9.999999434009325672e-01,-5.657016199944950863e-01 +5.890553669043755747e+01,3.594328092363928704e+02,2.687066841980064069e+00,5.657101832471915337e+00,3.689207106938850456e-01,5.021017547538522696e-02,6.539316092015533266e-02,9.999999391536710247e-01,-5.657101832471920222e-01 +5.890730438002422886e+01,3.594421364072946972e+02,2.690672931686161728e+00,5.657190588476248116e+00,3.691597126408812657e-01,5.197786495449915195e-02,6.439316092015533177e-02,9.999999338988898590e-01,-5.657190588476253001e-01 +5.890907204187751489e+01,3.594514627160676810e+02,2.694281250501250558e+00,5.657282467765343270e+00,3.693950495402215650e-01,5.374552669093755203e-02,6.339316092015533088e-02,9.999999287295050499e-01,-5.657282467765347711e-01 +5.891083967502240171e+01,3.594607881754118353e+02,2.697891764040987184e+00,5.657377470139711484e+00,3.696267218645371000e-01,5.551315970984267018e-02,6.239316092015533000e-02,9.999999227274924962e-01,-5.657377470139716147e-01 +5.891260727848403889e+01,3.594701127980496835e+02,2.701504437934654224e+00,5.657475595392980949e+00,3.698547300790399062e-01,5.728076303489143539e-02,6.139316092015532911e-02,9.999999149534718468e-01,-5.657475595392985612e-01 +5.891437485128773943e+01,3.594794365967258045e+02,2.705119237824954226e+00,5.657576843311896475e+00,3.700790746415265620e-01,5.904833568826318990e-02,6.039316092015532822e-02,9.999999072896795793e-01,-5.657576843311901138e-01 +5.891614239245897977e+01,3.594887595842066048e+02,2.708736129367804057e+00,5.657681213676318599e+00,3.702997560023818524e-01,6.081587669563250087e-02,5.939316092015532733e-02,9.999998973329174978e-01,-5.657681213676323262e-01 +5.891790990102341397e+01,3.594980817732798641e+02,2.712355078232129735e+00,5.657788706259231581e+00,3.705167746045825994e-01,6.258338507859974309e-02,5.839316092015532644e-02,9.999998860702216108e-01,-5.657788706259236911e-01 +5.891967737600687371e+01,3.595074031767543943e+02,2.715976050099660810e+00,5.657899320826738077e+00,3.707301308837009368e-01,6.435085986068893316e-02,5.739316092015532556e-02,9.999998724773365710e-01,-5.657899320826743628e-01 +5.892144481643536835e+01,3.595167238074596412e+02,2.719599010664723426e+00,5.658013057138064461e+00,3.709398252679080299e-01,6.611830006379812441e-02,5.639316092015532467e-02,9.999998552243589689e-01,-5.658013057138069346e-01 +5.892321222133511327e+01,3.595260436782455145e+02,2.723223925634033815e+00,5.658129914945559946e+00,3.711458581779774057e-01,6.788570470766470966e-02,5.539316092015532378e-02,9.999998346660545767e-01,-5.658129914945565497e-01 +5.892497958973250149e+01,3.595353628019818188e+02,2.726850760726492240e+00,5.658249893994694801e+00,3.713482300272884506e-01,6.965307281284841001e-02,5.439316092015532289e-02,9.999998071551338130e-01,-5.658249893994699020e-01 +5.892674692065413922e+01,3.595446811915579701e+02,2.730479481672974718e+00,5.658372994024063907e+00,3.715469412218295187e-01,7.142040339366363677e-02,5.339316092015532200e-02,9.999997712972806818e-01,-5.658372994024069014e-01 +5.892851421312682447e+01,3.595539988598826540e+02,2.734110054216126962e+00,5.658499214765377872e+00,3.717419921602014288e-01,7.318769546216707944e-02,5.239316092015532111e-02,9.999997205578733395e-01,-5.658499214765382312e-01 +5.893028146617758267e+01,3.595633158198835417e+02,2.737742444110155215e+00,5.658628555943461258e+00,3.719333832336205736e-01,7.495494801907909288e-02,5.139316092015532023e-02,9.999996443978990124e-01,-5.658628555943466809e-01 +5.893204867883363818e+01,3.595726320845067789e+02,2.741376617120620196e+00,5.658761017276234817e+00,3.721211148259220280e-01,7.672216004671353340e-02,5.039316092015531934e-02,9.999995174651021834e-01,-5.658761017276239258e-01 +5.893381585012245694e+01,3.595819476667167578e+02,2.745012539024227038e+00,5.658896598474685291e+00,3.723051873135627132e-01,7.848933048280740121e-02,4.939316092015531845e-02,9.999992634668990465e-01,-5.658896598474689732e-01 +5.893558297907171095e+01,3.595912625794957194e+02,2.748650175608617907e+00,5.659035299242789030e+00,3.724856010656242833e-01,8.025645813051250632e-02,4.839316092015531756e-02,9.999985005778734282e-01,-5.659035299242793915e-01 +5.893735006470932092e+01,3.596005768358434125e+02,2.752289492672163274e+00,5.659177119277276624e+00,3.726623564438162339e-01,8.202354111851167806e-02,4.739316092015531667e-02,-4.383362119087416686e-01,-5.659177119277281065e-01 +5.893911710606343490e+01,3.596098904487767527e+02,2.755930456023752750e+00,5.659322058266443634e+00,3.728354538024787335e-01,8.124898290506470111e-02,4.639316092015531579e-02,-9.999984677836899483e-01,-5.659322058266448296e-01 +5.894088410216244256e+01,3.596192034313294243e+02,2.759573031482585925e+00,5.659465624902285441e+00,3.730048934885855094e-01,7.948198951347459906e-02,4.539316092015531490e-02,-9.999992301907387748e-01,-5.659465624902290104e-01 +5.894265105343713174e+01,3.596285157965515964e+02,2.763217184877963195e+00,5.659606065704971378e+00,3.731706758417465686e-01,7.771503959899746239e-02,4.439316092015531401e-02,-9.999994848521998048e-01,-5.659606065704976263e-01 +5.894441796086565688e+01,3.596378275575094676e+02,2.766862882049076156e+00,5.659743380985746697e+00,3.733328011942109725e-01,7.594813308069434110e-02,4.339316092015531312e-02,-9.999996113084544946e-01,-5.659743380985752248e-01 +5.894618482542590954e+01,3.596471387272850393e+02,2.770510088844796659e+00,5.659877571050504486e+00,3.734912698708695022e-01,7.418126920720492790e-02,4.239316092015531223e-02,-9.999996875737575674e-01,-5.659877571050508926e-01 +5.894795164809556098e+01,3.596564493189756604e+02,2.774158771123468537e+00,5.660008636198603504e+00,3.736460821892572670e-01,7.241444708955238618e-02,4.139316092015531134e-02,-9.999997381663447982e-01,-5.660008636198607945e-01 +5.894971842985204802e+01,3.596657593456937434e+02,2.777808894752696212e+00,5.660136576722627488e+00,3.737972384595562025e-01,7.064766579566734983e-02,4.039316092015531046e-02,-9.999997744994981730e-01,-5.660136576722633039e-01 +5.895148517167258007e+01,3.596750688205663664e+02,2.781460425609134202e+00,5.660261392908311429e+00,3.739447389845976799e-01,6.888092437353982023e-02,3.939316092015530957e-02,-9.999998011380353269e-01,-5.660261392908315647e-01 +5.895325187453413207e+01,3.596843777567350458e+02,2.785113329578276620e+00,5.660383085034508710e+00,3.740885840598647816e-01,6.711422186331489348e-02,3.839316092015530868e-02,-9.999998220571751917e-01,-5.660383085034513817e-01 +5.895501853941348003e+01,3.596936861673551675e+02,2.788767572554246676e+00,5.660501653373179565e+00,3.742287739734947438e-01,6.534755729832975035e-02,3.739316092015530779e-02,-9.999998395039958465e-01,-5.660501653373184450e-01 +5.895678516728718677e+01,3.597029940655958171e+02,2.792423120439584405e+00,5.660617098189381302e+00,3.743653090062812328e-01,6.358092970816187073e-02,3.639316092015530690e-02,-9.999998522892649122e-01,-5.660617098189386631e-01 +5.895855175913160195e+01,3.597123014646393244e+02,2.796079939145036608e+00,5.660729419741263868e+00,3.744981894316767312e-01,6.181433812469453587e-02,3.539316092015530602e-02,-9.999998640404564876e-01,-5.660729419741268309e-01 +5.896031831592287631e+01,3.597216083776810365e+02,2.799737994589344581e+00,5.660838618280076062e+00,3.746274155157945374e-01,6.004778157360228519e-02,3.439316092015530513e-02,-9.999998738103075269e-01,-5.660838618280080725e-01 +5.896208483863696870e+01,3.597309148179288627e+02,2.803397252699033171e+00,5.660944694050156656e+00,3.747529875174110403e-01,5.828125908242740710e-02,3.339316092015530424e-02,-9.999998814837456340e-01,-5.660944694050161763e-01 +5.896385132824964614e+01,3.597402207986029907e+02,2.807057679408198503e+00,5.661047647288939721e+00,3.748749056879677188e-01,5.651476967910435550e-02,3.239316092015530335e-02,-9.999998886320953240e-01,-5.661047647288944829e-01 +5.896561778573650514e+01,3.597495263329354316e+02,2.810719240658295703e+00,5.661147478226957297e+00,3.749931702715731952e-01,5.474831238897539393e-02,3.139316092015530246e-02,-9.999998948129219523e-01,-5.661147478226962182e-01 +5.896738421207294323e+01,3.597588314341697355e+02,2.814381902397927071e+00,5.661244187087836721e+00,3.751077815050051223e-01,5.298188623834255984e-02,3.039316092015530157e-02,-9.999999004162377636e-01,-5.661244187087841606e-01 +5.896915060823420163e+01,3.597681361155607647e+02,2.818045630582629801e+00,5.661337774088304187e+00,3.752187396177122380e-01,5.121549025299178270e-02,2.939316092015530069e-02,-9.999999046720142726e-01,-5.661337774088309738e-01 +5.897091697519534392e+01,3.597774403903741813e+02,2.821710391174663712e+00,5.661428239438185628e+00,3.753260448318159748e-01,4.944912346023659644e-02,2.839316092015529980e-02,-9.999999090660718348e-01,-5.661428239438189847e-01 +5.897268331393127028e+01,3.597867442718861071e+02,2.825376150142798082e+00,5.661515583340411162e+00,3.754296973621124578e-01,4.768278488492806721e-02,2.739316092015529891e-02,-9.999999127855938585e-01,-5.661515583340416269e-01 +5.897444962541673874e+01,3.597960477733828384e+02,2.829042873462098484e+00,5.661599805991012424e+00,3.755296974160740597e-01,4.591647355350968185e-02,2.639316092015529802e-02,-9.999999158502749230e-01,-5.661599805991016643e-01 +5.897621591062633684e+01,3.598053509081605057e+02,2.832710527113715404e+00,5.661680907579127009e+00,3.756260451938512324e-01,4.415018849254141731e-02,2.539316092015529713e-02,-9.999999193972813893e-01,-5.661680907579131894e-01 +5.897798217053452419e+01,3.598146536895247323e+02,2.836379077084670186e+00,5.661758888287000246e+00,3.757187408882739499e-01,4.238392872672061551e-02,2.439316092015529625e-02,-9.999999219801178896e-01,-5.661758888287005131e-01 +5.897974840611560410e+01,3.598239561307901795e+02,2.840048489367641427e+00,5.661833748289983426e+00,3.758077846848532633e-01,4.061769328344006641e-02,2.339316092015529536e-02,-9.999999241237641501e-01,-5.661833748289988311e-01 +5.898151461834375908e+01,3.598332582452803763e+02,2.843718729960752256e+00,5.661905487756540012e+00,3.758931767617829101e-01,3.885148118930044359e-02,2.239316092015529447e-02,-9.999999263319105935e-01,-5.661905487756544453e-01 +5.898328080819302954e+01,3.598425600463272076e+02,2.847389764867356732e+00,5.661974106848245647e+00,3.759749172899407021e-01,3.708529147014257704e-02,2.139316092015529358e-02,-9.999999288022599631e-01,-5.661974106848250976e-01 +5.898504697663733509e+01,3.598518615472706301e+02,2.851061560095826675e+00,5.662039605719788149e+00,3.760530064328897470e-01,3.531912315158254601e-02,2.039316092015529269e-02,-9.999999302874333917e-01,-5.662039605719793034e-01 +5.898681312465048165e+01,3.598611627614583313e+02,2.854734081659337619e+00,5.662101984518968401e+00,3.761274443468800022e-01,3.355297526155854443e-02,1.939316092015529180e-02,-9.999999317966120627e-01,-5.662101984518973508e-01 +5.898857925320615436e+01,3.598704637022454449e+02,2.858407295575654761e+00,5.662161243386705678e+00,3.761982311808492740e-01,3.178684682634003167e-02,1.839316092015529092e-02,-9.999999337482211592e-01,-5.662161243386710785e-01 +5.899034536327793887e+01,3.598797643829940398e+02,2.862081167866919795e+00,5.662217382457035875e+00,3.762653670764246061e-01,3.002073687156578061e-02,1.739316092015529003e-02,-9.999999348308912239e-01,-5.662217382457040982e-01 +5.899211145583930715e+01,3.598890648170730060e+02,2.865755664559436422e+00,5.662270401857111501e+00,3.763288521679232779e-01,2.825464442529351111e-02,1.639316092015528914e-02,-9.999999359899177653e-01,-5.662270401857116831e-01 +5.899387753186363881e+01,3.598983650178574294e+02,2.869430751683456293e+00,5.662320301707207015e+00,3.763886865823540262e-01,2.648856851400898868e-02,1.539316092015528825e-02,-9.999999372950837406e-01,-5.662320301707212122e-01 +5.899564359232422106e+01,3.599076649987285350e+02,2.873106395272965408e+00,5.662367082120717043e+00,3.764448704394178780e-01,2.472250816416692726e-02,1.439316092015528736e-02,-9.999999385101163707e-01,-5.662367082120721706e-01 +5.899740963819425588e+01,3.599169647730731185e+02,2.876782561365468727e+00,5.662410743204157271e+00,3.764974038515092603e-01,2.295646240272613409e-02,1.339316092015528648e-02,-9.999999390926599396e-01,-5.662410743204162600e-01 +5.899917567044685995e+01,3.599262643542833189e+02,2.880459216001777456e+00,5.662451285057166217e+00,3.765462869237168886e-01,2.119043025768468230e-02,1.239316092015528559e-02,-9.999999401877380789e-01,-5.662451285057171768e-01 +5.900094169005507894e+01,3.599355637557562204e+02,2.884136325225792774e+00,5.662488707772507901e+00,3.765915197538244330e-01,1.942441075509457327e-02,1.139316092015528470e-02,-9.999999406408991431e-01,-5.662488707772512786e-01 +5.900270769799188741e+01,3.599448629908935686e+02,2.887813855084293113e+00,5.662523011436069176e+00,3.766331024323115728e-01,1.765840292311732229e-02,1.039316092015528381e-02,-9.999999415546708681e-01,-5.662523011436074727e-01 +5.900447369523018892e+01,3.599541620731013154e+02,2.891491771626718776e+00,5.662554196126864170e+00,3.766710350423544962e-01,1.589240578803272422e-02,9.393160920155282922e-03,-9.999999420168287356e-01,-5.662554196126868833e-01 +5.900623968274283015e+01,3.599634610157894485e+02,2.895170040904957443e+00,5.662582261917031623e+00,3.767053176598266773e-01,1.412641837779156535e-02,8.393160920155282034e-03,-9.999999428026300485e-01,-5.662582261917031845e-01 +5.900800566150260096e+01,3.599727598323714233e+02,2.898848628973129671e+00,5.662607208871838438e+00,3.767359503532994314e-01,1.236043971903017132e-02,7.393160920155282013e-03,-9.999999426725291185e-01,-5.662607208871838216e-01 +5.900977163248224855e+01,3.599820585362639349e+02,2.902527501887373962e+00,5.662629037049677905e+00,3.767629331840425255e-01,1.059446884062315714e-02,6.393160920155281993e-03,-9.999999437832765015e-01,-5.662629037049677905e-01 +5.901153759665447041e+01,3.599913571408866915e+02,2.906206625705632263e+00,5.662647746502074142e+00,3.767862662060245671e-01,8.828504767680295240e-03,5.393160920155281972e-03,-9.999999434288476818e-01,-5.662647746502074142e-01 +5.901330355499192137e+01,3.600006556596618452e+02,2.909885966487435027e+00,5.662663337273675879e+00,3.768059494659135589e-01,7.062546530128671271e-03,4.393160920155281951e-03,-9.999999442931337690e-01,-5.662663337273675657e-01 +5.901506950846723498e+01,3.600099541060137653e+02,2.913565490293686722e+00,5.662675809402265337e+00,3.768219830030772322e-01,5.296593153188925568e-03,3.393160920155281930e-03,-9.999999439124007683e-01,-5.662675809402265559e-01 +5.901683545805300923e+01,3.600192524933686968e+02,2.917245163186450441e+00,5.662685162918750237e+00,3.768343668495832688e-01,3.530643666460392925e-03,2.393160920155281909e-03,-9.999999443584940417e-01,-5.662685162918750237e-01 +5.901860140472182081e+01,3.600285508351544195e+02,2.920924951228733857e+00,5.662691397847171793e+00,3.768431010301996342e-01,1.764697095906118300e-03,1.393160920155281889e-03,-9.999999442644067482e-01,-5.662691397847171570e-01 +5.902036734944623220e+01,3.600378491447998499e+02,2.924604820484273393e+00,5.662694514204698493e+00,3.768481855623948551e-01,-1.247530079652998104e-06,3.931609201552818678e-04,-9.999999442355174128e-01,-5.662694514204699159e-01 +5.902213329319879165e+01,3.600471474357347574e+02,2.928284737017320172e+00,5.662694512001630542e+00,3.768496204563379637e-01,-1.767191184159963308e-03,-6.068390798447181531e-04,-9.999999442863692911e-01,-5.662694512001630320e-01 +5.902389923695203322e+01,3.600564457213893661e+02,2.931964666892424631e+00,5.662691391241398087e+00,3.768474057148987755e-01,-3.533134839017114739e-03,-1.606839079844718174e-03,-9.999999444102747326e-01,-5.662691391241397865e-01 +5.902566518167850518e+01,3.600657440151940136e+02,2.935644576174221587e+00,5.662685151920561211e+00,3.768415413336478337e-01,-5.299079467320531173e-03,-2.606839079844718195e-03,-9.999999437249066370e-01,-5.662685151920561211e-01 +5.902743112835074868e+01,3.600750423305789241e+02,2.939324430927215293e+00,5.662675794028809939e+00,3.768320273008562982e-01,-7.065026040185783812e-03,-3.606839079844718216e-03,-9.999999438899377369e-01,-5.662675794028809717e-01 +5.902919707794131909e+01,3.600843406809736393e+02,2.943004197215564943e+00,5.662663317548966901e+00,3.768188635974959455e-01,-8.830975531668979264e-03,-4.606839079844718236e-03,-9.999999431261744620e-01,-5.662663317548967123e-01 +5.903096303142278600e+01,3.600936390798069056e+02,2.946683841102869739e+00,5.662647722456982002e+00,3.768020501972390579e-01,-1.059692891269926017e-02,-5.606839079844718257e-03,-9.999999433356138168e-01,-5.662647722456981558e-01 +5.903272898976774030e+01,3.601029375405062183e+02,2.950363328651953054e+00,5.662629008721937751e+00,3.767815870664580902e-01,-1.236288715758496019e-02,-6.606839079844718278e-03,-9.999999424118105606e-01,-5.662629008721937751e-01 +5.903449495394879420e+01,3.601122360764973678e+02,2.954042625924648391e+00,5.662607176306043044e+00,3.767574741642254477e-01,-1.412885123694023436e-02,-7.606839079844718299e-03,-9.999999422142779038e-01,-5.662607176306048151e-01 +5.903626092493859545e+01,3.601215347012043821e+02,2.957721698981584879e+00,5.662582225164639382e+00,3.767297114423132087e-01,-1.589482212469413291e-02,-8.606839079844719187e-03,-9.999999414484996851e-01,-5.662582225164645156e-01 +5.903802690370982731e+01,3.601308334280489021e+02,2.961400513881971897e+00,5.662554155246194654e+00,3.766982988451926806e-01,-1.766080079252605947e-02,-9.606839079844720075e-03,-9.999999407923109151e-01,-5.662554155246199983e-01 +5.903979289123521568e+01,3.601401322704499535e+02,2.965079036683383684e+00,5.662522966492306686e+00,3.766632363100339553e-01,-1.942678821335423744e-02,-1.060683907984472096e-02,-9.999999400478956080e-01,-5.662522966492311571e-01 +5.904155888848752909e+01,3.601494312418236063e+02,2.968757233441545740e+00,5.662488658837700584e+00,3.766245237667054102e-01,-2.119278535979469275e-02,-1.160683907984472185e-02,-9.999999392809900689e-01,-5.662488658837705469e-01 +5.904332489643960002e+01,3.601587303555826338e+02,2.972435070210119434e+00,5.662451232210228724e+00,3.765821611377732636e-01,-2.295879320463204212e-02,-1.260683907984472274e-02,-9.999999382512928525e-01,-5.662451232210233831e-01 +5.904509091606430360e+01,3.601680296251361710e+02,2.976112513040487517e+00,5.662410686530869874e+00,3.765361483385007424e-01,-2.472481272028438648e-02,-1.360683907984472363e-02,-9.999999372668011421e-01,-5.662410686530875426e-01 +5.904685694833458598e+01,3.601773290638893172e+02,2.979789527981539621e+00,5.662367021713729187e+00,3.764864852768475822e-01,-2.649084487977697300e-02,-1.460683907984472452e-02,-9.999999360446923946e-01,-5.662367021713734516e-01 +5.904862299422346439e+01,3.601866286852427947e+02,2.983466081079457322e+00,5.662320237666036427e+00,3.764331718534691951e-01,-2.825689065570415742e-02,-1.560683907984472540e-02,-9.999999351351928079e-01,-5.662320237666040867e-01 +5.905038905470402000e+01,3.601959285025927215e+02,2.987142138377499645e+00,5.662270334288145968e+00,3.763762079617158918e-01,-3.002295102170596600e-02,-1.660683907984472629e-02,-9.999999333586351291e-01,-5.662270334288150853e-01 +5.905215513074942635e+01,3.602052285293300429e+02,2.990817665915789458e+00,5.662217311473534131e+00,3.763155934876321052e-01,-3.178902694941836832e-02,-1.760683907984472718e-02,-9.999999317922275699e-01,-5.662217311473538572e-01 +5.905392122333293514e+01,3.602145287788404744e+02,2.994492629731097644e+00,5.662161169108801850e+00,3.762513283099553352e-01,-3.355511941246441809e-02,-1.860683907984472807e-02,-9.999999306375196850e-01,-5.662161169108806957e-01 +5.905568733342788335e+01,3.602238292645038769e+02,2.998166995856630379e+00,5.662101907073670226e+00,3.761834123001152608e-01,-3.532122938491318032e-02,-1.960683907984472896e-02,-9.999999283663104643e-01,-5.662101907073675555e-01 +5.905745346200771451e+01,3.602331299996941425e+02,3.001840730321813311e+00,5.662039525240978755e+00,3.761118453222327962e-01,-3.708735783823015331e-02,-2.060683907984472985e-02,-9.999999265613255250e-01,-5.662039525240983862e-01 +5.905921961004596454e+01,3.602424309977786834e+02,3.005513799152079280e+00,5.661974023476688878e+00,3.760366272331188142e-01,-3.885350574677687990e-02,-2.160683907984473073e-02,-9.999999242212646022e-01,-5.661974023476693541e-01 +5.906098577851627596e+01,3.602517322721180903e+02,3.009186168368652492e+00,5.661905401639877766e+00,3.759577578822730914e-01,-4.061967408325261458e-02,-2.260683907984473162e-02,-9.999999220319426563e-01,-5.661905401639882873e-01 +5.906275196839241204e+01,3.602610338360659625e+02,3.012857803988335359e+00,5.661833659582740097e+00,3.758752371118832536e-01,-4.238586382167938010e-02,-2.360683907984473251e-02,-9.999999189494532814e-01,-5.661833659582744538e-01 +5.906451818064823556e+01,3.602703357029683389e+02,3.016528672023294888e+00,5.661758797150584499e+00,3.757890647568232212e-01,-4.415207593435234446e-02,-2.460683907984473340e-02,-9.999999161863839525e-01,-5.661758797150588940e-01 +5.906628441625775139e+01,3.602796378861635276e+02,3.020198738480848633e+00,5.661680814181835331e+00,3.756992406446520438e-01,-4.591831139583060079e-02,-2.560683907984473429e-02,-9.999999126561631702e-01,-5.661680814181839771e-01 +5.906805067619507099e+01,3.602889403989816515e+02,3.023867969363251085e+00,5.661599710508027350e+00,3.756057645956126234e-01,-4.768457117888174474e-02,-2.660683907984473517e-02,-9.999999092438872639e-01,-5.661599710508032901e-01 +5.906981696143446214e+01,3.602982432547443636e+02,3.027536330667480069e+00,5.661515485953807492e+00,3.755086364226301043e-01,-4.945085625796967477e-02,-2.760683907984473606e-02,-9.999999048203540575e-01,-5.661515485953811933e-01 +5.907158327295031341e+01,3.603075464667643928e+02,3.031203788385023135e+00,5.661428140336930426e+00,3.754078559313103747e-01,-5.121716760570218380e-02,-2.860683907984473695e-02,-9.999998999432014868e-01,-5.661428140336934867e-01 +5.907334961171716259e+01,3.603168500483453727e+02,3.034870308501664837e+00,5.661337673468260334e+00,3.753034229199386784e-01,-5.298350619581575216e-02,-2.960683907984473784e-02,-9.999998948639147178e-01,-5.661337673468265219e-01 +5.907511597870969666e+01,3.603261540127813873e+02,3.038535856997273576e+00,5.661244085151767358e+00,3.751953371794777836e-01,-5.474987300264021195e-02,-3.060683907984473873e-02,-9.999998889585646200e-01,-5.661244085151772021e-01 +5.907688237490275895e+01,3.603354583733565732e+02,3.042200399845587544e+00,5.661147375184524932e+00,3.750835984935664835e-01,-5.651626899955783379e-02,-3.160683907984473962e-02,-9.999998812972894502e-01,-5.661147375184529817e-01 +5.907864880127134910e+01,3.603447631433448919e+02,3.045863903014002894e+00,5.661047543356709788e+00,3.749682066385177648e-01,-5.828269515846823401e-02,-3.260683907984474050e-02,-9.999998737752686662e-01,-5.661047543356714229e-01 +5.908041525879063727e+01,3.603540683360096750e+02,3.049526332463360578e+00,5.660944589451602837e+00,3.748491613833170866e-01,-6.004915245478396196e-02,-3.360683907984474139e-02,-9.999998639965722580e-01,-5.660944589451608611e-01 +5.908218174843595705e+01,3.603633739646033405e+02,3.053187654147733632e+00,5.660838513245581183e+00,3.747264624896204377e-01,-6.181564185985592708e-02,-3.460683907984474228e-02,-9.999998523903843584e-01,-5.660838513245586290e-01 +5.908394827118282677e+01,3.603726800423671079e+02,3.056847834014215337e+00,5.660729314508123444e+00,3.746001097117525047e-01,-6.358216434596911104e-02,-3.560683907984474317e-02,-9.999998393643388939e-01,-5.660729314508128329e-01 +5.908571482800694241e+01,3.603819865825304873e+02,3.060506838002706065e+00,5.660616993001806208e+00,3.744701027967046736e-01,-6.534872088630994114e-02,-3.660683907984474406e-02,-9.999998221740297177e-01,-5.660616993001811315e-01 +5.908748141988418467e+01,3.603912935983109946e+02,3.064164632045701886e+00,5.660501548482300471e+00,3.743364414841330312e-01,-6.711531244940337204e-02,-3.760683907984474494e-02,-9.999998011844956070e-01,-5.660501548482305134e-01 +5.908924804779062612e+01,3.604006011029139245e+02,3.067821182068082297e+00,5.660382980698377864e+00,3.741991255063562005e-01,-6.888194000461111965e-02,-3.860683907984474583e-02,-9.999997744626687446e-01,-5.660382980698382971e-01 +5.909101471270253825e+01,3.604099091095318386e+02,3.071476453986898392e+00,5.660261289391907091e+00,3.740581545883532866e-01,-7.064860451807711272e-02,-3.960683907984474672e-02,-9.999997380625491594e-01,-5.660261289391911310e-01 +5.909278141559640574e+01,3.604192176313443383e+02,3.075130413711160582e+00,5.660136474297857490e+00,3.739135284477616006e-01,-7.241530694917633348e-02,-4.060683907984474761e-02,-9.999996874484596843e-01,-5.660136474297862152e-01 +5.909454815744890510e+01,3.604285266815175532e+02,3.078783027141628992e+00,5.660008535144308794e+00,3.737652467948744395e-01,-7.418204824947777221e-02,-4.160683907984474850e-02,-9.999996115201307267e-01,-5.660008535144314123e-01 +5.909631493923694023e+01,3.604378362732039704e+02,3.082434260170599849e+00,5.659877471652462688e+00,3.736133093326387544e-01,-7.594882935115085387e-02,-4.260683907984474939e-02,-9.999994843637857178e-01,-5.659877471652466907e-01 +5.909808176193762108e+01,3.604471464195420367e+02,3.086084078681696763e+00,5.659743283536674774e+00,3.734577157566527639e-01,-7.771565114079610759e-02,-4.360683907984475027e-02,-9.999992305474570964e-01,-5.659743283536680103e-01 +5.909984862652829918e+01,3.604564571336557037e+02,3.089732448549658006e+00,5.659605970504532735e+00,3.732984657551635110e-01,-7.948251437195413827e-02,-4.460683907984475116e-02,-9.999984676757056601e-01,-5.659605970504537620e-01 +5.910161553398653922e+01,3.604657684286542008e+02,3.093379335640126460e+00,5.659465532257089038e+00,3.731355590090643659e-01,-8.124941912272172495e-02,-4.560683907984475205e-02,-4.370840176533123955e-01,-5.659465532257094145e-01 +5.910338248529015459e+01,3.604750803176316936e+02,3.097024705809440004e+00,5.659321968490051979e+00,3.729689951918924717e-01,-8.202172529750462182e-02,-4.660683907984475294e-02,9.999985009425974569e-01,-5.659321968490056420e-01 +5.910514948141719316e+01,3.604843928136667728e+02,3.100668524904419687e+00,5.659177036419118068e+00,3.727987739698260805e-01,-8.025473181929224098e-02,-4.760683907984475383e-02,9.999992631446913416e-01,-5.659177036419122953e-01 +5.910691652279717800e+01,3.604937059298222835e+02,3.104310758762161004e+00,5.659035222987053970e+00,3.726248950016819994e-01,-7.848769174136344118e-02,-4.860683907984475471e-02,9.999995173706919260e-01,-5.659035222987058855e-01 +5.910868360845859826e+01,3.605030196791448702e+02,3.107951373209823842e+00,5.658896528512380009e+00,3.724473579389126487e-01,-7.672060693279274257e-02,-4.960683907984475560e-02,9.999996446614048962e-01,-5.658896528512384894e-01 +5.911045073742970146e+01,3.605123340746646363e+02,3.111590334064422425e+00,5.658760953305188579e+00,3.722661624256034529e-01,-7.495347858962035648e-02,-5.060683907984475649e-02,9.999997202085529890e-01,-5.658760953305193020e-01 +5.911221790873849358e+01,3.605216491293948593e+02,3.115227607132615706e+00,5.658628497668330759e+00,3.720813080984698984e-01,-7.318630777526660691e-02,-5.160683907984475738e-02,9.999997713866858318e-01,-5.658628497668335422e-01 +5.911398512141275319e+01,3.605309648563315932e+02,3.118863158210499975e+00,5.658499161897648122e+00,3.718927945868545915e-01,-7.141909550501641946e-02,-5.260683907984475827e-02,9.999998070581684884e-01,-5.658499161897653229e-01 +5.911575237448002440e+01,3.605402812684533274e+02,3.122496953083397475e+00,5.658372946282055338e+00,3.717006215127243718e-01,-6.965184277872493723e-02,-5.360683907984475915e-02,9.999998346403247140e-01,-5.658372946282059779e-01 +5.911751966696762395e+01,3.605495983787205319e+02,3.126128957525649898e+00,5.658249851103565042e+00,3.715047884906672038e-01,-6.788455058336444192e-02,-5.460683907984476004e-02,9.999998555563339719e-01,-5.658249851103570593e-01 +5.911928699790265540e+01,3.605589162000754868e+02,3.129759137300408778e+00,5.658129876637308264e+00,3.713052951278890679e-01,-6.611721990361141277e-02,-5.560683907984476093e-02,9.999998720609218905e-01,-5.658129876637313371e-01 +5.912105436631200917e+01,3.605682347454417709e+02,3.133387458159427652e+00,5.658013023151536203e+00,3.711021410242109075e-01,-6.434985172037127610e-02,-5.660683907984476182e-02,9.999998863872632260e-01,-5.658013023151541310e-01 +5.912282177122236959e+01,3.605775540277240339e+02,3.137013885842854677e+00,5.657899290907624668e+00,3.708953257720652430e-01,-6.258244701081078221e-02,-5.760683907984476271e-02,9.999998970508618967e-01,-5.657899290907629775e-01 +5.912458921166021497e+01,3.605868740598075419e+02,3.140638386079024791e+00,5.657788680160078520e+00,3.706848489564930627e-01,-6.081500675492308022e-02,-5.860683907984476360e-02,9.999999073795697857e-01,-5.657788680160082961e-01 +5.912635668665182465e+01,3.605961948545578934e+02,3.144260924584251882e+00,5.657681191156524569e+00,3.704707101551403814e-01,-5.904753192701685943e-02,-5.960683907984476448e-02,9.999999149936150689e-01,-5.657681191156529454e-01 +5.912812419522329321e+01,3.606055164248205642e+02,3.147881467062622285e+00,5.657576824137719562e+00,3.702529089382549654e-01,-5.728002350579880497e-02,-6.060683907984476537e-02,9.999999226096250027e-01,-5.657576824137724447e-01 +5.912989173640052343e+01,3.606148387834207369e+02,3.151499979205787838e+00,5.657475579337540417e+00,3.700314448686826685e-01,-5.551248246536046038e-02,-6.160683907984476626e-02,9.999999289427661253e-01,-5.657475579337545302e-01 +5.913165930920924040e+01,3.606241619431626759e+02,3.155116426692758935e+00,5.657377456982990438e+00,3.698063175018641013e-01,-5.374490978224538695e-02,-6.260683907984476715e-02,9.999999338243292790e-01,-5.657377456982994879e-01 +5.913342691267498452e+01,3.606334859168296703e+02,3.158730775189699802e+00,5.657282457294193101e+00,3.695775263858310233e-01,-5.197730643347110019e-02,-6.360683907984476804e-02,9.999999390542636535e-01,-5.657282457294198208e-01 +5.913519454582313983e+01,3.606428107171834654e+02,3.162342990349721106e+00,5.657190580484389386e+00,3.693450710612026233e-01,-5.020967339304385768e-02,-6.460683907984476892e-02,9.999999435685671401e-01,-5.657190580484394715e-01 +5.913696220767891987e+01,3.606521363569639220e+02,3.165953037812674786e+00,5.657101826759941332e+00,3.691089510611819668e-01,-4.844201163701557927e-02,-6.560683907984476981e-02,9.999999471349262370e-01,-5.657101826759945995e-01 +5.913872989726737472e+01,3.606614628488888457e+02,3.169560883204948887e+00,5.657016196320326706e+00,3.688691659115519994e-01,-4.667432214200843699e-02,-6.660683907984477070e-02,9.999999506367970303e-01,-5.657016196320331369e-01 +5.914049761361340529e+01,3.606707902056533612e+02,3.173166492139262385e+00,5.656933689358136341e+00,3.686257151306720492e-01,-4.490660588323714536e-02,-6.760683907984477159e-02,9.999999540835932121e-01,-4.448170509130916495e-01 +5.914226535574176324e+01,3.606801184399297995e+02,3.176769830214461354e+00,5.656854306059075022e+00,3.683785982294736638e-01,-4.313886383604857711e-02,-6.839316092015533532e-02,9.999999514950528301e-01,0.000000000000000000e+00 +5.914403312267705104e+01,3.606894475643671285e+02,3.180370863015313798e+00,5.656778046601959709e+00,3.681285982294736914e-01,-4.137109698650474204e-02,-6.839316092015533532e-02,9.999999490912818700e-01,0.000000000000000000e+00 +5.914580091344374324e+01,3.606987775887711223e+02,3.183969563422548887e+00,5.656704911158699112e+00,3.678785982294737189e-01,-3.960330630981028638e-02,-6.839316092015533532e-02,9.999999468179505691e-01,0.000000000000000000e+00 +5.914756872706617230e+01,3.607081085125586242e+02,3.187565931211247872e+00,5.656634899894311452e+00,3.676285982294737464e-01,-3.783549278139854144e-02,-6.839316092015533532e-02,9.999999434626813954e-01,0.000000000000000000e+00 +5.914933656256854277e+01,3.607174403351464775e+02,3.191159966156637662e+00,5.656568012966922687e+00,3.673785982294737740e-01,-3.606765737897339036e-02,-6.839316092015533532e-02,9.999999403496593331e-01,0.000000000000000000e+00 +5.915110441897495264e+01,3.607267730559514689e+02,3.194751668034091274e+00,5.656504250527761180e+00,3.671285982294738015e-01,-3.429980107801971351e-02,-6.839316092015533532e-02,9.999999376449085764e-01,0.000000000000000000e+00 +5.915287229530936486e+01,3.607361066743902711e+02,3.198341036619127387e+00,5.656443612721160363e+00,3.668785982294738290e-01,-3.253192485384538007e-02,-6.839316092015533532e-02,9.999999340722914853e-01,0.000000000000000000e+00 +5.915464019059563583e+01,3.607454411898795001e+02,3.201928071687410338e+00,5.656386099684557855e+00,3.666285982294738566e-01,-3.076402968412544556e-02,-6.839316092015533532e-02,9.999999300394991630e-01,0.000000000000000000e+00 +5.915640810385752246e+01,3.607547766018357720e+02,3.205512773014750572e+00,5.656331711548490127e+00,3.663785982294738841e-01,-2.899611654591999904e-02,-6.839316092015533532e-02,9.999999262170415903e-01,0.000000000000000000e+00 +5.915817603411868220e+01,3.607641129096756458e+02,3.209095140377103750e+00,5.656280448436592501e+00,3.661285982294739116e-01,-2.722818641520409824e-02,-6.839316092015533532e-02,9.999999218332684681e-01,0.000000000000000000e+00 +5.915994398040266589e+01,3.607734501128156239e+02,3.212675173550572527e+00,5.656232310465600044e+00,3.658785982294739392e-01,-2.546024026941199822e-02,-6.839316092015533532e-02,9.999999169477221672e-01,0.000000000000000000e+00 +5.916171194173294623e+01,3.607827882106720949e+02,3.216252872311404332e+00,5.656187297745344011e+00,3.656285982294739667e-01,-2.369227908596229296e-02,-6.839316092015533532e-02,9.999999121669060909e-01,0.000000000000000000e+00 +5.916347991713291066e+01,3.607921272026613906e+02,3.219828236435993585e+00,5.656145410378750960e+00,3.653785982294739942e-01,-2.192430384128550569e-02,-6.839316092015533532e-02,9.999999066552180960e-01,0.000000000000000000e+00 +5.916524790562586134e+01,3.608014670881998995e+02,3.223401265700879481e+00,5.656106648461843633e+00,3.651285982294740218e-01,-2.015631551336828642e-02,-6.839316092015533532e-02,9.999999006923376843e-01,0.000000000000000000e+00 +5.916701590623502938e+01,3.608108078667038399e+02,3.226971959882747765e+00,5.656071012083737415e+00,3.648785982294740493e-01,-1.838831507977624347e-02,-6.839316092015533532e-02,9.999998936841554276e-01,0.000000000000000000e+00 +5.916878391798358194e+01,3.608201495375894297e+02,3.230540318758430285e+00,5.656038501326640322e+00,3.646285982294740768e-01,-1.662030351919339954e-02,-6.839316092015533532e-02,9.999998870041668653e-01,0.000000000000000000e+00 +5.917055193989461515e+01,3.608294921002727733e+02,3.234106342104904552e+00,5.656009116265850345e+00,3.643785982294741044e-01,-1.485228180793804996e-02,-6.839316092015533532e-02,9.999998788790014359e-01,0.000000000000000000e+00 +5.917231997099117535e+01,3.608388355541699752e+02,3.237670029699294183e+00,5.655982856969758998e+00,3.641285982294741319e-01,-1.308425092552106643e-02,-6.839316092015533532e-02,9.999998703552831492e-01,0.000000000000000000e+00 +5.917408801029625920e+01,3.608481798986970830e+02,3.241231381318868454e+00,5.655959723499845104e+00,3.638785982294741594e-01,-1.131621184965469866e-02,-6.839316092015533532e-02,9.999998607534544837e-01,0.000000000000000000e+00 +5.917585605683280647e+01,3.608575251332700873e+02,3.244790396741043192e+00,5.655939715910677457e+00,3.636285982294741870e-01,-9.548165559299106112e-03,-6.839316092015533532e-02,9.999998499408578878e-01,0.000000000000000000e+00 +5.917762410962372854e+01,3.608668712573049220e+02,3.248347075743379886e+00,5.655922834249912157e+00,3.633785982294742145e-01,-7.780113033690025555e-03,-6.839316092015533532e-02,9.999998383316931472e-01,0.000000000000000000e+00 +5.917939216769189414e+01,3.608762182702174073e+02,3.251901418103585684e+00,5.655909078558291725e+00,3.631285982294742420e-01,-6.012055251366492381e-03,-6.839316092015533532e-02,9.999998248981547544e-01,0.000000000000000000e+00 +5.918116023006013648e+01,3.608855661714234202e+02,3.255453423599514728e+00,5.655898448869645989e+00,3.628785982294742696e-01,-4.243993192714980850e-03,-6.839316092015533532e-02,9.999998100116669342e-01,0.000000000000000000e+00 +5.918292829575127456e+01,3.608949149603386672e+02,3.259003092009166380e+00,5.655890945210888532e+00,3.626285982294742971e-01,-2.475927837490081353e-03,-6.839316092015533532e-02,9.999997931698866305e-01,0.000000000000000000e+00 +5.918469636378809895e+01,3.609042646363788549e+02,3.262550423110686548e+00,5.655886567602017578e+00,3.623785982294743246e-01,-7.078601663539645008e-04,-6.839316092015533532e-02,9.999997741331921874e-01,0.000000000000000000e+00 +5.918646443319339312e+01,3.609136151989596328e+02,3.266095416682366803e+00,5.655885316056114220e+00,3.621285982294743522e-01,1.060208839593536389e-03,-6.839316092015533532e-02,9.999997517881954456e-01,0.000000000000000000e+00 +5.918823250298993344e+01,3.609229666474965939e+02,3.269638072502645265e+00,5.655887190579341528e+00,3.618785982294743797e-01,2.828278197275459465e-03,-6.839316092015533532e-02,9.999997264206906822e-01,0.000000000000000000e+00 +5.919000057220048205e+01,3.609323189814052739e+02,3.273178390350105715e+00,5.655892191170940997e+00,3.616285982294744072e-01,4.596346924116984610e-03,-6.839316092015533532e-02,9.999996974426869079e-01,0.000000000000000000e+00 +5.919176863984781534e+01,3.609416722001010953e+02,3.276716370003478485e+00,5.655900317823233436e+00,3.613785982294744348e-01,6.364414036505943763e-03,-6.839316092015533532e-02,9.999996622559117476e-01,0.000000000000000000e+00 +5.919353670495470965e+01,3.609510263029995372e+02,3.280252011241640009e+00,5.655911570521617193e+00,3.611285982294744623e-01,8.132478546243940981e-03,-6.839316092015533532e-02,9.999996213659562150e-01,0.000000000000000000e+00 +5.919530476654395557e+01,3.609603812895159649e+02,3.283785313843612386e+00,5.655925949244560158e+00,3.608785982294744898e-01,9.900539466039635569e-03,-6.839316092015533532e-02,9.999995718474721240e-01,0.000000000000000000e+00 +5.919707282363836498e+01,3.609697371590656871e+02,3.287316277588564262e+00,5.655943453963601542e+00,3.606285982294745174e-01,1.166859580344808099e-02,-6.839316092015533532e-02,9.999995116059439138e-01,0.000000000000000000e+00 +5.919884087526077110e+01,3.609790939110640124e+02,3.290844902255810389e+00,5.655964084643342993e+00,3.603785982294745449e-01,1.343664656234518258e-02,-6.839316092015533532e-02,9.999994365363775728e-01,0.000000000000000000e+00 +5.920060892043403555e+01,3.609884515449260789e+02,3.294371187624811625e+00,5.655987841241442382e+00,3.601285982294745724e-01,1.520469073937859468e-02,-6.839316092015533532e-02,9.999993416597016127e-01,0.000000000000000000e+00 +5.920237695818105550e+01,3.609978100600670246e+02,3.297895133475175378e+00,5.656014723708601366e+00,3.598785982294746000e-01,1.697272732242791418e-02,-6.839316092015533532e-02,9.999992177130132553e-01,0.000000000000000000e+00 +5.920414498752477073e+01,3.610071694559019875e+02,3.301416739586655158e+00,5.656044731988550289e+00,3.596285982294746275e-01,1.874075528303640811e-02,-6.839316092015533532e-02,9.999990505809415176e-01,0.000000000000000000e+00 +5.920591300748816366e+01,3.610165297318459920e+02,3.304936005739150140e+00,5.656077866018019762e+00,3.593785982294746550e-01,2.050877356783763553e-02,-6.839316092015533532e-02,9.999988147598732890e-01,0.000000000000000000e+00 +5.920768101709426645e+01,3.610258908873140058e+02,3.308452931712706491e+00,5.656114125726697139e+00,3.591285982294746826e-01,2.227678107842710753e-02,-6.839316092015533532e-02,9.999984597178543932e-01,0.000000000000000000e+00 +5.920944901536617522e+01,3.610352529217209963e+02,3.311967517287516483e+00,5.656153511037147474e+00,3.588785982294747101e-01,2.404477662711907229e-02,-6.839316092015533532e-02,9.999978706793761773e-01,0.000000000000000000e+00 +5.921121700132703580e+01,3.610446158344818173e+02,3.315479762243918049e+00,5.656196021864656309e+00,3.586285982294747376e-01,2.581275882337316641e-02,-6.839316092015533532e-02,9.999967225636675616e-01,0.000000000000000000e+00 +5.921298497400007221e+01,3.610539796250112659e+02,3.318989666362396118e+00,5.656241658116871740e+00,3.583785982294747652e-01,2.758072570199276985e-02,-6.839316092015533532e-02,9.999935536063153663e-01,0.000000000000000000e+00 +5.921475293240857951e+01,3.610633442927240822e+02,3.322497229423581722e+00,5.656290419692789229e+00,3.581285982294747927e-01,2.934867271354114557e-02,-6.839316092015533532e-02,9.999493031337343130e-01,0.000000000000000000e+00 +5.921652087557592381e+01,3.610727098370350063e+02,3.326002451208252442e+00,5.656342306478183701e+00,3.578785982294748202e-01,3.111652625170520034e-02,-6.839316092015533532e-02,-9.999901365614054516e-01,0.000000000000000000e+00 +5.921828880252556360e+01,3.610820762573587217e+02,3.329505331497331522e+00,5.656397318223523207e+00,3.576285982294748478e-01,2.934861673990616857e-02,-6.839316092015533532e-02,-9.999952069497608509e-01,0.000000000000000000e+00 +5.922005671228108525e+01,3.610914435531097979e+02,3.333005870071889198e+00,5.656449203929368785e+00,3.573785982294748753e-01,2.758071545806371067e-02,-6.839316092015533532e-02,-9.999966878063186737e-01,0.000000000000000000e+00 +5.922182460581985453e+01,3.611008117237027477e+02,3.336504066713141370e+00,5.656497963698021714e+00,3.571285982294749028e-01,2.581282777490083447e-02,-6.839316092015533532e-02,-9.999973764234864060e-01,0.000000000000000000e+00 +5.922359248411914479e+01,3.611101807685521408e+02,3.339999921202451372e+00,5.656543597636088272e+00,3.568785982294749304e-01,2.404495411377478506e-02,-6.839316092015533532e-02,-9.999977593138132947e-01,0.000000000000000000e+00 +5.922536034815615125e+01,3.611195506870723193e+02,3.343493433321327757e+00,5.656586105845737400e+00,3.566285982294749579e-01,2.227709403800038485e-02,-6.839316092015533532e-02,-9.999979885186172091e-01,0.000000000000000000e+00 +5.922712819890797675e+01,3.611289214786777393e+02,3.346984602851426072e+00,5.656625488423181025e+00,3.563785982294749854e-01,2.050924684217111937e-02,-6.839316092015533532e-02,-9.999981276865984592e-01,0.000000000000000000e+00 +5.922889603735166730e+01,3.611382931427826861e+02,3.350473429574548412e+00,5.656661745458199775e+00,3.561285982294750130e-01,1.874141170842717752e-02,-6.839316092015533532e-02,-9.999982026522215017e-01,0.000000000000000000e+00 +5.923066386446419074e+01,3.611476656788014452e+02,3.353959913272643423e+00,5.656694877033944913e+00,3.558785982294750405e-01,1.697358777330301716e-02,-6.839316092015533532e-02,-9.999982292839955100e-01,0.000000000000000000e+00 +5.923243168122245095e+01,3.611570390861482451e+02,3.357444053727805411e+00,5.656724883226858402e+00,3.556285982294750680e-01,1.520577414534163285e-02,-6.839316092015533532e-02,-9.999982100729261081e-01,0.000000000000000000e+00 +5.923419948860330209e+01,3.611664133642372008e+02,3.360925850722275676e+00,5.656751764106624059e+00,3.553785982294750956e-01,1.343796992873903806e-02,-6.839316092015533532e-02,-9.999981426578027355e-01,0.000000000000000000e+00 +5.923596728758353436e+01,3.611757885124824838e+02,3.364405304038442068e+00,5.656775519736160440e+00,3.551285982294751231e-01,1.167017423191702395e-02,-6.839316092015533532e-02,-9.999980152775670428e-01,0.000000000000000000e+00 +5.923773507913989533e+01,3.611851645302980955e+02,3.367882413458838542e+00,5.656796150171628845e+00,3.548785982294751506e-01,9.902386184134975497e-03,-6.839316092015533532e-02,-9.999978027920106705e-01,0.000000000000000000e+00 +5.923950286424908285e+01,3.611945414170980371e+02,3.371357178766146045e+00,5.656813655462470614e+00,3.546285982294751782e-01,8.134604959135961766e-03,-6.839316092015533532e-02,-9.999974499129444805e-01,0.000000000000000000e+00 +5.924127064388777342e+01,3.612039191722962528e+02,3.374829599743191189e+00,5.656828035651486175e+00,3.543785982294752057e-01,6.366829828436186035e-03,-6.839316092015533532e-02,-9.999968271505352835e-01,0.000000000000000000e+00 +5.924303841903260093e+01,3.612132977953066870e+02,3.378299676172948462e+00,5.656839290775008244e+00,3.541285982294752332e-01,4.599060292490998736e-03,-6.839316092015533532e-02,-9.999955366933017675e-01,0.000000000000000000e+00 +5.924480619066017795e+01,3.612226772855431136e+02,3.381767407838537576e+00,5.656847420863306830e+00,3.538785982294752608e-01,2.831296555020036080e-03,-6.839316092015533532e-02,-9.999915939258920972e-01,0.000000000000000000e+00 +5.924657395974709573e+01,3.612320576424193632e+02,3.385232794523225230e+00,5.656852425941832685e+00,3.536285982294752883e-01,1.063542328102456015e-03,-6.839316092015533532e-02,-6.016935663474189955e-01,0.000000000000000000e+00 +5.924834172726992421e+01,3.612414388653491528e+02,3.388695836010425122e+00,5.656854306037419455e+00,3.533785982294753159e-01,-1.120171799216284032e-07,-6.839316092015533532e-02,6.337785534298224664e-05,0.000000000000000000e+00 +5.925010949420521911e+01,3.612508209537461425e+02,3.392156532083696607e+00,5.656854305839399188e+00,3.531285982294753434e-01,2.009718367133714802e-11,-6.839316092015533532e-02,-1.136868399864488223e-08,0.000000000000000000e+00 +5.925187726114057796e+01,3.612602039070239357e+02,3.395614882526746925e+00,5.656854305839434716e+00,3.528785982294753709e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.925364502807593681e+01,3.612695877245960787e+02,3.399070887123428530e+00,5.656854305839434716e+00,3.526285982294753985e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.925541279501129566e+01,3.612789724058761180e+02,3.402524545657741317e+00,5.656854305839434716e+00,3.523785982294754260e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.925718056194665451e+01,3.612883579502775433e+02,3.405975857913831728e+00,5.656854305839434716e+00,3.521285982294754535e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.925894832888201336e+01,3.612977443572137304e+02,3.409424823675992755e+00,5.656854305839434716e+00,3.518785982294754811e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.926071609581737221e+01,3.613071316260979984e+02,3.412871442728663940e+00,5.656854305839434716e+00,3.516285982294755086e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.926248386275273106e+01,3.613165197563436664e+02,3.416315714856431818e+00,5.656854305839434716e+00,3.513785982294755361e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.926425162968808991e+01,3.613259087473639966e+02,3.419757639844029029e+00,5.656854305839434716e+00,3.511285982294755637e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.926601939662344876e+01,3.613352985985721375e+02,3.423197217476335652e+00,5.656854305839434716e+00,3.508785982294755912e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.926778716355880761e+01,3.613446893093812378e+02,3.426634447538377870e+00,5.656854305839434716e+00,3.506285982294756187e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.926955493049416646e+01,3.613540808792043890e+02,3.430069329815328860e+00,5.656854305839434716e+00,3.503785982294756463e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.927132269742952531e+01,3.613634733074546261e+02,3.433501864092508349e+00,5.656854305839434716e+00,3.501285982294756738e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.927309046436488416e+01,3.613728665935449271e+02,3.436932050155383056e+00,5.656854305839434716e+00,3.498785982294757013e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.927485823130024301e+01,3.613822607368882132e+02,3.440359887789566251e+00,5.656854305839434716e+00,3.496285982294757289e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.927662599823560186e+01,3.613916557368972917e+02,3.443785376780818197e+00,5.656854305839434716e+00,3.493785982294757564e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.927839376517096071e+01,3.614010515929850271e+02,3.447208516915045706e+00,5.656854305839434716e+00,3.491285982294757839e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.928016153210631956e+01,3.614104483045641700e+02,3.450629307978302585e+00,5.656854305839434716e+00,3.488785982294758115e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.928192929904167841e+01,3.614198458710474142e+02,3.454047749756789631e+00,5.656854305839434716e+00,3.486285982294758390e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.928369706597703725e+01,3.614292442918474535e+02,3.457463842036854196e+00,5.656854305839434716e+00,3.483785982294758665e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.928546483291239610e+01,3.614386435663768111e+02,3.460877584604990176e+00,5.656854305839434716e+00,3.481285982294758941e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.928723259984775495e+01,3.614480436940480672e+02,3.464288977247838908e+00,5.656854305839434716e+00,3.478785982294759216e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.928900036678311380e+01,3.614574446742737450e+02,3.467698019752188276e+00,5.656854305839434716e+00,3.476285982294759491e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.929076813371847265e+01,3.614668465064662541e+02,3.471104711904973161e+00,5.656854305839434716e+00,3.473785982294759767e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.929253590065383150e+01,3.614762491900380041e+02,3.474509053493274990e+00,5.656854305839434716e+00,3.471285982294760042e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.929430366758919035e+01,3.614856527244012909e+02,3.477911044304323074e+00,5.656854305839434716e+00,3.468785982294760317e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.929607143452454920e+01,3.614950571089684104e+02,3.481310684125492383e+00,5.656854305839434716e+00,3.466285982294760593e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.929783920145990805e+01,3.615044623431516015e+02,3.484707972744305771e+00,5.656854305839434716e+00,3.463785982294760868e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.929960696839526690e+01,3.615138684263629898e+02,3.488102909948432639e+00,5.656854305839434716e+00,3.461285982294761143e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.930137473533062575e+01,3.615232753580147573e+02,3.491495495525689385e+00,5.656854305839434716e+00,3.458785982294761419e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.930314250226598460e+01,3.615326831375189158e+02,3.494885729264039398e+00,5.656854305839434716e+00,3.456285982294761694e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.930491026920134345e+01,3.615420917642875338e+02,3.498273610951593060e+00,5.656854305839434716e+00,3.453785982294761969e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.930667803613670230e+01,3.615515012377325661e+02,3.501659140376607748e+00,5.656854305839434716e+00,3.451285982294762245e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.930844580307206115e+01,3.615609115572658538e+02,3.505042317327487833e+00,5.656854305839434716e+00,3.448785982294762520e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.931021357000742000e+01,3.615703227222992950e+02,3.508423141592784678e+00,5.656854305839434716e+00,3.446285982294762795e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.931198133694277885e+01,3.615797347322447308e+02,3.511801612961197083e+00,5.656854305839434716e+00,3.443785982294763071e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.931374910387813770e+01,3.615891475865138887e+02,3.515177731221570401e+00,5.656854305839434716e+00,3.441285982294763346e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.931551687081349655e+01,3.615985612845184392e+02,3.518551496162896974e+00,5.656854305839434716e+00,3.438785982294763621e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.931728463774885540e+01,3.616079758256700529e+02,3.521922907574317030e+00,5.656854305839434716e+00,3.436285982294763897e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.931905240468421425e+01,3.616173912093802869e+02,3.525291965245116899e+00,5.656854305839434716e+00,3.433785982294764172e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.932082017161957310e+01,3.616268074350606980e+02,3.528658668964730794e+00,5.656854305839434716e+00,3.431285982294764447e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.932258793855493195e+01,3.616362245021227864e+02,3.532023018522739477e+00,5.656854305839434716e+00,3.428785982294764723e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.932435570549029080e+01,3.616456424099779383e+02,3.535385013708871593e+00,5.656854305839434716e+00,3.426285982294764998e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.932612347242564965e+01,3.616550611580375971e+02,3.538744654313001892e+00,5.656854305839434716e+00,3.423785982294765273e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.932789123936100850e+01,3.616644807457130355e+02,3.542101940125153003e+00,5.656854305839434716e+00,3.421285982294765549e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.932965900629636735e+01,3.616739011724155830e+02,3.545456870935494553e+00,5.656854305839434716e+00,3.418785982294765824e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.933142677323172620e+01,3.616833224375563987e+02,3.548809446534343603e+00,5.656854305839434716e+00,3.416285982294766099e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.933319454016708505e+01,3.616927445405466983e+02,3.552159666712163766e+00,5.656854305839434716e+00,3.413785982294766375e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.933496230710244390e+01,3.617021674807975842e+02,3.555507531259566534e+00,5.656854305839434716e+00,3.411285982294766650e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.933673007403780275e+01,3.617115912577201584e+02,3.558853039967310394e+00,5.656854305839434716e+00,3.408785982294766925e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.933849784097316160e+01,3.617210158707254095e+02,3.562196192626301272e+00,5.656854305839434716e+00,3.406285982294767201e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.934026560790852045e+01,3.617304413192242691e+02,3.565536989027591641e+00,5.656854305839434716e+00,3.403785982294767476e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.934203337484387930e+01,3.617398676026277258e+02,3.568875428962381857e+00,5.656854305839434716e+00,3.401285982294767751e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.934380114177923815e+01,3.617492947203465405e+02,3.572211512222019714e+00,5.656854305839434716e+00,3.398785982294768027e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.934556890871459700e+01,3.617587226717915883e+02,3.575545238597999553e+00,5.656854305839434716e+00,3.396285982294768302e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.934733667564995585e+01,3.617681514563735732e+02,3.578876607881964045e+00,5.656854305839434716e+00,3.393785982294768577e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.934910444258531470e+01,3.617775810735032564e+02,3.582205619865701962e+00,5.656854305839434716e+00,3.391285982294768853e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.935087220952067355e+01,3.617870115225912286e+02,3.585532274341150405e+00,5.656854305839434716e+00,3.388785982294769128e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.935263997645603240e+01,3.617964428030481372e+02,3.588856571100393467e+00,5.656854305839434716e+00,3.386285982294769403e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.935440774339139125e+01,3.618058749142844590e+02,3.592178509935662678e+00,5.656854305839434716e+00,3.383785982294769679e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.935617551032675010e+01,3.618153078557107278e+02,3.595498090639337008e+00,5.656854305839434716e+00,3.381285982294769954e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.935794327726210895e+01,3.618247416267374206e+02,3.598815313003942418e+00,5.656854305839434716e+00,3.378785982294770229e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.935971104419746780e+01,3.618341762267749004e+02,3.602130176822152308e+00,5.656854305839434716e+00,3.376285982294770505e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.936147881113282665e+01,3.618436116552334738e+02,3.605442681886787959e+00,5.656854305839434716e+00,3.373785982294770780e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.936324657806818550e+01,3.618530479115234471e+02,3.608752827990817647e+00,5.656854305839434716e+00,3.371285982294771055e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.936501434500354435e+01,3.618624849950550697e+02,3.612060614927357527e+00,5.656854305839434716e+00,3.368785982294771331e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.936678211193890320e+01,3.618719229052384776e+02,3.615366042489670750e+00,5.656854305839434716e+00,3.366285982294771606e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.936854987887426205e+01,3.618813616414838634e+02,3.618669110471167905e+00,5.656854305839434716e+00,3.363785982294771881e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.937031764580962090e+01,3.618908012032012493e+02,3.621969818665407459e+00,5.656854305839434716e+00,3.361285982294772157e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.937208541274497975e+01,3.619002415898007143e+02,3.625268166866095321e+00,5.656854305839434716e+00,3.358785982294772432e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.937385317968033860e+01,3.619096828006921669e+02,3.628564154867084390e+00,5.656854305839434716e+00,3.356285982294772707e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.937562094661569745e+01,3.619191248352855723e+02,3.631857782462375450e+00,5.656854305839434716e+00,3.353785982294772983e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.937738871355105630e+01,3.619285676929908391e+02,3.635149049446117164e+00,5.656854305839434716e+00,3.351285982294773258e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.937915648048641515e+01,3.619380113732177620e+02,3.638437955612604746e+00,5.656854305839434716e+00,3.348785982294773533e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.938092424742177400e+01,3.619474558753760789e+02,3.641724500756282179e+00,5.656854305839434716e+00,3.346285982294773809e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.938269201435713285e+01,3.619569011988755278e+02,3.645008684671739996e+00,5.656854305839434716e+00,3.343785982294774084e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.938445978129249170e+01,3.619663473431257898e+02,3.648290507153716611e+00,5.656854305839434716e+00,3.341285982294774359e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.938622754822785055e+01,3.619757943075364892e+02,3.651569967997098320e+00,5.656854305839434716e+00,3.338785982294774635e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.938799531516320940e+01,3.619852420915171365e+02,3.654847066996918858e+00,5.656854305839434716e+00,3.336285982294774910e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.938976308209856825e+01,3.619946906944772991e+02,3.658121803948359396e+00,5.656854305839434716e+00,3.333785982294775185e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.939153084903392710e+01,3.620041401158264307e+02,3.661394178646748987e+00,5.656854305839434716e+00,3.331285982294775461e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.939329861596928595e+01,3.620135903549739282e+02,3.664664190887564565e+00,5.656854305839434716e+00,3.328785982294775736e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.939506638290464480e+01,3.620230414113291317e+02,3.667931840466429616e+00,5.656854305839434716e+00,3.326285982294776011e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.939683414984000365e+01,3.620324932843013812e+02,3.671197127179116393e+00,5.656854305839434716e+00,3.323785982294776287e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.939860191677536250e+01,3.620419459732999599e+02,3.674460050821544588e+00,5.656854305839434716e+00,3.321285982294776562e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.940036968371072135e+01,3.620513994777340372e+02,3.677720611189781330e+00,5.656854305839434716e+00,3.318785982294776837e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.940213745064608020e+01,3.620608537970127827e+02,3.680978808080042075e+00,5.656854305839434716e+00,3.316285982294777113e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.940390521758143905e+01,3.620703089305453091e+02,3.684234641288688827e+00,5.656854305839434716e+00,3.313785982294777388e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.940567298451679790e+01,3.620797648777406152e+02,3.687488110612232362e+00,5.656854305839434716e+00,3.311285982294777663e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.940744075145215675e+01,3.620892216380077571e+02,3.690739215847330890e+00,5.656854305839434716e+00,3.308785982294777939e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.940920851838751560e+01,3.620986792107556766e+02,3.693987956790790061e+00,5.656854305839434716e+00,3.306285982294778214e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.941097628532287445e+01,3.621081375953932593e+02,3.697234333239563853e+00,5.656854305839434716e+00,3.303785982294778489e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.941274405225823330e+01,3.621175967913293903e+02,3.700478344990753676e+00,5.656854305839434716e+00,3.301285982294778765e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.941451181919359215e+01,3.621270567979728412e+02,3.703719991841608383e+00,5.656854305839434716e+00,3.298785982294779040e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.941627958612895100e+01,3.621365176147323837e+02,3.706959273589525594e+00,5.656854305839434716e+00,3.296285982294779315e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.941804735306430985e+01,3.621459792410166756e+02,3.710196190032049923e+00,5.656854305839434716e+00,3.293785982294779591e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.941981511999966870e+01,3.621554416762344317e+02,3.713430740966874311e+00,5.656854305839434716e+00,3.291285982294779866e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.942158288693502755e+01,3.621649049197941963e+02,3.716662926191839134e+00,5.656854305839434716e+00,3.288785982294780141e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.942335065387038640e+01,3.621743689711045135e+02,3.719892745504932652e+00,5.656854305839434716e+00,3.286285982294780417e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.942511842080574525e+01,3.621838338295739277e+02,3.723120198704291450e+00,5.656854305839434716e+00,3.283785982294780692e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.942688618774110410e+01,3.621932994946108693e+02,3.726345285588199996e+00,5.656854305839434716e+00,3.281285982294780967e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.942865395467646294e+01,3.622027659656237120e+02,3.729568005955089749e+00,5.656854305839434716e+00,3.278785982294781243e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.943042172161182179e+01,3.622122332420208295e+02,3.732788359603540940e+00,5.656854305839434716e+00,3.276285982294781518e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.943218948854718064e+01,3.622217013232104819e+02,3.736006346332281680e+00,5.656854305839434716e+00,3.273785982294781793e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.943395725548253949e+01,3.622311702086009291e+02,3.739221965940187520e+00,5.656854305839434716e+00,3.271285982294782069e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.943572502241789834e+01,3.622406398976003743e+02,3.742435218226282334e+00,5.656854305839434716e+00,3.268785982294782344e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.943749278935325719e+01,3.622501103896169639e+02,3.745646102989737436e+00,5.656854305839434716e+00,3.266285982294782619e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.943926055628861604e+01,3.622595816840587304e+02,3.748854620029872908e+00,5.656854305839434716e+00,3.263785982294782895e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.944102832322397489e+01,3.622690537803338202e+02,3.752060769146156716e+00,5.656854305839434716e+00,3.261285982294783170e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.944279609015933374e+01,3.622785266778501523e+02,3.755264550138204260e+00,5.656854305839434716e+00,3.258785982294783445e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.944456385709469259e+01,3.622880003760157024e+02,3.758465962805779270e+00,5.656854305839434716e+00,3.256285982294783721e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.944633162403005144e+01,3.622974748742383326e+02,3.761665006948793355e+00,5.656854305839434716e+00,3.253785982294783996e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.944809939096541029e+01,3.623069501719259620e+02,3.764861682367306450e+00,5.656854305839434716e+00,3.251285982294784271e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.944986715790076914e+01,3.623164262684862820e+02,3.768055988861525929e+00,5.656854305839434716e+00,3.248785982294784547e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.945163492483612799e+01,3.623259031633270979e+02,3.771247926231807934e+00,5.656854305839434716e+00,3.246285982294784822e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.945340269177148684e+01,3.623353808558561013e+02,3.774437494278656491e+00,5.656854305839434716e+00,3.243785982294785097e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.945517045870684569e+01,3.623448593454809270e+02,3.777624692802723505e+00,5.656854305839434716e+00,3.241285982294785373e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.945693822564220454e+01,3.623543386316092096e+02,3.780809521604809209e+00,5.656854305839434716e+00,3.238785982294785648e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.945870599257756339e+01,3.623638187136484134e+02,3.783991980485861273e+00,5.656854305839434716e+00,3.236285982294785923e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.946047375951292224e+01,3.623732995910061163e+02,3.787172069246976580e+00,5.656854305839434716e+00,3.233785982294786199e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.946224152644828109e+01,3.623827812630897256e+02,3.790349787689399452e+00,5.656854305839434716e+00,3.231285982294786474e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.946400929338363994e+01,3.623922637293065918e+02,3.793525135614522092e+00,5.656854305839434716e+00,3.228785982294786749e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.946577706031899879e+01,3.624017469890641223e+02,3.796698112823885918e+00,5.656854305839434716e+00,3.226285982294787025e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.946754482725435764e+01,3.624112310417696108e+02,3.799868719119179339e+00,5.656854305839434716e+00,3.223785982294787300e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.946931259418971649e+01,3.624207158868302940e+02,3.803036954302239536e+00,5.656854305839434716e+00,3.221285982294787575e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.947108036112507534e+01,3.624302015236533521e+02,3.806202818175052016e+00,5.656854305839434716e+00,3.218785982294787851e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.947284812806043419e+01,3.624396879516459649e+02,3.809366310539750167e+00,5.656854305839434716e+00,3.216285982294788126e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.947461589499579304e+01,3.624491751702151987e+02,3.812527431198615702e+00,5.656854305839434716e+00,3.213785982294788401e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.947638366193115189e+01,3.624586631787681199e+02,3.815686179954078661e+00,5.656854305839434716e+00,3.211285982294788677e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.947815142886651074e+01,3.624681519767116811e+02,3.818842556608717409e+00,5.656854305839434716e+00,3.208785982294788952e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.947991919580186959e+01,3.624776415634528917e+02,3.821996560965258194e+00,5.656854305839434716e+00,3.206285982294789227e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.948168696273722844e+01,3.624871319383986474e+02,3.825148192826575588e+00,5.656854305839434716e+00,3.203785982294789503e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.948345472967258729e+01,3.624966231009557873e+02,3.828297451995692935e+00,5.656854305839434716e+00,3.201285982294789778e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.948522249660794614e+01,3.625061150505310934e+02,3.831444338275781458e+00,5.656854305839434716e+00,3.198785982294790053e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.948699026354330499e+01,3.625156077865313478e+02,3.834588851470160265e+00,5.656854305839434716e+00,3.196285982294790329e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.948875803047866384e+01,3.625251013083632188e+02,3.837730991382298118e+00,5.656854305839434716e+00,3.193785982294790604e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.949052579741402269e+01,3.625345956154334317e+02,3.840870757815810776e+00,5.656854305839434716e+00,3.191285982294790879e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.949229356434938154e+01,3.625440907071485412e+02,3.844008150574462768e+00,5.656854305839434716e+00,3.188785982294791155e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.949406133128474039e+01,3.625535865829151021e+02,3.847143169462167389e+00,5.656854305839434716e+00,3.186285982294791430e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.949582909822009924e+01,3.625630832421396121e+02,3.850275814282985376e+00,5.656854305839434716e+00,3.183785982294791705e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.949759686515545809e+01,3.625725806842285692e+02,3.853406084841127122e+00,5.656854305839434716e+00,3.181285982294791981e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.949936463209081694e+01,3.625820789085883575e+02,3.856533980940950457e+00,5.656854305839434716e+00,3.178785982294792256e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.950113239902617579e+01,3.625915779146253612e+02,3.859659502386961538e+00,5.656854305839434716e+00,3.176285982294792531e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.950290016596153464e+01,3.626010777017458508e+02,3.862782648983815736e+00,5.656854305839434716e+00,3.173785982294792807e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.950466793289689349e+01,3.626105782693560968e+02,3.865903420536316304e+00,5.656854305839434716e+00,3.171285982294793082e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.950643569983225234e+01,3.626200796168623697e+02,3.869021816849414819e+00,5.656854305839434716e+00,3.168785982294793357e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.950820346676761119e+01,3.626295817436707694e+02,3.872137837728211629e+00,5.656854305839434716e+00,3.166285982294793633e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.950997123370297004e+01,3.626390846491874527e+02,3.875251482977955408e+00,5.656854305839434716e+00,3.163785982294793908e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.951173900063832889e+01,3.626485883328184627e+02,3.878362752404043601e+00,5.656854305839434716e+00,3.161285982294794183e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.951350676757368774e+01,3.626580927939698427e+02,3.881471645812021531e+00,5.656854305839434716e+00,3.158785982294794459e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.951527453450904659e+01,3.626675980320475219e+02,3.884578163007583296e+00,5.656854305839434716e+00,3.156285982294794734e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.951704230144440544e+01,3.626771040464574867e+02,3.887682303796571759e+00,5.656854305839434716e+00,3.153785982294795009e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.951881006837976429e+01,3.626866108366055528e+02,3.890784067984978112e+00,5.656854305839434716e+00,3.151285982294795285e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.952057783531512314e+01,3.626961184018975928e+02,3.893883455378941871e+00,5.656854305839434716e+00,3.148785982294795560e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.952234560225048199e+01,3.627056267417393656e+02,3.896980465784751768e+00,5.656854305839434716e+00,3.146285982294795835e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.952411336918584084e+01,3.627151358555365732e+02,3.900075099008844415e+00,5.656854305839434716e+00,3.143785982294796111e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.952588113612119969e+01,3.627246457426949178e+02,3.903167354857805194e+00,5.656854305839434716e+00,3.141285982294796386e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.952764890305655854e+01,3.627341564026200444e+02,3.906257233138368257e+00,5.656854305839434716e+00,3.138785982294796661e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.952941666999191739e+01,3.627436678347175416e+02,3.909344733657416082e+00,5.656854305839434716e+00,3.136285982294796937e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.953118443692727624e+01,3.627531800383928839e+02,3.912429856221979918e+00,5.656854305839434716e+00,3.133785982294797212e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.953295220386263509e+01,3.627626930130516030e+02,3.915512600639239338e+00,5.656854305839434716e+00,3.131285982294797487e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.953471997079799394e+01,3.627722067580991734e+02,3.918592966716523129e+00,5.656854305839434716e+00,3.128785982294797763e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.953648773773335279e+01,3.627817212729409562e+02,3.921670954261308406e+00,5.656854305839434716e+00,3.126285982294798038e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.953825550466871164e+01,3.627912365569822555e+02,3.924746563081221051e+00,5.656854305839434716e+00,3.123785982294798313e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.954002327160407049e+01,3.628007526096284323e+02,3.927819792984035274e+00,5.656854305839434716e+00,3.121285982294798589e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.954179103853942934e+01,3.628102694302846771e+02,3.930890643777674498e+00,5.656854305839434716e+00,3.118785982294798864e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.954355880547478819e+01,3.628197870183562372e+02,3.933959115270210027e+00,5.656854305839434716e+00,3.116285982294799140e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.954532657241014704e+01,3.628293053732481894e+02,3.937025207269862825e+00,5.656854305839434716e+00,3.113785982294799415e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.954709433934550589e+01,3.628388244943657241e+02,3.940088919585002181e+00,5.656854305839434716e+00,3.111285982294799690e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.954886210628086474e+01,3.628483443811138613e+02,3.943150252024145708e+00,5.656854305839434716e+00,3.108785982294799966e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.955062987321622359e+01,3.628578650328975641e+02,3.946209204395960679e+00,5.656854305839434716e+00,3.106285982294800241e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.955239764015158244e+01,3.628673864491218524e+02,3.949265776509262249e+00,5.656854305839434716e+00,3.103785982294800516e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.955416540708694129e+01,3.628769086291916324e+02,3.952319968173014342e+00,5.656854305839434716e+00,3.101285982294800792e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.955593317402230014e+01,3.628864315725117535e+02,3.955371779196330539e+00,5.656854305839434716e+00,3.098785982294801067e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.955770094095765899e+01,3.628959552784870084e+02,3.958421209388472306e+00,5.656854305839434716e+00,3.096285982294801342e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.955946870789301784e+01,3.629054797465221895e+02,3.961468258558850319e+00,5.656854305839434716e+00,3.093785982294801618e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.956123647482837669e+01,3.629150049760220327e+02,3.964512926517024027e+00,5.656854305839434716e+00,3.091285982294801893e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.956300424176373554e+01,3.629245309663911598e+02,3.967555213072701648e+00,5.656854305839434716e+00,3.088785982294802168e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.956477200869909439e+01,3.629340577170342499e+02,3.970595118035740612e+00,5.656854305839434716e+00,3.086285982294802444e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.956653977563445324e+01,3.629435852273558680e+02,3.973632641216146677e+00,5.656854305839434716e+00,3.083785982294802719e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.956830754256981209e+01,3.629531134967605226e+02,3.976667782424074371e+00,5.656854305839434716e+00,3.081285982294802994e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.957007530950517094e+01,3.629626425246527219e+02,3.979700541469827435e+00,5.656854305839434716e+00,3.078785982294803270e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.957184307644052979e+01,3.629721723104369175e+02,3.982730918163858824e+00,5.656854305839434716e+00,3.076285982294803545e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.957361084337588863e+01,3.629817028535174472e+02,3.985758912316769376e+00,5.656854305839434716e+00,3.073785982294803820e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.957537861031124748e+01,3.629912341532987057e+02,3.988784523739310028e+00,5.656854305839434716e+00,3.071285982294804096e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.957714637724660633e+01,3.630007662091849170e+02,3.991807752242379603e+00,5.656854305839434716e+00,3.068785982294804371e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.957891414418196518e+01,3.630102990205803621e+02,3.994828597637026579e+00,5.656854305839434716e+00,3.066285982294804646e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.958068191111732403e+01,3.630198325868892653e+02,3.997847059734448205e+00,5.656854305839434716e+00,3.063785982294804922e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.958244967805268288e+01,3.630293669075157936e+02,4.000863138345990500e+00,5.656854305839434716e+00,3.061285982294805197e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.958421744498804173e+01,3.630389019818640008e+02,4.003876833283148251e+00,5.656854305839434716e+00,3.058785982294805472e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.958598521192340058e+01,3.630484378093379405e+02,4.006888144357565906e+00,5.656854305839434716e+00,3.056285982294805748e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.958775297885875943e+01,3.630579743893416662e+02,4.009897071381036682e+00,5.656854305839434716e+00,3.053785982294806023e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.958952074579411828e+01,3.630675117212791179e+02,4.012903614165502120e+00,5.656854305839434716e+00,3.051285982294806298e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.959128851272947713e+01,3.630770498045542354e+02,4.015907772523053865e+00,5.656854305839434716e+00,3.048785982294806574e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.959305627966483598e+01,3.630865886385708450e+02,4.018909546265931887e+00,5.656854305839434716e+00,3.046285982294806849e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.959482404660019483e+01,3.630961282227327729e+02,4.021908935206525371e+00,5.656854305839434716e+00,3.043785982294807124e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.959659181353555368e+01,3.631056685564438453e+02,4.024905939157371826e+00,5.656854305839434716e+00,3.041285982294807400e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.959835958047091253e+01,3.631152096391077748e+02,4.027900557931158865e+00,5.656854305839434716e+00,3.038785982294807675e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.960012734740627138e+01,3.631247514701282171e+02,4.030892791340723313e+00,5.656854305839434716e+00,3.036285982294807950e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.960189511434163023e+01,3.631342940489088278e+02,4.033882639199050324e+00,5.656854305839434716e+00,3.033785982294808226e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.960366288127698908e+01,3.631438373748532058e+02,4.036870101319274262e+00,5.656854305839434716e+00,3.031285982294808501e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.960543064821234793e+01,3.631533814473648363e+02,4.039855177514678708e+00,5.656854305839434716e+00,3.028785982294808776e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.960719841514770678e+01,3.631629262658472612e+02,4.042837867598696455e+00,5.656854305839434716e+00,3.026285982294809052e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.960896618208306563e+01,3.631724718297039658e+02,4.045818171384909512e+00,5.656854305839434716e+00,3.023785982294809327e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.961073394901842448e+01,3.631820181383382646e+02,4.048796088687048211e+00,5.656854305839434716e+00,3.021285982294809602e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.961250171595378333e+01,3.631915651911535861e+02,4.051771619318993878e+00,5.656854305839434716e+00,3.018785982294809878e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.961426948288914218e+01,3.632011129875531878e+02,4.054744763094775273e+00,5.656854305839434716e+00,3.016285982294810153e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.961603724982450103e+01,3.632106615269403846e+02,4.057715519828570372e+00,5.656854305839434716e+00,3.013785982294810428e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.961780501675985988e+01,3.632202108087183774e+02,4.060683889334707253e+00,5.656854305839434716e+00,3.011285982294810704e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.961957278369521873e+01,3.632297608322903102e+02,4.063649871427663207e+00,5.656854305839434716e+00,3.008785982294810979e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.962134055063057758e+01,3.632393115970593271e+02,4.066613465922063853e+00,5.656854305839434716e+00,3.006285982294811254e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.962310831756593643e+01,3.632488631024284587e+02,4.069574672632684909e+00,5.656854305839434716e+00,3.003785982294811530e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.962487608450129528e+01,3.632584153478007920e+02,4.072533491374451309e+00,5.656854305839434716e+00,3.001285982294811805e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.962664385143665413e+01,3.632679683325793007e+02,4.075489921962436313e+00,5.656854305839434716e+00,2.998785982294812080e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.962841161837201298e+01,3.632775220561669016e+02,4.078443964211863282e+00,5.656854305839434716e+00,2.996285982294812356e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.963017938530737183e+01,3.632870765179665113e+02,4.081395617938103904e+00,5.656854305839434716e+00,2.993785982294812631e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.963194715224273068e+01,3.632966317173809898e+02,4.084344882956680856e+00,5.656854305839434716e+00,2.991285982294812906e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.963371491917808953e+01,3.633061876538130832e+02,4.087291759083264253e+00,5.656854305839434716e+00,2.988785982294813182e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.963548268611344838e+01,3.633157443266655946e+02,4.090236246133674314e+00,5.656854305839434716e+00,2.986285982294813457e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.963725045304880723e+01,3.633253017353412133e+02,4.093178343923881357e+00,5.656854305839434716e+00,2.983785982294813732e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.963901821998416608e+01,3.633348598792426287e+02,4.096118052270003140e+00,5.656854305839434716e+00,2.981285982294814008e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.964078598691952493e+01,3.633444187577724165e+02,4.099055370988309299e+00,5.656854305839434716e+00,2.978785982294814283e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.964255375385488378e+01,3.633539783703331523e+02,4.101990299895216019e+00,5.656854305839434716e+00,2.976285982294814558e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.964432152079024263e+01,3.633635387163273549e+02,4.104922838807291363e+00,5.656854305839434716e+00,2.973785982294814834e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.964608928772560148e+01,3.633730997951575432e+02,4.107852987541250833e+00,5.656854305839434716e+00,2.971285982294815109e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.964785705466096033e+01,3.633826616062261223e+02,4.110780745913960921e+00,5.656854305839434716e+00,2.968785982294815384e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.964962482159631918e+01,3.633922241489354974e+02,4.113706113742436443e+00,5.656854305839434716e+00,2.966285982294815660e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.965139258853167803e+01,3.634017874226879599e+02,4.116629090843841432e+00,5.656854305839434716e+00,2.963785982294815935e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.965316035546703688e+01,3.634113514268858580e+02,4.119549677035490021e+00,5.656854305839434716e+00,2.961285982294816210e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.965492812240239573e+01,3.634209161609314265e+02,4.122467872134846445e+00,5.656854305839434716e+00,2.958785982294816486e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.965669588933775458e+01,3.634304816242268430e+02,4.125383675959522378e+00,5.656854305839434716e+00,2.956285982294816761e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.965846365627311343e+01,3.634400478161742853e+02,4.128297088327280484e+00,5.656854305839434716e+00,2.953785982294817036e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.966023142320847228e+01,3.634496147361758744e+02,4.131208109056032640e+00,5.656854305839434716e+00,2.951285982294817312e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.966199919014383113e+01,3.634591823836336744e+02,4.134116737963839938e+00,5.656854305839434716e+00,2.948785982294817587e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.966376695707918998e+01,3.634687507579496923e+02,4.137022974868912684e+00,5.656854305839434716e+00,2.946285982294817862e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.966553472401454883e+01,3.634783198585259356e+02,4.139926819589611284e+00,5.656854305839434716e+00,2.943785982294818138e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.966730249094990768e+01,3.634878896847642977e+02,4.142828271944446250e+00,5.656854305839434716e+00,2.941285982294818413e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.966907025788526653e+01,3.634974602360666722e+02,4.145727331752075528e+00,5.656854305839434716e+00,2.938785982294818688e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.967083802482062538e+01,3.635070315118349527e+02,4.148623998831308946e+00,5.656854305839434716e+00,2.936285982294818964e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.967260579175598423e+01,3.635166035114708620e+02,4.151518273001104653e+00,5.656854305839434716e+00,2.933785982294819239e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.967437355869134308e+01,3.635261762343761802e+02,4.154410154080570017e+00,5.656854305839434716e+00,2.931285982294819514e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.967614132562670193e+01,3.635357496799526302e+02,4.157299641888962505e+00,5.656854305839434716e+00,2.928785982294819790e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.967790909256206078e+01,3.635453238476018214e+02,4.160186736245689687e+00,5.656854305839434716e+00,2.926285982294820065e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.967967685949741963e+01,3.635548987367254199e+02,4.163071436970307460e+00,5.656854305839434716e+00,2.923785982294820340e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.968144462643277848e+01,3.635644743467249782e+02,4.165953743882522708e+00,5.656854305839434716e+00,2.921285982294820616e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.968321239336813733e+01,3.635740506770020488e+02,4.168833656802190646e+00,5.656854305839434716e+00,2.918785982294820891e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.968498016030349618e+01,3.635836277269580705e+02,4.171711175549316586e+00,5.656854305839434716e+00,2.916285982294821166e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.968674792723885503e+01,3.635932054959944821e+02,4.174586299944055945e+00,5.656854305839434716e+00,2.913785982294821442e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.968851569417421388e+01,3.636027839835126656e+02,4.177459029806714241e+00,5.656854305839434716e+00,2.911285982294821717e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.969028346110957273e+01,3.636123631889140029e+02,4.180329364957744431e+00,5.656854305839434716e+00,2.908785982294821992e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.969205122804493158e+01,3.636219431115997622e+02,4.183197305217751349e+00,5.656854305839434716e+00,2.906285982294822268e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.969381899498029043e+01,3.636315237509712119e+02,4.186062850407489044e+00,5.656854305839434716e+00,2.903785982294822543e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.969558676191564928e+01,3.636411051064295634e+02,4.188926000347860779e+00,5.656854305839434716e+00,2.901285982294822818e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.969735452885100813e+01,3.636506871773759713e+02,4.191786754859919029e+00,5.656854305839434716e+00,2.898785982294823094e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.969912229578636698e+01,3.636602699632115332e+02,4.194645113764867261e+00,5.656854305839434716e+00,2.896285982294823369e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.970089006272172583e+01,3.636698534633373470e+02,4.197501076884057269e+00,5.656854305839434716e+00,2.893785982294823644e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.970265782965708468e+01,3.636794376771544535e+02,4.200354644038992724e+00,5.656854305839434716e+00,2.891285982294823920e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.970442559659244353e+01,3.636890226040638368e+02,4.203205815051324734e+00,5.656854305839434716e+00,2.888785982294824195e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.970619336352780238e+01,3.636986082434664240e+02,4.206054589742855399e+00,5.656854305839434716e+00,2.886285982294824470e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.970796113046316123e+01,3.637081945947631425e+02,4.208900967935536030e+00,5.656854305839434716e+00,2.883785982294824746e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.970972889739852008e+01,3.637177816573548625e+02,4.211744949451468045e+00,5.656854305839434716e+00,2.881285982294825021e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.971149666433387893e+01,3.637273694306423408e+02,4.214586534112902960e+00,5.656854305839434716e+00,2.878785982294825296e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.971326443126923778e+01,3.637369579140263340e+02,4.217425721742240619e+00,5.656854305839434716e+00,2.876285982294825572e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.971503219820459663e+01,3.637465471069075988e+02,4.220262512162032742e+00,5.656854305839434716e+00,2.873785982294825847e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.971679996513995548e+01,3.637561370086867782e+02,4.223096905194980266e+00,5.656854305839434716e+00,2.871285982294826122e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.971856773207531432e+01,3.637657276187645721e+02,4.225928900663933341e+00,5.656854305839434716e+00,2.868785982294826398e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.972033549901067317e+01,3.637753189365415096e+02,4.228758498391892218e+00,5.656854305839434716e+00,2.866285982294826673e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.972210326594603202e+01,3.637849109614181202e+02,4.231585698202006363e+00,5.656854305839434716e+00,2.863785982294826948e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.972387103288139087e+01,3.637945036927949332e+02,4.234410499917576232e+00,5.656854305839434716e+00,2.861285982294827224e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.972563879981674972e+01,3.638040971300724209e+02,4.237232903362052383e+00,5.656854305839434716e+00,2.858785982294827499e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.972740656675210857e+01,3.638136912726509422e+02,4.240052908359033701e+00,5.656854305839434716e+00,2.856285982294827774e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.972917433368746742e+01,3.638232861199309127e+02,4.242870514732270060e+00,5.656854305839434716e+00,2.853785982294828050e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.973094210062282627e+01,3.638328816713126344e+02,4.245685722305661436e+00,5.656854305839434716e+00,2.851285982294828325e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.973270986755818512e+01,3.638424779261963522e+02,4.248498530903257020e+00,5.656854305839434716e+00,2.848785982294828600e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.973447763449354397e+01,3.638520748839823113e+02,4.251308940349256105e+00,5.656854305839434716e+00,2.846285982294828876e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.973624540142890282e+01,3.638616725440707569e+02,4.254116950468008973e+00,5.656854305839434716e+00,2.843785982294829151e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.973801316836426167e+01,3.638712709058617634e+02,4.256922561084014234e+00,5.656854305839434716e+00,2.841285982294829426e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.973978093529962052e+01,3.638808699687554622e+02,4.259725772021921486e+00,5.656854305839434716e+00,2.838785982294829702e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.974154870223497937e+01,3.638904697321519279e+02,4.262526583106529543e+00,5.656854305839434716e+00,2.836285982294829977e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.974331646917033822e+01,3.639000701954511783e+02,4.265324994162788208e+00,5.656854305839434716e+00,2.833785982294830252e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.974508423610569707e+01,3.639096713580531741e+02,4.268121005015797387e+00,5.656854305839434716e+00,2.831285982294830528e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.974685200304105592e+01,3.639192732193578195e+02,4.270914615490805311e+00,5.656854305839434716e+00,2.828785982294830803e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.974861976997641477e+01,3.639288757787650184e+02,4.273705825413212089e+00,5.656854305839434716e+00,2.826285982294831078e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.975038753691177362e+01,3.639384790356746180e+02,4.276494634608566159e+00,5.656854305839434716e+00,2.823785982294831354e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.975215530384713247e+01,3.639480829894864087e+02,4.279281042902567833e+00,5.656854305839434716e+00,2.821285982294831629e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.975392307078249132e+01,3.639576876396001239e+02,4.282065050121066641e+00,5.656854305839434716e+00,2.818785982294831904e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.975569083771785017e+01,3.639672929854154972e+02,4.284846656090061323e+00,5.656854305839434716e+00,2.816285982294832180e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.975745860465320902e+01,3.639768990263322053e+02,4.287625860635702502e+00,5.656854305839434716e+00,2.813785982294832455e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.975922637158856787e+01,3.639865057617498678e+02,4.290402663584289122e+00,5.656854305839434716e+00,2.811285982294832730e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.976099413852392672e+01,3.639961131910680479e+02,4.293177064762271122e+00,5.656854305839434716e+00,2.808785982294833006e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.976276190545928557e+01,3.640057213136862515e+02,4.295949063996248540e+00,5.656854305839434716e+00,2.806285982294833281e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.976452967239464442e+01,3.640153301290040417e+02,4.298718661112971517e+00,5.656854305839434716e+00,2.803785982294833556e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.976629743933000327e+01,3.640249396364208110e+02,4.301485855939340297e+00,5.656854305839434716e+00,2.801285982294833832e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.976806520626536212e+01,3.640345498353360085e+02,4.304250648302405224e+00,5.656854305839434716e+00,2.798785982294834107e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.976983297320072097e+01,3.640441607251489700e+02,4.307013038029365859e+00,5.656854305839434716e+00,2.796285982294834382e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.977160074013607982e+01,3.640537723052589740e+02,4.309773024947573639e+00,5.656854305839434716e+00,2.793785982294834658e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.977336850707143867e+01,3.640633845750653563e+02,4.312530608884530103e+00,5.656854305839434716e+00,2.791285982294834933e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.977513627400679752e+01,3.640729975339673388e+02,4.315285789667885119e+00,5.656854305839434716e+00,2.788785982294835208e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.977690404094215637e+01,3.640826111813640864e+02,4.318038567125440430e+00,5.656854305839434716e+00,2.786285982294835484e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.977867180787751522e+01,3.640922255166547643e+02,4.320788941085146995e+00,5.656854305839434716e+00,2.783785982294835759e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.978043957481287407e+01,3.641018405392384807e+02,4.323536911375106762e+00,5.656854305839434716e+00,2.781285982294836034e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.978220734174823292e+01,3.641114562485142869e+02,4.326282477823571782e+00,5.656854305839434716e+00,2.778785982294836310e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.978397510868359177e+01,3.641210726438812344e+02,4.329025640258944208e+00,5.656854305839434716e+00,2.776285982294836585e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.978574287561895062e+01,3.641306897247382608e+02,4.331766398509775406e+00,5.656854305839434716e+00,2.773785982294836860e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.978751064255430947e+01,3.641403074904843038e+02,4.334504752404769512e+00,5.656854305839434716e+00,2.771285982294837136e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.978927840948966832e+01,3.641499259405182443e+02,4.337240701772778095e+00,5.656854305839434716e+00,2.768785982294837411e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.979104617642502717e+01,3.641595450742389630e+02,4.339974246442804606e+00,5.656854305839434716e+00,2.766285982294837686e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.979281394336038602e+01,3.641691648910452273e+02,4.342705386244002597e+00,5.656854305839434716e+00,2.763785982294837962e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.979458171029574487e+01,3.641787853903358041e+02,4.345434121005676609e+00,5.656854305839434716e+00,2.761285982294838237e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.979634947723110372e+01,3.641884065715094607e+02,4.348160450557279511e+00,5.656854305839434716e+00,2.758785982294838512e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.979811724416646257e+01,3.641980284339648506e+02,4.350884374728416937e+00,5.656854305839434716e+00,2.756285982294838788e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.979988501110182142e+01,3.642076509771005703e+02,4.353605893348842848e+00,5.656854305839434716e+00,2.753785982294839063e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.980165277803718027e+01,3.642172742003152166e+02,4.356325006248462195e+00,5.656854305839434716e+00,2.751285982294839338e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.980342054497253912e+01,3.642268981030073860e+02,4.359041713257330919e+00,5.656854305839434716e+00,2.748785982294839614e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.980518831190789797e+01,3.642365226845755615e+02,4.361756014205654175e+00,5.656854305839434716e+00,2.746285982294839889e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.980695607884325682e+01,3.642461479444181691e+02,4.364467908923788997e+00,5.656854305839434716e+00,2.743785982294840164e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.980872384577861567e+01,3.642557738819336350e+02,4.367177397242240744e+00,5.656854305839434716e+00,2.741285982294840440e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.981049161271397452e+01,3.642654004965203853e+02,4.369884478991667542e+00,5.656854305839434716e+00,2.738785982294840715e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.981225937964933337e+01,3.642750277875767324e+02,4.372589154002876732e+00,5.656854305839434716e+00,2.736285982294840990e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.981402714658469222e+01,3.642846557545009887e+02,4.375291422106825756e+00,5.656854305839434716e+00,2.733785982294841266e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.981579491352005107e+01,3.642942843966913529e+02,4.377991283134623046e+00,5.656854305839434716e+00,2.731285982294841541e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.981756268045540992e+01,3.643039137135460805e+02,4.380688736917527137e+00,5.656854305839434716e+00,2.728785982294841816e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.981933044739076877e+01,3.643135437044633704e+02,4.383383783286946667e+00,5.656854305839434716e+00,2.726285982294842092e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.982109821432612762e+01,3.643231743688413076e+02,4.386076422074442149e+00,5.656854305839434716e+00,2.723785982294842367e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.982286598126148647e+01,3.643328057060779770e+02,4.388766653111723315e+00,5.656854305839434716e+00,2.721285982294842642e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.982463374819684532e+01,3.643424377155714069e+02,4.391454476230650883e+00,5.656854305839434716e+00,2.718785982294842918e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.982640151513220417e+01,3.643520703967196255e+02,4.394139891263235675e+00,5.656854305839434716e+00,2.716285982294843193e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.982816928206756302e+01,3.643617037489205472e+02,4.396822898041638616e+00,5.656854305839434716e+00,2.713785982294843468e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.982993704900292187e+01,3.643713377715721435e+02,4.399503496398172508e+00,5.656854305839434716e+00,2.711285982294843744e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.983170481593828072e+01,3.643809724640722152e+02,4.402181686165300256e+00,5.656854305839434716e+00,2.708785982294844019e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.983347258287363957e+01,3.643906078258186767e+02,4.404857467175634866e+00,5.656854305839434716e+00,2.706285982294844294e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.983524034980899842e+01,3.644002438562092721e+02,4.407530839261939448e+00,5.656854305839434716e+00,2.703785982294844570e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.983700811674435727e+01,3.644098805546417452e+02,4.410201802257128989e+00,5.656854305839434716e+00,2.701285982294844845e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.983877588367971612e+01,3.644195179205137833e+02,4.412870355994267690e+00,5.656854305839434716e+00,2.698785982294845120e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.984054365061507497e+01,3.644291559532231304e+02,4.415536500306570744e+00,5.656854305839434716e+00,2.696285982294845396e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.984231141755043382e+01,3.644387946521673598e+02,4.418200235027405220e+00,5.656854305839434716e+00,2.693785982294845671e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.984407918448579267e+01,3.644484340167440450e+02,4.420861559990286516e+00,5.656854305839434716e+00,2.691285982294845947e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.984584695142115152e+01,3.644580740463507027e+02,4.423520475028882792e+00,5.656854305839434716e+00,2.688785982294846222e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.984761471835651037e+01,3.644677147403848494e+02,4.426176979977011428e+00,5.656854305839434716e+00,2.686285982294846497e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.984938248529186922e+01,3.644773560982440017e+02,4.428831074668640788e+00,5.656854305839434716e+00,2.683785982294846773e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.985115025222722807e+01,3.644869981193255057e+02,4.431482758937889344e+00,5.656854305839434716e+00,2.681285982294847048e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.985291801916258692e+01,3.644966408030267644e+02,4.434132032619028330e+00,5.656854305839434716e+00,2.678785982294847323e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.985468578609794577e+01,3.645062841487451237e+02,4.436778895546477308e+00,5.656854305839434716e+00,2.676285982294847599e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.985645355303330462e+01,3.645159281558778162e+02,4.439423347554806831e+00,5.656854305839434716e+00,2.673785982294847874e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.985822131996866347e+01,3.645255728238221309e+02,4.442065388478739330e+00,5.656854305839434716e+00,2.671285982294848149e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.985998908690402232e+01,3.645352181519753003e+02,4.444705018153147336e+00,5.656854305839434716e+00,2.668785982294848425e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.986175685383938117e+01,3.645448641397344431e+02,4.447342236413053485e+00,5.656854305839434716e+00,2.666285982294848700e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.986352462077474001e+01,3.645545107864967349e+02,4.449977043093631401e+00,5.656854305839434716e+00,2.663785982294848975e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.986529238771009886e+01,3.645641580916591806e+02,4.452609438030206590e+00,5.656854305839434716e+00,2.661285982294849251e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.986706015464545771e+01,3.645738060546188990e+02,4.455239421058253768e+00,5.656854305839434716e+00,2.658785982294849526e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.986882792158081656e+01,3.645834546747728950e+02,4.457866992013399532e+00,5.656854305839434716e+00,2.656285982294849801e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.987059568851617541e+01,3.645931039515180601e+02,4.460492150731420580e+00,5.656854305839434716e+00,2.653785982294850077e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.987236345545153426e+01,3.646027538842513991e+02,4.463114897048243712e+00,5.656854305839434716e+00,2.651285982294850352e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.987413122238689311e+01,3.646124044723697466e+02,4.465735230799947608e+00,5.656854305839434716e+00,2.648785982294850627e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.987589898932225196e+01,3.646220557152699371e+02,4.468353151822761937e+00,5.656854305839434716e+00,2.646285982294850903e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.987766675625761081e+01,3.646317076123487482e+02,4.470968659953066471e+00,5.656854305839434716e+00,2.643785982294851178e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.987943452319296966e+01,3.646413601630029575e+02,4.473581755027391971e+00,5.656854305839434716e+00,2.641285982294851453e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.988120229012832851e+01,3.646510133666292859e+02,4.476192436882419301e+00,5.656854305839434716e+00,2.638785982294851729e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.988297005706368736e+01,3.646606672226244541e+02,4.478800705354981204e+00,5.656854305839434716e+00,2.636285982294852004e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.988473782399904621e+01,3.646703217303850124e+02,4.481406560282061413e+00,5.656854305839434716e+00,2.633785982294852279e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.988650559093440506e+01,3.646799768893076248e+02,4.484010001500793763e+00,5.656854305839434716e+00,2.631285982294852555e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.988827335786976391e+01,3.646896326987887846e+02,4.486611028848463079e+00,5.656854305839434716e+00,2.628785982294852830e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.989004112480512276e+01,3.646992891582250422e+02,4.489209642162505176e+00,5.656854305839434716e+00,2.626285982294853105e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.989180889174048161e+01,3.647089462670128341e+02,4.491805841280506861e+00,5.656854305839434716e+00,2.623785982294853381e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.989357665867584046e+01,3.647186040245486538e+02,4.494399626040205042e+00,5.656854305839434716e+00,2.621285982294853656e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.989534442561119931e+01,3.647282624302288241e+02,4.496990996279488506e+00,5.656854305839434716e+00,2.618785982294853931e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.989711219254655816e+01,3.647379214834497247e+02,4.499579951836397029e+00,5.656854305839434716e+00,2.616285982294854207e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.989887995948191701e+01,3.647475811836076787e+02,4.502166492549120491e+00,5.656854305839434716e+00,2.613785982294854482e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.990064772641727586e+01,3.647572415300989519e+02,4.504750618256000649e+00,5.656854305839434716e+00,2.611285982294854757e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.990241549335263471e+01,3.647669025223197536e+02,4.507332328795529364e+00,5.656854305839434716e+00,2.608785982294855033e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.990418326028799356e+01,3.647765641596662363e+02,4.509911624006349484e+00,5.656854305839434716e+00,2.606285982294855308e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.990595102722335241e+01,3.647862264415346090e+02,4.512488503727254852e+00,5.656854305839434716e+00,2.603785982294855583e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.990771879415871126e+01,3.647958893673209673e+02,4.515062967797191185e+00,5.656854305839434716e+00,2.601285982294855859e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.990948656109407011e+01,3.648055529364213498e+02,4.517635016055253416e+00,5.656854305839434716e+00,2.598785982294856134e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.991125432802942896e+01,3.648152171482317954e+02,4.520204648340689246e+00,5.656854305839434716e+00,2.596285982294856409e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.991302209496478781e+01,3.648248820021483425e+02,4.522771864492897365e+00,5.656854305839434716e+00,2.593785982294856685e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.991478986190014666e+01,3.648345474975668594e+02,4.525336664351425675e+00,5.656854305839434716e+00,2.591285982294856960e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.991655762883550551e+01,3.648442136338833279e+02,4.527899047755974848e+00,5.656854305839434716e+00,2.588785982294857235e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.991832539577086436e+01,3.648538804104935593e+02,4.530459014546394769e+00,5.656854305839434716e+00,2.586285982294857511e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.992009316270622321e+01,3.648635478267933649e+02,4.533016564562688977e+00,5.656854305839434716e+00,2.583785982294857786e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.992186092964158206e+01,3.648732158821785561e+02,4.535571697645009337e+00,5.656854305839434716e+00,2.581285982294858061e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.992362869657694091e+01,3.648828845760448871e+02,4.538124413633661369e+00,5.656854305839434716e+00,2.578785982294858337e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.992539646351229976e+01,3.648925539077881126e+02,4.540674712369098920e+00,5.656854305839434716e+00,2.576285982294858612e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.992716423044765861e+01,3.649022238768038164e+02,4.543222593691929490e+00,5.656854305839434716e+00,2.573785982294858887e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.992893199738301746e+01,3.649118944824876394e+02,4.545768057442909793e+00,5.656854305839434716e+00,2.571285982294859163e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.993069976431837631e+01,3.649215657242352222e+02,4.548311103462948424e+00,5.656854305839434716e+00,2.568785982294859438e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.993246753125373516e+01,3.649312376014420920e+02,4.550851731593105853e+00,5.656854305839434716e+00,2.566285982294859713e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.993423529818909401e+01,3.649409101135037190e+02,4.553389941674591768e+00,5.656854305839434716e+00,2.563785982294859989e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.993600306512445286e+01,3.649505832598155735e+02,4.555925733548768619e+00,5.656854305839434716e+00,2.561285982294860264e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.993777083205981171e+01,3.649602570397731256e+02,4.558459107057148962e+00,5.656854305839434716e+00,2.558785982294860539e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.993953859899517056e+01,3.649699314527717320e+02,4.560990062041397231e+00,5.656854305839434716e+00,2.556285982294860815e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.994130636593052941e+01,3.649796064982067492e+02,4.563518598343328847e+00,5.656854305839434716e+00,2.553785982294861090e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.994307413286588826e+01,3.649892821754734769e+02,4.566044715804910226e+00,5.656854305839434716e+00,2.551285982294861365e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.994484189980124711e+01,3.649989584839672148e+02,4.568568414268258771e+00,5.656854305839434716e+00,2.548785982294861641e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.994660966673660596e+01,3.650086354230832058e+02,4.571089693575643764e+00,5.656854305839434716e+00,2.546285982294861916e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.994837743367196481e+01,3.650183129922165790e+02,4.573608553569484592e+00,5.656854305839434716e+00,2.543785982294862191e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.995014520060732366e+01,3.650279911907625205e+02,4.576124994092352516e+00,5.656854305839434716e+00,2.541285982294862467e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.995191296754268251e+01,3.650376700181161596e+02,4.578639014986970679e+00,5.656854305839434716e+00,2.538785982294862742e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.995368073447804136e+01,3.650473494736725684e+02,4.581150616096212325e+00,5.656854305839434716e+00,2.536285982294863017e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.995544850141340021e+01,3.650570295568267625e+02,4.583659797263102575e+00,5.656854305839434716e+00,2.533785982294863293e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.995721626834875906e+01,3.650667102669737005e+02,4.586166558330817544e+00,5.656854305839434716e+00,2.531285982294863568e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.995898403528411791e+01,3.650763916035083980e+02,4.588670899142685222e+00,5.656854305839434716e+00,2.528785982294863843e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.996075180221947676e+01,3.650860735658257568e+02,4.591172819542183703e+00,5.656854305839434716e+00,2.526285982294864119e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.996251956915483561e+01,3.650957561533206217e+02,4.593672319372942958e+00,5.656854305839434716e+00,2.523785982294864394e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.996428733609019446e+01,3.651054393653878947e+02,4.596169398478743950e+00,5.656854305839434716e+00,2.521285982294864669e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.996605510302555331e+01,3.651151232014223069e+02,4.598664056703520409e+00,5.656854305839434716e+00,2.518785982294864945e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.996782286996091216e+01,3.651248076608186466e+02,4.601156293891355276e+00,5.656854305839434716e+00,2.516285982294865220e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.996959063689627101e+01,3.651344927429716449e+02,4.603646109886483373e+00,5.656854305839434716e+00,2.513785982294865495e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.997135840383162986e+01,3.651441784472759764e+02,4.606133504533292289e+00,5.656854305839434716e+00,2.511285982294865771e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.997312617076698871e+01,3.651538647731263154e+02,4.608618477676318825e+00,5.656854305839434716e+00,2.508785982294866046e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.997489393770234756e+01,3.651635517199172227e+02,4.611101029160252551e+00,5.656854305839434716e+00,2.506285982294866321e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.997666170463770641e+01,3.651732392870432591e+02,4.613581158829934026e+00,5.656854305839434716e+00,2.503785982294866597e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.997842947157306526e+01,3.651829274738989852e+02,4.616058866530355687e+00,5.656854305839434716e+00,2.501285982294866872e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.998019723850842411e+01,3.651926162798788482e+02,4.618534152106660073e+00,5.656854305839434716e+00,2.498785982294866870e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.998196500544378296e+01,3.652023057043773520e+02,4.621007015404141605e+00,5.656854305839434716e+00,2.496285982294866868e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.998373277237914181e+01,3.652119957467888867e+02,4.623477456268246577e+00,5.656854305839434716e+00,2.493785982294866865e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.998550053931450066e+01,3.652216864065077857e+02,4.625945474544573166e+00,5.656854305839434716e+00,2.491285982294866863e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.998726830624985951e+01,3.652313776829284393e+02,4.628411070078869649e+00,5.656854305839434716e+00,2.488785982294866861e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.998903607318521836e+01,3.652410695754451240e+02,4.630874242717036182e+00,5.656854305839434716e+00,2.486285982294866859e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.999080384012057721e+01,3.652507620834520594e+02,4.633334992305124800e+00,5.656854305839434716e+00,2.483785982294866856e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.999257160705593606e+01,3.652604552063435221e+02,4.635793318689338527e+00,5.656854305839434716e+00,2.481285982294866854e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.999433937399129491e+01,3.652701489435136750e+02,4.638249221716032267e+00,5.656854305839434716e+00,2.478785982294866852e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.999610714092665376e+01,3.652798432943566240e+02,4.640702701231711025e+00,5.656854305839434716e+00,2.476285982294866850e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.999787490786201261e+01,3.652895382582664752e+02,4.643153757083033462e+00,5.656854305839434716e+00,2.473785982294866848e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +5.999964267479737146e+01,3.652992338346373344e+02,4.645602389116808340e+00,5.656854305839434716e+00,2.471285982294866845e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.000141044173273031e+01,3.653089300228631942e+02,4.648048597179995411e+00,5.656854305839434716e+00,2.468785982294866843e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.000317820866808916e+01,3.653186268223380466e+02,4.650492381119707197e+00,5.656854305839434716e+00,2.466285982294866841e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.000494597560344801e+01,3.653283242324558842e+02,4.652933740783208094e+00,5.656854305839434716e+00,2.463785982294866839e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.000671374253880686e+01,3.653380222526105854e+02,4.655372676017911715e+00,5.656854305839434716e+00,2.461285982294866836e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.000848150947416570e+01,3.653477208821960289e+02,4.657809186671385326e+00,5.656854305839434716e+00,2.458785982294866834e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.001024927640952455e+01,3.653574201206060366e+02,4.660243272591347186e+00,5.656854305839434716e+00,2.456285982294866832e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.001201704334488340e+01,3.653671199672344301e+02,4.662674933625666540e+00,5.656854305839434716e+00,2.453785982294866830e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.001378481028024225e+01,3.653768204214749744e+02,4.665104169622364516e+00,5.656854305839434716e+00,2.451285982294866828e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.001555257721560110e+01,3.653865214827213208e+02,4.667530980429614118e+00,5.656854305839434716e+00,2.448785982294866825e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.001732034415095995e+01,3.653962231503672342e+02,4.669955365895739341e+00,5.656854305839434716e+00,2.446285982294866823e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.001908811108631880e+01,3.654059254238063090e+02,4.672377325869216058e+00,5.656854305839434716e+00,2.443785982294866821e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.002085587802167765e+01,3.654156283024321965e+02,4.674796860198672022e+00,5.656854305839434716e+00,2.441285982294866819e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.002262364495703650e+01,3.654253317856384342e+02,4.677213968732886862e+00,5.656854305839434716e+00,2.438785982294866816e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.002439141189239535e+01,3.654350358728185597e+02,4.679628651320790311e+00,5.656854305839434716e+00,2.436285982294866814e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.002615917882775420e+01,3.654447405633661106e+02,4.682040907811465758e+00,5.656854305839434716e+00,2.433785982294866812e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.002792694576311305e+01,3.654544458566744538e+02,4.684450738054145802e+00,5.656854305839434716e+00,2.431285982294866810e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.002969471269847190e+01,3.654641517521370702e+02,4.686858141898217589e+00,5.656854305839434716e+00,2.428785982294866808e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.003146247963383075e+01,3.654738582491473267e+02,4.689263119193217477e+00,5.656854305839434716e+00,2.426285982294866805e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.003323024656918960e+01,3.654835653470985903e+02,4.691665669788834592e+00,5.656854305839434716e+00,2.423785982294866803e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.003499801350454845e+01,3.654932730453841714e+02,4.694065793534909048e+00,5.656854305839434716e+00,2.421285982294866801e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.003676578043990730e+01,3.655029813433973231e+02,4.696463490281433728e+00,5.656854305839434716e+00,2.418785982294866799e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.003853354737526615e+01,3.655126902405312421e+02,4.698858759878552505e+00,5.656854305839434716e+00,2.416285982294866796e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.004030131431062500e+01,3.655223997361791817e+02,4.701251602176561128e+00,5.656854305839434716e+00,2.413785982294866794e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.004206908124598385e+01,3.655321098297342246e+02,4.703642017025906341e+00,5.656854305839434716e+00,2.411285982294866792e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.004383684818134270e+01,3.655418205205895674e+02,4.706030004277187651e+00,5.656854305839434716e+00,2.408785982294866790e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.004560461511670155e+01,3.655515318081382361e+02,4.708415563781155555e+00,5.656854305839434716e+00,2.406285982294866788e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.004737238205206040e+01,3.655612436917733135e+02,4.710798695388713320e+00,5.656854305839434716e+00,2.403785982294866785e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.004914014898741925e+01,3.655709561708877686e+02,4.713179398950914312e+00,5.656854305839434716e+00,2.401285982294866783e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.005090791592277810e+01,3.655806692448746276e+02,4.715557674318965553e+00,5.656854305839434716e+00,2.398785982294866781e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.005267568285813695e+01,3.655903829131267457e+02,4.717933521344224168e+00,5.656854305839434716e+00,2.396285982294866779e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.005444344979349580e+01,3.656000971750370923e+02,4.720306939878199159e+00,5.656854305839434716e+00,2.393785982294866777e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.005621121672885465e+01,3.656098120299984657e+02,4.722677929772553185e+00,5.656854305839434716e+00,2.391285982294866774e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.005797898366421350e+01,3.656195274774037216e+02,4.725046490879098116e+00,5.656854305839434716e+00,2.388785982294866772e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.005974675059957235e+01,3.656292435166456585e+02,4.727412623049799478e+00,5.656854305839434716e+00,2.386285982294866770e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.006151451753493120e+01,3.656389601471170181e+02,4.729776326136774678e+00,5.656854305839434716e+00,2.383785982294866768e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.006328228447029005e+01,3.656486773682104854e+02,4.732137599992291221e+00,5.656854305839434716e+00,2.381285982294866765e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.006505005140564890e+01,3.656583951793187452e+02,4.734496444468770271e+00,5.656854305839434716e+00,2.378785982294866763e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.006681781834100775e+01,3.656681135798344258e+02,4.736852859418783090e+00,5.656854305839434716e+00,2.376285982294866761e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.006858558527636660e+01,3.656778325691501550e+02,4.739206844695054599e+00,5.656854305839434716e+00,2.373785982294866759e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.007035335221172545e+01,3.656875521466584473e+02,4.741558400150460706e+00,5.656854305839434716e+00,2.371285982294866757e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.007212111914708430e+01,3.656972723117518740e+02,4.743907525638028311e+00,5.656854305839434716e+00,2.368785982294866754e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.007388888608244315e+01,3.657069930638229494e+02,4.746254221010937968e+00,5.656854305839434716e+00,2.366285982294866752e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.007565665301780200e+01,3.657167144022640741e+02,4.748598486122521223e+00,5.656854305839434716e+00,2.363785982294866750e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.007742441995316085e+01,3.657264363264676490e+02,4.750940320826261498e+00,5.656854305839434716e+00,2.361285982294866748e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.007919218688851970e+01,3.657361588358260747e+02,4.753279724975793208e+00,5.656854305839434716e+00,2.358785982294866745e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.008095995382387855e+01,3.657458819297317518e+02,4.755616698424904421e+00,5.656854305839434716e+00,2.356285982294866743e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.008272772075923740e+01,3.657556056075769106e+02,4.757951241027534195e+00,5.656854305839434716e+00,2.353785982294866741e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.008449548769459625e+01,3.657653298687538381e+02,4.760283352637773469e+00,5.656854305839434716e+00,2.351285982294866739e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.008626325462995510e+01,3.657750547126548213e+02,4.762613033109865057e+00,5.656854305839434716e+00,2.348785982294866737e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.008803102156531395e+01,3.657847801386719766e+02,4.764940282298204544e+00,5.656854305839434716e+00,2.346285982294866734e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.008979878850067280e+01,3.657945061461975342e+02,4.767265100057338501e+00,5.656854305839434716e+00,2.343785982294866732e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.009156655543603165e+01,3.658042327346235538e+02,4.769587486241966268e+00,5.656854305839434716e+00,2.341285982294866730e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.009333432237139050e+01,3.658139599033421518e+02,4.771907440706938175e+00,5.656854305839434716e+00,2.338785982294866728e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.009510208930674935e+01,3.658236876517453879e+02,4.774224963307257319e+00,5.656854305839434716e+00,2.336285982294866725e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.009686985624210820e+01,3.658334159792253217e+02,4.776540053898077787e+00,5.656854305839434716e+00,2.333785982294866723e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.009863762317746705e+01,3.658431448851738423e+02,4.778852712334707320e+00,5.656854305839434716e+00,2.331285982294866721e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.010040539011282590e+01,3.658528743689829525e+02,4.781162938472604651e+00,5.656854305839434716e+00,2.328785982294866719e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.010217315704818475e+01,3.658626044300445415e+02,4.783470732167380390e+00,5.656854305839434716e+00,2.326285982294866717e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.010394092398354360e+01,3.658723350677504982e+02,4.785776093274797027e+00,5.656854305839434716e+00,2.323785982294866714e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.010570869091890245e+01,3.658820662814926550e+02,4.788079021650770706e+00,5.656854305839434716e+00,2.321285982294866712e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.010747645785426130e+01,3.658917980706627873e+02,4.790379517151367672e+00,5.656854305839434716e+00,2.318785982294866710e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.010924422478962015e+01,3.659015304346526705e+02,4.792677579632806939e+00,5.656854305839434716e+00,2.316285982294866708e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.011101199172497900e+01,3.659112633728540231e+02,4.794973208951459398e+00,5.656854305839434716e+00,2.313785982294866705e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.011277975866033785e+01,3.659209968846585639e+02,4.797266404963848707e+00,5.656854305839434716e+00,2.311285982294866703e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.011454752559569670e+01,3.659307309694578976e+02,4.799557167526649515e+00,5.656854305839434716e+00,2.308785982294866701e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.011631529253105555e+01,3.659404656266436859e+02,4.801845496496689236e+00,5.656854305839434716e+00,2.306285982294866699e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.011808305946641440e+01,3.659502008556075339e+02,4.804131391730948053e+00,5.656854305839434716e+00,2.303785982294866697e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.011985082640177325e+01,3.659599366557409326e+02,4.806414853086557137e+00,5.656854305839434716e+00,2.301285982294866694e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.012161859333713210e+01,3.659696730264354301e+02,4.808695880420799540e+00,5.656854305839434716e+00,2.298785982294866692e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.012338636027249095e+01,3.659794099670824608e+02,4.810974473591111966e+00,5.656854305839434716e+00,2.296285982294866690e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.012515412720784980e+01,3.659891474770735158e+02,4.813250632455082112e+00,5.656854305839434716e+00,2.293785982294866688e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.012692189414320865e+01,3.659988855557999727e+02,4.815524356870449552e+00,5.656854305839434716e+00,2.291285982294866685e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.012868966107856750e+01,3.660086242026532091e+02,4.817795646695106626e+00,5.656854305839434716e+00,2.288785982294866683e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.013045742801392635e+01,3.660183634170246023e+02,4.820064501787098443e+00,5.656854305839434716e+00,2.286285982294866681e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.013222519494928520e+01,3.660281031983054163e+02,4.822330922004621101e+00,5.656854305839434716e+00,2.283785982294866679e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.013399296188464405e+01,3.660378435458868580e+02,4.824594907206022576e+00,5.656854305839434716e+00,2.281285982294866677e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.013576072882000290e+01,3.660475844591602481e+02,4.826856457249804500e+00,5.656854305839434716e+00,2.278785982294866674e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.013752849575536175e+01,3.660573259375167368e+02,4.829115571994620382e+00,5.656854305839434716e+00,2.276285982294866672e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.013929626269072060e+01,3.660670679803474741e+02,4.831372251299275611e+00,5.656854305839434716e+00,2.273785982294866670e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.014106402962607945e+01,3.660768105870436102e+02,4.833626495022726566e+00,5.656854305839434716e+00,2.271285982294866668e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.014283179656143830e+01,3.660865537569961816e+02,4.835878303024084168e+00,5.656854305839434716e+00,2.268785982294866665e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.014459956349679715e+01,3.660962974895962816e+02,4.838127675162610331e+00,5.656854305839434716e+00,2.266285982294866663e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.014636733043215600e+01,3.661060417842349466e+02,4.840374611297718843e+00,5.656854305839434716e+00,2.263785982294866661e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.014813509736751485e+01,3.661157866403030994e+02,4.842619111288976264e+00,5.656854305839434716e+00,2.261285982294866659e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.014990286430287370e+01,3.661255320571917196e+02,4.844861174996101028e+00,5.656854305839434716e+00,2.258785982294866657e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.015167063123823255e+01,3.661352780342917299e+02,4.847100802278964338e+00,5.656854305839434716e+00,2.256285982294866654e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.015343839817359139e+01,3.661450245709939963e+02,4.849337992997590163e+00,5.656854305839434716e+00,2.253785982294866652e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.015520616510895024e+01,3.661547716666893280e+02,4.851572747012153464e+00,5.656854305839434716e+00,2.251285982294866650e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.015697393204430909e+01,3.661645193207685907e+02,4.853805064182981965e+00,5.656854305839434716e+00,2.248785982294866648e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.015874169897966794e+01,3.661742675326225367e+02,4.856034944370556161e+00,5.656854305839434716e+00,2.246285982294866646e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.016050946591502679e+01,3.661840163016418614e+02,4.858262387435508423e+00,5.656854305839434716e+00,2.243785982294866643e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.016227723285038564e+01,3.661937656272173172e+02,4.860487393238623888e+00,5.656854305839434716e+00,2.241285982294866641e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.016404499978574449e+01,3.662035155087395424e+02,4.862709961640839573e+00,5.656854305839434716e+00,2.238785982294866639e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.016581276672110334e+01,3.662132659455991757e+02,4.864930092503244374e+00,5.656854305839434716e+00,2.236285982294866637e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.016758053365646219e+01,3.662230169371867987e+02,4.867147785687080841e+00,5.656854305839434716e+00,2.233785982294866634e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.016934830059182104e+01,3.662327684828929932e+02,4.869363041053742513e+00,5.656854305839434716e+00,2.231285982294866632e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.017111606752717989e+01,3.662425205821082841e+02,4.871575858464776587e+00,5.656854305839434716e+00,2.228785982294866630e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.017288383446253874e+01,3.662522732342231961e+02,4.873786237781882136e+00,5.656854305839434716e+00,2.226285982294866628e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.017465160139789759e+01,3.662620264386281406e+02,4.875994178866910111e+00,5.656854305839434716e+00,2.223785982294866626e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.017641936833325644e+01,3.662717801947135854e+02,4.878199681581863345e+00,5.656854305839434716e+00,2.221285982294866623e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.017818713526861529e+01,3.662815345018698849e+02,4.880402745788899210e+00,5.656854305839434716e+00,2.218785982294866621e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.017995490220397414e+01,3.662912893594873935e+02,4.882603371350325183e+00,5.656854305839434716e+00,2.216285982294866619e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.018172266913933299e+01,3.663010447669564655e+02,4.884801558128603283e+00,5.656854305839434716e+00,2.213785982294866617e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.018349043607469184e+01,3.663108007236673984e+02,4.886997305986345630e+00,5.656854305839434716e+00,2.211285982294866614e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.018525820301005069e+01,3.663205572290103760e+02,4.889190614786318889e+00,5.656854305839434716e+00,2.208785982294866612e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.018702596994540954e+01,3.663303142823756957e+02,4.891381484391440715e+00,5.656854305839434716e+00,2.206285982294866610e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.018879373688076839e+01,3.663400718831534846e+02,4.893569914664781528e+00,5.656854305839434716e+00,2.203785982294866608e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.019056150381612724e+01,3.663498300307339264e+02,4.895755905469565405e+00,5.656854305839434716e+00,2.201285982294866606e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.019232927075148609e+01,3.663595887245070912e+02,4.897939456669167413e+00,5.656854305839434716e+00,2.198785982294866603e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.019409703768684494e+01,3.663693479638631061e+02,4.900120568127115384e+00,5.656854305839434716e+00,2.196285982294866601e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.019586480462220379e+01,3.663791077481919842e+02,4.902299239707089917e+00,5.656854305839434716e+00,2.193785982294866599e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.019763257155756264e+01,3.663888680768837958e+02,4.904475471272924381e+00,5.656854305839434716e+00,2.191285982294866597e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.019940033849292149e+01,3.663986289493284403e+02,4.906649262688604018e+00,5.656854305839434716e+00,2.188785982294866594e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.020116810542828034e+01,3.664083903649159311e+02,4.908820613818266843e+00,5.656854305839434716e+00,2.186285982294866592e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.020293587236363919e+01,3.664181523230361677e+02,4.910989524526203631e+00,5.656854305839434716e+00,2.183785982294866590e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.020470363929899804e+01,3.664279148230789929e+02,4.913155994676857041e+00,5.656854305839434716e+00,2.181285982294866588e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.020647140623435689e+01,3.664376778644343062e+02,4.915320024134823385e+00,5.656854305839434716e+00,2.178785982294866586e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.020823917316971574e+01,3.664474414464918368e+02,4.917481612764849963e+00,5.656854305839434716e+00,2.176285982294866583e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.021000694010507459e+01,3.664572055686414274e+02,4.919640760431837734e+00,5.656854305839434716e+00,2.173785982294866581e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.021177470704043344e+01,3.664669702302728069e+02,4.921797467000840420e+00,5.656854305839434716e+00,2.171285982294866579e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.021354247397579229e+01,3.664767354307756477e+02,4.923951732337063625e+00,5.656854305839434716e+00,2.168785982294866577e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.021531024091115114e+01,3.664865011695396788e+02,4.926103556305865716e+00,5.656854305839434716e+00,2.166285982294866574e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.021707800784650999e+01,3.664962674459545156e+02,4.928252938772757830e+00,5.656854305839434716e+00,2.163785982294866572e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.021884577478186884e+01,3.665060342594097733e+02,4.930399879603403868e+00,5.656854305839434716e+00,2.161285982294866570e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.022061354171722769e+01,3.665158016092950106e+02,4.932544378663619611e+00,5.656854305839434716e+00,2.158785982294866568e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.022238130865258654e+01,3.665255694949997860e+02,4.934686435819373607e+00,5.656854305839434716e+00,2.156285982294866566e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.022414907558794539e+01,3.665353379159136011e+02,4.936826050936787169e+00,5.656854305839434716e+00,2.153785982294866563e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.022591684252330424e+01,3.665451068714259009e+02,4.938963223882135267e+00,5.656854305839434716e+00,2.151285982294866561e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.022768460945866309e+01,3.665548763609261869e+02,4.941097954521843860e+00,5.656854305839434716e+00,2.148785982294866559e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.022945237639402194e+01,3.665646463838037903e+02,4.943230242722492562e+00,5.656854305839434716e+00,2.146285982294866557e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.023122014332938079e+01,3.665744169394481560e+02,4.945360088350812866e+00,5.656854305839434716e+00,2.143785982294866554e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.023298791026473964e+01,3.665841880272486151e+02,4.947487491273689919e+00,5.656854305839434716e+00,2.141285982294866552e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.023475567720009849e+01,3.665939596465944419e+02,4.949612451358161636e+00,5.656854305839434716e+00,2.138785982294866550e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.023652344413545734e+01,3.666037317968749107e+02,4.951734968471416920e+00,5.656854305839434716e+00,2.136285982294866548e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.023829121107081619e+01,3.666135044774792391e+02,4.953855042480799220e+00,5.656854305839434716e+00,2.133785982294866546e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.024005897800617504e+01,3.666232776877967012e+02,4.955972673253802974e+00,5.656854305839434716e+00,2.131285982294866543e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.024182674494153389e+01,3.666330514272164578e+02,4.958087860658077162e+00,5.656854305839434716e+00,2.128785982294866541e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.024359451187689274e+01,3.666428256951276126e+02,4.960200604561422644e+00,5.656854305839434716e+00,2.126285982294866539e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.024536227881225159e+01,3.666526004909192693e+02,4.962310904831792158e+00,5.656854305839434716e+00,2.123785982294866537e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.024713004574761044e+01,3.666623758139805318e+02,4.964418761337292096e+00,5.656854305839434716e+00,2.121285982294866534e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.024889781268296929e+01,3.666721516637004470e+02,4.966524173946181619e+00,5.656854305839434716e+00,2.118785982294866532e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.025066557961832814e+01,3.666819280394680050e+02,4.968627142526872653e+00,5.656854305839434716e+00,2.116285982294866530e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.025243334655368699e+01,3.666917049406721958e+02,4.970727666947929890e+00,5.656854305839434716e+00,2.113785982294866528e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.025420111348904584e+01,3.667014823667019527e+02,4.972825747078069902e+00,5.656854305839434716e+00,2.111285982294866526e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.025596888042440469e+01,3.667112603169462091e+02,4.974921382786162916e+00,5.656854305839434716e+00,2.108785982294866523e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.025773664735976354e+01,3.667210387907938411e+02,4.977014573941231923e+00,5.656854305839434716e+00,2.106285982294866521e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.025950441429512239e+01,3.667308177876336686e+02,4.979105320412451796e+00,5.656854305839434716e+00,2.103785982294866519e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.026127218123048124e+01,3.667405973068545109e+02,4.981193622069151949e+00,5.656854305839434716e+00,2.101285982294866517e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.026303994816584009e+01,3.667503773478451308e+02,4.983279478780812788e+00,5.656854305839434716e+00,2.098785982294866514e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.026480771510119894e+01,3.667601579099942910e+02,4.985362890417068371e+00,5.656854305839434716e+00,2.096285982294866512e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.026657548203655779e+01,3.667699389926907543e+02,4.987443856847705526e+00,5.656854305839434716e+00,2.093785982294866510e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.026834324897191664e+01,3.667797205953231128e+02,4.989522377942663844e+00,5.656854305839434716e+00,2.091285982294866508e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.027011101590727549e+01,3.667895027172800724e+02,4.991598453572035687e+00,5.656854305839434716e+00,2.088785982294866506e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.027187878284263434e+01,3.667992853579502821e+02,4.993672083606066181e+00,5.656854305839434716e+00,2.086285982294866503e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.027364654977799319e+01,3.668090685167222773e+02,4.995743267915154107e+00,5.656854305839434716e+00,2.083785982294866501e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.027541431671335204e+01,3.668188521929845933e+02,4.997812006369850124e+00,5.656854305839434716e+00,2.081285982294866499e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.027718208364871089e+01,3.668286363861257655e+02,4.999878298840857660e+00,5.656854305839434716e+00,2.078785982294866497e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.027894985058406974e+01,3.668384210955343292e+02,5.001942145199033796e+00,5.656854305839434716e+00,2.076285982294866495e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.028071761751942859e+01,3.668482063205987060e+02,5.004003545315387491e+00,5.656854305839434716e+00,2.073785982294866492e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.028248538445478744e+01,3.668579920607073177e+02,5.006062499061082249e+00,5.656854305839434716e+00,2.071285982294866490e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.028425315139014629e+01,3.668677783152485290e+02,5.008119006307433452e+00,5.656854305839434716e+00,2.068785982294866488e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.028602091832550514e+01,3.668775650836107616e+02,5.010173066925908358e+00,5.656854305839434716e+00,2.066285982294866486e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.028778868526086399e+01,3.668873523651822666e+02,5.012224680788128772e+00,5.656854305839434716e+00,2.063785982294866483e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.028955645219622284e+01,3.668971401593514088e+02,5.014273847765869263e+00,5.656854305839434716e+00,2.061285982294866481e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.029132421913158169e+01,3.669069284655064394e+02,5.016320567731056279e+00,5.656854305839434716e+00,2.058785982294866479e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.029309198606694054e+01,3.669167172830355526e+02,5.018364840555769923e+00,5.656854305839434716e+00,2.056285982294866477e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.029485975300229939e+01,3.669265066113269427e+02,5.020406666112243066e+00,5.656854305839434716e+00,2.053785982294866475e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.029662751993765823e+01,3.669362964497688040e+02,5.022446044272862231e+00,5.656854305839434716e+00,2.051285982294866472e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.029839528687301708e+01,3.669460867977492740e+02,5.024482974910165822e+00,5.656854305839434716e+00,2.048785982294866470e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.030016305380837593e+01,3.669558776546564332e+02,5.026517457896845897e+00,5.656854305839434716e+00,2.046285982294866468e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.030193082074373478e+01,3.669656690198784190e+02,5.028549493105746393e+00,5.656854305839434716e+00,2.043785982294866466e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.030369858767909363e+01,3.669754608928031985e+02,5.030579080409866677e+00,5.656854305839434716e+00,2.041285982294866463e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.030546635461445248e+01,3.669852532728187953e+02,5.032606219682356219e+00,5.656854305839434716e+00,2.038785982294866461e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.030723412154981133e+01,3.669950461593131763e+02,5.034630910796519032e+00,5.656854305839434716e+00,2.036285982294866459e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.030900188848517018e+01,3.670048395516743085e+02,5.036653153625812784e+00,5.656854305839434716e+00,2.033785982294866457e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.031076965542052903e+01,3.670146334492901019e+02,5.038672948043846134e+00,5.656854305839434716e+00,2.031285982294866455e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.031253742235588788e+01,3.670244278515484666e+02,5.040690293924382281e+00,5.656854305839434716e+00,2.028785982294866452e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.031430518929124673e+01,3.670342227578371990e+02,5.042705191141337195e+00,5.656854305839434716e+00,2.026285982294866450e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.031607295622660558e+01,3.670440181675441522e+02,5.044717639568780498e+00,5.656854305839434716e+00,2.023785982294866448e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.031784072316196443e+01,3.670538140800570659e+02,5.046727639080933692e+00,5.656854305839434716e+00,2.021285982294866446e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.031960849009732328e+01,3.670636104947637364e+02,5.048735189552171043e+00,5.656854305839434716e+00,2.018785982294866443e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.032137625703268213e+01,3.670734074110519032e+02,5.050740290857021364e+00,5.656854305839434716e+00,2.016285982294866441e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.032314402396804098e+01,3.670832048283092490e+02,5.052742942870166232e+00,5.656854305839434716e+00,2.013785982294866439e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.032491179090339983e+01,3.670930027459233997e+02,5.054743145466439103e+00,5.656854305839434716e+00,2.011285982294866437e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.032667955783875868e+01,3.671028011632820380e+02,5.056740898520827976e+00,5.656854305839434716e+00,2.008785982294866435e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.032844732477411753e+01,3.671126000797727329e+02,5.058736201908472729e+00,5.656854305839434716e+00,2.006285982294866432e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.033021509170947638e+01,3.671223994947830533e+02,5.060729055504666896e+00,5.656854305839434716e+00,2.003785982294866430e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.033198285864483523e+01,3.671321994077005115e+02,5.062719459184857662e+00,5.656854305839434716e+00,2.001285982294866428e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.033375062558019408e+01,3.671419998179126196e+02,5.064707412824644095e+00,5.656854305839434716e+00,1.998785982294866426e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.033551839251555293e+01,3.671518007248068898e+02,5.066692916299779803e+00,5.656854305839434716e+00,1.996285982294866423e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.033728615945091178e+01,3.671616021277707773e+02,5.068675969486170274e+00,5.656854305839434716e+00,1.993785982294866421e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.033905392638627063e+01,3.671714040261916239e+02,5.070656572259874650e+00,5.656854305839434716e+00,1.991285982294866419e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.034082169332162948e+01,3.671812064194568848e+02,5.072634724497105729e+00,5.656854305839434716e+00,1.988785982294866417e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.034258946025698833e+01,3.671910093069538448e+02,5.074610426074229075e+00,5.656854305839434716e+00,1.986285982294866415e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.034435722719234718e+01,3.672008126880698455e+02,5.076583676867763018e+00,5.656854305839434716e+00,1.983785982294866412e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.034612499412770603e+01,3.672106165621921718e+02,5.078554476754379543e+00,5.656854305839434716e+00,1.981285982294866410e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.034789276106306488e+01,3.672204209287081085e+02,5.080522825610903404e+00,5.656854305839434716e+00,1.978785982294866408e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.034966052799842373e+01,3.672302257870048834e+02,5.082488723314313006e+00,5.656854305839434716e+00,1.976285982294866406e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.035142829493378258e+01,3.672400311364696677e+02,5.084452169741739525e+00,5.656854305839434716e+00,1.973785982294866403e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.035319606186914143e+01,3.672498369764896324e+02,5.086413164770467787e+00,5.656854305839434716e+00,1.971285982294866401e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.035496382880450028e+01,3.672596433064519488e+02,5.088371708277935390e+00,5.656854305839434716e+00,1.968785982294866399e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.035673159573985913e+01,3.672694501257436741e+02,5.090327800141733583e+00,5.656854305839434716e+00,1.966285982294866397e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.035849936267521798e+01,3.672792574337518658e+02,5.092281440239606383e+00,5.656854305839434716e+00,1.963785982294866395e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.036026712961057683e+01,3.672890652298636383e+02,5.094232628449451461e+00,5.656854305839434716e+00,1.961285982294866392e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.036203489654593568e+01,3.672988735134659350e+02,5.096181364649319256e+00,5.656854305839434716e+00,1.958785982294866390e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.036380266348129453e+01,3.673086822839457568e+02,5.098127648717413862e+00,5.656854305839434716e+00,1.956285982294866388e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.036557043041665338e+01,3.673184915406901041e+02,5.100071480532093027e+00,5.656854305839434716e+00,1.953785982294866386e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.036733819735201223e+01,3.673283012830858638e+02,5.102012859971866376e+00,5.656854305839434716e+00,1.951285982294866383e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.036910596428737108e+01,3.673381115105199228e+02,5.103951786915398081e+00,5.656854305839434716e+00,1.948785982294866381e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.037087373122272993e+01,3.673479222223791112e+02,5.105888261241505965e+00,5.656854305839434716e+00,1.946285982294866379e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.037264149815808878e+01,3.673577334180503158e+02,5.107822282829159732e+00,5.656854305839434716e+00,1.943785982294866377e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.037440926509344763e+01,3.673675450969203098e+02,5.109753851557482740e+00,5.656854305839434716e+00,1.941285982294866375e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.037617703202880648e+01,3.673773572583758664e+02,5.111682967305752889e+00,5.656854305839434716e+00,1.938785982294866372e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.037794479896416533e+01,3.673871699018037020e+02,5.113609629953399072e+00,5.656854305839434716e+00,1.936285982294866370e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.037971256589952418e+01,3.673969830265905898e+02,5.115533839380005610e+00,5.656854305839434716e+00,1.933785982294866368e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.038148033283488303e+01,3.674067966321231324e+02,5.117455595465309592e+00,5.656854305839434716e+00,1.931285982294866366e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.038324809977024188e+01,3.674166107177880463e+02,5.119374898089201764e+00,5.656854305839434716e+00,1.928785982294866364e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.038501586670560073e+01,3.674264252829718771e+02,5.121291747131724748e+00,5.656854305839434716e+00,1.926285982294866361e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.038678363364095958e+01,3.674362403270612845e+02,5.123206142473075708e+00,5.656854305839434716e+00,1.923785982294866359e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.038855140057631843e+01,3.674460558494428142e+02,5.125118083993604579e+00,5.656854305839434716e+00,1.921285982294866357e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.039031916751167728e+01,3.674558718495029552e+02,5.127027571573815834e+00,5.656854305839434716e+00,1.918785982294866355e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.039208693444703613e+01,3.674656883266282534e+02,5.128934605094365828e+00,5.656854305839434716e+00,1.916285982294866352e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.039385470138239498e+01,3.674755052802051409e+02,5.130839184436065459e+00,5.656854305839434716e+00,1.913785982294866350e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.039562246831775383e+01,3.674853227096201067e+02,5.132741309479878389e+00,5.656854305839434716e+00,1.911285982294866348e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.039739023525311268e+01,3.674951406142595260e+02,5.134640980106921937e+00,5.656854305839434716e+00,1.908785982294866346e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.039915800218847153e+01,3.675049589935097742e+02,5.136538196198466188e+00,5.656854305839434716e+00,1.906285982294866344e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.040092576912383038e+01,3.675147778467572266e+02,5.138432957635935772e+00,5.656854305839434716e+00,1.903785982294866341e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.040269353605918923e+01,3.675245971733882016e+02,5.140325264300907193e+00,5.656854305839434716e+00,1.901285982294866339e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.040446130299454808e+01,3.675344169727889607e+02,5.142215116075112391e+00,5.656854305839434716e+00,1.898785982294866337e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.040622906992990693e+01,3.675442372443458225e+02,5.144102512840435182e+00,5.656854305839434716e+00,1.896285982294866335e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.040799683686526578e+01,3.675540579874449918e+02,5.145987454478913037e+00,5.656854305839434716e+00,1.893785982294866332e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.040976460380062463e+01,3.675638792014726732e+02,5.147869940872737082e+00,5.656854305839434716e+00,1.891285982294866330e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.041153237073598348e+01,3.675737008858150148e+02,5.149749971904252099e+00,5.656854305839434716e+00,1.888785982294866328e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.041330013767134233e+01,3.675835230398581643e+02,5.151627547455956524e+00,5.656854305839434716e+00,1.886285982294866326e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.041506790460670118e+01,3.675933456629882699e+02,5.153502667410501559e+00,5.656854305839434716e+00,1.883785982294866324e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.041683567154206003e+01,3.676031687545914224e+02,5.155375331650692061e+00,5.656854305839434716e+00,1.881285982294866321e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.041860343847741888e+01,3.676129923140536562e+02,5.157245540059486544e+00,5.656854305839434716e+00,1.878785982294866319e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.042037120541277773e+01,3.676228163407610054e+02,5.159113292519997174e+00,5.656854305839434716e+00,1.876285982294866317e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.042213897234813658e+01,3.676326408340994476e+02,5.160978588915488885e+00,5.656854305839434716e+00,1.873785982294866315e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.042390673928349543e+01,3.676424657934549600e+02,5.162841429129381154e+00,5.656854305839434716e+00,1.871285982294866312e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.042567450621885428e+01,3.676522912182135201e+02,5.164701813045246226e+00,5.656854305839434716e+00,1.868785982294866310e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.042744227315421313e+01,3.676621171077609915e+02,5.166559740546809998e+00,5.656854305839434716e+00,1.866285982294866308e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.042921004008957198e+01,3.676719434614832380e+02,5.168415211517952912e+00,5.656854305839434716e+00,1.863785982294866306e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.043097780702493083e+01,3.676817702787661801e+02,5.170268225842707288e+00,5.656854305839434716e+00,1.861285982294866304e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.043274557396028968e+01,3.676915975589956247e+02,5.172118783405259990e+00,5.656854305839434716e+00,1.858785982294866301e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.043451334089564853e+01,3.677014253015573217e+02,5.173966884089950646e+00,5.656854305839434716e+00,1.856285982294866299e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.043628110783100738e+01,3.677112535058370781e+02,5.175812527781273431e+00,5.656854305839434716e+00,1.853785982294866297e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.043804887476636623e+01,3.677210821712206439e+02,5.177655714363875283e+00,5.656854305839434716e+00,1.851285982294866295e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.043981664170172508e+01,3.677309112970937122e+02,5.179496443722557686e+00,5.656854305839434716e+00,1.848785982294866292e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.044158440863708392e+01,3.677407408828419193e+02,5.181334715742274000e+00,5.656854305839434716e+00,1.846285982294866290e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.044335217557244277e+01,3.677505709278509585e+02,5.183170530308133017e+00,5.656854305839434716e+00,1.843785982294866288e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.044511994250780162e+01,3.677604014315064660e+02,5.185003887305396297e+00,5.656854305839434716e+00,1.841285982294866286e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.044688770944316047e+01,3.677702323931940214e+02,5.186834786619479054e+00,5.656854305839434716e+00,1.838785982294866284e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.044865547637851932e+01,3.677800638122991472e+02,5.188663228135950156e+00,5.656854305839434716e+00,1.836285982294866281e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.045042324331387817e+01,3.677898956882074231e+02,5.190489211740531239e+00,5.656854305839434716e+00,1.833785982294866279e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.045219101024923702e+01,3.677997280203043715e+02,5.192312737319099369e+00,5.656854305839434716e+00,1.831285982294866277e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.045395877718459587e+01,3.678095608079754584e+02,5.194133804757683492e+00,5.656854305839434716e+00,1.828785982294866275e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.045572654411995472e+01,3.678193940506060926e+02,5.195952413942467096e+00,5.656854305839434716e+00,1.826285982294866272e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.045749431105531357e+01,3.678292277475817400e+02,5.197768564759787324e+00,5.656854305839434716e+00,1.823785982294866270e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.045926207799067242e+01,3.678390618982877527e+02,5.199582257096134086e+00,5.656854305839434716e+00,1.821285982294866268e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.046102984492603127e+01,3.678488965021095396e+02,5.201393490838151834e+00,5.656854305839434716e+00,1.818785982294866266e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.046279761186139012e+01,3.678587315584324529e+02,5.203202265872638677e+00,5.656854305839434716e+00,1.816285982294866264e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.046456537879674897e+01,3.678685670666417877e+02,5.205008582086546376e+00,5.656854305839434716e+00,1.813785982294866261e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.046633314573210782e+01,3.678784030261227826e+02,5.206812439366980350e+00,5.656854305839434716e+00,1.811285982294866259e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.046810091266746667e+01,3.678882394362607329e+02,5.208613837601198782e+00,5.656854305839434716e+00,1.808785982294866257e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.046986867960282552e+01,3.678980762964408200e+02,5.210412776676615287e+00,5.656854305839434716e+00,1.806285982294866255e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.047163644653818437e+01,3.679079136060482824e+02,5.212209256480795361e+00,5.656854305839434716e+00,1.803785982294866252e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.047340421347354322e+01,3.679177513644683017e+02,5.214003276901459039e+00,5.656854305839434716e+00,1.801285982294866250e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.047517198040890207e+01,3.679275895710859459e+02,5.215794837826480013e+00,5.656854305839434716e+00,1.798785982294866248e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.047693974734426092e+01,3.679374282252863964e+02,5.217583939143885630e+00,5.656854305839434716e+00,1.796285982294866246e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.047870751427961977e+01,3.679472673264547211e+02,5.219370580741857779e+00,5.656854305839434716e+00,1.793785982294866244e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.048047528121497862e+01,3.679571068739759880e+02,5.221154762508731118e+00,5.656854305839434716e+00,1.791285982294866241e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.048224304815033747e+01,3.679669468672352082e+02,5.222936484332993956e+00,5.656854305839434716e+00,1.788785982294866239e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.048401081508569632e+01,3.679767873056173357e+02,5.224715746103289149e+00,5.656854305839434716e+00,1.786285982294866237e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.048577858202105517e+01,3.679866281885073818e+02,5.226492547708412317e+00,5.656854305839434716e+00,1.783785982294866235e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.048754634895641402e+01,3.679964695152903005e+02,5.228266889037313625e+00,5.656854305839434716e+00,1.781285982294866233e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.048931411589177287e+01,3.680063112853510461e+02,5.230038769979096003e+00,5.656854305839434716e+00,1.778785982294866230e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.049108188282713172e+01,3.680161534980744591e+02,5.231808190423017813e+00,5.656854305839434716e+00,1.776285982294866228e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.049284964976249057e+01,3.680259961528453800e+02,5.233575150258490183e+00,5.656854305839434716e+00,1.773785982294866226e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.049461741669784942e+01,3.680358392490487063e+02,5.235339649375077897e+00,5.656854305839434716e+00,1.771285982294866224e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.049638518363320827e+01,3.680456827860691646e+02,5.237101687662499394e+00,5.656854305839434716e+00,1.768785982294866221e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.049815295056856712e+01,3.680555267632915957e+02,5.238861265010627655e+00,5.656854305839434716e+00,1.766285982294866219e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.049992071750392597e+01,3.680653711801007262e+02,5.240618381309489315e+00,5.656854305839434716e+00,1.763785982294866217e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.050168848443928482e+01,3.680752160358812830e+02,5.242373036449264667e+00,5.656854305839434716e+00,1.761285982294866215e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.050345625137464367e+01,3.680850613300179930e+02,5.244125230320287656e+00,5.656854305839434716e+00,1.758785982294866213e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.050522401831000252e+01,3.680949070618955261e+02,5.245874962813045883e+00,5.656854305839434716e+00,1.756285982294866210e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.050699178524536137e+01,3.681047532308984955e+02,5.247622233818181492e+00,5.656854305839434716e+00,1.753785982294866208e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.050875955218072022e+01,3.681145998364115144e+02,5.249367043226489393e+00,5.656854305839434716e+00,1.751285982294866206e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.051052731911607907e+01,3.681244468778191390e+02,5.251109390928919929e+00,5.656854305839434716e+00,1.748785982294866204e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.051229508605143792e+01,3.681342943545059825e+02,5.252849276816575319e+00,5.656854305839434716e+00,1.746285982294866201e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.051406285298679677e+01,3.681441422658565443e+02,5.254586700780713215e+00,5.656854305839434716e+00,1.743785982294866199e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.051583061992215562e+01,3.681539906112553808e+02,5.256321662712744924e+00,5.656854305839434716e+00,1.741285982294866197e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.051759838685751447e+01,3.681638393900869346e+02,5.258054162504234519e+00,5.656854305839434716e+00,1.738785982294866195e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.051936615379287332e+01,3.681736886017356483e+02,5.259784200046901503e+00,5.656854305839434716e+00,1.736285982294866193e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.052113392072823217e+01,3.681835382455859644e+02,5.261511775232618149e+00,5.656854305839434716e+00,1.733785982294866190e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.052290168766359102e+01,3.681933883210222689e+02,5.263236887953411269e+00,5.656854305839434716e+00,1.731285982294866188e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.052466945459894987e+01,3.682032388274288905e+02,5.264959538101461334e+00,5.656854305839434716e+00,1.728785982294866186e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.052643722153430872e+01,3.682130897641902152e+02,5.266679725569102466e+00,5.656854305839434716e+00,1.726285982294866184e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.052820498846966757e+01,3.682229411306905718e+02,5.268397450248823333e+00,5.656854305839434716e+00,1.723785982294866181e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.052997275540502642e+01,3.682327929263142323e+02,5.270112712033265367e+00,5.656854305839434716e+00,1.721285982294866179e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.053174052234038527e+01,3.682426451504454690e+02,5.271825510815225435e+00,5.656854305839434716e+00,1.718785982294866177e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.053350828927574412e+01,3.682524978024685538e+02,5.273535846487653167e+00,5.656854305839434716e+00,1.716285982294866175e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.053527605621110297e+01,3.682623508817676452e+02,5.275243718943652738e+00,5.656854305839434716e+00,1.713785982294866173e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.053704382314646182e+01,3.682722043877269016e+02,5.276949128076482864e+00,5.656854305839434716e+00,1.711285982294866170e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.053881159008182067e+01,3.682820583197305382e+02,5.278652073779554144e+00,5.656854305839434716e+00,1.708785982294866168e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.054057935701717952e+01,3.682919126771626566e+02,5.280352555946433490e+00,5.656854305839434716e+00,1.706285982294866166e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.054234712395253837e+01,3.683017674594073583e+02,5.282050574470840587e+00,5.656854305839434716e+00,1.703785982294866164e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.054411489088789722e+01,3.683116226658487449e+02,5.283746129246648771e+00,5.656854305839434716e+00,1.701285982294866161e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.054588265782325607e+01,3.683214782958708611e+02,5.285439220167885921e+00,5.656854305839434716e+00,1.698785982294866159e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.054765042475861492e+01,3.683313343488576947e+02,5.287129847128734461e+00,5.656854305839434716e+00,1.696285982294866157e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.054941819169397377e+01,3.683411908241932338e+02,5.288818010023529581e+00,5.656854305839434716e+00,1.693785982294866155e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.055118595862933262e+01,3.683510477212615228e+02,5.290503708746761902e+00,5.656854305839434716e+00,1.691285982294866153e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.055295372556469147e+01,3.683609050394464361e+02,5.292186943193074811e+00,5.656854305839434716e+00,1.688785982294866150e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.055472149250005032e+01,3.683707627781319047e+02,5.293867713257266239e+00,5.656854305839434716e+00,1.686285982294866148e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.055648925943540917e+01,3.683806209367018596e+02,5.295546018834287771e+00,5.656854305839434716e+00,1.683785982294866146e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.055825702637076802e+01,3.683904795145401181e+02,5.297221859819245537e+00,5.656854305839434716e+00,1.681285982294866144e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.056002479330612687e+01,3.684003385110305544e+02,5.298895236107399320e+00,5.656854305839434716e+00,1.678785982294866141e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.056179256024148572e+01,3.684101979255569290e+02,5.300566147594162558e+00,5.656854305839434716e+00,1.676285982294866139e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.056356032717684457e+01,3.684200577575031161e+02,5.302234594175104121e+00,5.656854305839434716e+00,1.673785982294866137e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.056532809411220342e+01,3.684299180062528194e+02,5.303900575745945645e+00,5.656854305839434716e+00,1.671285982294866135e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.056709586104756227e+01,3.684397786711897425e+02,5.305564092202564197e+00,5.656854305839434716e+00,1.668785982294866133e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.056886362798292112e+01,3.684496397516976458e+02,5.307225143440988724e+00,5.656854305839434716e+00,1.666285982294866130e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.057063139491827997e+01,3.684595012471601763e+02,5.308883729357404491e+00,5.656854305839434716e+00,1.663785982294866128e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.057239916185363882e+01,3.684693631569610375e+02,5.310539849848149530e+00,5.656854305839434716e+00,1.661285982294866126e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.057416692878899767e+01,3.684792254804838194e+02,5.312193504809716416e+00,5.656854305839434716e+00,1.658785982294866124e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.057593469572435652e+01,3.684890882171121689e+02,5.313844694138751379e+00,5.656854305839434716e+00,1.656285982294866121e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.057770246265971537e+01,3.684989513662296190e+02,5.315493417732055192e+00,5.656854305839434716e+00,1.653785982294866119e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.057947022959507422e+01,3.685088149272197029e+02,5.317139675486582284e+00,5.656854305839434716e+00,1.651285982294866117e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.058123799653043307e+01,3.685186788994660105e+02,5.318783467299442513e+00,5.656854305839434716e+00,1.648785982294866115e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.058300576346579192e+01,3.685285432823520182e+02,5.320424793067898506e+00,5.656854305839434716e+00,1.646285982294866113e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.058477353040115077e+01,3.685384080752612022e+02,5.322063652689366542e+00,5.656854305839434716e+00,1.643785982294866110e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.058654129733650961e+01,3.685482732775770387e+02,5.323700046061419222e+00,5.656854305839434716e+00,1.641285982294866108e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.058830906427186846e+01,3.685581388886828904e+02,5.325333973081781025e+00,5.656854305839434716e+00,1.638785982294866106e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.059007683120722731e+01,3.685680049079621767e+02,5.326965433648331860e+00,5.656854305839434716e+00,1.636285982294866104e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.059184459814258616e+01,3.685778713347983171e+02,5.328594427659105293e+00,5.656854305839434716e+00,1.633785982294866101e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.059361236507794501e+01,3.685877381685746172e+02,5.330220955012289430e+00,5.656854305839434716e+00,1.631285982294866099e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.059538013201330386e+01,3.685976054086744398e+02,5.331845015606226035e+00,5.656854305839434716e+00,1.628785982294866097e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.059714789894866271e+01,3.686074730544810336e+02,5.333466609339411413e+00,5.656854305839434716e+00,1.626285982294866095e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.059891566588402156e+01,3.686173411053777045e+02,5.335085736110496413e+00,5.656854305839434716e+00,1.623785982294866093e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.060068343281938041e+01,3.686272095607477013e+02,5.336702395818285538e+00,5.656854305839434716e+00,1.621285982294866090e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.060245119975473926e+01,3.686370784199742161e+02,5.338316588361736947e+00,5.656854305839434716e+00,1.618785982294866088e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.060421896669009811e+01,3.686469476824404410e+02,5.339928313639964230e+00,5.656854305839434716e+00,1.616285982294866086e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.060598673362545696e+01,3.686568173475295680e+02,5.341537571552233743e+00,5.656854305839434716e+00,1.613785982294866084e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.060775450056081581e+01,3.686666874146247324e+02,5.343144361997967273e+00,5.656854305839434716e+00,1.611285982294866082e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.060952226749617466e+01,3.686765578831090693e+02,5.344748684876740263e+00,5.656854305839434716e+00,1.608785982294866079e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.061129003443153351e+01,3.686864287523657140e+02,5.346350540088283587e+00,5.656854305839434716e+00,1.606285982294866077e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.061305780136689236e+01,3.686963000217776880e+02,5.347949927532479997e+00,5.656854305839434716e+00,1.603785982294866075e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.061482556830225121e+01,3.687061716907280129e+02,5.349546847109368564e+00,5.656854305839434716e+00,1.601285982294866073e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.061659333523761006e+01,3.687160437585997670e+02,5.351141298719141126e+00,5.656854305839434716e+00,1.598785982294866070e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.061836110217296891e+01,3.687259162247759150e+02,5.352733282262144954e+00,5.656854305839434716e+00,1.596285982294866068e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.062012886910832776e+01,3.687357890886394216e+02,5.354322797638880971e+00,5.656854305839434716e+00,1.593785982294866066e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.062189663604368661e+01,3.687456623495732515e+02,5.355909844750004645e+00,5.656854305839434716e+00,1.591285982294866064e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.062366440297904546e+01,3.687555360069603125e+02,5.357494423496325098e+00,5.656854305839434716e+00,1.588785982294866062e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.062543216991440431e+01,3.687654100601835125e+02,5.359076533778806883e+00,5.656854305839434716e+00,1.586285982294866059e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.062719993684976316e+01,3.687752845086257025e+02,5.360656175498567322e+00,5.656854305839434716e+00,1.583785982294866057e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.062896770378512201e+01,3.687851593516697335e+02,5.362233348556879164e+00,5.656854305839434716e+00,1.581285982294866055e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.063073547072048086e+01,3.687950345886984564e+02,5.363808052855168818e+00,5.656854305839434716e+00,1.578785982294866053e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.063250323765583971e+01,3.688049102190946087e+02,5.365380288295018119e+00,5.656854305839434716e+00,1.576285982294866050e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.063427100459119856e+01,3.688147862422410412e+02,5.366950054778161672e+00,5.656854305839434716e+00,1.573785982294866048e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.063603877152655741e+01,3.688246626575204345e+02,5.368517352206488624e+00,5.656854305839434716e+00,1.571285982294866046e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.063780653846191626e+01,3.688345394643155259e+02,5.370082180482043555e+00,5.656854305839434716e+00,1.568785982294866044e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.063957430539727511e+01,3.688444166620090527e+02,5.371644539507024696e+00,5.656854305839434716e+00,1.566285982294866042e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.064134207233263396e+01,3.688542942499836954e+02,5.373204429183783937e+00,5.656854305839434716e+00,1.563785982294866039e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.064310983926799281e+01,3.688641722276220776e+02,5.374761849414829484e+00,5.656854305839434716e+00,1.561285982294866037e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.064487760620335166e+01,3.688740505943068229e+02,5.376316800102821425e+00,5.656854305839434716e+00,1.558785982294866035e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.064664537313871051e+01,3.688839293494204981e+02,5.377869281150575276e+00,5.656854305839434716e+00,1.556285982294866033e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.064841314007406936e+01,3.688938084923457268e+02,5.379419292461061985e+00,5.656854305839434716e+00,1.553785982294866030e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.065018090700942821e+01,3.689036880224650758e+02,5.380966833937405269e+00,5.656854305839434716e+00,1.551285982294866028e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.065194867394478706e+01,3.689135679391610552e+02,5.382511905482883385e+00,5.656854305839434716e+00,1.548785982294866026e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.065371644088014591e+01,3.689234482418161747e+02,5.384054507000930023e+00,5.656854305839434716e+00,1.546285982294866024e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.065548420781550476e+01,3.689333289298128875e+02,5.385594638395132527e+00,5.656854305839434716e+00,1.543785982294866022e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.065725197475086361e+01,3.689432100025337036e+02,5.387132299569231897e+00,5.656854305839434716e+00,1.541285982294866019e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.065901974168622246e+01,3.689530914593610191e+02,5.388667490427125450e+00,5.656854305839434716e+00,1.538785982294866017e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.066078750862158131e+01,3.689629732996772304e+02,5.390200210872863273e+00,5.656854305839434716e+00,1.536285982294866015e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.066255527555694016e+01,3.689728555228647338e+02,5.391730460810649994e+00,5.656854305839434716e+00,1.533785982294866013e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.066432304249229901e+01,3.689827381283059253e+02,5.393258240144844784e+00,5.656854305839434716e+00,1.531285982294866010e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.066609080942765786e+01,3.689926211153830877e+02,5.394783548779962246e+00,5.656854305839434716e+00,1.528785982294866008e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.066785857636301671e+01,3.690025044834785604e+02,5.396306386620670636e+00,5.656854305839434716e+00,1.526285982294866006e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.066962634329837556e+01,3.690123882319746258e+02,5.397826753571791869e+00,5.656854305839434716e+00,1.523785982294866004e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.067139411023373441e+01,3.690222723602535666e+02,5.399344649538303287e+00,5.656854305839434716e+00,1.521285982294866002e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.067316187716909326e+01,3.690321568676976085e+02,5.400860074425336776e+00,5.656854305839434716e+00,1.518785982294865999e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.067492964410445211e+01,3.690420417536889772e+02,5.402373028138177879e+00,5.656854305839434716e+00,1.516285982294865997e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.067669741103981096e+01,3.690519270176098985e+02,5.403883510582266680e+00,5.656854305839434716e+00,1.513785982294865995e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.067846517797516981e+01,3.690618126588424843e+02,5.405391521663198695e+00,5.656854305839434716e+00,1.511285982294865993e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.068023294491052866e+01,3.690716986767689036e+02,5.406897061286723094e+00,5.656854305839434716e+00,1.508785982294865990e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.068200071184588751e+01,3.690815850707713253e+02,5.408400129358743591e+00,5.656854305839434716e+00,1.506285982294865988e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.068376847878124636e+01,3.690914718402318044e+02,5.409900725785318443e+00,5.656854305839434716e+00,1.503785982294865986e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.068553624571660521e+01,3.691013589845323963e+02,5.411398850472659561e+00,5.656854305839434716e+00,1.501285982294865984e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.068730401265196406e+01,3.691112465030552130e+02,5.412894503327135176e+00,5.656854305839434716e+00,1.498785982294865982e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.068907177958732291e+01,3.691211343951822528e+02,5.414387684255267175e+00,5.656854305839434716e+00,1.496285982294865979e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.069083954652268176e+01,3.691310226602955140e+02,5.415878393163731097e+00,5.656854305839434716e+00,1.493785982294865977e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.069260731345804061e+01,3.691409112977769951e+02,5.417366629959357915e+00,5.656854305839434716e+00,1.491285982294865975e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.069437508039339946e+01,3.691508003070086374e+02,5.418852394549132256e+00,5.656854305839434716e+00,1.488785982294865973e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.069614284732875831e+01,3.691606896873723827e+02,5.420335686840194178e+00,5.656854305839434716e+00,1.486285982294865970e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.069791061426411716e+01,3.691705794382501722e+02,5.421816506739838282e+00,5.656854305839434716e+00,1.483785982294865968e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.069967838119947601e+01,3.691804695590238907e+02,5.423294854155512823e+00,5.656854305839434716e+00,1.481285982294865966e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.070144614813483486e+01,3.691903600490753661e+02,5.424770728994821489e+00,5.656854305839434716e+00,1.478785982294865964e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.070321391507019371e+01,3.692002509077864829e+02,5.426244131165521623e+00,5.656854305839434716e+00,1.476285982294865962e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.070498168200555256e+01,3.692101421345390690e+02,5.427715060575525996e+00,5.656854305839434716e+00,1.473785982294865959e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.070674944894091141e+01,3.692200337287148955e+02,5.429183517132901926e+00,5.656854305839434716e+00,1.471285982294865957e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.070851721587627026e+01,3.692299256896957331e+02,5.430649500745870384e+00,5.656854305839434716e+00,1.468785982294865955e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.071028498281162911e+01,3.692398180168633530e+02,5.432113011322806884e+00,5.656854305839434716e+00,1.466285982294865953e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.071205274974698796e+01,3.692497107095994693e+02,5.433574048772243259e+00,5.656854305839434716e+00,1.463785982294865951e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.071382051668234681e+01,3.692596037672857960e+02,5.435032613002863222e+00,5.656854305839434716e+00,1.461285982294865948e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.071558828361770566e+01,3.692694971893040474e+02,5.436488703923507693e+00,5.656854305839434716e+00,1.458785982294865946e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.071735605055306451e+01,3.692793909750358239e+02,5.437942321443170357e+00,5.656854305839434716e+00,1.456285982294865944e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.071912381748842336e+01,3.692892851238627827e+02,5.439393465471000333e+00,5.656854305839434716e+00,1.453785982294865942e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.072089158442378221e+01,3.692991796351665812e+02,5.440842135916301281e+00,5.656854305839434716e+00,1.451285982294865939e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.072265935135914106e+01,3.693090745083287629e+02,5.442288332688530517e+00,5.656854305839434716e+00,1.448785982294865937e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.072442711829449991e+01,3.693189697427309284e+02,5.443732055697301675e+00,5.656854305839434716e+00,1.446285982294865935e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.072619488522985876e+01,3.693288653377546211e+02,5.445173304852382046e+00,5.656854305839434716e+00,1.443785982294865933e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.072796265216521761e+01,3.693387612927813848e+02,5.446612080063692574e+00,5.656854305839434716e+00,1.441285982294865931e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.072973041910057646e+01,3.693486576071927061e+02,5.448048381241310523e+00,5.656854305839434716e+00,1.438785982294865928e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.073149818603593530e+01,3.693585542803700150e+02,5.449482208295467700e+00,5.656854305839434716e+00,1.436285982294865926e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.073326595297129415e+01,3.693684513116948551e+02,5.450913561136548680e+00,5.656854305839434716e+00,1.433785982294865924e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.073503371990665300e+01,3.693783487005485995e+02,5.452342439675094354e+00,5.656854305839434716e+00,1.431285982294865922e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.073680148684201185e+01,3.693882464463126780e+02,5.453768843821800161e+00,5.656854305839434716e+00,1.428785982294865919e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.073856925377737070e+01,3.693981445483684638e+02,5.455192773487515190e+00,5.656854305839434716e+00,1.426285982294865917e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.074033702071272955e+01,3.694080430060973868e+02,5.456614228583244852e+00,5.656854305839434716e+00,1.423785982294865915e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.074210478764808840e+01,3.694179418188807063e+02,5.458033209020147325e+00,5.656854305839434716e+00,1.421285982294865913e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.074387255458344725e+01,3.694278409860997954e+02,5.459449714709537105e+00,5.656854305839434716e+00,1.418785982294865911e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.074564032151880610e+01,3.694377405071359703e+02,5.460863745562881455e+00,5.656854305839434716e+00,1.416285982294865908e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.074740808845416495e+01,3.694476403813704906e+02,5.462275301491803958e+00,5.656854305839434716e+00,1.413785982294865906e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.074917585538952380e+01,3.694575406081846154e+02,5.463684382408082740e+00,5.656854305839434716e+00,1.411285982294865904e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.075094362232488265e+01,3.694674411869596042e+02,5.465090988223650470e+00,5.656854305839434716e+00,1.408785982294865902e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.075271138926024150e+01,3.694773421170766596e+02,5.466495118850593471e+00,5.656854305839434716e+00,1.406285982294865899e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.075447915619560035e+01,3.694872433979169273e+02,5.467896774201153498e+00,5.656854305839434716e+00,1.403785982294865897e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.075624692313095920e+01,3.694971450288616097e+02,5.469295954187727737e+00,5.656854305839434716e+00,1.401285982294865895e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.075801469006631805e+01,3.695070470092919095e+02,5.470692658722867030e+00,5.656854305839434716e+00,1.398785982294865893e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.075978245700167690e+01,3.695169493385888586e+02,5.472086887719277648e+00,5.656854305839434716e+00,1.396285982294865891e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.076155022393703575e+01,3.695268520161336028e+02,5.473478641089820407e+00,5.656854305839434716e+00,1.393785982294865888e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.076331799087239460e+01,3.695367550413072308e+02,5.474867918747510664e+00,5.656854305839434716e+00,1.391285982294865886e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.076508575780775345e+01,3.695466584134908317e+02,5.476254720605518322e+00,5.656854305839434716e+00,1.388785982294865884e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.076685352474311230e+01,3.695565621320653804e+02,5.477639046577167825e+00,5.656854305839434716e+00,1.386285982294865882e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.076862129167847115e+01,3.695664661964119659e+02,5.479020896575939936e+00,5.656854305839434716e+00,1.383785982294865879e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.077038905861383000e+01,3.695763706059115066e+02,5.480400270515468186e+00,5.656854305839434716e+00,1.381285982294865877e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.077215682554918885e+01,3.695862753599450343e+02,5.481777168309541537e+00,5.656854305839434716e+00,1.378785982294865875e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.077392459248454770e+01,3.695961804578934675e+02,5.483151589872104381e+00,5.656854305839434716e+00,1.376285982294865873e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.077569235941990655e+01,3.696060858991377813e+02,5.484523535117255655e+00,5.656854305839434716e+00,1.373785982294865871e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.077746012635526540e+01,3.696159916830588372e+02,5.485893003959247949e+00,5.656854305839434716e+00,1.371285982294865868e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.077922789329062425e+01,3.696258978090375535e+02,5.487259996312490173e+00,5.656854305839434716e+00,1.368785982294865866e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.078099566022598310e+01,3.696358042764547918e+02,5.488624512091544894e+00,5.656854305839434716e+00,1.366285982294865864e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.078276342716134195e+01,3.696457110846914134e+02,5.489986551211130106e+00,5.656854305839434716e+00,1.363785982294865862e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.078453119409670080e+01,3.696556182331282230e+02,5.491346113586118349e+00,5.656854305839434716e+00,1.361285982294865859e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.078629896103205965e+01,3.696655257211460253e+02,5.492703199131536707e+00,5.656854305839434716e+00,1.358785982294865857e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.078806672796741850e+01,3.696754335481255680e+02,5.494057807762567691e+00,5.656854305839434716e+00,1.356285982294865855e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.078983449490277735e+01,3.696853417134476558e+02,5.495409939394547472e+00,5.656854305839434716e+00,1.353785982294865853e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.079160226183813620e+01,3.696952502164930365e+02,5.496759593942968536e+00,5.656854305839434716e+00,1.351285982294865851e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.079337002877349505e+01,3.697051590566424011e+02,5.498106771323477027e+00,5.656854305839434716e+00,1.348785982294865848e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.079513779570885390e+01,3.697150682332764404e+02,5.499451471451875406e+00,5.656854305839434716e+00,1.346285982294865846e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.079690556264421275e+01,3.697249777457758455e+02,5.500793694244118903e+00,5.656854305839434716e+00,1.343785982294865844e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.079867332957957160e+01,3.697348875935212504e+02,5.502133439616319066e+00,5.656854305839434716e+00,1.341285982294865842e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.080044109651493045e+01,3.697447977758933462e+02,5.503470707484741098e+00,5.656854305839434716e+00,1.338785982294865839e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.080220886345028930e+01,3.697547082922727100e+02,5.504805497765806521e+00,5.656854305839434716e+00,1.336285982294865837e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.080397663038564815e+01,3.697646191420399191e+02,5.506137810376090513e+00,5.656854305839434716e+00,1.333785982294865835e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.080574439732100700e+01,3.697745303245755508e+02,5.507467645232323683e+00,5.656854305839434716e+00,1.331285982294865833e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.080751216425636585e+01,3.697844418392601824e+02,5.508795002251392070e+00,5.656854305839434716e+00,1.328785982294865831e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.080927993119172470e+01,3.697943536854743343e+02,5.510119881350335369e+00,5.656854305839434716e+00,1.326285982294865828e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.081104769812708355e+01,3.698042658625985268e+02,5.511442282446347818e+00,5.656854305839434716e+00,1.323785982294865826e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.081281546506244240e+01,3.698141783700132237e+02,5.512762205456779974e+00,5.656854305839434716e+00,1.321285982294865824e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.081458323199780125e+01,3.698240912070988884e+02,5.514079650299136937e+00,5.656854305839434716e+00,1.318785982294865822e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.081635099893316010e+01,3.698340043732359845e+02,5.515394616891078350e+00,5.656854305839434716e+00,1.316285982294865819e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.081811876586851895e+01,3.698439178678049757e+02,5.516707105150418400e+00,5.656854305839434716e+00,1.313785982294865817e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.081988653280387780e+01,3.698538316901862117e+02,5.518017114995126704e+00,5.656854305839434716e+00,1.311285982294865815e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.082165429973923665e+01,3.698637458397600994e+02,5.519324646343327423e+00,5.656854305839434716e+00,1.308785982294865813e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.082342206667459550e+01,3.698736603159069887e+02,5.520629699113300148e+00,5.656854305839434716e+00,1.306285982294865811e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.082518983360995435e+01,3.698835751180072293e+02,5.521932273223479015e+00,5.656854305839434716e+00,1.303785982294865808e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.082695760054531320e+01,3.698934902454411713e+02,5.523232368592453589e+00,5.656854305839434716e+00,1.301285982294865806e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.082872536748067205e+01,3.699034056975891076e+02,5.524529985138967092e+00,5.656854305839434716e+00,1.298785982294865804e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.083049313441603090e+01,3.699133214738313313e+02,5.525825122781919063e+00,5.656854305839434716e+00,1.296285982294865802e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.083226090135138975e+01,3.699232375735480787e+02,5.527117781440363586e+00,5.656854305839434716e+00,1.293785982294865800e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.083402866828674860e+01,3.699331539961196427e+02,5.528407961033509288e+00,5.656854305839434716e+00,1.291285982294865797e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.083579643522210745e+01,3.699430707409262027e+02,5.529695661480719338e+00,5.656854305839434716e+00,1.288785982294865795e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.083756420215746630e+01,3.699529878073479381e+02,5.530980882701513224e+00,5.656854305839434716e+00,1.286285982294865793e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.083933196909282515e+01,3.699629051947650851e+02,5.532263624615564090e+00,5.656854305839434716e+00,1.283785982294865791e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.084109973602818400e+01,3.699728229025578230e+02,5.533543887142701401e+00,5.656854305839434716e+00,1.281285982294865788e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.084286750296354285e+01,3.699827409301062175e+02,5.534821670202907384e+00,5.656854305839434716e+00,1.278785982294865786e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.084463526989890170e+01,3.699926592767904481e+02,5.536096973716321479e+00,5.656854305839434716e+00,1.276285982294865784e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.084640303683426055e+01,3.700025779419906371e+02,5.537369797603237664e+00,5.656854305839434716e+00,1.273785982294865782e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.084817080376961940e+01,3.700124969250867935e+02,5.538640141784103577e+00,5.656854305839434716e+00,1.271285982294865780e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.084993857070497825e+01,3.700224162254590397e+02,5.539908006179523170e+00,5.656854305839434716e+00,1.268785982294865777e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.085170633764033710e+01,3.700323358424873845e+02,5.541173390710254942e+00,5.656854305839434716e+00,1.266285982294865775e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.085347410457569595e+01,3.700422557755518937e+02,5.542436295297211934e+00,5.656854305839434716e+00,1.263785982294865773e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.085524187151105480e+01,3.700521760240325193e+02,5.543696719861462618e+00,5.656854305839434716e+00,1.261285982294865771e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.085700963844641365e+01,3.700620965873093269e+02,5.544954664324230897e+00,5.656854305839434716e+00,1.258785982294865768e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.085877740538177250e+01,3.700720174647622116e+02,5.546210128606895218e+00,5.656854305839434716e+00,1.256285982294865766e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.086054517231713135e+01,3.700819386557711255e+02,5.547463112630988569e+00,5.656854305839434716e+00,1.253785982294865764e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.086231293925249020e+01,3.700918601597160205e+02,5.548713616318200259e+00,5.656854305839434716e+00,1.251285982294865762e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.086408070618784905e+01,3.701017819759767917e+02,5.549961639590373252e+00,5.656854305839434716e+00,1.248785982294865760e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.086584847312320790e+01,3.701117041039332776e+02,5.551207182369505944e+00,5.656854305839434716e+00,1.246285982294865757e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.086761624005856675e+01,3.701216265429654300e+02,5.552450244577752159e+00,5.656854305839434716e+00,1.243785982294865755e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.086938400699392560e+01,3.701315492924530304e+02,5.553690826137420267e+00,5.656854305839434716e+00,1.241285982294865753e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.087115177392928445e+01,3.701414723517759171e+02,5.554928926970974068e+00,5.656854305839434716e+00,1.238785982294865751e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.087291954086464330e+01,3.701513957203139285e+02,5.556164547001032794e+00,5.656854305839434716e+00,1.236285982294865748e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.087468730780000215e+01,3.701613193974468459e+02,5.557397686150369331e+00,5.656854305839434716e+00,1.233785982294865746e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.087645507473536099e+01,3.701712433825544508e+02,5.558628344341912886e+00,5.656854305839434716e+00,1.231285982294865744e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.087822284167071984e+01,3.701811676750164679e+02,5.559856521498747206e+00,5.656854305839434716e+00,1.228785982294865742e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.087999060860607869e+01,3.701910922742126218e+02,5.561082217544111472e+00,5.656854305839434716e+00,1.226285982294865740e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.088175837554143754e+01,3.702010171795226370e+02,5.562305432401399408e+00,5.656854305839434716e+00,1.223785982294865737e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.088352614247679639e+01,3.702109423903262382e+02,5.563526165994160166e+00,5.656854305839434716e+00,1.221285982294865735e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.088529390941215524e+01,3.702208679060030363e+02,5.564744418246098334e+00,5.656854305839434716e+00,1.218785982294865733e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.088706167634751409e+01,3.702307937259327559e+02,5.565960189081073040e+00,5.656854305839434716e+00,1.216285982294865731e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.088882944328287294e+01,3.702407198494949512e+02,5.567173478423097954e+00,5.656854305839434716e+00,1.213785982294865728e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.089059721021823179e+01,3.702506462760692898e+02,5.568384286196343069e+00,5.656854305839434716e+00,1.211285982294865726e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.089236497715359064e+01,3.702605730050353827e+02,5.569592612325132919e+00,5.656854305839434716e+00,1.208785982294865724e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.089413274408894949e+01,3.702705000357727840e+02,5.570798456733946580e+00,5.656854305839434716e+00,1.206285982294865722e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.089590051102430834e+01,3.702804273676611047e+02,5.572001819347419449e+00,5.656854305839434716e+00,1.203785982294865720e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.089766827795966719e+01,3.702903550000798418e+02,5.573202700090340578e+00,5.656854305839434716e+00,1.201285982294865717e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.089943604489502604e+01,3.703002829324084928e+02,5.574401098887655337e+00,5.656854305839434716e+00,1.198785982294865715e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.090120381183038489e+01,3.703102111640266116e+02,5.575597015664463640e+00,5.656854305839434716e+00,1.196285982294865713e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.090297157876574374e+01,3.703201396943136388e+02,5.576790450346020833e+00,5.656854305839434716e+00,1.193785982294865711e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.090473934570110259e+01,3.703300685226490714e+02,5.577981402857737692e+00,5.656854305839434716e+00,1.191285982294865708e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.090650711263646144e+01,3.703399976484123499e+02,5.579169873125179535e+00,5.656854305839434716e+00,1.188785982294865706e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.090827487957182029e+01,3.703499270709829148e+02,5.580355861074066226e+00,5.656854305839434716e+00,1.186285982294865704e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.091004264650717914e+01,3.703598567897402063e+02,5.581539366630273946e+00,5.656854305839434716e+00,1.183785982294865702e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.091181041344253799e+01,3.703697868040635512e+02,5.582720389719834309e+00,5.656854305839434716e+00,1.181285982294865700e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.091357818037789684e+01,3.703797171133323332e+02,5.583898930268932581e+00,5.656854305839434716e+00,1.178785982294865697e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.091534594731325569e+01,3.703896477169259356e+02,5.585074988203909463e+00,5.656854305839434716e+00,1.176285982294865695e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.091711371424861454e+01,3.703995786142236852e+02,5.586248563451261973e+00,5.656854305839434716e+00,1.173785982294865693e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.091888148118397339e+01,3.704095098046049088e+02,5.587419655937641672e+00,5.656854305839434716e+00,1.171285982294865691e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.092064924811933224e+01,3.704194412874489331e+02,5.588588265589855553e+00,5.656854305839434716e+00,1.168785982294865688e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.092241701505469109e+01,3.704293730621349710e+02,5.589754392334865152e+00,5.656854305839434716e+00,1.166285982294865686e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.092418478199004994e+01,3.704393051280423492e+02,5.590918036099787436e+00,5.656854305839434716e+00,1.163785982294865684e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.092595254892540879e+01,3.704492374845502809e+02,5.592079196811895692e+00,5.656854305839434716e+00,1.161285982294865682e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.092772031586076764e+01,3.704591701310379790e+02,5.593237874398615972e+00,5.656854305839434716e+00,1.158785982294865680e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.092948808279612649e+01,3.704691030668847134e+02,5.594394068787531538e+00,5.656854305839434716e+00,1.156285982294865677e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.093125584973148534e+01,3.704790362914696402e+02,5.595547779906380192e+00,5.656854305839434716e+00,1.153785982294865675e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.093302361666684419e+01,3.704889698041719157e+02,5.596699007683055171e+00,5.656854305839434716e+00,1.151285982294865673e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.093479138360220304e+01,3.704989036043706960e+02,5.597847752045604253e+00,5.656854305839434716e+00,1.148785982294865671e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.093655915053756189e+01,3.705088376914451374e+02,5.598994012922231533e+00,5.656854305839434716e+00,1.146285982294865669e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.093832691747292074e+01,3.705187720647743390e+02,5.600137790241295654e+00,5.656854305839434716e+00,1.143785982294865666e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.094009468440827959e+01,3.705287067237374572e+02,5.601279083931309799e+00,5.656854305839434716e+00,1.141285982294865664e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.094186245134363844e+01,3.705386416677135344e+02,5.602417893920944358e+00,5.656854305839434716e+00,1.138785982294865662e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.094363021827899729e+01,3.705485768960816131e+02,5.603554220139022490e+00,5.656854305839434716e+00,1.136285982294865660e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.094539798521435614e+01,3.705585124082207926e+02,5.604688062514524560e+00,5.656854305839434716e+00,1.133785982294865657e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.094716575214971499e+01,3.705684482035100586e+02,5.605819420976584588e+00,5.656854305839434716e+00,1.131285982294865655e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.094893351908507384e+01,3.705783842813284537e+02,5.606948295454493802e+00,5.656854305839434716e+00,1.128785982294865653e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.095070128602043269e+01,3.705883206410549633e+02,5.608074685877697085e+00,5.656854305839434716e+00,1.126285982294865651e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.095246905295579154e+01,3.705982572820685732e+02,5.609198592175794751e+00,5.656854305839434716e+00,1.123785982294865649e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.095423681989115039e+01,3.706081942037482122e+02,5.610320014278542544e+00,5.656854305839434716e+00,1.121285982294865646e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.095600458682650924e+01,3.706181314054728659e+02,5.611438952115851642e+00,5.656854305839434716e+00,1.118785982294865644e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.095777235376186809e+01,3.706280688866214064e+02,5.612555405617788651e+00,5.656854305839434716e+00,1.116285982294865642e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.095954012069722694e+01,3.706380066465728191e+02,5.613669374714575611e+00,5.656854305839434716e+00,1.113785982294865640e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.096130788763258579e+01,3.706479446847059194e+02,5.614780859336589103e+00,5.656854305839434716e+00,1.111285982294865637e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.096307565456794464e+01,3.706578830003996359e+02,5.615889859414361140e+00,5.656854305839434716e+00,1.108785982294865635e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.096484342150330349e+01,3.706678215930327838e+02,5.616996374878579168e+00,5.656854305839434716e+00,1.106285982294865633e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.096661118843866234e+01,3.706777604619841782e+02,5.618100405660086061e+00,5.656854305839434716e+00,1.103785982294865631e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.096837895537402119e+01,3.706876996066326910e+02,5.619201951689880126e+00,5.656854305839434716e+00,1.101285982294865629e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.097014672230938004e+01,3.706976390263571375e+02,5.620301012899115101e+00,5.656854305839434716e+00,1.098785982294865626e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.097191448924473889e+01,3.707075787205362758e+02,5.621397589219099267e+00,5.656854305839434716e+00,1.096285982294865624e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.097368225618009774e+01,3.707175186885488642e+02,5.622491680581296336e+00,5.656854305839434716e+00,1.093785982294865622e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.097545002311545659e+01,3.707274589297736611e+02,5.623583286917325452e+00,5.656854305839434716e+00,1.091285982294865620e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.097721779005081544e+01,3.707373994435894247e+02,5.624672408158962078e+00,5.656854305839434716e+00,1.088785982294865617e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.097898555698617429e+01,3.707473402293748563e+02,5.625759044238135331e+00,5.656854305839434716e+00,1.086285982294865615e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.098075332392153314e+01,3.707572812865086576e+02,5.626843195086930649e+00,5.656854305839434716e+00,1.083785982294865613e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.098252109085689199e+01,3.707672226143694729e+02,5.627924860637588900e+00,5.656854305839434716e+00,1.081285982294865611e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.098428885779225084e+01,3.707771642123360039e+02,5.629004040822505495e+00,5.656854305839434716e+00,1.078785982294865609e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.098605662472760969e+01,3.707871060797868950e+02,5.630080735574232165e+00,5.656854305839434716e+00,1.076285982294865606e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.098782439166296854e+01,3.707970482161007908e+02,5.631154944825475184e+00,5.656854305839434716e+00,1.073785982294865604e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.098959215859832739e+01,3.708069906206563360e+02,5.632226668509096257e+00,5.656854305839434716e+00,1.071285982294865602e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.099135992553368624e+01,3.708169332928321182e+02,5.633295906558113408e+00,5.656854305839434716e+00,1.068785982294865600e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.099312769246904509e+01,3.708268762320066685e+02,5.634362658905699206e+00,5.656854305839434716e+00,1.066285982294865597e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.099489545940440394e+01,3.708368194375585745e+02,5.635426925485180760e+00,5.656854305839434716e+00,1.063785982294865595e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.099666322633976279e+01,3.708467629088664239e+02,5.636488706230042389e+00,5.656854305839434716e+00,1.061285982294865593e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.099843099327512164e+01,3.708567066453086909e+02,5.637548001073922066e+00,5.656854305839434716e+00,1.058785982294865591e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.100019876021048049e+01,3.708666506462639632e+02,5.638604809950614083e+00,5.656854305839434716e+00,1.056285982294865589e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.100196652714583934e+01,3.708765949111106579e+02,5.639659132794068164e+00,5.656854305839434716e+00,1.053785982294865586e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.100373429408119819e+01,3.708865394392273060e+02,5.640710969538388575e+00,5.656854305839434716e+00,1.051285982294865584e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.100550206101655704e+01,3.708964842299923816e+02,5.641760320117835903e+00,5.656854305839434716e+00,1.048785982294865582e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.100726982795191589e+01,3.709064292827843587e+02,5.642807184466825277e+00,5.656854305839434716e+00,1.046285982294865580e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.100903759488727474e+01,3.709163745969815977e+02,5.643851562519928144e+00,5.656854305839434716e+00,1.043785982294865577e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.101080536182263359e+01,3.709263201719625727e+02,5.644893454211870498e+00,5.656854305839434716e+00,1.041285982294865575e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.101257312875799244e+01,3.709362660071056439e+02,5.645932859477534649e+00,5.656854305839434716e+00,1.038785982294865573e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.101434089569335129e+01,3.709462121017892287e+02,5.646969778251957450e+00,5.656854305839434716e+00,1.036285982294865571e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.101610866262871014e+01,3.709561584553916873e+02,5.648004210470332076e+00,5.656854305839434716e+00,1.033785982294865569e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.101787642956406899e+01,3.709661050672913802e+02,5.649036156068005354e+00,5.656854305839434716e+00,1.031285982294865566e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.101964419649942784e+01,3.709760519368666678e+02,5.650065614980481321e+00,5.656854305839434716e+00,1.028785982294865564e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.102141196343478668e+01,3.709859990634958535e+02,5.651092587143419443e+00,5.656854305839434716e+00,1.026285982294865562e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.102317973037014553e+01,3.709959464465571841e+02,5.652117072492632843e+00,5.656854305839434716e+00,1.023785982294865560e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.102494749730550438e+01,3.710058940854290199e+02,5.653139070964091850e+00,5.656854305839434716e+00,1.021285982294865557e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.102671526424086323e+01,3.710158419794896076e+02,5.654158582493921337e+00,5.656854305839434716e+00,1.018785982294865555e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.102848303117622208e+01,3.710257901281171939e+02,5.655175607018401607e+00,5.656854305839434716e+00,1.016285982294865553e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.103025079811158093e+01,3.710357385306900255e+02,5.656190144473969283e+00,5.656854305839434716e+00,1.013785982294865551e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.103201856504693978e+01,3.710456871865863491e+02,5.657202194797214645e+00,5.656854305839434716e+00,1.011285982294865549e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.103378633198229863e+01,3.710556360951843544e+02,5.658211757924886065e+00,5.656854305839434716e+00,1.008785982294865546e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.103555409891765748e+01,3.710655852558622314e+02,5.659218833793884684e+00,5.656854305839434716e+00,1.006285982294865544e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.103732186585301633e+01,3.710755346679981699e+02,5.660223422341268851e+00,5.656854305839434716e+00,1.003785982294865542e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.103908963278837518e+01,3.710854843309703028e+02,5.661225523504251456e+00,5.656854305839434716e+00,1.001285982294865540e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.104085739972373403e+01,3.710954342441568201e+02,5.662225137220200821e+00,5.656854305839434716e+00,9.987859822948655375e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.104262516665909288e+01,3.711053844069357979e+02,5.663222263426641589e+00,5.656854305839434716e+00,9.962859822948655353e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.104439293359445173e+01,3.711153348186853691e+02,5.664216902061253833e+00,5.656854305839434716e+00,9.937859822948655331e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.104616070052981058e+01,3.711252854787836668e+02,5.665209053061872169e+00,5.656854305839434716e+00,9.912859822948655308e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.104792846746516943e+01,3.711352363866087671e+02,5.666198716366486643e+00,5.656854305839434716e+00,9.887859822948655286e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.104969623440052828e+01,3.711451875415387462e+02,5.667185891913243623e+00,5.656854305839434716e+00,9.862859822948655264e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.105146400133588713e+01,3.711551389429516234e+02,5.668170579640444906e+00,5.656854305839434716e+00,9.837859822948655242e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.105323176827124598e+01,3.711650905902254181e+02,5.669152779486547722e+00,5.656854305839434716e+00,9.812859822948655220e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.105499953520660483e+01,3.711750424827382062e+02,5.670132491390163842e+00,5.656854305839434716e+00,9.787859822948655197e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.105676730214196368e+01,3.711849946198679504e+02,5.671109715290062248e+00,5.656854305839434716e+00,9.762859822948655175e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.105853506907732253e+01,3.711949470009926699e+02,5.672084451125165572e+00,5.656854305839434716e+00,9.737859822948655153e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.106030283601268138e+01,3.712048996254903273e+02,5.673056698834552769e+00,5.656854305839434716e+00,9.712859822948655131e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.106207060294804023e+01,3.712148524927388848e+02,5.674026458357459113e+00,5.656854305839434716e+00,9.687859822948655109e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.106383836988339908e+01,3.712248056021163052e+02,5.674993729633274420e+00,5.656854305839434716e+00,9.662859822948655086e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.106560613681875793e+01,3.712347589530004939e+02,5.675958512601543937e+00,5.656854305839434716e+00,9.637859822948655064e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.106737390375411678e+01,3.712447125447694134e+02,5.676920807201969232e+00,5.656854305839434716e+00,9.612859822948655042e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.106914167068947563e+01,3.712546663768009125e+02,5.677880613374406416e+00,5.656854305839434716e+00,9.587859822948655020e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.107090943762483448e+01,3.712646204484728969e+02,5.678837931058867028e+00,5.656854305839434716e+00,9.562859822948654998e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.107267720456019333e+01,3.712745747591632153e+02,5.679792760195519818e+00,5.656854305839434716e+00,9.537859822948654975e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.107444497149555218e+01,3.712845293082497733e+02,5.680745100724687191e+00,5.656854305839434716e+00,9.512859822948654953e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.107621273843091103e+01,3.712944840951103629e+02,5.681694952586848757e+00,5.656854305839434716e+00,9.487859822948654931e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.107798050536626988e+01,3.713044391191228328e+02,5.682642315722637782e+00,5.656854305839434716e+00,9.462859822948654909e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.107974827230162873e+01,3.713143943796649751e+02,5.683587190072844741e+00,5.656854305839434716e+00,9.437859822948654887e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.108151603923698758e+01,3.713243498761146384e+02,5.684529575578414651e+00,5.656854305839434716e+00,9.412859822948654864e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.108328380617234643e+01,3.713343056078495579e+02,5.685469472180448847e+00,5.656854305839434716e+00,9.387859822948654842e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.108505157310770528e+01,3.713442615742475255e+02,5.686406879820203208e+00,5.656854305839434716e+00,9.362859822948654820e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.108681934004306413e+01,3.713542177746862762e+02,5.687341798439089935e+00,5.656854305839434716e+00,9.337859822948654798e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.108858710697842298e+01,3.713641742085435453e+02,5.688274227978676656e+00,5.656854305839434716e+00,9.312859822948654775e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.109035487391378183e+01,3.713741308751970109e+02,5.689204168380686433e+00,5.656854305839434716e+00,9.287859822948654753e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.109212264084914068e+01,3.713840877740244650e+02,5.690131619586998646e+00,5.656854305839434716e+00,9.262859822948654731e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.109389040778449953e+01,3.713940449044035290e+02,5.691056581539647219e+00,5.656854305839434716e+00,9.237859822948654709e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.109565817471985838e+01,3.714040022657119380e+02,5.691979054180821507e+00,5.656854305839434716e+00,9.212859822948654687e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.109742594165521723e+01,3.714139598573273133e+02,5.692899037452867184e+00,5.656854305839434716e+00,9.187859822948654664e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.109919370859057608e+01,3.714239176786273333e+02,5.693816531298285355e+00,5.656854305839434716e+00,9.162859822948654642e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.110096147552593493e+01,3.714338757289896762e+02,5.694731535659733446e+00,5.656854305839434716e+00,9.137859822948654620e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.110272924246129378e+01,3.714438340077919065e+02,5.695644050480022536e+00,5.656854305839434716e+00,9.112859822948654598e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.110449700939665263e+01,3.714537925144116457e+02,5.696554075702120912e+00,5.656854305839434716e+00,9.087859822948654576e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.110626477633201148e+01,3.714637512482264583e+02,5.697461611269152293e+00,5.656854305839434716e+00,9.062859822948654553e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.110803254326737033e+01,3.714737102086139657e+02,5.698366657124394941e+00,5.656854305839434716e+00,9.037859822948654531e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.110980031020272918e+01,3.714836693949517326e+02,5.699269213211284324e+00,5.656854305839434716e+00,9.012859822948654509e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.111156807713808803e+01,3.714936288066172665e+02,5.700169279473410455e+00,5.656854305839434716e+00,8.987859822948654487e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.111333584407344688e+01,3.715035884429881321e+02,5.701066855854518778e+00,5.656854305839434716e+00,8.962859822948654465e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.111510361100880573e+01,3.715135483034418371e+02,5.701961942298511055e+00,5.656854305839434716e+00,8.937859822948654442e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.111687137794416458e+01,3.715235083873559461e+02,5.702854538749444480e+00,5.656854305839434716e+00,8.912859822948654420e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.111863914487952343e+01,3.715334686941079099e+02,5.703744645151531678e+00,5.656854305839434716e+00,8.887859822948654398e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.112040691181488228e+01,3.715434292230751794e+02,5.704632261449140707e+00,5.656854305839434716e+00,8.862859822948654376e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.112217467875024113e+01,3.715533899736352623e+02,5.705517387586795941e+00,5.656854305839434716e+00,8.837859822948654354e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.112394244568559998e+01,3.715633509451656096e+02,5.706400023509177188e+00,5.656854305839434716e+00,8.812859822948654331e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.112571021262095883e+01,3.715733121370436720e+02,5.707280169161119687e+00,5.656854305839434716e+00,8.787859822948654309e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.112747797955631768e+01,3.715832735486468437e+02,5.708157824487614107e+00,5.656854305839434716e+00,8.762859822948654287e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.112924574649167653e+01,3.715932351793525754e+02,5.709032989433806549e+00,5.656854305839434716e+00,8.737859822948654265e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.113101351342703538e+01,3.716031970285382044e+02,5.709905663944999432e+00,5.656854305839434716e+00,8.712859822948654243e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.113278128036239423e+01,3.716131590955811816e+02,5.710775847966650609e+00,5.656854305839434716e+00,8.687859822948654220e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.113454904729775308e+01,3.716231213798588442e+02,5.711643541444374250e+00,5.656854305839434716e+00,8.662859822948654198e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.113631681423311193e+01,3.716330838807485293e+02,5.712508744323939069e+00,5.656854305839434716e+00,8.637859822948654176e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.113808458116847078e+01,3.716430465976276309e+02,5.713371456551269212e+00,5.656854305839434716e+00,8.612859822948654154e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.113985234810382963e+01,3.716530095298734295e+02,5.714231678072446030e+00,5.656854305839434716e+00,8.587859822948654132e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.114162011503918848e+01,3.716629726768632622e+02,5.715089408833705420e+00,5.656854305839434716e+00,8.562859822948654109e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.114338788197454733e+01,3.716729360379744662e+02,5.715944648781439597e+00,5.656854305839434716e+00,8.537859822948654087e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.114515564890990618e+01,3.716828996125842650e+02,5.716797397862195318e+00,5.656854305839434716e+00,8.512859822948654065e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.114692341584526503e+01,3.716928634000699958e+02,5.717647656022676550e+00,5.656854305839434716e+00,8.487859822948654043e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.114869118278062388e+01,3.717028273998088821e+02,5.718495423209740913e+00,5.656854305839434716e+00,8.462859822948654021e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.115045894971598273e+01,3.717127916111782042e+02,5.719340699370404124e+00,5.656854305839434716e+00,8.437859822948653998e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.115222671665134158e+01,3.717227560335551857e+02,5.720183484451836442e+00,5.656854305839434716e+00,8.412859822948653976e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.115399448358670043e+01,3.717327206663170500e+02,5.721023778401363558e+00,5.656854305839434716e+00,8.387859822948653954e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.115576225052205928e+01,3.717426855088409638e+02,5.721861581166466593e+00,5.656854305839434716e+00,8.362859822948653932e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.115753001745741813e+01,3.717526505605042075e+02,5.722696892694782989e+00,5.656854305839434716e+00,8.337859822948653910e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.115929778439277698e+01,3.717626158206838909e+02,5.723529712934106506e+00,5.656854305839434716e+00,8.312859822948653887e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.116106555132813583e+01,3.717725812887572374e+02,5.724360041832385448e+00,5.656854305839434716e+00,8.287859822948653865e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.116283331826349468e+01,3.717825469641013569e+02,5.725187879337723551e+00,5.656854305839434716e+00,8.262859822948653843e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.116460108519885353e+01,3.717925128460934161e+02,5.726013225398381756e+00,5.656854305839434716e+00,8.237859822948653821e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.116636885213421237e+01,3.718024789341105816e+02,5.726836079962776438e+00,5.656854305839434716e+00,8.212859822948653798e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.116813661906957122e+01,3.718124452275299632e+02,5.727656442979478513e+00,5.656854305839434716e+00,8.187859822948653776e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.116990438600493007e+01,3.718224117257286139e+02,5.728474314397215217e+00,5.656854305839434716e+00,8.162859822948653754e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.117167215294028892e+01,3.718323784280837003e+02,5.729289694164869218e+00,5.656854305839434716e+00,8.137859822948653732e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.117343991987564777e+01,3.718423453339722755e+02,5.730102582231480390e+00,5.656854305839434716e+00,8.112859822948653710e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.117520768681100662e+01,3.718523124427713924e+02,5.730912978546242265e+00,5.656854305839434716e+00,8.087859822948653687e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.117697545374636547e+01,3.718622797538581040e+02,5.731720883058505578e+00,5.656854305839434716e+00,8.062859822948653665e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.117874322068172432e+01,3.718722472666094632e+02,5.732526295717776499e+00,5.656854305839434716e+00,8.037859822948653643e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.118051098761708317e+01,3.718822149804024662e+02,5.733329216473715739e+00,5.656854305839434716e+00,8.012859822948653621e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.118227875455244202e+01,3.718921828946141659e+02,5.734129645276142107e+00,5.656854305839434716e+00,7.987859822948653599e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.118404652148780087e+01,3.719021510086216153e+02,5.734927582075028063e+00,5.656854305839434716e+00,7.962859822948653576e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.118581428842315972e+01,3.719121193218017538e+02,5.735723026820502390e+00,5.656854305839434716e+00,7.937859822948653554e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.118758205535851857e+01,3.719220878335315206e+02,5.736515979462850190e+00,5.656854305839434716e+00,7.912859822948653532e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.118934982229387742e+01,3.719320565431879686e+02,5.737306439952511106e+00,5.656854305839434716e+00,7.887859822948653510e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.119111758922923627e+01,3.719420254501479803e+02,5.738094408240081989e+00,5.656854305839434716e+00,7.862859822948653488e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.119288535616459512e+01,3.719519945537885519e+02,5.738879884276315124e+00,5.656854305839434716e+00,7.837859822948653465e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.119465312309995397e+01,3.719619638534866226e+02,5.739662868012118224e+00,5.656854305839434716e+00,7.812859822948653443e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.119642089003531282e+01,3.719719333486190749e+02,5.740443359398554435e+00,5.656854305839434716e+00,7.787859822948653421e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.119818865697067167e+01,3.719819030385627912e+02,5.741221358386843221e+00,5.656854305839434716e+00,7.762859822948653399e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.119995642390603052e+01,3.719918729226947107e+02,5.741996864928359479e+00,5.656854305839434716e+00,7.737859822948653377e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.120172419084138937e+01,3.720018430003917160e+02,5.742769878974634423e+00,5.656854305839434716e+00,7.712859822948653354e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.120349195777674822e+01,3.720118132710306895e+02,5.743540400477353813e+00,5.656854305839434716e+00,7.687859822948653332e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.120525972471210707e+01,3.720217837339884568e+02,5.744308429388360615e+00,5.656854305839434716e+00,7.662859822948653310e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.120702749164746592e+01,3.720317543886418434e+02,5.745073965659653226e+00,5.656854305839434716e+00,7.637859822948653288e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.120879525858282477e+01,3.720417252343677319e+02,5.745837009243385474e+00,5.656854305839434716e+00,7.612859822948653266e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.121056302551818362e+01,3.720516962705428909e+02,5.746597560091867507e+00,5.656854305839434716e+00,7.587859822948653243e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.121233079245354247e+01,3.720616674965442030e+02,5.747355618157564017e+00,5.656854305839434716e+00,7.562859822948653221e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.121409855938890132e+01,3.720716389117484368e+02,5.748111183393096901e+00,5.656854305839434716e+00,7.537859822948653199e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.121586632632426017e+01,3.720816105155323612e+02,5.748864255751243491e+00,5.656854305839434716e+00,7.512859822948653177e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.121763409325961902e+01,3.720915823072727449e+02,5.749614835184936545e+00,5.656854305839434716e+00,7.487859822948653155e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.121940186019497787e+01,3.721015542863463565e+02,5.750362921647264258e+00,5.656854305839434716e+00,7.462859822948653132e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.122116962713033672e+01,3.721115264521299650e+02,5.751108515091472029e+00,5.656854305839434716e+00,7.437859822948653110e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.122293739406569557e+01,3.721214988040003391e+02,5.751851615470960688e+00,5.656854305839434716e+00,7.412859822948653088e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.122470516100105442e+01,3.721314713413341337e+02,5.752592222739285610e+00,5.656854305839434716e+00,7.387859822948653066e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.122647292793641327e+01,3.721414440635081178e+02,5.753330336850158488e+00,5.656854305839434716e+00,7.362859822948653044e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.122824069487177212e+01,3.721514169698989463e+02,5.754065957757448224e+00,5.656854305839434716e+00,7.337859822948653021e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.123000846180713097e+01,3.721613900598833879e+02,5.754799085415178261e+00,5.656854305839434716e+00,7.312859822948652999e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.123177622874248982e+01,3.721713633328380411e+02,5.755529719777527475e+00,5.656854305839434716e+00,7.287859822948652977e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.123354399567784867e+01,3.721813367881396175e+02,5.756257860798831949e+00,5.656854305839434716e+00,7.262859822948652955e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.123531176261320752e+01,3.721913104251648292e+02,5.756983508433582308e+00,5.656854305839434716e+00,7.237859822948652933e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.123707952954856637e+01,3.722012842432902744e+02,5.757706662636426387e+00,5.656854305839434716e+00,7.212859822948652910e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.123884729648392522e+01,3.722112582418925513e+02,5.758427323362166561e+00,5.656854305839434716e+00,7.187859822948652888e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.124061506341928407e+01,3.722212324203483149e+02,5.759145490565761527e+00,5.656854305839434716e+00,7.162859822948652866e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.124238283035464292e+01,3.722312067780342204e+02,5.759861164202325412e+00,5.656854305839434716e+00,7.137859822948652844e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.124415059729000177e+01,3.722411813143268091e+02,5.760574344227128663e+00,5.656854305839434716e+00,7.112859822948652821e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.124591836422536062e+01,3.722511560286026793e+02,5.761285030595598045e+00,5.656854305839434716e+00,7.087859822948652799e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.124768613116071947e+01,3.722611309202384291e+02,5.761993223263315755e+00,5.656854305839434716e+00,7.062859822948652777e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.124945389809607832e+01,3.722711059886106568e+02,5.762698922186019423e+00,5.656854305839434716e+00,7.037859822948652755e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.125122166503143717e+01,3.722810812330959038e+02,5.763402127319602997e+00,5.656854305839434716e+00,7.012859822948652733e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.125298943196679602e+01,3.722910566530707115e+02,5.764102838620115854e+00,5.656854305839434716e+00,6.987859822948652710e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.125475719890215487e+01,3.723010322479115644e+02,5.764801056043763694e+00,5.656854305839434716e+00,6.962859822948652688e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.125652496583751372e+01,3.723110080169950606e+02,5.765496779546908535e+00,5.656854305839434716e+00,6.937859822948652666e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.125829273277287257e+01,3.723209839596976849e+02,5.766190009086066937e+00,5.656854305839434716e+00,6.912859822948652644e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.126006049970823142e+01,3.723309600753959216e+02,5.766880744617911780e+00,5.656854305839434716e+00,6.887859822948652622e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.126182826664359027e+01,3.723409363634663123e+02,5.767568986099273154e+00,5.656854305839434716e+00,6.862859822948652599e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.126359603357894912e+01,3.723509128232852845e+02,5.768254733487134800e+00,5.656854305839434716e+00,6.837859822948652577e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.126536380051430797e+01,3.723608894542293797e+02,5.768937986738638557e+00,5.656854305839434716e+00,6.812859822948652555e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.126713156744966682e+01,3.723708662556750255e+02,5.769618745811079918e+00,5.656854305839434716e+00,6.787859822948652533e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.126889933438502567e+01,3.723808432269986497e+02,5.770297010661912473e+00,5.656854305839434716e+00,6.762859822948652511e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.127066710132038452e+01,3.723908203675766799e+02,5.770972781248744354e+00,5.656854305839434716e+00,6.737859822948652488e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.127243486825574337e+01,3.724007976767856007e+02,5.771646057529340013e+00,5.656854305839434716e+00,6.712859822948652466e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.127420263519110222e+01,3.724107751540017830e+02,5.772316839461619331e+00,5.656854305839434716e+00,6.687859822948652444e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.127597040212646107e+01,3.724207527986016544e+02,5.772985127003658512e+00,5.656854305839434716e+00,6.662859822948652422e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.127773816906181992e+01,3.724307306099615857e+02,5.773650920113690077e+00,5.656854305839434716e+00,6.637859822948652400e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.127950593599717877e+01,3.724407085874580048e+02,5.774314218750101979e+00,5.656854305839434716e+00,6.612859822948652377e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.128127370293253762e+01,3.724506867304672824e+02,5.774975022871437602e+00,5.656854305839434716e+00,6.587859822948652355e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.128304146986789647e+01,3.724606650383657325e+02,5.775633332436396650e+00,5.656854305839434716e+00,6.562859822948652333e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.128480923680325532e+01,3.724706435105297828e+02,5.776289147403834257e+00,5.656854305839434716e+00,6.537859822948652311e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.128657700373861417e+01,3.724806221463357474e+02,5.776942467732762765e+00,5.656854305839434716e+00,6.512859822948652289e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.128834477067397302e+01,3.724906009451599402e+02,5.777593293382349948e+00,5.656854305839434716e+00,6.487859822948652266e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.129011253760933187e+01,3.725005799063787322e+02,5.778241624311919011e+00,5.656854305839434716e+00,6.462859822948652244e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.129188030454469072e+01,3.725105590293683804e+02,5.778887460480948590e+00,5.656854305839434716e+00,6.437859822948652222e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.129364807148004957e+01,3.725205383135052557e+02,5.779530801849074528e+00,5.656854305839434716e+00,6.412859822948652200e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.129541583841540842e+01,3.725305177581656153e+02,5.780171648376088100e+00,5.656854305839434716e+00,6.387859822948652178e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.129718360535076727e+01,3.725404973627257164e+02,5.780810000021936013e+00,5.656854305839434716e+00,6.362859822948652155e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.129895137228612612e+01,3.725504771265618729e+02,5.781445856746721290e+00,5.656854305839434716e+00,6.337859822948652133e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.130071913922148497e+01,3.725604570490503420e+02,5.782079218510702390e+00,5.656854305839434716e+00,6.312859822948652111e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.130248690615684382e+01,3.725704371295673809e+02,5.782710085274294975e+00,5.656854305839434716e+00,6.287859822948652089e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.130425467309220267e+01,3.725804173674892468e+02,5.783338456998070143e+00,5.656854305839434716e+00,6.262859822948652067e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.130602244002756152e+01,3.725903977621921399e+02,5.783964333642754418e+00,5.656854305839434716e+00,6.237859822948652044e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.130779020696292037e+01,3.726003783130523175e+02,5.784587715169229760e+00,5.656854305839434716e+00,6.212859822948652022e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.130955797389827922e+01,3.726103590194459798e+02,5.785208601538535333e+00,5.656854305839434716e+00,6.187859822948652000e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.131132574083363806e+01,3.726203398807493272e+02,5.785826992711865735e+00,5.656854305839434716e+00,6.162859822948651978e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.131309350776899691e+01,3.726303208963385600e+02,5.786442888650571881e+00,5.656854305839434716e+00,6.137859822948651956e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.131486127470435576e+01,3.726403020655898786e+02,5.787056289316160118e+00,5.656854305839434716e+00,6.112859822948651933e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.131662904163971461e+01,3.726502833878794263e+02,5.787667194670292226e+00,5.656854305839434716e+00,6.087859822948651911e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.131839680857507346e+01,3.726602648625834036e+02,5.788275604674787189e+00,5.656854305839434716e+00,6.062859822948651889e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.132016457551043231e+01,3.726702464890779538e+02,5.788881519291619426e+00,5.656854305839434716e+00,6.037859822948651867e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.132193234244579116e+01,3.726802282667392774e+02,5.789484938482919674e+00,5.656854305839434716e+00,6.012859822948651844e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.132370010938115001e+01,3.726902101949434609e+02,5.790085862210973211e+00,5.656854305839434716e+00,5.987859822948651822e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.132546787631650886e+01,3.727001922730665910e+02,5.790684290438223414e+00,5.656854305839434716e+00,5.962859822948651800e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.132723564325186771e+01,3.727101745004848681e+02,5.791280223127267313e+00,5.656854305839434716e+00,5.937859822948651778e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.132900341018722656e+01,3.727201568765743787e+02,5.791873660240860033e+00,5.656854305839434716e+00,5.912859822948651756e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.133077117712258541e+01,3.727301394007112094e+02,5.792464601741911245e+00,5.656854305839434716e+00,5.887859822948651733e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.133253894405794426e+01,3.727401220722714470e+02,5.793053047593487825e+00,5.656854305839434716e+00,5.862859822948651711e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.133430671099330311e+01,3.727501048906311780e+02,5.793638997758811193e+00,5.656854305839434716e+00,5.837859822948651689e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.133607447792866196e+01,3.727600878551664891e+02,5.794222452201259976e+00,5.656854305839434716e+00,5.812859822948651667e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.133784224486402081e+01,3.727700709652534670e+02,5.794803410884367345e+00,5.656854305839434716e+00,5.787859822948651645e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.133961001179937966e+01,3.727800542202681413e+02,5.795381873771824566e+00,5.656854305839434716e+00,5.762859822948651622e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.134137777873473851e+01,3.727900376195865420e+02,5.795957840827476559e+00,5.656854305839434716e+00,5.737859822948651600e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.134314554567009736e+01,3.728000211625847555e+02,5.796531312015326343e+00,5.656854305839434716e+00,5.712859822948651578e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.134491331260545621e+01,3.728100048486387550e+02,5.797102287299531476e+00,5.656854305839434716e+00,5.687859822948651556e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.134668107954081506e+01,3.728199886771245701e+02,5.797670766644405838e+00,5.656854305839434716e+00,5.662859822948651534e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.134844884647617391e+01,3.728299726474182307e+02,5.798236750014419627e+00,5.656854305839434716e+00,5.637859822948651511e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.135021661341153276e+01,3.728399567588957666e+02,5.798800237374199362e+00,5.656854305839434716e+00,5.612859822948651489e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.135198438034689161e+01,3.728499410109330938e+02,5.799361228688526992e+00,5.656854305839434716e+00,5.587859822948651467e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.135375214728225046e+01,3.728599254029062422e+02,5.799919723922339898e+00,5.656854305839434716e+00,5.562859822948651445e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.135551991421760931e+01,3.728699099341911847e+02,5.800475723040732667e+00,5.656854305839434716e+00,5.537859822948651423e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.135728768115296816e+01,3.728798946041638942e+02,5.801029226008955320e+00,5.656854305839434716e+00,5.512859822948651400e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.135905544808832701e+01,3.728898794122003437e+02,5.801580232792414193e+00,5.656854305839434716e+00,5.487859822948651378e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.136082321502368586e+01,3.728998643576764493e+02,5.802128743356671059e+00,5.656854305839434716e+00,5.462859822948651356e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.136259098195904471e+01,3.729098494399681840e+02,5.802674757667443117e+00,5.656854305839434716e+00,5.437859822948651334e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.136435874889440356e+01,3.729198346584514638e+02,5.803218275690605665e+00,5.656854305839434716e+00,5.412859822948651312e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.136612651582976241e+01,3.729298200125022049e+02,5.803759297392188543e+00,5.656854305839434716e+00,5.387859822948651289e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.136789428276512126e+01,3.729398055014963234e+02,5.804297822738377910e+00,5.656854305839434716e+00,5.362859822948651267e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.136966204970048011e+01,3.729497911248097353e+02,5.804833851695515357e+00,5.656854305839434716e+00,5.337859822948651245e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.137142981663583896e+01,3.729597768818182999e+02,5.805367384230099681e+00,5.656854305839434716e+00,5.312859822948651223e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.137319758357119781e+01,3.729697627718979902e+02,5.805898420308785113e+00,5.656854305839434716e+00,5.287859822948651201e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.137496535050655666e+01,3.729797487944246086e+02,5.806426959898382201e+00,5.656854305839434716e+00,5.262859822948651178e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.137673311744191551e+01,3.729897349487740712e+02,5.806953002965856037e+00,5.656854305839434716e+00,5.237859822948651156e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.137850088437727436e+01,3.729997212343222373e+02,5.807476549478329808e+00,5.656854305839434716e+00,5.212859822948651134e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.138026865131263321e+01,3.730097076504449660e+02,5.807997599403082134e+00,5.656854305839434716e+00,5.187859822948651112e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.138203641824799206e+01,3.730196941965180599e+02,5.808516152707547064e+00,5.656854305839434716e+00,5.162859822948651090e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.138380418518335091e+01,3.730296808719174351e+02,5.809032209359314969e+00,5.656854305839434716e+00,5.137859822948651067e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.138557195211870976e+01,3.730396676760188939e+02,5.809545769326131648e+00,5.656854305839434716e+00,5.112859822948651045e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.138733971905406861e+01,3.730496546081982387e+02,5.810056832575900110e+00,5.656854305839434716e+00,5.087859822948651023e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.138910748598942746e+01,3.730596416678312721e+02,5.810565399076679682e+00,5.656854305839434716e+00,5.062859822948651001e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.139087525292478631e+01,3.730696288542938532e+02,5.811071468796684236e+00,5.656854305839434716e+00,5.037859822948650979e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.139264301986014516e+01,3.730796161669617845e+02,5.811575041704283962e+00,5.656854305839434716e+00,5.012859822948650956e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.139441078679550401e+01,3.730896036052108116e+02,5.812076117768006256e+00,5.656854305839434716e+00,4.987859822948650934e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.139617855373086286e+01,3.730995911684167368e+02,5.812574696956533948e+00,5.656854305839434716e+00,4.962859822948650912e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.139794632066622171e+01,3.731095788559553625e+02,5.813070779238705299e+00,5.656854305839434716e+00,4.937859822948650890e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.139971408760158056e+01,3.731195666672024345e+02,5.813564364583515776e+00,5.656854305839434716e+00,4.912859822948650868e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.140148185453693941e+01,3.731295546015337550e+02,5.814055452960115389e+00,5.656854305839434716e+00,4.887859822948650845e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.140324962147229826e+01,3.731395426583250128e+02,5.814544044337812245e+00,5.656854305839434716e+00,4.862859822948650823e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.140501738840765711e+01,3.731495308369520103e+02,5.815030138686068995e+00,5.656854305839434716e+00,4.837859822948650801e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.140678515534301596e+01,3.731595191367904363e+02,5.815513735974504606e+00,5.656854305839434716e+00,4.812859822948650779e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.140855292227837481e+01,3.731695075572160363e+02,5.815994836172893478e+00,5.656854305839434716e+00,4.787859822948650756e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.141032068921373366e+01,3.731794960976045559e+02,5.816473439251168109e+00,5.656854305839434716e+00,4.762859822948650734e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.141208845614909251e+01,3.731894847573317406e+02,5.816949545179414649e+00,5.656854305839434716e+00,4.737859822948650712e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.141385622308445136e+01,3.731994735357732225e+02,5.817423153927877344e+00,5.656854305839434716e+00,4.712859822948650690e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.141562399001981021e+01,3.732094624323047469e+02,5.817894265466955872e+00,5.656854305839434716e+00,4.687859822948650668e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.141739175695516906e+01,3.732194514463020028e+02,5.818362879767205342e+00,5.656854305839434716e+00,4.662859822948650645e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.141915952389052791e+01,3.732294405771406787e+02,5.818828996799337183e+00,5.656854305839434716e+00,4.637859822948650623e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.142092729082588676e+01,3.732394298241964634e+02,5.819292616534219142e+00,5.656854305839434716e+00,4.612859822948650601e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.142269505776124561e+01,3.732494191868449889e+02,5.819753738942875287e+00,5.656854305839434716e+00,4.587859822948650579e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.142446282469660446e+01,3.732594086644619438e+02,5.820212363996485117e+00,5.656854305839434716e+00,4.562859822948650557e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.142623059163196331e+01,3.732693982564230168e+02,5.820668491666384448e+00,5.656854305839434716e+00,4.537859822948650534e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.142799835856732216e+01,3.732793879621038400e+02,5.821122121924065418e+00,5.656854305839434716e+00,4.512859822948650512e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.142976612550268101e+01,3.732893777808800451e+02,5.821573254741176484e+00,5.656854305839434716e+00,4.487859822948650490e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.143153389243803986e+01,3.732993677121272640e+02,5.822021890089521534e+00,5.656854305839434716e+00,4.462859822948650468e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.143330165937339871e+01,3.733093577552211286e+02,5.822468027941060775e+00,5.656854305839434716e+00,4.437859822948650446e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.143506942630875756e+01,3.733193479095372709e+02,5.822911668267910734e+00,5.656854305839434716e+00,4.412859822948650423e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.143683719324411641e+01,3.733293381744513226e+02,5.823352811042344257e+00,5.656854305839434716e+00,4.387859822948650401e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.143860496017947526e+01,3.733393285493388589e+02,5.823791456236789621e+00,5.656854305839434716e+00,4.362859822948650379e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.144037272711483411e+01,3.733493190335755116e+02,5.824227603823831423e+00,5.656854305839434716e+00,4.337859822948650357e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.144214049405019296e+01,3.733593096265368558e+02,5.824661253776210579e+00,5.656854305839434716e+00,4.312859822948650335e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.144390826098555181e+01,3.733693003275984665e+02,5.825092406066823436e+00,5.656854305839434716e+00,4.287859822948650312e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.144567602792091066e+01,3.733792911361359188e+02,5.825521060668723550e+00,5.656854305839434716e+00,4.262859822948650290e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.144744379485626951e+01,3.733892820515248445e+02,5.825947217555119906e+00,5.656854305839434716e+00,4.237859822948650268e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.144921156179162836e+01,3.733992730731407619e+02,5.826370876699377810e+00,5.656854305839434716e+00,4.212859822948650246e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.145097932872698721e+01,3.734092642003592459e+02,5.826792038075017999e+00,5.656854305839434716e+00,4.187859822948650224e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.145274709566234606e+01,3.734192554325558149e+02,5.827210701655718417e+00,5.656854305839434716e+00,4.162859822948650201e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.145451486259770491e+01,3.734292467691061006e+02,5.827626867415312439e+00,5.656854305839434716e+00,4.137859822948650179e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.145628262953306375e+01,3.734392382093855645e+02,5.828040535327789762e+00,5.656854305839434716e+00,4.112859822948650157e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.145805039646842260e+01,3.734492297527697815e+02,5.828451705367296398e+00,5.656854305839434716e+00,4.087859822948650135e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.145981816340378145e+01,3.734592213986342699e+02,5.828860377508133794e+00,5.656854305839434716e+00,4.062859822948650113e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.146158593033914030e+01,3.734692131463545479e+02,5.829266551724759715e+00,5.656854305839434716e+00,4.037859822948650090e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.146335369727449915e+01,3.734792049953061337e+02,5.829670227991789133e+00,5.656854305839434716e+00,4.012859822948650068e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.146512146420985800e+01,3.734891969448645455e+02,5.830071406283991564e+00,5.656854305839434716e+00,3.987859822948650046e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.146688923114521685e+01,3.734991889944053014e+02,5.830470086576293731e+00,5.656854305839434716e+00,3.962859822948650024e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.146865699808057570e+01,3.735091811433038629e+02,5.830866268843777789e+00,5.656854305839434716e+00,3.937859822948650002e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.147042476501593455e+01,3.735191733909357481e+02,5.831259953061682211e+00,5.656854305839434716e+00,3.912859822948649979e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.147219253195129340e+01,3.735291657366764184e+02,5.831651139205402679e+00,5.656854305839434716e+00,3.887859822948649957e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.147396029888665225e+01,3.735391581799013352e+02,5.832039827250489417e+00,5.656854305839434716e+00,3.862859822948649935e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.147572806582201110e+01,3.735491507199860166e+02,5.832426017172648969e+00,5.656854305839434716e+00,3.837859822948649913e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.147749583275736995e+01,3.735591433563059240e+02,5.832809708947745087e+00,5.656854305839434716e+00,3.812859822948649891e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.147926359969272880e+01,3.735691360882365188e+02,5.833190902551796952e+00,5.656854305839434716e+00,3.787859822948649868e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.148103136662808765e+01,3.735791289151532055e+02,5.833569597960980069e+00,5.656854305839434716e+00,3.762859822948649846e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.148279913356344650e+01,3.735891218364315023e+02,5.833945795151625369e+00,5.656854305839434716e+00,3.737859822948649824e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.148456690049880535e+01,3.735991148514468136e+02,5.834319494100220993e+00,5.656854305839434716e+00,3.712859822948649802e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.148633466743416420e+01,3.736091079595745441e+02,5.834690694783410514e+00,5.656854305839434716e+00,3.687859822948649779e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.148810243436952305e+01,3.736191011601901550e+02,5.835059397177994711e+00,5.656854305839434716e+00,3.662859822948649757e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.148987020130488190e+01,3.736290944526691078e+02,5.835425601260928907e+00,5.656854305839434716e+00,3.637859822948649735e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.149163796824024075e+01,3.736390878363867500e+02,5.835789307009325633e+00,5.656854305839434716e+00,3.612859822948649713e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.149340573517559960e+01,3.736490813107185431e+02,5.836150514400452849e+00,5.656854305839434716e+00,3.587859822948649691e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.149517350211095845e+01,3.736590748750398916e+02,5.836509223411735725e+00,5.656854305839434716e+00,3.562859822948649668e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.149694126904631730e+01,3.736690685287261999e+02,5.836865434020754861e+00,5.656854305839434716e+00,3.537859822948649646e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.149870903598167615e+01,3.736790622711528727e+02,5.837219146205246290e+00,5.656854305839434716e+00,3.512859822948649624e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.150047680291703500e+01,3.736890561016952574e+02,5.837570359943104137e+00,5.656854305839434716e+00,3.487859822948649602e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.150224456985239385e+01,3.736990500197288156e+02,5.837919075212376185e+00,5.656854305839434716e+00,3.462859822948649580e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.150401233678775270e+01,3.737090440246288381e+02,5.838265291991269201e+00,5.656854305839434716e+00,3.437859822948649557e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.150578010372311155e+01,3.737190381157707861e+02,5.838609010258143606e+00,5.656854305839434716e+00,3.412859822948649535e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.150754787065847040e+01,3.737290322925299506e+02,5.838950229991517027e+00,5.656854305839434716e+00,3.387859822948649513e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.150931563759382925e+01,3.737390265542817360e+02,5.839288951170064301e+00,5.656854305839434716e+00,3.362859822948649491e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.151108340452918810e+01,3.737490209004014901e+02,5.839625173772613920e+00,5.656854305839434716e+00,3.337859822948649469e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.151285117146454695e+01,3.737590153302645604e+02,5.839958897778153357e+00,5.656854305839434716e+00,3.312859822948649446e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.151461893839990580e+01,3.737690098432462946e+02,5.840290123165823744e+00,5.656854305839434716e+00,3.287859822948649424e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.151638670533526465e+01,3.737790044387220973e+02,5.840618849914924304e+00,5.656854305839434716e+00,3.262859822948649402e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.151815447227062350e+01,3.737889991160672025e+02,5.840945078004908808e+00,5.656854305839434716e+00,3.237859822948649380e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.151992223920598235e+01,3.737989938746570147e+02,5.841268807415388231e+00,5.656854305839434716e+00,3.212859822948649358e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.152169000614134120e+01,3.738089887138668246e+02,5.841590038126129869e+00,5.656854305839434716e+00,3.187859822948649335e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.152345777307670005e+01,3.738189836330719800e+02,5.841908770117056449e+00,5.656854305839434716e+00,3.162859822948649313e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.152522554001205890e+01,3.738289786316478285e+02,5.842225003368247904e+00,5.656854305839434716e+00,3.137859822948649291e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.152699330694741775e+01,3.738389737089696041e+02,5.842538737859938713e+00,5.656854305839434716e+00,3.112859822948649269e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.152876107388277660e+01,3.738489688644126545e+02,5.842849973572521449e+00,5.656854305839434716e+00,3.087859822948649247e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.153052884081813545e+01,3.738589640973523274e+02,5.843158710486543228e+00,5.656854305839434716e+00,3.062859822948649224e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.153229660775349430e+01,3.738689594071638567e+02,5.843464948582707486e+00,5.656854305839434716e+00,3.037859822948649202e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.153406437468885315e+01,3.738789547932225332e+02,5.843768687841875753e+00,5.656854305839434716e+00,3.012859822948649180e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.153583214162421200e+01,3.738889502549037047e+02,5.844069928245063217e+00,5.656854305839434716e+00,2.987859822948649158e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.153759990855957085e+01,3.738989457915826051e+02,5.844368669773442271e+00,5.656854305839434716e+00,2.962859822948649136e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.153936767549492970e+01,3.739089414026345253e+02,5.844664912408342516e+00,5.656854305839434716e+00,2.937859822948649113e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.154113544243028855e+01,3.739189370874347560e+02,5.844958656131248098e+00,5.656854305839434716e+00,2.912859822948649091e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.154290320936564740e+01,3.739289328453585313e+02,5.845249900923800368e+00,5.656854305839434716e+00,2.887859822948649069e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.154467097630100625e+01,3.739389286757811419e+02,5.845538646767796109e+00,5.656854305839434716e+00,2.862859822948649047e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.154643874323636510e+01,3.739489245780778219e+02,5.845824893645188425e+00,5.656854305839434716e+00,2.837859822948649025e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.154820651017172395e+01,3.739589205516238621e+02,5.846108641538087625e+00,5.656854305839434716e+00,2.812859822948649002e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.154997427710708280e+01,3.739689165957944965e+02,5.846389890428759450e+00,5.656854305839434716e+00,2.787859822948648980e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.155174204404244165e+01,3.739789127099650159e+02,5.846668640299625963e+00,5.656854305839434716e+00,2.762859822948648958e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.155350981097780050e+01,3.739889088935105974e+02,5.846944891133264655e+00,5.656854305839434716e+00,2.737859822948648936e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.155527757791315935e+01,3.739989051458065319e+02,5.847218642912410225e+00,5.656854305839434716e+00,2.712859822948648914e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.155704534484851820e+01,3.740089014662279965e+02,5.847489895619952804e+00,5.656854305839434716e+00,2.687859822948648891e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.155881311178387705e+01,3.740188978541502820e+02,5.847758649238939732e+00,5.656854305839434716e+00,2.662859822948648869e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.156058087871923590e+01,3.740288943089485656e+02,5.848024903752573778e+00,5.656854305839434716e+00,2.637859822948648847e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.156234864565459475e+01,3.740388908299980812e+02,5.848288659144213142e+00,5.656854305839434716e+00,2.612859822948648825e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.156411641258995360e+01,3.740488874166740629e+02,5.848549915397374122e+00,5.656854305839434716e+00,2.587859822948648802e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.156588417952531245e+01,3.740588840683516878e+02,5.848808672495727556e+00,5.656854305839434716e+00,2.562859822948648780e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.156765194646067130e+01,3.740688807844061898e+02,5.849064930423101494e+00,5.656854305839434716e+00,2.537859822948648758e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.156941971339603015e+01,3.740788775642128030e+02,5.849318689163480300e+00,5.656854305839434716e+00,2.512859822948648736e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.157118748033138900e+01,3.740888744071467045e+02,5.849569948701002886e+00,5.656854305839434716e+00,2.487859822948648714e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.157295524726674785e+01,3.740988713125830714e+02,5.849818709019966256e+00,5.656854305839434716e+00,2.462859822948648691e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.157472301420210670e+01,3.741088682798971377e+02,5.850064970104822848e+00,5.656854305839434716e+00,2.437859822948648669e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.157649078113746555e+01,3.741188653084640237e+02,5.850308731940181417e+00,5.656854305839434716e+00,2.412859822948648647e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.157825854807282440e+01,3.741288623976589633e+02,5.850549994510807039e+00,5.656854305839434716e+00,2.387859822948648625e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.158002631500818325e+01,3.741388595468571339e+02,5.850788757801620221e+00,5.656854305839434716e+00,2.362859822948648603e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.158179408194354210e+01,3.741488567554337124e+02,5.851025021797698678e+00,5.656854305839434716e+00,2.337859822948648580e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.158356184887890095e+01,3.741588540227638759e+02,5.851258786484275554e+00,5.656854305839434716e+00,2.312859822948648558e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.158532961581425980e+01,3.741688513482228018e+02,5.851490051846741203e+00,5.656854305839434716e+00,2.287859822948648536e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.158709738274961865e+01,3.741788487311856670e+02,5.851718817870640521e+00,5.656854305839434716e+00,2.262859822948648514e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.158886514968497750e+01,3.741888461710276488e+02,5.851945084541676501e+00,5.656854305839434716e+00,2.237859822948648492e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.159063291662033635e+01,3.741988436671238674e+02,5.852168851845707565e+00,5.656854305839434716e+00,2.212859822948648469e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.159240068355569520e+01,3.742088412188494999e+02,5.852390119768747567e+00,5.656854305839434716e+00,2.187859822948648447e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.159416845049105405e+01,3.742188388255796667e+02,5.852608888296967571e+00,5.656854305839434716e+00,2.162859822948648425e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.159593621742641290e+01,3.742288364866895449e+02,5.852825157416694957e+00,5.656854305839434716e+00,2.137859822948648403e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.159770398436177175e+01,3.742388342015542548e+02,5.853038927114411649e+00,5.656854305839434716e+00,2.112859822948648381e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.159947175129713060e+01,3.742488319695489736e+02,5.853250197376758557e+00,5.656854305839434716e+00,2.087859822948648358e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.160123951823248944e+01,3.742588297900488215e+02,5.853458968190530243e+00,5.656854305839434716e+00,2.062859822948648336e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.160300728516784829e+01,3.742688276624289756e+02,5.853665239542679366e+00,5.656854305839434716e+00,2.037859822948648314e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.160477505210320714e+01,3.742788255860644995e+02,5.853869011420313129e+00,5.656854305839434716e+00,2.012859822948648292e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.160654281903856599e+01,3.742888235603305702e+02,5.854070283810695940e+00,5.656854305839434716e+00,1.987859822948648270e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.160831058597392484e+01,3.742988215846023081e+02,5.854269056701248530e+00,5.656854305839434716e+00,1.962859822948648247e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.161007835290928369e+01,3.743088196582548335e+02,5.854465330079547947e+00,5.656854305839434716e+00,1.937859822948648225e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.161184611984464254e+01,3.743188177806632666e+02,5.854659103933326669e+00,5.656854305839434716e+00,1.912859822948648203e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.161361388678000139e+01,3.743288159512027278e+02,5.854850378250473497e+00,5.656854305839434716e+00,1.887859822948648181e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.161538165371536024e+01,3.743388141692482805e+02,5.855039153019034437e+00,5.656854305839434716e+00,1.862859822948648159e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.161714942065071909e+01,3.743488124341751018e+02,5.855225428227210926e+00,5.656854305839434716e+00,1.837859822948648136e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.161891718758607794e+01,3.743588107453582552e+02,5.855409203863360723e+00,5.656854305839434716e+00,1.812859822948648114e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.162068495452143679e+01,3.743688091021728610e+02,5.855590479915997904e+00,5.656854305839434716e+00,1.787859822948648092e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.162245272145679564e+01,3.743788075039940395e+02,5.855769256373791976e+00,5.656854305839434716e+00,1.762859822948648070e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.162422048839215449e+01,3.743888059501969110e+02,5.855945533225570543e+00,5.656854305839434716e+00,1.737859822948648048e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.162598825532751334e+01,3.743988044401565389e+02,5.856119310460315752e+00,5.656854305839434716e+00,1.712859822948648025e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.162775602226287219e+01,3.744088029732480436e+02,5.856290588067166070e+00,5.656854305839434716e+00,1.687859822948648003e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.162952378919823104e+01,3.744188015488464885e+02,5.856459366035417169e+00,5.656854305839434716e+00,1.662859822948647981e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.163129155613358989e+01,3.744288001663269370e+02,5.856625644354521043e+00,5.656854305839434716e+00,1.637859822948647959e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.163305932306894874e+01,3.744387988250645094e+02,5.856789423014084228e+00,5.656854305839434716e+00,1.612859822948647937e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.163482709000430759e+01,3.744487975244343261e+02,5.856950702003871356e+00,5.656854305839434716e+00,1.587859822948647914e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.163659485693966644e+01,3.744587962638113936e+02,5.857109481313801602e+00,5.656854305839434716e+00,1.562859822948647892e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.163836262387502529e+01,3.744687950425708323e+02,5.857265760933952237e+00,5.656854305839434716e+00,1.537859822948647870e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.164013039081038414e+01,3.744787938600877055e+02,5.857419540854555073e+00,5.656854305839434716e+00,1.512859822948647848e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.164189815774574299e+01,3.744887927157371337e+02,5.857570821065999134e+00,5.656854305839434716e+00,1.487859822948647825e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.164366592468110184e+01,3.744987916088941233e+02,5.857719601558829758e+00,5.656854305839434716e+00,1.462859822948647803e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.164543369161646069e+01,3.745087905389337948e+02,5.857865882323747719e+00,5.656854305839434716e+00,1.437859822948647781e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.164720145855181954e+01,3.745187895052311546e+02,5.858009663351610108e+00,5.656854305839434716e+00,1.412859822948647759e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.164896922548717839e+01,3.745287885071613232e+02,5.858150944633431223e+00,5.656854305839434716e+00,1.387859822948647737e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.165073699242253724e+01,3.745387875440993639e+02,5.858289726160380795e+00,5.656854305839434716e+00,1.362859822948647714e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.165250475935789609e+01,3.745487866154202834e+02,5.858426007923784873e+00,5.656854305839434716e+00,1.337859822948647692e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.165427252629325494e+01,3.745587857204992019e+02,5.858559789915125826e+00,5.656854305839434716e+00,1.312859822948647670e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.165604029322861379e+01,3.745687848587111262e+02,5.858691072126042343e+00,5.656854305839434716e+00,1.287859822948647648e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.165780806016397264e+01,3.745787840294311195e+02,5.858819854548329431e+00,5.656854305839434716e+00,1.262859822948647626e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.165957582709933149e+01,3.745887832320342454e+02,5.858946137173938418e+00,5.656854305839434716e+00,1.237859822948647603e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.166134359403469034e+01,3.745987824658955674e+02,5.859069919994976061e+00,5.656854305839434716e+00,1.212859822948647581e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.166311136097004919e+01,3.746087817303900920e+02,5.859191203003706327e+00,5.656854305839434716e+00,1.187859822948647559e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.166487912790540804e+01,3.746187810248928827e+02,5.859309986192548614e+00,5.656854305839434716e+00,1.162859822948647537e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.166664689484076689e+01,3.746287803487790029e+02,5.859426269554079525e+00,5.656854305839434716e+00,1.137859822948647515e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.166841466177612574e+01,3.746387797014235161e+02,5.859540053081031097e+00,5.656854305839434716e+00,1.112859822948647492e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.167018242871148459e+01,3.746487790822014290e+02,5.859651336766291685e+00,5.656854305839434716e+00,1.087859822948647470e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.167195019564684344e+01,3.746587784904877481e+02,5.859760120602905964e+00,5.656854305839434716e+00,1.062859822948647448e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.167371796258220229e+01,3.746687779256575368e+02,5.859866404584075816e+00,5.656854305839434716e+00,1.037859822948647426e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.167548572951756114e+01,3.746787773870858587e+02,5.859970188703157667e+00,5.656854305839434716e+00,1.012859822948647404e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.167725349645291999e+01,3.746887768741477203e+02,5.860071472953665150e+00,5.656854305839434716e+00,9.878598229486473814e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.167902126338827884e+01,3.746987763862181851e+02,5.860170257329268217e+00,5.656854305839434716e+00,9.628598229486473592e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.168078903032363769e+01,3.747087759226722596e+02,5.860266541823792252e+00,5.656854305839434716e+00,9.378598229486473370e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.168255679725899654e+01,3.747187754828849506e+02,5.860360326431219846e+00,5.656854305839434716e+00,9.128598229486473148e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.168432456419435539e+01,3.747287750662313215e+02,5.860451611145689910e+00,5.656854305839434716e+00,8.878598229486472926e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.168609233112971424e+01,3.747387746720863788e+02,5.860540395961496785e+00,5.656854305839434716e+00,8.628598229486472704e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.168786009806507309e+01,3.747487742998251292e+02,5.860626680873091132e+00,5.656854305839434716e+00,8.378598229486472482e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.168962786500043194e+01,3.747587739488226362e+02,5.860710465875080821e+00,5.656854305839434716e+00,8.128598229486472260e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.169139563193579079e+01,3.747687736184539062e+02,5.860791750962229152e+00,5.656854305839434716e+00,7.878598229486472038e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.169316339887114964e+01,3.747787733080939461e+02,5.860870536129454855e+00,5.656854305839434716e+00,7.628598229486471816e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.169493116580650849e+01,3.747887730171178191e+02,5.860946821371834758e+00,5.656854305839434716e+00,7.378598229486471594e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.169669893274186734e+01,3.747987727449004751e+02,5.861020606684601120e+00,5.656854305839434716e+00,7.128598229486471372e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.169846669967722619e+01,3.748087724908169776e+02,5.861091892063141628e+00,5.656854305839434716e+00,6.878598229486471149e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.170023446661258504e+01,3.748187722542423330e+02,5.861160677503002070e+00,5.656854305839434716e+00,6.628598229486470927e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.170200223354794389e+01,3.748287720345515481e+02,5.861226962999881884e+00,5.656854305839434716e+00,6.378598229486470705e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.170377000048330274e+01,3.748387718311196863e+02,5.861290748549639495e+00,5.656854305839434716e+00,6.128598229486470483e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.170553776741866159e+01,3.748487716433216974e+02,5.861352034148287871e+00,5.656854305839434716e+00,5.878598229486470261e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.170730553435402044e+01,3.748587714705325880e+02,5.861410819791996296e+00,5.656854305839434716e+00,5.628598229486470039e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.170907330128937929e+01,3.748687713121274214e+02,5.861467105477091266e+00,5.656854305839434716e+00,5.378598229486469817e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.171084106822473814e+01,3.748787711674811476e+02,5.861520891200054706e+00,5.656854305839434716e+00,5.128598229486469595e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.171260883516009699e+01,3.748887710359688299e+02,5.861572176957524860e+00,5.656854305839434716e+00,4.878598229486469373e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.171437660209545584e+01,3.748987709169654750e+02,5.861620962746296293e+00,5.656854305839434716e+00,4.628598229486469151e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.171614436903081469e+01,3.749087708098460325e+02,5.861667248563319887e+00,5.656854305839434716e+00,4.378598229486468929e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.171791213596617354e+01,3.749187707139855661e+02,5.861711034405702847e+00,5.656854305839434716e+00,4.128598229486468707e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.171967990290153239e+01,3.749287706287590822e+02,5.861752320270708694e+00,5.656854305839434716e+00,3.878598229486468485e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.172144766983689124e+01,3.749387705535415307e+02,5.861791106155757269e+00,5.656854305839434716e+00,3.628598229486468263e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.172321543677225009e+01,3.749487704877079750e+02,5.861827392058423847e+00,5.656854305839434716e+00,3.378598229486468041e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.172498320370760894e+01,3.749587704306334217e+02,5.861861177976440906e+00,5.656854305839434716e+00,3.128598229486467819e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.172675097064296779e+01,3.749687703816928206e+02,5.861892463907697248e+00,5.656854305839434716e+00,2.878598229486467597e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.172851873757832664e+01,3.749787703402612351e+02,5.861921249850237103e+00,5.656854305839434716e+00,2.628598229486467375e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.173028650451368549e+01,3.749887703057136150e+02,5.861947535802261022e+00,5.656854305839434716e+00,2.378598229486467153e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.173205427144904434e+01,3.749987702774249669e+02,5.861971321762126763e+00,5.656854305839434716e+00,2.128598229486466931e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.173382203838440319e+01,3.750087702547702975e+02,5.861992607728347515e+00,5.656854305839434716e+00,1.878598229486466925e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.173558980531976204e+01,3.750187702371246701e+02,5.862011393699592787e+00,5.656854305839434716e+00,1.628598229486466920e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.173735757225512089e+01,3.750287702238630345e+02,5.862027679674688407e+00,5.656854305839434716e+00,1.378598229486466915e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.173912533919047974e+01,3.750387702143603974e+02,5.862041465652616523e+00,5.656854305839434716e+00,1.128598229486466910e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.174089310612583859e+01,3.750487702079917085e+02,5.862052751632515601e+00,5.656854305839434716e+00,8.785982294864669046e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.174266087306119744e+01,3.750587702041320313e+02,5.862061537613680429e+00,5.656854305839434716e+00,6.285982294864668994e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.174442863999655629e+01,3.750687702021563723e+02,5.862067823595561222e+00,5.656854305839434716e+00,3.785982294864668942e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.174619640693191513e+01,3.750787702014396814e+02,5.862071609577765408e+00,5.656854305839434716e+00,1.285982294864668890e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.174796417386727398e+01,3.750887702013570220e+02,5.862072895560056729e+00,5.656854305839434716e+00,-1.214017705135331162e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.174973194080263283e+01,3.750987702012833438e+02,5.862071681542354362e+00,5.656854305839434716e+00,-3.714017705135331214e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.175149970773799168e+01,3.751087702005936535e+02,5.862067967524734691e+00,5.656854305839434716e+00,-6.214017705135331266e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.175326747467335053e+01,3.751187701986629577e+02,5.862061753507429529e+00,5.656854305839434716e+00,-8.714017705135331318e-04,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.175503524160870938e+01,3.751287701948662630e+02,5.862053039490827011e+00,5.656854305839434716e+00,-1.121401770513533137e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.175680300854406823e+01,3.751387701885785759e+02,5.862041825475472479e+00,5.656854305839434716e+00,-1.371401770513533142e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.175857077547942708e+01,3.751487701791748464e+02,5.862028111462065816e+00,5.656854305839434716e+00,-1.621401770513533147e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.176033854241478593e+01,3.751587701660301377e+02,5.862011897451465003e+00,5.656854305839434716e+00,-1.871401770513533153e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.176210630935014478e+01,3.751687701485193998e+02,5.861993183444683453e+00,5.656854305839434716e+00,-2.121401770513533375e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.176387407628550363e+01,3.751787701260176959e+02,5.861971969442890007e+00,5.656854305839434716e+00,-2.371401770513533597e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.176564184322086248e+01,3.751887700978999760e+02,5.861948255447410716e+00,5.656854305839434716e+00,-2.621401770513533819e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.176740961015622133e+01,3.751987700635412466e+02,5.861922041459727950e+00,5.656854305839434716e+00,-2.871401770513534041e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.176917737709158018e+01,3.752087700223165143e+02,5.861893327481480398e+00,5.656854305839434716e+00,-3.121401770513534263e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.177094514402693903e+01,3.752187699736007858e+02,5.861862113514462180e+00,5.656854305839434716e+00,-3.371401770513534485e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.177271291096229788e+01,3.752287699167690675e+02,5.861828399560624625e+00,5.656854305839434716e+00,-3.621401770513534707e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.177448067789765673e+01,3.752387698511963663e+02,5.861792185622074491e+00,5.656854305839434716e+00,-3.871401770513534929e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.177624844483301558e+01,3.752487697762576886e+02,5.861753471701074858e+00,5.656854305839434716e+00,-4.121401770513535151e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.177801621176837443e+01,3.752587696913280411e+02,5.861712257800046011e+00,5.656854305839434716e+00,-4.371401770513535373e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.177978397870373328e+01,3.752687695957824303e+02,5.861668543921563668e+00,5.656854305839434716e+00,-4.621401770513535595e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.178155174563909213e+01,3.752787694889958630e+02,5.861622330068359865e+00,5.656854305839434716e+00,-4.871401770513535817e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.178331951257445098e+01,3.752887693703433456e+02,5.861573616243322959e+00,5.656854305839434716e+00,-5.121401770513536039e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.178508727950980983e+01,3.752987692391998280e+02,5.861522402449497626e+00,5.656854305839434716e+00,-5.371401770513536261e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.178685504644516868e+01,3.753087690949403736e+02,5.861468688690084861e+00,5.656854305839434716e+00,-5.621401770513536483e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.178862281338052753e+01,3.753187689369399891e+02,5.861412474968441089e+00,5.656854305839434716e+00,-5.871401770513536705e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.179039058031588638e+01,3.753287687645736810e+02,5.861353761288079944e+00,5.656854305839434716e+00,-6.121401770513536927e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.179215834725124523e+01,3.753387685772164559e+02,5.861292547652671381e+00,5.656854305839434716e+00,-6.371401770513537149e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.179392611418660408e+01,3.753487683742433205e+02,5.861228834066041671e+00,5.656854305839434716e+00,-6.621401770513537371e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.179569388112196293e+01,3.753587681550293382e+02,5.861162620532171630e+00,5.656854305839434716e+00,-6.871401770513537594e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.179746164805732178e+01,3.753687679189494588e+02,5.861093907055200170e+00,5.656854305839434716e+00,-7.121401770513537816e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.179922941499268063e+01,3.753787676653786889e+02,5.861022693639422521e+00,5.656854305839434716e+00,-7.371401770513538038e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.180099718192803948e+01,3.753887673936920919e+02,5.860948980289289345e+00,5.656854305839434716e+00,-7.621401770513538260e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.180276494886339833e+01,3.753987671032646745e+02,5.860872767009406736e+00,5.656854305839434716e+00,-7.871401770513538482e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.180453271579875718e+01,3.754087667934714432e+02,5.860794053804538883e+00,5.656854305839434716e+00,-8.121401770513538704e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.180630048273411603e+01,3.754187664636874047e+02,5.860712840679605407e+00,5.656854305839434716e+00,-8.371401770513538926e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.180806824966947488e+01,3.754287661132876224e+02,5.860629127639681357e+00,5.656854305839434716e+00,-8.621401770513539148e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.180983601660483373e+01,3.754387657416471029e+02,5.860542914689999883e+00,5.656854305839434716e+00,-8.871401770513539370e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.181160378354019258e+01,3.754487653481408529e+02,5.860454201835948673e+00,5.656854305839434716e+00,-9.121401770513539592e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.181337155047555143e+01,3.754587649321438789e+02,5.860362989083072627e+00,5.656854305839434716e+00,-9.371401770513539814e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.181513931741091028e+01,3.754687644930312445e+02,5.860269276437072072e+00,5.656854305839434716e+00,-9.621401770513540036e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.181690708434626913e+01,3.754787640301779561e+02,5.860173063903803659e+00,5.656854305839434716e+00,-9.871401770513540258e-03,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.181867485128162798e+01,3.754887635429590205e+02,5.860074351489281241e+00,5.656854305839434716e+00,-1.012140177051354048e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.182044261821698683e+01,3.754987630307495010e+02,5.859973139199674996e+00,5.656854305839434716e+00,-1.037140177051354070e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.182221038515234568e+01,3.755087624929244612e+02,5.859869427041309642e+00,5.656854305839434716e+00,-1.062140177051354092e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.182397815208770453e+01,3.755187619288589076e+02,5.859763215020667992e+00,5.656854305839434716e+00,-1.087140177051354115e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.182574591902306338e+01,3.755287613379278469e+02,5.859654503144387405e+00,5.656854305839434716e+00,-1.112140177051354137e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.182751368595842223e+01,3.755387607195063424e+02,5.859543291419263333e+00,5.656854305839434716e+00,-1.137140177051354159e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.182928145289378108e+01,3.755487600729694009e+02,5.859429579852245773e+00,5.656854305839434716e+00,-1.162140177051354181e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.183104921982913993e+01,3.755587593976920857e+02,5.859313368450441928e+00,5.656854305839434716e+00,-1.187140177051354203e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.183281698676449878e+01,3.755687586930494604e+02,5.859194657221115321e+00,5.656854305839434716e+00,-1.212140177051354226e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.183458475369985763e+01,3.755787579584165314e+02,5.859073446171684907e+00,5.656854305839434716e+00,-1.237140177051354248e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.183635252063521648e+01,3.755887571931683624e+02,5.858949735309726847e+00,5.656854305839434716e+00,-1.262140177051354270e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.183812028757057533e+01,3.755987563966800167e+02,5.858823524642972735e+00,5.656854305839434716e+00,-1.287140177051354292e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.183988805450593418e+01,3.756087555683265577e+02,5.858694814179310484e+00,5.656854305839434716e+00,-1.312140177051354314e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.184165582144129303e+01,3.756187547074829922e+02,5.858563603926785213e+00,5.656854305839434716e+00,-1.337140177051354337e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.184342358837665188e+01,3.756287538135243835e+02,5.858429893893597473e+00,5.656854305839434716e+00,-1.362140177051354359e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.184519135531201073e+01,3.756387528858257951e+02,5.858293684088103248e+00,5.656854305839434716e+00,-1.387140177051354381e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.184695912224736958e+01,3.756487519237622905e+02,5.858154974518816616e+00,5.656854305839434716e+00,-1.412140177051354403e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.184872688918272843e+01,3.756587509267089331e+02,5.858013765194406197e+00,5.656854305839434716e+00,-1.437140177051354425e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.185049465611808728e+01,3.756687498940407863e+02,5.857870056123697822e+00,5.656854305839434716e+00,-1.462140177051354448e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.185226242305344613e+01,3.756787488251328568e+02,5.857723847315673638e+00,5.656854305839434716e+00,-1.487140177051354470e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.185403018998880498e+01,3.756887477193602649e+02,5.857575138779471224e+00,5.656854305839434716e+00,-1.512140177051354492e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.185579795692416383e+01,3.756987465760980740e+02,5.857423930524385369e+00,5.656854305839434716e+00,-1.537140177051354514e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.185756572385952268e+01,3.757087453947213476e+02,5.857270222559866291e+00,5.656854305839434716e+00,-1.562140177051354537e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.185933349079488153e+01,3.757187441746052059e+02,5.857114014895521414e+00,5.656854305839434716e+00,-1.587140177051354559e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.186110125773024038e+01,3.757287429151246556e+02,5.856955307541112710e+00,5.656854305839434716e+00,-1.612140177051354581e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.186286902466559923e+01,3.757387416156548170e+02,5.856794100506560241e+00,5.656854305839434716e+00,-1.637140177051354603e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.186463679160095808e+01,3.757487402755707535e+02,5.856630393801938617e+00,5.656854305839434716e+00,-1.662140177051354625e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.186640455853631693e+01,3.757587388942475854e+02,5.856464187437479652e+00,5.656854305839434716e+00,-1.687140177051354648e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.186817232547167578e+01,3.757687374710603763e+02,5.856295481423571481e+00,5.656854305839434716e+00,-1.712140177051354670e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.186994009240703463e+01,3.757787360053841894e+02,5.856124275770758558e+00,5.656854305839434716e+00,-1.737140177051354692e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.187170785934239348e+01,3.757887344965941452e+02,5.855950570489740770e+00,5.656854305839434716e+00,-1.762140177051354714e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.187347562627775233e+01,3.757987329440653070e+02,5.855774365591375208e+00,5.656854305839434716e+00,-1.787140177051354736e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.187524339321311118e+01,3.758087313471727953e+02,5.855595661086673509e+00,5.656854305839434716e+00,-1.812140177051354759e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.187701116014847003e+01,3.758187297052917302e+02,5.855414456986805405e+00,5.656854305839434716e+00,-1.837140177051354781e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.187877892708382888e+01,3.758287280177971752e+02,5.855230753303096947e+00,5.656854305839434716e+00,-1.862140177051354803e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.188054669401918773e+01,3.758387262840642506e+02,5.855044550047028729e+00,5.656854305839434716e+00,-1.887140177051354825e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.188231446095454658e+01,3.758487245034680768e+02,5.854855847230238552e+00,5.656854305839434716e+00,-1.912140177051354847e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.188408222788990543e+01,3.758587226753837740e+02,5.854664644864520540e+00,5.656854305839434716e+00,-1.937140177051354870e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.188584999482526428e+01,3.758687207991864057e+02,5.854470942961824242e+00,5.656854305839434716e+00,-1.962140177051354892e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.188761776176062313e+01,3.758787188742511489e+02,5.854274741534256421e+00,5.656854305839434716e+00,-1.987140177051354914e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.188938552869598198e+01,3.758887168999530672e+02,5.854076040594080155e+00,5.656854305839434716e+00,-2.012140177051354936e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.189115329563134082e+01,3.758987148756673378e+02,5.853874840153713954e+00,5.656854305839434716e+00,-2.037140177051354958e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.189292106256669967e+01,3.759087128007690239e+02,5.853671140225732650e+00,5.656854305839434716e+00,-2.062140177051354981e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.189468882950205852e+01,3.759187106746333029e+02,5.853464940822867391e+00,5.656854305839434716e+00,-2.087140177051355003e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.189645659643741737e+01,3.759287084966352950e+02,5.853256241958005646e+00,5.656854305839434716e+00,-2.112140177051355025e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.189822436337277622e+01,3.759387062661501773e+02,5.853045043644191203e+00,5.656854305839434716e+00,-2.137140177051355047e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.189999213030813507e+01,3.759487039825530132e+02,5.852831345894624171e+00,5.656854305839434716e+00,-2.162140177051355069e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.190175989724349392e+01,3.759587016452189800e+02,5.852615148722660976e+00,5.656854305839434716e+00,-2.187140177051355092e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.190352766417885277e+01,3.759686992535232548e+02,5.852396452141813477e+00,5.656854305839434716e+00,-2.212140177051355114e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.190529543111421162e+01,3.759786968068409578e+02,5.852175256165749850e+00,5.656854305839434716e+00,-2.237140177051355136e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.190706319804957047e+01,3.759886943045472094e+02,5.851951560808295483e+00,5.656854305839434716e+00,-2.262140177051355158e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.190883096498492932e+01,3.759986917460172435e+02,5.851725366083431190e+00,5.656854305839434716e+00,-2.287140177051355180e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.191059873192028817e+01,3.760086891306261805e+02,5.851496672005294108e+00,5.656854305839434716e+00,-2.312140177051355203e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.191236649885564702e+01,3.760186864577491406e+02,5.851265478588176805e+00,5.656854305839434716e+00,-2.337140177051355225e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.191413426579100587e+01,3.760286837267613578e+02,5.851031785846529942e+00,5.656854305839434716e+00,-2.362140177051355247e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.191590203272636472e+01,3.760386809370379524e+02,5.850795593794958727e+00,5.656854305839434716e+00,-2.387140177051355269e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.191766979966172357e+01,3.760486780879541584e+02,5.850556902448225571e+00,5.656854305839434716e+00,-2.412140177051355291e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.191943756659708242e+01,3.760586751788850961e+02,5.850315711821248321e+00,5.656854305839434716e+00,-2.437140177051355314e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.192120533353244127e+01,3.760686722092059426e+02,5.850072021929102029e+00,5.656854305839434716e+00,-2.462140177051355336e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.192297310046780012e+01,3.760786691782919320e+02,5.849825832787016289e+00,5.656854305839434716e+00,-2.487140177051355358e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.192474086740315897e+01,3.760886660855182413e+02,5.849577144410378793e+00,5.656854305839434716e+00,-2.512140177051355380e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.192650863433851782e+01,3.760986629302600477e+02,5.849325956814732663e+00,5.656854305839434716e+00,-2.537140177051355402e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.192827640127387667e+01,3.761086597118925283e+02,5.849072270015776454e+00,5.656854305839434716e+00,-2.562140177051355425e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.193004416820923552e+01,3.761186564297909172e+02,5.848816084029365925e+00,5.656854305839434716e+00,-2.587140177051355447e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.193181193514459437e+01,3.761286530833304482e+02,5.848557398871512270e+00,5.656854305839434716e+00,-2.612140177051355469e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.193357970207995322e+01,3.761386496718862986e+02,5.848296214558383888e+00,5.656854305839434716e+00,-2.637140177051355491e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.193534746901531207e+01,3.761486461948336455e+02,5.848032531106304610e+00,5.656854305839434716e+00,-2.662140177051355514e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.193711523595067092e+01,3.761586426515477797e+02,5.847766348531754588e+00,5.656854305839434716e+00,-2.687140177051355536e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.193888300288602977e+01,3.761686390414038783e+02,5.847497666851370290e+00,5.656854305839434716e+00,-2.712140177051355558e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.194065076982138862e+01,3.761786353637771185e+02,5.847226486081944508e+00,5.656854305839434716e+00,-2.737140177051355580e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.194241853675674747e+01,3.761886316180427912e+02,5.846952806240425460e+00,5.656854305839434716e+00,-2.762140177051355602e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.194418630369210632e+01,3.761986278035761302e+02,5.846676627343918575e+00,5.656854305839434716e+00,-2.787140177051355625e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.194595407062746517e+01,3.762086239197523696e+02,5.846397949409685602e+00,5.656854305839434716e+00,-2.812140177051355647e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.194772183756282402e+01,3.762186199659467434e+02,5.846116772455142829e+00,5.656854305839434716e+00,-2.837140177051355669e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.194948960449818287e+01,3.762286159415344855e+02,5.845833096497864645e+00,5.656854305839434716e+00,-2.862140177051355691e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.195125737143354172e+01,3.762386118458908868e+02,5.845546921555579978e+00,5.656854305839434716e+00,-2.887140177051355713e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.195302513836890057e+01,3.762486076783911813e+02,5.845258247646174965e+00,5.656854305839434716e+00,-2.912140177051355736e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.195479290530425942e+01,3.762586034384106597e+02,5.844967074787692063e+00,5.656854305839434716e+00,-2.937140177051355758e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.195656067223961827e+01,3.762685991253245561e+02,5.844673402998330047e+00,5.656854305839434716e+00,-2.962140177051355780e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.195832843917497712e+01,3.762785947385081045e+02,5.844377232296442237e+00,5.656854305839434716e+00,-2.987140177051355802e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.196009620611033597e+01,3.762885902773366524e+02,5.844078562700540047e+00,5.656854305839434716e+00,-3.012140177051355824e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.196186397304569482e+01,3.762985857411854340e+02,5.843777394229290323e+00,5.656854305839434716e+00,-3.037140177051355847e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.196363173998105367e+01,3.763085811294297400e+02,5.843473726901516230e+00,5.656854305839434716e+00,-3.062140177051355869e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.196539950691641252e+01,3.763185764414448613e+02,5.843167560736196364e+00,5.656854305839434716e+00,-3.087140177051355891e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.196716727385177137e+01,3.763285716766060887e+02,5.842858895752466530e+00,5.656854305839434716e+00,-3.112140177051355913e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.196893504078713022e+01,3.763385668342887129e+02,5.842547731969617963e+00,5.656854305839434716e+00,-3.137140177051355588e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.197070280772248907e+01,3.763485619138680249e+02,5.842234069407099106e+00,5.656854305839434716e+00,-3.162140177051355611e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.197247057465784792e+01,3.763585569147193723e+02,5.841917908084512945e+00,5.656854305839434716e+00,-3.187140177051355633e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.197423834159320677e+01,3.763685518362180460e+02,5.841599248021620561e+00,5.656854305839434716e+00,-3.212140177051355655e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.197600610852856562e+01,3.763785466777393367e+02,5.841278089238337579e+00,5.656854305839434716e+00,-3.237140177051355677e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.197777387546392447e+01,3.763885414386585921e+02,5.840954431754735943e+00,5.656854305839434716e+00,-3.262140177051355699e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.197954164239928332e+01,3.763985361183511600e+02,5.840628275591044805e+00,5.656854305839434716e+00,-3.287140177051355722e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.198130940933464217e+01,3.764085307161923311e+02,5.840299620767649635e+00,5.656854305839434716e+00,-3.312140177051355744e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.198307717627000102e+01,3.764185252315575099e+02,5.839968467305090449e+00,5.656854305839434716e+00,-3.337140177051355766e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.198484494320535987e+01,3.764285196638219873e+02,5.839634815224064468e+00,5.656854305839434716e+00,-3.362140177051355788e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.198661271014071872e+01,3.764385140123611109e+02,5.839298664545425233e+00,5.656854305839434716e+00,-3.387140177051355810e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.198838047707607757e+01,3.764485082765502284e+02,5.838960015290181715e+00,5.656854305839434716e+00,-3.412140177051355833e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.199014824401143642e+01,3.764585024557646875e+02,5.838618867479500096e+00,5.656854305839434716e+00,-3.437140177051355855e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.199191601094679527e+01,3.764684965493798927e+02,5.838275221134701098e+00,5.656854305839434716e+00,-3.462140177051355877e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.199368377788215412e+01,3.764784905567711917e+02,5.837929076277263540e+00,5.656854305839434716e+00,-3.487140177051355899e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.199545154481751297e+01,3.764884844773139889e+02,5.837580432928820784e+00,5.656854305839434716e+00,-3.512140177051355922e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.199721931175287182e+01,3.764984783103836321e+02,5.837229291111164287e+00,5.656854305839434716e+00,-3.537140177051355944e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.199898707868823067e+01,3.765084720553555258e+02,5.836875650846239161e+00,5.656854305839434716e+00,-3.562140177051355966e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.200075484562358952e+01,3.765184657116050175e+02,5.836519512156148615e+00,5.656854305839434716e+00,-3.587140177051355988e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.200252261255894837e+01,3.765284592785075688e+02,5.836160875063150399e+00,5.656854305839434716e+00,-3.612140177051356010e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.200429037949430722e+01,3.765384527554385272e+02,5.835799739589660362e+00,5.656854305839434716e+00,-3.637140177051356033e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.200605814642966607e+01,3.765484461417733542e+02,5.835436105758248893e+00,5.656854305839434716e+00,-3.662140177051356055e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.200782591336502492e+01,3.765584394368873973e+02,5.835069973591643588e+00,5.656854305839434716e+00,-3.687140177051356077e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.200959368030038377e+01,3.765684326401561179e+02,5.834701343112727479e+00,5.656854305839434716e+00,-3.712140177051356099e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.201136144723574262e+01,3.765784257509549207e+02,5.834330214344539911e+00,5.656854305839434716e+00,-3.737140177051356121e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.201312921417110147e+01,3.765884187686592668e+02,5.833956587310276554e+00,5.656854305839434716e+00,-3.762140177051356144e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.201489698110646032e+01,3.765984116926445608e+02,5.833580462033288505e+00,5.656854305839434716e+00,-3.787140177051356166e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.201666474804181917e+01,3.766084045222862642e+02,5.833201838537084072e+00,5.656854305839434716e+00,-3.812140177051356188e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.201843251497717802e+01,3.766183972569598382e+02,5.832820716845327880e+00,5.656854305839434716e+00,-3.837140177051356210e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.202020028191253687e+01,3.766283898960406873e+02,5.832437096981839098e+00,5.656854305839434716e+00,-3.862140177051356232e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.202196804884789572e+01,3.766383824389043298e+02,5.832050978970594102e+00,5.656854305839434716e+00,-3.887140177051356255e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.202373581578325457e+01,3.766483748849261701e+02,5.831662362835725588e+00,5.656854305839434716e+00,-3.912140177051356277e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.202550358271861342e+01,3.766583672334817265e+02,5.831271248601521684e+00,5.656854305839434716e+00,-3.937140177051356299e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.202727134965397227e+01,3.766683594839464604e+02,5.830877636292426835e+00,5.656854305839434716e+00,-3.962140177051356321e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.202903911658933112e+01,3.766783516356958899e+02,5.830481525933042697e+00,5.656854305839434716e+00,-3.987140177051356343e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.203080688352468997e+01,3.766883436881054763e+02,5.830082917548125465e+00,5.656854305839434716e+00,-4.012140177051356366e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.203257465046004882e+01,3.766983356405506811e+02,5.829681811162588545e+00,5.656854305839434716e+00,-4.037140177051356388e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.203434241739540767e+01,3.767083274924070793e+02,5.829278206801500772e+00,5.656854305839434716e+00,-4.062140177051356410e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.203611018433076651e+01,3.767183192430501322e+02,5.828872104490087303e+00,5.656854305839434716e+00,-4.087140177051356432e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.203787795126612536e+01,3.767283108918553580e+02,5.828463504253730498e+00,5.656854305839434716e+00,-4.112140177051356454e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.203964571820148421e+01,3.767383024381982750e+02,5.828052406117967266e+00,5.656854305839434716e+00,-4.137140177051356477e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.204141348513684306e+01,3.767482938814544013e+02,5.827638810108490830e+00,5.656854305839434716e+00,-4.162140177051356499e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.204318125207220191e+01,3.767582852209993121e+02,5.827222716251150736e+00,5.656854305839434716e+00,-4.187140177051356521e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.204494901900756076e+01,3.767682764562085254e+02,5.826804124571953736e+00,5.656854305839434716e+00,-4.212140177051356543e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.204671678594291961e+01,3.767782675864576163e+02,5.826383035097061125e+00,5.656854305839434716e+00,-4.237140177051356565e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.204848455287827846e+01,3.767882586111221030e+02,5.825959447852791406e+00,5.656854305839434716e+00,-4.262140177051356588e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.205025231981363731e+01,3.767982495295775607e+02,5.825533362865618514e+00,5.656854305839434716e+00,-4.287140177051356610e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.205202008674899616e+01,3.768082403411995642e+02,5.825104780162173590e+00,5.656854305839434716e+00,-4.312140177051356632e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.205378785368435501e+01,3.768182310453636887e+02,5.824673699769242319e+00,5.656854305839434716e+00,-4.337140177051356654e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.205555562061971386e+01,3.768282216414455092e+02,5.824240121713766705e+00,5.656854305839434716e+00,-4.362140177051356676e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.205732338755507271e+01,3.768382121288206008e+02,5.823804046022845959e+00,5.656854305839434716e+00,-4.387140177051356699e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.205909115449043156e+01,3.768482025068645385e+02,5.823365472723735614e+00,5.656854305839434716e+00,-4.412140177051356721e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.206085892142579041e+01,3.768581927749529541e+02,5.822924401843845743e+00,5.656854305839434716e+00,-4.437140177051356743e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.206262668836114926e+01,3.768681829324614796e+02,5.822480833410742740e+00,5.656854305839434716e+00,-4.462140177051356765e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.206439445529650811e+01,3.768781729787656900e+02,5.822034767452150206e+00,5.656854305839434716e+00,-4.487140177051356787e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.206616222223186696e+01,3.768881629132412172e+02,5.821586203995947173e+00,5.656854305839434716e+00,-4.512140177051356810e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.206792998916722581e+01,3.768981527352636931e+02,5.821135143070168994e+00,5.656854305839434716e+00,-4.537140177051356832e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.206969775610258466e+01,3.769081424442088064e+02,5.820681584703006450e+00,5.656854305839434716e+00,-4.562140177051356854e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.207146552303794351e+01,3.769181320394521322e+02,5.820225528922807534e+00,5.656854305839434716e+00,-4.587140177051356876e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.207323328997330236e+01,3.769281215203693591e+02,5.819766975758075667e+00,5.656854305839434716e+00,-4.612140177051356899e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.207500105690866121e+01,3.769381108863361192e+02,5.819305925237470589e+00,5.656854305839434716e+00,-4.637140177051356921e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.207676882384402006e+01,3.769481001367280442e+02,5.818842377389807474e+00,5.656854305839434716e+00,-4.662140177051356943e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.207853659077937891e+01,3.769580892709208797e+02,5.818376332244057814e+00,5.656854305839434716e+00,-4.687140177051356965e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.208030435771473776e+01,3.769680782882902577e+02,5.817907789829350307e+00,5.656854305839434716e+00,-4.712140177051356987e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.208207212465009661e+01,3.769780671882118668e+02,5.817436750174968196e+00,5.656854305839434716e+00,-4.737140177051357010e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.208383989158545546e+01,3.769880559700613958e+02,5.816963213310351932e+00,5.656854305839434716e+00,-4.762140177051357032e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.208560765852081431e+01,3.769980446332145902e+02,5.816487179265097396e+00,5.656854305839434716e+00,-4.787140177051357054e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.208737542545617316e+01,3.770080331770471389e+02,5.816008648068956788e+00,5.656854305839434716e+00,-4.812140177051357076e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.208914319239153201e+01,3.770180216009347305e+02,5.815527619751837740e+00,5.656854305839434716e+00,-4.837140177051357098e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.209091095932689086e+01,3.770280099042531106e+02,5.815044094343805092e+00,5.656854305839434716e+00,-4.862140177051357121e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.209267872626224971e+01,3.770379980863780247e+02,5.814558071875079115e+00,5.656854305839434716e+00,-4.887140177051357143e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.209444649319760856e+01,3.770479861466851617e+02,5.814069552376036398e+00,5.656854305839434716e+00,-4.912140177051357165e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.209621426013296741e+01,3.770579740845503238e+02,5.813578535877208964e+00,5.656854305839434716e+00,-4.937140177051357187e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.209798202706832626e+01,3.770679618993491999e+02,5.813085022409285152e+00,5.656854305839434716e+00,-4.962140177051357209e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.209974979400368511e+01,3.770779495904575924e+02,5.812589012003110511e+00,5.656854305839434716e+00,-4.987140177051357232e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.210151756093904396e+01,3.770879371572513037e+02,5.812090504689685133e+00,5.656854305839434716e+00,-5.012140177051357254e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.210328532787440281e+01,3.770979245991060793e+02,5.811589500500165428e+00,5.656854305839434716e+00,-5.037140177051357276e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.210505309480976166e+01,3.771079119153976649e+02,5.811085999465864127e+00,5.656854305839434716e+00,-5.062140177051357298e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.210682086174512051e+01,3.771178991055019196e+02,5.810580001618250279e+00,5.656854305839434716e+00,-5.087140177051357320e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.210858862868047936e+01,3.771278861687945891e+02,5.810071506988949253e+00,5.656854305839434716e+00,-5.112140177051357343e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.211035639561583821e+01,3.771378731046515327e+02,5.809560515609740960e+00,5.656854305839434716e+00,-5.137140177051357365e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.211212416255119706e+01,3.771478599124485527e+02,5.809047027512563410e+00,5.656854305839434716e+00,-5.162140177051357387e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.211389192948655591e+01,3.771578465915614515e+02,5.808531042729509153e+00,5.656854305839434716e+00,-5.187140177051357409e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.211565969642191476e+01,3.771678331413660317e+02,5.808012561292827058e+00,5.656854305839434716e+00,-5.212140177051357431e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.211742746335727361e+01,3.771778195612382092e+02,5.807491583234922317e+00,5.656854305839434716e+00,-5.237140177051357454e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.211919523029263246e+01,3.771878058505537865e+02,5.806968108588356436e+00,5.656854305839434716e+00,-5.262140177051357476e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.212096299722799131e+01,3.771977920086886229e+02,5.806442137385845470e+00,5.656854305839434716e+00,-5.287140177051357498e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.212273076416335016e+01,3.772077780350185776e+02,5.805913669660263565e+00,5.656854305839434716e+00,-5.312140177051357520e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.212449853109870901e+01,3.772177639289195668e+02,5.805382705444640301e+00,5.656854305839434716e+00,-5.337140177051357542e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.212626629803406786e+01,3.772277496897674496e+02,5.804849244772159800e+00,5.656854305839434716e+00,-5.362140177051357565e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.212803406496942671e+01,3.772377353169380854e+02,5.804313287676164279e+00,5.656854305839434716e+00,-5.387140177051357587e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.212980183190478556e+01,3.772477208098073902e+02,5.803774834190150500e+00,5.656854305839434716e+00,-5.412140177051357609e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.213156959884014441e+01,3.772577061677512802e+02,5.803233884347772431e+00,5.656854305839434716e+00,-5.437140177051357631e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.213333736577550326e+01,3.772676913901456714e+02,5.802690438182839472e+00,5.656854305839434716e+00,-5.462140177051357653e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.213510513271086211e+01,3.772776764763664801e+02,5.802144495729316453e+00,5.656854305839434716e+00,-5.487140177051357676e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.213687289964622096e+01,3.772876614257896790e+02,5.801596057021324526e+00,5.656854305839434716e+00,-5.512140177051357698e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.213864066658157981e+01,3.772976462377911844e+02,5.801045122093142048e+00,5.656854305839434716e+00,-5.537140177051357720e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.214040843351693866e+01,3.773076309117469123e+02,5.800491690979201920e+00,5.656854305839434716e+00,-5.562140177051357742e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.214217620045229751e+01,3.773176154470328356e+02,5.799935763714093362e+00,5.656854305839434716e+00,-5.587140177051357764e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.214394396738765636e+01,3.773275998430249274e+02,5.799377340332561914e+00,5.656854305839434716e+00,-5.612140177051357787e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.214571173432301521e+01,3.773375840990991605e+02,5.798816420869509436e+00,5.656854305839434716e+00,-5.637140177051357809e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.214747950125837406e+01,3.773475682146315080e+02,5.798253005359993217e+00,5.656854305839434716e+00,-5.662140177051357831e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.214924726819373291e+01,3.773575521889979996e+02,5.797687093839225980e+00,5.656854305839434716e+00,-5.687140177051357853e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.215101503512909176e+01,3.773675360215746082e+02,5.797118686342578542e+00,5.656854305839434716e+00,-5.712140177051357876e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.215278280206445061e+01,3.773775197117373637e+02,5.796547782905575374e+00,5.656854305839434716e+00,-5.737140177051357898e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.215455056899980946e+01,3.773875032588622389e+02,5.795974383563898158e+00,5.656854305839434716e+00,-5.762140177051357920e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.215631833593516831e+01,3.773974866623253206e+02,5.795398488353384003e+00,5.656854305839434716e+00,-5.787140177051357942e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.215808610287052716e+01,3.774074699215026385e+02,5.794820097310027229e+00,5.656854305839434716e+00,-5.812140177051357964e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.215985386980588601e+01,3.774174530357701656e+02,5.794239210469976697e+00,5.656854305839434716e+00,-5.837140177051357987e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.216162163674124486e+01,3.774274360045040453e+02,5.793655827869538477e+00,5.656854305839434716e+00,-5.862140177051358009e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.216338940367660371e+01,3.774374188270803074e+02,5.793069949545173181e+00,5.656854305839434716e+00,-5.887140177051358031e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.216515717061196256e+01,3.774474015028750387e+02,5.792481575533498628e+00,5.656854305839434716e+00,-5.912140177051358053e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.216692493754732141e+01,3.774573840312642687e+02,5.791890705871288070e+00,5.656854305839434716e+00,-5.937140177051358075e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.216869270448268026e+01,3.774673664116241412e+02,5.791297340595471077e+00,5.656854305839434716e+00,-5.962140177051358098e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.217046047141803911e+01,3.774773486433307426e+02,5.790701479743132651e+00,5.656854305839434716e+00,-5.987140177051358120e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.217222823835339796e+01,3.774873307257602164e+02,5.790103123351514114e+00,5.656854305839434716e+00,-6.012140177051358142e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.217399600528875681e+01,3.774973126582886493e+02,5.789502271458013105e+00,5.656854305839434716e+00,-6.037140177051358164e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.217576377222411566e+01,3.775072944402921848e+02,5.788898924100181809e+00,5.656854305839434716e+00,-6.062140177051358186e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.217753153915947451e+01,3.775172760711469095e+02,5.788293081315730504e+00,5.656854305839434716e+00,-6.087140177051358209e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.217929930609483336e+01,3.775272575502290238e+02,5.787684743142524013e+00,5.656854305839434716e+00,-6.112140177051358231e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.218106707303019220e+01,3.775372388769146710e+02,5.787073909618583478e+00,5.656854305839434716e+00,-6.137140177051358253e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.218283483996555105e+01,3.775472200505800515e+02,5.786460580782086360e+00,5.656854305839434716e+00,-6.162140177051358275e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.218460260690090990e+01,3.775572010706013089e+02,5.785844756671365552e+00,5.656854305839434716e+00,-6.187140177051358297e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.218637037383626875e+01,3.775671819363546433e+02,5.785226437324910265e+00,5.656854305839434716e+00,-6.212140177051358320e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.218813814077162760e+01,3.775771626472161984e+02,5.784605622781364254e+00,5.656854305839434716e+00,-6.237140177051358342e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.218990590770698645e+01,3.775871432025622312e+02,5.783982313079529369e+00,5.656854305839434716e+00,-6.262140177051357670e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.219167367464234530e+01,3.775971236017689421e+02,5.783356508258362894e+00,5.656854305839434716e+00,-6.287140177051357692e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.219344144157770415e+01,3.776071038442125882e+02,5.782728208356976651e+00,5.656854305839434716e+00,-6.312140177051357715e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.219520920851306300e+01,3.776170839292693699e+02,5.782097413414640563e+00,5.656854305839434716e+00,-6.337140177051357737e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.219697697544842185e+01,3.776270638563155444e+02,5.781464123470778205e+00,5.656854305839434716e+00,-6.362140177051357759e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.219874474238378070e+01,3.776370436247273688e+02,5.780828338564970359e+00,5.656854305839434716e+00,-6.387140177051357781e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.220051250931913955e+01,3.776470232338811002e+02,5.780190058736954128e+00,5.656854305839434716e+00,-6.412140177051357803e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.220228027625449840e+01,3.776570026831529958e+02,5.779549284026622047e+00,5.656854305839434716e+00,-6.437140177051357826e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.220404804318985725e+01,3.776669819719193697e+02,5.778906014474022079e+00,5.656854305839434716e+00,-6.462140177051357848e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.220581581012521610e+01,3.776769610995564790e+02,5.778260250119358510e+00,5.656854305839434716e+00,-6.487140177051357870e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.220758357706057495e+01,3.776869400654406945e+02,5.777611991002991942e+00,5.656854305839434716e+00,-6.512140177051357892e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.220935134399593380e+01,3.776969188689482735e+02,5.776961237165438412e+00,5.656854305839434716e+00,-6.537140177051357914e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.221111911093129265e+01,3.777068975094555867e+02,5.776307988647369385e+00,5.656854305839434716e+00,-6.562140177051357937e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.221288687786665150e+01,3.777168759863388914e+02,5.775652245489613534e+00,5.656854305839434716e+00,-6.587140177051357959e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.221465464480201035e+01,3.777268542989746152e+02,5.774994007733154966e+00,5.656854305839434716e+00,-6.612140177051357981e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.221642241173736920e+01,3.777368324467390721e+02,5.774333275419133216e+00,5.656854305839434716e+00,-6.637140177051358003e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.221819017867272805e+01,3.777468104290086330e+02,5.773670048588845027e+00,5.656854305839434716e+00,-6.662140177051358025e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.221995794560808690e+01,3.777567882451596688e+02,5.773004327283740800e+00,5.656854305839434716e+00,-6.687140177051358048e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.222172571254344575e+01,3.777667658945685503e+02,5.772336111545429027e+00,5.656854305839434716e+00,-6.712140177051358070e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.222349347947880460e+01,3.777767433766117051e+02,5.771665401415672747e+00,5.656854305839434716e+00,-6.737140177051358092e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.222526124641416345e+01,3.777867206906655611e+02,5.770992196936391316e+00,5.656854305839434716e+00,-6.762140177051358114e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.222702901334952230e+01,3.777966978361064889e+02,5.770316498149659523e+00,5.656854305839434716e+00,-6.787140177051358136e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.222879678028488115e+01,3.778066748123109733e+02,5.769638305097709363e+00,5.656854305839434716e+00,-6.812140177051358159e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.223056454722024000e+01,3.778166516186553849e+02,5.768957617822927375e+00,5.656854305839434716e+00,-6.837140177051358181e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.223233231415559885e+01,3.778266282545162085e+02,5.768274436367856417e+00,5.656854305839434716e+00,-6.862140177051358203e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.223410008109095770e+01,3.778366047192698716e+02,5.767588760775195666e+00,5.656854305839434716e+00,-6.887140177051358225e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.223586784802631655e+01,3.778465810122929156e+02,5.766900591087800620e+00,5.656854305839434716e+00,-6.912140177051358247e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.223763561496167540e+01,3.778565571329617683e+02,5.766209927348680431e+00,5.656854305839434716e+00,-6.937140177051358270e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.223940338189703425e+01,3.778665330806529141e+02,5.765516769601002345e+00,5.656854305839434716e+00,-6.962140177051358292e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.224117114883239310e+01,3.778765088547428945e+02,5.764821117888089042e+00,5.656854305839434716e+00,-6.987140177051358314e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.224293891576775195e+01,3.778864844546081940e+02,5.764122972253417743e+00,5.656854305839434716e+00,-7.012140177051358336e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.224470668270311080e+01,3.778964598796253540e+02,5.763422332740623766e+00,5.656854305839434716e+00,-7.037140177051358358e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.224647444963846965e+01,3.779064351291709158e+02,5.762719199393496083e+00,5.656854305839434716e+00,-7.062140177051358381e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.224824221657382850e+01,3.779164102026214209e+02,5.762013572255980876e+00,5.656854305839434716e+00,-7.087140177051358403e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.225000998350918735e+01,3.779263850993534106e+02,5.761305451372179753e+00,5.656854305839434716e+00,-7.112140177051358425e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.225177775044454620e+01,3.779363598187434832e+02,5.760594836786350648e+00,5.656854305839434716e+00,-7.137140177051358447e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.225354551737990505e+01,3.779463343601681800e+02,5.759881728542906920e+00,5.656854305839434716e+00,-7.162140177051358469e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.225531328431526390e+01,3.779563087230040992e+02,5.759166126686417364e+00,5.656854305839434716e+00,-7.187140177051358492e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.225708105125062275e+01,3.779662829066278960e+02,5.758448031261607092e+00,5.656854305839434716e+00,-7.212140177051358514e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.225884881818598160e+01,3.779762569104161116e+02,5.757727442313357535e+00,5.656854305839434716e+00,-7.237140177051358536e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.226061658512134045e+01,3.779862307337454013e+02,5.757004359886705558e+00,5.656854305839434716e+00,-7.262140177051358558e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.226238435205669930e+01,3.779962043759924200e+02,5.756278784026843454e+00,5.656854305839434716e+00,-7.287140177051358580e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.226415211899205815e+01,3.780061778365338228e+02,5.755550714779119836e+00,5.656854305839434716e+00,-7.312140177051358603e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.226591988592741700e+01,3.780161511147462079e+02,5.754820152189038751e+00,5.656854305839434716e+00,-7.337140177051358625e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.226768765286277585e+01,3.780261242100062873e+02,5.754087096302260562e+00,5.656854305839434716e+00,-7.362140177051358647e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.226945541979813470e+01,3.780360971216907728e+02,5.753351547164601953e+00,5.656854305839434716e+00,-7.387140177051358669e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.227122318673349355e+01,3.780460698491763196e+02,5.752613504822034152e+00,5.656854305839434716e+00,-7.412140177051358692e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.227299095366885240e+01,3.780560423918396395e+02,5.751872969320684703e+00,5.656854305839434716e+00,-7.437140177051358714e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.227475872060421125e+01,3.780660147490574445e+02,5.751129940706836585e+00,5.656854305839434716e+00,-7.462140177051358736e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.227652648753957010e+01,3.780759869202064465e+02,5.750384419026929983e+00,5.656854305839434716e+00,-7.487140177051358758e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.227829425447492895e+01,3.780859589046634142e+02,5.749636404327559625e+00,5.656854305839434716e+00,-7.512140177051358780e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.228006202141028780e+01,3.780959307018050595e+02,5.748885896655476557e+00,5.656854305839434716e+00,-7.537140177051358803e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.228182978834564665e+01,3.781059023110081512e+02,5.748132896057587260e+00,5.656854305839434716e+00,-7.562140177051358825e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.228359755528100550e+01,3.781158737316495149e+02,5.747377402580954531e+00,5.656854305839434716e+00,-7.587140177051358847e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.228536532221636435e+01,3.781258449631059193e+02,5.746619416272796599e+00,5.656854305839434716e+00,-7.612140177051358869e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.228713308915172320e+01,3.781358160047541332e+02,5.745858937180487125e+00,5.656854305839434716e+00,-7.637140177051358891e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.228890085608708205e+01,3.781457868559709823e+02,5.745095965351556977e+00,5.656854305839434716e+00,-7.662140177051358914e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.229066862302244090e+01,3.781557575161332920e+02,5.744330500833691566e+00,5.656854305839434716e+00,-7.687140177051358936e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.229243638995779975e+01,3.781657279846178881e+02,5.743562543674731735e+00,5.656854305839434716e+00,-7.712140177051358958e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.229420415689315860e+01,3.781756982608015960e+02,5.742792093922675534e+00,5.656854305839434716e+00,-7.737140177051358980e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.229597192382851745e+01,3.781856683440612983e+02,5.742019151625676443e+00,5.656854305839434716e+00,-7.762140177051359002e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.229773969076387630e+01,3.781956382337738773e+02,5.741243716832042487e+00,5.656854305839434716e+00,-7.787140177051359025e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.229950745769923515e+01,3.782056079293162156e+02,5.740465789590238899e+00,5.656854305839434716e+00,-7.812140177051359047e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.230127522463459400e+01,3.782155774300651956e+02,5.739685369948885452e+00,5.656854305839434716e+00,-7.837140177051359069e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.230304299156995285e+01,3.782255467353976996e+02,5.738902457956759129e+00,5.656854305839434716e+00,-7.862140177051359091e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.230481075850531170e+01,3.782355158446906671e+02,5.738117053662791456e+00,5.656854305839434716e+00,-7.887140177051359113e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.230657852544067055e+01,3.782454847573210373e+02,5.737329157116070277e+00,5.656854305839434716e+00,-7.912140177051359136e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.230834629237602940e+01,3.782554534726657494e+02,5.736538768365839758e+00,5.656854305839434716e+00,-7.937140177051359158e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.231011405931138825e+01,3.782654219901017427e+02,5.735745887461498604e+00,5.656854305839434716e+00,-7.962140177051359180e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.231188182624674710e+01,3.782753903090060135e+02,5.734950514452601844e+00,5.656854305839434716e+00,-7.987140177051359202e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.231364959318210595e+01,3.782853584287555009e+02,5.734152649388859935e+00,5.656854305839434716e+00,-8.012140177051359224e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.231541736011746480e+01,3.782953263487272011e+02,5.733352292320140542e+00,5.656854305839434716e+00,-8.037140177051359247e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.231718512705282365e+01,3.783052940682981671e+02,5.732549443296464986e+00,5.656854305839434716e+00,-8.062140177051359269e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.231895289398818250e+01,3.783152615868453950e+02,5.731744102368011795e+00,5.656854305839434716e+00,-8.087140177051359291e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.232072066092354135e+01,3.783252289037458809e+02,5.730936269585114928e+00,5.656854305839434716e+00,-8.112140177051359313e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.232248842785890020e+01,3.783351960183766778e+02,5.730125944998263776e+00,5.656854305839434716e+00,-8.137140177051359335e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.232425619479425905e+01,3.783451629301148955e+02,5.729313128658103160e+00,5.656854305839434716e+00,-8.162140177051359358e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.232602396172961789e+01,3.783551296383375302e+02,5.728497820615434222e+00,5.656854305839434716e+00,-8.187140177051359380e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.232779172866497674e+01,3.783650961424216916e+02,5.727680020921214421e+00,5.656854305839434716e+00,-8.212140177051359402e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.232955949560033559e+01,3.783750624417444897e+02,5.726859729626555762e+00,5.656854305839434716e+00,-8.237140177051359424e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.233132726253569444e+01,3.783850285356830341e+02,5.726036946782726567e+00,5.656854305839434716e+00,-8.262140177051359446e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.233309502947105329e+01,3.783949944236144347e+02,5.725211672441150590e+00,5.656854305839434716e+00,-8.287140177051359469e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.233486279640641214e+01,3.784049601049158014e+02,5.724383906653407017e+00,5.656854305839434716e+00,-8.312140177051359491e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.233663056334177099e+01,3.784149255789643007e+02,5.723553649471232241e+00,5.656854305839434716e+00,-8.337140177051359513e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.233839833027712984e+01,3.784248908451370994e+02,5.722720900946516309e+00,5.656854305839434716e+00,-8.362140177051359535e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.234016609721248869e+01,3.784348559028113641e+02,5.721885661131306478e+00,5.656854305839434716e+00,-8.387140177051359557e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.234193386414784754e+01,3.784448207513642615e+02,5.721047930077805432e+00,5.656854305839434716e+00,-8.412140177051359580e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.234370163108320639e+01,3.784547853901730150e+02,5.720207707838371292e+00,5.656854305839434716e+00,-8.437140177051359602e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.234546939801856524e+01,3.784647498186147914e+02,5.719364994465517604e+00,5.656854305839434716e+00,-8.462140177051359624e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.234723716495392409e+01,3.784747140360668141e+02,5.718519790011914239e+00,5.656854305839434716e+00,-8.487140177051359646e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.234900493188928294e+01,3.784846780419063634e+02,5.717672094530386495e+00,5.656854305839434716e+00,-8.512140177051359669e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.235077269882464179e+01,3.784946418355106630e+02,5.716821908073915104e+00,5.656854305839434716e+00,-8.537140177051359691e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.235254046576000064e+01,3.785046054162569931e+02,5.715969230695637116e+00,5.656854305839434716e+00,-8.562140177051359713e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.235430823269535949e+01,3.785145687835226340e+02,5.715114062448845011e+00,5.656854305839434716e+00,-8.587140177051359735e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.235607599963071834e+01,3.785245319366848662e+02,5.714256403386986705e+00,5.656854305839434716e+00,-8.612140177051359757e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.235784376656607719e+01,3.785344948751209699e+02,5.713396253563665539e+00,5.656854305839434716e+00,-8.637140177051359780e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.235961153350143604e+01,3.785444575982082824e+02,5.712533613032640289e+00,5.656854305839434716e+00,-8.662140177051359802e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.236137930043679489e+01,3.785544201053241409e+02,5.711668481847826939e+00,5.656854305839434716e+00,-8.687140177051359824e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.236314706737215374e+01,3.785643823958458256e+02,5.710800860063296014e+00,5.656854305839434716e+00,-8.712140177051359846e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.236491483430751259e+01,3.785743444691507875e+02,5.709930747733273471e+00,5.656854305839434716e+00,-8.737140177051359868e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.236668260124287144e+01,3.785843063246163638e+02,5.709058144912141586e+00,5.656854305839434716e+00,-8.762140177051359891e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.236845036817823029e+01,3.785942679616198916e+02,5.708183051654438067e+00,5.656854305839434716e+00,-8.787140177051359913e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.237021813511358914e+01,3.786042293795388218e+02,5.707305468014856942e+00,5.656854305839434716e+00,-8.812140177051359935e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.237198590204894799e+01,3.786141905777505485e+02,5.706425394048245892e+00,5.656854305839434716e+00,-8.837140177051359957e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.237375366898430684e+01,3.786241515556325226e+02,5.705542829809610694e+00,5.656854305839434716e+00,-8.862140177051359979e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.237552143591966569e+01,3.786341123125621380e+02,5.704657775354110782e+00,5.656854305839434716e+00,-8.887140177051360002e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.237728920285502454e+01,3.786440728479168456e+02,5.703770230737062796e+00,5.656854305839434716e+00,-8.912140177051360024e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.237905696979038339e+01,3.786540331610741532e+02,5.702880196013937919e+00,5.656854305839434716e+00,-8.937140177051360046e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.238082473672574224e+01,3.786639932514115117e+02,5.701987671240362765e+00,5.656854305839434716e+00,-8.962140177051360068e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.238259250366110109e+01,3.786739531183064287e+02,5.701092656472121156e+00,5.656854305839434716e+00,-8.987140177051360090e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.238436027059645994e+01,3.786839127611364120e+02,5.700195151765150570e+00,5.656854305839434716e+00,-9.012140177051360113e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.238612803753181879e+01,3.786938721792789693e+02,5.699295157175545690e+00,5.656854305839434716e+00,-9.037140177051360135e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.238789580446717764e+01,3.787038313721116651e+02,5.698392672759555744e+00,5.656854305839434716e+00,-9.062140177051360157e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.238966357140253649e+01,3.787137903390120641e+02,5.697487698573586279e+00,5.656854305839434716e+00,-9.087140177051360179e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.239143133833789534e+01,3.787237490793576740e+02,5.696580234674198273e+00,5.656854305839434716e+00,-9.112140177051360201e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.239319910527325419e+01,3.787337075925261161e+02,5.695670281118107248e+00,5.656854305839434716e+00,-9.137140177051360224e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.239496687220861304e+01,3.787436658778949550e+02,5.694757837962186819e+00,5.656854305839434716e+00,-9.162140177051360246e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.239673463914397189e+01,3.787536239348418121e+02,5.693842905263463372e+00,5.656854305839434716e+00,-9.187140177051360268e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.239850240607933074e+01,3.787635817627443089e+02,5.692925483079121385e+00,5.656854305839434716e+00,-9.212140177051360290e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.240027017301468959e+01,3.787735393609800667e+02,5.692005571466498992e+00,5.656854305839434716e+00,-9.237140177051360312e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.240203793995004844e+01,3.787834967289267638e+02,5.691083170483090647e+00,5.656854305839434716e+00,-9.262140177051360335e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.240380570688540729e+01,3.787934538659620216e+02,5.690158280186546236e+00,5.656854305839434716e+00,-9.287140177051360357e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.240557347382076614e+01,3.788034107714635752e+02,5.689230900634671961e+00,5.656854305839434716e+00,-9.312140177051360379e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.240734124075612499e+01,3.788133674448091028e+02,5.688301031885429460e+00,5.656854305839434716e+00,-9.337140177051360401e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.240910900769148384e+01,3.788233238853762828e+02,5.687368673996934909e+00,5.656854305839434716e+00,-9.362140177051360423e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.241087677462684269e+01,3.788332800925428501e+02,5.686433827027459920e+00,5.656854305839434716e+00,-9.387140177051360446e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.241264454156220154e+01,3.788432360656865399e+02,5.685496491035433309e+00,5.656854305839434716e+00,-9.412140177051360468e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.241441230849756039e+01,3.788531918041851441e+02,5.684556666079438436e+00,5.656854305839434716e+00,-9.437140177051360490e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.241618007543291924e+01,3.788631473074163978e+02,5.683614352218214982e+00,5.656854305839434716e+00,-9.462140177051360512e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.241794784236827809e+01,3.788731025747580361e+02,5.682669549510656282e+00,5.656854305839434716e+00,-9.487140177051360534e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.241971560930363694e+01,3.788830576055879078e+02,5.681722258015813765e+00,5.656854305839434716e+00,-9.512140177051360557e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.242148337623899579e+01,3.788930123992838048e+02,5.680772477792892516e+00,5.656854305839434716e+00,-9.537140177051360579e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.242325114317435464e+01,3.789029669552235760e+02,5.679820208901253942e+00,5.656854305839434716e+00,-9.562140177051360601e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.242501891010971349e+01,3.789129212727850700e+02,5.678865451400413988e+00,5.656854305839434716e+00,-9.587140177051360623e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.242678667704507234e+01,3.789228753513460788e+02,5.677908205350045812e+00,5.656854305839434716e+00,-9.612140177051360646e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.242855444398043119e+01,3.789328291902845081e+02,5.676948470809977998e+00,5.656854305839434716e+00,-9.637140177051360668e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.243032221091579004e+01,3.789427827889782634e+02,5.675986247840192789e+00,5.656854305839434716e+00,-9.662140177051360690e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.243208997785114889e+01,3.789527361468052504e+02,5.675021536500829633e+00,5.656854305839434716e+00,-9.687140177051360712e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.243385774478650774e+01,3.789626892631433179e+02,5.674054336852182523e+00,5.656854305839434716e+00,-9.712140177051360734e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.243562551172186659e+01,3.789726421373704852e+02,5.673084648954701770e+00,5.656854305839434716e+00,-9.737140177051360757e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.243739327865722544e+01,3.789825947688646579e+02,5.672112472868993116e+00,5.656854305839434716e+00,-9.762140177051360779e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.243916104559258429e+01,3.789925471570037985e+02,5.671137808655817736e+00,5.656854305839434716e+00,-9.787140177051360801e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.244092881252794314e+01,3.790024993011658694e+02,5.670160656376091346e+00,5.656854305839434716e+00,-9.812140177051360823e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.244269657946330199e+01,3.790124512007288331e+02,5.669181016090886871e+00,5.656854305839434716e+00,-9.837140177051360845e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.244446434639866084e+01,3.790224028550707658e+02,5.668198887861430890e+00,5.656854305839434716e+00,-9.862140177051360868e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.244623211333401969e+01,3.790323542635696299e+02,5.667214271749107191e+00,5.656854305839434716e+00,-9.887140177051360890e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.244799988026937854e+01,3.790423054256035016e+02,5.666227167815453214e+00,5.656854305839434716e+00,-9.912140177051360912e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.244976764720473739e+01,3.790522563405504002e+02,5.665237576122164498e+00,5.656854305839434716e+00,-9.937140177051360934e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.245153541414009624e+01,3.790622070077884018e+02,5.664245496731089347e+00,5.656854305839434716e+00,-9.962140177051360956e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.245330318107545509e+01,3.790721574266956395e+02,5.663250929704233272e+00,5.656854305839434716e+00,-9.987140177051360979e-02,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.245507094801081394e+01,3.790821075966501326e+02,5.662253875103756329e+00,5.656854305839434716e+00,-1.001214017705136100e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.245683871494617279e+01,3.790920575170300708e+02,5.661254332991974891e+00,5.656854305839434716e+00,-1.003714017705136102e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.245860648188153164e+01,3.791020071872135304e+02,5.660252303431359877e+00,5.656854305839434716e+00,-1.006214017705136105e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.246037424881689049e+01,3.791119566065787012e+02,5.659247786484538523e+00,5.656854305839434716e+00,-1.008714017705136107e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.246214201575224934e+01,3.791219057745037162e+02,5.658240782214292608e+00,5.656854305839434716e+00,-1.011214017705136109e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.246390978268760819e+01,3.791318546903667084e+02,5.657231290683560232e+00,5.656854305839434716e+00,-1.013714017705136111e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.246567754962296704e+01,3.791418033535459244e+02,5.656219311955434925e+00,5.656854305839434716e+00,-1.016214017705136113e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.246744531655832589e+01,3.791517517634195542e+02,5.655204846093164761e+00,5.656854305839434716e+00,-1.018714017705136116e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.246921308349368474e+01,3.791616999193658444e+02,5.654187893160154132e+00,5.656854305839434716e+00,-1.021214017705136118e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.247098085042904358e+01,3.791716478207630416e+02,5.653168453219962863e+00,5.656854305839434716e+00,-1.023714017705136120e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.247274861736440243e+01,3.791815954669893927e+02,5.652146526336305321e+00,5.656854305839434716e+00,-1.026214017705136122e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.247451638429976128e+01,3.791915428574231441e+02,5.651122112573052192e+00,5.656854305839434716e+00,-1.028714017705136125e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.247628415123512013e+01,3.792014899914425996e+02,5.650095211994229594e+00,5.656854305839434716e+00,-1.031214017705136127e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.247805191817047898e+01,3.792114368684260626e+02,5.649065824664019075e+00,5.656854305839434716e+00,-1.033714017705136129e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.247981968510583783e+01,3.792213834877518934e+02,5.648033950646756729e+00,5.656854305839434716e+00,-1.036214017705136131e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.248158745204119668e+01,3.792313298487983388e+02,5.646999590006934966e+00,5.656854305839434716e+00,-1.038714017705136133e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.248335521897655553e+01,3.792412759509438160e+02,5.645962742809200741e+00,5.656854305839434716e+00,-1.041214017705136136e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.248512298591191438e+01,3.792512217935666854e+02,5.644923409118358215e+00,5.656854305839434716e+00,-1.043714017705136138e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.248689075284727323e+01,3.792611673760453641e+02,5.643881588999365206e+00,5.656854305839434716e+00,-1.046214017705136140e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.248865851978263208e+01,3.792711126977582126e+02,5.642837282517334963e+00,5.656854305839434716e+00,-1.048714017705136142e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.249042628671799093e+01,3.792810577580836480e+02,5.641790489737537051e+00,5.656854305839434716e+00,-1.051214017705136144e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.249219405365334978e+01,3.792910025564000875e+02,5.640741210725395582e+00,5.656854305839434716e+00,-1.053714017705136147e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.249396182058870863e+01,3.793009470920860053e+02,5.639689445546490987e+00,5.656854305839434716e+00,-1.056214017705136149e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.249572958752406748e+01,3.793108913645198754e+02,5.638635194266558237e+00,5.656854305839434716e+00,-1.058714017705136151e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.249749735445942633e+01,3.793208353730801718e+02,5.637578456951488626e+00,5.656854305839434716e+00,-1.061214017705136153e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.249926512139478518e+01,3.793307791171453687e+02,5.636519233667327988e+00,5.656854305839434716e+00,-1.063714017705136156e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.250103288833014403e+01,3.793407225960939968e+02,5.635457524480277591e+00,5.656854305839434716e+00,-1.066214017705136158e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.250280065526550288e+01,3.793506658093045871e+02,5.634393329456694133e+00,5.656854305839434716e+00,-1.068714017705136160e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.250456842220086173e+01,3.793606087561557274e+02,5.633326648663090630e+00,5.656854305839434716e+00,-1.071214017705136162e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.250633618913622058e+01,3.793705514360259485e+02,5.632257482166133755e+00,5.656854305839434716e+00,-1.073714017705136164e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.250810395607157943e+01,3.793804938482938383e+02,5.631185830032646500e+00,5.656854305839434716e+00,-1.076214017705136167e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.250987172300693828e+01,3.793904359923379843e+02,5.630111692329607287e+00,5.656854305839434716e+00,-1.078714017705136169e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.251163948994229713e+01,3.794003778675370313e+02,5.629035069124149970e+00,5.656854305839434716e+00,-1.081214017705136171e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.251340725687765598e+01,3.794103194732696238e+02,5.627955960483562947e+00,5.656854305839434716e+00,-1.083714017705136173e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.251517502381301483e+01,3.794202608089143496e+02,5.626874366475290934e+00,5.656854305839434716e+00,-1.086214017705136176e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.251694279074837368e+01,3.794302018738499100e+02,5.625790287166933190e+00,5.656854305839434716e+00,-1.088714017705136178e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.251871055768373253e+01,3.794401426674550066e+02,5.624703722626245295e+00,5.656854305839434716e+00,-1.091214017705136180e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.252047832461909138e+01,3.794500831891082839e+02,5.623614672921137370e+00,5.656854305839434716e+00,-1.093714017705136182e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.252224609155445023e+01,3.794600234381885002e+02,5.622523138119674080e+00,5.656854305839434716e+00,-1.096214017705136184e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.252401385848980908e+01,3.794699634140744138e+02,5.621429118290077298e+00,5.656854305839434716e+00,-1.098714017705136187e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.252578162542516793e+01,3.794799031161447260e+02,5.620332613500723440e+00,5.656854305839434716e+00,-1.101214017705136189e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.252754939236052678e+01,3.794898425437782521e+02,5.619233623820143464e+00,5.656854305839434716e+00,-1.103714017705136191e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.252931715929588563e+01,3.794997816963537502e+02,5.618132149317024648e+00,5.656854305839434716e+00,-1.106214017705136193e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.253108492623124448e+01,3.795097205732500356e+02,5.617028190060208814e+00,5.656854305839434716e+00,-1.108714017705136196e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.253285269316660333e+01,3.795196591738459233e+02,5.615921746118693214e+00,5.656854305839434716e+00,-1.111214017705136198e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.253462046010196218e+01,3.795295974975202284e+02,5.614812817561631419e+00,5.656854305839434716e+00,-1.113714017705136200e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.253638822703732103e+01,3.795395355436518230e+02,5.613701404458330657e+00,5.656854305839434716e+00,-1.116214017705136202e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.253815599397267988e+01,3.795494733116195789e+02,5.612587506878254473e+00,5.656854305839434716e+00,-1.118714017705136204e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.253992376090803873e+01,3.795594108008023682e+02,5.611471124891021844e+00,5.656854305839434716e+00,-1.121214017705136207e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.254169152784339758e+01,3.795693480105791195e+02,5.610352258566406292e+00,5.656854305839434716e+00,-1.123714017705136209e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.254345929477875643e+01,3.795792849403287619e+02,5.609230907974336766e+00,5.656854305839434716e+00,-1.126214017705136211e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.254522706171411528e+01,3.795892215894302240e+02,5.608107073184897651e+00,5.656854305839434716e+00,-1.128714017705136213e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.254699482864947413e+01,3.795991579572624914e+02,5.606980754268328759e+00,5.656854305839434716e+00,-1.131214017705136216e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.254876259558483298e+01,3.796090940432045500e+02,5.605851951295025337e+00,5.656854305839434716e+00,-1.133714017705136218e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.255053036252019183e+01,3.796190298466353283e+02,5.604720664335537172e+00,5.656854305839434716e+00,-1.136214017705136220e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.255229812945555068e+01,3.796289653669338691e+02,5.603586893460570373e+00,5.656854305839434716e+00,-1.138714017705136222e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.255406589639090953e+01,3.796389006034792146e+02,5.602450638740984701e+00,5.656854305839434716e+00,-1.141214017705136224e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.255583366332626838e+01,3.796488355556504075e+02,5.601311900247797126e+00,5.656854305839434716e+00,-1.143714017705136227e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.255760143026162723e+01,3.796587702228265471e+02,5.600170678052178275e+00,5.656854305839434716e+00,-1.146214017705136229e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.255936919719698608e+01,3.796687046043866758e+02,5.599026972225454202e+00,5.656854305839434716e+00,-1.148714017705136231e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.256113696413234493e+01,3.796786386997098930e+02,5.597880782839106395e+00,5.656854305839434716e+00,-1.151214017705136233e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.256290473106770378e+01,3.796885725081752980e+02,5.596732109964772661e+00,5.656854305839434716e+00,-1.153714017705136236e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.256467249800306263e+01,3.796985060291621039e+02,5.595580953674244462e+00,5.656854305839434716e+00,-1.156214017705136238e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.256644026493842148e+01,3.797084392620494100e+02,5.594427314039468691e+00,5.656854305839434716e+00,-1.158714017705136240e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.256820803187378033e+01,3.797183722062163724e+02,5.593271191132548559e+00,5.656854305839434716e+00,-1.161214017705136242e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.256997579880913918e+01,3.797283048610422043e+02,5.592112585025740934e+00,5.656854305839434716e+00,-1.163714017705136244e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.257174356574449803e+01,3.797382372259061185e+02,5.590951495791459003e+00,5.656854305839434716e+00,-1.166214017705136247e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.257351133267985688e+01,3.797481693001873282e+02,5.589787923502271383e+00,5.656854305839434716e+00,-1.168714017705136249e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.257527909961521573e+01,3.797581010832651032e+02,5.588621868230901235e+00,5.656854305839434716e+00,-1.171214017705136251e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.257704686655057458e+01,3.797680325745187133e+02,5.587453330050226263e+00,5.656854305839434716e+00,-1.173714017705136253e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.257881463348593343e+01,3.797779637733274285e+02,5.586282309033280491e+00,5.656854305839434716e+00,-1.176214017705136256e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.258058240042129228e+01,3.797878946790705186e+02,5.585108805253253372e+00,5.656854305839434716e+00,-1.178714017705136258e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.258235016735665113e+01,3.797978252911273103e+02,5.583932818783488017e+00,5.656854305839434716e+00,-1.181214017705136260e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.258411793429200998e+01,3.798077556088771871e+02,5.582754349697483853e+00,5.656854305839434716e+00,-1.183714017705136262e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.258588570122736883e+01,3.798176856316994758e+02,5.581573398068894853e+00,5.656854305839434716e+00,-1.186214017705136264e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.258765346816272768e+01,3.798276153589735600e+02,5.580389963971531309e+00,5.656854305839434716e+00,-1.188714017705136267e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.258942123509808653e+01,3.798375447900787663e+02,5.579204047479357165e+00,5.656854305839434716e+00,-1.191214017705136269e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.259118900203344538e+01,3.798474739243945919e+02,5.578015648666492687e+00,5.656854305839434716e+00,-1.193714017705136271e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.259295676896880423e+01,3.798574027613004205e+02,5.576824767607212685e+00,5.656854305839434716e+00,-1.196214017705136273e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.259472453590416308e+01,3.798673313001756924e+02,5.575631404375946509e+00,5.656854305839434716e+00,-1.198714017705136275e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.259649230283952193e+01,3.798772595403999048e+02,5.574435559047280719e+00,5.656854305839434716e+00,-1.201214017705136278e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.259826006977488078e+01,3.798871874813525551e+02,5.573237231695954641e+00,5.656854305839434716e+00,-1.203714017705136280e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.260002783671023963e+01,3.798971151224130836e+02,5.572036422396863919e+00,5.656854305839434716e+00,-1.206214017705136282e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.260179560364559848e+01,3.799070424629611011e+02,5.570833131225059631e+00,5.656854305839434716e+00,-1.208714017705136284e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.260356337058095733e+01,3.799169695023760482e+02,5.569627358255746508e+00,5.656854305839434716e+00,-1.211214017705136287e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.260533113751631618e+01,3.799268962400375926e+02,5.568419103564285599e+00,5.656854305839434716e+00,-1.213714017705136289e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.260709890445167503e+01,3.799368226753252316e+02,5.567208367226193388e+00,5.656854305839434716e+00,-1.216214017705136291e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.260886667138703388e+01,3.799467488076185759e+02,5.565995149317140900e+00,5.656854305839434716e+00,-1.218714017705136293e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.261063443832239273e+01,3.799566746362972367e+02,5.564779449912953702e+00,5.656854305839434716e+00,-1.221214017705136295e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.261240220525775158e+01,3.799666001607408816e+02,5.563561269089613681e+00,5.656854305839434716e+00,-1.223714017705136298e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.261416997219311042e+01,3.799765253803291785e+02,5.562340606923256381e+00,5.656854305839434716e+00,-1.226214017705136300e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.261593773912846927e+01,3.799864502944417382e+02,5.561117463490173662e+00,5.656854305839434716e+00,-1.228714017705136302e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.261770550606382812e+01,3.799963749024582853e+02,5.559891838866811931e+00,5.656854305839434716e+00,-1.231214017705136304e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.261947327299918697e+01,3.800062992037585445e+02,5.558663733129773021e+00,5.656854305839434716e+00,-1.233714017705136307e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.262124103993454582e+01,3.800162231977222405e+02,5.557433146355812426e+00,5.656854305839434716e+00,-1.236214017705136309e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.262300880686990467e+01,3.800261468837291545e+02,5.556200078621842842e+00,5.656854305839434716e+00,-1.238714017705136311e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.262477657380526352e+01,3.800360702611590114e+02,5.554964530004930623e+00,5.656854305839434716e+00,-1.241214017705136313e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.262654434074062237e+01,3.800459933293915924e+02,5.553726500582297554e+00,5.656854305839434716e+00,-1.243714017705136315e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.262831210767598122e+01,3.800559160878067360e+02,5.552485990431320850e+00,5.656854305839434716e+00,-1.246214017705136318e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.263007987461134007e+01,3.800658385357842803e+02,5.551242999629532271e+00,5.656854305839434716e+00,-1.248714017705136320e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.263184764154669892e+01,3.800757606727040070e+02,5.549997528254619006e+00,5.656854305839434716e+00,-1.251214017705136183e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.263361540848205777e+01,3.800856824979458679e+02,5.548749576384421900e+00,5.656854305839434716e+00,-1.253714017705136186e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.263538317541741662e+01,3.800956040108897014e+02,5.547499144096939006e+00,5.656854305839434716e+00,-1.256214017705136188e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.263715094235277547e+01,3.801055252109154026e+02,5.546246231470322030e+00,5.656854305839434716e+00,-1.258714017705136190e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.263891870928813432e+01,3.801154460974029234e+02,5.544990838582878112e+00,5.656854305839434716e+00,-1.261214017705136192e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.264068647622349317e+01,3.801253666697322160e+02,5.543732965513068933e+00,5.656854305839434716e+00,-1.263714017705136194e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.264245424315885202e+01,3.801352869272831754e+02,5.542472612339511606e+00,5.656854305839434716e+00,-1.266214017705136197e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.264422201009421087e+01,3.801452068694358672e+02,5.541209779140978675e+00,5.656854305839434716e+00,-1.268714017705136199e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.264598977702956972e+01,3.801551264955702436e+02,5.539944465996397227e+00,5.656854305839434716e+00,-1.271214017705136201e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.264775754396492857e+01,3.801650458050663701e+02,5.538676672984848892e+00,5.656854305839434716e+00,-1.273714017705136203e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.264952531090028742e+01,3.801749647973042556e+02,5.537406400185570732e+00,5.656854305839434716e+00,-1.276214017705136206e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.265129307783564627e+01,3.801848834716639658e+02,5.536133647677955238e+00,5.656854305839434716e+00,-1.278714017705136208e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.265306084477100512e+01,3.801948018275256231e+02,5.534858415541548560e+00,5.656854305839434716e+00,-1.281214017705136210e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.265482861170636397e+01,3.802047198642692933e+02,5.533580703856054051e+00,5.656854305839434716e+00,-1.283714017705136212e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.265659637864172282e+01,3.802146375812750989e+02,5.532300512701327833e+00,5.656854305839434716e+00,-1.286214017705136214e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.265836414557708167e+01,3.802245549779232192e+02,5.531017842157381459e+00,5.656854305839434716e+00,-1.288714017705136217e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.266013191251244052e+01,3.802344720535937768e+02,5.529732692304382802e+00,5.656854305839434716e+00,-1.291214017705136219e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.266189967944779937e+01,3.802443888076669509e+02,5.528445063222653388e+00,5.656854305839434716e+00,-1.293714017705136221e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.266366744638315822e+01,3.802543052395229779e+02,5.527154954992669289e+00,5.656854305839434716e+00,-1.296214017705136223e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.266543521331851707e+01,3.802642213485420370e+02,5.525862367695062893e+00,5.656854305839434716e+00,-1.298714017705136226e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.266720298025387592e+01,3.802741371341044214e+02,5.524567301410621134e+00,5.656854305839434716e+00,-1.301214017705136228e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.266897074718923477e+01,3.802840525955903672e+02,5.523269756220285487e+00,5.656854305839434716e+00,-1.303714017705136230e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.267073851412459362e+01,3.802939677323801675e+02,5.521969732205151971e+00,5.656854305839434716e+00,-1.306214017705136232e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.267250628105995247e+01,3.803038825438541153e+02,5.520667229446472923e+00,5.656854305839434716e+00,-1.308714017705136234e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.267427404799531132e+01,3.803137970293925036e+02,5.519362248025654338e+00,5.656854305839434716e+00,-1.311214017705136237e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.267604181493067017e+01,3.803237111883757393e+02,5.518054788024257640e+00,5.656854305839434716e+00,-1.313714017705136239e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.267780958186602902e+01,3.803336250201841722e+02,5.516744849523999683e+00,5.656854305839434716e+00,-1.316214017705136241e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.267957734880138787e+01,3.803435385241981521e+02,5.515432432606750979e+00,5.656854305839434716e+00,-1.318714017705136243e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.268134511573674672e+01,3.803534516997981427e+02,5.514117537354537468e+00,5.656854305839434716e+00,-1.321214017705136246e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.268311288267210557e+01,3.803633645463644939e+02,5.512800163849539636e+00,5.656854305839434716e+00,-1.323714017705136248e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.268488064960746442e+01,3.803732770632777260e+02,5.511480312174094287e+00,5.656854305839434716e+00,-1.326214017705136250e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.268664841654282327e+01,3.803831892499182459e+02,5.510157982410691879e+00,5.656854305839434716e+00,-1.328714017705136252e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.268841618347818212e+01,3.803931011056665739e+02,5.508833174641978303e+00,5.656854305839434716e+00,-1.331214017705136254e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.269018395041354097e+01,3.804030126299032304e+02,5.507505888950753103e+00,5.656854305839434716e+00,-1.333714017705136257e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.269195171734889982e+01,3.804129238220087359e+02,5.506176125419972145e+00,5.656854305839434716e+00,-1.336214017705136259e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.269371948428425867e+01,3.804228346813636108e+02,5.504843884132745835e+00,5.656854305839434716e+00,-1.338714017705136261e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.269548725121961752e+01,3.804327452073484892e+02,5.503509165172339124e+00,5.656854305839434716e+00,-1.341214017705136263e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.269725501815497637e+01,3.804426553993438915e+02,5.502171968622172393e+00,5.656854305839434716e+00,-1.343714017705136266e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.269902278509033522e+01,3.804525652567305087e+02,5.500832294565819680e+00,5.656854305839434716e+00,-1.346214017705136268e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.270079055202569407e+01,3.804624747788889181e+02,5.499490143087011340e+00,5.656854305839434716e+00,-1.348714017705136270e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.270255831896105292e+01,3.804723839651998105e+02,5.498145514269631384e+00,5.656854305839434716e+00,-1.351214017705136272e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.270432608589641177e+01,3.804822928150438202e+02,5.496798408197719255e+00,5.656854305839434716e+00,-1.353714017705136274e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.270609385283177062e+01,3.804922013278016379e+02,5.495448824955468936e+00,5.656854305839434716e+00,-1.356214017705136277e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.270786161976712947e+01,3.805021095028540117e+02,5.494096764627228957e+00,5.656854305839434716e+00,-1.358714017705136279e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.270962938670248832e+01,3.805120173395816892e+02,5.492742227297504165e+00,5.656854305839434716e+00,-1.361214017705136281e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.271139715363784717e+01,3.805219248373654182e+02,5.491385213050952174e+00,5.656854305839434716e+00,-1.363714017705136283e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.271316492057320602e+01,3.805318319955860034e+02,5.490025721972386918e+00,5.656854305839434716e+00,-1.366214017705136285e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.271493268750856487e+01,3.805417388136241925e+02,5.488663754146775986e+00,5.656854305839434716e+00,-1.368714017705136288e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.271670045444392372e+01,3.805516452908608471e+02,5.487299309659243285e+00,5.656854305839434716e+00,-1.371214017705136290e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.271846822137928257e+01,3.805615514266768287e+02,5.485932388595065490e+00,5.656854305839434716e+00,-1.373714017705136292e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.272023598831464142e+01,3.805714572204529418e+02,5.484562991039676483e+00,5.656854305839434716e+00,-1.376214017705136294e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.272200375525000027e+01,3.805813626715701616e+02,5.483191117078662913e+00,5.656854305839434716e+00,-1.378714017705136297e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.272377152218535912e+01,3.805912677794093497e+02,5.481816766797766860e+00,5.656854305839434716e+00,-1.381214017705136299e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.272553928912071797e+01,3.806011725433514243e+02,5.480439940282884947e+00,5.656854305839434716e+00,-1.383714017705136301e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.272730705605607682e+01,3.806110769627773607e+02,5.479060637620069230e+00,5.656854305839434716e+00,-1.386214017705136303e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.272907482299143567e+01,3.806209810370680771e+02,5.477678858895526304e+00,5.656854305839434716e+00,-1.388714017705136305e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.273084258992679452e+01,3.806308847656046055e+02,5.476294604195616422e+00,5.656854305839434716e+00,-1.391214017705136308e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.273261035686215337e+01,3.806407881477679780e+02,5.474907873606856157e+00,5.656854305839434716e+00,-1.393714017705136310e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.273437812379751222e+01,3.806506911829392266e+02,5.473518667215916622e+00,5.656854305839434716e+00,-1.396214017705136312e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.273614589073287107e+01,3.806605938704994401e+02,5.472126985109622588e+00,5.656854305839434716e+00,-1.398714017705136314e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.273791365766822992e+01,3.806704962098296505e+02,5.470732827374954255e+00,5.656854305839434716e+00,-1.401214017705136317e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.273968142460358877e+01,3.806803982003110036e+02,5.469336194099046367e+00,5.656854305839434716e+00,-1.403714017705136319e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.274144919153894762e+01,3.806902998413245882e+02,5.467937085369189099e+00,5.656854305839434716e+00,-1.406214017705136321e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.274321695847430647e+01,3.807002011322515500e+02,5.466535501272826281e+00,5.656854305839434716e+00,-1.408714017705136323e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.274498472540966532e+01,3.807101020724730915e+02,5.465131441897557174e+00,5.656854305839434716e+00,-1.411214017705136325e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.274675249234502417e+01,3.807200026613704154e+02,5.463724907331135583e+00,5.656854305839434716e+00,-1.413714017705136328e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.274852025928038302e+01,3.807299028983246671e+02,5.462315897661468966e+00,5.656854305839434716e+00,-1.416214017705136330e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.275028802621574187e+01,3.807398027827171632e+02,5.460904412976621103e+00,5.656854305839434716e+00,-1.418714017705136332e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.275205579315110072e+01,3.807497023139291059e+02,5.459490453364810314e+00,5.656854305839434716e+00,-1.421214017705136334e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.275382356008645957e+01,3.807596014913418117e+02,5.458074018914408576e+00,5.656854305839434716e+00,-1.423714017705136337e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.275559132702181842e+01,3.807695003143365398e+02,5.456655109713942409e+00,5.656854305839434716e+00,-1.426214017705136339e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.275735909395717727e+01,3.807793987822946065e+02,5.455233725852094651e+00,5.656854305839434716e+00,-1.428714017705136341e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.275912686089253611e+01,3.807892968945973848e+02,5.453809867417701795e+00,5.656854305839434716e+00,-1.431214017705136343e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.276089462782789496e+01,3.807991946506262479e+02,5.452383534499753992e+00,5.656854305839434716e+00,-1.433714017705136345e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.276266239476325381e+01,3.808090920497625689e+02,5.450954727187397708e+00,5.656854305839434716e+00,-1.436214017705136348e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.276443016169861266e+01,3.808189890913877775e+02,5.449523445569933067e+00,5.656854305839434716e+00,-1.438714017705136350e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.276619792863397151e+01,3.808288857748833038e+02,5.448089689736815622e+00,5.656854305839434716e+00,-1.441214017705136352e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.276796569556933036e+01,3.808387820996306345e+02,5.446653459777655470e+00,5.656854305839434716e+00,-1.443714017705136354e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.276973346250468921e+01,3.808486780650111996e+02,5.445214755782216365e+00,5.656854305839434716e+00,-1.446214017705136357e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.277150122944004806e+01,3.808585736704065425e+02,5.443773577840417488e+00,5.656854305839434716e+00,-1.448714017705136359e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.277326899637540691e+01,3.808684689151981502e+02,5.442329926042331678e+00,5.656854305839434716e+00,-1.451214017705136361e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.277503676331076576e+01,3.808783637987675661e+02,5.440883800478188093e+00,5.656854305839434716e+00,-1.453714017705136363e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.277680453024612461e+01,3.808882583204963908e+02,5.439435201238369544e+00,5.656854305839434716e+00,-1.456214017705136365e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.277857229718148346e+01,3.808981524797662246e+02,5.437984128413413387e+00,5.656854305839434716e+00,-1.458714017705136368e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.278034006411684231e+01,3.809080462759586680e+02,5.436530582094011521e+00,5.656854305839434716e+00,-1.461214017705136370e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.278210783105220116e+01,3.809179397084553216e+02,5.435074562371010387e+00,5.656854305839434716e+00,-1.463714017705136372e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.278387559798756001e+01,3.809278327766378993e+02,5.433616069335411858e+00,5.656854305839434716e+00,-1.466214017705136374e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.278564336492291886e+01,3.809377254798880585e+02,5.432155103078371461e+00,5.656854305839434716e+00,-1.468714017705136377e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.278741113185827771e+01,3.809476178175875134e+02,5.430691663691199267e+00,5.656854305839434716e+00,-1.471214017705136379e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.278917889879363656e+01,3.809575097891179780e+02,5.429225751265359889e+00,5.656854305839434716e+00,-1.473714017705136381e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.279094666572899541e+01,3.809674013938612234e+02,5.427757365892473373e+00,5.656854305839434716e+00,-1.476214017705136383e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.279271443266435426e+01,3.809772926311990204e+02,5.426286507664314307e+00,5.656854305839434716e+00,-1.478714017705136385e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.279448219959971311e+01,3.809871835005131402e+02,5.424813176672810933e+00,5.656854305839434716e+00,-1.481214017705136388e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.279624996653507196e+01,3.809970740011854673e+02,5.423337373010046036e+00,5.656854305839434716e+00,-1.483714017705136390e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.279801773347043081e+01,3.810069641325977727e+02,5.421859096768257835e+00,5.656854305839434716e+00,-1.486214017705136392e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.279978550040578966e+01,3.810168538941319980e+02,5.420378348039838201e+00,5.656854305839434716e+00,-1.488714017705136394e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.280155326734114851e+01,3.810267432851699709e+02,5.418895126917334437e+00,5.656854305839434716e+00,-1.491214017705136397e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.280332103427650736e+01,3.810366323050936330e+02,5.417409433493447501e+00,5.656854305839434716e+00,-1.493714017705136399e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.280508880121186621e+01,3.810465209532848689e+02,5.415921267861033783e+00,5.656854305839434716e+00,-1.496214017705136401e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.280685656814722506e+01,3.810564092291256770e+02,5.414430630113103327e+00,5.656854305839434716e+00,-1.498714017705136403e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.280862433508258391e+01,3.810662971319980556e+02,5.412937520342820719e+00,5.656854305839434716e+00,-1.501214017705136405e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.281039210201794276e+01,3.810761846612840031e+02,5.411441938643505090e+00,5.656854305839434716e+00,-1.503714017705136408e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.281215986895330161e+01,3.810860718163655747e+02,5.409943885108631001e+00,5.656854305839434716e+00,-1.506214017705136410e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.281392763588866046e+01,3.810959585966247687e+02,5.408443359831825781e+00,5.656854305839434716e+00,-1.508714017705136412e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.281569540282401931e+01,3.811058450014436971e+02,5.406940362906873077e+00,5.656854305839434716e+00,-1.511214017705136414e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.281746316975937816e+01,3.811157310302044152e+02,5.405434894427710191e+00,5.656854305839434716e+00,-1.513714017705136416e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.281923093669473701e+01,3.811256166822890918e+02,5.403926954488428969e+00,5.656854305839434716e+00,-1.516214017705136419e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.282099870363009586e+01,3.811355019570798959e+02,5.402416543183274911e+00,5.656854305839434716e+00,-1.518714017705136421e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.282276647056545471e+01,3.811453868539589394e+02,5.400903660606649836e+00,5.656854305839434716e+00,-1.521214017705136423e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.282453423750081356e+01,3.811552713723084480e+02,5.399388306853108332e+00,5.656854305839434716e+00,-1.523714017705136425e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.282630200443617241e+01,3.811651555115106476e+02,5.397870482017359528e+00,5.656854305839434716e+00,-1.526214017705136428e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.282806977137153126e+01,3.811750392709477637e+02,5.396350186194267984e+00,5.656854305839434716e+00,-1.528714017705136430e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.282983753830689011e+01,3.811849226500020222e+02,5.394827419478851915e+00,5.656854305839434716e+00,-1.531214017705136432e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.283160530524224896e+01,3.811948056480557625e+02,5.393302181966284969e+00,5.656854305839434716e+00,-1.533714017705136434e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.283337307217760781e+01,3.812046882644912671e+02,5.391774473751893559e+00,5.656854305839434716e+00,-1.536214017705136436e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.283514083911296666e+01,3.812145704986909323e+02,5.390244294931160418e+00,5.656854305839434716e+00,-1.538714017705136439e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.283690860604832551e+01,3.812244523500370406e+02,5.388711645599721045e+00,5.656854305839434716e+00,-1.541214017705136441e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.283867637298368436e+01,3.812343338179120451e+02,5.387176525853366371e+00,5.656854305839434716e+00,-1.543714017705136443e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.284044413991904321e+01,3.812442149016982853e+02,5.385638935788040982e+00,5.656854305839434716e+00,-1.546214017705136445e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.284221190685440206e+01,3.812540956007782711e+02,5.384098875499844006e+00,5.656854305839434716e+00,-1.548714017705136448e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.284397967378976091e+01,3.812639759145343987e+02,5.382556345085030003e+00,5.656854305839434716e+00,-1.551214017705136450e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.284574744072511976e+01,3.812738558423491781e+02,5.381011344640007188e+00,5.656854305839434716e+00,-1.553714017705136452e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.284751520766047861e+01,3.812837353836050625e+02,5.379463874261337430e+00,5.656854305839434716e+00,-1.556214017705136454e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.284928297459583746e+01,3.812936145376846184e+02,5.377913934045738031e+00,5.656854305839434716e+00,-1.558714017705136456e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.285105074153119631e+01,3.813034933039704129e+02,5.376361524090079946e+00,5.656854305839434716e+00,-1.561214017705136459e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.285281850846655516e+01,3.813133716818450125e+02,5.374806644491388674e+00,5.656854305839434716e+00,-1.563714017705136461e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.285458627540191401e+01,3.813232496706910410e+02,5.373249295346844256e+00,5.656854305839434716e+00,-1.566214017705136463e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.285635404233727286e+01,3.813331272698910652e+02,5.371689476753781278e+00,5.656854305839434716e+00,-1.568714017705136465e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.285812180927263171e+01,3.813430044788277655e+02,5.370127188809688867e+00,5.656854305839434716e+00,-1.571214017705136468e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.285988957620799056e+01,3.813528812968838224e+02,5.368562431612208918e+00,5.656854305839434716e+00,-1.573714017705136470e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.286165734314334941e+01,3.813627577234419732e+02,5.366995205259139645e+00,5.656854305839434716e+00,-1.576214017705136472e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.286342511007870826e+01,3.813726337578848984e+02,5.365425509848432029e+00,5.656854305839434716e+00,-1.578714017705136474e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.286519287701406711e+01,3.813825093995953353e+02,5.363853345478192480e+00,5.656854305839434716e+00,-1.581214017705136476e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.286696064394942596e+01,3.813923846479560780e+02,5.362278712246681067e+00,5.656854305839434716e+00,-1.583714017705136479e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.286872841088478481e+01,3.814022595023499207e+02,5.360701610252313287e+00,5.656854305839434716e+00,-1.586214017705136481e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.287049617782014366e+01,3.814121339621596576e+02,5.359122039593656517e+00,5.656854305839434716e+00,-1.588714017705136483e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.287226394475550251e+01,3.814220080267681396e+02,5.357540000369435340e+00,5.656854305839434716e+00,-1.591214017705136485e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.287403171169086136e+01,3.814318816955582747e+02,5.355955492678526220e+00,5.656854305839434716e+00,-1.593714017705136488e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.287579947862622021e+01,3.814417549679129706e+02,5.354368516619961049e+00,5.656854305839434716e+00,-1.596214017705136490e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.287756724556157906e+01,3.814516278432150784e+02,5.352779072292926266e+00,5.656854305839434716e+00,-1.598714017705136492e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.287933501249693791e+01,3.814615003208476196e+02,5.351187159796761073e+00,5.656854305839434716e+00,-1.601214017705136494e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.288110277943229676e+01,3.814713724001935020e+02,5.349592779230960993e+00,5.656854305839434716e+00,-1.603714017705136496e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.288287054636765561e+01,3.814812440806357472e+02,5.347995930695174316e+00,5.656854305839434716e+00,-1.606214017705136499e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.288463831330301446e+01,3.814911153615573767e+02,5.346396614289204763e+00,5.656854305839434716e+00,-1.608714017705136501e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.288640608023837331e+01,3.815009862423414120e+02,5.344794830113008821e+00,5.656854305839434716e+00,-1.611214017705136503e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.288817384717373216e+01,3.815108567223709315e+02,5.343190578266698409e+00,5.656854305839434716e+00,-1.613714017705136505e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.288994161410909101e+01,3.815207268010290704e+02,5.341583858850539102e+00,5.656854305839434716e+00,-1.616214017705136508e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.289170938104444986e+01,3.815305964776989072e+02,5.339974671964951014e+00,5.656854305839434716e+00,-1.618714017705136510e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.289347714797980871e+01,3.815404657517636338e+02,5.338363017710507918e+00,5.656854305839434716e+00,-1.621214017705136512e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.289524491491516756e+01,3.815503346226063854e+02,5.336748896187939017e+00,5.656854305839434716e+00,-1.623714017705136514e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.289701268185052641e+01,3.815602030896103543e+02,5.335132307498126281e+00,5.656854305839434716e+00,-1.626214017705136516e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.289878044878588526e+01,3.815700711521587323e+02,5.333513251742107109e+00,5.656854305839434716e+00,-1.628714017705136519e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.290054821572124411e+01,3.815799388096348252e+02,5.331891729021071669e+00,5.656854305839434716e+00,-1.631214017705136521e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.290231598265660296e+01,3.815898060614218821e+02,5.330267739436365559e+00,5.656854305839434716e+00,-1.633714017705136523e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.290408374959196180e+01,3.815996729069031517e+02,5.328641283089488034e+00,5.656854305839434716e+00,-1.636214017705136525e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.290585151652732065e+01,3.816095393454619966e+02,5.327012360082092890e+00,5.656854305839434716e+00,-1.638714017705136528e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.290761928346267950e+01,3.816194053764817795e+02,5.325380970515987578e+00,5.656854305839434716e+00,-1.641214017705136530e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.290938705039803835e+01,3.816292709993458629e+02,5.323747114493133203e+00,5.656854305839434716e+00,-1.643714017705136532e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.291115481733339720e+01,3.816391362134376664e+02,5.322110792115647193e+00,5.656854305839434716e+00,-1.646214017705136534e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.291292258426875605e+01,3.816490010181406092e+02,5.320472003485798851e+00,5.656854305839434716e+00,-1.648714017705136536e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.291469035120411490e+01,3.816588654128381108e+02,5.318830748706012024e+00,5.656854305839434716e+00,-1.651214017705136539e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.291645811813947375e+01,3.816687293969136476e+02,5.317187027878865990e+00,5.656854305839434716e+00,-1.653714017705136541e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.291822588507483260e+01,3.816785929697507527e+02,5.315540841107092795e+00,5.656854305839434716e+00,-1.656214017705136543e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.291999365201019145e+01,3.816884561307329022e+02,5.313892188493579916e+00,5.656854305839434716e+00,-1.658714017705136545e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.292176141894555030e+01,3.816983188792436863e+02,5.312241070141367594e+00,5.656854305839434716e+00,-1.661214017705136547e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.292352918588090915e+01,3.817081812146666948e+02,5.310587486153650616e+00,5.656854305839434716e+00,-1.663714017705136550e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.292529695281626800e+01,3.817180431363855178e+02,5.308931436633778311e+00,5.656854305839434716e+00,-1.666214017705136552e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.292706471975162685e+01,3.817279046437837451e+02,5.307272921685253664e+00,5.656854305839434716e+00,-1.668714017705136554e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.292883248668698570e+01,3.817377657362450805e+02,5.305611941411733312e+00,5.656854305839434716e+00,-1.671214017705136556e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.293060025362234455e+01,3.817476264131531707e+02,5.303948495917029327e+00,5.656854305839434716e+00,-1.673714017705136559e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.293236802055770340e+01,3.817574866738917763e+02,5.302282585305106544e+00,5.656854305839434716e+00,-1.676214017705136561e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.293413578749306225e+01,3.817673465178446008e+02,5.300614209680084343e+00,5.656854305839434716e+00,-1.678714017705136563e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.293590355442842110e+01,3.817772059443954049e+02,5.298943369146236648e+00,5.656854305839434716e+00,-1.681214017705136565e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.293767132136377995e+01,3.817870649529279490e+02,5.297270063807990148e+00,5.656854305839434716e+00,-1.683714017705136567e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.293943908829913880e+01,3.817969235428261072e+02,5.295594293769926963e+00,5.656854305839434716e+00,-1.686214017705136570e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.294120685523449765e+01,3.818067817134736401e+02,5.293916059136782870e+00,5.656854305839434716e+00,-1.688714017705136572e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.294297462216985650e+01,3.818166394642544788e+02,5.292235360013447298e+00,5.656854305839434716e+00,-1.691214017705136574e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.294474238910521535e+01,3.818264967945524972e+02,5.290552196504964222e+00,5.656854305839434716e+00,-1.693714017705136576e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.294651015604057420e+01,3.818363537037515698e+02,5.288866568716531269e+00,5.656854305839434716e+00,-1.696214017705136579e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.294827792297593305e+01,3.818462101912356843e+02,5.287178476753499723e+00,5.656854305839434716e+00,-1.698714017705136581e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.295004568991129190e+01,3.818560662563887718e+02,5.285487920721376298e+00,5.656854305839434716e+00,-1.701214017705136583e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.295181345684665075e+01,3.818659218985948769e+02,5.283794900725819588e+00,5.656854305839434716e+00,-1.703714017705136585e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.295358122378200960e+01,3.818757771172379876e+02,5.282099416872643616e+00,5.656854305839434716e+00,-1.706214017705136587e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.295534899071736845e+01,3.818856319117021485e+02,5.280401469267816950e+00,5.656854305839434716e+00,-1.708714017705136590e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.295711675765272730e+01,3.818954862813714612e+02,5.278701058017460923e+00,5.656854305839434716e+00,-1.711214017705136592e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.295888452458808615e+01,3.819053402256300274e+02,5.276998183227850525e+00,5.656854305839434716e+00,-1.713714017705136594e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.296065229152344500e+01,3.819151937438619484e+02,5.275292845005416176e+00,5.656854305839434716e+00,-1.716214017705136596e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.296242005845880385e+01,3.819250468354514396e+02,5.273585043456741062e+00,5.656854305839434716e+00,-1.718714017705136599e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.296418782539416270e+01,3.819348994997826026e+02,5.271874778688562913e+00,5.656854305839434716e+00,-1.721214017705136601e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.296595559232952155e+01,3.819447517362397093e+02,5.270162050807774001e+00,5.656854305839434716e+00,-1.723714017705136603e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.296772335926488040e+01,3.819546035442069751e+02,5.268446859921419367e+00,5.656854305839434716e+00,-1.726214017705136605e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.296949112620023925e+01,3.819644549230686152e+02,5.266729206136697705e+00,5.656854305839434716e+00,-1.728714017705136607e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.297125889313559810e+01,3.819743058722089586e+02,5.265009089560963140e+00,5.656854305839434716e+00,-1.731214017705136610e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.297302666007095695e+01,3.819841563910123341e+02,5.263286510301722565e+00,5.656854305839434716e+00,-1.733714017705136612e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.297479442700631580e+01,3.819940064788630707e+02,5.261561468466637415e+00,5.656854305839434716e+00,-1.736214017705136614e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.297656219394167465e+01,3.820038561351455542e+02,5.259833964163522779e+00,5.656854305839434716e+00,-1.738714017705136616e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.297832996087703350e+01,3.820137053592441703e+02,5.258103997500348292e+00,5.656854305839434716e+00,-1.741214017705136619e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.298009772781239235e+01,3.820235541505433048e+02,5.256371568585236353e+00,5.656854305839434716e+00,-1.743714017705136621e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.298186549474775120e+01,3.820334025084274572e+02,5.254636677526463018e+00,5.656854305839434716e+00,-1.746214017705136623e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.298363326168311005e+01,3.820432504322810701e+02,5.252899324432459771e+00,5.656854305839434716e+00,-1.748714017705136625e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.298540102861846890e+01,3.820530979214886997e+02,5.251159509411810866e+00,5.656854305839434716e+00,-1.751214017705136627e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.298716879555382775e+01,3.820629449754348457e+02,5.249417232573255099e+00,5.656854305839434716e+00,-1.753714017705136630e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.298893656248918660e+01,3.820727915935040642e+02,5.247672494025684919e+00,5.656854305839434716e+00,-1.756214017705136632e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.299070432942454545e+01,3.820826377750809115e+02,5.245925293878146434e+00,5.656854305839434716e+00,-1.758714017705136634e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.299247209635990430e+01,3.820924835195500577e+02,5.244175632239838514e+00,5.656854305839434716e+00,-1.761214017705136636e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.299423986329526315e+01,3.821023288262961159e+02,5.242423509220116351e+00,5.656854305839434716e+00,-1.763714017705136639e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.299600763023062200e+01,3.821121736947037562e+02,5.240668924928487016e+00,5.656854305839434716e+00,-1.766214017705136641e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.299777539716598085e+01,3.821220181241576483e+02,5.238911879474612121e+00,5.656854305839434716e+00,-1.768714017705136643e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.299954316410133970e+01,3.821318621140425762e+02,5.237152372968306935e+00,5.656854305839434716e+00,-1.771214017705136645e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.300131093103669855e+01,3.821417056637432665e+02,5.235390405519541268e+00,5.656854305839434716e+00,-1.773714017705136647e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.300307869797205740e+01,3.821515487726444462e+02,5.233625977238437699e+00,5.656854305839434716e+00,-1.776214017705136650e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.300484646490741625e+01,3.821613914401309557e+02,5.231859088235272459e+00,5.656854305839434716e+00,-1.778714017705136652e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.300661423184277510e+01,3.821712336655876356e+02,5.230089738620476325e+00,5.656854305839434716e+00,-1.781214017705136654e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.300838199877813395e+01,3.821810754483993833e+02,5.228317928504633727e+00,5.656854305839434716e+00,-1.783714017705136656e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.301014976571349280e+01,3.821909167879510392e+02,5.226543657998482750e+00,5.656854305839434716e+00,-1.786214017705136659e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.301191753264885165e+01,3.822007576836275575e+02,5.224766927212916023e+00,5.656854305839434716e+00,-1.788714017705136661e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.301368529958421050e+01,3.822105981348138357e+02,5.222987736258978053e+00,5.656854305839434716e+00,-1.791214017705136663e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.301545306651956935e+01,3.822204381408948848e+02,5.221206085247869666e+00,5.656854305839434716e+00,-1.793714017705136665e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.301722083345492820e+01,3.822302777012556589e+02,5.219421974290942678e+00,5.656854305839434716e+00,-1.796214017705136667e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.301898860039028705e+01,3.822401168152812261e+02,5.217635403499704339e+00,5.656854305839434716e+00,-1.798714017705136670e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.302075636732564590e+01,3.822499554823565973e+02,5.215846372985815549e+00,5.656854305839434716e+00,-1.801214017705136672e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.302252413426100475e+01,3.822597937018668972e+02,5.214054882861090867e+00,5.656854305839434716e+00,-1.803714017705136674e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.302429190119636360e+01,3.822696314731972507e+02,5.212260933237498506e+00,5.656854305839434716e+00,-1.806214017705136676e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.302605966813172245e+01,3.822794687957327824e+02,5.210464524227160332e+00,5.656854305839434716e+00,-1.808714017705136679e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.302782743506708130e+01,3.822893056688586171e+02,5.208665655942351869e+00,5.656854305839434716e+00,-1.811214017705136681e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.302959520200244015e+01,3.822991420919599932e+02,5.206864328495502292e+00,5.656854305839434716e+00,-1.813714017705136683e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.303136296893779900e+01,3.823089780644221491e+02,5.205060541999194434e+00,5.656854305839434716e+00,-1.816214017705136685e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.303313073587315785e+01,3.823188135856302665e+02,5.203254296566164783e+00,5.656854305839434716e+00,-1.818714017705136687e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.303489850280851670e+01,3.823286486549696974e+02,5.201445592309303478e+00,5.656854305839434716e+00,-1.821214017705136690e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.303666626974387555e+01,3.823384832718257371e+02,5.199634429341655206e+00,5.656854305839434716e+00,-1.823714017705136692e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.303843403667923440e+01,3.823483174355836809e+02,5.197820807776417418e+00,5.656854305839434716e+00,-1.826214017705136694e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.304020180361459325e+01,3.823581511456289377e+02,5.196004727726941219e+00,5.656854305839434716e+00,-1.828714017705136696e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.304196957054995210e+01,3.823679844013468596e+02,5.194186189306732260e+00,5.656854305839434716e+00,-1.831214017705136698e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.304373733748531095e+01,3.823778172021229125e+02,5.192365192629448067e+00,5.656854305839434716e+00,-1.833714017705136701e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.304550510442066980e+01,3.823876495473425052e+02,5.190541737808901601e+00,5.656854305839434716e+00,-1.836214017705136703e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.304727287135602865e+01,3.823974814363911605e+02,5.188715824959059475e+00,5.656854305839434716e+00,-1.838714017705136705e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.304904063829138749e+01,3.824073128686543441e+02,5.186887454194040181e+00,5.656854305839434716e+00,-1.841214017705136707e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.305080840522674634e+01,3.824171438435176356e+02,5.185056625628117644e+00,5.656854305839434716e+00,-1.843714017705136710e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.305257617216210519e+01,3.824269743603665574e+02,5.183223339375717664e+00,5.656854305839434716e+00,-1.846214017705136712e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.305434393909746404e+01,3.824368044185866893e+02,5.181387595551421477e+00,5.656854305839434716e+00,-1.848714017705136714e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.305611170603282289e+01,3.824466340175637242e+02,5.179549394269963081e+00,5.656854305839434716e+00,-1.851214017705136716e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.305787947296818174e+01,3.824564631566832418e+02,5.177708735646230132e+00,5.656854305839434716e+00,-1.853714017705136718e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.305964723990354059e+01,3.824662918353309351e+02,5.175865619795263051e+00,5.656854305839434716e+00,-1.856214017705136721e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.306141500683889944e+01,3.824761200528925542e+02,5.174020046832256803e+00,5.656854305839434716e+00,-1.858714017705136723e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.306318277377425829e+01,3.824859478087537923e+02,5.172172016872560008e+00,5.656854305839434716e+00,-1.861214017705136725e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.306495054070961714e+01,3.824957751023003993e+02,5.170321530031674939e+00,5.656854305839434716e+00,-1.863714017705136727e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.306671830764497599e+01,3.825056019329182391e+02,5.168468586425255751e+00,5.656854305839434716e+00,-1.866214017705136730e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.306848607458033484e+01,3.825154282999930615e+02,5.166613186169112915e+00,5.656854305839434716e+00,-1.868714017705136732e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.307025384151569369e+01,3.825252542029107872e+02,5.164755329379207893e+00,5.656854305839434716e+00,-1.871214017705136734e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.307202160845105254e+01,3.825350796410572229e+02,5.162895016171656692e+00,5.656854305839434716e+00,-1.873714017705136736e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.307378937538641139e+01,3.825449046138183462e+02,5.161032246662729861e+00,5.656854305839434716e+00,-1.876214017705136738e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.307555714232177024e+01,3.825547291205800775e+02,5.159167020968849826e+00,5.656854305839434716e+00,-1.878714017705136741e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.307732490925712909e+01,3.825645531607283374e+02,5.157299339206592670e+00,5.656854305839434716e+00,-1.881214017705136743e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.307909267619248794e+01,3.825743767336491601e+02,5.155429201492689018e+00,5.656854305839434716e+00,-1.883714017705136745e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.308086044312784679e+01,3.825841998387285798e+02,5.153556607944023149e+00,5.656854305839434716e+00,-1.886214017705136747e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.308262821006320564e+01,3.825940224753526309e+02,5.151681558677631223e+00,5.656854305839434716e+00,-1.888714017705136750e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.308439597699856449e+01,3.826038446429074611e+02,5.149804053810703941e+00,5.656854305839434716e+00,-1.891214017705136752e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.308616374393392334e+01,3.826136663407791048e+02,5.147924093460585659e+00,5.656854305839434716e+00,-1.893714017705136754e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.308793151086928219e+01,3.826234875683537666e+02,5.146041677744774390e+00,5.656854305839434716e+00,-1.896214017705136756e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.308969927780464104e+01,3.826333083250175946e+02,5.144156806780920022e+00,5.656854305839434716e+00,-1.898714017705136758e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.309146704473999989e+01,3.826431286101567366e+02,5.142269480686827876e+00,5.656854305839434716e+00,-1.901214017705136761e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.309323481167535874e+01,3.826529484231575111e+02,5.140379699580455153e+00,5.656854305839434716e+00,-1.903714017705136763e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.309500257861071759e+01,3.826627677634061229e+02,5.138487463579913594e+00,5.656854305839434716e+00,-1.906214017705136765e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.309677034554607644e+01,3.826725866302888903e+02,5.136592772803467710e+00,5.656854305839434716e+00,-1.908714017705136767e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.309853811248143529e+01,3.826824050231921319e+02,5.134695627369535664e+00,5.656854305839434716e+00,-1.911214017705136770e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.310030587941679414e+01,3.826922229415022230e+02,5.132796027396689276e+00,5.656854305839434716e+00,-1.913714017705136772e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.310207364635215299e+01,3.827020403846054819e+02,5.130893973003653130e+00,5.656854305839434716e+00,-1.916214017705136774e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.310384141328751184e+01,3.827118573518883409e+02,5.128989464309306356e+00,5.656854305839434716e+00,-1.918714017705136776e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.310560918022287069e+01,3.827216738427372889e+02,5.127082501432679962e+00,5.656854305839434716e+00,-1.921214017705136778e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.310737694715822954e+01,3.827314898565387580e+02,5.125173084492959497e+00,5.656854305839434716e+00,-1.923714017705136781e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.310914471409358839e+01,3.827413053926792372e+02,5.123261213609484166e+00,5.656854305839434716e+00,-1.926214017705136783e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.311091248102894724e+01,3.827511204505452724e+02,5.121346888901745054e+00,5.656854305839434716e+00,-1.928714017705136785e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.311268024796430609e+01,3.827609350295234094e+02,5.119430110489387786e+00,5.656854305839434716e+00,-1.931214017705136787e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.311444801489966494e+01,3.827707491290002508e+02,5.117510878492210757e+00,5.656854305839434716e+00,-1.933714017705136790e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.311621578183502379e+01,3.827805627483623994e+02,5.115589193030166015e+00,5.656854305839434716e+00,-1.936214017705136792e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.311798354877038264e+01,3.827903758869965145e+02,5.113665054223359263e+00,5.656854305839434716e+00,-1.938714017705136794e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.311975131570574149e+01,3.828001885442892558e+02,5.111738462192048082e+00,5.656854305839434716e+00,-1.941214017705136796e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.312151908264110034e+01,3.828100007196273395e+02,5.109809417056645486e+00,5.656854305839434716e+00,-1.943714017705136798e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.312328684957645919e+01,3.828198124123975390e+02,5.107877918937716366e+00,5.656854305839434716e+00,-1.946214017705136801e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.312505461651181804e+01,3.828296236219865705e+02,5.105943967955980156e+00,5.656854305839434716e+00,-1.948714017705136803e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.312682238344717689e+01,3.828394343477812640e+02,5.104007564232308169e+00,5.656854305839434716e+00,-1.951214017705136805e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.312859015038253574e+01,3.828492445891684497e+02,5.102068707887725374e+00,5.656854305839434716e+00,-1.953714017705136807e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.313035791731789459e+01,3.828590543455350144e+02,5.100127399043410392e+00,5.656854305839434716e+00,-1.956214017705136810e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.313212568425325344e+01,3.828688636162677881e+02,5.098183637820695502e+00,5.656854305839434716e+00,-1.958714017705136812e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.313389345118861229e+01,3.828786724007537146e+02,5.096237424341065747e+00,5.656854305839434716e+00,-1.961214017705136814e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.313566121812397114e+01,3.828884806983797944e+02,5.094288758726158939e+00,5.656854305839434716e+00,-1.963714017705136816e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.313742898505932999e+01,3.828982885085329144e+02,5.092337641097767431e+00,5.656854305839434716e+00,-1.966214017705136818e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.313919675199468884e+01,3.829080958306001889e+02,5.090384071577835456e+00,5.656854305839434716e+00,-1.968714017705136821e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.314096451893004769e+01,3.829179026639685617e+02,5.088428050288460902e+00,5.656854305839434716e+00,-1.971214017705136823e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.314273228586540654e+01,3.829277090080252037e+02,5.086469577351895310e+00,5.656854305839434716e+00,-1.973714017705136825e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.314450005280076539e+01,3.829375148621571157e+02,5.084508652890543878e+00,5.656854305839434716e+00,-1.976214017705136827e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.314626781973612424e+01,3.829473202257515254e+02,5.082545277026963682e+00,5.656854305839434716e+00,-1.978714017705136829e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.314803558667148309e+01,3.829571250981955473e+02,5.080579449883865450e+00,5.656854305839434716e+00,-1.981214017705136832e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.314980335360684194e+01,3.829669294788764091e+02,5.078611171584114459e+00,5.656854305839434716e+00,-1.983714017705136834e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.315157112054220079e+01,3.829767333671812821e+02,5.076640442250726970e+00,5.656854305839434716e+00,-1.986214017705136836e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.315333888747755964e+01,3.829865367624974510e+02,5.074667262006874680e+00,5.656854305839434716e+00,-1.988714017705136838e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.315510665441291849e+01,3.829963396642122007e+02,5.072691630975880273e+00,5.656854305839434716e+00,-1.991214017705136841e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.315687442134827734e+01,3.830061420717128726e+02,5.070713549281220978e+00,5.656854305839434716e+00,-1.993714017705136843e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.315864218828363619e+01,3.830159439843868086e+02,5.068733017046527678e+00,5.656854305839434716e+00,-1.996214017705136845e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.316040995521899504e+01,3.830257454016213501e+02,5.066750034395583135e+00,5.656854305839434716e+00,-1.998714017705136847e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.316217772215435389e+01,3.830355463228039525e+02,5.064764601452323767e+00,5.656854305839434716e+00,-2.001214017705136849e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.316394548908971274e+01,3.830453467473220712e+02,5.062776718340838755e+00,5.656854305839434716e+00,-2.003714017705136852e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.316571325602507159e+01,3.830551466745631615e+02,5.060786385185370939e+00,5.656854305839434716e+00,-2.006214017705136854e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.316748102296043044e+01,3.830649461039146786e+02,5.058793602110316812e+00,5.656854305839434716e+00,-2.008714017705136856e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.316924878989578929e+01,3.830747450347642484e+02,5.056798369240224744e+00,5.656854305839434716e+00,-2.011214017705136858e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.317101655683114814e+01,3.830845434664993832e+02,5.054800686699796763e+00,5.656854305839434716e+00,-2.013714017705136861e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.317278432376650699e+01,3.830943413985076518e+02,5.052800554613887662e+00,5.656854305839434716e+00,-2.016214017705136863e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.317455209070186584e+01,3.831041388301767370e+02,5.050797973107505889e+00,5.656854305839434716e+00,-2.018714017705136865e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.317631985763722469e+01,3.831139357608942646e+02,5.048792942305813547e+00,5.656854305839434716e+00,-2.021214017705136867e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.317808762457258354e+01,3.831237321900479742e+02,5.046785462334124617e+00,5.656854305839434716e+00,-2.023714017705136869e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.317985539150794239e+01,3.831335281170255485e+02,5.044775533317906735e+00,5.656854305839434716e+00,-2.026214017705136872e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.318162315844330124e+01,3.831433235412147269e+02,5.042763155382779416e+00,5.656854305839434716e+00,-2.028714017705136874e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.318339092537866009e+01,3.831531184620033059e+02,5.040748328654517607e+00,5.656854305839434716e+00,-2.031214017705136876e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.318515869231401894e+01,3.831629128787791387e+02,5.038731053259047243e+00,5.656854305839434716e+00,-2.033714017705136878e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.318692645924937779e+01,3.831727067909300786e+02,5.036711329322448805e+00,5.656854305839434716e+00,-2.036214017705136881e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.318869422618473664e+01,3.831825001978439786e+02,5.034689156970953761e+00,5.656854305839434716e+00,-2.038714017705136883e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.319046199312009549e+01,3.831922930989087490e+02,5.032664536330949012e+00,5.656854305839434716e+00,-2.041214017705136885e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.319222976005545434e+01,3.832020854935122998e+02,5.030637467528973339e+00,5.656854305839434716e+00,-2.043714017705136887e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.319399752699081318e+01,3.832118773810426546e+02,5.028607950691717399e+00,5.656854305839434716e+00,-2.046214017705136889e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.319576529392617203e+01,3.832216687608878374e+02,5.026575985946027281e+00,5.656854305839434716e+00,-2.048714017705136892e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.319753306086153088e+01,3.832314596324358149e+02,5.024541573418900064e+00,5.656854305839434716e+00,-2.051214017705136894e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.319930082779688973e+01,3.832412499950747247e+02,5.022504713237486484e+00,5.656854305839434716e+00,-2.053714017705136896e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.320106859473224858e+01,3.832510398481926472e+02,5.020465405529090930e+00,5.656854305839434716e+00,-2.056214017705136898e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.320283636166760743e+01,3.832608291911777201e+02,5.018423650421169668e+00,5.656854305839434716e+00,-2.058714017705136901e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.320460412860296628e+01,3.832706180234180806e+02,5.016379448041332623e+00,5.656854305839434716e+00,-2.061214017705136903e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.320637189553832513e+01,3.832804063443019800e+02,5.014332798517342482e+00,5.656854305839434716e+00,-2.063714017705136905e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.320813966247368398e+01,3.832901941532176124e+02,5.012283701977114703e+00,5.656854305839434716e+00,-2.066214017705136907e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.320990742940904283e+01,3.832999814495532291e+02,5.010232158548717507e+00,5.656854305839434716e+00,-2.068714017705136909e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.321167519634440168e+01,3.833097682326971380e+02,5.008178168360372773e+00,5.656854305839434716e+00,-2.071214017705136912e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.321344296327976053e+01,3.833195545020377040e+02,5.006121731540454256e+00,5.656854305839434716e+00,-2.073714017705136914e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.321521073021511938e+01,3.833293402569632349e+02,5.004062848217490256e+00,5.656854305839434716e+00,-2.076214017705136916e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.321697849715047823e+01,3.833391254968621524e+02,5.002001518520160062e+00,5.656854305839434716e+00,-2.078714017705136918e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.321874626408583708e+01,3.833489102211228214e+02,4.999937742577297506e+00,5.656854305839434716e+00,-2.081214017705136921e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.322051403102119593e+01,3.833586944291337772e+02,4.997871520517888300e+00,5.656854305839434716e+00,-2.083714017705136923e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.322228179795655478e+01,3.833684781202834415e+02,4.995802852471070921e+00,5.656854305839434716e+00,-2.086214017705136925e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.322404956489191363e+01,3.833782612939603496e+02,4.993731738566137501e+00,5.656854305839434716e+00,-2.088714017705136927e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.322581733182727248e+01,3.833880439495530936e+02,4.991658178932532941e+00,5.656854305839434716e+00,-2.091214017705136929e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.322758509876263133e+01,3.833978260864502090e+02,4.989582173699854017e+00,5.656854305839434716e+00,-2.093714017705136932e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.322935286569799018e+01,3.834076077040403447e+02,4.987503722997852051e+00,5.656854305839434716e+00,-2.096214017705136934e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.323112063263334903e+01,3.834173888017120930e+02,4.985422826956429354e+00,5.656854305839434716e+00,-2.098714017705136936e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.323288839956870788e+01,3.834271693788542166e+02,4.983339485705641891e+00,5.656854305839434716e+00,-2.101214017705136938e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.323465616650406673e+01,3.834369494348553644e+02,4.981253699375699284e+00,5.656854305839434716e+00,-2.103714017705136941e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.323642393343942558e+01,3.834467289691042993e+02,4.979165468096962144e+00,5.656854305839434716e+00,-2.106214017705136943e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.323819170037478443e+01,3.834565079809898407e+02,4.977074791999945624e+00,5.656854305839434716e+00,-2.108714017705136945e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.323995946731014328e+01,3.834662864699007514e+02,4.974981671215316759e+00,5.656854305839434716e+00,-2.111214017705136947e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.324172723424550213e+01,3.834760644352259078e+02,4.972886105873895346e+00,5.656854305839434716e+00,-2.113714017705136949e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.324349500118086098e+01,3.834858418763541863e+02,4.970788096106654841e+00,5.656854305839434716e+00,-2.116214017705136952e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.324526276811621983e+01,3.834956187926744633e+02,4.968687642044720576e+00,5.656854305839434716e+00,-2.118714017705136954e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.324703053505157868e+01,3.835053951835757289e+02,4.966584743819370651e+00,5.656854305839434716e+00,-2.121214017705136956e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.324879830198693753e+01,3.835151710484469163e+02,4.964479401562036820e+00,5.656854305839434716e+00,-2.123714017705136958e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.325056606892229638e+01,3.835249463866770157e+02,4.962371615404302716e+00,5.656854305839434716e+00,-2.126214017705136961e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.325233383585765523e+01,3.835347211976551307e+02,4.960261385477904739e+00,5.656854305839434716e+00,-2.128714017705136963e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.325410160279301408e+01,3.835444954807703084e+02,4.958148711914732054e+00,5.656854305839434716e+00,-2.131214017705136965e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.325586936972837293e+01,3.835542692354116525e+02,4.956033594846827484e+00,5.656854305839434716e+00,-2.133714017705136967e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.325763713666373178e+01,3.835640424609683237e+02,4.953916034406385727e+00,5.656854305839434716e+00,-2.136214017705136969e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.325940490359909063e+01,3.835738151568294256e+02,4.951796030725753361e+00,5.656854305839434716e+00,-2.138714017705136972e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.326117267053444948e+01,3.835835873223842327e+02,4.949673583937431509e+00,5.656854305839434716e+00,-2.141214017705136974e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.326294043746980833e+01,3.835933589570219624e+02,4.947548694174073169e+00,5.656854305839434716e+00,-2.143714017705136976e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.326470820440516718e+01,3.836031300601318890e+02,4.945421361568483221e+00,5.656854305839434716e+00,-2.146214017705136978e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.326647597134052603e+01,3.836129006311033436e+02,4.943291586253620196e+00,5.656854305839434716e+00,-2.148714017705136980e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.326824373827588488e+01,3.836226706693256574e+02,4.941159368362595394e+00,5.656854305839434716e+00,-2.151214017705136983e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.327001150521124373e+01,3.836324401741881616e+02,4.939024708028671995e+00,5.656854305839434716e+00,-2.153714017705136985e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.327177927214660258e+01,3.836422091450803009e+02,4.936887605385266831e+00,5.656854305839434716e+00,-2.156214017705136987e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.327354703908196143e+01,3.836519775813915203e+02,4.934748060565948613e+00,5.656854305839434716e+00,-2.158714017705136989e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.327531480601732028e+01,3.836617454825112645e+02,4.932606073704438820e+00,5.656854305839434716e+00,-2.161214017705136992e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.327708257295267913e+01,3.836715128478290353e+02,4.930461644934611698e+00,5.656854305839434716e+00,-2.163714017705136994e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.327885033988803798e+01,3.836812796767343912e+02,4.928314774390494257e+00,5.656854305839434716e+00,-2.166214017705136996e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.328061810682339683e+01,3.836910459686168906e+02,4.926165462206265389e+00,5.656854305839434716e+00,-2.168714017705136998e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.328238587375875568e+01,3.837008117228662059e+02,4.924013708516257637e+00,5.656854305839434716e+00,-2.171214017705137000e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.328415364069411453e+01,3.837105769388718954e+02,4.921859513454954538e+00,5.656854305839434716e+00,-2.173714017705137003e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.328592140762947338e+01,3.837203416160236884e+02,4.919702877156994170e+00,5.656854305839434716e+00,-2.176214017705137005e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.328768917456483223e+01,3.837301057537112570e+02,4.917543799757166489e+00,5.656854305839434716e+00,-2.178714017705137007e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.328945694150019108e+01,3.837398693513243302e+02,4.915382281390413333e+00,5.656854305839434716e+00,-2.181214017705137009e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.329122470843554993e+01,3.837496324082526939e+02,4.913218322191830190e+00,5.656854305839434716e+00,-2.183714017705137012e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.329299247537090878e+01,3.837593949238861910e+02,4.911051922296663541e+00,5.656854305839434716e+00,-2.186214017705137014e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.329476024230626763e+01,3.837691568976146641e+02,4.908883081840314411e+00,5.656854305839434716e+00,-2.188714017705137016e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.329652800924162648e+01,3.837789183288279560e+02,4.906711800958334813e+00,5.656854305839434716e+00,-2.191214017705137018e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.329829577617698533e+01,3.837886792169159662e+02,4.904538079786429527e+00,5.656854305839434716e+00,-2.193714017705137020e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.330006354311234418e+01,3.837984395612686512e+02,4.902361918460456103e+00,5.656854305839434716e+00,-2.196214017705137023e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.330183131004770303e+01,3.838081993612760243e+02,4.900183317116425741e+00,5.656854305839434716e+00,-2.198714017705137025e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.330359907698306188e+01,3.838179586163280419e+02,4.898002275890499746e+00,5.656854305839434716e+00,-2.201214017705137027e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.330536684391842073e+01,3.838277173258148309e+02,4.895818794918993966e+00,5.656854305839434716e+00,-2.203714017705137029e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.330713461085377958e+01,3.838374754891264047e+02,4.893632874338375238e+00,5.656854305839434716e+00,-2.206214017705137032e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.330890237778913843e+01,3.838472331056528901e+02,4.891444514285264056e+00,5.656854305839434716e+00,-2.208714017705137034e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.331067014472449728e+01,3.838569901747844710e+02,4.889253714896433678e+00,5.656854305839434716e+00,-2.211214017705137036e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.331243791165985613e+01,3.838667466959112744e+02,4.887060476308807466e+00,5.656854305839434716e+00,-2.213714017705137038e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.331420567859521498e+01,3.838765026684235409e+02,4.884864798659464213e+00,5.656854305839434716e+00,-2.216214017705137040e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.331597344553057383e+01,3.838862580917115110e+02,4.882666682085632814e+00,5.656854305839434716e+00,-2.218714017705137043e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.331774121246593268e+01,3.838960129651654825e+02,4.880466126724695819e+00,5.656854305839434716e+00,-2.221214017705137045e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.331950897940129153e+01,3.839057672881758094e+02,4.878263132714188544e+00,5.656854305839434716e+00,-2.223714017705137047e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.332127674633665038e+01,3.839155210601327894e+02,4.876057700191797295e+00,5.656854305839434716e+00,-2.226214017705137049e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.332304451327200923e+01,3.839252742804268337e+02,4.873849829295362035e+00,5.656854305839434716e+00,-2.228714017705137052e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.332481228020736808e+01,3.839350269484484102e+02,4.871639520162874604e+00,5.656854305839434716e+00,-2.231214017705137054e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.332658004714272693e+01,3.839447790635879301e+02,4.869426772932479608e+00,5.656854305839434716e+00,-2.233714017705137056e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.332834781407808578e+01,3.839545306252359183e+02,4.867211587742473533e+00,5.656854305839434716e+00,-2.236214017705137058e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.333011558101344463e+01,3.839642816327828427e+02,4.864993964731305631e+00,5.656854305839434716e+00,-2.238714017705137060e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.333188334794880348e+01,3.839740320856192852e+02,4.862773904037577033e+00,5.656854305839434716e+00,-2.241214017705137063e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.333365111488416233e+01,3.839837819831358843e+02,4.860551405800041636e+00,5.656854305839434716e+00,-2.243714017705137065e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.333541888181952118e+01,3.839935313247232216e+02,4.858326470157605215e+00,5.656854305839434716e+00,-2.246214017705137067e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.333718664875488003e+01,3.840032801097719926e+02,4.856099097249326313e+00,5.656854305839434716e+00,-2.248714017705137069e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.333895441569023887e+01,3.840130283376728926e+02,4.853869287214416239e+00,5.656854305839434716e+00,-2.251214017705137072e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.334072218262559772e+01,3.840227760078166739e+02,4.851637040192238182e+00,5.656854305839434716e+00,-2.253714017705137074e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.334248994956095657e+01,3.840325231195940887e+02,4.849402356322307206e+00,5.656854305839434716e+00,-2.256214017705137076e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.334425771649631542e+01,3.840422696723959461e+02,4.847165235744291145e+00,5.656854305839434716e+00,-2.258714017705137078e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.334602548343167427e+01,3.840520156656131121e+02,4.844925678598009711e+00,5.656854305839434716e+00,-2.261214017705137080e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.334779325036703312e+01,3.840617610986363957e+02,4.842683685023435380e+00,5.656854305839434716e+00,-2.263714017705137083e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.334956101730239197e+01,3.840715059708567765e+02,4.840439255160693399e+00,5.656854305839434716e+00,-2.266214017705137085e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.335132878423775082e+01,3.840812502816651772e+02,4.838192389150060002e+00,5.656854305839434716e+00,-2.268714017705137087e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.335309655117310967e+01,3.840909940304525207e+02,4.835943087131964191e+00,5.656854305839434716e+00,-2.271214017705137089e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.335486431810846852e+01,3.841007372166099003e+02,4.833691349246987734e+00,5.656854305839434716e+00,-2.273714017705137092e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.335663208504382737e+01,3.841104798395283524e+02,4.831437175635864278e+00,5.656854305839434716e+00,-2.276214017705137094e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.335839985197918622e+01,3.841202218985989134e+02,4.829180566439479350e+00,5.656854305839434716e+00,-2.278714017705137096e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.336016761891454507e+01,3.841299633932127904e+02,4.826921521798871240e+00,5.656854305839434716e+00,-2.281214017705137098e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.336193538584990392e+01,3.841397043227610766e+02,4.824660041855230119e+00,5.656854305839434716e+00,-2.283714017705137100e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.336370315278526277e+01,3.841494446866349790e+02,4.822396126749898926e+00,5.656854305839434716e+00,-2.286214017705137103e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.336547091972062162e+01,3.841591844842257046e+02,4.820129776624371587e+00,5.656854305839434716e+00,-2.288714017705137105e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.336723868665598047e+01,3.841689237149245741e+02,4.817860991620295685e+00,5.656854305839434716e+00,-2.291214017705137107e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.336900645359133932e+01,3.841786623781227945e+02,4.815589771879469794e+00,5.656854305839434716e+00,-2.293714017705137109e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.337077422052669817e+01,3.841884004732118001e+02,4.813316117543845252e+00,5.656854305839434716e+00,-2.296214017705137111e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.337254198746205702e+01,3.841981379995829116e+02,4.811040028755525277e+00,5.656854305839434716e+00,-2.298714017705137114e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.337430975439741587e+01,3.842078749566275064e+02,4.808761505656765856e+00,5.656854305839434716e+00,-2.301214017705137116e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.337607752133277472e+01,3.842176113437370759e+02,4.806480548389974849e+00,5.656854305839434716e+00,-2.303714017705137118e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.337784528826813357e+01,3.842273471603030544e+02,4.804197157097711113e+00,5.656854305839434716e+00,-2.306214017705137120e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.337961305520349242e+01,3.842370824057169898e+02,4.801911331922687154e+00,5.656854305839434716e+00,-2.308714017705137123e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.338138082213885127e+01,3.842468170793703734e+02,4.799623073007767360e+00,5.656854305839434716e+00,-2.311214017705137125e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.338314858907421012e+01,3.842565511806548670e+02,4.797332380495967996e+00,5.656854305839434716e+00,-2.313714017705137127e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.338491635600956897e+01,3.842662847089620186e+02,4.795039254530457207e+00,5.656854305839434716e+00,-2.316214017705137129e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.338668412294492782e+01,3.842760176636835467e+02,4.792743695254555014e+00,5.656854305839434716e+00,-2.318714017705137131e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.338845188988028667e+01,3.842857500442110563e+02,4.790445702811733319e+00,5.656854305839434716e+00,-2.321214017705137134e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.339021965681564552e+01,3.842954818499363228e+02,4.788145277345617679e+00,5.656854305839434716e+00,-2.323714017705137136e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.339198742375100437e+01,3.843052130802511215e+02,4.785842418999984638e+00,5.656854305839434716e+00,-2.326214017705137138e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.339375519068636322e+01,3.843149437345472279e+02,4.783537127918762621e+00,5.656854305839434716e+00,-2.328714017705137140e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.339552295762172207e+01,3.843246738122165311e+02,4.781229404246031933e+00,5.656854305839434716e+00,-2.331214017705137143e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.339729072455708092e+01,3.843344033126508634e+02,4.778919248126025643e+00,5.656854305839434716e+00,-2.333714017705137145e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.339905849149243977e+01,3.843441322352421139e+02,4.776606659703128699e+00,5.656854305839434716e+00,-2.336214017705137147e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.340082625842779862e+01,3.843538605793822285e+02,4.774291639121877928e+00,5.656854305839434716e+00,-2.338714017705137149e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.340259402536315747e+01,3.843635883444632100e+02,4.771974186526961148e+00,5.656854305839434716e+00,-2.341214017705137151e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.340436179229851632e+01,3.843733155298770612e+02,4.769654302063219831e+00,5.656854305839434716e+00,-2.343714017705137154e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.340612955923387517e+01,3.843830421350157849e+02,4.767331985875647327e+00,5.656854305839434716e+00,-2.346214017705137156e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.340789732616923402e+01,3.843927681592715544e+02,4.765007238109387977e+00,5.656854305839434716e+00,-2.348714017705137158e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.340966509310459287e+01,3.844024936020364294e+02,4.762680058909738001e+00,5.656854305839434716e+00,-2.351214017705137160e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.341143286003995172e+01,3.844122184627025831e+02,4.760350448422146385e+00,5.656854305839434716e+00,-2.353714017705137163e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.341320062697531057e+01,3.844219427406622458e+02,4.758018406792213995e+00,5.656854305839434716e+00,-2.356214017705137165e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.341496839391066942e+01,3.844316664353075907e+02,4.755683934165693572e+00,5.656854305839434716e+00,-2.358714017705137167e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.341673616084602827e+01,3.844413895460309050e+02,4.753347030688488850e+00,5.656854305839434716e+00,-2.361214017705137169e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.341850392778138712e+01,3.844511120722245323e+02,4.751007696506657219e+00,5.656854305839434716e+00,-2.363714017705137171e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.342027169471674597e+01,3.844608340132808166e+02,4.748665931766407056e+00,5.656854305839434716e+00,-2.366214017705137174e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.342203946165210482e+01,3.844705553685921018e+02,4.746321736614097730e+00,5.656854305839434716e+00,-2.368714017705137176e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.342380722858746367e+01,3.844802761375507885e+02,4.743975111196242267e+00,5.656854305839434716e+00,-2.371214017705137178e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.342557499552282252e+01,3.844899963195493342e+02,4.741626055659504679e+00,5.656854305839434716e+00,-2.373714017705137180e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.342734276245818137e+01,3.844997159139802534e+02,4.739274570150700860e+00,5.656854305839434716e+00,-2.376214017705137183e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.342911052939354022e+01,3.845094349202360604e+02,4.736920654816797693e+00,5.656854305839434716e+00,-2.378714017705137185e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.343087829632889907e+01,3.845191533377093265e+02,4.734564309804915716e+00,5.656854305839434716e+00,-2.381214017705137187e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.343264606326425792e+01,3.845288711657926797e+02,4.732205535262327345e+00,5.656854305839434716e+00,-2.383714017705137189e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.343441383019961677e+01,3.845385884038786912e+02,4.729844331336455099e+00,5.656854305839434716e+00,-2.386214017705137191e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.343618159713497562e+01,3.845483050513601029e+02,4.727480698174874263e+00,5.656854305839434716e+00,-2.388714017705137194e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.343794936407033447e+01,3.845580211076295427e+02,4.725114635925312001e+00,5.656854305839434716e+00,-2.391214017705137196e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.343971713100569332e+01,3.845677365720798093e+02,4.722746144735646467e+00,5.656854305839434716e+00,-2.393714017705137198e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.344148489794105217e+01,3.845774514441037013e+02,4.720375224753909471e+00,5.656854305839434716e+00,-2.396214017705137200e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.344325266487641102e+01,3.845871657230940173e+02,4.718001876128282923e+00,5.656854305839434716e+00,-2.398714017705137203e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.344502043181176987e+01,3.845968794084436126e+02,4.715626099007101502e+00,5.656854305839434716e+00,-2.401214017705137205e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.344678819874712872e+01,3.846065924995453429e+02,4.713247893538850875e+00,5.656854305839434716e+00,-2.403714017705137207e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.344855596568248757e+01,3.846163049957921771e+02,4.710867259872168589e+00,5.656854305839434716e+00,-2.406214017705137209e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.345032373261784642e+01,3.846260168965770845e+02,4.708484198155844958e+00,5.656854305839434716e+00,-2.408714017705137211e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.345209149955320527e+01,3.846357282012930909e+02,4.706098708538821285e+00,5.656854305839434716e+00,-2.411214017705137214e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.345385926648856412e+01,3.846454389093332225e+02,4.703710791170189864e+00,5.656854305839434716e+00,-2.413714017705137216e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.345562703342392297e+01,3.846551490200905619e+02,4.701320446199196645e+00,5.656854305839434716e+00,-2.416214017705137218e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.345739480035928182e+01,3.846648585329581920e+02,4.698927673775237679e+00,5.656854305839434716e+00,-2.418714017705137220e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.345916256729464067e+01,3.846745674473293093e+02,4.696532474047860894e+00,5.656854305839434716e+00,-2.421214017705137223e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.346093033422999952e+01,3.846842757625971103e+02,4.694134847166766988e+00,5.656854305839434716e+00,-2.423714017705137225e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.346269810116535837e+01,3.846939834781547916e+02,4.691734793281806759e+00,5.656854305839434716e+00,-2.426214017705137227e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.346446586810071722e+01,3.847036905933956632e+02,4.689332312542984660e+00,5.656854305839434716e+00,-2.428714017705137229e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.346623363503607607e+01,3.847133971077130354e+02,4.686927405100454358e+00,5.656854305839434716e+00,-2.431214017705137231e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.346800140197143492e+01,3.847231030205002185e+02,4.684520071104524064e+00,5.656854305839434716e+00,-2.433714017705137234e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.346976916890679377e+01,3.847328083311505793e+02,4.682110310705651202e+00,5.656854305839434716e+00,-2.436214017705137236e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.347153693584215262e+01,3.847425130390575418e+02,4.679698124054445962e+00,5.656854305839434716e+00,-2.438714017705137238e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.347330470277751147e+01,3.847522171436145868e+02,4.677283511301670416e+00,5.656854305839434716e+00,-2.441214017705137240e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.347507246971287032e+01,3.847619206442151949e+02,4.674866472598237621e+00,5.656854305839434716e+00,-2.443714017705137242e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.347684023664822917e+01,3.847716235402529037e+02,4.672447008095211629e+00,5.656854305839434716e+00,-2.446214017705137245e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.347860800358358802e+01,3.847813258311212508e+02,4.670025117943810145e+00,5.656854305839434716e+00,-2.448714017705137247e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.348037577051894687e+01,3.847910275162138873e+02,4.667600802295400975e+00,5.656854305839434716e+00,-2.451214017705137249e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.348214353745430572e+01,3.848007285949244647e+02,4.665174061301503805e+00,5.656854305839434716e+00,-2.453714017705137251e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.348391130438966456e+01,3.848104290666466341e+02,4.662744895113790200e+00,5.656854305839434716e+00,-2.456214017705137254e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.348567907132502341e+01,3.848201289307741035e+02,4.660313303884082714e+00,5.656854305839434716e+00,-2.458714017705137256e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.348744683826038226e+01,3.848298281867006381e+02,4.657879287764355780e+00,5.656854305839434716e+00,-2.461214017705137258e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.348921460519574111e+01,3.848395268338200594e+02,4.655442846906734822e+00,5.656854305839434716e+00,-2.463714017705137260e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.349098237213109996e+01,3.848492248715261894e+02,4.653003981463498029e+00,5.656854305839434716e+00,-2.466214017705137262e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.349275013906645881e+01,3.848589222992129066e+02,4.650562691587074582e+00,5.656854305839434716e+00,-2.468714017705137265e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.349451790600181766e+01,3.848686191162741466e+02,4.648118977430045540e+00,5.656854305839434716e+00,-2.471214017705137267e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.349628567293717651e+01,3.848783153221037878e+02,4.645672839145142063e+00,5.656854305839434716e+00,-2.473714017705137269e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.349805343987253536e+01,3.848880109160958796e+02,4.643224276885248081e+00,5.656854305839434716e+00,-2.476214017705137271e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.349982120680789421e+01,3.848977058976444141e+02,4.640773290803399398e+00,5.656854305839434716e+00,-2.478714017705137274e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.350158897374325306e+01,3.849074002661434974e+02,4.638319881052781923e+00,5.656854305839434716e+00,-2.481214017705137276e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.350335674067861191e+01,3.849170940209871787e+02,4.635864047786734332e+00,5.656854305839434716e+00,-2.483714017705137278e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.350512450761397076e+01,3.849267871615696208e+02,4.633405791158745402e+00,5.656854305839434716e+00,-2.486214017705137280e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.350689227454932961e+01,3.849364796872849865e+02,4.630945111322456675e+00,5.656854305839434716e+00,-2.488714017705137282e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.350866004148468846e+01,3.849461715975274956e+02,4.628482008431660688e+00,5.656854305839434716e+00,-2.491214017705137285e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.351042780842004731e+01,3.849558628916914245e+02,4.626016482640300964e+00,5.656854305839434716e+00,-2.493714017705137287e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.351219557535540616e+01,3.849655535691710497e+02,4.623548534102473795e+00,5.656854305839434716e+00,-2.496214017705137289e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.351396334229076501e+01,3.849752436293607616e+02,4.621078162972424686e+00,5.656854305839434716e+00,-2.498714017705137291e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.351573110922612386e+01,3.849849330716548366e+02,4.618605369404552796e+00,5.656854305839434716e+00,-2.501214017705137294e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.351749887616148271e+01,3.849946218954477786e+02,4.616130153553407389e+00,5.656854305839434716e+00,-2.503714017705137018e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.351926664309684156e+01,3.850043101001339778e+02,4.613652515573689605e+00,5.656854305839434716e+00,-2.506214017705136743e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.352103441003220041e+01,3.850139976851079382e+02,4.611172455620251576e+00,5.656854305839434716e+00,-2.508714017705136468e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.352280217696755926e+01,3.850236846497641636e+02,4.608689973848097310e+00,5.656854305839434716e+00,-2.511214017705136192e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.352456994390291811e+01,3.850333709934972148e+02,4.606205070412381808e+00,5.656854305839434716e+00,-2.513714017705135917e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.352633771083827696e+01,3.850430567157017094e+02,4.603717745468411060e+00,5.656854305839434716e+00,-2.516214017705135642e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.352810547777363581e+01,3.850527418157723218e+02,4.601227999171643823e+00,5.656854305839434716e+00,-2.518714017705135366e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.352987324470899466e+01,3.850624262931037265e+02,4.598735831677688957e+00,5.656854305839434716e+00,-2.521214017705135091e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.353164101164435351e+01,3.850721101470905978e+02,4.596241243142306310e+00,5.656854305839434716e+00,-2.523714017705134816e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.353340877857971236e+01,3.850817933771277239e+02,4.593744233721407610e+00,5.656854305839434716e+00,-2.526214017705134540e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.353517654551507121e+01,3.850914759826098930e+02,4.591244803571056465e+00,5.656854305839434716e+00,-2.528714017705134265e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.353694431245043006e+01,3.851011579629319499e+02,4.588742952847467471e+00,5.656854305839434716e+00,-2.531214017705133990e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.353871207938578891e+01,3.851108393174887965e+02,4.586238681707006215e+00,5.656854305839434716e+00,-2.533714017705133714e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.354047984632114776e+01,3.851205200456752777e+02,4.583731990306189275e+00,5.656854305839434716e+00,-2.536214017705133439e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.354224761325650661e+01,3.851302001468864091e+02,4.581222878801685106e+00,5.656854305839434716e+00,-2.538714017705133164e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.354401538019186546e+01,3.851398796205172061e+02,4.578711347350313154e+00,5.656854305839434716e+00,-2.541214017705132888e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.354578314712722431e+01,3.851495584659626275e+02,4.576197396109043858e+00,5.656854305839434716e+00,-2.543714017705132613e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.354755091406258316e+01,3.851592366826178022e+02,4.573681025234999531e+00,5.656854305839434716e+00,-2.546214017705132338e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.354931868099794201e+01,3.851689142698778028e+02,4.571162234885453479e+00,5.656854305839434716e+00,-2.548714017705132062e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.355108644793330086e+01,3.851785912271378152e+02,4.568641025217829110e+00,5.656854305839434716e+00,-2.551214017705131787e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.355285421486865971e+01,3.851882675537930254e+02,4.566117396389703487e+00,5.656854305839434716e+00,-2.553714017705131512e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.355462198180401856e+01,3.851979432492386195e+02,4.563591348558801997e+00,5.656854305839434716e+00,-2.556214017705131236e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.355638974873937741e+01,3.852076183128698972e+02,4.561062881883003683e+00,5.656854305839434716e+00,-2.558714017705130961e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.355815751567473626e+01,3.852172927440821582e+02,4.558531996520336804e+00,5.656854305839434716e+00,-2.561214017705130686e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.355992528261009511e+01,3.852269665422707590e+02,4.555998692628982383e+00,5.656854305839434716e+00,-2.563714017705130410e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.356169304954545396e+01,3.852366397068311130e+02,4.553462970367272433e+00,5.656854305839434716e+00,-2.566214017705130135e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.356346081648081281e+01,3.852463122371586337e+02,4.550924829893688184e+00,5.656854305839434716e+00,-2.568714017705129860e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.356522858341617166e+01,3.852559841326487344e+02,4.548384271366864517e+00,5.656854305839434716e+00,-2.571214017705129584e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.356699635035153051e+01,3.852656553926969991e+02,4.545841294945585531e+00,5.656854305839434716e+00,-2.573714017705129309e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.356876411728688936e+01,3.852753260166988980e+02,4.543295900788788089e+00,5.656854305839434716e+00,-2.576214017705129034e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.357053188422224821e+01,3.852849960040500719e+02,4.540748089055559156e+00,5.656854305839434716e+00,-2.578714017705128758e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.357229965115760706e+01,3.852946653541461615e+02,4.538197859905136688e+00,5.656854305839434716e+00,-2.581214017705128483e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.357406741809296591e+01,3.853043340663828076e+02,4.535645213496909633e+00,5.656854305839434716e+00,-2.583714017705128208e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.357583518502832476e+01,3.853140021401557078e+02,4.533090149990418816e+00,5.656854305839434716e+00,-2.586214017705127932e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.357760295196368361e+01,3.853236695748605598e+02,4.530532669545356050e+00,5.656854305839434716e+00,-2.588714017705127657e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.357937071889904246e+01,3.853333363698932317e+02,4.527972772321563255e+00,5.656854305839434716e+00,-2.591214017705127381e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.358113848583440131e+01,3.853430025246495347e+02,4.525410458479034226e+00,5.656854305839434716e+00,-2.593714017705127106e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.358290625276976016e+01,3.853526680385252803e+02,4.522845728177913749e+00,5.656854305839434716e+00,-2.596214017705126831e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.358467401970511901e+01,3.853623329109164501e+02,4.520278581578497601e+00,5.656854305839434716e+00,-2.598714017705126555e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.358644178664047786e+01,3.853719971412189125e+02,4.517709018841231661e+00,5.656854305839434716e+00,-2.601214017705126280e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.358820955357583671e+01,3.853816607288287059e+02,4.515137040126714574e+00,5.656854305839434716e+00,-2.603714017705126005e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.358997732051119556e+01,3.853913236731418124e+02,4.512562645595694200e+00,5.656854305839434716e+00,-2.606214017705125729e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.359174508744655441e+01,3.854009859735543273e+02,4.509985835409070276e+00,5.656854305839434716e+00,-2.608714017705125454e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.359351285438191326e+01,3.854106476294624031e+02,4.507406609727893532e+00,5.656854305839434716e+00,-2.611214017705125179e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.359528062131727211e+01,3.854203086402621352e+02,4.504824968713366573e+00,5.656854305839434716e+00,-2.613714017705124903e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.359704838825263096e+01,3.854299690053496761e+02,4.502240912526840333e+00,5.656854305839434716e+00,-2.616214017705124628e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.359881615518798981e+01,3.854396287241212917e+02,4.499654441329819399e+00,5.656854305839434716e+00,-2.618714017705124353e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.360058392212334866e+01,3.854492877959732482e+02,4.497065555283958460e+00,5.656854305839434716e+00,-2.621214017705124077e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.360235168905870751e+01,3.854589462203018684e+02,4.494474254551062309e+00,5.656854305839434716e+00,-2.623714017705123802e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.360411945599406636e+01,3.854686039965034752e+02,4.491880539293086727e+00,5.656854305839434716e+00,-2.626214017705123527e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.360588722292942521e+01,3.854782611239745052e+02,4.489284409672139375e+00,5.656854305839434716e+00,-2.628714017705123251e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.360765498986478406e+01,3.854879176021113381e+02,4.486685865850478905e+00,5.656854305839434716e+00,-2.631214017705122976e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.360942275680014291e+01,3.854975734303104673e+02,4.484084907990514068e+00,5.656854305839434716e+00,-2.633714017705122701e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.361119052373550176e+01,3.855072286079683863e+02,4.481481536254804610e+00,5.656854305839434716e+00,-2.636214017705122425e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.361295829067086061e+01,3.855168831344816454e+02,4.478875750806061262e+00,5.656854305839434716e+00,-2.638714017705122150e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.361472605760621946e+01,3.855265370092468515e+02,4.476267551807144862e+00,5.656854305839434716e+00,-2.641214017705121875e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.361649382454157831e+01,3.855361902316606120e+02,4.473656939421069012e+00,5.656854305839434716e+00,-2.643714017705121599e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.361826159147693716e+01,3.855458428011196474e+02,4.471043913810996528e+00,5.656854305839434716e+00,-2.646214017705121324e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.362002935841229601e+01,3.855554947170206219e+02,4.468428475140241218e+00,5.656854305839434716e+00,-2.648714017705121049e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.362179712534765486e+01,3.855651459787603130e+02,4.465810623572267879e+00,5.656854305839434716e+00,-2.651214017705120773e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.362356489228301371e+01,3.855747965857354984e+02,4.463190359270693186e+00,5.656854305839434716e+00,-2.653714017705120498e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.362533265921837256e+01,3.855844465373430694e+02,4.460567682399283029e+00,5.656854305839434716e+00,-2.656214017705120223e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.362710042615373141e+01,3.855940958329798605e+02,4.457942593121954289e+00,5.656854305839434716e+00,-2.658714017705119947e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.362886819308909025e+01,3.856037444720427629e+02,4.455315091602775723e+00,5.656854305839434716e+00,-2.661214017705119672e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.363063596002444910e+01,3.856133924539287818e+02,4.452685178005966193e+00,5.656854305839434716e+00,-2.663714017705119397e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.363240372695980795e+01,3.856230397780349222e+02,4.450052852495894662e+00,5.656854305839434716e+00,-2.666214017705119121e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.363417149389516680e+01,3.856326864437582458e+02,4.447418115237081970e+00,5.656854305839434716e+00,-2.668714017705118846e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.363593926083052565e+01,3.856423324504957577e+02,4.444780966394199062e+00,5.656854305839434716e+00,-2.671214017705118571e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.363770702776588450e+01,3.856519777976446335e+02,4.442141406132067871e+00,5.656854305839434716e+00,-2.673714017705118295e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.363947479470124335e+01,3.856616224846020486e+02,4.439499434615661322e+00,5.656854305839434716e+00,-2.676214017705118020e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.364124256163660220e+01,3.856712665107651787e+02,4.436855052010101552e+00,5.656854305839434716e+00,-2.678714017705117745e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.364301032857196105e+01,3.856809098755313130e+02,4.434208258480663467e+00,5.656854305839434716e+00,-2.681214017705117469e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.364477809550731990e+01,3.856905525782976838e+02,4.431559054192771185e+00,5.656854305839434716e+00,-2.683714017705117194e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.364654586244267875e+01,3.857001946184616941e+02,4.428907439311999816e+00,5.656854305839434716e+00,-2.686214017705116919e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.364831362937803760e+01,3.857098359954206330e+02,4.426253414004075459e+00,5.656854305839434716e+00,-2.688714017705116643e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.365008139631339645e+01,3.857194767085719604e+02,4.423596978434875204e+00,5.656854305839434716e+00,-2.691214017705116368e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.365184916324875530e+01,3.857291167573131361e+02,4.420938132770425355e+00,5.656854305839434716e+00,-2.693714017705116093e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.365361693018411415e+01,3.857387561410416765e+02,4.418276877176904982e+00,5.656854305839434716e+00,-2.696214017705115817e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.365538469711947300e+01,3.857483948591550984e+02,4.415613211820641482e+00,5.656854305839434716e+00,-2.698714017705115542e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.365715246405483185e+01,3.857580329110509751e+02,4.412947136868114129e+00,5.656854305839434716e+00,-2.701214017705115267e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.365892023099019070e+01,3.857676702961269370e+02,4.410278652485953188e+00,5.656854305839434716e+00,-2.703714017705114991e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.366068799792554955e+01,3.857773070137806144e+02,4.407607758840938139e+00,5.656854305839434716e+00,-2.706214017705114716e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.366245576486090840e+01,3.857869430634097512e+02,4.404934456100000340e+00,5.656854305839434716e+00,-2.708714017705114441e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.366422353179626725e+01,3.857965784444120914e+02,4.402258744430221249e+00,5.656854305839434716e+00,-2.711214017705114165e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.366599129873162610e+01,3.858062131561854358e+02,4.399580623998832429e+00,5.656854305839434716e+00,-2.713714017705113890e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.366775906566698495e+01,3.858158471981275852e+02,4.396900094973216433e+00,5.656854305839434716e+00,-2.716214017705113615e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.366952683260234380e+01,3.858254805696363974e+02,4.394217157520906802e+00,5.656854305839434716e+00,-2.718714017705113339e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.367129459953770265e+01,3.858351132701098436e+02,4.391531811809586294e+00,5.656854305839434716e+00,-2.721214017705113064e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.367306236647306150e+01,3.858447452989458384e+02,4.388844058007089544e+00,5.656854305839434716e+00,-2.723714017705112789e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.367483013340842035e+01,3.858543766555423531e+02,4.386153896281401288e+00,5.656854305839434716e+00,-2.726214017705112513e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.367659790034377920e+01,3.858640073392974728e+02,4.383461326800656366e+00,5.656854305839434716e+00,-2.728714017705112238e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.367836566727913805e+01,3.858736373496092824e+02,4.380766349733140608e+00,5.656854305839434716e+00,-2.731214017705111963e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.368013343421449690e+01,3.858832666858758671e+02,4.378068965247289945e+00,5.656854305839434716e+00,-2.733714017705111687e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.368190120114985575e+01,3.858928953474954255e+02,4.375369173511691301e+00,5.656854305839434716e+00,-2.736214017705111412e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.368366896808521460e+01,3.859025233338661565e+02,4.372666974695081699e+00,5.656854305839434716e+00,-2.738714017705111137e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.368543673502057345e+01,3.859121506443863154e+02,4.369962368966348265e+00,5.656854305839434716e+00,-2.741214017705110861e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.368720450195593230e+01,3.859217772784542149e+02,4.367255356494528229e+00,5.656854305839434716e+00,-2.743714017705110586e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.368897226889129115e+01,3.859314032354681672e+02,4.364545937448810697e+00,5.656854305839434716e+00,-2.746214017705110311e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.369074003582665000e+01,3.859410285148265416e+02,4.361834111998533992e+00,5.656854305839434716e+00,-2.748714017705110035e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.369250780276200885e+01,3.859506531159278211e+02,4.359119880313187423e+00,5.656854305839434716e+00,-2.751214017705109760e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.369427556969736770e+01,3.859602770381703749e+02,4.356403242562410405e+00,5.656854305839434716e+00,-2.753714017705109485e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.369604333663272655e+01,3.859699002809527428e+02,4.353684198915992454e+00,5.656854305839434716e+00,-2.756214017705109209e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.369781110356808540e+01,3.859795228436735215e+02,4.350962749543874075e+00,5.656854305839434716e+00,-2.758714017705108934e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.369957887050344425e+01,3.859891447257312507e+02,4.348238894616145878e+00,5.656854305839434716e+00,-2.761214017705108659e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.370134663743880310e+01,3.859987659265245838e+02,4.345512634303048571e+00,5.656854305839434716e+00,-2.763714017705108383e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.370311440437416195e+01,3.860083864454521745e+02,4.342783968774973857e+00,5.656854305839434716e+00,-2.766214017705108108e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.370488217130952080e+01,3.860180062819127329e+02,4.340052898202463538e+00,5.656854305839434716e+00,-2.768714017705107833e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.370664993824487965e+01,3.860276254353050263e+02,4.337319422756208631e+00,5.656854305839434716e+00,-2.771214017705107557e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.370841770518023850e+01,3.860372439050278786e+02,4.334583542607052031e+00,5.656854305839434716e+00,-2.773714017705107282e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.371018547211559735e+01,3.860468616904801138e+02,4.331845257925985848e+00,5.656854305839434716e+00,-2.776214017705107007e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.371195323905095620e+01,3.860564787910606128e+02,4.329104568884153181e+00,5.656854305839434716e+00,-2.778714017705106731e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.371372100598631505e+01,3.860660952061683702e+02,4.326361475652847233e+00,5.656854305839434716e+00,-2.781214017705106456e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.371548877292167390e+01,3.860757109352023235e+02,4.323615978403510418e+00,5.656854305839434716e+00,-2.783714017705106181e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.371725653985703275e+01,3.860853259775614674e+02,4.320868077307737032e+00,5.656854305839434716e+00,-2.786214017705105905e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.371902430679239160e+01,3.860949403326448532e+02,4.318117772537270582e+00,5.656854305839434716e+00,-2.788714017705105630e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.372079207372775045e+01,3.861045539998515892e+02,4.315365064264005568e+00,5.656854305839434716e+00,-2.791214017705105355e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.372255984066310930e+01,3.861141669785808404e+02,4.312609952659986590e+00,5.656854305839434716e+00,-2.793714017705105079e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.372432760759846815e+01,3.861237792682318286e+02,4.309852437897407462e+00,5.656854305839434716e+00,-2.796214017705104804e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.372609537453382700e+01,3.861333908682037190e+02,4.307092520148612991e+00,5.656854305839434716e+00,-2.798714017705104529e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.372786314146918585e+01,3.861430017778958472e+02,4.304330199586098082e+00,5.656854305839434716e+00,-2.801214017705104253e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.372963090840454470e+01,3.861526119967074919e+02,4.301565476382506858e+00,5.656854305839434716e+00,-2.803714017705103978e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.373139867533990355e+01,3.861622215240379887e+02,4.298798350710636207e+00,5.656854305839434716e+00,-2.806214017705103703e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.373316644227526240e+01,3.861718303592867869e+02,4.296028822743430453e+00,5.656854305839434716e+00,-2.808714017705103427e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.373493420921062125e+01,3.861814385018533358e+02,4.293256892653984913e+00,5.656854305839434716e+00,-2.811214017705103152e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.373670197614598010e+01,3.861910459511371414e+02,4.290482560615545893e+00,5.656854305839434716e+00,-2.813714017705102877e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.373846974308133895e+01,3.862006527065377099e+02,4.287705826801508913e+00,5.656854305839434716e+00,-2.816214017705102601e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.374023751001669780e+01,3.862102587674546044e+02,4.284926691385419595e+00,5.656854305839434716e+00,-2.818714017705102326e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.374200527695205665e+01,3.862198641332874445e+02,4.282145154540973664e+00,5.656854305839434716e+00,-2.821214017705102051e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.374377304388741550e+01,3.862294688034359069e+02,4.279361216442017835e+00,5.656854305839434716e+00,-2.823714017705101775e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.374554081082277435e+01,3.862390727772997252e+02,4.276574877262548036e+00,5.656854305839434716e+00,-2.826214017705101500e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.374730857775813320e+01,3.862486760542786328e+02,4.273786137176710298e+00,5.656854305839434716e+00,-2.828714017705101225e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.374907634469349205e+01,3.862582786337724201e+02,4.270994996358800755e+00,5.656854305839434716e+00,-2.831214017705100949e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.375084411162885090e+01,3.862678805151809343e+02,4.268201454983266530e+00,5.656854305839434716e+00,-2.833714017705100674e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.375261187856420975e+01,3.862774816979040793e+02,4.265405513224703071e+00,5.656854305839434716e+00,-2.836214017705100399e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.375437964549956860e+01,3.862870821813417024e+02,4.262607171257856820e+00,5.656854305839434716e+00,-2.838714017705100123e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.375614741243492745e+01,3.862966819648938781e+02,4.259806429257624316e+00,5.656854305839434716e+00,-2.841214017705099848e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.375791517937028630e+01,3.863062810479605673e+02,4.257003287399052205e+00,5.656854305839434716e+00,-2.843714017705099573e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.375968294630564515e+01,3.863158794299417877e+02,4.254197745857336344e+00,5.656854305839434716e+00,-2.846214017705099297e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.376145071324100400e+01,3.863254771102376708e+02,4.251389804807823580e+00,5.656854305839434716e+00,-2.848714017705099022e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.376321848017636285e+01,3.863350740882484047e+02,4.248579464426009977e+00,5.656854305839434716e+00,-2.851214017705098747e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.376498624711172170e+01,3.863446703633741208e+02,4.245766724887541699e+00,5.656854305839434716e+00,-2.853714017705098471e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.376675401404708055e+01,3.863542659350150643e+02,4.242951586368215011e+00,5.656854305839434716e+00,-2.856214017705098196e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.376852178098243940e+01,3.863638608025715371e+02,4.240134049043976283e+00,5.656854305839434716e+00,-2.858714017705097921e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.377028954791779825e+01,3.863734549654438410e+02,4.237314113090921097e+00,5.656854305839434716e+00,-2.861214017705097645e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.377205731485315710e+01,3.863830484230323918e+02,4.234491778685296026e+00,5.656854305839434716e+00,-2.863714017705097370e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.377382508178851594e+01,3.863926411747375482e+02,4.231667046003496857e+00,5.656854305839434716e+00,-2.866214017705097095e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.377559284872387479e+01,3.864022332199597258e+02,4.228839915222069479e+00,5.656854305839434716e+00,-2.868714017705096819e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.377736061565923364e+01,3.864118245580995108e+02,4.226010386517708994e+00,5.656854305839434716e+00,-2.871214017705096544e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.377912838259459249e+01,3.864214151885573756e+02,4.223178460067261497e+00,5.656854305839434716e+00,-2.873714017705096269e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.378089614952995134e+01,3.864310051107339063e+02,4.220344136047722294e+00,5.656854305839434716e+00,-2.876214017705095993e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.378266391646531019e+01,3.864405943240297461e+02,4.217507414636236796e+00,5.656854305839434716e+00,-2.878714017705095718e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.378443168340066904e+01,3.864501828278455946e+02,4.214668296010099624e+00,5.656854305839434716e+00,-2.881214017705095443e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.378619945033602789e+01,3.864597706215821518e+02,4.211826780346755505e+00,5.656854305839434716e+00,-2.883714017705095167e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.378796721727138674e+01,3.864693577046401742e+02,4.208982867823800156e+00,5.656854305839434716e+00,-2.886214017705094892e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.378973498420674559e+01,3.864789440764204755e+02,4.206136558618977617e+00,5.656854305839434716e+00,-2.888714017705094617e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.379150275114210444e+01,3.864885297363239260e+02,4.203287852910182032e+00,5.656854305839434716e+00,-2.891214017705094341e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.379327051807746329e+01,3.864981146837513961e+02,4.200436750875457648e+00,5.656854305839434716e+00,-2.893714017705094066e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.379503828501282214e+01,3.865076989181038698e+02,4.197583252692997924e+00,5.656854305839434716e+00,-2.896214017705093791e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.379680605194818099e+01,3.865172824387822743e+02,4.194727358541147311e+00,5.656854305839434716e+00,-2.898714017705093515e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.379857381888353984e+01,3.865268652451876505e+02,4.191869068598398584e+00,5.656854305839434716e+00,-2.901214017705093240e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.380034158581889869e+01,3.865364473367210962e+02,4.189008383043394623e+00,5.656854305839434716e+00,-2.903714017705092965e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.380210935275425754e+01,3.865460287127837091e+02,4.186145302054928408e+00,5.656854305839434716e+00,-2.906214017705092689e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.380387711968961639e+01,3.865556093727767006e+02,4.183279825811943020e+00,5.656854305839434716e+00,-2.908714017705092414e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.380564488662497524e+01,3.865651893161012254e+02,4.180411954493530757e+00,5.656854305839434716e+00,-2.911214017705092139e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.380741265356033409e+01,3.865747685421585516e+02,4.177541688278933130e+00,5.656854305839434716e+00,-2.913714017705091863e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.380918042049569294e+01,3.865843470503500043e+02,4.174669027347541750e+00,5.656854305839434716e+00,-2.916214017705091588e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.381094818743105179e+01,3.865939248400768520e+02,4.171793971878898333e+00,5.656854305839434716e+00,-2.918714017705091313e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.381271595436641064e+01,3.866035019107405333e+02,4.168916522052693807e+00,5.656854305839434716e+00,-2.921214017705091037e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.381448372130176949e+01,3.866130782617424870e+02,4.166036678048768316e+00,5.656854305839434716e+00,-2.923714017705090762e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.381625148823712834e+01,3.866226538924842089e+02,4.163154440047112104e+00,5.656854305839434716e+00,-2.926214017705090487e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.381801925517248719e+01,3.866322288023671945e+02,4.160269808227865518e+00,5.656854305839434716e+00,-2.928714017705090211e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.381978702210784604e+01,3.866418029907929963e+02,4.157382782771318119e+00,5.656854305839434716e+00,-2.931214017705089936e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.382155478904320489e+01,3.866513764571632805e+02,4.154493363857908683e+00,5.656854305839434716e+00,-2.933714017705089661e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.382332255597856374e+01,3.866609492008796565e+02,4.151601551668226087e+00,5.656854305839434716e+00,-2.936214017705089385e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.382509032291392259e+01,3.866705212213438472e+02,4.148707346383008421e+00,5.656854305839434716e+00,-2.938714017705089110e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.382685808984928144e+01,3.866800925179576325e+02,4.145810748183143879e+00,5.656854305839434716e+00,-2.941214017705088835e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.382862585678464029e+01,3.866896630901227354e+02,4.142911757249668980e+00,5.656854305839434716e+00,-2.943714017705088559e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.383039362371999914e+01,3.866992329372410495e+02,4.140010373763771234e+00,5.656854305839434716e+00,-2.946214017705088284e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.383216139065535799e+01,3.867088020587144115e+02,4.137106597906787364e+00,5.656854305839434716e+00,-2.948714017705088009e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.383392915759071684e+01,3.867183704539448286e+02,4.134200429860202419e+00,5.656854305839434716e+00,-2.951214017705087733e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.383569692452607569e+01,3.867279381223341943e+02,4.131291869805653327e+00,5.656854305839434716e+00,-2.953714017705087458e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.383746469146143454e+01,3.867375050632845728e+02,4.128380917924923565e+00,5.656854305839434716e+00,-2.956214017705087183e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.383923245839679339e+01,3.867470712761980280e+02,4.125467574399948489e+00,5.656854305839434716e+00,-2.958714017705086907e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.384100022533215224e+01,3.867566367604766810e+02,4.122551839412812669e+00,5.656854305839434716e+00,-2.961214017705086632e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.384276799226751109e+01,3.867662015155226527e+02,4.119633713145748111e+00,5.656854305839434716e+00,-2.963714017705086357e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.384453575920286994e+01,3.867757655407381776e+02,4.116713195781138701e+00,5.656854305839434716e+00,-2.966214017705086081e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.384630352613822879e+01,3.867853288355254904e+02,4.113790287501516652e+00,5.656854305839434716e+00,-2.968714017705085806e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.384807129307358764e+01,3.867948913992868825e+02,4.110864988489563387e+00,5.656854305839434716e+00,-2.971214017705085531e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.384983906000894649e+01,3.868044532314247022e+02,4.107937298928110437e+00,5.656854305839434716e+00,-2.973714017705085255e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.385160682694430534e+01,3.868140143313413546e+02,4.105007219000137653e+00,5.656854305839434716e+00,-2.976214017705084980e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.385337459387966419e+01,3.868235746984392449e+02,4.102074748888775879e+00,5.656854305839434716e+00,-2.978714017705084705e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.385514236081502304e+01,3.868331343321208351e+02,4.099139888777304286e+00,5.656854305839434716e+00,-2.981214017705084429e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.385691012775038189e+01,3.868426932317886440e+02,4.096202638849151256e+00,5.656854305839434716e+00,-2.983714017705084154e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.385867789468574074e+01,3.868522513968453040e+02,4.093262999287895276e+00,5.656854305839434716e+00,-2.986214017705083879e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.386044566162109959e+01,3.868618088266933910e+02,4.090320970277264045e+00,5.656854305839434716e+00,-2.988714017705083603e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.386221342855645844e+01,3.868713655207355373e+02,4.087376552001134478e+00,5.656854305839434716e+00,-2.991214017705083328e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.386398119549181729e+01,3.868809214783744892e+02,4.084429744643531812e+00,5.656854305839434716e+00,-2.993714017705083053e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.386574896242717614e+01,3.868904766990129929e+02,4.081480548388632279e+00,5.656854305839434716e+00,-2.996214017705082777e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.386751672936253499e+01,3.869000311820537945e+02,4.078528963420760434e+00,5.656854305839434716e+00,-2.998714017705082502e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.386928449629789384e+01,3.869095849268998109e+02,4.075574989924390046e+00,5.656854305839434716e+00,-3.001214017705082227e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.387105226323325269e+01,3.869191379329539018e+02,4.072618628084144987e+00,5.656854305839434716e+00,-3.003714017705081951e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.387282003016861154e+01,3.869286901996189840e+02,4.069659878084797455e+00,5.656854305839434716e+00,-3.006214017705081676e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.387458779710397039e+01,3.869382417262980880e+02,4.066698740111269750e+00,5.656854305839434716e+00,-3.008714017705081400e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.387635556403932924e+01,3.869477925123942441e+02,4.063735214348632496e+00,5.656854305839434716e+00,-3.011214017705081125e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.387812333097468809e+01,3.869573425573104828e+02,4.060769300982106422e+00,5.656854305839434716e+00,-3.013714017705080850e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.387989109791004694e+01,3.869668918604499481e+02,4.057801000197060581e+00,5.656854305839434716e+00,-3.016214017705080574e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.388165886484540579e+01,3.869764404212158411e+02,4.054830312179014129e+00,5.656854305839434716e+00,-3.018714017705080299e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.388342663178076464e+01,3.869859882390113057e+02,4.051857237113635435e+00,5.656854305839434716e+00,-3.021214017705080024e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.388519439871612349e+01,3.869955353132396567e+02,4.048881775186741194e+00,5.656854305839434716e+00,-3.023714017705079748e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.388696216565148234e+01,3.870050816433042087e+02,4.045903926584298205e+00,5.656854305839434716e+00,-3.026214017705079473e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.388872993258684119e+01,3.870146272286082763e+02,4.042923691492421590e+00,5.656854305839434716e+00,-3.028714017705079198e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.389049769952220004e+01,3.870241720685552878e+02,4.039941070097375686e+00,5.656854305839434716e+00,-3.031214017705078922e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.389226546645755889e+01,3.870337161625486715e+02,4.036956062585574934e+00,5.656854305839434716e+00,-3.033714017705078647e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.389403323339291774e+01,3.870432595099919126e+02,4.033968669143582098e+00,5.656854305839434716e+00,-3.036214017705078372e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.389580100032827659e+01,3.870528021102886100e+02,4.030978889958109157e+00,5.656854305839434716e+00,-3.038714017705078096e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.389756876726363544e+01,3.870623439628423057e+02,4.027986725216018193e+00,5.656854305839434716e+00,-3.041214017705077821e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.389933653419899429e+01,3.870718850670565985e+02,4.024992175104318726e+00,5.656854305839434716e+00,-3.043714017705077546e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.390110430113435314e+01,3.870814254223352577e+02,4.021995239810170375e+00,5.656854305839434716e+00,-3.046214017705077270e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.390287206806971199e+01,3.870909650280819392e+02,4.018995919520881088e+00,5.656854305839434716e+00,-3.048714017705076995e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.390463983500507084e+01,3.871005038837004690e+02,4.015994214423908915e+00,5.656854305839434716e+00,-3.051214017705076720e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.390640760194042969e+01,3.871100419885946167e+02,4.012990124706860229e+00,5.656854305839434716e+00,-3.053714017705076444e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.390817536887578854e+01,3.871195793421682652e+02,4.009983650557490620e+00,5.656854305839434716e+00,-3.056214017705076169e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.390994313581114739e+01,3.871291159438253544e+02,4.006974792163704890e+00,5.656854305839434716e+00,-3.058714017705075894e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.391171090274650624e+01,3.871386517929698243e+02,4.003963549713556169e+00,5.656854305839434716e+00,-3.061214017705075618e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.391347866968186509e+01,3.871481868890057285e+02,4.000949923395247687e+00,5.656854305839434716e+00,-3.063714017705075343e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.391524643661722394e+01,3.871577212313370637e+02,3.997933913397130556e+00,5.656854305839434716e+00,-3.066214017705075068e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.391701420355258279e+01,3.871672548193679404e+02,3.994915519907705992e+00,5.656854305839434716e+00,-3.068714017705074792e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.391878197048794163e+01,3.871767876525025827e+02,3.991894743115623090e+00,5.656854305839434716e+00,-3.071214017705074517e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.392054973742330048e+01,3.871863197301451009e+02,3.988871583209680605e+00,5.656854305839434716e+00,-3.073714017705074242e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.392231750435865933e+01,3.871958510516997762e+02,3.985846040378826061e+00,5.656854305839434716e+00,-3.076214017705073966e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.392408527129401818e+01,3.872053816165708895e+02,3.982818114812156196e+00,5.656854305839434716e+00,-3.078714017705073691e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.392585303822937703e+01,3.872149114241627785e+02,3.979787806698916075e+00,5.656854305839434716e+00,-3.081214017705073416e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.392762080516473588e+01,3.872244404738798380e+02,3.976755116228499531e+00,5.656854305839434716e+00,-3.083714017705073140e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.392938857210009473e+01,3.872339687651265194e+02,3.973720043590450501e+00,5.656854305839434716e+00,-3.086214017705072865e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.393115633903545358e+01,3.872434962973072743e+02,3.970682588974460359e+00,5.656854305839434716e+00,-3.088714017705072590e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.393292410597081243e+01,3.872530230698266678e+02,3.967642752570370135e+00,5.656854305839434716e+00,-3.091214017705072314e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.393469187290617128e+01,3.872625490820892651e+02,3.964600534568170076e+00,5.656854305839434716e+00,-3.093714017705072039e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.393645963984153013e+01,3.872720743334996882e+02,3.961555935157998309e+00,5.656854305839434716e+00,-3.096214017705071764e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.393822740677688898e+01,3.872815988234626161e+02,3.958508954530142621e+00,5.656854305839434716e+00,-3.098714017705071488e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.393999517371224783e+01,3.872911225513827276e+02,3.955459592875039121e+00,5.656854305839434716e+00,-3.101214017705071213e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.394176294064760668e+01,3.873006455166648152e+02,3.952407850383273136e+00,5.656854305839434716e+00,-3.103714017705070938e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.394353070758296553e+01,3.873101677187137284e+02,3.949353727245578316e+00,5.656854305839434716e+00,-3.106214017705070662e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.394529847451832438e+01,3.873196891569342597e+02,3.946297223652837083e+00,5.656854305839434716e+00,-3.108714017705070387e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.394706624145368323e+01,3.873292098307313722e+02,3.943238339796081515e+00,5.656854305839434716e+00,-3.111214017705070112e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.394883400838904208e+01,3.873387297395099722e+02,3.940177075866491574e+00,5.656854305839434716e+00,-3.113714017705069836e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.395060177532440093e+01,3.873482488826751364e+02,3.937113432055395990e+00,5.656854305839434716e+00,-3.116214017705069561e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.395236954225975978e+01,3.873577672596318848e+02,3.934047408554273151e+00,5.656854305839434716e+00,-3.118714017705069286e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.395413730919511863e+01,3.873672848697852942e+02,3.930979005554748884e+00,5.656854305839434716e+00,-3.121214017705069010e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.395590507613047748e+01,3.873768017125405549e+02,3.927908223248598674e+00,5.656854305839434716e+00,-3.123714017705068735e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.395767284306583633e+01,3.873863177873028576e+02,3.924835061827746330e+00,5.656854305839434716e+00,-3.126214017705068460e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.395944061000119518e+01,3.873958330934773926e+02,3.921759521484264432e+00,5.656854305839434716e+00,-3.128714017705068184e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.396120837693655403e+01,3.874053476304695209e+02,3.918681602410374332e+00,5.656854305839434716e+00,-3.131214017705067909e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.396297614387191288e+01,3.874148613976845468e+02,3.915601304798446147e+00,5.656854305839434716e+00,-3.133714017705067634e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.396474391080727173e+01,3.874243743945278879e+02,3.912518628840998325e+00,5.656854305839434716e+00,-3.136214017705067358e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.396651167774263058e+01,3.874338866204049623e+02,3.909433574730698080e+00,5.656854305839434716e+00,-3.138714017705067083e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.396827944467798943e+01,3.874433980747212445e+02,3.906346142660360954e+00,5.656854305839434716e+00,-3.141214017705066808e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.397004721161334828e+01,3.874529087568823229e+02,3.903256332822952146e+00,5.656854305839434716e+00,-3.143714017705066532e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.397181497854870713e+01,3.874624186662937291e+02,3.900164145411584293e+00,5.656854305839434716e+00,-3.146214017705066257e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.397358274548406598e+01,3.874719278023611082e+02,3.897069580619519247e+00,5.656854305839434716e+00,-3.148714017705065982e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.397535051241942483e+01,3.874814361644901055e+02,3.893972638640167183e+00,5.656854305839434716e+00,-3.151214017705065706e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.397711827935478368e+01,3.874909437520864799e+02,3.890873319667087049e+00,5.656854305839434716e+00,-3.153714017705065431e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.397888604629014253e+01,3.875004505645560471e+02,3.887771623893986117e+00,5.656854305839434716e+00,-3.156214017705065156e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.398065381322550138e+01,3.875099566013045660e+02,3.884667551514720873e+00,5.656854305839434716e+00,-3.158714017705064880e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.398242158016086023e+01,3.875194618617379660e+02,3.881561102723295242e+00,5.656854305839434716e+00,-3.161214017705064605e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.398418934709621908e+01,3.875289663452621198e+02,3.878452277713862806e+00,5.656854305839434716e+00,-3.163714017705064330e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.398595711403157793e+01,3.875384700512830136e+02,3.875341076680724584e+00,5.656854305839434716e+00,-3.166214017705064054e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.398772488096693678e+01,3.875479729792066337e+02,3.872227499818331253e+00,5.656854305839434716e+00,-3.168714017705063779e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.398949264790229563e+01,3.875574751284390800e+02,3.869111547321280931e+00,5.656854305839434716e+00,-3.171214017705063504e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.399126041483765448e+01,3.875669764983865093e+02,3.865993219384320501e+00,5.656854305839434716e+00,-3.173714017705063228e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.399302818177301333e+01,3.875764770884550217e+02,3.862872516202346063e+00,5.656854305839434716e+00,-3.176214017705062953e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.399479594870837218e+01,3.875859768980508306e+02,3.859749437970401154e+00,5.656854305839434716e+00,-3.178714017705062678e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.399656371564373103e+01,3.875954759265802636e+02,3.856623984883678080e+00,5.656854305839434716e+00,-3.181214017705062402e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.399833148257908988e+01,3.876049741734495910e+02,3.853496157137517919e+00,5.656854305839434716e+00,-3.183714017705062127e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.400009924951444873e+01,3.876144716380651403e+02,3.850365954927409629e+00,5.656854305839434716e+00,-3.186214017705061852e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.400186701644980758e+01,3.876239683198333523e+02,3.847233378448990937e+00,5.656854305839434716e+00,-3.188714017705061576e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.400363478338516643e+01,3.876334642181606682e+02,3.844098427898047898e+00,5.656854305839434716e+00,-3.191214017705061301e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.400540255032052528e+01,3.876429593324536427e+02,3.840961103470514892e+00,5.656854305839434716e+00,-3.193714017705061026e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.400717031725588413e+01,3.876524536621187735e+02,3.837821405362475069e+00,5.656854305839434716e+00,-3.196214017705060750e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.400893808419124298e+01,3.876619472065626724e+02,3.834679333770159015e+00,5.656854305839434716e+00,-3.198714017705060475e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.401070585112660183e+01,3.876714399651920075e+02,3.831534888889946533e+00,5.656854305839434716e+00,-3.201214017705060200e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.401247361806196068e+01,3.876809319374135043e+02,3.828388070918365305e+00,5.656854305839434716e+00,-3.203714017705059924e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.401424138499731953e+01,3.876904231226338879e+02,3.825238880052091783e+00,5.656854305839434716e+00,-3.206214017705059649e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.401600915193267838e+01,3.876999135202599973e+02,3.822087316487949860e+00,5.656854305839434716e+00,-3.208714017705059374e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.401777691886803723e+01,3.877094031296986145e+02,3.818933380422912638e+00,5.656854305839434716e+00,-3.211214017705059098e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.401954468580339608e+01,3.877188919503566922e+02,3.815777072054100660e+00,5.656854305839434716e+00,-3.213714017705058823e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.402131245273875493e+01,3.877283799816411261e+02,3.812618391578783683e+00,5.656854305839434716e+00,-3.216214017705058548e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.402308021967411378e+01,3.877378672229589824e+02,3.809457339194378900e+00,5.656854305839434716e+00,-3.218714017705058272e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.402484798660947263e+01,3.877473536737172708e+02,3.806293915098452274e+00,5.656854305839434716e+00,-3.221214017705057997e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.402661575354483148e+01,3.877568393333230574e+02,3.803128119488718095e+00,5.656854305839434716e+00,-3.223714017705057722e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.402838352048019033e+01,3.877663242011835791e+02,3.799959952563038090e+00,5.656854305839434716e+00,-3.226214017705057446e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.403015128741554918e+01,3.877758082767059591e+02,3.796789414519422756e+00,5.656854305839434716e+00,-3.228714017705057171e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.403191905435090803e+01,3.877852915592974341e+02,3.793616505556030916e+00,5.656854305839434716e+00,-3.231214017705056896e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.403368682128626688e+01,3.877947740483653547e+02,3.790441225871169273e+00,5.656854305839434716e+00,-3.233714017705056620e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.403545458822162573e+01,3.878042557433170145e+02,3.787263575663292858e+00,5.656854305839434716e+00,-3.236214017705056345e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.403722235515698458e+01,3.878137366435598210e+02,3.784083555131005028e+00,5.656854305839434716e+00,-3.238714017705056070e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.403899012209234343e+01,3.878232167485012383e+02,3.780901164473056575e+00,5.656854305839434716e+00,-3.241214017705055794e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.404075788902770228e+01,3.878326960575487306e+02,3.777716403888347063e+00,5.656854305839434716e+00,-3.243714017705055519e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.404252565596306113e+01,3.878421745701098757e+02,3.774529273575924382e+00,5.656854305839434716e+00,-3.246214017705055244e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.404429342289841998e+01,3.878516522855922517e+02,3.771339773734983858e+00,5.656854305839434716e+00,-3.248714017705054968e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.404606118983377883e+01,3.878611292034034932e+02,3.768147904564869144e+00,5.656854305839434716e+00,-3.251214017705054693e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.404782895676913768e+01,3.878706053229512918e+02,3.764953666265072219e+00,5.656854305839434716e+00,-3.253714017705054418e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.404959672370449653e+01,3.878800806436433959e+02,3.761757059035232942e+00,5.656854305839434716e+00,-3.256214017705054142e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.405136449063985538e+01,3.878895551648876108e+02,3.758558083075139500e+00,5.656854305839434716e+00,-3.258714017705053867e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.405313225757521423e+01,3.878990288860917417e+02,3.755356738584727516e+00,5.656854305839434716e+00,-3.261214017705053592e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.405490002451057308e+01,3.879085018066637076e+02,3.752153025764081384e+00,5.656854305839434716e+00,-3.263714017705053316e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.405666779144593193e+01,3.879179739260114275e+02,3.748946944813432935e+00,5.656854305839434716e+00,-3.266214017705053041e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.405843555838129078e+01,3.879274452435429339e+02,3.745738495933162326e+00,5.656854305839434716e+00,-3.268714017705052766e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.406020332531664963e+01,3.879369157586662595e+02,3.742527679323797596e+00,5.656854305839434716e+00,-3.271214017705052490e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.406197109225200848e+01,3.879463854707894939e+02,3.739314495186014664e+00,5.656854305839434716e+00,-3.273714017705052215e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.406373885918736732e+01,3.879558543793207832e+02,3.736098943720637333e+00,5.656854305839434716e+00,-3.276214017705051940e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.406550662612272617e+01,3.879653224836682739e+02,3.732881025128637731e+00,5.656854305839434716e+00,-3.278714017705051664e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.406727439305808502e+01,3.879747897832402828e+02,3.729660739611135867e+00,5.656854305839434716e+00,-3.281214017705051389e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.406904215999344387e+01,3.879842562774450698e+02,3.726438087369399632e+00,5.656854305839434716e+00,-3.283714017705051114e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.407080992692880272e+01,3.879937219656909519e+02,3.723213068604844800e+00,5.656854305839434716e+00,-3.286214017705050838e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.407257769386416157e+01,3.880031868473863597e+02,3.719985683519035025e+00,5.656854305839434716e+00,-3.288714017705050563e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.407434546079952042e+01,3.880126509219397235e+02,3.716755932313681843e+00,5.656854305839434716e+00,-3.291214017705050288e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.407611322773487927e+01,3.880221141887595309e+02,3.713523815190644672e+00,5.656854305839434716e+00,-3.293714017705050012e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.407788099467023812e+01,3.880315766472543260e+02,3.710289332351930813e+00,5.656854305839434716e+00,-3.296214017705049737e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.407964876160559697e+01,3.880410382968327099e+02,3.707052483999695447e+00,5.656854305839434716e+00,-3.298714017705049462e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.408141652854095582e+01,3.880504991369033405e+02,3.703813270336241636e+00,5.656854305839434716e+00,-3.301214017705049186e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.408318429547631467e+01,3.880599591668749326e+02,3.700571691564020327e+00,5.656854305839434716e+00,-3.303714017705048911e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.408495206241167352e+01,3.880694183861562010e+02,3.697327747885630345e+00,5.656854305839434716e+00,-3.306214017705048636e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.408671982934703237e+01,3.880788767941559740e+02,3.694081439503817510e+00,5.656854305839434716e+00,-3.308714017705048360e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.408848759628239122e+01,3.880883343902830802e+02,3.690832766621476857e+00,5.656854305839434716e+00,-3.311214017705048085e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.409025536321775007e+01,3.880977911739464048e+02,3.687581729441649969e+00,5.656854305839434716e+00,-3.313714017705047810e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.409202313015310892e+01,3.881072471445549468e+02,3.684328328167526756e+00,5.656854305839434716e+00,-3.316214017705047534e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.409379089708846777e+01,3.881167023015176483e+02,3.681072563002445008e+00,5.656854305839434716e+00,-3.318714017705047259e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.409555866402382662e+01,3.881261566442436219e+02,3.677814434149889511e+00,5.656854305839434716e+00,-3.321214017705046984e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.409732643095918547e+01,3.881356101721419236e+02,3.674553941813493818e+00,5.656854305839434716e+00,-3.323714017705046708e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.409909419789454432e+01,3.881450628846217228e+02,3.671291086197038478e+00,5.656854305839434716e+00,-3.326214017705046433e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.410086196482990317e+01,3.881545147810922458e+02,3.668025867504451920e+00,5.656854305839434716e+00,-3.328714017705046158e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.410262973176526202e+01,3.881639658609627190e+02,3.664758285939810456e+00,5.656854305839434716e+00,-3.331214017705045882e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.410439749870062087e+01,3.881734161236424825e+02,3.661488341707337835e+00,5.656854305839434716e+00,-3.333714017705045607e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.410616526563597972e+01,3.881828655685408762e+02,3.658216035011405687e+00,5.656854305839434716e+00,-3.336214017705045332e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.410793303257133857e+01,3.881923141950672971e+02,3.654941366056533525e+00,5.656854305839434716e+00,-3.338714017705045056e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.410970079950669742e+01,3.882017620026312557e+02,3.651664335047387411e+00,5.656854305839434716e+00,-3.341214017705044781e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.411146856644205627e+01,3.882112089906422057e+02,3.648384942188782176e+00,5.656854305839434716e+00,-3.343714017705044506e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.411323633337741512e+01,3.882206551585097145e+02,3.645103187685680091e+00,5.656854305839434716e+00,-3.346214017705044230e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.411500410031277397e+01,3.882301005056434064e+02,3.641819071743190417e+00,5.656854305839434716e+00,-3.348714017705043955e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.411677186724813282e+01,3.882395450314529626e+02,3.638532594566570300e+00,5.656854305839434716e+00,-3.351214017705043680e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.411853963418349167e+01,3.882489887353481208e+02,3.635243756361225209e+00,5.656854305839434716e+00,-3.353714017705043404e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.412030740111885052e+01,3.882584316167386191e+02,3.631952557332706721e+00,5.656854305839434716e+00,-3.356214017705043129e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.412207516805420937e+01,3.882678736750342523e+02,3.628658997686715182e+00,5.656854305839434716e+00,-3.358714017705042854e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.412384293498956822e+01,3.882773149096449288e+02,3.625363077629098374e+00,5.656854305839434716e+00,-3.361214017705042578e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.412561070192492707e+01,3.882867553199805570e+02,3.622064797365851074e+00,5.656854305839434716e+00,-3.363714017705042303e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.412737846886028592e+01,3.882961949054511024e+02,3.618764157103115497e+00,5.656854305839434716e+00,-3.366214017705042028e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.412914623579564477e+01,3.883056336654666438e+02,3.615461157047181739e+00,5.656854305839434716e+00,-3.368714017705041752e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.413091400273100362e+01,3.883150715994372035e+02,3.612155797404487778e+00,5.656854305839434716e+00,-3.371214017705041477e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.413268176966636247e+01,3.883245087067729173e+02,3.608848078381618141e+00,5.656854305839434716e+00,-3.373714017705041202e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.413444953660172132e+01,3.883339449868839779e+02,3.605538000185305236e+00,5.656854305839434716e+00,-3.376214017705040926e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.413621730353708017e+01,3.883433804391806348e+02,3.602225563022428911e+00,5.656854305839434716e+00,-3.378714017705040651e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.413798507047243902e+01,3.883528150630731375e+02,3.598910767100016894e+00,5.656854305839434716e+00,-3.381214017705040376e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.413975283740779787e+01,3.883622488579718492e+02,3.595593612625243463e+00,5.656854305839434716e+00,-3.383714017705040100e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.414152060434315672e+01,3.883716818232871333e+02,3.592274099805431220e+00,5.656854305839434716e+00,-3.386214017705039825e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.414328837127851557e+01,3.883811139584294096e+02,3.588952228848049320e+00,5.656854305839434716e+00,-3.388714017705039550e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.414505613821387442e+01,3.883905452628092121e+02,3.585627999960715240e+00,5.656854305839434716e+00,-3.391214017705039274e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.414682390514923327e+01,3.883999757358370744e+02,3.582301413351192565e+00,5.656854305839434716e+00,-3.393714017705038999e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.414859167208459212e+01,3.884094053769235870e+02,3.578972469227393649e+00,5.656854305839434716e+00,-3.396214017705038724e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.415035943901995097e+01,3.884188341854793975e+02,3.575641167797376951e+00,5.656854305839434716e+00,-3.398714017705038448e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.415212720595530982e+01,3.884282621609152102e+02,3.572307509269349257e+00,5.656854305839434716e+00,-3.401214017705038173e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.415389497289066867e+01,3.884376893026417861e+02,3.568971493851663901e+00,5.656854305839434716e+00,-3.403714017705037898e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.415566273982602752e+01,3.884471156100699432e+02,3.565633121752821655e+00,5.656854305839434716e+00,-3.406214017705037622e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.415743050676138637e+01,3.884565410826104994e+02,3.562292393181471173e+00,5.656854305839434716e+00,-3.408714017705037347e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.415919827369674522e+01,3.884659657196743865e+02,3.558949308346408102e+00,5.656854305839434716e+00,-3.411214017705037072e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.416096604063210407e+01,3.884753895206725360e+02,3.555603867456574640e+00,5.656854305839434716e+00,-3.413714017705036796e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.416273380756746292e+01,3.884848124850159934e+02,3.552256070721061310e+00,5.656854305839434716e+00,-3.416214017705036521e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.416450157450282177e+01,3.884942346121158039e+02,3.548905918349105182e+00,5.656854305839434716e+00,-3.418714017705036246e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.416626934143818062e+01,3.885036559013830697e+02,3.545553410550091211e+00,5.656854305839434716e+00,-3.421214017705035970e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.416803710837353947e+01,3.885130763522290067e+02,3.542198547533550901e+00,5.656854305839434716e+00,-3.423714017705035695e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.416980487530889832e+01,3.885224959640647739e+02,3.538841329509162748e+00,5.656854305839434716e+00,-3.426214017705035420e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.417157264224425717e+01,3.885319147363017009e+02,3.535481756686753574e+00,5.656854305839434716e+00,-3.428714017705035144e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.417334040917961602e+01,3.885413326683510604e+02,3.532119829276296308e+00,5.656854305839434716e+00,-3.431214017705034869e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.417510817611497487e+01,3.885507497596242956e+02,3.528755547487911315e+00,5.656854305839434716e+00,-3.433714017705034593e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.417687594305033372e+01,3.885601660095327929e+02,3.525388911531866398e+00,5.656854305839434716e+00,-3.436214017705034318e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.417864370998569257e+01,3.885695814174880525e+02,3.522019921618576355e+00,5.656854305839434716e+00,-3.438714017705034043e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.418041147692105142e+01,3.885789959829016311e+02,3.518648577958602974e+00,5.656854305839434716e+00,-3.441214017705033767e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.418217924385641027e+01,3.885884097051850858e+02,3.515274880762655041e+00,5.656854305839434716e+00,-3.443714017705033492e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.418394701079176912e+01,3.885978225837500872e+02,3.511898830241588776e+00,5.656854305839434716e+00,-3.446214017705033217e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.418571477772712797e+01,3.886072346180083059e+02,3.508520426606407394e+00,5.656854305839434716e+00,-3.448714017705032941e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.418748254466248682e+01,3.886166458073714693e+02,3.505139670068261104e+00,5.656854305839434716e+00,-3.451214017705032666e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.418925031159784567e+01,3.886260561512514187e+02,3.501756560838447108e+00,5.656854305839434716e+00,-3.453714017705032391e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.419101807853320452e+01,3.886354656490599950e+02,3.498371099128409600e+00,5.656854305839434716e+00,-3.456214017705032115e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.419278584546856337e+01,3.886448743002090964e+02,3.494983285149740215e+00,5.656854305839434716e+00,-3.458714017705031840e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.419455361240392222e+01,3.886542821041107345e+02,3.491593119114177579e+00,5.656854305839434716e+00,-3.461214017705031565e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.419632137933928107e+01,3.886636890601768641e+02,3.488200601233606424e+00,5.656854305839434716e+00,-3.463714017705031289e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.419808914627463992e+01,3.886730951678195538e+02,3.484805731720059363e+00,5.656854305839434716e+00,-3.466214017705031014e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.419985691320999877e+01,3.886825004264509289e+02,3.481408510785716004e+00,5.656854305839434716e+00,-3.468714017705030739e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.420162468014535762e+01,3.886919048354831716e+02,3.478008938642902503e+00,5.656854305839434716e+00,-3.471214017705030463e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.420339244708071647e+01,3.887013083943285210e+02,3.474607015504092011e+00,5.656854305839434716e+00,-3.473714017705030188e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.420516021401607532e+01,3.887107111023992161e+02,3.471202741581904672e+00,5.656854305839434716e+00,-3.476214017705029913e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.420692798095143417e+01,3.887201129591076096e+02,3.467796117089107621e+00,5.656854305839434716e+00,-3.478714017705029637e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.420869574788679301e+01,3.887295139638660544e+02,3.464387142238614992e+00,5.656854305839434716e+00,-3.481214017705029362e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.421046351482215186e+01,3.887389141160870167e+02,3.460975817243487906e+00,5.656854305839434716e+00,-3.483714017705029087e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.421223128175751071e+01,3.887483134151830200e+02,3.457562142316934040e+00,5.656854305839434716e+00,-3.486214017705028811e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.421399904869286956e+01,3.887577118605665305e+02,3.454146117672307614e+00,5.656854305839434716e+00,-3.488714017705028536e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.421576681562822841e+01,3.887671094516501853e+02,3.450727743523110735e+00,5.656854305839434716e+00,-3.491214017705028261e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.421753458256358726e+01,3.887765061878466781e+02,3.447307020082991613e+00,5.656854305839434716e+00,-3.493714017705027985e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.421930234949894611e+01,3.887859020685686460e+02,3.443883947565745451e+00,5.656854305839434716e+00,-3.496214017705027710e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.422107011643430496e+01,3.887952970932288963e+02,3.440458526185314447e+00,5.656854305839434716e+00,-3.498714017705027435e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.422283788336966381e+01,3.888046912612401798e+02,3.437030756155786904e+00,5.656854305839434716e+00,-3.501214017705027159e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.422460565030502266e+01,3.888140845720154175e+02,3.433600637691399005e+00,5.656854305839434716e+00,-3.503714017705026884e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.422637341724038151e+01,3.888234770249675307e+02,3.430168171006533040e+00,5.656854305839434716e+00,-3.506214017705026609e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.422814118417574036e+01,3.888328686195094406e+02,3.426733356315717849e+00,5.656854305839434716e+00,-3.508714017705026333e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.422990895111109921e+01,3.888422593550541819e+02,3.423296193833629708e+00,5.656854305839434716e+00,-3.511214017705026058e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.423167671804645806e+01,3.888516492310149033e+02,3.419856683775091000e+00,5.656854305839434716e+00,-3.513714017705025783e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.423344448498181691e+01,3.888610382468046396e+02,3.416414826355071543e+00,5.656854305839434716e+00,-3.516214017705025507e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.423521225191717576e+01,3.888704264018366530e+02,3.412970621788687264e+00,5.656854305839434716e+00,-3.518714017705025232e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.423698001885253461e+01,3.888798136955241489e+02,3.409524070291200637e+00,5.656854305839434716e+00,-3.521214017705024957e-01,0.000000000000000000e+00,-6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.423874778578789346e+01,3.888892001272804464e+02,3.406075172078021129e+00,5.656854305839434716e+00,-3.523714017705024681e-01,0.000000000000000000e+00,-6.839316092015533532e-02,-1.136868399864502285e-08,0.000000000000000000e+00 +6.424051555272325231e+01,3.888985856965188646e+02,3.402623927364705203e+00,5.656854305839434716e+00,-3.526214017705024406e-01,-2.009718367133727080e-11,-6.839316092015533532e-02,6.337728690434598375e-05,0.000000000000000000e+00 +6.424228331965861116e+01,3.889079704026527793e+02,3.399170336366955425e+00,5.656854305839399188e+00,-3.528714017705024131e-01,1.120161750585236386e-07,-6.839316092015533532e-02,-6.018556849369633976e-01,0.000000000000000000e+00 +6.424405108659397001e+01,3.889173542450956802e+02,3.395714399300621356e+00,5.656854306037417679e+00,-3.531214017705023855e-01,-1.063828563513702450e-03,-6.839316092015533532e-02,-9.999915936716478049e-01,0.000000000000000000e+00 +6.424581885352927202e+01,3.889267372232611137e+02,3.392256116381699105e+00,5.656852425436458276e+00,-3.533714017705023580e-01,-2.831580638380438997e-03,-6.839316092015533532e-02,-9.999955363138088860e-01,0.000000000000000000e+00 +6.424758662105224971e+01,3.889361193365625695e+02,3.388795487826331332e+00,5.656847419860167037e+00,-3.536214017705023305e-01,-4.599340270604985841e-03,-6.839316092015533532e-02,-9.999968264281742236e-01,0.000000000000000000e+00 +6.424935439013947303e+01,3.889455005844137077e+02,3.385332513850807246e+00,5.656839289288615014e+00,-3.538714017705023029e-01,-6.367103747691828415e-03,-6.839316092015533532e-02,-9.999974500772101926e-01,0.000000000000000000e+00 +6.425112216176751190e+01,3.889548809662281883e+02,3.381867194671562604e+00,5.656828033703257042e+00,-3.541214017705022754e-01,-8.134870868053076243e-03,-6.839316092015533532e-02,-9.999978025427691541e-01,0.000000000000000000e+00 +6.425288993691295047e+01,3.889642604814197853e+02,3.378399530505180159e+00,5.656813653080725146e+00,-3.543714017705022479e-01,-9.902642128881236974e-03,-6.839316092015533532e-02,-9.999980147645798345e-01,0.000000000000000000e+00 +6.425465771655238711e+01,3.889736391294022155e+02,3.374929521568388768e+00,5.656796147391593088e+00,-3.546214017705022203e-01,-1.167041825885853715e-02,-6.839316092015533532e-02,-9.999981426282402719e-01,0.000000000000000000e+00 +6.425642550166244860e+01,3.889830169095893666e+02,3.371457168078063837e+00,5.656775516599966913e+00,-3.548714017705021928e-01,-1.343820008548375460e-02,-6.839316092015533532e-02,-9.999982095977214547e-01,0.000000000000000000e+00 +6.425819329321979012e+01,3.889923938213950692e+02,3.367982470251227767e+00,5.656751760663309980e+00,-3.551214017705021653e-01,-1.520598847776341751e-02,-6.839316092015533532e-02,-9.999982291683812141e-01,0.000000000000000000e+00 +6.425996109220109531e+01,3.890017698642333244e+02,3.364505428305049062e+00,5.656724879532369243e+00,-3.553714017705021377e-01,-1.697378432859481673e-02,-6.839316092015533532e-02,-9.999982025935365559e-01,0.000000000000000000e+00 +6.426172889958310463e+01,3.890111450375180766e+02,3.361026042456842777e+00,5.656694873151132619e+00,-3.556214017705021102e-01,-1.874158853312987011e-02,-6.839316092015533532e-02,-9.999981268426533232e-01,0.000000000000000000e+00 +6.426349671634258698e+01,3.890205193406633839e+02,3.357544312924070518e+00,5.656661741456824544e+00,-3.558714017705020827e-01,-2.050940198120717803e-02,-6.839316092015533532e-02,-9.999979883492996491e-01,0.000000000000000000e+00 +6.426526454345636807e+01,3.890298927730834180e+02,3.354060239924339992e+00,5.656625484379914859e+00,-3.561214017705020551e-01,-2.227722553873133504e-02,-6.839316092015533532e-02,-9.999977584650011631e-01,0.000000000000000000e+00 +6.426703238190131628e+01,3.890392653341922937e+02,3.350573823675406349e+00,5.656586101844160552e+00,-3.563714017705020276e-01,-2.404506002101476289e-02,-6.839316092015533532e-02,-9.999973755569625533e-01,0.000000000000000000e+00 +6.426880023265439945e+01,3.890486370234041829e+02,3.347085064395170395e+00,5.656543593766694578e+00,-3.566214017705020001e-01,-2.581290613446991442e-02,-6.839316092015533532e-02,-9.999966864698439650e-01,0.000000000000000000e+00 +6.427056809669261384e+01,3.890580078401334276e+02,3.343593962301679490e+00,5.656497960058217700e+00,-3.568714017705019725e-01,-2.758076431481135821e-02,-6.839316092015533532e-02,-9.999952035632249103e-01,0.000000000000000000e+00 +6.427233597499304096e+01,3.890673777837943135e+02,3.340100517613127540e+00,5.656449200623476337e+00,-3.571214017705019450e-01,-2.934863413572248031e-02,-6.839316092015533532e-02,-9.999901220698570459e-01,0.000000000000000000e+00 +6.427410386853284763e+01,3.890767468538012395e+02,3.336604730547855002e+00,5.656397315362785783e+00,-3.573714017705019175e-01,-3.111651021239551784e-02,-6.839316092015533532e-02,9.999496962156104729e-01,0.000000000000000000e+00 +6.427587177828925746e+01,3.890861150495686047e+02,3.333106601324348439e+00,5.656342304180795644e+00,-3.576214017705018899e-01,-2.934868938852986525e-02,-6.839316092015533532e-02,9.999935601395295581e-01,0.000000000000000000e+00 +6.427763970523960779e+01,3.890954823705109220e+02,3.329606130161240962e+00,5.656290417841868035e+00,-3.578714017705018624e-01,-2.758077382337674466e-02,-6.839316092015533532e-02,9.999967240926425083e-01,0.000000000000000000e+00 +6.427940764840752763e+01,3.891048488160427041e+02,3.326103317277312232e+00,5.656241656601221024e+00,-3.581214017705018349e-01,-2.581283644707387318e-02,-6.839316092015533532e-02,9.999978717949077334e-01,0.000000000000000000e+00 +6.428117560681650389e+01,3.891142143855785775e+02,3.322598162891488016e+00,5.656196020579964845e+00,-3.583714017705018073e-01,-2.404488180067392358e-02,-6.839316092015533532e-02,9.999984599835537447e-01,0.000000000000000000e+00 +6.428294357948993820e+01,3.891235790785332256e+02,3.319090667222840185e+00,5.656153509886005182e+00,-3.586214017705017798e-01,-2.227691184994188070e-02,-6.839316092015533532e-02,9.999988149185062847e-01,0.000000000000000000e+00 +6.428471156545116116e+01,3.891329428943212747e+02,3.315580830490587161e+00,5.656114124618595085e+00,-3.588714017705017523e-01,-2.050892798392644004e-02,-6.839316092015533532e-02,9.999990508409593026e-01,0.000000000000000000e+00 +6.428647956372341810e+01,3.891423058323575788e+02,3.312068652914093914e+00,5.656077864869353711e+00,-3.591214017705017247e-01,-1.874093138978347520e-02,-6.839316092015533532e-02,9.999992177459999798e-01,0.000000000000000000e+00 +6.428824757332988327e+01,3.891516678920568779e+02,3.308554134712871519e+00,5.656044730722622482e+00,-3.593714017705016972e-01,-1.697292316635160350e-02,-6.839316092015533532e-02,9.999993417359042125e-01,0.000000000000000000e+00 +6.429001559329367410e+01,3.891610290728340829e+02,3.305037276106577604e+00,5.656014722255620519e+00,-3.596214017705016697e-01,-1.520490436638687395e-02,-6.839316092015533532e-02,9.999994366718109040e-01,0.000000000000000000e+00 +6.429178362263783697e+01,3.891703893741041043e+02,3.301518077315015454e+00,5.655987839538525463e+00,-3.598714017705016421e-01,-1.343687601819860966e-02,-6.839316092015533532e-02,9.999995115621903574e-01,0.000000000000000000e+00 +6.429355166038538982e+01,3.891797487952819097e+02,3.297996538558134905e+00,5.655964082634516110e+00,-3.601214017705016146e-01,-1.166883913422295249e-02,-6.839316092015533532e-02,9.999995719839250841e-01,0.000000000000000000e+00 +6.429531970555927956e+01,3.891891073357825803e+02,3.294472660056032343e+00,5.655943451599799943e+00,-3.603714017705015871e-01,-9.900794717084202001e-03,-6.839316092015533532e-02,9.999996212191059053e-01,0.000000000000000000e+00 +6.429708775718242464e+01,3.891984649950211406e+02,3.290946442028950258e+00,5.655925946483630007e+00,-3.606214017705015595e-01,-8.132743763646445995e-03,-6.839316092015533532e-02,9.999996625281828422e-01,0.000000000000000000e+00 +6.429885581427770092e+01,3.892078217724127853e+02,3.287417884697277248e+00,5.655911567328314682e+00,-3.608714017705015320e-01,-6.364687265046253123e-03,-6.839316092015533532e-02,9.999996974453008169e-01,0.000000000000000000e+00 +6.430062387586794159e+01,3.892171776673727095e+02,3.283886988281548014e+00,5.655900314169227450e+00,-3.611214017705015045e-01,-4.596626209739352112e-03,-6.839316092015533532e-02,9.999997263466120501e-01,0.000000000000000000e+00 +6.430239194097597988e+01,3.892265326793161648e+02,3.280353753002443806e+00,5.655892187034811336e+00,-3.613714017705014769e-01,-2.828561585542562189e-03,-6.839316092015533532e-02,9.999997518597760759e-01,0.000000000000000000e+00 +6.430416000862460635e+01,3.892358868076584599e+02,3.276818179080791982e+00,5.655887185946579798e+00,-3.616214017705014494e-01,-1.060494375647528208e-03,-6.839316092015533532e-02,9.999997740338998353e-01,0.000000000000000000e+00 +6.430592807783659737e+01,3.892452400518150171e+02,3.273280266737565558e+00,5.655885310919124720e+00,-3.618714017705014219e-01,7.075744368256789126e-04,-6.839316092015533532e-02,9.999997934649084153e-01,0.000000000000000000e+00 +6.430769614763474351e+01,3.892545924112012017e+02,3.269740016193884102e+00,5.655886561960116410e+00,-3.621214017705013943e-01,2.475643869800798254e-03,-6.839316092015533532e-02,9.999998095908246842e-01,0.000000000000000000e+00 +6.430946421704180693e+01,3.892639438852324929e+02,3.266197427671013287e+00,5.655890939070305379e+00,-3.623714017705013668e-01,4.243712940203551477e-03,-6.839316092015533532e-02,9.999998252376959273e-01,0.000000000000000000e+00 +6.431123228508054979e+01,3.892732944733244267e+02,3.262652501390364890e+00,5.655898442243520563e+00,-3.626214017705013393e-01,6.011780669957322680e-03,-6.839316092015533532e-02,9.999998380960043454e-01,0.000000000000000000e+00 +6.431300035077376265e+01,3.892826441748925959e+02,3.259105237573496794e+00,5.655909071466678206e+00,-3.628714017705013117e-01,7.779846076908539416e-03,-6.839316092015533532e-02,9.999998503807577821e-01,0.000000000000000000e+00 +6.431476841314422188e+01,3.892919929893526501e+02,3.255555636442112988e+00,5.655922826719774754e+00,-3.631214017705012842e-01,9.547908182831752258e-03,-6.839316092015533532e-02,9.999998603078651405e-01,0.000000000000000000e+00 +6.431653647121473227e+01,3.893013409161202389e+02,3.252003698218063565e+00,5.655939707975893960e+00,-3.633714017705012567e-01,1.131596600636437626e-02,-6.839316092015533532e-02,9.999998703336855366e-01,0.000000000000000000e+00 +6.431830452400814124e+01,3.893106879546111827e+02,3.248449423123344726e+00,5.655959715201201554e+00,-3.636214017705012291e-01,1.308401857050947407e-02,-6.839316092015533532e-02,9.999998791995949876e-01,0.000000000000000000e+00 +6.432007257054728200e+01,3.893200341042412447e+02,3.244892811380098330e+00,5.655982848354953241e+00,-3.638714017705012016e-01,1.485206489607284776e-02,-6.839316092015533532e-02,9.999998867620639720e-01,0.000000000000000000e+00 +6.432184060985505880e+01,3.893293793644263019e+02,3.241333863210612787e+00,5.656009107389491142e+00,-3.641214017705011741e-01,1.662010400364000509e-02,-6.839316092015533532e-02,9.999998939926979524e-01,0.000000000000000000e+00 +6.432360864095439013e+01,3.893387237345822882e+02,3.237772578837322612e+00,5.656038492250243799e+00,-3.643714017705011465e-01,1.838813491555316496e-02,-6.839316092015533532e-02,9.999999004210969877e-01,0.000000000000000000e+00 +6.432537666286826550e+01,3.893480672141251944e+02,3.234208958482807983e+00,5.656071002875729725e+00,-3.646214017705011190e-01,2.015615665336713269e-02,-6.839316092015533532e-02,9.999999066920083335e-01,0.000000000000000000e+00 +6.432714467461968866e+01,3.893574098024710679e+02,3.230643002369795180e+00,5.656106639197556518e+00,-3.648714017705010915e-01,2.192416823982631241e-02,-6.839316092015533532e-02,9.999999122922914596e-01,0.000000000000000000e+00 +6.432891267523174861e+01,3.893667514990359564e+02,3.227074710721156148e+00,5.656145401140423523e+00,-3.651214017705010639e-01,2.369216869682293572e-02,-6.839316092015533532e-02,9.999999166873991818e-01,0.000000000000000000e+00 +6.433068066372759120e+01,3.893760923032360211e+02,3.223504083759909378e+00,5.656187288622120946e+00,-3.653714017705010364e-01,2.546015704536463628e-02,-6.839316092015533532e-02,9.999999221629052304e-01,0.000000000000000000e+00 +6.433244863913040490e+01,3.893854322144874232e+02,3.219931121709219024e+00,5.656232301553528963e+00,-3.656214017705010089e-01,2.722813231056578354e-02,-6.839316092015533532e-02,9.999999261525479577e-01,0.000000000000000000e+00 +6.433421660046347768e+01,3.893947712322064376e+02,3.216355824792395346e+00,5.656280439838625718e+00,-3.658714017705009813e-01,2.899609351307489910e-02,-6.839316092015533532e-02,9.999999300467761199e-01,0.000000000000000000e+00 +6.433598454675015432e+01,3.894041093558093962e+02,3.212778193232894264e+00,5.656331703374480213e+00,-3.661214017705009538e-01,3.076403967607544906e-02,-6.839316092015533532e-02,9.999999340781543511e-01,0.000000000000000000e+00 +6.433775247701386490e+01,3.894134465847126876e+02,3.209198227254317803e+00,5.656386092051257641e+00,-3.663714017705009263e-01,3.253196982324409875e-02,-6.839316092015533532e-02,9.999999373212417053e-01,0.000000000000000000e+00 +6.433952039027813896e+01,3.894227829183327003e+02,3.205615927080413652e+00,5.656443605752221160e+00,-3.666214017705008987e-01,3.429988297670883562e-02,-6.839316092015533532e-02,9.999999408184373495e-01,0.000000000000000000e+00 +6.434128828556659130e+01,3.894321183560859367e+02,3.202031292935075601e+00,5.656504244353730115e+00,-3.668714017705008712e-01,3.606777816053335917e-02,-6.839316092015533532e-02,9.999999433174546759e-01,0.000000000000000000e+00 +6.434305616190293620e+01,3.894414528973888991e+02,3.198444325042343550e+00,5.656568007725244485e+00,-3.671214017705008437e-01,3.783565439666567581e-02,-6.839316092015533532e-02,9.999999466706765983e-01,0.000000000000000000e+00 +6.434482401831098741e+01,3.894507865416582035e+02,3.194855023626402613e+00,5.656634895729322210e+00,-3.673714017705008161e-01,3.960351071043219373e-02,-6.839316092015533532e-02,9.999999490148038239e-01,0.000000000000000000e+00 +6.434659185381465818e+01,3.894601192883104659e+02,3.191263388911584453e+00,5.656704908221626305e+00,-3.676214017705007886e-01,4.137134612397424388e-02,-6.839316092015533532e-02,9.999999518755207095e-01,0.000000000000000000e+00 +6.434835966743800384e+01,3.894694511367624159e+02,3.187669421122365954e+00,5.656778045050920412e+00,-3.678714017705007611e-01,4.313915966224471377e-02,-6.839316092015533532e-02,9.999999536310509862e-01,0.000000000000000000e+00 +6.435012745820517921e+01,3.894787820864307832e+02,3.184073120483370545e+00,5.656854306059075022e+00,-3.681214017705007335e-01,4.490695034744924402e-02,-6.839316092015533532e-02,9.999999509328341141e-01,5.656854306059080351e-01 +6.435189522514046701e+01,3.894881121367324113e+02,3.180474487219366431e+00,5.656933691081063920e+00,-3.683714017705007060e-01,4.667471719599920743e-02,-6.739316092015533444e-02,9.999999472320436622e-01,5.656933691081068583e-01 +6.435366296726829205e+01,3.894974412870842002e+02,3.176873521555268365e+00,5.657016199944955304e+00,-3.686177352603979829e-01,4.844245923053760311e-02,-6.639316092015533355e-02,9.999999434009342325e-01,5.657016199944959745e-01 +6.435543068361319285e+01,3.895067695501144840e+02,3.173270257918283654e+00,5.657101832471924219e+00,-3.688604027351042314e-01,5.021017547538531023e-02,-6.539316092015533266e-02,9.999999391536725790e-01,5.657101832471929104e-01 +6.435719837319986425e+01,3.895160969384752434e+02,3.169664730721381662e+00,5.657190588476256998e+00,-3.690994046821004515e-01,5.197786495449923522e-02,-6.439316092015533177e-02,9.999999338988914133e-01,5.657190588476261883e-01 +6.435896603505314317e+01,3.895254234648415945e+02,3.166056974363499421e+00,5.657282467765352152e+00,-3.693347415814407508e-01,5.374552669093763529e-02,-6.339316092015533088e-02,9.999999287295104899e-01,5.657282467765356593e-01 +6.436073366819802288e+01,3.895347491419115045e+02,3.162447023229745913e+00,5.657377470139720366e+00,-3.695664139057562858e-01,5.551315970984276038e-02,-6.239316092015533000e-02,9.999999227274940505e-01,5.657377470139725029e-01 +6.436250127165965296e+01,3.895440739824053935e+02,3.158834911691605907e+00,5.657475595392989831e+00,-3.697944221202590920e-01,5.728076303489152560e-02,-6.139316092015532911e-02,9.999999149534772869e-01,5.657475595392994494e-01 +6.436426884446335350e+01,3.895533979990657940e+02,3.155220674107145573e+00,5.657576843311905357e+00,-3.700187666827457478e-01,5.904833568826328705e-02,-6.039316092015532822e-02,9.999999072896772478e-01,5.657576843311910020e-01 +6.436603638563458674e+01,3.895627212046570094e+02,3.151604344821217651e+00,5.657681213676327481e+00,-3.702394480436010382e-01,6.081587669563259108e-02,-5.939316092015532733e-02,9.999998973329228269e-01,5.657681213676332144e-01 +6.436780389419901383e+01,3.895720436119647161e+02,3.147985958165667064e+00,5.657788706259240463e+00,-3.704564666458017852e-01,6.258338507859984023e-02,-5.839316092015532644e-02,9.999998860702230541e-01,5.657788706259244682e-01 +6.436957136918246647e+01,3.895813652337956796e+02,3.144365548459536974e+00,5.657899320826746958e+00,-3.706698229249201226e-01,6.435085986068903030e-02,-5.739316092015532556e-02,9.999998724773458969e-01,5.657899320826751399e-01 +6.437133880961096111e+01,3.895906860829773564e+02,3.140743150009274842e+00,5.658013057138073343e+00,-3.708795173091272157e-01,6.611830006379823543e-02,-5.639316092015532467e-02,9.999998552243527516e-01,5.658013057138078228e-01 +6.437310621451069892e+01,3.896000061723574959e+02,3.137118797108939372e+00,5.658129914945568828e+00,-3.710855502191965916e-01,6.788570470766480680e-02,-5.539316092015532378e-02,9.999998346660639026e-01,5.658129914945573269e-01 +6.437487358290809425e+01,3.896093255148038565e+02,3.133492524040406568e+00,5.658249893994703683e+00,-3.712879220685076365e-01,6.965307281284852103e-02,-5.439316092015532289e-02,9.999998071551275958e-01,5.658249893994709012e-01 +6.437664091382973197e+01,3.896186441232038078e+02,3.129864365073577126e+00,5.658372994024072788e+00,-3.714866332630487045e-01,7.142040339366373392e-02,-5.339316092015532200e-02,9.999997712972977792e-01,5.658372994024077896e-01 +6.437840820630242433e+01,3.896279620104639889e+02,3.126234354466584264e+00,5.658499214765386753e+00,-3.716816842014206146e-01,7.318769546216720434e-02,-5.239316092015532111e-02,9.999997205578748938e-01,5.658499214765391194e-01 +6.438017545935318253e+01,3.896372791895099112e+02,3.122602526466000672e+00,5.658628555943470140e+00,-3.718730752748397594e-01,7.495494801907921778e-02,-5.139316092015532023e-02,9.999996443979006777e-01,5.658628555943475691e-01 +6.438194267200924514e+01,3.896465956732857308e+02,3.118968915307047229e+00,5.658761017276243699e+00,-3.720608068671412139e-01,7.672216004671365830e-02,-5.039316092015531934e-02,9.999995174651038488e-01,5.658761017276248140e-01 +6.438370984329806390e+01,3.896559114747537933e+02,3.115333555213799954e+00,5.658896598474694173e+00,-3.722448793547818990e-01,7.848933048280752611e-02,-4.939316092015531845e-02,9.999992634669007119e-01,5.658896598474698614e-01 +6.438547697224731792e+01,3.896652266068942936e+02,3.111696480399399611e+00,5.659035299242797912e+00,-3.724252931068434691e-01,8.025645813051263122e-02,-4.839316092015531756e-02,9.999985005778749825e-01,5.659035299242802797e-01 +6.438724405788492788e+01,3.896745410827048772e+02,3.108057725066259991e+00,5.659177119277285506e+00,-3.726020484850354197e-01,8.202354111851180296e-02,-4.739316092015531667e-02,-4.383362119087423903e-01,5.659177119277289947e-01 +6.438901109923904187e+01,3.896838549152003566e+02,3.104417323406276186e+00,5.659322058266452515e+00,-3.727751458436979193e-01,8.124898290506482601e-02,-4.639316092015531579e-02,-9.999984677836916136e-01,5.659322058266457178e-01 +6.439077809533804952e+01,3.896931681174124265e+02,3.100775309601034646e+00,5.659465624902294323e+00,-3.729445855298046952e-01,7.948198951347472396e-02,-4.539316092015531490e-02,-9.999992304752388650e-01,5.659465624902298986e-01 +6.439254504661273870e+01,3.897024807023890958e+02,3.097131717822021901e+00,5.659606065704980260e+00,-3.731103678829657544e-01,7.771503959849489218e-02,-4.439316092015531401e-02,-9.999994845677034894e-01,5.659606065704985145e-01 +6.439431195404125674e+01,3.897117926831945738e+02,3.093486582230834614e+00,5.659743380985754690e+00,-3.732724932354301584e-01,7.594813308069445212e-02,-4.339316092015531312e-02,-9.999996113084635985e-01,5.659743380985760020e-01 +6.439607881860150940e+01,3.897211040729088154e+02,3.089839936979389190e+00,5.659877571050512479e+00,-3.734309619120886881e-01,7.418126920720502504e-02,-4.239316092015531223e-02,-9.999996878582861903e-01,5.659877571050517808e-01 +6.439784564127116084e+01,3.897304148846270664e+02,3.086191816210131833e+00,5.660008636198611498e+00,-3.735857742304764528e-01,7.241444708904977434e-02,-4.139316092015531134e-02,-9.999997378818202831e-01,5.660008636198615717e-01 +6.439961242302764788e+01,3.897397251314596929e+02,3.082542254056249043e+00,5.660136576722634594e+00,-3.737369305007753884e-01,7.064766579566743310e-02,-4.039316092015531046e-02,-9.999997742149435709e-01,5.660136576722639701e-01 +6.440137916484817993e+01,3.897490348265317834e+02,3.078891284641878112e+00,5.660261392908318534e+00,-3.738844310258168657e-01,6.888092437404264023e-02,-3.939316092015530957e-02,-9.999998017071530798e-01,5.660261392908323419e-01 +6.440314586770973904e+01,3.897583439829826943e+02,3.075238942082316740e+00,5.660383085034516704e+00,-3.740282761010839674e-01,6.711422186281225388e-02,-3.839316092015530868e-02,-9.999998220572002827e-01,5.660383085034521589e-01 +6.440491253258909410e+01,3.897676526139658222e+02,3.071585260484235747e+00,5.660501653373186670e+00,-3.741684660147139296e-01,6.534755729782706912e-02,-3.739316092015530779e-02,-9.999998389348251360e-01,5.660501653373192221e-01 +6.440667916046280084e+01,3.897769607326481491e+02,3.067930273945888686e+00,5.660617098189387519e+00,-3.743050010475004186e-01,6.358092970866470461e-02,-3.639316092015530690e-02,-9.999998528584574942e-01,5.660617098189392182e-01 +6.440844575230721603e+01,3.897862683522100156e+02,3.064274016557324121e+00,5.660729419741270974e+00,-3.744378814728959171e-01,6.181433812419184076e-02,-3.539316092015530602e-02,-9.999998637558602521e-01,5.660729419741276081e-01 +6.441021230909848327e+01,3.897955754858446653e+02,3.060616522400596118e+00,5.660838618280082279e+00,-3.745671075570137232e-01,6.004778157360234764e-02,-3.439316092015530513e-02,-9.999998738103046403e-01,5.660838618280087386e-01 +6.441197883181257566e+01,3.898048821467579614e+02,3.056957825549976082e+00,5.660944694050162873e+00,-3.746926795586302261e-01,5.828125908242747649e-02,-3.339316092015530424e-02,-9.999998814837506300e-01,5.660944694050168424e-01 +6.441374532142525311e+01,3.898141883481679884e+02,3.053297960072165917e+00,5.661047647288945939e+00,-3.748145977291869047e-01,5.651476967910441795e-02,-3.239316092015530335e-02,-9.999998889167412974e-01,5.661047647288950380e-01 +6.441551177891210500e+01,3.898234941033047676e+02,3.049636960026508081e+00,5.661147478226963514e+00,-3.749328623127923810e-01,5.474831238847264331e-02,-3.139316092015530246e-02,-9.999998945282770890e-01,5.661147478226967733e-01 +6.441727820524853598e+01,3.898327994254098030e+02,3.045974859465198747e+00,5.661244187087842050e+00,-3.750474735462243081e-01,5.298188623834261535e-02,-3.039316092015530157e-02,-9.999999004162466454e-01,5.661244187087847157e-01 +6.441904460140979438e+01,3.898421043277359104e+02,3.042311692433499637e+00,5.661337774088309516e+00,-3.751584316589314239e-01,5.121549025299182434e-02,-2.939316092015530069e-02,-9.999999046720112750e-01,5.661337774088314179e-01 +6.442081096837092957e+01,3.898514088235465920e+02,3.038647492969951625e+00,5.661428239438190957e+00,-3.752657368730351606e-01,4.944912346023664501e-02,-2.839316092015529980e-02,-9.999999090660768308e-01,5.661428239438195398e-01 +6.442257730710686303e+01,3.898607129261160367e+02,3.034982295106586125e+00,5.661515583340416491e+00,-3.753693894033316436e-01,4.768278488492810885e-02,-2.739316092015529891e-02,-9.999999127855907499e-01,5.661515583340420710e-01 +6.442434361859233150e+01,3.898700166487284378e+02,3.031316132869137814e+00,5.661599805991017753e+00,-3.754693894572932455e-01,4.591647355350973042e-02,-2.639316092015529802e-02,-9.999999161349799603e-01,5.661599805991022194e-01 +6.442610990380192959e+01,3.898793200046779361e+02,3.027649040277258674e+00,5.661680907579132338e+00,-3.755657372350704182e-01,4.415018849203859730e-02,-2.539316092015529713e-02,-9.999999191125858999e-01,5.661680907579137445e-01 +6.442787616371010984e+01,3.898886230072679950e+02,3.023981051344730275e+00,5.661758888287004687e+00,-3.756584329294931357e-01,4.238392872672064327e-02,-2.439316092015529625e-02,-9.999999219801186667e-01,5.661758888287009572e-01 +6.442964239929119685e+01,3.898979256698113431e+02,3.020312200079676046e+00,5.661833748289987867e+00,-3.757474767260724491e-01,4.061769328344009417e-02,-2.339316092015529536e-02,-9.999999241237610415e-01,5.661833748289992752e-01 +6.443140861151934473e+01,3.899072280056293494e+02,3.016642520484776657e+00,5.661905487756544453e+00,-3.758328688030020959e-01,3.885148118930047828e-02,-2.239316092015529447e-02,-9.999999266166427203e-01,5.661905487756550004e-01 +6.443317480136860809e+01,3.899165300280518522e+02,3.012972046557481853e+00,5.661974106848250088e+00,-3.759146093311598880e-01,3.708529146963972234e-02,-2.139316092015529358e-02,-9.999999285175339425e-01,5.661974106848255417e-01 +6.443494096981291364e+01,3.899258317504168190e+02,3.009300812290224059e+00,5.662039605719791702e+00,-3.759926984741089329e-01,3.531912315158256682e-02,-2.039316092015529269e-02,-9.999999302874379437e-01,5.662039605719796365e-01 +6.443670711782606020e+01,3.899351331860698906e+02,3.005628851670633317e+00,5.662101984518971953e+00,-3.760671363880991880e-01,3.355297526155855831e-02,-1.939316092015529180e-02,-9.999999317966087320e-01,5.662101984518976838e-01 +6.443847324638173291e+01,3.899444343483640978e+02,3.001956198681749122e+00,5.662161243386709231e+00,-3.761379232220684599e-01,3.178684682634005249e-02,-1.839316092015529092e-02,-9.999999337482237127e-01,5.662161243386714116e-01 +6.444023935645351742e+01,3.899537352506595198e+02,2.998282887302235800e+00,5.662217382457039427e+00,-3.762050591176437919e-01,3.002073687156579795e-02,-1.739316092015529003e-02,-9.999999348308918901e-01,5.662217382457044312e-01 +6.444200544901488570e+01,3.899630359063229434e+02,2.994608951506596117e+00,5.662270401857115054e+00,-3.762685442091424637e-01,2.825464442529352846e-02,-1.639316092015528914e-02,-9.999999362746836429e-01,5.662270401857120161e-01 +6.444377152503921025e+01,3.899723363287274651e+02,2.990934425265384444e+00,5.662320301707210568e+00,-3.763283786235732120e-01,2.648856851350608888e-02,-1.539316092015528825e-02,-9.999999372950882925e-01,5.662320301707215453e-01 +6.444553758549979250e+01,3.899816365312522066e+02,2.987259342545422136e+00,5.662367082120719708e+00,-3.763845624806370638e-01,2.472250816366402051e-02,-1.439316092015528736e-02,-9.999999379405766220e-01,5.662367082120725037e-01 +6.444730363136982021e+01,3.899909365272819741e+02,2.983583737310011585e+00,5.662410743204159047e+00,-3.764370958927284461e-01,2.295646240322906165e-02,-1.339316092015528648e-02,-9.999999396622087922e-01,5.662410743204163710e-01 +6.444906966362242429e+01,3.900002363302068034e+02,2.979907643519148941e+00,5.662451285057168882e+00,-3.764859789649360744e-01,2.119043025718176862e-02,-1.239316092015528559e-02,-9.999999396181799005e-01,5.662451285057173989e-01 +6.445083568323065037e+01,3.900095359534217891e+02,2.976231095129740822e+00,5.662488707772509677e+00,-3.765312117950436188e-01,1.942441075559751124e-02,-1.139316092015528470e-02,-9.999999412104697560e-01,5.662488707772515006e-01 +6.445260169116745885e+01,3.900188354103265738e+02,2.972554126095817040e+00,5.662523011436071840e+00,-3.765727944735307586e-01,1.765840292261439473e-02,-1.039316092015528381e-02,-9.999999412698835632e-01,5.662523011436076947e-01 +6.445436768840575326e+01,3.900281347143250628e+02,2.968876770368745976e+00,5.662554196126865946e+00,-3.766107270835736820e-01,1.589240578803273116e-02,-9.393160920155282922e-03,-9.999999423016233679e-01,5.662554196126871053e-01 +6.445613367591839449e+01,3.900374338788251976e+02,2.965199061897448196e+00,5.662582261917033399e+00,-3.766450097010458631e-01,1.412641837728862912e-02,-8.393160920155282034e-03,-9.999999422330427823e-01,5.662582261917032955e-01 +6.445789965467815819e+01,3.900467329172383870e+02,2.961521034628612270e+00,5.662607208871839326e+00,-3.766756423945186172e-01,1.236043971953311449e-02,-7.393160920155282013e-03,-9.999999432421202705e-01,5.662607208871839326e-01 +6.445966562565780578e+01,3.900560318429793369e+02,2.957842722506908828e+00,5.662629037049679681e+00,-3.767026252252617113e-01,1.059446884012021917e-02,-6.393160920155281993e-03,-9.999999434984797597e-01,5.662629037049680125e-01 +6.446143158983002763e+01,3.900653306694655953e+02,2.954164159475205054e+00,5.662647746502075030e+00,-3.767259582472437529e-01,8.828504767680298709e-03,-5.393160920155281972e-03,-9.999999437136498637e-01,5.662647746502075252e-01 +6.446319754816748571e+01,3.900746294101173248e+02,2.950485379474779624e+00,5.662663337273676767e+00,-3.767456415071327447e-01,7.062546529625726363e-03,-4.393160920155281951e-03,-9.999999437235314037e-01,5.662663337273676767e-01 +6.446496350164279932e+01,3.900839280783569052e+02,2.946806416445538090e+00,5.662675809402265337e+00,-3.767616750442964180e-01,5.296593153691872211e-03,-3.393160920155281930e-03,-9.999999441972029501e-01,5.662675809402265559e-01 +6.446672945122857357e+01,3.900932266876084782e+02,2.943127304326226934e+00,5.662685162918751125e+00,-3.767740588908024546e-01,3.530643666460393359e-03,-2.393160920155281909e-03,-9.999999443584942638e-01,5.662685162918751347e-01 +6.446849539789738515e+01,3.901025252512977772e+02,2.939448077054648056e+00,5.662691397847172681e+00,-3.767827930714188200e-01,1.764697095906118517e-03,-1.393160920155281889e-03,-9.999999445492111505e-01,5.662691397847172681e-01 +6.447026134262179653e+01,3.901118237828516726e+02,2.935768768567874609e+00,5.662694514204699381e+00,-3.767878776036140409e-01,-1.247530582601304555e-06,-3.931609201552818678e-04,-9.999999439507132326e-01,5.662694514204699159e-01 +6.447202728637435598e+01,3.901211222956978872e+02,2.932089412802465933e+00,5.662694512001630542e+00,-3.767893124975571495e-01,-1.767191184159963308e-03,6.068390798447181531e-04,-9.999999445711733603e-01,5.662694512001630320e-01 +6.447379323012759755e+01,3.901304208032645988e+02,2.928410043694681164e+00,5.662691391241398087e+00,-3.767870977561179613e-01,-3.533134839520062683e-03,1.606839079844718174e-03,-9.999999441254703303e-01,5.662691391241397865e-01 +6.447555917485406951e+01,3.901397193189801555e+02,2.924730695180695506e+00,5.662685151920560322e+00,-3.767812333748670195e-01,-5.299079467320530305e-03,2.606839079844718195e-03,-9.999999437249065259e-01,5.662685151920560100e-01 +6.447732512152632012e+01,3.901490178562726783e+02,2.921051401196814279e+00,5.662675794028809051e+00,-3.767717193420754840e-01,-7.065026040185782945e-03,3.606839079844718216e-03,-9.999999438899370707e-01,5.662675794028809717e-01 +6.447909107111689764e+01,3.901583164285696625e+02,2.917372195679688307e+00,5.662663317548966013e+00,-3.767585556387151313e-01,-8.830975531668977530e-03,4.606839079844718236e-03,-9.999999434109740903e-01,5.662663317548966013e-01 +6.448085702459836455e+01,3.901676150492978650e+02,2.913693112566528409e+00,5.662647722456981114e+00,-3.767417422384582437e-01,-1.059692891320220161e-02,5.606839079844718257e-03,-9.999999430508127451e-01,5.662647722456981558e-01 +6.448262298294331174e+01,3.901769137318826211e+02,2.910014185795320785e+00,5.662629008721935975e+00,-3.767212791076772760e-01,-1.236288715758495499e-02,6.606839079844718278e-03,-9.999999424118101166e-01,5.662629008721935531e-01 +6.448438894712437275e+01,3.901862124897477884e+02,2.906335449305041063e+00,5.662607176306041268e+00,-3.766971662054446335e-01,-1.412885123694022915e-02,7.606839079844718299e-03,-9.999999422142765715e-01,5.662607176306045931e-01 +6.448615491811418110e+01,3.901955113363152918e+02,2.902656937035870133e+00,5.662582225164637606e+00,-3.766694034835323945e-01,-1.589482212469412598e-02,8.606839079844719187e-03,-9.999999414484992410e-01,5.662582225164642935e-01 +6.448792089688541296e+01,3.902048102850047258e+02,2.898978682929408190e+00,5.662554155246192877e+00,-3.766379908864118664e-01,-1.766080079252605253e-02,9.606839079844720075e-03,-9.999999407923105821e-01,5.662554155246197762e-01 +6.448968688441080133e+01,3.902141093492330697e+02,2.895300720928889682e+00,5.662522966492304910e+00,-3.766029283512531411e-01,-1.942678821335423051e-02,1.060683907984472096e-02,-9.999999403326790270e-01,5.662522966492309351e-01 +6.449145288166312184e+01,3.902234085424143473e+02,2.891623084979398683e+00,5.662488658837698807e+00,-3.765642158079245960e-01,-2.119278536029761337e-02,1.160683907984472185e-02,-9.999999389962055396e-01,5.662488658837703248e-01 +6.449321888961519278e+01,3.902327078779592853e+02,2.887945809028082067e+00,5.662451232210226060e+00,-3.765218531789924494e-01,-2.295879320463203171e-02,1.260683907984472274e-02,-9.999999382512904100e-01,5.662451232210231611e-01 +6.449498490923988925e+01,3.902420073692749725e+02,2.884268927024365770e+00,5.662410686530867210e+00,-3.764758403797199282e-01,-2.472481272028437260e-02,1.360683907984472363e-02,-9.999999372668006981e-01,5.662410686530872095e-01 +6.449675094151017163e+01,3.902513070297644617e+02,2.880592472920169289e+00,5.662367021713726523e+00,-3.764261773180667681e-01,-2.649084487977695912e-02,1.460683907984472452e-02,-9.999999363294600485e-01,5.662367021713731186e-01 +6.449851698739904293e+01,3.902606068728264290e+02,2.876916480670118403e+00,5.662320237666033762e+00,-3.763728638946883809e-01,-2.825689065620705723e-02,1.560683907984472540e-02,-9.999999345656586103e-01,5.662320237666038647e-01 +6.450028304787960565e+01,3.902699069118549460e+02,2.873240984231761885e+00,5.662270334288142415e+00,-3.763159000029350776e-01,-3.002295102120303497e-02,1.660683907984472629e-02,-9.999999339281572253e-01,5.662270334288147522e-01 +6.450204912392500489e+01,3.902792071602389115e+02,2.869566017565785110e+00,5.662217311473531467e+00,-3.762552855288512910e-01,-3.178902694992125771e-02,1.760683907984472718e-02,-9.999999317922192432e-01,5.662217311473536352e-01 +6.450381521650851369e+01,3.902885076313619948e+02,2.865891614636223661e+00,5.662161169108798298e+00,-3.761910203511745210e-01,-3.355511941296729361e-02,1.860683907984472807e-02,-9.999999300680191272e-01,5.662161169108802516e-01 +6.450558132660346189e+01,3.902978083386020103e+02,2.862217809410678715e+00,5.662101907073665785e+00,-3.761231043413344466e-01,-3.532122938441025622e-02,1.960683907984472896e-02,-9.999999289357995869e-01,5.662101907073670004e-01 +6.450734745518329305e+01,3.903071092953308039e+02,2.858544635860530647e+00,5.662039525240975202e+00,-3.760515373634519820e-01,-3.708735783873302189e-02,2.060683907984472985e-02,-9.999999262765790764e-01,5.662039525240980531e-01 +6.450911360322155019e+01,3.903164105149136844e+02,2.854872127961153083e+00,5.661974023476684437e+00,-3.759763192743380000e-01,-3.885350574677684521e-02,2.160683907984473073e-02,-9.999999245059983943e-01,5.661974023476689100e-01 +6.451087977169186161e+01,3.903257120107093101e+02,2.851200319692127394e+00,5.661905401639873325e+00,-3.758974499234922773e-01,-4.061967408375546928e-02,2.260683907984473162e-02,-9.999999214624833987e-01,5.661905401639878432e-01 +6.451264596156799769e+01,3.903350137960691200e+02,2.847529245037456302e+00,5.661833659582734768e+00,-3.758149291531024394e-01,-4.238586382117646295e-02,2.360683907984473251e-02,-9.999999195188917778e-01,5.661833659582738987e-01 +6.451441217382382831e+01,3.903443158843371634e+02,2.843858937985777491e+00,5.661758797150580058e+00,-3.757287567980424070e-01,-4.415207593485517834e-02,2.460683907984473340e-02,-9.999999159016632611e-01,5.661758797150584499e-01 +6.451617840943333704e+01,3.903536182888496455e+02,2.840189432530578095e+00,5.661680814181830002e+00,-3.756389326858712296e-01,-4.591831139583055221e-02,2.560683907984473429e-02,-9.999999126561622820e-01,5.661680814181834220e-01 +6.451794466937066375e+01,3.903629210229346995e+02,2.836520762670407425e+00,5.661599710508022021e+00,-3.755454566368318092e-01,-4.768457117888169616e-02,2.660683907984473517e-02,-9.999999092438862647e-01,5.661599710508027350e-01 +6.451971095461004779e+01,3.903722240999118753e+02,2.832852962409091013e+00,5.661515485953802163e+00,-3.754483284638492901e-01,-4.945085625796962620e-02,2.760683907984473606e-02,-9.999999048203530583e-01,5.661515485953806381e-01 +6.452147726612589906e+01,3.903815275330919121e+02,2.829186065755943780e+00,5.661428140336925097e+00,-3.753475479725295605e-01,-5.121716760570213522e-02,2.860683907984473695e-02,-9.999999002278723292e-01,5.661428140336929316e-01 +6.452324360489274113e+01,3.903908313357763404e+02,2.825520106725983638e+00,5.661337673468255005e+00,-3.752431149611578642e-01,-5.298350619631853053e-02,2.960683907984473784e-02,-9.999998945792385463e-01,5.661337673468259668e-01 +6.452500997188526810e+01,3.904001355212571411e+02,2.821855119340144213e+00,5.661244085151761141e+00,-3.751350292206969694e-01,-5.474987300264014950e-02,3.060683907984473873e-02,-9.999998889585635098e-01,5.661244085151766470e-01 +6.452677636807833039e+01,3.904094401028165180e+02,2.818191137625488008e+00,5.661147375184518715e+00,-3.750232905347856693e-01,-5.651626899955777134e-02,3.160683907984473962e-02,-9.999998812972883400e-01,5.661147375184523156e-01 +6.452854279444692054e+01,3.904187450937262724e+02,2.814528195615419559e+00,5.661047543356703571e+00,-3.749078986797369506e-01,-5.828269515846817156e-02,3.260683907984474050e-02,-9.999998737752676670e-01,5.661047543356708678e-01 +6.453030925196620160e+01,3.904280505072477467e+02,2.810866327349897720e+00,5.660944589451596620e+00,-3.747888534245362724e-01,-6.004915245478389951e-02,3.360683907984474139e-02,-9.999998639965711478e-01,5.660944589451601949e-01 +6.453207574161152138e+01,3.904373563566313692e+02,2.807205566875648373e+00,5.660838513245574966e+00,-3.746661545308396235e-01,-6.181564185985586463e-02,3.460683907984474228e-02,-9.999998526749941385e-01,5.660838513245579628e-01 +6.453384226435838400e+01,3.904466626551161994e+02,2.803545948246376707e+00,5.660729314508117227e+00,-3.745398017529716905e-01,-6.358216434647182003e-02,3.560683907984474317e-02,-9.999998390797207870e-01,5.660729314508122778e-01 +6.453560882118249253e+01,3.904559694159297010e+02,2.799887505522979936e+00,5.660616993001799102e+00,-3.744097948379238594e-01,-6.534872088630985787e-02,3.660683907984474406e-02,-9.999998221740283855e-01,5.660616993001803543e-01 +6.453737541305973480e+01,3.904652766522874003e+02,2.796230272773759573e+00,5.660501548482293366e+00,-3.742761335253522170e-01,-6.711531244940328877e-02,3.760683907984474494e-02,-9.999998014690685277e-01,5.660501548482298473e-01 +6.453914204096616913e+01,3.904745843773924889e+02,2.792574284074632374e+00,5.660382980698370758e+00,-3.741388175475753863e-01,-6.888194000511377313e-02,3.860683907984474583e-02,-9.999997741780913829e-01,5.660382980698375199e-01 +6.454090870587808126e+01,3.904838926044354821e+02,2.788919573509342609e+00,5.660261289391899098e+00,-3.739978466295724724e-01,-7.064860451807701558e-02,3.960683907984474672e-02,-9.999997380625478272e-01,5.660261289391904649e-01 +6.454267540877194165e+01,3.904932013465938780e+02,2.785266175169674341e+00,5.660136474297849496e+00,-3.738532204889807864e-01,-7.241530694917623634e-02,4.060683907984474761e-02,-9.999996874484505804e-01,5.660136474297854381e-01 +6.454444215062443391e+01,3.905025106170318168e+02,2.781614123155662366e+00,5.660008535144300801e+00,-3.737049388360936253e-01,-7.418204824947766118e-02,4.160683907984474850e-02,-9.999996115201292834e-01,5.660008535144305242e-01 +6.454620893241246904e+01,3.905118204288997390e+02,2.777963451575802711e+00,5.659877471652454695e+00,-3.735530013738579402e-01,-7.594882935115074285e-02,4.260683907984474939e-02,-9.999994846482958000e-01,5.659877471652460246e-01 +6.454797575511315699e+01,3.905211307953339883e+02,2.774314194547264467e+00,5.659743283536666780e+00,-3.733974077978719497e-01,-7.771565114129867780e-02,4.360683907984475027e-02,-9.999992302629353569e-01,5.659743283536672331e-01 +6.454974261970383509e+01,3.905304417294564701e+02,2.770666386196100728e+00,5.659605970504523853e+00,-3.732381577963826969e-01,-7.948251437195399949e-02,4.460683907984475116e-02,-9.999984676757119884e-01,5.659605970504528738e-01 +6.455150952716208224e+01,3.905397532443743671e+02,2.767020060657458647e+00,5.659465532257080156e+00,-3.730752510502835517e-01,-8.124941912272160005e-02,4.560683907984475205e-02,-4.370840176533038468e-01,5.659465532257085263e-01 +6.455327647846570471e+01,3.905490653531797420e+02,2.763375252075790822e+00,5.659321968490043098e+00,-3.729086872331116576e-01,-8.202172529750448304e-02,4.660683907984475294e-02,9.999985009425880200e-01,5.659321968490047539e-01 +6.455504347459275039e+01,3.905583780689491391e+02,2.759731994605064020e+00,5.659177036419109186e+00,-3.727384660110452663e-01,-8.025473181929211608e-02,4.760683907984475383e-02,9.999992631446896763e-01,5.659177036419114071e-01 +6.455681051597272813e+01,3.905676914047433570e+02,2.756090322408971005e+00,5.659035222987045088e+00,-3.725645870429011852e-01,-7.848769174136331628e-02,4.860683907984475471e-02,9.999995173706824891e-01,5.659035222987049973e-01 +6.455857760163414127e+01,3.905770053736069940e+02,2.752450269661138371e+00,5.658896528512371127e+00,-3.723870499801318346e-01,-7.672060693279263155e-02,4.960683907984475560e-02,9.999996446614112244e-01,5.658896528512376012e-01 +6.456034473060523737e+01,3.905863199885681070e+02,2.748811870545338376e+00,5.658760953305179697e+00,-3.722058544668226387e-01,-7.495347858962023158e-02,5.060683907984475649e-02,9.999997202085514347e-01,5.658760953305184138e-01 +6.456211190191403659e+01,3.905956352626379271e+02,2.745175159255695885e+00,5.658628497668321877e+00,-3.720210001396890842e-01,-7.318630777526648201e-02,5.160683907984475738e-02,9.999997713866685123e-01,5.658628497668326540e-01 +6.456387911458828910e+01,3.906049512088104052e+02,2.741540169996898868e+00,5.658499161897639240e+00,-3.718324866280737773e-01,-7.141909550501632231e-02,5.260683907984475827e-02,9.999998070581749277e-01,5.658499161897644347e-01 +6.456564636765556031e+01,3.906142678400619275e+02,2.737906936984407569e+00,5.658372946282046456e+00,-3.716403135539435576e-01,-6.965184277872482621e-02,5.360683907984475915e-02,9.999998346403231597e-01,5.658372946282050897e-01 +6.456741366014315986e+01,3.906235851693509744e+02,2.734275494444661891e+00,5.658249851103556161e+00,-3.714444805318863896e-01,-6.788455058336433090e-02,5.460683907984476004e-02,9.999998555563245350e-01,5.658249851103560601e-01 +6.456918099107819842e+01,3.906329032096177230e+02,2.730645876615290568e+00,5.658129876637299382e+00,-3.712449871691082537e-01,-6.611721990361131562e-02,5.560683907984476093e-02,9.999998720609202252e-01,5.658129876637304490e-01 +6.457094835948755929e+01,3.906422219737837054e+02,2.727018117745319437e+00,5.658013023151527321e+00,-3.710418330654300934e-01,-6.434985172037117895e-02,5.660683907984476182e-02,9.999998863872617827e-01,5.658013023151532428e-01 +6.457271576439791261e+01,3.906515414747514683e+02,2.723392252095378385e+00,5.657899290907615786e+00,-3.708350178132844288e-01,-6.258244701081068506e-02,5.760683907984476271e-02,9.999998970508564566e-01,5.657899290907620893e-01 +6.457448320483575799e+01,3.906608617254042315e+02,2.719768313937909632e+00,5.657788680160069639e+00,-3.706245409977122485e-01,-6.081500675492299002e-02,5.860683907984476360e-02,9.999999073795722282e-01,5.657788680160075190e-01 +6.457625067982736766e+01,3.906701827386055470e+02,2.716146337557375556e+00,5.657681191156515688e+00,-3.704104021963595672e-01,-5.904753192701676229e-02,5.960683907984476448e-02,9.999999149936135145e-01,5.657681191156520573e-01 +6.457801818839882912e+01,3.906795045271987874e+02,2.712526357250463871e+00,5.657576824137710680e+00,-3.701926009794741512e-01,-5.728002350579870783e-02,6.060683907984476537e-02,9.999999226096194516e-01,5.657576824137715565e-01 +6.457978572957605934e+01,3.906888271040070890e+02,2.708908407326296786e+00,5.657475579337531535e+00,-3.699711369099018543e-01,-5.551248246536037018e-02,6.160683907984476626e-02,9.999999289427605742e-01,5.657475579337536420e-01 +6.458155330238477632e+01,3.906981504818326698e+02,2.705292522106635289e+00,5.657377456982981556e+00,-3.697460095430832872e-01,-5.374490978224530369e-02,6.260683907984476715e-02,9.999999338243276137e-01,5.657377456982985997e-01 +6.458332090585052754e+01,3.907074746734566588e+02,2.701678735926086539e+00,5.657282457294184219e+00,-3.695172184270502092e-01,-5.197730643347101692e-02,6.360683907984476804e-02,9.999999390542619881e-01,5.657282457294189326e-01 +6.458508853899868996e+01,3.907167996916388120e+02,2.698067083132309474e+00,5.657190580484380504e+00,-3.692847631024218091e-01,-5.020967339304377441e-02,6.460683907984476892e-02,9.999999435685617000e-01,5.657190580484385833e-01 +6.458685620085446999e+01,3.907261255491169436e+02,2.694457598086219985e+00,5.657101826759932450e+00,-3.690486431024011527e-01,-4.844201163701550295e-02,6.560683907984476981e-02,9.999999471349246827e-01,5.657101826759937113e-01 +6.458862389044293195e+01,3.907354522586066992e+02,2.690850315162197415e+00,5.657016196320317825e+00,-3.688088579527711852e-01,-4.667432214200836066e-02,6.660683907984477070e-02,9.999999506367915902e-01,5.657016196320322488e-01 +6.459039160678896963e+01,3.907447798328011572e+02,2.687245268748287508e+00,5.656933689358127459e+00,-3.685654071718912350e-01,-4.490660588323707597e-02,6.760683907984477159e-02,9.999999540835915468e-01,4.448170509130909278e-01 +6.459215934891732047e+01,3.907541082843706022e+02,2.683642493246408911e+00,5.656854306059066140e+00,-3.683182902706928497e-01,-4.313886383604850772e-02,6.839316092015533532e-02,9.999999514950433932e-01,0.000000000000000000e+00 +6.459392711585260827e+01,3.907634376259618989e+02,2.680042023072557011e+00,5.656778046601950827e+00,-3.680682902706928772e-01,-4.137109698650468653e-02,6.839316092015533532e-02,9.999999490912843125e-01,0.000000000000000000e+00 +6.459569490661930047e+01,3.907727678673791729e+02,2.676443885346593277e+00,5.656704911158690230e+00,-3.678182902706929047e-01,-3.960330630981022393e-02,6.839316092015533532e-02,9.999999468179451290e-01,0.000000000000000000e+00 +6.459746272024172242e+01,3.907820990080393244e+02,2.672848080293401374e+00,5.656634899894302571e+00,-3.675682902706929323e-01,-3.783549278139848593e-02,6.839316092015533532e-02,9.999999434626798411e-01,0.000000000000000000e+00 +6.459923055574410000e+01,3.907914310473591399e+02,2.669254608137718865e+00,5.656568012966913805e+00,-3.673182902706929598e-01,-3.606765737897333485e-02,6.839316092015533532e-02,9.999999403496577788e-01,0.000000000000000000e+00 +6.460099841215050276e+01,3.908007639847553492e+02,2.665663469104138095e+00,5.656504250527752298e+00,-3.670682902706929873e-01,-3.429980107801965800e-02,6.839316092015533532e-02,9.999999376449070221e-01,0.000000000000000000e+00 +6.460276628848491498e+01,3.908100978196446249e+02,2.662074663417105302e+00,5.656443612721151482e+00,-3.668182902706930149e-01,-3.253192485384532456e-02,6.839316092015533532e-02,9.999999340722840468e-01,0.000000000000000000e+00 +6.460453418377119306e+01,3.908194325514436400e+02,2.658488191300920622e+00,5.656386099684548974e+00,-3.665682902706930424e-01,-3.076402968412540045e-02,6.839316092015533532e-02,9.999999300394957213e-01,0.000000000000000000e+00 +6.460630209703307969e+01,3.908287681795689537e+02,2.654904052979738527e+00,5.656331711548481245e+00,-3.663182902706930699e-01,-2.899611654591995741e-02,6.839316092015533532e-02,9.999999262170401471e-01,0.000000000000000000e+00 +6.460807002729423232e+01,3.908381047034371250e+02,2.651322248677567828e+00,5.656280448436583619e+00,-3.660682902706930975e-01,-2.722818641520405661e-02,6.839316092015533532e-02,9.999999218332649153e-01,0.000000000000000000e+00 +6.460983797357822311e+01,3.908474421224645994e+02,2.647742778618271231e+00,5.656232310465591162e+00,-3.658182902706931250e-01,-2.546024026941196006e-02,6.839316092015533532e-02,9.999999169477188365e-01,0.000000000000000000e+00 +6.461160593490851056e+01,3.908567804360677655e+02,2.644165643025565782e+00,5.656187297745335130e+00,-3.655682902706931525e-01,-2.369227908596225826e-02,6.839316092015533532e-02,9.999999121669025381e-01,0.000000000000000000e+00 +6.461337391030846788e+01,3.908661196436630121e+02,2.640590842123021975e+00,5.656145410378742078e+00,-3.653182902706931801e-01,-2.192430384128547446e-02,6.839316092015533532e-02,9.999999066552166527e-01,0.000000000000000000e+00 +6.461514189880141146e+01,3.908754597446666139e+02,2.637018376134065534e+00,5.656106648461834752e+00,-3.650682902706932076e-01,-2.015631551336825519e-02,6.839316092015533532e-02,9.999999006923360190e-01,0.000000000000000000e+00 +6.461690989941058660e+01,3.908848007384948460e+02,2.633448245281975186e+00,5.656071012083728533e+00,-3.648182902706932351e-01,-1.838831507977621224e-02,6.839316092015533532e-02,9.999998936841498764e-01,0.000000000000000000e+00 +6.461867791115913917e+01,3.908941426245638695e+02,2.629880449789884000e+00,5.656038501326631440e+00,-3.645682902706932627e-01,-1.662030351919337526e-02,6.839316092015533532e-02,9.999998870041654220e-01,0.000000000000000000e+00 +6.462044593307017237e+01,3.909034854022898458e+02,2.626314989880779383e+00,5.656009116265841463e+00,-3.643182902706932902e-01,-1.485228180793802567e-02,6.839316092015533532e-02,9.999998788789978832e-01,0.000000000000000000e+00 +6.462221396416673258e+01,3.909128290710888223e+02,2.622751865777502633e+00,5.655982856969750117e+00,-3.640682902706933177e-01,-1.308425092552104561e-02,6.839316092015533532e-02,9.999998703552795964e-01,0.000000000000000000e+00 +6.462398200347180932e+01,3.909221736303767898e+02,2.619191077702748949e+00,5.655959723499836223e+00,-3.638182902706933453e-01,-1.131621184965468131e-02,6.839316092015533532e-02,9.999998607534518191e-01,0.000000000000000000e+00 +6.462575005000836370e+01,3.909315190795697958e+02,2.615632625879067419e+00,5.655939715910668575e+00,-3.635682902706933728e-01,-9.548165559299090499e-03,6.839316092015533532e-02,9.999998499408547792e-01,0.000000000000000000e+00 +6.462751810279928577e+01,3.909408654180836606e+02,2.612076510528861473e+00,5.655922834249903275e+00,-3.633182902706934003e-01,-7.780113033690012544e-03,6.839316092015533532e-02,9.999998383316895945e-01,0.000000000000000000e+00 +6.462928616086745137e+01,3.909502126453343180e+02,2.608522731874388434e+00,5.655909078558282843e+00,-3.630682902706934279e-01,-6.012055251366482840e-03,6.839316092015533532e-02,9.999998248981516458e-01,0.000000000000000000e+00 +6.463105422323569371e+01,3.909595607607375314e+02,2.604971290137759077e+00,5.655898448869637107e+00,-3.628182902706934554e-01,-4.243993192714973911e-03,6.839316092015533532e-02,9.999998100116636035e-01,0.000000000000000000e+00 +6.463282228892683179e+01,3.909689097637090072e+02,2.601422185540938958e+00,5.655890945210879650e+00,-3.625682902706934829e-01,-2.475927837490077450e-03,6.839316092015533532e-02,9.999997931698835218e-01,0.000000000000000000e+00 +6.463459035696365618e+01,3.909782596536644519e+02,2.597875418305746642e+00,5.655886567602008697e+00,-3.623182902706935105e-01,-7.078601663539633082e-04,6.839316092015533532e-02,9.999997741331891898e-01,0.000000000000000000e+00 +6.463635842636895745e+01,3.909876104300195152e+02,2.594330988653855474e+00,5.655885316056105339e+00,-3.620682902706935380e-01,1.060208839593534871e-03,6.839316092015533532e-02,9.999997517881922260e-01,0.000000000000000000e+00 +6.463812649616549777e+01,3.909969620921897899e+02,2.590788896806791808e+00,5.655887190579332646e+00,-3.618182902706935655e-01,2.828278197275455128e-03,6.839316092015533532e-02,9.999997264206870184e-01,0.000000000000000000e+00 +6.463989456537605349e+01,3.910063146395907552e+02,2.587249142985936778e+00,5.655892191170932115e+00,-3.615682902706935931e-01,4.596346924116976804e-03,6.839316092015533532e-02,9.999996974426842433e-01,0.000000000000000000e+00 +6.464166263302338677e+01,3.910156680716379469e+02,2.583711727412524972e+00,5.655900317823224555e+00,-3.613182902706936206e-01,6.364414036505934222e-03,6.839316092015533532e-02,9.999996622559077508e-01,0.000000000000000000e+00 +6.464343069813027398e+01,3.910250223877467306e+02,2.580176650307644870e+00,5.655911570521608311e+00,-3.610682902706936481e-01,8.132478546243927103e-03,6.839316092015533532e-02,9.999996213659535504e-01,0.000000000000000000e+00 +6.464519875971951990e+01,3.910343775873324148e+02,2.576643911892238847e+00,5.655925949244551276e+00,-3.608182902706936757e-01,9.900539466039619957e-03,6.839316092015533532e-02,9.999995718474696815e-01,0.000000000000000000e+00 +6.464696681681392931e+01,3.910437336698103650e+02,2.573113512387103174e+00,5.655943453963592660e+00,-3.605682902706937032e-01,1.166859580344806364e-02,6.839316092015533532e-02,9.999995116059404721e-01,0.000000000000000000e+00 +6.464873486843633543e+01,3.910530906345957760e+02,2.569585452012887572e+00,5.655964084643334111e+00,-3.603182902706937307e-01,1.343664656234516176e-02,6.839316092015533532e-02,9.999994365363749083e-01,0.000000000000000000e+00 +6.465050291360959989e+01,3.910624484811038997e+02,2.566059730990095655e+00,5.655987841241433500e+00,-3.600682902706937583e-01,1.520469073937857213e-02,6.839316092015533532e-02,9.999993416596970608e-01,0.000000000000000000e+00 +6.465227095135661273e+01,3.910718072087498172e+02,2.562536349539085379e+00,5.656014723708592484e+00,-3.598182902706937858e-01,1.697272732242788643e-02,6.839316092015533532e-02,9.999992177130117010e-01,0.000000000000000000e+00 +6.465403898070032085e+01,3.910811668169486666e+02,2.559015307880067702e+00,5.656044731988541407e+00,-3.595682902706938133e-01,1.874075528303638036e-02,6.839316092015533532e-02,9.999990505809359664e-01,0.000000000000000000e+00 +6.465580700066371378e+01,3.910905273051154154e+02,2.555496606233107926e+00,5.656077866018010880e+00,-3.593182902706938409e-01,2.050877356783760083e-02,6.839316092015533532e-02,9.999988147598716237e-01,0.000000000000000000e+00 +6.465757501026982368e+01,3.910998886726650312e+02,2.551980244818124799e+00,5.656114125726688258e+00,-3.590682902706938684e-01,2.227678107842707284e-02,6.839316092015533532e-02,9.999984597178508405e-01,0.000000000000000000e+00 +6.465934300854172534e+01,3.911092509190124815e+02,2.548466223854890966e+00,5.656153511037138593e+00,-3.588182902706938959e-01,2.404477662711903413e-02,6.839316092015533532e-02,9.999978706793726246e-01,0.000000000000000000e+00 +6.466111099450259303e+01,3.911186140435725633e+02,2.544954543563032967e+00,5.656196021864647427e+00,-3.585682902706939235e-01,2.581275882337312477e-02,6.839316092015533532e-02,9.999967225636638979e-01,0.000000000000000000e+00 +6.466287896717562944e+01,3.911279780457601305e+02,2.541445204162030347e+00,5.656241658116862858e+00,-3.583182902706939510e-01,2.758072570199272475e-02,6.839316092015533532e-02,9.999935536063156993e-01,0.000000000000000000e+00 +6.466464692558413674e+01,3.911373429249899232e+02,2.537938205871217434e+00,5.656290419692780347e+00,-3.580682902706939785e-01,2.934867271354110393e-02,6.839316092015533532e-02,9.999493031337308713e-01,0.000000000000000000e+00 +6.466641486875147393e+01,3.911467086806766247e+02,2.534433548909781120e+00,5.656342306478174820e+00,-3.578182902706940061e-01,3.111652625170515524e-02,6.839316092015533532e-02,-9.999901365614058957e-01,0.000000000000000000e+00 +6.466818279570111372e+01,3.911560753122348615e+02,2.530931233496762633e+00,5.656397318223514326e+00,-3.575682902706940336e-01,2.934861673990611999e-02,6.839316092015533532e-02,-9.999952069497552998e-01,0.000000000000000000e+00 +6.466995070545664248e+01,3.911654428190792601e+02,2.527431259851056655e+00,5.656449203929359903e+00,-3.573182902706940611e-01,2.758071545806366903e-02,6.839316092015533532e-02,-9.999966878063172304e-01,0.000000000000000000e+00 +6.467171859899541175e+01,3.911748112006242764e+02,2.523933628191411316e+00,5.656497963698012832e+00,-3.570682902706940887e-01,2.581282777490079283e-02,6.839316092015533532e-02,-9.999973764234828533e-01,0.000000000000000000e+00 +6.467348647729470201e+01,3.911841804562844800e+02,2.520438338736429085e+00,5.656543597636079390e+00,-3.568182902706941162e-01,2.404495411377474690e-02,6.839316092015533532e-02,-9.999977593138097420e-01,0.000000000000000000e+00 +6.467525434133170847e+01,3.911935505854742132e+02,2.516945391704565438e+00,5.656586105845728518e+00,-3.565682902706941437e-01,2.227709403800035015e-02,6.839316092015533532e-02,-9.999979885186155437e-01,0.000000000000000000e+00 +6.467702219208354109e+01,3.912029215876078752e+02,2.513454787314129302e+00,5.656625488423172143e+00,-3.563182902706941713e-01,2.050924684217108468e-02,6.839316092015533532e-02,-9.999981276865930191e-01,0.000000000000000000e+00 +6.467879003052723874e+01,3.912122934620998080e+02,2.509966525783283497e+00,5.656661745458190893e+00,-3.560682902706941988e-01,1.874141170842714976e-02,6.839316092015533532e-02,-9.999982026522200584e-01,0.000000000000000000e+00 +6.468055785763976928e+01,3.912216662083642404e+02,2.506480607330044297e+00,5.656694877033936031e+00,-3.558182902706942263e-01,1.697358777330298940e-02,6.839316092015533532e-02,-9.999982292839919573e-01,0.000000000000000000e+00 +6.468232567439802949e+01,3.912310398258154009e+02,2.502997032172281866e+00,5.656724883226849521e+00,-3.555682902706942539e-01,1.520577414534160857e-02,6.839316092015533532e-02,-9.999982100729224443e-01,0.000000000000000000e+00 +6.468409348177887352e+01,3.912404143138674044e+02,2.499515800527719378e+00,5.656751764106615177e+00,-3.553182902706942814e-01,1.343796992873901724e-02,6.839316092015533532e-02,-9.999981426578000709e-01,0.000000000000000000e+00 +6.468586128075909869e+01,3.912497896719343657e+02,2.496036912613934344e+00,5.656775519736151558e+00,-3.550682902706943089e-01,1.167017423191700487e-02,6.839316092015533532e-02,-9.999980152775643782e-01,0.000000000000000000e+00 +6.468762907231545967e+01,3.912591658994302861e+02,2.492560368648356839e+00,5.656796150171619963e+00,-3.548182902706943365e-01,9.902386184134958150e-03,6.839316092015533532e-02,-9.999978027920061185e-01,0.000000000000000000e+00 +6.468939685742465429e+01,3.912685429957691667e+02,2.489086168848270830e+00,5.656813655462461732e+00,-3.545682902706943640e-01,8.134604959135949623e-03,6.839316092015533532e-02,-9.999974499129419270e-01,0.000000000000000000e+00 +6.469116463706335196e+01,3.912779209603649520e+02,2.485614313430813738e+00,5.656828035651477293e+00,-3.543182902706943915e-01,6.366829828436175627e-03,6.839316092015533532e-02,-9.999968271505317308e-01,0.000000000000000000e+00 +6.469293241220817947e+01,3.912872997926315293e+02,2.482144802612976875e+00,5.656839290774999363e+00,-3.540682902706944191e-01,4.599060292490991797e-03,6.839316092015533532e-02,-9.999955366932987699e-01,0.000000000000000000e+00 +6.469470018383576360e+01,3.912966794919827294e+02,2.478677636611604118e+00,5.656847420863297948e+00,-3.538182902706944466e-01,2.831296555020031743e-03,6.839316092015533532e-02,-9.999915939258888775e-01,0.000000000000000000e+00 +6.469646795292267427e+01,3.913060600578323260e+02,2.475212815643393682e+00,5.656852425941823803e+00,-3.535682902706944741e-01,1.063542328102454497e-03,6.839316092015533532e-02,-6.016935663474171081e-01,0.000000000000000000e+00 +6.469823572044549564e+01,3.913154414895939794e+02,2.471750339924896789e+00,5.656854306037410574e+00,-3.533182902706945017e-01,-1.120171799216282311e-07,6.839316092015533532e-02,6.337785534298204335e-05,0.000000000000000000e+00 +6.470000348738079765e+01,3.913248237866814065e+02,2.468290209672518554e+00,5.656854305839390307e+00,-3.530682902706945292e-01,2.009718367133711571e-11,6.839316092015533532e-02,-1.136868399864484583e-08,0.000000000000000000e+00 +6.470177125431615650e+01,3.913342069485081538e+02,2.464832425102516655e+00,5.656854305839425834e+00,-3.528182902706945567e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.470353902125151535e+01,3.913435909744878245e+02,2.461376986431002667e+00,5.656854305839425834e+00,-3.525682902706945843e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.470530678818687420e+01,3.913529758640339082e+02,2.457923893873941612e+00,5.656854305839425834e+00,-3.523182902706946118e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.470707455512223305e+01,3.913623616165598378e+02,2.454473147647151965e+00,5.656854305839425834e+00,-3.520682902706946393e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.470884232205759190e+01,3.913717482314790459e+02,2.451024747966305206e+00,5.656854305839425834e+00,-3.518182902706946669e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.471061008899295075e+01,3.913811357082047948e+02,2.447578695046926267e+00,5.656854305839425834e+00,-3.515682902706946944e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.471237785592830960e+01,3.913905240461504036e+02,2.444134989104393529e+00,5.656854305839425834e+00,-3.513182902706947219e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.471414562286366845e+01,3.913999132447291345e+02,2.440693630353938381e+00,5.656854305839425834e+00,-3.510682902706947495e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.471591338979902730e+01,3.914093033033541360e+02,2.437254619010646106e+00,5.656854305839425834e+00,-3.508182902706947770e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.471768115673438615e+01,3.914186942214384999e+02,2.433817955289454549e+00,5.656854305839425834e+00,-3.505682902706948045e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.471944892366974500e+01,3.914280859983953178e+02,2.430383639405155449e+00,5.656854305839425834e+00,-3.503182902706948321e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.472121669060510385e+01,3.914374786336376246e+02,2.426951671572393554e+00,5.656854305839425834e+00,-3.500682902706948596e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.472298445754046270e+01,3.914468721265783415e+02,2.423522052005666616e+00,5.656854305839425834e+00,-3.498182902706948871e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.472475222447582155e+01,3.914562664766303897e+02,2.420094780919326283e+00,5.656854305839425834e+00,-3.495682902706949147e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.472651999141118040e+01,3.914656616832066334e+02,2.416669858527576764e+00,5.656854305839425834e+00,-3.493182902706949422e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.472828775834653925e+01,3.914750577457198801e+02,2.413247285044475277e+00,5.656854305839425834e+00,-3.490682902706949697e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.473005552528189810e+01,3.914844546635828806e+02,2.409827060683933375e+00,5.656854305839425834e+00,-3.488182902706949973e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.473182329221725695e+01,3.914938524362082717e+02,2.406409185659714733e+00,5.656854305839425834e+00,-3.485682902706950248e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.473359105915261580e+01,3.915032510630087472e+02,2.402993660185436475e+00,5.656854305839425834e+00,-3.483182902706950523e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.473535882608797465e+01,3.915126505433968873e+02,2.399580484474569175e+00,5.656854305839425834e+00,-3.480682902706950799e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.473712659302333350e+01,3.915220508767852152e+02,2.396169658740435970e+00,5.656854305839425834e+00,-3.478182902706951074e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.473889435995869235e+01,3.915314520625861974e+02,2.392761183196213892e+00,5.656854305839425834e+00,-3.475682902706951349e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.474066212689405120e+01,3.915408541002122433e+02,2.389355058054932091e+00,5.656854305839425834e+00,-3.473182902706951625e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.474242989382941005e+01,3.915502569890757627e+02,2.385951283529474054e+00,5.656854305839425834e+00,-3.470682902706951900e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.474419766076476890e+01,3.915596607285890514e+02,2.382549859832575390e+00,5.656854305839425834e+00,-3.468182902706952175e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.474596542770012775e+01,3.915690653181644052e+02,2.379150787176824711e+00,5.656854305839425834e+00,-3.465682902706952451e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.474773319463548660e+01,3.915784707572140064e+02,2.375754065774664525e+00,5.656854305839425834e+00,-3.463182902706952726e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.474950096157084545e+01,3.915878770451500372e+02,2.372359695838389904e+00,5.656854305839425834e+00,-3.460682902706953001e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.475126872850620430e+01,3.915972841813846230e+02,2.368967677580148923e+00,5.656854305839425834e+00,-3.458182902706953277e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.475303649544156315e+01,3.916066921653297754e+02,2.365578011211942666e+00,5.656854305839425834e+00,-3.455682902706953552e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.475480426237692200e+01,3.916161009963975062e+02,2.362190696945625223e+00,5.656854305839425834e+00,-3.453182902706953827e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.475657202931228085e+01,3.916255106739997700e+02,2.358805734992903691e+00,5.656854305839425834e+00,-3.450682902706954103e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.475833979624763970e+01,3.916349211975484650e+02,2.355423125565338172e+00,5.656854305839425834e+00,-3.448182902706954378e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.476010756318299855e+01,3.916443325664554322e+02,2.352042868874341774e+00,5.656854305839425834e+00,-3.445682902706954653e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.476187533011835740e+01,3.916537447801324561e+02,2.348664965131180615e+00,5.656854305839425834e+00,-3.443182902706954929e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.476364309705371625e+01,3.916631578379912639e+02,2.345289414546973816e+00,5.656854305839425834e+00,-3.440682902706955204e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.476541086398907510e+01,3.916725717394435833e+02,2.341916217332693062e+00,5.656854305839425834e+00,-3.438182902706955479e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.476717863092443395e+01,3.916819864839009711e+02,2.338545373699163488e+00,5.656854305839425834e+00,-3.435682902706955755e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.476894639785979280e+01,3.916914020707750410e+02,2.335176883857062347e+00,5.656854305839425834e+00,-3.433182902706956030e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.477071416479515165e+01,3.917008184994773501e+02,2.331810748016920787e+00,5.656854305839425834e+00,-3.430682902706956305e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.477248193173051050e+01,3.917102357694193415e+02,2.328446966389122075e+00,5.656854305839425834e+00,-3.428182902706956581e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.477424969866586935e+01,3.917196538800124586e+02,2.325085539183902483e+00,5.656854305839425834e+00,-3.425682902706956856e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.477601746560122820e+01,3.917290728306680307e+02,2.321726466611351292e+00,5.656854305839425834e+00,-3.423182902706957131e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.477778523253658705e+01,3.917384926207973876e+02,2.318369748881410342e+00,5.656854305839425834e+00,-3.420682902706957407e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.477955299947194590e+01,3.917479132498118020e+02,2.315015386203874481e+00,5.656854305839425834e+00,-3.418182902706957682e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.478132076640730475e+01,3.917573347171224896e+02,2.311663378788391565e+00,5.656854305839425834e+00,-3.415682902706957957e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.478308853334266360e+01,3.917667570221406095e+02,2.308313726844462010e+00,5.656854305839425834e+00,-3.413182902706958233e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.478485630027802245e+01,3.917761801642772639e+02,2.304966430581439241e+00,5.656854305839425834e+00,-3.410682902706958508e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.478662406721338130e+01,3.917856041429434981e+02,2.301621490208529242e+00,5.656854305839425834e+00,-3.408182902706958783e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.478839183414874014e+01,3.917950289575503007e+02,2.298278905934790561e+00,5.656854305839425834e+00,-3.405682902706959059e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.479015960108409899e+01,3.918044546075086600e+02,2.294938677969134755e+00,5.656854305839425834e+00,-3.403182902706959334e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.479192736801945784e+01,3.918138810922294510e+02,2.291600806520325939e+00,5.656854305839425834e+00,-3.400682902706959609e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.479369513495481669e+01,3.918233084111234916e+02,2.288265291796981238e+00,5.656854305839425834e+00,-3.398182902706959885e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.479546290189017554e+01,3.918327365636015998e+02,2.284932134007570337e+00,5.656854305839425834e+00,-3.395682902706960160e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.479723066882553439e+01,3.918421655490745366e+02,2.281601333360415929e+00,5.656854305839425834e+00,-3.393182902706960435e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.479899843576089324e+01,3.918515953669529495e+02,2.278272890063692380e+00,5.656854305839425834e+00,-3.390682902706960711e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.480076620269625209e+01,3.918610260166475427e+02,2.274946804325427951e+00,5.656854305839425834e+00,-3.388182902706960986e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.480253396963161094e+01,3.918704574975688502e+02,2.271623076353502579e+00,5.656854305839425834e+00,-3.385682902706961261e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.480430173656696979e+01,3.918798898091274054e+02,2.268301706355649650e+00,5.656854305839425834e+00,-3.383182902706961537e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.480606950350232864e+01,3.918893229507336855e+02,2.264982694539454666e+00,5.656854305839425834e+00,-3.380682902706961812e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.480783727043768749e+01,3.918987569217981104e+02,2.261666041112355696e+00,5.656854305839425834e+00,-3.378182902706962087e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.480960503737304634e+01,3.919081917217311002e+02,2.258351746281643813e+00,5.656854305839425834e+00,-3.375682902706962363e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.481137280430840519e+01,3.919176273499429044e+02,2.255039810254462207e+00,5.656854305839425834e+00,-3.373182902706962638e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.481314057124376404e+01,3.919270638058438863e+02,2.251730233237807077e+00,5.656854305839425834e+00,-3.370682902706962913e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.481490833817912289e+01,3.919365010888441816e+02,2.248423015438526740e+00,5.656854305839425834e+00,-3.368182902706963189e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.481667610511448174e+01,3.919459391983540399e+02,2.245118157063322517e+00,5.656854305839425834e+00,-3.365682902706963464e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.481844387204984059e+01,3.919553781337835403e+02,2.241815658318747850e+00,5.656854305839425834e+00,-3.363182902706963739e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.482021163898519944e+01,3.919648178945427617e+02,2.238515519411209187e+00,5.656854305839425834e+00,-3.360682902706964015e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.482197940592055829e+01,3.919742584800416694e+02,2.235217740546965093e+00,5.656854305839425834e+00,-3.358182902706964290e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.482374717285591714e+01,3.919836998896902855e+02,2.231922321932126696e+00,5.656854305839425834e+00,-3.355682902706964565e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.482551493979127599e+01,3.919931421228985187e+02,2.228629263772657687e+00,5.656854305839425834e+00,-3.353182902706964841e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.482728270672663484e+01,3.920025851790762204e+02,2.225338566274374319e+00,5.656854305839425834e+00,-3.350682902706965116e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.482905047366199369e+01,3.920120290576331854e+02,2.222050229642944963e+00,5.656854305839425834e+00,-3.348182902706965391e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.483081824059735254e+01,3.920214737579791517e+02,2.218764254083890997e+00,5.656854305839425834e+00,-3.345682902706965667e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.483258600753271139e+01,3.920309192795238573e+02,2.215480639802585472e+00,5.656854305839425834e+00,-3.343182902706965942e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.483435377446807024e+01,3.920403656216769832e+02,2.212199387004254447e+00,5.656854305839425834e+00,-3.340682902706966217e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.483612154140342909e+01,3.920498127838480968e+02,2.208920495893976099e+00,5.656854305839425834e+00,-3.338182902706966493e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.483788930833878794e+01,3.920592607654467088e+02,2.205643966676681611e+00,5.656854305839425834e+00,-3.335682902706966768e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.483965707527414679e+01,3.920687095658823864e+02,2.202369799557153396e+00,5.656854305839425834e+00,-3.333182902706967043e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.484142484220950564e+01,3.920781591845645835e+02,2.199097994740027318e+00,5.656854305839425834e+00,-3.330682902706967319e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.484319260914486449e+01,3.920876096209026400e+02,2.195828552429791358e+00,5.656854305839425834e+00,-3.328182902706967594e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.484496037608022334e+01,3.920970608743059529e+02,2.192561472830785174e+00,5.656854305839425834e+00,-3.325682902706967869e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.484672814301558219e+01,3.921065129441838053e+02,2.189296756147201428e+00,5.656854305839425834e+00,-3.323182902706968145e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.484849590995094104e+01,3.921159658299454236e+02,2.186034402583084901e+00,5.656854305839425834e+00,-3.320682902706968420e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.485026367688629989e+01,3.921254195310000341e+02,2.182774412342332937e+00,5.656854305839425834e+00,-3.318182902706968695e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.485203144382165874e+01,3.921348740467568064e+02,2.179516785628694553e+00,5.656854305839425834e+00,-3.315682902706968971e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.485379921075701759e+01,3.921443293766247962e+02,2.176261522645771329e+00,5.656854305839425834e+00,-3.313182902706969246e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.485556697769237644e+01,3.921537855200130025e+02,2.173008623597017852e+00,5.656854305839425834e+00,-3.310682902706969521e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.485733474462773529e+01,3.921632424763304812e+02,2.169758088685739494e+00,5.656854305839425834e+00,-3.308182902706969797e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.485910251156309414e+01,3.921727002449861175e+02,2.166509918115095523e+00,5.656854305839425834e+00,-3.305682902706970072e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.486087027849845299e+01,3.921821588253888535e+02,2.163264112088095992e+00,5.656854305839425834e+00,-3.303182902706970347e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.486263804543381184e+01,3.921916182169475178e+02,2.160020670807603960e+00,5.656854305839425834e+00,-3.300682902706970623e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.486440581236917069e+01,3.922010784190708819e+02,2.156779594476334605e+00,5.656854305839425834e+00,-3.298182902706970898e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.486617357930452954e+01,3.922105394311676605e+02,2.153540883296854780e+00,5.656854305839425834e+00,-3.295682902706971174e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.486794134623988839e+01,3.922200012526465684e+02,2.150304537471584343e+00,5.656854305839425834e+00,-3.293182902706971449e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.486970911317524724e+01,3.922294638829162636e+02,2.147070557202794827e+00,5.656854305839425834e+00,-3.290682902706971724e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.487147688011060609e+01,3.922389273213852903e+02,2.143838942692609884e+00,5.656854305839425834e+00,-3.288182902706972000e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.487324464704596494e+01,3.922483915674622494e+02,2.140609694143005726e+00,5.656854305839425834e+00,-3.285682902706972275e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.487501241398132379e+01,3.922578566205555717e+02,2.137382811755810241e+00,5.656854305839425834e+00,-3.283182902706972550e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.487678018091668264e+01,3.922673224800736875e+02,2.134158295732703436e+00,5.656854305839425834e+00,-3.280682902706972826e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.487854794785204149e+01,3.922767891454249707e+02,2.130936146275217435e+00,5.656854305839425834e+00,-3.278182902706973101e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.488031571478740034e+01,3.922862566160177948e+02,2.127716363584736925e+00,5.656854305839425834e+00,-3.275682902706973376e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.488208348172275919e+01,3.922957248912604200e+02,2.124498947862498266e+00,5.656854305839425834e+00,-3.273182902706973652e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.488385124865811804e+01,3.923051939705611062e+02,2.121283899309589938e+00,5.656854305839425834e+00,-3.270682902706973927e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.488561901559347689e+01,3.923146638533279997e+02,2.118071218126952093e+00,5.656854305839425834e+00,-3.268182902706974202e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.488738678252883574e+01,3.923241345389692469e+02,2.114860904515377893e+00,5.656854305839425834e+00,-3.265682902706974478e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.488915454946419459e+01,3.923336060268929373e+02,2.111652958675511282e+00,5.656854305839425834e+00,-3.263182902706974753e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.489092231639955344e+01,3.923430783165071034e+02,2.108447380807849214e+00,5.656854305839425834e+00,-3.260682902706975028e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.489269008333491229e+01,3.923525514072197211e+02,2.105244171112740315e+00,5.656854305839425834e+00,-3.258182902706975304e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.489445785027027114e+01,3.923620252984387093e+02,2.102043329790385329e+00,5.656854305839425834e+00,-3.255682902706975579e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.489622561720562999e+01,3.923714999895719302e+02,2.098844857040836676e+00,5.656854305839425834e+00,-3.253182902706975854e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.489799338414098884e+01,3.923809754800272458e+02,2.095648753063998893e+00,5.656854305839425834e+00,-3.250682902706976130e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.489976115107634769e+01,3.923904517692124614e+02,2.092455018059628635e+00,5.656854305839425834e+00,-3.248182902706976405e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.490152891801170654e+01,3.923999288565352686e+02,2.089263652227334234e+00,5.656854305839425834e+00,-3.245682902706976680e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.490329668494706539e+01,3.924094067414033589e+02,2.086074655766576136e+00,5.656854305839425834e+00,-3.243182902706976956e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.490506445188242424e+01,3.924188854232244239e+02,2.082888028876666464e+00,5.656854305839425834e+00,-3.240682902706977231e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.490683221881778309e+01,3.924283649014059847e+02,2.079703771756769459e+00,5.656854305839425834e+00,-3.238182902706977506e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.490859998575314194e+01,3.924378451753555623e+02,2.076521884605901036e+00,5.656854305839425834e+00,-3.235682902706977782e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.491036775268850079e+01,3.924473262444806778e+02,2.073342367622929228e+00,5.656854305839425834e+00,-3.233182902706978057e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.491213551962385964e+01,3.924568081081887385e+02,2.070165221006574185e+00,5.656854305839425834e+00,-3.230682902706978332e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.491390328655921849e+01,3.924662907658871518e+02,2.066990444955407291e+00,5.656854305839425834e+00,-3.228182902706978608e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.491567105349457734e+01,3.924757742169832113e+02,2.063818039667852045e+00,5.656854305839425834e+00,-3.225682902706978883e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.491743882042993619e+01,3.924852584608842108e+02,2.060648005342183620e+00,5.656854305839425834e+00,-3.223182902706979158e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.491920658736529504e+01,3.924947434969974438e+02,2.057480342176529309e+00,5.656854305839425834e+00,-3.220682902706979434e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.492097435430065389e+01,3.925042293247300336e+02,2.054315050368868079e+00,5.656854305839425834e+00,-3.218182902706979709e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.492274212123601274e+01,3.925137159434891601e+02,2.051152130117030570e+00,5.656854305839425834e+00,-3.215682902706979984e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.492450988817137159e+01,3.925232033526818327e+02,2.047991581618699541e+00,5.656854305839425834e+00,-3.213182902706980260e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.492627765510673044e+01,3.925326915517151747e+02,2.044833405071408983e+00,5.656854305839425834e+00,-3.210682902706980535e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.492804542204208929e+01,3.925421805399961386e+02,2.041677600672545001e+00,5.656854305839425834e+00,-3.208182902706980810e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.492981318897744814e+01,3.925516703169316770e+02,2.038524168619345822e+00,5.656854305839425834e+00,-3.205682902706981086e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.493158095591280698e+01,3.925611608819286289e+02,2.035373109108900458e+00,5.656854305839425834e+00,-3.203182902706981361e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.493334872284816583e+01,3.925706522343938900e+02,2.032224422338150038e+00,5.656854305839425834e+00,-3.200682902706981636e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.493511648978352468e+01,3.925801443737342424e+02,2.029078108503887812e+00,5.656854305839425834e+00,-3.198182902706981912e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.493688425671888353e+01,3.925896372993564114e+02,2.025934167802758257e+00,5.656854305839425834e+00,-3.195682902706982187e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.493865202365424238e+01,3.925991310106670653e+02,2.022792600431257526e+00,5.656854305839425834e+00,-3.193182902706982462e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.494041979058960123e+01,3.926086255070728726e+02,2.019653406585733890e+00,5.656854305839425834e+00,-3.190682902706982738e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.494218755752496008e+01,3.926181207879804447e+02,2.016516586462386851e+00,5.656854305839425834e+00,-3.188182902706983013e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.494395532446031893e+01,3.926276168527963364e+02,2.013382140257267583e+00,5.656854305839425834e+00,-3.185682902706983288e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.494572309139567778e+01,3.926371137009269887e+02,2.010250068166278936e+00,5.656854305839425834e+00,-3.183182902706983564e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.494749085833103663e+01,3.926466113317788995e+02,2.007120370385175434e+00,5.656854305839425834e+00,-3.180682902706983839e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.494925862526639548e+01,3.926561097447584530e+02,2.003993047109563275e+00,5.656854305839425834e+00,-3.178182902706984114e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.495102639220175433e+01,3.926656089392719764e+02,2.000868098534899886e+00,5.656854305839425834e+00,-3.175682902706984390e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.495279415913711318e+01,3.926751089147257971e+02,1.997745524856495036e+00,5.656854305839425834e+00,-3.173182902706984665e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.495456192607247203e+01,3.926846096705261289e+02,1.994625326269509280e+00,5.656854305839425834e+00,-3.170682902706984940e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.495632969300783088e+01,3.926941112060791852e+02,1.991507502968955068e+00,5.656854305839425834e+00,-3.168182902706985216e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.495809745994318973e+01,3.927036135207911798e+02,1.988392055149696303e+00,5.656854305839425834e+00,-3.165682902706985491e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.495986522687854858e+01,3.927131166140681557e+02,1.985278983006448561e+00,5.656854305839425834e+00,-3.163182902706985766e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.496163299381390743e+01,3.927226204853162130e+02,1.982168286733778872e+00,5.656854305839425834e+00,-3.160682902706986042e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.496340076074926628e+01,3.927321251339413379e+02,1.979059966526105718e+00,5.656854305839425834e+00,-3.158182902706986317e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.496516852768462513e+01,3.927416305593494599e+02,1.975954022577699032e+00,5.656854305839425834e+00,-3.155682902706986592e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.496693629461998398e+01,3.927511367609465083e+02,1.972850455082680421e+00,5.656854305839425834e+00,-3.153182902706986868e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.496870406155534283e+01,3.927606437381383557e+02,1.969749264235022723e+00,5.656854305839425834e+00,-3.150682902706987143e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.497047182849070168e+01,3.927701514903308180e+02,1.966650450228550451e+00,5.656854305839425834e+00,-3.148182902706987418e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.497223959542606053e+01,3.927796600169296539e+02,1.963554013256939568e+00,5.656854305839425834e+00,-3.145682902706987694e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.497400736236141938e+01,3.927891693173405656e+02,1.960459953513717268e+00,5.656854305839425834e+00,-3.143182902706987969e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.497577512929677823e+01,3.927986793909692551e+02,1.957368271192262199e+00,5.656854305839425834e+00,-3.140682902706988244e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.497754289623213708e+01,3.928081902372213108e+02,1.954278966485804681e+00,5.656854305839425834e+00,-3.138182902706988520e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.497931066316749593e+01,3.928177018555023210e+02,1.951192039587426263e+00,5.656854305839425834e+00,-3.135682902706988795e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.498107843010285478e+01,3.928272142452178173e+02,1.948107490690059729e+00,5.656854305839425834e+00,-3.133182902706989070e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.498284619703821363e+01,3.928367274057732743e+02,1.945025319986489531e+00,5.656854305839425834e+00,-3.130682902706989346e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.498461396397357248e+01,3.928462413365741099e+02,1.941945527669351135e+00,5.656854305839425834e+00,-3.128182902706989621e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.498638173090893133e+01,3.928557560370257420e+02,1.938868113931131676e+00,5.656854305839425834e+00,-3.125682902706989896e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.498814949784429018e+01,3.928652715065334178e+02,1.935793078964169522e+00,5.656854305839425834e+00,-3.123182902706990172e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.498991726477964903e+01,3.928747877445024983e+02,1.932720422960654494e+00,5.656854305839425834e+00,-3.120682902706990447e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.499168503171500788e+01,3.928843047503381740e+02,1.929650146112627418e+00,5.656854305839425834e+00,-3.118182902706990722e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.499345279865036673e+01,3.928938225234456354e+02,1.926582248611980575e+00,5.656854305839425834e+00,-3.115682902706990998e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.499522056558572558e+01,3.929033410632300729e+02,1.923516730650457696e+00,5.656854305839425834e+00,-3.113182902706991273e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.499698833252108443e+01,3.929128603690965065e+02,1.920453592419653521e+00,5.656854305839425834e+00,-3.110682902706991548e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.499875609945644328e+01,3.929223804404500129e+02,1.917392834111014244e+00,5.656854305839425834e+00,-3.108182902706991824e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.500052386639180213e+01,3.929319012766956121e+02,1.914334455915837285e+00,5.656854305839425834e+00,-3.105682902706992099e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.500229163332716098e+01,3.929414228772382103e+02,1.911278458025271076e+00,5.656854305839425834e+00,-3.103182902706992374e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.500405940026251983e+01,3.929509452414827138e+02,1.908224840630315722e+00,5.656854305839425834e+00,-3.100682902706992650e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.500582716719787868e+01,3.929604683688339719e+02,1.905173603921822334e+00,5.656854305839425834e+00,-3.098182902706992925e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.500759493413323753e+01,3.929699922586968341e+02,1.902124748090493034e+00,5.656854305839425834e+00,-3.095682902706993200e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.500936270106859638e+01,3.929795169104760362e+02,1.899078273326881394e+00,5.656854305839425834e+00,-3.093182902706993476e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.501113046800395523e+01,3.929890423235762569e+02,1.896034179821391996e+00,5.656854305839425834e+00,-3.090682902706993751e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.501289823493931408e+01,3.929985684974021751e+02,1.892992467764280873e+00,5.656854305839425834e+00,-3.088182902706994026e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.501466600187467293e+01,3.930080954313584130e+02,1.889953137345654843e+00,5.656854305839425834e+00,-3.085682902706994302e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.501643376881003178e+01,3.930176231248495355e+02,1.886916188755472179e+00,5.656854305839425834e+00,-3.083182902706994577e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.501820153574539063e+01,3.930271515772800512e+02,1.883881622183542159e+00,5.656854305839425834e+00,-3.080682902706994852e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.501996930268074948e+01,3.930366807880544116e+02,1.880849437819525072e+00,5.656854305839425834e+00,-3.078182902706995128e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.502173706961610833e+01,3.930462107565770680e+02,1.877819635852932656e+00,5.656854305839425834e+00,-3.075682902706995403e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.502350483655146718e+01,3.930557414822524152e+02,1.874792216473127437e+00,5.656854305839425834e+00,-3.073182902706995678e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.502527260348682603e+01,3.930652729644847909e+02,1.871767179869322950e+00,5.656854305839425834e+00,-3.070682902706995954e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.502704037042218488e+01,3.930748052026784194e+02,1.868744526230584180e+00,5.656854305839425834e+00,-3.068182902706996229e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.502880813735754373e+01,3.930843381962375815e+02,1.865724255745826898e+00,5.656854305839425834e+00,-3.065682902706996504e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.503057590429290258e+01,3.930938719445664447e+02,1.862706368603818108e+00,5.656854305839425834e+00,-3.063182902706996780e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.503234367122826143e+01,3.931034064470691760e+02,1.859690864993175596e+00,5.656854305839425834e+00,-3.060682902706997055e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.503411143816362028e+01,3.931129417031498292e+02,1.856677745102368382e+00,5.656854305839425834e+00,-3.058182902706997330e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.503587920509897913e+01,3.931224777122124578e+02,1.853667009119716491e+00,5.656854305839425834e+00,-3.055682902706997606e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.503764697203433798e+01,3.931320144736610587e+02,1.850658657233390958e+00,5.656854305839425834e+00,-3.053182902706997881e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.503941473896969683e+01,3.931415519868996284e+02,1.847652689631413825e+00,5.656854305839425834e+00,-3.050682902706998156e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.504118250590505568e+01,3.931510902513320502e+02,1.844649106501657920e+00,5.656854305839425834e+00,-3.048182902706998432e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.504295027284041453e+01,3.931606292663621502e+02,1.841647908031847303e+00,5.656854305839425834e+00,-3.045682902706998707e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.504471803977577338e+01,3.931701690313937547e+02,1.838649094409556817e+00,5.656854305839425834e+00,-3.043182902706998982e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.504648580671113223e+01,3.931797095458306899e+02,1.835652665822212315e+00,5.656854305839425834e+00,-3.040682902706999258e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.504825357364649108e+01,3.931892508090766114e+02,1.832658622457090658e+00,5.656854305839425834e+00,-3.038182902706999533e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.505002134058184993e+01,3.931987928205351750e+02,1.829666964501319493e+00,5.656854305839425834e+00,-3.035682902706999808e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.505178910751720878e+01,3.932083355796100363e+02,1.826677692141877252e+00,5.656854305839425834e+00,-3.033182902707000084e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.505355687445256763e+01,3.932178790857047943e+02,1.823690805565593820e+00,5.656854305839425834e+00,-3.030682902707000359e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.505532464138792648e+01,3.932274233382229340e+02,1.820706304959149424e+00,5.656854305839425834e+00,-3.028182902707000634e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.505709240832328533e+01,3.932369683365679407e+02,1.817724190509075299e+00,5.656854305839425834e+00,-3.025682902707000910e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.505886017525864418e+01,3.932465140801432995e+02,1.814744462401753688e+00,5.656854305839425834e+00,-3.023182902707001185e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.506062794219400303e+01,3.932560605683523818e+02,1.811767120823417399e+00,5.656854305839425834e+00,-3.020682902707001460e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.506239570912936188e+01,3.932656078005985023e+02,1.808792165960150466e+00,5.656854305839425834e+00,-3.018182902707001736e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.506416347606472073e+01,3.932751557762849757e+02,1.805819597997887493e+00,5.656854305839425834e+00,-3.015682902707002011e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.506593124300007958e+01,3.932847044948150597e+02,1.802849417122414089e+00,5.656854305839425834e+00,-3.013182902707002286e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.506769900993543843e+01,3.932942539555919552e+02,1.799881623519366425e+00,5.656854305839425834e+00,-3.010682902707002562e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.506946677687079728e+01,3.933038041580188633e+02,1.796916217374231683e+00,5.656854305839425834e+00,-3.008182902707002837e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.507123454380615613e+01,3.933133551014988143e+02,1.793953198872347832e+00,5.656854305839425834e+00,-3.005682902707003112e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.507300231074151498e+01,3.933229067854349523e+02,1.790992568198903401e+00,5.656854305839425834e+00,-3.003182902707003388e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.507477007767687383e+01,3.933324592092302510e+02,1.788034325538937930e+00,5.656854305839425834e+00,-3.000682902707003663e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.507653784461223267e+01,3.933420123722876838e+02,1.785078471077341300e+00,5.656854305839425834e+00,-2.998182902707003938e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.507830561154759152e+01,3.933515662740101675e+02,1.782125004998854623e+00,5.656854305839425834e+00,-2.995682902707004214e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.508007337848295037e+01,3.933611209138006188e+02,1.779173927488069573e+00,5.656854305839425834e+00,-2.993182902707004489e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.508184114541830922e+01,3.933706762910618409e+02,1.776225238729428391e+00,5.656854305839425834e+00,-2.990682902707004764e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.508360891235366807e+01,3.933802324051966366e+02,1.773278938907224100e+00,5.656854305839425834e+00,-2.988182902707005040e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.508537667928902692e+01,3.933897892556077522e+02,1.770335028205600514e+00,5.656854305839425834e+00,-2.985682902707005315e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.508714444622438577e+01,3.933993468416979340e+02,1.767393506808552228e+00,5.656854305839425834e+00,-2.983182902707005590e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.508891221315974462e+01,3.934089051628697575e+02,1.764454374899923961e+00,5.656854305839425834e+00,-2.980682902707005866e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.509067998009510347e+01,3.934184642185258554e+02,1.761517632663411659e+00,5.656854305839425834e+00,-2.978182902707006141e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.509244774703046232e+01,3.934280240080688031e+02,1.758583280282561612e+00,5.656854305839425834e+00,-2.975682902707006416e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.509421551396582117e+01,3.934375845309010629e+02,1.755651317940771117e+00,5.656854305839425834e+00,-2.973182902707006692e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.509598328090118002e+01,3.934471457864251533e+02,1.752721745821287591e+00,5.656854305839425834e+00,-2.970682902707006967e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.509775104783653887e+01,3.934567077740434797e+02,1.749794564107209238e+00,5.656854305839425834e+00,-2.968182902707007242e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.509951881477189772e+01,3.934662704931583903e+02,1.746869772981485047e+00,5.656854305839425834e+00,-2.965682902707007518e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.510128658170725657e+01,3.934758339431722334e+02,1.743947372626914349e+00,5.656854305839425834e+00,-2.963182902707007793e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.510305434864261542e+01,3.934853981234873004e+02,1.741027363226147262e+00,5.656854305839425834e+00,-2.960682902707008068e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.510482211557797427e+01,3.934949630335058259e+02,1.738109744961684244e+00,5.656854305839425834e+00,-2.958182902707008344e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.510658988251333312e+01,3.935045286726300446e+02,1.735194518015876541e+00,5.656854305839425834e+00,-2.955682902707008619e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.510835764944869197e+01,3.935140950402620206e+02,1.732281682570925740e+00,5.656854305839425834e+00,-2.953182902707008894e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.511012541638405082e+01,3.935236621358039315e+02,1.729371238808884215e+00,5.656854305839425834e+00,-2.950682902707009170e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.511189318331940967e+01,3.935332299586577847e+02,1.726463186911654679e+00,5.656854305839425834e+00,-2.948182902707009445e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.511366095025476852e+01,3.935427985082256441e+02,1.723557527060990191e+00,5.656854305839425834e+00,-2.945682902707009720e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.511542871719012737e+01,3.935523677839094034e+02,1.720654259438494815e+00,5.656854305839425834e+00,-2.943182902707009996e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.511719648412548622e+01,3.935619377851110130e+02,1.717753384225622515e+00,5.656854305839425834e+00,-2.940682902707010271e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.511896425106084507e+01,3.935715085112323663e+02,1.714854901603678039e+00,5.656854305839425834e+00,-2.938182902707010546e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.512073201799620392e+01,3.935810799616753002e+02,1.711958811753816478e+00,5.656854305839425834e+00,-2.935682902707010822e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.512249978493156277e+01,3.935906521358415944e+02,1.709065114857043488e+00,5.656854305839425834e+00,-2.933182902707011097e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.512426755186692162e+01,3.936002250331329719e+02,1.706173811094215287e+00,5.656854305839425834e+00,-2.930682902707011372e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.512603531880228047e+01,3.936097986529510990e+02,1.703284900646038214e+00,5.656854305839425834e+00,-2.928182902707011648e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.512780308573763932e+01,3.936193729946976987e+02,1.700398383693069171e+00,5.656854305839425834e+00,-2.925682902707011923e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.512957085267299817e+01,3.936289480577743234e+02,1.697514260415715626e+00,5.656854305839425834e+00,-2.923182902707012198e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.513133861960835702e+01,3.936385238415825256e+02,1.694632530994234942e+00,5.656854305839425834e+00,-2.920682902707012474e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.513310638654371587e+01,3.936481003455238579e+02,1.691753195608735494e+00,5.656854305839425834e+00,-2.918182902707012749e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.513487415347907472e+01,3.936576775689997589e+02,1.688876254439175773e+00,5.656854305839425834e+00,-2.915682902707013024e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.513664192041443357e+01,3.936672555114116108e+02,1.686001707665364391e+00,5.656854305839425834e+00,-2.913182902707013300e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.513840968734979242e+01,3.936768341721608522e+02,1.683129555466960525e+00,5.656854305839425834e+00,-2.910682902707013575e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.514017745428515127e+01,3.936864135506488083e+02,1.680259798023473916e+00,5.656854305839425834e+00,-2.908182902707013850e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.514194522122051012e+01,3.936959936462767473e+02,1.677392435514264202e+00,5.656854305839425834e+00,-2.905682902707014126e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.514371298815586897e+01,3.937055744584459376e+02,1.674527468118541584e+00,5.656854305839425834e+00,-2.903182902707014401e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.514548075509122782e+01,3.937151559865575905e+02,1.671664896015366608e+00,5.656854305839425834e+00,-2.900682902707014676e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.514724852202658667e+01,3.937247382300128038e+02,1.668804719383649937e+00,5.656854305839425834e+00,-2.898182902707014952e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.514901628896194552e+01,3.937343211882127321e+02,1.665946938402152577e+00,5.656854305839425834e+00,-2.895682902707015227e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.515078405589730437e+01,3.937439048605584162e+02,1.663091553249486099e+00,5.656854305839425834e+00,-2.893182902707015502e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.515255182283266322e+01,3.937534892464508971e+02,1.660238564104111747e+00,5.656854305839425834e+00,-2.890682902707015778e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.515431958976802207e+01,3.937630743452911588e+02,1.657387971144341554e+00,5.656854305839425834e+00,-2.888182902707016053e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.515608735670338092e+01,3.937726601564801285e+02,1.654539774548337450e+00,5.656854305839425834e+00,-2.885682902707016328e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.515785512363873977e+01,3.937822466794186766e+02,1.651693974494111705e+00,5.656854305839425834e+00,-2.883182902707016604e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.515962289057409862e+01,3.937918339135076735e+02,1.648850571159526934e+00,5.656854305839425834e+00,-2.880682902707016879e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.516139065750945747e+01,3.938014218581478758e+02,1.646009564722295870e+00,5.656854305839425834e+00,-2.878182902707017154e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.516315842444481632e+01,3.938110105127400402e+02,1.643170955359981367e+00,5.656854305839425834e+00,-2.875682902707017430e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.516492619138017517e+01,3.938205998766849234e+02,1.640334743249996396e+00,5.656854305839425834e+00,-2.873182902707017705e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.516669395831553402e+01,3.938301899493831684e+02,1.637500928569604275e+00,5.656854305839425834e+00,-2.870682902707017981e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.516846172525089287e+01,3.938397807302353613e+02,1.634669511495918437e+00,5.656854305839425834e+00,-2.868182902707018256e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.517022949218625172e+01,3.938493722186420882e+02,1.631840492205902438e+00,5.656854305839425834e+00,-2.865682902707018531e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.517199725912161057e+01,3.938589644140039354e+02,1.629013870876369952e+00,5.656854305839425834e+00,-2.863182902707018807e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.517376502605696942e+01,3.938685573157213184e+02,1.626189647683984996e+00,5.656854305839425834e+00,-2.860682902707019082e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.517553279299232827e+01,3.938781509231947098e+02,1.623367822805261262e+00,5.656854305839425834e+00,-2.858182902707019357e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.517730055992768712e+01,3.938877452358245250e+02,1.620548396416563008e+00,5.656854305839425834e+00,-2.855682902707019633e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.517906832686304597e+01,3.938973402530111230e+02,1.617731368694104166e+00,5.656854305839425834e+00,-2.853182902707019908e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.518083609379840482e+01,3.939069359741548055e+02,1.614916739813949231e+00,5.656854305839425834e+00,-2.850682902707020183e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.518260386073376367e+01,3.939165323986558178e+02,1.612104509952012377e+00,5.656854305839425834e+00,-2.848182902707020459e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.518437162766912252e+01,3.939261295259144049e+02,1.609294679284057894e+00,5.656854305839425834e+00,-2.845682902707020734e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.518613939460448137e+01,3.939357273553307550e+02,1.606487247985700417e+00,5.656854305839425834e+00,-2.843182902707021009e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.518790716153984022e+01,3.939453258863049996e+02,1.603682216232404256e+00,5.656854305839425834e+00,-2.840682902707021285e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.518967492847519907e+01,3.939549251182372132e+02,1.600879584199483840e+00,5.656854305839425834e+00,-2.838182902707021560e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.519144269541055792e+01,3.939645250505274134e+02,1.598079352062103720e+00,5.656854305839425834e+00,-2.835682902707021835e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.519321046234591677e+01,3.939741256825756750e+02,1.595281519995278341e+00,5.656854305839425834e+00,-2.833182902707022111e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.519497822928127562e+01,3.939837270137819019e+02,1.592486088173872272e+00,5.656854305839425834e+00,-2.830682902707022386e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.519674599621663447e+01,3.939933290435460549e+02,1.589693056772599977e+00,5.656854305839425834e+00,-2.828182902707022661e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.519851376315199332e+01,3.940029317712679813e+02,1.586902425966026042e+00,5.656854305839425834e+00,-2.825682902707022937e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.520028153008735217e+01,3.940125351963475282e+02,1.584114195928564728e+00,5.656854305839425834e+00,-2.823182902707023212e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.520204929702271102e+01,3.940221393181844292e+02,1.581328366834480414e+00,5.656854305839425834e+00,-2.820682902707023487e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.520381706395806987e+01,3.940317441361784745e+02,1.578544938857887603e+00,5.656854305839425834e+00,-2.818182902707023763e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.520558483089342872e+01,3.940413496497293977e+02,1.575763912172750469e+00,5.656854305839425834e+00,-2.815682902707024038e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.520735259782878757e+01,3.940509558582368186e+02,1.572985286952883088e+00,5.656854305839425834e+00,-2.813182902707024313e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.520912036476414642e+01,3.940605627611003001e+02,1.570209063371949432e+00,5.656854305839425834e+00,-2.810682902707024589e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.521088813169950527e+01,3.940701703577194621e+02,1.567435241603463814e+00,5.656854305839425834e+00,-2.808182902707024864e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.521265589863486412e+01,3.940797786474938107e+02,1.564663821820789780e+00,5.656854305839425834e+00,-2.805682902707025139e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.521442366557022297e+01,3.940893876298228520e+02,1.561894804197141218e+00,5.656854305839425834e+00,-2.803182902707025415e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.521619143250558182e+01,3.940989973041060352e+02,1.559128188905581691e+00,5.656854305839425834e+00,-2.800682902707025690e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.521795919944094067e+01,3.941086076697426961e+02,1.556363976119024661e+00,5.656854305839425834e+00,-2.798182902707025965e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.521972696637629952e+01,3.941182187261322269e+02,1.553602166010233487e+00,5.656854305839425834e+00,-2.795682902707026241e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.522149473331165836e+01,3.941278304726739634e+02,1.550842758751821204e+00,5.656854305839425834e+00,-2.793182902707026516e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.522326250024701721e+01,3.941374429087671274e+02,1.548085754516250745e+00,5.656854305839425834e+00,-2.790682902707026791e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.522503026718237606e+01,3.941470560338109408e+02,1.545331153475834940e+00,5.656854305839425834e+00,-2.788182902707027067e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.522679803411773491e+01,3.941566698472046255e+02,1.542578955802736296e+00,5.656854305839425834e+00,-2.785682902707027342e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.522856580105309376e+01,3.941662843483472898e+02,1.539829161668967217e+00,5.656854305839425834e+00,-2.783182902707027617e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.523033356798845261e+01,3.941758995366379850e+02,1.537081771246389783e+00,5.656854305839425834e+00,-2.780682902707027893e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.523210133492381146e+01,3.941855154114758193e+02,1.534336784706715973e+00,5.656854305839425834e+00,-2.778182902707028168e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.523386910185917031e+01,3.941951319722597873e+02,1.531594202221507439e+00,5.656854305839425834e+00,-2.775682902707028443e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.523563686879452916e+01,3.942047492183888835e+02,1.528854023962175512e+00,5.656854305839425834e+00,-2.773182902707028719e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.523740463572988801e+01,3.942143671492619887e+02,1.526116250099981420e+00,5.656854305839425834e+00,-2.770682902707028994e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.523917240266524686e+01,3.942239857642779839e+02,1.523380880806036064e+00,5.656854305839425834e+00,-2.768182902707029269e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.524094016960060571e+01,3.942336050628356929e+02,1.520647916251299803e+00,5.656854305839425834e+00,-2.765682902707029545e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.524270793653596456e+01,3.942432250443339399e+02,1.517917356606583112e+00,5.656854305839425834e+00,-2.763182902707029820e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.524447570347132341e+01,3.942528457081714919e+02,1.515189202042545924e+00,5.656854305839425834e+00,-2.760682902707030095e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.524624347040668226e+01,3.942624670537470024e+02,1.512463452729697844e+00,5.656854305839425834e+00,-2.758182902707030371e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.524801123734204111e+01,3.942720890804591818e+02,1.509740108838398376e+00,5.656854305839425834e+00,-2.755682902707030646e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.524977900427739996e+01,3.942817117877066266e+02,1.507019170538856256e+00,5.656854305839425834e+00,-2.753182902707030921e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.525154677121275881e+01,3.942913351748879336e+02,1.504300638001130341e+00,5.656854305839425834e+00,-2.750682902707031197e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.525331453814811766e+01,3.943009592414016424e+02,1.501584511395128718e+00,5.656854305839425834e+00,-2.748182902707031472e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.525508230508347651e+01,3.943105839866462361e+02,1.498870790890609594e+00,5.656854305839425834e+00,-2.745682902707031747e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.525685007201883536e+01,3.943202094100201975e+02,1.496159476657180187e+00,5.656854305839425834e+00,-2.743182902707032023e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.525861783895419421e+01,3.943298355109218960e+02,1.493450568864297834e+00,5.656854305839425834e+00,-2.740682902707032298e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.526038560588955306e+01,3.943394622887497007e+02,1.490744067681269103e+00,5.656854305839425834e+00,-2.738182902707032573e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.526215337282491191e+01,3.943490897429019810e+02,1.488039973277250461e+00,5.656854305839425834e+00,-2.735682902707032849e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.526392113976027076e+01,3.943587178727769924e+02,1.485338285821247828e+00,5.656854305839425834e+00,-2.733182902707033124e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.526568890669562961e+01,3.943683466777729905e+02,1.482639005482116579e+00,5.656854305839425834e+00,-2.730682902707033399e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.526745667363098846e+01,3.943779761572881739e+02,1.479942132428561763e+00,5.656854305839425834e+00,-2.728182902707033675e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.526922444056634731e+01,3.943876063107206846e+02,1.477247666829137884e+00,5.656854305839425834e+00,-2.725682902707033950e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.527099220750170616e+01,3.943972371374686645e+02,1.474555608852249122e+00,5.656854305839425834e+00,-2.723182902707034225e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.527275997443706501e+01,3.944068686369301417e+02,1.471865958666149110e+00,5.656854305839425834e+00,-2.720682902707034501e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.527452774137242386e+01,3.944165008085031445e+02,1.469178716438940935e+00,5.656854305839425834e+00,-2.718182902707034776e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.527629550830778271e+01,3.944261336515857010e+02,1.466493882338577359e+00,5.656854305839425834e+00,-2.715682902707035051e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.527806327524314156e+01,3.944357671655757827e+02,1.463811456532860378e+00,5.656854305839425834e+00,-2.713182902707035327e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.527983104217850041e+01,3.944454013498712470e+02,1.461131439189441661e+00,5.656854305839425834e+00,-2.710682902707035602e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.528159880911385926e+01,3.944550362038699518e+02,1.458453830475822111e+00,5.656854305839425834e+00,-2.708182902707035877e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.528336657604921811e+01,3.944646717269697547e+02,1.455778630559352527e+00,5.656854305839425834e+00,-2.705682902707036153e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.528513434298457696e+01,3.944743079185683996e+02,1.453105839607232719e+00,5.656854305839425834e+00,-2.703182902707036428e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.528690210991993581e+01,3.944839447780636874e+02,1.450435457786512172e+00,5.656854305839425834e+00,-2.700682902707036703e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.528866987685529466e+01,3.944935823048532484e+02,1.447767485264089826e+00,5.656854305839425834e+00,-2.698182902707036979e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.529043764379065351e+01,3.945032204983347697e+02,1.445101922206713851e+00,5.656854305839425834e+00,-2.695682902707037254e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.529220541072601236e+01,3.945128593579058247e+02,1.442438768780982095e+00,5.656854305839425834e+00,-2.693182902707037529e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.529397317766137121e+01,3.945224988829640438e+02,1.439778025153341634e+00,5.656854305839425834e+00,-2.690682902707037805e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.529574094459673006e+01,3.945321390729069435e+02,1.437119691490088780e+00,5.656854305839425834e+00,-2.688182902707038080e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.529750871153208891e+01,3.945417799271319836e+02,1.434463767957369518e+00,5.656854305839425834e+00,-2.685682902707038355e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.529927647846744776e+01,3.945514214450366239e+02,1.431810254721179065e+00,5.656854305839425834e+00,-2.683182902707038631e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.530104424540280661e+01,3.945610636260182673e+02,1.429159151947361872e+00,5.656854305839425834e+00,-2.680682902707038906e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.530281201233816546e+01,3.945707064694742598e+02,1.426510459801611841e+00,5.656854305839425834e+00,-2.678182902707039181e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.530457977927352431e+01,3.945803499748019476e+02,1.423864178449472329e+00,5.656854305839425834e+00,-2.675682902707039457e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.530634754620888316e+01,3.945899941413986198e+02,1.421220308056335924e+00,5.656854305839425834e+00,-2.673182902707039732e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.530811531314424201e+01,3.945996389686615089e+02,1.418578848787444668e+00,5.656854305839425834e+00,-2.670682902707040007e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.530988308007960086e+01,3.946092844559877904e+02,1.415939800807889615e+00,5.656854305839425834e+00,-2.668182902707040283e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.531165084701495971e+01,3.946189306027746397e+02,1.413303164282611268e+00,5.656854305839425834e+00,-2.665682902707040558e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.531341861395031856e+01,3.946285774084191758e+02,1.410668939376399367e+00,5.656854305839425834e+00,-2.663182902707040833e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.531518638088567741e+01,3.946382248723184603e+02,1.408037126253892879e+00,5.656854305839425834e+00,-2.660682902707041109e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.531695414782103626e+01,3.946478729938695551e+02,1.405407725079580450e+00,5.656854305839425834e+00,-2.658182902707041384e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.531872191475639511e+01,3.946575217724694085e+02,1.402780736017799290e+00,5.656854305839425834e+00,-2.655682902707041659e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.532048968169175396e+01,3.946671712075150253e+02,1.400156159232736508e+00,5.656854305839425834e+00,-2.653182902707041935e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.532225744862711281e+01,3.946768212984032971e+02,1.397533994888427999e+00,5.656854305839425834e+00,-2.650682902707042210e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.532402521556247166e+01,3.946864720445310581e+02,1.394914243148759114e+00,5.656854305839425834e+00,-2.648182902707042485e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.532579298249783051e+01,3.946961234452951430e+02,1.392296904177464212e+00,5.656854305839425834e+00,-2.645682902707042761e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.532756074943318936e+01,3.947057755000923862e+02,1.389681978138127105e+00,5.656854305839425834e+00,-2.643182902707043036e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.532932851636854821e+01,3.947154282083195085e+02,1.387069465194180617e+00,5.656854305839425834e+00,-2.640682902707043311e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.533109628330390706e+01,3.947250815693731738e+02,1.384459365508906803e+00,5.656854305839425834e+00,-2.638182902707043587e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.533286405023926591e+01,3.947347355826501030e+02,1.381851679245436726e+00,5.656854305839425834e+00,-2.635682902707043862e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.533463181717462476e+01,3.947443902475469031e+02,1.379246406566750904e+00,5.656854305839425834e+00,-2.633182902707044137e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.533639958410998361e+01,3.947540455634601813e+02,1.376643547635679088e+00,5.656854305839425834e+00,-2.630682902707044413e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.533816735104534246e+01,3.947637015297864309e+02,1.374043102614899592e+00,5.656854305839425834e+00,-2.628182902707044688e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.533993511798070131e+01,3.947733581459222023e+02,1.371445071666940629e+00,5.656854305839425834e+00,-2.625682902707044963e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.534170288491606016e+01,3.947830154112639320e+02,1.368849454954178757e+00,5.656854305839425834e+00,-2.623182902707045239e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.534347065185141901e+01,3.947926733252080567e+02,1.366256252638840207e+00,5.656854305839425834e+00,-2.620682902707045514e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.534523841878677786e+01,3.948023318871508991e+02,1.363665464883000222e+00,5.656854305839425834e+00,-2.618182902707045789e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.534700618572213671e+01,3.948119910964888959e+02,1.361077091848582832e+00,5.656854305839425834e+00,-2.615682902707046065e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.534877395265749556e+01,3.948216509526182563e+02,1.358491133697361519e+00,5.656854305839425834e+00,-2.613182902707046340e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.535054171959285441e+01,3.948313114549353031e+02,1.355907590590958556e+00,5.656854305839425834e+00,-2.610682902707046615e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.535230948652821326e+01,3.948409726028361888e+02,1.353326462690845444e+00,5.656854305839425834e+00,-2.608182902707046891e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.535407725346357211e+01,3.948506343957171794e+02,1.350747750158342475e+00,5.656854305839425834e+00,-2.605682902707047166e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.535584502039893096e+01,3.948602968329743703e+02,1.348171453154619392e+00,5.656854305839425834e+00,-2.603182902707047441e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.535761278733428981e+01,3.948699599140038003e+02,1.345597571840694728e+00,5.656854305839425834e+00,-2.600682902707047717e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.535938055426964866e+01,3.948796236382016218e+02,1.343026106377436024e+00,5.656854305839425834e+00,-2.598182902707047992e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.536114832120500751e+01,3.948892880049638165e+02,1.340457056925560053e+00,5.656854305839425834e+00,-2.595682902707048267e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.536291608814036636e+01,3.948989530136863095e+02,1.337890423645632154e+00,5.656854305839425834e+00,-2.593182902707048543e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.536468385507572521e+01,3.949086186637650826e+02,1.335326206698067120e+00,5.656854305839425834e+00,-2.590682902707048818e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.536645162201108405e+01,3.949182849545960607e+02,1.332764406243128308e+00,5.656854305839425834e+00,-2.588182902707049093e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.536821938894644290e+01,3.949279518855750553e+02,1.330205022440928309e+00,5.656854305839425834e+00,-2.585682902707049369e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.536998715588180175e+01,3.949376194560979343e+02,1.327648055451428721e+00,5.656854305839425834e+00,-2.583182902707049644e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.537175492281716060e+01,3.949472876655604523e+02,1.325093505434439933e+00,5.656854305839425834e+00,-2.580682902707049919e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.537352268975251945e+01,3.949569565133583069e+02,1.322541372549621119e+00,5.656854305839425834e+00,-2.578182902707050195e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.537529045668787830e+01,3.949666259988872525e+02,1.319991656956480908e+00,5.656854305839425834e+00,-2.575682902707050470e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.537705822362323715e+01,3.949762961215428732e+02,1.317444358814376271e+00,5.656854305839425834e+00,-2.573182902707050745e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.537882599055859600e+01,3.949859668807208664e+02,1.314899478282513412e+00,5.656854305839425834e+00,-2.570682902707051021e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.538059375749395485e+01,3.949956382758167592e+02,1.312357015519947323e+00,5.656854305839425834e+00,-2.568182902707051296e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.538236152442931370e+01,3.950053103062261357e+02,1.309816970685582005e+00,5.656854305839425834e+00,-2.565682902707051571e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.538412929136467255e+01,3.950149829713444660e+02,1.307279343938170246e+00,5.656854305839425834e+00,-2.563182902707051847e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.538589705830003140e+01,3.950246562705671636e+02,1.304744135436313623e+00,5.656854305839425834e+00,-2.560682902707052122e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.538766482523539025e+01,3.950343302032896986e+02,1.302211345338462944e+00,5.656854305839425834e+00,-2.558182902707052397e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.538943259217074910e+01,3.950440047689074277e+02,1.299680973802917361e+00,5.656854305839425834e+00,-2.555682902707052673e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.539120035910610795e+01,3.950536799668157073e+02,1.297153020987825034e+00,5.656854305839425834e+00,-2.553182902707052948e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.539296812604146680e+01,3.950633557964098372e+02,1.294627487051183135e+00,5.656854305839425834e+00,-2.550682902707053223e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.539473589297682565e+01,3.950730322570850603e+02,1.292104372150837621e+00,5.656854305839425834e+00,-2.548182902707053499e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.539650365991218450e+01,3.950827093482366195e+02,1.289583676444483018e+00,5.656854305839425834e+00,-2.545682902707053774e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.539827142684754335e+01,3.950923870692597006e+02,1.287065400089662859e+00,5.656854305839425834e+00,-2.543182902707054049e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.540003919378290220e+01,3.951020654195494330e+02,1.284549543243769243e+00,5.656854305839425834e+00,-2.540682902707054325e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.540180696071826105e+01,3.951117443985009459e+02,1.282036106064043501e+00,5.656854305839425834e+00,-2.538182902707054600e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.540357472765361990e+01,3.951214240055092546e+02,1.279525088707575309e+00,5.656854305839425834e+00,-2.535682902707054875e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.540534249458897875e+01,3.951311042399694315e+02,1.277016491331303349e+00,5.656854305839425834e+00,-2.533182902707055151e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.540711026152433760e+01,3.951407851012764354e+02,1.274510314092014873e+00,5.656854305839425834e+00,-2.530682902707055426e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.540887802845969645e+01,3.951504665888252248e+02,1.272006557146345918e+00,5.656854305839425834e+00,-2.528182902707055701e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.541064579539505530e+01,3.951601487020107015e+02,1.269505220650781308e+00,5.656854305839425834e+00,-2.525682902707055977e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.541241356233041415e+01,3.951698314402277106e+02,1.267006304761654656e+00,5.656854305839425834e+00,-2.523182902707056252e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.541418132926577300e+01,3.951795148028710969e+02,1.264509809635148141e+00,5.656854305839425834e+00,-2.520682902707056527e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.541594909620113185e+01,3.951891987893356486e+02,1.262015735427292729e+00,5.656854305839425834e+00,-2.518182902707056803e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.541771686313649070e+01,3.951988833990161538e+02,1.259524082293968172e+00,5.656854305839425834e+00,-2.515682902707057078e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.541948463007184955e+01,3.952085686313072870e+02,1.257034850390902569e+00,5.656854305839425834e+00,-2.513182902707057353e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.542125239700720840e+01,3.952182544856037225e+02,1.254548039873673027e+00,5.656854305839425834e+00,-2.510682902707057629e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.542302016394256725e+01,3.952279409613000780e+02,1.252063650897705216e+00,5.656854305839425834e+00,-2.508182902707057904e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.542478793087792610e+01,3.952376280577909711e+02,1.249581683618273376e+00,5.656854305839425834e+00,-2.505682902707058179e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.542655569781328495e+01,3.952473157744709624e+02,1.247102138190500531e+00,5.656854305839425834e+00,-2.503182902707058455e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.542832346474864380e+01,3.952570041107345560e+02,1.244625014769358273e+00,5.656854305839425834e+00,-2.500682902707058730e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.543009123168400265e+01,3.952666930659762556e+02,1.242150313509666759e+00,5.656854305839425834e+00,-2.498182902707058728e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.543185899861936150e+01,3.952763826395904516e+02,1.239678034566094933e+00,5.656854305839425834e+00,-2.495682902707058726e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.543362676555472035e+01,3.952860728309715910e+02,1.237208178093160083e+00,5.656854305839425834e+00,-2.493182902707058723e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.543539453249007920e+01,3.952957636395140071e+02,1.234740744245228283e+00,5.656854305839425834e+00,-2.490682902707058721e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.543716229942543805e+01,3.953054550646120333e+02,1.232275733176514176e+00,5.656854305839425834e+00,-2.488182902707058719e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.543893006636079690e+01,3.953151471056600030e+02,1.229813145041080968e+00,5.656854305839425834e+00,-2.485682902707058717e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.544069783329615575e+01,3.953248397620521359e+02,1.227352979992840432e+00,5.656854305839425834e+00,-2.483182902707058715e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.544246560023151460e+01,3.953345330331825949e+02,1.224895238185552682e+00,5.656854305839425834e+00,-2.480682902707058712e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.544423336716687345e+01,3.953442269184455995e+02,1.222439919772826844e+00,5.656854305839425834e+00,-2.478182902707058710e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.544600113410223230e+01,3.953539214172352558e+02,1.219987024908120166e+00,5.656854305839425834e+00,-2.475682902707058708e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.544776890103759115e+01,3.953636165289456699e+02,1.217536553744738681e+00,5.656854305839425834e+00,-2.473182902707058706e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.544953666797295000e+01,3.953733122529708908e+02,1.215088506435836768e+00,5.656854305839425834e+00,-2.470682902707058703e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.545130443490830885e+01,3.953830085887049677e+02,1.212642883134417371e+00,5.656854305839425834e+00,-2.468182902707058701e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.545307220184366770e+01,3.953927055355418361e+02,1.210199683993331998e+00,5.656854305839425834e+00,-2.465682902707058699e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.545483996877902655e+01,3.954024030928754314e+02,1.207758909165280503e+00,5.656854305839425834e+00,-2.463182902707058697e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.545660773571438540e+01,3.954121012600996892e+02,1.205320558802811304e+00,5.656854305839425834e+00,-2.460682902707058695e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.545837550264974425e+01,3.954218000366084880e+02,1.202884633058321384e+00,5.656854305839425834e+00,-2.458182902707058692e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.546014326958510310e+01,3.954314994217955928e+02,1.200451132084056072e+00,5.656854305839425834e+00,-2.455682902707058690e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.546191103652046195e+01,3.954411994150548253e+02,1.198020056032109260e+00,5.656854305839425834e+00,-2.453182902707058688e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.546367880345582080e+01,3.954509000157799505e+02,1.195591405054423184e+00,5.656854305839425834e+00,-2.450682902707058686e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.546544657039117965e+01,3.954606012233646766e+02,1.193165179302788426e+00,5.656854305839425834e+00,-2.448182902707058684e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.546721433732653850e+01,3.954703030372026547e+02,1.190741378928844130e+00,5.656854305839425834e+00,-2.445682902707058681e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.546898210426189735e+01,3.954800054566875360e+02,1.188320004084077786e+00,5.656854305839425834e+00,-2.443182902707058679e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.547074987119725620e+01,3.954897084812129719e+02,1.185901054919825448e+00,5.656854305839425834e+00,-2.440682902707058677e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.547251763813261505e+01,3.954994121101724431e+02,1.183484531587271293e+00,5.656854305839425834e+00,-2.438182902707058675e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.547428540506797390e+01,3.955091163429594872e+02,1.181070434237448064e+00,5.656854305839425834e+00,-2.435682902707058672e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.547605317200333275e+01,3.955188211789676416e+02,1.178658763021236844e+00,5.656854305839425834e+00,-2.433182902707058670e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.547782093893869160e+01,3.955285266175903303e+02,1.176249518089367285e+00,5.656854305839425834e+00,-2.430682902707058668e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.547958870587405045e+01,3.955382326582209203e+02,1.173842699592416938e+00,5.656854305839425834e+00,-2.428182902707058666e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.548135647280940930e+01,3.955479393002528354e+02,1.171438307680812141e+00,5.656854305839425834e+00,-2.425682902707058664e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.548312423974476815e+01,3.955576465430793860e+02,1.169036342504827131e+00,5.656854305839425834e+00,-2.423182902707058661e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.548489200668012700e+01,3.955673543860938821e+02,1.166636804214584933e+00,5.656854305839425834e+00,-2.420682902707058659e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.548665977361548585e+01,3.955770628286895771e+02,1.164239692960056693e+00,5.656854305839425834e+00,-2.418182902707058657e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.548842754055084470e+01,3.955867718702596676e+02,1.161845008891061681e+00,5.656854305839425834e+00,-2.415682902707058655e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.549019530748620355e+01,3.955964815101973500e+02,1.159452752157267952e+00,5.656854305839425834e+00,-2.413182902707058652e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.549196307442156240e+01,3.956061917478958208e+02,1.157062922908191238e+00,5.656854305839425834e+00,-2.410682902707058650e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.549373084135692125e+01,3.956159025827481059e+02,1.154675521293196061e+00,5.656854305839425834e+00,-2.408182902707058648e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.549549860829228010e+01,3.956256140141473452e+02,1.152290547461495063e+00,5.656854305839425834e+00,-2.405682902707058646e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.549726637522763895e+01,3.956353260414865645e+02,1.149908001562149007e+00,5.656854305839425834e+00,-2.403182902707058644e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.549903414216299780e+01,3.956450386641587329e+02,1.147527883744067001e+00,5.656854305839425834e+00,-2.400682902707058641e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.550080190909835665e+01,3.956547518815568196e+02,1.145150194156006274e+00,5.656854305839425834e+00,-2.398182902707058639e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.550256967603371550e+01,3.956644656930737938e+02,1.142774932946572619e+00,5.656854305839425834e+00,-2.395682902707058637e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.550433744296907435e+01,3.956741800981025108e+02,1.140402100264219953e+00,5.656854305839425834e+00,-2.393182902707058635e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.550610520990443320e+01,3.956838950960357693e+02,1.138031696257250092e+00,5.656854305839425834e+00,-2.390682902707058632e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.550787297683979205e+01,3.956936106862664815e+02,1.135663721073813415e+00,5.656854305839425834e+00,-2.388182902707058630e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.550964074377515090e+01,3.957033268681873324e+02,1.133298174861908425e+00,5.656854305839425834e+00,-2.385682902707058628e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.551140851071050974e+01,3.957130436411911205e+02,1.130935057769381524e+00,5.656854305839425834e+00,-2.383182902707058626e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.551317627764586859e+01,3.957227610046705308e+02,1.128574369943927680e+00,5.656854305839425834e+00,-2.380682902707058624e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.551494404458122744e+01,3.957324789580181914e+02,1.126216111533089981e+00,5.656854305839425834e+00,-2.378182902707058621e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.551671181151658629e+01,3.957421975006267871e+02,1.123860282684259415e+00,5.656854305839425834e+00,-2.375682902707058619e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.551847957845194514e+01,3.957519166318888892e+02,1.121506883544675315e+00,5.656854305839425834e+00,-2.373182902707058617e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.552024734538730399e+01,3.957616363511970121e+02,1.119155914261425133e+00,5.656854305839425834e+00,-2.370682902707058615e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.552201511232266284e+01,3.957713566579437270e+02,1.116807374981444445e+00,5.656854305839425834e+00,-2.368182902707058612e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.552378287925802169e+01,3.957810775515214914e+02,1.114461265851516947e+00,5.656854305839425834e+00,-2.365682902707058610e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.552555064619338054e+01,3.957907990313227629e+02,1.112117587018274456e+00,5.656854305839425834e+00,-2.363182902707058608e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.552731841312873939e+01,3.958005210967399421e+02,1.109776338628197134e+00,5.656854305839425834e+00,-2.360682902707058606e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.552908618006409824e+01,3.958102437471653730e+02,1.107437520827612598e+00,5.656854305839425834e+00,-2.358182902707058604e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.553085394699945709e+01,3.958199669819914561e+02,1.105101133762697252e+00,5.656854305839425834e+00,-2.355682902707058601e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.553262171393481594e+01,3.958296908006104218e+02,1.102767177579475177e+00,5.656854305839425834e+00,-2.353182902707058599e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.553438948087017479e+01,3.958394152024145569e+02,1.100435652423818800e+00,5.656854305839425834e+00,-2.350682902707058597e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.553615724780553364e+01,3.958491401867960917e+02,1.098106558441448222e+00,5.656854305839425834e+00,-2.348182902707058595e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.553792501474089249e+01,3.958588657531471995e+02,1.095779895777931889e+00,5.656854305839425834e+00,-2.345682902707058592e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.553969278167625134e+01,3.958685919008600536e+02,1.093455664578686148e+00,5.656854305839425834e+00,-2.343182902707058590e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.554146054861161019e+01,3.958783186293267704e+02,1.091133864988975466e+00,5.656854305839425834e+00,-2.340682902707058588e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.554322831554696904e+01,3.958880459379394097e+02,1.088814497153912431e+00,5.656854305839425834e+00,-2.338182902707058586e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.554499608248232789e+01,3.958977738260900310e+02,1.086497561218457530e+00,5.656854305839425834e+00,-2.335682902707058584e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.554676384941768674e+01,3.959075022931706371e+02,1.084183057327419153e+00,5.656854305839425834e+00,-2.333182902707058581e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.554853161635304559e+01,3.959172313385731741e+02,1.081870985625453807e+00,5.656854305839425834e+00,-2.330682902707058579e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.555029938328840444e+01,3.959269609616895877e+02,1.079561346257066123e+00,5.656854305839425834e+00,-2.328182902707058577e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.555206715022376329e+01,3.959366911619118241e+02,1.077254139366608410e+00,5.656854305839425834e+00,-2.325682902707058575e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.555383491715912214e+01,3.959464219386317154e+02,1.074949365098281095e+00,5.656854305839425834e+00,-2.323182902707058572e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.555560268409448099e+01,3.959561532912410371e+02,1.072647023596132509e+00,5.656854305839425834e+00,-2.320682902707058570e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.555737045102983984e+01,3.959658852191316782e+02,1.070347115004059102e+00,5.656854305839425834e+00,-2.318182902707058568e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.555913821796519869e+01,3.959756177216953006e+02,1.068049639465805223e+00,5.656854305839425834e+00,-2.315682902707058566e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.556090598490055754e+01,3.959853507983236796e+02,1.065754597124963121e+00,5.656854305839425834e+00,-2.313182902707058564e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.556267375183591639e+01,3.959950844484084769e+02,1.063461988124972724e+00,5.656854305839425834e+00,-2.310682902707058561e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.556444151877127524e+01,3.960048186713413543e+02,1.061171812609122300e+00,5.656854305839425834e+00,-2.308182902707058559e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.556620928570663409e+01,3.960145534665139166e+02,1.058884070720547577e+00,5.656854305839425834e+00,-2.305682902707058557e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.556797705264199294e+01,3.960242888333177120e+02,1.056598762602232622e+00,5.656854305839425834e+00,-2.303182902707058555e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.556974481957735179e+01,3.960340247711442885e+02,1.054315888397009182e+00,5.656854305839425834e+00,-2.300682902707058552e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.557151258651271064e+01,3.960437612793851940e+02,1.052035448247556904e+00,5.656854305839425834e+00,-2.298182902707058550e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.557328035344806949e+01,3.960534983574318630e+02,1.049757442296403109e+00,5.656854305839425834e+00,-2.295682902707058548e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.557504812038342834e+01,3.960632360046757299e+02,1.047481870685923466e+00,5.656854305839425834e+00,-2.293182902707058546e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.557681588731878719e+01,3.960729742205081720e+02,1.045208733558340874e+00,5.656854305839425834e+00,-2.290682902707058544e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.557858365425414604e+01,3.960827130043205671e+02,1.042938031055726578e+00,5.656854305839425834e+00,-2.288182902707058541e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.558035142118950489e+01,3.960924523555042356e+02,1.040669763319999497e+00,5.656854305839425834e+00,-2.285682902707058539e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.558211918812486374e+01,3.961021922734504983e+02,1.038403930492926452e+00,5.656854305839425834e+00,-2.283182902707058537e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.558388695506022259e+01,3.961119327575505622e+02,1.036140532716121720e+00,5.656854305839425834e+00,-2.280682902707058535e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.558565472199558144e+01,3.961216738071956911e+02,1.033879570131047920e+00,5.656854305839425834e+00,-2.278182902707058533e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.558742248893094029e+01,3.961314154217770351e+02,1.031621042879015127e+00,5.656854305839425834e+00,-2.275682902707058530e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.558919025586629914e+01,3.961411576006858013e+02,1.029364951101181314e+00,5.656854305839425834e+00,-2.273182902707058528e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.559095802280165799e+01,3.961509003433130260e+02,1.027111294938552133e+00,5.656854305839425834e+00,-2.270682902707058526e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.559272578973701684e+01,3.961606436490498595e+02,1.024860074531981136e+00,5.656854305839425834e+00,-2.268182902707058524e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.559449355667237569e+01,3.961703875172872813e+02,1.022611290022169550e+00,5.656854305839425834e+00,-2.265682902707058521e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.559626132360773454e+01,3.961801319474163279e+02,1.020364941549666504e+00,5.656854305839425834e+00,-2.263182902707058519e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.559802909054309339e+01,3.961898769388279788e+02,1.018121029254868803e+00,5.656854305839425834e+00,-2.260682902707058517e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.559979685747845224e+01,3.961996224909131570e+02,1.015879553278020930e+00,5.656854305839425834e+00,-2.258182902707058515e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.560156462441381109e+01,3.962093686030627850e+02,1.013640513759215045e+00,5.656854305839425834e+00,-2.255682902707058513e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.560333239134916994e+01,3.962191152746677290e+02,1.011403910838391207e+00,5.656854305839425834e+00,-2.253182902707058510e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.560510015828452879e+01,3.962288625051187978e+02,1.009169744655336931e+00,5.656854305839425834e+00,-2.250682902707058508e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.560686792521988764e+01,3.962386102938068007e+02,1.006938015349687854e+00,5.656854305839425834e+00,-2.248182902707058506e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.560863569215524649e+01,3.962483586401225466e+02,1.004708723060926845e+00,5.656854305839425834e+00,-2.245682902707058504e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.561040345909060534e+01,3.962581075434566742e+02,1.002481867928384895e+00,5.656854305839425834e+00,-2.243182902707058501e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.561217122602596419e+01,3.962678570031999357e+02,1.000257450091240230e+00,5.656854305839425834e+00,-2.240682902707058499e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.561393899296132304e+01,3.962776070187429696e+02,9.980354696885190835e-01,5.656854305839425834e+00,-2.238182902707058497e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.561570675989668189e+01,3.962873575894764144e+02,9.958159268590951463e-01,5.656854305839425834e+00,-2.235682902707058495e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.561747452683204074e+01,3.962971087147908520e+02,9.935988217416898971e-01,5.656854305839425834e+00,-2.233182902707058493e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.561924229376739959e+01,3.963068603940768639e+02,9.913841544748723811e-01,5.656854305839425834e+00,-2.230682902707058490e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.562101006070275844e+01,3.963166126267249751e+02,9.891719251970593207e-01,5.656854305839425834e+00,-2.228182902707058488e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.562277782763811729e+01,3.963263654121255968e+02,9.869621340465151160e-01,5.656854305839425834e+00,-2.225682902707058486e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.562454559457347614e+01,3.963361187496692537e+02,9.847547811613516222e-01,5.656854305839425834e+00,-2.223182902707058484e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.562631336150883499e+01,3.963458726387463003e+02,9.825498666795283720e-01,5.656854305839425834e+00,-2.220682902707058481e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.562808112844419384e+01,3.963556270787472045e+02,9.803473907388525754e-01,5.656854305839425834e+00,-2.218182902707058479e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.562984889537955269e+01,3.963653820690622638e+02,9.781473534769790090e-01,5.656854305839425834e+00,-2.215682902707058477e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.563161666231491154e+01,3.963751376090817757e+02,9.759497550314100156e-01,5.656854305839425834e+00,-2.213182902707058475e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.563338442925027039e+01,3.963848936981960378e+02,9.737545955394953934e-01,5.656854305839425834e+00,-2.210682902707058473e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.563515219618562924e+01,3.963946503357952906e+02,9.715618751384326179e-01,5.656854305839425834e+00,-2.208182902707058470e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.563691996312098809e+01,3.964044075212697180e+02,9.693715939652668423e-01,5.656854305839425834e+00,-2.205682902707058468e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.563868773005634694e+01,3.964141652540095038e+02,9.671837521568904528e-01,5.656854305839425834e+00,-2.203182902707058466e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.564045549699170579e+01,3.964239235334048317e+02,9.649983498500437351e-01,5.656854305839425834e+00,-2.200682902707058464e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.564222326392706464e+01,3.964336823588457719e+02,9.628153871813142084e-01,5.656854305839425834e+00,-2.198182902707058461e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.564399103086242349e+01,3.964434417297223945e+02,9.606348642871370691e-01,5.656854305839425834e+00,-2.195682902707058459e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.564575879779778234e+01,3.964532016454247696e+02,9.584567813037950801e-01,5.656854305839425834e+00,-2.193182902707058457e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.564752656473314119e+01,3.964629621053429105e+02,9.562811383674183485e-01,5.656854305839425834e+00,-2.190682902707058455e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.564929433166850004e+01,3.964727231088667736e+02,9.541079356139845480e-01,5.656854305839425834e+00,-2.188182902707058453e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.565106209860385889e+01,3.964824846553862585e+02,9.519371731793189184e-01,5.656854305839425834e+00,-2.185682902707058450e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.565282986553921774e+01,3.964922467442913216e+02,9.497688511990940441e-01,5.656854305839425834e+00,-2.183182902707058448e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.565459763247457659e+01,3.965020093749718058e+02,9.476029698088300757e-01,5.656854305839425834e+00,-2.180682902707058446e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.565636539940993543e+01,3.965117725468175536e+02,9.454395291438946192e-01,5.656854305839425834e+00,-2.178182902707058444e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.565813316634529428e+01,3.965215362592183510e+02,9.432785293395026249e-01,5.656854305839425834e+00,-2.175682902707058441e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.565990093328065313e+01,3.965313005115639839e+02,9.411199705307167207e-01,5.656854305839425834e+00,-2.173182902707058439e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.566166870021601198e+01,3.965410653032441815e+02,9.389638528524467675e-01,5.656854305839425834e+00,-2.170682902707058437e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.566343646715137083e+01,3.965508306336486157e+02,9.368101764394500819e-01,5.656854305839425834e+00,-2.168182902707058435e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.566520423408672968e+01,3.965605965021670158e+02,9.346589414263314355e-01,5.656854305839425834e+00,-2.165682902707058433e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.566697200102208853e+01,3.965703629081889403e+02,9.325101479475430555e-01,5.656854305839425834e+00,-2.163182902707058430e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.566873976795744738e+01,3.965801298511040613e+02,9.303637961373845133e-01,5.656854305839425834e+00,-2.160682902707058428e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.567050753489280623e+01,3.965898973303018806e+02,9.282198861300028359e-01,5.656854305839425834e+00,-2.158182902707058426e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.567227530182816508e+01,3.965996653451719567e+02,9.260784180593923942e-01,5.656854305839425834e+00,-2.155682902707058424e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.567404306876352393e+01,3.966094338951038480e+02,9.239393920593949039e-01,5.656854305839425834e+00,-2.153182902707058421e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.567581083569888278e+01,3.966192029794869427e+02,9.218028082636995357e-01,5.656854305839425834e+00,-2.150682902707058419e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.567757860263424163e+01,3.966289725977106855e+02,9.196686668058426939e-01,5.656854305839425834e+00,-2.148182902707058417e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.567934636956960048e+01,3.966387427491645212e+02,9.175369678192082379e-01,5.656854305839425834e+00,-2.145682902707058415e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.568111413650495933e+01,3.966485134332377811e+02,9.154077114370273716e-01,5.656854305839425834e+00,-2.143182902707058413e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.568288190344031818e+01,3.966582846493197962e+02,9.132808977923786431e-01,5.656854305839425834e+00,-2.140682902707058410e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.568464967037567703e+01,3.966680563967998410e+02,9.111565270181879450e-01,5.656854305839425834e+00,-2.138182902707058408e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.568641743731103588e+01,3.966778286750671896e+02,9.090345992472284031e-01,5.656854305839425834e+00,-2.135682902707058406e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.568818520424639473e+01,3.966876014835111164e+02,9.069151146121204876e-01,5.656854305839425834e+00,-2.133182902707058404e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.568995297118175358e+01,3.966973748215207820e+02,9.047980732453320130e-01,5.656854305839425834e+00,-2.130682902707058402e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.569172073811711243e+01,3.967071486884853471e+02,9.026834752791780270e-01,5.656854305839425834e+00,-2.128182902707058399e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.569348850505247128e+01,3.967169230837939722e+02,9.005713208458209218e-01,5.656854305839425834e+00,-2.125682902707058397e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.569525627198783013e+01,3.967266980068357611e+02,8.984616100772703229e-01,5.656854305839425834e+00,-2.123182902707058395e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.569702403892318898e+01,3.967364734569997609e+02,8.963543431053832000e-01,5.656854305839425834e+00,-2.120682902707058393e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.569879180585854783e+01,3.967462494336750183e+02,8.942495200618637563e-01,5.656854305839425834e+00,-2.118182902707058390e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.570055957279390668e+01,3.967560259362505235e+02,8.921471410782633171e-01,5.656854305839425834e+00,-2.115682902707058388e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.570232733972926553e+01,3.967658029641152666e+02,8.900472062859806632e-01,5.656854305839425834e+00,-2.113182902707058386e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.570409510666462438e+01,3.967755805166581808e+02,8.879497158162616977e-01,5.656854305839425834e+00,-2.110682902707058384e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.570586287359998323e+01,3.967853585932681426e+02,8.858546698001995567e-01,5.656854305839425834e+00,-2.108182902707058382e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.570763064053534208e+01,3.967951371933340283e+02,8.837620683687346101e-01,5.656854305839425834e+00,-2.105682902707058379e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.570939840747070093e+01,3.968049163162447144e+02,8.816719116526544608e-01,5.656854305839425834e+00,-2.103182902707058377e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.571116617440605978e+01,3.968146959613889635e+02,8.795841997825939451e-01,5.656854305839425834e+00,-2.100682902707058375e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.571293394134141863e+01,3.968244761281555952e+02,8.774989328890350215e-01,5.656854305839425834e+00,-2.098182902707058373e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.571470170827677748e+01,3.968342568159333155e+02,8.754161111023068820e-01,5.656854305839425834e+00,-2.095682902707058370e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.571646947521213633e+01,3.968440380241108301e+02,8.733357345525858406e-01,5.656854305839425834e+00,-2.093182902707058368e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.571823724214749518e+01,3.968538197520767881e+02,8.712578033698955560e-01,5.656854305839425834e+00,-2.090682902707058366e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.572000500908285403e+01,3.968636019992198385e+02,8.691823176841065868e-01,5.656854305839425834e+00,-2.088182902707058364e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.572177277601821288e+01,3.968733847649286304e+02,8.671092776249368361e-01,5.656854305839425834e+00,-2.085682902707058362e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.572354054295357173e+01,3.968831680485916991e+02,8.650386833219513294e-01,5.656854305839425834e+00,-2.083182902707058359e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.572530830988893058e+01,3.968929518495976367e+02,8.629705349045622143e-01,5.656854305839425834e+00,-2.080682902707058357e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.572707607682428943e+01,3.969027361673349219e+02,8.609048325020286496e-01,5.656854305839425834e+00,-2.078182902707058355e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.572884384375964828e+01,3.969125210011920331e+02,8.588415762434571388e-01,5.656854305839425834e+00,-2.075682902707058353e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.573061161069500713e+01,3.969223063505574487e+02,8.567807662578011962e-01,5.656854305839425834e+00,-2.073182902707058350e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.573237937763036598e+01,3.969320922148195336e+02,8.547224026738614588e-01,5.656854305839425834e+00,-2.070682902707058348e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.573414714456572483e+01,3.969418785933667095e+02,8.526664856202855747e-01,5.656854305839425834e+00,-2.068182902707058346e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.573591491150108368e+01,3.969516654855873412e+02,8.506130152255684251e-01,5.656854305839425834e+00,-2.065682902707058344e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.573768267843644253e+01,3.969614528908697366e+02,8.485619916180519029e-01,5.656854305839425834e+00,-2.063182902707058342e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.573945044537180138e+01,3.969712408086021469e+02,8.465134149259250229e-01,5.656854305839425834e+00,-2.060682902707058339e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.574121821230716023e+01,3.969810292381728800e+02,8.444672852772238114e-01,5.656854305839425834e+00,-2.058182902707058337e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.574298597924251908e+01,3.969908181789701302e+02,8.424236027998313059e-01,5.656854305839425834e+00,-2.055682902707058335e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.574475374617787793e+01,3.970006076303820919e+02,8.403823676214776661e-01,5.656854305839425834e+00,-2.053182902707058333e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.574652151311323678e+01,3.970103975917969024e+02,8.383435798697400632e-01,5.656854305839425834e+00,-2.050682902707058330e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.574828928004859563e+01,3.970201880626026991e+02,8.363072396720427903e-01,5.656854305839425834e+00,-2.048182902707058328e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.575005704698395448e+01,3.970299790421876196e+02,8.342733471556571523e-01,5.656854305839425834e+00,-2.045682902707058326e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.575182481391931333e+01,3.970397705299396875e+02,8.322419024477013538e-01,5.656854305839425834e+00,-2.043182902707058324e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.575359258085467218e+01,3.970495625252469267e+02,8.302129056751407221e-01,5.656854305839425834e+00,-2.040682902707058322e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.575536034779003103e+01,3.970593550274973609e+02,8.281863569647875956e-01,5.656854305839425834e+00,-2.038182902707058319e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.575712811472538988e+01,3.970691480360789569e+02,8.261622564433012128e-01,5.656854305839425834e+00,-2.035682902707058317e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.575889588166074873e+01,3.970789415503796249e+02,8.241406042371878238e-01,5.656854305839425834e+00,-2.033182902707058315e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.576066364859610758e+01,3.970887355697872749e+02,8.221214004728008007e-01,5.656854305839425834e+00,-2.030682902707058313e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.576243141553146643e+01,3.970985300936898170e+02,8.201046452763403050e-01,5.656854305839425834e+00,-2.028182902707058310e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.576419918246682528e+01,3.971083251214751044e+02,8.180903387738535093e-01,5.656854305839425834e+00,-2.025682902707058308e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.576596694940218413e+01,3.971181206525308767e+02,8.160784810912345977e-01,5.656854305839425834e+00,-2.023182902707058306e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.576773471633754298e+01,3.971279166862449870e+02,8.140690723542246543e-01,5.656854305839425834e+00,-2.020682902707058304e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.576950248327290183e+01,3.971377132220051180e+02,8.120621126884117746e-01,5.656854305839425834e+00,-2.018182902707058302e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.577127025020826068e+01,3.971475102591990094e+02,8.100576022192308434e-01,5.656854305839425834e+00,-2.015682902707058299e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.577303801714361953e+01,3.971573077972144006e+02,8.080555410719638676e-01,5.656854305839425834e+00,-2.013182902707058297e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.577480578407897838e+01,3.971671058354388606e+02,8.060559293717396434e-01,5.656854305839425834e+00,-2.010682902707058295e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.577657355101433723e+01,3.971769043732600721e+02,8.040587672435338673e-01,5.656854305839425834e+00,-2.008182902707058293e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.577834131794969608e+01,3.971867034100656042e+02,8.020640548121692470e-01,5.656854305839425834e+00,-2.005682902707058290e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.578010908488505493e+01,3.971965029452430258e+02,8.000717922023151685e-01,5.656854305839425834e+00,-2.003182902707058288e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.578187685182041378e+01,3.972063029781798491e+02,7.980819795384881399e-01,5.656854305839425834e+00,-2.000682902707058286e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.578364461875577263e+01,3.972161035082635863e+02,7.960946169450514587e-01,5.656854305839425834e+00,-1.998182902707058284e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.578541238569113148e+01,3.972259045348816926e+02,7.941097045462153226e-01,5.656854305839425834e+00,-1.995682902707058282e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.578718015262649033e+01,3.972357060574216234e+02,7.921272424660367184e-01,5.656854305839425834e+00,-1.993182902707058279e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.578894791956184918e+01,3.972455080752707772e+02,7.901472308284194224e-01,5.656854305839425834e+00,-1.990682902707058277e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.579071568649720803e+01,3.972553105878164956e+02,7.881696697571143329e-01,5.656854305839425834e+00,-1.988182902707058275e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.579248345343256688e+01,3.972651135944461771e+02,7.861945593757189155e-01,5.656854305839425834e+00,-1.985682902707058273e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.579425122036792573e+01,3.972749170945471064e+02,7.842218998076775360e-01,5.656854305839425834e+00,-1.983182902707058270e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.579601898730328458e+01,3.972847210875065684e+02,7.822516911762814606e-01,5.656854305839425834e+00,-1.980682902707058268e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.579778675423864343e+01,3.972945255727117910e+02,7.802839336046687446e-01,5.656854305839425834e+00,-1.978182902707058266e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.579955452117400228e+01,3.973043305495500022e+02,7.783186272158242325e-01,5.656854305839425834e+00,-1.975682902707058264e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.580132228810936112e+01,3.973141360174084298e+02,7.763557721325795580e-01,5.656854305839425834e+00,-1.973182902707058262e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.580309005504471997e+01,3.973239419756741881e+02,7.743953684776131441e-01,5.656854305839425834e+00,-1.970682902707058259e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.580485782198007882e+01,3.973337484237343915e+02,7.724374163734503140e-01,5.656854305839425834e+00,-1.968182902707058257e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.580662558891543767e+01,3.973435553609761541e+02,7.704819159424629582e-01,5.656854305839425834e+00,-1.965682902707058255e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.580839335585079652e+01,3.973533627867865903e+02,7.685288673068698673e-01,5.656854305839425834e+00,-1.963182902707058253e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.581016112278615537e+01,3.973631707005527005e+02,7.665782705887366211e-01,5.656854305839425834e+00,-1.960682902707058251e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.581192888972151422e+01,3.973729791016614854e+02,7.646301259099755887e-01,5.656854305839425834e+00,-1.958182902707058248e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.581369665665687307e+01,3.973827879894998887e+02,7.626844333923457064e-01,5.656854305839425834e+00,-1.955682902707058246e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.581546442359223192e+01,3.973925973634549109e+02,7.607411931574528108e-01,5.656854305839425834e+00,-1.953182902707058244e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.581723219052759077e+01,3.974024072229134390e+02,7.588004053267493054e-01,5.656854305839425834e+00,-1.950682902707058242e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.581899995746294962e+01,3.974122175672623598e+02,7.568620700215344943e-01,5.656854305839425834e+00,-1.948182902707058239e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.582076772439830847e+01,3.974220283958885602e+02,7.549261873629543595e-01,5.656854305839425834e+00,-1.945682902707058237e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.582253549133366732e+01,3.974318397081788135e+02,7.529927574720015615e-01,5.656854305839425834e+00,-1.943182902707058235e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.582430325826902617e+01,3.974416515035199495e+02,7.510617804695154387e-01,5.656854305839425834e+00,-1.940682902707058233e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.582607102520438502e+01,3.974514637812986848e+02,7.491332564761821189e-01,5.656854305839425834e+00,-1.938182902707058231e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.582783879213974387e+01,3.974612765409017925e+02,7.472071856125342970e-01,5.656854305839425834e+00,-1.935682902707058228e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.582960655907510272e+01,3.974710897817159321e+02,7.452835679989514572e-01,5.656854305839425834e+00,-1.933182902707058226e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.583137432601046157e+01,3.974809035031278199e+02,7.433624037556596509e-01,5.656854305839425834e+00,-1.930682902707058224e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.583314209294582042e+01,3.974907177045241156e+02,7.414436930027316075e-01,5.656854305839425834e+00,-1.928182902707058222e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.583490985988117927e+01,3.975005323852913648e+02,7.395274358600867348e-01,5.656854305839425834e+00,-1.925682902707058219e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.583667762681653812e+01,3.975103475448161703e+02,7.376136324474912298e-01,5.656854305839425834e+00,-1.923182902707058217e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.583844539375189697e+01,3.975201631824851347e+02,7.357022828845576345e-01,5.656854305839425834e+00,-1.920682902707058215e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.584021316068725582e+01,3.975299792976847471e+02,7.337933872907453914e-01,5.656854305839425834e+00,-1.918182902707058213e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.584198092762261467e+01,3.975397958898014963e+02,7.318869457853605098e-01,5.656854305839425834e+00,-1.915682902707058211e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.584374869455797352e+01,3.975496129582218714e+02,7.299829584875555666e-01,5.656854305839425834e+00,-1.913182902707058208e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.584551646149333237e+01,3.975594305023322477e+02,7.280814255163297055e-01,5.656854305839425834e+00,-1.910682902707058206e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.584728422842869122e+01,3.975692485215190572e+02,7.261823469905288597e-01,5.656854305839425834e+00,-1.908182902707058204e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.584905199536405007e+01,3.975790670151686754e+02,7.242857230288453074e-01,5.656854305839425834e+00,-1.905682902707058202e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.585081976229940892e+01,3.975888859826674775e+02,7.223915537498181161e-01,5.656854305839425834e+00,-1.903182902707058199e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.585258752923476777e+01,3.975987054234017251e+02,7.204998392718328093e-01,5.656854305839425834e+00,-1.900682902707058197e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.585435529617012662e+01,3.976085253367577366e+02,7.186105797131215889e-01,5.656854305839425834e+00,-1.898182902707058195e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.585612306310548547e+01,3.976183457221217736e+02,7.167237751917632238e-01,5.656854305839425834e+00,-1.895682902707058193e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.585789083004084432e+01,3.976281665788800410e+02,7.148394258256828282e-01,5.656854305839425834e+00,-1.893182902707058191e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.585965859697620317e+01,3.976379879064187435e+02,7.129575317326524164e-01,5.656854305839425834e+00,-1.890682902707058188e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.586142636391156202e+01,3.976478097041240289e+02,7.110780930302902370e-01,5.656854305839425834e+00,-1.888182902707058186e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.586319413084692087e+01,3.976576319713821022e+02,7.092011098360613275e-01,5.656854305839425834e+00,-1.885682902707058184e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.586496189778227972e+01,3.976674547075789974e+02,7.073265822672770708e-01,5.656854305839425834e+00,-1.883182902707058182e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.586672966471763857e+01,3.976772779121008057e+02,7.054545104410954171e-01,5.656854305839425834e+00,-1.880682902707058179e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.586849743165299742e+01,3.976871015843336181e+02,7.035848944745208833e-01,5.656854305839425834e+00,-1.878182902707058177e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.587026519858835627e+01,3.976969257236634121e+02,7.017177344844044429e-01,5.656854305839425834e+00,-1.875682902707058175e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.587203296552371512e+01,3.977067503294762219e+02,6.998530305874436364e-01,5.656854305839425834e+00,-1.873182902707058173e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.587380073245907397e+01,3.977165754011579679e+02,6.979907829001824604e-01,5.656854305839425834e+00,-1.870682902707058171e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.587556849939443282e+01,3.977264009380945708e+02,6.961309915390113678e-01,5.656854305839425834e+00,-1.868182902707058168e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.587733626632979167e+01,3.977362269396720080e+02,6.942736566201672677e-01,5.656854305839425834e+00,-1.865682902707058166e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.587910403326515052e+01,3.977460534052760863e+02,6.924187782597337470e-01,5.656854305839425834e+00,-1.863182902707058164e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.588087180020050937e+01,3.977558803342926694e+02,6.905663565736405163e-01,5.656854305839425834e+00,-1.860682902707058162e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.588263956713586822e+01,3.977657077261075642e+02,6.887163916776640749e-01,5.656854305839425834e+00,-1.858182902707058159e-01,0.000000000000000000e+00,6.839316092015533532e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.588440733407122707e+01,3.977755355801065775e+02,6.868688836874271564e-01,5.656854305839425834e+00,-1.855682902707058157e-01,0.000000000000000000e+00,6.839316092015533532e-02,3.126388099627371481e-09,0.000000000000000000e+00 +6.588617510100658592e+01,3.977853638956754594e+02,6.850238327183990616e-01,5.656854305839425834e+00,-1.853182902707058155e-01,5.526725509617741312e-12,6.839316092015533532e-02,7.022578214513003412e-05,0.000000000000000000e+00 +6.588794286794194477e+01,3.977951926721999598e+02,6.831812388858954366e-01,5.656854305839435604e+00,-1.850682902707058153e-01,1.241483424113188857e-07,6.839316092015533532e-02,-3.664748412965700974e-01,0.000000000000000000e+00 +6.588971063487730362e+01,3.978050219090657720e+02,6.813411023050783832e-01,5.656854306058900939e+00,-1.848182902707058151e-01,-6.477179587422044610e-04,6.839316092015533532e-02,-9.999993580576717056e-01,0.000000000000000000e+00 +6.589147840181259141e+01,3.978148516056585322e+02,6.795034230909564599e-01,5.656853161044510081e+00,-1.845682902707058148e-01,-2.415483759227113423e-03,6.839316092015533532e-02,-9.999996826171496656e-01,0.000000000000000000e+00 +6.589324616910569432e+01,3.978246817613639337e+02,6.776682013583845698e-01,5.656848891031323490e+00,-1.843182902707058146e-01,-4.183250491274484971e-03,6.839316092015533532e-02,-9.999997909499331872e-01,0.000000000000000000e+00 +6.589501393773318227e+01,3.978345123755675559e+02,6.758354372220640727e-01,5.656841496012344095e+00,-1.840682902707058144e-01,-5.951018749209370517e-03,6.839316092015533532e-02,-9.999998447390828771e-01,0.000000000000000000e+00 +6.589678170867162521e+01,3.978443434476550351e+02,6.740051307965427840e-01,5.656830975974345144e+00,-1.838182902707058142e-01,-7.718789413181498769e-03,6.839316092015533532e-02,-9.999998768963176410e-01,0.000000000000000000e+00 +6.589854948289759307e+01,3.978541749770118940e+02,6.721772821962148647e-01,5.656817330897364826e+00,-1.835682902707058139e-01,-9.486563421532659413e-03,6.839316092015533532e-02,-9.999998992800076536e-01,0.000000000000000000e+00 +6.590031726138769841e+01,3.978640069630236553e+02,6.703518915353208207e-01,5.656800560754603246e+00,-1.833182902707058137e-01,-1.125434173358462984e-02,6.839316092015533532e-02,-9.999999140638590189e-01,0.000000000000000000e+00 +6.590208504511855381e+01,3.978738394050757847e+02,6.685289589279475031e-01,5.656780665512385120e+00,-1.830682902707058135e-01,-1.302212531252427974e-02,6.839316092015533532e-02,-9.999999256739107167e-01,0.000000000000000000e+00 +6.590385283506681446e+01,3.978836723025538049e+02,6.667084844880283301e-01,5.656757645130152667e+00,-1.828182902707058133e-01,-1.478991512939060483e-02,6.839316092015533532e-02,-9.999999351042532236e-01,0.000000000000000000e+00 +6.590562063220916400e+01,3.978935056548431817e+02,6.648904683293428430e-01,5.656731499560451404e+00,-1.825682902707058131e-01,-1.655771215701321020e-02,6.839316092015533532e-02,-9.999999416223738224e-01,0.000000000000000000e+00 +6.590738843752231446e+01,3.979033394613292671e+02,6.630749105655171505e-01,5.656702228748926586e+00,-1.823182902707058128e-01,-1.832551736696541936e-02,6.839316092015533532e-02,-9.999999481690552416e-01,0.000000000000000000e+00 +6.590915625198303474e+01,3.979131737213975271e+02,6.612618113100234840e-01,5.656669832634324990e+00,-1.820682902707058126e-01,-2.009333173606333428e-02,6.839316092015533532e-02,-9.999999528322082165e-01,0.000000000000000000e+00 +6.591092407656815055e+01,3.979230084344332568e+02,6.594511706761806424e-01,5.656634311148485139e+00,-1.818182902707058124e-01,-2.186115623779230632e-02,6.839316092015533532e-02,-9.999999568046082921e-01,0.000000000000000000e+00 +6.591269191225451607e+01,3.979328435998218083e+02,6.576429887771536587e-01,5.656595664216342634e+00,-1.815682902707058122e-01,-2.362899184780114029e-02,6.839316092015533532e-02,-9.999999606892006065e-01,0.000000000000000000e+00 +6.591445976001907070e+01,3.979426792169484770e+02,6.558372657259539107e-01,5.656553891755925711e+00,-1.813182902707058120e-01,-2.539683954286480957e-02,6.839316092015533532e-02,-9.999999633623917195e-01,0.000000000000000000e+00 +6.591622762083881071e+01,3.979525152851985581e+02,6.540340016354390107e-01,5.656508993678352581e+00,-1.810682902707058117e-01,-2.716470029783760176e-02,6.839316092015533532e-02,-9.999999662369060127e-01,0.000000000000000000e+00 +6.591799549569080341e+01,3.979623518039572332e+02,6.522331966183130270e-01,5.656460969887834089e+00,-1.808182902707058115e-01,-2.893257509014235049e-02,6.839316092015533532e-02,-9.999999687147160810e-01,0.000000000000000000e+00 +6.591976338555218717e+01,3.979721887726097975e+02,6.504348507871262619e-01,5.656409820281668388e+00,-1.805682902707058113e-01,-3.070046489622112532e-02,6.839316092015533532e-02,-9.999999707447873032e-01,0.000000000000000000e+00 +6.592153129140019985e+01,3.979820261905414327e+02,6.486389642542753631e-01,5.656355544750241826e+00,-1.803182902707058111e-01,-3.246837069250763097e-02,6.839316092015533532e-02,-9.999999728229881368e-01,0.000000000000000000e+00 +6.592329921421213612e+01,3.979918640571372634e+02,6.468455371320032121e-01,5.656298143177028059e+00,-1.800682902707058108e-01,-3.423629345639948862e-02,6.839316092015533532e-02,-9.999999740029428263e-01,0.000000000000000000e+00 +6.592506715496541858e+01,3.980017023717824145e+02,6.450545695323989248e-01,5.656237615438585387e+00,-1.798182902707058106e-01,-3.600423416371387186e-02,6.839316092015533532e-02,-9.999999758742983413e-01,0.000000000000000000e+00 +6.592683511463754087e+01,3.980115411338620106e+02,6.432660615673980731e-01,5.656173961404558526e+00,-1.795682902707058104e-01,-3.777219379317642983e-02,6.839316092015533532e-02,-9.999999771636360890e-01,0.000000000000000000e+00 +6.592860309420611031e+01,3.980213803427611197e+02,6.414800133487823519e-01,5.656107180937672396e+00,-1.793182902707058102e-01,-3.954017332136497420e-02,6.839316092015533532e-02,-9.999999785651912942e-01,0.000000000000000000e+00 +6.593037109464883372e+01,3.980312199978648096e+02,6.396964249881798015e-01,5.656037273893734785e+00,-1.790682902707058100e-01,-4.130817372619360189e-02,6.839316092015533532e-02,-9.999999796151594067e-01,0.000000000000000000e+00 +6.593213911694354579e+01,3.980410600985580913e+02,6.379152965970646960e-01,5.655964240121632791e+00,-1.788182902707058097e-01,-4.307619598487072432e-02,6.839316092015533532e-02,-9.999999806806584290e-01,0.000000000000000000e+00 +6.593390716206820912e+01,3.980509006442259761e+02,6.361366282867575439e-01,5.655888079463332829e+00,-1.785682902707058095e-01,-4.484424107537354764e-02,6.839316092015533532e-02,-9.999999818232032656e-01,0.000000000000000000e+00 +6.593567523100088579e+01,3.980607416342534179e+02,6.343604201684250876e-01,5.655808791753877962e+00,-1.783182902707058093e-01,-4.661230997591319508e-02,6.839316092015533532e-02,-9.999999825145513555e-01,0.000000000000000000e+00 +6.593744332471977998e+01,3.980705830680253712e+02,6.325866723530804148e-01,5.655726376821386125e+00,-1.780682902707058091e-01,-4.838040366389738389e-02,6.839316092015533532e-02,-9.999999833414805472e-01,0.000000000000000000e+00 +6.593921144420323799e+01,3.980804249449267331e+02,6.308153849515827361e-01,5.655640834487050128e+00,-1.778182902707058088e-01,-5.014852311790728157e-02,6.839316092015533532e-02,-9.999999843009492739e-01,0.000000000000000000e+00 +6.594097959042974821e+01,3.980902672643423443e+02,6.290465580746374963e-01,5.655552164565134099e+00,-1.775682902707058086e-01,-5.191666931666009954e-02,6.839316092015533532e-02,-9.999999848002389946e-01,0.000000000000000000e+00 +6.594274776437794117e+01,3.981001100256571021e+02,6.272801918327963744e-01,5.655460366862971711e+00,-1.773182902707058084e-01,-5.368484323797186736e-02,6.839316092015533532e-02,-9.999999859296248017e-01,0.000000000000000000e+00 +6.594451596702658946e+01,3.981099532282558471e+02,6.255162863364572834e-01,5.655365441180966180e+00,-1.770682902707058082e-01,-5.545304586173866596e-02,6.839316092015533532e-02,-9.999999859170344285e-01,0.000000000000000000e+00 +6.594628419935463626e+01,3.981197968715233628e+02,6.237548416958642594e-01,5.655267387312584937e+00,-1.768182902707058080e-01,-5.722127816488088714e-02,6.839316092015533532e-02,-9.999999869458514601e-01,0.000000000000000000e+00 +6.594805246234118101e+01,3.981296409548444331e+02,6.219958580211075727e-01,5.655166205044363181e+00,-1.765682902707058077e-01,-5.898954112834273872e-02,6.839316092015533532e-02,-9.999999874849728743e-01,0.000000000000000000e+00 +6.594982075696549373e+01,3.981394854776037846e+02,6.202393354221238386e-01,5.655061894155894997e+00,-1.763182902707058075e-01,-6.075783573052963987e-02,6.839316092015533532e-02,-9.999999879701684247e-01,0.000000000000000000e+00 +6.595158908420702915e+01,3.981493304391861443e+02,6.184852740086955736e-01,5.654954454419836019e+00,-1.760682902707058073e-01,-6.252616295079153896e-02,6.839316092015533532e-02,-9.999999885315388193e-01,0.000000000000000000e+00 +6.595335744504541253e+01,3.981591758389761821e+02,6.167336738904517501e-01,5.654843885601899878e+00,-1.758182902707058071e-01,-6.429452376888787624e-02,6.839316092015533532e-02,-9.999999887094963569e-01,0.000000000000000000e+00 +6.595512584046043969e+01,3.981690216763585681e+02,6.149845351768672419e-01,5.654730187460855539e+00,-1.755682902707058068e-01,-6.606291916395024000e-02,6.839316092015533532e-02,-9.999999894428988068e-01,0.000000000000000000e+00 +6.595689427143211958e+01,3.981788679507179722e+02,6.132378579772632676e-01,5.654613359748526413e+00,-1.753182902707058066e-01,-6.783135011696080074e-02,6.839316092015533532e-02,-9.999999896608671168e-01,0.000000000000000000e+00 +6.595866273894064591e+01,3.981887146614389508e+02,6.114936424008071691e-01,5.654493402209785025e+00,-1.750682902707058064e-01,-6.959981760720374000e-02,6.839316092015533532e-02,-9.999999902588826428e-01,0.000000000000000000e+00 +6.596043124396641133e+01,3.981985618079061169e+02,6.097518885565124114e-01,5.654370314582553902e+00,-1.748182902707058062e-01,-7.136832261574806158e-02,6.839316092015533532e-02,-9.999999904067917722e-01,0.000000000000000000e+00 +6.596219978749003587e+01,3.982084093895040269e+02,6.080125965532385823e-01,5.654244096597800251e+00,-1.745682902707058060e-01,-7.313686612240132001e-02,6.839316092015533532e-02,-9.999999909566000822e-01,0.000000000000000000e+00 +6.596396837049232431e+01,3.982182574056171802e+02,6.062757664996915041e-01,5.654114747979535949e+00,-1.743182902707058057e-01,-7.490544910868998651e-02,6.839316092015533532e-02,-9.999999913187308520e-01,0.000000000000000000e+00 +6.596573699395430879e+01,3.982281058556300763e+02,6.045413985044230110e-01,5.653982268444812220e+00,-1.740682902707058055e-01,-7.667407255531542842e-02,6.839316092015533532e-02,-9.999999914498410858e-01,0.000000000000000000e+00 +6.596750565885723461e+01,3.982379547389272147e+02,6.028094926758310601e-01,5.653846657703718748e+00,-1.738182902707058053e-01,-7.844273744312538210e-02,6.839316092015533532e-02,-9.999999918526555343e-01,0.000000000000000000e+00 +6.596927436618260288e+01,3.982478040548930380e+02,6.010800491221598429e-01,5.653707915459381006e+00,-1.735682902707058051e-01,-8.021144475408524543e-02,6.839316092015533532e-02,-9.999999921563349492e-01,0.000000000000000000e+00 +6.597104311691212786e+01,3.982576538029119320e+02,5.993530679514995629e-01,5.653566041407955822e+00,-1.733182902707058048e-01,-8.198019546973851768e-02,6.839316092015533532e-02,-9.999999925360534281e-01,0.000000000000000000e+00 +6.597281191202776540e+01,3.982675039823683392e+02,5.976285492717865466e-01,5.653421035238629599e+00,-1.730682902707058046e-01,-8.374899057217799481e-02,6.839316092015533532e-02,-9.999999925774434306e-01,0.000000000000000000e+00 +6.597458075251172716e+01,3.982773545926465886e+02,5.959064931908031326e-01,5.653272896633614764e+00,-1.728182902707058044e-01,-8.551783104300847427e-02,6.839316092015533532e-02,-9.999999929797775966e-01,0.000000000000000000e+00 +6.597634963934645214e+01,3.982872056331310091e+02,5.941868998161778936e-01,5.653121625268147987e+00,-1.725682902707058042e-01,-8.728671786532206378e-02,6.839316092015533532e-02,-9.999999930010903260e-01,0.000000000000000000e+00 +6.597811857351466358e+01,3.982970571032059297e+02,5.924697692553854145e-01,5.652967220810484861e+00,-1.723182902707058040e-01,-8.905565202115434120e-02,6.839316092015533532e-02,-9.999999935807124540e-01,0.000000000000000000e+00 +6.597988755599932631e+01,3.983069090022556225e+02,5.907551016157462920e-01,5.652809682921899004e+00,-1.720682902707058037e-01,-9.082463449446388781e-02,6.839316092015533532e-02,-9.999999939329239362e-01,0.000000000000000000e+00 +6.598165658778367515e+01,3.983167613296643594e+02,5.890428970044273571e-01,5.652649011256675848e+00,-1.718182902707058035e-01,-9.259366626808629430e-02,6.839316092015533532e-02,-9.999999935341401525e-01,0.000000000000000000e+00 +6.598342566985122915e+01,3.983266140848163559e+02,5.873331555284413419e-01,5.652485205462111750e+00,-1.715682902707058033e-01,-9.436274832420324388e-02,6.839316092015533532e-02,-9.999999941090941258e-01,0.000000000000000000e+00 +6.598519480318577735e+01,3.983364672670958271e+02,5.856258772946471014e-01,5.652318265178512213e+00,-1.713182902707058031e-01,-9.613188164832547900e-02,6.839316092015533532e-02,-9.999999942388008156e-01,0.000000000000000000e+00 +6.598696398877137881e+01,3.983463208758869314e+02,5.839210624097495028e-01,5.652148190039183007e+00,-1.710682902707058028e-01,-9.790106722373684289e-02,6.839316092015533532e-02,-9.999999944688289233e-01,0.000000000000000000e+00 +6.598873322759240523e+01,3.983561749105738272e+02,5.822187109802994254e-01,5.651974979670431054e+00,-1.708182902707058026e-01,-9.967030603497525898e-02,6.839316092015533532e-02,-9.999999944714167421e-01,0.000000000000000000e+00 +6.599050252063349831e+01,3.983660293705406161e+02,5.805188231126939824e-01,5.651798633691559104e+00,-1.705682902707058024e-01,-1.014395990662931846e-01,6.839316092015533532e-02,-9.999999950316420527e-01,0.000000000000000000e+00 +6.599227186887962660e+01,3.983758842551714565e+02,5.788213989131760773e-01,5.651619151714863065e+00,-1.703182902707058022e-01,-1.032089473036320593e-01,6.839316092015533532e-02,-9.999999949265145904e-01,0.000000000000000000e+00 +6.599404127331604286e+01,3.983857395638503363e+02,5.771264384878346254e-01,5.651436533345625790e+00,-1.700682902707058020e-01,-1.049783517310749203e-01,6.839316092015533532e-02,-9.999999951806235465e-01,0.000000000000000000e+00 +6.599581073492832672e+01,3.983955952959613569e+02,5.754339419426047764e-01,5.651250778182117074e+00,-1.698182902707058017e-01,-1.067478133348286617e-01,6.839316092015533532e-02,-9.999999950942605187e-01,0.000000000000000000e+00 +6.599758025470235623e+01,3.984054514508885063e+02,5.737439093832675807e-01,5.651061885815586550e+00,-1.695682902707058015e-01,-1.085173331001786229e-01,6.839316092015533532e-02,-9.999999953639240324e-01,0.000000000000000000e+00 +6.599934983362435048e+01,3.984153080280158292e+02,5.720563409154499901e-01,5.650869855830261912e+00,-1.693182902707058013e-01,-1.102869120139646636e-01,6.839316092015533532e-02,-9.999999955292268039e-01,0.000000000000000000e+00 +6.600111947268084123e+01,3.984251650267271998e+02,5.703712366446250792e-01,5.650674687803342700e+00,-1.690682902707058011e-01,-1.120565510625396027e-01,6.839316092015533532e-02,-9.999999959585831322e-01,0.000000000000000000e+00 +6.600288917285870127e+01,3.984350224464066059e+02,5.686885966761118238e-01,5.650476381304997631e+00,-1.688182902707058008e-01,-1.138262512332413878e-01,6.839316092015533532e-02,-9.999999955801325280e-01,0.000000000000000000e+00 +6.600465893514513027e+01,3.984448802864379786e+02,5.670084211150753228e-01,5.650274935898359274e+00,-1.685682902707058006e-01,-1.155960135118497961e-01,6.839316092015533532e-02,-9.999999961356469402e-01,0.000000000000000000e+00 +6.600642876052769736e+01,3.984547385462051921e+02,5.653307100665264651e-01,5.650070351139523162e+00,-1.683182902707058004e-01,-1.173658388875713637e-01,6.839316092015533532e-02,-9.999999959416481232e-01,0.000000000000000000e+00 +6.600819864999429853e+01,3.984645972250920636e+02,5.636554636353221515e-01,5.649862626577538016e+00,-1.680682902707058002e-01,-1.191357283469830775e-01,6.839316092015533532e-02,-9.999999961280064964e-01,0.000000000000000000e+00 +6.600996860453318504e+01,3.984744563224824674e+02,5.619826819261654061e-01,5.649651761754406643e+00,-1.678182902707058000e-01,-1.209056828790170124e-01,6.839316092015533532e-02,-9.999999963844241613e-01,0.000000000000000000e+00 +6.601173862513299184e+01,3.984843158377602208e+02,5.603123650436049319e-01,5.649437756205077932e+00,-1.675682902707057997e-01,-1.226757034724170747e-01,6.839316092015533532e-02,-9.999999963783033907e-01,0.000000000000000000e+00 +6.601350871278269494e+01,3.984941757703090843e+02,5.586445130920356661e-01,5.649220609457443310e+00,-1.673182902707057995e-01,-1.244457911157050289e-01,6.839316092015533532e-02,-9.999999963216726906e-01,0.000000000000000000e+00 +6.601527886847165405e+01,3.985040361195127616e+02,5.569791261756983358e-01,5.649000321032333183e+00,-1.670682902707057993e-01,-1.262159467981500693e-01,6.839316092015533532e-02,-9.999999966874527635e-01,0.000000000000000000e+00 +6.601704909318959835e+01,3.985138968847550700e+02,5.553162043986795693e-01,5.648776890443511611e+00,-1.668182902707057991e-01,-1.279861715102363073e-01,6.839316092015533532e-02,-9.999999967922981181e-01,0.000000000000000000e+00 +6.601881938792666915e+01,3.985237580654196563e+02,5.536557478649120068e-01,5.648550317197670090e+00,-1.665682902707057989e-01,-1.297564662416215708e-01,6.839316092015533532e-02,-9.999999967807793322e-01,0.000000000000000000e+00 +6.602058975367334881e+01,3.985336196608902242e+02,5.519977566781741896e-01,5.648320600794424884e+00,-1.663182902707057986e-01,-1.315268319826085330e-01,6.839316092015533532e-02,-9.999999967748358642e-01,0.000000000000000000e+00 +6.602236019142056023e+01,3.985434816705503636e+02,5.503422309420905600e-01,5.648087740726311701e+00,-1.660682902707057984e-01,-1.332972697241102955e-01,6.839316092015533532e-02,-9.999999968737913747e-01,0.000000000000000000e+00 +6.602413070215959578e+01,3.985533440937837781e+02,5.486891707601314616e-01,5.647851736478780360e+00,-1.658182902707057982e-01,-1.350677804576159990e-01,6.839316092015533532e-02,-9.999999971543539479e-01,0.000000000000000000e+00 +6.602590128688217419e+01,3.985632069299740010e+02,5.470385762356131387e-01,5.647612587530189465e+00,-1.655682902707057980e-01,-1.368383651751564345e-01,6.839316092015533532e-02,-9.999999968206724210e-01,0.000000000000000000e+00 +6.602767194658041205e+01,3.985730701785046790e+02,5.453904474716977369e-01,5.647370293351801074e+00,-1.653182902707057977e-01,-1.386090248677646908e-01,6.839316092015533532e-02,-9.999999973206458170e-01,0.000000000000000000e+00 +6.602944268224685231e+01,3.985829338387592884e+02,5.437447845713934136e-01,5.647124853407778033e+00,-1.650682902707057975e-01,-1.403797605294546391e-01,6.839316092015533532e-02,-9.999999975296566257e-01,0.000000000000000000e+00 +6.603121349487445002e+01,3.985927979101213623e+02,5.421015876375540055e-01,5.646876267155174212e+00,-1.648182902707057973e-01,-1.421505731526715721e-01,6.839316092015533532e-02,-9.999999968674315731e-01,0.000000000000000000e+00 +6.603298438545658655e+01,3.986026623919744338e+02,5.404608567728793611e-01,5.646624534043932719e+00,-1.645682902707057971e-01,-1.439214637292614840e-01,6.839316092015533532e-02,-9.999999975627625881e-01,0.000000000000000000e+00 +6.603475535498709803e+01,3.986125272837019793e+02,5.388225920799151192e-01,5.646369653516882359e+00,-1.643182902707057969e-01,-1.456924332554513091e-01,6.839316092015533532e-02,-9.999999975734535917e-01,0.000000000000000000e+00 +6.603652640446023270e+01,3.986223925846874181e+02,5.371867936610528194e-01,5.646111625009725188e+00,-1.640682902707057966e-01,-1.474634827242911617e-01,6.839316092015533532e-02,-9.999999973834480249e-01,0.000000000000000000e+00 +6.603829753487070775e+01,3.986322582943141697e+02,5.355534616185299024e-01,5.645850447951037410e+00,-1.638182902707057964e-01,-1.492346131301334755e-01,6.839316092015533532e-02,-9.999999974536205594e-01,0.000000000000000000e+00 +6.604006874721368092e+01,3.986421244119655967e+02,5.339225960544295990e-01,5.645586121762262266e+00,-1.635682902707057962e-01,-1.510058254685979762e-01,6.839316092015533532e-02,-9.999999976554909686e-01,0.000000000000000000e+00 +6.604184004248476469e+01,3.986519909370251185e+02,5.322941970706809300e-01,5.645318645857702933e+00,-1.633182902707057960e-01,-1.527771207355335947e-01,6.839316092015533532e-02,-9.999999975546819408e-01,0.000000000000000000e+00 +6.604361142168004051e+01,3.986618578688760408e+02,5.306682647690589283e-01,5.645048019644517190e+00,-1.630682902707057957e-01,-1.545484999264822579e-01,6.839316092015533532e-02,-9.999999978260429856e-01,0.000000000000000000e+00 +6.604538288579605876e+01,3.986717252069016695e+02,5.290447992511844166e-01,5.644774242522712981e+00,-1.628182902707057955e-01,-1.563199640386493949e-01,6.839316092015533532e-02,-9.999999977060801681e-01,0.000000000000000000e+00 +6.604715443582983880e+01,3.986815929504853102e+02,5.274238006185238969e-01,5.644497313885140422e+00,-1.625682902707057953e-01,-1.580915140683617770e-01,6.839316092015533532e-02,-9.999999978234458409e-01,0.000000000000000000e+00 +6.604892607277886896e+01,3.986914610990102688e+02,5.258052689723897721e-01,5.644217233117488242e+00,-1.623182902707057951e-01,-1.598631510135393452e-01,6.839316092015533532e-02,-9.999999976515465683e-01,0.000000000000000000e+00 +6.605069779764114912e+01,3.987013296518597372e+02,5.241892044139403462e-01,5.643933999598275797e+00,-1.620682902707057949e-01,-1.616348758716543710e-01,6.839316092015533532e-02,-9.999999980554454826e-01,0.000000000000000000e+00 +6.605246961141514817e+01,3.987111986084169644e+02,5.225756070441796020e-01,5.643647612698848626e+00,-1.618182902707057946e-01,-1.634066896422027571e-01,6.839316092015533532e-02,-9.999999976135079960e-01,0.000000000000000000e+00 +6.605424151509983233e+01,3.987210679680651424e+02,5.209644769639573125e-01,5.643358071783369567e+00,-1.615682902707057944e-01,-1.651785933226582737e-01,6.839316092015533532e-02,-9.999999982757782346e-01,0.000000000000000000e+00 +6.605601350969467944e+01,3.987309377301874065e+02,5.193558142739691519e-01,5.643065376208816986e+00,-1.613182902707057942e-01,-1.669505879144523863e-01,6.839316092015533532e-02,-9.999999977256550654e-01,0.000000000000000000e+00 +6.605778559619967893e+01,3.987408078941668919e+02,5.177496190747565841e-01,5.642769525324972335e+00,-1.610682902707057940e-01,-1.687226744154198543e-01,6.839316092015533532e-02,-9.999999981490664824e-01,0.000000000000000000e+00 +6.605955777561531761e+01,3.987506784593867337e+02,5.161458914667068631e-01,5.642470518474421048e+00,-1.608182902707057937e-01,-1.704948538277829273e-01,6.839316092015533532e-02,-9.999999980314951964e-01,0.000000000000000000e+00 +6.606133004894262228e+01,3.987605494252300105e+02,5.145446315500528112e-01,5.642168354992539214e+00,-1.605682902707057935e-01,-1.722671271515997249e-01,6.839316092015533532e-02,-9.999999978149468616e-01,0.000000000000000000e+00 +6.606310241718313137e+01,3.987704207910798004e+02,5.129458394248732622e-01,5.641863034207491800e+00,-1.603182902707057933e-01,-1.740394953882371254e-01,6.839316092015533532e-02,-9.999999982003175969e-01,0.000000000000000000e+00 +6.606487488133892327e+01,3.987802925563191252e+02,5.113495151910927294e-01,5.641554555440224661e+00,-1.600682902707057931e-01,-1.758119595408355884e-01,6.839316092015533532e-02,-9.999999981686950035e-01,0.000000000000000000e+00 +6.606664744241260223e+01,3.987901647203310063e+02,5.097556589484814049e-01,5.641242918004455653e+00,-1.598182902707057929e-01,-1.775845206112667551e-01,6.839316092015533532e-02,-9.999999980912829267e-01,0.000000000000000000e+00 +6.606842010140732668e+01,3.988000372824984652e+02,5.081642707966553818e-01,5.640928121206671086e+00,-1.595682902707057926e-01,-1.793571796026030563e-01,6.839316092015533532e-02,-9.999999980327971549e-01,0.000000000000000000e+00 +6.607019285932679509e+01,3.988099102422044098e+02,5.065753508350764323e-01,5.640610164346117728e+00,-1.593182902707057924e-01,-1.811299375185803362e-01,6.839316092015533532e-02,-9.999999983169539641e-01,0.000000000000000000e+00 +6.607196571717526012e+01,3.988197835988318616e+02,5.049888991630520074e-01,5.640289046714795695e+00,-1.590682902707057922e-01,-1.829027953640628701e-01,6.839316092015533532e-02,-9.999999978307425597e-01,0.000000000000000000e+00 +6.607373867595754291e+01,3.988296573517636716e+02,5.034049158797353485e-01,5.639964767597450468e+00,-1.588182902707057920e-01,-1.846757541425020632e-01,6.839316092015533532e-02,-9.999999985456875518e-01,0.000000000000000000e+00 +6.607551173667903299e+01,3.988395315003827477e+02,5.018234010841253756e-01,5.639637326271569329e+00,-1.585682902707057917e-01,-1.864488148614109053e-01,6.839316092015533532e-02,-9.999999978887592622e-01,0.000000000000000000e+00 +6.607728490034567415e+01,3.988494060440719409e+02,5.002443548750667990e-01,5.639306722007368045e+00,-1.583182902707057915e-01,-1.882219785243123833e-01,6.839316092015533532e-02,-9.999999980660252419e-01,0.000000000000000000e+00 +6.607905816796400700e+01,3.988592809822141021e+02,4.986677773512500078e-01,5.638972954067791754e+00,-1.580682902707057913e-01,-1.899952461392188929e-01,6.839316092015533532e-02,-9.999999984342773374e-01,0.000000000000000000e+00 +6.608083154054115482e+01,3.988691563141920255e+02,4.970936686112110703e-01,5.638636021708500756e+00,-1.578182902707057911e-01,-1.917686187135861919e-01,6.839316092015533532e-02,-9.999999980444213010e-01,0.000000000000000000e+00 +6.608260501908480933e+01,3.988790320393885622e+02,4.955220287533317891e-01,5.638295924177865182e+00,-1.575682902707057909e-01,-1.935420972537765238e-01,6.839316092015533532e-02,-9.999999984648946239e-01,0.000000000000000000e+00 +6.608437860460328750e+01,3.988889081571864494e+02,4.939528578758396460e-01,5.637952660716960551e+00,-1.573182902707057906e-01,-1.953156827695291531e-01,6.839316092015533532e-02,-9.999999978515105026e-01,0.000000000000000000e+00 +6.608615229810548897e+01,3.988987846669684245e+02,4.923861560768078571e-01,5.637606230559555343e+00,-1.570682902707057904e-01,-1.970893762679139793e-01,6.839316092015533532e-02,-9.999999982888586603e-01,0.000000000000000000e+00 +6.608792610060091022e+01,3.989086615681171679e+02,4.908219234541552622e-01,5.637256632932109213e+00,-1.568182902707057902e-01,-1.988631787603055145e-01,6.839316092015533532e-02,-9.999999981669802640e-01,0.000000000000000000e+00 +6.608970001309968723e+01,3.989185388600154170e+02,4.892601601056464355e-01,5.636903867053758788e+00,-1.565682902707057900e-01,-2.006370912558358977e-01,6.839316092015533532e-02,-9.999999981103852020e-01,0.000000000000000000e+00 +6.609147403661256703e+01,3.989284165420458521e+02,4.877008661288915192e-01,5.636547932136314998e+00,-1.563182902707057897e-01,-2.024111147653641085e-01,6.839316092015533532e-02,-9.999999981544780425e-01,0.000000000000000000e+00 +6.609324817215090775e+01,3.989382946135910970e+02,4.861440416213464455e-01,5.636188827384253308e+00,-1.560682902707057895e-01,-2.041852503004370212e-01,6.839316092015533532e-02,-9.999999983104214119e-01,0.000000000000000000e+00 +6.609502242072672118e+01,3.989481730740337753e+02,4.845896866803127145e-01,5.635826551994705724e+00,-1.558182902707057893e-01,-2.059594988732523502e-01,6.839316092015533532e-02,-9.999999980007077127e-01,0.000000000000000000e+00 +6.609679678335263020e+01,3.989580519227564537e+02,4.830378014029375056e-01,5.635461105157452799e+00,-1.555682902707057891e-01,-2.077338614956200924e-01,6.839316092015533532e-02,-9.999999980341048866e-01,0.000000000000000000e+00 +6.609857126104192560e+01,3.989679311591417559e+02,4.814883858862136767e-01,5.635092486054917416e+00,-1.553182902707057889e-01,-2.095083391814281382e-01,6.839316092015533532e-02,-9.999999983482422694e-01,0.000000000000000000e+00 +6.610034585480853764e+01,3.989778107825721918e+02,4.799414402269796542e-01,5.634720693862154128e+00,-1.550682902707057886e-01,-2.112829329451026972e-01,6.839316092015533532e-02,-9.999999980103875252e-01,0.000000000000000000e+00 +6.610212056566703609e+01,3.989876907924303282e+02,4.783969645219195987e-01,5.634345727746841170e+00,-1.548182902707057884e-01,-2.130576438000696127e-01,6.839316092015533532e-02,-9.999999977553815089e-01,0.000000000000000000e+00 +6.610389539463267283e+01,3.989975711880986182e+02,4.768549588675631834e-01,5.633967586869275124e+00,-1.545682902707057882e-01,-2.148324727617195729e-01,6.839316092015533532e-02,-9.999999982929252962e-01,0.000000000000000000e+00 +6.610567034272135345e+01,3.990074519689595718e+02,4.753154233602858159e-01,5.633586270382360262e+00,-1.543182902707057880e-01,-2.166074208473698359e-01,6.839316092015533532e-02,-9.999999980526752541e-01,0.000000000000000000e+00 +6.610744541094966564e+01,3.990173331343955851e+02,4.737783580963084162e-01,5.633201777431597890e+00,-1.540682902707057877e-01,-2.183824890722233514e-01,6.839316092015533532e-02,-9.999999979768645630e-01,0.000000000000000000e+00 +6.610922060033486503e+01,3.990272146837891682e+02,4.722437631716975837e-01,5.632814107155082795e+00,-1.538182902707057875e-01,-2.201576784538343268e-01,6.839316092015533532e-02,-9.999999978552379654e-01,0.000000000000000000e+00 +6.611099591189490354e+01,3.990370966165226605e+02,4.707116386823654852e-01,5.632423258683491696e+00,-1.535682902707057873e-01,-2.219329900100686925e-01,6.839316092015533532e-02,-9.999999980161928814e-01,0.000000000000000000e+00 +6.611277134664842947e+01,3.990469789319784581e+02,4.691819847240699115e-01,5.632029231140075254e+00,-1.533182902707057871e-01,-2.237084247600663878e-01,6.839316092015533532e-02,-9.999999976360923748e-01,0.000000000000000000e+00 +6.611454690561475900e+01,3.990568616295389006e+02,4.676548013924142211e-01,5.631632023640648299e+00,-1.530682902707057869e-01,-2.254839837222020749e-01,6.839316092015533532e-02,-9.999999981202865040e-01,0.000000000000000000e+00 +6.611632258981394727e+01,3.990667447085863273e+02,4.661300887828473960e-01,5.631231635293583615e+00,-1.528182902707057866e-01,-2.272596679180487744e-01,6.839316092015533532e-02,-9.999999977500169113e-01,0.000000000000000000e+00 +6.611809840026673157e+01,3.990766281685030776e+02,4.646078469906639863e-01,5.630828065199798615e+00,-1.525682902707057864e-01,-2.290354783668368255e-01,6.839316092015533532e-02,-9.999999978801696887e-01,0.000000000000000000e+00 +6.611987433799457392e+01,3.990865120086714342e+02,4.630880761110041099e-01,5.630421312452751792e+00,-1.523182902707057862e-01,-2.308114160909177093e-01,6.839316092015533532e-02,-9.999999975870283997e-01,0.000000000000000000e+00 +6.612165040401966110e+01,3.990963962284736226e+02,4.615707762388533975e-01,5.630011376138429391e+00,-1.520682902707057860e-01,-2.325874821117238922e-01,6.839316092015533532e-02,-9.999999976113066458e-01,0.000000000000000000e+00 +6.612342659936490463e+01,3.991062808272918687e+02,4.600559474690431028e-01,5.629598255335339196e+00,-1.518182902707057857e-01,-2.343636774527308175e-01,6.839316092015533532e-02,-9.999999975419706644e-01,0.000000000000000000e+00 +6.612520292505395503e+01,3.991161658045084550e+02,4.585435898962500478e-01,5.629181949114498984e+00,-1.515682902707057855e-01,-2.361400031374175368e-01,6.839316092015533532e-02,-9.999999977872152668e-01,0.000000000000000000e+00 +6.612697938211120174e+01,3.991260511595054936e+02,4.570337036149965670e-01,5.628762456539428527e+00,-1.513182902707057853e-01,-2.379164601907279575e-01,6.839316092015533532e-02,-9.999999976038345118e-01,0.000000000000000000e+00 +6.612875597156175900e+01,3.991359368916652102e+02,4.555262887196505628e-01,5.628339776666138938e+00,-1.510682902707057851e-01,-2.396930496370316410e-01,6.839316092015533532e-02,-9.999999973491329186e-01,0.000000000000000000e+00 +6.613053269443152260e+01,3.991458230003697167e+02,4.540213453044254499e-01,5.627913908543125565e+00,-1.508182902707057849e-01,-2.414697725020848729e-01,6.839316092015533532e-02,-9.999999973544503318e-01,0.000000000000000000e+00 +6.613230955174712733e+01,3.991557094850011254e+02,4.525188734633801557e-01,5.627484851211357331e+00,-1.505682902707057846e-01,-2.432466298129908888e-01,6.839316092015533532e-02,-9.999999973627072825e-01,0.000000000000000000e+00 +6.613408654453598956e+01,3.991655963449415481e+02,4.510188732904192310e-01,5.627052603704266076e+00,-1.503182902707057844e-01,-2.450236225971606230e-01,6.839316092015533532e-02,-9.999999973725511859e-01,0.000000000000000000e+00 +6.613586367382626463e+01,3.991754835795730401e+02,4.495213448792926836e-01,5.626617165047737679e+00,-1.500682902707057842e-01,-2.468007518827732283e-01,6.839316092015533532e-02,-9.999999970756200396e-01,0.000000000000000000e+00 +6.613764094064693211e+01,3.991853711882776565e+02,4.480262883235959781e-01,5.626178534260102282e+00,-1.498182902707057840e-01,-2.485780186982366469e-01,6.839316092015533532e-02,-9.999999972624482591e-01,0.000000000000000000e+00 +6.613941834602771053e+01,3.991952591704373958e+02,4.465337037167702028e-01,5.625736710352125414e+00,-1.495682902707057838e-01,-2.503554240741468484e-01,6.839316092015533532e-02,-9.999999972915677438e-01,0.000000000000000000e+00 +6.614119589099912844e+01,3.992051475254343131e+02,4.450435911521019028e-01,5.625291692326995552e+00,-1.493182902707057835e-01,-2.521329690407490554e-01,6.839316092015533532e-02,-9.999999964960408771e-01,0.000000000000000000e+00 +6.614297357659251020e+01,3.992150362526503500e+02,4.435559507227230802e-01,5.624843479180316130e+00,-1.490682902707057833e-01,-2.539106546278983578e-01,6.839316092015533532e-02,-9.999999972742994458e-01,0.000000000000000000e+00 +6.614475140383997598e+01,3.992249253514674479e+02,4.420707825216113052e-01,5.624392069900097546e+00,-1.488182902707057831e-01,-2.556884818705152940e-01,6.839316092015533532e-02,-9.999999966586305966e-01,0.000000000000000000e+00 +6.614652937377445596e+01,3.992348148212675483e+02,4.405880866415895492e-01,5.623937463466739395e+00,-1.485682902707057829e-01,-2.574664517990526424e-01,6.839316092015533532e-02,-9.999999969947614975e-01,0.000000000000000000e+00 +6.614830748742969035e+01,3.992447046614325927e+02,4.391078631753262962e-01,5.623479658853029584e+00,-1.483182902707057826e-01,-2.592445654489479168e-01,6.839316092015533532e-02,-9.999999963872786557e-01,0.000000000000000000e+00 +6.615008574584025780e+01,3.992545948713444091e+02,4.376301122153355427e-01,5.623018655024126566e+00,-1.480682902707057824e-01,-2.610228238530891698e-01,6.839316092015533532e-02,-9.999999965664969626e-01,0.000000000000000000e+00 +6.615186415004154696e+01,3.992644854503849388e+02,4.361548338539766867e-01,5.622554450937554904e+00,-1.478182902707057822e-01,-2.628012280482682206e-01,6.839316092015533532e-02,-9.999999964272286990e-01,0.000000000000000000e+00 +6.615364270106978495e+01,3.992743763979359528e+02,4.346820281834546384e-01,5.622087045543189276e+00,-1.475682902707057820e-01,-2.645797790701449048e-01,6.839316092015533532e-02,-9.999999965230187415e-01,0.000000000000000000e+00 +6.615542139996202309e+01,3.992842677133792790e+02,4.332116952958197653e-01,5.621616437783247378e+00,-1.473182902707057818e-01,-2.663584779562031546e-01,6.839316092015533532e-02,-9.999999962576373580e-01,0.000000000000000000e+00 +6.615720024775619379e+01,3.992941593960967452e+02,4.317438352829678916e-01,5.621142626592277480e+00,-1.470682902707057815e-01,-2.681373257437124069e-01,6.839316092015533532e-02,-9.999999958505699782e-01,0.000000000000000000e+00 +6.615897924549105369e+01,3.993040514454700656e+02,4.302784482366402430e-01,5.620665610897149556e+00,-1.468182902707057813e-01,-2.699163234711847714e-01,6.839316092015533532e-02,-9.999999963361670963e-01,0.000000000000000000e+00 +6.616075839420621207e+01,3.993139438608810110e+02,4.288155342484235022e-01,5.620185389617043725e+00,-1.465682902707057811e-01,-2.716954721798313099e-01,6.839316092015533532e-02,-9.999999956351101060e-01,0.000000000000000000e+00 +6.616253769494217352e+01,3.993238366417113525e+02,4.273550934097498089e-01,5.619701961663436052e+00,-1.463182902707057809e-01,-2.734747729080289069e-01,6.839316092015533532e-02,-9.999999958503614783e-01,0.000000000000000000e+00 +6.616431714874029524e+01,3.993337297873427474e+02,4.258971258118967040e-01,5.619215325940094097e+00,-1.460682902707057806e-01,-2.752542266987675901e-01,6.839316092015533532e-02,-9.999999956908161014e-01,0.000000000000000000e+00 +6.616609675664281554e+01,3.993436232971568529e+02,4.244416315459871858e-01,5.618725481343059158e+00,-1.458182902707057804e-01,-2.770338345936181335e-01,6.839316092015533532e-02,-9.999999955216398728e-01,0.000000000000000000e+00 +6.616787651969285378e+01,3.993535171705353264e+02,4.229886107029895981e-01,5.618232426760639164e+00,-1.455682902707057802e-01,-2.788135976356854728e-01,6.839316092015533532e-02,-9.999999951200739812e-01,0.000000000000000000e+00 +6.616965643893442461e+01,3.993634114068598251e+02,4.215380633737177973e-01,5.617736161073396239e+00,-1.453182902707057800e-01,-2.805935168685689263e-01,6.839316092015533532e-02,-9.999999953573498468e-01,0.000000000000000000e+00 +6.617143651541243798e+01,3.993733060055120063e+02,4.200899896488309859e-01,5.617236683154136045e+00,-1.450682902707057798e-01,-2.823735933383159091e-01,6.839316092015533532e-02,-9.999999951150518873e-01,0.000000000000000000e+00 +6.617321675017269911e+01,3.993832009658734137e+02,4.186443896188337122e-01,5.616733991867893572e+00,-1.448182902707057795e-01,-2.841538280898869284e-01,6.839316092015533532e-02,-9.999999949294318125e-01,0.000000000000000000e+00 +6.617499714426195112e+01,3.993930962873255908e+02,4.172012633740760368e-01,5.616228086071925141e+00,-1.445682902707057793e-01,-2.859342221701073328e-01,6.839316092015533532e-02,-9.999999944684034858e-01,0.000000000000000000e+00 +6.617677769872781823e+01,3.994029919692500812e+02,4.157606110047533110e-01,5.615718964615695086e+00,-1.443182902707057791e-01,-2.877147766261280437e-01,6.839316092015533532e-02,-9.999999947731751382e-01,0.000000000000000000e+00 +6.617855841461887678e+01,3.994128880110284285e+02,4.143224326009063430e-01,5.615206626340865093e+00,-1.440682902707057789e-01,-2.894954925078773167e-01,6.839316092015533532e-02,-9.999999943359111354e-01,0.000000000000000000e+00 +6.618033929298461260e+01,3.994227844120421196e+02,4.128867282524212312e-01,5.614691070081279101e+00,-1.438182902707057786e-01,-2.912763708635284221e-01,6.839316092015533532e-02,-9.999999941424957406e-01,0.000000000000000000e+00 +6.618212033487546364e+01,3.994326811716726411e+02,4.114534980490295313e-01,5.614172294662956197e+00,-1.435682902707057784e-01,-2.930574127439466436e-01,6.839316092015533532e-02,-9.999999937501820035e-01,0.000000000000000000e+00 +6.618390154134280579e+01,3.994425782893014230e+02,4.100227420803081446e-01,5.613650298904075520e+00,-1.433182902707057782e-01,-2.948386192001518080e-01,6.839316092015533532e-02,-9.999999940884276572e-01,0.000000000000000000e+00 +6.618568291343895282e+01,3.994524757643098951e+02,4.085944604356793186e-01,5.613125081614965595e+00,-1.430682902707057780e-01,-2.966199912857689913e-01,6.839316092015533532e-02,-9.999999932594967333e-01,0.000000000000000000e+00 +6.618746445221718488e+01,3.994623735960794875e+02,4.071686532044106466e-01,5.612596641598089242e+00,-1.428182902707057778e-01,-2.984015300519989866e-01,6.839316092015533532e-02,-9.999999935357990477e-01,0.000000000000000000e+00 +6.618924615873176265e+01,3.994722717839915731e+02,4.057453204756150678e-01,5.612064977648037356e+00,-1.425682902707057775e-01,-3.001832365550536341e-01,6.839316092015533532e-02,-9.999999929640580598e-01,0.000000000000000000e+00 +6.619102803403788471e+01,3.994821703274275251e+02,4.043244623382508673e-01,5.611530088551509365e+00,-1.423182902707057773e-01,-3.019651118486343377e-01,6.839316092015533532e-02,-9.999999929201776050e-01,0.000000000000000000e+00 +6.619281007919173021e+01,3.994920692257686596e+02,4.029060788811217320e-01,5.610991973087307016e+00,-1.420682902707057771e-01,-3.037471569898701484e-01,6.839316092015533532e-02,-9.999999922343022485e-01,0.000000000000000000e+00 +6.619459229525048727e+01,3.995019684783963498e+02,4.014901701928765831e-01,5.610450630026317498e+00,-1.418182902707057769e-01,-3.055293730347882764e-01,6.839316092015533532e-02,-9.999999927841046743e-01,0.000000000000000000e+00 +6.619637468327231034e+01,3.995118680846918551e+02,4.000767363620096884e-01,5.609906058131504558e+00,-1.415682902707057766e-01,-3.073117610437518521e-01,6.839316092015533532e-02,-9.999999916657056342e-01,0.000000000000000000e+00 +6.619815724431636283e+01,3.995217680440364347e+02,3.986657774768607165e-01,5.609358256157889855e+00,-1.413182902707057764e-01,-3.090943220729445162e-01,6.839316092015533532e-02,-9.999999918176298852e-01,0.000000000000000000e+00 +6.619993997944280295e+01,3.995316683558113482e+02,3.972572936256145715e-01,5.608807222852549401e+00,-1.410682902707057762e-01,-3.108770571847905839e-01,6.839316092015533532e-02,-9.999999911179093814e-01,0.000000000000000000e+00 +6.620172288971278363e+01,3.995415690193978548e+02,3.958512848963015029e-01,5.608252956954591362e+00,-1.408182902707057760e-01,-3.126599674389414218e-01,6.839316092015533532e-02,-9.999999913285535502e-01,0.000000000000000000e+00 +6.620350597618850941e+01,3.995514700341771572e+02,3.944477513767970511e-01,5.607695457195149835e+00,-1.405682902707057758e-01,-3.144430538992061819e-01,6.839316092015533532e-02,-9.999999905503905717e-01,0.000000000000000000e+00 +6.620528923993317960e+01,3.995613713995304010e+02,3.930466931548220466e-01,5.607134722297366203e+00,-1.403182902707057755e-01,-3.162263176270309617e-01,6.839316092015533532e-02,-9.999999904869424361e-01,0.000000000000000000e+00 +6.620707268201104512e+01,3.995712731148387888e+02,3.916481103179426104e-01,5.606570750976382023e+00,-1.400682902707057753e-01,-3.180097596879294386e-01,6.839316092015533532e-02,-9.999999897404000526e-01,0.000000000000000000e+00 +6.620885630348738005e+01,3.995811751794834663e+02,3.902520029535702095e-01,5.606003541939320378e+00,-1.398182902707057751e-01,-3.197933811459592879e-01,6.839316092015533532e-02,-9.999999896759439455e-01,0.000000000000000000e+00 +6.621064010542849587e+01,3.995910775928455223e+02,3.888583711489615458e-01,5.605433093885276996e+00,-1.395682902707057749e-01,-3.215771830686566246e-01,6.839316092015533532e-02,-9.999999891170739952e-01,0.000000000000000000e+00 +6.621242408890176989e+01,3.996009803543061025e+02,3.874672149912186114e-01,5.604859405505302483e+00,-1.393182902707057746e-01,-3.233611665225095133e-01,6.839316092015533532e-02,-9.999999885328030302e-01,0.000000000000000000e+00 +6.621420825497561680e+01,3.996108834632462390e+02,3.860785345672886892e-01,5.604282475482392556e+00,-1.390682902707057744e-01,-3.251453325758998369e-01,6.839316092015533532e-02,-9.999999880833783106e-01,0.000000000000000000e+00 +6.621599260471954551e+01,3.996207869190470205e+02,3.846923299639642413e-01,5.603702302491472942e+00,-1.388182902707057742e-01,-3.269296822985595652e-01,6.839316092015533532e-02,-9.999999876205829530e-01,0.000000000000000000e+00 +6.621777713920410235e+01,3.996306907210894224e+02,3.833086012678830756e-01,5.603118885199385169e+00,-1.385682902707057740e-01,-3.287142167610273003e-01,6.839316092015533532e-02,-9.999999872453871896e-01,0.000000000000000000e+00 +6.621956185950094209e+01,3.996405948687545333e+02,3.819273485655282907e-01,5.602532222264873241e+00,-1.383182902707057738e-01,-3.304989370350998046e-01,6.839316092015533532e-02,-9.999999861926747169e-01,0.000000000000000000e+00 +6.622134676668278530e+01,3.996504993614233285e+02,3.805485719432281089e-01,5.601942312338569430e+00,-1.380682902707057735e-01,-3.322838441922931207e-01,6.839316092015533532e-02,-9.999999861767338016e-01,0.000000000000000000e+00 +6.622313186182344680e+01,3.996604041984767264e+02,3.791722714871560984e-01,5.601349154062982727e+00,-1.378182902707057733e-01,-3.340689393082749148e-01,6.839316092015533532e-02,-9.999999849789397155e-01,0.000000000000000000e+00 +6.622491714599783563e+01,3.996703093792957020e+02,3.777984472833310625e-01,5.600752746072479304e+00,-1.375682902707057731e-01,-3.358542234558513639e-01,6.839316092015533532e-02,-9.999999845318753300e-01,0.000000000000000000e+00 +6.622670262028198351e+01,3.996802149032612306e+02,3.764270994176169838e-01,5.600153086993275409e+00,-1.373182902707057729e-01,-3.376396977123843346e-01,6.839316092015533532e-02,-9.999999836720488977e-01,0.000000000000000000e+00 +6.622848828575303060e+01,3.996901207697541736e+02,3.750582279757230797e-01,5.599550175443416933e+00,-1.370682902707057726e-01,-3.394253631542712979e-01,6.839316092015533532e-02,-9.999999828778911581e-01,0.000000000000000000e+00 +6.623027414348922548e+01,3.997000269781553925e+02,3.736918330432038582e-01,5.598944010032768759e+00,-1.368182902707057724e-01,-3.412112208598837015e-01,6.839316092015533532e-02,-9.999999817616107567e-01,0.000000000000000000e+00 +6.623206019456993943e+01,3.997099335278457488e+02,3.723279147054589511e-01,5.598334589362998770e+00,-1.365682902707057722e-01,-3.429972719080272570e-01,6.839316092015533532e-02,-9.999999812971873681e-01,0.000000000000000000e+00 +6.623384644007569477e+01,3.997198404182061040e+02,3.709664730477333361e-01,5.597721912027564528e+00,-1.363182902707057720e-01,-3.447835173803811548e-01,6.839316092015533532e-02,-9.999999796441672029e-01,0.000000000000000000e+00 +6.623563288108815073e+01,3.997297476486173196e+02,3.696075081551170594e-01,5.597105976611695510e+00,-1.360682902707057718e-01,-3.465699583564780806e-01,6.839316092015533532e-02,-9.999999791067072374e-01,0.000000000000000000e+00 +6.623741951869011757e+01,3.997396552184601433e+02,3.682510201125454019e-01,5.596486781692384227e+00,-1.358182902707057715e-01,-3.483565959211147867e-01,6.839316092015533532e-02,-9.999999775051687800e-01,0.000000000000000000e+00 +6.623920635396554246e+01,3.997495631271153798e+02,3.668970090047989352e-01,5.595864325838364017e+00,-1.355682902707057713e-01,-3.501434311563492163e-01,6.839316092015533532e-02,-9.999999759686044598e-01,0.000000000000000000e+00 +6.624099338799955206e+01,3.997594713739637200e+02,3.655454749165032990e-01,5.595238607610101056e+00,-1.353182902707057711e-01,-3.519304651474186585e-01,6.839316092015533532e-02,-9.999999750376697971e-01,0.000000000000000000e+00 +6.624278062187843830e+01,3.997693799583859686e+02,3.641964179321293682e-01,5.594609625559775701e+00,-1.350682902707057709e-01,-3.537176989816961936e-01,6.839316092015533532e-02,-9.999999727197530497e-01,0.000000000000000000e+00 +6.624456805668967263e+01,3.997792888797628166e+02,3.628498381359932523e-01,5.593977378231265618e+00,-1.348182902707057707e-01,-3.555051337441702541e-01,6.839316092015533532e-02,-9.999999711615923381e-01,0.000000000000000000e+00 +6.624635569352190601e+01,3.997891981374749548e+02,3.615057356122561849e-01,5.593341864160136900e+00,-1.345682902707057704e-01,-3.572927705248498675e-01,6.839316092015533532e-02,-9.999999694203294265e-01,0.000000000000000000e+00 +6.624814353346498308e+01,3.997991077309030743e+02,3.601641104449245234e-01,5.592703081873621862e+00,-1.343182902707057702e-01,-3.590806104132499010e-01,6.839316092015533532e-02,-9.999999665222598644e-01,0.000000000000000000e+00 +6.624993157760994222e+01,3.998090176594278091e+02,3.588249627178498602e-01,5.592061029890606605e+00,-1.340682902707057700e-01,-3.608686544983423783e-01,6.839316092015533532e-02,-9.999999639631064197e-01,0.000000000000000000e+00 +6.625171982704901552e+01,3.998189279224297934e+02,3.574882925147289670e-01,5.591415706721618584e+00,-1.338182902707057698e-01,-3.626569038729788863e-01,6.839316092015533532e-02,-9.999999612614287603e-01,0.000000000000000000e+00 +6.625350828287568561e+01,3.998288385192896044e+02,3.561540999191036838e-01,5.590767110868806178e+00,-1.335682902707057695e-01,-3.644453596303630083e-01,6.839316092015533532e-02,-9.999999573494331440e-01,0.000000000000000000e+00 +6.625529694618461463e+01,3.998387494493878762e+02,3.548223850143610858e-01,5.590115240825924481e+00,-1.333182902707057693e-01,-3.662340228630084349e-01,6.839316092015533532e-02,-9.999999536264201350e-01,0.000000000000000000e+00 +6.625708581807171527e+01,3.998486607121051293e+02,3.534931478837333163e-01,5.589460095078322865e+00,-1.330682902707057691e-01,-3.680228946671587065e-01,6.839316092015533532e-02,-9.999999486835198237e-01,0.000000000000000000e+00 +6.625887489963413657e+01,3.998585723068219409e+02,3.521663886102976981e-01,5.588801672102924556e+00,-1.328182902707057689e-01,-3.698119761377716697e-01,6.839316092015533532e-02,-9.999999427456147671e-01,0.000000000000000000e+00 +6.626066419197026391e+01,3.998684842329188314e+02,3.508421072769767335e-01,5.588139970368215081e+00,-1.325682902707057687e-01,-3.716012683714489118e-01,6.839316092015533532e-02,-9.999999357279030221e-01,0.000000000000000000e+00 +6.626245369617971903e+01,3.998783964897763212e+02,3.495203039665379374e-01,5.587474988334225401e+00,-1.323182902707057684e-01,-3.733907724658891425e-01,6.839316092015533532e-02,-9.999999266815529086e-01,0.000000000000000000e+00 +6.626424341336340262e+01,3.998883090767748740e+02,3.482009787615940599e-01,5.586806724452515915e+00,-1.320682902707057682e-01,-3.751804895183491473e-01,6.839316092015533532e-02,-9.999999157350326628e-01,0.000000000000000000e+00 +6.626603334462346595e+01,3.998982219932949533e+02,3.468841317446029193e-01,5.586135177166163146e+00,-1.318182902707057680e-01,-3.769704206275786840e-01,6.839316092015533532e-02,-9.999998999359809293e-01,0.000000000000000000e+00 +6.626782349106332504e+01,3.999081352387169659e+02,3.455697629978674579e-01,5.585460344909742858e+00,-1.315682902707057678e-01,-3.787605668883128884e-01,6.839316092015533532e-02,-9.999998790731970955e-01,0.000000000000000000e+00 +6.626961385378770331e+01,3.999180488124213753e+02,3.442578726035356862e-01,5.584782226109322956e+00,-1.313182902707057675e-01,-3.805509293961848449e-01,6.839316092015533532e-02,-9.999998468094387638e-01,0.000000000000000000e+00 +6.627140443390258895e+01,3.999279627137885882e+02,3.429484606436007943e-01,5.584100819182447495e+00,-1.310682902707057673e-01,-3.823415092367636881e-01,6.839316092015533532e-02,-9.999997934592212978e-01,0.000000000000000000e+00 +6.627319523251526334e+01,3.999378769421990114e+02,3.416415271999010406e-01,5.583416122538140236e+00,-1.308182902707057671e-01,-3.841323074795605086e-01,6.839316092015533532e-02,-9.999996871678827892e-01,0.000000000000000000e+00 +6.627498625073431526e+01,3.999477914970329380e+02,3.403370723541196963e-01,5.582728134576918855e+00,-1.305682902707057669e-01,-3.859233251383218932e-01,6.839316092015533532e-02,-9.999993665529113285e-01,0.000000000000000000e+00 +6.627677748966964089e+01,3.999577063776707746e+02,3.390350961877852676e-01,5.582036853690880207e+00,-1.303182902707057667e-01,-3.877145629389938675e-01,6.839316092015533532e-02,-4.255206495044587256e-01,0.000000000000000000e+00 +6.627856895043245800e+01,3.999676215834928144e+02,3.377355987822712180e-01,5.581342278264201262e+00,-1.300682902707057664e-01,-3.884768664863506027e-01,6.839316092015533532e-02,9.999993726421712026e-01,0.000000000000000000e+00 +6.628036063413530599e+01,3.999775371138793503e+02,3.364385802187961350e-01,5.580646250593582991e+00,-1.298182902707057662e-01,-3.866851839075262642e-01,6.839316092015533532e-02,9.999996931298998915e-01,0.000000000000000000e+00 +6.628215254129999323e+01,3.999874529682106754e+02,3.351440405784236742e-01,5.579953346642062328e+00,-1.295682902707057660e-01,-3.848932772927259882e-01,6.839316092015533532e-02,9.999997992146185677e-01,0.000000000000000000e+00 +6.628394467097899678e+01,3.999973691458670260e+02,3.338519799420626155e-01,5.579263567976575189e+00,-1.293182902707057658e-01,-3.831011479735509373e-01,6.839316092015533532e-02,9.999998532785743244e-01,0.000000000000000000e+00 +6.628573702222359998e+01,4.000072856462286381e+02,3.325623983904666958e-01,5.578576916157198085e+00,-1.290682902707057655e-01,-3.813087969919298215e-01,6.839316092015533532e-02,9.999998845535986725e-01,0.000000000000000000e+00 +6.628752959408382139e+01,4.000172024686757482e+02,3.312752960042347761e-01,5.577893392737654388e+00,-1.288182902707057653e-01,-3.795162253386515361e-01,6.839316092015533532e-02,9.999999064721962760e-01,0.000000000000000000e+00 +6.628932238560848589e+01,4.000271196125885353e+02,3.299906728638107856e-01,5.577212999265393378e+00,-1.285682902707057651e-01,-3.777234339816596953e-01,6.839316092015533532e-02,9.999999213865058412e-01,0.000000000000000000e+00 +6.629111539584519619e+01,4.000370370773471791e+02,3.287085290494836110e-01,5.576535737281618665e+00,-1.283182902707057649e-01,-3.759304238859035863e-01,6.839316092015533532e-02,9.999999327364380575e-01,0.000000000000000000e+00 +6.629290862384033289e+01,4.000469548623318587e+02,3.274288646413872628e-01,5.575861608321281082e+00,-1.280682902707057647e-01,-3.741371960113810680e-01,6.839316092015533532e-02,9.999999420108097725e-01,0.000000000000000000e+00 +6.629470206863908288e+01,4.000568729669226968e+02,3.261516797195007644e-01,5.575190613913075133e+00,-1.278182902707057644e-01,-3.723437513166303336e-01,6.839316092015533532e-02,9.999999487500140782e-01,0.000000000000000000e+00 +6.629649572928542511e+01,4.000667913904998727e+02,3.248769743636482077e-01,5.574522755579429223e+00,-1.275682902707057642e-01,-3.705500907622190088e-01,6.839316092015533532e-02,9.999999544124723583e-01,0.000000000000000000e+00 +6.629828960482211642e+01,4.000767101324433952e+02,3.236047486534986417e-01,5.573858034836489672e+00,-1.273182902707057640e-01,-3.687562153072994064e-01,6.839316092015533532e-02,9.999999598884413698e-01,0.000000000000000000e+00 +6.630008369429076254e+01,4.000866291921333868e+02,3.223350026685661840e-01,5.573196453194110944e+00,-1.270682902707057638e-01,-3.669621259106221611e-01,6.839316092015533532e-02,9.999999632942920824e-01,0.000000000000000000e+00 +6.630187799673173288e+01,4.000965485689499133e+02,3.210677364882099649e-01,5.572538012155844100e+00,-1.268182902707057635e-01,-3.651678235355081958e-01,6.839316092015533532e-02,9.999999674221361490e-01,0.000000000000000000e+00 +6.630367251118424576e+01,4.001064682622729833e+02,3.198029501916341277e-01,5.571882713218916372e+00,-1.265682902707057633e-01,-3.633733091414551586e-01,6.839316092015533532e-02,9.999999698074223398e-01,0.000000000000000000e+00 +6.630546723668632580e+01,4.001163882714826627e+02,3.185406438578877730e-01,5.571230557874225831e+00,-1.263182902707057631e-01,-3.615785836935648256e-01,6.839316092015533532e-02,9.999999729355824041e-01,0.000000000000000000e+00 +6.630726217227481811e+01,4.001263085959589034e+02,3.172808175658650698e-01,5.570581547606319184e+00,-1.260682902707057629e-01,-3.597836481536557662e-01,6.839316092015533532e-02,9.999999751401721371e-01,0.000000000000000000e+00 +6.630905731698538830e+01,4.001362292350817143e+02,3.160234713943051998e-01,5.569935683893385558e+00,-1.258182902707057627e-01,-3.579885034877099415e-01,6.839316092015533532e-02,9.999999772216541238e-01,0.000000000000000000e+00 +6.631085266985255089e+01,4.001461501882310472e+02,3.147686054217922469e-01,5.569292968207236960e+00,-1.255682902707057624e-01,-3.561931506614405829e-01,6.839316092015533532e-02,9.999999788624442942e-01,0.000000000000000000e+00 +6.631264822990965513e+01,4.001560714547868542e+02,3.135162197267553630e-01,5.568653402013296727e+00,-1.253182902707057622e-01,-3.543975906422944799e-01,6.839316092015533532e-02,9.999999811072041167e-01,0.000000000000000000e+00 +6.631444399618887076e+01,4.001659930341290305e+02,3.122663143874686020e-01,5.568016986770584431e+00,-1.250682902707057620e-01,-3.526018243970013843e-01,6.839316092015533532e-02,9.999999819554902247e-01,0.000000000000000000e+00 +6.631623996772124485e+01,4.001759149256374712e+02,3.110188894820510863e-01,5.567383723931705219e+00,-1.248182902707057618e-01,-3.508058528970374734e-01,6.839316092015533532e-02,9.999999837981269346e-01,0.000000000000000000e+00 +6.631803614353664500e+01,4.001858371286920715e+02,3.097739450884668955e-01,5.566753614942829387e+00,-1.245682902707057615e-01,-3.490096771107348839e-01,6.839316092015533532e-02,9.999999846043807761e-01,0.000000000000000000e+00 +6.631983252266381612e+01,4.001957596426727264e+02,3.085314812845250110e-01,5.566126661243686158e+00,-1.243182902707057613e-01,-3.472132980112179190e-01,6.839316092015533532e-02,9.999999864575517261e-01,0.000000000000000000e+00 +6.632162910413035206e+01,4.002056824669592174e+02,3.072914981478794272e-01,5.565502864267543259e+00,-1.240682902707057611e-01,-3.454167165690088526e-01,6.839316092015533532e-02,9.999999867465616532e-01,0.000000000000000000e+00 +6.632342588696272401e+01,4.002156056009314398e+02,3.060539957560291513e-01,5.564882225441199814e+00,-1.238182902707057609e-01,-3.436199337604563531e-01,6.839316092015533532e-02,9.999999880728825952e-01,0.000000000000000000e+00 +6.632522287018625207e+01,4.002255290439691180e+02,3.048189741863179814e-01,5.564264746184964139e+00,-1.235682902707057607e-01,-3.418229505583660344e-01,6.839316092015533532e-02,9.999999891699510313e-01,0.000000000000000000e+00 +6.632702005282513369e+01,4.002354527954520904e+02,3.035864335159348393e-01,5.563650427912648411e+00,-1.233182902707057604e-01,-3.400257679389452337e-01,6.839316092015533532e-02,9.999999898563670664e-01,0.000000000000000000e+00 +6.632881743390245788e+01,4.002453768547601385e+02,3.023563738219134933e-01,5.563039272031550908e+00,-1.230682902707057602e-01,-3.382283868798488524e-01,6.839316092015533532e-02,9.999999902096445847e-01,0.000000000000000000e+00 +6.633061501244019098e+01,4.002553012212729300e+02,3.011287951811326691e-01,5.562431279942441797e+00,-1.228182902707057600e-01,-3.364308083597093435e-01,6.839316092015533532e-02,9.999999916652130283e-01,0.000000000000000000e+00 +6.633241278745919089e+01,4.002652258943702464e+02,2.999036976703160495e-01,5.561826453039549811e+00,-1.225682902707057598e-01,-3.346330333556906678e-01,6.839316092015533532e-02,9.999999917946956751e-01,0.000000000000000000e+00 +6.633421075797920707e+01,4.002751508734318122e+02,2.986810813660322195e-01,5.561224792710553366e+00,-1.223182902707057595e-01,-3.328350628504294084e-01,6.839316092015533532e-02,9.999999925506789511e-01,0.000000000000000000e+00 +6.633600892301888052e+01,4.002850761578372953e+02,2.974609463446946656e-01,5.560626300336559247e+00,-1.220682902707057593e-01,-3.310368978241541860e-01,6.839316092015533532e-02,9.999999933958720888e-01,0.000000000000000000e+00 +6.633780728159575801e+01,4.002950017469663635e+02,2.962432926825618873e-01,5.560030977292095500e+00,-1.218182902707057591e-01,-3.292385392591570259e-01,6.839316092015533532e-02,9.999999935028185405e-01,0.000000000000000000e+00 +6.633960583272629208e+01,4.003049276401986845e+02,2.950281204557371750e-01,5.559438824945096336e+00,-1.215682902707057589e-01,-3.274399881403108337e-01,6.839316092015533532e-02,9.999999944985761280e-01,0.000000000000000000e+00 +6.634140457542585523e+01,4.003148538369138691e+02,2.938154297401688320e-01,5.558849844656886141e+00,-1.213182902707057587e-01,-3.256412454506501519e-01,6.839316092015533532e-02,9.999999949733965332e-01,0.000000000000000000e+00 +6.634320350870872574e+01,4.003247803364915285e+02,2.926052206116500076e-01,5.558264037782171485e+00,-1.210682902707057584e-01,-3.238423121768280732e-01,6.839316092015533532e-02,9.999999948743180100e-01,0.000000000000000000e+00 +6.634500263158810185e+01,4.003347071383112734e+02,2.913974931458188089e-01,5.557681405669023356e+00,-1.208182902707057582e-01,-3.220431893066714180e-01,6.839316092015533532e-02,9.999999960515547626e-01,0.000000000000000000e+00 +6.634680194307613021e+01,4.003446342417526580e+02,2.901922474181581890e-01,5.557101949658863838e+00,-1.205682902707057580e-01,-3.202438778257514773e-01,6.839316092015533532e-02,9.999999959487783086e-01,0.000000000000000000e+00 +6.634860144218386324e+01,4.003545616461952363e+02,2.889894835039959475e-01,5.556525671086459006e+00,-1.203182902707057578e-01,-3.184443787253072866e-01,6.839316092015533532e-02,9.999999963825716431e-01,0.000000000000000000e+00 +6.635040112792130174e+01,4.003644893510185625e+02,2.877892014785048969e-01,5.555952571279897612e+00,-1.200682902707057575e-01,-3.166446929943727562e-01,6.839316092015533532e-02,9.999999972315958274e-01,0.000000000000000000e+00 +6.635220099929739490e+01,4.003744173556021337e+02,2.865914014167026402e-01,5.555382651560583973e+00,-1.198182902707057573e-01,-3.148448216232583863e-01,6.839316092015533532e-02,9.999999969871300465e-01,0.000000000000000000e+00 +6.635400105532002613e+01,4.003843456593255041e+02,2.853960833934516828e-01,5.554815913243224657e+00,-1.195682902707057571e-01,-3.130447656060437733e-01,6.839316092015533532e-02,9.999999976873132912e-01,0.000000000000000000e+00 +6.635580129499604141e+01,4.003942742615681141e+02,2.842032474834593758e-01,5.554252357635810711e+00,-1.193182902707057569e-01,-3.112445259341885540e-01,6.839316092015533532e-02,9.999999980632506835e-01,0.000000000000000000e+00 +6.635760171733123514e+01,4.004042031617094040e+02,2.830128937612780282e-01,5.553691986039611450e+00,-1.190682902707057567e-01,-3.094441036024799807e-01,6.839316092015533532e-02,9.999999981996833265e-01,0.000000000000000000e+00 +6.635940232133036432e+01,4.004141323591288710e+02,2.818250223013046840e-01,5.553134799749157580e+00,-1.188182902707057564e-01,-3.076434996065914862e-01,6.839316092015533532e-02,9.999999987114525091e-01,0.000000000000000000e+00 +6.636120310599714855e+01,4.004240618532058988e+02,2.806396331777813447e-01,5.552580800052228760e+00,-1.185682902707057562e-01,-3.058427149421230062e-01,6.839316092015533532e-02,9.999999985527275870e-01,0.000000000000000000e+00 +6.636300407033429849e+01,4.004339916433199278e+02,2.794567264647948024e-01,5.552029988229842949e+00,-1.183182902707057560e-01,-3.040417506075863141e-01,6.839316092015533532e-02,9.999999993983565982e-01,0.000000000000000000e+00 +6.636480521334347316e+01,4.004439217288502846e+02,2.782763022362767513e-01,5.551482365556240417e+00,-1.180682902707057558e-01,-3.022406075995003882e-01,6.839316092015533532e-02,9.999999990724057763e-01,0.000000000000000000e+00 +6.636660653402532262e+01,4.004538521091764096e+02,2.770983605660036764e-01,5.550937933298876636e+00,-1.178182902707057556e-01,-3.004392869193216464e-01,6.839316092015533532e-02,9.999999997615500735e-01,0.000000000000000000e+00 +6.636840803137948797e+01,4.004637827836776296e+02,2.759229015275969643e-01,5.550396692718402747e+00,-1.175682902707057553e-01,-2.986377895655811798e-01,6.839316092015533532e-02,1.000000000075885964e+00,0.000000000000000000e+00 +6.637020970440461554e+01,4.004737137517332712e+02,2.747499251945227927e-01,5.549858645068660223e+00,-1.173182902707057551e-01,-2.968361165403219371e-01,6.839316092015533532e-02,9.999999999766373548e-01,0.000000000000000000e+00 +6.637201155209831427e+01,4.004836450127226612e+02,2.735794316400921855e-01,5.549323791596664002e+00,-1.170682902707057549e-01,-2.950342688466600638e-01,6.839316092015533532e-02,1.000000000227652341e+00,0.000000000000000000e+00 +6.637381357345722677e+01,4.004935765660250695e+02,2.724114209374609574e-01,5.548792133542590044e+00,-1.168182902707057547e-01,-2.932322474873334528e-01,6.839316092015533532e-02,1.000000000753572094e+00,0.000000000000000000e+00 +6.637561576747698666e+01,4.005035084110197658e+02,2.712458931596298251e-01,5.548263672139765568e+00,-1.165682902707057544e-01,-2.914300534662084829e-01,6.839316092015533532e-02,1.000000000640965947e+00,0.000000000000000000e+00 +6.637741813315226125e+01,4.005134405470860770e+02,2.700828483794442403e-01,5.547738408614656613e+00,-1.163182902707057542e-01,-2.896276877897854263e-01,6.839316092015533532e-02,1.000000000872399930e+00,0.000000000000000000e+00 +6.637922066947669464e+01,4.005233729736031592e+02,2.689222866695945013e-01,5.547216344186852943e+00,-1.160682902707057540e-01,-2.878251514637762964e-01,6.839316092015533532e-02,1.000000001318077203e+00,0.000000000000000000e+00 +6.638102337544299303e+01,4.005333056899502822e+02,2.677642081026157528e-01,5.546697480069059161e+00,-1.158182902707057538e-01,-2.860224454951042494e-01,6.839316092015533532e-02,1.000000001283439799e+00,0.000000000000000000e+00 +6.638282625004286785e+01,4.005432386955066590e+02,2.666086127508878745e-01,5.546181817467082276e+00,-1.155682902707057536e-01,-2.842195708929166620e-01,6.839316092015533532e-02,1.000000001422279849e+00,0.000000000000000000e+00 +6.638462929226706422e+01,4.005531719896514460e+02,2.654555006866355371e-01,5.545669357579817493e+00,-1.153182902707057533e-01,-2.824165286661492469e-01,6.839316092015533532e-02,1.000000001549592010e+00,0.000000000000000000e+00 +6.638643250110538929e+01,4.005631055717638560e+02,2.643048719819283132e-01,5.545160101599238445e+00,-1.150682902707057531e-01,-2.806133198250329031e-01,6.839316092015533532e-02,1.000000002281458356e+00,0.000000000000000000e+00 +6.638823587554666972e+01,4.005730394412229884e+02,2.631567267086804551e-01,5.544654050710384752e+00,-1.148182902707057529e-01,-2.788099453796439309e-01,6.839316092015533532e-02,1.000000001484311118e+00,0.000000000000000000e+00 +6.639003941457878000e+01,4.005829735974079995e+02,2.620110649386510615e-01,5.544151206091352257e+00,-1.145682902707057527e-01,-2.770064063448574587e-01,6.839316092015533532e-02,1.000000002467391624e+00,0.000000000000000000e+00 +6.639184311718865672e+01,4.005929080396980453e+02,2.608678867434439663e-01,5.543651568913274374e+00,-1.143182902707057524e-01,-2.752027037305263546e-01,6.839316092015533532e-02,1.000000002240759356e+00,0.000000000000000000e+00 +6.639364698236229856e+01,4.006028427674721684e+02,2.597271921945078499e-01,5.543155140340321196e+00,-1.140682902707057522e-01,-2.733988385528366427e-01,6.839316092015533532e-02,1.000000002710225155e+00,0.000000000000000000e+00 +6.639545100908478048e+01,4.006127777801094680e+02,2.585889813631360723e-01,5.542661921529678182e+00,-1.138182902707057520e-01,-2.715948118254720711e-01,6.839316092015533532e-02,1.000000002213897732e+00,0.000000000000000000e+00 +6.639725519634021111e+01,4.006227130769889868e+02,2.574532543204668400e-01,5.542171913631540825e+00,-1.135682902707057518e-01,-2.697906245660443569e-01,6.839316092015533532e-02,1.000000002891515027e+00,0.000000000000000000e+00 +6.639905954311180381e+01,4.006326486574898240e+02,2.563200111374830947e-01,5.541685117789097781e+00,-1.133182902707057516e-01,-2.679862777892294545e-01,6.839316092015533532e-02,1.000000003043434837e+00,0.000000000000000000e+00 +6.640086404838184819e+01,4.006425845209909653e+02,2.551892518850125136e-01,5.541201535138526424e+00,-1.130682902707057513e-01,-2.661817725136890189e-01,6.839316092015533532e-02,1.000000002861090920e+00,0.000000000000000000e+00 +6.640266871113172442e+01,4.006525206668713963e+02,2.540609766337275643e-01,5.540721166808975973e+00,-1.128182902707057511e-01,-2.643771097586533614e-01,6.839316092015533532e-02,1.000000003061827902e+00,0.000000000000000000e+00 +6.640447353034188893e+01,4.006624570945101595e+02,2.529351854541454503e-01,5.540244013922556832e+00,-1.125682902707057509e-01,-2.625722905429667686e-01,6.839316092015533532e-02,1.000000003252680791e+00,0.000000000000000000e+00 +6.640627850499190288e+01,4.006723938032861838e+02,2.518118784166281654e-01,5.539770077594331710e+00,-1.123182902707057507e-01,-2.607673158870857377e-01,6.839316092015533532e-02,1.000000003294077677e+00,0.000000000000000000e+00 +6.640808363406043213e+01,4.006823307925784547e+02,2.506910555913823280e-01,5.539299358932303186e+00,-1.120682902707057504e-01,-2.589621868126164017e-01,6.839316092015533532e-02,1.000000003572161011e+00,0.000000000000000000e+00 +6.640988891652523307e+01,4.006922680617659012e+02,2.495727170484594026e-01,5.538831859037402161e+00,-1.118182902707057502e-01,-2.571569043413601263e-01,6.839316092015533532e-02,1.000000003635832302e+00,0.000000000000000000e+00 +6.641169435136320942e+01,4.007022056102273950e+02,2.484568628577555338e-01,5.538367579003478092e+00,-1.115682902707057500e-01,-2.553514694968194165e-01,6.839316092015533532e-02,1.000000003559523565e+00,0.000000000000000000e+00 +6.641349993755035541e+01,4.007121434373419220e+02,2.473434930890116012e-01,5.537906519917286552e+00,-1.113182902707057498e-01,-2.535458833032438464e-01,6.839316092015533532e-02,1.000000003942599136e+00,0.000000000000000000e+00 +6.641530567406179841e+01,4.007220815424882971e+02,2.462326078118132200e-01,5.537448682858478577e+00,-1.110682902707057496e-01,-2.517401467846766550e-01,6.839316092015533532e-02,1.000000003730426634e+00,0.000000000000000000e+00 +6.641711155987179893e+01,4.007320199250454493e+02,2.451242070955907404e-01,5.536994068899591781e+00,-1.108182902707057493e-01,-2.499342609679358340e-01,6.839316092015533532e-02,1.000000004027329803e+00,0.000000000000000000e+00 +6.641891759395375061e+01,4.007419585843921936e+02,2.440182910096191926e-01,5.536542679106036147e+00,-1.105682902707057491e-01,-2.481282268787101120e-01,6.839316092015533532e-02,1.000000004283696953e+00,0.000000000000000000e+00 +6.642072377528018023e+01,4.007518975199074021e+02,2.429148596230183144e-01,5.536094514536086919e+00,-1.103182902707057489e-01,-2.463220455445400969e-01,6.839316092015533532e-02,1.000000003930181736e+00,0.000000000000000000e+00 +6.642253010282277614e+01,4.007618367309698328e+02,2.418139130047525787e-01,5.535649576240872172e+00,-1.100682902707057487e-01,-2.445157179948487247e-01,6.839316092015533532e-02,1.000000004555159583e+00,0.000000000000000000e+00 +6.642433657555235982e+01,4.007717762169583011e+02,2.407154512236311661e-01,5.535207865264360372e+00,-1.098182902707057484e-01,-2.427092452570381864e-01,6.839316092015533532e-02,1.000000004188128511e+00,0.000000000000000000e+00 +6.642614319243891430e+01,4.007817159772516220e+02,2.396194743483079093e-01,5.534769382643355051e+00,-1.095682902707057482e-01,-2.409026283629129850e-01,6.839316092015533532e-02,1.000000004376891960e+00,0.000000000000000000e+00 +6.642794995245159839e+01,4.007916560112285538e+02,2.385259824472813761e-01,5.534334129407477931e+00,-1.093182902707057480e-01,-2.390958683423187736e-01,6.839316092015533532e-02,1.000000004743569981e+00,0.000000000000000000e+00 +6.642975685455873247e+01,4.008015963182677979e+02,2.374349755888948144e-01,5.533902106579163593e+00,-1.090682902707057478e-01,-2.372889662266154109e-01,6.839316092015533532e-02,1.000000004346282223e+00,0.000000000000000000e+00 +6.643156389772779846e+01,4.008115368977481694e+02,2.363464538413361515e-01,5.533473315173647933e+00,-1.088182902707057476e-01,-2.354819230496907612e-01,6.839316092015533532e-02,1.000000004942924736e+00,0.000000000000000000e+00 +6.643337108092548249e+01,4.008214777490483129e+02,2.352604172726379950e-01,5.533047756198954836e+00,-1.085682902707057473e-01,-2.336747398430766287e-01,6.839316092015533532e-02,1.000000004734815651e+00,0.000000000000000000e+00 +6.643517840311763223e+01,4.008314188715469299e+02,2.341768659506776318e-01,5.532625430655891741e+00,-1.083182902707057471e-01,-2.318674176423700384e-01,6.839316092015533532e-02,1.000000004894670447e+00,0.000000000000000000e+00 +6.643698586326929956e+01,4.008413602646227218e+02,2.330957999431770011e-01,5.532206339538033646e+00,-1.080682902707057469e-01,-2.300599574818579240e-01,6.839316092015533532e-02,1.000000004942739107e+00,0.000000000000000000e+00 +6.643879346034472633e+01,4.008513019276543332e+02,2.320172193177027498e-01,5.531790483831716898e+00,-1.078182902707057467e-01,-2.282523603974978277e-01,6.839316092015533532e-02,1.000000004922463548e+00,0.000000000000000000e+00 +6.644060119330735859e+01,4.008612438600204086e+02,2.309411241416661487e-01,5.531377864516027643e+00,-1.075682902707057464e-01,-2.264446274259667158e-01,6.839316092015533532e-02,1.000000004856696156e+00,0.000000000000000000e+00 +6.644240906111984657e+01,4.008711860610995927e+02,2.298675144823231764e-01,5.530968482562792055e+00,-1.073182902707057462e-01,-2.246367596046925097e-01,6.839316092015533532e-02,1.000000005562374117e+00,0.000000000000000000e+00 +6.644421706274407313e+01,4.008811285302705301e+02,2.287963904067744081e-01,5.530562338936566569e+00,-1.070682902707057460e-01,-2.228287579704126831e-01,6.839316092015533532e-02,1.000000004846900881e+00,0.000000000000000000e+00 +6.644602519714111111e+01,4.008910712669117515e+02,2.277277519819650986e-01,5.530159434594630774e+00,-1.068182902707057458e-01,-2.210206235646097750e-01,6.839316092015533532e-02,1.000000005659031244e+00,0.000000000000000000e+00 +6.644783346327128015e+01,4.009010142704019017e+02,2.266615992746851549e-01,5.529759770486970538e+00,-1.065682902707057456e-01,-2.192123574242099138e-01,6.839316092015533532e-02,1.000000004949639587e+00,0.000000000000000000e+00 +6.644964186009411833e+01,4.009109575401195116e+02,2.255979323515691359e-01,5.529363347556278008e+00,-1.063182902707057453e-01,-2.174039605924220908e-01,6.839316092015533532e-02,1.000000005624598787e+00,0.000000000000000000e+00 +6.645145038656841052e+01,4.009209010754431119e+02,2.245367512790961972e-01,5.528970166737932068e+00,-1.060682902707057451e-01,-2.155954341079642511e-01,6.839316092015533532e-02,1.000000005408239634e+00,0.000000000000000000e+00 +6.645325904165216002e+01,4.009308448757512338e+02,2.234780561235901741e-01,5.528580228959998344e+00,-1.058182902707057449e-01,-2.137867790144276636e-01,6.839316092015533532e-02,1.000000005534067871e+00,0.000000000000000000e+00 +6.645506782430265957e+01,4.009407889404224079e+02,2.224218469512194984e-01,5.528193535143212323e+00,-1.055682902707057447e-01,-2.119779963539250023e-01,6.839316092015533532e-02,1.000000005856585217e+00,0.000000000000000000e+00 +6.645687673347640612e+01,4.009507332688351084e+02,2.213681238279972541e-01,5.527810086200974027e+00,-1.053182902707057444e-01,-2.101690871695784391e-01,6.839316092015533532e-02,1.000000005394856784e+00,0.000000000000000000e+00 +6.645868576812920026e+01,4.009606778603678094e+02,2.203168868197811492e-01,5.527429883039338243e+00,-1.050682902707057442e-01,-2.083600525070252729e-01,6.839316092015533532e-02,1.000000005589327001e+00,0.000000000000000000e+00 +6.646049492721607521e+01,4.009706227143989850e+02,2.192681359922734885e-01,5.527052926557002088e+00,-1.048182902707057440e-01,-2.065508934100319660e-01,6.839316092015533532e-02,1.000000005958978200e+00,0.000000000000000000e+00 +6.646230420969136787e+01,4.009805678303071090e+02,2.182218714110211732e-01,5.526679217645300568e+00,-1.045682902707057438e-01,-2.047416109239640902e-01,6.839316092015533532e-02,1.000000005730252273e+00,0.000000000000000000e+00 +6.646411361450864774e+01,4.009905132074705989e+02,2.171780931414157567e-01,5.526308757188195919e+00,-1.043182902707057436e-01,-2.029322060963100749e-01,6.839316092015533532e-02,1.000000005736010777e+00,0.000000000000000000e+00 +6.646592314062081641e+01,4.010004588452678718e+02,2.161368012486933887e-01,5.525941546062266063e+00,-1.040682902707057433e-01,-2.011226799737688975e-01,6.839316092015533532e-02,1.000000006244616158e+00,0.000000000000000000e+00 +6.646773278698002230e+01,4.010104047430772880e+02,2.150979957979348156e-01,5.525577585136698389e+00,-1.038182902707057431e-01,-1.993130336032653827e-01,6.839316092015533532e-02,1.000000005604333442e+00,0.000000000000000000e+00 +6.646954255253773169e+01,4.010203509002772648e+02,2.140616768540653525e-01,5.525216875273281758e+00,-1.035682902707057429e-01,-1.975032680354191494e-01,6.839316092015533532e-02,1.000000006209792458e+00,0.000000000000000000e+00 +6.647135243624470036e+01,4.010302973162461626e+02,2.130278444818549666e-01,5.524859417326392297e+00,-1.033182902707057427e-01,-1.956933843172160847e-01,6.839316092015533532e-02,1.000000006094727834e+00,0.000000000000000000e+00 +6.647316243705098771e+01,4.010402439903623417e+02,2.119964987459181383e-01,5.524505212142992505e+00,-1.030682902707057425e-01,-1.938833834998945627e-01,6.839316092015533532e-02,1.000000006254005536e+00,0.000000000000000000e+00 +6.647497255390598525e+01,4.010501909220041057e+02,2.109676397107140000e-01,5.524154260562616159e+00,-1.028182902707057422e-01,-1.920732666335804861e-01,6.839316092015533532e-02,1.000000005762725408e+00,0.000000000000000000e+00 +6.647678278575837396e+01,4.010601381105497580e+02,2.099412674405462531e-01,5.523806563417362980e+00,-1.025682902707057420e-01,-1.902630347707561509e-01,6.839316092015533532e-02,1.000000006655536122e+00,0.000000000000000000e+00 +6.647859313155618111e+01,4.010700855553776591e+02,2.089173819995631398e-01,5.523462121531887092e+00,-1.023182902707057418e-01,-1.884526889608969524e-01,6.839316092015533532e-02,1.000000006066579683e+00,0.000000000000000000e+00 +6.648040359024675183e+01,4.010800332558660557e+02,2.078959834517575267e-01,5.523120935723395242e+00,-1.020682902707057416e-01,-1.866422302593367111e-01,6.839316092015533532e-02,1.000000006257226515e+00,0.000000000000000000e+00 +6.648221416077677759e+01,4.010899812113931944e+02,2.068770718609667936e-01,5.522783006801629035e+00,-1.018182902707057413e-01,-1.848316597179798237e-01,6.839316092015533532e-02,1.000000006214669002e+00,0.000000000000000000e+00 +6.648402484209228192e+01,4.010999294213373787e+02,2.058606472908729446e-01,5.522448335568864053e+00,-1.015682902707057411e-01,-1.830209783912228050e-01,6.839316092015533532e-02,1.000000006529637053e+00,0.000000000000000000e+00 +6.648583563313863465e+01,4.011098778850767985e+02,2.048467098050024970e-01,5.522116922819898299e+00,-1.013182902707057409e-01,-1.812101873330451141e-01,6.839316092015533532e-02,1.000000006416222664e+00,0.000000000000000000e+00 +6.648764653286056614e+01,4.011198266019897005e+02,2.038352594667265372e-01,5.521788769342045988e+00,-1.010682902707057407e-01,-1.793992875994958880e-01,6.839316092015533532e-02,1.000000006691347254e+00,0.000000000000000000e+00 +6.648945754020215304e+01,4.011297755714542745e+02,2.028262963392607199e-01,5.521463875915126884e+00,-1.008182902707057405e-01,-1.775882802457855736e-01,6.839316092015533532e-02,1.000000006253850104e+00,0.000000000000000000e+00 +6.649126865410686094e+01,4.011397247928487673e+02,2.018198204856652411e-01,5.521142243311460973e+00,-1.005682902707057402e-01,-1.757771663297534592e-01,6.839316092015533532e-02,1.000000006688082532e+00,0.000000000000000000e+00 +6.649307987351750171e+01,4.011496742655512548e+02,2.008158319688448379e-01,5.520823872295856916e+00,-1.003182902707057400e-01,-1.739659469069980979e-01,6.839316092015533532e-02,1.000000006306652534e+00,0.000000000000000000e+00 +6.649489119737627618e+01,4.011596239889399840e+02,1.998143308515487881e-01,5.520508763625609383e+00,-1.000682902707057398e-01,-1.721546230367968222e-01,6.839316092015533532e-02,1.000000006919277373e+00,0.000000000000000000e+00 +6.649670262462477410e+01,4.011695739623930308e+02,1.988153171963709387e-01,5.520196918050485735e+00,-9.981829027070573956e-02,-1.703431957757656767e-01,6.839316092015533532e-02,1.000000006523195095e+00,0.000000000000000000e+00 +6.649851415420395995e+01,4.011795241852885852e+02,1.978187910657496218e-01,5.519888336312724242e+00,-9.956829027070573934e-02,-1.685316661847590658e-01,6.839316092015533532e-02,1.000000006882654668e+00,0.000000000000000000e+00 +6.650032578505421554e+01,4.011894746570047232e+02,1.968247525219677108e-01,5.519583019147019876e+00,-9.931829027070573912e-02,-1.667200353220401055e-01,6.839316092015533532e-02,1.000000006491355009e+00,0.000000000000000000e+00 +6.650213751611529744e+01,4.011994253769195211e+02,1.958332016271526199e-01,5.519280967280522532e+00,-9.906829027070573890e-02,-1.649083042491992224e-01,6.839316092015533532e-02,1.000000007067625152e+00,0.000000000000000000e+00 +6.650394934632637955e+01,4.012093763444111119e+02,1.948441384432762769e-01,5.518982181432824596e+00,-9.881829027070573868e-02,-1.630964740253062206e-01,6.839316092015533532e-02,1.000000006518904971e+00,0.000000000000000000e+00 +6.650576127462606735e+01,4.012193275588575148e+02,1.938575630321551502e-01,5.518686662315959168e+00,-9.856829027070573845e-02,-1.612845457138085969e-01,6.839316092015533532e-02,1.000000007058712281e+00,0.000000000000000000e+00 +6.650757329995235523e+01,4.012292790196368060e+02,1.928734754554501940e-01,5.518394410634385849e+00,-9.831829027070573823e-02,-1.594725203747235642e-01,6.839316092015533532e-02,1.000000006819680598e+00,0.000000000000000000e+00 +6.650938542124269759e+01,4.012392307261270048e+02,1.918918757746668757e-01,5.518105427084990744e+00,-9.806829027070573801e-02,-1.576603990720261694e-01,6.839316092015533532e-02,1.000000006887200144e+00,0.000000000000000000e+00 +6.651119763743395197e+01,4.012491826777061306e+02,1.909127640511551760e-01,5.517819712357073136e+00,-9.781829027070573779e-02,-1.558481828682928838e-01,6.839316092015533532e-02,1.000000006971208943e+00,0.000000000000000000e+00 +6.651300994746242168e+01,4.012591348737521457e+02,1.899361403461095610e-01,5.517537267132341938e+00,-9.756829027070573757e-02,-1.540358728271878364e-01,6.839316092015533532e-02,1.000000006758669180e+00,0.000000000000000000e+00 +6.651482235026385581e+01,4.012690873136431264e+02,1.889620047205690379e-01,5.517258092084907695e+00,-9.731829027070573734e-02,-1.522234700134984520e-01,6.839316092015533532e-02,1.000000007265503532e+00,0.000000000000000000e+00 +6.651663484477346344e+01,4.012790399967569783e+02,1.879903572354170715e-01,5.516982187881274591e+00,-9.706829027070573712e-02,-1.504109754907207164e-01,6.839316092015533532e-02,1.000000007051029316e+00,0.000000000000000000e+00 +6.651844742992589943e+01,4.012889929224716639e+02,1.870211979513816403e-01,5.516709555180336899e+00,-9.681829027070573690e-02,-1.485983903255054805e-01,6.839316092015533532e-02,1.000000006814572462e+00,0.000000000000000000e+00 +6.652026010465527861e+01,4.012989460901651455e+02,1.860545269290351800e-01,5.516440194633367433e+00,-9.656829027070573668e-02,-1.467857155837737071e-01,6.839316092015533532e-02,1.000000007231901078e+00,0.000000000000000000e+00 +6.652207286789519003e+01,4.013088994992153289e+02,1.850903442287946399e-01,5.516174106884013106e+00,-9.631829027070573646e-02,-1.449729523307527745e-01,6.839316092015533532e-02,1.000000007333700758e+00,0.000000000000000000e+00 +6.652388571857869692e+01,4.013188531490001765e+02,1.841286499109214547e-01,5.515911292568290492e+00,-9.606829027070573623e-02,-1.431601016339523746e-01,6.839316092015533532e-02,1.000000006938590369e+00,0.000000000000000000e+00 +6.652569865563833673e+01,4.013288070388975370e+02,1.831694440355214892e-01,5.515651752314576051e+00,-9.581829027070573601e-02,-1.413471645617302153e-01,6.839316092015533532e-02,1.000000007192797469e+00,0.000000000000000000e+00 +6.652751167800614951e+01,4.013387611682853162e+02,1.822127266625451214e-01,5.515395486743599029e+00,-9.556829027070573579e-02,-1.395341421808789228e-01,6.839316092015533532e-02,1.000000007327577656e+00,0.000000000000000000e+00 +6.652932478461364951e+01,4.013487155365413628e+02,1.812584978517871870e-01,5.515142496468438793e+00,-9.531829027070573557e-02,-1.377210355600915204e-01,6.839316092015533532e-02,1.000000007091313536e+00,0.000000000000000000e+00 +6.653113797439186783e+01,4.013586701430435255e+02,1.803067576628869795e-01,5.514892782094515944e+00,-9.506829027070573535e-02,-1.359078457690178487e-01,6.839316092015533532e-02,1.000000007289584270e+00,0.000000000000000000e+00 +6.653295124627132395e+01,4.013686249871696532e+02,1.793575061553282779e-01,5.514646344219585217e+00,-9.481829027070573512e-02,-1.340945738763414663e-01,6.839316092015533532e-02,1.000000007353607057e+00,0.000000000000000000e+00 +6.653476459918206842e+01,4.013785800682975378e+02,1.784107433884392913e-01,5.514403183433731925e+00,-9.456829027070573490e-02,-1.322812209522653826e-01,6.839316092015533532e-02,1.000000007501560928e+00,0.000000000000000000e+00 +6.653657803205365440e+01,4.013885353858050280e+02,1.774664694213926863e-01,5.514163300319363969e+00,-9.431829027070573468e-02,-1.304677880670789270e-01,6.839316092015533532e-02,1.000000007117682221e+00,0.000000000000000000e+00 +6.653839154381516607e+01,4.013984909390699158e+02,1.765246843132056154e-01,5.513926695451206506e+00,-9.406829027070573446e-02,-1.286542762926638217e-01,6.839316092015533532e-02,1.000000007453207829e+00,0.000000000000000000e+00 +6.654020513339520448e+01,4.014084467274699932e+02,1.755853881227396052e-01,5.513693369396293953e+00,-9.381829027070573424e-02,-1.268406866991021731e-01,6.839316092015533532e-02,1.000000007304975735e+00,0.000000000000000000e+00 +6.654201879972193012e+01,4.014184027503829952e+02,1.746485809087006957e-01,5.513463322713968218e+00,-9.356829027070573401e-02,-1.250270203591213047e-01,6.839316092015533532e-02,1.000000007336588670e+00,0.000000000000000000e+00 +6.654383254172304873e+01,4.014283590071866570e+02,1.737142627296393294e-01,5.513236555955868923e+00,-9.331829027070573379e-02,-1.232132783447020541e-01,6.839316092015533532e-02,1.000000007647727784e+00,0.000000000000000000e+00 +6.654564635832578290e+01,4.014383154972587135e+02,1.727824336439503783e-01,5.513013069665929855e+00,-9.306829027070573357e-02,-1.213994617280951677e-01,6.839316092015533532e-02,1.000000007504353139e+00,0.000000000000000000e+00 +6.654746024845694308e+01,4.014482722199769000e+02,1.718530937098731726e-01,5.512792864380373636e+00,-9.281829027070573335e-02,-1.195855715833272909e-01,6.839316092015533532e-02,1.000000007498545118e+00,0.000000000000000000e+00 +6.654927421104288499e+01,4.014582291747189515e+02,1.709262429854914722e-01,5.512575940627703730e+00,-9.256829027070573312e-02,-1.177716089837893831e-01,6.839316092015533532e-02,1.000000007388580636e+00,0.000000000000000000e+00 +6.655108824500952380e+01,4.014681863608624894e+02,1.700018815287334395e-01,5.512362298928700888e+00,-9.231829027070573290e-02,-1.159575750037428188e-01,6.839316092015533532e-02,1.000000007448704320e+00,0.000000000000000000e+00 +6.655290234928237680e+01,4.014781437777852489e+02,1.690800093973716389e-01,5.512151939796416933e+00,-9.206829027070573268e-02,-1.141434707173771546e-01,6.839316092015533532e-02,1.000000007929074286e+00,0.000000000000000000e+00 +6.655471652278652073e+01,4.014881014248648512e+02,1.681606266490231205e-01,5.511944863736170319e+00,-9.181829027070573246e-02,-1.123292971988474609e-01,6.839316092015533532e-02,1.000000007167022531e+00,0.000000000000000000e+00 +6.655653076444662020e+01,4.014980593014789747e+02,1.672437333411492810e-01,5.511741071245541690e+00,-9.156829027070573224e-02,-1.105150555257382872e-01,6.839316092015533532e-02,1.000000007793448331e+00,0.000000000000000000e+00 +6.655834507318695614e+01,4.015080174070052408e+02,1.663293295310559472e-01,5.511540562814363220e+00,-9.131829027070573201e-02,-1.087007467712679532e-01,6.839316092015533532e-02,1.000000007827778425e+00,0.000000000000000000e+00 +6.656015944793136896e+01,4.015179757408212708e+02,1.654174152758933758e-01,5.511343338924722168e+00,-9.106829027070573179e-02,-1.068863720126484729e-01,6.839316092015533532e-02,1.000000007424286519e+00,0.000000000000000000e+00 +6.656197388760334377e+01,4.015279343023046295e+02,1.645079906326561980e-01,5.511149400050949332e+00,-9.081829027070573157e-02,-1.050719323272062133e-01,6.839316092015533532e-02,1.000000007792087420e+00,0.000000000000000000e+00 +6.656378839112595358e+01,4.015378930908329380e+02,1.636010556581834474e-01,5.510958746659614604e+00,-9.056829027070573135e-02,-1.032574287904615140e-01,6.839316092015533532e-02,1.000000007418359482e+00,0.000000000000000000e+00 +6.656560295742188771e+01,4.015478521057838179e+02,1.626966104091585597e-01,5.510771379209526089e+00,-9.031829027070573113e-02,-1.014428624810611856e-01,6.839316092015533532e-02,1.000000008003274710e+00,0.000000000000000000e+00 +6.656741758541348020e+01,4.015578113465347769e+02,1.617946549421093727e-01,5.510587298151720326e+00,-9.006829027070573090e-02,-9.962823447494216500e-02,6.839316092015533532e-02,1.000000007716095762e+00,0.000000000000000000e+00 +6.656923227402268139e+01,4.015677708124633796e+02,1.608951893134080990e-01,5.510406503929463184e+00,-8.981829027070573068e-02,-9.781354585173225591e-02,6.839316092015533532e-02,1.000000007668955693e+00,0.000000000000000000e+00 +6.657104702217108638e+01,4.015777305029471336e+02,1.599982135792713256e-01,5.510228996978239202e+00,-8.956829027070573046e-02,-9.599879768940365599e-02,6.839316092015533532e-02,1.000000007870734731e+00,0.000000000000000000e+00 +6.657286182877993497e+01,4.015876904173636035e+02,1.591037277957600415e-01,5.510054777725750697e+00,-8.931829027070573024e-02,-9.418399106626852701e-02,6.839316092015533532e-02,1.000000007766669086e+00,0.000000000000000000e+00 +6.657467669277011169e+01,4.015976505550902402e+02,1.582117320187796106e-01,5.509883846591913326e+00,-8.906829027070573002e-02,-9.236912706199557066e-02,6.839316092015533532e-02,1.000000007586758999e+00,0.000000000000000000e+00 +6.657649161306216001e+01,4.016076109155045515e+02,1.573222263040797708e-01,5.509716203988849870e+00,-8.881829027070572979e-02,-9.055420675617950610e-02,6.839316092015533532e-02,1.000000008075789815e+00,0.000000000000000000e+00 +6.657830658857628237e+01,4.016175714979840450e+02,1.564352107072546350e-01,5.509551850320886679e+00,-8.856829027070572957e-02,-8.873923122740032254e-02,6.839316092015533532e-02,1.000000007797146040e+00,0.000000000000000000e+00 +6.658012161823235431e+01,4.016275323019061716e+02,1.555506852837426901e-01,5.509390785984551897e+00,-8.831829027070572935e-02,-8.692420155717604791e-02,6.839316092015533532e-02,1.000000007986060702e+00,0.000000000000000000e+00 +6.658193670094992456e+01,4.016374933266483822e+02,1.546686500888267424e-01,5.509233011368566579e+00,-8.806829027070572913e-02,-8.510911882510704962e-02,6.839316092015533532e-02,1.000000007696399296e+00,0.000000000000000000e+00 +6.658375183564822919e+01,4.016474545715881277e+02,1.537891051776340001e-01,5.509078526853844693e+00,-8.781829027070572891e-02,-8.329398411282885883e-02,6.839316092015533532e-02,1.000000007844714212e+00,0.000000000000000000e+00 +6.658556702124619164e+01,4.016574160361028021e+02,1.529120506051360462e-01,5.508927332813486011e+00,-8.756829027070572868e-02,-8.147879850062485219e-02,6.839316092015533532e-02,1.000000007975084593e+00,0.000000000000000000e+00 +6.658738225666242272e+01,4.016673777195697994e+02,1.520374864261487546e-01,5.508779429612775225e+00,-8.731829027070572846e-02,-7.966356306991102809e-02,6.839316092015533532e-02,1.000000008146257890e+00,0.000000000000000000e+00 +6.658919754081524900e+01,4.016773396213665706e+02,1.511654126953324018e-01,5.508634817609176615e+00,-8.706829027070572824e-02,-7.784827890229542580e-02,6.839316092015533532e-02,1.000000007853397044e+00,0.000000000000000000e+00 +6.659101287262269864e+01,4.016873017408704527e+02,1.502958294671916106e-01,5.508493497152330498e+00,-8.681829027070572802e-02,-7.603294708059479823e-02,6.839316092015533532e-02,1.000000007914677580e+00,0.000000000000000000e+00 +6.659282825100250136e+01,4.016972640774587830e+02,1.494287367960753232e-01,5.508355468584047898e+00,-8.656829027070572780e-02,-7.421756868642652438e-02,6.839316092015533532e-02,1.000000008045531574e+00,0.000000000000000000e+00 +6.659464367487211689e+01,4.017072266305089556e+02,1.485641347361768283e-01,5.508220732238309658e+00,-8.631829027070572757e-02,-7.240214480220398541e-02,6.839316092015533532e-02,1.000000007936875823e+00,0.000000000000000000e+00 +6.659645914314873494e+01,4.017171893993983645e+02,1.477020233415337336e-01,5.508089288441261999e+00,-8.606829027070572735e-02,-7.058667651117470077e-02,6.839316092015533532e-02,1.000000008063350432e+00,0.000000000000000000e+00 +6.659827465474927521e+01,4.017271523835042331e+02,1.468424026660280213e-01,5.507961137511212080e+00,-8.581829027070572713e-02,-6.877116489599109650e-02,6.839316092015533532e-02,1.000000008066552315e+00,0.000000000000000000e+00 +6.660009020859040163e+01,4.017371155822039555e+02,1.459852727633859926e-01,5.507836279758626219e+00,-8.556829027070572691e-02,-6.695561104021642562e-02,6.839316092015533532e-02,1.000000008102271520e+00,0.000000000000000000e+00 +6.660190580358852230e+01,4.017470789948748120e+02,1.451306336871782676e-01,5.507714715486125456e+00,-8.531829027070572669e-02,-6.514001602738482555e-02,6.839316092015533532e-02,1.000000008032169374e+00,0.000000000000000000e+00 +6.660372143865978956e+01,4.017570426208940830e+02,1.442784854908197578e-01,5.507596444988482887e+00,-8.506829027070572646e-02,-6.332438094152888219e-02,6.839316092015533532e-02,1.000000007962552173e+00,0.000000000000000000e+00 +6.660553711272012833e+01,4.017670064596389921e+02,1.434288282275697490e-01,5.507481468552620107e+00,-8.481829027070572624e-02,-6.150870686672901128e-02,6.839316092015533532e-02,1.000000008244403604e+00,0.000000000000000000e+00 +6.660735282468522200e+01,4.017769705104868763e+02,1.425816619505318184e-01,5.507369786457604555e+00,-8.456829027070572602e-02,-5.969299488666272857e-02,6.839316092015533532e-02,1.000000008126251227e+00,0.000000000000000000e+00 +6.660916857347052655e+01,4.017869347728149592e+02,1.417369867126538618e-01,5.507261398974647726e+00,-8.431829027070572580e-02,-5.787724608659992886e-02,6.839316092015533532e-02,1.000000007909515931e+00,0.000000000000000000e+00 +6.661098435799128481e+01,4.017968992460004642e+02,1.408948025667280668e-01,5.507156306367099852e+00,-8.406829027070572558e-02,-5.606146155148471200e-02,6.839316092015533532e-02,1.000000008409447583e+00,0.000000000000000000e+00 +6.661280017716249802e+01,4.018068639294206150e+02,1.400551095653909395e-01,5.507054508890448119e+00,-8.381829027070572535e-02,-5.424564236499585662e-02,6.839316092015533532e-02,1.000000007992109863e+00,0.000000000000000000e+00 +6.661461602989899689e+01,4.018168288224525782e+02,1.392179077611233051e-01,5.506956006792316671e+00,-8.356829027070572513e-02,-5.242978961398760823e-02,6.839316092015533532e-02,1.000000008231173965e+00,0.000000000000000000e+00 +6.661643191511538475e+01,4.018267939244736340e+02,1.383831972062502802e-01,5.506860800312458615e+00,-8.331829027070572491e-02,-5.061390438265878089e-02,6.839316092015533532e-02,1.000000008251098471e+00,0.000000000000000000e+00 +6.661824783172606601e+01,4.018367592348608923e+02,1.375509779529412724e-01,5.506768889682758683e+00,-8.306829027070572469e-02,-4.879798775699364932e-02,6.839316092015533532e-02,1.000000008228944193e+00,0.000000000000000000e+00 +6.662006377864527451e+01,4.018467247529915198e+02,1.367212500532099806e-01,5.506680275127227908e+00,-8.281829027070572447e-02,-4.698204082284411498e-02,6.839316092015533532e-02,1.000000008047492450e+00,0.000000000000000000e+00 +6.662187975478704516e+01,4.018566904782427400e+02,1.358940135589143949e-01,5.506594956862001844e+00,-8.256829027070572424e-02,-4.516606466645761014e-02,6.839316092015533532e-02,1.000000008372563531e+00,0.000000000000000000e+00 +6.662369575906525654e+01,4.018666564099916627e+02,1.350692685217567968e-01,5.506512935095337902e+00,-8.231829027070572402e-02,-4.335006037304862947e-02,6.839316092015533532e-02,1.000000008229114501e+00,0.000000000000000000e+00 +6.662551179039358829e+01,4.018766225476153977e+02,1.342470149932837586e-01,5.506434210027615350e+00,-8.206829027070572380e-02,-4.153402902977203215e-02,6.839316092015533532e-02,1.000000008233073556e+00,0.000000000000000000e+00 +6.662732784768557792e+01,4.018865888904910548e+02,1.334272530248861166e-01,5.506358781851329987e+00,-8.181829027070572358e-02,-3.971797172282736516e-02,6.839316092015533532e-02,1.000000008167432064e+00,0.000000000000000000e+00 +6.662914392985460665e+01,4.018965554379957439e+02,1.326099826677989979e-01,5.506286650751094136e+00,-8.156829027070572335e-02,-3.790188953896499180e-02,6.839316092015533532e-02,1.000000008328818968e+00,0.000000000000000000e+00 +6.663096003581389937e+01,4.019065221895065747e+02,1.317952039731017932e-01,5.506217816903633988e+00,-8.131829027070572313e-02,-3.608578356454680142e-02,6.839316092015533532e-02,1.000000008450255828e+00,0.000000000000000000e+00 +6.663277616447653884e+01,4.019164891444006003e+02,1.309829169917181846e-01,5.506152280477788707e+00,-8.106829027070572291e-02,-3.426965488656327080e-02,6.839316092015533532e-02,1.000000008239801508e+00,0.000000000000000000e+00 +6.663459231475546574e+01,4.019264563020549303e+02,1.301731217744160896e-01,5.506090041634507770e+00,-8.081829027070572269e-02,-3.245350459267232895e-02,6.839316092015533532e-02,1.000000008188328016e+00,0.000000000000000000e+00 +6.663640848556349283e+01,4.019364236618465611e+02,1.293658183718077170e-01,5.506031100526848299e+00,-8.056829027070572247e-02,-3.063733376977115924e-02,6.839316092015533532e-02,1.000000008492345938e+00,0.000000000000000000e+00 +6.663822467581331921e+01,4.019463912231526024e+02,1.285610068343495394e-01,5.505975457299975062e+00,-8.031829027070572224e-02,-2.882114350452427351e-02,6.839316092015533532e-02,1.000000008246312300e+00,0.000000000000000000e+00 +6.664004088441750184e+01,4.019563589853499934e+02,1.277586872123422645e-01,5.505923112091159588e+00,-8.006829027070572202e-02,-2.700493488535855510e-02,6.839316092015533532e-02,1.000000008404448471e+00,0.000000000000000000e+00 +6.664185711028851244e+01,4.019663269478157872e+02,1.269588595559308641e-01,5.505874065029775721e+00,-7.981829027070572180e-02,-2.518870899907906663e-02,6.839316092015533532e-02,1.000000008280370833e+00,0.000000000000000000e+00 +6.664367335233870904e+01,4.019762951099270367e+02,1.261615239151045731e-01,5.505828316237301401e+00,-7.956829027070572158e-02,-2.337246693384221335e-02,6.839316092015533532e-02,1.000000008508885374e+00,0.000000000000000000e+00 +6.664548960948035017e+01,4.019862634710606812e+02,1.253666803396968898e-01,5.505785865827315106e+00,-7.931829027070572136e-02,-2.155620977674965744e-02,6.839316092015533532e-02,1.000000008353478576e+00,0.000000000000000000e+00 +6.664730588062559491e+01,4.019962320305937169e+02,1.245743288793855069e-01,5.505746713905496748e+00,-7.906829027070572113e-02,-1.973993861633245930e-02,6.839316092015533532e-02,1.000000008398779894e+00,0.000000000000000000e+00 +6.664912216468653128e+01,4.020062007879030830e+02,1.237844695836924080e-01,5.505710860569624110e+00,-7.881829027070572091e-02,-1.792365454014503354e-02,6.839316092015533532e-02,1.000000008396597639e+00,0.000000000000000000e+00 +6.665093846057514781e+01,4.020161697423657188e+02,1.229971025019837849e-01,5.505678305909573744e+00,-7.856829027070572069e-02,-1.610735863627125661e-02,6.839316092015533532e-02,1.000000008612103031e+00,0.000000000000000000e+00 +6.665275476720339043e+01,4.020261388933586204e+02,1.222122276834700927e-01,5.505649050007319190e+00,-7.831829027070572047e-02,-1.429105199238553739e-02,6.839316092015533532e-02,1.000000008208450364e+00,0.000000000000000000e+00 +6.665457108348311976e+01,4.020361082402586703e+02,1.214298451772059945e-01,5.505623092936930973e+00,-7.806829027070572025e-02,-1.247473569774790354e-02,6.839316092015533532e-02,1.000000008477503366e+00,0.000000000000000000e+00 +6.665638740832613962e+01,4.020460777824428078e+02,1.206499550320904030e-01,5.505600434764573059e+00,-7.781829027070572002e-02,-1.065841083933108564e-02,6.839316092015533532e-02,1.000000008532192508e+00,0.000000000000000000e+00 +6.665820374064419696e+01,4.020560475192879721e+02,1.198725572968664527e-01,5.505581075548506398e+00,-7.756829027070571980e-02,-8.842078505771623978e-03,6.839316092015533532e-02,1.000000008537230256e+00,0.000000000000000000e+00 +6.666002007934901030e+01,4.020660174501709889e+02,1.190976520201215139e-01,5.505565015339085377e+00,-7.731829027070571958e-02,-7.025739785452982632e-03,6.839316092015533532e-02,1.000000008362985859e+00,0.000000000000000000e+00 +6.666183642335224135e+01,4.020759875744687406e+02,1.183252392502871508e-01,5.505552254178757821e+00,-7.706829027070571936e-02,-5.209395767033655686e-03,6.839316092015533532e-02,1.000000008662349948e+00,0.000000000000000000e+00 +6.666365277156552338e+01,4.020859578915581096e+02,1.175553190356391636e-01,5.505542792102064098e+00,-7.681829027070571914e-02,-3.393047538019314593e-03,6.839316092015533532e-02,1.000000008178562050e+00,0.000000000000000000e+00 +6.666546912290046123e+01,4.020959284008159784e+02,1.167878914242975741e-01,5.505536629135638904e+00,-7.656829027070571891e-02,-1.576696188224877134e-03,6.839316092015533532e-02,1.000000008860324474e+00,0.000000000000000000e+00 +6.666728547626864554e+01,4.021058991016191726e+02,1.160229564642265981e-01,5.505533765298206816e+00,-7.631829027070571869e-02,2.396571960542551053e-04,6.839316092015533532e-02,1.000000008323753020e+00,0.000000000000000000e+00 +6.666910183058165273e+01,4.021158699933445178e+02,1.152605142032346736e-01,5.505534200600588512e+00,-7.606829027070571847e-02,2.056011524179219944e-03,6.839316092015533532e-02,1.000000008467274437e+00,0.000000000000000000e+00 +6.667091818475104503e+01,4.021258410753688395e+02,1.145005646889744322e-01,5.505537935045692777e+00,-7.581829027070571825e-02,3.872365708952400266e-03,6.839316092015533532e-02,1.000000008741242619e+00,0.000000000000000000e+00 +6.667273453768839886e+01,4.021358123470689634e+02,1.137431079689427277e-01,5.505544968628522717e+00,-7.556829027070571803e-02,5.688718662177384700e-03,6.839316092015533532e-02,1.000000008570874455e+00,0.000000000000000000e+00 +6.667455088830527643e+01,4.021457838078216582e+02,1.129881440904806078e-01,5.505555301336173990e+00,-7.531829027070571780e-02,7.505069294619830765e-03,6.839316092015533532e-02,1.000000008433111098e+00,0.000000000000000000e+00 +6.667636723551326838e+01,4.021557554570036928e+02,1.122356731007733144e-01,5.505568933147833022e+00,-7.506829027070571758e-02,9.321416517924291031e-03,6.839316092015533532e-02,1.000000008510546268e+00,0.000000000000000000e+00 +6.667818357822396536e+01,4.021657272939918357e+02,1.114856950468502833e-01,5.505585864034778787e+00,-7.481829027070571736e-02,1.113775924408609390e-02,6.839316092015533532e-02,1.000000008691434239e+00,0.000000000000000000e+00 +6.667999991534901483e+01,4.021756993181629127e+02,1.107382099755851446e-01,5.505606093960383696e+00,-7.456829027070571714e-02,1.295409638492324086e-02,6.839316092015533532e-02,1.000000008569666088e+00,0.000000000000000000e+00 +6.668181624580007849e+01,4.021856715288936357e+02,1.099932179336957083e-01,5.505629622880113594e+00,-7.431829027070571692e-02,1.477042685154826909e-02,6.839316092015533532e-02,1.000000008790891792e+00,0.000000000000000000e+00 +6.668363256848884646e+01,4.021956439255607165e+02,1.092507189677439788e-01,5.505656450741526875e+00,-7.406829027070571669e-02,1.658674955628511652e-02,6.839316092015533532e-02,1.000000008360304005e+00,0.000000000000000000e+00 +6.668544888232706569e+01,4.022056165075409240e+02,1.085107131241361406e-01,5.505686577484277144e+00,-7.381829027070571647e-02,1.840306340969603827e-02,6.839316092015533532e-02,1.000000008681001917e+00,0.000000000000000000e+00 +6.668726518622653998e+01,4.022155892742109131e+02,1.077732004491225581e-01,5.505720003040110555e+00,-7.356829027070571625e-02,2.021936732494348729e-02,6.839316092015533532e-02,1.000000008707932819e+00,0.000000000000000000e+00 +6.668908147909912998e+01,4.022255622249474527e+02,1.070381809887977764e-01,5.505756727332871137e+00,-7.331829027070571603e-02,2.203566021335001679e-02,6.839316092015533532e-02,1.000000008447835542e+00,0.000000000000000000e+00 +6.669089775985675317e+01,4.022355353591271978e+02,1.063056547891005066e-01,5.505796750278498131e+00,-7.306829027070571581e-02,2.385194098631519127e-02,6.839316092015533532e-02,1.000000008959307074e+00,0.000000000000000000e+00 +6.669271402741139809e+01,4.022455086761268035e+02,1.055756218958136400e-01,5.505840071785026879e+00,-7.281829027070571558e-02,2.566820855723256009e-02,6.839316092015533532e-02,1.000000008314210431e+00,0.000000000000000000e+00 +6.669453028067513856e+01,4.022554821753229817e+02,1.048480823545642343e-01,5.505886691752593265e+00,-7.256829027070571536e-02,2.748446183607144988e-02,6.839316092015533532e-02,1.000000008867191204e+00,0.000000000000000000e+00 +6.669634651856011942e+01,4.022654558560923306e+02,1.041230362108234997e-01,5.505936610073428383e+00,-7.231829027070571514e-02,2.930069973716214332e-02,6.839316092015533532e-02,1.000000008639916338e+00,0.000000000000000000e+00 +6.669816273997859923e+01,4.022754297178115621e+02,1.034004835099068403e-01,5.505989826631867423e+00,-7.206829027070571492e-02,3.111692117133259619e-02,6.839316092015533532e-02,1.000000008590663070e+00,0.000000000000000000e+00 +6.669997894384290760e+01,4.022854037598572745e+02,1.026804242969737851e-01,5.506046341304344338e+00,-7.181829027070571470e-02,3.293312505124856154e-02,6.839316092015533532e-02,1.000000008844946109e+00,0.000000000000000000e+00 +6.670179512906550201e+01,4.022953779816061228e+02,1.019628586170280293e-01,5.506106153959396288e+00,-7.156829027070571447e-02,3.474931028990758258e-02,6.839316092015533532e-02,1.000000008695412390e+00,0.000000000000000000e+00 +6.670361129455893945e+01,4.023053523824347053e+02,1.012477865149174344e-01,5.506169264457665413e+00,-7.131829027070571425e-02,3.656547579913286411e-02,6.839316092015533532e-02,1.000000008755980829e+00,0.000000000000000000e+00 +6.670542743923589057e+01,4.023153269617195633e+02,1.005352080353340144e-01,5.506235672651897950e+00,-7.106829027070571403e-02,3.838162049197945541e-02,6.839316092015533532e-02,1.000000008538466822e+00,0.000000000000000000e+00 +6.670724356200913974e+01,4.023253017188373519e+02,9.982512322281392181e-02,5.506305378386947780e+00,-7.081829027070571381e-02,4.019774328073914826e-02,6.839316092015533532e-02,1.000000008606770852e+00,0.000000000000000000e+00 +6.670905966179162760e+01,4.023352766531646125e+02,9.911753212173744776e-02,5.506378381499776431e+00,-7.056829027070571358e-02,4.201384307885771413e-02,6.839316092015533532e-02,1.000000008961237752e+00,0.000000000000000000e+00 +6.671087573749640853e+01,4.023452517640779433e+02,9.841243477632903580e-02,5.506454681819456631e+00,-7.031829027070571336e-02,4.382991879991789130e-02,6.839316092015533532e-02,1.000000008769315496e+00,0.000000000000000000e+00 +6.671269178803669320e+01,4.023552270509538857e+02,9.770983123065728193e-02,5.506534279167174084e+00,-7.006829027070571314e-02,4.564596935613329798e-02,6.839316092015533532e-02,1.000000008789216688e+00,0.000000000000000000e+00 +6.671450781232584859e+01,4.023652025131689811e+02,9.700972152863489295e-02,5.506617173356226580e+00,-6.981829027070571292e-02,4.746199366124388003e-02,6.839316092015533532e-02,1.000000008677005781e+00,0.000000000000000000e+00 +6.671632380927736961e+01,4.023751781500997708e+02,9.631210571401874199e-02,5.506703364192028438e+00,-6.956829027070571270e-02,4.927799062852082634e-02,6.839316092015533532e-02,1.000000008602395463e+00,0.000000000000000000e+00 +6.671813977780493587e+01,4.023851539611227963e+02,9.561698383040979909e-02,5.506792851472111394e+00,-6.931829027070571247e-02,5.109395917170586610e-02,6.839316092015533532e-02,1.000000008979511135e+00,0.000000000000000000e+00 +6.671995571682238335e+01,4.023951299456145421e+02,9.492435592125318677e-02,5.506885634986127265e+00,-6.906829027070571225e-02,5.290989820546157518e-02,6.839316092015533532e-02,1.000000008581518163e+00,0.000000000000000000e+00 +6.672177162524373273e+01,4.024051061029514926e+02,9.423422202983815221e-02,5.506981714515851500e+00,-6.881829027070571203e-02,5.472580664239797693e-02,6.839316092015533532e-02,1.000000008850069788e+00,0.000000000000000000e+00 +6.672358750198318944e+01,4.024150824325101894e+02,9.354658219929806728e-02,5.507081089835181409e+00,-6.856829027070571181e-02,5.654168339792482040e-02,6.839316092015533532e-02,1.000000009047183669e+00,0.000000000000000000e+00 +6.672540334595512945e+01,4.024250589336670600e+02,9.286143647261041467e-02,5.507183760710143261e+00,-6.831829027070571159e-02,5.835752738629999825e-02,6.839316092015533532e-02,1.000000008679270413e+00,0.000000000000000000e+00 +6.672721915607415610e+01,4.024350356057985891e+02,9.217878489259681563e-02,5.507289726898892290e+00,-6.806829027070571136e-02,6.017333752107988792e-02,6.839316092015533532e-02,1.000000008574703614e+00,0.000000000000000000e+00 +6.672903493125502905e+01,4.024450124482812612e+02,9.149862750192297445e-02,5.507398988151713581e+00,-6.781829027070571114e-02,6.198911271752628044e-02,6.839316092015533532e-02,1.000000008998392476e+00,0.000000000000000000e+00 +6.673085067041274954e+01,4.024549894604915039e+02,9.082096434309874788e-02,5.507511544211027399e+00,-6.756829027070571092e-02,6.380485189158963122e-02,6.839316092015533532e-02,1.000000008843380250e+00,0.000000000000000000e+00 +6.673266637246253197e+01,4.024649666418057450e+02,9.014579545847806186e-02,5.507627394811392740e+00,-6.731829027070571070e-02,6.562055395742458219e-02,6.839316092015533532e-02,1.000000008863662915e+00,0.000000000000000000e+00 +6.673448203631978970e+01,4.024749439916004121e+02,8.947312089025898085e-02,5.507746539679506448e+00,-6.706829027070571048e-02,6.743621783077545506e-02,6.839316092015533532e-02,1.000000008710854926e+00,0.000000000000000000e+00 +6.673629766090017768e+01,4.024849215092519330e+02,8.880294068048366629e-02,5.507868978534208537e+00,-6.681829027070571025e-02,6.925184242698108339e-02,6.839316092015533532e-02,1.000000008820038477e+00,0.000000000000000000e+00 +6.673811324511959242e+01,4.024948991941367353e+02,8.813525487103839040e-02,5.507994711086483974e+00,-6.656829027070571003e-02,7.106742666240377371e-02,6.839316092015533532e-02,1.000000009062760542e+00,0.000000000000000000e+00 +6.673992878789414362e+01,4.025048770456311331e+02,8.747006350365349459e-02,5.508123737039467116e+00,-6.631829027070570981e-02,7.288296945341256328e-02,6.839316092015533532e-02,1.000000008746835256e+00,0.000000000000000000e+00 +6.674174428814021098e+01,4.025148550631116109e+02,8.680736661990345882e-02,5.508256056088444375e+00,-6.606829027070570959e-02,7.469846971536622804e-02,6.839316092015533532e-02,1.000000008772142790e+00,0.000000000000000000e+00 +6.674355974477442999e+01,4.025248332459544827e+02,8.614716426120683224e-02,5.508391667920855106e+00,-6.581829027070570937e-02,7.651392636551017368e-02,6.839316092015533532e-02,1.000000008936057450e+00,0.000000000000000000e+00 +6.674537515671367771e+01,4.025348115935361193e+02,8.548945646882624705e-02,5.508530572216297827e+00,-6.556829027070570914e-02,7.832933832098121218e-02,6.839316092015533532e-02,1.000000008741763979e+00,0.000000000000000000e+00 +6.674719052287510124e+01,4.025447901052328916e+02,8.483424328386846014e-02,5.508672768646532880e+00,-6.531829027070570892e-02,8.014470449827997001e-02,6.839316092015533532e-02,1.000000009015322711e+00,0.000000000000000000e+00 +6.674900584217613186e+01,4.025547687804211137e+02,8.418152474728428369e-02,5.508818256875484209e+00,-6.506829027070570870e-02,8.196002381567885076e-02,6.839316092015533532e-02,1.000000008941088758e+00,0.000000000000000000e+00 +6.675082111353447090e+01,4.025647476184771563e+02,8.353130089986864071e-02,5.508967036559245578e+00,-6.481829027070570848e-02,8.377529519024816407e-02,6.839316092015533532e-02,1.000000009026440706e+00,0.000000000000000000e+00 +6.675263633586810386e+01,4.025747266187772766e+02,8.288357178226050948e-02,5.509119107346081456e+00,-6.456829027070570826e-02,8.559051754026428260e-02,6.839316092015533532e-02,1.000000008676037888e+00,0.000000000000000000e+00 +6.675445150809530048e+01,4.025847057806978455e+02,8.223833743494295134e-02,5.509274468876432351e+00,-6.431829027070570803e-02,8.740568978321433535e-02,6.839316092015533532e-02,1.000000008887309333e+00,0.000000000000000000e+00 +6.675626662913464315e+01,4.025946851036151770e+02,8.159559789824312459e-02,5.509433120782916582e+00,-6.406829027070570781e-02,8.922081083869380647e-02,6.839316092015533532e-02,1.000000009015886260e+00,0.000000000000000000e+00 +6.675808169790501267e+01,4.026046645869055283e+02,8.095535321233225667e-02,5.509595062690337386e+00,-6.381829027070570759e-02,9.103587962543276124e-02,6.839316092015533532e-02,1.000000008931945850e+00,0.000000000000000000e+00 +6.675989671332560249e+01,4.026146442299451564e+02,8.031760341722563035e-02,5.509760294215684695e+00,-6.356829027070570737e-02,9.285089506223628830e-02,6.839316092015533532e-02,1.000000009020424629e+00,0.000000000000000000e+00 +6.676171167431591869e+01,4.026246240321103755e+02,7.968234855278261142e-02,5.509928814968138688e+00,-6.331829027070570715e-02,9.466585606892519156e-02,6.839316092015533532e-02,1.000000008832986786e+00,0.000000000000000000e+00 +6.676352657979579419e+01,4.026346039927774427e+02,7.904958865870662099e-02,5.510100624549075121e+00,-6.306829027070570692e-02,9.648076156482998655e-02,6.839316092015533532e-02,1.000000008975444388e+00,0.000000000000000000e+00 +6.676534142868538879e+01,4.026445841113226152e+02,7.841932377454514935e-02,5.510275722552067990e+00,-6.281829027070570670e-02,9.829561047071050384e-02,6.839316092015533532e-02,1.000000008680966390e+00,0.000000000000000000e+00 +6.676715621990518912e+01,4.026545643871221500e+02,7.779155393968976984e-02,5.510454108562895748e+00,-6.256829027070570648e-02,1.001104017062710710e-01,6.839316092015533532e-02,1.000000009315796135e+00,0.000000000000000000e+00 +6.676897095237605129e+01,4.026645448195522476e+02,7.716627919337608332e-02,5.510635782159543083e+00,-6.231829027070570626e-02,1.019251341940380223e-01,6.839316092015533532e-02,1.000000008715867361e+00,0.000000000000000000e+00 +6.677078562501915826e+01,4.026745254079891083e+02,7.654349957468375987e-02,5.510820742912209802e+00,-6.206829027070570604e-02,1.037398068529593875e-01,6.839316092015533532e-02,1.000000009277758339e+00,0.000000000000000000e+00 +6.677260023675604828e+01,4.026845061518089892e+02,7.592321512253653870e-02,5.511008990383308159e+00,-6.181829027070570581e-02,1.055544186066875723e-01,6.839316092015533532e-02,1.000000008518874717e+00,0.000000000000000000e+00 +6.677441478650862905e+01,4.026944870503880907e+02,7.530542587570218660e-02,5.511200524127475298e+00,-6.156829027070570559e-02,1.073689683747316298e-01,6.839316092015533532e-02,1.000000009327140171e+00,0.000000000000000000e+00 +6.677622927319917778e+01,4.027044681031026130e+02,7.469013187279253951e-02,5.511395343691569693e+00,-6.131829027070570537e-02,1.091834550822089606e-01,6.839316092015533532e-02,1.000000008901554605e+00,0.000000000000000000e+00 +6.677804369575034116e+01,4.027144493093286997e+02,7.407733315226346094e-02,5.511593448614685364e+00,-6.106829027070570515e-02,1.109978776495288144e-01,6.839316092015533532e-02,1.000000009002832702e+00,0.000000000000000000e+00 +6.677985805308514955e+01,4.027244306684425510e+02,7.346702975241488354e-02,5.511794838428147436e+00,-6.081829027070570493e-02,1.128122350006759284e-01,6.839316092015533532e-02,1.000000008939682772e+00,0.000000000000000000e+00 +6.678167234412701703e+01,4.027344121798203673e+02,7.285922171139075365e-02,5.511999512655522793e+00,-6.056829027070570470e-02,1.146265260587677470e-01,6.839316092015533532e-02,1.000000009075854512e+00,0.000000000000000000e+00 +6.678348656779975556e+01,4.027443938428382353e+02,7.225390906717908679e-02,5.512207470812622745e+00,-6.031829027070570448e-02,1.164407497479750114e-01,6.839316092015533532e-02,1.000000008941627883e+00,0.000000000000000000e+00 +6.678530072302757503e+01,4.027543756568723552e+02,7.165109185761191213e-02,5.512418712407509247e+00,-6.006829027070570426e-02,1.182549049920159356e-01,6.839316092015533532e-02,1.000000008852663047e+00,0.000000000000000000e+00 +6.678711480873508322e+01,4.027643576212988705e+02,7.105077012036531414e-02,5.512633236940498449e+00,-5.981829027070570404e-02,1.200689907155873953e-01,6.839316092015533532e-02,1.000000009370776155e+00,0.000000000000000000e+00 +6.678892882384731422e+01,4.027743397354938679e+02,7.045294389295940485e-02,5.512851043904166914e+00,-5.956829027070570381e-02,1.218830058448176767e-01,6.839316092015533532e-02,1.000000008604496893e+00,0.000000000000000000e+00 +6.679074276728971427e+01,4.027843219988334909e+02,6.985761321275830993e-02,5.513072132783358725e+00,-5.931829027070570359e-02,1.236969493028224898e-01,6.839316092015533532e-02,1.000000009227127284e+00,0.000000000000000000e+00 +6.679255663798814169e+01,4.027943044106938260e+02,6.926477811697021036e-02,5.513296503055184594e+00,-5.906829027070570337e-02,1.255108200179917144e-01,6.839316092015533532e-02,1.000000009299349069e+00,0.000000000000000000e+00 +6.679437043486890957e+01,4.028042869704509599e+02,6.867443864264728692e-02,5.513524154189036075e+00,-5.881829027070570315e-02,1.273246169156285468e-01,6.839316092015533532e-02,1.000000008747349289e+00,0.000000000000000000e+00 +6.679618415685875732e+01,4.028142696774810361e+02,6.808659482668576179e-02,5.513755085646584675e+00,-5.856829027070570293e-02,1.291383389213398569e-01,6.839316092015533532e-02,1.000000009093574560e+00,0.000000000000000000e+00 +6.679799780288486488e+01,4.028242525311600843e+02,6.750124670582588471e-02,5.513989296881787183e+00,-5.831829027070570270e-02,1.309519849639375344e-01,6.839316092015533532e-02,1.000000008866795520e+00,0.000000000000000000e+00 +6.679981137187486695e+01,4.028342355308641913e+02,6.691839431665190518e-02,5.514226787340896330e+00,-5.806829027070570248e-02,1.327655539700150489e-01,6.839316092015533532e-02,1.000000009272228096e+00,0.000000000000000000e+00 +6.680162486275683875e+01,4.028442186759694437e+02,6.633803769559208641e-02,5.514467556462461673e+00,-5.781829027070570226e-02,1.345790448688078678e-01,6.839316092015533532e-02,1.000000009060945327e+00,0.000000000000000000e+00 +6.680343827445935290e+01,4.028542019658518711e+02,6.576017687891873298e-02,5.514711603677339369e+00,-5.756829027070570204e-02,1.363924565877489559e-01,6.839316092015533532e-02,1.000000008850788102e+00,0.000000000000000000e+00 +6.680525160591140832e+01,4.028641853998875035e+02,6.518481190274813541e-02,5.514958928408693950e+00,-5.731829027070570182e-02,1.382057880558604790e-01,6.839316092015533532e-02,1.000000009236138965e+00,0.000000000000000000e+00 +6.680706485604251554e+01,4.028741689774524275e+02,6.461194280304061177e-02,5.515209530072006316e+00,-5.706829027070570159e-02,1.400190382037173054e-01,6.839316092015533532e-02,1.000000009167214099e+00,0.000000000000000000e+00 +6.680887802378265405e+01,4.028841526979226160e+02,6.404156961560046601e-02,5.515463408075081730e+00,-5.681829027070570137e-02,1.418322059604718854e-01,6.839316092015533532e-02,1.000000008921025474e+00,0.000000000000000000e+00 +6.681069110806227229e+01,4.028941365606740987e+02,6.347369237607604353e-02,5.515720561818052481e+00,-5.656829027070570115e-02,1.436452902562664058e-01,6.839316092015533532e-02,1.000000009291845071e+00,0.000000000000000000e+00 +6.681250410781233029e+01,4.029041205650829056e+02,6.290831111995964786e-02,5.515980990693384989e+00,-5.631829027070570093e-02,1.454582900231767006e-01,6.839316092015533532e-02,1.000000008888749514e+00,0.000000000000000000e+00 +6.681431702196429967e+01,4.029141047105250095e+02,6.234542588258762397e-02,5.516244694085888689e+00,-5.606829027070570071e-02,1.472712041912566105e-01,6.839316092015533532e-02,1.000000008999655243e+00,0.000000000000000000e+00 +6.681612984945013523e+01,4.029240889963764403e+02,6.178503669914029578e-02,5.516511671372717807e+00,-5.581829027070570048e-02,1.490840316934009258e-01,6.839316092015533532e-02,1.000000009267763446e+00,0.000000000000000000e+00 +6.681794258920230334e+01,4.029340734220131708e+02,6.122714360464198702e-02,5.516781921923382015e+00,-5.556829027070570026e-02,1.508967714623696832e-01,6.839316092015533532e-02,1.000000009042619542e+00,0.000000000000000000e+00 +6.681975524015381040e+01,4.029440579868111740e+02,6.067174663396101425e-02,5.517055445099751765e+00,-5.531829027070570004e-02,1.527094224302621706e-01,6.839316092015533532e-02,1.000000009272198120e+00,0.000000000000000000e+00 +6.682156780123816020e+01,4.029540426901463661e+02,6.011884582180969383e-02,5.517332240256062725e+00,-5.506829027070569982e-02,1.545219835314205759e-01,6.839316092015533532e-02,1.000000008989168743e+00,0.000000000000000000e+00 +6.682338027138941072e+01,4.029640275313947200e+02,5.956844120274432108e-02,5.517612306738925554e+00,-5.481829027070569960e-02,1.563344536989643707e-01,6.839316092015533532e-02,1.000000008824871722e+00,0.000000000000000000e+00 +6.682519264954214577e+01,4.029740125099322086e+02,5.902053281116518418e-02,5.517895643887329449e+00,-5.456829027070569937e-02,1.581468318676942098e-01,6.839316092015533532e-02,1.000000009387936428e+00,0.000000000000000000e+00 +6.682700493463148916e+01,4.029839976251348048e+02,5.847512068131655721e-02,5.518182251032651031e+00,-5.431829027070569915e-02,1.599591169740566809e-01,6.839316092015533532e-02,1.000000009370901388e+00,0.000000000000000000e+00 +6.682881712559313314e+01,4.029939828763783680e+02,5.793220484728670017e-02,5.518472127498663227e+00,-5.406829027070569893e-02,1.617713079526778841e-01,6.839316092015533532e-02,1.000000008795141726e+00,0.000000000000000000e+00 +6.683062922136329576e+01,4.030039682630388711e+02,5.739178534300785200e-02,5.518765272601537930e+00,-5.381829027070569871e-02,1.635834037387780271e-01,6.839316092015533532e-02,1.000000009282082880e+00,0.000000000000000000e+00 +6.683244122087877770e+01,4.030139537844921733e+02,5.685386220225623066e-02,5.519061685649853111e+00,-5.356829027070569849e-02,1.653954032710768240e-01,6.839316092015533532e-02,1.000000008914025296e+00,0.000000000000000000e+00 +6.683425312307693389e+01,4.030239394401142476e+02,5.631843545865203304e-02,5.519361365944605247e+00,-5.331829027070569826e-02,1.672073054853864260e-01,6.839316092015533532e-02,1.000000009266783563e+00,0.000000000000000000e+00 +6.683606492689570189e+01,4.030339252292809533e+02,5.578550514565942808e-02,5.519664312779210213e+00,-5.306829027070569804e-02,1.690191093209478246e-01,6.839316092015533532e-02,1.000000009188176442e+00,0.000000000000000000e+00 +6.683787663127360190e+01,4.030439111513681496e+02,5.525507129658656369e-02,5.519970525439515718e+00,-5.281829027070569782e-02,1.708308137154939954e-01,6.839316092015533532e-02,1.000000009126386535e+00,0.000000000000000000e+00 +6.683968823514973678e+01,4.030538972057517526e+02,5.472713394458555286e-02,5.520280003203804853e+00,-5.256829027070569760e-02,1.726424176081556572e-01,6.839316092015533532e-02,1.000000009236486909e+00,0.000000000000000000e+00 +6.684149973746379203e+01,4.030638833918076216e+02,5.420169312265248063e-02,5.520592745342804974e+00,-5.231829027070569738e-02,1.744539199389361916e-01,6.839316092015533532e-02,1.000000009109445864e+00,0.000000000000000000e+00 +6.684331113715604999e+01,4.030738697089116158e+02,5.367874886362739711e-02,5.520908751119695701e+00,-5.206829027070569715e-02,1.762653196476958173e-01,6.839316092015533532e-02,1.000000009125689315e+00,0.000000000000000000e+00 +6.684512243316741831e+01,4.030838561564395945e+02,5.315830120019431754e-02,5.521228019790115127e+00,-5.181829027070569693e-02,1.780766156755877461e-01,6.839316092015533532e-02,1.000000009101658538e+00,0.000000000000000000e+00 +6.684693362443938724e+01,4.030938427337674170e+02,5.264035016488122221e-02,5.521550550602168705e+00,-5.156829027070569671e-02,1.798878069640425792e-01,6.839316092015533532e-02,1.000000009372743692e+00,0.000000000000000000e+00 +6.684874470991408657e+01,4.031038294402709425e+02,5.212489579006004958e-02,5.521876342796436354e+00,-5.131829027070569649e-02,1.816988924557142726e-01,6.839316092015533532e-02,1.000000008897964143e+00,0.000000000000000000e+00 +6.685055568853425711e+01,4.031138162753259735e+02,5.161193810794670322e-02,5.522205395605981337e+00,-5.106829027070569627e-02,1.835098710919934317e-01,6.839316092015533532e-02,1.000000009321854400e+00,0.000000000000000000e+00 +6.685236655924326499e+01,4.031238032383083123e+02,5.110147715060103096e-02,5.522537708256354705e+00,-5.081829027070569604e-02,1.853207418178768884e-01,6.839316092015533532e-02,1.000000009287712599e+00,0.000000000000000000e+00 +6.685417732098511578e+01,4.031337903285938182e+02,5.059351294992684572e-02,5.522873279965608617e+00,-5.056829027070569582e-02,1.871315035765384605e-01,6.839316092015533532e-02,1.000000009041335458e+00,0.000000000000000000e+00 +6.685598797270444038e+01,4.031437775455582937e+02,5.008804553767191164e-02,5.523212109944299897e+00,-5.031829027070569560e-02,1.889421553122370978e-01,6.839316092015533532e-02,1.000000009348246177e+00,0.000000000000000000e+00 +6.685779851334653756e+01,4.031537648885774843e+02,4.958507494542794408e-02,5.523554197395498910e+00,-5.006829027070569538e-02,1.907526959712637360e-01,6.839316092015533532e-02,1.000000009055243666e+00,0.000000000000000000e+00 +6.685960894185735981e+01,4.031637523570272492e+02,4.908460120463059573e-02,5.523899541514800227e+00,-4.981829027070569516e-02,1.925631244984732093e-01,6.839316092015533532e-02,1.000000009154594194e+00,0.000000000000000000e+00 +6.686141925718348489e+01,4.031737399502833341e+02,4.858662434655948437e-02,5.524248141490327058e+00,-4.956829027070569493e-02,1.943734398411746944e-01,6.839316092015533532e-02,1.000000009261656331e+00,0.000000000000000000e+00 +6.686322945827218689e+01,4.031837276677214845e+02,4.809114440233815818e-02,5.524599996502742805e+00,-4.931829027070569471e-02,1.961836409466447273e-01,6.839316092015533532e-02,1.000000009240656906e+00,0.000000000000000000e+00 +6.686503954407139361e+01,4.031937155087175029e+02,4.759816140293411657e-02,5.524955105725258164e+00,-4.906829027070569449e-02,1.979937267625837827e-01,6.839316092015533532e-02,1.000000009204834228e+00,0.000000000000000000e+00 +6.686684951352972917e+01,4.032037034726471916e+02,4.710767537915879627e-02,5.525313468323639121e+00,-4.881829027070569427e-02,1.998036962375729642e-01,6.839316092015533532e-02,1.000000009245633370e+00,0.000000000000000000e+00 +6.686865936559645718e+01,4.032136915588862394e+02,4.661968636166757135e-02,5.525675083456215830e+00,-4.856829027070569405e-02,2.016135483210404200e-01,6.839316092015533532e-02,1.000000009161411407e+00,0.000000000000000000e+00 +6.687046909922158022e+01,4.032236797668103918e+02,4.613419438095975322e-02,5.526039950273891499e+00,-4.831829027070569382e-02,2.034232819627367905e-01,6.839316092015533532e-02,1.000000009271128532e+00,0.000000000000000000e+00 +6.687227871335575458e+01,4.032336680957954513e+02,4.565119946737859757e-02,5.526408067920150380e+00,-4.806829027070569360e-02,2.052328961136832830e-01,6.839316092015533532e-02,1.000000009058263473e+00,0.000000000000000000e+00 +6.687408820695034706e+01,4.032436565452171067e+02,4.517070165111127661e-02,5.526779435531067541e+00,-4.781829027070569338e-02,2.070423897246655986e-01,6.839316092015533532e-02,1.000000009340906049e+00,0.000000000000000000e+00 +6.687589757895743503e+01,4.032536451144510465e+02,4.469270096218891375e-02,5.527154052235315973e+00,-4.756829027070569316e-02,2.088517617486548572e-01,6.839316092015533532e-02,1.000000009287955516e+00,0.000000000000000000e+00 +6.687770682832980640e+01,4.032636338028730165e+02,4.421719743048654894e-02,5.527531917154178132e+00,-4.731829027070569293e-02,2.106610111378292571e-01,6.839316092015533532e-02,1.000000009131645662e+00,0.000000000000000000e+00 +6.687951595402095961e+01,4.032736226098587053e+02,4.374419108572314557e-02,5.527913029401552159e+00,-4.706829027070569271e-02,2.124701368455040318e-01,6.839316092015533532e-02,1.000000009354346853e+00,0.000000000000000000e+00 +6.688132495498511787e+01,4.032836115347838586e+02,4.327368195746161134e-02,5.528297388083961650e+00,-4.681829027070569249e-02,2.142791378265896662e-01,6.839316092015533532e-02,1.000000009331429407e+00,0.000000000000000000e+00 +6.688313383017724334e+01,4.032936005770241081e+02,4.280567007510875654e-02,5.528684992300566314e+00,-4.656829027070569227e-02,2.160880130355950501e-01,6.839316092015533532e-02,1.000000008959391673e+00,0.000000000000000000e+00 +6.688494257855302294e+01,4.033035897359551996e+02,4.234015546791532886e-02,5.529075841143169079e+00,-4.631829027070569205e-02,2.178967614275761910e-01,6.839316092015533532e-02,1.000000009471072371e+00,0.000000000000000000e+00 +6.688675119906888256e+01,4.033135790109527647e+02,4.187713816497599245e-02,5.529469933696224970e+00,-4.606829027070569182e-02,2.197053819605589986e-01,6.839316092015533532e-02,1.000000009091525088e+00,0.000000000000000000e+00 +6.688855969068198704e+01,4.033235684013924924e+02,4.141661819522932803e-02,5.529867269036854438e+00,-4.581829027070569160e-02,2.215138735901048817e-01,6.839316092015533532e-02,1.000000009554385727e+00,0.000000000000000000e+00 +6.689036805235026861e+01,4.033335579066500713e+02,4.095859558745783280e-02,5.530267846234846907e+00,-4.556829027070569138e-02,2.233222352756622231e-01,6.839316092015533532e-02,1.000000009041765558e+00,0.000000000000000000e+00 +6.689217628303241270e+01,4.033435475261011334e+02,4.050307037028792051e-02,5.530671664352675876e+00,-4.531829027070569116e-02,2.251304659741492631e-01,6.839316092015533532e-02,1.000000009245520793e+00,0.000000000000000000e+00 +6.689398438168785788e+01,4.033535372591213104e+02,4.005004257218991448e-02,5.531078722445502471e+00,-4.506829027070569094e-02,2.269385646463067674e-01,6.839316092015533532e-02,1.000000009120300515e+00,0.000000000000000000e+00 +6.689579234727681012e+01,4.033635271050862343e+02,3.959951222147804761e-02,5.531489019561190545e+00,-4.481829027070569071e-02,2.287465302517540933e-01,6.839316092015533532e-02,1.000000009501457621e+00,0.000000000000000000e+00 +6.689760017876027121e+01,4.033735170633715938e+02,3.915147934631047627e-02,5.531902554740312894e+00,-4.456829027070569049e-02,2.305543617523954647e-01,6.839316092015533532e-02,1.000000009301417192e+00,0.000000000000000000e+00 +6.689940787510001030e+01,4.033835071333529640e+02,3.870594397468925252e-02,5.532319327016163690e+00,-4.431829027070569027e-02,2.323620581089491655e-01,6.839316092015533532e-02,1.000000009313893656e+00,0.000000000000000000e+00 +6.690121543525857817e+01,4.033934973144059768e+02,3.826290613446033106e-02,5.532739335414764703e+00,-4.406829027070569005e-02,2.341696182843543694e-01,6.839316092015533532e-02,1.000000008952973474e+00,0.000000000000000000e+00 +6.690302285819932138e+01,4.034034876059062640e+02,3.782236585331358314e-02,5.533162578954877731e+00,-4.381829027070568983e-02,2.359770412412828255e-01,6.839316092015533532e-02,1.000000009515186861e+00,0.000000000000000000e+00 +6.690483014288638230e+01,4.034134780072294006e+02,3.738432315878277568e-02,5.533589056648012594e+00,-4.356829027070568960e-02,2.377843259455469649e-01,6.839316092015533532e-02,1.000000009285603175e+00,0.000000000000000000e+00 +6.690663728828471335e+01,4.034234685177510187e+02,3.694877807824557131e-02,5.534018767498441349e+00,-4.331829027070568938e-02,2.395914713606626945e-01,6.839316092015533532e-02,1.000000009247673960e+00,0.000000000000000000e+00 +6.690844429336007693e+01,4.034334591368466931e+02,3.651573063892354226e-02,5.534451710503202726e+00,-4.306829027070568916e-02,2.413984764527319915e-01,6.839316092015533532e-02,1.000000009548907220e+00,0.000000000000000000e+00 +6.691025115707903126e+01,4.034434498638920559e+02,3.608518086788215645e-02,5.534887884652115453e+00,-4.281829027070568894e-02,2.432053401889375521e-01,6.839316092015533532e-02,1.000000008955908681e+00,0.000000000000000000e+00 +6.691205787840897301e+01,4.034534406982626251e+02,3.565712879203077057e-02,5.535327288927788913e+00,-4.256829027070568872e-02,2.450120615350534214e-01,6.839316092015533532e-02,1.000000009479903307e+00,0.000000000000000000e+00 +6.691386445631810886e+01,4.034634316393340328e+02,3.523157443812263701e-02,5.535769922305629365e+00,-4.231829027070568849e-02,2.468186394613129664e-01,6.839316092015533532e-02,1.000000009302490334e+00,0.000000000000000000e+00 +6.691567088977548394e+01,4.034734226864817970e+02,3.480851783275490385e-02,5.536215783753856812e+00,-4.206829027070568827e-02,2.486250729354953504e-01,6.839316092015533532e-02,1.000000009033909620e+00,0.000000000000000000e+00 +6.691747717775099602e+01,4.034834138390814928e+02,3.438795900236860797e-02,5.536664872233509449e+00,-4.181829027070568805e-02,2.504313609273189911e-01,6.839316092015533532e-02,1.000000009536918366e+00,0.000000000000000000e+00 +6.691928331921535289e+01,4.034934050965086385e+02,3.396989797324868193e-02,5.537117186698456095e+00,-4.156829027070568783e-02,2.522375024089028583e-01,6.839316092015533532e-02,1.000000009476383234e+00,0.000000000000000000e+00 +6.692108931314014342e+01,4.035033964581388091e+02,3.355433477152393318e-02,5.537572726095409514e+00,-4.131829027070568761e-02,2.540434963508021449e-01,6.839316092015533532e-02,1.000000009130098011e+00,0.000000000000000000e+00 +6.692289515849778070e+01,4.035133879233475795e+02,3.314126942316706487e-02,5.538031489363932636e+00,-4.106829027070568738e-02,2.558493417249272928e-01,6.839316092015533532e-02,1.000000009301190040e+00,0.000000000000000000e+00 +6.692470085426155890e+01,4.035233794915104681e+02,3.273070195399466198e-02,5.538493475436450098e+00,-4.081829027070568716e-02,2.576550375054979525e-01,6.839316092015533532e-02,1.000000009138694912e+00,0.000000000000000000e+00 +6.692650639940562485e+01,4.035333711620029931e+02,3.232263238966719132e-02,5.538958683238261571e+00,-4.056829027070568694e-02,2.594605826660614789e-01,6.839316092015533532e-02,1.000000009678667645e+00,0.000000000000000000e+00 +6.692831179290499222e+01,4.035433629342006157e+02,3.191706075568899459e-02,5.539427111687549754e+00,-4.031829027070568672e-02,2.612659761829057570e-01,6.839316092015533532e-02,1.000000009212772101e+00,0.000000000000000000e+00 +6.693011703373556998e+01,4.035533548074789110e+02,3.151398707740830918e-02,5.539898759695394581e+00,-4.006829027070568650e-02,2.630712170301097719e-01,6.839316092015533532e-02,1.000000009282841607e+00,0.000000000000000000e+00 +6.693192212087411974e+01,4.035633467812133972e+02,3.111341138001723003e-02,5.540373626165778553e+00,-3.981829027070568627e-02,2.648763041854169664e-01,6.839316092015533532e-02,1.000000009231237996e+00,0.000000000000000000e+00 +6.693372705329831263e+01,4.035733388547795357e+02,3.071533368855174431e-02,5.540851709995602725e+00,-3.956829027070568605e-02,2.666812366262698575e-01,6.839316092015533532e-02,1.000000009470933149e+00,0.000000000000000000e+00 +6.693553182998670081e+01,4.035833310275528447e+02,3.031975402789170368e-02,5.541333010074695586e+00,-3.931829027070568583e-02,2.684860133317480968e-01,6.839316092015533532e-02,1.000000009304865767e+00,0.000000000000000000e+00 +6.693733644991873177e+01,4.035933232989088424e+02,2.992667242276083814e-02,5.541817525285825496e+00,-3.906829027070568561e-02,2.702906332805704581e-01,6.839316092015533532e-02,1.000000009380038302e+00,0.000000000000000000e+00 +6.693914091207476247e+01,4.036033156682229901e+02,2.953608889772674911e-02,5.542305254504709566e+00,-3.881829027070568539e-02,2.720950954535260036e-01,6.839316092015533532e-02,1.000000009233325438e+00,0.000000000000000000e+00 +6.694094521543605936e+01,4.036133081348707492e+02,2.914800347720090598e-02,5.542796196600026981e+00,-3.856829027070568516e-02,2.738993988314760708e-01,6.839316092015533532e-02,1.000000009473417828e+00,0.000000000000000000e+00 +6.694274935898478418e+01,4.036233006982275811e+02,2.876241618543864606e-02,5.543290350433428770e+00,-3.831829027070568494e-02,2.757035423972936661e-01,6.839316092015533532e-02,1.000000009325928696e+00,0.000000000000000000e+00 +6.694455334170403660e+01,4.036332933576689470e+02,2.837932704653917809e-02,5.543787714859551130e+00,-3.806829027070568472e-02,2.775075251333734005e-01,6.839316092015533532e-02,1.000000009361349695e+00,0.000000000000000000e+00 +6.694635716257783997e+01,4.036432861125703653e+02,2.799873608444557183e-02,5.544288288726024305e+00,-3.781829027070568450e-02,2.793113460240632673e-01,6.839316092015533532e-02,1.000000009312895122e+00,0.000000000000000000e+00 +6.694816082059114137e+01,4.036532789623072404e+02,2.762064332294476149e-02,5.544792070873485912e+00,-3.756829027070568428e-02,2.811150040541594564e-01,6.839316092015533532e-02,1.000000009440540572e+00,0.000000000000000000e+00 +6.694996431472981158e+01,4.036632719062550336e+02,2.724504878566754579e-02,5.545299060135591596e+00,-3.731829027070568405e-02,2.829184982098618684e-01,6.839316092015533532e-02,1.000000009439441007e+00,0.000000000000000000e+00 +6.695176764398068769e+01,4.036732649437891496e+02,2.687195249608858097e-02,5.545809255339027466e+00,-3.706829027070568383e-02,2.847218274777607028e-01,6.839316092015533532e-02,1.000000008985815425e+00,0.000000000000000000e+00 +6.695357080733153055e+01,4.036832580742850496e+02,2.650135447752638429e-02,5.546322655303520754e+00,-3.681829027070568361e-02,2.865249908448078142e-01,6.839316092015533532e-02,1.000000009649418820e+00,0.000000000000000000e+00 +6.695537380377106729e+01,4.036932512971181950e+02,2.613325475314333401e-02,5.546839258841850473e+00,-3.656829027070568339e-02,2.883279873017362549e-01,6.839316092015533532e-02,1.000000009430050296e+00,0.000000000000000000e+00 +6.695717663228896299e+01,4.037032446116639903e+02,2.576765334594566248e-02,5.547359064759864289e+00,-3.631829027070568316e-02,2.901308158366284751e-01,6.839316092015533532e-02,1.000000009314008675e+00,0.000000000000000000e+00 +6.695897929187584907e+01,4.037132380172978401e+02,2.540455027878345956e-02,5.547882071856483854e+00,-3.606829027070568294e-02,2.919334754403065668e-01,6.839316092015533532e-02,1.000000009176395865e+00,0.000000000000000000e+00 +6.696078178152333749e+01,4.037232315133951488e+02,2.504394557435066573e-02,5.548408278923719905e+00,-3.581829027070568272e-02,2.937359651043339182e-01,6.839316092015533532e-02,1.000000009694136383e+00,0.000000000000000000e+00 +6.696258410022399232e+01,4.037332250993313210e+02,2.468583925518507208e-02,5.548937684746683807e+00,-3.556829027070568250e-02,2.955382838224656639e-01,6.839316092015533532e-02,1.000000009064976991e+00,0.000000000000000000e+00 +6.696438624697137243e+01,4.037432187744818179e+02,2.433023134366832721e-02,5.549470288103601767e+00,-3.531829027070568228e-02,2.973404305861855890e-01,6.839316092015533532e-02,1.000000009570121584e+00,0.000000000000000000e+00 +6.696618822076001720e+01,4.037532125382219874e+02,2.397712186202592341e-02,5.550006087765821050e+00,-3.506829027070568205e-02,2.991424043920708487e-01,6.839316092015533532e-02,1.000000009370511922e+00,0.000000000000000000e+00 +6.696799002058543238e+01,4.037632063899271770e+02,2.362651083232720356e-02,5.550545082497829519e+00,-3.481829027070568183e-02,3.009442042343716817e-01,6.839316092015533532e-02,1.000000009344064633e+00,0.000000000000000000e+00 +6.696979164544413266e+01,4.037732003289728482e+02,2.327839827648535420e-02,5.551087271057261852e+00,-3.456829027070568161e-02,3.027458291099128229e-01,6.839316092015533532e-02,1.000000009530235934e+00,0.000000000000000000e+00 +6.697159309433364172e+01,4.037831943547343485e+02,2.293278421625741248e-02,5.551632652194914641e+00,-3.431829027070568139e-02,3.045472780165875970e-01,6.839316092015533532e-02,1.000000009129409229e+00,0.000000000000000000e+00 +6.697339436625246378e+01,4.037931884665870257e+02,2.258966867324425920e-02,5.552181224654758829e+00,-3.406829027070568117e-02,3.063485499518516231e-01,6.839316092015533532e-02,1.000000009513926535e+00,0.000000000000000000e+00 +6.697519546020011205e+01,4.038031826639062842e+02,2.224905166889061189e-02,5.552732987173949475e+00,-3.381829027070568094e-02,3.081496439166404033e-01,6.839316092015533532e-02,1.000000009574739002e+00,0.000000000000000000e+00 +6.697699637517713711e+01,4.038131769460674718e+02,2.191093322448503522e-02,5.553287938482842634e+00,-3.356829027070568072e-02,3.099505589109046721e-01,6.839316092015533532e-02,1.000000009279862656e+00,0.000000000000000000e+00 +6.697879711018508431e+01,4.038231713124459361e+02,2.157531336115993056e-02,5.553846077305004236e+00,-3.331829027070568050e-02,3.117512939355557844e-01,6.839316092015533532e-02,1.000000009401613488e+00,0.000000000000000000e+00 +6.698059766422652217e+01,4.038331657624170816e+02,2.124219209989154297e-02,5.554407402357222523e+00,-3.306829027070568028e-02,3.135518479939189973e-01,6.839316092015533532e-02,1.000000009325310080e+00,0.000000000000000000e+00 +6.698239803630505662e+01,4.038431602953561992e+02,2.091156946149994728e-02,5.554971912349523144e+00,-3.281829027070568006e-02,3.153522200892408534e-01,6.839316092015533532e-02,1.000000009240640031e+00,0.000000000000000000e+00 +6.698419822542531676e+01,4.038531549106386365e+02,2.058344546664905850e-02,5.555539605985179819e+00,-3.256829027070567983e-02,3.171524092261426842e-01,6.839316092015533532e-02,1.000000009868254436e+00,0.000000000000000000e+00 +6.698599823059299752e+01,4.038631496076397411e+02,2.025782013584662838e-02,5.556110481960727654e+00,-3.231829027070567961e-02,3.189524144115812310e-01,6.839316092015533532e-02,1.000000009170346260e+00,0.000000000000000000e+00 +6.698779805081480276e+01,4.038731443857348609e+02,1.993469348944423847e-02,5.556684538965978248e+00,-3.206829027070567939e-02,3.207522346498883903e-01,6.839316092015533532e-02,1.000000009203791285e+00,0.000000000000000000e+00 +6.698959768509850221e+01,4.038831392442992865e+02,1.961406554763730353e-02,5.557261775684025906e+00,-3.181829027070567917e-02,3.225518689501466474e-01,6.839316092015533532e-02,1.000000009815873225e+00,0.000000000000000000e+00 +6.699139713245290295e+01,4.038931341827083656e+02,1.929593633046507162e-02,5.557842190791267178e+00,-3.156829027070567895e-02,3.243513163222164764e-01,6.839316092015533532e-02,1.000000009190344485e+00,0.000000000000000000e+00 +6.699319639188789210e+01,4.039031292003373892e+02,1.898030585781061708e-02,5.558425782957413297e+00,-3.131829027070567872e-02,3.261505757737482858e-01,6.839316092015533532e-02,1.000000009334423012e+00,0.000000000000000000e+00 +6.699499546241442260e+01,4.039131242965617048e+02,1.866717414940084405e-02,5.559012550845497280e+00,-3.106829027070567850e-02,3.279496463170674114e-01,6.839316092015533532e-02,1.000000009495525033e+00,0.000000000000000000e+00 +6.699679434304448478e+01,4.039231194707566033e+02,1.835654122480648645e-02,5.559602493111893473e+00,-3.081829027070567828e-02,3.297485269642129735e-01,6.839316092015533532e-02,1.000000009727161077e+00,0.000000000000000000e+00 +6.699859303279116318e+01,4.039331147222973755e+02,1.804840710344210106e-02,5.560195608406328205e+00,-3.056829027070567806e-02,3.315472167283932681e-01,6.839316092015533532e-02,1.000000008967820486e+00,0.000000000000000000e+00 +6.700039153066862241e+01,4.039431100505593122e+02,1.774277180456606748e-02,5.560791895371893112e+00,-3.031829027070567784e-02,3.333457146219852563e-01,6.839316092015533532e-02,1.000000009708981175e+00,0.000000000000000000e+00 +6.700218983569210707e+01,4.039531054549177043e+02,1.743963534728059511e-02,5.561391352645054909e+00,-3.006829027070567761e-02,3.351440196629296153e-01,6.839316092015533532e-02,1.000000009483013486e+00,0.000000000000000000e+00 +6.700398794687794179e+01,4.039631009347478994e+02,1.713899775053171273e-02,5.561993978855676701e+00,-2.981829027070567739e-02,3.369421308658166470e-01,6.839316092015533532e-02,1.000000009375670018e+00,0.000000000000000000e+00 +6.700578586324354546e+01,4.039730964894251315e+02,1.684085903310926849e-02,5.562599772627023320e+00,-2.956829027070567717e-02,3.387400472482817171e-01,6.839316092015533532e-02,1.000000009358023023e+00,0.000000000000000000e+00 +6.700758358380744539e+01,4.039830921183246346e+02,1.654521921364693338e-02,5.563208732575778193e+00,-2.931829027070567695e-02,3.405377678290053556e-01,6.839316092015533532e-02,1.000000009384777178e+00,0.000000000000000000e+00 +6.700938110758926314e+01,4.039930878208217564e+02,1.625207831062219430e-02,5.563820857312056667e+00,-2.906829027070567673e-02,3.423352916276886648e-01,6.839316092015533532e-02,1.000000009394668821e+00,0.000000000000000000e+00 +6.701117843360971449e+01,4.040030835962917308e+02,1.596143634235635753e-02,5.564436145439419334e+00,-2.881829027070567650e-02,3.441326176650294499e-01,6.839316092015533532e-02,1.000000009584977700e+00,0.000000000000000000e+00 +6.701297556089065210e+01,4.040130794441098487e+02,1.567329332701454872e-02,5.565054595554885353e+00,-2.856829027070567628e-02,3.459297449631916765e-01,6.839316092015533532e-02,1.000000009587287630e+00,0.000000000000000000e+00 +6.701477248845502288e+01,4.040230753636513441e+02,1.538764928260570423e-02,5.565676206248946656e+00,-2.831829027070567606e-02,3.477266725447935580e-01,6.839316092015533532e-02,1.000000009291911240e+00,0.000000000000000000e+00 +6.701656921532691058e+01,4.040330713542914509e+02,1.510450422698257633e-02,5.566300976105580389e+00,-2.806829027070567584e-02,3.495233994333774574e-01,6.839316092015533532e-02,1.000000009398881895e+00,0.000000000000000000e+00 +6.701836574053152162e+01,4.040430674154054600e+02,1.482385817784173145e-02,5.566928903702262232e+00,-2.781829027070567562e-02,3.513199246548693866e-01,6.839316092015533532e-02,1.000000009492103104e+00,0.000000000000000000e+00 +6.702016206309518509e+01,4.040530635463686053e+02,1.454571115272354845e-02,5.567559987609982386e+00,-2.756829027070567539e-02,3.531162472355782178e-01,6.839316092015533532e-02,1.000000009414794500e+00,0.000000000000000000e+00 +6.702195818204536693e+01,4.040630597465561209e+02,1.427006316901221518e-02,5.568194226393258006e+00,-2.731829027070567517e-02,3.549123662026664738e-01,6.839316092015533532e-02,1.000000009545175539e+00,0.000000000000000000e+00 +6.702375409641066994e+01,4.040730560153432407e+02,1.399691424393573018e-02,5.568831618610146528e+00,-2.706829027070567495e-02,3.567082805851159444e-01,6.839316092015533532e-02,1.000000009420029645e+00,0.000000000000000000e+00 +6.702554980522086225e+01,4.040830523521051987e+02,1.372626439456590269e-02,5.569472162812260763e+00,-2.681829027070567473e-02,3.585039894122210580e-01,6.839316092015533532e-02,1.000000009386857736e+00,0.000000000000000000e+00 +6.702734530750683462e+01,4.040930487562172857e+02,1.345811363781834746e-02,5.570115857544781335e+00,-2.656829027070567451e-02,3.602994917150495469e-01,6.839316092015533532e-02,1.000000009502599152e+00,0.000000000000000000e+00 +6.702914060230065729e+01,4.041030452270546220e+02,1.319246199045248646e-02,5.570762701346471779e+00,-2.631829027070567428e-02,3.620947865259251386e-01,6.839316092015533532e-02,1.000000009533444034e+00,0.000000000000000000e+00 +6.703093568863552321e+01,4.041130417639924985e+02,1.292930946907154717e-02,5.571412692749692752e+00,-2.606829027070567406e-02,3.638898728779101921e-01,6.839316092015533532e-02,1.000000009505833232e+00,0.000000000000000000e+00 +6.703273056554583320e+01,4.041230383664061492e+02,1.266865609012256255e-02,5.572065830280415355e+00,-2.581829027070567384e-02,3.656847498052775980e-01,6.839316092015533532e-02,1.000000009431333048e+00,0.000000000000000000e+00 +6.703452523206712499e+01,4.041330350336706942e+02,1.241050186989636935e-02,5.572722112458235344e+00,-2.556829027070567362e-02,3.674794163434886296e-01,6.839316092015533532e-02,1.000000009306480031e+00,0.000000000000000000e+00 +6.703631968723610157e+01,4.041430317651614246e+02,1.215484682452760458e-02,5.573381537796387342e+00,-2.531829027070567339e-02,3.692738715291705165e-01,6.839316092015533532e-02,1.000000009664787415e+00,0.000000000000000000e+00 +6.703811393009067388e+01,4.041530285602535173e+02,1.190169096999471078e-02,5.574044104801759048e+00,-2.506829027070567317e-02,3.710681144010844479e-01,6.839316092015533532e-02,1.000000009369752973e+00,0.000000000000000000e+00 +6.703990795966991811e+01,4.041630254183221496e+02,1.165103432211992730e-02,5.574709811974907225e+00,-2.481829027070567295e-02,3.728621439971335771e-01,6.839316092015533532e-02,1.000000009753316599e+00,0.000000000000000000e+00 +6.704170177501409000e+01,4.041730223387425553e+02,1.140287689656929379e-02,5.575378657810068361e+00,-2.456829027070567273e-02,3.746559593587964199e-01,6.839316092015533532e-02,1.000000009097147480e+00,0.000000000000000000e+00 +6.704349537516463897e+01,4.041830193208899118e+02,1.115721870885265192e-02,5.576050640795177316e+00,-2.431829027070567251e-02,3.764495595256592275e-01,6.839316092015533532e-02,1.000000009532821865e+00,0.000000000000000000e+00 +6.704528875916420816e+01,4.041930163641393960e+02,1.091405977432363672e-02,5.576725759411876204e+00,-2.406829027070567228e-02,3.782429435423262931e-01,6.839316092015533532e-02,1.000000009588922989e+00,0.000000000000000000e+00 +6.704708192605664863e+01,4.042030134678662421e+02,1.067340010817968005e-02,5.577404012135535716e+00,-2.381829027070567206e-02,3.800361104519617839e-01,6.839316092015533532e-02,1.000000009712187055e+00,0.000000000000000000e+00 +6.704887487488700515e+01,4.042130106314455702e+02,1.043523972546201231e-02,5.578085397435264881e+00,-2.356829027070567184e-02,3.818290592997345967e-01,6.839316092015533532e-02,1.000000009230061160e+00,0.000000000000000000e+00 +6.705066760470154463e+01,4.042230078542526144e+02,1.019957864105565902e-02,5.578769913773927058e+00,-2.331829027070567162e-02,3.836217891308157935e-01,6.839316092015533532e-02,1.000000009390132227e+00,0.000000000000000000e+00 +6.705246011454772770e+01,4.042330051356624949e+02,9.966416869689435562e-03,5.579457559608152373e+00,-2.306829027070567140e-02,3.854142989938254549e-01,6.839316092015533532e-02,1.000000009768571951e+00,0.000000000000000000e+00 +6.705425240347423710e+01,4.042430024750503890e+02,9.735754425935954151e-03,5.580148333388356363e+00,-2.281829027070567117e-02,3.872065879378402964e-01,6.839316092015533532e-02,1.000000009097047560e+00,0.000000000000000000e+00 +6.705604447053097772e+01,4.042529998717914737e+02,9.507591324211615152e-03,5.580842233558753307e+00,-2.256829027070567095e-02,3.889986550108849861e-01,6.839316092015533532e-02,1.000000009965292813e+00,0.000000000000000000e+00 +6.705783631476909079e+01,4.042629973252609261e+02,9.281927578776614021e-03,5.581539258557366878e+00,-2.231829027070567073e-02,3.907904992668506661e-01,6.839316092015533532e-02,1.000000009140876722e+00,0.000000000000000000e+00 +6.705962793524092547e+01,4.042729948348339235e+02,9.058763203734934363e-03,5.582239406816053240e+00,-2.206829027070567051e-02,3.925821197550658503e-01,6.839316092015533532e-02,1.000000009740378060e+00,0.000000000000000000e+00 +6.706141933100008146e+01,4.042829923998855861e+02,8.838098213034351405e-03,5.582942676760505485e+00,-2.181829027070567029e-02,3.943735155316772101e-01,6.839316092015533532e-02,1.000000009332989492e+00,0.000000000000000000e+00 +6.706321050110140902e+01,4.042929900197910342e+02,8.619932620466425055e-03,5.583649066810278505e+00,-2.156829027070567006e-02,3.961646856497147429e-01,6.839316092015533532e-02,1.000000009348690044e+00,0.000000000000000000e+00 +6.706500144460096635e+01,4.043029876939255018e+02,8.404266439666505106e-03,5.584358575378796097e+00,-2.131829027070566984e-02,3.979556291660126810e-01,6.839316092015533532e-02,1.000000009820868341e+00,0.000000000000000000e+00 +6.706679216055607640e+01,4.043129854216640524e+02,8.191099684113727769e-03,5.585071200873370501e+00,-2.106829027070566962e-02,3.997463451387115452e-01,6.839316092015533532e-02,1.000000009383992028e+00,0.000000000000000000e+00 +6.706858264802532688e+01,4.043229832023818631e+02,7.980432367131013935e-03,5.585786941695217500e+00,-2.081829027070566940e-02,4.015368326247575892e-01,6.839316092015533532e-02,1.000000009429319325e+00,0.000000000000000000e+00 +6.707037290606852764e+01,4.043329810354540541e+02,7.772264501885072646e-03,5.586505796239467081e+00,-2.056829027070566918e-02,4.033270906848436255e-01,6.839316092015533532e-02,1.000000009673449153e+00,0.000000000000000000e+00 +6.707216293374678173e+01,4.043429789202558027e+02,7.566596101386395025e-03,5.587227762895182970e+00,-2.031829027070566895e-02,4.051171183804142539e-01,6.839316092015533532e-02,1.000000009542124202e+00,0.000000000000000000e+00 +6.707395273012244274e+01,4.043529768561622291e+02,7.363427178489256007e-03,5.587952840045376846e+00,-2.006829027070566873e-02,4.069069147731497194e-01,6.839316092015533532e-02,1.000000009279520263e+00,0.000000000000000000e+00 +6.707574229425912904e+01,4.043629748425484536e+02,7.162757745891712609e-03,5.588681026067021662e+00,-1.981829027070566851e-02,4.086964789264352360e-01,6.839316092015533532e-02,1.000000009672367796e+00,0.000000000000000000e+00 +6.707753162522172374e+01,4.043729728787895965e+02,6.964587816135604792e-03,5.589412319331067636e+00,-1.956829027070566829e-02,4.104858099063357080e-01,6.839316092015533532e-02,1.000000009552887148e+00,0.000000000000000000e+00 +6.707932072207640317e+01,4.043829709642607781e+02,6.768917401606553731e-03,5.590146718202460008e+00,-1.931829027070566807e-02,4.122749067781023014e-01,6.839316092015533532e-02,1.000000009404625967e+00,0.000000000000000000e+00 +6.708110958389060841e+01,4.043929690983371188e+02,6.575746514533959211e-03,5.590884221040150592e+00,-1.906829027070566784e-02,4.140637686091316327e-01,6.839316092015533532e-02,1.000000009421807556e+00,0.000000000000000000e+00 +6.708289820973307371e+01,4.044029672803937387e+02,6.385075166991002228e-03,5.591624826197114650e+00,-1.881829027070566762e-02,4.158523944684519025e-01,6.839316092015533532e-02,1.000000009786058186e+00,0.000000000000000000e+00 +6.708468659867382655e+01,4.044129655098057583e+02,6.196903370894641522e-03,5.592368532020366878e+00,-1.856829027070566740e-02,4.176407834267042429e-01,6.839316092015533532e-02,1.000000009278096735e+00,0.000000000000000000e+00 +6.708647474978417335e+01,4.044229637859482978e+02,6.011231138005614441e-03,5.593115336850977393e+00,-1.831829027070566718e-02,4.194289345536415525e-01,6.839316092015533532e-02,1.000000009721460081e+00,0.000000000000000000e+00 +6.708826266213672795e+01,4.044329621081964206e+02,5.828058479928436078e-03,5.593865239024083280e+00,-1.806829027070566696e-02,4.212168469235739732e-01,6.839316092015533532e-02,1.000000009316213134e+00,0.000000000000000000e+00 +6.709005033480539737e+01,4.044429604759252470e+02,5.647385408111396665e-03,5.594618236868909911e+00,-1.781829027070566673e-02,4.230045196088935699e-01,6.839316092015533532e-02,1.000000009584710359e+00,0.000000000000000000e+00 +6.709183776686539602e+01,4.044529588885098974e+02,5.469211933846563310e-03,5.595374328708780709e+00,-1.756829027070566651e-02,4.247919516860184097e-01,6.839316092015533532e-02,1.000000009814124180e+00,0.000000000000000000e+00 +6.709362495739323151e+01,4.044629573453254920e+02,5.293538068269778261e-03,5.596133512861137582e+00,-1.731829027070566629e-02,4.265791422314003656e-01,6.839316092015533532e-02,1.000000009279060853e+00,0.000000000000000000e+00 +6.709541190546676148e+01,4.044729558457470944e+02,5.120363822360658040e-03,5.596895787637554243e+00,-1.706829027070566607e-02,4.283660903215072979e-01,6.839316092015533532e-02,1.000000009467157280e+00,0.000000000000000000e+00 +6.709719861016512255e+01,4.044829543891497678e+02,4.949689206942593442e-03,5.597661151343749530e+00,-1.681829027070566585e-02,4.301527950367817210e-01,6.839316092015533532e-02,1.000000009629822273e+00,0.000000000000000000e+00 +6.709898507056878714e+01,4.044929529749086896e+02,4.781514232682746932e-03,5.598429602279607842e+00,-1.656829027070566562e-02,4.319392554576483301e-01,6.839316092015533532e-02,1.000000009562654668e+00,0.000000000000000000e+00 +6.710077128575954930e+01,4.045029516023988663e+02,4.615838910092055249e-03,5.599201138739192452e+00,-1.631829027070566540e-02,4.337254706654906644e-01,6.839316092015533532e-02,1.000000009606386575e+00,0.000000000000000000e+00 +6.710255725482052469e+01,4.045129502709954181e+02,4.452663249525225068e-03,5.599975759010760612e+00,-1.606829027070566518e-02,4.355114397436287699e-01,6.839316092015533532e-02,1.000000009255108013e+00,0.000000000000000000e+00 +6.710434297683617899e+01,4.045229489800734086e+02,4.291987261180735605e-03,5.600753461376780429e+00,-1.581829027070566496e-02,4.372971617758108498e-01,6.839316092015533532e-02,1.000000009941363732e+00,0.000000000000000000e+00 +6.710612845089229950e+01,4.045329477290079581e+02,4.133810955100836008e-03,5.601534244113945071e+00,-1.556829027070566474e-02,4.390826358496786597e-01,6.839316092015533532e-02,1.000000009186378991e+00,0.000000000000000000e+00 +6.710791367607600932e+01,4.045429465171741299e+02,3.978134341171545366e-03,5.602318105493193201e+00,-1.531829027070566451e-02,4.408678610497873129e-01,6.839316092015533532e-02,1.000000009793941436e+00,0.000000000000000000e+00 +6.710969865147578162e+01,4.045529453439469876e+02,3.824957429122652266e-03,5.603105043779716965e+00,-1.506829027070566429e-02,4.426528364670407889e-01,6.839316092015533532e-02,1.000000009262096201e+00,0.000000000000000000e+00 +6.711148337618143955e+01,4.045629442087015946e+02,3.674280228527713500e-03,5.603895057232986865e+00,-1.481829027070566407e-02,4.444375611892236178e-01,6.839316092015533532e-02,1.000000009816665703e+00,0.000000000000000000e+00 +6.711326784928414213e+01,4.045729431108130711e+02,3.526102748804054061e-03,5.604688144106759751e+00,-1.456829027070566385e-02,4.462220343094437380e-01,6.839316092015533532e-02,1.000000009490130903e+00,0.000000000000000000e+00 +6.711505206987641259e+01,4.045829420496564239e+02,3.380424999212766277e-03,5.605484302649101913e+00,-1.431829027070566362e-02,4.480062549186521470e-01,6.839316092015533532e-02,1.000000009651030641e+00,0.000000000000000000e+00 +6.711683603705213841e+01,4.045929410246067732e+02,3.237246988858709373e-03,5.606283531102398854e+00,-1.406829027070566340e-02,4.497902221116000243e-01,6.839316092015533532e-02,1.000000009425295211e+00,0.000000000000000000e+00 +6.711861974990657131e+01,4.046029400350391256e+02,3.096568726690509046e-03,5.607085827703375713e+00,-1.381829027070566318e-02,4.515739349828408744e-01,6.839316092015533532e-02,1.000000009323839256e+00,0.000000000000000000e+00 +6.712040320753631306e+01,4.046129390803286014e+02,2.958390221500556590e-03,5.607891190683110594e+00,-1.356829027070566296e-02,4.533573926292051581e-01,6.839316092015533532e-02,1.000000009847413107e+00,0.000000000000000000e+00 +6.712218640903932965e+01,4.046229381598502073e+02,2.822711481925008897e-03,5.608699618267052323e+00,-1.331829027070566274e-02,4.551405941497853047e-01,6.839316092015533532e-02,1.000000009531388789e+00,0.000000000000000000e+00 +6.712396935351497973e+01,4.046329372729790634e+02,2.689532516443786728e-03,5.609511108675038216e+00,-1.306829027070566251e-02,4.569235386424346790e-01,6.839316092015533532e-02,1.000000009414269808e+00,0.000000000000000000e+00 +6.712575204006400043e+01,4.046429364190901765e+02,2.558853333380575572e-03,5.610325660121305624e+00,-1.281829027070566229e-02,4.587062252082350078e-01,6.839316092015533532e-02,1.000000009687030511e+00,0.000000000000000000e+00 +6.712753446778849309e+01,4.046529355975586100e+02,2.430673940902824352e-03,5.611143270814511474e+00,-1.256829027070566207e-02,4.604886529499882530e-01,6.839316092015533532e-02,1.000000009691922598e+00,0.000000000000000000e+00 +6.712931663579193753e+01,4.046629348077594273e+02,2.304994347021744987e-03,5.611963938957749143e+00,-1.231829027070566185e-02,4.622708209707074301e-01,6.839316092015533532e-02,1.000000009319719663e+00,0.000000000000000000e+00 +6.713109854317922043e+01,4.046729340490676350e+02,2.181814559592311960e-03,5.612787662748562667e+00,-1.206829027070566163e-02,4.640527283745982667e-01,6.839316092015533532e-02,1.000000009570549464e+00,0.000000000000000000e+00 +6.713288018905660692e+01,4.046829333208582966e+02,2.061134586313261886e-03,5.613614440378962733e+00,-1.181829027070566140e-02,4.658343742690393419e-01,6.839316092015533532e-02,1.000000009756578434e+00,0.000000000000000000e+00 +6.713466157253176902e+01,4.046929326225064756e+02,1.942954434727093291e-03,5.614444270035446216e+00,-1.156829027070566118e-02,4.676157577615776550e-01,6.839316092015533532e-02,1.000000009459341088e+00,0.000000000000000000e+00 +6.713644269271375720e+01,4.047029319533872354e+02,1.827274112220065531e-03,5.615277149899010389e+00,-1.131829027070566096e-02,4.693968779604126285e-01,6.839316092015533532e-02,1.000000009370567211e+00,0.000000000000000000e+00 +6.713822354871302878e+01,4.047129313128755825e+02,1.714093626022198790e-03,5.616113078145168025e+00,-1.106829027070566074e-02,4.711777339763771333e-01,6.839316092015533532e-02,1.000000009893197372e+00,0.000000000000000000e+00 +6.714000413964146219e+01,4.047229307003465806e+02,1.603412983207273216e-03,5.616952052943966045e+00,-1.081829027070566052e-02,4.729583249224260100e-01,6.839316092015533532e-02,1.000000009459720118e+00,0.000000000000000000e+00 +6.714178446461232852e+01,4.047329301151752929e+02,1.495232190692829134e-03,5.617794072460003285e+00,-1.056829027070566029e-02,4.747386499101310386e-01,6.839316092015533532e-02,1.000000009574604221e+00,0.000000000000000000e+00 +6.714356452274030573e+01,4.047429295567366694e+02,1.389551255240165963e-03,5.618639134852442041e+00,-1.031829027070566007e-02,4.765187080551543386e-01,6.839316092015533532e-02,1.000000009491997632e+00,0.000000000000000000e+00 +6.714534431314150709e+01,4.047529290244058302e+02,1.286370183454342217e-03,5.619487238275029384e+00,-1.006829027070565985e-02,4.782984984732450706e-01,6.839316092015533532e-02,1.000000009577898474e+00,0.000000000000000000e+00 +6.714712383493343850e+01,4.047629285175577820e+02,1.185688981784174638e-03,5.620338380876111373e+00,-9.818290270705659628e-03,4.800780202822221843e-01,6.839316092015533532e-02,1.000000009628590592e+00,0.000000000000000000e+00 +6.714890308723505541e+01,4.047729280355675314e+02,1.087507656522238627e-03,5.621192560798650817e+00,-9.568290270705659406e-03,4.818572726009637264e-01,6.839316092015533532e-02,1.000000009711854432e+00,0.000000000000000000e+00 +6.715068206916670590e+01,4.047829275778101419e+02,9.918262138048667288e-04,5.622049776180243263e+00,-9.318290270705659184e-03,4.836362545498933962e-01,6.839316092015533532e-02,1.000000009325175743e+00,0.000000000000000000e+00 +6.715246077985020179e+01,4.047929271436606200e+02,8.986446596121490642e-04,5.622910025153133873e+00,-9.068290270705658962e-03,4.854149652499694101e-01,6.839316092015533532e-02,1.000000009641717647e+00,0.000000000000000000e+00 +6.715423921840874755e+01,4.048029267324939724e+02,8.079629997679328973e-04,5.623773305844232517e+00,-8.818290270705658740e-03,4.871934038256684474e-01,6.839316092015533532e-02,1.000000009861209183e+00,0.000000000000000000e+00 +6.715601738396702558e+01,4.048129263436852625e+02,7.197812399398218755e-04,5.624639616375134210e+00,-8.568290270705658518e-03,4.889715694014785674e-01,6.839316092015533532e-02,1.000000009173524607e+00,0.000000000000000000e+00 +6.715779527565112517e+01,4.048229259766094970e+02,6.340993856391759220e-04,5.625508954862133315e+00,-8.318290270705658296e-03,4.907494611018858310e-01,6.839316092015533532e-02,1.000000009851302218e+00,0.000000000000000000e+00 +6.715957289258858509e+01,4.048329256306417392e+02,5.509174422211109102e-04,5.626381319416237758e+00,-8.068290270705658074e-03,4.925270780568584139e-01,6.839316092015533532e-02,1.000000009381796673e+00,0.000000000000000000e+00 +6.716135023390839365e+01,4.048429253051569390e+02,4.702354148844983383e-04,5.627256708143193009e+00,-7.818290270705657852e-03,4.943044193933420760e-01,6.839316092015533532e-02,1.000000009740825480e+00,0.000000000000000000e+00 +6.716312729874098864e+01,4.048529249995301598e+02,3.920533086719647873e-04,5.628135119143490961e+00,-7.568290270705657630e-03,4.960814842432426097e-01,6.839316092015533532e-02,1.000000009803892365e+00,0.000000000000000000e+00 +6.716490408621824315e+01,4.048629247131364650e+02,3.163711284698919753e-04,5.629016550512393025e+00,-7.318290270705657408e-03,4.978582717379182454e-01,6.839316092015533532e-02,1.000000009281130531e+00,0.000000000000000000e+00 +6.716668059547350822e+01,4.048729244453508045e+02,2.431888790084160798e-04,5.629901000339943451e+00,-7.068290270705657186e-03,4.996347810096667952e-01,6.839316092015533532e-02,1.000000009563742465e+00,0.000000000000000000e+00 +6.716845682564157016e+01,4.048829241955481848e+02,1.725065648614276836e-04,5.630788466710985318e+00,-6.818290270705656964e-03,5.014110111947150950e-01,6.839316092015533532e-02,1.000000009783932997e+00,0.000000000000000000e+00 +6.717023277585869323e+01,4.048929239631036694e+02,1.043241904465713949e-04,5.631678947705181848e+00,-6.568290270705656742e-03,5.031869614292087123e-01,6.839316092015533532e-02,1.000000009346558638e+00,0.000000000000000000e+00 +6.717200844526259118e+01,4.049029237473922649e+02,3.864176002524559049e-05,5.632572441397030616e+00,-6.318290270705656519e-03,5.049626308497001670e-01,6.839316092015533532e-02,1.000000009902583642e+00,0.000000000000000000e+00 +6.717378383299245570e+01,4.049129235477889779e+02,-2.454072229739784230e-05,5.633468945855878651e+00,-6.068290270705656297e-03,5.067380185971404050e-01,6.839316092015533532e-02,1.000000009432924664e+00,0.000000000000000000e+00 +6.717555893818894219e+01,4.049229233636688150e+02,-8.522325257245377643e-05,5.634368459145944641e+00,-5.818290270705656075e-03,5.085131238103652862e-01,6.839316092015533532e-02,1.000000009574279591e+00,0.000000000000000000e+00 +6.717733375999416978e+01,4.049329231944067828e+02,-1.434058270072640891e-04,5.635270979326329588e+00,-5.568290270705655853e-03,5.102879456325892793e-01,6.839316092015533532e-02,1.000000009701305537e+00,0.000000000000000000e+00 +6.717910829755176394e+01,4.049429230393778880e+02,-1.990884419654179193e-04,5.636176504451039015e+00,-5.318290270705655631e-03,5.120624832073925603e-01,6.839316092015533532e-02,1.000000009462951311e+00,0.000000000000000000e+00 +6.718088255000679965e+01,4.049529228979571371e+02,-2.522710939667518440e-04,5.637085032568998066e+00,-5.068290270705655409e-03,5.138367356792113982e-01,6.839316092015533532e-02,1.000000009629578246e+00,0.000000000000000000e+00 +6.718265651650582981e+01,4.049629227695195937e+02,-3.029537796873501220e-04,5.637996561724067490e+00,-4.818290270705655187e-03,5.156107021953308944e-01,6.839316092015533532e-02,1.000000009553545954e+00,0.000000000000000000e+00 +6.718443019619692791e+01,4.049729226534402073e+02,-3.511364959595449108e-04,5.638911089955063183e+00,-4.568290270705654965e-03,5.173843819033719926e-01,6.839316092015533532e-02,1.000000009709382631e+00,0.000000000000000000e+00 +6.718620358822961691e+01,4.049829225490939848e+02,-3.968192397719164295e-04,5.639828615295771286e+00,-4.318290270705654743e-03,5.191577739532852176e-01,6.839316092015533532e-02,1.000000009717584737e+00,0.000000000000000000e+00 +6.718797669175494036e+01,4.049929224558559895e+02,-4.400020082692932292e-04,5.640749135774966838e+00,-4.068290270705654521e-03,5.209308774958387733e-01,6.839316092015533532e-02,1.000000009474186990e+00,0.000000000000000000e+00 +6.718974950592541973e+01,4.050029223731011712e+02,-4.806847987527523023e-04,5.641672649416429763e+00,-3.818290270705654299e-03,5.227036916831103719e-01,6.839316092015533532e-02,1.000000009716218052e+00,0.000000000000000000e+00 +6.719152202989506861e+01,4.050129223002045364e+02,-5.188676086796192985e-04,5.642599154238961745e+00,-3.568290270705654077e-03,5.244762156699809275e-01,6.839316092015533532e-02,1.000000009478682950e+00,0.000000000000000000e+00 +6.719329426281940698e+01,4.050229222365411488e+02,-5.545504356634685253e-04,5.643528648256405766e+00,-3.318290270705653855e-03,5.262484486111201898e-01,6.839316092015533532e-02,1.000000009485860542e+00,0.000000000000000000e+00 +6.719506620385546114e+01,4.050329221814859579e+02,-5.877332774741233275e-04,5.644461129477660322e+00,-3.068290270705653633e-03,5.280203896639840133e-01,6.839316092015533532e-02,1.000000009890897879e+00,0.000000000000000000e+00 +6.719683785216176375e+01,4.050429221344139705e+02,-6.184161320376560869e-04,5.645396595906698956e+00,-2.818290270705653411e-03,5.297920379878044983e-01,6.839316092015533532e-02,1.000000009425206837e+00,0.000000000000000000e+00 +6.719860920689833961e+01,4.050529220947001932e+02,-6.465989974363884393e-04,5.646335045542588027e+00,-2.568290270705653189e-03,5.315633927410742254e-01,6.839316092015533532e-02,1.000000009644146148e+00,0.000000000000000000e+00 +6.720038026722673408e+01,4.050629220617196324e+02,-6.722818719088913828e-04,5.647276476379500032e+00,-2.318290270705652967e-03,5.333344530865519184e-01,6.839316092015533532e-02,1.000000009549757429e+00,0.000000000000000000e+00 +6.720215103231001308e+01,4.050729220348472950e+02,-6.954647538499851697e-04,5.648220886406735808e+00,-2.068290270705652745e-03,5.351052181867420598e-01,6.839316092015533532e-02,1.000000009836793158e+00,0.000000000000000000e+00 +6.720392150131274889e+01,4.050829220134581874e+02,-7.161476418107397398e-04,5.649168273608738744e+00,-1.818290270705652740e-03,5.368756872068957131e-01,6.839316092015533532e-02,1.000000009494242503e+00,0.000000000000000000e+00 +6.720569167340103434e+01,4.050929219969273163e+02,-7.343305344984745039e-04,5.650118635965114322e+00,-1.568290270705652734e-03,5.386458593119929361e-01,6.839316092015533532e-02,1.000000009772581633e+00,0.000000000000000000e+00 +6.720746154774249703e+01,4.051029219846296314e+02,-7.500134307767587771e-04,5.651071971450644327e+00,-1.318290270705652729e-03,5.404157336707492432e-01,6.839316092015533532e-02,1.000000009364909737e+00,0.000000000000000000e+00 +6.720923112350627093e+01,4.051129219759401963e+02,-7.631963296654115624e-04,5.652028278035308162e+00,-1.068290270705652724e-03,5.421853094510913351e-01,6.839316092015533532e-02,1.000000009795289468e+00,0.000000000000000000e+00 +6.721100039986302477e+01,4.051229219702339606e+02,-7.738792303405015501e-04,5.652987553684296174e+00,-8.182902707056527187e-04,5.439545858251700894e-01,6.839316092015533532e-02,1.000000009461014416e+00,0.000000000000000000e+00 +6.721276937598494783e+01,4.051329219668859878e+02,-7.820621321343475523e-04,5.653949796358031854e+00,-5.682902707056527135e-04,5.457235619638302060e-01,6.839316092015533532e-02,1.000000009591999861e+00,0.000000000000000000e+00 +6.721453805104577839e+01,4.051429219652712277e+02,-7.877450345355181769e-04,5.654915004012184276e+00,-3.182902707056527083e-04,5.474922370416247519e-01,6.839316092015533532e-02,1.000000009710034554e+00,0.000000000000000000e+00 +6.721630642422077528e+01,4.051529219647646869e+02,-7.909279371888320448e-04,5.655883174597689411e+00,-6.829027070565270308e-05,5.492606102337956875e-01,6.839316092015533532e-02,1.000000009898995623e+00,0.000000000000000000e+00 +6.721807449468674633e+01,4.051629219647413720e+02,-7.916108398953577898e-04,5.656854306060766113e+00,1.817097292943473021e-04,5.510286807172708468e-01,6.839316092015533532e-02,1.000000009385536570e+00,-5.656854306060771220e-01 +6.721984226162203413e+01,4.051729219645762896e+02,-7.897937426124139503e-04,5.657828396342933885e+00,4.317097292943473073e-04,5.527964476691510365e-01,6.739316092015533444e-02,1.000000009380027421e+00,-5.657828396342938770e-01 +6.722160972420653025e+01,4.051829219636444464e+02,-7.854766454535690775e-04,5.658805443381027978e+00,6.780432191916228868e-04,5.545639102702196732e-01,6.639316092015533355e-02,1.000000009952335400e+00,-5.658805443381033085e-01 +6.722337688162164682e+01,4.051929219613457462e+02,-7.786962137811950574e-04,5.659785445107220703e+00,9.207106938978924186e-04,5.563310677029283946e-01,6.539316092015533266e-02,1.000000009460239259e+00,-5.659785445107224922e-01 +6.722514373305037338e+01,4.052029219571072076e+02,-7.694891081430393822e-04,5.660768399449039201e+00,1.159712640894116882e-03,5.580979191483744772e-01,6.439316092015533177e-02,1.000000009669745893e+00,-5.660768399449044308e-01 +6.722691027767724847e+01,4.052129219503825652e+02,-7.578919843336585395e-04,5.661754304329377874e+00,1.395049540234425322e-03,5.598644637923261280e-01,6.339316092015533088e-02,1.000000009782518795e+00,-5.661754304329382759e-01 +6.722867651468833117e+01,4.052229219406517586e+02,-7.439414934563040550e-04,5.662743157666521476e+00,1.626721864549980244e-03,5.616307008206935514e-01,6.239316092015533000e-02,1.000000009564099290e+00,-5.662743157666526583e-01 +6.723044244327127217e+01,4.052329219274206480e+02,-7.276742819852541431e-04,5.663734957374160217e+00,1.854730079052782079e-03,5.633966294205281500e-01,6.139316092015532911e-02,1.000000009344784502e+00,-5.663734957374164658e-01 +6.723220806261527116e+01,4.052429219102205593e+02,-7.091269918285834830e-04,5.664729701361406633e+00,2.079074641539413806e-03,5.651622487810223916e-01,6.039316092015532822e-02,1.000000009736494277e+00,-5.664729701361411740e-01 +6.723397337191107681e+01,4.052529218886078297e+02,-6.883362603913642909e-04,5.665727387532814241e+00,2.299756002394723765e-03,5.669275580940089654e-01,5.939316092015532733e-02,1.000000009636768272e+00,-5.665727387532819570e-01 +6.723573837035100098e+01,4.052629218621634664e+02,-6.653387206392919655e-04,5.666728013788397078e+00,2.516774604595450361e-03,5.686925565509365343e-01,5.839316092015532644e-02,1.000000009648617905e+00,-5.666728013788401297e-01 +6.723750305712891873e+01,4.052729218304926917e+02,-6.401710011627272838e-04,5.667731578023643912e+00,2.730130883713784758e-03,5.704572433458831027e-01,5.739316092015532556e-02,1.000000009516171851e+00,-5.667731578023649242e-01 +6.723926743144028251e+01,4.052829217932246593e+02,-6.128697262411492933e-04,5.668738078129537783e+00,2.939825267920873932e-03,5.722216176740422267e-01,5.639316092015532467e-02,1.000000009835084525e+00,-5.668738078129542668e-01 +6.724103149248212219e+01,4.052929217500118284e+02,-5.834715159080110930e-04,5.669747511992572875e+00,3.145858177990263661e-03,5.739856787332278110e-01,5.539316092015532378e-02,1.000000009199735640e+00,-5.669747511992577760e-01 +6.724279523945301662e+01,4.053029217005297369e+02,-5.520129860159916739e-04,5.670759877494774059e+00,3.348230027301281244e-03,5.757494257203459309e-01,5.439316092015532289e-02,1.000000009911566234e+00,-5.670759877494778722e-01 +6.724455867155312205e+01,4.053129216444765461e+02,-5.185307483026369881e-04,5.671775172513710217e+00,3.546941221842358355e-03,5.775128578379360444e-01,5.339316092015532200e-02,1.000000009414413471e+00,-5.671775172513714436e-01 +6.724632178798418636e+01,4.053229215815726434e+02,-4.830614104563830361e-04,5.672793394922519106e+00,3.741992160214294930e-03,5.792759742856058436e-01,5.239316092015532111e-02,1.000000009717874505e+00,-5.672793394922523991e-01 +6.724808458794953481e+01,4.053329215115601869e+02,-4.456415761829541971e-04,5.673814542589917131e+00,3.933383233633460166e-03,5.810387742680852563e-01,5.139316092015532023e-02,1.000000009686027980e+00,-5.673814542589922238e-01 +6.724984707065405587e+01,4.053429214342027649e+02,-4.063078452721296456e-04,5.674838613380223329e+00,4.121114825934937137e-03,5.828012569896822148e-01,5.039316092015531934e-02,1.000000009321807104e+00,-5.674838613380228658e-01 +6.725160923530424384e+01,4.053529213492849408e+02,-3.650968136648710238e-04,5.675865605153373572e+00,4.305187313575606703e-03,5.845634216562931584e-01,4.939316092015531845e-02,1.000000009769358877e+00,-5.675865605153378457e-01 +6.725337108110815620e+01,4.053629212566119122e+02,-3.220450735208042693e-04,5.676895515764938338e+00,4.485601065637168962e-03,5.863252674774158679e-01,4.839316092015531756e-02,1.000000009595347850e+00,-5.676895515764943667e-01 +6.725513260727544207e+01,4.053729211560089993e+02,-2.771892132860490922e-04,5.677928343066144024e+00,4.662356443829109194e-03,5.880867936616098746e-01,4.739316092015531667e-02,1.000000009651685673e+00,-5.677928343066148686e-01 +6.725689381301735636e+01,4.053829210473213607e+02,-2.305658177613884301e-04,5.678964084903886267e+00,4.835453802491601789e-03,5.898479994205252375e-01,4.639316092015531579e-02,1.000000009356458497e+00,-4.305788807240021332e-01 +6.725865469754673143e+01,4.053929209304135384e+02,-1.822114681707717569e-04,5.680002739120750377e+00,5.004893488598353458e-03,5.916088839663787846e-01,4.563496123041156649e-02,1.000000009556658354e+00,0.000000000000000000e+00 +6.726041526007800542e+01,4.054029208051690034e+02,-1.321627422301447903e-04,5.681044303555027319e+00,5.171560155265019984e-03,5.933694465144726538e-01,4.563496123041156649e-02,1.000000009664445244e+00,0.000000000000000000e+00 +6.726217549982719390e+01,4.054129206714441125e+02,-8.044737119977709021e-05,5.682088776040734146e+00,5.338226821931686510e-03,5.951296862806696453e-01,4.563496123041156649e-02,1.000000009661845324e+00,0.000000000000000000e+00 +6.726393541601191828e+01,4.054229205289611286e+02,-2.706535651620673312e-05,5.683136154407629981e+00,5.504893488598353035e-03,5.968896024823989732e-01,4.563496123041156649e-02,1.000000009528127620e+00,0.000000000000000000e+00 +6.726569500785140576e+01,4.054329203774422581e+02,2.798330033773253450e-05,5.684186436481233784e+00,5.671560155265019561e-03,5.986491943386534897e-01,4.563496123041156649e-02,1.000000009527073574e+00,0.000000000000000000e+00 +6.726745427456648940e+01,4.054429202166097070e+02,8.469859783291137077e-05,5.685239620082842116e+00,5.838226821931686086e-03,6.004084610704922831e-01,4.563496123041156649e-02,1.000000009633377651e+00,0.000000000000000000e+00 +6.726921321537957965e+01,4.054529200461857386e+02,1.430805343939048249e-04,5.686295703029547788e+00,6.004893488598352612e-03,6.021674019005338607e-01,4.563496123041156649e-02,1.000000009531758716e+00,0.000000000000000000e+00 +6.727097182951473542e+01,4.054629198658925588e+02,2.031291083989924726e-04,5.687354683134257627e+00,6.171560155265019137e-03,6.039260160524482224e-01,4.563496123041156649e-02,1.000000009766775388e+00,0.000000000000000000e+00 +6.727273011619757881e+01,4.054729196754523741e+02,2.648443181801583553e-04,5.688416558205709350e+00,6.338226821931685663e-03,6.056843027524710932e-01,4.563496123041156649e-02,1.000000009156152059e+00,0.000000000000000000e+00 +6.727448807465538039e+01,4.054829194745874474e+02,3.282261620230911086e-04,5.689481326048491105e+00,6.504893488598352189e-03,6.074422612263694621e-01,4.563496123041156649e-02,1.000000009965055670e+00,0.000000000000000000e+00 +6.727624570411700233e+01,4.054929192630199850e+02,3.932746381671839084e-04,5.690548984463055682e+00,6.671560155265018714e-03,6.091998907055043988e-01,4.563496123041156649e-02,1.000000009281967639e+00,0.000000000000000000e+00 +6.727800300381291265e+01,4.055029190404722499e+02,4.599897448055346874e-04,5.691619531245745378e+00,6.838226821931685240e-03,6.109571904177329982e-01,4.563496123041156649e-02,1.000000009656555555e+00,0.000000000000000000e+00 +6.727975997297522781e+01,4.055129188066664483e+02,5.283714800849461084e-04,5.692692964188800886e+00,7.004893488598351765e-03,6.127141595970092558e-01,4.563496123041156649e-02,1.000000009610363172e+00,0.000000000000000000e+00 +6.728151661083764168e+01,4.055229185613247864e+02,5.984198421059254555e-04,5.693769281080387046e+00,7.171560155265018291e-03,6.144707974763066183e-01,4.563496123041156649e-02,1.000000009388807287e+00,0.000000000000000000e+00 +6.728327291663549659e+01,4.055329183041695273e+02,6.701348289226849051e-04,5.694848479704606170e+00,7.338226821931684817e-03,6.162271032906494472e-01,4.563496123041156649e-02,1.000000009524245614e+00,0.000000000000000000e+00 +6.728502888960574069e+01,4.055429180349228773e+02,7.435164385431415265e-04,5.695930557841516695e+00,7.504893488598351342e-03,6.179830762776183928e-01,4.563496123041156649e-02,1.000000009683630786e+00,0.000000000000000000e+00 +6.728678452898695639e+01,4.055529177533070424e+02,8.185646689289171728e-04,5.697015513267152720e+00,7.671560155265017868e-03,6.197387156758321636e-01,4.563496123041156649e-02,1.000000009532006073e+00,0.000000000000000000e+00 +6.728853983401934613e+01,4.055629174590442858e+02,8.952795179953389150e-04,5.698103343753540884e+00,7.838226821931684393e-03,6.214940207249464166e-01,4.563496123041156649e-02,1.000000009597741935e+00,0.000000000000000000e+00 +6.729029480394473239e+01,4.055729171518568705e+02,9.736609836114386079e-04,5.699194047068717239e+00,8.004893488598351786e-03,6.232489906671710989e-01,4.563496123041156649e-02,1.000000009543278168e+00,0.000000000000000000e+00 +6.729204943800657190e+01,4.055829168314670028e+02,1.053709063599953324e-03,5.700287620976746794e+00,8.171560155265019179e-03,6.250036247457521066e-01,4.563496123041156649e-02,1.000000009317818295e+00,0.000000000000000000e+00 +6.729380373544995564e+01,4.055929164975968888e+02,1.135423755737325572e-03,5.701384063237740385e+00,8.338226821931686572e-03,6.267579222054765475e-01,4.563496123041156649e-02,1.000000009735843021e+00,0.000000000000000000e+00 +6.729555769552159461e+01,4.056029161499687916e+02,1.218805057753702533e-03,5.702483371607872442e+00,8.504893488598353965e-03,6.285118822941921923e-01,4.563496123041156649e-02,1.000000009590120031e+00,0.000000000000000000e+00 +6.729731131746984829e+01,4.056129157883049174e+02,1.303852967332936935e-03,5.703585543839401417e+00,8.671560155265021358e-03,6.302655042592627543e-01,4.563496123041156649e-02,1.000000009404284462e+00,0.000000000000000000e+00 +6.729906460054469619e+01,4.056229154123274725e+02,1.390567482112586937e-03,5.704690577680683994e+00,8.838226821931688751e-03,6.320187873506059040e-01,4.563496123041156649e-02,1.000000009412810531e+00,0.000000000000000000e+00 +6.730081754399778049e+01,4.056329150217587198e+02,1.478948599683915918e-03,5.705798470876194628e+00,9.004893488598356144e-03,6.337717308201873401e-01,4.563496123041156649e-02,1.000000009561124781e+00,0.000000000000000000e+00 +6.730257014708234919e+01,4.056429146163209225e+02,1.568996317591892908e-03,5.706909221166544199e+00,9.171560155265023537e-03,6.355243339215155274e-01,4.563496123041156649e-02,1.000000009793622135e+00,0.000000000000000000e+00 +6.730432240905331298e+01,4.056529141957362867e+02,1.660710633335192371e-03,5.708022826288497775e+00,9.338226821931690930e-03,6.372765959096415855e-01,4.563496123041156649e-02,1.000000009185609828e+00,0.000000000000000000e+00 +6.730607432916721677e+01,4.056629137597270756e+02,1.754091544366194640e-03,5.709139283974992374e+00,9.504893488598358323e-03,6.390285160396383946e-01,4.563496123041156649e-02,1.000000009706155657e+00,0.000000000000000000e+00 +6.730782590668225396e+01,4.056729133080154952e+02,1.849139048090985265e-03,5.710258591955152063e+00,9.671560155265025716e-03,6.407800935716720936e-01,4.563496123041156649e-02,1.000000009561563541e+00,0.000000000000000000e+00 +6.730957714085825216e+01,4.056829128403237519e+02,1.945853141869355882e-03,5.711380747954311943e+00,9.838226821931693108e-03,6.425313277644114640e-01,4.563496123041156649e-02,1.000000009273131818e+00,0.000000000000000000e+00 +6.731132803095668748e+01,4.056929123563741086e+02,2.044233823014804212e-03,5.712505749694030577e+00,1.000489348859836050e-02,6.442822178790852394e-01,4.563496123041156649e-02,1.000000009652610933e+00,0.000000000000000000e+00 +6.731307857624069868e+01,4.057029118558888285e+02,2.144281088794532976e-03,5.713633594892109535e+00,1.017156015526502789e-02,6.460327631799913650e-01,4.563496123041156649e-02,1.000000009483352770e+00,0.000000000000000000e+00 +6.731482877597505876e+01,4.057129113385901178e+02,2.245994936429452065e-03,5.714764281262613821e+00,1.033822682193169529e-02,6.477829629309472814e-01,4.563496123041156649e-02,1.000000009576936355e+00,0.000000000000000000e+00 +6.731657862942618920e+01,4.057229108042001826e+02,2.349375363094176154e-03,5.715897806515886082e+00,1.050489348859836268e-02,6.495328163988421943e-01,4.563496123041156649e-02,1.000000009295779702e+00,0.000000000000000000e+00 +6.731832813586218833e+01,4.057329102524413429e+02,2.454422365917027088e-03,5.717034168358567037e+00,1.067156015526503007e-02,6.512823228511021023e-01,4.563496123041156649e-02,1.000000009743140517e+00,0.000000000000000000e+00 +6.732007729455277456e+01,4.057429096830357480e+02,2.561135941980033012e-03,5.718173364493611466e+00,1.083822682193169747e-02,6.530314815587371369e-01,4.563496123041156649e-02,1.000000009410458635e+00,0.000000000000000000e+00 +6.732182610476935736e+01,4.057529090957057178e+02,2.669516088318927075e-03,5.719315392620309524e+00,1.100489348859836486e-02,6.547802917917738830e-01,4.563496123041156649e-02,1.000000009402040480e+00,0.000000000000000000e+00 +6.732357456578496624e+01,4.057629084901734018e+02,2.779562801923150459e-03,5.720460250434300065e+00,1.117156015526503225e-02,6.565287528238273884e-01,4.563496123041156649e-02,1.000000009371077914e+00,0.000000000000000000e+00 +6.732532267687432181e+01,4.057729078661611197e+02,2.891276079735849349e-03,5.721607935627591957e+00,1.133822682193169964e-02,6.582768639295643043e-01,4.563496123041156649e-02,1.000000009843325932e+00,0.000000000000000000e+00 +6.732707043731377894e+01,4.057829072233910779e+02,3.004655918653877534e-03,5.722758445888580958e+00,1.150489348859836704e-02,6.600246243862297746e-01,4.563496123041156649e-02,1.000000009018539027e+00,0.000000000000000000e+00 +6.732881784638136935e+01,4.057929065615854825e+02,3.119702315527795103e-03,5.723911778902069258e+00,1.167156015526503443e-02,6.617720334695835760e-01,4.563496123041156649e-02,1.000000009750243057e+00,0.000000000000000000e+00 +6.733056490335678745e+01,4.058029058804666533e+02,3.236415267161868448e-03,5.725067932349277910e+00,1.183822682193170182e-02,6.635190904620343888e-01,4.563496123041156649e-02,1.000000009658117861e+00,0.000000000000000000e+00 +6.733231160752137612e+01,4.058129051797567399e+02,3.354794770314071563e-03,5.726226903907873478e+00,1.200489348859836922e-02,6.652657946434951119e-01,4.563496123041156649e-02,1.000000009269909063e+00,0.000000000000000000e+00 +6.733405795815815509e+01,4.058229044591780621e+02,3.474840821696084745e-03,5.727388691251978692e+00,1.217156015526503661e-02,6.670121452964660191e-01,4.563496123041156649e-02,1.000000009407589818e+00,0.000000000000000000e+00 +6.733580395455180678e+01,4.058329037184528261e+02,3.596553417973295461e-03,5.728553292052191992e+00,1.233822682193170400e-02,6.687581417065490141e-01,4.563496123041156649e-02,1.000000009437727710e+00,0.000000000000000000e+00 +6.733754959598869050e+01,4.058429029573032949e+02,3.719932555764798345e-03,5.729720703975607954e+00,1.250489348859837140e-02,6.705037831599071074e-01,4.563496123041156649e-02,1.000000009601994089e+00,0.000000000000000000e+00 +6.733929488175681399e+01,4.058529021754516748e+02,3.844978231643394768e-03,5.730890924685833276e+00,1.267156015526503879e-02,6.722490689447938594e-01,4.563496123041156649e-02,1.000000009560146008e+00,0.000000000000000000e+00 +6.734103981114587612e+01,4.058629013726202288e+02,3.971690442135594572e-03,5.732063951843005434e+00,1.283822682193170618e-02,6.739939983505388588e-01,4.563496123041156649e-02,1.000000009264284229e+00,0.000000000000000000e+00 +6.734278438344723838e+01,4.058729005485312200e+02,4.100069183721613032e-03,5.733239783103809550e+00,1.300489348859837357e-02,6.757385706680594240e-01,4.563496123041156649e-02,1.000000009544121493e+00,0.000000000000000000e+00 +6.734452859795392499e+01,4.058828997029068546e+02,4.230114452835375197e-03,5.734418416121496165e+00,1.317156015526504097e-02,6.774827851913926002e-01,4.563496123041156649e-02,1.000000009187717254e+00,0.000000000000000000e+00 +6.734627245396065121e+01,4.058928988354693956e+02,4.361826245864511113e-03,5.735599848545901658e+00,1.333822682193170836e-02,6.792266412141347853e-01,4.563496123041156649e-02,1.000000009611949459e+00,0.000000000000000000e+00 +6.734801595076378078e+01,4.059028979459411062e+02,4.495204559150360601e-03,5.736784078023462463e+00,1.350489348859837575e-02,6.809701380340279497e-01,4.563496123041156649e-02,1.000000009607533213e+00,0.000000000000000000e+00 +6.734975908766138275e+01,4.059128970340442493e+02,4.630249388987970650e-03,5.737971102197237272e+00,1.367156015526504315e-02,6.827132749483809659e-01,4.563496123041156649e-02,1.000000009134242474e+00,0.000000000000000000e+00 +6.735150186395318883e+01,4.059228960995010311e+02,4.766960731626096286e-03,5.739160918706921244e+00,1.383822682193171054e-02,6.844560512561098653e-01,4.563496123041156649e-02,1.000000009616438978e+00,0.000000000000000000e+00 +6.735324427894060761e+01,4.059328951420337148e+02,4.905338583267199702e-03,5.740353525188863770e+00,1.400489348859837793e-02,6.861984662602909069e-01,4.563496123041156649e-02,1.000000009556234026e+00,0.000000000000000000e+00 +6.735498633192673879e+01,4.059428941613645634e+02,5.045382940067451999e-03,5.741548919276090679e+00,1.417156015526504532e-02,6.879405192630688726e-01,4.563496123041156649e-02,1.000000009211694074e+00,0.000000000000000000e+00 +6.735672802221634470e+01,4.059528931572157830e+02,5.187093798136731444e-03,5.742747098598317557e+00,1.433822682193171272e-02,6.896822095687186183e-01,4.563496123041156649e-02,1.000000009429559800e+00,0.000000000000000000e+00 +6.735846934911587880e+01,4.059628921293096369e+02,5.330471153538626078e-03,5.743948060781968401e+00,1.450489348859838011e-02,6.914235364846708087e-01,4.563496123041156649e-02,1.000000009594882000e+00,0.000000000000000000e+00 +6.736021031193347142e+01,4.059728910773683879e+02,5.475515002290431109e-03,5.745151803450196049e+00,1.467156015526504750e-02,6.931644993189669535e-01,4.563496123041156649e-02,1.000000009387008948e+00,0.000000000000000000e+00 +6.736195090997894397e+01,4.059828900011142991e+02,5.622225340363151518e-03,5.746358324222898162e+00,1.483822682193171490e-02,6.949050973807735510e-01,4.563496123041156649e-02,1.000000009366839082e+00,0.000000000000000000e+00 +6.736369114256378055e+01,4.059928889002696337e+02,5.770602163681499454e-03,5.747567620716734105e+00,1.500489348859838229e-02,6.966453299819176381e-01,4.563496123041156649e-02,1.000000009218876995e+00,0.000000000000000000e+00 +6.736543100900118475e+01,4.060028877745565978e+02,5.920645468123896839e-03,5.748779690545144483e+00,1.517156015526504968e-02,6.983851964353621211e-01,4.563496123041156649e-02,1.000000009509509624e+00,0.000000000000000000e+00 +6.736717050860602285e+01,4.060128866236975114e+02,6.072355249522473630e-03,5.749994531318368018e+00,1.533822682193171708e-02,7.001246960567412136e-01,4.563496123041156649e-02,1.000000009634989917e+00,0.000000000000000000e+00 +6.736890964069485221e+01,4.060228854474145805e+02,6.225731503663069558e-03,5.751212140643461090e+00,1.550489348859838447e-02,7.018638281623255093e-01,4.563496123041156649e-02,1.000000008992009137e+00,0.000000000000000000e+00 +6.737064840458592130e+01,4.060328842454300684e+02,6.380774226285233254e-03,5.752432516124313722e+00,1.567156015526505186e-02,7.036025920690245350e-01,4.563496123041156649e-02,1.000000009625285458e+00,0.000000000000000000e+00 +6.737238679959915544e+01,4.060428830174662380e+02,6.537483413082222257e-03,5.753655655361665566e+00,1.583822682193171752e-02,7.053409870989918451e-01,4.563496123041156649e-02,1.000000009468730244e+00,0.000000000000000000e+00 +6.737412482505618527e+01,4.060528817632452956e+02,6.695859059701003875e-03,5.754881555953129890e+00,1.600489348859838318e-02,7.070790125724781827e-01,4.563496123041156649e-02,1.000000009397577605e+00,0.000000000000000000e+00 +6.737586248028031832e+01,4.060628804824895610e+02,6.855901161742254321e-03,5.756110215493205118e+00,1.617156015526504884e-02,7.088166678129463882e-01,4.563496123041156649e-02,1.000000009114084598e+00,0.000000000000000000e+00 +6.737759976459656741e+01,4.060728791749212405e+02,7.017609714760359579e-03,5.757341631573295260e+00,1.633822682193171449e-02,7.105539521450331408e-01,4.563496123041156649e-02,1.000000009500886966e+00,0.000000000000000000e+00 +6.737933667733163645e+01,4.060828778402626540e+02,7.180984714263415405e-03,5.758575801781726788e+00,1.650489348859838015e-02,7.122908648966004286e-01,4.563496123041156649e-02,1.000000009383873678e+00,0.000000000000000000e+00 +6.738107321781390624e+01,4.060928764782360076e+02,7.346026155713227326e-03,5.759812723703769066e+00,1.667156015526504581e-02,7.140274053951634059e-01,4.563496123041156649e-02,1.000000009357525865e+00,0.000000000000000000e+00 +6.738280938537346287e+01,4.061028750885636214e+02,7.512734034525311508e-03,5.761052394921648556e+00,1.683822682193171147e-02,7.157635729709634909e-01,4.563496123041156649e-02,1.000000009431606385e+00,0.000000000000000000e+00 +6.738454517934208354e+01,4.061128736709677014e+02,7.681108346068893020e-03,5.762294813014568362e+00,1.700489348859837713e-02,7.174993669559532883e-01,4.563496123041156649e-02,1.000000009324121919e+00,0.000000000000000000e+00 +6.738628059905323653e+01,4.061228722251705108e+02,7.851149085666907571e-03,5.763539975558725992e+00,1.717156015526504279e-02,7.192347866832909942e-01,4.563496123041156649e-02,1.000000009346292185e+00,0.000000000000000000e+00 +6.738801564384209541e+01,4.061328707508943694e+02,8.022856248596001508e-03,5.764787880127330233e+00,1.733822682193170844e-02,7.209698314883707937e-01,4.563496123041156649e-02,1.000000009222813846e+00,0.000000000000000000e+00 +6.738975031304552488e+01,4.061428692478614835e+02,8.196229830086531817e-03,5.766038524290619804e+00,1.750489348859837410e-02,7.227045007078056749e-01,4.563496123041156649e-02,1.000000009568017934e+00,0.000000000000000000e+00 +6.739148460600209489e+01,4.061528677157941161e+02,8.371269825322564390e-03,5.767291905615880232e+00,1.767156015526503976e-02,7.244387936809714157e-01,4.563496123041156649e-02,1.000000009228008135e+00,0.000000000000000000e+00 +6.739321852205206653e+01,4.061628661544145302e+02,8.547976229441879223e-03,5.768548021667463388e+00,1.783822682193170542e-02,7.261727097469403702e-01,4.563496123041156649e-02,1.000000009415206392e+00,0.000000000000000000e+00 +6.739495206053739196e+01,4.061728645634450459e+02,8.726349037535963485e-03,5.769806870006801702e+00,1.800489348859837108e-02,7.279062482485859631e-01,4.563496123041156649e-02,1.000000009278336766e+00,0.000000000000000000e+00 +6.739668522080172863e+01,4.061828629426078692e+02,8.906388244650016717e-03,5.771068448192429479e+00,1.817156015526503673e-02,7.296394085290047737e-01,4.563496123041156649e-02,1.000000009151634561e+00,0.000000000000000000e+00 +6.739841800219043932e+01,4.061928612916253201e+02,9.088093845782950833e-03,5.772332753779997994e+00,1.833822682193170239e-02,7.313721899335726695e-01,4.563496123041156649e-02,1.000000009670483747e+00,0.000000000000000000e+00 +6.740015040405057789e+01,4.062028596102196047e+02,9.271465835887388388e-03,5.773599784322294148e+00,1.850489348859836805e-02,7.331045918104666104e-01,4.563496123041156649e-02,1.000000009106298826e+00,0.000000000000000000e+00 +6.740188242573090349e+01,4.062128578981130431e+02,9.456504209869662572e-03,5.774869537369260009e+00,1.867156015526503371e-02,7.348366135065698135e-01,4.563496123041156649e-02,1.000000009286074798e+00,0.000000000000000000e+00 +6.740361406658188059e+01,4.062228561550278982e+02,9.643208962589817218e-03,5.776142010468005239e+00,1.883822682193169937e-02,7.365682543736319365e-01,4.563496123041156649e-02,1.000000009081603913e+00,0.000000000000000000e+00 +6.740534532595567896e+01,4.062328543806864332e+02,9.831580088861610264e-03,5.777417201162830196e+00,1.900489348859836503e-02,7.382995137631506166e-01,4.563496123041156649e-02,1.000000009738245765e+00,0.000000000000000000e+00 +6.740707620320615945e+01,4.062428525748109109e+02,1.002161758345251029e-02,5.778695106995240138e+00,1.917156015526503068e-02,7.400303910304820709e-01,4.563496123041156649e-02,1.000000008948927377e+00,0.000000000000000000e+00 +6.740880669768888822e+01,4.062528507371235946e+02,1.021332144108369824e-02,5.779975725503966544e+00,1.933822682193169634e-02,7.417608855286922376e-01,4.563496123041156649e-02,1.000000009451331939e+00,0.000000000000000000e+00 +6.741053680876113674e+01,4.062628488673468041e+02,1.040669165643006745e-02,5.781259054224977767e+00,1.950489348859836200e-02,7.434909966172887907e-01,4.563496123041156649e-02,1.000000009242997256e+00,0.000000000000000000e+00 +6.741226653578188177e+01,4.062728469652027457e+02,1.060172822412022188e-02,5.782545090691504797e+00,1.967156015526502766e-02,7.452207236540182578e-01,4.563496123041156649e-02,1.000000009292416170e+00,0.000000000000000000e+00 +6.741399587811180538e+01,4.062828450304137391e+02,1.079843113873648133e-02,5.783833832434052802e+00,1.983822682193169332e-02,7.469500660000073511e-01,4.563496123041156649e-02,1.000000009385876965e+00,0.000000000000000000e+00 +6.741572483511329494e+01,4.062928430627020475e+02,1.099680039481487279e-02,5.785125276980421560e+00,2.000489348859835897e-02,7.486790230177179373e-01,4.563496123041156649e-02,1.000000009314435889e+00,0.000000000000000000e+00 +6.741745340615042892e+01,4.063028410617899340e+02,1.119683598684514080e-02,5.786419421855722334e+00,2.017156015526502463e-02,7.504075940709560300e-01,4.563496123041156649e-02,1.000000008873160429e+00,0.000000000000000000e+00 +6.741918159058901949e+01,4.063128390273997184e+02,1.139853790927074229e-02,5.787716264582394743e+00,2.033822682193169029e-02,7.521357785248794503e-01,4.563496123041156649e-02,1.000000009647539656e+00,0.000000000000000000e+00 +6.742090938779656994e+01,4.063228369592536637e+02,1.160190615648884482e-02,5.789015802680223644e+00,2.050489348859835595e-02,7.538635757490920186e-01,4.563496123041156649e-02,1.000000009063174211e+00,0.000000000000000000e+00 +6.742263679714227465e+01,4.063328348570740332e+02,1.180694072285033008e-02,5.790318033666361330e+00,2.067156015526502161e-02,7.555909851104556374e-01,4.563496123041156649e-02,1.000000009310877180e+00,0.000000000000000000e+00 +6.742436381799706169e+01,4.063428327205830897e+02,1.201364160265979385e-02,5.791622955055337307e+00,2.083822682193168727e-02,7.573180059813242604e-01,4.563496123041156649e-02,1.000000009313907867e+00,0.000000000000000000e+00 +6.742609044973355026e+01,4.063528305495031532e+02,1.222200879017554601e-02,5.792930564359082268e+00,2.100489348859835292e-02,7.590446377338989636e-01,4.563496123041156649e-02,1.000000008892200087e+00,0.000000000000000000e+00 +6.742781669172607906e+01,4.063628283435564867e+02,1.243204227960960709e-02,5.794240859086942308e+00,2.117156015526501858e-02,7.607708797417778168e-01,4.563496123041156649e-02,1.000000009660835243e+00,0.000000000000000000e+00 +6.742954254335067787e+01,4.063728261024654103e+02,1.264374206512771520e-02,5.795553836745695797e+00,2.133822682193168424e-02,7.624967313830546267e-01,4.563496123041156649e-02,1.000000009065828088e+00,0.000000000000000000e+00 +6.743126800398511023e+01,4.063828238259521868e+02,1.285710814084932083e-02,5.796869494839575587e+00,2.150489348859834990e-02,7.642221920331231377e-01,4.563496123041156649e-02,1.000000009031145165e+00,0.000000000000000000e+00 +6.743299307300881651e+01,4.063928215137390794e+02,1.307214050084758682e-02,5.798187830870278781e+00,2.167156015526501556e-02,7.659472610724060715e-01,4.563496123041156649e-02,1.000000009400086043e+00,0.000000000000000000e+00 +6.743471774980295663e+01,4.064028191655484079e+02,1.328883913914939360e-02,5.799508842336989822e+00,2.183822682193168122e-02,7.676719378827638884e-01,4.563496123041156649e-02,1.000000009124550671e+00,0.000000000000000000e+00 +6.743644203375042423e+01,4.064128167811024355e+02,1.350720404973533399e-02,5.800832526736397377e+00,2.200489348859834687e-02,7.693962218459582392e-01,4.563496123041156649e-02,1.000000009252741462e+00,0.000000000000000000e+00 +6.743816592423578982e+01,4.064228143601234251e+02,1.372723522653971663e-02,5.802158881562708537e+00,2.217156015526501253e-02,7.711201123472676278e-01,4.563496123041156649e-02,1.000000009046004612e+00,0.000000000000000000e+00 +6.743988942064534342e+01,4.064328119023336967e+02,1.394893266345056428e-02,5.803487904307669254e+00,2.233822682193167819e-02,7.728436087724063208e-01,4.563496123041156649e-02,1.000000009266417855e+00,0.000000000000000000e+00 +6.744161252236708037e+01,4.064428094074555702e+02,1.417229635430961379e-02,5.804819592460579436e+00,2.250489348859834385e-02,7.745667105101116112e-01,4.563496123041156649e-02,1.000000009186852390e+00,0.000000000000000000e+00 +6.744333522879071552e+01,4.064528068752113086e+02,1.439732629291231962e-02,5.806153943508312487e+00,2.267156015526500951e-02,7.762894169495773156e-01,4.563496123041156649e-02,1.000000009282078217e+00,0.000000000000000000e+00 +6.744505753930768321e+01,4.064628043053231750e+02,1.462402247300784858e-02,5.807490954935330407e+00,2.283822682193167516e-02,7.780117274825251172e-01,4.563496123041156649e-02,1.000000008836091414e+00,0.000000000000000000e+00 +6.744677945331109470e+01,4.064728016975134892e+02,1.485238488829908506e-02,5.808830624223702443e+00,2.300489348859834082e-02,7.797336415011535404e-01,4.563496123041156649e-02,1.000000009535029211e+00,0.000000000000000000e+00 +6.744850097019579493e+01,4.064827990515045713e+02,1.508241353244262929e-02,5.810172948853120189e+00,2.317156015526500648e-02,7.814551584022745301e-01,4.563496123041156649e-02,1.000000008876870350e+00,0.000000000000000000e+00 +6.745022208935834840e+01,4.064927963670186841e+02,1.531410839904879737e-02,5.811517926300919790e+00,2.333822682193167214e-02,7.831762775801025533e-01,4.563496123041156649e-02,1.000000009160417536e+00,0.000000000000000000e+00 +6.745194281019699645e+01,4.065027936437781477e+02,1.554746948168161946e-02,5.812865554042091709e+00,2.350489348859833780e-02,7.848969984345195439e-01,4.563496123041156649e-02,1.000000009093856113e+00,0.000000000000000000e+00 +6.745366313211172837e+01,4.065127908815052251e+02,1.578249677385884508e-02,5.814215829549304715e+00,2.367156015526500346e-02,7.866173203648942902e-01,4.563496123041156649e-02,1.000000009191435169e+00,0.000000000000000000e+00 +6.745538305450421035e+01,4.065227880799222362e+02,1.601919026905193610e-02,5.815568750292919198e+00,2.383822682193166911e-02,7.883372427731908383e-01,4.563496123041156649e-02,1.000000009072785856e+00,0.000000000000000000e+00 +6.745710257677784227e+01,4.065327852387515009e+02,1.625754996068607544e-02,5.816924313741005825e+00,2.400489348859833477e-02,7.900567650624293892e-01,4.563496123041156649e-02,1.000000009265696432e+00,0.000000000000000000e+00 +6.745882169833772934e+01,4.065427823577152822e+02,1.649757584214015665e-02,5.818282517359361528e+00,2.417156015526500043e-02,7.917758866382481608e-01,4.563496123041156649e-02,1.000000009102452569e+00,0.000000000000000000e+00 +6.746054041859068207e+01,4.065527794365359000e+02,1.673926790674679782e-02,5.819643358611528150e+00,2.433822682193166609e-02,7.934946069068478103e-01,4.563496123041156649e-02,1.000000008823154429e+00,0.000000000000000000e+00 +6.746225873694523045e+01,4.065627764749356743e+02,1.698262614779232765e-02,5.821006834958807552e+00,2.450489348859833175e-02,7.952129252765524070e-01,4.563496123041156649e-02,1.000000009277632440e+00,0.000000000000000000e+00 +6.746397665281159561e+01,4.065727734726368681e+02,1.722765055851679938e-02,5.822372943860279371e+00,2.467156015526499740e-02,7.969308411588564844e-01,4.563496123041156649e-02,1.000000008914534000e+00,0.000000000000000000e+00 +6.746569416560173238e+01,4.065827704293618581e+02,1.747434113211397688e-02,5.823741682772820560e+00,2.483822682193166306e-02,7.986483539642995622e-01,4.563496123041156649e-02,1.000000009199639051e+00,0.000000000000000000e+00 +6.746741127472928667e+01,4.065927673448329074e+02,1.772269786173134160e-02,5.825113049151117828e+00,2.500489348859832872e-02,8.003654631076493331e-01,4.563496123041156649e-02,1.000000009196820416e+00,0.000000000000000000e+00 +6.746912797960962394e+01,4.066027642187722790e+02,1.797272074047009949e-02,5.826487040447688948e+00,2.517156015526499438e-02,8.020821680037758528e-01,4.563496123041156649e-02,1.000000008879915692e+00,0.000000000000000000e+00 +6.747084427965982911e+01,4.066127610509023498e+02,1.822440976138517063e-02,5.827863654112896974e+00,2.533822682193166004e-02,8.037984680692147332e-01,4.563496123041156649e-02,1.000000008833332066e+00,0.000000000000000000e+00 +6.747256017429867825e+01,4.066227578409453827e+02,1.847776491748518921e-02,5.829242887594967115e+00,2.550489348859832570e-02,8.055143627232147496e-01,4.563496123041156649e-02,1.000000009347830288e+00,0.000000000000000000e+00 +6.747427566294666690e+01,4.066327545886237544e+02,1.873278620173251738e-02,5.830624738340005386e+00,2.567156015526499135e-02,8.072298513872330217e-01,4.563496123041156649e-02,1.000000008910164606e+00,0.000000000000000000e+00 +6.747599074502599592e+01,4.066427512936597282e+02,1.898947360704322795e-02,5.832009203792016372e+00,2.583822682193165701e-02,8.089449334818403781e-01,4.563496123041156649e-02,1.000000009032403048e+00,0.000000000000000000e+00 +6.747770541996058569e+01,4.066527479557756237e+02,1.924782712628711479e-02,5.833396281392915661e+00,2.600489348859832267e-02,8.106596084319110940e-01,4.563496123041156649e-02,1.000000008819135644e+00,0.000000000000000000e+00 +6.747941968717604766e+01,4.066627445746937610e+02,1.950784675228768930e-02,5.834785968582551163e+00,2.617156015526498833e-02,8.123738756624931945e-01,4.563496123041156649e-02,1.000000009194956796e+00,0.000000000000000000e+00 +6.748113354609972703e+01,4.066727411501364600e+02,1.976953247782218745e-02,5.836178262798717320e+00,2.633822682193165399e-02,8.140877346019289584e-01,4.563496123041156649e-02,1.000000008673158414e+00,0.000000000000000000e+00 +6.748284699616066007e+01,4.066827376818259836e+02,2.003288429562155928e-02,5.837573161477174644e+00,2.650489348859831965e-02,8.158011846777215581e-01,4.563496123041156649e-02,1.000000009404308443e+00,0.000000000000000000e+00 +6.748456003678960258e+01,4.066927341694847087e+02,2.029790219837047938e-02,5.838970662051662153e+00,2.667156015526498530e-02,8.175142253227680733e-01,4.563496123041156649e-02,1.000000008705243415e+00,0.000000000000000000e+00 +6.748627266741900144e+01,4.067027306128349551e+02,2.056458617870733641e-02,5.840370761953920464e+00,2.683822682193165096e-02,8.192268559670773387e-01,4.563496123041156649e-02,1.000000009045636240e+00,0.000000000000000000e+00 +6.748798488748303726e+01,4.067127270115990427e+02,2.083293622922424357e-02,5.841773458613700676e+00,2.700489348859831662e-02,8.209390760465968828e-01,4.563496123041156649e-02,1.000000008664420070e+00,0.000000000000000000e+00 +6.748969669641758173e+01,4.067227233654992915e+02,2.110295234246703164e-02,5.843178749458788346e+00,2.717156015526498228e-02,8.226508849959663916e-01,4.563496123041156649e-02,1.000000009140833201e+00,0.000000000000000000e+00 +6.749140809366021188e+01,4.067327196742580213e+02,2.137463451093525590e-02,5.844586631915015040e+00,2.733822682193164794e-02,8.243622822542369111e-01,4.563496123041156649e-02,1.000000009030536763e+00,0.000000000000000000e+00 +6.749311907865022420e+01,4.067427159375975521e+02,2.164798272708218577e-02,5.845997103406279649e+00,2.750489348859831359e-02,8.260732672596946546e-01,4.563496123041156649e-02,1.000000008716120714e+00,0.000000000000000000e+00 +6.749482965082860630e+01,4.067527121552402036e+02,2.192299698331481861e-02,5.847410161354560820e+00,2.767156015526497925e-02,8.277838394529881683e-01,4.563496123041156649e-02,1.000000008892023118e+00,0.000000000000000000e+00 +6.749653980963806532e+01,4.067627083269082959e+02,2.219967727199386592e-02,5.848825803179934724e+00,2.783822682193164491e-02,8.294939982776606824e-01,4.563496123041156649e-02,1.000000009047385952e+00,0.000000000000000000e+00 +6.749824955452302788e+01,4.067727044523241489e+02,2.247802358543376719e-02,5.850244026300593703e+00,2.800489348859831057e-02,8.312037431780878727e-01,4.563496123041156649e-02,1.000000008678014751e+00,0.000000000000000000e+00 +6.749995888492959750e+01,4.067827005312101392e+02,2.275803591590267946e-02,5.851664828132861373e+00,2.817156015526497623e-02,8.329130735994897394e-01,4.563496123041156649e-02,1.000000008807716112e+00,0.000000000000000000e+00 +6.750166780030559721e+01,4.067926965632885867e+02,2.303971425562248432e-02,5.853088206091207724e+00,2.833822682193164189e-02,8.346219889905422962e-01,4.563496123041156649e-02,1.000000008949248675e+00,0.000000000000000000e+00 +6.750337630010055534e+01,4.068026925482818115e+02,2.332305859676878090e-02,5.854514157588268652e+00,2.850489348859830754e-02,8.363304888007938587e-01,4.563496123041156649e-02,1.000000008622347503e+00,0.000000000000000000e+00 +6.750508438376570552e+01,4.068126884859121333e+02,2.360806893147089289e-02,5.855942680034861070e+00,2.867156015526497320e-02,8.380385724806773684e-01,4.563496123041156649e-02,1.000000009182064220e+00,0.000000000000000000e+00 +6.750679205075398670e+01,4.068226843759018720e+02,2.389474525181186845e-02,5.857373770839997995e+00,2.883822682193163886e-02,8.397462394846448852e-01,4.563496123041156649e-02,1.000000008642488503e+00,0.000000000000000000e+00 +6.750849930052004311e+01,4.068326802179734045e+02,2.418308754982847336e-02,5.858807427410908986e+00,2.900489348859830452e-02,8.414534892654610410e-01,4.563496123041156649e-02,1.000000008680126840e+00,0.000000000000000000e+00 +6.751020613252022429e+01,4.068426760118490506e+02,2.447309581751120136e-02,5.860243647153050794e+00,2.917156015526497018e-02,8.431603212804570369e-01,4.563496123041156649e-02,1.000000008849259769e+00,0.000000000000000000e+00 +6.751191254621257087e+01,4.068526717572511870e+02,2.476477004680426725e-02,5.861682427470128687e+00,2.933822682193163583e-02,8.448667349879059874e-01,4.563496123041156649e-02,1.000000008710973498e+00,0.000000000000000000e+00 +6.751361854105684301e+01,4.068626674539020769e+02,2.505811022960561033e-02,5.863123765764111539e+00,2.950489348859830149e-02,8.465727298470347995e-01,4.563496123041156649e-02,1.000000008750477454e+00,0.000000000000000000e+00 +6.751532411651447774e+01,4.068726631015241537e+02,2.535311635776689096e-02,5.864567659435246938e+00,2.967156015526496715e-02,8.482783053196005785e-01,4.563496123041156649e-02,1.000000008546383601e+00,0.000000000000000000e+00 +6.751702927204864579e+01,4.068826586998396806e+02,2.564978842309349402e-02,5.866014105882078944e+00,2.983822682193163281e-02,8.499834608683434212e-01,4.563496123041156649e-02,1.000000008907356186e+00,0.000000000000000000e+00 +6.751873400712419482e+01,4.068926542485710343e+02,2.594812641734452890e-02,5.867463102501463190e+00,3.000489348859829847e-02,8.516881959590835161e-01,4.563496123041156649e-02,1.000000008818284769e+00,0.000000000000000000e+00 +6.752043832120769196e+01,4.069026497474405915e+02,2.624813033223282951e-02,5.868914646688585535e+00,3.017156015526496413e-02,8.533925100576109646e-01,4.563496123041156649e-02,1.000000008494017711e+00,0.000000000000000000e+00 +6.752214221376739545e+01,4.069126451961706721e+02,2.654980015942495428e-02,5.870368735836975382e+00,3.033822682193162978e-02,8.550964026317826594e-01,4.563496123041156649e-02,1.000000008771577020e+00,0.000000000000000000e+00 +6.752384568427325462e+01,4.069226405944835960e+02,2.685313589054118613e-02,5.871825367338522561e+00,3.050489348859829544e-02,8.567998731525812151e-01,4.563496123041156649e-02,1.000000008354821945e+00,0.000000000000000000e+00 +6.752554873219692411e+01,4.069326359421017401e+02,2.715813751715552907e-02,5.873284538583495973e+00,3.067156015526496110e-02,8.585029210904800978e-01,4.563496123041156649e-02,1.000000009017705249e+00,0.000000000000000000e+00 +6.752725135701176384e+01,4.069426312387474809e+02,2.746480503079571853e-02,5.874746246960556029e+00,3.083822682193162676e-02,8.602055459206724430e-01,4.563496123041156649e-02,1.000000008255662598e+00,0.000000000000000000e+00 +6.752895355819282486e+01,4.069526264841431384e+02,2.777313842294321447e-02,5.876210489856775965e+00,3.100489348859829242e-02,8.619077471157845505e-01,4.563496123041156649e-02,1.000000008781580574e+00,0.000000000000000000e+00 +6.753065533521684927e+01,4.069626216780110894e+02,2.808313768503319791e-02,5.877677264657650724e+00,3.117156015526495808e-02,8.636095241547584456e-01,4.563496123041156649e-02,1.000000008414206665e+00,0.000000000000000000e+00 +6.753235668756229870e+01,4.069726168200736538e+02,2.839480280845457782e-02,5.879146568747120938e+00,3.133822682193162373e-02,8.653108765145199888e-01,4.563496123041156649e-02,1.000000008660492989e+00,0.000000000000000000e+00 +6.753405761470929747e+01,4.069826119100532082e+02,2.870813378454999121e-02,5.880618399507582694e+00,3.150489348859829286e-02,8.670118036762552993e-01,4.563496123041156649e-02,1.000000008582817124e+00,0.000000000000000000e+00 +6.753575811613970359e+01,4.069926069476721295e+02,2.902313060461579955e-02,5.882092754319907968e+00,3.167156015526496199e-02,8.687123051212505276e-01,4.563496123041156649e-02,1.000000008480205871e+00,0.000000000000000000e+00 +6.753745819133703776e+01,4.070026019326527376e+02,2.933979325990208886e-02,5.883569630563457942e+00,3.183822682193163112e-02,8.704123803329951725e-01,4.563496123041156649e-02,1.000000008661863671e+00,0.000000000000000000e+00 +6.753915783978651177e+01,4.070125968647174091e+02,2.965812174161267661e-02,5.885049025616099883e+00,3.200489348859830024e-02,8.721120287971981799e-01,4.563496123041156649e-02,1.000000008216763936e+00,0.000000000000000000e+00 +6.754085706097507114e+01,4.070225917435885208e+02,2.997811604090510479e-02,5.886530936854224016e+00,3.217156015526496937e-02,8.738112499997132687e-01,4.563496123041156649e-02,1.000000008395414808e+00,0.000000000000000000e+00 +6.754255585439130982e+01,4.070325865689884495e+02,3.029977614889064336e-02,5.888015361652756852e+00,3.233822682193163850e-02,8.755100434302117707e-01,4.563496123041156649e-02,1.000000008613767921e+00,0.000000000000000000e+00 +6.754425421952552711e+01,4.070425813406395150e+02,3.062310205663429027e-02,5.889502297385180718e+00,3.250489348859830763e-02,8.772084085790640140e-01,4.563496123041156649e-02,1.000000008295537812e+00,0.000000000000000000e+00 +6.754595215586972756e+01,4.070525760582641510e+02,3.094809375515476801e-02,5.890991741423547978e+00,3.267156015526497675e-02,8.789063449373527570e-01,4.563496123041156649e-02,1.000000008106177951e+00,0.000000000000000000e+00 +6.754764966291759265e+01,4.070625707215846774e+02,3.127475123542453050e-02,5.892483691138495239e+00,3.283822682193164588e-02,8.806038519989812796e-01,4.563496123041156649e-02,1.000000008722409683e+00,0.000000000000000000e+00 +6.754934674016449492e+01,4.070725653303234708e+02,3.160307448836975619e-02,5.893978143899261113e+00,3.300489348859831501e-02,8.823009292606905918e-01,4.563496123041156649e-02,1.000000008363728154e+00,0.000000000000000000e+00 +6.755104338710749801e+01,4.070825598842029081e+02,3.193306350487035844e-02,5.895475097073703985e+00,3.317156015526498414e-02,8.839975762178884366e-01,4.563496123041156649e-02,1.000000008033772980e+00,0.000000000000000000e+00 +6.755273960324535665e+01,4.070925543829453659e+02,3.226471827575997514e-02,5.896974548028312668e+00,3.333822682193165327e-02,8.856937923693740666e-01,4.563496123041156649e-02,1.000000008439860144e+00,0.000000000000000000e+00 +6.755443538807850246e+01,4.071025488262732210e+02,3.259803879182597564e-02,5.898476494128225056e+00,3.350489348859832239e-02,8.873895772168332030e-01,4.563496123041156649e-02,1.000000008137458041e+00,0.000000000000000000e+00 +6.755613074110905814e+01,4.071125432139088502e+02,3.293302504380945378e-02,5.899980932737245887e+00,3.367156015526499152e-02,8.890849302611878446e-01,4.563496123041156649e-02,1.000000008162243548e+00,0.000000000000000000e+00 +6.755782566184083748e+01,4.071225375455746303e+02,3.326967702240523489e-02,5.901487861217858288e+00,3.383822682193166065e-02,8.907798510068016817e-01,4.563496123041156649e-02,1.000000008325056422e+00,0.000000000000000000e+00 +6.755952014977933118e+01,4.071325318209929378e+02,3.360799471826187573e-02,5.902997276931242432e+00,3.400489348859832978e-02,8.924743389594019805e-01,4.563496123041156649e-02,1.000000008136963769e+00,0.000000000000000000e+00 +6.756121420443172099e+01,4.071425260398861496e+02,3.394797812198166453e-02,5.904509177237290629e+00,3.417156015526499890e-02,8.941683936255712117e-01,4.563496123041156649e-02,1.000000008046920463e+00,0.000000000000000000e+00 +6.756290782530685135e+01,4.071525202019766425e+02,3.428962722412061404e-02,5.906023559494621544e+00,3.433822682193166803e-02,8.958620145143354474e-01,4.563496123041156649e-02,1.000000008205279789e+00,0.000000000000000000e+00 +6.756460101191528622e+01,4.071625143069867931e+02,3.463294201518847537e-02,5.907540421060597069e+00,3.450489348859833716e-02,8.975552011366570992e-01,4.563496123041156649e-02,1.000000007843424132e+00,0.000000000000000000e+00 +6.756629376376922380e+01,4.071725083546390351e+02,3.497792248564872419e-02,5.909059759291338310e+00,3.467156015526500629e-02,8.992479530038781643e-01,4.563496123041156649e-02,1.000000008371977112e+00,0.000000000000000000e+00 +6.756798608038258180e+01,4.071825023446556884e+02,3.532456862591857455e-02,5.910581571541738910e+00,3.483822682193167541e-02,9.009402696314086079e-01,4.563496123041156649e-02,1.000000007491470333e+00,0.000000000000000000e+00 +6.756967796127094061e+01,4.071924962767591865e+02,3.567288042636895806e-02,5.912105855165484591e+00,3.500489348859834454e-02,9.026321505324459427e-01,4.563496123041156649e-02,1.000000008496356729e+00,0.000000000000000000e+00 +6.757136940595155750e+01,4.072024901506719061e+02,3.602285787732455863e-02,5.913632607515062034e+00,3.517156015526501367e-02,9.043235952274401024e-01,4.563496123041156649e-02,1.000000007554188164e+00,0.000000000000000000e+00 +6.757306041394338081e+01,4.072124839661162810e+02,3.637450096906377078e-02,5.915161825941783746e+00,3.533822682193168280e-02,9.060146032320350873e-01,4.563496123041156649e-02,1.000000007982724703e+00,0.000000000000000000e+00 +6.757475098476700737e+01,4.072224777228146877e+02,3.672780969181873439e-02,5.916693507795792506e+00,3.550489348859835192e-02,9.077051740691626236e-01,4.563496123041156649e-02,1.000000007831778781e+00,0.000000000000000000e+00 +6.757644111794473929e+01,4.072324714204895031e+02,3.708278403577532079e-02,5.918227650426086228e+00,3.567156015526502105e-02,9.093953072601318466e-01,4.563496123041156649e-02,1.000000007646016487e+00,0.000000000000000000e+00 +6.757813081300054137e+01,4.072424650588631039e+02,3.743942399107312580e-02,5.919764251180527737e+00,3.583822682193169018e-02,9.110850023288472599e-01,4.563496123041156649e-02,1.000000007981846295e+00,0.000000000000000000e+00 +6.757982006946004105e+01,4.072524586376579236e+02,3.779772954780548366e-02,5.921303307405861638e+00,3.600489348859835931e-02,9.127742588018266101e-01,4.563496123041156649e-02,1.000000007539516345e+00,0.000000000000000000e+00 +6.758150888685054269e+01,4.072624521565963391e+02,3.815770069601946701e-02,5.922844816447731198e+00,3.617156015526502844e-02,9.144630762050641737e-01,4.563496123041156649e-02,1.000000007519528333e+00,0.000000000000000000e+00 +6.758319726470104172e+01,4.072724456154007839e+02,3.851933742571587993e-02,5.924388775650689887e+00,3.633822682193169756e-02,9.161514540682533791e-01,4.563496123041156649e-02,1.000000007889083831e+00,0.000000000000000000e+00 +6.758488520254216780e+01,4.072824390137936348e+02,3.888263972684925102e-02,5.925935182358220032e+00,3.650489348859836669e-02,9.178393919227019193e-01,4.563496123041156649e-02,1.000000007378053946e+00,0.000000000000000000e+00 +6.758657269990625593e+01,4.072924323514972684e+02,3.924760758932785421e-02,5.927484033912747918e+00,3.667156015526503582e-02,9.195268892992427556e-01,4.563496123041156649e-02,1.000000007533526691e+00,0.000000000000000000e+00 +6.758825975632728955e+01,4.073024256282341753e+02,3.961424100301368795e-02,5.929035327655655330e+00,3.683822682193170495e-02,9.212139457329880932e-01,4.563496123041156649e-02,1.000000007418818448e+00,0.000000000000000000e+00 +6.758994637134092898e+01,4.073124188437266753e+02,3.998253995772249603e-02,5.930589060927299094e+00,3.700489348859837407e-02,9.229005607591364013e-01,4.563496123041156649e-02,1.000000007355761777e+00,0.000000000000000000e+00 +6.759163254448448299e+01,4.073224119976972588e+02,4.035250444322375368e-02,5.932145231067023516e+00,3.717156015526504320e-02,9.245867339150950492e-01,4.563496123041156649e-02,1.000000007365609456e+00,0.000000000000000000e+00 +6.759331827529693726e+01,4.073324050898683026e+02,4.072413444924066067e-02,5.933703835413176364e+00,3.733822682193171233e-02,9.262724647399719347e-01,4.563496123041156649e-02,1.000000007167397342e+00,0.000000000000000000e+00 +6.759500356331895432e+01,4.073423981199621835e+02,4.109742996545016902e-02,5.935264871303123968e+00,3.750489348859838146e-02,9.279577527740650034e-01,4.563496123041156649e-02,1.000000007117276768e+00,0.000000000000000000e+00 +6.759668840809283097e+01,4.073523910877013918e+02,4.147239098148295527e-02,5.936828336073265433e+00,3.767156015526505058e-02,9.296425975599350577e-01,4.563496123041156649e-02,1.000000007269455038e+00,0.000000000000000000e+00 +6.759837280916254088e+01,4.073623839928083044e+02,4.184901748692344131e-02,5.938394227059048625e+00,3.783822682193171971e-02,9.313269986418953872e-01,4.563496123041156649e-02,1.000000007063761354e+00,0.000000000000000000e+00 +6.760005676607372038e+01,4.073723768350052978e+02,4.222730947130977353e-02,5.939962541594985268e+00,3.800489348859838884e-02,9.330109555649759301e-01,4.563496123041156649e-02,1.000000006889497417e+00,0.000000000000000000e+00 +6.760174027837366850e+01,4.073823696140148627e+02,4.260726692413384364e-02,5.941533277014664272e+00,3.817156015526505797e-02,9.346944678765215508e-01,4.563496123041156649e-02,1.000000006834959487e+00,0.000000000000000000e+00 +6.760342334561133271e+01,4.073923623295593757e+02,4.298888983484127485e-02,5.943106430650767713e+00,3.833822682193172710e-02,9.363775351256835577e-01,4.563496123041156649e-02,1.000000006999934410e+00,0.000000000000000000e+00 +6.760510596733730893e+01,4.074023549813613272e+02,4.337217819283143566e-02,5.944681999835085939e+00,3.850489348859839622e-02,9.380601568634376886e-01,4.563496123041156649e-02,1.000000006554044418e+00,0.000000000000000000e+00 +6.760678814310386997e+01,4.074123475691430940e+02,4.375713198745742605e-02,5.946259981898532665e+00,3.867156015526506535e-02,9.397423326410180300e-01,4.563496123041156649e-02,1.000000006560773036e+00,0.000000000000000000e+00 +6.760846987246492290e+01,4.074223400926271097e+02,4.414375120802608438e-02,5.947840374171157407e+00,3.883822682193173448e-02,9.414240620131022474e-01,4.563496123041156649e-02,1.000000006526457819e+00,0.000000000000000000e+00 +6.761015115497603745e+01,4.074323325515358079e+02,4.453203584379798741e-02,5.949423173982163249e+00,3.900489348859840361e-02,9.431053445351904596e-01,4.563496123041156649e-02,1.000000006596568403e+00,0.000000000000000000e+00 +6.761183199019443180e+01,4.074423249455916221e+02,4.492198588398745029e-02,5.951008378659920162e+00,3.917156015526507273e-02,9.447861797646791571e-01,4.563496123041156649e-02,1.000000005984438500e+00,0.000000000000000000e+00 +6.761351237767898681e+01,4.074523172745169290e+02,4.531360131776252659e-02,5.952595985531980105e+00,3.933822682193174186e-02,9.464665672592933454e-01,4.563496123041156649e-02,1.000000006431475130e+00,0.000000000000000000e+00 +6.761519231699021759e+01,4.074623095380342193e+02,4.570688213424501517e-02,5.954185991925089461e+00,3.950489348859841099e-02,9.481465065813337034e-01,4.563496123041156649e-02,1.000000005915647527e+00,0.000000000000000000e+00 +6.761687180769030192e+01,4.074723017358659263e+02,4.610182832251044638e-02,5.955778395165208572e+00,3.967156015526508012e-02,9.498259972913515314e-01,4.563496123041156649e-02,1.000000005887666132e+00,0.000000000000000000e+00 +6.761855084934305182e+01,4.074822938677344837e+02,4.649843987158808895e-02,5.957373192577520626e+00,3.983822682193174924e-02,9.515050389539819742e-01,4.563496123041156649e-02,1.000000005606696885e+00,0.000000000000000000e+00 +6.762022944151391357e+01,4.074922859333623819e+02,4.689671677046095694e-02,5.958970381486450307e+00,4.000489348859841837e-02,9.531836311342614110e-01,4.563496123041156649e-02,1.000000005918884272e+00,0.000000000000000000e+00 +6.762190758377001032e+01,4.075022779324719977e+02,4.729665900806580281e-02,5.960569959215676228e+00,4.017156015526508750e-02,9.548617734002906587e-01,4.563496123041156649e-02,1.000000005159509486e+00,0.000000000000000000e+00 +6.762358527568008526e+01,4.075122698647858215e+02,4.769826657329312436e-02,5.962171923088147807e+00,4.033822682193175663e-02,9.565394653190196772e-01,4.563496123041156649e-02,1.000000005460769836e+00,0.000000000000000000e+00 +6.762526251681453004e+01,4.075222617300262300e+02,4.810153945498715083e-02,5.963776270426095039e+00,4.050489348859842575e-02,9.582167064626175845e-01,4.563496123041156649e-02,1.000000004864842751e+00,0.000000000000000000e+00 +6.762693930674537057e+01,4.075322535279157137e+02,4.850647764194586375e-02,5.965382998551048921e+00,4.067156015526509488e-02,9.598934964016093696e-01,4.563496123041156649e-02,1.000000004897707795e+00,0.000000000000000000e+00 +6.762861564504626699e+01,4.075422452581767629e+02,4.891308112292097610e-02,5.966992104783850337e+00,4.083822682193176401e-02,9.615698347107181077e-01,4.563496123041156649e-02,1.000000004255215957e+00,0.000000000000000000e+00 +6.763029153129254212e+01,4.075522369205317545e+02,4.932134988661794617e-02,5.968603586444668707e+00,4.100489348859843314e-02,9.632457209641178686e-01,4.563496123041156649e-02,1.000000004805852161e+00,0.000000000000000000e+00 +6.763196696506112460e+01,4.075622285147031789e+02,4.973128392169597761e-02,5.970217440853012647e+00,4.117156015526510227e-02,9.649211547407502421e-01,4.563496123041156649e-02,1.000000004002538523e+00,0.000000000000000000e+00 +6.763364194593059153e+01,4.075722200404135265e+02,5.014288321676801247e-02,5.971833665327749507e+00,4.133822682193177139e-02,9.665961356169235907e-01,4.563496123041156649e-02,1.000000003421436690e+00,0.000000000000000000e+00 +6.763531647348115428e+01,4.075822114973852308e+02,5.055614776040073810e-02,5.973452257187112480e+00,4.150489348859844052e-02,9.682706631732207470e-01,4.563496123041156649e-02,1.000000003704765605e+00,0.000000000000000000e+00 +6.763699054729465843e+01,4.075922028853407255e+02,5.097107754111458028e-02,5.975073213748719247e+00,4.167156015526510965e-02,9.699447369929312668e-01,4.563496123041156649e-02,1.000000002970653279e+00,0.000000000000000000e+00 +6.763866416695458383e+01,4.076021942040025010e+02,5.138767254738371704e-02,5.976696532329587974e+00,4.183822682193177878e-02,9.716183566578244779e-01,4.563496123041156649e-02,1.000000002835116364e+00,0.000000000000000000e+00 +6.764033733204601617e+01,4.076121854530929909e+02,5.180593276763605787e-02,5.978322210246146184e+00,4.200489348859844790e-02,9.732915217540040187e-01,4.563496123041156649e-02,1.000000001756050416e+00,0.000000000000000000e+00 +6.764201004215568958e+01,4.076221766323346856e+02,5.222585819025327147e-02,5.979950244814249416e+00,4.217156015526511703e-02,9.749642318666208451e-01,4.563496123041156649e-02,1.000000001693249985e+00,0.000000000000000000e+00 +6.764368229687197243e+01,4.076321677414500186e+02,5.264744880357075801e-02,5.981580633349190990e+00,4.233822682193178616e-02,9.766364865857306565e-01,4.563496123041156649e-02,1.000000001127963056e+00,0.000000000000000000e+00 +6.764535409578482472e+01,4.076421587801614805e+02,5.307070459587766298e-02,5.983213373165721549e+00,4.250489348859845529e-02,9.783082855004734402e-01,4.563496123041156649e-02,1.000000000139823042e+00,0.000000000000000000e+00 +6.764702543848586913e+01,4.076521497481915617e+02,5.349562555541689107e-02,5.984848461578058831e+00,4.267156015526512441e-02,9.799796282017462223e-01,4.563496123041156649e-02,9.999999994572086326e-01,0.000000000000000000e+00 +6.764869632456831994e+01,4.076621406452626957e+02,5.392221167038507845e-02,5.986485895899901877e+00,4.283822682193179354e-02,9.816505142832854247e-01,4.563496123041156649e-02,9.999999982310151525e-01,0.000000000000000000e+00 +6.765036675362701146e+01,4.076721314710974298e+02,5.435046292893260661e-02,5.988125673444447017e+00,4.300489348859846267e-02,9.833209433390289744e-01,4.563496123041156649e-02,9.999999975334890046e-01,0.000000000000000000e+00 +6.765203672525842649e+01,4.076821222254181976e+02,5.478037931916360931e-02,5.989767791524399421e+00,4.317156015526513180e-02,9.849909149663249597e-01,4.563496123041156649e-02,9.999999955837870491e-01,0.000000000000000000e+00 +6.765370623906063940e+01,4.076921129079474326e+02,5.521196082913596564e-02,5.991412247451989970e+00,4.333822682193180093e-02,9.866604287611648871e-01,4.563496123041156649e-02,9.999999937971441044e-01,0.000000000000000000e+00 +6.765537529463334465e+01,4.077021035184076823e+02,5.564520744686130005e-02,5.993059038538984140e+00,4.350489348859847005e-02,9.883294843235198579e-01,4.563496123041156649e-02,9.999999916915188747e-01,0.000000000000000000e+00 +6.765704389157785670e+01,4.077120940565213800e+02,5.608011916030498922e-02,5.994708162096699766e+00,4.367156015526513918e-02,9.899980812541706587e-01,4.563496123041156649e-02,9.999999881567872562e-01,0.000000000000000000e+00 +6.765871202949709584e+01,4.077220845220110732e+02,5.651669595738614132e-02,5.996359615436019475e+00,4.383822682193180831e-02,9.916662191536593784e-01,4.563496123041156649e-02,9.999999836898003647e-01,0.000000000000000000e+00 +6.766037970799560242e+01,4.077320749145991954e+02,5.695493782597763066e-02,5.998013395867401343e+00,4.400489348859847744e-02,9.933338976249698193e-01,4.563496123041156649e-02,9.999999765641400806e-01,0.000000000000000000e+00 +6.766204692667952258e+01,4.077420652340082370e+02,5.739484475390606993e-02,5.999669500700893998e+00,4.417156015526514656e-02,9.950011162698183531e-01,4.563496123041156649e-02,9.999999647408199799e-01,0.000000000000000000e+00 +6.766371368515660834e+01,4.077520554799606884e+02,5.783641672895182412e-02,6.001327927246145499e+00,4.433822682193181569e-02,9.966678746881345585e-01,4.563496123041156649e-02,9.999999385093115700e-01,0.000000000000000000e+00 +6.766537998303621748e+01,4.077620456521790970e+02,5.827965373884900352e-02,6.002988672812411330e+00,4.450489348859848482e-02,9.983341724652803340e-01,4.563496123041156649e-02,9.999998452437579566e-01,0.000000000000000000e+00 +6.766704581992931367e+01,4.077720357503858963e+02,5.872455577128547072e-02,6.004651734708541078e+00,4.467156015526515395e-02,1.000000009100576293e+00,4.563496123041156649e-02,4.138059499842551369e-07,0.000000000000000000e+00 +6.766871119544846636e+01,4.077820257743036336e+02,5.917112281390283363e-02,6.006317110242846091e+00,4.483822682193182307e-02,1.000000009789718591e+00,4.563496123041156649e-02,-2.731356794466976350e-10,0.000000000000000000e+00 +6.767037610920783663e+01,4.077920157236547425e+02,5.961935485429645937e-02,6.007982024018517997e+00,4.500489348859849220e-02,1.000000009789263844e+00,4.563496123041156649e-02,-1.776941273233282481e-10,0.000000000000000000e+00 +6.767204056159135916e+01,4.078020055981617702e+02,6.006925188001544652e-02,6.009646476418327943e+00,4.517156015526516133e-02,1.000000009788968081e+00,4.563496123041156649e-02,-2.352564085300715195e-10,0.000000000000000000e+00 +6.767370455298240017e+01,4.078119953975472072e+02,6.052081387856265982e-02,6.011310467825664361e+00,4.533822682193183046e-02,1.000000009788576616e+00,4.563496123041156649e-02,-1.752564903035901746e-10,0.000000000000000000e+00 +6.767536808376384272e+01,4.078219851215336007e+02,6.097404083739471625e-02,6.012973998623384553e+00,4.550489348859849958e-02,1.000000009788285071e+00,4.563496123041156649e-02,-3.687679980090627502e-10,0.000000000000000000e+00 +6.767703115431800143e+01,4.078319747698433844e+02,6.142893274392197123e-02,6.014637069193816465e+00,4.567156015526516871e-02,1.000000009787671784e+00,4.563496123041156649e-02,-2.220965954717727880e-10,0.000000000000000000e+00 +6.767869376502666512e+01,4.078419643421991054e+02,6.188548958550853935e-02,6.016299679918758692e+00,4.583822682193183784e-02,1.000000009787302524e+00,4.563496123041156649e-02,-1.039319996948682983e-10,0.000000000000000000e+00 +6.768035591627112524e+01,4.078519538383233112e+02,6.234371134947228749e-02,6.017961831179483134e+00,4.600489348859850697e-02,1.000000009787129773e+00,4.563496123041156649e-02,-3.827037061587387910e-10,0.000000000000000000e+00 +6.768201760843211900e+01,4.078619432579384352e+02,6.280359802308484174e-02,6.019623523356735006e+00,4.617156015526517610e-02,1.000000009786493838e+00,4.563496123041156649e-02,1.816473275848951742e-10,0.000000000000000000e+00 +6.768367884188985784e+01,4.078719326007670816e+02,6.326514959357155965e-02,6.021284756830732832e+00,4.633822682193184522e-02,1.000000009786795596e+00,4.563496123041156649e-02,-7.083393125759501153e-10,0.000000000000000000e+00 +6.768533961702404156e+01,4.078819218665316839e+02,6.372836604811156491e-02,6.022945531981172884e+00,4.650489348859851435e-02,1.000000009785619204e+00,4.563496123041156649e-02,1.225024105998507771e-10,0.000000000000000000e+00 +6.768699993421384420e+01,4.078919110549548463e+02,6.419324737383773349e-02,6.024605849187223860e+00,4.667156015526518348e-02,1.000000009785822597e+00,4.563496123041156649e-02,-2.674124719998007943e-10,0.000000000000000000e+00 +6.768865979383791398e+01,4.079019001657590024e+02,6.465979355783670057e-02,6.026265708827536649e+00,4.683822682193185261e-02,1.000000009785378730e+00,4.563496123041156649e-02,-3.104391509296507678e-10,0.000000000000000000e+00 +6.769031919627437333e+01,4.079118891986667563e+02,6.512800458714886054e-02,6.027925111280237225e+00,4.700489348859852173e-02,1.000000009784863586e+00,4.563496123041156649e-02,-3.699526242590639355e-10,0.000000000000000000e+00 +6.769197814190083307e+01,4.079218781534005984e+02,6.559788044876833923e-02,6.029584056922931978e+00,4.717156015526519086e-02,1.000000009784249855e+00,4.563496123041156649e-02,1.591876729030464860e-10,0.000000000000000000e+00 +6.769363663109437823e+01,4.079318670296830760e+02,6.606942112964302172e-02,6.031242546132707716e+00,4.733822682193185999e-02,1.000000009784513866e+00,4.563496123041156649e-02,-7.010737485880708289e-10,0.000000000000000000e+00 +6.769529466423158226e+01,4.079418558272366795e+02,6.654262661667456613e-02,6.032900579286134324e+00,4.750489348859852912e-02,1.000000009783351462e+00,4.563496123041156649e-02,2.416589738325965945e-10,0.000000000000000000e+00 +6.769695224168849279e+01,4.079518445457839562e+02,6.701749689671837595e-02,6.034558156759260328e+00,4.767156015526519824e-02,1.000000009783752031e+00,4.563496123041156649e-02,-6.064573336293491218e-10,0.000000000000000000e+00 +6.769860936384064587e+01,4.079618331850474533e+02,6.749403195658360000e-02,6.036215278927622663e+00,4.783822682193186737e-02,1.000000009782747057e+00,4.563496123041156649e-02,-4.918934165246552798e-11,0.000000000000000000e+00 +6.770026603106305174e+01,4.079718217447497182e+02,6.797223178303316016e-02,6.037871946166237791e+00,4.800489348859853650e-02,1.000000009782665567e+00,4.563496123041156649e-02,-6.314588156018480873e-11,0.000000000000000000e+00 +6.770192224373022327e+01,4.079818102246132980e+02,6.845209636278373755e-02,6.039528158849611472e+00,4.817156015526520563e-02,1.000000009782560983e+00,4.563496123041156649e-02,-3.611433226198724503e-10,0.000000000000000000e+00 +6.770357800221614752e+01,4.079917986243607402e+02,6.893362568250574474e-02,6.041183917351734323e+00,4.833822682193187475e-02,1.000000009781963017e+00,4.563496123041156649e-02,-3.297191424078818380e-10,0.000000000000000000e+00 +6.770523330689429997e+01,4.080017869437145350e+02,6.941681972882338125e-02,6.042839222046083592e+00,4.850489348859854388e-02,1.000000009781417232e+00,4.563496123041156649e-02,-3.264550369416890149e-10,0.000000000000000000e+00 +6.770688815813765871e+01,4.080117751823972867e+02,6.990167848831457809e-02,6.044494073305625825e+00,4.867156015526521301e-02,1.000000009780876997e+00,4.563496123041156649e-02,-6.012819897185206888e-11,0.000000000000000000e+00 +6.770854255631866181e+01,4.080217633401314856e+02,7.038820194751103931e-02,6.046148471502816868e+00,4.883822682193188214e-02,1.000000009780777521e+00,4.563496123041156649e-02,-2.110433027713837732e-10,0.000000000000000000e+00 +6.771019650180927840e+01,4.080317514166397359e+02,7.087639009289822822e-02,6.047802417009603637e+00,4.900489348859855127e-02,1.000000009780428467e+00,4.563496123041156649e-02,-1.618172687511203888e-10,0.000000000000000000e+00 +6.771184999498092338e+01,4.080417394116445848e+02,7.136624291091536731e-02,6.049455910197423236e+00,4.917156015526522039e-02,1.000000009780160903e+00,4.563496123041156649e-02,-5.927758047019888706e-10,0.000000000000000000e+00 +6.771350303620454270e+01,4.080517273248685797e+02,7.185776038795542442e-02,6.051108951437205619e+00,4.933822682193188952e-02,1.000000009779181021e+00,4.563496123041156649e-02,9.257514904748541744e-11,0.000000000000000000e+00 +6.771515562585054226e+01,4.080617151560342677e+02,7.235094251036514046e-02,6.052761541099372700e+00,4.950489348859855865e-02,1.000000009779334009e+00,4.563496123041156649e-02,-4.105868202776937085e-10,0.000000000000000000e+00 +6.771680776428885906e+01,4.080717029048641962e+02,7.284578926444501557e-02,6.054413679553843686e+00,4.967156015526522778e-02,1.000000009778655663e+00,4.563496123041156649e-02,-1.787985358393886933e-10,0.000000000000000000e+00 +6.771845945188889004e+01,4.080816905710809692e+02,7.334230063644929520e-02,6.056065367170029745e+00,4.983822682193189690e-02,1.000000009778360344e+00,4.563496123041156649e-02,1.112080662812789848e-10,0.000000000000000000e+00 +6.772011068901954900e+01,4.080916781544071341e+02,7.384047661258601181e-02,6.057716604316840225e+00,5.000489348859856603e-02,1.000000009778543975e+00,4.563496123041156649e-02,-8.706724137162536959e-10,0.000000000000000000e+00 +6.772176147604925234e+01,4.081016656545652381e+02,7.434031717901692926e-02,6.059367391362681765e+00,5.017156015526523516e-02,1.000000009777106680e+00,4.563496123041156649e-02,1.095196168547745806e-10,0.000000000000000000e+00 +6.772341181334589066e+01,4.081116530712778854e+02,7.484182232185759842e-02,6.061017728675455629e+00,5.033822682193190429e-02,1.000000009777287424e+00,4.563496123041156649e-02,-2.318841462513667793e-10,0.000000000000000000e+00 +6.772506170127687142e+01,4.081216404042676231e+02,7.534499202717731547e-02,6.062667616622567479e+00,5.050489348859857341e-02,1.000000009776904841e+00,4.563496123041156649e-02,-2.888907936265290422e-10,0.000000000000000000e+00 +6.772671114020909044e+01,4.081316276532569987e+02,7.584982628099914970e-02,6.064317055570919379e+00,5.067156015526524254e-02,1.000000009776428334e+00,4.563496123041156649e-02,-8.294741130025342444e-11,0.000000000000000000e+00 +6.772836013050896042e+01,4.081416148179686161e+02,7.635632506929991570e-02,6.065966045886915126e+00,5.083822682193191167e-02,1.000000009776291554e+00,4.563496123041156649e-02,-6.167523941361926401e-10,0.000000000000000000e+00 +6.773000867254239665e+01,4.081516018981250795e+02,7.686448837801021505e-02,6.067614587936461135e+00,5.100489348859858080e-02,1.000000009775274812e+00,4.563496123041156649e-02,5.025358443378590993e-11,0.000000000000000000e+00 +6.773165676667478863e+01,4.081615888934489362e+02,7.737431619301439467e-02,6.069262682084964666e+00,5.117156015526524993e-02,1.000000009775357634e+00,4.563496123041156649e-02,-3.908176399846396005e-10,0.000000000000000000e+00 +6.773330441327105689e+01,4.081715758036627903e+02,7.788580850015057455e-02,6.070910328697340042e+00,5.133822682193191905e-02,1.000000009774713705e+00,4.563496123041156649e-02,3.370032213677232295e-12,0.000000000000000000e+00 +6.773495161269562459e+01,4.081815626284892460e+02,7.839896528521063390e-02,6.072557528138003313e+00,5.150489348859858818e-02,1.000000009774719256e+00,4.563496123041156649e-02,-4.221773513135593148e-10,0.000000000000000000e+00 +6.773659836531240330e+01,4.081915493676508504e+02,7.891378653394021114e-02,6.074204280770878484e+00,5.167156015526525731e-02,1.000000009774024035e+00,4.563496123041156649e-02,-3.756252846975204822e-10,0.000000000000000000e+00 +6.773824467148482142e+01,4.082015360208702077e+02,7.943027223203871778e-02,6.075850586959393951e+00,5.183822682193192644e-02,1.000000009773405640e+00,4.563496123041156649e-02,1.270861472261352849e-10,0.000000000000000000e+00 +6.773989053157582418e+01,4.082115225878699221e+02,7.994842236515933842e-02,6.077496447066486951e+00,5.200489348859859556e-02,1.000000009773614806e+00,4.563496123041156649e-02,-5.693436280245990807e-10,0.000000000000000000e+00 +6.774153594594785943e+01,4.082215090683725407e+02,8.046823691890900299e-02,6.079141861454604445e+00,5.217156015526526469e-02,1.000000009772678000e+00,4.563496123041156649e-02,-1.847931853833662504e-10,0.000000000000000000e+00 +6.774318091496287764e+01,4.082314954621007246e+02,8.098971587884842838e-02,6.080786830485699568e+00,5.233822682193193382e-02,1.000000009772374021e+00,4.563496123041156649e-02,-3.736019751333403682e-10,0.000000000000000000e+00 +6.774482543898234610e+01,4.082414817687770778e+02,8.151285923049207682e-02,6.082431354521238731e+00,5.250489348859860295e-02,1.000000009771759624e+00,4.563496123041156649e-02,-1.644995559725718828e-10,0.000000000000000000e+00 +6.774646951836723474e+01,4.082514679881241477e+02,8.203766695930819752e-02,6.084075433922198073e+00,5.267156015526527207e-02,1.000000009771489173e+00,4.563496123041156649e-02,-2.269572691779695932e-10,0.000000000000000000e+00 +6.774811315347804452e+01,4.082614541198645384e+02,8.256413905071879888e-02,6.085719069049067009e+00,5.283822682193194120e-02,1.000000009771116138e+00,4.563496123041156649e-02,-2.444503665246458542e-10,0.000000000000000000e+00 +6.774975634467476482e+01,4.082714401637209107e+02,8.309227549009964853e-02,6.087362260261847346e+00,5.300489348859861033e-02,1.000000009770714460e+00,4.563496123041156649e-02,-2.276205456626312626e-10,0.000000000000000000e+00 +6.775139909231691604e+01,4.082814261194158689e+02,8.362207626278028716e-02,6.089005007920055057e+00,5.317156015526527946e-02,1.000000009770340537e+00,4.563496123041156649e-02,-1.871210504536281690e-10,0.000000000000000000e+00 +6.775304139676353543e+01,4.082914119866719602e+02,8.415354135404404246e-02,6.090647312382721168e+00,5.333822682193194858e-02,1.000000009770033227e+00,4.563496123041156649e-02,-4.613020628271838314e-10,0.000000000000000000e+00 +6.775468325837316286e+01,4.083013977652118456e+02,8.468667074912797355e-02,6.092289174008392649e+00,5.350489348859861771e-02,1.000000009769275833e+00,4.563496123041156649e-02,-7.047879301632358841e-11,0.000000000000000000e+00 +6.775632467750386922e+01,4.083113834547581860e+02,8.522146443322295428e-02,6.093930593155132414e+00,5.367156015526528684e-02,1.000000009769160147e+00,4.563496123041156649e-02,-3.404461018070195740e-10,0.000000000000000000e+00 +6.775796565451322806e+01,4.083213690550335286e+02,8.575792239147358997e-02,6.095571570180522869e+00,5.383822682193195597e-02,1.000000009768601483e+00,4.563496123041156649e-02,-2.896465991538992123e-10,0.000000000000000000e+00 +6.775960618975834393e+01,4.083313545657605346e+02,8.629604460897827289e-02,6.097212105441663255e+00,5.400489348859862510e-02,1.000000009768126308e+00,4.563496123041156649e-02,-2.534412915397420267e-10,0.000000000000000000e+00 +6.776124628359583824e+01,4.083413399866618079e+02,8.683583107078916841e-02,6.098852199295173193e+00,5.417156015526529422e-02,1.000000009767710640e+00,4.563496123041156649e-02,-2.371234364632234668e-10,0.000000000000000000e+00 +6.776288593638183499e+01,4.083513253174600095e+02,8.737728176191220109e-02,6.100491852097192691e+00,5.433822682193196335e-02,1.000000009767321840e+00,4.563496123041156649e-02,-2.454501321302895946e-10,0.000000000000000000e+00 +6.776452514847201769e+01,4.083613105578777436e+02,8.792039666730708247e-02,6.102131064203383026e+00,5.450489348859863248e-02,1.000000009766919495e+00,4.563496123041156649e-02,-2.822351021055801726e-10,0.000000000000000000e+00 +6.776616392022155821e+01,4.083712957076376142e+02,8.846517577188726944e-02,6.103769835968927637e+00,5.467156015526530161e-02,1.000000009766456976e+00,4.563496123041156649e-02,-3.502118874042216929e-10,0.000000000000000000e+00 +6.776780225198515950e+01,4.083812807664622824e+02,8.901161906052003359e-02,6.105408167748533010e+00,5.483822682193197073e-02,1.000000009765883213e+00,4.563496123041156649e-02,-1.202481901783724780e-10,0.000000000000000000e+00 +6.776944014411705552e+01,4.083912657340744090e+02,8.955972651802637796e-02,6.107046059896429568e+00,5.500489348859863986e-02,1.000000009765686260e+00,4.563496123041156649e-02,-2.560197156738932225e-10,0.000000000000000000e+00 +6.777107759697101130e+01,4.084012506101965982e+02,9.010949812918110646e-02,6.108683512766373447e+00,5.517156015526530899e-02,1.000000009765267039e+00,4.563496123041156649e-02,-4.269947883759016198e-10,0.000000000000000000e+00 +6.777271461090029447e+01,4.084112353945515110e+02,9.066093387871276832e-02,6.110320526711645606e+00,5.533822682193197812e-02,1.000000009764568043e+00,4.563496123041156649e-02,-3.014728957662810599e-10,0.000000000000000000e+00 +6.777435118625771793e+01,4.084212200868618083e+02,9.121403375130371360e-02,6.111957102085053606e+00,5.550489348859864724e-02,1.000000009764074660e+00,4.563496123041156649e-02,-2.094047115379024798e-10,0.000000000000000000e+00 +6.777598732339562559e+01,4.084312046868500943e+02,9.176879773159006548e-02,6.113593239238933386e+00,5.567156015526531637e-02,1.000000009763732045e+00,4.563496123041156649e-02,-1.487809473445149732e-10,0.000000000000000000e+00 +6.777762302266586403e+01,4.084411891942390298e+02,9.232522580416170632e-02,6.115228938525149260e+00,5.583822682193198550e-02,1.000000009763488684e+00,4.563496123041156649e-02,-4.494495395083896070e-10,0.000000000000000000e+00 +6.777925828441983924e+01,4.084511736087512759e+02,9.288331795356230547e-02,6.116864200295094811e+00,5.600489348859865463e-02,1.000000009762753717e+00,4.563496123041156649e-02,-1.115095906377099888e-10,0.000000000000000000e+00 +6.778089310900847408e+01,4.084611579301094935e+02,9.344307416428929147e-02,6.118499024899692884e+00,5.617156015526532375e-02,1.000000009762571418e+00,4.563496123041156649e-02,-4.593357961365698619e-10,0.000000000000000000e+00 +6.778252749678222244e+01,4.084711421580363435e+02,9.400449442079389373e-02,6.120133412689399144e+00,5.633822682193199288e-02,1.000000009761820685e+00,4.563496123041156649e-02,-1.583168135651102696e-10,0.000000000000000000e+00 +6.778416144809106925e+01,4.084811262922544870e+02,9.456757870748110084e-02,6.121767364014199408e+00,5.650489348859866201e-02,1.000000009761562003e+00,4.563496123041156649e-02,-2.000897572036231087e-10,0.000000000000000000e+00 +6.778579496328454468e+01,4.084911103324865849e+02,9.513232700870967451e-02,6.123400879223614091e+00,5.667156015526533114e-02,1.000000009761235154e+00,4.563496123041156649e-02,-2.456920309147807479e-10,0.000000000000000000e+00 +6.778742804271168154e+01,4.085010942784552981e+02,9.569873930879217727e-02,6.125033958666696421e+00,5.683822682193200027e-02,1.000000009760833919e+00,4.563496123041156649e-02,-6.208540353228258099e-10,0.000000000000000000e+00 +6.778906068672108631e+01,4.085110781298832876e+02,9.626681559199491700e-02,6.126666602692034225e+00,5.700489348859866939e-02,1.000000009759820285e+00,4.563496123041156649e-02,1.591660120403499767e-11,0.000000000000000000e+00 +6.779069289566086809e+01,4.085210618864932712e+02,9.683655584253800241e-02,6.128298811647749922e+00,5.717156015526533852e-02,1.000000009759846265e+00,4.563496123041156649e-02,-3.260370629633692988e-10,0.000000000000000000e+00 +6.779232466987869543e+01,4.085310455480078531e+02,9.740796004459532920e-02,6.129930585881504967e+00,5.733822682193200765e-02,1.000000009759314246e+00,4.563496123041156649e-02,-3.039376527852111237e-10,0.000000000000000000e+00 +6.779395600972176794e+01,4.085410291141497510e+02,9.798102818229453836e-02,6.131561925740495411e+00,5.750489348859867678e-02,1.000000009758818420e+00,4.563496123041156649e-02,-2.401651152840463393e-10,0.000000000000000000e+00 +6.779558691553681626e+01,4.085510125846416258e+02,9.855576023971708566e-02,6.133192831571456338e+00,5.767156015526534590e-02,1.000000009758426733e+00,4.563496123041156649e-02,-4.575790394163468397e-10,0.000000000000000000e+00 +6.779721738767011630e+01,4.085609959592061955e+02,9.913215620089818603e-02,6.134823303720661869e+00,5.783822682193201503e-02,1.000000009757680663e+00,4.563496123041156649e-02,-2.759826148354806816e-10,0.000000000000000000e+00 +6.779884742646747497e+01,4.085709792375660641e+02,9.971021604982684139e-02,6.136453342533925159e+00,5.800489348859868416e-02,1.000000009757230801e+00,4.563496123041156649e-02,-1.580576975377246449e-11,0.000000000000000000e+00 +6.780047703227424449e+01,4.085809624194440062e+02,1.002899397704458267e-01,6.138082948356601065e+00,5.817156015526535329e-02,1.000000009757205044e+00,4.563496123041156649e-02,-6.674259411388277825e-10,0.000000000000000000e+00 +6.780210620543533651e+01,4.085909455045626828e+02,1.008713273466517180e-01,6.139712121533586142e+00,5.833822682193202241e-02,1.000000009756117691e+00,4.563496123041156649e-02,1.255590046141382271e-10,0.000000000000000000e+00 +6.780373494629517950e+01,4.086009284926447549e+02,1.014543787622948501e-01,6.141340862409316870e+00,5.850489348859869154e-02,1.000000009756322195e+00,4.563496123041156649e-02,-6.338252662380861722e-10,0.000000000000000000e+00 +6.780536325519774721e+01,4.086109113834129403e+02,1.020390940011793590e-01,6.142969171327776756e+00,5.867156015526536067e-02,1.000000009755290131e+00,4.563496123041156649e-02,-2.507056193068558222e-10,0.000000000000000000e+00 +6.780699113248657284e+01,4.086208941765899567e+02,1.026254730470631538e-01,6.144597048632489233e+00,5.883822682193202980e-02,1.000000009754882013e+00,4.563496123041156649e-02,-4.802598676786642870e-11,0.000000000000000000e+00 +6.780861857850473484e+01,4.086308768718984652e+02,1.032135158836579164e-01,6.146224494666525651e+00,5.900489348859869893e-02,1.000000009754803854e+00,4.563496123041156649e-02,-6.795020492710220760e-10,0.000000000000000000e+00 +6.781024559359484272e+01,4.086408594690611835e+02,1.038032224946291299e-01,6.147851509772502610e+00,5.917156015526536805e-02,1.000000009753698293e+00,4.563496123041156649e-02,-1.138491114527410590e-10,0.000000000000000000e+00 +6.781187217809905121e+01,4.086508419678008295e+02,1.043945928635960640e-01,6.149478094292581076e+00,5.933822682193203718e-02,1.000000009753513108e+00,4.563496123041156649e-02,-9.148571507413614036e-12,0.000000000000000000e+00 +6.781349833235908875e+01,4.086608243678400640e+02,1.049876269741317480e-01,6.151104248568472599e+00,5.950489348859870631e-02,1.000000009753498231e+00,4.563496123041156649e-02,-6.833195022168518169e-10,0.000000000000000000e+00 +6.781512405671620058e+01,4.086708066689016619e+02,1.055823248097630257e-01,6.152729972941435754e+00,5.967156015526537544e-02,1.000000009752387342e+00,4.563496123041156649e-02,-9.850161376536215126e-11,0.000000000000000000e+00 +6.781674935151119143e+01,4.086807888707082839e+02,1.061786863539705000e-01,6.154355267752276148e+00,5.983822682193204456e-02,1.000000009752227248e+00,4.563496123041156649e-02,-5.869295244264278061e-10,0.000000000000000000e+00 +6.781837421708442548e+01,4.086907709729827047e+02,1.067767115901885888e-01,6.155980133341352634e+00,6.000489348859871369e-02,1.000000009751273566e+00,4.563496123041156649e-02,2.282726634978984120e-10,0.000000000000000000e+00 +6.781999865377579795e+01,4.087007529754475854e+02,1.073764005018054690e-01,6.157604570048571979e+00,6.017156015526538282e-02,1.000000009751644381e+00,4.563496123041156649e-02,-6.587472527129548961e-10,0.000000000000000000e+00 +6.782162266192479194e+01,4.087107348778257006e+02,1.079777530721631185e-01,6.159228578213395977e+00,6.033822682193205195e-02,1.000000009750574570e+00,4.563496123041156649e-02,-5.317320075824679240e-10,0.000000000000000000e+00 +6.782324624187039319e+01,4.087207166798397679e+02,1.085807692845573019e-01,6.160852158174834337e+00,6.050489348859872107e-02,1.000000009749711261e+00,4.563496123041156649e-02,-3.871394673201585270e-11,0.000000000000000000e+00 +6.782486939395118952e+01,4.087306983812124486e+02,1.091854491222375573e-01,6.162475310271452678e+00,6.067156015526539020e-02,1.000000009749648422e+00,4.563496123041156649e-02,-1.658433407502935106e-10,0.000000000000000000e+00 +6.782649211850528559e+01,4.087406799816665739e+02,1.097917925684072371e-01,6.164098034841371643e+00,6.083822682193205933e-02,1.000000009749379304e+00,4.563496123041156649e-02,-5.509036469283694909e-10,0.000000000000000000e+00 +6.782811441587035972e+01,4.087506614809248049e+02,1.103997996062234532e-01,6.165720332222265121e+00,6.100489348859872846e-02,1.000000009748485574e+00,4.563496123041156649e-02,-1.545674311893327363e-10,0.000000000000000000e+00 +6.782973628638364971e+01,4.087606428787099162e+02,1.110094702187971322e-01,6.167342202751362024e+00,6.117156015526539758e-02,1.000000009748234886e+00,4.563496123041156649e-02,-2.994932612447260435e-10,0.000000000000000000e+00 +6.783135773038192440e+01,4.087706241747446256e+02,1.116208043891929874e-01,6.168963646765449838e+00,6.133822682193206671e-02,1.000000009747749274e+00,4.563496123041156649e-02,-6.202386913523917839e-10,0.000000000000000000e+00 +6.783297874820154050e+01,4.087806053687516510e+02,1.122338021004294917e-01,6.170584664600871960e+00,6.150489348859873584e-02,1.000000009746743856e+00,4.563496123041156649e-02,-7.385081733301812807e-11,0.000000000000000000e+00 +6.783459934017839998e+01,4.087905864604537669e+02,1.128484633354789463e-01,6.172205256593529477e+00,6.167156015526540497e-02,1.000000009746624174e+00,4.563496123041156649e-02,-3.209722423612070449e-10,0.000000000000000000e+00 +6.783621950664796429e+01,4.088005674495737480e+02,1.134647880772674255e-01,6.173825423078884711e+00,6.183822682193207410e-02,1.000000009746104146e+00,4.563496123041156649e-02,-3.168068152866810441e-10,0.000000000000000000e+00 +6.783783924794525433e+01,4.088105483358343122e+02,1.140827763086748048e-01,6.175445164391957675e+00,6.200489348859874322e-02,1.000000009745591001e+00,4.563496123041156649e-02,-3.684479645098812565e-10,0.000000000000000000e+00 +6.783945856440485045e+01,4.088205291189581772e+02,1.147024280125347323e-01,6.177064480867329621e+00,6.217156015526541235e-02,1.000000009744994367e+00,4.563496123041156649e-02,-1.056119558532984997e-10,0.000000000000000000e+00 +6.784107745636089248e+01,4.088305097986681744e+02,1.153237431716346573e-01,6.178683372839143040e+00,6.233822682193208148e-02,1.000000009744823393e+00,4.563496123041156649e-02,-5.118720483934878062e-10,0.000000000000000000e+00 +6.784269592414707972e+01,4.088404903746870218e+02,1.159467217687158436e-01,6.180301840641103439e+00,6.250489348859875061e-02,1.000000009743994944e+00,4.563496123041156649e-02,-5.375309599607015174e-10,0.000000000000000000e+00 +6.784431396809668513e+01,4.088504708467374371e+02,1.165713637864733143e-01,6.181919884606477567e+00,6.267156015526541279e-02,1.000000009743125196e+00,4.563496123041156649e-02,-1.478356929256724633e-10,0.000000000000000000e+00 +6.784593158854254114e+01,4.088604512145422518e+02,1.171976692075559073e-01,6.183537505068096962e+00,6.283822682193207498e-02,1.000000009742886053e+00,4.563496123041156649e-02,-3.256806149658847512e-10,0.000000000000000000e+00 +6.784754878581705384e+01,4.088704314778242406e+02,1.178256380145662474e-01,6.185154702358358847e+00,6.300489348859873717e-02,1.000000009742359364e+00,4.563496123041156649e-02,-1.730459092679555143e-11,0.000000000000000000e+00 +6.784916556025217460e+01,4.088804116363061212e+02,1.184552701900607602e-01,6.186771476809224346e+00,6.317156015526539936e-02,1.000000009742331386e+00,4.563496123041156649e-02,-5.457865954153328289e-10,0.000000000000000000e+00 +6.785078191217942845e+01,4.088903916897107251e+02,1.190865657165496583e-01,6.188387828752222042e+00,6.333822682193206155e-02,1.000000009741449203e+00,4.563496123041156649e-02,-5.145997498940307027e-10,0.000000000000000000e+00 +6.785239784192991408e+01,4.089003716377607702e+02,1.197195245764969690e-01,6.190003758518445309e+00,6.350489348859872374e-02,1.000000009740617646e+00,4.563496123041156649e-02,-2.252734923094242150e-10,0.000000000000000000e+00 +6.785401334983428967e+01,4.089103514801790880e+02,1.203541467523204789e-01,6.191619266438556757e+00,6.367156015526538593e-02,1.000000009740253715e+00,4.563496123041156649e-02,-3.199196026538180658e-10,0.000000000000000000e+00 +6.785562843622278706e+01,4.089203312166883961e+02,1.209904322263918169e-01,6.193234352842788226e+00,6.383822682193204812e-02,1.000000009739737017e+00,4.563496123041156649e-02,-4.192906364734496829e-10,0.000000000000000000e+00 +6.785724310142521176e+01,4.089303108470115262e+02,1.216283809810363714e-01,6.194849018060939905e+00,6.400489348859871030e-02,1.000000009739060003e+00,4.563496123041156649e-02,-1.426427516488625249e-10,0.000000000000000000e+00 +6.785885734577092876e+01,4.089402903708712529e+02,1.222679929985333452e-01,6.196463262422382101e+00,6.417156015526537249e-02,1.000000009738829743e+00,4.563496123041156649e-02,-4.716555160563002124e-10,0.000000000000000000e+00 +6.786047116958889092e+01,4.089502697879904076e+02,1.229092682611157422e-01,6.198077086256057022e+00,6.433822682193203468e-02,1.000000009738068574e+00,4.563496123041156649e-02,-3.422732700268674322e-10,0.000000000000000000e+00 +6.786208457320759635e+01,4.089602490980917082e+02,1.235522067509703670e-01,6.199690489890476996e+00,6.450489348859869687e-02,1.000000009737516349e+00,4.563496123041156649e-02,-3.943981420015111328e-10,0.000000000000000000e+00 +6.786369755695514527e+01,4.089702283008979862e+02,1.241968084502378111e-01,6.201303473653728027e+00,6.467156015526535906e-02,1.000000009736880191e+00,4.563496123041156649e-02,-2.438606750274796965e-10,0.000000000000000000e+00 +6.786531012115918315e+01,4.089802073961320730e+02,1.248430733410124671e-01,6.202916037873468902e+00,6.483822682193202125e-02,1.000000009736486950e+00,4.563496123041156649e-02,-1.886933936187474194e-10,0.000000000000000000e+00 +6.786692226614695755e+01,4.089901863835167433e+02,1.254910014053425282e-01,6.204528182876932973e+00,6.500489348859868344e-02,1.000000009736182749e+00,4.563496123041156649e-02,-5.262745274812160096e-10,0.000000000000000000e+00 +6.786853399224526129e+01,4.090001652627748285e+02,1.261405926252300025e-01,6.206139908990928156e+00,6.517156015526534563e-02,1.000000009735334539e+00,4.563496123041156649e-02,-5.286160995796418862e-10,0.000000000000000000e+00 +6.787014529978048927e+01,4.090101440336291034e+02,1.267918469826306849e-01,6.207751216541836925e+00,6.533822682193200782e-02,1.000000009734482775e+00,4.563496123041156649e-02,-1.485912684325208088e-10,0.000000000000000000e+00 +6.787175618907859587e+01,4.090201226958023994e+02,1.274447644594541851e-01,6.209362105855618985e+00,6.550489348859867000e-02,1.000000009734243411e+00,4.563496123041156649e-02,-3.673004267401440881e-10,0.000000000000000000e+00 +6.787336666046510913e+01,4.090301012490174912e+02,1.280993450375638998e-01,6.210972577257812155e+00,6.567156015526533219e-02,1.000000009733651885e+00,4.563496123041156649e-02,-1.101911248741814146e-10,0.000000000000000000e+00 +6.787497671426515922e+01,4.090400796929972671e+02,1.287555886987770404e-01,6.212582631073530592e+00,6.583822682193199438e-02,1.000000009733474471e+00,4.563496123041156649e-02,-6.998053622683468867e-10,0.000000000000000000e+00 +6.787658635080343572e+01,4.090500580274645017e+02,1.294134954248646052e-01,6.214192267627468347e+00,6.600489348859865657e-02,1.000000009732348039e+00,4.563496123041156649e-02,-3.743473003153435031e-10,0.000000000000000000e+00 +6.787819557040420193e+01,4.090600362521420266e+02,1.300730651975514074e-01,6.215801487243896695e+00,6.617156015526531876e-02,1.000000009731745632e+00,4.563496123041156649e-02,-1.122090555833851892e-10,0.000000000000000000e+00 +6.787980437339132322e+01,4.090700143667526731e+02,1.307342979985160747e-01,6.217410290246669469e+00,6.633822682193198095e-02,1.000000009731565109e+00,4.563496123041156649e-02,-5.501461510045263995e-10,0.000000000000000000e+00 +6.788141276008822445e+01,4.090799923710192729e+02,1.313971938093910496e-01,6.219018676959221281e+00,6.650489348859864314e-02,1.000000009730680262e+00,4.563496123041156649e-02,-2.645803528501270958e-10,0.000000000000000000e+00 +6.788302073081791832e+01,4.090899702646646574e+02,1.320617526117625340e-01,6.220626647704566636e+00,6.667156015526530533e-02,1.000000009730254824e+00,4.563496123041156649e-02,-2.339848657320405861e-10,0.000000000000000000e+00 +6.788462828590301967e+01,4.090999480474116581e+02,1.327279743871705442e-01,6.222234202805304371e+00,6.683822682193196751e-02,1.000000009729878681e+00,4.563496123041156649e-02,-7.506306337355099437e-10,0.000000000000000000e+00 +6.788623542566568858e+01,4.091099257189831064e+02,1.333958591171089392e-01,6.223841342583615877e+00,6.700489348859862970e-02,1.000000009728672312e+00,4.563496123041156649e-02,-4.187370287851067653e-11,0.000000000000000000e+00 +6.788784215042770143e+01,4.091199032791018340e+02,1.340654067830253648e-01,6.225448067361265103e+00,6.717156015526529189e-02,1.000000009728605033e+00,4.563496123041156649e-02,-4.623884338822089182e-10,0.000000000000000000e+00 +6.788944846051040827e+01,4.091298807274907290e+02,1.347366173663212818e-01,6.227054377459603884e+00,6.733822682193195408e-02,1.000000009727862293e+00,4.563496123041156649e-02,-2.371302766888843026e-10,0.000000000000000000e+00 +6.789105435623474705e+01,4.091398580638726230e+02,1.354094908483519377e-01,6.228660273199566610e+00,6.750489348859861627e-02,1.000000009727481487e+00,4.563496123041156649e-02,-6.888924280092255111e-10,0.000000000000000000e+00 +6.789265983792124359e+01,4.091498352879703475e+02,1.360840272104264226e-01,6.230265754901675557e+00,6.767156015526527846e-02,1.000000009726375483e+00,4.563496123041156649e-02,-3.901179252712766642e-11,0.000000000000000000e+00 +6.789426490588999741e+01,4.091598123995067908e+02,1.367602264338075857e-01,6.231870822886038219e+00,6.783822682193194065e-02,1.000000009726312866e+00,4.563496123041156649e-02,-6.439987834053001223e-10,0.000000000000000000e+00 +6.789586956046071009e+01,4.091697893982047844e+02,1.374380884997121466e-01,6.233475477472352644e+00,6.800489348859860284e-02,1.000000009725279471e+00,4.563496123041156649e-02,-3.782771535994364537e-10,0.000000000000000000e+00 +6.789747380195265691e+01,4.091797662837872167e+02,1.381176133893105840e-01,6.235079718979902097e+00,6.817156015526526502e-02,1.000000009724672623e+00,4.563496123041156649e-02,-2.181918121094101042e-10,0.000000000000000000e+00 +6.789907763068471525e+01,4.091897430559769191e+02,1.387988010837272190e-01,6.236683547727561283e+00,6.833822682193192721e-02,1.000000009724322680e+00,4.563496123041156649e-02,-1.058003957879773319e-10,0.000000000000000000e+00 +6.790068104697535034e+01,4.091997197144967799e+02,1.394816515640401600e-01,6.238286964033794568e+00,6.850489348859858940e-02,1.000000009724153038e+00,4.563496123041156649e-02,-1.019075428363361400e-09,0.000000000000000000e+00 +6.790228405114262955e+01,4.092096962590696307e+02,1.401661648112813296e-01,6.239889968216656868e+00,6.867156015526525159e-02,1.000000009722519456e+00,4.563496123041156649e-02,2.129565608554928710e-10,0.000000000000000000e+00 +6.790388664350417969e+01,4.092196726894184167e+02,1.408523408064364935e-01,6.241492560593791872e+00,6.883822682193191378e-02,1.000000009722860739e+00,4.563496123041156649e-02,-8.440068576035783935e-10,0.000000000000000000e+00 +6.790548882437724387e+01,4.092296490052659692e+02,1.415401795304452037e-01,6.243094741482440924e+00,6.900489348859857597e-02,1.000000009721508487e+00,4.563496123041156649e-02,2.176405443449754368e-11,0.000000000000000000e+00 +6.790709059407866732e+01,4.092396252063351767e+02,1.422296809642008275e-01,6.244696511199432365e+00,6.917156015526523816e-02,1.000000009721543348e+00,4.563496123041156649e-02,-5.881962161892849110e-10,0.000000000000000000e+00 +6.790869195292485472e+01,4.092496012923489275e+02,1.429208450885505466e-01,6.246297870061193080e+00,6.933822682193190035e-02,1.000000009720601435e+00,4.563496123041156649e-02,-5.345331286758145326e-10,0.000000000000000000e+00 +6.791029290123184126e+01,4.092595772630300530e+02,1.436136718842953297e-01,6.247898818383740505e+00,6.950489348859856253e-02,1.000000009719745675e+00,4.563496123041156649e-02,-9.988648018125030434e-11,0.000000000000000000e+00 +6.791189343931523581e+01,4.092695531181014985e+02,1.443081613321900158e-01,6.249499356482688839e+00,6.967156015526522472e-02,1.000000009719585803e+00,4.563496123041156649e-02,-6.066882815357014327e-10,0.000000000000000000e+00 +6.791349356749024935e+01,4.092795288572861523e+02,1.450043134129432310e-01,6.251099484673249052e+00,6.983822682193188691e-02,1.000000009718615024e+00,4.563496123041156649e-02,-6.039287704998243016e-10,0.000000000000000000e+00 +6.791509328607168072e+01,4.092895044803069027e+02,1.457021281072174157e-01,6.252699203270226214e+00,7.000489348859854910e-02,1.000000009717648908e+00,4.563496123041156649e-02,-2.540731967478507586e-11,0.000000000000000000e+00 +6.791669259537393089e+01,4.092994799868866949e+02,1.464016053956288255e-01,6.254298512588023939e+00,7.017156015526521129e-02,1.000000009717608274e+00,4.563496123041156649e-02,-5.410504712042949762e-10,0.000000000000000000e+00 +6.791829149571101709e+01,4.093094553767483603e+02,1.471027452587475304e-01,6.255897412940645275e+00,7.033822682193187348e-02,1.000000009716743188e+00,4.563496123041156649e-02,-3.481055203386874983e-10,0.000000000000000000e+00 +6.791988998739653027e+01,4.093194306496148442e+02,1.478055476770974430e-01,6.257495904641689144e+00,7.050489348859853567e-02,1.000000009716186744e+00,4.563496123041156649e-02,-4.215570686901344952e-10,0.000000000000000000e+00 +6.792148807074366346e+01,4.093294058052090350e+02,1.485100126311562629e-01,6.259093988004355680e+00,7.067156015526519786e-02,1.000000009715513061e+00,4.563496123041156649e-02,-3.456427754714848461e-10,0.000000000000000000e+00 +6.792308574606522598e+01,4.093393808432538776e+02,1.492161401013555044e-01,6.260691663341444446e+00,7.083822682193186004e-02,1.000000009714960836e+00,4.563496123041156649e-02,-3.993909014350364887e-10,0.000000000000000000e+00 +6.792468301367361505e+01,4.093493557634722606e+02,1.499239300680805242e-01,6.262288930965356215e+00,7.100489348859852223e-02,1.000000009714322902e+00,4.563496123041156649e-02,-5.136534600100000824e-10,0.000000000000000000e+00 +6.792627987388084421e+01,4.093593305655871291e+02,1.506333825116705216e-01,6.263885791188092966e+00,7.117156015526518442e-02,1.000000009713502669e+00,4.563496123041156649e-02,-2.703835817034961409e-10,0.000000000000000000e+00 +6.792787632699850064e+01,4.093693052493213713e+02,1.513444974124184550e-01,6.265482244321258776e+00,7.133822682193184661e-02,1.000000009713071014e+00,4.563496123041156649e-02,-6.435767665953250628e-10,0.000000000000000000e+00 +6.792947237333780208e+01,4.093792798143979326e+02,1.520572747505711253e-01,6.267078290676061592e+00,7.150489348859850880e-02,1.000000009712043836e+00,4.563496123041156649e-02,-1.678234533243412323e-10,0.000000000000000000e+00 +6.793106801320955412e+01,4.093892542605397011e+02,1.527717145063291759e-01,6.268673930563311458e+00,7.167156015526517099e-02,1.000000009711776050e+00,4.563496123041156649e-02,-5.147339486915731079e-10,0.000000000000000000e+00 +6.793266324692417868e+01,4.093992285874696790e+02,1.534878166598470373e-01,6.270269164293424957e+00,7.183822682193183318e-02,1.000000009710954929e+00,4.563496123041156649e-02,-5.651262244358748451e-10,0.000000000000000000e+00 +6.793425807479168554e+01,4.094092027949107546e+02,1.542055811912330099e-01,6.271863992176421654e+00,7.200489348859849537e-02,1.000000009710053650e+00,4.563496123041156649e-02,-2.452427703186250677e-10,0.000000000000000000e+00 +6.793585249712171503e+01,4.094191768825858730e+02,1.549250080805491814e-01,6.273458414521927651e+00,7.217156015526515755e-02,1.000000009709662629e+00,4.563496123041156649e-02,-5.287780911250647698e-10,0.000000000000000000e+00 +6.793744651422348113e+01,4.094291508502179795e+02,1.556460973078114540e-01,6.275052431639176476e+00,7.233822682193181974e-02,1.000000009708819748e+00,4.563496123041156649e-02,-2.928803913017207980e-10,0.000000000000000000e+00 +6.793904012640584256e+01,4.094391246975300191e+02,1.563688488529896004e-01,6.276646043837007305e+00,7.250489348859848193e-02,1.000000009708353010e+00,4.563496123041156649e-02,-5.112074694400923370e-10,0.000000000000000000e+00 +6.794063333397723170e+01,4.094490984242449372e+02,1.570932626960071798e-01,6.278239251423868517e+00,7.267156015526514412e-02,1.000000009707538551e+00,4.563496123041156649e-02,-4.077593776056168652e-10,0.000000000000000000e+00 +6.794222613724571147e+01,4.094590720300856788e+02,1.578193388167415667e-01,6.279832054707815914e+00,7.283822682193180631e-02,1.000000009706889070e+00,4.563496123041156649e-02,-6.061469091503929783e-10,0.000000000000000000e+00 +6.794381853651894687e+01,4.094690455147752459e+02,1.585470771950240054e-01,6.281424453996515389e+00,7.300489348859846850e-02,1.000000009705923842e+00,4.563496123041156649e-02,-3.283256592092120199e-10,0.000000000000000000e+00 +6.794541053210421921e+01,4.094790188780365270e+02,1.592764778106395274e-01,6.283016449597242037e+00,7.317156015526513069e-02,1.000000009705401149e+00,4.563496123041156649e-02,-1.967104966456492489e-10,0.000000000000000000e+00 +6.794700212430841191e+01,4.094889921195925240e+02,1.600075406433270064e-01,6.284608041816882817e+00,7.333822682193179288e-02,1.000000009705088067e+00,4.563496123041156649e-02,-8.343475129018594910e-10,0.000000000000000000e+00 +6.794859331343802467e+01,4.094989652391662389e+02,1.607402656727791312e-01,6.286199230961935669e+00,7.350489348859845506e-02,1.000000009703760462e+00,4.563496123041156649e-02,-5.736806327595002227e-11,0.000000000000000000e+00 +6.795018409979915930e+01,4.095089382364805601e+02,1.614746528786424606e-01,6.287790017338508619e+00,7.367156015526511725e-02,1.000000009703669201e+00,4.563496123041156649e-02,-9.436712017849785025e-10,0.000000000000000000e+00 +6.795177448369754813e+01,4.095189111112585465e+02,1.622107022405173127e-01,6.289380401252326003e+00,7.383822682193177944e-02,1.000000009702168402e+00,4.563496123041156649e-02,9.845487054256117972e-11,0.000000000000000000e+00 +6.795336446543851139e+01,4.095288838632230863e+02,1.629484137379579034e-01,6.290970383008721356e+00,7.400489348859844163e-02,1.000000009702324943e+00,4.563496123041156649e-02,-7.136639654079859270e-10,0.000000000000000000e+00 +6.795495404532701400e+01,4.095388564920972385e+02,1.636877873504722358e-01,6.292559962912647187e+00,7.417156015526510382e-02,1.000000009701190518e+00,4.563496123041156649e-02,-4.872137491379913323e-10,0.000000000000000000e+00 +6.795654322366762301e+01,4.095488289976039482e+02,1.644288230575221277e-01,6.294149141268666092e+00,7.433822682193176601e-02,1.000000009700416248e+00,4.563496123041156649e-02,-1.934253293426520558e-10,0.000000000000000000e+00 +6.795813200076450755e+01,4.095588013794661606e+02,1.651715208385232947e-01,6.295737918380958753e+00,7.450489348859842820e-02,1.000000009700108938e+00,4.563496123041156649e-02,-8.047909715562612732e-10,0.000000000000000000e+00 +6.795972037692146728e+01,4.095687736374069345e+02,1.659158806728452118e-01,6.297326294553322157e+00,7.467156015526509039e-02,1.000000009698830628e+00,4.563496123041156649e-02,-1.257060308913135221e-10,0.000000000000000000e+00 +6.796130835244191815e+01,4.095787457711492152e+02,1.666619025398112242e-01,6.298914270089167822e+00,7.483822682193175257e-02,1.000000009698631009e+00,4.563496123041156649e-02,-5.359588213900520946e-10,0.000000000000000000e+00 +6.796289592762887821e+01,4.095887177804160046e+02,1.674095864186985194e-01,6.300501845291528014e+00,7.500489348859841476e-02,1.000000009697780134e+00,4.563496123041156649e-02,-5.419696724442286707e-10,0.000000000000000000e+00 +6.796448310278501026e+01,4.095986896649303048e+02,1.681589322887380999e-01,6.302089020463050417e+00,7.517156015526507695e-02,1.000000009696919934e+00,4.563496123041156649e-02,-7.626429523793470587e-10,0.000000000000000000e+00 +6.796606987821257917e+01,4.096086614244151747e+02,1.689099401291147828e-01,6.303675795906002577e+00,7.533822682193173914e-02,1.000000009695709791e+00,4.563496123041156649e-02,-5.234867534273590503e-11,0.000000000000000000e+00 +6.796765625421346613e+01,4.096186330585935593e+02,1.696626099189672554e-01,6.305262171922271008e+00,7.550489348859840133e-02,1.000000009695626746e+00,4.563496123041156649e-02,-4.417156008166226284e-10,0.000000000000000000e+00 +6.796924223108918284e+01,4.096286045671884608e+02,1.704169416373880197e-01,6.306848148813364752e+00,7.567156015526506352e-02,1.000000009694926195e+00,4.563496123041156649e-02,-7.842248990942400391e-10,0.000000000000000000e+00 +6.797082780914085731e+01,4.096385759499229380e+02,1.711729352634233925e-01,6.308433726880410930e+00,7.583822682193172571e-02,1.000000009693682745e+00,4.563496123041156649e-02,-2.847732220422977268e-10,0.000000000000000000e+00 +6.797241298866923387e+01,4.096485472065199929e+02,1.719305907760735885e-01,6.310018906424158303e+00,7.600489348859838790e-02,1.000000009693231329e+00,4.563496123041156649e-02,-6.206898052298686469e-10,0.000000000000000000e+00 +6.797399776997468734e+01,4.096585183367026275e+02,1.726899081542926095e-01,6.311603687744979929e+00,7.617156015526505008e-02,1.000000009692247671e+00,4.563496123041156649e-02,-2.881396717225576943e-10,0.000000000000000000e+00 +6.797558215335722309e+01,4.096684893401939007e+02,1.734508873769882997e-01,6.313188071142869617e+00,7.633822682193171227e-02,1.000000009691791147e+00,4.563496123041156649e-02,-2.577927396625709019e-10,0.000000000000000000e+00 +6.797716613911644856e+01,4.096784602167168146e+02,1.742135284230223458e-01,6.314772056917446363e+00,7.650489348859837446e-02,1.000000009691382807e+00,4.563496123041156649e-02,-7.933427314652277575e-10,0.000000000000000000e+00 +6.797874972755160172e+01,4.096884309659943710e+02,1.749778312712102768e-01,6.316355645367952576e+00,7.667156015526503665e-02,1.000000009690126479e+00,4.563496123041156649e-02,-7.406669536178113560e-10,0.000000000000000000e+00 +6.798033291896156527e+01,4.096984015877496290e+02,1.757437959003214645e-01,6.317938836793254076e+00,7.683822682193169884e-02,1.000000009688953861e+00,4.563496123041156649e-02,-6.172602625007587275e-12,0.000000000000000000e+00 +6.798191571364482400e+01,4.097083720817056474e+02,1.765114222890790951e-01,6.319521631491843650e+00,7.700489348859836103e-02,1.000000009688944091e+00,4.563496123041156649e-02,-6.244309793710090764e-10,0.000000000000000000e+00 +6.798349811189949321e+01,4.097183424475854849e+02,1.772807104161602254e-01,6.321104029761841936e+00,7.717156015526502322e-02,1.000000009687955993e+00,4.563496123041156649e-02,-7.291530809053263082e-10,0.000000000000000000e+00 +6.798508011402331874e+01,4.097283126851121438e+02,1.780516602601957543e-01,6.322686031900992987e+00,7.733822682193168541e-02,1.000000009686802471e+00,4.563496123041156649e-02,-2.257500661805699557e-10,0.000000000000000000e+00 +6.798666172031367694e+01,4.097382827940086827e+02,1.788242717997703957e-01,6.324267638206669595e+00,7.750489348859834760e-02,1.000000009686445424e+00,4.563496123041156649e-02,-7.939739804823211015e-10,0.000000000000000000e+00 +6.798824293106756045e+01,4.097482527739981606e+02,1.795985450134227057e-01,6.325848848975874184e+00,7.767156015526500978e-02,1.000000009685189983e+00,4.563496123041156649e-02,-2.074624638734282614e-10,0.000000000000000000e+00 +6.798982374658160666e+01,4.097582226248036363e+02,1.803744798796451110e-01,6.327429664505235252e+00,7.783822682193167197e-02,1.000000009684862023e+00,4.563496123041156649e-02,-5.022773541664408437e-10,0.000000000000000000e+00 +6.799140416715208346e+01,4.097681923461481688e+02,1.811520763768838804e-01,6.329010085091013593e+00,7.800489348859833416e-02,1.000000009684068214e+00,4.563496123041156649e-02,-5.150507123432248871e-10,0.000000000000000000e+00 +6.799298419307486085e+01,4.097781619377548168e+02,1.819313344835390700e-01,6.330590111029097855e+00,7.817156015526499635e-02,1.000000009683254421e+00,4.563496123041156649e-02,-8.602721086492088468e-10,0.000000000000000000e+00 +6.799456382464548199e+01,4.097881313993466392e+02,1.827122541779646614e-01,6.332169742615008090e+00,7.833822682193165854e-02,1.000000009681895508e+00,4.563496123041156649e-02,-1.546626541698905412e-11,0.000000000000000000e+00 +6.799614306215907789e+01,4.097981007306466950e+02,1.834948354384684233e-01,6.333748980143894869e+00,7.850489348859832073e-02,1.000000009681871083e+00,4.563496123041156649e-02,-7.306117033999977435e-10,0.000000000000000000e+00 +6.799772190591043852e+01,4.098080699313780997e+02,1.842790782433119945e-01,6.335327823910543721e+00,7.867156015526498292e-02,1.000000009680717561e+00,4.563496123041156649e-02,-7.701821366425993579e-10,0.000000000000000000e+00 +6.799930035619398438e+01,4.098180390012639123e+02,1.850649825707108287e-01,6.336906274209368917e+00,7.883822682193164511e-02,1.000000009679501867e+00,4.563496123041156649e-02,-3.292557489242825143e-11,0.000000000000000000e+00 +6.800087841330376648e+01,4.098280079400271916e+02,1.858525483988342775e-01,6.338484331334419686e+00,7.900489348859830729e-02,1.000000009679449908e+00,4.563496123041156649e-02,-9.146863193386065629e-10,0.000000000000000000e+00 +6.800245607753345212e+01,4.098379767473910533e+02,1.866417757058055071e-01,6.340061995579381104e+00,7.917156015526496948e-02,1.000000009678006840e+00,4.563496123041156649e-02,-4.609060460742252104e-10,0.000000000000000000e+00 +6.800403334917638176e+01,4.098479454230785564e+02,1.874326644697015265e-01,6.341639267237568767e+00,7.933822682193163167e-02,1.000000009677279866e+00,4.563496123041156649e-02,-3.537214485605127340e-10,0.000000000000000000e+00 +6.800561022852548376e+01,4.098579139668128164e+02,1.882252146685532146e-01,6.343216146601936778e+00,7.950489348859829386e-02,1.000000009676722090e+00,4.563496123041156649e-02,-4.908542077443678605e-10,0.000000000000000000e+00 +6.800718671587335962e+01,4.098678823783169491e+02,1.890194262803452652e-01,6.344792633965074202e+00,7.967156015526495605e-02,1.000000009675948265e+00,4.563496123041156649e-02,-7.700648238462968859e-10,0.000000000000000000e+00 +6.800876281151224134e+01,4.098778506573140135e+02,1.898152992830162700e-01,6.346368729619205951e+00,7.983822682193161824e-02,1.000000009674734569e+00,4.563496123041156649e-02,-3.718817937473658072e-10,0.000000000000000000e+00 +6.801033851573399147e+01,4.098878188035271251e+02,1.906128336544586355e-01,6.347944433856193669e+00,8.000489348859828043e-02,1.000000009674148593e+00,4.563496123041156649e-02,-6.230108517445293551e-10,0.000000000000000000e+00 +6.801191382883010306e+01,4.098977868166793996e+02,1.914120293725186384e-01,6.349519746967538403e+00,8.017156015526494262e-02,1.000000009673167156e+00,4.563496123041156649e-02,-7.031054622547630402e-10,0.000000000000000000e+00 +6.801348875109171388e+01,4.099077546964939529e+02,1.922128864149963978e-01,6.351094669244377933e+00,8.033822682193160480e-02,1.000000009672059820e+00,4.563496123041156649e-02,-1.480737622007532184e-10,0.000000000000000000e+00 +6.801506328280959224e+01,4.099177224426939006e+02,1.930154047596458755e-01,6.352669200977489439e+00,8.050489348859826699e-02,1.000000009671826673e+00,4.563496123041156649e-02,-6.429405056808200302e-10,0.000000000000000000e+00 +6.801663742427416537e+01,4.099276900550023583e+02,1.938195843841749033e-01,6.354243342457291277e+00,8.067156015526492918e-02,1.000000009670814594e+00,4.563496123041156649e-02,-1.006977495501663823e-09,0.000000000000000000e+00 +6.801821117577549103e+01,4.099376575331424419e+02,1.946254252662451556e-01,6.355817093973839427e+00,8.083822682193159137e-02,1.000000009669229861e+00,4.563496123041156649e-02,-5.574535837648367903e-11,0.000000000000000000e+00 +6.801978453760327170e+01,4.099476248768372670e+02,1.954329273834721492e-01,6.357390455816831043e+00,8.100489348859825356e-02,1.000000009669142154e+00,4.563496123041156649e-02,-5.510981080260914046e-10,0.000000000000000000e+00 +6.802135751004684039e+01,4.099575920858099494e+02,1.962420907134252712e-01,6.358963428275608010e+00,8.117156015526491575e-02,1.000000009668275291e+00,4.563496123041156649e-02,-9.505405751209260349e-10,0.000000000000000000e+00 +6.802293009339517482e+01,4.099675591597836615e+02,1.970529152336277789e-01,6.360536011639150722e+00,8.133822682193157794e-02,1.000000009666780487e+00,4.563496123041156649e-02,-4.251091344505706793e-10,0.000000000000000000e+00 +6.802450228793691167e+01,4.099775260984815191e+02,1.978654009215567722e-01,6.362108206196082527e+00,8.150489348859824013e-02,1.000000009666112133e+00,4.563496123041156649e-02,-3.024530330512267907e-10,0.000000000000000000e+00 +6.802607409396030391e+01,4.099874929016266947e+02,1.986795477546431932e-01,6.363680012234672390e+00,8.167156015526490231e-02,1.000000009665636735e+00,4.563496123041156649e-02,-8.315627491484410499e-10,0.000000000000000000e+00 +6.802764551175327767e+01,4.099974595689423040e+02,1.994953557102718544e-01,6.365251430042832226e+00,8.183822682193156450e-02,1.000000009664330003e+00,4.563496123041156649e-02,-4.637266113765144163e-10,0.000000000000000000e+00 +6.802921654160337539e+01,4.100074261001514628e+02,2.003128247657814109e-01,6.366822459908116905e+00,8.200489348859822669e-02,1.000000009663601475e+00,4.563496123041156649e-02,-5.254791953452568754e-10,0.000000000000000000e+00 +6.803078718379781265e+01,4.100173924949773436e+02,2.011319548984644157e-01,6.368393102117728688e+00,8.217156015526488888e-02,1.000000009662776135e+00,4.563496123041156649e-02,-9.055687183670432023e-10,0.000000000000000000e+00 +6.803235743862342133e+01,4.100273587531431190e+02,2.019527460855672363e-01,6.369963356958514566e+00,8.233822682193155107e-02,1.000000009661354161e+00,4.563496123041156649e-02,-4.100391975253077513e-10,0.000000000000000000e+00 +6.803392730636670649e+01,4.100373248743719614e+02,2.027751983042901107e-01,6.371533224716967148e+00,8.250489348859821326e-02,1.000000009660710454e+00,4.563496123041156649e-02,-3.665655020688532300e-10,0.000000000000000000e+00 +6.803549678731380368e+01,4.100472908583869867e+02,2.035993115317871749e-01,6.373102705679228208e+00,8.267156015526487545e-02,1.000000009660135136e+00,4.563496123041156649e-02,-6.617068726678903248e-10,0.000000000000000000e+00 +6.803706588175050740e+01,4.100572567049114241e+02,2.044250857451663517e-01,6.374671800131086030e+00,8.283822682193153764e-02,1.000000009659096856e+00,4.563496123041156649e-02,-8.204014746118154448e-10,0.000000000000000000e+00 +6.803863458996224267e+01,4.100672224136683894e+02,2.052525209214894897e-01,6.376240508357976289e+00,8.300489348859819982e-02,1.000000009657809885e+00,4.563496123041156649e-02,-3.659868344853071907e-10,0.000000000000000000e+00 +6.804020291223410766e+01,4.100771879843811121e+02,2.060816170377722800e-01,6.377808830644983829e+00,8.317156015526486201e-02,1.000000009657235900e+00,4.563496123041156649e-02,-6.265083178197052467e-10,0.000000000000000000e+00 +6.804177084885083104e+01,4.100871534167727077e+02,2.069123740709842840e-01,6.379376767276844440e+00,8.333822682193152420e-02,1.000000009656253575e+00,4.563496123041156649e-02,-7.640634410208967651e-10,0.000000000000000000e+00 +6.804333840009678624e+01,4.100971187105664058e+02,2.077447919980489055e-01,6.380944318537942195e+00,8.350489348859818639e-02,1.000000009655055866e+00,4.563496123041156649e-02,-6.612458832625861583e-10,0.000000000000000000e+00 +6.804490556625601982e+01,4.101070838654853787e+02,2.085788707958434185e-01,6.382511484712312111e+00,8.367156015526484858e-02,1.000000009654019584e+00,4.563496123041156649e-02,-1.996837957642860144e-10,0.000000000000000000e+00 +6.804647234761222307e+01,4.101170488812527992e+02,2.094146104411989950e-01,6.384078266083641040e+00,8.383822682193151077e-02,1.000000009653706723e+00,4.563496123041156649e-02,-1.070675618025201825e-09,0.000000000000000000e+00 +6.804803874444873202e+01,4.101270137575918966e+02,2.102520109109006219e-01,6.385644662935268556e+00,8.400489348859817296e-02,1.000000009652029620e+00,4.563496123041156649e-02,-2.603260629541005003e-10,0.000000000000000000e+00 +6.804960475704852740e+01,4.101369784942258434e+02,2.110910721816871838e-01,6.387210675550183403e+00,8.417156015526483515e-02,1.000000009651621946e+00,4.563496123041156649e-02,-9.071099311878988595e-10,0.000000000000000000e+00 +6.805117038569426313e+01,4.101469430908778691e+02,2.119317942302514080e-01,6.388776304211031487e+00,8.433822682193149733e-02,1.000000009650201749e+00,4.563496123041156649e-02,-3.559250615851157102e-10,0.000000000000000000e+00 +6.805273563066823783e+01,4.101569075472711461e+02,2.127741770332399196e-01,6.390341549200108773e+00,8.450489348859815952e-02,1.000000009649644639e+00,4.563496123041156649e-02,-6.602331843114784596e-10,0.000000000000000000e+00 +6.805430049225239486e+01,4.101668718631289039e+02,2.136182205672531864e-01,6.391906410799368388e+00,8.467156015526482171e-02,1.000000009648611465e+00,4.563496123041156649e-02,-9.744833699209745231e-10,0.000000000000000000e+00 +6.805586497072835073e+01,4.101768360381743150e+02,2.144639248088455741e-01,6.393470889290416181e+00,8.483822682193148390e-02,1.000000009647086907e+00,4.563496123041156649e-02,-4.508763039453880726e-10,0.000000000000000000e+00 +6.805742906637735246e+01,4.101868000721306089e+02,2.153112897345252630e-01,6.395034984954513391e+00,8.500489348859814609e-02,1.000000009646381693e+00,4.563496123041156649e-02,-4.179010018195124176e-10,0.000000000000000000e+00 +6.805899277948033443e+01,4.101967639647210717e+02,2.161603153207543593e-01,6.396598698072579303e+00,8.517156015526480828e-02,1.000000009645728216e+00,4.563496123041156649e-02,-7.540533195197723340e-10,0.000000000000000000e+00 +6.806055611031786157e+01,4.102067277156688760e+02,2.170110015439488393e-01,6.398162028925188594e+00,8.533822682193147047e-02,1.000000009644549381e+00,4.563496123041156649e-02,-9.724536528919561969e-10,0.000000000000000000e+00 +6.806211905917017191e+01,4.102166913246972513e+02,2.178633483804784943e-01,6.399724977792572211e+00,8.550489348859813266e-02,1.000000009643029486e+00,4.563496123041156649e-02,-2.209692948721963826e-10,0.000000000000000000e+00 +6.806368162631714824e+01,4.102266547915294268e+02,2.187173558066670409e-01,6.401287544954619158e+00,8.567156015526479484e-02,1.000000009642684207e+00,4.563496123041156649e-02,-9.209065066908767202e-10,0.000000000000000000e+00 +6.806524381203834650e+01,4.102366181158886320e+02,2.195730237987920663e-01,6.402849730690879149e+00,8.583822682193145703e-02,1.000000009641245580e+00,4.563496123041156649e-02,-4.006401997066899083e-10,0.000000000000000000e+00 +6.806680561661296736e+01,4.102465812974981532e+02,2.204303523330850001e-01,6.404411535280557288e+00,8.600489348859811922e-02,1.000000009640619858e+00,4.563496123041156649e-02,-1.082049280664016031e-09,0.000000000000000000e+00 +6.806836704031988461e+01,4.102565443360812196e+02,2.212893413857311420e-01,6.405972959002521172e+00,8.617156015526478141e-02,1.000000009638930321e+00,4.563496123041156649e-02,-2.891763056934087665e-10,0.000000000000000000e+00 +6.806992808343761681e+01,4.102665072313610608e+02,2.221499909328697175e-01,6.407534002135295559e+00,8.633822682193144360e-02,1.000000009638478904e+00,4.563496123041156649e-02,-8.096917804268236364e-10,0.000000000000000000e+00 +6.807148874624434143e+01,4.102764699830609061e+02,2.230123009505937670e-01,6.409094664957069476e+00,8.650489348859810579e-02,1.000000009637215248e+00,4.563496123041156649e-02,-6.940482562222267486e-10,0.000000000000000000e+00 +6.807304902901792332e+01,4.102864325909040986e+02,2.238762714149502564e-01,6.410654947745690002e+00,8.667156015526476798e-02,1.000000009636132337e+00,4.563496123041156649e-02,-5.429043430527538445e-10,0.000000000000000000e+00 +6.807460893203587204e+01,4.102963950546138108e+02,2.247419023019399942e-01,6.412214850778667596e+00,8.683822682193143017e-02,1.000000009635285458e+00,4.563496123041156649e-02,-9.575039621509193113e-10,0.000000000000000000e+00 +6.807616845557535612e+01,4.103063573739133290e+02,2.256091935875176868e-01,6.413774374333175210e+00,8.700489348859809235e-02,1.000000009633792208e+00,4.563496123041156649e-02,-3.477759640740177075e-10,0.000000000000000000e+00 +6.807772759991320299e+01,4.103163195485259394e+02,2.264781452475918833e-01,6.415333518686047398e+00,8.717156015526475454e-02,1.000000009633249975e+00,4.563496123041156649e-02,-7.756349120590206612e-10,0.000000000000000000e+00 +6.807928636532592748e+01,4.103262815781749282e+02,2.273487572580250582e-01,6.416892284113784761e+00,8.733822682193141673e-02,1.000000009632040943e+00,4.563496123041156649e-02,-1.014768421458053890e-09,0.000000000000000000e+00 +6.808084475208967490e+01,4.103362434625835249e+02,2.282210295946335565e-01,6.418450670892549503e+00,8.750489348859807892e-02,1.000000009630459541e+00,4.563496123041156649e-02,-5.675076091614468336e-10,0.000000000000000000e+00 +6.808240276048029216e+01,4.103462052014750725e+02,2.290949622331875657e-01,6.420008679298168985e+00,8.767156015526474111e-02,1.000000009629575359e+00,4.563496123041156649e-02,-3.995755799140525086e-10,0.000000000000000000e+00 +6.808396039077325668e+01,4.103561667945728004e+02,2.299705551494111988e-01,6.421566309606137501e+00,8.783822682193140330e-02,1.000000009628952968e+00,4.563496123041156649e-02,-1.111468903211672813e-09,0.000000000000000000e+00 +6.808551764324373323e+01,4.103661282416000518e+02,2.308478083189824392e-01,6.423123562091614502e+00,8.800489348859806549e-02,1.000000009627222131e+00,4.563496123041156649e-02,-3.728138906768370074e-10,0.000000000000000000e+00 +6.808707451816655976e+01,4.103760895422800559e+02,2.317267217175331129e-01,6.424680437029423707e+00,8.817156015526472768e-02,1.000000009626641706e+00,4.563496123041156649e-02,-9.811918399080439105e-10,0.000000000000000000e+00 +6.808863101581620469e+01,4.103860506963361559e+02,2.326072953206489713e-01,6.426236934694059322e+00,8.833822682193138986e-02,1.000000009625114483e+00,4.563496123041156649e-02,-2.118123075065486693e-01,0.000000000000000000e+00 +6.809018713646685228e+01,4.103960117034916379e+02,2.334895291038696363e-01,6.427793055359679819e+00,8.850489348859805205e-02,9.996704041193432699e-01,4.563496123041156649e-02,-9.999997686367223526e-01,0.000000000000000000e+00 +6.809174288039231726e+01,4.104059725634698452e+02,2.343734230426886278e-01,6.429348286518352218e+00,8.867156015526471424e-02,9.981146605538236960e-01,4.563496123041156649e-02,-9.999998891191168582e-01,0.000000000000000000e+00 +6.809329824799014830e+01,4.104159332759940071e+02,2.352589771125533358e-01,6.430900721720294477e+00,8.883822682193137643e-02,9.965592931284564804e-01,4.563496123041156649e-02,-9.999999290565760868e-01,0.000000000000000000e+00 +6.809485324011842522e+01,4.104258938407875235e+02,2.361461912888650205e-01,6.432450363576469599e+00,8.900489348859803862e-02,9.950043011104968693e-01,4.563496123041156649e-02,-9.999999492939827261e-01,0.000000000000000000e+00 +6.809640785763349413e+01,4.104358542575736237e+02,2.370350655469788403e-01,6.433997214690540645e+00,8.917156015526470081e-02,9.934496836742606751e-01,4.563496123041156649e-02,-9.999999615006588405e-01,0.000000000000000000e+00 +6.809796210138995320e+01,4.104458145260757078e+02,2.379255998622038515e-01,6.435541277658746395e+00,8.933822682193136300e-02,9.918954399776401809e-01,4.563496123041156649e-02,-9.999999692379829552e-01,0.000000000000000000e+00 +6.809951597224068109e+01,4.104557746460170620e+02,2.388177942098029805e-01,6.437082555069896017e+00,8.950489348859802519e-02,9.903415691747140537e-01,4.563496123041156649e-02,-9.999999749294242735e-01,0.000000000000000000e+00 +6.810106947103682273e+01,4.104657346171210293e+02,2.397116485649930795e-01,6.438621049505383276e+00,8.967156015526468738e-02,9.887880704175141533e-01,4.563496123041156649e-02,-9.999999794892540095e-01,0.000000000000000000e+00 +6.810262259862783196e+01,4.104756944391109528e+02,2.406071629029448433e-01,6.440156763539203411e+00,8.983822682193134956e-02,9.872349428583668818e-01,4.563496123041156649e-02,-9.999999830553405467e-01,0.000000000000000000e+00 +6.810417535586141469e+01,4.104856541117101187e+02,2.415043371987828646e-01,6.441689699737973562e+00,9.000489348859801175e-02,9.856821856510938895e-01,4.563496123041156649e-02,-9.999999853562639984e-01,0.000000000000000000e+00 +6.810572774358359993e+01,4.104956136346419271e+02,2.424031714275856342e-01,6.443219860660954978e+00,9.017156015526467394e-02,9.841297979516414607e-01,4.563496123041156649e-02,-9.999999875539212768e-01,0.000000000000000000e+00 +6.810727976263871142e+01,4.105055730076297209e+02,2.433036655643855684e-01,6.444747248860076105e+00,9.033822682193133613e-02,9.825777789158494091e-01,4.563496123041156649e-02,-9.999999896645396236e-01,0.000000000000000000e+00 +6.810883141386936757e+01,4.105155322303967864e+02,2.442058195841688983e-01,6.446271866879952128e+00,9.050489348859799832e-02,9.810261277012243264e-01,4.563496123041156649e-02,-9.999999909259782438e-01,0.000000000000000000e+00 +6.811038269811652412e+01,4.105254913026665804e+02,2.451096334618758088e-01,6.447793717257907176e+00,9.067156015526466051e-02,9.794748434681409544e-01,4.563496123041156649e-02,-9.999999923799655077e-01,0.000000000000000000e+00 +6.811193361621944575e+01,4.105354502241623891e+02,2.460151071724003546e-01,6.449312802523998300e+00,9.083822682193132270e-02,9.779239253770373175e-01,4.563496123041156649e-02,-9.999999931828884581e-01,0.000000000000000000e+00 +6.811348416901572023e+01,4.105454089946076124e+02,2.469222406905905165e-01,6.450829125201035019e+00,9.100489348859798489e-02,9.763733725913334993e-01,4.563496123041156649e-02,-9.999999950364898416e-01,0.000000000000000000e+00 +6.811503435734127265e+01,4.105553676137255934e+02,2.478310339912481175e-01,6.452342687804603294e+00,9.117156015526464707e-02,9.748231842734785824e-01,4.563496123041156649e-02,-9.999999951683152810e-01,0.000000000000000000e+00 +6.811658418203035126e+01,4.105653260812396752e+02,2.487414870491288788e-01,6.453853492843083295e+00,9.133822682193130926e-02,9.732733595918813263e-01,4.563496123041156649e-02,-9.999999959398369054e-01,0.000000000000000000e+00 +6.811813364391558423e+01,4.105752843968733146e+02,2.496535998389424749e-01,6.455361542817677822e+00,9.150489348859797145e-02,9.717238977129453170e-01,4.563496123041156649e-02,-9.999999970874442479e-01,0.000000000000000000e+00 +6.811968274382790867e+01,4.105852425603497977e+02,2.505673723353524229e-01,6.456866840222428294e+00,9.167156015526463364e-02,9.701747978051329380e-01,4.563496123041156649e-02,-9.999999975660777141e-01,0.000000000000000000e+00 +6.812123148259664163e+01,4.105952005713925814e+02,2.514828045129761658e-01,6.458369387544236950e+00,9.183822682193129583e-02,9.686260590401692960e-01,4.563496123041156649e-02,-9.999999977710379850e-01,0.000000000000000000e+00 +6.812277986104945171e+01,4.106051584297250088e+02,2.523998963463849887e-01,6.459869187262890833e+00,9.200489348859795802e-02,9.670776805908045670e-01,4.563496123041156649e-02,-9.999999988016912145e-01,0.000000000000000000e+00 +6.812432788001238748e+01,4.106151161350705365e+02,2.533186478101041583e-01,6.461366241851082215e+00,9.217156015526462021e-02,9.655296616297187606e-01,4.563496123041156649e-02,-9.999999991239396646e-01,0.000000000000000000e+00 +6.812587554030986325e+01,4.106250736871525078e+02,2.542390588786128114e-01,6.462860553774427252e+00,9.233822682193128240e-02,9.639820013335931304e-01,4.563496123041156649e-02,-9.999999997590288681e-01,0.000000000000000000e+00 +6.812742284276468752e+01,4.106350310856943224e+02,2.551611295263439549e-01,6.464352125491490852e+00,9.250489348859794458e-02,9.624346988791482316e-01,4.563496123041156649e-02,-9.999999994648109958e-01,0.000000000000000000e+00 +6.812896978819802030e+01,4.106449883304193804e+02,2.560848597276844663e-01,6.465840959453805326e+00,9.267156015526460677e-02,9.608877534466409021e-01,4.563496123041156649e-02,-1.000000000671510403e+00,0.000000000000000000e+00 +6.813051637742944422e+01,4.106549454210511385e+02,2.570102494569752594e-01,6.467327058105894366e+00,9.283822682193126896e-02,9.593411642141770335e-01,4.563496123041156649e-02,-1.000000000203364880e+00,0.000000000000000000e+00 +6.813206261127693608e+01,4.106649023573129966e+02,2.579372986885110075e-01,6.468810423885288152e+00,9.300489348859793115e-02,9.577949303663774172e-01,4.563496123041156649e-02,-1.000000001158902974e+00,0.000000000000000000e+00 +6.813360849055685264e+01,4.106748591389283547e+02,2.588660073965403652e-01,6.470291059222551766e+00,9.317156015526459334e-02,9.562490510846681779e-01,4.563496123041156649e-02,-1.000000001398966498e+00,0.000000000000000000e+00 +6.813515401608398747e+01,4.106848157656206126e+02,2.597963755552658571e-01,6.471768966541298518e+00,9.333822682193125553e-02,9.547035255553744104e-01,4.563496123041156649e-02,-1.000000001346196932e+00,0.000000000000000000e+00 +6.813669918867152830e+01,4.106947722371132272e+02,2.607284031388439338e-01,6.473244148258215702e+00,9.350489348859791772e-02,9.531583529657530196e-01,4.563496123041156649e-02,-1.000000001759442814e+00,0.000000000000000000e+00 +6.813824400913109969e+01,4.107047285531296552e+02,2.616620901213849715e-01,6.474716606783084138e+00,9.367156015526457991e-02,9.516135325034682513e-01,4.563496123041156649e-02,-1.000000002244004094e+00,0.000000000000000000e+00 +6.813978847827273455e+01,4.107146847133932965e+02,2.625974364769531610e-01,6.476186344518796822e+00,9.383822682193124209e-02,9.500690633583687150e-01,4.563496123041156649e-02,-1.000000001994931109e+00,0.000000000000000000e+00 +6.814133259690490263e+01,4.107246407176276080e+02,2.635344421795666747e-01,6.477653363861380242e+00,9.400489348859790428e-02,9.485249447231146602e-01,4.563496123041156649e-02,-1.000000002777583497e+00,0.000000000000000000e+00 +6.814287636583452468e+01,4.107345965655559894e+02,2.644731072031976105e-01,6.479117667200016584e+00,9.417156015526456647e-02,9.469811757892032666e-01,4.563496123041156649e-02,-1.000000002595086146e+00,0.000000000000000000e+00 +6.814441978586694404e+01,4.107445522569019545e+02,2.654134315217718809e-01,6.480579256917059716e+00,9.433822682193122866e-02,9.454377557527722242e-01,4.563496123041156649e-02,-1.000000002767312601e+00,0.000000000000000000e+00 +6.814596285780596929e+01,4.107545077913889031e+02,2.663554151091694355e-01,6.482038135388060063e+00,9.450489348859789085e-02,9.438946838094733893e-01,4.563496123041156649e-02,-1.000000002714371394e+00,0.000000000000000000e+00 +6.814750558245386003e+01,4.107644631687403489e+02,2.672990579392240384e-01,6.483494304981781475e+00,9.467156015526455304e-02,9.423519591573998877e-01,4.563496123041156649e-02,-1.000000003685624916e+00,0.000000000000000000e+00 +6.814904796061131265e+01,4.107744183886796918e+02,2.682443599857233796e-01,6.484947768060222550e+00,9.483822682193121523e-02,9.408095809942583765e-01,4.563496123041156649e-02,-1.000000003161154005e+00,0.000000000000000000e+00 +6.815058999307751719e+01,4.107843734509304454e+02,2.691913212224090746e-01,6.486398526978633505e+00,9.500489348859787742e-02,9.392675485231776200e-01,4.563496123041156649e-02,-1.000000003438398899e+00,0.000000000000000000e+00 +6.815213168065011473e+01,4.107943283552160665e+02,2.701399416229766093e-01,6.487846584085541934e+00,9.517156015526453960e-02,9.377258609452726601e-01,4.563496123041156649e-02,-1.000000004166296419e+00,0.000000000000000000e+00 +6.815367302412523998e+01,4.108042831012600118e+02,2.710902211610754509e-01,6.489291941722767021e+00,9.533822682193120179e-02,9.361845174637247746e-01,4.563496123041156649e-02,-1.000000003461273268e+00,0.000000000000000000e+00 +6.815521402429749287e+01,4.108142376887857949e+02,2.720421598103089367e-01,6.490734602225439964e+00,9.550489348859786398e-02,9.346435172861371488e-01,4.563496123041156649e-02,-1.000000003890780143e+00,0.000000000000000000e+00 +6.815675468195996700e+01,4.108241921175168727e+02,2.729957575442343298e-01,6.492174567922027961e+00,9.567156015526452617e-02,9.331028596176693668e-01,4.563496123041156649e-02,-1.000000003874133014e+00,0.000000000000000000e+00 +6.815829499790424961e+01,4.108341463871767019e+02,2.739510143363628192e-01,6.493611841134347529e+00,9.583822682193118836e-02,9.315625436674249693e-01,4.563496123041156649e-02,-1.000000004413910792e+00,0.000000000000000000e+00 +6.815983497292040738e+01,4.108441004974888529e+02,2.749079301601594638e-01,6.495046424177587596e+00,9.600489348859785055e-02,9.300225686444657525e-01,4.563496123041156649e-02,-1.000000004606051318e+00,0.000000000000000000e+00 +6.816137460779704327e+01,4.108540544481767824e+02,2.758665049890433041e-01,6.496478319360326381e+00,9.617156015526451274e-02,9.284829337607433120e-01,4.563496123041156649e-02,-1.000000003884605526e+00,0.000000000000000000e+00 +6.816291390332123967e+01,4.108640082389640042e+02,2.768267387963872506e-01,6.497907528984552705e+00,9.633822682193117493e-02,9.269436382305720201e-01,4.563496123041156649e-02,-1.000000005023495842e+00,0.000000000000000000e+00 +6.816445286027860107e+01,4.108739618695739750e+02,2.777886315555181396e-01,6.499334055345686423e+00,9.650489348859783711e-02,9.254046812654830312e-01,4.563496123041156649e-02,-1.000000004388525321e+00,0.000000000000000000e+00 +6.816599147945325399e+01,4.108839153397302653e+02,2.787521832397167332e-01,6.500757900732590855e+00,9.667156015526449930e-02,9.238660620840823956e-01,4.563496123041156649e-02,-1.000000004685404287e+00,0.000000000000000000e+00 +6.816752976162784705e+01,4.108938686491563317e+02,2.797173938222176637e-01,6.502179067427600323e+00,9.683822682193116149e-02,9.223277799022883139e-01,4.563496123041156649e-02,-1.000000004835681189e+00,0.000000000000000000e+00 +6.816906770758355094e+01,4.109038217975757448e+02,2.806842632762096001e-01,6.503597557706532584e+00,9.700489348859782368e-02,9.207898339391493714e-01,4.563496123041156649e-02,-1.000000004851465896e+00,0.000000000000000000e+00 +6.817060531810007262e+01,4.109137747847120181e+02,2.816527915748349709e-01,6.505013373838710145e+00,9.717156015526448587e-02,9.192522234151609961e-01,4.563496123041156649e-02,-1.000000005086992605e+00,0.000000000000000000e+00 +6.817214259395568376e+01,4.109237276102886653e+02,2.826229786911902964e-01,6.506426518086978916e+00,9.733822682193114806e-02,9.177149475517343280e-01,4.563496123041156649e-02,-1.000000005111113088e+00,0.000000000000000000e+00 +6.817367953592716390e+01,4.109336802740292569e+02,2.835948245983258564e-01,6.507836992707725976e+00,9.750489348859781025e-02,9.161780055723985905e-01,4.563496123041156649e-02,-1.000000005210878395e+00,0.000000000000000000e+00 +6.817521614478985725e+01,4.109436327756572496e+02,2.845683292692459676e-01,6.509244799950899107e+00,9.767156015526447244e-02,9.146413967016917557e-01,4.563496123041156649e-02,-1.000000005263372405e+00,0.000000000000000000e+00 +6.817675242131767277e+01,4.109535851148962706e+02,2.855434926769088722e-01,6.510649942060024564e+00,9.783822682193113462e-02,9.131051201657855998e-01,4.563496123041156649e-02,-1.000000005112961166e+00,0.000000000000000000e+00 +6.817828836628306988e+01,4.109635372914698337e+02,2.865203147942266271e-01,6.512052421272225722e+00,9.800489348859779681e-02,9.115691751925306674e-01,4.563496123041156649e-02,-1.000000005699627659e+00,0.000000000000000000e+00 +6.817982398045707271e+01,4.109734893051014524e+02,2.874987955940653261e-01,6.513452239818241729e+00,9.817156015526445900e-02,9.100335610097685102e-01,4.563496123041156649e-02,-1.000000005294711114e+00,0.000000000000000000e+00 +6.818135926460928431e+01,4.109834411555147540e+02,2.884789350492449889e-01,6.514849399922443496e+00,9.833822682193112119e-02,9.084982768494249683e-01,4.563496123041156649e-02,-1.000000005526270330e+00,0.000000000000000000e+00 +6.818289421950787244e+01,4.109933928424332521e+02,2.894607331325394495e-01,6.516243903802855897e+00,9.850489348859778338e-02,9.069633219423504089e-01,4.563496123041156649e-02,-1.000000005352176480e+00,0.000000000000000000e+00 +6.818442884591959796e+01,4.110033443655805172e+02,2.904441898166765790e-01,6.517635753671171983e+00,9.867156015526444557e-02,9.054286955224145617e-01,4.563496123041156649e-02,-1.000000005960472560e+00,0.000000000000000000e+00 +6.818596314460978647e+01,4.110132957246801197e+02,2.914293050743381186e-01,6.519024951732773410e+00,9.883822682193110776e-02,9.038943968230783721e-01,4.563496123041156649e-02,-1.000000005487760246e+00,0.000000000000000000e+00 +6.818749711634237087e+01,4.110232469194556302e+02,2.924160788781597353e-01,6.520411500186745535e+00,9.900489348859776995e-02,9.023604250820713712e-01,4.563496123041156649e-02,-1.000000005812619719e+00,0.000000000000000000e+00 +6.818903076187987722e+01,4.110331979496306190e+02,2.934045112007310774e-01,6.521795401225899624e+00,9.917156015526443213e-02,9.008267795356453833e-01,4.563496123041156649e-02,-1.000000006139175168e+00,0.000000000000000000e+00 +6.819056408198343888e+01,4.110431488149287134e+02,2.943946020145956632e-01,6.523176657036786175e+00,9.933822682193109432e-02,8.992934594226728029e-01,4.563496123041156649e-02,-1.000000005638747913e+00,0.000000000000000000e+00 +6.819209707741278237e+01,4.110530995150734270e+02,2.953863512922509926e-01,6.524555269799714452e+00,9.950489348859775651e-02,8.977604639846908929e-01,4.563496123041156649e-02,-1.000000005717337492e+00,0.000000000000000000e+00 +6.819362974892624152e+01,4.110630500497883872e+02,2.963797590061484910e-01,6.525931241688772033e+00,9.967156015526441870e-02,8.962277924624707515e-01,4.563496123041156649e-02,-1.000000006239240014e+00,0.000000000000000000e+00 +6.819516209728077172e+01,4.110730004187972213e+02,2.973748251286934541e-01,6.527304574871839016e+00,9.983822682193108089e-02,8.946954440983766466e-01,4.563496123041156649e-02,-1.000000006279602616e+00,0.000000000000000000e+00 +6.819669412323196411e+01,4.110829506218234997e+02,2.983715496322451588e-01,6.528675271510605782e+00,1.000048934885977431e-01,8.931634181375699422e-01,4.563496123041156649e-02,-1.000000005637411205e+00,0.000000000000000000e+00 +6.819822582753400297e+01,4.110929006585908496e+02,2.993699324891168634e-01,6.530043333760592539e+00,1.001715601552644053e-01,8.916317138268943232e-01,4.563496123041156649e-02,-1.000000006352635529e+00,0.000000000000000000e+00 +6.819975721093973675e+01,4.111028505288228416e+02,3.003699736715756963e-01,6.531408763771167081e+00,1.003382268219310675e-01,8.901003304114388781e-01,4.563496123041156649e-02,-1.000000006270211461e+00,0.000000000000000000e+00 +6.820128827420062123e+01,4.111128002322431030e+02,3.013716731518427117e-01,6.532771563685557226e+00,1.005048934885977296e-01,8.885692671409587406e-01,4.563496123041156649e-02,-1.000000006231272165e+00,0.000000000000000000e+00 +6.820281901806676217e+01,4.111227497685752610e+02,3.023750309020929450e-01,6.534131735640873018e+00,1.006715601552643918e-01,8.870385232652810981e-01,4.563496123041156649e-02,-1.000000005911284795e+00,0.000000000000000000e+00 +6.820434944328691529e+01,4.111326991375429429e+02,3.033800468944553019e-01,6.535489281768121828e+00,1.008382268219310540e-01,8.855080980360854337e-01,4.563496123041156649e-02,-1.000000006850411127e+00,0.000000000000000000e+00 +6.820587955060847207e+01,4.111426483388697761e+02,3.043867211010127249e-01,6.536844204192226115e+00,1.010048934885977162e-01,8.839779907040451468e-01,4.563496123041156649e-02,-1.000000006006571462e+00,0.000000000000000000e+00 +6.820740934077748818e+01,4.111525973722793879e+02,3.053950534938020267e-01,6.538196505032036754e+00,1.011715601552643784e-01,8.824482005258346140e-01,4.563496123041156649e-02,-1.000000006376800865e+00,0.000000000000000000e+00 +6.820893881453868346e+01,4.111625462374954054e+02,3.064050440448139456e-01,6.539546186400357008e+00,1.013382268219310406e-01,8.809187267548839184e-01,4.563496123041156649e-02,-1.000000006754940163e+00,0.000000000000000000e+00 +6.821046797263542771e+01,4.111724949342415130e+02,3.074166927259932569e-01,6.540893250403952308e+00,1.015048934885977028e-01,8.793895686478052642e-01,4.563496123041156649e-02,-1.000000006281862586e+00,0.000000000000000000e+00 +6.821199681580976915e+01,4.111824434622413378e+02,3.084299995092385505e-01,6.542237699143569785e+00,1.016715601552643650e-01,8.778607254638561841e-01,4.563496123041156649e-02,-1.000000006348263026e+00,0.000000000000000000e+00 +6.821352534480242014e+01,4.111923918212185072e+02,3.094449643664024530e-01,6.543579534713956924e+00,1.018382268219310272e-01,8.763321964614948500e-01,4.563496123041156649e-02,-1.000000006795730201e+00,0.000000000000000000e+00 +6.821505356035278567e+01,4.112023400108967053e+02,3.104615872692914613e-01,6.544918759203874892e+00,1.020048934885976893e-01,8.748039809007445156e-01,4.563496123041156649e-02,-1.000000006294250454e+00,0.000000000000000000e+00 +6.821658146319893490e+01,4.112122880309995594e+02,3.114798681896660537e-01,6.546255374696115403e+00,1.021715601552643515e-01,8.732760780449787541e-01,4.563496123041156649e-02,-1.000000006907601824e+00,0.000000000000000000e+00 +6.821810905407762959e+01,4.112222358812507537e+02,3.124998070992406340e-01,6.547589383267520269e+00,1.023382268219310137e-01,8.717484871557308335e-01,4.563496123041156649e-02,-1.000000006484509374e+00,0.000000000000000000e+00 +6.821963633372432412e+01,4.112321835613739722e+02,3.135214039696835875e-01,6.548920786988992937e+00,1.025048934885976759e-01,8.702212074991292345e-01,4.563496123041156649e-02,-1.000000007031150329e+00,0.000000000000000000e+00 +6.822116330287317965e+01,4.112421310710928992e+02,3.145446587726172250e-01,6.550249587925519812e+00,1.026715601552643381e-01,8.686942383395420686e-01,4.563496123041156649e-02,-1.000000006335450609e+00,0.000000000000000000e+00 +6.822268996225703575e+01,4.112520784101312188e+02,3.155695714796178386e-01,6.551575788136181799e+00,1.028382268219310003e-01,8.671675789460148165e-01,4.563496123041156649e-02,-1.000000006727490121e+00,0.000000000000000000e+00 +6.822421631260745301e+01,4.112620255782125582e+02,3.165961420622155909e-01,6.552899389674175623e+00,1.030048934885976625e-01,8.656412285853301025e-01,4.563496123041156649e-02,-1.000000007079451025e+00,0.000000000000000000e+00 +6.822574235465469883e+01,4.112719725750606585e+02,3.176243704918946253e-01,6.554220394586824483e+00,1.031715601552643247e-01,8.641151865272829191e-01,4.563496123041156649e-02,-1.000000006614222947e+00,0.000000000000000000e+00 +6.822726808912774743e+01,4.112819194003992038e+02,3.186542567400930670e-01,6.555538804915596707e+00,1.033382268219309869e-01,8.625894520441396152e-01,4.563496123041156649e-02,-1.000000006814746545e+00,0.000000000000000000e+00 +6.822879351675430826e+01,4.112918660539518783e+02,3.196858007782029665e-01,6.556854622696123513e+00,1.035048934885976490e-01,8.610640244071848803e-01,4.563496123041156649e-02,-1.000000007228241117e+00,0.000000000000000000e+00 +6.823031863826079757e+01,4.113018125354424228e+02,3.207190025775703002e-01,6.558167849958211448e+00,1.036715601552643112e-01,8.595389028896712746e-01,4.563496123041156649e-02,-1.000000006608630310e+00,0.000000000000000000e+00 +6.823184345437236686e+01,4.113117588445945216e+02,3.217538621094950257e-01,6.559478488725859258e+00,1.038382268219309734e-01,8.580140867680238204e-01,4.563496123041156649e-02,-1.000000006736662117e+00,0.000000000000000000e+00 +6.823336796581290287e+01,4.113217049811319157e+02,3.227903793452310266e-01,6.560786541017276541e+00,1.040048934885976356e-01,8.564895753172195869e-01,4.563496123041156649e-02,-1.000000007456028461e+00,0.000000000000000000e+00 +6.823489217330501333e+01,4.113316509447782892e+02,3.238285542559861674e-01,6.562092008844895297e+00,1.041715601552642978e-01,8.549653678137378865e-01,4.563496123041156649e-02,-1.000000006669327535e+00,0.000000000000000000e+00 +6.823641607757006966e+01,4.113415967352573830e+02,3.248683868129222940e-01,6.563394894215385911e+00,1.043382268219309600e-01,8.534414635385136894e-01,4.563496123041156649e-02,-1.000000006839281808e+00,0.000000000000000000e+00 +6.823793967932817850e+01,4.113515423522928813e+02,3.259098769871551227e-01,6.564695199129677583e+00,1.045048934885976222e-01,8.519178617699828537e-01,4.563496123041156649e-02,-1.000000007342262576e+00,0.000000000000000000e+00 +6.823946297929819593e+01,4.113614877956085820e+02,3.269530247497544062e-01,6.565992925582968098e+00,1.046715601552642844e-01,8.503945617887821440e-01,4.563496123041156649e-02,-1.000000006760041416e+00,0.000000000000000000e+00 +6.824098597819772749e+01,4.113714330649281692e+02,3.279978300717437678e-01,6.567288075564740701e+00,1.048382268219309466e-01,8.488715628789542667e-01,4.563496123041156649e-02,-1.000000007475144503e+00,0.000000000000000000e+00 +6.824250867674314236e+01,4.113813781599753838e+02,3.290442929241008674e-01,6.568580651058782749e+00,1.050048934885976087e-01,8.473488643221543937e-01,4.563496123041156649e-02,-1.000000006863631885e+00,0.000000000000000000e+00 +6.824403107564957338e+01,4.113913230804740238e+02,3.300924132777572906e-01,6.569870654043195479e+00,1.051715601552642709e-01,8.458264654052705112e-01,4.563496123041156649e-02,-1.000000006871387459e+00,0.000000000000000000e+00 +6.824555317563093126e+01,4.114012678261478300e+02,3.311421911035986043e-01,6.571158086490415329e+00,1.053382268219309331e-01,8.443043654134602116e-01,4.563496123041156649e-02,-1.000000007501521626e+00,0.000000000000000000e+00 +6.824707497739987616e+01,4.114112123967205434e+02,3.321936263724643013e-01,6.572442950367224590e+00,1.055048934885975953e-01,8.427825636331052195e-01,4.563496123041156649e-02,-1.000000007195485319e+00,0.000000000000000000e+00 +6.824859648166784609e+01,4.114211567919159052e+02,3.332467190551478553e-01,6.573725247634766511e+00,1.056715601552642575e-01,8.412610593541831605e-01,4.563496123041156649e-02,-1.000000007051726536e+00,0.000000000000000000e+00 +6.825011768914508536e+01,4.114311010114577130e+02,3.343014691223966661e-01,6.575004980248563946e+00,1.058382268219309197e-01,8.397398518662195777e-01,4.563496123041156649e-02,-1.000000006991414780e+00,0.000000000000000000e+00 +6.825163860054060194e+01,4.114410450550697078e+02,3.353578765449121146e-01,6.576282150158531792e+00,1.060048934885975819e-01,8.382189404600755012e-01,4.563496123041156649e-02,-1.000000007676992597e+00,0.000000000000000000e+00 +6.825315921656218165e+01,4.114509889224756876e+02,3.364159412933495630e-01,6.577556759308992085e+00,1.061715601552642441e-01,8.366983244268159092e-01,4.563496123041156649e-02,-1.000000007055215967e+00,0.000000000000000000e+00 +6.825467953791643083e+01,4.114609326133994500e+02,3.374756633383183546e-01,6.578828809638687325e+00,1.063382268219309063e-01,8.351780030618349837e-01,4.563496123041156649e-02,-1.000000007271101277e+00,0.000000000000000000e+00 +6.825619956530874788e+01,4.114708761275647930e+02,3.385370426503817032e-01,6.580098303080800015e+00,1.065048934885975684e-01,8.336579756584679979e-01,4.563496123041156649e-02,-1.000000007370271948e+00,0.000000000000000000e+00 +6.825771929944330907e+01,4.114808194646954576e+02,3.396000792000569146e-01,6.581365241562962431e+00,1.066715601552642306e-01,8.321382415126998833e-01,4.563496123041156649e-02,-1.000000007139708158e+00,0.000000000000000000e+00 +6.825923874102312539e+01,4.114907626245152414e+02,3.406647729578151651e-01,6.582629627007273498e+00,1.068382268219308928e-01,8.306187999220334683e-01,4.563496123041156649e-02,-1.000000007494125764e+00,0.000000000000000000e+00 +6.826075789074999989e+01,4.115007056067479994e+02,3.417311238940816120e-01,6.583891461330313888e+00,1.070048934885975550e-01,8.290996501837718524e-01,4.563496123041156649e-02,-1.000000007398416990e+00,0.000000000000000000e+00 +6.826227674932455614e+01,4.115106484111174723e+02,3.427991319792354497e-01,6.585150746443158454e+00,1.071715601552642172e-01,8.275807915979768170e-01,4.563496123041156649e-02,-1.000000007330174245e+00,0.000000000000000000e+00 +6.826379531744623819e+01,4.115205910373475149e+02,3.438687971836097423e-01,6.586407484251393107e+00,1.073382268219308794e-01,8.260622234651663343e-01,4.563496123041156649e-02,-1.000000006970949373e+00,0.000000000000000000e+00 +6.826531359581329639e+01,4.115305334851619250e+02,3.449401194774915913e-01,6.587661676655128140e+00,1.075048934885975416e-01,8.245439450875196030e-01,4.563496123041156649e-02,-1.000000007903845134e+00,0.000000000000000000e+00 +6.826683158512283001e+01,4.115404757542845573e+02,3.460130988311220235e-01,6.588913325549013322e+00,1.076715601552642038e-01,8.230259557659860281e-01,4.563496123041156649e-02,-1.000000007446018246e+00,0.000000000000000000e+00 +6.826834928607075881e+01,4.115504178444392096e+02,3.470877352146960471e-01,6.590162432822248562e+00,1.078382268219308660e-01,8.215082548067573764e-01,4.563496123041156649e-02,-1.000000007128397206e+00,0.000000000000000000e+00 +6.826986669935183727e+01,4.115603597553496797e+02,3.481640285983626515e-01,6.591409000358604331e+00,1.080048934885975281e-01,8.199908415148665641e-01,4.563496123041156649e-02,-1.000000007686685510e+00,0.000000000000000000e+00 +6.827138382565965458e+01,4.115703014867398792e+02,3.492419789522248075e-01,6.592653030036432327e+00,1.081715601552641903e-01,8.184737151953918044e-01,4.563496123041156649e-02,-1.000000007130144031e+00,0.000000000000000000e+00 +6.827290066568664884e+01,4.115802430383336059e+02,3.503215862463394670e-01,6.593894523728677903e+00,1.083382268219308525e-01,8.169568751575889687e-01,4.563496123041156649e-02,-1.000000008073853586e+00,0.000000000000000000e+00 +6.827441722012409286e+01,4.115901844098547144e+02,3.514028504507175632e-01,6.595133483302898725e+00,1.085048934885975147e-01,8.154403207079002902e-01,4.563496123041156649e-02,-1.000000006929681495e+00,0.000000000000000000e+00 +6.827593348966212261e+01,4.116001256010270026e+02,3.524857715353238996e-01,6.596369910621272759e+00,1.086715601552641769e-01,8.139240511593590632e-01,4.563496123041156649e-02,-1.000000007808780067e+00,0.000000000000000000e+00 +6.827744947498973715e+01,4.116100666115743820e+02,3.535703494700774274e-01,6.597603807540620480e+00,1.088382268219308391e-01,8.124080658199095417e-01,4.563496123041156649e-02,-1.000000007458012874e+00,0.000000000000000000e+00 +6.827896517679477029e+01,4.116200074412207073e+02,3.546565842248509126e-01,6.598835175912409312e+00,1.090048934885975013e-01,8.108923640035696767e-01,4.563496123041156649e-02,-1.000000007621347775e+00,0.000000000000000000e+00 +6.828048059576393314e+01,4.116299480896898331e+02,3.557444757694712134e-01,6.600064017582774945e+00,1.091715601552641635e-01,8.093769450228507356e-01,4.563496123041156649e-02,-1.000000007699918925e+00,0.000000000000000000e+00 +6.828199573258281418e+01,4.116398885567056709e+02,3.568340240737190583e-01,6.601290334392531101e+00,1.093382268219308256e-01,8.078618081923050198e-01,4.563496123041156649e-02,-1.000000007455388751e+00,0.000000000000000000e+00 +6.828351058793585082e+01,4.116498288419920755e+02,3.579252291073292680e-01,6.602514128177184638e+00,1.095048934885974878e-01,8.063469528279750831e-01,4.563496123041156649e-02,-1.000000007399532098e+00,0.000000000000000000e+00 +6.828502516250637200e+01,4.116597689452729014e+02,3.590180908399905890e-01,6.603735400766949759e+00,1.096715601552641500e-01,8.048323782462534215e-01,4.563496123041156649e-02,-1.000000007632511734e+00,0.000000000000000000e+00 +6.828653945697656980e+01,4.116697088662720603e+02,3.601126092413457491e-01,6.604954153986760446e+00,1.098382268219308122e-01,8.033180837645024219e-01,4.563496123041156649e-02,-1.000000007842799299e+00,0.000000000000000000e+00 +6.828805347202752785e+01,4.116796486047134067e+02,3.612087842809914573e-01,6.606170389656283781e+00,1.100048934885974744e-01,8.018040687016738666e-01,4.563496123041156649e-02,-1.000000007694203275e+00,0.000000000000000000e+00 +6.828956720833920713e+01,4.116895881603208522e+02,3.623066159284784038e-01,6.607384109589934162e+00,1.101715601552641366e-01,8.002903323783420175e-01,4.563496123041156649e-02,-1.000000007212813680e+00,0.000000000000000000e+00 +6.829108066659048859e+01,4.116995275328183084e+02,3.634061041533112602e-01,6.608595315596887509e+00,1.103382268219307988e-01,7.987768741161510588e-01,4.563496123041156649e-02,-1.000000007952977166e+00,0.000000000000000000e+00 +6.829259384745910211e+01,4.117094667219296866e+02,3.645072489249486791e-01,6.609804009481094589e+00,1.105048934885974610e-01,7.972636932354987271e-01,4.563496123041156649e-02,-1.000000007954683356e+00,0.000000000000000000e+00 +6.829410675162171174e+01,4.117194057273788985e+02,3.656100502128032947e-01,6.611010193041290783e+00,1.106715601552641232e-01,7.957507890608510603e-01,4.563496123041156649e-02,-1.000000007171514715e+00,0.000000000000000000e+00 +6.829561937975387309e+01,4.117293445488898556e+02,3.667145079862417778e-01,6.612213868071013856e+00,1.108382268219307853e-01,7.942381609178418289e-01,4.563496123041156649e-02,-1.000000007863611096e+00,0.000000000000000000e+00 +6.829713173253004754e+01,4.117392831861864693e+02,3.678206222145847248e-01,6.613415036358617272e+00,1.110048934885974475e-01,7.927258081297803294e-01,4.563496123041156649e-02,-1.000000007997370766e+00,0.000000000000000000e+00 +6.829864381062358802e+01,4.117492216389927080e+02,3.689283928671067136e-01,6.614613699687278192e+00,1.111715601552641097e-01,7.912137300241425253e-01,4.563496123041156649e-02,-1.000000007454913575e+00,0.000000000000000000e+00 +6.830015561470679586e+01,4.117591599070324264e+02,3.700378199130364143e-01,6.615809859835015239e+00,1.113382268219307719e-01,7.897019259296688132e-01,4.563496123041156649e-02,-1.000000007650731382e+00,0.000000000000000000e+00 +6.830166714545084972e+01,4.117690979900296497e+02,3.711489033215563116e-01,6.617003518574701815e+00,1.115048934885974341e-01,7.881903951740438785e-01,4.563496123041156649e-02,-1.000000008032470245e+00,0.000000000000000000e+00 +6.830317840352589087e+01,4.117790358877082326e+02,3.722616430618030381e-01,6.618194677674075876e+00,1.116715601552640963e-01,7.866791370868668754e-01,4.563496123041156649e-02,-1.000000007246047096e+00,0.000000000000000000e+00 +6.830468938960095215e+01,4.117889735997922003e+02,3.733760391028671521e-01,6.619383338895754143e+00,1.118382268219307585e-01,7.851681510008584608e-01,4.563496123041156649e-02,-1.000000008192590162e+00,0.000000000000000000e+00 +6.830620010434400058e+01,4.117989111260054642e+02,3.744920914137931933e-01,6.620569503997248084e+00,1.120048934885974207e-01,7.836574362454271636e-01,4.563496123041156649e-02,-1.000000007915154754e+00,0.000000000000000000e+00 +6.830771054842195156e+01,4.118088484660719928e+02,3.756097999635797380e-01,6.621753174730970137e+00,1.121715601552640829e-01,7.821469921555170846e-01,4.563496123041156649e-02,-1.000000007322986439e+00,0.000000000000000000e+00 +6.830922072250064048e+01,4.118187856197157544e+02,3.767291647211792882e-01,6.622934352844253247e+00,1.123382268219307450e-01,7.806368180657623501e-01,4.563496123041156649e-02,-1.000000008083673064e+00,0.000000000000000000e+00 +6.831073062724485112e+01,4.118287225866607173e+02,3.778501856554983829e-01,6.624113040079361525e+00,1.125048934885974072e-01,7.791269133093393640e-01,4.563496123041156649e-02,-1.000000007946743041e+00,0.000000000000000000e+00 +6.831224026331831567e+01,4.118386593666308499e+02,3.789728627353975976e-01,6.625289238173499129e+00,1.126715601552640694e-01,7.776172772238797437e-01,4.563496123041156649e-02,-1.000000007754147990e+00,0.000000000000000000e+00 +6.831374963138370049e+01,4.118485959593501207e+02,3.800971959296914338e-01,6.626462948858828028e+00,1.128382268219307316e-01,7.761079091467966151e-01,4.563496123041156649e-02,-1.000000007546608671e+00,0.000000000000000000e+00 +6.831525873210262034e+01,4.118585323645424978e+02,3.812231852071483740e-01,6.627634173862478661e+00,1.130048934885973938e-01,7.745988084164909804e-01,4.563496123041156649e-02,-1.000000008123135942e+00,0.000000000000000000e+00 +6.831676756613565260e+01,4.118684685819320066e+02,3.823508305364909932e-01,6.628802914906562371e+00,1.131715601552640560e-01,7.730899743712039696e-01,4.563496123041156649e-02,-1.000000007918503409e+00,0.000000000000000000e+00 +6.831827613414233724e+01,4.118784046112426154e+02,3.834801318863957920e-01,6.629969173708182062e+00,1.133382268219307182e-01,7.715814063525806565e-01,4.563496123041156649e-02,-1.000000007685992287e+00,0.000000000000000000e+00 +6.831978443678116264e+01,4.118883404521983493e+02,3.846110892254932523e-01,6.631132951979448187e+00,1.135048934885973804e-01,7.700731037021677494e-01,4.563496123041156649e-02,-1.000000007766947974e+00,0.000000000000000000e+00 +6.832129247470957978e+01,4.118982761045231769e+02,3.857437025223679483e-01,6.632294251427489407e+00,1.136715601552640426e-01,7.685650657620319848e-01,4.563496123041156649e-02,-1.000000008089982684e+00,0.000000000000000000e+00 +6.832280024858403067e+01,4.119082115679411231e+02,3.868779717455583800e-01,6.633453073754464135e+00,1.138382268219307047e-01,7.670572918753791880e-01,4.563496123041156649e-02,-1.000000007780223577e+00,0.000000000000000000e+00 +6.832430775905991993e+01,4.119181468421762133e+02,3.880138968635570285e-01,6.634609420657572976e+00,1.140048934885973669e-01,7.655497813877618629e-01,4.563496123041156649e-02,-1.000000007893725229e+00,0.000000000000000000e+00 +6.832581500679161479e+01,4.119280819269524727e+02,3.891514778448104672e-01,6.635763293829072929e+00,1.141715601552640291e-01,7.640425336441643012e-01,4.563496123041156649e-02,-1.000000007901997501e+00,0.000000000000000000e+00 +6.832732199243248772e+01,4.119380168219938696e+02,3.902907146577191955e-01,6.636914694956287164e+00,1.143382268219306913e-01,7.625355479913880075e-01,4.563496123041156649e-02,-1.000000008036012300e+00,0.000000000000000000e+00 +6.832882871663485957e+01,4.119479515270244860e+02,3.914316072706378047e-01,6.638063625721618344e+00,1.145048934885973535e-01,7.610288237769032849e-01,4.563496123041156649e-02,-1.000000008114275696e+00,0.000000000000000000e+00 +6.833033518005007068e+01,4.119578860417683472e+02,3.925741556518747566e-01,6.639210087802560167e+00,1.146715601552640157e-01,7.595223603494672959e-01,4.563496123041156649e-02,-1.000000007541518299e+00,0.000000000000000000e+00 +6.833184138332843816e+01,4.119678203659495352e+02,3.937183597696926607e-01,6.640354082871709807e+00,1.148382268219306779e-01,7.580161570597435672e-01,4.563496123041156649e-02,-1.000000008049434008e+00,0.000000000000000000e+00 +6.833334732711927018e+01,4.119777544992920753e+02,3.948642195923079967e-01,6.641495612596781228e+00,1.150048934885973401e-01,7.565102132567935733e-01,4.563496123041156649e-02,-1.000000008217496017e+00,0.000000000000000000e+00 +6.833485301207086593e+01,4.119876884415199925e+02,3.960117350878913922e-01,6.642634678640613188e+00,1.151715601552640023e-01,7.550045282928212753e-01,4.563496123041156649e-02,-1.000000007776105537e+00,0.000000000000000000e+00 +6.833635843883054406e+01,4.119976221923573689e+02,3.971609062245674004e-01,6.643771282661184330e+00,1.153382268219306644e-01,7.534991015214355103e-01,4.563496123041156649e-02,-1.000000007610617914e+00,0.000000000000000000e+00 +6.833786360804461424e+01,4.120075557515282298e+02,3.983117329704146115e-01,6.644905426311625618e+00,1.155048934885973266e-01,7.519939322959078298e-01,4.563496123041156649e-02,-1.000000008586610756e+00,0.000000000000000000e+00 +6.833936852035840559e+01,4.120174891187566573e+02,3.994642152934655965e-01,6.646037111240230111e+00,1.156715601552639888e-01,7.504890199691996999e-01,4.563496123041156649e-02,-1.000000007626088649e+00,0.000000000000000000e+00 +6.834087317641623827e+01,4.120274222937667332e+02,4.006183531617069082e-01,6.647166339090462728e+00,1.158382268219306510e-01,7.489843638998936459e-01,4.563496123041156649e-02,-1.000000007904474408e+00,0.000000000000000000e+00 +6.834237757686146608e+01,4.120373552762825398e+02,4.017741465430792469e-01,6.648293111500978902e+00,1.160048934885973132e-01,7.474799634427790052e-01,4.563496123041156649e-02,-1.000000008262962092e+00,0.000000000000000000e+00 +6.834388172233644809e+01,4.120472880660281589e+02,4.029315954054771831e-01,6.649417430105629023e+00,1.161715601552639754e-01,7.459758179553710455e-01,4.563496123041156649e-02,-1.000000007912191125e+00,0.000000000000000000e+00 +6.834538561348256280e+01,4.120572206627276728e+02,4.040906997167493797e-01,6.650539296533472644e+00,1.163382268219306376e-01,7.444719267973507471e-01,4.563496123041156649e-02,-1.000000008005275776e+00,0.000000000000000000e+00 +6.834688925094023659e+01,4.120671530661052202e+02,4.052514594446985363e-01,6.651658712408791807e+00,1.165048934885972998e-01,7.429682893276398081e-01,4.563496123041156649e-02,-1.000000008104334537e+00,0.000000000000000000e+00 +6.834839263534890108e+01,4.120770852758848264e+02,4.064138745570812783e-01,6.652775679351099924e+00,1.166715601552639620e-01,7.414649049067902897e-01,4.563496123041156649e-02,-1.000000008142815533e+00,0.000000000000000000e+00 +6.834989576734703576e+01,4.120870172917906302e+02,4.075779450216082678e-01,6.653890198975154213e+00,1.168382268219306241e-01,7.399617728964226204e-01,4.563496123041156649e-02,-1.000000008033996135e+00,0.000000000000000000e+00 +6.835139864757212536e+01,4.120969491135467706e+02,4.087436708059442592e-01,6.655002272890967241e+00,1.170048934885972863e-01,7.384588926592524638e-01,4.563496123041156649e-02,-1.000000007669715973e+00,0.000000000000000000e+00 +6.835290127666073090e+01,4.121068807408773296e+02,4.099110518777079881e-01,6.656111902703818473e+00,1.171715601552639485e-01,7.369562635591194732e-01,4.563496123041156649e-02,-1.000000008496237491e+00,0.000000000000000000e+00 +6.835440365524843287e+01,4.121168121735064460e+02,4.110800882044721716e-01,6.657219090014265817e+00,1.173382268219306107e-01,7.354538849586484961e-01,4.563496123041156649e-02,-1.000000007610285291e+00,0.000000000000000000e+00 +6.835590578396987382e+01,4.121267434111582588e+02,4.122507797537636187e-01,6.658323836418153618e+00,1.175048934885972729e-01,7.339517562257812378e-01,4.563496123041156649e-02,-1.000000008385309336e+00,0.000000000000000000e+00 +6.835740766345871577e+01,4.121366744535568500e+02,4.134231264930631200e-01,6.659426143506630424e+00,1.176715601552639351e-01,7.324498767243431407e-01,4.563496123041156649e-02,-1.000000008270341523e+00,0.000000000000000000e+00 +6.835890929434769703e+01,4.121466053004264154e+02,4.145971283898054471e-01,6.660526012866152534e+00,1.178382268219305973e-01,7.309482458229397128e-01,4.563496123041156649e-02,-1.000000007843045768e+00,0.000000000000000000e+00 +6.836041067726860376e+01,4.121565359514910369e+02,4.157727854113794641e-01,6.661623446078500876e+00,1.180048934885972595e-01,7.294468628902534002e-01,4.563496123041156649e-02,-1.000000008055794032e+00,0.000000000000000000e+00 +6.836191181285228424e+01,4.121664664064749104e+02,4.169500975251280162e-01,6.662718444720790778e+00,1.181715601552639217e-01,7.279457272944783730e-01,4.563496123041156649e-02,-1.000000007871051366e+00,0.000000000000000000e+00 +6.836341270172864881e+01,4.121763966651021747e+02,4.181290646983479853e-01,6.663811010365480847e+00,1.183382268219305838e-01,7.264448384063048048e-01,4.563496123041156649e-02,-1.000000008596417800e+00,0.000000000000000000e+00 +6.836491334452665569e+01,4.121863267270969686e+02,4.193096868982902903e-01,6.664901144580386294e+00,1.185048934885972460e-01,7.249441955953953576e-01,4.563496123041156649e-02,-1.000000007575724714e+00,0.000000000000000000e+00 +6.836641374187435360e+01,4.121962565921834880e+02,4.204919640921598867e-01,6.665988848928686927e+00,1.186715601552639082e-01,7.234437982363304265e-01,4.563496123041156649e-02,-1.000000008444181576e+00,0.000000000000000000e+00 +6.836791389439885336e+01,4.122061862600859286e+02,4.216758962471157113e-01,6.667074124968944027e+00,1.188382268219305704e-01,7.219436456991642492e-01,4.563496123041156649e-02,-1.000000008111135985e+00,0.000000000000000000e+00 +6.836941380272634206e+01,4.122161157305284291e+02,4.228614833302707932e-01,6.668156974255103009e+00,1.190048934885972326e-01,7.204437373595133920e-01,4.563496123041156649e-02,-1.000000008200601309e+00,0.000000000000000000e+00 +6.837091346748208309e+01,4.122260450032351855e+02,4.240487253086921426e-01,6.669237398336511191e+00,1.191715601552638948e-01,7.189440725914800767e-01,4.563496123041156649e-02,-1.000000007949001013e+00,0.000000000000000000e+00 +6.837241288929041616e+01,4.122359740779303365e+02,4.252376221494008068e-01,6.670315398757924896e+00,1.193382268219305570e-01,7.174446507712305410e-01,4.563496123041156649e-02,-1.000000008153576481e+00,0.000000000000000000e+00 +6.837391206877477146e+01,4.122459029543381348e+02,4.264281738193718696e-01,6.671390977059521887e+00,1.195048934885972192e-01,7.159454712746511351e-01,4.563496123041156649e-02,-1.000000008011203034e+00,0.000000000000000000e+00 +6.837541100655766968e+01,4.122558316321827192e+02,4.276203802855344516e-01,6.672464134776910250e+00,1.196715601552638814e-01,7.144465334797447387e-01,4.563496123041156649e-02,-1.000000008676168450e+00,0.000000000000000000e+00 +6.837690970326072204e+01,4.122657601111883423e+02,4.288142415147717101e-01,6.673534873441140824e+00,1.198382268219305435e-01,7.129478367636932212e-01,4.563496123041156649e-02,-1.000000007724555440e+00,0.000000000000000000e+00 +6.837840815950463025e+01,4.122756883910791998e+02,4.300097574739208395e-01,6.674603194578715204e+00,1.200048934885972057e-01,7.114493805082171551e-01,4.563496123041156649e-02,-1.000000008249964489e+00,0.000000000000000000e+00 +6.837990637590918652e+01,4.122856164715795444e+02,4.312069281297730705e-01,6.675669099711601717e+00,1.201715601552638679e-01,7.099511640913038768e-01,4.563496123041156649e-02,-1.000000008185324640e+00,0.000000000000000000e+00 +6.838140435309328780e+01,4.122955443524135148e+02,4.324057534490736709e-01,6.676732590357238983e+00,1.203382268219305301e-01,7.084531868949378586e-01,4.563496123041156649e-02,-1.000000008213127733e+00,0.000000000000000000e+00 +6.838290209167494993e+01,4.123054720333054206e+02,4.336062333985219452e-01,6.677793668028551011e+00,1.205048934885971923e-01,7.069554483009774515e-01,4.563496123041156649e-02,-1.000000007810120994e+00,0.000000000000000000e+00 +6.838439959227127929e+01,4.123153995139794006e+02,4.348083679447711791e-01,6.678852334233956078e+00,1.206715601552638545e-01,7.054579476929579984e-01,4.563496123041156649e-02,-1.000000008810307373e+00,0.000000000000000000e+00 +6.838589685549848696e+01,4.123253267941597642e+02,4.360121570544288061e-01,6.679908590477378283e+00,1.208382268219305167e-01,7.039606844525587714e-01,4.563496123041156649e-02,-1.000000007879166875e+00,0.000000000000000000e+00 +6.838739388197191715e+01,4.123352538735707071e+02,4.372176006940561854e-01,6.680962438258253755e+00,1.210048934885971789e-01,7.024636579673390058e-01,4.563496123041156649e-02,-1.000000008002179808e+00,0.000000000000000000e+00 +6.838889067230600460e+01,4.123451807519365389e+02,4.384246988301687686e-01,6.682013879071548423e+00,1.211715601552638411e-01,7.009668676212719163e-01,4.563496123041156649e-02,-1.000000008581120259e+00,0.000000000000000000e+00 +6.839038722711433138e+01,4.123551074289814551e+02,4.396334514292360995e-01,6.683062914407761568e+00,1.213382268219305032e-01,6.994703128001076298e-01,4.563496123041156649e-02,-1.000000007807836822e+00,0.000000000000000000e+00 +6.839188354700957007e+01,4.123650339044297652e+02,4.408438584576817032e-01,6.684109545752937365e+00,1.215048934885971654e-01,6.979739928931799620e-01,4.563496123041156649e-02,-1.000000008615878677e+00,0.000000000000000000e+00 +6.839337963260355480e+01,4.123749601780056651e+02,4.420559198818831415e-01,6.685153774588679099e+00,1.216715601552638276e-01,6.964779072863076514e-01,4.563496123041156649e-02,-1.000000007969275906e+00,0.000000000000000000e+00 +6.839487548450722443e+01,4.123848862494334639e+02,4.432696356681720684e-01,6.686195602392152715e+00,1.218382268219304898e-01,6.949820553707235504e-01,4.563496123041156649e-02,-1.000000008369064997e+00,0.000000000000000000e+00 +6.839637110333063674e+01,4.123948121184374713e+02,4.444850057828341194e-01,6.687235030636103694e+00,1.220048934885971520e-01,6.934864365347874759e-01,4.563496123041156649e-02,-1.000000007932184687e+00,0.000000000000000000e+00 +6.839786648968302529e+01,4.124047377847419398e+02,4.457020301921090222e-01,6.688272060788861495e+00,1.221715601552638142e-01,6.919910501705414108e-01,4.563496123041156649e-02,-1.000000008330208967e+00,0.000000000000000000e+00 +6.839936164417272835e+01,4.124146632480711219e+02,4.469207088621905966e-01,6.689306694314353763e+00,1.223382268219304764e-01,6.904958956683899807e-01,4.563496123041156649e-02,-1.000000008437448740e+00,0.000000000000000000e+00 +6.840085656740721731e+01,4.124245885081493270e+02,4.481410417592265882e-01,6.690338932672112549e+00,1.225048934885971386e-01,6.890009724212806663e-01,4.563496123041156649e-02,-1.000000007903108834e+00,0.000000000000000000e+00 +6.840235125999313937e+01,4.124345135647008647e+02,4.493630288493188907e-01,6.691368777317286742e+00,1.226715601552638008e-01,6.875062798235415107e-01,4.563496123041156649e-02,-1.000000008744060587e+00,0.000000000000000000e+00 +6.840384572253627482e+01,4.124444384174500442e+02,4.505866700985234341e-01,6.692396229700652732e+00,1.228382268219304629e-01,6.860118172673393966e-01,4.563496123041156649e-02,-1.000000007790823764e+00,0.000000000000000000e+00 +6.840533995564155134e+01,4.124543630661211751e+02,4.518119654728501855e-01,6.693421291268619733e+00,1.230048934885971251e-01,6.845175841504285152e-01,4.563496123041156649e-02,-1.000000008616151792e+00,0.000000000000000000e+00 +6.840683395991302973e+01,4.124642875104385666e+02,4.530389149382631486e-01,6.694443963463246661e+00,1.231715601552637873e-01,6.830235798660715396e-01,4.563496123041156649e-02,-1.000000008013073760e+00,0.000000000000000000e+00 +6.840832773595396077e+01,4.124742117501265852e+02,4.542675184606803640e-01,6.695464247722243911e+00,1.233382268219304495e-01,6.815298038131673009e-01,4.563496123041156649e-02,-1.000000008326879630e+00,0.000000000000000000e+00 +6.840982128436674259e+01,4.124841357849094834e+02,4.554977760059739644e-01,6.696482145478990233e+00,1.235048934885971117e-01,6.800362553879523153e-01,4.563496123041156649e-02,-1.000000008303963517e+00,0.000000000000000000e+00 +6.841131460575292067e+01,4.124940596145116274e+02,4.567296875399701750e-01,6.697497658162537171e+00,1.236715601552637739e-01,6.785429339893742640e-01,4.563496123041156649e-02,-1.000000007865943674e+00,0.000000000000000000e+00 +6.841280770071321626e+01,4.125039832386573266e+02,4.579632530284492020e-01,6.698510787197621497e+00,1.238382268219304361e-01,6.770498390173331771e-01,4.563496123041156649e-02,-1.000000008910469473e+00,0.000000000000000000e+00 +6.841430056984751218e+01,4.125139066570710042e+02,4.591984724371453441e-01,6.699521534004674983e+00,1.240048934885970983e-01,6.755569698697284631e-01,4.563496123041156649e-02,-1.000000007738119923e+00,0.000000000000000000e+00 +6.841579321375488121e+01,4.125238298694769128e+02,4.604353457317469367e-01,6.700529899999829730e+00,1.241715601552637604e-01,6.740643259508121155e-01,4.563496123041156649e-02,-1.000000008603165735e+00,0.000000000000000000e+00 +6.841728563303354349e+01,4.125337528755994754e+02,4.616738728778964074e-01,6.701535886594935931e+00,1.243382268219304226e-01,6.725719066593122131e-01,4.563496123041156649e-02,-1.000000008168875798e+00,0.000000000000000000e+00 +6.841877782828090915e+01,4.125436756751630014e+02,4.629140538411902206e-01,6.702539495197561870e+00,1.245048934885970848e-01,6.710797113997610808e-01,4.563496123041156649e-02,-1.000000008264119611e+00,0.000000000000000000e+00 +6.842026980009356407e+01,4.125535982678919140e+02,4.641558885871788775e-01,6.703540727211010797e+00,1.246715601552637470e-01,6.695877395747824590e-01,4.563496123041156649e-02,-1.000000008707539356e+00,0.000000000000000000e+00 +6.842176154906726993e+01,4.125635206535105226e+02,4.653993770813669717e-01,6.704539584034326261e+00,1.248382268219304092e-01,6.680959905880889949e-01,4.563496123041156649e-02,-1.000000007702417371e+00,0.000000000000000000e+00 +6.842325307579697835e+01,4.125734428317432503e+02,4.666445192892131888e-01,6.705536067062301875e+00,1.250048934885970853e-01,6.666044638468885397e-01,4.563496123041156649e-02,-1.000000008625740566e+00,0.000000000000000000e+00 +6.842474438087684518e+01,4.125833648023144633e+02,4.678913151761302514e-01,6.706530177685494643e+00,1.251715601552637613e-01,6.651131587541641021e-01,4.563496123041156649e-02,-1.000000008049612532e+00,0.000000000000000000e+00 +6.842623546490018782e+01,4.125932865649485848e+02,4.691397647074849186e-01,6.707521917290226732e+00,1.253382268219304374e-01,6.636220747188206204e-01,4.563496123041156649e-02,-1.000000008518722838e+00,0.000000000000000000e+00 +6.842772632845952785e+01,4.126032081193699810e+02,4.703898678485980422e-01,6.708511287258602351e+00,1.255048934885971135e-01,6.621312111467747563e-01,4.563496123041156649e-02,-1.000000008168095533e+00,0.000000000000000000e+00 +6.842921697214660526e+01,4.126131294653030750e+02,4.716416245647445105e-01,6.709498288968511304e+00,1.256715601552637895e-01,6.606405674475275269e-01,4.563496123041156649e-02,-1.000000008710944188e+00,0.000000000000000000e+00 +6.843070739655232160e+01,4.126230506024722331e+02,4.728950348211533594e-01,6.710482923793642307e+00,1.258382268219304656e-01,6.591501430288267960e-01,4.563496123041156649e-02,-1.000000007846945982e+00,0.000000000000000000e+00 +6.843219760226681103e+01,4.126329715306018784e+02,4.741500985830076065e-01,6.711465193103488325e+00,1.260048934885971417e-01,6.576599373026469353e-01,4.563496123041156649e-02,-1.000000008457240686e+00,0.000000000000000000e+00 +6.843368758987939771e+01,4.126428922494164340e+02,4.754068158154443613e-01,6.712445098263360777e+00,1.261715601552638177e-01,6.561699496774636708e-01,4.563496123041156649e-02,-1.000000008607078827e+00,0.000000000000000000e+00 +6.843517735997860996e+01,4.126528127586403230e+02,4.766651864835547703e-01,6.713422640634392202e+00,1.263382268219304938e-01,6.546801795654283440e-01,4.563496123041156649e-02,-1.000000007944179758e+00,0.000000000000000000e+00 +6.843666691315219452e+01,4.126627330579980253e+02,4.779252105523841831e-01,6.714397821573549585e+00,1.265048934885971699e-01,6.531906263800062451e-01,4.563496123041156649e-02,-1.000000008501997106e+00,0.000000000000000000e+00 +6.843815624998711655e+01,4.126726531472139072e+02,4.791868879869318754e-01,6.715370642433644122e+00,1.266715601552638459e-01,6.517012895324203470e-01,4.563496123041156649e-02,-1.000000008294519738e+00,0.000000000000000000e+00 +6.843964537106954538e+01,4.126825730260124487e+02,4.804502187521512702e-01,6.716341104563335662e+00,1.268382268219305220e-01,6.502121684376357402e-01,4.563496123041156649e-02,-1.000000008521843009e+00,0.000000000000000000e+00 +6.844113427698488294e+01,4.126924926941180729e+02,4.817152028129498276e-01,6.717309209307146034e+00,1.270048934885971981e-01,6.487232625096113203e-01,4.563496123041156649e-02,-1.000000007964730209e+00,0.000000000000000000e+00 +6.844262296831773540e+01,4.127024121512552597e+02,4.829818401341890999e-01,6.718274958005465258e+00,1.271715601552638741e-01,6.472345711648996858e-01,4.563496123041156649e-02,-1.000000008593517675e+00,0.000000000000000000e+00 +6.844411144565194149e+01,4.127123313971484322e+02,4.842501306806847317e-01,6.719238351994563097e+00,1.273382268219305502e-01,6.457460938178957166e-01,4.563496123041156649e-02,-1.000000008354274605e+00,0.000000000000000000e+00 +6.844559970957057260e+01,4.127222504315221272e+02,4.855200744172064597e-01,6.720199392606593491e+00,1.275048934885972263e-01,6.442578298868246733e-01,4.563496123041156649e-02,-1.000000008383466588e+00,0.000000000000000000e+00 +6.844708776065593270e+01,4.127321692541007678e+02,4.867916713084780023e-01,6.721158081169607890e+00,1.276715601552639023e-01,6.427697787889902203e-01,4.563496123041156649e-02,-1.000000008197787782e+00,0.000000000000000000e+00 +6.844857559948954417e+01,4.127420878646088340e+02,4.880649213191772806e-01,6.722114419007561459e+00,1.278382268219305784e-01,6.412819399431826106e-01,4.563496123041156649e-02,-1.000000008501653159e+00,0.000000000000000000e+00 +6.845006322665217624e+01,4.127520062627708057e+02,4.893398244139361974e-01,6.723068407440322858e+00,1.280048934885972545e-01,6.397943127679086572e-01,4.563496123041156649e-02,-1.000000007976690863e+00,0.000000000000000000e+00 +6.845155064272381651e+01,4.127619244483111629e+02,4.906163805573408032e-01,6.724020047783681342e+00,1.281715601552639305e-01,6.383068966843983283e-01,4.563496123041156649e-02,-1.000000008901133830e+00,0.000000000000000000e+00 +6.845303784828372784e+01,4.127718424209543855e+02,4.918945897139312406e-01,6.724969341349358309e+00,1.283382268219306066e-01,6.368196911112520286e-01,4.563496123041156649e-02,-1.000000007916584721e+00,0.000000000000000000e+00 +6.845452484391039150e+01,4.127817601804250103e+02,4.931744518482016337e-01,6.725916289445010854e+00,1.285048934885972827e-01,6.353326954728214515e-01,4.563496123041156649e-02,-1.000000008877450774e+00,0.000000000000000000e+00 +6.845601163018153557e+01,4.127916777264475172e+02,4.944559669246003097e-01,6.726860893374247752e+00,1.286715601552639587e-01,6.338459091884801611e-01,4.563496123041156649e-02,-1.000000007989823025e+00,0.000000000000000000e+00 +6.845749820767414917e+01,4.128015950587464431e+02,4.957391349075295772e-01,6.727803154436629463e+00,1.288382268219306348e-01,6.323593316839939416e-01,4.563496123041156649e-02,-1.000000008274935404e+00,0.000000000000000000e+00 +6.845898457696445405e+01,4.128115121770463247e+02,4.970239557613458925e-01,6.728743073927685003e+00,1.290048934885973109e-01,6.308729623813851273e-01,4.563496123041156649e-02,-1.000000008719969857e+00,0.000000000000000000e+00 +6.846047073862794718e+01,4.128214290810716420e+02,4.983104294503598042e-01,6.729680653138913726e+00,1.291715601552639869e-01,6.293868007049276958e-01,4.563496123041156649e-02,-1.000000008295325760e+00,0.000000000000000000e+00 +6.846195669323938660e+01,4.128313457705469318e+02,4.995985559388359531e-01,6.730615893357795976e+00,1.293382268219306630e-01,6.279008460811686954e-01,4.563496123041156649e-02,-1.000000008369126947e+00,0.000000000000000000e+00 +6.846344244137276291e+01,4.128412622451967877e+02,5.008883351909929615e-01,6.731548795867803747e+00,1.295048934885973391e-01,6.264150979353623194e-01,4.563496123041156649e-02,-1.000000008282999175e+00,0.000000000000000000e+00 +6.846492798360134202e+01,4.128511785047456897e+02,5.021797671710037658e-01,6.732479361948406016e+00,1.296715601552640151e-01,6.249295556944788332e-01,4.563496123041156649e-02,-1.000000008570034016e+00,0.000000000000000000e+00 +6.846641332049766504e+01,4.128610945489181745e+02,5.034728518429951727e-01,6.733407592875078507e+00,1.298382268219306912e-01,6.234442187854316586e-01,4.563496123041156649e-02,-1.000000008138146379e+00,0.000000000000000000e+00 +6.846789845263351992e+01,4.128710103774388358e+02,5.047675891710481366e-01,6.734333489919310800e+00,1.300048934885973673e-01,6.219590866374887783e-01,4.563496123041156649e-02,-1.000000008295040210e+00,0.000000000000000000e+00 +6.846938338057998408e+01,4.128809259900322104e+02,5.060639791191977599e-01,6.735257054348616990e+00,1.301715601552640433e-01,6.204741586787057006e-01,4.563496123041156649e-02,-1.000000008723305411e+00,0.000000000000000000e+00 +6.847086810490739595e+01,4.128908413864228919e+02,5.073620216514331815e-01,6.736178287426541011e+00,1.303382268219307194e-01,6.189894343383367525e-01,4.563496123041156649e-02,-1.000000008283936204e+00,0.000000000000000000e+00 +6.847235262618538343e+01,4.129007565663354740e+02,5.086617167316976884e-01,6.737097190412665526e+00,1.305048934885973955e-01,6.175049130480518844e-01,4.563496123041156649e-02,-1.000000008239743110e+00,0.000000000000000000e+00 +6.847383694498283546e+01,4.129106715294944934e+02,5.099630643238887151e-01,6.738013764562622576e+00,1.306715601552640715e-01,6.160205942383680799e-01,4.563496123041156649e-02,-1.000000008630953285e+00,0.000000000000000000e+00 +6.847532106186793044e+01,4.129205862756245438e+02,5.112660643918576220e-01,6.738928011128098916e+00,1.308382268219307476e-01,6.145364773404622394e-01,4.563496123041156649e-02,-1.000000008271987095e+00,0.000000000000000000e+00 +6.847680497740813621e+01,4.129305008044501619e+02,5.125707168994100282e-01,6.739839931356844005e+00,1.310048934885974237e-01,6.130525617879876155e-01,4.563496123041156649e-02,-1.000000008785542738e+00,0.000000000000000000e+00 +6.847828869217018166e+01,4.129404151156959983e+02,5.138770218103055898e-01,6.740749526492680666e+00,1.311715601552640997e-01,6.115688470129035936e-01,4.563496123041156649e-02,-1.000000007745434738e+00,0.000000000000000000e+00 +6.847977220672011356e+01,4.129503292090866466e+02,5.151849790882579994e-01,6.741656797775509524e+00,1.313382268219307758e-01,6.100853324514809994e-01,4.563496123041156649e-02,-1.000000008762925274e+00,0.000000000000000000e+00 +6.848125552162325391e+01,4.129602430843467573e+02,5.164945886969350974e-01,6.742561746441322335e+00,1.315048934885974519e-01,6.086020175353421546e-01,4.563496123041156649e-02,-1.000000008574359223e+00,0.000000000000000000e+00 +6.848273863744422840e+01,4.129701567412009240e+02,5.178058505999588723e-01,6.743464373722201977e+00,1.316715601552641279e-01,6.071189017016574985e-01,4.563496123041156649e-02,-1.000000008340197422e+00,0.000000000000000000e+00 +6.848422155474693795e+01,4.129800701793737403e+02,5.191187647609053490e-01,6.744364680846337556e+00,1.318382268219308040e-01,6.056359843865798398e-01,4.563496123041156649e-02,-1.000000007995410112e+00,0.000000000000000000e+00 +6.848570427409460137e+01,4.129899833985898567e+02,5.204333311433048115e-01,6.745262669038029735e+00,1.320048934885974801e-01,6.041532650270597937e-01,4.563496123041156649e-02,-1.000000009076938312e+00,0.000000000000000000e+00 +6.848718679604974113e+01,4.129998963985738669e+02,5.217495497106413582e-01,6.746158339517698721e+00,1.321715601552641561e-01,6.026707430584682390e-01,4.563496123041156649e-02,-1.000000007853748096e+00,0.000000000000000000e+00 +6.848866912117416916e+01,4.130098091790504213e+02,5.230674204263534577e-01,6.747051693501888714e+00,1.323382268219308322e-01,6.011884179224038505e-01,4.563496123041156649e-02,-1.000000008662912387e+00,0.000000000000000000e+00 +6.849015125002900106e+01,4.130197217397441705e+02,5.243869432538336151e-01,6.747942732203283889e+00,1.325048934885975083e-01,5.997062890547296687e-01,4.563496123041156649e-02,-1.000000008551310993e+00,0.000000000000000000e+00 +6.849163318317468452e+01,4.130296340803798216e+02,5.257081181564283723e-01,6.748831456830706621e+00,1.326715601552641843e-01,5.982243558963775687e-01,4.563496123041156649e-02,-1.000000008189566580e+00,0.000000000000000000e+00 +6.849311492117095668e+01,4.130395462006819685e+02,5.270309450974384191e-01,6.749717868589131697e+00,1.328382268219308604e-01,5.967426178879740029e-01,4.563496123041156649e-02,-1.000000008639113869e+00,0.000000000000000000e+00 +6.849459646457687256e+01,4.130494581003752614e+02,5.283554240401185931e-01,6.750601968679692533e+00,1.330048934885975365e-01,5.952610744692590217e-01,4.563496123041156649e-02,-1.000000008114683814e+00,0.000000000000000000e+00 +6.849607781395080508e+01,4.130593697791844079e+02,5.296815549476777685e-01,6.751483758299686500e+00,1.331715601552642125e-01,5.937797250833015683e-01,4.563496123041156649e-02,-1.000000008863680012e+00,0.000000000000000000e+00 +6.849755896985045922e+01,4.130692812368341151e+02,5.310093377832790784e-01,6.752363238642586474e+00,1.333382268219308886e-01,5.922985691705225930e-01,4.563496123041156649e-02,-1.000000007856427953e+00,0.000000000000000000e+00 +6.849903993283284365e+01,4.130791924730489768e+02,5.323387725100395818e-01,6.753240410898043500e+00,1.335048934885975647e-01,5.908176061765094689e-01,4.563496123041156649e-02,-1.000000008932985907e+00,0.000000000000000000e+00 +6.850052070345428490e+01,4.130891034875537571e+02,5.336698590910304851e-01,6.754115276251901001e+00,1.336715601552642407e-01,5.893368355418386884e-01,4.563496123041156649e-02,-1.000000008224082082e+00,0.000000000000000000e+00 +6.850200128227045582e+01,4.130990142800731064e+02,5.350025974892772540e-01,6.754987835886193892e+00,1.338382268219309168e-01,5.878562567134906214e-01,4.563496123041156649e-02,-1.000000008732512047e+00,0.000000000000000000e+00 +6.850348166983634712e+01,4.131089248503317322e+02,5.363369876677593906e-01,6.755858090979164565e+00,1.340048934885975929e-01,5.863758691346707685e-01,4.563496123041156649e-02,-1.000000008179784627e+00,0.000000000000000000e+00 +6.850496186670628163e+01,4.131188351980543416e+02,5.376730295894104339e-01,6.756726042705263779e+00,1.341715601552642689e-01,5.848956722526269525e-01,4.563496123041156649e-02,-1.000000008326002998e+00,0.000000000000000000e+00 +6.850644187343391422e+01,4.131287453229656990e+02,5.390107232171180707e-01,6.757591692235163094e+00,1.343382268219309450e-01,5.834156655126679913e-01,4.563496123041156649e-02,-1.000000008486010561e+00,0.000000000000000000e+00 +6.850792169057224612e+01,4.131386552247904547e+02,5.403500685137242465e-01,6.758455040735758423e+00,1.345048934885976211e-01,5.819358483617811384e-01,4.563496123041156649e-02,-1.000000008770568494e+00,0.000000000000000000e+00 +6.850940131867359639e+01,4.131485649032533729e+02,5.416910654420248328e-01,6.759316089370178915e+00,1.346715601552642971e-01,5.804562202474514709e-01,4.563496123041156649e-02,-1.000000008059870105e+00,0.000000000000000000e+00 +6.851088075828964463e+01,4.131584743580791610e+02,5.430337139647699596e-01,6.760174839297794058e+00,1.348382268219309732e-01,5.789767806194801025e-01,4.563496123041156649e-02,-1.000000008466166657e+00,0.000000000000000000e+00 +6.851236000997140252e+01,4.131683835889925831e+02,5.443780140446639049e-01,6.761031291674223453e+00,1.350048934885976493e-01,5.774975289251998989e-01,4.563496123041156649e-02,-1.000000008842013566e+00,0.000000000000000000e+00 +6.851383907426922804e+01,4.131782925957183465e+02,5.457239656443649833e-01,6.761885447651339476e+00,1.351715601552643253e-01,5.760184646142959553e-01,4.563496123041156649e-02,-1.000000008024923392e+00,0.000000000000000000e+00 +6.851531795173282546e+01,4.131882013779812155e+02,5.470715687264855465e-01,6.762737308377277046e+00,1.353382268219310014e-01,5.745395871388245812e-01,4.563496123041156649e-02,-1.000000008899872617e+00,0.000000000000000000e+00 +6.851679664291125960e+01,4.131981099355059541e+02,5.484208232535922045e-01,6.763586874996443399e+00,1.355048934885976775e-01,5.730608959472250907e-01,4.563496123041156649e-02,-1.000000007839942473e+00,0.000000000000000000e+00 +6.851827514835294153e+01,4.132080182680173266e+02,5.497717291882057156e-01,6.764434148649518974e+00,1.356715601552643535e-01,5.715823904939474343e-01,4.563496123041156649e-02,-1.000000008922852013e+00,0.000000000000000000e+00 +6.851975346860564287e+01,4.132179263752400971e+02,5.511242864928008744e-01,6.765279130473472513e+00,1.358382268219310296e-01,5.701040702280572026e-01,4.563496123041156649e-02,-1.000000008493162618e+00,0.000000000000000000e+00 +6.852123160421648151e+01,4.132278342568990297e+02,5.524784951298067348e-01,6.766121821601559283e+00,1.360048934885977057e-01,5.686259346046669272e-01,4.563496123041156649e-02,-1.000000008164086740e+00,0.000000000000000000e+00 +6.852270955573193589e+01,4.132377419127188887e+02,5.538343550616062760e-01,6.766962223163336176e+00,1.361715601552643817e-01,5.671479830771442021e-01,4.563496123041156649e-02,-1.000000008316840328e+00,0.000000000000000000e+00 +6.852418732369785914e+01,4.132476493424244950e+02,5.551918662505367363e-01,6.767800336284665264e+00,1.363382268219310578e-01,5.656702150989311173e-01,4.563496123041156649e-02,-1.000000008913169092e+00,0.000000000000000000e+00 +6.852566490865946491e+01,4.132575565457406697e+02,5.565510286588895017e-01,6.768636162087720010e+00,1.365048934885977339e-01,5.641926301241619868e-01,4.563496123041156649e-02,-1.000000008273050689e+00,0.000000000000000000e+00 +6.852714231116131316e+01,4.132674635223921769e+02,5.579118422489101059e-01,6.769469701690992380e+00,1.366715601552644099e-01,5.627152276100865214e-01,4.563496123041156649e-02,-1.000000008365213855e+00,0.000000000000000000e+00 +6.852861953174736698e+01,4.132773702721037807e+02,5.592743069827981195e-01,6.770300956209303500e+00,1.368382268219310860e-01,5.612380070116762543e-01,4.563496123041156649e-02,-1.000000008703925802e+00,0.000000000000000000e+00 +6.853009657096093576e+01,4.132872767946003592e+02,5.606384228227072608e-01,6.771129926753806316e+00,1.370048934885977621e-01,5.597609677852489751e-01,4.563496123041156649e-02,-1.000000008383064021e+00,0.000000000000000000e+00 +6.853157342934471785e+01,4.132971830896067331e+02,5.620041897307455070e-01,6.771956614431993593e+00,1.371715601552644381e-01,5.582841093890869022e-01,4.563496123041156649e-02,-1.000000008110868199e+00,0.000000000000000000e+00 +6.853305010744077208e+01,4.133070891568476668e+02,5.633716076689748720e-01,6.772781020347706793e+00,1.373382268219311142e-01,5.568074312810498139e-01,4.563496123041156649e-02,-1.000000008991224210e+00,0.000000000000000000e+00 +6.853452660579056044e+01,4.133169949960480380e+02,5.647406765994115174e-01,6.773603145601141406e+00,1.375048934885977903e-01,5.553309329179890730e-01,4.563496123041156649e-02,-1.000000008040658361e+00,0.000000000000000000e+00 +6.853600292493490542e+01,4.133269006069326679e+02,5.661113964840257529e-01,6.774422991288851392e+00,1.376715601552644663e-01,5.538546137617803566e-01,4.563496123041156649e-02,-1.000000008781391170e+00,0.000000000000000000e+00 +6.853747906541400425e+01,4.133368059892264341e+02,5.674837672847419245e-01,6.775240558503762500e+00,1.378382268219311424e-01,5.523784732697158972e-01,4.563496123041156649e-02,-1.000000008202685420e+00,0.000000000000000000e+00 +6.853895502776747151e+01,4.133467111426541578e+02,5.688577889634387486e-01,6.776055848335171383e+00,1.380048934885978185e-01,5.509025109041471024e-01,4.563496123041156649e-02,-1.000000008579646549e+00,0.000000000000000000e+00 +6.854043081253428227e+01,4.133566160669406599e+02,5.702334614819488667e-01,6.776868861868758920e+00,1.381715601552644945e-01,5.494267261246793543e-01,4.563496123041156649e-02,-1.000000008505062432e+00,0.000000000000000000e+00 +6.854190642025280056e+01,4.133665207618108752e+02,5.716107848020592908e-01,6.777679600186591991e+00,1.383382268219311706e-01,5.479511183936049967e-01,4.563496123041156649e-02,-1.000000008598019852e+00,0.000000000000000000e+00 +6.854338185146080775e+01,4.133764252269896247e+02,5.729897588855108470e-01,6.778488064367133248e+00,1.385048934885978467e-01,5.464756871729103960e-01,4.563496123041156649e-02,-1.000000008240728322e+00,0.000000000000000000e+00 +6.854485710669545995e+01,4.133863294622017861e+02,5.743703836939988427e-01,6.779294255485246445e+00,1.386715601552645227e-01,5.450004319260988161e-01,4.563496123041156649e-02,-1.000000008842795163e+00,0.000000000000000000e+00 +6.854633218649331639e+01,4.133962334671722942e+02,5.757526591891725110e-01,6.780098174612204431e+00,1.388382268219311988e-01,5.435253521151971468e-01,4.563496123041156649e-02,-1.000000008128216988e+00,0.000000000000000000e+00 +6.854780709139033945e+01,4.134061372416259701e+02,5.771365853326353434e-01,6.780899822815692701e+00,1.390048934885978749e-01,5.420504472061905554e-01,4.563496123041156649e-02,-1.000000008298030263e+00,0.000000000000000000e+00 +6.854928182192188046e+01,4.134160407852877483e+02,5.785221620859449798e-01,6.781699201159820944e+00,1.391715601552645509e-01,5.405757166624162169e-01,4.563496123041156649e-02,-1.000000009092171238e+00,0.000000000000000000e+00 +6.855075637862269389e+01,4.134259440978825069e+02,5.799093894106132074e-01,6.782496310705124820e+00,1.393382268219312270e-01,5.391011599481916328e-01,4.563496123041156649e-02,-1.000000007785690759e+00,0.000000000000000000e+00 +6.855223076202696575e+01,4.134358471791351803e+02,5.812982672681058505e-01,6.783291152508573063e+00,1.395048934885979031e-01,5.376267765324463932e-01,4.563496123041156649e-02,-1.000000008994891942e+00,0.000000000000000000e+00 +6.855370497266825680e+01,4.134457500287706466e+02,5.826887956198429919e-01,6.784083727623579918e+00,1.396715601552645791e-01,5.361525658778955039e-01,4.563496123041156649e-02,-1.000000008334967605e+00,0.000000000000000000e+00 +6.855517901107955936e+01,4.134556526465138404e+02,5.840809744271988624e-01,6.784874037100001587e+00,1.398382268219312552e-01,5.346785274543083277e-01,4.563496123041156649e-02,-1.000000008355039993e+00,0.000000000000000000e+00 +6.855665287779326889e+01,4.134655550320896964e+02,5.854748036515018406e-01,6.785662081984152216e+00,1.400048934885979313e-01,5.332046607282836526e-01,4.563496123041156649e-02,-1.000000008322732725e+00,0.000000000000000000e+00 +6.855812657334119820e+01,4.134754571852232061e+02,5.868702832540343417e-01,6.786447863318804785e+00,1.401715601552646073e-01,5.317309651680851568e-01,4.563496123041156649e-02,-1.000000008719288180e+00,0.000000000000000000e+00 +6.855960009825459167e+01,4.134853591056392474e+02,5.882674131960331509e-01,6.787231382143199099e+00,1.403382268219312834e-01,5.302574402418503974e-01,4.563496123041156649e-02,-1.000000008787070627e+00,0.000000000000000000e+00 +6.856107345306408263e+01,4.134952607930627551e+02,5.896661934386890902e-01,6.788012639493047118e+00,1.405048934885979595e-01,5.287840854194142404e-01,4.563496123041156649e-02,-1.000000008164135590e+00,0.000000000000000000e+00 +6.856254663829975016e+01,4.135051622472187205e+02,5.910666239431471292e-01,6.788791636400540952e+00,1.406715601552646355e-01,5.273109001717232180e-01,4.563496123041156649e-02,-1.000000008522722972e+00,0.000000000000000000e+00 +6.856401965449107649e+01,4.135150634678320785e+02,5.924687046705063853e-01,6.789568373894359965e+00,1.408382268219313116e-01,5.258378839678367056e-01,4.563496123041156649e-02,-1.000000008249096073e+00,0.000000000000000000e+00 +6.856549250216700386e+01,4.135249644546277636e+02,5.938724355818202350e-01,6.790342852999673440e+00,1.410048934885979877e-01,5.243650362797656062e-01,4.563496123041156649e-02,-1.000000008582465849e+00,0.000000000000000000e+00 +6.856696518185586342e+01,4.135348652073308244e+02,5.952778166380960911e-01,6.791115074738150348e+00,1.411715601552646637e-01,5.228923565782676031e-01,4.563496123041156649e-02,-1.000000008702578214e+00,0.000000000000000000e+00 +6.856843769408543210e+01,4.135447657256661955e+02,5.966848478002957368e-01,6.791885040127962903e+00,1.413382268219313398e-01,5.214198443358784019e-01,4.563496123041156649e-02,-1.000000008186149314e+00,0.000000000000000000e+00 +6.856991003938293261e+01,4.135546660093588685e+02,5.980935290293347695e-01,6.792652750183794552e+00,1.415048934885980159e-01,5.199474990263245333e-01,4.563496123041156649e-02,-1.000000008646739325e+00,0.000000000000000000e+00 +6.857138221827500502e+01,4.135645660581338348e+02,5.995038602860832677e-01,6.793418205916847086e+00,1.416715601552646919e-01,5.184753201215223095e-01,4.563496123041156649e-02,-1.000000008407408103e+00,0.000000000000000000e+00 +6.857285423128773516e+01,4.135744658717160860e+02,6.009158415313653467e-01,6.794181408334843297e+00,1.418382268219313680e-01,5.170033070964203947e-01,4.563496123041156649e-02,-1.000000008648343819e+00,0.000000000000000000e+00 +6.857432607894664045e+01,4.135843654498306137e+02,6.023294727259593806e-01,6.794942358442036756e+00,1.420048934885980441e-01,5.155314594247912829e-01,4.563496123041156649e-02,-1.000000008487811343e+00,0.000000000000000000e+00 +6.857579776177666986e+01,4.135942647922024662e+02,6.037447538305977801e-01,6.795701057239215359e+00,1.421715601552647201e-01,5.140597765822644272e-01,4.563496123041156649e-02,-1.000000008262209583e+00,0.000000000000000000e+00 +6.857726928030224656e+01,4.136041638985566351e+02,6.051616848059671039e-01,6.796457505723709325e+00,1.423382268219313962e-01,5.125882580445310088e-01,4.563496123041156649e-02,-1.000000008706400489e+00,0.000000000000000000e+00 +6.857874063504721107e+01,4.136140627686181688e+02,6.065802656127082804e-01,6.797211704889396522e+00,1.425048934885980723e-01,5.111169032867557416e-01,4.563496123041156649e-02,-1.000000008492291093e+00,0.000000000000000000e+00 +6.858021182653486392e+01,4.136239614021120587e+02,6.080004962114161637e-01,6.797963655726706911e+00,1.426715601552647483e-01,5.096457117866102227e-01,4.563496123041156649e-02,-1.000000008330984347e+00,0.000000000000000000e+00 +6.858168285528795138e+01,4.136338597987633534e+02,6.094223765626399780e-01,6.798713359222631425e+00,1.428382268219314244e-01,5.081746830212702237e-01,4.563496123041156649e-02,-1.000000008511877203e+00,0.000000000000000000e+00 +6.858315372182866554e+01,4.136437579582971580e+02,6.108459066268829840e-01,6.799460816360726412e+00,1.430048934885981005e-01,5.067038164680343071e-01,4.563496123041156649e-02,-1.000000008491618297e+00,0.000000000000000000e+00 +6.858462442667865844e+01,4.136536558804384640e+02,6.122710863646028123e-01,6.800206028121118962e+00,1.431715601552647765e-01,5.052331116055466254e-01,4.563496123041156649e-02,-1.000000008535949281e+00,0.000000000000000000e+00 +6.858609497035904212e+01,4.136635535649123199e+02,6.136979157362110193e-01,6.800948995480514014e+00,1.433382268219314526e-01,5.037625679126046530e-01,4.563496123041156649e-02,-1.000000008488580061e+00,0.000000000000000000e+00 +6.858756535339038862e+01,4.136734510114438308e+02,6.151263947020735312e-01,6.801689719412199686e+00,1.435048934885981287e-01,5.022921848687778024e-01,4.563496123041156649e-02,-1.000000008592023759e+00,0.000000000000000000e+00 +6.858903557629271575e+01,4.136833482197580452e+02,6.165565232225103109e-01,6.802428200886053489e+00,1.436715601552648047e-01,5.008219619538188949e-01,4.563496123041156649e-02,-1.000000008255561124e+00,0.000000000000000000e+00 +6.859050563958551550e+01,4.136932451895800682e+02,6.179883012577955803e-01,6.803164440868547658e+00,1.438382268219314808e-01,4.993518986488871270e-01,4.563496123041156649e-02,-1.000000008520705475e+00,0.000000000000000000e+00 +6.859197554378772566e+01,4.137031419206349483e+02,6.194217287681577089e-01,6.803898440322756258e+00,1.440048934885981569e-01,4.978819944341463799e-01,4.563496123041156649e-02,-1.000000008362631254e+00,0.000000000000000000e+00 +6.859344528941778663e+01,4.137130384126477907e+02,6.208568057137793250e-01,6.804630200208358737e+00,1.441715601552648329e-01,4.964122487918007920e-01,4.563496123041156649e-02,-1.000000008799928786e+00,0.000000000000000000e+00 +6.859491487699357037e+01,4.137229346653437005e+02,6.222935320547972049e-01,6.805359721481647917e+00,1.443382268219315090e-01,4.949426612030890515e-01,4.563496123041156649e-02,-1.000000008372967875e+00,0.000000000000000000e+00 +6.859638430703243728e+01,4.137328306784477832e+02,6.237319077513021615e-01,6.806087005095533549e+00,1.445048934885981851e-01,4.934732311519245407e-01,4.563496123041156649e-02,-1.000000008489240422e+00,0.000000000000000000e+00 +6.859785358005120770e+01,4.137427264516851437e+02,6.251719327633393775e-01,6.806812051999551194e+00,1.446715601552648611e-01,4.920039581206797630e-01,4.563496123041156649e-02,-1.000000008488500569e+00,0.000000000000000000e+00 +6.859932269656619042e+01,4.137526219847808875e+02,6.266136070509081835e-01,6.807534863139864889e+00,1.448382268219315372e-01,4.905348415932229145e-01,4.563496123041156649e-02,-1.000000008110067951e+00,0.000000000000000000e+00 +6.860079165709316840e+01,4.137625172774601197e+02,6.280569305739620578e-01,6.808255439459274250e+00,1.450048934885982133e-01,4.890658810543284662e-01,4.563496123041156649e-02,-1.000000009140309620e+00,0.000000000000000000e+00 +6.860226046214739881e+01,4.137724123294480023e+02,6.295019032924087377e-01,6.808973781897220690e+00,1.451715601552648893e-01,4.875970759866682380e-01,4.563496123041156649e-02,-1.000000008002750462e+00,0.000000000000000000e+00 +6.860372911224362724e+01,4.137823071404696975e+02,6.309485251661099969e-01,6.809689891389789196e+00,1.453382268219315654e-01,4.861284258786865986e-01,4.563496123041156649e-02,-1.000000008519677408e+00,0.000000000000000000e+00 +6.860519760789607346e+01,4.137922017102503105e+02,6.323967961548819794e-01,6.810403768869721652e+00,1.455048934885982415e-01,4.846599302137311605e-01,4.563496123041156649e-02,-1.000000008738871182e+00,0.000000000000000000e+00 +6.860666594961844567e+01,4.138020960385150033e+02,6.338467162184948656e-01,6.811115415266414175e+00,1.456715601552649175e-01,4.831915884785320525e-01,4.563496123041156649e-02,-1.000000008342710967e+00,0.000000000000000000e+00 +6.860813413792392623e+01,4.138119901249889381e+02,6.352982853166730948e-01,6.811824831505926880e+00,1.458382268219315936e-01,4.817234001607987870e-01,4.563496123041156649e-02,-1.000000008650964611e+00,0.000000000000000000e+00 +6.860960217332521438e+01,4.138218839693972768e+02,6.367515034090953652e-01,6.812532018510990106e+00,1.460048934885982697e-01,4.802553647468142950e-01,4.563496123041156649e-02,-1.000000008087821302e+00,0.000000000000000000e+00 +6.861107005633446931e+01,4.138317775714651816e+02,6.382063704553944117e-01,6.813236977201007072e+00,1.461715601552649457e-01,4.787874817256840831e-01,4.563496123041156649e-02,-1.000000008775817184e+00,0.000000000000000000e+00 +6.861253778746336707e+01,4.138416709309178145e+02,6.396628864151573390e-01,6.813939708492062763e+00,1.463382268219316218e-01,4.773197505839050780e-01,4.563496123041156649e-02,-1.000000008291834552e+00,0.000000000000000000e+00 +6.861400536722307208e+01,4.138515640474803945e+02,6.411210512479252888e-01,6.814640213296924820e+00,1.465048934885982979e-01,4.758521708120360127e-01,4.563496123041156649e-02,-1.000000008737103485e+00,0.000000000000000000e+00 +6.861547279612423722e+01,4.138614569208780836e+02,6.425808649131937722e-01,6.815338492525054193e+00,1.466715601552649739e-01,4.743847418980547959e-01,4.563496123041156649e-02,-1.000000008490331327e+00,0.000000000000000000e+00 +6.861694007467701795e+01,4.138713495508361007e+02,6.440423273704124485e-01,6.816034547082606032e+00,1.468382268219316500e-01,4.729174633328197541e-01,4.563496123041156649e-02,-1.000000008393860274e+00,0.000000000000000000e+00 +6.861840720339107236e+01,4.138812419370796647e+02,6.455054385789850135e-01,6.816728377872438571e+00,1.470048934885983261e-01,4.714503346064521927e-01,4.563496123041156649e-02,-1.000000008041646238e+00,0.000000000000000000e+00 +6.861987418277556117e+01,4.138911340793339377e+02,6.469701984982695331e-01,6.817419985794116677e+00,1.471715601552650021e-01,4.699833552101662648e-01,4.563496123041156649e-02,-1.000000009080540764e+00,0.000000000000000000e+00 +6.862134101333914771e+01,4.139010259773241955e+02,6.484366070875782206e-01,6.818109371743918068e+00,1.473382268219316782e-01,4.685165246332554934e-01,4.563496123041156649e-02,-1.000000008193195677e+00,0.000000000000000000e+00 +6.862280769559001214e+01,4.139109176307756002e+02,6.499046643061775486e-01,6.818796536614835091e+00,1.475048934885983543e-01,4.670498423703726698e-01,4.563496123041156649e-02,-1.000000008655914874e+00,0.000000000000000000e+00 +6.862427423003583726e+01,4.139208090394134274e+02,6.513743701132881370e-01,6.819481481296587155e+00,1.476715601552650303e-01,4.655833079118560924e-01,4.563496123041156649e-02,-1.000000008367762261e+00,0.000000000000000000e+00 +6.862574061718380847e+01,4.139307002029628961e+02,6.528457244680848648e-01,6.820164206675618956e+00,1.478382268219317064e-01,4.641169207516146478e-01,4.563496123041156649e-02,-1.000000008519770445e+00,0.000000000000000000e+00 +6.862720685754062799e+01,4.139405911211492821e+02,6.543187273296967588e-01,6.820844713635110246e+00,1.480048934885983825e-01,4.626506803822977854e-01,4.563496123041156649e-02,-1.000000008227808213e+00,0.000000000000000000e+00 +6.862867295161252912e+01,4.139504817936978043e+02,6.557933786572069934e-01,6.821523003054978496e+00,1.481715601552650585e-01,4.611845862983366406e-01,4.563496123041156649e-02,-1.000000008662123241e+00,0.000000000000000000e+00 +6.863013889990523353e+01,4.139603722203337384e+02,6.572696784096531131e-01,6.822199075811886004e+00,1.483382268219317346e-01,4.597186379929299460e-01,4.563496123041156649e-02,-1.000000008503603821e+00,0.000000000000000000e+00 +6.863160470292400817e+01,4.139702624007823601e+02,6.587476265460266989e-01,6.822872932779242561e+00,1.485048934885984107e-01,4.582528349616916685e-01,4.563496123041156649e-02,-1.000000008488252767e+00,0.000000000000000000e+00 +6.863307036117362259e+01,4.139801523347689454e+02,6.602272230252737018e-01,6.823544574827213438e+00,1.486715601552650867e-01,4.567871766996361993e-01,4.563496123041156649e-02,-1.000000008515177008e+00,0.000000000000000000e+00 +6.863453587515837739e+01,4.139900420220187129e+02,6.617084678062942205e-01,6.824214002822722946e+00,1.488382268219317628e-01,4.553216627024033181e-01,4.563496123041156649e-02,-1.000000008472763158e+00,0.000000000000000000e+00 +6.863600124538209002e+01,4.139999314622569955e+02,6.631913608479426125e-01,6.824881217629459762e+00,1.490048934885984389e-01,4.538562924662719045e-01,4.563496123041156649e-02,-1.000000008238902671e+00,0.000000000000000000e+00 +6.863746647234812315e+01,4.140098206552091256e+02,6.646759021090273833e-01,6.825546220107882256e+00,1.491715601552651149e-01,4.523910654881733162e-01,4.563496123041156649e-02,-1.000000008922132810e+00,0.000000000000000000e+00 +6.863893155655934208e+01,4.140197096006003221e+02,6.661620915483111860e-01,6.826209011115223824e+00,1.493382268219317910e-01,4.509259812638863885e-01,4.563496123041156649e-02,-1.000000007896427068e+00,0.000000000000000000e+00 +6.864039649851815739e+01,4.140295982981559746e+02,6.676499291245110435e-01,6.826869591505495549e+00,1.495048934885984671e-01,4.494610392935070586e-01,4.563496123041156649e-02,-1.000000008732766732e+00,0.000000000000000000e+00 +6.864186129872651065e+01,4.140394867476013587e+02,6.691394147962981265e-01,6.827527962129496863e+00,1.496715601552651431e-01,4.479962390723675747e-01,4.563496123041156649e-02,-1.000000008783925143e+00,0.000000000000000000e+00 +6.864332595768587453e+01,4.140493749486617503e+02,6.706305485222978646e-01,6.828184123834812880e+00,1.498382268219318192e-01,4.465315801001441542e-01,4.563496123041156649e-02,-1.000000007874875418e+00,0.000000000000000000e+00 +6.864479047589725269e+01,4.140592629010625387e+02,6.721233302610898352e-01,6.828838077465825052e+00,1.500048934885984953e-01,4.450670618772329945e-01,4.563496123041156649e-02,-1.000000008719226230e+00,0.000000000000000000e+00 +6.864625485386119408e+01,4.140691506045290566e+02,6.736177599712078745e-01,6.829489823863716502e+00,1.501715601552651713e-01,4.436026839005182132e-01,4.563496123041156649e-02,-1.000000008637330629e+00,0.000000000000000000e+00 +6.864771909207779288e+01,4.140790380587866366e+02,6.751138376111400774e-01,6.830139363866471136e+00,1.503382268219318474e-01,4.421384456712684763e-01,4.563496123041156649e-02,-1.000000008251541228e+00,0.000000000000000000e+00 +6.864918319104667432e+01,4.140889252635606113e+02,6.766115631393286867e-01,6.830786698308884297e+00,1.505048934885985235e-01,4.406743466902991457e-01,4.563496123041156649e-02,-1.000000008588957767e+00,0.000000000000000000e+00 +6.865064715126702310e+01,4.140988122185763132e+02,6.781109365141703149e-01,6.831431828022566322e+00,1.506715601552651995e-01,4.392103864573781991e-01,4.563496123041156649e-02,-1.000000008594841949e+00,0.000000000000000000e+00 +6.865211097323754075e+01,4.141086989235591318e+02,6.796119576940156115e-01,6.832074753835945202e+00,1.508382268219318756e-01,4.377465644742723483e-01,4.563496123041156649e-02,-1.000000008032226662e+00,0.000000000000000000e+00 +6.865357465745650245e+01,4.141185853782344566e+02,6.811146266371695956e-01,6.832715476574273694e+00,1.510048934885985517e-01,4.362828802435476105e-01,4.563496123041156649e-02,-1.000000008727673917e+00,0.000000000000000000e+00 +6.865503820442172866e+01,4.141284715823276201e+02,6.826189433018914343e-01,6.833353997059634644e+00,1.511715601552652277e-01,4.348193332655472254e-01,4.563496123041156649e-02,-1.000000008765878690e+00,0.000000000000000000e+00 +6.865650161463058510e+01,4.141383575355640687e+02,6.841249076463945533e-01,6.833990316110941876e+00,1.513382268219319038e-01,4.333559230438666643e-01,4.563496123041156649e-02,-1.000000007879198405e+00,0.000000000000000000e+00 +6.865796488857998270e+01,4.141482432376691349e+02,6.856325196288466373e-01,6.834624434543949079e+00,1.515048934885985799e-01,4.318926490829397280e-01,4.563496123041156649e-02,-1.000000008694254428e+00,0.000000000000000000e+00 +6.865942802676640611e+01,4.141581286883682651e+02,6.871417792073695185e-01,6.835256353171255128e+00,1.516715601552652559e-01,4.304295108838018247e-01,4.563496123041156649e-02,-1.000000008434811738e+00,0.000000000000000000e+00 +6.866089102968587099e+01,4.141680138873868486e+02,6.886526863400393994e-01,6.835886072802303204e+00,1.518382268219319320e-01,4.289665079519939250e-01,4.563496123041156649e-02,-1.000000008462862189e+00,0.000000000000000000e+00 +6.866235389783398091e+01,4.141778988344502750e+02,6.901652409848865188e-01,6.836513594243391445e+00,1.520048934885986081e-01,4.275036397915055186e-01,4.563496123041156649e-02,-1.000000008886322567e+00,0.000000000000000000e+00 +6.866381663170588467e+01,4.141877835292839336e+02,6.916794430998955967e-01,6.837138918297674728e+00,1.521715601552652841e-01,4.260409059066078696e-01,4.563496123041156649e-02,-1.000000007726855378e+00,0.000000000000000000e+00 +6.866527923179629056e+01,4.141976679716133276e+02,6.931952926430053896e-01,6.837762045765169105e+00,1.523382268219319602e-01,4.245783058049035774e-01,4.563496123041156649e-02,-1.000000008808742402e+00,0.000000000000000000e+00 +6.866674169859948051e+01,4.142075521611638464e+02,6.947127895721090240e-01,6.838382977442760691e+00,1.525048934885986363e-01,4.231158389888375337e-01,4.563496123041156649e-02,-1.000000008473024282e+00,0.000000000000000000e+00 +6.866820403260928174e+01,4.142174360976609364e+02,6.962319338450536632e-01,6.839001714124202103e+00,1.526715601552653123e-01,4.216535049666401136e-01,4.563496123041156649e-02,-1.000000008448370226e+00,0.000000000000000000e+00 +6.866966623431912353e+01,4.142273197808299869e+02,6.977527254196410622e-01,6.839618256600124901e+00,1.528382268219319884e-01,4.201913032444455909e-01,4.563496123041156649e-02,-1.000000008377454952e+00,0.000000000000000000e+00 +6.867112830422198044e+01,4.142372032103965012e+02,6.992751642536269019e-01,6.840232605658040477e+00,1.530048934885986645e-01,4.187292333293410884e-01,4.563496123041156649e-02,-1.000000008308543631e+00,0.000000000000000000e+00 +6.867259024281040070e+01,4.142470863860859822e+02,7.007992503047212329e-01,6.840844762082345376e+00,1.531715601552653405e-01,4.172672947287716094e-01,4.563496123041156649e-02,-1.000000008695562714e+00,0.000000000000000000e+00 +6.867405205057652040e+01,4.142569693076238195e+02,7.023249835305882538e-01,6.841454726654325746e+00,1.533382268219320166e-01,4.158054869499452355e-01,4.563496123041156649e-02,-1.000000008320371947e+00,0.000000000000000000e+00 +6.867551372801203513e+01,4.142668519747355731e+02,7.038523638888465328e-01,6.842062500152160887e+00,1.535048934885986927e-01,4.143438095022755618e-01,4.563496123041156649e-02,-1.000000008448633571e+00,0.000000000000000000e+00 +6.867697527560821413e+01,4.142767343871466323e+02,7.053813913370688971e-01,6.842668083350930353e+00,1.536715601552653687e-01,4.128822618937490474e-01,4.563496123041156649e-02,-1.000000008257971862e+00,0.000000000000000000e+00 +6.867843669385591454e+01,4.142866165445825573e+02,7.069120658327823215e-01,6.843271477022615734e+00,1.538382268219320448e-01,4.114208436339753527e-01,4.563496123041156649e-02,-1.000000008579722488e+00,0.000000000000000000e+00 +6.867989798324558137e+01,4.142964984467687941e+02,7.084443873334680397e-01,6.843872681936106872e+00,1.540048934885987209e-01,4.099595542317685526e-01,4.563496123041156649e-02,-1.000000008571678478e+00,0.000000000000000000e+00 +6.868135914426723332e+01,4.143063800934309029e+02,7.099783557965616554e-01,6.844471698857204522e+00,1.541715601552653969e-01,4.084983931975910698e-01,4.563496123041156649e-02,-1.000000008213746128e+00,0.000000000000000000e+00 +6.868282017741047696e+01,4.143162614842943299e+02,7.115139711794528088e-01,6.845068528548626574e+00,1.543382268219320730e-01,4.070373600423503047e-01,4.563496123041156649e-02,-1.000000008724764244e+00,0.000000000000000000e+00 +6.868428108316449254e+01,4.143261426190846350e+02,7.130512334394856211e-01,6.845663171770012490e+00,1.545048934885987491e-01,4.055764542755868618e-01,4.563496123041156649e-02,-1.000000007984790606e+00,0.000000000000000000e+00 +6.868574186201806242e+01,4.143360234975273215e+02,7.145901425339583612e-01,6.846255629277925081e+00,1.546715601552654251e-01,4.041156754103505944e-01,4.563496123041156649e-02,-1.000000008858547007e+00,0.000000000000000000e+00 +6.868720251445955682e+01,4.143459041193478924e+02,7.161306984201234460e-01,6.846845901825859393e+00,1.548382268219321012e-01,4.026550229559168748e-01,4.563496123041156649e-02,-1.000000008373955973e+00,0.000000000000000000e+00 +6.868866304097693387e+01,4.143557844842719646e+02,7.176729010551877730e-01,6.847433990164240925e+00,1.550048934885987773e-01,4.011944964263110536e-01,4.563496123041156649e-02,-1.000000008128339557e+00,0.000000000000000000e+00 +6.869012344205773957e+01,4.143656645920250412e+02,7.192167503963123876e-01,6.848019895040436289e+00,1.551715601552654533e-01,3.997340953336320224e-01,4.563496123041156649e-02,-1.000000008460803391e+00,0.000000000000000000e+00 +6.869158371818912201e+01,4.143755444423326253e+02,7.207622464006124829e-01,6.848603617198754101e+00,1.553382268219321294e-01,3.982738191898885782e-01,4.563496123041156649e-02,-1.000000008451850331e+00,0.000000000000000000e+00 +6.869304386985783140e+01,4.143854240349203337e+02,7.223093890251576221e-01,6.849185157380448530e+00,1.555048934885988055e-01,3.968136675088355658e-01,4.563496123041156649e-02,-1.000000008838153320e+00,0.000000000000000000e+00 +6.869450389755020581e+01,4.143953033695137265e+02,7.238581782269717380e-01,6.849764516323725516e+00,1.556715601552654815e-01,3.953536398035535915e-01,4.563496123041156649e-02,-1.000000007847334116e+00,0.000000000000000000e+00 +6.869596380175218542e+01,4.144051824458383635e+02,7.254086139630328001e-01,6.850341694763745437e+00,1.558382268219321576e-01,3.938937355901105941e-01,4.563496123041156649e-02,-1.000000008697965015e+00,0.000000000000000000e+00 +6.869742358294932671e+01,4.144150612636198616e+02,7.269606961902731479e-01,6.850916693432631099e+00,1.560048934885988337e-01,3.924339543802735086e-01,4.563496123041156649e-02,-1.000000008348263636e+00,0.000000000000000000e+00 +6.869888324162677407e+01,4.144249398225837808e+02,7.285144248655794907e-01,6.851489513059465075e+00,1.561715601552655097e-01,3.909742956906460676e-01,4.563496123041156649e-02,-1.000000008331617174e+00,0.000000000000000000e+00 +6.870034277826927394e+01,4.144348181224557379e+02,7.300697999457925746e-01,6.852060154370300360e+00,1.563382268219321858e-01,3.895147590359879231e-01,4.563496123041156649e-02,-1.000000008504756899e+00,0.000000000000000000e+00 +6.870180219336118910e+01,4.144446961629612929e+02,7.316268213877076265e-01,6.852628618088161261e+00,1.565048934885988619e-01,3.880553439316605790e-01,4.563496123041156649e-02,-1.000000008298223664e+00,0.000000000000000000e+00 +6.870326148738649863e+01,4.144545739438260625e+02,7.331854891480740211e-01,6.853194904933047837e+00,1.566715601552655379e-01,3.865960498942475065e-01,4.563496123041156649e-02,-1.000000008801477103e+00,0.000000000000000000e+00 +6.870472066082876950e+01,4.144644514647757205e+02,7.347458031835953918e-01,6.853759015621941231e+00,1.568382268219322140e-01,3.851368764391314703e-01,4.563496123041156649e-02,-1.000000007757489540e+00,0.000000000000000000e+00 +6.870617971417121339e+01,4.144743287255358268e+02,7.363077634509297420e-01,6.854320950868805440e+00,1.570048934885988901e-01,3.836778230853760130e-01,4.563496123041156649e-02,-1.000000008740647761e+00,0.000000000000000000e+00 +6.870763864789661568e+01,4.144842057258320551e+02,7.378713699066893339e-01,6.854880711384596204e+00,1.571715601552655661e-01,3.822188893472149851e-01,4.563496123041156649e-02,-1.000000008641064086e+00,0.000000000000000000e+00 +6.870909746248742067e+01,4.144940824653900222e+02,7.394366225074405774e-01,6.855438297877257448e+00,1.573382268219322422e-01,3.807600747438036337e-01,4.563496123041156649e-02,-1.000000008093992587e+00,0.000000000000000000e+00 +6.871055615842566056e+01,4.145039589439354017e+02,7.410035212097041413e-01,6.855993711051731943e+00,1.575048934885989182e-01,3.793013787937523640e-01,4.563496123041156649e-02,-1.000000008561212850e+00,0.000000000000000000e+00 +6.871201473619301225e+01,4.145138351611938106e+02,7.425720659699551751e-01,6.856546951609963969e+00,1.576715601552655943e-01,3.778428010139197601e-01,4.563496123041156649e-02,-1.000000008155792708e+00,0.000000000000000000e+00 +6.871347319627074057e+01,4.145237111168909223e+02,7.441422567446229763e-01,6.857098020250900205e+00,1.578382268219322704e-01,3.763843409242955129e-01,4.563496123041156649e-02,-1.000000008321559442e+00,0.000000000000000000e+00 +6.871493153913975505e+01,4.145335868107524107e+02,7.457140934900912121e-01,6.857646917670497722e+00,1.580048934885989464e-01,3.749259980431404182e-01,4.563496123041156649e-02,-1.000000008823225706e+00,0.000000000000000000e+00 +6.871638976528059573e+01,4.145434622425039493e+02,7.472875761626975866e-01,6.858193644561724867e+00,1.581715601552656225e-01,3.734677718894338638e-01,4.563496123041156649e-02,-1.000000008163238752e+00,0.000000000000000000e+00 +6.871784787517341897e+01,4.145533374118712118e+02,7.488627047187343955e-01,6.858738201614565710e+00,1.583382268219322986e-01,3.720096619847125252e-01,4.563496123041156649e-02,-1.000000008176464616e+00,0.000000000000000000e+00 +6.871930586929799745e+01,4.145632123185798719e+02,7.504394791144479715e-01,6.859280589516027149e+00,1.585048934885989746e-01,3.705516678482093096e-01,4.563496123041156649e-02,-1.000000008600566481e+00,0.000000000000000000e+00 +6.872076374813376276e+01,4.145730869623556600e+02,7.520178993060391281e-01,6.859820808950138904e+00,1.586715601552656507e-01,3.690937889999099664e-01,4.563496123041156649e-02,-1.000000008328298051e+00,0.000000000000000000e+00 +6.872222151215974861e+01,4.145829613429242499e+02,7.535979652496627157e-01,6.860358860597957964e+00,1.588382268219323268e-01,3.676360249617829368e-01,4.563496123041156649e-02,-1.000000008332341928e+00,0.000000000000000000e+00 +6.872367916185464765e+01,4.145928354600113721e+02,7.551796769014281763e-01,6.860894745137574802e+00,1.590048934885990028e-01,3.661783752547453363e-01,4.563496123041156649e-02,-1.000000008323506107e+00,0.000000000000000000e+00 +6.872513669769675460e+01,4.146027093133427570e+02,7.567630342173989888e-01,6.861428463244115150e+00,1.591715601552656789e-01,3.647208394005009291e-01,4.563496123041156649e-02,-1.000000008421024766e+00,0.000000000000000000e+00 +6.872659412016403735e+01,4.146125829026441352e+02,7.583480371535930020e-01,6.861960015589744444e+00,1.593382268219323550e-01,3.632634169209430497e-01,4.563496123041156649e-02,-1.000000008317488698e+00,0.000000000000000000e+00 +6.872805142973408010e+01,4.146224562276412371e+02,7.599346856659823235e-01,6.862489402843671371e+00,1.595048934885990310e-01,3.618061073387747184e-01,4.563496123041156649e-02,-1.000000008532712092e+00,0.000000000000000000e+00 +6.872950862688412599e+01,4.146323292880597933e+02,7.615229797104934306e-01,6.863016625672152315e+00,1.596715601552657071e-01,3.603489101763013847e-01,4.563496123041156649e-02,-1.000000007904732202e+00,0.000000000000000000e+00 +6.873096571209103445e+01,4.146422020836255342e+02,7.631129192430070596e-01,6.863541684738494020e+00,1.598382268219323832e-01,3.588918249578799680e-01,4.563496123041156649e-02,-1.000000008609415181e+00,0.000000000000000000e+00 +6.873242268583132386e+01,4.146520746140642473e+02,7.647045042193582054e-01,6.864064580703059804e+00,1.600048934885990592e-01,3.574348512050535276e-01,4.563496123041156649e-02,-1.000000008630252957e+00,0.000000000000000000e+00 +6.873387954858114313e+01,4.146619468791016629e+02,7.662977345953361219e-01,6.864585314223268675e+00,1.601715601552657353e-01,3.559779884426582663e-01,4.563496123041156649e-02,-1.000000008033414156e+00,0.000000000000000000e+00 +6.873533630081631429e+01,4.146718188784635686e+02,7.678926103266844327e-01,6.865103885953603324e+00,1.603382268219324114e-01,3.545212361957870151e-01,4.563496123041156649e-02,-1.000000008550713027e+00,0.000000000000000000e+00 +6.873679294301228992e+01,4.146816906118757515e+02,7.694891313691011314e-01,6.865620296545613677e+00,1.605048934885990874e-01,3.530645939873613415e-01,4.563496123041156649e-02,-1.000000008138552943e+00,0.000000000000000000e+00 +6.873824947564416732e+01,4.146915620790639991e+02,7.710872976782383592e-01,6.866134546647916892e+00,1.606715601552657635e-01,3.516080613436296520e-01,4.563496123041156649e-02,-1.000000008511593208e+00,0.000000000000000000e+00 +6.873970589918670271e+01,4.147014332797540987e+02,7.726871092097025162e-01,6.866646636906205359e+00,1.608382268219324396e-01,3.501516377886910170e-01,4.563496123041156649e-02,-1.000000008026662890e+00,0.000000000000000000e+00 +6.874116221411432548e+01,4.147113042136718377e+02,7.742885659190544834e-01,6.867156567963246694e+00,1.610048934885991156e-01,3.486953228493843149e-01,4.563496123041156649e-02,-1.000000008800641993e+00,0.000000000000000000e+00 +6.874261842090108132e+01,4.147211748805430034e+02,7.758916677618094004e-01,6.867664340458890848e+00,1.611715601552657917e-01,3.472391160498104479e-01,4.563496123041156649e-02,-1.000000007915846645e+00,0.000000000000000000e+00 +6.874407452002070329e+01,4.147310452800934399e+02,7.774964146934365550e-01,6.868169955030069218e+00,1.613382268219324678e-01,3.457830169186624225e-01,4.563496123041156649e-02,-1.000000008729127421e+00,0.000000000000000000e+00 +6.874553051194656916e+01,4.147409154120489916e+02,7.791028066693597154e-01,6.868673412310804416e+00,1.615048934885991438e-01,3.443270249800867711e-01,4.563496123041156649e-02,-1.000000007885872622e+00,0.000000000000000000e+00 +6.874698639715171566e+01,4.147507852761354457e+02,7.807108436449567979e-01,6.869174712932206717e+00,1.616715601552658199e-01,3.428711397634544578e-01,4.563496123041156649e-02,-1.000000008307453170e+00,0.000000000000000000e+00 +6.874844217610885266e+01,4.147606548720786463e+02,7.823205255755601994e-01,6.869673857522484717e+00,1.618382268219324960e-01,3.414153607942213564e-01,4.563496123041156649e-02,-1.000000008716944278e+00,0.000000000000000000e+00 +6.874989784929034897e+01,4.147705241996044379e+02,7.839318524164564650e-01,6.870170846706942669e+00,1.620048934885991720e-01,3.399596876000391954e-01,4.563496123041156649e-02,-1.000000008247038608e+00,0.000000000000000000e+00 +6.875135341716823234e+01,4.147803932584387212e+02,7.855448241228865092e-01,6.870665681107986700e+00,1.621715601552658481e-01,3.385041197101571475e-01,4.563496123041156649e-02,-1.000000008118012262e+00,0.000000000000000000e+00 +6.875280888021418946e+01,4.147902620483072837e+02,7.871594406500456165e-01,6.871158361345130139e+00,1.623382268219325242e-01,3.370486566523814287e-01,4.563496123041156649e-02,-1.000000008284217756e+00,0.000000000000000000e+00 +6.875426423889959437e+01,4.148001305689360265e+02,7.887757019530833302e-01,6.871648888034994407e+00,1.625048934885992002e-01,3.355932979549165474e-01,4.563496123041156649e-02,-1.000000008272141194e+00,0.000000000000000000e+00 +6.875571949369548008e+01,4.148099988200508506e+02,7.903936079871034526e-01,6.872137261791312568e+00,1.626715601552658763e-01,3.341380431469863077e-01,4.563496123041156649e-02,-1.000000008438373333e+00,0.000000000000000000e+00 +6.875717464507256693e+01,4.148198668013776000e+02,7.920131587071641555e-01,6.872623483224933771e+00,1.628382268219325524e-01,3.326828917576240552e-01,4.563496123041156649e-02,-1.000000008292344811e+00,0.000000000000000000e+00 +6.875862969350122000e+01,4.148297345126421760e+02,7.936343540682779807e-01,6.873107552943825915e+00,1.630048934885992284e-01,3.312278433169038583e-01,4.563496123041156649e-02,-1.000000008173632216e+00,0.000000000000000000e+00 +6.876008463945150595e+01,4.148396019535704795e+02,7.952571940254117289e-01,6.873589471553080088e+00,1.631715601552659045e-01,3.297728973547308651e-01,4.563496123041156649e-02,-1.000000008414079211e+00,0.000000000000000000e+00 +6.876153948339315036e+01,4.148494691238884116e+02,7.968816785334864594e-01,6.874069239654913233e+00,1.633382268219325806e-01,3.283180534008510731e-01,4.563496123041156649e-02,-1.000000008077716718e+00,0.000000000000000000e+00 +6.876299422579555198e+01,4.148593360233218732e+02,7.985078075473776016e-01,6.874546857848670811e+00,1.635048934885992566e-01,3.268633109866941888e-01,4.563496123041156649e-02,-1.000000008738491486e+00,0.000000000000000000e+00 +6.876444886712781113e+01,4.148692026515968223e+02,8.001355810219149545e-01,6.875022326730832134e+00,1.636715601552659327e-01,3.254086696417206048e-01,4.563496123041156649e-02,-1.000000007764804577e+00,0.000000000000000000e+00 +6.876590340785870126e+01,4.148790690084391599e+02,8.017649989118824649e-01,6.875495646895010360e+00,1.638382268219326088e-01,3.239541288995375634e-01,4.563496123041156649e-02,-1.000000008393065354e+00,0.000000000000000000e+00 +6.876735784845666899e+01,4.148889350935747871e+02,8.033960611720186717e-01,6.875966818931961377e+00,1.640048934885992848e-01,3.224996882893618189e-01,4.563496123041156649e-02,-1.000000008394660744e+00,0.000000000000000000e+00 +6.876881218938984830e+01,4.148988009067296616e+02,8.050287677570162614e-01,6.876435843429580252e+00,1.641715601552659609e-01,3.210453473439673355e-01,4.563496123041156649e-02,-1.000000008470825374e+00,0.000000000000000000e+00 +6.877026643112607474e+01,4.149086664476297415e+02,8.066631186215221794e-01,6.876902720972909222e+00,1.643382268219326370e-01,3.195911055954220870e-01,4.563496123041156649e-02,-1.000000007634956001e+00,0.000000000000000000e+00 +6.877172057413285700e+01,4.149185317160010413e+02,8.082991137201378518e-01,6.877367452144139470e+00,1.645048934885993130e-01,3.181369625775410936e-01,4.563496123041156649e-02,-1.000000008672580876e+00,0.000000000000000000e+00 +6.877317461887739114e+01,4.149283967115694622e+02,8.099367530074189636e-01,6.877830037522616458e+00,1.646715601552659891e-01,3.166829178203995898e-01,4.563496123041156649e-02,-1.000000008480286251e+00,0.000000000000000000e+00 +6.877462856582656059e+01,4.149382614340609621e+02,8.115760364378755698e-01,6.878290477684837256e+00,1.648382268219326652e-01,3.152289708588947303e-01,4.563496123041156649e-02,-1.000000007726579154e+00,0.000000000000000000e+00 +6.877608241544696455e+01,4.149481258832015556e+02,8.132169639659719840e-01,6.878748773204460321e+00,1.650048934885993412e-01,3.137751212272589796e-01,4.563496123041156649e-02,-1.000000008332850632e+00,0.000000000000000000e+00 +6.877753616820487537e+01,4.149579900587172574e+02,8.148595355461268896e-01,6.879204924652307263e+00,1.651715601552660173e-01,3.123213684572374027e-01,4.563496123041156649e-02,-1.000000008430895093e+00,0.000000000000000000e+00 +6.877898982456626698e+01,4.149678539603340255e+02,8.165037511327133402e-01,6.879658932596361964e+00,1.653382268219326934e-01,3.108677120835955932e-01,4.563496123041156649e-02,-1.000000008244637417e+00,0.000000000000000000e+00 +6.878044338499680066e+01,4.149777175877778177e+02,8.181496106800586476e-01,6.880110797601777683e+00,1.655048934885993694e-01,3.094141516410763293e-01,4.563496123041156649e-02,-1.000000007990253792e+00,0.000000000000000000e+00 +6.878189684996185349e+01,4.149875809407747056e+02,8.197971141424444941e-01,6.880560520230879717e+00,1.656715601552660455e-01,3.079606866644093444e-01,4.563496123041156649e-02,-1.000000008716875000e+00,0.000000000000000000e+00 +6.878335021992648990e+01,4.149974440190507039e+02,8.214462614741068203e-01,6.881008101043168068e+00,1.658382268219327216e-01,3.065073166870992405e-01,4.563496123041156649e-02,-1.000000007681207004e+00,0.000000000000000000e+00 +6.878480349535549010e+01,4.150073068223318273e+02,8.230970526292360478e-01,6.881453540595318330e+00,1.660048934885993976e-01,3.050540412469357476e-01,4.563496123041156649e-02,-1.000000008439170474e+00,0.000000000000000000e+00 +6.878625667671332167e+01,4.150171693503440906e+02,8.247494875619768573e-01,6.881896839441190572e+00,1.661715601552660737e-01,3.036008598768372146e-01,4.563496123041156649e-02,-1.000000008231090920e+00,0.000000000000000000e+00 +6.878770976446416796e+01,4.150270316028135653e+02,8.264035662264282989e-01,6.882337998131824897e+00,1.663382268219327498e-01,3.021477721140274908e-01,4.563496123041156649e-02,-1.000000008073752111e+00,0.000000000000000000e+00 +6.878916275907191391e+01,4.150368935794663230e+02,8.280592885766436817e-01,6.882777017215450321e+00,1.665048934885994258e-01,3.006947774945461505e-01,4.563496123041156649e-02,-1.000000008135039975e+00,0.000000000000000000e+00 +6.879061566100016023e+01,4.150467552800283784e+02,8.297166545666307957e-01,6.883213897237485668e+00,1.666715601552661019e-01,2.992418755544806741e-01,4.563496123041156649e-02,-1.000000008574968735e+00,0.000000000000000000e+00 +6.879206847071220920e+01,4.150566167042258030e+02,8.313756641503516898e-01,6.883648638740542225e+00,1.668382268219327780e-01,2.977890658299763849e-01,4.563496123041156649e-02,-1.000000007862137386e+00,0.000000000000000000e+00 +6.879352118867107890e+01,4.150664778517846685e+02,8.330363172817227824e-01,6.884081242264426415e+00,1.670048934885994540e-01,2.963363478596920952e-01,4.563496123041156649e-02,-1.000000008244460670e+00,0.000000000000000000e+00 +6.879497381533948897e+01,4.150763387224310463e+02,8.346986139146147510e-01,6.884511708346146008e+00,1.671715601552661301e-01,2.948837211793080559e-01,4.563496123041156649e-02,-1.000000008174580790e+00,0.000000000000000000e+00 +6.879642635117988902e+01,4.150861993158910082e+02,8.363625540028527539e-01,6.884940037519908351e+00,1.673382268219328062e-01,2.934311853270379911e-01,4.563496123041156649e-02,-1.000000008201301194e+00,0.000000000000000000e+00 +6.879787879665443029e+01,4.150960596318906823e+02,8.380281375002162081e-01,6.885366230317126579e+00,1.675048934885994822e-01,2.919787398405824241e-01,4.563496123041156649e-02,-1.000000008023672837e+00,0.000000000000000000e+00 +6.879933115222499396e+01,4.151059196701561405e+02,8.396953643604387896e-01,6.885790287266421394e+00,1.676715601552661583e-01,2.905263842583614697e-01,4.563496123041156649e-02,-1.000000008596062528e+00,0.000000000000000000e+00 +6.880078341835317701e+01,4.151157794304135109e+02,8.413642345372087661e-01,6.886212208893624620e+00,1.678382268219328344e-01,2.890741181176901264e-01,4.563496123041156649e-02,-1.000000007917088318e+00,0.000000000000000000e+00 +6.880223559550030643e+01,4.151256389123889221e+02,8.430347479841686642e-01,6.886631995721780086e+00,1.680048934885995104e-01,2.876219409590693443e-01,4.563496123041156649e-02,-1.000000007767672061e+00,0.000000000000000000e+00 +6.880368768412741076e+01,4.151354981158085025e+02,8.447069046549152693e-01,6.887049648271150737e+00,1.681715601552661865e-01,2.861698523206915312e-01,4.563496123041156649e-02,-1.000000008657701001e+00,0.000000000000000000e+00 +6.880513968469524855e+01,4.151453570403983804e+02,8.463807045029997367e-01,6.887465167059217741e+00,1.683382268219328626e-01,2.847178517402851883e-01,4.563496123041156649e-02,-1.000000007719109796e+00,0.000000000000000000e+00 +6.880659159766430832e+01,4.151552156858846843e+02,8.480561474819277024e-01,6.887878552600682269e+00,1.685048934885995386e-01,2.832659387600180434e-01,4.563496123041156649e-02,-1.000000008395018236e+00,0.000000000000000000e+00 +6.880804342349480862e+01,4.151650740519935425e+02,8.497332335451590613e-01,6.888289805407474375e+00,1.686715601552662147e-01,2.818141129173317716e-01,4.563496123041156649e-02,-1.000000008222545311e+00,0.000000000000000000e+00 +6.880949516264668375e+01,4.151749321384511404e+02,8.514119626461081891e-01,6.888698925988748556e+00,1.688382268219328908e-01,2.803623737535156368e-01,4.563496123041156649e-02,-1.000000008101480153e+00,0.000000000000000000e+00 +6.881094681557961223e+01,4.151847899449836632e+02,8.530923347381436095e-01,6.889105914850891743e+00,1.690048934885995668e-01,2.789107208088226764e-01,4.563496123041156649e-02,-1.000000008081300518e+00,0.000000000000000000e+00 +6.881239838275300258e+01,4.151946474713172393e+02,8.547743497745883268e-01,6.889510772497524194e+00,1.691715601552662429e-01,2.774591536237027700e-01,4.563496123041156649e-02,-1.000000007782260614e+00,0.000000000000000000e+00 +6.881384986462597908e+01,4.152045047171780539e+02,8.564580077087197152e-01,6.889913499429502153e+00,1.693382268219329190e-01,2.760076717394241430e-01,4.563496123041156649e-02,-1.000000008502926807e+00,0.000000000000000000e+00 +6.881530126165742445e+01,4.152143616822923491e+02,8.581433084937695188e-01,6.890314096144921407e+00,1.695048934885995950e-01,2.745562746956358158e-01,4.563496123041156649e-02,-1.000000007739828334e+00,0.000000000000000000e+00 +6.881675257430593717e+01,4.152242183663862534e+02,8.598302520829237405e-01,6.890712563139117286e+00,1.696715601552662711e-01,2.731049620358844687e-01,4.563496123041156649e-02,-1.000000008463020729e+00,0.000000000000000000e+00 +6.881820380302987417e+01,4.152340747691860088e+02,8.615188384293229751e-01,6.891108900904672652e+00,1.698382268219329472e-01,2.716537332996687426e-01,4.563496123041156649e-02,-1.000000008152962083e+00,0.000000000000000000e+00 +6.881965494828730812e+01,4.152439308904178006e+02,8.632090674860619650e-01,6.891503109931414350e+00,1.700048934885996232e-01,2.702025880304049221e-01,4.563496123041156649e-02,-1.000000007656160594e+00,0.000000000000000000e+00 +6.882110601053607013e+01,4.152537867298078709e+02,8.649009392061898227e-01,6.891895190706421204e+00,1.701715601552662993e-01,2.687515257705402338e-01,4.563496123041156649e-02,-1.000000008233335791e+00,0.000000000000000000e+00 +6.882255699023370710e+01,4.152636422870824049e+02,8.665944535427102524e-01,6.892285143714024898e+00,1.703382268219329754e-01,2.673005460609506057e-01,4.563496123041156649e-02,-1.000000008184976474e+00,0.000000000000000000e+00 +6.882400788783755274e+01,4.152734975619677016e+02,8.682896104485811062e-01,6.892672969435809982e+00,1.705048934885996514e-01,2.658496484452345654e-01,4.563496123041156649e-02,-1.000000007912799083e+00,0.000000000000000000e+00 +6.882545870380464237e+01,4.152833525541899462e+02,8.699864098767147169e-01,6.893058668350620088e+00,1.706715601552663275e-01,2.643988324666626810e-01,4.563496123041156649e-02,-1.000000008233161930e+00,0.000000000000000000e+00 +6.882690943859178390e+01,4.152932072634754377e+02,8.716848517799777873e-01,6.893442240934559706e+00,1.708382268219330036e-01,2.629480976675746540e-01,4.563496123041156649e-02,-1.000000007844832561e+00,0.000000000000000000e+00 +6.882836009265552946e+01,4.153030616895504181e+02,8.733849361111913900e-01,6.893823687660995070e+00,1.710048934885996796e-01,2.614974435924499740e-01,4.563496123041156649e-02,-1.000000007971007854e+00,0.000000000000000000e+00 +6.882981066645217538e+01,4.153129158321411296e+02,8.750866628231309674e-01,6.894203009000559490e+00,1.711715601552663557e-01,2.600468697842441279e-01,4.563496123041156649e-02,-1.000000008139237950e+00,0.000000000000000000e+00 +6.883126116043776221e+01,4.153227696909738711e+02,8.767900318685262206e-01,6.894580205421153352e+00,1.713382268219330318e-01,2.585963757868470214e-01,4.563496123041156649e-02,-1.000000008291501485e+00,0.000000000000000000e+00 +6.883271157506810312e+01,4.153326232657748847e+02,8.784950432000614429e-01,6.894955277387947667e+00,1.715048934885997078e-01,2.571459611444802396e-01,4.563496123041156649e-02,-1.000000007517696909e+00,0.000000000000000000e+00 +6.883416191079875546e+01,4.153424765562704692e+02,8.802016967703751860e-01,6.895328225363386743e+00,1.716715601552663839e-01,2.556956254029313369e-01,4.563496123041156649e-02,-1.000000008277991626e+00,0.000000000000000000e+00 +6.883561216808502081e+01,4.153523295621869806e+02,8.819099925320603717e-01,6.895699049807192615e+00,1.718382268219330600e-01,2.542453681046643044e-01,4.563496123041156649e-02,-1.000000007958239179e+00,0.000000000000000000e+00 +6.883706234738197338e+01,4.153621822832506609e+02,8.836199304376644026e-01,6.896067751176362393e+00,1.720048934885997360e-01,2.527951887961775168e-01,4.563496123041156649e-02,-1.000000008159342535e+00,0.000000000000000000e+00 +6.883851244914443157e+01,4.153720347191878659e+02,8.853315104396890511e-01,6.896434329925176243e+00,1.721715601552664121e-01,2.513450870218891797e-01,4.563496123041156649e-02,-1.000000007940802682e+00,0.000000000000000000e+00 +6.883996247382698641e+01,4.153818868697248945e+02,8.870447324905903486e-01,6.896798786505196510e+00,1.723382268219330882e-01,2.498950623278214378e-01,4.563496123041156649e-02,-1.000000008044056532e+00,0.000000000000000000e+00 +6.884141242188398735e+01,4.153917387345881025e+02,8.887595965427788069e-01,6.897161121365272152e+00,1.725048934885997642e-01,2.484451142591598827e-01,4.563496123041156649e-02,-1.000000007513547340e+00,0.000000000000000000e+00 +6.884286229376954225e+01,4.154015903135037888e+02,8.904761025486193082e-01,6.897521334951539629e+00,1.726715601552664403e-01,2.469952423627127247e-01,4.563496123041156649e-02,-1.000000008343521651e+00,0.000000000000000000e+00 +6.884431208993753160e+01,4.154114416061983093e+02,8.921942504604311042e-01,6.897879427707427347e+00,1.728382268219331164e-01,2.455454461826324097e-01,4.563496123041156649e-02,-1.000000007873075081e+00,0.000000000000000000e+00 +6.884576181084158009e+01,4.154212926123980196e+02,8.939140402304878164e-01,6.898235400073653878e+00,1.730048934885997924e-01,2.440957252671634159e-01,4.563496123041156649e-02,-1.000000008081886493e+00,0.000000000000000000e+00 +6.884721145693511346e+01,4.154311433318292757e+02,8.956354718110176583e-01,6.898589252488235957e+00,1.731715601552664685e-01,2.426460791619127755e-01,4.563496123041156649e-02,-1.000000007561369308e+00,0.000000000000000000e+00 +6.884866102867130166e+01,4.154409937642184900e+02,8.973585451542029912e-01,6.898940985386486702e+00,1.733382268219331446e-01,2.411965074147607302e-01,4.563496123041156649e-02,-1.000000008277058150e+00,0.000000000000000000e+00 +6.885011052650310148e+01,4.154508439092919616e+02,8.990832602121806572e-01,6.899290599201020946e+00,1.735048934885998206e-01,2.397470095709680615e-01,4.563496123041156649e-02,-1.000000007959908732e+00,0.000000000000000000e+00 +6.885155995088321390e+01,4.154606937667761599e+02,9.008096169370419792e-01,6.899638094361753460e+00,1.736715601552664967e-01,2.382975851793129041e-01,4.563496123041156649e-02,-1.000000007715209138e+00,0.000000000000000000e+00 +6.885300930226414096e+01,4.154705433363973839e+02,9.025376152808325392e-01,6.899983471295906057e+00,1.738382268219331728e-01,2.368482337871980203e-01,4.563496123041156649e-02,-1.000000007795515344e+00,0.000000000000000000e+00 +6.885445858109815731e+01,4.154803926178821030e+02,9.042672551955523996e-01,6.900326730428007593e+00,1.740048934885998488e-01,2.353989549418855076e-01,4.563496123041156649e-02,-1.000000008023376186e+00,0.000000000000000000e+00 +6.885590778783729604e+01,4.154902416109567298e+02,9.059985366331559931e-01,6.900667872179895745e+00,1.741715601552665249e-01,2.339497481911185783e-01,4.563496123041156649e-02,-1.000000008213861369e+00,0.000000000000000000e+00 +6.885735692293337706e+01,4.155000903153476202e+02,9.077314595455521218e-01,6.901006896970719673e+00,1.743382268219332010e-01,2.325006130831308859e-01,4.563496123041156649e-02,-1.000000007328523566e+00,0.000000000000000000e+00 +6.885880598683800713e+01,4.155099387307812435e+02,9.094660238846041800e-01,6.901343805216942684e+00,1.745048934885998770e-01,2.310515491678818145e-01,4.563496123041156649e-02,-1.000000008128573814e+00,0.000000000000000000e+00 +6.886025498000256562e+01,4.155197868569840693e+02,9.112022296021297096e-01,6.901678597332346676e+00,1.746715601552665531e-01,2.296025559915490510e-01,4.563496123041156649e-02,-1.000000007869110252e+00,0.000000000000000000e+00 +6.886170390287820453e+01,4.155296346936824534e+02,9.129400766499007336e-01,6.902011273728028584e+00,1.748382268219332292e-01,2.281536331045058430e-01,4.563496123041156649e-02,-1.000000008027932985e+00,0.000000000000000000e+00 +6.886315275591587692e+01,4.155394822406029220e+02,9.146795649796438665e-01,6.902341834812408372e+00,1.750048934885999052e-01,2.267047800552006998e-01,4.563496123041156649e-02,-1.000000007537121594e+00,0.000000000000000000e+00 +6.886460153956630847e+01,4.155493294974718879e+02,9.164206945430398710e-01,6.902670280991228147e+00,1.751715601552665813e-01,2.252559963938445542e-01,4.563496123041156649e-02,-1.000000007860397222e+00,0.000000000000000000e+00 +6.886605025428002591e+01,4.155591764640158203e+02,9.181634652917241013e-01,6.902996612667556597e+00,1.753382268219332574e-01,2.238072816687413924e-01,4.563496123041156649e-02,-1.000000007915264444e+00,0.000000000000000000e+00 +6.886749890050732859e+01,4.155690231399611889e+02,9.199078771772862817e-01,6.903320830241788109e+00,1.755048934885999334e-01,2.223586354299757761e-01,4.563496123041156649e-02,-1.000000007881493236e+00,0.000000000000000000e+00 +6.886894747869830269e+01,4.155788695250345199e+02,9.216539301512705062e-01,6.903642934111647200e+00,1.756715601552666095e-01,2.209100572275826124e-01,4.563496123041156649e-02,-1.000000007508194733e+00,0.000000000000000000e+00 +6.887039598930283546e+01,4.155887156189622260e+02,9.234016241651752388e-01,6.903962924672190304e+00,1.758382268219332856e-01,2.194615466121695724e-01,4.563496123041156649e-02,-1.000000008230760962e+00,0.000000000000000000e+00 +6.887184443277061519e+01,4.155985614214708903e+02,9.251509591704534241e-01,6.904280802315808430e+00,1.760048934885999616e-01,2.180131031324731017e-01,4.563496123041156649e-02,-1.000000007243894817e+00,0.000000000000000000e+00 +6.887329280955110278e+01,4.156084069322869823e+02,9.269019351185124878e-01,6.904596567432226273e+00,1.761715601552666377e-01,2.165647263414994805e-01,4.563496123041156649e-02,-1.000000008085547343e+00,0.000000000000000000e+00 +6.887474112009356020e+01,4.156182521511369714e+02,9.286545519607142252e-01,6.904910220408510213e+00,1.763382268219333138e-01,2.151164157873356464e-01,4.563496123041156649e-02,-1.000000007935746726e+00,0.000000000000000000e+00 +6.887618936484705046e+01,4.156280970777474408e+02,9.304088096483748016e-01,6.905221761629062982e+00,1.765048934885999898e-01,2.136681710223565234e-01,4.563496123041156649e-02,-1.000000007354370446e+00,0.000000000000000000e+00 +6.887763754426042340e+01,4.156379417118448600e+02,9.321647081327648632e-01,6.905531191475631658e+00,1.766715601552666659e-01,2.122199915983282170e-01,4.563496123041156649e-02,-1.000000007741329133e+00,0.000000000000000000e+00 +6.887908565878234413e+01,4.156477860531558122e+02,9.339222473651094258e-01,6.905838510327308555e+00,1.768382268219333420e-01,2.107718770651902662e-01,4.563496123041156649e-02,-1.000000007948620429e+00,0.000000000000000000e+00 +6.888053370886127880e+01,4.156576301014068235e+02,9.356814272965878754e-01,6.906143718560530331e+00,1.770048934886000180e-01,2.093238269747440816e-01,4.563496123041156649e-02,-1.000000007667718016e+00,0.000000000000000000e+00 +6.888198169494548040e+01,4.156674738563244773e+02,9.374422478783341894e-01,6.906446816549082435e+00,1.771715601552666941e-01,2.078758408794356694e-01,4.563496123041156649e-02,-1.000000007853881767e+00,0.000000000000000000e+00 +6.888342961748301718e+01,4.156773173176352998e+02,9.392047090614367155e-01,6.906747804664101764e+00,1.773382268219333702e-01,2.064279183305242626e-01,4.563496123041156649e-02,-1.000000007337164876e+00,0.000000000000000000e+00 +6.888487747692175844e+01,4.156871604850658741e+02,9.409688107969381710e-01,6.907046683274076671e+00,1.775048934886000462e-01,2.049800588811581392e-01,4.563496123041156649e-02,-1.000000007906172161e+00,0.000000000000000000e+00 +6.888632527370937453e+01,4.156970033583427835e+02,9.427345530358356429e-01,6.907343452744851398e+00,1.776715601552667223e-01,2.035322620820895212e-01,4.563496123041156649e-02,-1.000000007529175727e+00,0.000000000000000000e+00 +6.888777300829336525e+01,4.157068459371926110e+02,9.445019357290808104e-01,6.907638113439624306e+00,1.778382268219333984e-01,2.020845274872044295e-01,4.563496123041156649e-02,-1.000000007557032999e+00,0.000000000000000000e+00 +6.888922068112100305e+01,4.157166882213419967e+02,9.462709588275797223e-01,6.907930665718954089e+00,1.780048934886000744e-01,2.006368546486238802e-01,4.563496123041156649e-02,-1.000000008062523760e+00,0.000000000000000000e+00 +6.889066829263940406e+01,4.157265302105174669e+02,9.480416222821929084e-01,6.908221109940758886e+00,1.781715601552667505e-01,1.991892431185529611e-01,4.563496123041156649e-02,-1.000000007415867698e+00,0.000000000000000000e+00 +6.889211584329547122e+01,4.157363719044456616e+02,9.498139260437351572e-01,6.908509446460318060e+00,1.783382268219334266e-01,1.977416924517439722e-01,4.563496123041156649e-02,-1.000000007370856592e+00,0.000000000000000000e+00 +6.889356333353595119e+01,4.157462133028532207e+02,9.515878700629758491e-01,6.908795675630277522e+00,1.785048934886001026e-01,1.962942022005969289e-01,4.563496123041156649e-02,-1.000000007555349013e+00,0.000000000000000000e+00 +6.889501076380737743e+01,4.157560544054667844e+02,9.533634542906387344e-01,6.909079797800647960e+00,1.786715601552667787e-01,1.948467719182357116e-01,4.563496123041156649e-02,-1.000000008013849362e+00,0.000000000000000000e+00 +6.889645813455611290e+01,4.157658952120129356e+02,9.551406786774021551e-01,6.909361813318807499e+00,1.788382268219334548e-01,1.933994011579035222e-01,4.563496123041156649e-02,-1.000000007511802513e+00,0.000000000000000000e+00 +6.889790544622833579e+01,4.157757357222183714e+02,9.569195431738986013e-01,6.909641722529503483e+00,1.790048934886001308e-01,1.919520894748126816e-01,4.563496123041156649e-02,-1.000000007351567355e+00,0.000000000000000000e+00 +6.889935269927003958e+01,4.157855759358097316e+02,9.587000477307152657e-01,6.909919525774856908e+00,1.791715601552668069e-01,1.905048364224713742e-01,4.563496123041156649e-02,-1.000000007556737680e+00,0.000000000000000000e+00 +6.890079989412704720e+01,4.157954158525136563e+02,9.604821922983937110e-01,6.910195223394361541e+00,1.793382268219334830e-01,1.890576415545331679e-01,4.563496123041156649e-02,-1.000000007295582138e+00,0.000000000000000000e+00 +6.890224703124498262e+01,4.158052554720567855e+02,9.622659768274298697e-01,6.910468815724885694e+00,1.795048934886001590e-01,1.876105044260333865e-01,4.563496123041156649e-02,-1.000000007849963124e+00,0.000000000000000000e+00 +6.890369411106932773e+01,4.158150947941658728e+02,9.640514012682741551e-01,6.910740303100675774e+00,1.796715601552668351e-01,1.861634245903289742e-01,4.563496123041156649e-02,-1.000000007525921442e+00,0.000000000000000000e+00 +6.890514113404536545e+01,4.158249338185675583e+02,9.658384655713314615e-01,6.911009685853355400e+00,1.798382268219335112e-01,1.847164016034034684e-01,4.563496123041156649e-02,-1.000000007167122451e+00,0.000000000000000000e+00 +6.890658810061820816e+01,4.158347725449885388e+02,9.676271696869610528e-01,6.911276964311930726e+00,1.800048934886001872e-01,1.832694350201933553e-01,4.563496123041156649e-02,-1.000000008035001109e+00,0.000000000000000000e+00 +6.890803501123279773e+01,4.158446109731555111e+02,9.694175135654767850e-01,6.911542138802790447e+00,1.801715601552668633e-01,1.818225243939823876e-01,4.563496123041156649e-02,-1.000000006717242540e+00,0.000000000000000000e+00 +6.890948186633390549e+01,4.158544491027951722e+02,9.712094971571468838e-01,6.911805209649704906e+00,1.803382268219335394e-01,1.803756692831627040e-01,4.563496123041156649e-02,-1.000000007855472939e+00,0.000000000000000000e+00 +6.891092866636611802e+01,4.158642869336342756e+02,9.730031204121940558e-01,6.912066177173834980e+00,1.805048934886002154e-01,1.789288692395802349e-01,4.563496123041156649e-02,-1.000000007599121998e+00,0.000000000000000000e+00 +6.891237541177387982e+01,4.158741244653995182e+02,9.747983832807953775e-01,6.912325041693724081e+00,1.806715601552668915e-01,1.774821238208203755e-01,4.563496123041156649e-02,-1.000000007181742312e+00,0.000000000000000000e+00 +6.891382210300146482e+01,4.158839616978176537e+02,9.765952857130824061e-01,6.912581803525307933e+00,1.808382268219335676e-01,1.760354325828505928e-01,4.563496123041156649e-02,-1.000000007406126823e+00,0.000000000000000000e+00 +6.891526874049296225e+01,4.158937986306154357e+02,9.783938276591412908e-01,6.912836462981913677e+00,1.810048934886002436e-01,1.745887950806424560e-01,4.563496123041156649e-02,-1.000000007370748456e+00,0.000000000000000000e+00 +6.891671532469230499e+01,4.159036352635196181e+02,9.801940090690124396e-01,6.913089020374259874e+00,1.811715601552669197e-01,1.731422108706358598e-01,4.563496123041156649e-02,-1.000000007015651171e+00,0.000000000000000000e+00 +6.891816185604326961e+01,4.159134715962569544e+02,9.819958298926908524e-01,6.913339476010460061e+00,1.813382268219335958e-01,1.716956795095200827e-01,4.563496123041156649e-02,-1.000000007972210891e+00,0.000000000000000000e+00 +6.891960833498947636e+01,4.159233076285541983e+02,9.837992900801258989e-01,6.913587830196024520e+00,1.815048934886002718e-01,1.702492005517859119e-01,4.563496123041156649e-02,-1.000000006770838112e+00,0.000000000000000000e+00 +6.892105476197436076e+01,4.159331433601381036e+02,9.856043895812215405e-01,6.913834083233858507e+00,1.816715601552669479e-01,1.688027735571027699e-01,4.563496123041156649e-02,-1.000000007576337335e+00,0.000000000000000000e+00 +6.892250113744123041e+01,4.159429787907355376e+02,9.874111283458361088e-01,6.914078235424271135e+00,1.818382268219336240e-01,1.673563980792744099e-01,4.563496123041156649e-02,-1.000000007329739704e+00,0.000000000000000000e+00 +6.892394746183322241e+01,4.159528139200731971e+02,9.892195063237823049e-01,6.914320287064968262e+00,1.820048934886003000e-01,1.659100736766863093e-01,4.563496123041156649e-02,-1.000000006785934925e+00,0.000000000000000000e+00 +6.892539373559330329e+01,4.159626487478779495e+02,9.910295234648275331e-01,6.914560238451060492e+00,1.821715601552669761e-01,1.644637999067877776e-01,4.563496123041156649e-02,-1.000000007967290383e+00,0.000000000000000000e+00 +6.892683995916431172e+01,4.159724832738766054e+02,9.928411797186935672e-01,6.914798089875063170e+00,1.823382268219336522e-01,1.630175763242576736e-01,4.563496123041156649e-02,-1.000000006519506712e+00,0.000000000000000000e+00 +6.892828613298891582e+01,4.159823174977959184e+02,9.946544750350565511e-01,6.915033841626893718e+00,1.825048934886003282e-01,1.615714024902251966e-01,4.563496123041156649e-02,-1.000000007848716566e+00,0.000000000000000000e+00 +6.892973225750964161e+01,4.159921514193627559e+02,9.964694093635471095e-01,6.915267493993882297e+00,1.826715601552670043e-01,1.601252779581528451e-01,4.563496123041156649e-02,-1.000000006737301605e+00,0.000000000000000000e+00 +6.893117833316885879e+01,4.160019850383039852e+02,9.982859826537504588e-01,6.915499047260762033e+00,1.828382268219336804e-01,1.586792022891988507e-01,4.563496123041156649e-02,-1.000000007304180372e+00,0.000000000000000000e+00 +6.893262436040878072e+01,4.160118183543464170e+02,1.000104194855206297e+00,6.915728501709681453e+00,1.830048934886003564e-01,1.572331750387138960e-01,4.563496123041156649e-02,-1.000000006865989333e+00,0.000000000000000000e+00 +6.893407033967149289e+01,4.160216513672169185e+02,1.001924045917408579e+00,6.915955857620197378e+00,1.831715601552670325e-01,1.557871957660764972e-01,4.563496123041156649e-02,-1.000000007404823865e+00,0.000000000000000000e+00 +6.893551627139891025e+01,4.160314840766423572e+02,1.003745535789805965e+00,6.916181115269282031e+00,1.833382268219337086e-01,1.543412640279451797e-01,4.563496123041156649e-02,-1.000000007072993746e+00,0.000000000000000000e+00 +6.893696215603283406e+01,4.160413164823495435e+02,1.005568664421801595e+00,6.916404274931320373e+00,1.835048934886003846e-01,1.528953793837949104e-01,4.563496123041156649e-02,-1.000000006989611112e+00,0.000000000000000000e+00 +6.893840799401489505e+01,4.160511485840654018e+02,1.007393431762752867e+00,6.916625336878115426e+00,1.836715601552670607e-01,1.514495413916258637e-01,4.563496123041156649e-02,-1.000000006992608492e+00,0.000000000000000000e+00 +6.893985378578659606e+01,4.160609803815168561e+02,1.009219837761971883e+00,6.916844301378887394e+00,1.838382268219337368e-01,1.500037496098145795e-01,4.563496123041156649e-02,-1.000000007338179397e+00,0.000000000000000000e+00 +6.894129953178929782e+01,4.160708118744307171e+02,1.011047882368725226e+00,6.917061168700275431e+00,1.840048934886004128e-01,1.485580035965078649e-01,4.563496123041156649e-02,-1.000000006575856970e+00,0.000000000000000000e+00 +6.894274523246420472e+01,4.160806430625339658e+02,1.012877565532233737e+00,6.917275939106338534e+00,1.841715601552670889e-01,1.471123029120887937e-01,4.563496123041156649e-02,-1.000000007498052401e+00,0.000000000000000000e+00 +6.894419088825240749e+01,4.160904739455534695e+02,1.014708887201672960e+00,6.917488612858559982e+00,1.843382268219337650e-01,1.456666471130413365e-01,4.563496123041156649e-02,-1.000000006515918693e+00,0.000000000000000000e+00 +6.894563649959485474e+01,4.161003045232161526e+02,1.016541847326172920e+00,6.917699190215842897e+00,1.845048934886004410e-01,1.442210357611743154e-01,4.563496123041156649e-02,-1.000000007258621260e+00,0.000000000000000000e+00 +6.894708206693235297e+01,4.161101347952489391e+02,1.018376445854817902e+00,6.917907671434519123e+00,1.846715601552671171e-01,1.427754684131852803e-01,4.563496123041156649e-02,-1.000000006548589226e+00,0.000000000000000000e+00 +6.894852759070556658e+01,4.161199647613787533e+02,1.020212682736646892e+00,6.918114056768343012e+00,1.848382268219337932e-01,1.413299446304990825e-01,4.563496123041156649e-02,-1.000000007151922610e+00,0.000000000000000000e+00 +6.894997307135504627e+01,4.161297944213325763e+02,1.022050557920653358e+00,6.918318346468499414e+00,1.850048934886004692e-01,1.398844639706744997e-01,4.563496123041156649e-02,-1.000000006727402413e+00,0.000000000000000000e+00 +6.895141850932121486e+01,4.161396237748373323e+02,1.023890071355785025e+00,6.918520540783599237e+00,1.851715601552671453e-01,1.384390259947856638e-01,4.563496123041156649e-02,-1.000000006752788551e+00,0.000000000000000000e+00 +6.895286390504433882e+01,4.161494528216200024e+02,1.025731222990944547e+00,6.918720639959685670e+00,1.853382268219338214e-01,1.369936302619003676e-01,4.563496123041156649e-02,-1.000000006573660505e+00,0.000000000000000000e+00 +6.895430925896457097e+01,4.161592815614075676e+02,1.027574012774988610e+00,6.918918644240232396e+00,1.855048934886004974e-01,1.355482763321607109e-01,4.563496123041156649e-02,-1.000000007229572496e+00,0.000000000000000000e+00 +6.895575457152195042e+01,4.161691099939270089e+02,1.029418440656728828e+00,6.919114553866146267e+00,1.856715601552671735e-01,1.341029637643333106e-01,4.563496123041156649e-02,-1.000000006351995596e+00,0.000000000000000000e+00 +6.895719984315637419e+01,4.161789381189053074e+02,1.031264506584931073e+00,6.919308369075766407e+00,1.858382268219338496e-01,1.326576921207337223e-01,4.563496123041156649e-02,-1.000000007093153176e+00,0.000000000000000000e+00 +6.895864507430761137e+01,4.161887659360694443e+02,1.033112210508315476e+00,6.919500090104870438e+00,1.860048934886005256e-01,1.312124609592459357e-01,4.563496123041156649e-02,-1.000000006220574722e+00,0.000000000000000000e+00 +6.896009026541531739e+01,4.161985934451464004e+02,1.034961552375557092e+00,6.919689717186669142e+00,1.861715601552672017e-01,1.297672698425486326e-01,4.563496123041156649e-02,-1.000000006873525527e+00,0.000000000000000000e+00 +6.896153541691903399e+01,4.162084206458632138e+02,1.036812532135285458e+00,6.919877250551814463e+00,1.863382268219338778e-01,1.283221183289051937e-01,4.563496123041156649e-02,-1.000000006656513563e+00,0.000000000000000000e+00 +6.896298052925816080e+01,4.162182475379469224e+02,1.038665149736084148e+00,6.920062690428394170e+00,1.865048934886005538e-01,1.268770059801611894e-01,4.563496123041156649e-02,-1.000000006569384814e+00,0.000000000000000000e+00 +6.896442560287199797e+01,4.162280741211245640e+02,1.040519405126491881e+00,6.920246037041938081e+00,1.866715601552672299e-01,1.254319323568361400e-01,4.563496123041156649e-02,-1.000000006329603508e+00,0.000000000000000000e+00 +6.896587063819971775e+01,4.162379003951231766e+02,1.042375298255001415e+00,6.920427290615417171e+00,1.868382268219339060e-01,1.239868970199754089e-01,4.563496123041156649e-02,-1.000000006924051776e+00,0.000000000000000000e+00 +6.896731563568037870e+01,4.162477263596697981e+02,1.044232829070060209e+00,6.920606451369245349e+00,1.870048934886005820e-01,1.225418995293145047e-01,4.563496123041156649e-02,-1.000000005930071989e+00,0.000000000000000000e+00 +6.896876059575292572e+01,4.162575520144914663e+02,1.046091997520069983e+00,6.920783519521278571e+00,1.871715601552672581e-01,1.210969394482045297e-01,4.563496123041156649e-02,-1.000000006873717595e+00,0.000000000000000000e+00 +6.897020551885619000e+01,4.162673773593152760e+02,1.047952803553387380e+00,6.920958495286821055e+00,1.873382268219339342e-01,1.196520163350150434e-01,4.563496123041156649e-02,-1.000000006042716993e+00,0.000000000000000000e+00 +6.897165040542888903e+01,4.162772023938682651e+02,1.049815247118323303e+00,6.921131378878619067e+00,1.875048934886006102e-01,1.182071297535917942e-01,4.563496123041156649e-02,-1.000000006524793150e+00,0.000000000000000000e+00 +6.897309525590962664e+01,4.162870271178775283e+02,1.051679328163143357e+00,6.921302170506869800e+00,1.876715601552672863e-01,1.167622792634298579e-01,4.563496123041156649e-02,-1.000000006296014377e+00,0.000000000000000000e+00 +6.897454007073690718e+01,4.162968515310701605e+02,1.053545046636067184e+00,6.921470870379216045e+00,1.878382268219339624e-01,1.153174644270581334e-01,4.563496123041156649e-02,-1.000000006303886302e+00,0.000000000000000000e+00 +6.897598485034910709e+01,4.163066756331732563e+02,1.055412402485269574e+00,6.921637478700751522e+00,1.880048934886006384e-01,1.138726848057446395e-01,4.563496123041156649e-02,-1.000000006212995007e+00,0.000000000000000000e+00 +6.897742959518453176e+01,4.163164994239139673e+02,1.057281395658879353e+00,6.921801995674019992e+00,1.881715601552673145e-01,1.124279399613487967e-01,4.563496123041156649e-02,-1.000000006106889661e+00,0.000000000000000000e+00 +6.897887430568134448e+01,4.163263229030193884e+02,1.059152026104980049e+00,6.921964421499017028e+00,1.883382268219339906e-01,1.109832294557147603e-01,4.563496123041156649e-02,-1.000000006488055426e+00,0.000000000000000000e+00 +6.898031898227762326e+01,4.163361460702166141e+02,1.061024293771609894e+00,6.922124756373190912e+00,1.885048934886006666e-01,1.095385528500648631e-01,4.563496123041156649e-02,-1.000000005724674512e+00,0.000000000000000000e+00 +6.898176362541133244e+01,4.163459689252327962e+02,1.062898198606761158e+00,6.922283000491442628e+00,1.886715601552673427e-01,1.080939097080816508e-01,4.563496123041156649e-02,-1.000000006008439968e+00,0.000000000000000000e+00 +6.898320823552035108e+01,4.163557914677950862e+02,1.064773740558381254e+00,6.922439154046130305e+00,1.888382268219340188e-01,1.066492995903828428e-01,4.563496123041156649e-02,-1.000000006119987184e+00,0.000000000000000000e+00 +6.898465281304244456e+01,4.163656136976306357e+02,1.066650919574371414e+00,6.922593217227065665e+00,1.890048934886006948e-01,1.052047220594478222e-01,4.563496123041156649e-02,-1.000000006110116413e+00,0.000000000000000000e+00 +6.898609735841527879e+01,4.163754356144665962e+02,1.068529735602588016e+00,6.922745190221517575e+00,1.891715601552673709e-01,1.037601766777813267e-01,4.563496123041156649e-02,-1.000000006023030519e+00,0.000000000000000000e+00 +6.898754187207643440e+01,4.163852572180301195e+02,1.070410188590841694e+00,6.922895073214212935e+00,1.893382268219340470e-01,1.023156630079216506e-01,4.563496123041156649e-02,-1.000000005470829789e+00,0.000000000000000000e+00 +6.898898635446339256e+01,4.163950785080484138e+02,1.072292278486897787e+00,6.923042866387337568e+00,1.895048934886007230e-01,1.008711806130634797e-01,4.563496123041156649e-02,-1.000000006187410806e+00,0.000000000000000000e+00 +6.899043080601352074e+01,4.164048994842486309e+02,1.074176005238475895e+00,6.923188569920537994e+00,1.896715601552673991e-01,9.942672905399167760e-02,4.563496123041156649e-02,-1.000000005217731580e+00,0.000000000000000000e+00 +6.899187522716412957e+01,4.164147201463579790e+02,1.076061368793250095e+00,6.923332183990918764e+00,1.898382268219340752e-01,9.798230789585296585e-02,4.563496123041156649e-02,-1.000000006411300157e+00,0.000000000000000000e+00 +6.899331961835240179e+01,4.164245404941036668e+02,1.077948369098849390e+00,6.923473708773049573e+00,1.900048934886007512e-01,9.653791669832580136e-02,4.563496123041156649e-02,-1.000000005096905564e+00,0.000000000000000000e+00 +6.899476398001543487e+01,4.164343605272129594e+02,1.079837006102857044e+00,6.923613144438958145e+00,1.901715601552674273e-01,9.509355502792650461e-02,4.563496123041156649e-02,-1.000000005537059700e+00,0.000000000000000000e+00 +6.899620831259025522e+01,4.164441802454130084e+02,1.081727279752811022e+00,6.923750491158140896e+00,1.903382268219341034e-01,9.364922244510411053e-02,4.563496123041156649e-02,-1.000000005601803243e+00,0.000000000000000000e+00 +6.899765261651378978e+01,4.164539996484310791e+02,1.083619189996203547e+00,6.923885749097554942e+00,1.905048934886007794e-01,9.220491851347220602e-02,4.563496123041156649e-02,-1.000000005709085205e+00,0.000000000000000000e+00 +6.899909689222289444e+01,4.164638187359943799e+02,1.085512736780481768e+00,6.924018918421623425e+00,1.906715601552674555e-01,9.076064279612747199e-02,4.563496123041156649e-02,-1.000000005418853810e+00,0.000000000000000000e+00 +6.900054114015431139e+01,4.164736375078301762e+02,1.087407920053046873e+00,6.924149999292235513e+00,1.908382268219341316e-01,8.931639485688756819e-02,4.563496123041156649e-02,-1.000000005136144621e+00,0.000000000000000000e+00 +6.900198536074471178e+01,4.164834559636657332e+02,1.089304739761255192e+00,6.924278991868748179e+00,1.910048934886008076e-01,8.787217425906926338e-02,4.563496123041156649e-02,-1.000000005259551683e+00,0.000000000000000000e+00 +6.900342955443069570e+01,4.164932741032283161e+02,1.091203195852417096e+00,6.924405896307986197e+00,1.911715601552674837e-01,8.642798056549645669e-02,4.563496123041156649e-02,-1.000000004903741413e+00,0.000000000000000000e+00 +6.900487372164876376e+01,4.165030919262451903e+02,1.093103288273797657e+00,6.924530712764242146e+00,1.913382268219341598e-01,8.498381334035309820e-02,4.563496123041156649e-02,-1.000000005306125539e+00,0.000000000000000000e+00 +6.900631786283533131e+01,4.165129094324436210e+02,1.095005016972616652e+00,6.924653441389279074e+00,1.915048934886008358e-01,8.353967214611622560e-02,4.563496123041156649e-02,-1.000000005142472670e+00,0.000000000000000000e+00 +6.900776197842677107e+01,4.165227266215509303e+02,1.096908381896048335e+00,6.924774082332328717e+00,1.916715601552675119e-01,8.209555654725407547e-02,4.563496123041156649e-02,-1.000000004785560392e+00,0.000000000000000000e+00 +6.900920606885934205e+01,4.165325434932943836e+02,1.098813382991221221e+00,6.924892635740095059e+00,1.918382268219341880e-01,8.065146610777398917e-02,4.563496123041156649e-02,-1.000000005027655181e+00,0.000000000000000000e+00 +6.901065013456924646e+01,4.165423600474013028e+02,1.100720020205218752e+00,6.925009101756754326e+00,1.920048934886008640e-01,7.920740039061535676e-02,4.563496123041156649e-02,-1.000000004525061659e+00,0.000000000000000000e+00 +6.901209417599260121e+01,4.165521762835990103e+02,1.102628293485078848e+00,6.925123480523954100e+00,1.921715601552675401e-01,7.776335896073278964e-02,4.563496123041156649e-02,-1.000000004909019191e+00,0.000000000000000000e+00 +6.901353819356545216e+01,4.165619922016148280e+02,1.104538202777793909e+00,6.925235772180816873e+00,1.923382268219342162e-01,7.631934138079880803e-02,4.563496123041156649e-02,-1.000000004396913722e+00,0.000000000000000000e+00 +6.901498218772377413e+01,4.165718078011761349e+02,1.106449748030310820e+00,6.925345976863937381e+00,1.925048934886008922e-01,7.487534721613225974e-02,4.563496123041156649e-02,-1.000000004607244142e+00,0.000000000000000000e+00 +6.901642615890347088e+01,4.165816230820101964e+02,1.108362929189531165e+00,6.925454094707387043e+00,1.926715601552675683e-01,7.343137602978572209e-02,4.563496123041156649e-02,-1.000000004170358947e+00,0.000000000000000000e+00 +6.901787010754037510e+01,4.165914380438444482e+02,1.110277746202311011e+00,6.925560125842711301e+00,1.928382268219342444e-01,7.198742738685906528e-02,4.563496123041156649e-02,-1.000000004692024991e+00,0.000000000000000000e+00 +6.901931403407026266e+01,4.166012526864062124e+02,1.112194199015460905e+00,6.925664070398933170e+00,1.930048934886009204e-01,7.054350085020172356e-02,4.563496123041156649e-02,-1.000000003937635995e+00,0.000000000000000000e+00 +6.902075793892882416e+01,4.166110670094228681e+02,1.114112287575746096e+00,6.925765928502550572e+00,1.931715601552675965e-01,6.909959598595664942e-02,4.563496123041156649e-02,-1.000000003926182712e+00,0.000000000000000000e+00 +6.902220182255169334e+01,4.166208810126217941e+02,1.116032011829886317e+00,6.925865700277541670e+00,1.933382268219342726e-01,6.765571235741710265e-02,4.563496123041156649e-02,-1.000000004114224295e+00,0.000000000000000000e+00 +6.902364568537444711e+01,4.166306946957303694e+02,1.117953371724556000e+00,6.925963385845361309e+00,1.935048934886009486e-01,6.621184952872530283e-02,4.563496123041156649e-02,-1.000000003525829406e+00,0.000000000000000000e+00 +6.902508952783259133e+01,4.166405080584759730e+02,1.119876367206384060e+00,6.926058985324942796e+00,1.936715601552676247e-01,6.476800706549551423e-02,4.563496123041156649e-02,-1.000000004160922717e+00,0.000000000000000000e+00 +6.902653335036156079e+01,4.166503211005860408e+02,1.121800998221953893e+00,6.926152498832700566e+00,1.938382268219343008e-01,6.332418453051603946e-02,4.563496123041156649e-02,-1.000000003326487974e+00,0.000000000000000000e+00 +6.902797715339674767e+01,4.166601338217879515e+02,1.123727264717803376e+00,6.926243926482526625e+00,1.940048934886009768e-01,6.188038149052374481e-02,4.563496123041156649e-02,-1.000000003009705152e+00,0.000000000000000000e+00 +6.902942093737348728e+01,4.166699462218091981e+02,1.125655166640425309e+00,6.926333268385796771e+00,1.941715601552676529e-01,6.043659750944534170e-02,4.563496123041156649e-02,-1.000000003913322999e+00,0.000000000000000000e+00 +6.903086470272702968e+01,4.166797583003771592e+02,1.127584703936266752e+00,6.926420524651367039e+00,1.943382268219343290e-01,5.899283215025064031e-02,4.563496123041156649e-02,-1.000000002472641647e+00,0.000000000000000000e+00 +6.903230844989259651e+01,4.166895700572193277e+02,1.129515876551729470e+00,6.926505695385572814e+00,1.945048934886010050e-01,5.754908498111240001e-02,4.563496123041156649e-02,-1.000000003212486055e+00,0.000000000000000000e+00 +6.903375217930533836e+01,4.166993814920630825e+02,1.131448684433169927e+00,6.926588780692236824e+00,1.946715601552676811e-01,5.610535556372567290e-02,4.563496123041156649e-02,-1.000000002981415337e+00,0.000000000000000000e+00 +6.903519589140037738e+01,4.167091926046359163e+02,1.133383127526898848e+00,6.926669780672660259e+00,1.948382268219343572e-01,5.466164346438912719e-02,4.563496123041156649e-02,-1.000000002456524317e+00,0.000000000000000000e+00 +6.903663958661275046e+01,4.167190033946653216e+02,1.135319205779181662e+00,6.926748695425629876e+00,1.950048934886010332e-01,5.321794824847627531e-02,4.563496123041156649e-02,-1.000000002308603753e+00,0.000000000000000000e+00 +6.903808326537745188e+01,4.167288138618787343e+02,1.137256919136238498e+00,6.926825525047417109e+00,1.951715601552677093e-01,5.177426948044330790e-02,4.563496123041156649e-02,-1.000000001923661674e+00,0.000000000000000000e+00 +6.903952692812943326e+01,4.167386240060037039e+02,1.139196267544243968e+00,6.926900269631777185e+00,1.953382268219343854e-01,5.033060672568261812e-02,4.563496123041156649e-02,-1.000000002385910580e+00,0.000000000000000000e+00 +6.904097057530360360e+01,4.167484338267676662e+02,1.141137250949327386e+00,6.926972929269950896e+00,1.955048934886010614e-01,4.888695954806984018e-02,4.563496123041156649e-02,-1.000000001363894331e+00,0.000000000000000000e+00 +6.904241420733481505e+01,4.167582433238981707e+02,1.143079869297572548e+00,6.927043504050662825e+00,1.956715601552677375e-01,4.744332751489357264e-02,4.563496123041156649e-02,-1.000000001633785551e+00,0.000000000000000000e+00 +6.904385782465786292e+01,4.167680524971227101e+02,1.145024122535017730e+00,6.927111994060126676e+00,1.958382268219344136e-01,4.599971018948046525e-02,4.563496123041156649e-02,-1.000000001277512762e+00,0.000000000000000000e+00 +6.904530142770752832e+01,4.167778613461687769e+02,1.146970010607655910e+00,6.927178399382039942e+00,1.960048934886010896e-01,4.455610713797069494e-02,4.563496123041156649e-02,-1.000000000501453989e+00,0.000000000000000000e+00 +6.904674501691852129e+01,4.167876698707639207e+02,1.148917533461434548e+00,6.927242720097588347e+00,1.961715601552677657e-01,4.311251792624971185e-02,4.563496123041156649e-02,-1.000000001210501477e+00,0.000000000000000000e+00 +6.904818859272552345e+01,4.167974780706356910e+02,1.150866691042255807e+00,6.927304956285445847e+00,1.963382268219344418e-01,4.166894211749500726e-02,4.563496123041156649e-02,-1.000000000188720595e+00,0.000000000000000000e+00 +6.904963215556317380e+01,4.168072859455116941e+02,1.152817483295976553e+00,6.927365108021771078e+00,1.965048934886011178e-01,4.022537927956713888e-02,4.563496123041156649e-02,-9.999999997544676278e-01,0.000000000000000000e+00 +6.905107570586608290e+01,4.168170934951194226e+02,1.154769910168408131e+00,6.927423175380214460e+00,1.966715601552677939e-01,3.878182897701922677e-02,4.563496123041156649e-02,-9.999999996625410503e-01,0.000000000000000000e+00 +6.905251924406879027e+01,4.168269007191864262e+02,1.156723971605316370e+00,6.927479158431913753e+00,1.968382268219344700e-01,3.733829077479635522e-02,4.563496123041156649e-02,-9.999999992351238376e-01,0.000000000000000000e+00 +6.905396277060583543e+01,4.168367076174403110e+02,1.158679667552421799e+00,6.927533057245494952e+00,1.970048934886011460e-01,3.589476423885874096e-02,4.563496123041156649e-02,-9.999999986404779495e-01,0.000000000000000000e+00 +6.905540628591170105e+01,4.168465141896086834e+02,1.160636997955399430e+00,6.927584871887074058e+00,1.971715601552678221e-01,3.445124893495906532e-02,4.563496123041156649e-02,-9.999999984667856667e-01,0.000000000000000000e+00 +6.905684979042084137e+01,4.168563204354191498e+02,1.162595962759879198e+00,6.927634602420257082e+00,1.973382268219344982e-01,3.300774442803501574e-02,4.563496123041156649e-02,-9.999999975908608896e-01,0.000000000000000000e+00 +6.905829328456768224e+01,4.168661263545992597e+02,1.164556561911445298e+00,6.927682248906139151e+00,1.975048934886011742e-01,3.156425028467835237e-02,4.563496123041156649e-02,-9.999999974406996728e-01,0.000000000000000000e+00 +6.905973676878660683e+01,4.168759319468766762e+02,1.166518795355636628e+00,6.927727811403307179e+00,1.976715601552678503e-01,3.012076606945096255e-02,4.563496123041156649e-02,-9.999999964541455011e-01,0.000000000000000000e+00 +6.906118024351196993e+01,4.168857372119789488e+02,1.168482663037946789e+00,6.927771289967837198e+00,1.978382268219345264e-01,2.867729134919981895e-02,4.563496123041156649e-02,-9.999999960465231208e-01,0.000000000000000000e+00 +6.906262370917811211e+01,4.168955421496337976e+02,1.170448164903823640e+00,6.927812684653297914e+00,1.980048934886012024e-01,2.723382568875772070e-02,4.563496123041156649e-02,-9.999999954954930104e-01,0.000000000000000000e+00 +6.906406716621934549e+01,4.169053467595688289e+02,1.172415300898670187e+00,6.927851995510748040e+00,1.981715601552678785e-01,2.579036865402766290e-02,4.563496123041156649e-02,-9.999999936460445271e-01,0.000000000000000000e+00 +6.906551061506993960e+01,4.169151510415116491e+02,1.174384070967843696e+00,6.927889222588738072e+00,1.983382268219345546e-01,2.434691981260604307e-02,4.563496123041156649e-02,-9.999999935996611855e-01,0.000000000000000000e+00 +6.906695405616414973e+01,4.169249549951899780e+02,1.176354475056656135e+00,6.927924365933312956e+00,1.985048934886012306e-01,2.290347872763731987e-02,4.563496123041156649e-02,-9.999999924835433207e-01,0.000000000000000000e+00 +6.906839748993620276e+01,4.169347586203314791e+02,1.178326513110373952e+00,6.927957425588005869e+00,1.986715601552679067e-01,2.146004496643628273e-02,4.563496123041156649e-02,-9.999999908287648953e-01,0.000000000000000000e+00 +6.906984091682029714e+01,4.169445619166638153e+02,1.180300185074218300e+00,6.927988401593844436e+00,1.988382268219345828e-01,2.001661809557341715e-02,4.563496123041156649e-02,-9.999999900127093388e-01,0.000000000000000000e+00 +6.907128433725063132e+01,4.169543648839146499e+02,1.182275490893365033e+00,6.928017293989349845e+00,1.990048934886012588e-01,1.857319767965203566e-02,4.563496123041156649e-02,-9.999999875697388463e-01,0.000000000000000000e+00 +6.907272775166137535e+01,4.169641675218117030e+02,1.184252430512944487e+00,6.928044102810534177e+00,1.991715601552679349e-01,1.712978328685407781e-02,4.563496123041156649e-02,-9.999999861434722970e-01,0.000000000000000000e+00 +6.907417116048667083e+01,4.169739698300826376e+02,1.186231003878041923e+00,6.928068828090905740e+00,1.993382268219346110e-01,1.568637448156399994e-02,4.563496123041156649e-02,-9.999999832555659385e-01,0.000000000000000000e+00 +6.907561456416064516e+01,4.169837718084552307e+02,1.188211210933696638e+00,6.928091469861463736e+00,1.995048934886012870e-01,1.424297083176058812e-02,4.563496123041156649e-02,-9.999999811106931036e-01,0.000000000000000000e+00 +6.907705796311741153e+01,4.169935734566572023e+02,1.190193051624903076e+00,6.928112028150703594e+00,1.996715601552679631e-01,1.279957190225614050e-02,4.563496123041156649e-02,-9.999999767914981019e-01,0.000000000000000000e+00 +6.907850135779108314e+01,4.170033747744162156e+02,1.192176525896609940e+00,6.928130502984612527e+00,1.998382268219346392e-01,1.135617726208831314e-02,4.563496123041156649e-02,-9.999999729163294715e-01,0.000000000000000000e+00 +6.907994474861573053e+01,4.170131757614600474e+02,1.194161633693720859e+00,6.928146894386675747e+00,2.000048934886013152e-01,9.912786476528582039e-03,4.563496123041156649e-02,-9.999999661288008213e-01,0.000000000000000000e+00 +6.908138813602543848e+01,4.170229764175164746e+02,1.196148374961093941e+00,6.928161202377871142e+00,2.001715601552679913e-01,8.469399115704837055e-03,4.563496123041156649e-02,-9.999999573293465449e-01,0.000000000000000000e+00 +6.908283152045427755e+01,4.170327767423132173e+02,1.198136749643541998e+00,6.928173426976676375e+00,2.003382268219346674e-01,7.026014748455806577e-03,4.563496123041156649e-02,-9.999999448541642133e-01,0.000000000000000000e+00 +6.908427490233630408e+01,4.170425767355781090e+02,1.200126757685832324e+00,6.928183568199067111e+00,2.005048934886013434e-01,5.582632946030942518e-03,4.563496123041156649e-02,-9.999999231961997914e-01,0.000000000000000000e+00 +6.908571828210556021e+01,4.170523763970388700e+02,1.202118399032686913e+00,6.928191626058520569e+00,2.006715601552680195e-01,4.139253287636378981e-03,4.563496123041156649e-02,-9.999998795945195251e-01,0.000000000000000000e+00 +6.908716166019608806e+01,4.170621757264232770e+02,1.204111673628782242e+00,6.928197600566027070e+00,2.008382268219346956e-01,2.695875370903691795e-03,4.563496123041156649e-02,-9.999997496964945221e-01,0.000000000000000000e+00 +6.908860503704191558e+01,4.170719747234591637e+02,1.206106581418749712e+00,6.928201491730116679e+00,2.010048934886013716e-01,1.252498886354816475e-03,4.563496123041156649e-02,-8.678430106467154292e-01,0.000000000000000000e+00 +6.909004841307708489e+01,4.170817733878743070e+02,1.208103122347175207e+00,6.928203299556993322e+00,2.011715601552680477e-01,-1.249175034008203889e-07,4.563496123041156649e-02,8.654325429514871462e-05,0.000000000000000000e+00 +6.909149178873562391e+01,4.170915717193965406e+02,1.210101296358599310e+00,6.928203299376690438e+00,2.013382268219347238e-01,-3.076740328900791373e-12,4.563496123041156649e-02,2.131628249801578676e-09,0.000000000000000000e+00 +6.909293516439420557e+01,4.171013697177536983e+02,1.212101103397517088e+00,6.928203299376685997e+00,2.015048934886013998e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.909437854005278723e+01,4.171111673826736137e+02,1.214102543408378532e+00,6.928203299376685997e+00,2.016715601552680759e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.909582191571136889e+01,4.171209647138841206e+02,1.216105616335587891e+00,6.928203299376685997e+00,2.018382268219347520e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.909726529136995055e+01,4.171307617111130526e+02,1.218110322123504341e+00,6.928203299376685997e+00,2.020048934886014280e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.909870866702853220e+01,4.171405583740883003e+02,1.220116660716441537e+00,6.928203299376685997e+00,2.021715601552681041e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910015204268711386e+01,4.171503547025376974e+02,1.222124632058667837e+00,6.928203299376685997e+00,2.023382268219347802e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910159541834569552e+01,4.171601506961891346e+02,1.224134236094406303e+00,6.928203299376685997e+00,2.025048934886014562e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910303879400427718e+01,4.171699463547705591e+02,1.226145472767834699e+00,6.928203299376685997e+00,2.026715601552681323e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910448216966285884e+01,4.171797416780098047e+02,1.228158342023085270e+00,6.928203299376685997e+00,2.028382268219348084e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910592554532144050e+01,4.171895366656348187e+02,1.230172843804244964e+00,6.928203299376685997e+00,2.030048934886014844e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910736892098002215e+01,4.171993313173734919e+02,1.232188978055355433e+00,6.928203299376685997e+00,2.031715601552681605e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.910881229663860381e+01,4.172091256329537146e+02,1.234206744720413029e+00,6.928203299376685997e+00,2.033382268219348366e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911025567229718547e+01,4.172189196121034911e+02,1.236226143743368366e+00,6.928203299376685997e+00,2.035048934886015126e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911169904795576713e+01,4.172287132545507120e+02,1.238247175068127426e+00,6.928203299376685997e+00,2.036715601552681887e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911314242361434879e+01,4.172385065600233816e+02,1.240269838638550226e+00,6.928203299376685997e+00,2.038382268219348648e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911458579927293044e+01,4.172482995282494471e+02,1.242294134398451710e+00,6.928203299376685997e+00,2.040048934886015408e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911602917493151210e+01,4.172580921589568561e+02,1.244320062291601303e+00,6.928203299376685997e+00,2.041715601552682169e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911747255059009376e+01,4.172678844518736128e+02,1.246347622261723354e+00,6.928203299376685997e+00,2.043382268219348930e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.911891592624867542e+01,4.172776764067277213e+02,1.248376814252496692e+00,6.928203299376685997e+00,2.045048934886015690e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912035930190725708e+01,4.172874680232471292e+02,1.250407638207555072e+00,6.928203299376685997e+00,2.046715601552682451e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912180267756583874e+01,4.172972593011598974e+02,1.252440094070486509e+00,6.928203299376685997e+00,2.048382268219349212e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912324605322442039e+01,4.173070502401940303e+02,1.254474181784833942e+00,6.928203299376685997e+00,2.050048934886015972e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912468942888300205e+01,4.173168408400775888e+02,1.256509901294095011e+00,6.928203299376685997e+00,2.051715601552682733e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912613280454158371e+01,4.173266311005385774e+02,1.258547252541721839e+00,6.928203299376685997e+00,2.053382268219349494e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912757618020016537e+01,4.173364210213050569e+02,1.260586235471121475e+00,6.928203299376685997e+00,2.055048934886016254e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.912901955585874703e+01,4.173462106021050886e+02,1.262626850025655445e+00,6.928203299376685997e+00,2.056715601552683015e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913046293151732868e+01,4.173559998426666766e+02,1.264669096148639982e+00,6.928203299376685997e+00,2.058382268219349776e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913190630717591034e+01,4.173657887427179958e+02,1.266712973783346019e+00,6.928203299376685997e+00,2.060048934886016536e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913334968283449200e+01,4.173755773019870503e+02,1.268758482872999194e+00,6.928203299376685997e+00,2.061715601552683297e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913479305849307366e+01,4.173853655202020150e+02,1.270805623360779846e+00,6.928203299376685997e+00,2.063382268219350058e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913623643415165532e+01,4.173951533970909509e+02,1.272854395189823018e+00,6.928203299376685997e+00,2.065048934886016818e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913767980981023697e+01,4.174049409323819759e+02,1.274904798303218234e+00,6.928203299376685997e+00,2.066715601552683579e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.913912318546881863e+01,4.174147281258032081e+02,1.276956832644009943e+00,6.928203299376685997e+00,2.068382268219350339e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914056656112740029e+01,4.174245149770827652e+02,1.279010498155197073e+00,6.928203299376685997e+00,2.070048934886017100e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914200993678598195e+01,4.174343014859488221e+02,1.281065794779733480e+00,6.928203299376685997e+00,2.071715601552683861e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914345331244456361e+01,4.174440876521294967e+02,1.283122722460527498e+00,6.928203299376685997e+00,2.073382268219350621e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914489668810314527e+01,4.174538734753529639e+02,1.285181281140442389e+00,6.928203299376685997e+00,2.075048934886017382e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914634006376172692e+01,4.174636589553473982e+02,1.287241470762295892e+00,6.928203299376685997e+00,2.076715601552684143e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914778343942030858e+01,4.174734440918410314e+02,1.289303291268860452e+00,6.928203299376685997e+00,2.078382268219350903e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.914922681507889024e+01,4.174832288845619814e+02,1.291366742602863438e+00,6.928203299376685997e+00,2.080048934886017664e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915067019073747190e+01,4.174930133332384798e+02,1.293431824706986477e+00,6.928203299376685997e+00,2.081715601552684425e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915211356639605356e+01,4.175027974375987583e+02,1.295498537523866345e+00,6.928203299376685997e+00,2.083382268219351185e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915355694205463521e+01,4.175125811973709915e+02,1.297566880996094518e+00,6.928203299376685997e+00,2.085048934886017946e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915500031771321687e+01,4.175223646122834111e+02,1.299636855066216734e+00,6.928203299376685997e+00,2.086715601552684707e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915644369337179853e+01,4.175321476820643056e+02,1.301708459676733876e+00,6.928203299376685997e+00,2.088382268219351467e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915788706903038019e+01,4.175419304064419066e+02,1.303781694770101307e+00,6.928203299376685997e+00,2.090048934886018228e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.915933044468896185e+01,4.175517127851444457e+02,1.305856560288729318e+00,6.928203299376685997e+00,2.091715601552684989e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916077382034754351e+01,4.175614948179002113e+02,1.307933056174982456e+00,6.928203299376685997e+00,2.093382268219351749e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916221719600612516e+01,4.175712765044374351e+02,1.310011182371180416e+00,6.928203299376685997e+00,2.095048934886018510e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916366057166470682e+01,4.175810578444844623e+02,1.312090938819597596e+00,6.928203299376685997e+00,2.096715601552685271e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916510394732328848e+01,4.175908388377695246e+02,1.314172325462462876e+00,6.928203299376685997e+00,2.098382268219352031e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916654732298187014e+01,4.176006194840209673e+02,1.316255342241960058e+00,6.928203299376685997e+00,2.100048934886018792e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916799069864045180e+01,4.176103997829671357e+02,1.318339989100227427e+00,6.928203299376685997e+00,2.101715601552685553e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.916943407429903345e+01,4.176201797343363182e+02,1.320426265979358194e+00,6.928203299376685997e+00,2.103382268219352313e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917087744995761511e+01,4.176299593378568602e+02,1.322514172821400269e+00,6.928203299376685997e+00,2.105048934886019074e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917232082561619677e+01,4.176397385932571069e+02,1.324603709568356047e+00,6.928203299376685997e+00,2.106715601552685835e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917376420127477843e+01,4.176495175002654037e+02,1.326694876162183068e+00,6.928203299376685997e+00,2.108382268219352595e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917520757693336009e+01,4.176592960586100958e+02,1.328787672544793352e+00,6.928203299376685997e+00,2.110048934886019356e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917665095259194175e+01,4.176690742680195854e+02,1.330882098658053403e+00,6.928203299376685997e+00,2.111715601552686117e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917809432825052340e+01,4.176788521282222746e+02,1.332978154443785090e+00,6.928203299376685997e+00,2.113382268219352877e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.917953770390910506e+01,4.176886296389465087e+02,1.335075839843764323e+00,6.928203299376685997e+00,2.115048934886019638e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918098107956768672e+01,4.176984067999207468e+02,1.337175154799722154e+00,6.928203299376685997e+00,2.116715601552686399e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918242445522626838e+01,4.177081836108733341e+02,1.339276099253344343e+00,6.928203299376685997e+00,2.118382268219353159e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918386783088485004e+01,4.177179600715327297e+02,1.341378673146271350e+00,6.928203299376685997e+00,2.120048934886019920e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918531120654343169e+01,4.177277361816273924e+02,1.343482876420098338e+00,6.928203299376685997e+00,2.121715601552686681e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918675458220201335e+01,4.177375119408857245e+02,1.345588709016375173e+00,6.928203299376685997e+00,2.123382268219353441e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918819795786059501e+01,4.177472873490361849e+02,1.347696170876606425e+00,6.928203299376685997e+00,2.125048934886020202e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.918964133351917667e+01,4.177570624058072326e+02,1.349805261942251589e+00,6.928203299376685997e+00,2.126715601552686963e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919108470917775833e+01,4.177668371109273266e+02,1.351915982154724860e+00,6.928203299376685997e+00,2.128382268219353723e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919252808483633999e+01,4.177766114641249260e+02,1.354028331455394918e+00,6.928203299376685997e+00,2.130048934886020484e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919397146049492164e+01,4.177863854651286033e+02,1.356142309785585587e+00,6.928203299376685997e+00,2.131715601552687245e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919541483615350330e+01,4.177961591136668176e+02,1.358257917086575173e+00,6.928203299376685997e+00,2.133382268219354005e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919685821181208496e+01,4.178059324094680278e+02,1.360375153299596906e+00,6.928203299376685997e+00,2.135048934886020766e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919830158747066662e+01,4.178157053522608066e+02,1.362494018365838500e+00,6.928203299376685997e+00,2.136715601552687527e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.919974496312924828e+01,4.178254779417736700e+02,1.364614512226442811e+00,6.928203299376685997e+00,2.138382268219354287e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920118833878782993e+01,4.178352501777351904e+02,1.366736634822506957e+00,6.928203299376685997e+00,2.140048934886021048e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920263171444641159e+01,4.178450220598738838e+02,1.368860386095083204e+00,6.928203299376685997e+00,2.141715601552687809e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920407509010499325e+01,4.178547935879183228e+02,1.370985765985178517e+00,6.928203299376685997e+00,2.143382268219354569e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920551846576357491e+01,4.178645647615970233e+02,1.373112774433754568e+00,6.928203299376685997e+00,2.145048934886021330e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920696184142215657e+01,4.178743355806386148e+02,1.375241411381727730e+00,6.928203299376685997e+00,2.146715601552688091e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920840521708073823e+01,4.178841060447716700e+02,1.377371676769969300e+00,6.928203299376685997e+00,2.148382268219354851e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.920984859273931988e+01,4.178938761537248183e+02,1.379503570539305057e+00,6.928203299376685997e+00,2.150048934886021612e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921129196839790154e+01,4.179036459072266325e+02,1.381637092630515928e+00,6.928203299376685997e+00,2.151715601552688373e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921273534405648320e+01,4.179134153050057421e+02,1.383772242984337320e+00,6.928203299376685997e+00,2.153382268219355133e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921417871971506486e+01,4.179231843467907765e+02,1.385909021541459341e+00,6.928203299376685997e+00,2.155048934886021894e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921562209537364652e+01,4.179329530323103654e+02,1.388047428242527248e+00,6.928203299376685997e+00,2.156715601552688655e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921706547103222817e+01,4.179427213612931951e+02,1.390187463028140780e+00,6.928203299376685997e+00,2.158382268219355415e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921850884669080983e+01,4.179524893334678950e+02,1.392329125838854598e+00,6.928203299376685997e+00,2.160048934886022176e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.921995222234939149e+01,4.179622569485630947e+02,1.394472416615177846e+00,6.928203299376685997e+00,2.161715601552688937e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.922139559800797315e+01,4.179720242063075375e+02,1.396617335297575035e+00,6.928203299376685997e+00,2.163382268219355697e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.922283897366655481e+01,4.179817911064298528e+02,1.398763881826464717e+00,6.928203299376685997e+00,2.165048934886022458e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.922428234932513647e+01,4.179915576486587838e+02,1.400912056142220807e+00,6.928203299376685997e+00,2.166715601552689219e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.922572572498371812e+01,4.180013238327230169e+02,1.403061858185171706e+00,6.928203299376685997e+00,2.168382268219355979e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.922716910064229978e+01,4.180110896583512385e+02,1.405213287895600738e+00,6.928203299376685997e+00,2.170048934886022740e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.922861247630088144e+01,4.180208551252721918e+02,1.407366345213746150e+00,6.928203299376685997e+00,2.171715601552689501e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923005585195946310e+01,4.180306202332146768e+02,1.409521030079800452e+00,6.928203299376685997e+00,2.173382268219356261e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923149922761804476e+01,4.180403849819073798e+02,1.411677342433911519e+00,6.928203299376685997e+00,2.175048934886023022e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923294260327662641e+01,4.180501493710790442e+02,1.413835282216181710e+00,6.928203299376685997e+00,2.176715601552689783e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923438597893520807e+01,4.180599134004584698e+02,1.415994849366668307e+00,6.928203299376685997e+00,2.178382268219356543e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923582935459378973e+01,4.180696770697744569e+02,1.418156043825383295e+00,6.928203299376685997e+00,2.180048934886023304e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923727273025237139e+01,4.180794403787557485e+02,1.420318865532293362e+00,6.928203299376685997e+00,2.181715601552690065e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.923871610591095305e+01,4.180892033271311448e+02,1.422483314427320344e+00,6.928203299376685997e+00,2.183382268219356825e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924015948156953471e+01,4.180989659146294457e+02,1.424649390450340558e+00,6.928203299376685997e+00,2.185048934886023586e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924160285722811636e+01,4.181087281409795082e+02,1.426817093541185244e+00,6.928203299376685997e+00,2.186715601552690347e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924304623288669802e+01,4.181184900059101324e+02,1.428986423639640346e+00,6.928203299376685997e+00,2.188382268219357107e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924448960854527968e+01,4.181282515091501750e+02,1.431157380685446956e+00,6.928203299376685997e+00,2.190048934886023868e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924593298420386134e+01,4.181380126504284362e+02,1.433329964618300423e+00,6.928203299376685997e+00,2.191715601552690629e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924737635986244300e+01,4.181477734294738298e+02,1.435504175377851244e+00,6.928203299376685997e+00,2.193382268219357389e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.924881973552102465e+01,4.181575338460152125e+02,1.437680012903704840e+00,6.928203299376685997e+00,2.195048934886024150e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925026311117960631e+01,4.181672938997814413e+02,1.439857477135421115e+00,6.928203299376685997e+00,2.196715601552690911e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925170648683818797e+01,4.181770535905014299e+02,1.442036568012514897e+00,6.928203299376685997e+00,2.198382268219357671e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925314986249676963e+01,4.181868129179040352e+02,1.444217285474456158e+00,6.928203299376685997e+00,2.200048934886024432e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925459323815535129e+01,4.181965718817181710e+02,1.446399629460669134e+00,6.928203299376685997e+00,2.201715601552691193e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925603661381393295e+01,4.182063304816728078e+02,1.448583599910533204e+00,6.928203299376685997e+00,2.203382268219357953e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925747998947251460e+01,4.182160887174968025e+02,1.450769196763382674e+00,6.928203299376685997e+00,2.205048934886024714e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.925892336513109626e+01,4.182258465889191257e+02,1.452956419958506551e+00,6.928203299376685997e+00,2.206715601552691475e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926036674078967792e+01,4.182356040956687480e+02,1.455145269435148325e+00,6.928203299376685997e+00,2.208382268219358235e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926181011644825958e+01,4.182453612374745830e+02,1.457335745132506855e+00,6.928203299376685997e+00,2.210048934886024996e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926325349210684124e+01,4.182551180140656015e+02,1.459527846989735700e+00,6.928203299376685997e+00,2.211715601552691757e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926469686776542289e+01,4.182648744251708308e+02,1.461721574945942903e+00,6.928203299376685997e+00,2.213382268219358517e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926614024342400455e+01,4.182746304705192415e+02,1.463916928940191653e+00,6.928203299376685997e+00,2.215048934886025278e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926758361908258621e+01,4.182843861498398041e+02,1.466113908911500063e+00,6.928203299376685997e+00,2.216715601552692039e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.926902699474116787e+01,4.182941414628615462e+02,1.468312514798840729e+00,6.928203299376685997e+00,2.218382268219358799e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927047037039974953e+01,4.183038964093134950e+02,1.470512746541141169e+00,6.928203299376685997e+00,2.220048934886025560e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927191374605833118e+01,4.183136509889246781e+02,1.472714604077284051e+00,6.928203299376685997e+00,2.221715601552692321e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927335712171691284e+01,4.183234052014241229e+02,1.474918087346106521e+00,6.928203299376685997e+00,2.223382268219359081e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927480049737549450e+01,4.183331590465408567e+02,1.477123196286400875e+00,6.928203299376685997e+00,2.225048934886025842e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927624387303407616e+01,4.183429125240039639e+02,1.479329930836913887e+00,6.928203299376685997e+00,2.226715601552692603e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927768724869265782e+01,4.183526656335425287e+02,1.481538290936347479e+00,6.928203299376685997e+00,2.228382268219359363e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.927913062435123948e+01,4.183624183748856353e+02,1.483748276523358278e+00,6.928203299376685997e+00,2.230048934886026124e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928057400000982113e+01,4.183721707477623681e+02,1.485959887536557833e+00,6.928203299376685997e+00,2.231715601552692885e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928201737566840279e+01,4.183819227519018114e+02,1.488173123914512619e+00,6.928203299376685997e+00,2.233382268219359645e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928346075132698445e+01,4.183916743870330492e+02,1.490387985595743592e+00,6.928203299376685997e+00,2.235048934886026406e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928490412698556611e+01,4.184014256528852229e+02,1.492604472518727077e+00,6.928203299376685997e+00,2.236715601552693167e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928634750264414777e+01,4.184111765491874735e+02,1.494822584621893657e+00,6.928203299376685997e+00,2.238382268219359927e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928779087830272942e+01,4.184209270756689989e+02,1.497042321843629509e+00,6.928203299376685997e+00,2.240048934886026688e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.928923425396131108e+01,4.184306772320588834e+02,1.499263684122275064e+00,6.928203299376685997e+00,2.241715601552693449e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929067762961989274e+01,4.184404270180862682e+02,1.501486671396125683e+00,6.928203299376685997e+00,2.243382268219360209e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929212100527847440e+01,4.184501764334804079e+02,1.503711283603431870e+00,6.928203299376685997e+00,2.245048934886026970e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929356438093705606e+01,4.184599254779704438e+02,1.505937520682398834e+00,6.928203299376685997e+00,2.246715601552693731e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929500775659563772e+01,4.184696741512855169e+02,1.508165382571186708e+00,6.928203299376685997e+00,2.248382268219360491e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929645113225421937e+01,4.184794224531548821e+02,1.510394869207910329e+00,6.928203299376685997e+00,2.250048934886027252e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929789450791280103e+01,4.184891703833077941e+02,1.512625980530639680e+00,6.928203299376685997e+00,2.251715601552694013e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.929933788357138269e+01,4.184989179414733940e+02,1.514858716477399225e+00,6.928203299376685997e+00,2.253382268219360773e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930078125922996435e+01,4.185086651273809935e+02,1.517093076986168576e+00,6.928203299376685997e+00,2.255048934886027534e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930222463488854601e+01,4.185184119407597905e+02,1.519329061994882268e+00,6.928203299376685997e+00,2.256715601552694295e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930366801054712766e+01,4.185281583813390398e+02,1.521566671441429541e+00,6.928203299376685997e+00,2.258382268219361055e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930511138620570932e+01,4.185379044488479963e+02,1.523805905263654559e+00,6.928203299376685997e+00,2.260048934886027816e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930655476186429098e+01,4.185476501430159715e+02,1.526046763399356410e+00,6.928203299376685997e+00,2.261715601552694577e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930799813752287264e+01,4.185573954635722203e+02,1.528289245786289108e+00,6.928203299376685997e+00,2.263382268219361337e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.930944151318145430e+01,4.185671404102460542e+02,1.530533352362161370e+00,6.928203299376685997e+00,2.265048934886028098e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931088488884003596e+01,4.185768849827667850e+02,1.532779083064637060e+00,6.928203299376685997e+00,2.266715601552694859e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931232826449861761e+01,4.185866291808637243e+02,1.535026437831334523e+00,6.928203299376685997e+00,2.268382268219361619e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931377164015719927e+01,4.185963730042661837e+02,1.537275416599827471e+00,6.928203299376685997e+00,2.270048934886028380e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931521501581578093e+01,4.186061164527035316e+02,1.539526019307644100e+00,6.928203299376685997e+00,2.271715601552695141e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931665839147436259e+01,4.186158595259051367e+02,1.541778245892267751e+00,6.928203299376685997e+00,2.273382268219361901e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931810176713294425e+01,4.186256022236003105e+02,1.544032096291136469e+00,6.928203299376685997e+00,2.275048934886028662e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.931954514279152590e+01,4.186353445455184215e+02,1.546287570441643444e+00,6.928203299376685997e+00,2.276715601552695423e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932098851845010756e+01,4.186450864913888950e+02,1.548544668281136572e+00,6.928203299376685997e+00,2.278382268219362183e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932243189410868922e+01,4.186548280609410995e+02,1.550803389746918670e+00,6.928203299376685997e+00,2.280048934886028944e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932387526976727088e+01,4.186645692539044035e+02,1.553063734776247484e+00,6.928203299376685997e+00,2.281715601552695705e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932531864542585254e+01,4.186743100700082323e+02,1.555325703306335683e+00,6.928203299376685997e+00,2.283382268219362465e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932676202108443420e+01,4.186840505089820113e+02,1.557589295274350860e+00,6.928203299376685997e+00,2.285048934886029226e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932820539674301585e+01,4.186937905705552225e+02,1.559854510617415313e+00,6.928203299376685997e+00,2.286715601552695987e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.932964877240159751e+01,4.187035302544572346e+02,1.562121349272606485e+00,6.928203299376685997e+00,2.288382268219362747e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933109214806017917e+01,4.187132695604175296e+02,1.564389811176956524e+00,6.928203299376685997e+00,2.290048934886029508e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933253552371876083e+01,4.187230084881655898e+02,1.566659896267452723e+00,6.928203299376685997e+00,2.291715601552696269e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933397889937734249e+01,4.187327470374308973e+02,1.568931604481037079e+00,6.928203299376685997e+00,2.293382268219363029e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933542227503592414e+01,4.187424852079428774e+02,1.571204935754606735e+00,6.928203299376685997e+00,2.295048934886029790e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933686565069450580e+01,4.187522229994310692e+02,1.573479890025013539e+00,6.928203299376685997e+00,2.296715601552696551e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933830902635308746e+01,4.187619604116249548e+02,1.575756467229064262e+00,6.928203299376685997e+00,2.298382268219363311e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.933975240201166912e+01,4.187716974442540732e+02,1.578034667303520600e+00,6.928203299376685997e+00,2.300048934886030072e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934119577767025078e+01,4.187814340970479634e+02,1.580314490185099174e+00,6.928203299376685997e+00,2.301715601552696833e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934263915332883244e+01,4.187911703697361645e+02,1.582595935810471754e+00,6.928203299376685997e+00,2.303382268219363593e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934408252898741409e+01,4.188009062620481586e+02,1.584879004116264811e+00,6.928203299376685997e+00,2.305048934886030354e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934552590464599575e+01,4.188106417737135416e+02,1.587163695039059741e+00,6.928203299376685997e+00,2.306715601552697115e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934696928030457741e+01,4.188203769044619094e+02,1.589450008515392865e+00,6.928203299376685997e+00,2.308382268219363875e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934841265596315907e+01,4.188301116540228008e+02,1.591737944481755429e+00,6.928203299376685997e+00,2.310048934886030636e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.934985603162174073e+01,4.188398460221258688e+02,1.594027502874593827e+00,6.928203299376685997e+00,2.311715601552697397e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935129940728032238e+01,4.188495800085006522e+02,1.596318683630309154e+00,6.928203299376685997e+00,2.313382268219364157e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935274278293890404e+01,4.188593136128768037e+02,1.598611486685257432e+00,6.928203299376685997e+00,2.315048934886030918e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935418615859748570e+01,4.188690468349839193e+02,1.600905911975749829e+00,6.928203299376685997e+00,2.316715601552697679e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935562953425606736e+01,4.188787796745516516e+02,1.603201959438052215e+00,6.928203299376685997e+00,2.318382268219364439e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935707290991464902e+01,4.188885121313095965e+02,1.605499629008385387e+00,6.928203299376685997e+00,2.320048934886031200e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935851628557323068e+01,4.188982442049874635e+02,1.607798920622925287e+00,6.928203299376685997e+00,2.321715601552697961e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.935995966123181233e+01,4.189079758953149053e+02,1.610099834217802783e+00,6.928203299376685997e+00,2.323382268219364721e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.936140303689039399e+01,4.189177072020215746e+02,1.612402369729103446e+00,6.928203299376685997e+00,2.325048934886031482e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.936284641254897565e+01,4.189274381248371810e+02,1.614706527092868216e+00,6.928203299376685997e+00,2.326715601552698243e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.936428978820755731e+01,4.189371686634913772e+02,1.617012306245092512e+00,6.928203299376685997e+00,2.328382268219365003e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.936573316386613897e+01,4.189468988177139295e+02,1.619319707121726903e+00,6.928203299376685997e+00,2.330048934886031764e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.936717653952472062e+01,4.189566285872345475e+02,1.621628729658677104e+00,6.928203299376685997e+00,2.331715601552698525e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.936861991518330228e+01,4.189663579717829407e+02,1.623939373791803309e+00,6.928203299376685997e+00,2.333382268219365285e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937006329084188394e+01,4.189760869710888187e+02,1.626251639456921305e+00,6.928203299376685997e+00,2.335048934886032046e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937150666650046560e+01,4.189858155848819479e+02,1.628565526589801138e+00,6.928203299376685997e+00,2.336715601552698807e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937295004215904726e+01,4.189955438128921514e+02,1.630881035126168443e+00,6.928203299376685997e+00,2.338382268219365567e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937439341781762892e+01,4.190052716548491389e+02,1.633198165001703339e+00,6.928203299376685997e+00,2.340048934886032328e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937583679347621057e+01,4.190149991104826768e+02,1.635516916152041311e+00,6.928203299376685997e+00,2.341715601552699089e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937728016913479223e+01,4.190247261795225882e+02,1.637837288512772327e+00,6.928203299376685997e+00,2.343382268219365849e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.937872354479337389e+01,4.190344528616986963e+02,1.640159282019441944e+00,6.928203299376685997e+00,2.345048934886032610e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938016692045195555e+01,4.190441791567407677e+02,1.642482896607550202e+00,6.928203299376685997e+00,2.346715601552699371e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938161029611053721e+01,4.190539050643786823e+02,1.644808132212552065e+00,6.928203299376685997e+00,2.348382268219366131e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938305367176911886e+01,4.190636305843422633e+02,1.647134988769857866e+00,6.928203299376685997e+00,2.350048934886032892e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938449704742770052e+01,4.190733557163613341e+02,1.649463466214832641e+00,6.928203299376685997e+00,2.351715601552699653e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938594042308628218e+01,4.190830804601657746e+02,1.651793564482796350e+00,6.928203299376685997e+00,2.353382268219366413e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938738379874486384e+01,4.190928048154854082e+02,1.654125283509024325e+00,6.928203299376685997e+00,2.355048934886033174e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.938882717440344550e+01,4.191025287820501717e+02,1.656458623228746374e+00,6.928203299376685997e+00,2.356715601552699935e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939027055006202716e+01,4.191122523595898883e+02,1.658793583577147457e+00,6.928203299376685997e+00,2.358382268219366695e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939171392572060881e+01,4.191219755478345519e+02,1.661130164489367678e+00,6.928203299376685997e+00,2.360048934886033456e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939315730137919047e+01,4.191316983465139856e+02,1.663468365900502066e+00,6.928203299376685997e+00,2.361715601552700217e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939460067703777213e+01,4.191414207553581832e+02,1.665808187745600355e+00,6.928203299376685997e+00,2.363382268219366977e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939604405269635379e+01,4.191511427740970248e+02,1.668149629959667646e+00,6.928203299376685997e+00,2.365048934886033738e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939748742835493545e+01,4.191608644024604473e+02,1.670492692477663965e+00,6.928203299376685997e+00,2.366715601552700499e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.939893080401351710e+01,4.191705856401784445e+02,1.672837375234504265e+00,6.928203299376685997e+00,2.368382268219367259e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940037417967209876e+01,4.191803064869809532e+02,1.675183678165058199e+00,6.928203299376685997e+00,2.370048934886034020e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940181755533068042e+01,4.191900269425979673e+02,1.677531601204150791e+00,6.928203299376685997e+00,2.371715601552700781e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940326093098926208e+01,4.191997470067594804e+02,1.679881144286562211e+00,6.928203299376685997e+00,2.373382268219367541e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940470430664784374e+01,4.192094666791954864e+02,1.682232307347027112e+00,6.928203299376685997e+00,2.375048934886034302e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940614768230642539e+01,4.192191859596359791e+02,1.684585090320235512e+00,6.928203299376685997e+00,2.376715601552701063e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940759105796500705e+01,4.192289048478110089e+02,1.686939493140832136e+00,6.928203299376685997e+00,2.378382268219367823e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.940903443362358871e+01,4.192386233434505698e+02,1.689295515743417075e+00,6.928203299376685997e+00,2.380048934886034584e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941047780928217037e+01,4.192483414462847122e+02,1.691653158062545348e+00,6.928203299376685997e+00,2.381715601552701345e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941192118494075203e+01,4.192580591560434868e+02,1.694012420032726673e+00,6.928203299376685997e+00,2.383382268219368105e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941336456059933369e+01,4.192677764724570011e+02,1.696373301588426141e+00,6.928203299376685997e+00,2.385048934886034866e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941480793625791534e+01,4.192774933952552487e+02,1.698735802664063765e+00,6.928203299376685997e+00,2.386715601552701627e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941625131191649700e+01,4.192872099241683941e+02,1.701099923194014263e+00,6.928203299376685997e+00,2.388382268219368387e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941769468757507866e+01,4.192969260589264877e+02,1.703465663112607942e+00,6.928203299376685997e+00,2.390048934886035148e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.941913806323366032e+01,4.193066417992596371e+02,1.705833022354129591e+00,6.928203299376685997e+00,2.391715601552701909e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942058143889224198e+01,4.193163571448980065e+02,1.708202000852819369e+00,6.928203299376685997e+00,2.393382268219368669e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942202481455082363e+01,4.193260720955717034e+02,1.710572598542872136e+00,6.928203299376685997e+00,2.395048934886035430e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942346819020940529e+01,4.193357866510108352e+02,1.712944815358438122e+00,6.928203299376685997e+00,2.396715601552702191e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942491156586798695e+01,4.193455008109455662e+02,1.715318651233622260e+00,6.928203299376685997e+00,2.398382268219368951e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942635494152656861e+01,4.193552145751060607e+02,1.717694106102484852e+00,6.928203299376685997e+00,2.400048934886035712e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942779831718515027e+01,4.193649279432225399e+02,1.720071179899040903e+00,6.928203299376685997e+00,2.401715601552702473e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.942924169284373193e+01,4.193746409150251111e+02,1.722449872557260564e+00,6.928203299376685997e+00,2.403382268219369233e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943068506850231358e+01,4.193843534902439956e+02,1.724830184011069134e+00,6.928203299376685997e+00,2.405048934886035994e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943212844416089524e+01,4.193940656686094144e+02,1.727212114194346837e+00,6.928203299376685997e+00,2.406715601552702755e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943357181981947690e+01,4.194037774498515887e+02,1.729595663040928821e+00,6.928203299376685997e+00,2.408382268219369515e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943501519547805856e+01,4.194134888337007396e+02,1.731980830484605605e+00,6.928203299376685997e+00,2.410048934886036276e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943645857113664022e+01,4.194231998198870883e+02,1.734367616459122408e+00,6.928203299376685997e+00,2.411715601552703037e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943790194679522187e+01,4.194329104081409128e+02,1.736756020898179598e+00,6.928203299376685997e+00,2.413382268219369797e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.943934532245380353e+01,4.194426205981924909e+02,1.739146043735432690e+00,6.928203299376685997e+00,2.415048934886036558e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944078869811238519e+01,4.194523303897720439e+02,1.741537684904492123e+00,6.928203299376685997e+00,2.416715601552703319e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944223207377096685e+01,4.194620397826099065e+02,1.743930944338923261e+00,6.928203299376685997e+00,2.418382268219370079e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944367544942954851e+01,4.194717487764363000e+02,1.746325821972246839e+00,6.928203299376685997e+00,2.420048934886036840e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944511882508813017e+01,4.194814573709816159e+02,1.748722317737938514e+00,6.928203299376685997e+00,2.421715601552703601e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944656220074671182e+01,4.194911655659761323e+02,1.751120431569428870e+00,6.928203299376685997e+00,2.423382268219370361e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944800557640529348e+01,4.195008733611501839e+02,1.753520163400103860e+00,6.928203299376685997e+00,2.425048934886037122e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.944944895206387514e+01,4.195105807562340487e+02,1.755921513163303915e+00,6.928203299376685997e+00,2.426715601552703883e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945089232772245680e+01,4.195202877509581754e+02,1.758324480792325062e+00,6.928203299376685997e+00,2.428382268219370643e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945233570338103846e+01,4.195299943450528417e+02,1.760729066220418249e+00,6.928203299376685997e+00,2.430048934886037404e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945377907903962011e+01,4.195397005382484963e+02,1.763135269380789349e+00,6.928203299376685997e+00,2.431715601552704165e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945522245469820177e+01,4.195494063302754739e+02,1.765543090206599386e+00,6.928203299376685997e+00,2.433382268219370925e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945666583035678343e+01,4.195591117208641663e+02,1.767952528630964526e+00,6.928203299376685997e+00,2.435048934886037686e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945810920601536509e+01,4.195688167097450219e+02,1.770363584586955863e+00,6.928203299376685997e+00,2.436715601552704447e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.945955258167394675e+01,4.195785212966484323e+02,1.772776258007599637e+00,6.928203299376685997e+00,2.438382268219371207e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946099595733252841e+01,4.195882254813047894e+02,1.775190548825877235e+00,6.928203299376685997e+00,2.440048934886037968e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946243933299111006e+01,4.195979292634445983e+02,1.777606456974724747e+00,6.928203299376685997e+00,2.441715601552704729e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946388270864969172e+01,4.196076326427982508e+02,1.780023982387033854e+00,6.928203299376685997e+00,2.443382268219371489e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946532608430827338e+01,4.196173356190962522e+02,1.782443124995650940e+00,6.928203299376685997e+00,2.445048934886038250e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946676945996685504e+01,4.196270381920690511e+02,1.784863884733377759e+00,6.928203299376685997e+00,2.446715601552705011e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946821283562543670e+01,4.196367403614470959e+02,1.787286261532970988e+00,6.928203299376685997e+00,2.448382268219371771e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.946965621128401835e+01,4.196464421269609488e+02,1.789710255327142230e+00,6.928203299376685997e+00,2.450048934886038532e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947109958694260001e+01,4.196561434883411152e+02,1.792135866048558457e+00,6.928203299376685997e+00,2.451715601552705293e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947254296260118167e+01,4.196658444453180437e+02,1.794563093629841344e+00,6.928203299376685997e+00,2.453382268219372053e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947398633825976333e+01,4.196755449976223531e+02,1.796991938003568157e+00,6.928203299376685997e+00,2.455048934886038814e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947542971391834499e+01,4.196852451449844921e+02,1.799422399102270864e+00,6.928203299376685997e+00,2.456715601552705575e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947687308957692665e+01,4.196949448871350796e+02,1.801854476858436804e+00,6.928203299376685997e+00,2.458382268219372335e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947831646523550830e+01,4.197046442238046779e+02,1.804288171204508018e+00,6.928203299376685997e+00,2.460048934886039096e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.947975984089408996e+01,4.197143431547238492e+02,1.806723482072882137e+00,6.928203299376685997e+00,2.461715601552705857e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948120321655267162e+01,4.197240416796231557e+02,1.809160409395911495e+00,6.928203299376685997e+00,2.463382268219372617e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948264659221125328e+01,4.197337397982332163e+02,1.811598953105903798e+00,6.928203299376685997e+00,2.465048934886039378e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948408996786983494e+01,4.197434375102845934e+02,1.814039113135121672e+00,6.928203299376685997e+00,2.466715601552706139e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948553334352841659e+01,4.197531348155079627e+02,1.816480889415782674e+00,6.928203299376685997e+00,2.468382268219372899e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948697671918699825e+01,4.197628317136339433e+02,1.818924281880059945e+00,6.928203299376685997e+00,2.470048934886039660e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948842009484557991e+01,4.197725282043931543e+02,1.821369290460081336e+00,6.928203299376685997e+00,2.471715601552706421e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.948986347050416157e+01,4.197822242875162715e+02,1.823815915087930062e+00,6.928203299376685997e+00,2.473382268219373181e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949130684616274323e+01,4.197919199627339708e+02,1.826264155695644265e+00,6.928203299376685997e+00,2.475048934886039942e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949275022182132489e+01,4.198016152297768713e+02,1.828714012215217233e+00,6.928203299376685997e+00,2.476715601552706703e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949419359747990654e+01,4.198113100883757056e+02,1.831165484578597402e+00,6.928203299376685997e+00,2.478382268219373463e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949563697313848820e+01,4.198210045382611497e+02,1.833618572717688355e+00,6.928203299376685997e+00,2.480048934886040224e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949708034879706986e+01,4.198306985791639363e+02,1.836073276564348822e+00,6.928203299376685997e+00,2.481715601552706985e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949852372445565152e+01,4.198403922108147981e+02,1.838529596050392456e+00,6.928203299376685997e+00,2.483382268219373745e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.949996710011423318e+01,4.198500854329444678e+02,1.840987531107588060e+00,6.928203299376685997e+00,2.485048934886040506e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.950141047577281483e+01,4.198597782452836213e+02,1.843447081667659804e+00,6.928203299376685997e+00,2.486715601552707267e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.950285385143139649e+01,4.198694706475631051e+02,1.845908247662287005e+00,6.928203299376685997e+00,2.488382268219374027e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.950429722708997815e+01,4.198791626395135950e+02,1.848371029023103684e+00,6.928203299376685997e+00,2.490048934886040788e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.950574060274855981e+01,4.198888542208659374e+02,1.850835425681699453e+00,6.928203299376685997e+00,2.491715601552707549e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.950718397840714147e+01,4.198985453913509218e+02,1.853301437569618626e+00,6.928203299376685997e+00,2.493382268219374309e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.950862735406572313e+01,4.199082361506992811e+02,1.855769064618361108e+00,6.928203299376685997e+00,2.495048934886041070e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951007072972430478e+01,4.199179264986419184e+02,1.858238306759381508e+00,6.928203299376685997e+00,2.496715601552707831e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951151410538288644e+01,4.199276164349095666e+02,1.860709163924089804e+00,6.928203299376685997e+00,2.498382268219374591e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951295748104146810e+01,4.199373059592331288e+02,1.863181636043851119e+00,6.928203299376685997e+00,2.500048934886041074e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951440085670004976e+01,4.199469950713434514e+02,1.865655723049985726e+00,6.928203299376685997e+00,2.501715601552707557e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951584423235863142e+01,4.199566837709713809e+02,1.868131424873768820e+00,6.928203299376685997e+00,2.503382268219374041e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951728760801721307e+01,4.199663720578477637e+02,1.870608741446430967e+00,6.928203299376685997e+00,2.505048934886040524e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.951873098367579473e+01,4.199760599317035030e+02,1.873087672699157880e+00,6.928203299376685997e+00,2.506715601552707007e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952017435933437639e+01,4.199857473922694453e+02,1.875568218563090417e+00,6.928203299376685997e+00,2.508382268219373490e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952161773499295805e+01,4.199954344392765506e+02,1.878050378969324363e+00,6.928203299376685997e+00,2.510048934886039973e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952306111065153971e+01,4.200051210724557222e+02,1.880534153848910872e+00,6.928203299376685997e+00,2.511715601552706456e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952450448631012137e+01,4.200148072915378634e+02,1.883019543132856244e+00,6.928203299376685997e+00,2.513382268219372939e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952594786196870302e+01,4.200244930962539343e+02,1.885506546752121926e+00,6.928203299376685997e+00,2.515048934886039422e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952739123762728468e+01,4.200341784863348948e+02,1.887995164637624512e+00,6.928203299376685997e+00,2.516715601552705905e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.952883461328586634e+01,4.200438634615116484e+02,1.890485396720235522e+00,6.928203299376685997e+00,2.518382268219372389e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953027798894444800e+01,4.200535480215152120e+02,1.892977242930782067e+00,6.928203299376685997e+00,2.520048934886038872e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953172136460302966e+01,4.200632321660766024e+02,1.895470703200045959e+00,6.928203299376685997e+00,2.521715601552705355e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953316474026161131e+01,4.200729158949267799e+02,1.897965777458764602e+00,6.928203299376685997e+00,2.523382268219371838e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953460811592019297e+01,4.200825992077967612e+02,1.900462465637630327e+00,6.928203299376685997e+00,2.525048934886038321e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953605149157877463e+01,4.200922821044175635e+02,1.902960767667290609e+00,6.928203299376685997e+00,2.526715601552704804e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953749486723735629e+01,4.201019645845202035e+02,1.905460683478348294e+00,6.928203299376685997e+00,2.528382268219371287e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.953893824289593795e+01,4.201116466478356983e+02,1.907962213001361373e+00,6.928203299376685997e+00,2.530048934886037770e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954038161855451960e+01,4.201213282940951217e+02,1.910465356166842765e+00,6.928203299376685997e+00,2.531715601552704253e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954182499421310126e+01,4.201310095230296042e+02,1.912970112905260534e+00,6.928203299376685997e+00,2.533382268219370737e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954326836987168292e+01,4.201406903343701629e+02,1.915476483147038333e+00,6.928203299376685997e+00,2.535048934886037220e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954471174553026458e+01,4.201503707278478714e+02,1.917984466822554745e+00,6.928203299376685997e+00,2.536715601552703703e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954615512118884624e+01,4.201600507031938605e+02,1.920494063862143497e+00,6.928203299376685997e+00,2.538382268219370186e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954759849684742790e+01,4.201697302601392039e+02,1.923005274196093684e+00,6.928203299376685997e+00,2.540048934886036669e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.954904187250600955e+01,4.201794093984150891e+02,1.925518097754649327e+00,6.928203299376685997e+00,2.541715601552703152e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955048524816459121e+01,4.201890881177525898e+02,1.928032534468009818e+00,6.928203299376685997e+00,2.543382268219369635e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955192862382317287e+01,4.201987664178828936e+02,1.930548584266329692e+00,6.928203299376685997e+00,2.545048934886036118e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955337199948175453e+01,4.202084442985371311e+02,1.933066247079718636e+00,6.928203299376685997e+00,2.546715601552702601e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955481537514033619e+01,4.202181217594464897e+02,1.935585522838241701e+00,6.928203299376685997e+00,2.548382268219369085e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955625875079891784e+01,4.202277988003421569e+02,1.938106411471918866e+00,6.928203299376685997e+00,2.550048934886035568e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955770212645749950e+01,4.202374754209553203e+02,1.940628912910725479e+00,6.928203299376685997e+00,2.551715601552702051e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.955914550211608116e+01,4.202471516210171671e+02,1.943153027084592033e+00,6.928203299376685997e+00,2.553382268219368534e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956058887777466282e+01,4.202568274002589419e+02,1.945678753923404392e+00,6.928203299376685997e+00,2.555048934886035017e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956203225343324448e+01,4.202665027584118889e+02,1.948206093357003343e+00,6.928203299376685997e+00,2.556715601552701500e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956347562909182614e+01,4.202761776952071955e+02,1.950735045315185046e+00,6.928203299376685997e+00,2.558382268219367983e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956491900475040779e+01,4.202858522103761629e+02,1.953265609727700802e+00,6.928203299376685997e+00,2.560048934886034466e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956636238040898945e+01,4.202955263036499787e+02,1.955797786524257287e+00,6.928203299376685997e+00,2.561715601552700949e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956780575606757111e+01,4.203051999747600007e+02,1.958331575634516097e+00,6.928203299376685997e+00,2.563382268219367432e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.956924913172615277e+01,4.203148732234374734e+02,1.960866976988094201e+00,6.928203299376685997e+00,2.565048934886033916e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957069250738473443e+01,4.203245460494136978e+02,1.963403990514563935e+00,6.928203299376685997e+00,2.566715601552700399e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957213588304331608e+01,4.203342184524199752e+02,1.965942616143452559e+00,6.928203299376685997e+00,2.568382268219366882e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957357925870189774e+01,4.203438904321876635e+02,1.968482853804242705e+00,6.928203299376685997e+00,2.570048934886033365e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957502263436047940e+01,4.203535619884480639e+02,1.971024703426372371e+00,6.928203299376685997e+00,2.571715601552699848e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957646601001906106e+01,4.203632331209325343e+02,1.973568164939234482e+00,6.928203299376685997e+00,2.573382268219366331e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957790938567764272e+01,4.203729038293724329e+02,1.976113238272177330e+00,6.928203299376685997e+00,2.575048934886032814e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.957935276133622438e+01,4.203825741134991745e+02,1.978659923354504580e+00,6.928203299376685997e+00,2.576715601552699297e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958079613699480603e+01,4.203922439730440601e+02,1.981208220115474816e+00,6.928203299376685997e+00,2.578382268219365780e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958223951265338769e+01,4.204019134077385047e+02,1.983758128484301997e+00,6.928203299376685997e+00,2.580048934886032264e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958368288831196935e+01,4.204115824173139231e+02,1.986309648390155447e+00,6.928203299376685997e+00,2.581715601552698747e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958512626397055101e+01,4.204212510015017870e+02,1.988862779762159638e+00,6.928203299376685997e+00,2.583382268219365230e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958656963962913267e+01,4.204309191600334543e+02,1.991417522529394191e+00,6.928203299376685997e+00,2.585048934886031713e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958801301528771432e+01,4.204405868926403969e+02,1.993973876620893870e+00,6.928203299376685997e+00,2.586715601552698196e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.958945639094629598e+01,4.204502541990540294e+02,1.996531841965649035e+00,6.928203299376685997e+00,2.588382268219364679e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959089976660487764e+01,4.204599210790058237e+02,1.999091418492604966e+00,6.928203299376685997e+00,2.590048934886031162e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959234314226345930e+01,4.204695875322273082e+02,2.001652606130662537e+00,6.928203299376685997e+00,2.591715601552697645e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959378651792204096e+01,4.204792535584498978e+02,2.004215404808677548e+00,6.928203299376685997e+00,2.593382268219364128e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959522989358062262e+01,4.204889191574051210e+02,2.006779814455461164e+00,6.928203299376685997e+00,2.595048934886030612e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959667326923920427e+01,4.204985843288245064e+02,2.009345834999779701e+00,6.928203299376685997e+00,2.596715601552697095e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959811664489778593e+01,4.205082490724395825e+02,2.011913466370354620e+00,6.928203299376685997e+00,2.598382268219363578e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.959956002055636759e+01,4.205179133879818778e+02,2.014482708495862973e+00,6.928203299376685997e+00,2.600048934886030061e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960100339621494925e+01,4.205275772751829209e+02,2.017053561304937404e+00,6.928203299376685997e+00,2.601715601552696544e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960244677187353091e+01,4.205372407337742402e+02,2.019626024726164815e+00,6.928203299376685997e+00,2.603382268219363027e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960389014753211256e+01,4.205469037634874780e+02,2.022200098688087699e+00,6.928203299376685997e+00,2.605048934886029510e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960533352319069422e+01,4.205565663640541629e+02,2.024775783119204586e+00,6.928203299376685997e+00,2.606715601552695993e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960677689884927588e+01,4.205662285352059371e+02,2.027353077947968263e+00,6.928203299376685997e+00,2.608382268219362476e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960822027450785754e+01,4.205758902766743290e+02,2.029931983102787552e+00,6.928203299376685997e+00,2.610048934886028960e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.960966365016643920e+01,4.205855515881910378e+02,2.032512498512025978e+00,6.928203299376685997e+00,2.611715601552695443e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961110702582502086e+01,4.205952124694876488e+02,2.035094624104002214e+00,6.928203299376685997e+00,2.613382268219361926e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961255040148360251e+01,4.206048729202958043e+02,2.037678359806990969e+00,6.928203299376685997e+00,2.615048934886028409e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961399377714218417e+01,4.206145329403472033e+02,2.040263705549222095e+00,6.928203299376685997e+00,2.616715601552694892e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961543715280076583e+01,4.206241925293734880e+02,2.042850661258879708e+00,6.928203299376685997e+00,2.618382268219361375e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961688052845934749e+01,4.206338516871063007e+02,2.045439226864104398e+00,6.928203299376685997e+00,2.620048934886027858e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961832390411792915e+01,4.206435104132773404e+02,2.048029402292991463e+00,6.928203299376685997e+00,2.621715601552694341e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.961976727977651080e+01,4.206531687076183630e+02,2.050621187473591789e+00,6.928203299376685997e+00,2.623382268219360824e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962121065543509246e+01,4.206628265698610107e+02,2.053214582333910965e+00,6.928203299376685997e+00,2.625048934886027308e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962265403109367412e+01,4.206724839997370964e+02,2.055809586801910616e+00,6.928203299376685997e+00,2.626715601552693791e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962409740675225578e+01,4.206821409969782621e+02,2.058406200805507069e+00,6.928203299376685997e+00,2.628382268219360274e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962554078241083744e+01,4.206917975613163208e+02,2.061004424272572244e+00,6.928203299376685997e+00,2.630048934886026757e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962698415806941910e+01,4.207014536924830281e+02,2.063604257130933206e+00,6.928203299376685997e+00,2.631715601552693240e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962842753372800075e+01,4.207111093902101402e+02,2.066205699308372168e+00,6.928203299376685997e+00,2.633382268219359723e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.962987090938658241e+01,4.207207646542294697e+02,2.068808750732626933e+00,6.928203299376685997e+00,2.635048934886026206e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963131428504516407e+01,4.207304194842727725e+02,2.071413411331390897e+00,6.928203299376685997e+00,2.636715601552692689e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963275766070374573e+01,4.207400738800719182e+02,2.074019681032312157e+00,6.928203299376685997e+00,2.638382268219359172e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963420103636232739e+01,4.207497278413586628e+02,2.076627559762994402e+00,6.928203299376685997e+00,2.640048934886025656e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963564441202090904e+01,4.207593813678648758e+02,2.079237047450996467e+00,6.928203299376685997e+00,2.641715601552692139e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963708778767949070e+01,4.207690344593224268e+02,2.081848144023832337e+00,6.928203299376685997e+00,2.643382268219358622e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963853116333807236e+01,4.207786871154631285e+02,2.084460849408972027e+00,6.928203299376685997e+00,2.645048934886025105e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.963997453899665402e+01,4.207883393360188506e+02,2.087075163533839817e+00,6.928203299376685997e+00,2.646715601552691588e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.964141791465523568e+01,4.207979911207215196e+02,2.089691086325816460e+00,6.928203299376685997e+00,2.648382268219358071e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.964286129031381734e+01,4.208076424693030049e+02,2.092308617712236973e+00,6.928203299376685997e+00,2.650048934886024554e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.964430466597239899e+01,4.208172933814951762e+02,2.094927757620392406e+00,6.928203299376685997e+00,2.651715601552691037e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.964574804163098065e+01,4.208269438570300167e+02,2.097548505977528954e+00,6.928203299376685997e+00,2.653382268219357520e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.964719141728956231e+01,4.208365938956394530e+02,2.100170862710847963e+00,6.928203299376685997e+00,2.655048934886024004e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.964863479294814397e+01,4.208462434970554114e+02,2.102794827747505924e+00,6.928203299376685997e+00,2.656715601552690487e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965007816860672563e+01,4.208558926610098183e+02,2.105420401014615361e+00,6.928203299376685997e+00,2.658382268219356970e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965152154426530728e+01,4.208655413872346571e+02,2.108047582439243062e+00,6.928203299376685997e+00,2.660048934886023453e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965296491992388894e+01,4.208751896754619111e+02,2.110676371948412289e+00,6.928203299376685997e+00,2.661715601552689936e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965440829558247060e+01,4.208848375254236203e+02,2.113306769469101010e+00,6.928203299376685997e+00,2.663382268219356419e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965585167124105226e+01,4.208944849368517112e+02,2.115938774928242783e+00,6.928203299376685997e+00,2.665048934886022902e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965729504689963392e+01,4.209041319094782239e+02,2.118572388252725869e+00,6.928203299376685997e+00,2.666715601552689385e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.965873842255821558e+01,4.209137784430351985e+02,2.121207609369394564e+00,6.928203299376685997e+00,2.668382268219355868e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966018179821679723e+01,4.209234245372546752e+02,2.123844438205048757e+00,6.928203299376685997e+00,2.670048934886022352e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966162517387537889e+01,4.209330701918687510e+02,2.126482874686442592e+00,6.928203299376685997e+00,2.671715601552688835e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966306854953396055e+01,4.209427154066094090e+02,2.129122918740286252e+00,6.928203299376685997e+00,2.673382268219355318e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966451192519254221e+01,4.209523601812088032e+02,2.131764570293245509e+00,6.928203299376685997e+00,2.675048934886021801e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966595530085112387e+01,4.209620045153989736e+02,2.134407829271940837e+00,6.928203299376685997e+00,2.676715601552688284e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966739867650970552e+01,4.209716484089120172e+02,2.137052695602948749e+00,6.928203299376685997e+00,2.678382268219354767e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.966884205216828718e+01,4.209812918614800878e+02,2.139699169212800456e+00,6.928203299376685997e+00,2.680048934886021250e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967028542782686884e+01,4.209909348728352825e+02,2.142347250027982763e+00,6.928203299376685997e+00,2.681715601552687733e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967172880348545050e+01,4.210005774427097549e+02,2.144996937974937623e+00,6.928203299376685997e+00,2.683382268219354216e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967317217914403216e+01,4.210102195708356021e+02,2.147648232980063021e+00,6.928203299376685997e+00,2.685048934886020700e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967461555480261381e+01,4.210198612569450347e+02,2.150301134969711647e+00,6.928203299376685997e+00,2.686715601552687183e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967605893046119547e+01,4.210295025007702634e+02,2.152955643870192226e+00,6.928203299376685997e+00,2.688382268219353666e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967750230611977713e+01,4.210391433020434420e+02,2.155611759607767741e+00,6.928203299376685997e+00,2.690048934886020149e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.967894568177835879e+01,4.210487836604967242e+02,2.158269482108657655e+00,6.928203299376685997e+00,2.691715601552686632e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968038905743694045e+01,4.210584235758623777e+02,2.160928811299036134e+00,6.928203299376685997e+00,2.693382268219353115e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968183243309552211e+01,4.210680630478726130e+02,2.163589747105032934e+00,6.928203299376685997e+00,2.695048934886019598e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968327580875410376e+01,4.210777020762596976e+02,2.166252289452733404e+00,6.928203299376685997e+00,2.696715601552686081e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968471918441268542e+01,4.210873406607558422e+02,2.168916438268177593e+00,6.928203299376685997e+00,2.698382268219352564e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968616256007126708e+01,4.210969788010933144e+02,2.171582193477362033e+00,6.928203299376685997e+00,2.700048934886019047e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968760593572984874e+01,4.211066164970043815e+02,2.174249555006237511e+00,6.928203299376685997e+00,2.701715601552685531e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.968904931138843040e+01,4.211162537482213679e+02,2.176918522780710408e+00,6.928203299376685997e+00,2.703382268219352014e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969049268704701205e+01,4.211258905544765412e+02,2.179589096726643138e+00,6.928203299376685997e+00,2.705048934886018497e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969193606270559371e+01,4.211355269155021688e+02,2.182261276769852820e+00,6.928203299376685997e+00,2.706715601552684980e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969337943836417537e+01,4.211451628310306319e+02,2.184935062836112607e+00,6.928203299376685997e+00,2.708382268219351463e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969482281402275703e+01,4.211547983007942548e+02,2.187610454851150354e+00,6.928203299376685997e+00,2.710048934886017946e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969626618968133869e+01,4.211644333245254188e+02,2.190287452740649954e+00,6.928203299376685997e+00,2.711715601552684429e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969770956533992035e+01,4.211740679019564482e+02,2.192966056430249999e+00,6.928203299376685997e+00,2.713382268219350912e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.969915294099850200e+01,4.211837020328196672e+02,2.195646265845545120e+00,6.928203299376685997e+00,2.715048934886017395e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970059631665708366e+01,4.211933357168475140e+02,2.198328080912084648e+00,6.928203299376685997e+00,2.716715601552683879e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970203969231566532e+01,4.212029689537724266e+02,2.201011501555373950e+00,6.928203299376685997e+00,2.718382268219350362e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970348306797424698e+01,4.212126017433267293e+02,2.203696527700873542e+00,6.928203299376685997e+00,2.720048934886016845e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970492644363282864e+01,4.212222340852429170e+02,2.206383159273999528e+00,6.928203299376685997e+00,2.721715601552683328e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970636981929141029e+01,4.212318659792533708e+02,2.209071396200123161e+00,6.928203299376685997e+00,2.723382268219349811e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970781319494999195e+01,4.212414974250905857e+02,2.211761238404570840e+00,6.928203299376685997e+00,2.725048934886016294e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.970925657060857361e+01,4.212511284224869996e+02,2.214452685812625443e+00,6.928203299376685997e+00,2.726715601552682777e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971069994626715527e+01,4.212607589711751075e+02,2.217145738349524109e+00,6.928203299376685997e+00,2.728382268219349260e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971214332192573693e+01,4.212703890708873473e+02,2.219840395940459565e+00,6.928203299376685997e+00,2.730048934886015743e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971358669758431859e+01,4.212800187213562140e+02,2.222536658510580576e+00,6.928203299376685997e+00,2.731715601552682227e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971503007324290024e+01,4.212896479223142592e+02,2.225234525984991052e+00,6.928203299376685997e+00,2.733382268219348710e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971647344890148190e+01,4.212992766734939778e+02,2.227933998288750050e+00,6.928203299376685997e+00,2.735048934886015193e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971791682456006356e+01,4.213089049746279215e+02,2.230635075346872220e+00,6.928203299376685997e+00,2.736715601552681676e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.971936020021864522e+01,4.213185328254486421e+02,2.233337757084327357e+00,6.928203299376685997e+00,2.738382268219348159e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972080357587722688e+01,4.213281602256886913e+02,2.236042043426041293e+00,6.928203299376685997e+00,2.740048934886014642e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972224695153580853e+01,4.213377871750806207e+02,2.238747934296895004e+00,6.928203299376685997e+00,2.741715601552681125e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972369032719439019e+01,4.213474136733570390e+02,2.241455429621725060e+00,6.928203299376685997e+00,2.743382268219347608e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972513370285297185e+01,4.213570397202505546e+02,2.244164529325322732e+00,6.928203299376685997e+00,2.745048934886014091e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972657707851155351e+01,4.213666653154937762e+02,2.246875233332435773e+00,6.928203299376685997e+00,2.746715601552680575e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972802045417013517e+01,4.213762904588192555e+02,2.249587541567766635e+00,6.928203299376685997e+00,2.748382268219347058e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.972946382982871683e+01,4.213859151499597147e+02,2.252301453955973365e+00,6.928203299376685997e+00,2.750048934886013541e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973090720548729848e+01,4.213955393886477623e+02,2.255016970421669154e+00,6.928203299376685997e+00,2.751715601552680024e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973235058114588014e+01,4.214051631746160638e+02,2.257734090889423673e+00,6.928203299376685997e+00,2.753382268219346507e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973379395680446180e+01,4.214147865075972845e+02,2.260452815283760852e+00,6.928203299376685997e+00,2.755048934886012990e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973523733246304346e+01,4.214244093873241468e+02,2.263173143529160658e+00,6.928203299376685997e+00,2.756715601552679473e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973668070812162512e+01,4.214340318135293160e+02,2.265895075550058646e+00,6.928203299376685997e+00,2.758382268219345956e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973812408378020677e+01,4.214436537859455143e+02,2.268618611270845520e+00,6.928203299376685997e+00,2.760048934886012439e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.973956745943878843e+01,4.214532753043054072e+02,2.271343750615867574e+00,6.928203299376685997e+00,2.761715601552678923e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974101083509737009e+01,4.214628963683418306e+02,2.274070493509426250e+00,6.928203299376685997e+00,2.763382268219345406e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974245421075595175e+01,4.214725169777874498e+02,2.276798839875778580e+00,6.928203299376685997e+00,2.765048934886011889e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974389758641453341e+01,4.214821371323750441e+02,2.279528789639137631e+00,6.928203299376685997e+00,2.766715601552678372e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974534096207311507e+01,4.214917568318373924e+02,2.282260342723671176e+00,6.928203299376685997e+00,2.768382268219344855e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974678433773169672e+01,4.215013760759073307e+02,2.284993499053502575e+00,6.928203299376685997e+00,2.770048934886011338e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974822771339027838e+01,4.215109948643175812e+02,2.287728258552711225e+00,6.928203299376685997e+00,2.771715601552677821e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.974967108904886004e+01,4.215206131968009799e+02,2.290464621145331225e+00,6.928203299376685997e+00,2.773382268219344304e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975111446470744170e+01,4.215302310730903628e+02,2.293202586755352712e+00,6.928203299376685997e+00,2.775048934886010787e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975255784036602336e+01,4.215398484929185656e+02,2.295942155306720966e+00,6.928203299376685997e+00,2.776715601552677271e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975400121602460501e+01,4.215494654560184813e+02,2.298683326723337306e+00,6.928203299376685997e+00,2.778382268219343754e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975544459168318667e+01,4.215590819621228889e+02,2.301426100929057306e+00,6.928203299376685997e+00,2.780048934886010237e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975688796734176833e+01,4.215686980109647379e+02,2.304170477847693466e+00,6.928203299376685997e+00,2.781715601552676720e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975833134300034999e+01,4.215783136022768645e+02,2.306916457403012988e+00,6.928203299376685997e+00,2.783382268219343203e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.975977471865893165e+01,4.215879287357921612e+02,2.309664039518738221e+00,6.928203299376685997e+00,2.785048934886009686e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976121809431751331e+01,4.215975434112435778e+02,2.312413224118547994e+00,6.928203299376685997e+00,2.786715601552676169e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976266146997609496e+01,4.216071576283640070e+02,2.315164011126075394e+00,6.928203299376685997e+00,2.788382268219342652e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976410484563467662e+01,4.216167713868864553e+02,2.317916400464910431e+00,6.928203299376685997e+00,2.790048934886009135e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976554822129325828e+01,4.216263846865438154e+02,2.320670392058597375e+00,6.928203299376685997e+00,2.791715601552675619e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976699159695183994e+01,4.216359975270690370e+02,2.323425985830636531e+00,6.928203299376685997e+00,2.793382268219342102e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976843497261042160e+01,4.216456099081951265e+02,2.326183181704483793e+00,6.928203299376685997e+00,2.795048934886008585e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.976987834826900325e+01,4.216552218296550905e+02,2.328941979603550205e+00,6.928203299376685997e+00,2.796715601552675068e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977132172392758491e+01,4.216648332911818784e+02,2.331702379451202400e+00,6.928203299376685997e+00,2.798382268219341551e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977276509958616657e+01,4.216744442925085536e+02,2.334464381170763048e+00,6.928203299376685997e+00,2.800048934886008034e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977420847524474823e+01,4.216840548333681227e+02,2.337227984685509519e+00,6.928203299376685997e+00,2.801715601552674517e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977565185090332989e+01,4.216936649134935919e+02,2.339993189918675220e+00,6.928203299376685997e+00,2.803382268219341000e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977709522656191155e+01,4.217032745326180816e+02,2.342759996793448707e+00,6.928203299376685997e+00,2.805048934886007483e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977853860222049320e+01,4.217128836904745981e+02,2.345528405232974123e+00,6.928203299376685997e+00,2.806715601552673967e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.977998197787907486e+01,4.217224923867962616e+02,2.348298415160351649e+00,6.928203299376685997e+00,2.808382268219340450e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.978142535353765652e+01,4.217321006213161922e+02,2.351070026498636167e+00,6.928203299376685997e+00,2.810048934886006933e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.978286872919623818e+01,4.217417083937674533e+02,2.353843239170838597e+00,6.928203299376685997e+00,2.811715601552673416e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.978431210485481984e+01,4.217513157038831650e+02,2.356618053099925447e+00,6.928203299376685997e+00,2.813382268219339899e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.978575548051340149e+01,4.217609225513964475e+02,2.359394468208818374e+00,6.928203299376685997e+00,2.815048934886006382e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.978719885617198315e+01,4.217705289360404208e+02,2.362172484420394625e+00,6.928203299376685997e+00,2.816715601552672865e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.978864223183056481e+01,4.217801348575482621e+02,2.364952101657487482e+00,6.928203299376685997e+00,2.818382268219339348e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979008560748914647e+01,4.217897403156531482e+02,2.367733319842884931e+00,6.928203299376685997e+00,2.820048934886005831e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979152898314772813e+01,4.217993453100883130e+02,2.370516138899330993e+00,6.928203299376685997e+00,2.821715601552672315e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979297235880630978e+01,4.218089498405868767e+02,2.373300558749525280e+00,6.928203299376685997e+00,2.823382268219338798e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979441573446489144e+01,4.218185539068820731e+02,2.376086579316122993e+00,6.928203299376685997e+00,2.825048934886005281e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979585911012347310e+01,4.218281575087071360e+02,2.378874200521734483e+00,6.928203299376685997e+00,2.826715601552671764e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979730248578205476e+01,4.218377606457952425e+02,2.381663422288925691e+00,6.928203299376685997e+00,2.828382268219338247e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.979874586144063642e+01,4.218473633178796831e+02,2.384454244540218149e+00,6.928203299376685997e+00,2.830048934886004730e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980018923709921808e+01,4.218569655246937486e+02,2.387246667198089423e+00,6.928203299376685997e+00,2.831715601552671213e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980163261275779973e+01,4.218665672659706729e+02,2.390040690184971783e+00,6.928203299376685997e+00,2.833382268219337696e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980307598841638139e+01,4.218761685414437466e+02,2.392836313423253536e+00,6.928203299376685997e+00,2.835048934886004179e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980451936407496305e+01,4.218857693508462603e+02,2.395633536835279020e+00,6.928203299376685997e+00,2.836715601552670662e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980596273973354471e+01,4.218953696939115048e+02,2.398432360343346836e+00,6.928203299376685997e+00,2.838382268219337146e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980740611539212637e+01,4.219049695703728275e+02,2.401232783869712506e+00,6.928203299376685997e+00,2.840048934886003629e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.980884949105070802e+01,4.219145689799635761e+02,2.404034807336586255e+00,6.928203299376685997e+00,2.841715601552670112e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981029286670928968e+01,4.219241679224170980e+02,2.406838430666133899e+00,6.928203299376685997e+00,2.843382268219336595e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981173624236787134e+01,4.219337663974667407e+02,2.409643653780477290e+00,6.928203299376685997e+00,2.845048934886003078e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981317961802645300e+01,4.219433644048459087e+02,2.412450476601693428e+00,6.928203299376685997e+00,2.846715601552669561e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981462299368503466e+01,4.219529619442879493e+02,2.415258899051814900e+00,6.928203299376685997e+00,2.848382268219336044e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981606636934361632e+01,4.219625590155262671e+02,2.418068921052830333e+00,6.928203299376685997e+00,2.850048934886002527e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981750974500219797e+01,4.219721556182943232e+02,2.420880542526683055e+00,6.928203299376685997e+00,2.851715601552669010e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.981895312066077963e+01,4.219817517523255219e+02,2.423693763395272871e+00,6.928203299376685997e+00,2.853382268219335494e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982039649631936129e+01,4.219913474173532677e+02,2.426508583580454737e+00,6.928203299376685997e+00,2.855048934886001977e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982183987197794295e+01,4.220009426131110786e+02,2.429325003004039196e+00,6.928203299376685997e+00,2.856715601552668460e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982328324763652461e+01,4.220105373393323589e+02,2.432143021587791942e+00,6.928203299376685997e+00,2.858382268219334943e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982472662329510626e+01,4.220201315957506267e+02,2.434962639253435146e+00,6.928203299376685997e+00,2.860048934886001426e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982616999895368792e+01,4.220297253820994001e+02,2.437783855922646126e+00,6.928203299376685997e+00,2.861715601552667909e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982761337461226958e+01,4.220393186981121403e+02,2.440606671517057347e+00,6.928203299376685997e+00,2.863382268219334392e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.982905675027085124e+01,4.220489115435223653e+02,2.443431085958257754e+00,6.928203299376685997e+00,2.865048934886000875e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983050012592943290e+01,4.220585039180635931e+02,2.446257099167790994e+00,6.928203299376685997e+00,2.866715601552667358e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983194350158801456e+01,4.220680958214693987e+02,2.449084711067156750e+00,6.928203299376685997e+00,2.868382268219333842e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983338687724659621e+01,4.220776872534733570e+02,2.451913921577810296e+00,6.928203299376685997e+00,2.870048934886000325e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983483025290517787e+01,4.220872782138089860e+02,2.454744730621162496e+00,6.928203299376685997e+00,2.871715601552666808e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983627362856375953e+01,4.220968687022099175e+02,2.457577138118579807e+00,6.928203299376685997e+00,2.873382268219333291e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983771700422234119e+01,4.221064587184097263e+02,2.460411143991384275e+00,6.928203299376685997e+00,2.875048934885999774e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.983916037988092285e+01,4.221160482621420442e+02,2.463246748160853539e+00,6.928203299376685997e+00,2.876715601552666257e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984060375553950450e+01,4.221256373331405030e+02,2.466083950548220827e+00,6.928203299376685997e+00,2.878382268219332740e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984204713119808616e+01,4.221352259311386774e+02,2.468922751074674959e+00,6.928203299376685997e+00,2.880048934885999223e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984349050685666782e+01,4.221448140558702562e+02,2.471763149661359904e+00,6.928203299376685997e+00,2.881715601552665706e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984493388251524948e+01,4.221544017070689279e+02,2.474605146229376107e+00,6.928203299376685997e+00,2.883382268219332190e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984637725817383114e+01,4.221639888844683242e+02,2.477448740699779162e+00,6.928203299376685997e+00,2.885048934885998673e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984782063383241280e+01,4.221735755878021905e+02,2.480293932993580697e+00,6.928203299376685997e+00,2.886715601552665156e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.984926400949099445e+01,4.221831618168041587e+02,2.483140723031747044e+00,6.928203299376685997e+00,2.888382268219331639e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985070738514957611e+01,4.221927475712080309e+02,2.485989110735201013e+00,6.928203299376685997e+00,2.890048934885998122e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985215076080815777e+01,4.222023328507474389e+02,2.488839096024820563e+00,6.928203299376685997e+00,2.891715601552664605e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985359413646673943e+01,4.222119176551561850e+02,2.491690678821439686e+00,6.928203299376685997e+00,2.893382268219331088e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985503751212532109e+01,4.222215019841680146e+02,2.494543859045847523e+00,6.928203299376685997e+00,2.895048934885997571e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985648088778390274e+01,4.222310858375166731e+02,2.497398636618788803e+00,6.928203299376685997e+00,2.896715601552664054e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985792426344248440e+01,4.222406692149359628e+02,2.500255011460964738e+00,6.928203299376685997e+00,2.898382268219330538e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.985936763910106606e+01,4.222502521161596860e+02,2.503112983493031241e+00,6.928203299376685997e+00,2.900048934885997021e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986081101475964772e+01,4.222598345409216449e+02,2.505972552635600259e+00,6.928203299376685997e+00,2.901715601552663504e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986225439041822938e+01,4.222694164889556987e+02,2.508833718809239333e+00,6.928203299376685997e+00,2.903382268219329987e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986369776607681104e+01,4.222789979599955927e+02,2.511696481934471592e+00,6.928203299376685997e+00,2.905048934885996470e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986514114173539269e+01,4.222885789537752430e+02,2.514560841931775759e+00,6.928203299376685997e+00,2.906715601552662953e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986658451739397435e+01,4.222981594700285086e+02,2.517426798721586145e+00,6.928203299376685997e+00,2.908382268219329436e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986802789305255601e+01,4.223077395084892487e+02,2.520294352224293100e+00,6.928203299376685997e+00,2.910048934885995919e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.986947126871113767e+01,4.223173190688913223e+02,2.523163502360242560e+00,6.928203299376685997e+00,2.911715601552662402e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987091464436971933e+01,4.223268981509687023e+02,2.526034249049735614e+00,6.928203299376685997e+00,2.913382268219328886e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987235802002830098e+01,4.223364767544552478e+02,2.528906592213029381e+00,6.928203299376685997e+00,2.915048934885995369e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987380139568688264e+01,4.223460548790848748e+02,2.531780531770336573e+00,6.928203299376685997e+00,2.916715601552661852e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987524477134546430e+01,4.223556325245915559e+02,2.534656067641825494e+00,6.928203299376685997e+00,2.918382268219328335e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987668814700404596e+01,4.223652096907092641e+02,2.537533199747620039e+00,6.928203299376685997e+00,2.920048934885994818e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987813152266262762e+01,4.223747863771719153e+02,2.540411928007800135e+00,6.928203299376685997e+00,2.921715601552661301e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.987957489832120928e+01,4.223843625837135392e+02,2.543292252342400861e+00,6.928203299376685997e+00,2.923382268219327784e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.988101827397979093e+01,4.223939383100681084e+02,2.546174172671413327e+00,6.928203299376685997e+00,2.925048934885994267e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.988246164963837259e+01,4.224035135559695959e+02,2.549057688914784237e+00,6.928203299376685997e+00,2.926715601552660750e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +6.988390502529695425e+01,4.224130883211520882e+02,2.551942800992415439e+00,6.928203299376685997e+00,2.928382268219327234e-01,0.000000000000000000e+00,4.563496123041156649e-02,2.302158509785702091e-08,0.000000000000000000e+00 +6.988534840095553591e+01,4.224226626053495579e+02,2.554829508824165707e+00,6.928203299376685997e+00,2.930048934885993717e-01,3.322879555212852534e-11,4.563496123041156649e-02,7.849209439114406407e-05,0.000000000000000000e+00 +6.988679177661411757e+01,4.224322364082960917e+02,2.557717812329848073e+00,6.928203299376733959e+00,2.931715601552660200e-01,1.133268072305351252e-07,4.563496123041156649e-02,-8.005191438800828285e-01,0.000000000000000000e+00 +6.988823515227269922e+01,4.224418097297257191e+02,2.560607711429232047e+00,6.928203299540307114e+00,2.933382268219326683e-01,-1.155336519694961624e-03,4.563496123041156649e-02,-9.999828653303544090e-01,0.000000000000000000e+00 +6.988967852793123825e+01,4.224513825693725835e+02,2.563499206042042733e+00,6.928201631955697160e+00,2.935048934885993166e-01,-2.598687446473776485e-03,4.563496123041156649e-02,-9.999904987201848616e-01,0.000000000000000000e+00 +6.989112190393719004e+01,4.224609549269707145e+02,2.566392296087961267e+00,6.928197881072589936e+00,2.936715601552659649e-01,-4.042049738511900754e-03,4.563496123041156649e-02,-9.999928881646183987e-01,0.000000000000000000e+00 +6.989256528072458252e+01,4.224705268022541986e+02,2.569286981486623489e+00,6.928192046871823884e+00,2.938382268219326132e-01,-5.485416260845994881e-03,4.563496123041156649e-02,-9.999939200304838183e-01,0.000000000000000000e+00 +6.989400865872742941e+01,4.224800981949571792e+02,2.572183262157621719e+00,6.928184129342656483e+00,2.940048934885992615e-01,-6.928785488005330395e-03,4.563496123041156649e-02,-9.999943420728373278e-01,0.000000000000000000e+00 +6.989545203837977283e+01,4.224896691048137995e+02,2.575081138020503424e+00,6.928174128474667626e+00,2.941715601552659098e-01,-8.372156973814435729e-03,4.563496123041156649e-02,-9.999943661511332405e-01,0.000000000000000000e+00 +6.989689542011564072e+01,4.224992395315581462e+02,2.577980608994772105e+00,6.928162044256201746e+00,2.943382268219325582e-01,-9.815530577894585745e-03,4.563496123041156649e-02,-9.999939994849200708e-01,0.000000000000000000e+00 +6.989833880436908942e+01,4.225088094749244192e+02,2.580881674999887299e+00,6.928147876673926397e+00,2.945048934885992065e-01,-1.125890617029136863e-02,4.563496123041156649e-02,-9.999930685311353429e-01,0.000000000000000000e+00 +6.989978219157416106e+01,4.225183789346468188e+02,2.583784335955263245e+00,6.928131625712817154e+00,2.946715601552658548e-01,-1.270228337056442808e-02,4.563496123041156649e-02,-9.999909389001284676e-01,0.000000000000000000e+00 +6.990122558216491200e+01,4.225279479104594316e+02,2.586688591780271107e+00,6.928113291356519099e+00,2.948382268219325031e-01,-1.414566088260360219e-02,4.563496123041156649e-02,-9.999845982421030621e-01,0.000000000000000000e+00 +6.990266897657539857e+01,4.225375164020965144e+02,2.589594442394236751e+00,6.928092873588668432e+00,2.950048934885991514e-01,-1.558903306228443843e-02,4.563496123041156649e-02,-9.998753531359825253e-01,0.000000000000000000e+00 +6.990411237523971977e+01,4.225470844092922675e+02,2.592501887716442077e+00,6.928070372399168342e+00,2.951715601552657997e-01,-1.703225181148411427e-02,4.563496123041156649e-02,9.999834453612557184e-01,0.000000000000000000e+00 +6.990555577859194614e+01,4.225566519317809480e+02,2.595410927666125023e+00,6.928045787989807636e+00,2.953382268219324480e-01,-1.558887235427608257e-02,4.563496123041156649e-02,9.999928814644696295e-01,0.000000000000000000e+00 +6.990699918706614824e+01,4.225662189692967559e+02,2.598321562162478671e+00,6.928023286879348319e+00,2.955048934885990963e-01,-1.414547415503493617e-02,4.563496123041156649e-02,9.999956943442187551e-01,0.000000000000000000e+00 +6.990844260022829815e+01,4.225757855215739482e+02,2.601233791124652139e+00,6.928002869115768014e+00,2.956715601552657446e-01,-1.270206720771987347e-02,4.563496123041156649e-02,9.999970220166489732e-01,0.000000000000000000e+00 +6.990988601764438215e+01,4.225853515883467821e+02,2.604147614471750138e+00,6.927984534730740052e+00,2.958382268219323930e-01,-1.125865409010336736e-02,4.563496123041156649e-02,9.999977836803165543e-01,0.000000000000000000e+00 +6.991132943888037232e+01,4.225949171693495146e+02,2.607063032122832968e+00,6.927968283750337797e+00,2.960048934885990413e-01,-9.815236053202131689e-03,4.563496123041156649e-02,9.999982709904861045e-01,0.000000000000000000e+00 +6.991277286350219811e+01,4.226044822643164594e+02,2.609980043996916965e+00,6.927954116196949563e+00,2.961715601552656896e-01,-8.371813927070292580e-03,4.563496123041156649e-02,9.999986067744931484e-01,0.000000000000000000e+00 +6.991421629107580316e+01,4.226140468729818735e+02,2.612898650012974056e+00,6.927942032089886126e+00,2.963382268219323379e-01,-6.928388364483808320e-03,4.563496123041156649e-02,9.999988494794083138e-01,0.000000000000000000e+00 +6.991565972116711691e+01,4.226236109950801279e+02,2.615818850089931757e+00,6.927932031445636518e+00,2.965048934885989862e-01,-5.484959933865505080e-03,4.563496123041156649e-02,9.999990319667478866e-01,0.000000000000000000e+00 +6.991710315334205461e+01,4.226331746303455361e+02,2.618740644146673624e+00,6.927924114277989709e+00,2.966715601552656345e-01,-4.041529156213836439e-03,4.563496123041156649e-02,9.999991725968846445e-01,0.000000000000000000e+00 +6.991854658716653148e+01,4.226427377785124690e+02,2.621664032102038355e+00,6.927918280598102996e+00,2.968382268219322828e-01,-2.598096526032519886e-03,4.563496123041156649e-02,9.999992841815720235e-01,0.000000000000000000e+00 +6.991999002220646275e+01,4.226523004393152405e+02,2.624589013874820687e+00,6.927914530414540195e+00,2.970048934885989311e-01,-1.154662519338030139e-03,4.563496123041156649e-02,9.999993744104311855e-01,0.000000000000000000e+00 +6.992143345802774945e+01,4.226618626124882212e+02,2.627515589383771388e+00,6.927912863733298288e+00,2.971715601552655794e-01,2.887723989484040628e-04,4.563496123041156649e-02,9.999994479825300431e-01,0.000000000000000000e+00 +6.992287689419629260e+01,4.226714242977658387e+02,2.630443758547596822e+00,6.927913280557823406e+00,2.973382268219322278e-01,1.732207770685531599e-03,4.563496123041156649e-02,9.999995091641861178e-01,0.000000000000000000e+00 +6.992432033027797900e+01,4.226809854948824636e+02,2.633373521284958940e+00,6.927915780889020603e+00,2.975048934885988761e-01,3.175643143888799876e-03,4.563496123041156649e-02,9.999995613627193913e-01,0.000000000000000000e+00 +6.992576376583872388e+01,4.226905462035725236e+02,2.636304877514475287e+00,6.927920364725262736e+00,2.976715601552655244e-01,4.619078071491795542e-03,4.563496123041156649e-02,9.999996049950268251e-01,0.000000000000000000e+00 +6.992720720044442828e+01,4.227001064235703893e+02,2.639237827154718996e+00,6.927927032062397572e+00,2.978382268219321727e-01,6.062512107031093125e-03,4.563496123041156649e-02,9.999996426030824948e-01,0.000000000000000000e+00 +6.992865063366099321e+01,4.227096661546105452e+02,2.642172370124219682e+00,6.927935782893748673e+00,2.980048934885988210e-01,7.505944807714993484e-03,4.563496123041156649e-02,9.999996745910407769e-01,0.000000000000000000e+00 +6.993009406505431969e+01,4.227192253964274187e+02,2.645108506341462107e+00,6.927946617210120728e+00,2.981715601552654693e-01,8.949375731339040407e-03,4.563496123041156649e-02,9.999997039144645772e-01,0.000000000000000000e+00 +6.993153749419032295e+01,4.227287841487554942e+02,2.648046235724887065e+00,6.927959534999800439e+00,2.983382268219321176e-01,1.039280443997011791e-02,4.563496123041156649e-02,9.999997279807515405e-01,0.000000000000000000e+00 +6.993298092063493243e+01,4.227383424113292563e+02,2.650985558192890945e+00,6.927974536248562742e+00,2.985048934885987659e-01,1.183623049193937259e-02,4.563496123041156649e-02,9.999997501590770499e-01,0.000000000000000000e+00 +6.993442434395406337e+01,4.227479001838831891e+02,2.653926473663825725e+00,6.927991620939665474e+00,2.986715601552654142e-01,1.327965345044892879e-02,4.563496123041156649e-02,9.999997691230242403e-01,0.000000000000000000e+00 +6.993586776371365943e+01,4.227574574661517772e+02,2.656868982055999417e+00,6.928010789053856477e+00,2.988382268219320625e-01,1.472307287679545072e-02,4.563496123041156649e-02,9.999997873765283929e-01,0.000000000000000000e+00 +6.993731117947966425e+01,4.227670142578695618e+02,2.659813083287675628e+00,6.928032040569370942e+00,2.990048934885987109e-01,1.616648833590026563e-02,4.563496123041156649e-02,9.999998018752876972e-01,0.000000000000000000e+00 +6.993875459081803569e+01,4.227765705587710841e+02,2.662758777277073996e+00,6.928055375461936727e+00,2.991715601552653592e-01,1.760989938830224630e-02,4.563496123041156649e-02,9.999998159631825478e-01,0.000000000000000000e+00 +6.994019799729476006e+01,4.227861263685908852e+02,2.665706063942369308e+00,6.928080793704768148e+00,2.993382268219320075e-01,1.905330559937992024e-02,4.563496123041156649e-02,9.999998287147465748e-01,0.000000000000000000e+00 +6.994164139847580941e+01,4.227956816870635635e+02,2.668654943201692831e+00,6.928108295268573080e+00,2.995048934885986558e-01,2.049670653319033559e-02,4.563496123041156649e-02,9.999998400507903451e-01,0.000000000000000000e+00 +6.994308479392718425e+01,4.228052365139236599e+02,2.671605414973130976e+00,6.928137880121551184e+00,2.996715601552653041e-01,2.194010175369190060e-02,4.563496123041156649e-02,9.999998503120985927e-01,0.000000000000000000e+00 +6.994452818321489929e+01,4.228147908489057158e+02,2.674557479174726193e+00,6.928169548229393904e+00,2.998382268219319524e-01,2.338349082535188042e-02,4.563496123041156649e-02,9.999998598331398814e-01,0.000000000000000000e+00 +6.994597156590499765e+01,4.228243446917443862e+02,2.677511135724476965e+00,6.928203299555285355e+00,3.000048934885986007e-01,2.482687331313858034e-02,4.563496123041156649e-02,9.999998467730192298e-01,-6.928203299555291128e-01 +6.994741494156353667e+01,4.228338980421742690e+02,2.680466384540337366e+00,6.928239134059903215e+00,3.001715601552652490e-01,2.627024875051526404e-02,4.463496123041156560e-02,9.999998319165770422e-01,-6.928239134059909210e-01 +6.994885830975658791e+01,4.228434508999300192e+02,2.683423225540216617e+00,6.928277051701373423e+00,3.003345697415719662e-01,2.771361670096674293e-02,4.363496123041156471e-02,9.999998143001819217e-01,-6.928277051701379197e-01 +6.995030167005026556e+01,4.228530032755654133e+02,2.686381623708195221e+00,6.928317052435313705e+00,3.004939225741884989e-01,2.915697672660921141e-02,4.263496123041156383e-02,9.999997938064699721e-01,-6.928317052435319923e-01 +6.995174502201068378e+01,4.228625551796503714e+02,2.689341544036721210e+00,6.928359136214831793e+00,3.006496189724283119e-01,3.060032838941304997e-02,4.163496123041156294e-02,9.999997686063724078e-01,-6.928359136214837788e-01 +6.995318836520398520e+01,4.228721066227706729e+02,2.692302951526427179e+00,6.928403302990525425e+00,3.008016592482510854e-01,3.204367124873356426e-02,4.063496123041156205e-02,9.999997385697577679e-01,-6.928403302990531198e-01 +6.995463169919634083e+01,4.228816576155273310e+02,2.695265811185945992e+00,6.928449552710478798e+00,3.009500437062653799e-01,3.348700486376449820e-02,3.963496123041156116e-02,9.999997001492728632e-01,-6.928449552710485015e-01 +6.995607502355396434e+01,4.228912081685365365e+02,2.698230088031725149e+00,6.928497885320262561e+00,3.010947726437308014e-01,3.493032878860719698e-02,3.863496123041156027e-02,9.999996502173409407e-01,-6.928497885320268335e-01 +6.995751833784308360e+01,4.229007582924290887e+02,2.701195747087842935e+00,6.928548300762926715e+00,3.012358463505606654e-01,3.637364257287793723e-02,3.763496123041155939e-02,9.999995843606338530e-01,-6.928548300762933376e-01 +6.995896164162995490e+01,4.229103079978500546e+02,2.704162753385823681e+00,6.928600798978994391e+00,3.013732651093241066e-01,3.781694575985365681e-02,3.663496123041155850e-02,9.999994917634780212e-01,-6.928600798978999942e-01 +6.996040493448086295e+01,4.229198572954585416e+02,2.707131071964451241e+00,6.928655379906452971e+00,3.015070291952485215e-01,3.926023787723302572e-02,3.563496123041155761e-02,9.999993522223874498e-01,-6.928655379906458744e-01 +6.996184821596214931e+01,4.229294061959271858e+02,2.710100667869585145e+00,6.928712043480731886e+00,3.016371388762216221e-01,4.070351842358903294e-02,3.463496123041155672e-02,9.999991195158342006e-01,-6.928712043480738103e-01 +6.996329148564015554e+01,4.229389547099418110e+02,2.713071506153973633e+00,6.928770789634660865e+00,3.017635944127936010e-01,4.214678683082027227e-02,3.363496123041155583e-02,9.999986536038166784e-01,-6.928770789634667304e-01 +6.996473474308128004e+01,4.229485028482011444e+02,2.716043551877068918e+00,6.928831618298374018e+00,3.018863960581794070e-01,4.359004232875043905e-02,3.263496123041155494e-02,9.999972537018061436e-01,-6.928831618298380013e-01 +6.996617798785194964e+01,4.229580506214164188e+02,2.719016770104840219e+00,6.928894529399018509e+00,3.020055440582605222e-01,4.503328313584540471e-02,3.163496123041155406e-02,-7.063994335932310964e-01,-6.928894529399024504e-01 +6.996762121951864799e+01,4.229675980403109179e+02,2.721991125909588582e+00,6.928959522859295284e+00,3.021210386515870705e-01,4.401378510395011906e-02,3.063496123041155317e-02,-9.999971629459900591e-01,-6.928959522859301501e-01 +6.996906443764785877e+01,4.229771451156196918e+02,2.724966584369759470e+00,6.929023044351892757e+00,3.022328800693797612e-01,4.257057106922108869e-02,2.963496123041155228e-02,-9.999985626811780381e-01,-6.929023044351898530e-01 +6.997050764254643695e+01,4.229866918580892730e+02,2.727943110569757135e+00,6.929084482408595314e+00,3.023410685355316097e-01,4.112736824498410687e-02,2.863496123041155139e-02,-9.999990293175298195e-01,-6.929084482408601753e-01 +6.997195083464856680e+01,4.229962382784771648e+02,2.730920669599757655e+00,6.929143837101627845e+00,3.024456042666098243e-01,3.968417754373590456e-02,2.763496123041155050e-02,-9.999992610619564681e-01,-6.929143837101633396e-01 +6.997339401438838991e+01,4.230057843875516141e+02,2.733899226555521533e+00,6.929201108502650364e+00,3.025464874718575281e-01,3.824099887033684947e-02,2.663496123041154962e-02,-9.999994013635948864e-01,-6.929201108502656137e-01 +6.997483718220000526e+01,4.230153301960910994e+02,2.736878746538208063e+00,6.929256296681304050e+00,3.026437183531954789e-01,3.679783192265435182e-02,2.563496123041154873e-02,-9.999994926072440782e-01,-6.929256296681309824e-01 +6.997628033851748341e+01,4.230248757148841037e+02,2.739859194654186592e+00,6.929309401704912830e+00,3.027372971052235129e-01,3.535467633742050281e-02,2.463496123041154784e-02,-9.999995588371096700e-01,-6.929309401704918381e-01 +6.997772348377486651e+01,4.230344209547287164e+02,2.742840536014850006e+00,6.929360423638395439e+00,3.028272239152223766e-01,3.391153171670106131e-02,2.363496123041154695e-02,-9.999996083136867275e-01,-6.929360423638402100e-01 +6.997916661840615404e+01,4.230439659264322358e+02,2.745822735736427322e+00,6.929409362544215689e+00,3.029134989631549479e-01,3.246839765067333766e-02,2.263496123041154606e-02,-9.999996458800362031e-01,-6.929409362544221018e-01 +6.998060974284530289e+01,4.230535106408107708e+02,2.748805758939796284e+00,6.929456218482365593e+00,3.029961224216679017e-01,3.102527372255708266e-02,2.163496123041154517e-02,-9.999996759468224861e-01,-6.929456218482371588e-01 +6.998205285752626992e+01,4.230630551086890705e+02,2.751789570750294622e+00,6.929500991510355590e+00,3.030750944560929305e-01,2.958215950923741983e-02,2.063496123041154429e-02,-9.999997007862903020e-01,-6.929500991510362251e-01 +6.998349596288295515e+01,4.230725993408998988e+02,2.754774136297533538e+00,6.929543681683205669e+00,3.031504152244481887e-01,2.813905458434970419e-02,1.963496123041154340e-02,-9.999997201055682572e-01,-6.929543681683211220e-01 +6.998493905934924442e+01,4.230821433482838643e+02,2.757759420715209409e+00,6.929584289053440926e+00,3.032220848774394573e-01,2.669595852198003091e-02,1.863496123041154251e-02,-9.999997374439545395e-01,-6.929584289053446478e-01 +6.998638214735898089e+01,4.230916871416890217e+02,2.760745389140915051e+00,6.929622813671092452e+00,3.032901035584614213e-01,2.525287089113377806e-02,1.763496123041154162e-02,-9.999997516430984001e-01,-6.929622813671098003e-01 +6.998782522734599354e+01,4.231012307319704746e+02,2.763732006715951872e+00,6.929659255583690225e+00,3.033544714035987799e-01,2.380979126251351469e-02,1.663496123041154073e-02,-9.999997636708292115e-01,-6.929659255583696664e-01 +6.998926829974409713e+01,4.231107741299900340e+02,2.766719238585142460e+00,6.929693614836265780e+00,3.034151885416273564e-01,2.236671920544943543e-02,1.563496123041153985e-02,-9.999997740621746622e-01,-6.929693614836271998e-01 +6.999071136498706380e+01,4.231203173466158205e+02,2.769707049896641404e+00,6.929725891471350430e+00,3.034722550940150976e-01,2.092365428852265355e-02,1.463496123041153896e-02,-9.999997829193699728e-01,-6.929725891471356647e-01 +6.999215442350865146e+01,4.231298603927219801e+02,2.772695405801746560e+00,6.929756085528974374e+00,3.035256711749231284e-01,1.948059608018846284e-02,1.363496123041153807e-02,-9.999997907648473516e-01,-6.929756085528980813e-01 +6.999359747574260382e+01,4.231394032791882864e+02,2.775684271454711194e+00,6.929784197046666705e+00,3.035754368912065293e-01,1.803754414816867435e-02,1.263496123041153718e-02,-9.999997976882303297e-01,-6.929784197046673366e-01 +6.999504052212263616e+01,4.231489460168997425e+02,2.778673612012554806e+00,6.929810226059454514e+00,3.036215523424153351e-01,1.659449806007489217e-02,1.163496123041153629e-02,-9.999998029197639804e-01,-6.929810226059460732e-01 +6.999648356308246377e+01,4.231584886167462400e+02,2.781663392634874832e+00,6.929834172599862896e+00,3.036640176207952013e-01,1.515145738464733320e-02,1.063496123041153540e-02,-9.999998082425212154e-01,-6.929834172599869113e-01 +6.999792659905575931e+01,4.231680310896222750e+02,2.784653578483657910e+00,6.929856036697916721e+00,3.037028328112882369e-01,1.370842168806968818e-02,9.634961230411534516e-03,-9.999998128741273140e-01,-6.929856036697922272e-01 +6.999936963047618121e+01,4.231775734464264929e+02,2.787644134723090694e+00,6.929875818381137087e+00,3.037379979915337258e-01,1.226539053766987665e-02,8.634961230411533628e-03,-9.999998160258680713e-01,-6.929875818381137087e-01 +7.000081265777740214e+01,4.231871156980613478e+02,2.790635026519371564e+00,6.929893517674543091e+00,3.037695132318685154e-01,1.082236350192787924e-02,7.634961230411533607e-03,-9.999998198884296752e-01,-6.929893517674542425e-01 +7.000225568139306631e+01,4.231966578554328180e+02,2.793626219040520553e+00,6.929909134600653609e+00,3.037973785953279049e-01,9.379340146175078885e-03,6.634961230411533586e-03,-9.999998219543299038e-01,-6.929909134600653609e-01 +7.000369870175678955e+01,4.232061999294498946e+02,2.796617677456191497e+00,6.929922669179482853e+00,3.038215941376458673e-01,7.936320039372543600e-03,5.634961230411533566e-03,-9.999998248281748436e-01,-6.929922669179483519e-01 +7.000514171930220186e+01,4.232157419310244109e+02,2.799609366937482857e+00,6.929934121428545701e+00,3.038421599072556600e-01,6.493302746732859849e-03,4.634961230411533545e-03,-9.999998259898218445e-01,-6.929934121428545923e-01 +7.000658473446291907e+01,4.232252838710704737e+02,2.802601252656747199e+00,6.929943491362852370e+00,3.038590759452901580e-01,5.050287837113948998e-03,3.634961230411533524e-03,-9.999998276047210588e-01,-6.929943491362852148e-01 +7.000802774767254277e+01,4.232348257605043500e+02,2.805593299787404238e+00,6.929950778994913740e+00,3.038723422855821310e-01,3.607274876256371006e-03,2.634961230411533503e-03,-9.999998284196996989e-01,-6.929950778994913296e-01 +7.000947075936467456e+01,4.232443676102438417e+02,2.808585473503750318e+00,6.929955984334736918e+00,3.038819589546646882e-01,2.164263431715151946e-03,1.634961230411533482e-03,-9.999998288814225811e-01,-6.929955984334736918e-01 +7.001091376997291604e+01,4.232539094312081716e+02,2.811577738980769681e+00,6.929959107389827899e+00,3.038879259717713333e-01,7.212530704055905790e-04,6.349612304115334616e-04,-9.999998298567818189e-01,-6.929959107389827011e-01 +7.001235677993084039e+01,4.232634512343174151e+02,2.814570061393944389e+00,6.929960148165190681e+00,3.038902433488360755e-01,-7.217566420044329526e-04,-3.650387695884665593e-04,-9.999998287940169428e-01,-6.929960148165190681e-01 +7.001379978967204920e+01,4.232729930304922732e+02,2.817562405919066926e+00,6.929959106663325485e+00,3.038889110904937074e-01,-2.164766136162608792e-03,-1.365038769588466580e-03,-9.999998282535517147e-01,-6.929959106663325930e-01 +7.001524279963012987e+01,4.232825348306537308e+02,2.820554737732049233e+00,6.929955982884234089e+00,3.038839291940797493e-01,-3.607775846410433192e-03,-2.365038769588466601e-03,-9.999998278036996702e-01,-6.929955982884233867e-01 +7.001668581023866977e+01,4.232920766457225454e+02,2.823547022008734420e+00,6.929950776825414493e+00,3.038752976496303382e-01,-5.050786206466864256e-03,-3.365038769588466622e-03,-9.999998261533742383e-01,-6.929950776825414271e-01 +7.001812882193125631e+01,4.233016184866190201e+02,2.826539223924707134e+00,6.929943488481861813e+00,3.038630164398822830e-01,-6.493797648189500275e-03,-4.365038769588466643e-03,-9.999998245644193817e-01,-6.929943488481862257e-01 +7.001957183514147687e+01,4.233111603642626619e+02,2.829531308655104826e+00,6.929934117846070940e+00,3.038470855402728432e-01,-7.936810605259787474e-03,-5.365038769588466663e-03,-9.999998221596588799e-01,-6.929934117846070496e-01 +7.002101485030294725e+01,4.233207022895716705e+02,2.832523241374428125e+00,6.929922664908033880e+00,3.038275049189396171e-01,-9.379825510097691138e-03,-6.365038769588466684e-03,-9.999998197617537832e-01,-6.929922664908034768e-01 +7.002245786784925485e+01,4.233302442734627675e+02,2.835514987256351649e+00,6.929909129655241529e+00,3.038042745367202091e-01,-1.082284279631588395e-02,-7.365038769588466705e-03,-9.999998160543653869e-01,-6.929909129655247302e-01 +7.002390088821401548e+01,4.233397863268506853e+02,2.838506511473534832e+00,6.929893512072681894e+00,3.037773943471519522e-01,-1.226586289563443705e-02,-8.365038769588467593e-03,-9.999998131271186086e-01,-6.929893512072687889e-01 +7.002534391183084495e+01,4.233493284606478824e+02,2.841497779197433182e+00,6.929875812142842761e+00,3.037468642964715193e-01,-1.370888624279699083e-02,-9.365038769588468481e-03,-9.999998079449103905e-01,-6.929875812142849423e-01 +7.002678693913335906e+01,4.233588706857642023e+02,2.844488755598109098e+00,6.929856029845707255e+00,3.037126843236144791e-01,-1.515191326817696277e-02,-1.036503876958846937e-02,-9.999998030112619007e-01,-6.929856029845713472e-01 +7.002822997055521625e+01,4.233684130131064194e+02,2.847479405844042688e+00,6.929834165158760051e+00,3.036748543602148520e-01,-1.659494440577121213e-02,-1.136503876958847026e-02,-9.999997978376256036e-01,-6.929834165158766934e-01 +7.002967300653006077e+01,4.233779554535780107e+02,2.850469695101942147e+00,6.929810218056982052e+00,3.036333743306044997e-01,-1.803798008888371843e-02,-1.236503876958847115e-02,-9.999997906495825539e-01,-6.929810218056988713e-01 +7.003111604749155106e+01,4.233874980180787020e+02,2.853459588536555902e+00,6.929784188512851273e+00,3.035882441518126251e-01,-1.948102074827131117e-02,-1.336503876958847203e-02,-9.999997826520929944e-01,-6.929784188512856380e-01 +7.003255909387337397e+01,4.233970407175040691e+02,2.856449051310482989e+00,6.929756076496346395e+00,3.035394637335649959e-01,-2.092406681644431651e-02,-1.436503876958847292e-02,-9.999997741907232784e-01,-6.929756076496351724e-01 +7.003400214610921637e+01,4.234065835627453680e+02,2.859438048583984315e+00,6.929725881974944102e+00,3.034870329782833331e-01,-2.236711872642773227e-02,-1.536503876958847381e-02,-9.999997638986509729e-01,-6.929725881974950763e-01 +7.003544520463279355e+01,4.234161265646889092e+02,2.862426545514793919e+00,6.929693604913618188e+00,3.034309517810843682e-01,-2.381017690929146044e-02,-1.636503876958847470e-02,-9.999997512558245205e-01,-6.929693604913623739e-01 +7.003688826987783500e+01,4.234256697342159441e+02,2.865414507257930676e+00,6.929659245274842228e+00,3.033712200297791206e-01,-2.525324179537351971e-02,-1.736503876958847559e-02,-9.999997374419014040e-01,-6.929659245274848445e-01 +7.003833134227808443e+01,4.234352130822021536e+02,2.868401898965508234e+00,6.929622803018590460e+00,3.033078376048720659e-01,-2.669631381673413101e-02,-1.836503876958847647e-02,-9.999997206446826770e-01,-6.929622803018596899e-01 +7.003977442226732819e+01,4.234447566195173067e+02,2.871388685786548489e+00,6.929584278102335126e+00,3.032408043795599695e-01,-2.813939340283956245e-02,-1.936503876958847736e-02,-9.999997003252285577e-01,-6.929584278102340900e-01 +7.004121751027935261e+01,4.234543003570249766e+02,2.874374832866791518e+00,6.929543670481050022e+00,3.031701202197311096e-01,-2.958248098240079740e-02,-2.036503876958847825e-02,-9.999996759383100731e-01,-6.929543670481056461e-01 +7.004266060674797245e+01,4.234638443055820858e+02,2.877360305348508174e+00,6.929500980107211383e+00,3.030957849839640561e-01,-3.102557698336573522e-02,-2.136503876958847914e-02,-9.999996460794737807e-01,-6.929500980107217156e-01 +7.004410371210703090e+01,4.234733884760386218e+02,2.880345068370310901e+00,6.929456206930798778e+00,3.030177985235265603e-01,-3.246868183168051536e-02,-2.236503876958848003e-02,-9.999996080586143199e-01,-6.929456206930804107e-01 +7.004554682679039956e+01,4.234829328792372394e+02,2.883329087066966334e+00,6.929409350899297770e+00,3.029361606823743336e-01,-3.391179594943541376e-02,-2.336503876958848092e-02,-9.999995587530405849e-01,-6.929409350899303766e-01 +7.004698995123197847e+01,4.234924775260129195e+02,2.886312326569206554e+00,6.929360411957705246e+00,3.028508712971499373e-01,-3.535491975424175093e-02,-2.436503876958848180e-02,-9.999994933281567411e-01,-6.929360411957711241e-01 +7.004843308586569606e+01,4.235020224271925144e+02,2.889294752003541245e+00,6.929309390048535633e+00,3.027619301971812837e-01,-3.679805365676253742e-02,-2.536503876958848269e-02,-9.999994005465594471e-01,-6.929309390048541406e-01 +7.004987623112550921e+01,4.235115675935945774e+02,2.892276328492071169e+00,6.929256285111830671e+00,3.026693372044804708e-01,-3.824119805147335738e-02,-2.636503876958848358e-02,-9.999992614894152032e-01,-6.929256285111836666e-01 +7.005131938744540321e+01,4.235211130360287939e+02,2.895257021152298105e+00,6.929201097085182504e+00,3.025730921337421719e-01,-3.968435330557762430e-02,-2.736503876958848447e-02,-9.999990290878555399e-01,-6.929201097085189165e-01 +7.005276255525939177e+01,4.235306587652958115e+02,2.898236795096938767e+00,6.929143825903772758e+00,3.024731947923421926e-01,-4.112751971838170956e-02,-2.836503876958848536e-02,-9.999985624546933183e-01,-6.929143825903778531e-01 +7.005420573500154546e+01,4.235402047921866711e+02,2.901215615433737405e+00,6.929084471500470244e+00,3.023696449803360831e-01,-4.257069738589716601e-02,-2.936503876958848624e-02,-9.999971637913619427e-01,-6.929084471500476239e-01 +7.005564892710594904e+01,4.235497511274826365e+02,2.904193447265277506e+00,6.929023033806124054e+00,3.022624424904573615e-01,-4.401388539710467812e-02,-3.036503876958848713e-02,-7.060902367713758343e-01,-6.929023033806130938e-01 +7.005709213200672991e+01,4.235592977819547400e+02,2.907170255688795280e+00,6.928959512751016625e+00,3.021515871081159044e-01,-4.503291828720537571e-02,-3.136503876958848802e-02,9.999972533130729868e-01,-6.928959512751022842e-01 +7.005853535013805811e+01,4.235688447663634406e+02,2.910146005795992696e+00,6.928894520426838177e+00,3.020370786113962813e-01,-4.358970411995150701e-02,-3.236503876958848891e-02,9.999986533689084744e-01,-6.928894520426844839e-01 +7.005997858180661808e+01,4.235783920914581699e+02,2.913120662672850525e+00,6.928831610385429052e+00,3.019189167710558674e-01,-4.214647439489097036e-02,-3.336503876958848980e-02,9.999991195670030475e-01,-6.928831610385435269e-01 +7.006142182657893613e+01,4.235879397679772183e+02,2.916094191399440927e+00,6.928770782706586751e+00,3.017971013505230671e-01,-4.070323089324758697e-02,-3.436503876958849069e-02,9.999993523015153762e-01,-6.928770782706592524e-01 +7.006286508402151014e+01,4.235974878066470524e+02,2.919066557049741828e+00,6.928712037465663443e+00,3.016716321058955375e-01,-3.925997438547365603e-02,-3.536503876958849157e-02,9.999994916266532474e-01,-6.928712037465669660e-01 +7.006430835370076693e+01,4.236070362181822020e+02,2.922037724691449956e+00,6.928655374735024353e+00,3.015425087859379683e-01,-3.781670543993320005e-02,-3.636503876958849246e-02,9.999995842008340130e-01,-6.928655374735031014e-01 +7.006575163518311911e+01,4.236165850132848050e+02,2.925007659385794767e+00,6.928600794584339084e+00,3.014097311320803607e-01,-3.637342455768975691e-02,-3.736503876958849335e-02,9.999996506633300752e-01,-6.928600794584345302e-01 +7.006719492803495086e+01,4.236261342026442094e+02,2.927976326187352818e+00,6.928548297080678431e+00,3.012732988784156962e-01,-3.493013221005591973e-02,-3.836503876958849424e-02,9.999997001334226532e-01,-6.928548297080684426e-01 +7.006863823182258955e+01,4.236356837969366325e+02,2.930943690143860803e+00,6.928497882288557008e+00,3.011332117516979934e-01,-3.348682885521783725e-02,-3.936503876958849513e-02,9.999997378860336905e-01,-6.928497882288562337e-01 +7.007008154611233408e+01,4.236452338068248196e+02,2.933909716296031256e+00,6.928449550269951907e+00,3.009894694713400320e-01,-3.204351494378206849e-02,-4.036503876958849601e-02,9.999997691893297569e-01,-6.928449550269958346e-01 +7.007152487047046918e+01,4.236547842429577031e+02,2.936874369677365593e+00,6.928403301084313348e+00,3.008420717494110774e-01,-3.060019091878376715e-02,-4.136503876958849690e-02,9.999997937622038258e-01,-6.928403301084319343e-01 +7.007296820446322272e+01,4.236643351159700046e+02,2.939837615313970698e+00,6.928359134788575346e+00,3.006910182906346596e-01,-2.915685722369459540e-02,-4.236503876958849779e-02,9.999998143016116670e-01,-6.928359134788582008e-01 +7.007441154765682256e+01,4.236738864364818369e+02,2.942799418224371966e+00,6.928317051437154817e+00,3.005363087923861309e-01,-2.771351429812304520e-02,-4.336503876958849868e-02,9.999998317926585001e-01,-6.928317051437161700e-01 +7.007585489961743974e+01,4.236834382150984197e+02,2.945759743419329890e+00,6.928277051081956905e+00,3.003779429446902793e-01,-2.627016258028382414e-02,-4.436503876958849957e-02,9.999998467877018182e-01,-6.928277051081963567e-01 +7.007729825991124528e+01,4.236929904624096253e+02,2.948718555901654437e+00,6.928239133772376768e+00,3.002159204302188855e-01,-2.482680250762111726e-02,-4.536503876958850046e-02,9.999998598327407562e-01,-1.870087356158507130e-01 +7.007874162810436758e+01,4.237025431889896936e+02,2.951675820666021188e+00,6.928203299555300454e+00,3.000502409242880031e-01,-2.338343451681643495e-02,-4.563496123041156649e-02,9.999998505775623547e-01,0.000000000000000000e+00 +7.008018500376290660e+01,4.237120964053968351e+02,2.954631502698787049e+00,6.928169548475105799e+00,2.998835742576213548e-01,-2.194005907394836960e-02,-4.563496123041156649e-02,9.999998395932331308e-01,0.000000000000000000e+00 +7.008162838645296233e+01,4.237216501142849552e+02,2.957585592487774306e+00,6.928137880573619789e+00,2.997169075909547065e-01,-2.049667661542679126e-02,-4.563496123041156649e-02,9.999998286855736884e-01,0.000000000000000000e+00 +7.008307177574059210e+01,4.237312043153886520e+02,2.960538089950925489e+00,6.928108295890161195e+00,2.995502409242880582e-01,-1.905328757507648851e-02,-4.563496123041156649e-02,9.999998162434855509e-01,0.000000000000000000e+00 +7.008451517119183904e+01,4.237407590084425806e+02,2.963488995006226201e+00,6.928080794461544123e+00,2.993835742576214098e-01,-1.760989238906777998e-02,-4.563496123041156649e-02,9.999998019285479822e-01,0.000000000000000000e+00 +7.008595857237273208e+01,4.237503141931812820e+02,2.966438307571707345e+00,6.928055376322074466e+00,2.992169075909547615e-01,-1.616649149407826253e-02,-4.563496123041156649e-02,9.999997871012336059e-01,0.000000000000000000e+00 +7.008740197884927170e+01,4.237598698693394113e+02,2.969386027565443342e+00,6.928032041503549010e+00,2.990502409242881132e-01,-1.472308532483931551e-02,-4.563496123041156649e-02,9.999997692789053261e-01,0.000000000000000000e+00 +7.008884539018745841e+01,4.237694260366514527e+02,2.972332154905553026e+00,6.928010790035258104e+00,2.988835742576214649e-01,-1.327967431968195278e-02,-4.563496123041156649e-02,9.999997502356774426e-01,0.000000000000000000e+00 +7.009028880595326427e+01,4.237789826948520044e+02,2.975276689510199635e+00,6.927991621943980327e+00,2.987169075909548166e-01,-1.183625891439129760e-02,-4.563496123041156649e-02,9.999997283288818428e-01,0.000000000000000000e+00 +7.009173222571264716e+01,4.237885398436756077e+02,2.978219631297590819e+00,6.927974537253986043e+00,2.985502409242881683e-01,-1.039283954713709178e-02,-4.563496123041156649e-02,9.999997027621487788e-01,0.000000000000000000e+00 +7.009317564903157916e+01,4.237980974828567469e+02,2.981160980185977749e+00,6.927959535987033846e+00,2.983835742576215200e-01,-8.949416657250843996e-03,-4.563496123041156649e-02,9.999996757168319039e-01,0.000000000000000000e+00 +7.009461907547597548e+01,4.238076556121299632e+02,2.984100736093656447e+00,6.927946618162368786e+00,2.982169075909548717e-01,-7.505990680926400913e-03,-4.563496123041156649e-02,9.999996421209186304e-01,0.000000000000000000e+00 +7.009606250461177979e+01,4.238172142312297410e+02,2.987038898938967346e+00,6.927935783796726810e+00,2.980502409242882234e-01,-6.062562061688327696e-03,-4.563496123041156649e-02,9.999996049956684230e-01,0.000000000000000000e+00 +7.009750593600492152e+01,4.238267733398905648e+02,2.989975468640294398e+00,6.927927032904324101e+00,2.978835742576215750e-01,-4.619131238708561009e-03,-4.563496123041156649e-02,9.999995613878632783e-01,0.000000000000000000e+00 +7.009894936922130171e+01,4.238363329378469189e+02,2.992910445116066409e+00,6.927920365496863297e+00,2.977169075909549267e-01,-3.175698655428820828e-03,-4.563496123041156649e-02,9.999995087642421510e-01,0.000000000000000000e+00 +7.010039280382684979e+01,4.238458930248332308e+02,2.995843828284756150e+00,6.927915781583527277e+00,2.975502409242882784e-01,-1.732264758953131097e-03,-4.563496123041156649e-02,9.999994488480841159e-01,0.000000000000000000e+00 +7.010183623938745257e+01,4.238554536005839282e+02,2.998775618064880799e+00,6.927913281170973825e+00,2.973835742576216301e-01,-2.888299939024620093e-04,-4.563496123041156649e-02,9.999993735516052862e-01,0.000000000000000000e+00 +7.010327967546902528e+01,4.238650146648334953e+02,3.001705814375001502e+00,6.927912864263339188e+00,2.972169075909549818e-01,1.154605183424963757e-03,-4.563496123041156649e-02,9.999992845853014067e-01,0.000000000000000000e+00 +7.010472311163745474e+01,4.238745762173163030e+02,3.004634417133724256e+00,6.927914530862221199e+00,2.970502409242883335e-01,2.598040319198187224e-03,-4.563496123041156649e-02,9.999991729959852860e-01,0.000000000000000000e+00 +7.010616654745864196e+01,4.238841382577667787e+02,3.007561426259699022e+00,6.927918280966682829e+00,2.968835742576216852e-01,4.041474946662520704e-03,-4.563496123041156649e-02,9.999990311028508216e-01,0.000000000000000000e+00 +7.010760998249850218e+01,4.238937007859192931e+02,3.010486841671619729e+00,6.927924114573233538e+00,2.967169075909550369e-01,5.484908587977522718e-03,-4.563496123041156649e-02,9.999988499396584851e-01,0.000000000000000000e+00 +7.010905341632292220e+01,4.239032638015082171e+02,3.013410663288225155e+00,6.927932031675813285e+00,2.965502409242883886e-01,6.928340752362971249e-03,-4.563496123041156649e-02,9.999986064658494822e-01,0.000000000000000000e+00 +7.011049684849781727e+01,4.239128273042679211e+02,3.016332891028297603e+00,6.927942032265773875e+00,2.963835742576217402e-01,8.371770915784995312e-03,-4.563496123041156649e-02,9.999982712394775985e-01,0.000000000000000000e+00 +7.011194027858908839e+01,4.239223912939327761e+02,3.019253524810664224e+00,6.927954116331831003e+00,2.962169075909550919e-01,9.815198511717736565e-03,-4.563496123041156649e-02,9.999977832653900167e-01,0.000000000000000000e+00 +7.011338370616266502e+01,4.239319557702370957e+02,3.022172564554196583e+00,6.927968283860002963e+00,2.960502409242884436e-01,1.125862288560037193e-02,-4.563496123041156649e-02,9.999970218584333104e-01,0.000000000000000000e+00 +7.011482713078446238e+01,4.239415207329151940e+02,3.025090010177810207e+00,6.927984534833483643e+00,2.958835742576217953e-01,1.270204320868140169e-02,-4.563496123041156649e-02,9.999956940978917963e-01,0.000000000000000000e+00 +7.011627055202042413e+01,4.239510861817013847e+02,3.028005861600464588e+00,6.928002869232391170e+00,2.957169075909551470e-01,1.414545822941358499e-02,-4.563496123041156649e-02,9.999928799559493209e-01,0.000000000000000000e+00 +7.011771396943649393e+01,4.239606521163299249e+02,3.030920118741164071e+00,6.928023287033157729e+00,2.955502409242884987e-01,1.558886536828324107e-02,-4.563496123041156649e-02,9.999834397999468605e-01,0.000000000000000000e+00 +7.011915738259861541e+01,4.239702185365351284e+02,3.033832781518956967e+00,6.928045788206612876e+00,2.953835742576218504e-01,1.703225462719576075e-02,-4.563496123041156649e-02,-9.998756666034193108e-01,0.000000000000000000e+00 +7.012060079107276067e+01,4.239797854420512522e+02,3.036743849852935995e+00,6.928070372707275659e+00,2.952169075909552021e-01,1.558902561692352036e-02,-4.563496123041156649e-02,-9.999846029376779910e-01,0.000000000000000000e+00 +7.012204419442493020e+01,4.239893528326125534e+02,3.039653323662238282e+00,6.928092873959108111e+00,2.950502409242885538e-01,1.414564448892999086e-02,-4.563496123041156649e-02,-9.999909401730351366e-01,0.000000000000000000e+00 +7.012348759308916613e+01,4.239989207079532889e+02,3.042561202866044923e+00,6.928113291763468240e+00,2.948835742576219054e-01,1.270225890163259770e-02,-4.563496123041156649e-02,-9.999930693471672516e-01,0.000000000000000000e+00 +7.012493098749956744e+01,4.240084890678076590e+02,3.045467487383581862e+00,6.928131626132966403e+00,2.947169075909552571e-01,1.125887449489084390e-02,-4.563496123041156649e-02,-9.999940002158179686e-01,0.000000000000000000e+00 +7.012637437809021890e+01,4.240180579119099207e+02,3.048372177134118566e+00,6.928147877086473727e+00,2.945502409242886088e-01,9.815492564264940642e-03,-4.563496123041156649e-02,-9.999943663144943429e-01,0.000000000000000000e+00 +7.012781776529520528e+01,4.240276272399942172e+02,3.051275272036969355e+00,6.928162044642851569e+00,2.943835742576219605e-01,8.372113490873933986e-03,-4.563496123041156649e-02,-9.999943424701843719e-01,0.000000000000000000e+00 +7.012926114954856871e+01,4.240371970517947489e+02,3.054176772011492957e+00,6.928174128819631683e+00,2.942169075909553122e-01,6.928737403498174026e-03,-4.563496123041156649e-02,-9.999939201912134701e-01,0.000000000000000000e+00 +7.013070453128436554e+01,4.240467673470457157e+02,3.057076676977091623e+00,6.928184129632652066e+00,2.940502409242886639e-01,5.485364443180294931e-03,-4.563496123041156649e-02,-9.999928889045800462e-01,0.000000000000000000e+00 +7.013214791093665212e+01,4.240563381254812612e+02,3.059974986853212897e+00,6.928192047096074724e+00,2.938835742576220156e-01,4.041995054905099180e-03,-4.563496123041156649e-02,-9.999904987309733428e-01,0.000000000000000000e+00 +7.013359128893945638e+01,4.240659093868355285e+02,3.062871701559347848e+00,6.928197881222824428e+00,2.937169075909553673e-01,2.598630766020936997e-03,-4.563496123041156649e-02,-9.999828658673995951e-01,0.000000000000000000e+00 +7.013503466572682044e+01,4.240754811308426042e+02,3.065766821015032395e+00,6.928201632026151024e+00,2.935502409242887190e-01,1.155278709669303175e-03,-4.563496123041156649e-02,-8.004728505678094796e-01,0.000000000000000000e+00 +7.013647804173275802e+01,4.240850533572366885e+02,3.068660345139846424e+00,6.928203299527720738e+00,2.933835742576220706e-01,-1.045962488755256454e-07,-4.563496123041156649e-02,7.244338607266558776e-05,0.000000000000000000e+00 +7.013792141739131125e+01,4.240946260657518110e+02,3.071552273853414228e+00,6.928203299376749058e+00,2.932169075909554223e-01,-3.322879555212882261e-11,-4.563496123041156649e-02,2.302158509785743450e-08,0.000000000000000000e+00 +7.013936479304989291e+01,4.241041992561221150e+02,3.074442607075404510e+00,6.928203299376701096e+00,2.930502409242887740e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014080816870847457e+01,4.241137729280816302e+02,3.077331344725530382e+00,6.928203299376701096e+00,2.928835742576221257e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014225154436705623e+01,4.241233470813644431e+02,3.080218486723549365e+00,6.928203299376701096e+00,2.927169075909554774e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014369492002563788e+01,4.241329217157046401e+02,3.083104032989262500e+00,6.928203299376701096e+00,2.925502409242888291e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014513829568421954e+01,4.241424968308362509e+02,3.085987983442516125e+00,6.928203299376701096e+00,2.923835742576221808e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014658167134280120e+01,4.241520724264932483e+02,3.088870338003200100e+00,6.928203299376701096e+00,2.922169075909555325e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014802504700138286e+01,4.241616485024096619e+02,3.091751096591249137e+00,6.928203299376701096e+00,2.920502409242888842e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.014946842265996452e+01,4.241712250583195214e+02,3.094630259126642358e+00,6.928203299376701096e+00,2.918835742576222358e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015091179831854618e+01,4.241808020939567996e+02,3.097507825529403291e+00,6.928203299376701096e+00,2.917169075909555875e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015235517397712783e+01,4.241903796090554692e+02,3.100383795719598989e+00,6.928203299376701096e+00,2.915502409242889392e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015379854963570949e+01,4.241999576033494463e+02,3.103258169617341800e+00,6.928203299376701096e+00,2.913835742576222909e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015524192529429115e+01,4.242095360765727605e+02,3.106130947142787591e+00,6.928203299376701096e+00,2.912169075909556426e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015668530095287281e+01,4.242191150284592709e+02,3.109002128216137084e+00,6.928203299376701096e+00,2.910502409242889943e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015812867661145447e+01,4.242286944587428934e+02,3.111871712757635411e+00,6.928203299376701096e+00,2.908835742576223460e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.015957205227003612e+01,4.242382743671576009e+02,3.114739700687572110e+00,6.928203299376701096e+00,2.907169075909556977e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016101542792861778e+01,4.242478547534371955e+02,3.117606091926280243e+00,6.928203299376701096e+00,2.905502409242890494e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016245880358719944e+01,4.242574356173155934e+02,3.120470886394138166e+00,6.928203299376701096e+00,2.903835742576224010e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016390217924578110e+01,4.242670169585267104e+02,3.123334084011568645e+00,6.928203299376701096e+00,2.902169075909557527e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016534555490436276e+01,4.242765987768043487e+02,3.126195684699037969e+00,6.928203299376701096e+00,2.900502409242891044e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016678893056294442e+01,4.242861810718823676e+02,3.129055688377057276e+00,6.928203299376701096e+00,2.898835742576224561e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016823230622152607e+01,4.242957638434945693e+02,3.131914094966182116e+00,6.928203299376701096e+00,2.897169075909558078e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.016967568188010773e+01,4.243053470913747560e+02,3.134770904387012003e+00,6.928203299376701096e+00,2.895502409242891595e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017111905753868939e+01,4.243149308152567301e+02,3.137626116560191303e+00,6.928203299376701096e+00,2.893835742576225112e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017256243319727105e+01,4.243245150148742937e+02,3.140479731406408792e+00,6.928203299376701096e+00,2.892169075909558629e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017400580885585271e+01,4.243340996899612492e+02,3.143331748846397211e+00,6.928203299376701096e+00,2.890502409242892146e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017544918451443436e+01,4.243436848402512851e+02,3.146182168800933709e+00,6.928203299376701096e+00,2.888835742576225663e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017689256017301602e+01,4.243532704654782037e+02,3.149030991190840290e+00,6.928203299376701096e+00,2.887169075909559179e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017833593583159768e+01,4.243628565653756937e+02,3.151878215936982475e+00,6.928203299376701096e+00,2.885502409242892696e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.017977931149017934e+01,4.243724431396775003e+02,3.154723842960271085e+00,6.928203299376701096e+00,2.883835742576226213e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018122268714876100e+01,4.243820301881173691e+02,3.157567872181660906e+00,6.928203299376701096e+00,2.882169075909559730e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018266606280734266e+01,4.243916177104289318e+02,3.160410303522151132e+00,6.928203299376701096e+00,2.880502409242893247e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018410943846592431e+01,4.244012057063458769e+02,3.163251136902785365e+00,6.928203299376701096e+00,2.878835742576226764e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018555281412450597e+01,4.244107941756018931e+02,3.166090372244651618e+00,6.928203299376701096e+00,2.877169075909560281e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018699618978308763e+01,4.244203831179306121e+02,3.168928009468881868e+00,6.928203299376701096e+00,2.875502409242893798e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018843956544166929e+01,4.244299725330657225e+02,3.171764048496652943e+00,6.928203299376701096e+00,2.873835742576227315e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.018988294110025095e+01,4.244395624207407991e+02,3.174598489249186528e+00,6.928203299376701096e+00,2.872169075909560831e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019132631675883260e+01,4.244491527806894737e+02,3.177431331647747381e+00,6.928203299376701096e+00,2.870502409242894348e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019276969241741426e+01,4.244587436126453213e+02,3.180262575613646003e+00,6.928203299376701096e+00,2.868835742576227865e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019421306807599592e+01,4.244683349163419734e+02,3.183092221068236416e+00,6.928203299376701096e+00,2.867169075909561382e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019565644373457758e+01,4.244779266915130052e+02,3.185920267932917493e+00,6.928203299376701096e+00,2.865502409242894899e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019709981939315924e+01,4.244875189378919345e+02,3.188746716129132519e+00,6.928203299376701096e+00,2.863835742576228416e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019854319505174089e+01,4.244971116552123362e+02,3.191571565578368741e+00,6.928203299376701096e+00,2.862169075909561933e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.019998657071032255e+01,4.245067048432077286e+02,3.194394816202158260e+00,6.928203299376701096e+00,2.860502409242895450e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.020142994636890421e+01,4.245162985016116863e+02,3.197216467922077587e+00,6.928203299376701096e+00,2.858835742576228967e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.020287332202748587e+01,4.245258926301576707e+02,3.200036520659747641e+00,6.928203299376701096e+00,2.857169075909562483e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.020431669768606753e+01,4.245354872285791998e+02,3.202854974336833305e+00,6.928203299376701096e+00,2.855502409242896000e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.020576007334464919e+01,4.245450822966097348e+02,3.205671828875044316e+00,6.928203299376701096e+00,2.853835742576229517e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.020720344900323084e+01,4.245546778339827370e+02,3.208487084196134376e+00,6.928203299376701096e+00,2.852169075909563034e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.020864682466181250e+01,4.245642738404317242e+02,3.211300740221902483e+00,6.928203299376701096e+00,2.850502409242896551e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021009020032039416e+01,4.245738703156901011e+02,3.214112796874191158e+00,6.928203299376701096e+00,2.848835742576230068e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021153357597897582e+01,4.245834672594912718e+02,3.216923254074887772e+00,6.928203299376701096e+00,2.847169075909563585e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021297695163755748e+01,4.245930646715686976e+02,3.219732111745924108e+00,6.928203299376701096e+00,2.845502409242897102e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021442032729613913e+01,4.246026625516557829e+02,3.222539369809276355e+00,6.928203299376701096e+00,2.843835742576230619e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021586370295472079e+01,4.246122608994858751e+02,3.225345028186965113e+00,6.928203299376701096e+00,2.842169075909564135e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021730707861330245e+01,4.246218597147923788e+02,3.228149086801055390e+00,6.928203299376701096e+00,2.840502409242897652e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.021875045427188411e+01,4.246314589973086981e+02,3.230951545573657047e+00,6.928203299376701096e+00,2.838835742576231169e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022019382993046577e+01,4.246410587467681239e+02,3.233752404426923466e+00,6.928203299376701096e+00,2.837169075909564686e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022163720558904743e+01,4.246506589629040604e+02,3.236551663283053326e+00,6.928203299376701096e+00,2.835502409242898203e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022308058124762908e+01,4.246602596454497984e+02,3.239349322064289272e+00,6.928203299376701096e+00,2.833835742576231720e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022452395690621074e+01,4.246698607941386285e+02,3.242145380692918799e+00,6.928203299376701096e+00,2.832169075909565237e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022596733256479240e+01,4.246794624087038983e+02,3.244939839091273370e+00,6.928203299376701096e+00,2.830502409242898754e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022741070822337406e+01,4.246890644888788415e+02,3.247732697181729300e+00,6.928203299376701096e+00,2.828835742576232271e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.022885408388195572e+01,4.246986670343968058e+02,3.250523954886706868e+00,6.928203299376701096e+00,2.827169075909565787e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023029745954053737e+01,4.247082700449910249e+02,3.253313612128671650e+00,6.928203299376701096e+00,2.825502409242899304e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023174083519911903e+01,4.247178735203947326e+02,3.256101668830132745e+00,6.928203299376701096e+00,2.823835742576232821e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023318421085770069e+01,4.247274774603411629e+02,3.258888124913644102e+00,6.928203299376701096e+00,2.822169075909566338e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023462758651628235e+01,4.247370818645635495e+02,3.261672980301804525e+00,6.928203299376701096e+00,2.820502409242899855e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023607096217486401e+01,4.247466867327951263e+02,3.264456234917256783e+00,6.928203299376701096e+00,2.818835742576233372e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023751433783344567e+01,4.247562920647690703e+02,3.267237888682688052e+00,6.928203299376701096e+00,2.817169075909566889e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.023895771349202732e+01,4.247658978602185584e+02,3.270017941520830362e+00,6.928203299376701096e+00,2.815502409242900406e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024040108915060898e+01,4.247755041188767677e+02,3.272796393354460154e+00,6.928203299376701096e+00,2.813835742576233923e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024184446480919064e+01,4.247851108404768752e+02,3.275573244106397830e+00,6.928203299376701096e+00,2.812169075909567439e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024328784046777230e+01,4.247947180247520009e+02,3.278348493699509092e+00,6.928203299376701096e+00,2.810502409242900956e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024473121612635396e+01,4.248043256714352651e+02,3.281122142056703606e+00,6.928203299376701096e+00,2.808835742576234473e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024617459178493561e+01,4.248139337802598448e+02,3.283894189100935446e+00,6.928203299376701096e+00,2.807169075909567990e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024761796744351727e+01,4.248235423509588031e+02,3.286664634755203096e+00,6.928203299376701096e+00,2.805502409242901507e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.024906134310209893e+01,4.248331513832652604e+02,3.289433478942549893e+00,6.928203299376701096e+00,2.803835742576235024e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025050471876068059e+01,4.248427608769122799e+02,3.292200721586063583e+00,6.928203299376701096e+00,2.802169075909568541e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025194809441926225e+01,4.248523708316329248e+02,3.294966362608876320e+00,6.928203299376701096e+00,2.800502409242902058e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025339147007784391e+01,4.248619812471602586e+02,3.297730401934164668e+00,6.928203299376701096e+00,2.798835742576235575e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025483484573642556e+01,4.248715921232273445e+02,3.300492839485149599e+00,6.928203299376701096e+00,2.797169075909569091e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025627822139500722e+01,4.248812034595671889e+02,3.303253675185096938e+00,6.928203299376701096e+00,2.795502409242902608e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025772159705358888e+01,4.248908152559128553e+02,3.306012908957316920e+00,6.928203299376701096e+00,2.793835742576236125e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.025916497271217054e+01,4.249004275119972931e+02,3.308770540725163745e+00,6.928203299376701096e+00,2.792169075909569642e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026060834837075220e+01,4.249100402275535089e+02,3.311526570412036907e+00,6.928203299376701096e+00,2.790502409242903159e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026205172402933385e+01,4.249196534023145091e+02,3.314280997941379869e+00,6.928203299376701096e+00,2.788835742576236676e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026349509968791551e+01,4.249292670360132433e+02,3.317033823236680945e+00,6.928203299376701096e+00,2.787169075909570193e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026493847534649717e+01,4.249388811283826612e+02,3.319785046221472857e+00,6.928203299376701096e+00,2.785502409242903710e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026638185100507883e+01,4.249484956791557124e+02,3.322534666819332294e+00,6.928203299376701096e+00,2.783835742576237227e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026782522666366049e+01,4.249581106880653465e+02,3.325282684953881240e+00,6.928203299376701096e+00,2.782169075909570743e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.026926860232224215e+01,4.249677261548444562e+02,3.328029100548785646e+00,6.928203299376701096e+00,2.780502409242904260e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027071197798082380e+01,4.249773420792259344e+02,3.330773913527756314e+00,6.928203299376701096e+00,2.778835742576237777e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027215535363940546e+01,4.249869584609426738e+02,3.333517123814548455e+00,6.928203299376701096e+00,2.777169075909571294e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027359872929798712e+01,4.249965752997275672e+02,3.336258731332961691e+00,6.928203299376701096e+00,2.775502409242904811e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027504210495656878e+01,4.250061925953135074e+02,3.338998736006840495e+00,6.928203299376701096e+00,2.773835742576238328e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027648548061515044e+01,4.250158103474333302e+02,3.341737137760073306e+00,6.928203299376701096e+00,2.772169075909571845e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027792885627373209e+01,4.250254285558198148e+02,3.344473936516593415e+00,6.928203299376701096e+00,2.770502409242905362e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.027937223193231375e+01,4.250350472202058540e+02,3.347209132200378967e+00,6.928203299376701096e+00,2.768835742576238879e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028081560759089541e+01,4.250446663403242269e+02,3.349942724735452071e+00,6.928203299376701096e+00,2.767169075909572395e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028225898324947707e+01,4.250542859159077693e+02,3.352674714045879689e+00,6.928203299376701096e+00,2.765502409242905912e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028370235890805873e+01,4.250639059466892604e+02,3.355405100055773193e+00,6.928203299376701096e+00,2.763835742576239429e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028514573456664039e+01,4.250735264324014793e+02,3.358133882689288363e+00,6.928203299376701096e+00,2.762169075909572946e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028658911022522204e+01,4.250831473727772050e+02,3.360861061870625832e+00,6.928203299376701096e+00,2.760502409242906463e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028803248588380370e+01,4.250927687675491597e+02,3.363586637524030643e+00,6.928203299376701096e+00,2.758835742576239980e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.028947586154238536e+01,4.251023906164500659e+02,3.366310609573792245e+00,6.928203299376701096e+00,2.757169075909573497e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029091923720096702e+01,4.251120129192127024e+02,3.369032977944244944e+00,6.928203299376701096e+00,2.755502409242907014e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029236261285954868e+01,4.251216356755697348e+02,3.371753742559767453e+00,6.928203299376701096e+00,2.753835742576240531e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029380598851813033e+01,4.251312588852538852e+02,3.374472903344782448e+00,6.928203299376701096e+00,2.752169075909574048e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029524936417671199e+01,4.251408825479978759e+02,3.377190460223758350e+00,6.928203299376701096e+00,2.750502409242907564e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029669273983529365e+01,4.251505066635343155e+02,3.379906413121207098e+00,6.928203299376701096e+00,2.748835742576241081e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029813611549387531e+01,4.251601312315959262e+02,3.382620761961685485e+00,6.928203299376701096e+00,2.747169075909574598e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.029957949115245697e+01,4.251697562519153166e+02,3.385333506669795156e+00,6.928203299376701096e+00,2.745502409242908115e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030102286681103863e+01,4.251793817242251521e+02,3.388044647170182166e+00,6.928203299376701096e+00,2.743835742576241632e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030246624246962028e+01,4.251890076482580412e+02,3.390754183387536980e+00,6.928203299376701096e+00,2.742169075909575149e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030390961812820194e+01,4.251986340237465924e+02,3.393462115246594468e+00,6.928203299376701096e+00,2.740502409242908666e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030535299378678360e+01,4.252082608504234145e+02,3.396168442672134358e+00,6.928203299376701096e+00,2.738835742576242183e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030679636944536526e+01,4.252178881280211158e+02,3.398873165588981227e+00,6.928203299376701096e+00,2.737169075909575700e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030823974510394692e+01,4.252275158562722481e+02,3.401576283922003618e+00,6.928203299376701096e+00,2.735502409242909216e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.030968312076252857e+01,4.252371440349093632e+02,3.404277797596114929e+00,6.928203299376701096e+00,2.733835742576242733e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031112649642111023e+01,4.252467726636650696e+02,3.406977706536272965e+00,6.928203299376701096e+00,2.732169075909576250e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031256987207969189e+01,4.252564017422718621e+02,3.409676010667480384e+00,6.928203299376701096e+00,2.730502409242909767e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031401324773827355e+01,4.252660312704622356e+02,3.412372709914784252e+00,6.928203299376701096e+00,2.728835742576243284e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031545662339685521e+01,4.252756612479687419e+02,3.415067804203276491e+00,6.928203299376701096e+00,2.727169075909576801e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031689999905543687e+01,4.252852916745238758e+02,3.417761293458092986e+00,6.928203299376701096e+00,2.725502409242910318e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031834337471401852e+01,4.252949225498601322e+02,3.420453177604414918e+00,6.928203299376701096e+00,2.723835742576243835e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.031978675037260018e+01,4.253045538737100060e+02,3.423143456567467879e+00,6.928203299376701096e+00,2.722169075909577352e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032123012603118184e+01,4.253141856458059351e+02,3.425832130272521425e+00,6.928203299376701096e+00,2.720502409242910868e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032267350168976350e+01,4.253238178658803577e+02,3.428519198644890409e+00,6.928203299376701096e+00,2.718835742576244385e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032411687734834516e+01,4.253334505336657116e+02,3.431204661609934092e+00,6.928203299376701096e+00,2.717169075909577902e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032556025300692681e+01,4.253430836488944351e+02,3.433888519093056146e+00,6.928203299376701096e+00,2.715502409242911419e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032700362866550847e+01,4.253527172112989660e+02,3.436570771019705095e+00,6.928203299376701096e+00,2.713835742576244936e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032844700432409013e+01,4.253623512206116857e+02,3.439251417315373871e+00,6.928203299376701096e+00,2.712169075909578453e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.032989037998267179e+01,4.253719856765649752e+02,3.441930457905600260e+00,6.928203299376701096e+00,2.710502409242911970e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033133375564125345e+01,4.253816205788912157e+02,3.444607892715966013e+00,6.928203299376701096e+00,2.708835742576245487e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033277713129983510e+01,4.253912559273227885e+02,3.447283721672098178e+00,6.928203299376701096e+00,2.707169075909579004e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033422050695841676e+01,4.254008917215920178e+02,3.449957944699668211e+00,6.928203299376701096e+00,2.705502409242912520e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033566388261699842e+01,4.254105279614312281e+02,3.452630561724392422e+00,6.928203299376701096e+00,2.703835742576246037e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033710725827558008e+01,4.254201646465728004e+02,3.455301572672031085e+00,6.928203299376701096e+00,2.702169075909579554e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033855063393416174e+01,4.254298017767490023e+02,3.457970977468389773e+00,6.928203299376701096e+00,2.700502409242913071e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.033999400959274340e+01,4.254394393516921582e+02,3.460638776039318021e+00,6.928203299376701096e+00,2.698835742576246588e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.034143738525132505e+01,4.254490773711345355e+02,3.463304968310710219e+00,6.928203299376701096e+00,2.697169075909580105e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.034288076090990671e+01,4.254587158348084586e+02,3.465969554208505610e+00,6.928203299376701096e+00,2.695502409242913622e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.034432413656848837e+01,4.254683547424461381e+02,3.468632533658688288e+00,6.928203299376701096e+00,2.693835742576247139e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.034576751222707003e+01,4.254779940937798415e+02,3.471293906587286315e+00,6.928203299376701096e+00,2.692169075909580656e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.034721088788565169e+01,4.254876338885418363e+02,3.473953672920372604e+00,6.928203299376701096e+00,2.690502409242914172e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.034865426354423334e+01,4.254972741264643332e+02,3.476611832584064476e+00,6.928203299376701096e+00,2.688835742576247689e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035009763920281500e+01,4.255069148072795429e+02,3.479268385504524552e+00,6.928203299376701096e+00,2.687169075909581206e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035154101486139666e+01,4.255165559307196759e+02,3.481923331607959859e+00,6.928203299376701096e+00,2.685502409242914723e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035298439051997832e+01,4.255261974965169429e+02,3.484576670820621391e+00,6.928203299376701096e+00,2.683835742576248240e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035442776617855998e+01,4.255358395044034978e+02,3.487228403068805882e+00,6.928203299376701096e+00,2.682169075909581757e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035587114183714164e+01,4.255454819541114944e+02,3.489878528278853587e+00,6.928203299376701096e+00,2.680502409242915274e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035731451749572329e+01,4.255551248453730864e+02,3.492527046377150057e+00,6.928203299376701096e+00,2.678835742576248791e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.035875789315430495e+01,4.255647681779204277e+02,3.495173957290125699e+00,6.928203299376701096e+00,2.677169075909582308e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036020126881288661e+01,4.255744119514856720e+02,3.497819260944254882e+00,6.928203299376701096e+00,2.675502409242915824e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036164464447146827e+01,4.255840561658009165e+02,3.500462957266056829e+00,6.928203299376701096e+00,2.673835742576249341e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036308802013004993e+01,4.255937008205982579e+02,3.503105046182095617e+00,6.928203299376701096e+00,2.672169075909582858e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036453139578863158e+01,4.256033459156097933e+02,3.505745527618980173e+00,6.928203299376701096e+00,2.670502409242916375e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036597477144721324e+01,4.256129914505676197e+02,3.508384401503363392e+00,6.928203299376701096e+00,2.668835742576249892e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036741814710579490e+01,4.256226374252037772e+02,3.511021667761943466e+00,6.928203299376701096e+00,2.667169075909583409e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.036886152276437656e+01,4.256322838392503627e+02,3.513657326321462993e+00,6.928203299376701096e+00,2.665502409242916926e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037030489842295822e+01,4.256419306924393595e+02,3.516291377108708982e+00,6.928203299376701096e+00,2.663835742576250443e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037174827408153988e+01,4.256515779845028646e+02,3.518923820050513740e+00,6.928203299376701096e+00,2.662169075909583960e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037319164974012153e+01,4.256612257151728613e+02,3.521554655073753537e+00,6.928203299376701096e+00,2.660502409242917476e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037463502539870319e+01,4.256708738841813329e+02,3.524183882105349497e+00,6.928203299376701096e+00,2.658835742576250993e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037607840105728485e+01,4.256805224912603194e+02,3.526811501072268040e+00,6.928203299376701096e+00,2.657169075909584510e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037752177671586651e+01,4.256901715361418042e+02,3.529437511901519553e+00,6.928203299376701096e+00,2.655502409242918027e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.037896515237444817e+01,4.256998210185577136e+02,3.532061914520159274e+00,6.928203299376701096e+00,2.653835742576251544e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038040852803302982e+01,4.257094709382400310e+02,3.534684708855286850e+00,6.928203299376701096e+00,2.652169075909585061e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038185190369161148e+01,4.257191212949207397e+02,3.537305894834047226e+00,6.928203299376701096e+00,2.650502409242918578e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038329527935019314e+01,4.257287720883317093e+02,3.539925472383629312e+00,6.928203299376701096e+00,2.648835742576252095e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038473865500877480e+01,4.257384233182049229e+02,3.542543441431267315e+00,6.928203299376701096e+00,2.647169075909585612e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038618203066735646e+01,4.257480749842722503e+02,3.545159801904239849e+00,6.928203299376701096e+00,2.645502409242919128e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038762540632593812e+01,4.257577270862656178e+02,3.547774553729870384e+00,6.928203299376701096e+00,2.643835742576252645e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.038906878198451977e+01,4.257673796239168951e+02,3.550387696835526796e+00,6.928203299376701096e+00,2.642169075909586162e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039051215764310143e+01,4.257770325969579517e+02,3.552999231148621817e+00,6.928203299376701096e+00,2.640502409242919679e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039195553330168309e+01,4.257866860051206572e+02,3.555609156596613030e+00,6.928203299376701096e+00,2.638835742576253196e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039339890896026475e+01,4.257963398481368813e+02,3.558217473107001982e+00,6.928203299376701096e+00,2.637169075909586713e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039484228461884641e+01,4.258059941257384367e+02,3.560824180607335965e+00,6.928203299376701096e+00,2.635502409242920230e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039628566027742806e+01,4.258156488376571360e+02,3.563429279025206231e+00,6.928203299376701096e+00,2.633835742576253747e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039772903593600972e+01,4.258253039836247922e+02,3.566032768288248889e+00,6.928203299376701096e+00,2.632169075909587264e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.039917241159459138e+01,4.258349595633732747e+02,3.568634648324144898e+00,6.928203299376701096e+00,2.630502409242920780e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040061578725317304e+01,4.258446155766342827e+02,3.571234919060619628e+00,6.928203299376701096e+00,2.628835742576254297e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040205916291175470e+01,4.258542720231396288e+02,3.573833580425443301e+00,6.928203299376701096e+00,2.627169075909587814e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040350253857033636e+01,4.258639289026211259e+02,3.576430632346430993e+00,6.928203299376701096e+00,2.625502409242921331e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040494591422891801e+01,4.258735862148104729e+02,3.579026074751442632e+00,6.928203299376701096e+00,2.623835742576254848e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040638928988749967e+01,4.258832439594394259e+02,3.581619907568382111e+00,6.928203299376701096e+00,2.622169075909588365e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040783266554608133e+01,4.258929021362396838e+02,3.584212130725198620e+00,6.928203299376701096e+00,2.620502409242921882e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.040927604120466299e+01,4.259025607449430026e+02,3.586802744149886202e+00,6.928203299376701096e+00,2.618835742576255399e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041071941686324465e+01,4.259122197852810814e+02,3.589391747770483310e+00,6.928203299376701096e+00,2.617169075909588916e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041216279252182630e+01,4.259218792569856191e+02,3.591979141515073248e+00,6.928203299376701096e+00,2.615502409242922432e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041360616818040796e+01,4.259315391597882581e+02,3.594564925311783732e+00,6.928203299376701096e+00,2.613835742576255949e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041504954383898962e+01,4.259411994934206973e+02,3.597149099088787771e+00,6.928203299376701096e+00,2.612169075909589466e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041649291949757128e+01,4.259508602576145790e+02,3.599731662774302343e+00,6.928203299376701096e+00,2.610502409242922983e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041793629515615294e+01,4.259605214521016023e+02,3.602312616296589720e+00,6.928203299376701096e+00,2.608835742576256500e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.041937967081473460e+01,4.259701830766133526e+02,3.604891959583957028e+00,6.928203299376701096e+00,2.607169075909590017e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042082304647331625e+01,4.259798451308814720e+02,3.607469692564755359e+00,6.928203299376701096e+00,2.605502409242923534e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042226642213189791e+01,4.259895076146375459e+02,3.610045815167381544e+00,6.928203299376701096e+00,2.603835742576257051e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042370979779047957e+01,4.259991705276131597e+02,3.612620327320276381e+00,6.928203299376701096e+00,2.602169075909590568e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042515317344906123e+01,4.260088338695399557e+02,3.615193228951925519e+00,6.928203299376701096e+00,2.600502409242924085e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042659654910764289e+01,4.260184976401494623e+02,3.617764519990859462e+00,6.928203299376701096e+00,2.598835742576257601e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042803992476622454e+01,4.260281618391732650e+02,3.620334200365653565e+00,6.928203299376701096e+00,2.597169075909591118e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.042948330042480620e+01,4.260378264663428922e+02,3.622902270004928038e+00,6.928203299376701096e+00,2.595502409242924635e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043092667608338786e+01,4.260474915213898726e+02,3.625468728837347498e+00,6.928203299376701096e+00,2.593835742576258152e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043237005174196952e+01,4.260571570040457914e+02,3.628033576791620973e+00,6.928203299376701096e+00,2.592169075909591669e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043381342740055118e+01,4.260668229140421204e+02,3.630596813796503231e+00,6.928203299376701096e+00,2.590502409242925186e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043525680305913284e+01,4.260764892511103312e+02,3.633158439780793003e+00,6.928203299376701096e+00,2.588835742576258703e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043670017871771449e+01,4.260861560149819525e+02,3.635718454673333877e+00,6.928203299376701096e+00,2.587169075909592220e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043814355437629615e+01,4.260958232053884558e+02,3.638276858403014735e+00,6.928203299376701096e+00,2.585502409242925737e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.043958693003487781e+01,4.261054908220613129e+02,3.640833650898768425e+00,6.928203299376701096e+00,2.583835742576259253e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044103030569345947e+01,4.261151588647319954e+02,3.643388832089573093e+00,6.928203299376701096e+00,2.582169075909592770e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044247368135204113e+01,4.261248273331319183e+02,3.645942401904451735e+00,6.928203299376701096e+00,2.580502409242926287e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044391705701062278e+01,4.261344962269925531e+02,3.648494360272471315e+00,6.928203299376701096e+00,2.578835742576259804e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044536043266920444e+01,4.261441655460452580e+02,3.651044707122744537e+00,6.928203299376701096e+00,2.577169075909593321e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044680380832778610e+01,4.261538352900215045e+02,3.653593442384428069e+00,6.928203299376701096e+00,2.575502409242926838e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044824718398636776e+01,4.261635054586526508e+02,3.656140565986724322e+00,6.928203299376701096e+00,2.573835742576260355e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.044969055964494942e+01,4.261731760516700547e+02,3.658686077858879226e+00,6.928203299376701096e+00,2.572169075909593872e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045113393530353108e+01,4.261828470688051311e+02,3.661229977930184454e+00,6.928203299376701096e+00,2.570502409242927389e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045257731096211273e+01,4.261925185097892381e+02,3.663772266129976085e+00,6.928203299376701096e+00,2.568835742576260905e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045402068662069439e+01,4.262021903743537337e+02,3.666312942387634610e+00,6.928203299376701096e+00,2.567169075909594422e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045546406227927605e+01,4.262118626622299189e+02,3.668852006632586260e+00,6.928203299376701096e+00,2.565502409242927939e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045690743793785771e+01,4.262215353731491518e+02,3.671389458794301230e+00,6.928203299376701096e+00,2.563835742576261456e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045835081359643937e+01,4.262312085068427336e+02,3.673925298802294570e+00,6.928203299376701096e+00,2.562169075909594973e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.045979418925502102e+01,4.262408820630419655e+02,3.676459526586126625e+00,6.928203299376701096e+00,2.560502409242928490e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046123756491360268e+01,4.262505560414781485e+02,3.678992142075402150e+00,6.928203299376701096e+00,2.558835742576262007e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046268094057218434e+01,4.262602304418825270e+02,3.681523145199770308e+00,6.928203299376701096e+00,2.557169075909595524e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046412431623076600e+01,4.262699052639864021e+02,3.684052535888925561e+00,6.928203299376701096e+00,2.555502409242929041e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046556769188934766e+01,4.262795805075210183e+02,3.686580314072607223e+00,6.928203299376701096e+00,2.553835742576262557e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046701106754792931e+01,4.262892561722176197e+02,3.689106479680599460e+00,6.928203299376701096e+00,2.552169075909596074e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046845444320651097e+01,4.262989322578074507e+02,3.691631032642730847e+00,6.928203299376701096e+00,2.550502409242929591e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.046989781886509263e+01,4.263086087640216988e+02,3.694153972888874815e+00,6.928203299376701096e+00,2.548835742576263108e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.047134119452367429e+01,4.263182856905916083e+02,3.696675300348949644e+00,6.928203299376701096e+00,2.547169075909596625e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.047278457018225595e+01,4.263279630372483666e+02,3.699195014952918470e+00,6.928203299376701096e+00,2.545502409242930142e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.047422794584083761e+01,4.263376408037231045e+02,3.701713116630789280e+00,6.928203299376701096e+00,2.543835742576263659e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.047567132149941926e+01,4.263473189897470661e+02,3.704229605312614915e+00,6.928203299376701096e+00,2.542169075909597176e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.047711469715800092e+01,4.263569975950513822e+02,3.706744480928492624e+00,6.928203299376701096e+00,2.540502409242930693e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.047855807281658258e+01,4.263666766193671833e+02,3.709257743408564956e+00,6.928203299376701096e+00,2.538835742576264209e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048000144847516424e+01,4.263763560624256570e+02,3.711769392683018864e+00,6.928203299376701096e+00,2.537169075909597726e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048144482413374590e+01,4.263860359239578770e+02,3.714279428682086603e+00,6.928203299376701096e+00,2.535502409242931243e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048288819979232755e+01,4.263957162036950308e+02,3.716787851336044834e+00,6.928203299376701096e+00,2.533835742576264760e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048433157545090921e+01,4.264053969013681353e+02,3.719294660575215072e+00,6.928203299376701096e+00,2.532169075909598277e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048577495110949087e+01,4.264150780167083212e+02,3.721799856329963685e+00,6.928203299376701096e+00,2.530502409242931794e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048721832676807253e+01,4.264247595494467191e+02,3.724303438530702337e+00,6.928203299376701096e+00,2.528835742576265311e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.048866170242665419e+01,4.264344414993143459e+02,3.726805407107886658e+00,6.928203299376701096e+00,2.527169075909598828e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049010507808523585e+01,4.264441238660422187e+02,3.729305761992017576e+00,6.928203299376701096e+00,2.525502409242932345e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049154845374381750e+01,4.264538066493614679e+02,3.731804503113640870e+00,6.928203299376701096e+00,2.523835742576265861e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049299182940239916e+01,4.264634898490030537e+02,3.734301630403347172e+00,6.928203299376701096e+00,2.522169075909599378e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049443520506098082e+01,4.264731734646980499e+02,3.736797143791771525e+00,6.928203299376701096e+00,2.520502409242932895e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049587858071956248e+01,4.264828574961774166e+02,3.739291043209594267e+00,6.928203299376701096e+00,2.518835742576266412e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049732195637814414e+01,4.264925419431722275e+02,3.741783328587540591e+00,6.928203299376701096e+00,2.517169075909599929e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.049876533203672579e+01,4.265022268054133860e+02,3.744273999856380097e+00,6.928203299376701096e+00,2.515502409242933446e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050020870769530745e+01,4.265119120826319090e+02,3.746763056946927684e+00,6.928203299376701096e+00,2.513835742576266963e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050165208335388911e+01,4.265215977745587566e+02,3.749250499790042657e+00,6.928203299376701096e+00,2.512169075909600480e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050309545901247077e+01,4.265312838809248888e+02,3.751736328316629177e+00,6.928203299376701096e+00,2.510502409242933997e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050453883467105243e+01,4.265409704014612657e+02,3.754220542457637144e+00,6.928203299376701096e+00,2.508835742576267513e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050598221032963409e+01,4.265506573358987907e+02,3.756703142144059981e+00,6.928203299376701096e+00,2.507169075909601030e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050742558598821574e+01,4.265603446839683670e+02,3.759184127306936851e+00,6.928203299376701096e+00,2.505502409242934547e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.050886896164679740e+01,4.265700324454009547e+02,3.761663497877351325e+00,6.928203299376701096e+00,2.503835742576268064e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051031233730537906e+01,4.265797206199274001e+02,3.764141253786432273e+00,6.928203299376701096e+00,2.502169075909601581e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051175571296396072e+01,4.265894092072786066e+02,3.766617394965352972e+00,6.928203299376701096e+00,2.500502409242935098e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051319908862254238e+01,4.265990982071854205e+02,3.769091921345331997e+00,6.928203299376701096e+00,2.498835742576268337e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051464246428112403e+01,4.266087876193787451e+02,3.771564832857631888e+00,6.928203299376701096e+00,2.497169075909601577e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051608583993970569e+01,4.266184774435894269e+02,3.774036129433561371e+00,6.928203299376701096e+00,2.495502409242934816e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051752921559828735e+01,4.266281676795482554e+02,3.776505811004472690e+00,6.928203299376701096e+00,2.493835742576268055e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.051897259125686901e+01,4.266378583269861338e+02,3.778973877501764278e+00,6.928203299376701096e+00,2.492169075909601295e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052041596691545067e+01,4.266475493856337948e+02,3.781440328856878086e+00,6.928203299376701096e+00,2.490502409242934534e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052185934257403233e+01,4.266572408552220850e+02,3.783905165001301807e+00,6.928203299376701096e+00,2.488835742576267773e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052330271823261398e+01,4.266669327354817938e+02,3.786368385866567987e+00,6.928203299376701096e+00,2.487169075909601013e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052474609389119564e+01,4.266766250261437108e+02,3.788829991384253582e+00,6.928203299376701096e+00,2.485502409242934252e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052618946954977730e+01,4.266863177269386256e+02,3.791289981485980398e+00,6.928203299376701096e+00,2.483835742576267491e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052763284520835896e+01,4.266960108375972709e+02,3.793748356103415986e+00,6.928203299376701096e+00,2.482169075909600731e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.052907622086694062e+01,4.267057043578503794e+02,3.796205115168271860e+00,6.928203299376701096e+00,2.480502409242933970e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053051959652552227e+01,4.267153982874286839e+02,3.798660258612304386e+00,6.928203299376701096e+00,2.478835742576267209e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053196297218410393e+01,4.267250926260629171e+02,3.801113786367315672e+00,6.928203299376701096e+00,2.477169075909600449e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053340634784268559e+01,4.267347873734838117e+02,3.803565698365151793e+00,6.928203299376701096e+00,2.475502409242933688e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053484972350126725e+01,4.267444825294220436e+02,3.806015994537704561e+00,6.928203299376701096e+00,2.473835742576266927e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053629309915984891e+01,4.267541780936083455e+02,3.808464674816909756e+00,6.928203299376701096e+00,2.472169075909600167e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053773647481843057e+01,4.267638740657733365e+02,3.810911739134748455e+00,6.928203299376701096e+00,2.470502409242933406e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.053917985047701222e+01,4.267735704456476924e+02,3.813357187423247030e+00,6.928203299376701096e+00,2.468835742576266645e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054062322613559388e+01,4.267832672329620891e+02,3.815801019614475820e+00,6.928203299376701096e+00,2.467169075909599885e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054206660179417554e+01,4.267929644274472025e+02,3.818243235640550903e+00,6.928203299376701096e+00,2.465502409242933124e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054350997745275720e+01,4.268026620288336517e+02,3.820683835433633213e+00,6.928203299376701096e+00,2.463835742576266363e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054495335311133886e+01,4.268123600368519988e+02,3.823122818925928090e+00,6.928203299376701096e+00,2.462169075909599603e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054639672876992051e+01,4.268220584512329197e+02,3.825560186049685729e+00,6.928203299376701096e+00,2.460502409242932842e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054784010442850217e+01,4.268317572717069766e+02,3.827995936737201621e+00,6.928203299376701096e+00,2.458835742576266081e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.054928348008708383e+01,4.268414564980047885e+02,3.830430070920816110e+00,6.928203299376701096e+00,2.457169075909599321e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055072685574566549e+01,4.268511561298569177e+02,3.832862588532914394e+00,6.928203299376701096e+00,2.455502409242932560e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055217023140424715e+01,4.268608561669939263e+02,3.835293489505926523e+00,6.928203299376701096e+00,2.453835742576265799e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055361360706282881e+01,4.268705566091463766e+02,3.837722773772327400e+00,6.928203299376701096e+00,2.452169075909599039e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055505698272141046e+01,4.268802574560448306e+02,3.840150441264637227e+00,6.928203299376701096e+00,2.450502409242932278e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055650035837999212e+01,4.268899587074197939e+02,3.842576491915420611e+00,6.928203299376701096e+00,2.448835742576265517e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055794373403857378e+01,4.268996603630017717e+02,3.845000925657287016e+00,6.928203299376701096e+00,2.447169075909598757e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.055938710969715544e+01,4.269093624225212693e+02,3.847423742422891202e+00,6.928203299376701096e+00,2.445502409242931996e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056083048535573710e+01,4.269190648857088490e+02,3.849844942144932780e+00,6.928203299376701096e+00,2.443835742576265235e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056227386101431875e+01,4.269287677522949593e+02,3.852264524756156217e+00,6.928203299376701096e+00,2.442169075909598475e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056371723667290041e+01,4.269384710220100487e+02,3.854682490189350830e+00,6.928203299376701096e+00,2.440502409242931714e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056516061233148207e+01,4.269481746945846226e+02,3.857098838377350791e+00,6.928203299376701096e+00,2.438835742576264953e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056660398799006373e+01,4.269578787697491293e+02,3.859513569253035570e+00,6.928203299376701096e+00,2.437169075909598193e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056804736364864539e+01,4.269675832472339607e+02,3.861926682749329043e+00,6.928203299376701096e+00,2.435502409242931432e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.056949073930722705e+01,4.269772881267696221e+02,3.864338178799200385e+00,6.928203299376701096e+00,2.433835742576264671e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057093411496580870e+01,4.269869934080865050e+02,3.866748057335663624e+00,6.928203299376701096e+00,2.432169075909597911e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057237749062439036e+01,4.269966990909150013e+02,3.869156318291777641e+00,6.928203299376701096e+00,2.430502409242931150e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057382086628297202e+01,4.270064051749855025e+02,3.871562961600646169e+00,6.928203299376701096e+00,2.428835742576264389e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057526424194155368e+01,4.270161116600284004e+02,3.873967987195418239e+00,6.928203299376701096e+00,2.427169075909597629e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057670761760013534e+01,4.270258185457740865e+02,3.876371395009287735e+00,6.928203299376701096e+00,2.425502409242930868e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057815099325871699e+01,4.270355258319529526e+02,3.878773184975492949e+00,6.928203299376701096e+00,2.423835742576264107e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.057959436891729865e+01,4.270452335182953334e+02,3.881173357027317472e+00,6.928203299376701096e+00,2.422169075909597347e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058103774457588031e+01,4.270549416045315638e+02,3.883571911098090190e+00,6.928203299376701096e+00,2.420502409242930586e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058248112023446197e+01,4.270646500903919218e+02,3.885968847121184400e+00,6.928203299376701096e+00,2.418835742576263825e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058392449589304363e+01,4.270743589756067990e+02,3.888364165030018693e+00,6.928203299376701096e+00,2.417169075909597065e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058536787155162529e+01,4.270840682599064735e+02,3.890757864758056517e+00,6.928203299376701096e+00,2.415502409242930304e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058681124721020694e+01,4.270937779430212800e+02,3.893149946238805725e+00,6.928203299376701096e+00,2.413835742576263543e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058825462286878860e+01,4.271034880246814396e+02,3.895540409405819915e+00,6.928203299376701096e+00,2.412169075909596783e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.058969799852737026e+01,4.271131985046172872e+02,3.897929254192697535e+00,6.928203299376701096e+00,2.410502409242930022e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059114137418595192e+01,4.271229093825590439e+02,3.900316480533081442e+00,6.928203299376701096e+00,2.408835742576263261e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059258474984453358e+01,4.271326206582369878e+02,3.902702088360660237e+00,6.928203299376701096e+00,2.407169075909596501e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059402812550311523e+01,4.271423323313813398e+02,3.905086077609166484e+00,6.928203299376701096e+00,2.405502409242929740e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059547150116169689e+01,4.271520444017223781e+02,3.907468448212378487e+00,6.928203299376701096e+00,2.403835742576262979e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059691487682027855e+01,4.271617568689902669e+02,3.909849200104119404e+00,6.928203299376701096e+00,2.402169075909596219e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059835825247886021e+01,4.271714697329152273e+02,3.912228333218257248e+00,6.928203299376701096e+00,2.400502409242929458e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.059980162813744187e+01,4.271811829932274804e+02,3.914605847488704882e+00,6.928203299376701096e+00,2.398835742576262697e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060124500379602352e+01,4.271908966496571907e+02,3.916981742849420467e+00,6.928203299376701096e+00,2.397169075909595937e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060268837945460518e+01,4.272006107019345791e+02,3.919356019234406574e+00,6.928203299376701096e+00,2.395502409242929176e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060413175511318684e+01,4.272103251497897531e+02,3.921728676577711070e+00,6.928203299376701096e+00,2.393835742576262415e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060557513077176850e+01,4.272200399929529340e+02,3.924099714813427120e+00,6.928203299376701096e+00,2.392169075909595655e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060701850643035016e+01,4.272297552311542290e+02,3.926469133875692297e+00,6.928203299376701096e+00,2.390502409242928894e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060846188208893182e+01,4.272394708641237457e+02,3.928836933698689471e+00,6.928203299376701096e+00,2.388835742576262133e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.060990525774751347e+01,4.272491868915915916e+02,3.931203114216646366e+00,6.928203299376701096e+00,2.387169075909595373e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.061134863340609513e+01,4.272589033132879308e+02,3.933567675363836003e+00,6.928203299376701096e+00,2.385502409242928612e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.061279200906467679e+01,4.272686201289428709e+02,3.935930617074575810e+00,6.928203299376701096e+00,2.383835742576261851e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.061423538472325845e+01,4.272783373382864625e+02,3.938291939283228960e+00,6.928203299376701096e+00,2.382169075909595091e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.061567876038184011e+01,4.272880549410487561e+02,3.940651641924202586e+00,6.928203299376701096e+00,2.380502409242928330e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.061712213604042176e+01,4.272977729369598592e+02,3.943009724931950011e+00,6.928203299376701096e+00,2.378835742576261569e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.061856551169900342e+01,4.273074913257498224e+02,3.945366188240968519e+00,6.928203299376701096e+00,2.377169075909594809e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062000888735758508e+01,4.273172101071486964e+02,3.947721031785800694e+00,6.928203299376701096e+00,2.375502409242928048e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062145226301616674e+01,4.273269292808865316e+02,3.950074255501034415e+00,6.928203299376701096e+00,2.373835742576261287e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062289563867474840e+01,4.273366488466933220e+02,3.952425859321302415e+00,6.928203299376701096e+00,2.372169075909594527e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062433901433333006e+01,4.273463688042990611e+02,3.954775843181282280e+00,6.928203299376701096e+00,2.370502409242927766e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062578238999191171e+01,4.273560891534337998e+02,3.957124207015696893e+00,6.928203299376701096e+00,2.368835742576261005e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062722576565049337e+01,4.273658098938275316e+02,3.959470950759313546e+00,6.928203299376701096e+00,2.367169075909594245e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.062866914130907503e+01,4.273755310252101935e+02,3.961816074346944827e+00,6.928203299376701096e+00,2.365502409242927484e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063011251696765669e+01,4.273852525473117794e+02,3.964159577713449067e+00,6.928203299376701096e+00,2.363835742576260723e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063155589262623835e+01,4.273949744598622260e+02,3.966501460793728562e+00,6.928203299376701096e+00,2.362169075909593963e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063299926828482000e+01,4.274046967625914704e+02,3.968841723522730902e+00,6.928203299376701096e+00,2.360502409242927202e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063444264394340166e+01,4.274144194552295062e+02,3.971180365835448978e+00,6.928203299376701096e+00,2.358835742576260441e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063588601960198332e+01,4.274241425375062136e+02,3.973517387666920087e+00,6.928203299376701096e+00,2.357169075909593681e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063732939526056498e+01,4.274338660091514726e+02,3.975852788952227268e+00,6.928203299376701096e+00,2.355502409242926920e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.063877277091914664e+01,4.274435898698952769e+02,3.978186569626498414e+00,6.928203299376701096e+00,2.353835742576260159e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064021614657772830e+01,4.274533141194674499e+02,3.980518729624906271e+00,6.928203299376701096e+00,2.352169075909593399e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064165952223630995e+01,4.274630387575978716e+02,3.982849268882668436e+00,6.928203299376701096e+00,2.350502409242926638e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064310289789489161e+01,4.274727637840164789e+02,3.985178187335047806e+00,6.928203299376701096e+00,2.348835742576259877e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064454627355347327e+01,4.274824891984530950e+02,3.987505484917352128e+00,6.928203299376701096e+00,2.347169075909593117e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064598964921205493e+01,4.274922150006375432e+02,3.989831161564934003e+00,6.928203299376701096e+00,2.345502409242926356e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064743302487063659e+01,4.275019411902997035e+02,3.992155217213191776e+00,6.928203299376701096e+00,2.343835742576259595e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.064887640052921824e+01,4.275116677671693424e+02,3.994477651797568196e+00,6.928203299376701096e+00,2.342169075909592835e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065031977618779990e+01,4.275213947309763398e+02,3.996798465253551313e+00,6.928203299376701096e+00,2.340502409242926074e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065176315184638156e+01,4.275311220814504622e+02,3.999117657516673585e+00,6.928203299376701096e+00,2.338835742576259313e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065320652750496322e+01,4.275408498183215329e+02,4.001435228522513654e+00,6.928203299376701096e+00,2.337169075909592553e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065464990316354488e+01,4.275505779413193181e+02,4.003751178206694128e+00,6.928203299376701096e+00,2.335502409242925792e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065609327882212654e+01,4.275603064501736412e+02,4.006065506504882912e+00,6.928203299376701096e+00,2.333835742576259031e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065753665448070819e+01,4.275700353446142117e+02,4.008378213352793651e+00,6.928203299376701096e+00,2.332169075909592271e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.065898003013928985e+01,4.275797646243707959e+02,4.010689298686184401e+00,6.928203299376701096e+00,2.330502409242925510e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066042340579787151e+01,4.275894942891731603e+02,4.012998762440857625e+00,6.928203299376701096e+00,2.328835742576258749e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066186678145645317e+01,4.275992243387510143e+02,4.015306604552661973e+00,6.928203299376701096e+00,2.327169075909591989e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066331015711503483e+01,4.276089547728340676e+02,4.017612824957491391e+00,6.928203299376701096e+00,2.325502409242925228e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066475353277361648e+01,4.276186855911520297e+02,4.019917423591283345e+00,6.928203299376701096e+00,2.323835742576258467e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066619690843219814e+01,4.276284167934346101e+02,4.022220400390021489e+00,6.928203299376701096e+00,2.322169075909591707e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066764028409077980e+01,4.276381483794115184e+02,4.024521755289734770e+00,6.928203299376701096e+00,2.320502409242924946e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.066908365974936146e+01,4.276478803488124072e+02,4.026821488226495660e+00,6.928203299376701096e+00,2.318835742576258185e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067052703540794312e+01,4.276576127013669293e+02,4.029119599136422814e+00,6.928203299376701096e+00,2.317169075909591425e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067197041106652478e+01,4.276673454368047942e+02,4.031416087955680183e+00,6.928203299376701096e+00,2.315502409242924664e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067341378672510643e+01,4.276770785548555978e+02,4.033710954620477018e+00,6.928203299376701096e+00,2.313835742576257903e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067485716238368809e+01,4.276868120552489927e+02,4.036004199067066089e+00,6.928203299376701096e+00,2.312169075909591143e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067630053804226975e+01,4.276965459377146317e+02,4.038295821231746352e+00,6.928203299376701096e+00,2.310502409242924382e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067774391370085141e+01,4.277062802019820538e+02,4.040585821050862059e+00,6.928203299376701096e+00,2.308835742576257621e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.067918728935943307e+01,4.277160148477809116e+02,4.042874198460801871e+00,6.928203299376701096e+00,2.307169075909590861e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068063066501801472e+01,4.277257498748408011e+02,4.045160953397999748e+00,6.928203299376701096e+00,2.305502409242924100e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068207404067659638e+01,4.277354852828913181e+02,4.047446085798934945e+00,6.928203299376701096e+00,2.303835742576257339e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068351741633517804e+01,4.277452210716620016e+02,4.049729595600131127e+00,6.928203299376701096e+00,2.302169075909590579e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068496079199375970e+01,4.277549572408824474e+02,4.052011482738157255e+00,6.928203299376701096e+00,2.300502409242923818e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068640416765234136e+01,4.277646937902821946e+02,4.054291747149628478e+00,6.928203299376701096e+00,2.298835742576257057e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068784754331092302e+01,4.277744307195907822e+02,4.056570388771203461e+00,6.928203299376701096e+00,2.297169075909590297e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.068929091896950467e+01,4.277841680285377493e+02,4.058847407539586172e+00,6.928203299376701096e+00,2.295502409242923536e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069073429462808633e+01,4.277939057168525778e+02,4.061122803391526759e+00,6.928203299376701096e+00,2.293835742576256775e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069217767028666799e+01,4.278036437842648070e+02,4.063396576263819782e+00,6.928203299376701096e+00,2.292169075909590015e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069362104594524965e+01,4.278133822305039189e+02,4.065668726093305096e+00,6.928203299376701096e+00,2.290502409242923254e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069506442160383131e+01,4.278231210552994526e+02,4.067939252816866968e+00,6.928203299376701096e+00,2.288835742576256493e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069650779726241296e+01,4.278328602583808333e+02,4.070208156371434960e+00,6.928203299376701096e+00,2.287169075909589733e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069795117292099462e+01,4.278425998394775434e+02,4.072475436693984818e+00,6.928203299376701096e+00,2.285502409242922972e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.069939454857957628e+01,4.278523397983190080e+02,4.074741093721535812e+00,6.928203299376701096e+00,2.283835742576256211e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070083792423815794e+01,4.278620801346347093e+02,4.077005127391153394e+00,6.928203299376701096e+00,2.282169075909589451e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070228129989673960e+01,4.278718208481540728e+02,4.079267537639947427e+00,6.928203299376701096e+00,2.280502409242922690e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070372467555532126e+01,4.278815619386065237e+02,4.081528324405073072e+00,6.928203299376701096e+00,2.278835742576255929e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070516805121390291e+01,4.278913034057214873e+02,4.083787487623731671e+00,6.928203299376701096e+00,2.277169075909589169e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070661142687248457e+01,4.279010452492283321e+02,4.086045027233168092e+00,6.928203299376701096e+00,2.275502409242922408e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070805480253106623e+01,4.279107874688564834e+02,4.088300943170672497e+00,6.928203299376701096e+00,2.273835742576255647e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.070949817818964789e+01,4.279205300643353098e+02,4.090555235373581233e+00,6.928203299376701096e+00,2.272169075909588887e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071094155384822955e+01,4.279302730353941797e+02,4.092807903779274170e+00,6.928203299376701096e+00,2.270502409242922126e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071238492950681120e+01,4.279400163817624616e+02,4.095058948325178250e+00,6.928203299376701096e+00,2.268835742576255365e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071382830516539286e+01,4.279497601031695240e+02,4.097308368948763935e+00,6.928203299376701096e+00,2.267169075909588605e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071527168082397452e+01,4.279595041993446785e+02,4.099556165587546985e+00,6.928203299376701096e+00,2.265502409242921844e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071671505648255618e+01,4.279692486700172935e+02,4.101802338179089347e+00,6.928203299376701096e+00,2.263835742576255083e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071815843214113784e+01,4.279789935149166240e+02,4.104046886660996485e+00,6.928203299376701096e+00,2.262169075909588323e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.071960180779971950e+01,4.279887387337720384e+02,4.106289810970920939e+00,6.928203299376701096e+00,2.260502409242921562e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072104518345830115e+01,4.279984843263128482e+02,4.108531111046557882e+00,6.928203299376701096e+00,2.258835742576254801e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072248855911688281e+01,4.280082302922683084e+02,4.110770786825650447e+00,6.928203299376701096e+00,2.257169075909588041e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072393193477546447e+01,4.280179766313676737e+02,4.113008838245984400e+00,6.928203299376701096e+00,2.255502409242921280e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072537531043404613e+01,4.280277233433402557e+02,4.115245265245391693e+00,6.928203299376701096e+00,2.253835742576254519e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072681868609262779e+01,4.280374704279153093e+02,4.117480067761749574e+00,6.928203299376701096e+00,2.252169075909587759e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072826206175120944e+01,4.280472178848220324e+02,4.119713245732980589e+00,6.928203299376701096e+00,2.250502409242920998e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.072970543740979110e+01,4.280569657137897366e+02,4.121944799097051693e+00,6.928203299376701096e+00,2.248835742576254237e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073114881306837276e+01,4.280667139145476199e+02,4.124174727791975137e+00,6.928203299376701096e+00,2.247169075909587477e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073259218872695442e+01,4.280764624868248802e+02,4.126403031755808470e+00,6.928203299376701096e+00,2.245502409242920716e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073403556438553608e+01,4.280862114303507155e+02,4.128629710926654539e+00,6.928203299376701096e+00,2.243835742576253955e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073547894004411773e+01,4.280959607448543807e+02,4.130854765242660598e+00,6.928203299376701096e+00,2.242169075909587195e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073692231570269939e+01,4.281057104300650167e+02,4.133078194642020087e+00,6.928203299376701096e+00,2.240502409242920434e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073836569136128105e+01,4.281154604857117647e+02,4.135299999062970855e+00,6.928203299376701096e+00,2.238835742576253673e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.073980906701986271e+01,4.281252109115238227e+02,4.137520178443796937e+00,6.928203299376701096e+00,2.237169075909586913e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074125244267844437e+01,4.281349617072303886e+02,4.139738732722825887e+00,6.928203299376701096e+00,2.235502409242920152e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074269581833702603e+01,4.281447128725605467e+02,4.141955661838431446e+00,6.928203299376701096e+00,2.233835742576253391e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074413919399560768e+01,4.281544644072434949e+02,4.144170965729031764e+00,6.928203299376701096e+00,2.232169075909586631e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074558256965418934e+01,4.281642163110083175e+02,4.146384644333091174e+00,6.928203299376701096e+00,2.230502409242919870e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074702594531277100e+01,4.281739685835840987e+02,4.148596697589118421e+00,6.928203299376701096e+00,2.228835742576253109e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074846932097135266e+01,4.281837212246999798e+02,4.150807125435667544e+00,6.928203299376701096e+00,2.227169075909586349e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.074991269662993432e+01,4.281934742340850448e+02,4.153015927811337882e+00,6.928203299376701096e+00,2.225502409242919588e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.075135607228851597e+01,4.282032276114683782e+02,4.155223104654774069e+00,6.928203299376701096e+00,2.223835742576252827e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.075279944794709763e+01,4.282129813565790641e+02,4.157428655904665149e+00,6.928203299376701096e+00,2.222169075909586067e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.075424282360567929e+01,4.282227354691461301e+02,4.159632581499745463e+00,6.928203299376701096e+00,2.220502409242919306e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.075568619926426095e+01,4.282324899488986603e+02,4.161834881378795536e+00,6.928203299376701096e+00,2.218835742576252545e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.075712957492284261e+01,4.282422447955656821e+02,4.164035555480640305e+00,6.928203299376701096e+00,2.217169075909585785e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.075857295058142427e+01,4.282520000088762799e+02,4.166234603744150000e+00,6.928203299376701096e+00,2.215502409242919024e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076001632624000592e+01,4.282617555885594243e+02,4.168432026108240152e+00,6.928203299376701096e+00,2.213835742576252263e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076145970189858758e+01,4.282715115343440857e+02,4.170627822511870697e+00,6.928203299376701096e+00,2.212169075909585503e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076290307755716924e+01,4.282812678459593485e+02,4.172821992894047760e+00,6.928203299376701096e+00,2.210502409242918742e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076434645321575090e+01,4.282910245231341833e+02,4.175014537193821873e+00,6.928203299376701096e+00,2.208835742576251981e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076578982887433256e+01,4.283007815655975605e+02,4.177205455350288865e+00,6.928203299376701096e+00,2.207169075909585221e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076723320453291421e+01,4.283105389730784509e+02,4.179394747302589863e+00,6.928203299376701096e+00,2.205502409242918460e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.076867658019149587e+01,4.283202967453057681e+02,4.181582412989911290e+00,6.928203299376701096e+00,2.203835742576251699e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077011995585007753e+01,4.283300548820085396e+02,4.183768452351484868e+00,6.928203299376701096e+00,2.202169075909584939e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077156333150865919e+01,4.283398133829156791e+02,4.185952865326587613e+00,6.928203299376701096e+00,2.200502409242918178e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077300670716724085e+01,4.283495722477561003e+02,4.188135651854540953e+00,6.928203299376701096e+00,2.198835742576251417e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077445008282582251e+01,4.283593314762587170e+02,4.190316811874711611e+00,6.928203299376701096e+00,2.197169075909584657e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077589345848440416e+01,4.283690910681524429e+02,4.192496345326512497e+00,6.928203299376701096e+00,2.195502409242917896e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077733683414298582e+01,4.283788510231661917e+02,4.194674252149400040e+00,6.928203299376701096e+00,2.193835742576251135e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.077878020980156748e+01,4.283886113410288772e+02,4.196850532282877744e+00,6.928203299376701096e+00,2.192169075909584375e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078022358546014914e+01,4.283983720214693562e+02,4.199025185666492632e+00,6.928203299376701096e+00,2.190502409242917614e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078166696111873080e+01,4.284081330642164858e+02,4.201198212239838803e+00,6.928203299376701096e+00,2.188835742576250853e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078311033677731245e+01,4.284178944689991795e+02,4.203369611942552986e+00,6.928203299376701096e+00,2.187169075909584093e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078455371243589411e+01,4.284276562355462374e+02,4.205539384714319873e+00,6.928203299376701096e+00,2.185502409242917332e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078599708809447577e+01,4.284374183635865165e+02,4.207707530494866788e+00,6.928203299376701096e+00,2.183835742576250571e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078744046375305743e+01,4.284471808528488168e+02,4.209874049223968129e+00,6.928203299376701096e+00,2.182169075909583811e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.078888383941163909e+01,4.284569437030619952e+02,4.212038940841442702e+00,6.928203299376701096e+00,2.180502409242917050e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079032721507022075e+01,4.284667069139548516e+02,4.214202205287154612e+00,6.928203299376701096e+00,2.178835742576250289e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079177059072880240e+01,4.284764704852561295e+02,4.216363842501013259e+00,6.928203299376701096e+00,2.177169075909583529e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079321396638738406e+01,4.284862344166946855e+02,4.218523852422973341e+00,6.928203299376701096e+00,2.175502409242916768e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079465734204596572e+01,4.284959987079993198e+02,4.220682234993034854e+00,6.928203299376701096e+00,2.173835742576250007e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079610071770454738e+01,4.285057633588987187e+02,4.222838990151242200e+00,6.928203299376701096e+00,2.172169075909583247e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079754409336312904e+01,4.285155283691216823e+02,4.224994117837685081e+00,6.928203299376701096e+00,2.170502409242916486e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.079898746902171069e+01,4.285252937383970107e+02,4.227147617992499384e+00,6.928203299376701096e+00,2.168835742576249725e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080043084468029235e+01,4.285350594664533901e+02,4.229299490555866292e+00,6.928203299376701096e+00,2.167169075909582965e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080187422033887401e+01,4.285448255530195638e+02,4.231449735468010509e+00,6.928203299376701096e+00,2.165502409242916204e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080331759599745567e+01,4.285545919978242182e+02,4.233598352669202924e+00,6.928203299376701096e+00,2.163835742576249443e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080476097165603733e+01,4.285643588005960964e+02,4.235745342099760613e+00,6.928203299376701096e+00,2.162169075909582683e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080620434731461899e+01,4.285741259610638849e+02,4.237890703700044170e+00,6.928203299376701096e+00,2.160502409242915922e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080764772297320064e+01,4.285838934789563268e+02,4.240034437410461265e+00,6.928203299376701096e+00,2.158835742576249161e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.080909109863178230e+01,4.285936613540020517e+02,4.242176543171463088e+00,6.928203299376701096e+00,2.157169075909582401e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081053447429036396e+01,4.286034295859297458e+02,4.244317020923546124e+00,6.928203299376701096e+00,2.155502409242915640e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081197784994894562e+01,4.286131981744680388e+02,4.246455870607253935e+00,6.928203299376701096e+00,2.153835742576248879e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081342122560752728e+01,4.286229671193456170e+02,4.248593092163172713e+00,6.928203299376701096e+00,2.152169075909582119e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081486460126610893e+01,4.286327364202911099e+02,4.250728685531935724e+00,6.928203299376701096e+00,2.150502409242915358e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081630797692469059e+01,4.286425060770331470e+02,4.252862650654221532e+00,6.928203299376701096e+00,2.148835742576248597e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081775135258327225e+01,4.286522760893003010e+02,4.254994987470752221e+00,6.928203299376701096e+00,2.147169075909581837e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.081919472824185391e+01,4.286620464568212583e+02,4.257125695922296948e+00,6.928203299376701096e+00,2.145502409242915076e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082063810390043557e+01,4.286718171793245915e+02,4.259254775949669281e+00,6.928203299376701096e+00,2.143835742576248315e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082208147955901723e+01,4.286815882565388733e+02,4.261382227493728081e+00,6.928203299376701096e+00,2.142169075909581555e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082352485521759888e+01,4.286913596881927333e+02,4.263508050495377510e+00,6.928203299376701096e+00,2.140502409242914794e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082496823087618054e+01,4.287011314740146872e+02,4.265632244895567027e+00,6.928203299376701096e+00,2.138835742576248033e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082641160653476220e+01,4.287109036137333078e+02,4.267754810635290497e+00,6.928203299376701096e+00,2.137169075909581273e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082785498219334386e+01,4.287206761070771677e+02,4.269875747655588860e+00,6.928203299376701096e+00,2.135502409242914512e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.082929835785192552e+01,4.287304489537747827e+02,4.271995055897546578e+00,6.928203299376701096e+00,2.133835742576247752e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083074173351050717e+01,4.287402221535547255e+02,4.274112735302294297e+00,6.928203299376701096e+00,2.132169075909580991e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083218510916908883e+01,4.287499957061455120e+02,4.276228785811007072e+00,6.928203299376701096e+00,2.130502409242914230e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083362848482767049e+01,4.287597696112756012e+02,4.278343207364906142e+00,6.928203299376701096e+00,2.128835742576247470e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083507186048625215e+01,4.287695438686735656e+02,4.280455999905257158e+00,6.928203299376701096e+00,2.127169075909580709e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083651523614483381e+01,4.287793184780678644e+02,4.282567163373371955e+00,6.928203299376701096e+00,2.125502409242913948e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083795861180341547e+01,4.287890934391869564e+02,4.284676697710606774e+00,6.928203299376701096e+00,2.123835742576247188e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.083940198746199712e+01,4.287988687517593576e+02,4.286784602858363158e+00,6.928203299376701096e+00,2.122169075909580427e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084084536312057878e+01,4.288086444155135268e+02,4.288890878758088832e+00,6.928203299376701096e+00,2.120502409242913666e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084228873877916044e+01,4.288184204301778664e+02,4.290995525351275930e+00,6.928203299376701096e+00,2.118835742576246906e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084373211443774210e+01,4.288281967954808920e+02,4.293098542579461885e+00,6.928203299376701096e+00,2.117169075909580145e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084517549009632376e+01,4.288379735111510058e+02,4.295199930384229425e+00,6.928203299376701096e+00,2.115502409242913384e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084661886575490541e+01,4.288477505769166100e+02,4.297299688707207466e+00,6.928203299376701096e+00,2.113835742576246624e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084806224141348707e+01,4.288575279925061636e+02,4.299397817490068441e+00,6.928203299376701096e+00,2.112169075909579863e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.084950561707206873e+01,4.288673057576480119e+02,4.301494316674531859e+00,6.928203299376701096e+00,2.110502409242913102e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085094899273065039e+01,4.288770838720706138e+02,4.303589186202360750e+00,6.928203299376701096e+00,2.108835742576246342e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085239236838923205e+01,4.288868623355023146e+02,4.305682426015364328e+00,6.928203299376701096e+00,2.107169075909579581e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085383574404781371e+01,4.288966411476715166e+02,4.307774036055397993e+00,6.928203299376701096e+00,2.105502409242912820e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085527911970639536e+01,4.289064203083065649e+02,4.309864016264360664e+00,6.928203299376701096e+00,2.103835742576246060e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085672249536497702e+01,4.289161998171358050e+02,4.311952366584197449e+00,6.928203299376701096e+00,2.102169075909579299e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085816587102355868e+01,4.289259796738876389e+02,4.314039086956898750e+00,6.928203299376701096e+00,2.100502409242912538e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.085960924668214034e+01,4.289357598782903551e+02,4.316124177324500266e+00,6.928203299376701096e+00,2.098835742576245778e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086105262234072200e+01,4.289455404300722989e+02,4.318207637629082107e+00,6.928203299376701096e+00,2.097169075909579017e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086249599799930365e+01,4.289553213289617588e+02,4.320289467812771456e+00,6.928203299376701096e+00,2.095502409242912256e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086393937365788531e+01,4.289651025746870801e+02,4.322369667817739014e+00,6.928203299376701096e+00,2.093835742576245496e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086538274931646697e+01,4.289748841669765511e+02,4.324448237586201671e+00,6.928203299376701096e+00,2.092169075909578735e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086682612497504863e+01,4.289846661055584605e+02,4.326525177060420724e+00,6.928203299376701096e+00,2.090502409242911974e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086826950063363029e+01,4.289944483901610965e+02,4.328600486182704543e+00,6.928203299376701096e+00,2.088835742576245214e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.086971287629221194e+01,4.290042310205127478e+02,4.330674164895405021e+00,6.928203299376701096e+00,2.087169075909578453e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087115625195079360e+01,4.290140139963416459e+02,4.332746213140919345e+00,6.928203299376701096e+00,2.085502409242911692e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087259962760937526e+01,4.290237973173760224e+02,4.334816630861691777e+00,6.928203299376701096e+00,2.083835742576244932e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087404300326795692e+01,4.290335809833441090e+02,4.336885418000210102e+00,6.928203299376701096e+00,2.082169075909578171e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087548637892653858e+01,4.290433649939741940e+02,4.338952574499008286e+00,6.928203299376701096e+00,2.080502409242911410e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087692975458512024e+01,4.290531493489944523e+02,4.341018100300664706e+00,6.928203299376701096e+00,2.078835742576244650e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087837313024370189e+01,4.290629340481331155e+02,4.343081995347804813e+00,6.928203299376701096e+00,2.077169075909577889e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.087981650590228355e+01,4.290727190911184152e+02,4.345144259583096691e+00,6.928203299376701096e+00,2.075502409242911128e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088125988156086521e+01,4.290825044776785262e+02,4.347204892949256383e+00,6.928203299376701096e+00,2.073835742576244368e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088270325721944687e+01,4.290922902075415664e+02,4.349263895389043455e+00,6.928203299376701096e+00,2.072169075909577607e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088414663287802853e+01,4.291020762804357673e+02,4.351321266845263658e+00,6.928203299376701096e+00,2.070502409242910846e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088559000853661018e+01,4.291118626960893039e+02,4.353377007260768039e+00,6.928203299376701096e+00,2.068835742576244086e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088703338419519184e+01,4.291216494542303508e+02,4.355431116578452055e+00,6.928203299376701096e+00,2.067169075909577325e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088847675985377350e+01,4.291314365545870260e+02,4.357483594741258237e+00,6.928203299376701096e+00,2.065502409242910564e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.088992013551235516e+01,4.291412239968874474e+02,4.359534441692172635e+00,6.928203299376701096e+00,2.063835742576243804e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.089136351117093682e+01,4.291510117808597329e+02,4.361583657374226597e+00,6.928203299376701096e+00,2.062169075909577043e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.089280688682951848e+01,4.291607999062320573e+02,4.363631241730498544e+00,6.928203299376701096e+00,2.060502409242910282e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.089425026248810013e+01,4.291705883727324817e+02,4.365677194704110420e+00,6.928203299376701096e+00,2.058835742576243522e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.089569363814668179e+01,4.291803771800891241e+02,4.367721516238230350e+00,6.928203299376701096e+00,2.057169075909576761e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.089713701380526345e+01,4.291901663280300454e+02,4.369764206276071761e+00,6.928203299376701096e+00,2.055502409242910000e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.089858038946384511e+01,4.291999558162833637e+02,4.371805264760893373e+00,6.928203299376701096e+00,2.053835742576243240e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090002376512242677e+01,4.292097456445771400e+02,4.373844691635998316e+00,6.928203299376701096e+00,2.052169075909576479e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090146714078100842e+01,4.292195358126393785e+02,4.375882486844736796e+00,6.928203299376701096e+00,2.050502409242909718e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090291051643959008e+01,4.292293263201981972e+02,4.377918650330503425e+00,6.928203299376701096e+00,2.048835742576242958e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090435389209817174e+01,4.292391171669816003e+02,4.379953182036737225e+00,6.928203299376701096e+00,2.047169075909576197e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090579726775675340e+01,4.292489083527176490e+02,4.381986081906924291e+00,6.928203299376701096e+00,2.045502409242909436e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090724064341533506e+01,4.292586998771343474e+02,4.384017349884595127e+00,6.928203299376701096e+00,2.043835742576242676e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.090868401907391672e+01,4.292684917399596998e+02,4.386046985913324647e+00,6.928203299376701096e+00,2.042169075909575915e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091012739473249837e+01,4.292782839409217672e+02,4.388074989936734838e+00,6.928203299376701096e+00,2.040502409242909154e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091157077039108003e+01,4.292880764797484971e+02,4.390101361898492094e+00,6.928203299376701096e+00,2.038835742576242394e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091301414604966169e+01,4.292978693561678369e+02,4.392126101742308997e+00,6.928203299376701096e+00,2.037169075909575633e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091445752170824335e+01,4.293076625699078477e+02,4.394149209411941648e+00,6.928203299376701096e+00,2.035502409242908872e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091590089736682501e+01,4.293174561206964199e+02,4.396170684851193222e+00,6.928203299376701096e+00,2.033835742576242112e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091734427302540666e+01,4.293272500082615579e+02,4.398190528003912192e+00,6.928203299376701096e+00,2.032169075909575351e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.091878764868398832e+01,4.293370442323312091e+02,4.400208738813990550e+00,6.928203299376701096e+00,2.030502409242908590e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092023102434256998e+01,4.293468387926332639e+02,4.402225317225367363e+00,6.928203299376701096e+00,2.028835742576241830e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092167440000115164e+01,4.293566336888956698e+02,4.404240263182026993e+00,6.928203299376701096e+00,2.027169075909575069e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092311777565973330e+01,4.293664289208463742e+02,4.406253576627998214e+00,6.928203299376701096e+00,2.025502409242908308e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092456115131831496e+01,4.293762244882132677e+02,4.408265257507355983e+00,6.928203299376701096e+00,2.023835742576241548e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092600452697689661e+01,4.293860203907242976e+02,4.410275305764220555e+00,6.928203299376701096e+00,2.022169075909574787e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092744790263547827e+01,4.293958166281072977e+02,4.412283721342756593e+00,6.928203299376701096e+00,2.020502409242908026e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.092889127829405993e+01,4.294056132000901584e+02,4.414290504187174946e+00,6.928203299376701096e+00,2.018835742576241266e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093033465395264159e+01,4.294154101064007705e+02,4.416295654241731761e+00,6.928203299376701096e+00,2.017169075909574505e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093177802961122325e+01,4.294252073467669675e+02,4.418299171450728480e+00,6.928203299376701096e+00,2.015502409242907744e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093322140526980490e+01,4.294350049209166400e+02,4.420301055758511843e+00,6.928203299376701096e+00,2.013835742576240984e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093466478092838656e+01,4.294448028285776218e+02,4.422301307109473889e+00,6.928203299376701096e+00,2.012169075909574223e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093610815658696822e+01,4.294546010694777465e+02,4.424299925448051951e+00,6.928203299376701096e+00,2.010502409242907462e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093755153224554988e+01,4.294643996433448478e+02,4.426296910718728661e+00,6.928203299376701096e+00,2.008835742576240702e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.093899490790413154e+01,4.294741985499067027e+02,4.428292262866032836e+00,6.928203299376701096e+00,2.007169075909573941e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094043828356271320e+01,4.294839977888911449e+02,4.430285981834537701e+00,6.928203299376701096e+00,2.005502409242907180e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094188165922129485e+01,4.294937973600260079e+02,4.432278067568861779e+00,6.928203299376701096e+00,2.003835742576240420e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094332503487987651e+01,4.295035972630390688e+02,4.434268520013669779e+00,6.928203299376701096e+00,2.002169075909573659e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094476841053845817e+01,4.295133974976580475e+02,4.436257339113671705e+00,6.928203299376701096e+00,2.000502409242906898e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094621178619703983e+01,4.295231980636107778e+02,4.438244524813621972e+00,6.928203299376701096e+00,1.998835742576240138e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094765516185562149e+01,4.295329989606250365e+02,4.440230077058321179e+00,6.928203299376701096e+00,1.997169075909573377e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.094909853751420314e+01,4.295428001884285436e+02,4.442213995792615222e+00,6.928203299376701096e+00,1.995502409242906616e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095054191317278480e+01,4.295526017467490192e+02,4.444196280961395296e+00,6.928203299376701096e+00,1.993835742576239856e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095198528883136646e+01,4.295624036353142401e+02,4.446176932509597890e+00,6.928203299376701096e+00,1.992169075909573095e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095342866448994812e+01,4.295722058538518695e+02,4.448155950382204793e+00,6.928203299376701096e+00,1.990502409242906334e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095487204014852978e+01,4.295820084020896843e+02,4.450133334524243089e+00,6.928203299376701096e+00,1.988835742576239574e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095631541580711144e+01,4.295918112797554045e+02,4.452109084880786050e+00,6.928203299376701096e+00,1.987169075909572813e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095775879146569309e+01,4.296016144865766933e+02,4.454083201396951353e+00,6.928203299376701096e+00,1.985502409242906052e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.095920216712427475e+01,4.296114180222812138e+02,4.456055684017901974e+00,6.928203299376701096e+00,1.983835742576239292e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096064554278285641e+01,4.296212218865966861e+02,4.458026532688847077e+00,6.928203299376701096e+00,1.982169075909572531e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096208891844143807e+01,4.296310260792507734e+02,4.459995747355041118e+00,6.928203299376701096e+00,1.980502409242905770e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096353229410001973e+01,4.296408305999711388e+02,4.461963327961783854e+00,6.928203299376701096e+00,1.978835742576239010e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096497566975860138e+01,4.296506354484854455e+02,4.463929274454419449e+00,6.928203299376701096e+00,1.977169075909572249e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096641904541718304e+01,4.296604406245212999e+02,4.465893586778339142e+00,6.928203299376701096e+00,1.975502409242905488e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096786242107576470e+01,4.296702461278063652e+02,4.467856264878977690e+00,6.928203299376701096e+00,1.973835742576238728e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.096930579673434636e+01,4.296800519580682476e+02,4.469817308701816927e+00,6.928203299376701096e+00,1.972169075909571967e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097074917239292802e+01,4.296898581150345535e+02,4.471776718192383981e+00,6.928203299376701096e+00,1.970502409242905206e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097219254805150968e+01,4.296996645984329461e+02,4.473734493296249504e+00,6.928203299376701096e+00,1.968835742576238446e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097363592371009133e+01,4.297094714079909750e+02,4.475690633959032105e+00,6.928203299376701096e+00,1.967169075909571685e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097507929936867299e+01,4.297192785434362463e+02,4.477645140126393919e+00,6.928203299376701096e+00,1.965502409242904924e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097652267502725465e+01,4.297290860044963097e+02,4.479598011744043262e+00,6.928203299376701096e+00,1.963835742576238164e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097796605068583631e+01,4.297388937908987714e+02,4.481549248757732862e+00,6.928203299376701096e+00,1.962169075909571403e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.097940942634441797e+01,4.297487019023711809e+02,4.483498851113262518e+00,6.928203299376701096e+00,1.960502409242904642e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098085280200299962e+01,4.297585103386410879e+02,4.485446818756476439e+00,6.928203299376701096e+00,1.958835742576237882e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098229617766158128e+01,4.297683190994360416e+02,4.487393151633265020e+00,6.928203299376701096e+00,1.957169075909571121e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098373955332016294e+01,4.297781281844835917e+02,4.489337849689563065e+00,6.928203299376701096e+00,1.955502409242904360e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098518292897874460e+01,4.297879375935112307e+02,4.491280912871350672e+00,6.928203299376701096e+00,1.953835742576237600e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098662630463732626e+01,4.297977473262465082e+02,4.493222341124654129e+00,6.928203299376701096e+00,1.952169075909570839e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098806968029590792e+01,4.298075573824169169e+02,4.495162134395545017e+00,6.928203299376701096e+00,1.950502409242904078e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.098951305595448957e+01,4.298173677617499493e+02,4.497100292630140217e+00,6.928203299376701096e+00,1.948835742576237318e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099095643161307123e+01,4.298271784639730981e+02,4.499036815774601905e+00,6.928203299376701096e+00,1.947169075909570557e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099239980727165289e+01,4.298369894888137992e+02,4.500971703775138444e+00,6.928203299376701096e+00,1.945502409242903796e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099384318293023455e+01,4.298468008359996020e+02,4.502904956578001716e+00,6.928203299376701096e+00,1.943835742576237036e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099528655858881621e+01,4.298566125052579423e+02,4.504836574129491567e+00,6.928203299376701096e+00,1.942169075909570275e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099672993424739786e+01,4.298664244963162560e+02,4.506766556375950472e+00,6.928203299376701096e+00,1.940502409242903514e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099817330990597952e+01,4.298762368089019787e+02,4.508694903263768872e+00,6.928203299376701096e+00,1.938835742576236754e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.099961668556456118e+01,4.298860494427426033e+02,4.510621614739381613e+00,6.928203299376701096e+00,1.937169075909569993e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100106006122314284e+01,4.298958623975655087e+02,4.512546690749267952e+00,6.928203299376701096e+00,1.935502409242903232e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100250343688172450e+01,4.299056756730981306e+02,4.514470131239954220e+00,6.928203299376701096e+00,1.933835742576236472e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100394681254030615e+01,4.299154892690678480e+02,4.516391936158012044e+00,6.928203299376701096e+00,1.932169075909569711e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100539018819888781e+01,4.299253031852020968e+02,4.518312105450057459e+00,6.928203299376701096e+00,1.930502409242902950e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100683356385746947e+01,4.299351174212282558e+02,4.520230639062751798e+00,6.928203299376701096e+00,1.928835742576236190e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100827693951605113e+01,4.299449319768737041e+02,4.522147536942803470e+00,6.928203299376701096e+00,1.927169075909569429e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.100972031517463279e+01,4.299547468518658206e+02,4.524062799036965288e+00,6.928203299376701096e+00,1.925502409242902668e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101116369083321445e+01,4.299645620459319844e+02,4.525976425292034477e+00,6.928203299376701096e+00,1.923835742576235908e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101260706649179610e+01,4.299743775587995174e+02,4.527888415654855336e+00,6.928203299376701096e+00,1.922169075909569147e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101405044215037776e+01,4.299841933901957987e+02,4.529798770072317460e+00,6.928203299376701096e+00,1.920502409242902386e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101549381780895942e+01,4.299940095398481503e+02,4.531707488491354852e+00,6.928203299376701096e+00,1.918835742576235626e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101693719346754108e+01,4.300038260074838945e+02,4.533614570858947701e+00,6.928203299376701096e+00,1.917169075909568865e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101838056912612274e+01,4.300136427928303533e+02,4.535520017122121494e+00,6.928203299376701096e+00,1.915502409242902104e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.101982394478470439e+01,4.300234598956148488e+02,4.537423827227947903e+00,6.928203299376701096e+00,1.913835742576235344e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102126732044328605e+01,4.300332773155646464e+02,4.539326001123542120e+00,6.928203299376701096e+00,1.912169075909568583e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102271069610186771e+01,4.300430950524070681e+02,4.541226538756066411e+00,6.928203299376701096e+00,1.910502409242901822e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102415407176044937e+01,4.300529131058694361e+02,4.543125440072728338e+00,6.928203299376701096e+00,1.908835742576235062e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102559744741903103e+01,4.300627314756789588e+02,4.545022705020780762e+00,6.928203299376701096e+00,1.907169075909568301e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102704082307761269e+01,4.300725501615629582e+02,4.546918333547521840e+00,6.928203299376701096e+00,1.905502409242901540e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102848419873619434e+01,4.300823691632486430e+02,4.548812325600295026e+00,6.928203299376701096e+00,1.903835742576234780e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.102992757439477600e+01,4.300921884804633351e+02,4.550704681126489071e+00,6.928203299376701096e+00,1.902169075909568019e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.103137095005335766e+01,4.301020081129342429e+02,4.552595400073538912e+00,6.928203299376701096e+00,1.900502409242901258e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.103281432571193932e+01,4.301118280603885751e+02,4.554484482388924782e+00,6.928203299376701096e+00,1.898835742576234498e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.103425770137052098e+01,4.301216483225535399e+02,4.556371928020171325e+00,6.928203299376701096e+00,1.897169075909567737e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.103570107702910263e+01,4.301314688991564026e+02,4.558257736914850256e+00,6.928203299376701096e+00,1.895502409242900976e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.103714445268768429e+01,4.301412897899243717e+02,4.560141909020577700e+00,6.928203299376701096e+00,1.893835742576234216e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.103858782834626595e+01,4.301511109945845988e+02,4.562024444285015967e+00,6.928203299376701096e+00,1.892169075909567455e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104003120400484761e+01,4.301609325128642922e+02,4.563905342655871777e+00,6.928203299376701096e+00,1.890502409242900694e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104147457966342927e+01,4.301707543444906605e+02,4.565784604080898923e+00,6.928203299376701096e+00,1.888835742576233934e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104291795532201093e+01,4.301805764891908552e+02,4.567662228507894717e+00,6.928203299376701096e+00,1.887169075909567173e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104436133098059258e+01,4.301903989466920279e+02,4.569538215884703547e+00,6.928203299376701096e+00,1.885502409242900412e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104580470663917424e+01,4.302002217167213303e+02,4.571412566159214208e+00,6.928203299376701096e+00,1.883835742576233652e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104724808229775590e+01,4.302100447990059138e+02,4.573285279279361681e+00,6.928203299376701096e+00,1.882169075909566891e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.104869145795633756e+01,4.302198681932729301e+02,4.575156355193126245e+00,6.928203299376701096e+00,1.880502409242900130e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105013483361491922e+01,4.302296918992494739e+02,4.577025793848533475e+00,6.928203299376701096e+00,1.878835742576233370e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105157820927350087e+01,4.302395159166626968e+02,4.578893595193654242e+00,6.928203299376701096e+00,1.877169075909566609e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105302158493208253e+01,4.302493402452396936e+02,4.580759759176604717e+00,6.928203299376701096e+00,1.875502409242899848e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105446496059066419e+01,4.302591648847075589e+02,4.582624285745548143e+00,6.928203299376701096e+00,1.873835742576233088e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105590833624924585e+01,4.302689898347933877e+02,4.584487174848691282e+00,6.928203299376701096e+00,1.872169075909566327e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105735171190782751e+01,4.302788150952242745e+02,4.586348426434287973e+00,6.928203299376701096e+00,1.870502409242899566e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.105879508756640917e+01,4.302886406657273142e+02,4.588208040450636460e+00,6.928203299376701096e+00,1.868835742576232806e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106023846322499082e+01,4.302984665460295446e+02,4.590066016846080288e+00,6.928203299376701096e+00,1.867169075909566045e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106168183888357248e+01,4.303082927358580605e+02,4.591922355569010072e+00,6.928203299376701096e+00,1.865502409242899284e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106312521454215414e+01,4.303181192349398998e+02,4.593777056567859951e+00,6.928203299376701096e+00,1.863835742576232524e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106456859020073580e+01,4.303279460430020436e+02,4.595630119791110246e+00,6.928203299376701096e+00,1.862169075909565763e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106601196585931746e+01,4.303377731597715865e+02,4.597481545187287466e+00,6.928203299376701096e+00,1.860502409242899002e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106745534151789911e+01,4.303476005849755666e+02,4.599331332704963415e+00,6.928203299376701096e+00,1.858835742576232242e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.106889871717648077e+01,4.303574283183409648e+02,4.601179482292754308e+00,6.928203299376701096e+00,1.857169075909565481e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107034209283506243e+01,4.303672563595947622e+02,4.603025993899323431e+00,6.928203299376701096e+00,1.855502409242898720e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107178546849364409e+01,4.303770847084639968e+02,4.604870867473378482e+00,6.928203299376701096e+00,1.853835742576231960e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107322884415222575e+01,4.303869133646756495e+02,4.606714102963673341e+00,6.928203299376701096e+00,1.852169075909565199e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107467221981080741e+01,4.303967423279567583e+02,4.608555700319006299e+00,6.928203299376701096e+00,1.850502409242898438e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107611559546938906e+01,4.304065715980341906e+02,4.610395659488222719e+00,6.928203299376701096e+00,1.848835742576231678e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107755897112797072e+01,4.304164011746349843e+02,4.612233980420211488e+00,6.928203299376701096e+00,1.847169075909564917e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.107900234678655238e+01,4.304262310574860635e+02,4.614070663063909450e+00,6.928203299376701096e+00,1.845502409242898156e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108044572244513404e+01,4.304360612463144093e+02,4.615905707368296973e+00,6.928203299376701096e+00,1.843835742576231396e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108188909810371570e+01,4.304458917408469460e+02,4.617739113282400609e+00,6.928203299376701096e+00,1.842169075909564635e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108333247376229735e+01,4.304557225408105978e+02,4.619570880755292208e+00,6.928203299376701096e+00,1.840502409242897874e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108477584942087901e+01,4.304655536459322889e+02,4.621401009736089804e+00,6.928203299376701096e+00,1.838835742576231114e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108621922507946067e+01,4.304753850559389434e+02,4.623229500173955842e+00,6.928203299376701096e+00,1.837169075909564353e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108766260073804233e+01,4.304852167705574288e+02,4.625056352018099837e+00,6.928203299376701096e+00,1.835502409242897592e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.108910597639662399e+01,4.304950487895146694e+02,4.626881565217774828e+00,6.928203299376701096e+00,1.833835742576230832e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109054935205520565e+01,4.305048811125375892e+02,4.628705139722280926e+00,6.928203299376701096e+00,1.832169075909564071e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109199272771378730e+01,4.305147137393529988e+02,4.630527075480963539e+00,6.928203299376701096e+00,1.830502409242897310e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109343610337236896e+01,4.305245466696878225e+02,4.632347372443213374e+00,6.928203299376701096e+00,1.828835742576230550e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109487947903095062e+01,4.305343799032688707e+02,4.634166030558466431e+00,6.928203299376701096e+00,1.827169075909563789e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109632285468953228e+01,4.305442134398230678e+02,4.635983049776204012e+00,6.928203299376701096e+00,1.825502409242897028e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109776623034811394e+01,4.305540472790772242e+02,4.637798430045954490e+00,6.928203299376701096e+00,1.823835742576230268e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.109920960600669559e+01,4.305638814207581504e+02,4.639612171317289757e+00,6.928203299376701096e+00,1.822169075909563507e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110065298166527725e+01,4.305737158645927138e+02,4.641424273539827894e+00,6.928203299376701096e+00,1.820502409242896746e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110209635732385891e+01,4.305835506103077250e+02,4.643234736663233164e+00,6.928203299376701096e+00,1.818835742576229986e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110353973298244057e+01,4.305933856576299945e+02,4.645043560637215130e+00,6.928203299376701096e+00,1.817169075909563225e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110498310864102223e+01,4.306032210062863328e+02,4.646850745411528649e+00,6.928203299376701096e+00,1.815502409242896464e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110642648429960389e+01,4.306130566560034936e+02,4.648656290935973878e+00,6.928203299376701096e+00,1.813835742576229704e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110786985995818554e+01,4.306228926065083442e+02,4.650460197160396270e+00,6.928203299376701096e+00,1.812169075909562943e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.110931323561676720e+01,4.306327288575275816e+02,4.652262464034688350e+00,6.928203299376701096e+00,1.810502409242896182e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111075661127534886e+01,4.306425654087880162e+02,4.654063091508786165e+00,6.928203299376701096e+00,1.808835742576229422e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111219998693393052e+01,4.306524022600164017e+02,4.655862079532672837e+00,6.928203299376701096e+00,1.807169075909562661e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111364336259251218e+01,4.306622394109395486e+02,4.657659428056376782e+00,6.928203299376701096e+00,1.805502409242895900e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111508673825109383e+01,4.306720768612841539e+02,4.659455137029970828e+00,6.928203299376701096e+00,1.803835742576229140e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111653011390967549e+01,4.306819146107769143e+02,4.661249206403574874e+00,6.928203299376701096e+00,1.802169075909562379e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111797348956825715e+01,4.306917526591446403e+02,4.663041636127353229e+00,6.928203299376701096e+00,1.800502409242895618e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.111941686522683881e+01,4.307015910061139721e+02,4.664832426151516387e+00,6.928203299376701096e+00,1.798835742576228858e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112086024088542047e+01,4.307114296514116631e+02,4.666621576426320139e+00,6.928203299376701096e+00,1.797169075909562097e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112230361654400213e+01,4.307212685947644104e+02,4.668409086902066463e+00,6.928203299376701096e+00,1.795502409242895336e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112374699220258378e+01,4.307311078358989676e+02,4.670194957529101742e+00,6.928203299376701096e+00,1.793835742576228576e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112519036786116544e+01,4.307409473745419746e+02,4.671979188257817661e+00,6.928203299376701096e+00,1.792169075909561815e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112663374351974710e+01,4.307507872104200715e+02,4.673761779038653863e+00,6.928203299376701096e+00,1.790502409242895054e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112807711917832876e+01,4.307606273432599551e+02,4.675542729822092625e+00,6.928203299376701096e+00,1.788835742576228294e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.112952049483691042e+01,4.307704677727883222e+02,4.677322040558663296e+00,6.928203299376701096e+00,1.787169075909561533e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113096387049549207e+01,4.307803084987318130e+02,4.679099711198941414e+00,6.928203299376701096e+00,1.785502409242894772e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113240724615407373e+01,4.307901495208170672e+02,4.680875741693546033e+00,6.928203299376701096e+00,1.783835742576228012e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113385062181265539e+01,4.307999908387707251e+02,4.682650131993144171e+00,6.928203299376701096e+00,1.782169075909561251e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113529399747123705e+01,4.308098324523194265e+02,4.684422882048446368e+00,6.928203299376701096e+00,1.780502409242894490e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113673737312981871e+01,4.308196743611897546e+02,4.686193991810210235e+00,6.928203299376701096e+00,1.778835742576227730e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113818074878840036e+01,4.308295165651083494e+02,4.687963461229237794e+00,6.928203299376701096e+00,1.777169075909560969e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.113962412444698202e+01,4.308393590638017940e+02,4.689731290256377250e+00,6.928203299376701096e+00,1.775502409242894208e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114106750010556368e+01,4.308492018569967286e+02,4.691497478842522106e+00,6.928203299376701096e+00,1.773835742576227448e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114251087576414534e+01,4.308590449444197361e+02,4.693262026938611164e+00,6.928203299376701096e+00,1.772169075909560687e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114395425142272700e+01,4.308688883257973430e+02,4.695024934495630298e+00,6.928203299376701096e+00,1.770502409242893926e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114539762708130866e+01,4.308787320008561892e+02,4.696786201464608901e+00,6.928203299376701096e+00,1.768835742576227166e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114684100273989031e+01,4.308885759693228010e+02,4.698545827796623442e+00,6.928203299376701096e+00,1.767169075909560405e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114828437839847197e+01,4.308984202309237617e+02,4.700303813442794798e+00,6.928203299376701096e+00,1.765502409242893644e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.114972775405705363e+01,4.309082647853855974e+02,4.702060158354290920e+00,6.928203299376701096e+00,1.763835742576226884e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115117112971563529e+01,4.309181096324348346e+02,4.703814862482324166e+00,6.928203299376701096e+00,1.762169075909560123e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115261450537421695e+01,4.309279547717980563e+02,4.705567925778152194e+00,6.928203299376701096e+00,1.760502409242893362e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115405788103279860e+01,4.309378002032017321e+02,4.707319348193079733e+00,6.928203299376701096e+00,1.758835742576226602e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115550125669138026e+01,4.309476459263723882e+02,4.709069129678455035e+00,6.928203299376701096e+00,1.757169075909559841e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115694463234996192e+01,4.309574919410365510e+02,4.710817270185673422e+00,6.928203299376701096e+00,1.755502409242893080e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115838800800854358e+01,4.309673382469207468e+02,4.712563769666176405e+00,6.928203299376701096e+00,1.753835742576226320e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.115983138366712524e+01,4.309771848437513881e+02,4.714308628071449014e+00,6.928203299376701096e+00,1.752169075909559559e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116127475932570690e+01,4.309870317312550014e+02,4.716051845353023353e+00,6.928203299376701096e+00,1.750502409242892798e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116271813498428855e+01,4.309968789091581129e+02,4.717793421462476822e+00,6.928203299376701096e+00,1.748835742576226038e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116416151064287021e+01,4.310067263771871353e+02,4.719533356351432118e+00,6.928203299376701096e+00,1.747169075909559277e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116560488630145187e+01,4.310165741350685380e+02,4.721271649971557238e+00,6.928203299376701096e+00,1.745502409242892516e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116704826196003353e+01,4.310264221825287336e+02,4.723008302274567249e+00,6.928203299376701096e+00,1.743835742576225756e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116849163761861519e+01,4.310362705192941917e+02,4.724743313212220741e+00,6.928203299376701096e+00,1.742169075909558995e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.116993501327719684e+01,4.310461191450913816e+02,4.726476682736324264e+00,6.928203299376701096e+00,1.740502409242892234e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.117137838893577850e+01,4.310559680596467160e+02,4.728208410798727890e+00,6.928203299376701096e+00,1.738835742576225474e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.117282176459436016e+01,4.310658172626866076e+02,4.729938497351327875e+00,6.928203299376701096e+00,1.737169075909558713e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.117426514025294182e+01,4.310756667539374121e+02,4.731666942346066662e+00,6.928203299376701096e+00,1.735502409242891952e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.117570851591152348e+01,4.310855165331255989e+02,4.733393745734931990e+00,6.928203299376701096e+00,1.733835742576225192e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.117715189157010514e+01,4.310953665999775808e+02,4.735118907469956007e+00,6.928203299376701096e+00,1.732169075909558431e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.117859526722868679e+01,4.311052169542197134e+02,4.736842427503218822e+00,6.928203299376701096e+00,1.730502409242891670e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118003864288726845e+01,4.311150675955783527e+02,4.738564305786844066e+00,6.928203299376701096e+00,1.728835742576224910e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118148201854585011e+01,4.311249185237798542e+02,4.740284542273002444e+00,6.928203299376701096e+00,1.727169075909558149e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118292539420443177e+01,4.311347697385506308e+02,4.742003136913909067e+00,6.928203299376701096e+00,1.725502409242891388e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118436876986301343e+01,4.311446212396170381e+02,4.743720089661826123e+00,6.928203299376701096e+00,1.723835742576224628e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118581214552159508e+01,4.311544730267054319e+02,4.745435400469059317e+00,6.928203299376701096e+00,1.722169075909557867e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118725552118017674e+01,4.311643250995421113e+02,4.747149069287961431e+00,6.928203299376701096e+00,1.720502409242891106e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.118869889683875840e+01,4.311741774578534319e+02,4.748861096070931431e+00,6.928203299376701096e+00,1.718835742576224346e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119014227249734006e+01,4.311840301013656926e+02,4.750571480770411803e+00,6.928203299376701096e+00,1.717169075909557585e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119158564815592172e+01,4.311938830298052494e+02,4.752280223338892995e+00,6.928203299376701096e+00,1.715502409242890824e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119302902381450338e+01,4.312037362428983442e+02,4.753987323728908976e+00,6.928203299376701096e+00,1.713835742576224064e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119447239947308503e+01,4.312135897403713329e+02,4.755692781893040788e+00,6.928203299376701096e+00,1.712169075909557303e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119591577513166669e+01,4.312234435219505144e+02,4.757396597783913883e+00,6.928203299376701096e+00,1.710502409242890542e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119735915079024835e+01,4.312332975873621308e+02,4.759098771354200785e+00,6.928203299376701096e+00,1.708835742576223782e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.119880252644883001e+01,4.312431519363324810e+02,4.760799302556619317e+00,6.928203299376701096e+00,1.707169075909557021e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120024590210741167e+01,4.312530065685878640e+02,4.762498191343931708e+00,6.928203299376701096e+00,1.705502409242890260e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120168927776599332e+01,4.312628614838544650e+02,4.764195437668946376e+00,6.928203299376701096e+00,1.703835742576223500e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120313265342457498e+01,4.312727166818585829e+02,4.765891041484517920e+00,6.928203299376701096e+00,1.702169075909556739e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120457602908315664e+01,4.312825721623264599e+02,4.767585002743546241e+00,6.928203299376701096e+00,1.700502409242889978e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120601940474173830e+01,4.312924279249843380e+02,4.769277321398977421e+00,6.928203299376701096e+00,1.698835742576223218e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120746278040031996e+01,4.313022839695584594e+02,4.770967997403801952e+00,6.928203299376701096e+00,1.697169075909556457e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.120890615605890162e+01,4.313121402957750092e+02,4.772657030711056514e+00,6.928203299376701096e+00,1.695502409242889696e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121034953171748327e+01,4.313219969033602297e+02,4.774344421273823968e+00,6.928203299376701096e+00,1.693835742576222936e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121179290737606493e+01,4.313318537920403060e+02,4.776030169045232476e+00,6.928203299376701096e+00,1.692169075909556175e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121323628303464659e+01,4.313417109615414233e+02,4.777714273978455495e+00,6.928203299376701096e+00,1.690502409242889414e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121467965869322825e+01,4.313515684115898239e+02,4.779396736026711778e+00,6.928203299376701096e+00,1.688835742576222654e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121612303435180991e+01,4.313614261419116360e+02,4.781077555143267155e+00,6.928203299376701096e+00,1.687169075909555893e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121756641001039156e+01,4.313712841522330450e+02,4.782756731281431861e+00,6.928203299376701096e+00,1.685502409242889132e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.121900978566897322e+01,4.313811424422802361e+02,4.784434264394561431e+00,6.928203299376701096e+00,1.683835742576222372e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122045316132755488e+01,4.313910010117793377e+02,4.786110154436058473e+00,6.928203299376701096e+00,1.682169075909555611e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122189653698613654e+01,4.314008598604565350e+02,4.787784401359370889e+00,6.928203299376701096e+00,1.680502409242888850e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122333991264471820e+01,4.314107189880379565e+02,4.789457005117990995e+00,6.928203299376701096e+00,1.678835742576222090e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122478328830329986e+01,4.314205783942497305e+02,4.791127965665458177e+00,6.928203299376701096e+00,1.677169075909555329e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122622666396188151e+01,4.314304380788179856e+02,4.792797282955356231e+00,6.928203299376701096e+00,1.675502409242888568e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122767003962046317e+01,4.314402980414688500e+02,4.794464956941316025e+00,6.928203299376701096e+00,1.673835742576221808e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.122911341527904483e+01,4.314501582819284522e+02,4.796130987577012839e+00,6.928203299376701096e+00,1.672169075909555047e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123055679093762649e+01,4.314600187999228638e+02,4.797795374816167246e+00,6.928203299376701096e+00,1.670502409242888286e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123200016659620815e+01,4.314698795951782131e+02,4.799458118612547786e+00,6.928203299376701096e+00,1.668835742576221526e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123344354225478980e+01,4.314797406674205718e+02,4.801119218919965626e+00,6.928203299376701096e+00,1.667169075909554765e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123488691791337146e+01,4.314896020163760113e+02,4.802778675692279897e+00,6.928203299376701096e+00,1.665502409242888004e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123633029357195312e+01,4.314994636417706033e+02,4.804436488883395029e+00,6.928203299376701096e+00,1.663835742576221244e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123777366923053478e+01,4.315093255433304194e+02,4.806092658447259858e+00,6.928203299376701096e+00,1.662169075909554483e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.123921704488911644e+01,4.315191877207815310e+02,4.807747184337870294e+00,6.928203299376701096e+00,1.660502409242887722e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124066042054769810e+01,4.315290501738500097e+02,4.809400066509266658e+00,6.928203299376701096e+00,1.658835742576220962e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124210379620627975e+01,4.315389129022618704e+02,4.811051304915536342e+00,6.928203299376701096e+00,1.657169075909554201e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124354717186486141e+01,4.315487759057431276e+02,4.812700899510811148e+00,6.928203299376701096e+00,1.655502409242887440e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124499054752344307e+01,4.315586391840198530e+02,4.814348850249268175e+00,6.928203299376701096e+00,1.653835742576220680e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124643392318202473e+01,4.315685027368180045e+02,4.815995157085132483e+00,6.928203299376701096e+00,1.652169075909553919e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124787729884060639e+01,4.315783665638636535e+02,4.817639819972672655e+00,6.928203299376701096e+00,1.650502409242887158e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.124932067449918804e+01,4.315882306648827580e+02,4.819282838866203456e+00,6.928203299376701096e+00,1.648835742576220398e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125076405015776970e+01,4.315980950396013895e+02,4.820924213720085838e+00,6.928203299376701096e+00,1.647169075909553637e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125220742581635136e+01,4.316079596877454492e+02,4.822563944488725163e+00,6.928203299376701096e+00,1.645502409242886876e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125365080147493302e+01,4.316178246090409516e+02,4.824202031126574752e+00,6.928203299376701096e+00,1.643835742576220116e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125509417713351468e+01,4.316276898032139115e+02,4.825838473588131450e+00,6.928203299376701096e+00,1.642169075909553355e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125653755279209633e+01,4.316375552699902300e+02,4.827473271827938284e+00,6.928203299376701096e+00,1.640502409242886594e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125798092845067799e+01,4.316474210090959218e+02,4.829106425800584468e+00,6.928203299376701096e+00,1.638835742576219834e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.125942430410925965e+01,4.316572870202569447e+02,4.830737935460704513e+00,6.928203299376701096e+00,1.637169075909553073e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126086767976784131e+01,4.316671533031991999e+02,4.832367800762979115e+00,6.928203299376701096e+00,1.635502409242886313e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126231105542642297e+01,4.316770198576486450e+02,4.833996021662133380e+00,6.928203299376701096e+00,1.633835742576219552e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126375443108500463e+01,4.316868866833311813e+02,4.835622598112939485e+00,6.928203299376701096e+00,1.632169075909552791e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126519780674358628e+01,4.316967537799727666e+02,4.837247530070214907e+00,6.928203299376701096e+00,1.630502409242886031e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126664118240216794e+01,4.317066211472993018e+02,4.838870817488822418e+00,6.928203299376701096e+00,1.628835742576219270e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126808455806074960e+01,4.317164887850366881e+02,4.840492460323670976e+00,6.928203299376701096e+00,1.627169075909552509e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.126952793371933126e+01,4.317263566929108265e+02,4.842112458529714836e+00,6.928203299376701096e+00,1.625502409242885749e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127097130937791292e+01,4.317362248706476180e+02,4.843730812061954438e+00,6.928203299376701096e+00,1.623835742576218988e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127241468503649457e+01,4.317460933179729068e+02,4.845347520875434633e+00,6.928203299376701096e+00,1.622169075909552227e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127385806069507623e+01,4.317559620346126508e+02,4.846962584925247342e+00,6.928203299376701096e+00,1.620502409242885467e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127530143635365789e+01,4.317658310202926373e+02,4.848576004166529785e+00,6.928203299376701096e+00,1.618835742576218706e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127674481201223955e+01,4.317757002747387673e+02,4.850187778554464479e+00,6.928203299376701096e+00,1.617169075909551945e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127818818767082121e+01,4.317855697976768852e+02,4.851797908044280128e+00,6.928203299376701096e+00,1.615502409242885185e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.127963156332940287e+01,4.317954395888328349e+02,4.853406392591250729e+00,6.928203299376701096e+00,1.613835742576218424e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128107493898798452e+01,4.318053096479324608e+02,4.855013232150696467e+00,6.928203299376701096e+00,1.612169075909551663e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128251831464656618e+01,4.318151799747016071e+02,4.856618426677981937e+00,6.928203299376701096e+00,1.610502409242884903e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128396169030514784e+01,4.318250505688660610e+02,4.858221976128519692e+00,6.928203299376701096e+00,1.608835742576218142e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128540506596372950e+01,4.318349214301516668e+02,4.859823880457765810e+00,6.928203299376701096e+00,1.607169075909551381e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128684844162231116e+01,4.318447925582842686e+02,4.861424139621223439e+00,6.928203299376701096e+00,1.605502409242884621e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128829181728089281e+01,4.318546639529895970e+02,4.863022753574441026e+00,6.928203299376701096e+00,1.603835742576217860e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.128973519293947447e+01,4.318645356139934961e+02,4.864619722273012314e+00,6.928203299376701096e+00,1.602169075909551099e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129117856859805613e+01,4.318744075410217533e+02,4.866215045672577233e+00,6.928203299376701096e+00,1.600502409242884339e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129262194425663779e+01,4.318842797338000992e+02,4.867808723728821008e+00,6.928203299376701096e+00,1.598835742576217578e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129406531991521945e+01,4.318941521920543778e+02,4.869400756397475050e+00,6.928203299376701096e+00,1.597169075909550817e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129550869557380111e+01,4.319040249155102629e+02,4.870991143634316067e+00,6.928203299376701096e+00,1.595502409242884057e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129695207123238276e+01,4.319138979038935986e+02,4.872579885395166066e+00,6.928203299376701096e+00,1.593835742576217296e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129839544689096442e+01,4.319237711569301155e+02,4.874166981635894125e+00,6.928203299376701096e+00,1.592169075909550535e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.129983882254954608e+01,4.319336446743455440e+02,4.875752432312413731e+00,6.928203299376701096e+00,1.590502409242883775e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130128219820812774e+01,4.319435184558656147e+02,4.877336237380685446e+00,6.928203299376701096e+00,1.588835742576217014e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130272557386670940e+01,4.319533925012160580e+02,4.878918396796714241e+00,6.928203299376701096e+00,1.587169075909550253e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130416894952529105e+01,4.319632668101226045e+02,4.880498910516551270e+00,6.928203299376701096e+00,1.585502409242883493e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130561232518387271e+01,4.319731413823109278e+02,4.882077778496292986e+00,6.928203299376701096e+00,1.583835742576216732e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130705570084245437e+01,4.319830162175067585e+02,4.883655000692082027e+00,6.928203299376701096e+00,1.582169075909549971e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130849907650103603e+01,4.319928913154358270e+02,4.885230577060107215e+00,6.928203299376701096e+00,1.580502409242883211e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.130994245215961769e+01,4.320027666758238070e+02,4.886804507556601784e+00,6.928203299376701096e+00,1.578835742576216450e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.131138582781819935e+01,4.320126422983963721e+02,4.888376792137846039e+00,6.928203299376701096e+00,1.577169075909549689e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.131282920347678100e+01,4.320225181828791960e+02,4.889947430760164693e+00,6.928203299376701096e+00,1.575502409242882929e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.131427257913536266e+01,4.320323943289979525e+02,4.891516423379929535e+00,6.928203299376701096e+00,1.573835742576216168e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.131571595479394432e+01,4.320422707364783150e+02,4.893083769953557649e+00,6.928203299376701096e+00,1.572169075909549407e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.131715933045252598e+01,4.320521474050459574e+02,4.894649470437511418e+00,6.928203299376701096e+00,1.570502409242882647e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.131860270611110764e+01,4.320620243344264964e+02,4.896213524788298521e+00,6.928203299376701096e+00,1.568835742576215886e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132004608176968929e+01,4.320719015243455488e+02,4.897775932962473711e+00,6.928203299376701096e+00,1.567169075909549125e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132148945742827095e+01,4.320817789745287882e+02,4.899336694916637036e+00,6.928203299376701096e+00,1.565502409242882365e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132293283308685261e+01,4.320916566847018316e+02,4.900895810607432956e+00,6.928203299376701096e+00,1.563835742576215604e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132437620874543427e+01,4.321015346545902958e+02,4.902453279991553892e+00,6.928203299376701096e+00,1.562169075909548843e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132581958440401593e+01,4.321114128839197974e+02,4.904009103025735783e+00,6.928203299376701096e+00,1.560502409242882083e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132726296006259759e+01,4.321212913724159534e+02,4.905563279666761645e+00,6.928203299376701096e+00,1.558835742576215322e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.132870633572117924e+01,4.321311701198043238e+02,4.907115809871459788e+00,6.928203299376701096e+00,1.557169075909548561e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133014971137976090e+01,4.321410491258105253e+02,4.908666693596704711e+00,6.928203299376701096e+00,1.555502409242881801e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133159308703834256e+01,4.321509283901601748e+02,4.910215930799416206e+00,6.928203299376701096e+00,1.553835742576215040e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133303646269692422e+01,4.321608079125787754e+02,4.911763521436560254e+00,6.928203299376701096e+00,1.552169075909548279e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133447983835550588e+01,4.321706876927919438e+02,4.913309465465147241e+00,6.928203299376701096e+00,1.550502409242881519e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133592321401408753e+01,4.321805677305252402e+02,4.914853762842235518e+00,6.928203299376701096e+00,1.548835742576214758e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133736658967266919e+01,4.321904480255042245e+02,4.916396413524926956e+00,6.928203299376701096e+00,1.547169075909547997e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.133880996533125085e+01,4.322003285774543997e+02,4.917937417470370498e+00,6.928203299376701096e+00,1.545502409242881237e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134025334098983251e+01,4.322102093861013259e+02,4.919476774635760385e+00,6.928203299376701096e+00,1.543835742576214476e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134169671664841417e+01,4.322200904511705630e+02,4.921014484978337045e+00,6.928203299376701096e+00,1.542169075909547715e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134314009230699583e+01,4.322299717723876142e+02,4.922550548455386199e+00,6.928203299376701096e+00,1.540502409242880955e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134458346796557748e+01,4.322398533494779826e+02,4.924084965024238869e+00,6.928203299376701096e+00,1.538835742576214194e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134602684362415914e+01,4.322497351821672282e+02,4.925617734642273149e+00,6.928203299376701096e+00,1.537169075909547433e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134747021928274080e+01,4.322596172701807973e+02,4.927148857266911541e+00,6.928203299376701096e+00,1.535502409242880673e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.134891359494132246e+01,4.322694996132442498e+02,4.928678332855622735e+00,6.928203299376701096e+00,1.533835742576213912e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135035697059990412e+01,4.322793822110830320e+02,4.930206161365921602e+00,6.928203299376701096e+00,1.532169075909547151e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135180034625848577e+01,4.322892650634226470e+02,4.931732342755368315e+00,6.928203299376701096e+00,1.530502409242880391e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135324372191706743e+01,4.322991481699885412e+02,4.933256876981569228e+00,6.928203299376701096e+00,1.528835742576213630e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135468709757564909e+01,4.323090315305062177e+02,4.934779764002175995e+00,6.928203299376701096e+00,1.527169075909546869e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135613047323423075e+01,4.323189151447011227e+02,4.936301003774886453e+00,6.928203299376701096e+00,1.525502409242880109e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135757384889281241e+01,4.323287990122987026e+02,4.937820596257443739e+00,6.928203299376701096e+00,1.523835742576213348e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.135901722455139407e+01,4.323386831330244604e+02,4.939338541407637173e+00,6.928203299376701096e+00,1.522169075909546587e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136046060020997572e+01,4.323485675066037857e+02,4.940854839183301372e+00,6.928203299376701096e+00,1.520502409242879827e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136190397586855738e+01,4.323584521327621246e+02,4.942369489542316252e+00,6.928203299376701096e+00,1.518835742576213066e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136334735152713904e+01,4.323683370112248667e+02,4.943882492442609689e+00,6.928203299376701096e+00,1.517169075909546305e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136479072718572070e+01,4.323782221417175151e+02,4.945393847842152191e+00,6.928203299376701096e+00,1.515502409242879545e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136623410284430236e+01,4.323881075239654024e+02,4.946903555698963117e+00,6.928203299376701096e+00,1.513835742576212784e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136767747850288401e+01,4.323979931576939748e+02,4.948411615971105348e+00,6.928203299376701096e+00,1.512169075909546023e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.136912085416146567e+01,4.324078790426286218e+02,4.949918028616688837e+00,6.928203299376701096e+00,1.510502409242879263e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137056422982004733e+01,4.324177651784947329e+02,4.951422793593867944e+00,6.928203299376701096e+00,1.508835742576212502e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137200760547862899e+01,4.324276515650176975e+02,4.952925910860844105e+00,6.928203299376701096e+00,1.507169075909545741e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137345098113721065e+01,4.324375382019229050e+02,4.954427380375864054e+00,6.928203299376701096e+00,1.505502409242878981e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137489435679579231e+01,4.324474250889357450e+02,4.955927202097220707e+00,6.928203299376701096e+00,1.503835742576212220e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137633773245437396e+01,4.324573122257815498e+02,4.957425375983252280e+00,6.928203299376701096e+00,1.502169075909545459e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137778110811295562e+01,4.324671996121856523e+02,4.958921901992342285e+00,6.928203299376701096e+00,1.500502409242878699e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.137922448377153728e+01,4.324770872478734418e+02,4.960416780082920418e+00,6.928203299376701096e+00,1.498835742576211938e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138066785943011894e+01,4.324869751325702509e+02,4.961910010213462563e+00,6.928203299376701096e+00,1.497169075909545177e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138211123508870060e+01,4.324968632660014123e+02,4.963401592342490787e+00,6.928203299376701096e+00,1.495502409242878417e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138355461074728225e+01,4.325067516478922585e+02,4.964891526428571566e+00,6.928203299376701096e+00,1.493835742576211656e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138499798640586391e+01,4.325166402779681221e+02,4.966379812430317564e+00,6.928203299376701096e+00,1.492169075909544895e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138644136206444557e+01,4.325265291559542788e+02,4.967866450306388515e+00,6.928203299376701096e+00,1.490502409242878135e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138788473772302723e+01,4.325364182815760614e+02,4.969351440015487675e+00,6.928203299376701096e+00,1.488835742576211374e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.138932811338160889e+01,4.325463076545588024e+02,4.970834781516366263e+00,6.928203299376701096e+00,1.487169075909544613e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139077148904019054e+01,4.325561972746277775e+02,4.972316474767819905e+00,6.928203299376701096e+00,1.485502409242877853e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139221486469877220e+01,4.325660871415082624e+02,4.973796519728691301e+00,6.928203299376701096e+00,1.483835742576211092e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139365824035735386e+01,4.325759772549255331e+02,4.975274916357866672e+00,6.928203299376701096e+00,1.482169075909544331e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139510161601593552e+01,4.325858676146049220e+02,4.976751664614280202e+00,6.928203299376701096e+00,1.480502409242877571e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139654499167451718e+01,4.325957582202716480e+02,4.978226764456911368e+00,6.928203299376701096e+00,1.478835742576210810e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139798836733309884e+01,4.326056490716509302e+02,4.979700215844784950e+00,6.928203299376701096e+00,1.477169075909544049e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.139943174299168049e+01,4.326155401684681010e+02,4.981172018736971907e+00,6.928203299376701096e+00,1.475502409242877289e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140087511865026215e+01,4.326254315104483794e+02,4.982642173092588500e+00,6.928203299376701096e+00,1.473835742576210528e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140231849430884381e+01,4.326353230973169843e+02,4.984110678870797173e+00,6.928203299376701096e+00,1.472169075909543767e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140376186996742547e+01,4.326452149287991915e+02,4.985577536030805668e+00,6.928203299376701096e+00,1.470502409242877007e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140520524562600713e+01,4.326551070046202199e+02,4.987042744531868799e+00,6.928203299376701096e+00,1.468835742576210246e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140664862128458878e+01,4.326649993245052315e+02,4.988506304333285790e+00,6.928203299376701096e+00,1.467169075909543485e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140809199694317044e+01,4.326748918881795021e+02,4.989968215394402051e+00,6.928203299376701096e+00,1.465502409242876725e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.140953537260175210e+01,4.326847846953681938e+02,4.991428477674609177e+00,6.928203299376701096e+00,1.463835742576209964e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141097874826033376e+01,4.326946777457965254e+02,4.992887091133344946e+00,6.928203299376701096e+00,1.462169075909543203e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141242212391891542e+01,4.327045710391897160e+02,4.994344055730091547e+00,6.928203299376701096e+00,1.460502409242876443e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141386549957749708e+01,4.327144645752729275e+02,4.995799371424378243e+00,6.928203299376701096e+00,1.458835742576209682e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141530887523607873e+01,4.327243583537713789e+02,4.997253038175778705e+00,6.928203299376701096e+00,1.457169075909542921e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141675225089466039e+01,4.327342523744101754e+02,4.998705055943914566e+00,6.928203299376701096e+00,1.455502409242876161e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141819562655324205e+01,4.327441466369145360e+02,5.000155424688450978e+00,6.928203299376701096e+00,1.453835742576209400e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.141963900221182371e+01,4.327540411410095658e+02,5.001604144369100169e+00,6.928203299376701096e+00,1.452169075909542639e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142108237787040537e+01,4.327639358864204837e+02,5.003051214945620551e+00,6.928203299376701096e+00,1.450502409242875879e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142252575352898702e+01,4.327738308728723950e+02,5.004496636377814944e+00,6.928203299376701096e+00,1.448835742576209118e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142396912918756868e+01,4.327837261000904618e+02,5.005940408625533244e+00,6.928203299376701096e+00,1.447169075909542357e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142541250484615034e+01,4.327936215677997893e+02,5.007382531648670643e+00,6.928203299376701096e+00,1.445502409242875597e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142685588050473200e+01,4.328035172757254827e+02,5.008823005407167628e+00,6.928203299376701096e+00,1.443835742576208836e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142829925616331366e+01,4.328134132235927041e+02,5.010261829861011762e+00,6.928203299376701096e+00,1.442169075909542075e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.142974263182189532e+01,4.328233094111265586e+02,5.011699004970235016e+00,6.928203299376701096e+00,1.440502409242875315e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143118600748047697e+01,4.328332058380521516e+02,5.013134530694916435e+00,6.928203299376701096e+00,1.438835742576208554e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143262938313905863e+01,4.328431025040945883e+02,5.014568406995179473e+00,6.928203299376701096e+00,1.437169075909541793e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143407275879764029e+01,4.328529994089789739e+02,5.016000633831194655e+00,6.928203299376701096e+00,1.435502409242875033e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143551613445622195e+01,4.328628965524303567e+02,5.017431211163178695e+00,6.928203299376701096e+00,1.433835742576208272e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143695951011480361e+01,4.328727939341738420e+02,5.018860138951392713e+00,6.928203299376701096e+00,1.432169075909541511e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143840288577338526e+01,4.328826915539344782e+02,5.020287417156144016e+00,6.928203299376701096e+00,1.430502409242874751e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.143984626143196692e+01,4.328925894114373705e+02,5.021713045737786096e+00,6.928203299376701096e+00,1.428835742576207990e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144128963709054858e+01,4.329024875064075104e+02,5.023137024656718630e+00,6.928203299376701096e+00,1.427169075909541229e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144273301274913024e+01,4.329123858385700032e+02,5.024559353873385703e+00,6.928203299376701096e+00,1.425502409242874469e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144417638840771190e+01,4.329222844076498973e+02,5.025980033348279363e+00,6.928203299376701096e+00,1.423835742576207708e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144561976406629356e+01,4.329321832133722410e+02,5.027399063041935179e+00,6.928203299376701096e+00,1.422169075909540947e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144706313972487521e+01,4.329420822554620258e+02,5.028816442914936680e+00,6.928203299376701096e+00,1.420502409242874187e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144850651538345687e+01,4.329519815336443003e+02,5.030232172927910916e+00,6.928203299376701096e+00,1.418835742576207426e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.144994989104203853e+01,4.329618810476441126e+02,5.031646253041532901e+00,6.928203299376701096e+00,1.417169075909540665e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.145139326670062019e+01,4.329717807971864545e+02,5.033058683216522944e+00,6.928203299376701096e+00,1.415502409242873905e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.145283664235920185e+01,4.329816807819963174e+02,5.034469463413646650e+00,6.928203299376701096e+00,1.413835742576207144e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.145428001801778350e+01,4.329915810017986928e+02,5.035878593593714925e+00,6.928203299376701096e+00,1.412169075909540383e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.145572339367636516e+01,4.330014814563186292e+02,5.037286073717585744e+00,6.928203299376701096e+00,1.410502409242873623e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.145716676933494682e+01,4.330113821452810612e+02,5.038691903746163270e+00,6.928203299376701096e+00,1.408835742576206862e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.145861014499352848e+01,4.330212830684109804e+02,5.040096083640396074e+00,6.928203299376701096e+00,1.407169075909540101e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146005352065211014e+01,4.330311842254333783e+02,5.041498613361278913e+00,6.928203299376701096e+00,1.405502409242873341e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146149689631069180e+01,4.330410856160731896e+02,5.042899492869852729e+00,6.928203299376701096e+00,1.403835742576206580e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146294027196927345e+01,4.330509872400554059e+02,5.044298722127203760e+00,6.928203299376701096e+00,1.402169075909539819e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146438364762785511e+01,4.330608890971049618e+02,5.045696301094465319e+00,6.928203299376701096e+00,1.400502409242873059e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146582702328643677e+01,4.330707911869468489e+02,5.047092229732815127e+00,6.928203299376701096e+00,1.398835742576206298e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146727039894501843e+01,4.330806935093059451e+02,5.048486508003477979e+00,6.928203299376701096e+00,1.397169075909539537e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.146871377460360009e+01,4.330905960639072418e+02,5.049879135867723079e+00,6.928203299376701096e+00,1.395502409242872777e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147015715026218174e+01,4.331004988504756739e+02,5.051270113286867591e+00,6.928203299376701096e+00,1.393835742576206016e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147160052592076340e+01,4.331104018687361190e+02,5.052659440222272202e+00,6.928203299376701096e+00,1.392169075909539255e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147304390157934506e+01,4.331203051184135120e+02,5.054047116635344672e+00,6.928203299376701096e+00,1.390502409242872495e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147448727723792672e+01,4.331302085992327306e+02,5.055433142487538944e+00,6.928203299376701096e+00,1.388835742576205734e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147593065289650838e+01,4.331401123109187097e+02,5.056817517740354262e+00,6.928203299376701096e+00,1.387169075909538973e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147737402855509004e+01,4.331500162531963838e+02,5.058200242355335163e+00,6.928203299376701096e+00,1.385502409242872213e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.147881740421367169e+01,4.331599204257905740e+02,5.059581316294072373e+00,6.928203299376701096e+00,1.383835742576205452e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148026077987225335e+01,4.331698248284262149e+02,5.060960739518203688e+00,6.928203299376701096e+00,1.382169075909538691e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148170415553083501e+01,4.331797294608281277e+02,5.062338511989411316e+00,6.928203299376701096e+00,1.380502409242871931e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148314753118941667e+01,4.331896343227212469e+02,5.063714633669423648e+00,6.928203299376701096e+00,1.378835742576205170e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148459090684799833e+01,4.331995394138303936e+02,5.065089104520015262e+00,6.928203299376701096e+00,1.377169075909538409e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148603428250657998e+01,4.332094447338804457e+02,5.066461924503006919e+00,6.928203299376701096e+00,1.375502409242871649e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148747765816516164e+01,4.332193502825962810e+02,5.067833093580263792e+00,6.928203299376701096e+00,1.373835742576204888e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.148892103382374330e+01,4.332292560597027204e+02,5.069202611713699014e+00,6.928203299376701096e+00,1.372169075909538127e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149036440948232496e+01,4.332391620649245851e+02,5.070570478865269237e+00,6.928203299376701096e+00,1.370502409242871367e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149180778514090662e+01,4.332490682979867529e+02,5.071936694996979078e+00,6.928203299376701096e+00,1.368835742576204606e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149325116079948828e+01,4.332589747586139879e+02,5.073301260070877561e+00,6.928203299376701096e+00,1.367169075909537845e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149469453645806993e+01,4.332688814465311680e+02,5.074664174049059895e+00,6.928203299376701096e+00,1.365502409242871085e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149613791211665159e+01,4.332787883614630573e+02,5.076025436893667475e+00,6.928203299376701096e+00,1.363835742576204324e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149758128777523325e+01,4.332886955031344769e+02,5.077385048566887882e+00,6.928203299376701096e+00,1.362169075909537563e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.149902466343381491e+01,4.332986028712702478e+02,5.078743009030953992e+00,6.928203299376701096e+00,1.360502409242870803e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150046803909239657e+01,4.333085104655951909e+02,5.080099318248143980e+00,6.928203299376701096e+00,1.358835742576204042e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150191141475097822e+01,4.333184182858340705e+02,5.081453976180783982e+00,6.928203299376701096e+00,1.357169075909537281e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150335479040955988e+01,4.333283263317116507e+02,5.082806982791243655e+00,6.928203299376701096e+00,1.355502409242870521e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150479816606814154e+01,4.333382346029526957e+02,5.084158338041939729e+00,6.928203299376701096e+00,1.353835742576203760e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150624154172672320e+01,4.333481430992820265e+02,5.085508041895334230e+00,6.928203299376701096e+00,1.352169075909536999e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150768491738530486e+01,4.333580518204243504e+02,5.086856094313935372e+00,6.928203299376701096e+00,1.350502409242870239e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.150912829304388652e+01,4.333679607661044884e+02,5.088202495260297553e+00,6.928203299376701096e+00,1.348835742576203478e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151057166870246817e+01,4.333778699360471478e+02,5.089547244697020467e+00,6.928203299376701096e+00,1.347169075909536717e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151201504436104983e+01,4.333877793299770929e+02,5.090890342586749995e+00,6.928203299376701096e+00,1.345502409242869957e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151345842001963149e+01,4.333976889476190308e+02,5.092231788892178201e+00,6.928203299376701096e+00,1.343835742576203196e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151490179567821315e+01,4.334075987886977259e+02,5.093571583576042450e+00,6.928203299376701096e+00,1.342169075909536435e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151634517133679481e+01,4.334175088529378854e+02,5.094909726601126287e+00,6.928203299376701096e+00,1.340502409242869675e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151778854699537646e+01,4.334274191400642735e+02,5.096246217930259448e+00,6.928203299376701096e+00,1.338835742576202914e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.151923192265395812e+01,4.334373296498015407e+02,5.097581057526316961e+00,6.928203299376701096e+00,1.337169075909536153e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152067529831253978e+01,4.334472403818744510e+02,5.098914245352220043e+00,6.928203299376701096e+00,1.335502409242869393e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152211867397112144e+01,4.334571513360076551e+02,5.100245781370935205e+00,6.928203299376701096e+00,1.333835742576202632e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152356204962970310e+01,4.334670625119259171e+02,5.101575665545475147e+00,6.928203299376701096e+00,1.332169075909535871e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152500542528828475e+01,4.334769739093538874e+02,5.102903897838899638e+00,6.928203299376701096e+00,1.330502409242869111e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152644880094686641e+01,4.334868855280162165e+02,5.104230478214312861e+00,6.928203299376701096e+00,1.328835742576202350e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152789217660544807e+01,4.334967973676376118e+02,5.105555406634865179e+00,6.928203299376701096e+00,1.327169075909535589e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.152933555226402973e+01,4.335067094279427806e+02,5.106878683063753144e+00,6.928203299376701096e+00,1.325502409242868829e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153077892792261139e+01,4.335166217086563165e+02,5.108200307464218604e+00,6.928203299376701096e+00,1.323835742576202068e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153222230358119305e+01,4.335265342095029268e+02,5.109520279799550480e+00,6.928203299376701096e+00,1.322169075909535307e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153366567923977470e+01,4.335364469302072621e+02,5.110838600033082990e+00,6.928203299376701096e+00,1.320502409242868547e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153510905489835636e+01,4.335463598704939159e+02,5.112155268128195651e+00,6.928203299376701096e+00,1.318835742576201786e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153655243055693802e+01,4.335562730300875955e+02,5.113470284048314163e+00,6.928203299376701096e+00,1.317169075909535025e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153799580621551968e+01,4.335661864087128947e+02,5.114783647756910412e+00,6.928203299376701096e+00,1.315502409242868265e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.153943918187410134e+01,4.335761000060944639e+02,5.116095359217502470e+00,6.928203299376701096e+00,1.313835742576201504e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154088255753268299e+01,4.335860138219569535e+02,5.117405418393653704e+00,6.928203299376701096e+00,1.312169075909534743e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154232593319126465e+01,4.335959278560249004e+02,5.118713825248973670e+00,6.928203299376701096e+00,1.310502409242867983e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154376930884984631e+01,4.336058421080230119e+02,5.120020579747117218e+00,6.928203299376701096e+00,1.308835742576201222e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154521268450842797e+01,4.336157565776758247e+02,5.121325681851786271e+00,6.928203299376701096e+00,1.307169075909534461e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154665606016700963e+01,4.336256712647079326e+02,5.122629131526728052e+00,6.928203299376701096e+00,1.305502409242867701e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154809943582559129e+01,4.336355861688439859e+02,5.123930928735735080e+00,6.928203299376701096e+00,1.303835742576200940e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.154954281148417294e+01,4.336455012898085215e+02,5.125231073442646945e+00,6.928203299376701096e+00,1.302169075909534179e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155098618714275460e+01,4.336554166273261330e+02,5.126529565611347650e+00,6.928203299376701096e+00,1.300502409242867419e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155242956280133626e+01,4.336653321811213573e+02,5.127826405205768268e+00,6.928203299376701096e+00,1.298835742576200658e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155387293845991792e+01,4.336752479509187879e+02,5.129121592189886059e+00,6.928203299376701096e+00,1.297169075909533897e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155531631411849958e+01,4.336851639364430184e+02,5.130415126527723579e+00,6.928203299376701096e+00,1.295502409242867137e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155675968977708123e+01,4.336950801374185858e+02,5.131707008183348684e+00,6.928203299376701096e+00,1.293835742576200376e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155820306543566289e+01,4.337049965535700267e+02,5.132997237120876299e+00,6.928203299376701096e+00,1.292169075909533615e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.155964644109424455e+01,4.337149131846218779e+02,5.134285813304465762e+00,6.928203299376701096e+00,1.290502409242866855e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156108981675282621e+01,4.337248300302987332e+02,5.135572736698324370e+00,6.928203299376701096e+00,1.288835742576200094e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156253319241140787e+01,4.337347470903250723e+02,5.136858007266703829e+00,6.928203299376701096e+00,1.287169075909533333e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156397656806998953e+01,4.337446643644254323e+02,5.138141624973902033e+00,6.928203299376701096e+00,1.285502409242866573e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156541994372857118e+01,4.337545818523243497e+02,5.139423589784263058e+00,6.928203299376701096e+00,1.283835742576199812e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156686331938715284e+01,4.337644995537463046e+02,5.140703901662177167e+00,6.928203299376701096e+00,1.282169075909533051e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156830669504573450e+01,4.337744174684158338e+02,5.141982560572079919e+00,6.928203299376701096e+00,1.280502409242866291e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.156975007070431616e+01,4.337843355960574172e+02,5.143259566478453060e+00,6.928203299376701096e+00,1.278835742576199530e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157119344636289782e+01,4.337942539363955916e+02,5.144534919345823631e+00,6.928203299376701096e+00,1.277169075909532769e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157263682202147947e+01,4.338041724891548370e+02,5.145808619138765749e+00,6.928203299376701096e+00,1.275502409242866009e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157408019768006113e+01,4.338140912540595764e+02,5.147080665821898826e+00,6.928203299376701096e+00,1.273835742576199248e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157552357333864279e+01,4.338240102308343467e+02,5.148351059359887572e+00,6.928203299376701096e+00,1.272169075909532487e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157696694899722445e+01,4.338339294192036277e+02,5.149619799717444657e+00,6.928203299376701096e+00,1.270502409242865727e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157841032465580611e+01,4.338438488188918427e+02,5.150886886859326275e+00,6.928203299376701096e+00,1.268835742576198966e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.157985370031438777e+01,4.338537684296234715e+02,5.152152320750335690e+00,6.928203299376701096e+00,1.267169075909532205e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158129707597296942e+01,4.338636882511229942e+02,5.153416101355321466e+00,6.928203299376701096e+00,1.265502409242865445e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158274045163155108e+01,4.338736082831148337e+02,5.154678228639179238e+00,6.928203299376701096e+00,1.263835742576198684e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158418382729013274e+01,4.338835285253234701e+02,5.155938702566849940e+00,6.928203299376701096e+00,1.262169075909531923e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158562720294871440e+01,4.338934489774732697e+02,5.157197523103320691e+00,6.928203299376701096e+00,1.260502409242865163e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158707057860729606e+01,4.339033696392887123e+02,5.158454690213623905e+00,6.928203299376701096e+00,1.258835742576198402e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158851395426587771e+01,4.339132905104942211e+02,5.159710203862838185e+00,6.928203299376701096e+00,1.257169075909531641e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.158995732992445937e+01,4.339232115908142191e+02,5.160964064016087427e+00,6.928203299376701096e+00,1.255502409242864881e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.159140070558304103e+01,4.339331328799731295e+02,5.162216270638543492e+00,6.928203299376701096e+00,1.253835742576198120e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.159284408124162269e+01,4.339430543776953186e+02,5.163466823695421759e+00,6.928203299376701096e+00,1.252169075909531359e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.159428745690020435e+01,4.339529760837052663e+02,5.164715723151985571e+00,6.928203299376701096e+00,1.250502409242864599e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.159573083255878601e+01,4.339628979977272820e+02,5.165962968973542679e+00,6.928203299376701096e+00,1.248835742576197977e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.159717420821736766e+01,4.339728201194857888e+02,5.167208561125447908e+00,6.928203299376701096e+00,1.247169075909531355e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.159861758387594932e+01,4.339827424487052099e+02,5.168452499573101377e+00,6.928203299376701096e+00,1.245502409242864733e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160006095953453098e+01,4.339926649851099114e+02,5.169694784281948507e+00,6.928203299376701096e+00,1.243835742576198111e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160150433519311264e+01,4.340025877284242029e+02,5.170935415217481790e+00,6.928203299376701096e+00,1.242169075909531489e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160294771085169430e+01,4.340125106783725073e+02,5.172174392345239902e+00,6.928203299376701096e+00,1.240502409242864867e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160439108651027595e+01,4.340224338346791910e+02,5.173411715630805929e+00,6.928203299376701096e+00,1.238835742576198246e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160583446216885761e+01,4.340323571970686203e+02,5.174647385039810032e+00,6.928203299376701096e+00,1.237169075909531624e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160727783782743927e+01,4.340422807652651045e+02,5.175881400537928556e+00,6.928203299376701096e+00,1.235502409242865002e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.160872121348602093e+01,4.340522045389930099e+02,5.177113762090882254e+00,6.928203299376701096e+00,1.233835742576198380e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161016458914460259e+01,4.340621285179767028e+02,5.178344469664439842e+00,6.928203299376701096e+00,1.232169075909531758e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161160796480318425e+01,4.340720527019404926e+02,5.179573523224414444e+00,6.928203299376701096e+00,1.230502409242865136e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161305134046176590e+01,4.340819770906086887e+02,5.180800922736666259e+00,6.928203299376701096e+00,1.228835742576198514e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161449471612034756e+01,4.340919016837056006e+02,5.182026668167100780e+00,6.928203299376701096e+00,1.227169075909531892e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161593809177892922e+01,4.341018264809555944e+02,5.183250759481668801e+00,6.928203299376701096e+00,1.225502409242865270e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161738146743751088e+01,4.341117514820829797e+02,5.184473196646368187e+00,6.928203299376701096e+00,1.223835742576198649e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.161882484309609254e+01,4.341216766868120089e+02,5.185693979627242101e+00,6.928203299376701096e+00,1.222169075909532027e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162026821875467419e+01,4.341316020948670484e+02,5.186913108390380778e+00,6.928203299376701096e+00,1.220502409242865405e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162171159441325585e+01,4.341415277059723508e+02,5.188130582901918864e+00,6.928203299376701096e+00,1.218835742576198783e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162315497007183751e+01,4.341514535198522253e+02,5.189346403128037188e+00,6.928203299376701096e+00,1.217169075909532161e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162459834573041917e+01,4.341613795362309247e+02,5.190560569034963656e+00,6.928203299376701096e+00,1.215502409242865539e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162604172138900083e+01,4.341713057548327583e+02,5.191773080588971467e+00,6.928203299376701096e+00,1.213835742576198917e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162748509704758249e+01,4.341812321753819788e+02,5.192983937756379120e+00,6.928203299376701096e+00,1.212169075909532295e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.162892847270616414e+01,4.341911587976028386e+02,5.194193140503552186e+00,6.928203299376701096e+00,1.210502409242865673e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163037184836474580e+01,4.342010856212196472e+02,5.195400688796901534e+00,6.928203299376701096e+00,1.208835742576199052e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163181522402332746e+01,4.342110126459566573e+02,5.196606582602884217e+00,6.928203299376701096e+00,1.207169075909532430e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163325859968190912e+01,4.342209398715380644e+02,5.197810821888003474e+00,6.928203299376701096e+00,1.205502409242865808e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163470197534049078e+01,4.342308672976881212e+02,5.199013406618807842e+00,6.928203299376701096e+00,1.203835742576199186e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163614535099907243e+01,4.342407949241310803e+02,5.200214336761892042e+00,6.928203299376701096e+00,1.202169075909532564e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163758872665765409e+01,4.342507227505911942e+02,5.201413612283897869e+00,6.928203299376701096e+00,1.200502409242865942e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.163903210231623575e+01,4.342606507767926587e+02,5.202611233151510639e+00,6.928203299376701096e+00,1.198835742576199320e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164047547797481741e+01,4.342705790024597263e+02,5.203807199331464517e+00,6.928203299376701096e+00,1.197169075909532698e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164191885363339907e+01,4.342805074273165928e+02,5.205001510790537189e+00,6.928203299376701096e+00,1.195502409242866076e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164336222929198073e+01,4.342904360510875108e+02,5.206194167495553415e+00,6.928203299376701096e+00,1.193835742576199455e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164480560495056238e+01,4.343003648734966191e+02,5.207385169413384141e+00,6.928203299376701096e+00,1.192169075909532833e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164624898060914404e+01,4.343102938942681703e+02,5.208574516510946495e+00,6.928203299376701096e+00,1.190502409242866211e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164769235626772570e+01,4.343202231131263034e+02,5.209762208755202906e+00,6.928203299376701096e+00,1.188835742576199589e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.164913573192630736e+01,4.343301525297952708e+02,5.210948246113161098e+00,6.928203299376701096e+00,1.187169075909532967e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165057910758488902e+01,4.343400821439992114e+02,5.212132628551875868e+00,6.928203299376701096e+00,1.185502409242866345e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165202248324347067e+01,4.343500119554623211e+02,5.213315356038448201e+00,6.928203299376701096e+00,1.183835742576199723e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165346585890205233e+01,4.343599419639087387e+02,5.214496428540024375e+00,6.928203299376701096e+00,1.182169075909533101e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165490923456063399e+01,4.343698721690626599e+02,5.215675846023796858e+00,6.928203299376701096e+00,1.180502409242866479e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165635261021921565e+01,4.343798025706482235e+02,5.216853608457003411e+00,6.928203299376701096e+00,1.178835742576199858e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165779598587779731e+01,4.343897331683896255e+02,5.218029715806928870e+00,6.928203299376701096e+00,1.177169075909533236e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.165923936153637896e+01,4.343996639620110045e+02,5.219204168040903369e+00,6.928203299376701096e+00,1.175502409242866614e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166068273719496062e+01,4.344095949512364996e+02,5.220376965126304114e+00,6.928203299376701096e+00,1.173835742576199992e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166212611285354228e+01,4.344195261357902496e+02,5.221548107030552721e+00,6.928203299376701096e+00,1.172169075909533370e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166356948851212394e+01,4.344294575153963365e+02,5.222717593721116991e+00,6.928203299376701096e+00,1.170502409242866748e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166501286417070560e+01,4.344393890897789561e+02,5.223885425165511798e+00,6.928203299376701096e+00,1.168835742576200126e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166645623982928726e+01,4.344493208586621904e+02,5.225051601331297313e+00,6.928203299376701096e+00,1.167169075909533504e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166789961548786891e+01,4.344592528217701783e+02,5.226216122186079893e+00,6.928203299376701096e+00,1.165502409242866882e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.166934299114645057e+01,4.344691849788270588e+02,5.227378987697511192e+00,6.928203299376701096e+00,1.163835742576200261e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167078636680503223e+01,4.344791173295569138e+02,5.228540197833289938e+00,6.928203299376701096e+00,1.162169075909533639e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167222974246361389e+01,4.344890498736838254e+02,5.229699752561160153e+00,6.928203299376701096e+00,1.160502409242867017e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167367311812219555e+01,4.344989826109319324e+02,5.230857651848912049e+00,6.928203299376701096e+00,1.158835742576200395e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167511649378077720e+01,4.345089155410252602e+02,5.232013895664382019e+00,6.928203299376701096e+00,1.157169075909533773e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167655986943935886e+01,4.345188486636879475e+02,5.233168483975451757e+00,6.928203299376701096e+00,1.155502409242867151e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167800324509794052e+01,4.345287819786440764e+02,5.234321416750049138e+00,6.928203299376701096e+00,1.153835742576200529e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.167944662075652218e+01,4.345387154856176721e+02,5.235472693956148227e+00,6.928203299376701096e+00,1.152169075909533907e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168088999641510384e+01,4.345486491843328736e+02,5.236622315561770158e+00,6.928203299376701096e+00,1.150502409242867285e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168233337207368550e+01,4.345585830745137059e+02,5.237770281534979588e+00,6.928203299376701096e+00,1.148835742576200664e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168377674773226715e+01,4.345685171558841944e+02,5.238916591843889137e+00,6.928203299376701096e+00,1.147169075909534042e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168522012339084881e+01,4.345784514281684210e+02,5.240061246456657607e+00,6.928203299376701096e+00,1.145502409242867420e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168666349904943047e+01,4.345883858910904678e+02,5.241204245341488210e+00,6.928203299376701096e+00,1.143835742576200798e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168810687470801213e+01,4.345983205443743600e+02,5.242345588466631234e+00,6.928203299376701096e+00,1.142169075909534176e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.168955025036659379e+01,4.346082553877441228e+02,5.243485275800382261e+00,6.928203299376701096e+00,1.140502409242867554e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169099362602517544e+01,4.346181904209237814e+02,5.244623307311083948e+00,6.928203299376701096e+00,1.138835742576200932e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169243700168375710e+01,4.346281256436373610e+02,5.245759682967124249e+00,6.928203299376701096e+00,1.137169075909534310e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169388037734233876e+01,4.346380610556088868e+02,5.246894402736936414e+00,6.928203299376701096e+00,1.135502409242867689e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169532375300092042e+01,4.346479966565623840e+02,5.248027466589001655e+00,6.928203299376701096e+00,1.133835742576201067e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169676712865950208e+01,4.346579324462218779e+02,5.249158874491844706e+00,6.928203299376701096e+00,1.132169075909534445e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169821050431808374e+01,4.346678684243113366e+02,5.250288626414038262e+00,6.928203299376701096e+00,1.130502409242867823e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.169965387997666539e+01,4.346778045905547856e+02,5.251416722324200315e+00,6.928203299376701096e+00,1.128835742576201201e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170109725563524705e+01,4.346877409446761931e+02,5.252543162190995041e+00,6.928203299376701096e+00,1.127169075909534579e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170254063129382871e+01,4.346976774863995843e+02,5.253667945983131915e+00,6.928203299376701096e+00,1.125502409242867957e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170398400695241037e+01,4.347076142154489276e+02,5.254791073669367485e+00,6.928203299376701096e+00,1.123835742576201335e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170542738261099203e+01,4.347175511315482481e+02,5.255912545218503595e+00,6.928203299376701096e+00,1.122169075909534713e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170687075826957368e+01,4.347274882344214575e+02,5.257032360599388277e+00,6.928203299376701096e+00,1.120502409242868092e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170831413392815534e+01,4.347374255237925240e+02,5.258150519780914856e+00,6.928203299376701096e+00,1.118835742576201470e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.170975750958673700e+01,4.347473629993854729e+02,5.259267022732023733e+00,6.928203299376701096e+00,1.117169075909534848e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171120088524531866e+01,4.347573006609242157e+02,5.260381869421701495e+00,6.928203299376701096e+00,1.115502409242868226e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171264426090390032e+01,4.347672385081327207e+02,5.261495059818980025e+00,6.928203299376701096e+00,1.113835742576201604e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171408763656248198e+01,4.347771765407348994e+02,5.262606593892937390e+00,6.928203299376701096e+00,1.112169075909534982e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171553101222106363e+01,4.347871147584547771e+02,5.263716471612696957e+00,6.928203299376701096e+00,1.110502409242868360e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171697438787964529e+01,4.347970531610162084e+02,5.264824692947429163e+00,6.928203299376701096e+00,1.108835742576201738e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171841776353822695e+01,4.348069917481431617e+02,5.265931257866350634e+00,6.928203299376701096e+00,1.107169075909535116e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.171986113919680861e+01,4.348169305195595484e+02,5.267036166338722403e+00,6.928203299376701096e+00,1.105502409242868495e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172130451485539027e+01,4.348268694749893370e+02,5.268139418333853463e+00,6.928203299376701096e+00,1.103835742576201873e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172274789051397192e+01,4.348368086141564390e+02,5.269241013821097219e+00,6.928203299376701096e+00,1.102169075909535251e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172419126617255358e+01,4.348467479367847091e+02,5.270340952769854148e+00,6.928203299376701096e+00,1.100502409242868629e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172563464183113524e+01,4.348566874425981155e+02,5.271439235149570912e+00,6.928203299376701096e+00,1.098835742576202007e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172707801748971690e+01,4.348666271313205129e+02,5.272535860929739471e+00,6.928203299376701096e+00,1.097169075909535385e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172852139314829856e+01,4.348765670026758130e+02,5.273630830079897081e+00,6.928203299376701096e+00,1.095502409242868763e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.172996476880688022e+01,4.348865070563879272e+02,5.274724142569628960e+00,6.928203299376701096e+00,1.093835742576202141e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.173140814446546187e+01,4.348964472921807101e+02,5.275815798368564735e+00,6.928203299376701096e+00,1.092169075909535519e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.173285152012404353e+01,4.349063877097780733e+02,5.276905797446381108e+00,6.928203299376701096e+00,1.090502409242868898e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.173429489578262519e+01,4.349163283089039282e+02,5.277994139772800075e+00,6.928203299376701096e+00,1.088835742576202276e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.173573827144120685e+01,4.349262690892820729e+02,5.279080825317589820e+00,6.928203299376701096e+00,1.087169075909535654e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.173718164709978851e+01,4.349362100506364186e+02,5.280165854050564711e+00,6.928203299376701096e+00,1.085502409242869032e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.173862502275837016e+01,4.349461511926908202e+02,5.281249225941584413e+00,6.928203299376701096e+00,1.083835742576202410e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174006839841695182e+01,4.349560925151691322e+02,5.282330940960556553e+00,6.928203299376701096e+00,1.082169075909535788e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174151177407553348e+01,4.349660340177952094e+02,5.283410999077432280e+00,6.928203299376701096e+00,1.080502409242869166e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174295514973411514e+01,4.349759757002929064e+02,5.284489400262210701e+00,6.928203299376701096e+00,1.078835742576202544e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174439852539269680e+01,4.349859175623860210e+02,5.285566144484936224e+00,6.928203299376701096e+00,1.077169075909535922e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174584190105127846e+01,4.349958596037984648e+02,5.286641231715699440e+00,6.928203299376701096e+00,1.075502409242869301e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174728527670986011e+01,4.350058018242539788e+02,5.287714661924636239e+00,6.928203299376701096e+00,1.073835742576202679e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.174872865236844177e+01,4.350157442234764744e+02,5.288786435081929582e+00,6.928203299376701096e+00,1.072169075909536057e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175017202802702343e+01,4.350256868011897495e+02,5.289856551157807729e+00,6.928203299376701096e+00,1.070502409242869435e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175161540368560509e+01,4.350356295571176020e+02,5.290925010122545125e+00,6.928203299376701096e+00,1.068835742576202813e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175305877934418675e+01,4.350455724909838295e+02,5.291991811946462398e+00,6.928203299376701096e+00,1.067169075909536191e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175450215500276840e+01,4.350555156025122869e+02,5.293056956599926366e+00,6.928203299376701096e+00,1.065502409242869569e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175594553066135006e+01,4.350654588914267720e+02,5.294120444053349139e+00,6.928203299376701096e+00,1.063835742576202947e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175738890631993172e+01,4.350754023574510256e+02,5.295182274277189904e+00,6.928203299376701096e+00,1.062169075909536325e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.175883228197851338e+01,4.350853460003089026e+02,5.296242447241954032e+00,6.928203299376701096e+00,1.060502409242869704e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176027565763709504e+01,4.350952898197241439e+02,5.297300962918191303e+00,6.928203299376701096e+00,1.058835742576203082e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176171903329567670e+01,4.351052338154205472e+02,5.298357821276498569e+00,6.928203299376701096e+00,1.057169075909536460e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176316240895425835e+01,4.351151779871219105e+02,5.299413022287518871e+00,6.928203299376701096e+00,1.055502409242869838e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176460578461284001e+01,4.351251223345519747e+02,5.300466565921941431e+00,6.928203299376701096e+00,1.053835742576203216e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176604916027142167e+01,4.351350668574345377e+02,5.301518452150500771e+00,6.928203299376701096e+00,1.052169075909536594e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176749253593000333e+01,4.351450115554933973e+02,5.302568680943977597e+00,6.928203299376701096e+00,1.050502409242869972e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.176893591158858499e+01,4.351549564284522376e+02,5.303617252273198801e+00,6.928203299376701096e+00,1.048835742576203350e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177037928724716664e+01,4.351649014760348564e+02,5.304664166109037460e+00,6.928203299376701096e+00,1.047169075909536728e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177182266290574830e+01,4.351748466979649947e+02,5.305709422422413724e+00,6.928203299376701096e+00,1.045502409242870107e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177326603856432996e+01,4.351847920939663936e+02,5.306753021184291264e+00,6.928203299376701096e+00,1.043835742576203485e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177470941422291162e+01,4.351947376637627940e+02,5.307794962365681712e+00,6.928203299376701096e+00,1.042169075909536863e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177615278988149328e+01,4.352046834070778800e+02,5.308835245937642888e+00,6.928203299376701096e+00,1.040502409242870241e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177759616554007494e+01,4.352146293236354495e+02,5.309873871871277018e+00,6.928203299376701096e+00,1.038835742576203619e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.177903954119865659e+01,4.352245754131591866e+02,5.310910840137734290e+00,6.928203299376701096e+00,1.037169075909536997e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178048291685723825e+01,4.352345216753728323e+02,5.311946150708209302e+00,6.928203299376701096e+00,1.035502409242870375e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178192629251581991e+01,4.352444681100001276e+02,5.312979803553943725e+00,6.928203299376701096e+00,1.033835742576203753e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178336966817440157e+01,4.352544147167646997e+02,5.314011798646225415e+00,6.928203299376701096e+00,1.032169075909537131e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178481304383298323e+01,4.352643614953903466e+02,5.315042135956387526e+00,6.928203299376701096e+00,1.030502409242870510e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178625641949156488e+01,4.352743084456006954e+02,5.316070815455809395e+00,6.928203299376701096e+00,1.028835742576203888e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178769979515014654e+01,4.352842555671194873e+02,5.317097837115916548e+00,6.928203299376701096e+00,1.027169075909537266e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.178914317080872820e+01,4.352942028596704063e+02,5.318123200908180692e+00,6.928203299376701096e+00,1.025502409242870644e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179058654646730986e+01,4.353041503229771365e+02,5.319146906804119723e+00,6.928203299376701096e+00,1.023835742576204022e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179202992212589152e+01,4.353140979567633622e+02,5.320168954775296832e+00,6.928203299376701096e+00,1.022169075909537400e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179347329778447317e+01,4.353240457607527674e+02,5.321189344793322284e+00,6.928203299376701096e+00,1.020502409242870778e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179491667344305483e+01,4.353339937346689794e+02,5.322208076829851642e+00,6.928203299376701096e+00,1.018835742576204156e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179636004910163649e+01,4.353439418782356825e+02,5.323225150856586652e+00,6.928203299376701096e+00,1.017169075909537534e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179780342476021815e+01,4.353538901911765606e+02,5.324240566845276135e+00,6.928203299376701096e+00,1.015502409242870913e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.179924680041879981e+01,4.353638386732152981e+02,5.325254324767713321e+00,6.928203299376701096e+00,1.013835742576204291e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180069017607738147e+01,4.353737873240755221e+02,5.326266424595738513e+00,6.928203299376701096e+00,1.012169075909537669e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180213355173596312e+01,4.353837361434808599e+02,5.327276866301237312e+00,6.928203299376701096e+00,1.010502409242871047e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180357692739454478e+01,4.353936851311549390e+02,5.328285649856142392e+00,6.928203299376701096e+00,1.008835742576204425e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180502030305312644e+01,4.354036342868214433e+02,5.329292775232431723e+00,6.928203299376701096e+00,1.007169075909537803e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180646367871170810e+01,4.354135836102040003e+02,5.330298242402130349e+00,6.928203299376701096e+00,1.005502409242871181e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180790705437028976e+01,4.354235331010262371e+02,5.331302051337307724e+00,6.928203299376701096e+00,1.003835742576204559e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.180935043002887141e+01,4.354334827590117811e+02,5.332304202010080374e+00,6.928203299376701096e+00,1.002169075909537937e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181079380568745307e+01,4.354434325838842597e+02,5.333304694392611012e+00,6.928203299376701096e+00,1.000502409242871316e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181223718134603473e+01,4.354533825753672431e+02,5.334303528457108534e+00,6.928203299376701096e+00,9.988357425762046937e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181368055700461639e+01,4.354633327331843589e+02,5.335300704175827136e+00,6.928203299376701096e+00,9.971690759095380718e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181512393266319805e+01,4.354732830570592341e+02,5.336296221521067196e+00,6.928203299376701096e+00,9.955024092428714499e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181656730832177971e+01,4.354832335467154962e+02,5.337290080465176167e+00,6.928203299376701096e+00,9.938357425762048281e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181801068398036136e+01,4.354931842018767156e+02,5.338282280980546801e+00,6.928203299376701096e+00,9.921690759095382062e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.181945405963894302e+01,4.355031350222664628e+02,5.339272823039617144e+00,6.928203299376701096e+00,9.905024092428715843e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182089743529752468e+01,4.355130860076083650e+02,5.340261706614873205e+00,6.928203299376701096e+00,9.888357425762049624e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182234081095610634e+01,4.355230371576259927e+02,5.341248931678845402e+00,6.928203299376701096e+00,9.871690759095383405e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182378418661468800e+01,4.355329884720429163e+02,5.342234498204110338e+00,6.928203299376701096e+00,9.855024092428717186e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182522756227326965e+01,4.355429399505827064e+02,5.343218406163291689e+00,6.928203299376701096e+00,9.838357425762050967e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182667093793185131e+01,4.355528915929689333e+02,5.344200655529059318e+00,6.928203299376701096e+00,9.821690759095384748e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182811431359043297e+01,4.355628433989251675e+02,5.345181246274127496e+00,6.928203299376701096e+00,9.805024092428718530e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.182955768924901463e+01,4.355727953681749796e+02,5.346160178371258453e+00,6.928203299376701096e+00,9.788357425762052311e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183100106490759629e+01,4.355827475004419398e+02,5.347137451793258833e+00,6.928203299376701096e+00,9.771690759095386092e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183244444056617795e+01,4.355926997954495619e+02,5.348113066512982350e+00,6.928203299376701096e+00,9.755024092428719873e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183388781622475960e+01,4.356026522529214162e+02,5.349087022503328903e+00,6.928203299376701096e+00,9.738357425762053654e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183533119188334126e+01,4.356126048725810165e+02,5.350059319737243690e+00,6.928203299376701096e+00,9.721690759095387435e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183677456754192292e+01,4.356225576541519331e+02,5.351029958187718982e+00,6.928203299376701096e+00,9.705024092428721216e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183821794320050458e+01,4.356325105973576797e+02,5.351998937827792346e+00,6.928203299376701096e+00,9.688357425762054997e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.183966131885908624e+01,4.356424637019218267e+02,5.352966258630547536e+00,6.928203299376701096e+00,9.671690759095388779e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184110469451766789e+01,4.356524169675678309e+02,5.353931920569115377e+00,6.928203299376701096e+00,9.655024092428722560e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184254807017624955e+01,4.356623703940192627e+02,5.354895923616671105e+00,6.928203299376701096e+00,9.638357425762056341e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184399144583483121e+01,4.356723239809996358e+02,5.355858267746437029e+00,6.928203299376701096e+00,9.621690759095390122e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184543482149341287e+01,4.356822777282324637e+02,5.356818952931680755e+00,6.928203299376701096e+00,9.605024092428723903e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184687819715199453e+01,4.356922316354412601e+02,5.357777979145717850e+00,6.928203299376701096e+00,9.588357425762057684e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184832157281057619e+01,4.357021857023494817e+02,5.358735346361907403e+00,6.928203299376701096e+00,9.571690759095391465e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.184976494846915784e+01,4.357121399286806422e+02,5.359691054553656464e+00,6.928203299376701096e+00,9.555024092428725246e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185120832412773950e+01,4.357220943141582552e+02,5.360645103694418268e+00,6.928203299376701096e+00,9.538357425762059028e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185265169978632116e+01,4.357320488585058342e+02,5.361597493757690458e+00,6.928203299376701096e+00,9.521690759095392809e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185409507544490282e+01,4.357420035614467793e+02,5.362548224717017753e+00,6.928203299376701096e+00,9.505024092428726590e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185553845110348448e+01,4.357519584227046607e+02,5.363497296545991944e+00,6.928203299376701096e+00,9.488357425762060371e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185698182676206613e+01,4.357619134420028786e+02,5.364444709218249230e+00,6.928203299376701096e+00,9.471690759095394152e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185842520242064779e+01,4.357718686190649464e+02,5.365390462707471997e+00,6.928203299376701096e+00,9.455024092428727933e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.185986857807922945e+01,4.357818239536143778e+02,5.366334556987390592e+00,6.928203299376701096e+00,9.438357425762061714e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186131195373781111e+01,4.357917794453745728e+02,5.367276992031779770e+00,6.928203299376701096e+00,9.421690759095395495e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186275532939639277e+01,4.358017350940689880e+02,5.368217767814460473e+00,6.928203299376701096e+00,9.405024092428729277e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186419870505497443e+01,4.358116908994210803e+02,5.369156884309299826e+00,6.928203299376701096e+00,9.388357425762063058e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186564208071355608e+01,4.358216468611543064e+02,5.370094341490211143e+00,6.928203299376701096e+00,9.371690759095396839e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186708545637213774e+01,4.358316029789921231e+02,5.371030139331154807e+00,6.928203299376701096e+00,9.355024092428730620e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186852883203071940e+01,4.358415592526579871e+02,5.371964277806135613e+00,6.928203299376701096e+00,9.338357425762064401e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.186997220768930106e+01,4.358515156818752985e+02,5.372896756889206316e+00,6.928203299376701096e+00,9.321690759095398182e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.187141558334788272e+01,4.358614722663675138e+02,5.373827576554464081e+00,6.928203299376701096e+00,9.305024092428731963e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.187285895900646437e+01,4.358714290058580332e+02,5.374756736776052257e+00,6.928203299376701096e+00,9.288357425762065744e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.187430233466504603e+01,4.358813859000703133e+02,5.375684237528161269e+00,6.928203299376701096e+00,9.271690759095399526e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.187574571032362769e+01,4.358913429487277540e+02,5.376610078785027724e+00,6.928203299376701096e+00,9.255024092428733307e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.187718908598220935e+01,4.359013001515538122e+02,5.377534260520933529e+00,6.928203299376701096e+00,9.238357425762067088e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.187863246164079101e+01,4.359112575082718308e+02,5.378456782710206774e+00,6.928203299376701096e+00,9.221690759095400869e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188007583729937267e+01,4.359212150186052668e+02,5.379377645327221735e+00,6.928203299376701096e+00,9.205024092428734650e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188151921295795432e+01,4.359311726822775199e+02,5.380296848346398875e+00,6.928203299376701096e+00,9.188357425762068431e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188296258861653598e+01,4.359411304990119902e+02,5.381214391742204839e+00,6.928203299376701096e+00,9.171690759095402212e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188440596427511764e+01,4.359510884685320207e+02,5.382130275489152460e+00,6.928203299376701096e+00,9.155024092428735993e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188584933993369930e+01,4.359610465905610681e+02,5.383044499561800755e+00,6.928203299376701096e+00,9.138357425762069774e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188729271559228096e+01,4.359710048648224756e+02,5.383957063934754039e+00,6.928203299376701096e+00,9.121690759095403556e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.188873609125086261e+01,4.359809632910396431e+02,5.384867968582663700e+00,6.928203299376701096e+00,9.105024092428737337e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189017946690944427e+01,4.359909218689359136e+02,5.385777213480226422e+00,6.928203299376701096e+00,9.088357425762071118e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189162284256802593e+01,4.360008805982346871e+02,5.386684798602185964e+00,6.928203299376701096e+00,9.071690759095404899e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189306621822660759e+01,4.360108394786593635e+02,5.387590723923331382e+00,6.928203299376701096e+00,9.055024092428738680e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189450959388518925e+01,4.360207985099332291e+02,5.388494989418497916e+00,6.928203299376701096e+00,9.038357425762072461e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189595296954377091e+01,4.360307576917796837e+02,5.389397595062567881e+00,6.928203299376701096e+00,9.021690759095406242e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189739634520235256e+01,4.360407170239221273e+02,5.390298540830467999e+00,6.928203299376701096e+00,9.005024092428740023e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.189883972086093422e+01,4.360506765060838461e+02,5.391197826697172069e+00,6.928203299376701096e+00,8.988357425762073805e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190028309651951588e+01,4.360606361379882401e+02,5.392095452637700070e+00,6.928203299376701096e+00,8.971690759095407586e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190172647217809754e+01,4.360705959193585954e+02,5.392991418627118172e+00,6.928203299376701096e+00,8.955024092428741367e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190316984783667920e+01,4.360805558499183121e+02,5.393885724640537838e+00,6.928203299376701096e+00,8.938357425762075148e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190461322349526085e+01,4.360905159293906763e+02,5.394778370653117605e+00,6.928203299376701096e+00,8.921690759095408929e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190605659915384251e+01,4.361004761574990880e+02,5.395669356640062198e+00,6.928203299376701096e+00,8.905024092428742710e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190749997481242417e+01,4.361104365339667766e+02,5.396558682576621635e+00,6.928203299376701096e+00,8.888357425762076491e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.190894335047100583e+01,4.361203970585171419e+02,5.397446348438092123e+00,6.928203299376701096e+00,8.871690759095410272e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191038672612958749e+01,4.361303577308734702e+02,5.398332354199816940e+00,6.928203299376701096e+00,8.855024092428744054e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191183010178816915e+01,4.361403185507591047e+02,5.399216699837184663e+00,6.928203299376701096e+00,8.838357425762077835e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191327347744675080e+01,4.361502795178973315e+02,5.400099385325629164e+00,6.928203299376701096e+00,8.821690759095411616e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191471685310533246e+01,4.361602406320114369e+02,5.400980410640632279e+00,6.928203299376701096e+00,8.805024092428745397e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191616022876391412e+01,4.361702018928247639e+02,5.401859775757721138e+00,6.928203299376701096e+00,8.788357425762079178e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191760360442249578e+01,4.361801633000605989e+02,5.402737480652469060e+00,6.928203299376701096e+00,8.771690759095412959e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.191904698008107744e+01,4.361901248534422280e+02,5.403613525300494658e+00,6.928203299376701096e+00,8.755024092428746740e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192049035573965909e+01,4.362000865526929374e+02,5.404487909677463620e+00,6.928203299376701096e+00,8.738357425762080521e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192193373139824075e+01,4.362100483975360135e+02,5.405360633759087818e+00,6.928203299376701096e+00,8.721690759095414303e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192337710705682241e+01,4.362200103876947423e+02,5.406231697521124424e+00,6.928203299376701096e+00,8.705024092428748084e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192482048271540407e+01,4.362299725228924103e+02,5.407101100939377680e+00,6.928203299376701096e+00,8.688357425762081865e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192626385837398573e+01,4.362399348028522468e+02,5.407968843989697127e+00,6.928203299376701096e+00,8.671690759095415646e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192770723403256738e+01,4.362498972272975948e+02,5.408834926647979380e+00,6.928203299376701096e+00,8.655024092428749427e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.192915060969114904e+01,4.362598597959516837e+02,5.409699348890165460e+00,6.928203299376701096e+00,8.638357425762083208e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193059398534973070e+01,4.362698225085377430e+02,5.410562110692244353e+00,6.928203299376701096e+00,8.621690759095416989e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193203736100831236e+01,4.362797853647790589e+02,5.411423212030251229e+00,6.928203299376701096e+00,8.605024092428750770e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193348073666689402e+01,4.362897483643989176e+02,5.412282652880265665e+00,6.928203299376701096e+00,8.588357425762084552e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193492411232547568e+01,4.362997115071205485e+02,5.413140433218414316e+00,6.928203299376701096e+00,8.571690759095418333e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193636748798405733e+01,4.363096747926671810e+02,5.413996553020870017e+00,6.928203299376701096e+00,8.555024092428752114e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193781086364263899e+01,4.363196382207621014e+02,5.414851012263851793e+00,6.928203299376701096e+00,8.538357425762085895e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.193925423930122065e+01,4.363296017911284821e+02,5.415703810923624850e+00,6.928203299376701096e+00,8.521690759095419676e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194069761495980231e+01,4.363395655034896095e+02,5.416554948976499695e+00,6.928203299376701096e+00,8.505024092428753457e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194214099061838397e+01,4.363495293575686560e+02,5.417404426398833905e+00,6.928203299376701096e+00,8.488357425762087238e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194358436627696562e+01,4.363594933530889080e+02,5.418252243167031246e+00,6.928203299376701096e+00,8.471690759095421019e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194502774193554728e+01,4.363694574897735379e+02,5.419098399257540777e+00,6.928203299376701096e+00,8.455024092428754801e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194647111759412894e+01,4.363794217673458320e+02,5.419942894646858633e+00,6.928203299376701096e+00,8.438357425762088582e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194791449325271060e+01,4.363893861855289629e+02,5.420785729311526246e+00,6.928203299376701096e+00,8.421690759095422363e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.194935786891129226e+01,4.363993507440461030e+02,5.421626903228132122e+00,6.928203299376701096e+00,8.405024092428756144e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195080124456987392e+01,4.364093154426205388e+02,5.422466416373309173e+00,6.928203299376701096e+00,8.388357425762089925e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195224462022845557e+01,4.364192802809754426e+02,5.423304268723738275e+00,6.928203299376701096e+00,8.371690759095423706e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195368799588703723e+01,4.364292452588339870e+02,5.424140460256145602e+00,6.928203299376701096e+00,8.355024092428757487e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195513137154561889e+01,4.364392103759194015e+02,5.424974990947304399e+00,6.928203299376701096e+00,8.338357425762091268e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195657474720420055e+01,4.364491756319548585e+02,5.425807860774032321e+00,6.928203299376701096e+00,8.321690759095425050e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195801812286278221e+01,4.364591410266635307e+02,5.426639069713194097e+00,6.928203299376701096e+00,8.305024092428758831e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.195946149852136386e+01,4.364691065597685906e+02,5.427468617741701529e+00,6.928203299376701096e+00,8.288357425762092612e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196090487417994552e+01,4.364790722309932676e+02,5.428296504836510827e+00,6.928203299376701096e+00,8.271690759095426393e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196234824983852718e+01,4.364890380400607341e+02,5.429122730974625277e+00,6.928203299376701096e+00,8.255024092428760174e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196379162549710884e+01,4.364990039866941061e+02,5.429947296133094348e+00,6.928203299376701096e+00,8.238357425762093955e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196523500115569050e+01,4.365089700706166127e+02,5.430770200289012806e+00,6.928203299376701096e+00,8.221690759095427736e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196667837681427216e+01,4.365189362915513698e+02,5.431591443419522491e+00,6.928203299376701096e+00,8.205024092428761517e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196812175247285381e+01,4.365289026492215498e+02,5.432411025501811430e+00,6.928203299376701096e+00,8.188357425762095299e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.196956512813143547e+01,4.365388691433503254e+02,5.433228946513112945e+00,6.928203299376701096e+00,8.171690759095429080e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197100850379001713e+01,4.365488357736608691e+02,5.434045206430707431e+00,6.928203299376701096e+00,8.155024092428762861e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197245187944859879e+01,4.365588025398762966e+02,5.434859805231921470e+00,6.928203299376701096e+00,8.138357425762096642e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197389525510718045e+01,4.365687694417197804e+02,5.435672742894126941e+00,6.928203299376701096e+00,8.121690759095430423e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197533863076576210e+01,4.365787364789144362e+02,5.436484019394741907e+00,6.928203299376701096e+00,8.105024092428764204e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197678200642434376e+01,4.365887036511833799e+02,5.437293634711230617e+00,6.928203299376701096e+00,8.088357425762097985e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197822538208292542e+01,4.365986709582497838e+02,5.438101588821104393e+00,6.928203299376701096e+00,8.071690759095431766e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.197966875774150708e+01,4.366086383998367637e+02,5.438907881701919855e+00,6.928203299376701096e+00,8.055024092428765548e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198111213340008874e+01,4.366186059756674922e+02,5.439712513331279808e+00,6.928203299376701096e+00,8.038357425762099329e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198255550905867040e+01,4.366285736854650281e+02,5.440515483686834131e+00,6.928203299376701096e+00,8.021690759095433110e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198399888471725205e+01,4.366385415289525440e+02,5.441316792746277109e+00,6.928203299376701096e+00,8.005024092428766891e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198544226037583371e+01,4.366485095058530987e+02,5.442116440487350992e+00,6.928203299376701096e+00,7.988357425762100672e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198688563603441537e+01,4.366584776158898649e+02,5.442914426887842438e+00,6.928203299376701096e+00,7.971690759095434453e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198832901169299703e+01,4.366684458587859012e+02,5.443710751925586067e+00,6.928203299376701096e+00,7.955024092428768234e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.198977238735157869e+01,4.366784142342643236e+02,5.444505415578460905e+00,6.928203299376701096e+00,7.938357425762102015e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199121576301016034e+01,4.366883827420482476e+02,5.445298417824393056e+00,6.928203299376701096e+00,7.921690759095435796e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199265913866874200e+01,4.366983513818607321e+02,5.446089758641355694e+00,6.928203299376701096e+00,7.905024092428769578e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199410251432732366e+01,4.367083201534248929e+02,5.446879438007366403e+00,6.928203299376701096e+00,7.888357425762103359e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199554588998590532e+01,4.367182890564638456e+02,5.447667455900488953e+00,6.928203299376701096e+00,7.871690759095437140e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199698926564448698e+01,4.367282580907006491e+02,5.448453812298835075e+00,6.928203299376701096e+00,7.855024092428770921e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199843264130306864e+01,4.367382272558584191e+02,5.449238507180560909e+00,6.928203299376701096e+00,7.838357425762104702e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.199987601696165029e+01,4.367481965516602145e+02,5.450021540523869668e+00,6.928203299376701096e+00,7.821690759095438483e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200131939262023195e+01,4.367581659778290941e+02,5.450802912307010750e+00,6.928203299376701096e+00,7.805024092428772264e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200276276827881361e+01,4.367681355340881169e+02,5.451582622508278853e+00,6.928203299376701096e+00,7.788357425762106045e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200420614393739527e+01,4.367781052201603984e+02,5.452360671106015744e+00,6.928203299376701096e+00,7.771690759095439827e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200564951959597693e+01,4.367880750357689408e+02,5.453137058078608490e+00,6.928203299376701096e+00,7.755024092428773608e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200709289525455858e+01,4.367980449806368597e+02,5.453911783404491231e+00,6.928203299376701096e+00,7.738357425762107389e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200853627091314024e+01,4.368080150544872140e+02,5.454684847062143405e+00,6.928203299376701096e+00,7.721690759095441170e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.200997964657172190e+01,4.368179852570430057e+02,5.455456249030091520e+00,6.928203299376701096e+00,7.705024092428774951e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.201142302223030356e+01,4.368279555880273506e+02,5.456225989286907385e+00,6.928203299376701096e+00,7.688357425762108732e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.201286639788888522e+01,4.368379260471632506e+02,5.456994067811208993e+00,6.928203299376701096e+00,7.671690759095442513e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.201430977354746688e+01,4.368478966341737646e+02,5.457760484581661409e+00,6.928203299376701096e+00,7.655024092428776294e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.201575314920604853e+01,4.368578673487818946e+02,5.458525239576974997e+00,6.928203299376701096e+00,7.638357425762110076e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.201719652486463019e+01,4.368678381907106996e+02,5.459288332775906305e+00,6.928203299376701096e+00,7.621690759095443857e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.201863990052321185e+01,4.368778091596832382e+02,5.460049764157258956e+00,6.928203299376701096e+00,7.605024092428777638e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202008327618179351e+01,4.368877802554225127e+02,5.460809533699881868e+00,6.928203299376701096e+00,7.588357425762111419e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202152665184037517e+01,4.368977514776515818e+02,5.461567641382670146e+00,6.928203299376701096e+00,7.571690759095445200e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202297002749895682e+01,4.369077228260934476e+02,5.462324087184565080e+00,6.928203299376701096e+00,7.555024092428778981e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202441340315753848e+01,4.369176943004711120e+02,5.463078871084555033e+00,6.928203299376701096e+00,7.538357425762112762e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202585677881612014e+01,4.369276659005075771e+02,5.463831993061672776e+00,6.928203299376701096e+00,7.521690759095446543e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202730015447470180e+01,4.369376376259259018e+02,5.464583453094999044e+00,6.928203299376701096e+00,7.505024092428780325e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.202874353013328346e+01,4.369476094764490881e+02,5.465333251163659867e+00,6.928203299376701096e+00,7.488357425762114106e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203018690579186512e+01,4.369575814518000811e+02,5.466081387246827461e+00,6.928203299376701096e+00,7.471690759095447887e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203163028145044677e+01,4.369675535517019398e+02,5.466827861323720228e+00,6.928203299376701096e+00,7.455024092428781668e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203307365710902843e+01,4.369775257758776092e+02,5.467572673373601866e+00,6.928203299376701096e+00,7.438357425762115449e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203451703276761009e+01,4.369874981240501484e+02,5.468315823375784035e+00,6.928203299376701096e+00,7.421690759095449230e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203596040842619175e+01,4.369974705959425023e+02,5.469057311309623692e+00,6.928203299376701096e+00,7.405024092428783011e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203740378408477341e+01,4.370074431912776731e+02,5.469797137154523980e+00,6.928203299376701096e+00,7.388357425762116792e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.203884715974335506e+01,4.370174159097786628e+02,5.470535300889934227e+00,6.928203299376701096e+00,7.371690759095450574e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204029053540193672e+01,4.370273887511684165e+02,5.471271802495349945e+00,6.928203299376701096e+00,7.355024092428784355e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204173391106051838e+01,4.370373617151699364e+02,5.472006641950311945e+00,6.928203299376701096e+00,7.338357425762118136e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204317728671910004e+01,4.370473348015061674e+02,5.472739819234408998e+00,6.928203299376701096e+00,7.321690759095451917e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204462066237768170e+01,4.370573080099001118e+02,5.473471334327274285e+00,6.928203299376701096e+00,7.305024092428785698e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204606403803626336e+01,4.370672813400747145e+02,5.474201187208588948e+00,6.928203299376701096e+00,7.288357425762119479e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204750741369484501e+01,4.370772547917529209e+02,5.474929377858078539e+00,6.928203299376701096e+00,7.271690759095453260e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.204895078935342667e+01,4.370872283646577330e+02,5.475655906255515681e+00,6.928203299376701096e+00,7.255024092428787041e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205039416501200833e+01,4.370972020585120958e+02,5.476380772380719186e+00,6.928203299376701096e+00,7.238357425762120823e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205183754067058999e+01,4.371071758730389547e+02,5.477103976213554049e+00,6.928203299376701096e+00,7.221690759095454604e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205328091632917165e+01,4.371171498079612547e+02,5.477825517733930560e+00,6.928203299376701096e+00,7.205024092428788385e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205472429198775330e+01,4.371271238630019411e+02,5.478545396921806088e+00,6.928203299376701096e+00,7.188357425762122166e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205616766764633496e+01,4.371370980378839590e+02,5.479263613757184181e+00,6.928203299376701096e+00,7.171690759095455947e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205761104330491662e+01,4.371470723323302536e+02,5.479980168220114578e+00,6.928203299376701096e+00,7.155024092428789728e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.205905441896349828e+01,4.371570467460637701e+02,5.480695060290693199e+00,6.928203299376701096e+00,7.138357425762123509e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206049779462207994e+01,4.371670212788074537e+02,5.481408289949061263e+00,6.928203299376701096e+00,7.121690759095457290e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206194117028066159e+01,4.371769959302841926e+02,5.482119857175407063e+00,6.928203299376701096e+00,7.105024092428791072e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206338454593924325e+01,4.371869707002169321e+02,5.482829761949965075e+00,6.928203299376701096e+00,7.088357425762124853e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206482792159782491e+01,4.371969455883286173e+02,5.483538004253015075e+00,6.928203299376701096e+00,7.071690759095458634e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206627129725640657e+01,4.372069205943421366e+02,5.484244584064884798e+00,6.928203299376701096e+00,7.055024092428792415e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206771467291498823e+01,4.372168957179803783e+02,5.484949501365945501e+00,6.928203299376701096e+00,7.038357425762126196e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.206915804857356989e+01,4.372268709589662876e+02,5.485652756136617292e+00,6.928203299376701096e+00,7.021690759095459977e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207060142423215154e+01,4.372368463170228097e+02,5.486354348357365573e+00,6.928203299376701096e+00,7.005024092428793758e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207204479989073320e+01,4.372468217918728328e+02,5.487054278008701047e+00,6.928203299376701096e+00,6.988357425762127539e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207348817554931486e+01,4.372567973832392454e+02,5.487752545071180599e+00,6.928203299376701096e+00,6.971690759095461321e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207493155120789652e+01,4.372667730908449357e+02,5.488449149525409076e+00,6.928203299376701096e+00,6.955024092428795102e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207637492686647818e+01,4.372767489144128490e+02,5.489144091352035737e+00,6.928203299376701096e+00,6.938357425762128883e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207781830252505983e+01,4.372867248536658167e+02,5.489837370531756910e+00,6.928203299376701096e+00,6.921690759095462664e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.207926167818364149e+01,4.372967009083267840e+02,5.490528987045315112e+00,6.928203299376701096e+00,6.905024092428796445e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208070505384222315e+01,4.373066770781185824e+02,5.491218940873498155e+00,6.928203299376701096e+00,6.888357425762130226e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208214842950080481e+01,4.373166533627641570e+02,5.491907231997140926e+00,6.928203299376701096e+00,6.871690759095464007e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208359180515938647e+01,4.373266297619863394e+02,5.492593860397124494e+00,6.928203299376701096e+00,6.855024092428797788e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208503518081796813e+01,4.373366062755080179e+02,5.493278826054375230e+00,6.928203299376701096e+00,6.838357425762131570e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208647855647654978e+01,4.373465829030520808e+02,5.493962128949866575e+00,6.928203299376701096e+00,6.821690759095465351e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208792193213513144e+01,4.373565596443414165e+02,5.494643769064618155e+00,6.928203299376701096e+00,6.805024092428799132e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.208936530779371310e+01,4.373665364990988564e+02,5.495323746379694896e+00,6.928203299376701096e+00,6.788357425762132913e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209080868345229476e+01,4.373765134670472889e+02,5.496002060876208795e+00,6.928203299376701096e+00,6.771690759095466694e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209225205911087642e+01,4.373864905479095455e+02,5.496678712535318034e+00,6.928203299376701096e+00,6.755024092428800475e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209369543476945807e+01,4.373964677414085145e+02,5.497353701338226983e+00,6.928203299376701096e+00,6.738357425762134256e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209513881042803973e+01,4.374064450472670273e+02,5.498027027266185307e+00,6.928203299376701096e+00,6.721690759095468037e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209658218608662139e+01,4.374164224652079724e+02,5.498698690300489744e+00,6.928203299376701096e+00,6.705024092428801818e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209802556174520305e+01,4.374263999949541812e+02,5.499368690422483219e+00,6.928203299376701096e+00,6.688357425762135600e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.209946893740378471e+01,4.374363776362284852e+02,5.500037027613554841e+00,6.928203299376701096e+00,6.671690759095469381e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210091231306236637e+01,4.374463553887537728e+02,5.500703701855139016e+00,6.928203299376701096e+00,6.655024092428803162e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210235568872094802e+01,4.374563332522528185e+02,5.501368713128717225e+00,6.928203299376701096e+00,6.638357425762136943e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210379906437952968e+01,4.374663112264485108e+02,5.502032061415817132e+00,6.928203299376701096e+00,6.621690759095470724e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210524244003811134e+01,4.374762893110636810e+02,5.502693746698012589e+00,6.928203299376701096e+00,6.605024092428804505e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210668581569669300e+01,4.374862675058211607e+02,5.503353768956922742e+00,6.928203299376701096e+00,6.588357425762138286e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210812919135527466e+01,4.374962458104437246e+02,5.504012128174213814e+00,6.928203299376701096e+00,6.571690759095472067e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.210957256701385631e+01,4.375062242246542610e+02,5.504668824331599097e+00,6.928203299376701096e+00,6.555024092428805849e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211101594267243797e+01,4.375162027481755445e+02,5.505323857410835409e+00,6.928203299376701096e+00,6.538357425762139630e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211245931833101963e+01,4.375261813807304065e+02,5.505977227393728413e+00,6.928203299376701096e+00,6.521690759095473411e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211390269398960129e+01,4.375361601220416787e+02,5.506628934262129071e+00,6.928203299376701096e+00,6.505024092428807192e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211534606964818295e+01,4.375461389718321925e+02,5.507278977997933644e+00,6.928203299376701096e+00,6.488357425762140973e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211678944530676461e+01,4.375561179298247225e+02,5.507927358583086352e+00,6.928203299376701096e+00,6.471690759095474754e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211823282096534626e+01,4.375660969957421003e+02,5.508574075999575825e+00,6.928203299376701096e+00,6.455024092428808535e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.211967619662392792e+01,4.375760761693071004e+02,5.509219130229437766e+00,6.928203299376701096e+00,6.438357425762142316e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212111957228250958e+01,4.375860554502425543e+02,5.509862521254754064e+00,6.928203299376701096e+00,6.421690759095476098e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212256294794109124e+01,4.375960348382712368e+02,5.510504249057652792e+00,6.928203299376701096e+00,6.405024092428809879e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212400632359967290e+01,4.376060143331159225e+02,5.511144313620308210e+00,6.928203299376701096e+00,6.388357425762143660e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212544969925825455e+01,4.376159939344994427e+02,5.511782714924940763e+00,6.928203299376701096e+00,6.371690759095477441e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212689307491683621e+01,4.376259736421445723e+02,5.512419452953817078e+00,6.928203299376701096e+00,6.355024092428811222e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212833645057541787e+01,4.376359534557741426e+02,5.513054527689249973e+00,6.928203299376701096e+00,6.338357425762145003e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.212977982623399953e+01,4.376459333751108716e+02,5.513687939113598446e+00,6.928203299376701096e+00,6.321690759095478784e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213122320189258119e+01,4.376559133998775337e+02,5.514319687209267684e+00,6.928203299376701096e+00,6.305024092428812565e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213266657755116285e+01,4.376658935297969606e+02,5.514949771958709945e+00,6.928203299376701096e+00,6.288357425762146347e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213410995320974450e+01,4.376758737645918700e+02,5.515578193344421898e+00,6.928203299376701096e+00,6.271690759095480128e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213555332886832616e+01,4.376858541039850934e+02,5.516204951348947283e+00,6.928203299376701096e+00,6.255024092428813909e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213699670452690782e+01,4.376958345476993486e+02,5.516830045954876915e+00,6.928203299376701096e+00,6.238357425762146996e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213844008018548948e+01,4.377058150954574103e+02,5.517453477144846907e+00,6.928203299376701096e+00,6.221690759095480083e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.213988345584407114e+01,4.377157957469820531e+02,5.518075244901539556e+00,6.928203299376701096e+00,6.205024092428813171e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214132683150265279e+01,4.377257765019960516e+02,5.518695349207683343e+00,6.928203299376701096e+00,6.188357425762146258e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214277020716123445e+01,4.377357573602221237e+02,5.519313790046052937e+00,6.928203299376701096e+00,6.171690759095479345e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214421358281981611e+01,4.377457383213830440e+02,5.519930567399470078e+00,6.928203299376701096e+00,6.155024092428812432e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214565695847839777e+01,4.377557193852015871e+02,5.520545681250801806e+00,6.928203299376701096e+00,6.138357425762145519e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214710033413697943e+01,4.377657005514004709e+02,5.521159131582961344e+00,6.928203299376701096e+00,6.121690759095478607e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214854370979556109e+01,4.377756818197024700e+02,5.521770918378908100e+00,6.928203299376701096e+00,6.105024092428811694e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.214998708545414274e+01,4.377856631898303021e+02,5.522381041621648556e+00,6.928203299376701096e+00,6.088357425762144781e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.215143046111272440e+01,4.377956446615066852e+02,5.522989501294235382e+00,6.928203299376701096e+00,6.071690759095477868e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.215287383677130606e+01,4.378056262344543939e+02,5.523596297379766540e+00,6.928203299376701096e+00,6.055024092428810956e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.215431721242988772e+01,4.378156079083961458e+02,5.524201429861386181e+00,6.928203299376701096e+00,6.038357425762144043e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.215576058808846938e+01,4.378255896830547158e+02,5.524804898722284641e+00,6.928203299376701096e+00,6.021690759095477130e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.215720396374705103e+01,4.378355715581527647e+02,5.525406703945700215e+00,6.928203299376701096e+00,6.005024092428810217e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.215864733940563269e+01,4.378455535334130673e+02,5.526006845514915611e+00,6.928203299376701096e+00,5.988357425762143305e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216009071506421435e+01,4.378555356085582844e+02,5.526605323413259718e+00,6.928203299376701096e+00,5.971690759095476392e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216153409072279601e+01,4.378655177833111907e+02,5.527202137624108502e+00,6.928203299376701096e+00,5.955024092428809479e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216297746638137767e+01,4.378755000573945040e+02,5.527797288130883224e+00,6.928203299376701096e+00,5.938357425762142566e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216442084203995933e+01,4.378854824305309421e+02,5.528390774917053108e+00,6.928203299376701096e+00,5.921690759095475654e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216586421769854098e+01,4.378954649024431660e+02,5.528982597966131785e+00,6.928203299376701096e+00,5.905024092428808741e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216730759335712264e+01,4.379054474728539503e+02,5.529572757261679072e+00,6.928203299376701096e+00,5.888357425762141828e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.216875096901570430e+01,4.379154301414859560e+02,5.530161252787302750e+00,6.928203299376701096e+00,5.871690759095474915e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217019434467428596e+01,4.379254129080619009e+02,5.530748084526655006e+00,6.928203299376701096e+00,5.855024092428808002e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217163772033286762e+01,4.379353957723045028e+02,5.531333252463435102e+00,6.928203299376701096e+00,5.838357425762141090e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217308109599144927e+01,4.379453787339364226e+02,5.531916756581388483e+00,6.928203299376701096e+00,5.821690759095474177e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217452447165003093e+01,4.379553617926803781e+02,5.532498596864306784e+00,6.928203299376701096e+00,5.805024092428807264e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217596784730861259e+01,4.379653449482590304e+02,5.533078773296027819e+00,6.928203299376701096e+00,5.788357425762140351e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217741122296719425e+01,4.379753282003950972e+02,5.533657285860435593e+00,6.928203299376701096e+00,5.771690759095473439e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.217885459862577591e+01,4.379853115488112962e+02,5.534234134541460293e+00,6.928203299376701096e+00,5.755024092428806526e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218029797428435757e+01,4.379952949932302886e+02,5.534809319323077403e+00,6.928203299376701096e+00,5.738357425762139613e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218174134994293922e+01,4.380052785333747352e+02,5.535382840189310372e+00,6.928203299376701096e+00,5.721690759095472700e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218318472560152088e+01,4.380152621689673538e+02,5.535954697124228829e+00,6.928203299376701096e+00,5.705024092428805788e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218462810126010254e+01,4.380252458997308054e+02,5.536524890111946817e+00,6.928203299376701096e+00,5.688357425762138875e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218607147691868420e+01,4.380352297253877509e+02,5.537093419136625450e+00,6.928203299376701096e+00,5.671690759095471962e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218751485257726586e+01,4.380452136456608514e+02,5.537660284182472914e+00,6.928203299376701096e+00,5.655024092428805049e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.218895822823584751e+01,4.380551976602728246e+02,5.538225485233742695e+00,6.928203299376701096e+00,5.638357425762138136e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219040160389442917e+01,4.380651817689462746e+02,5.538789022274735352e+00,6.928203299376701096e+00,5.621690759095471224e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219184497955301083e+01,4.380751659714039192e+02,5.539350895289796739e+00,6.928203299376701096e+00,5.605024092428804311e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219328835521159249e+01,4.380851502673683626e+02,5.539911104263318897e+00,6.928203299376701096e+00,5.588357425762137398e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219473173087017415e+01,4.380951346565623226e+02,5.540469649179740941e+00,6.928203299376701096e+00,5.571690759095470485e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219617510652875580e+01,4.381051191387084032e+02,5.541026530023547281e+00,6.928203299376701096e+00,5.555024092428803573e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219761848218733746e+01,4.381151037135293222e+02,5.541581746779268514e+00,6.928203299376701096e+00,5.538357425762136660e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.219906185784591912e+01,4.381250883807476839e+02,5.542135299431483197e+00,6.928203299376701096e+00,5.521690759095469747e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220050523350450078e+01,4.381350731400861491e+02,5.542687187964814299e+00,6.928203299376701096e+00,5.505024092428802834e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220194860916308244e+01,4.381450579912673220e+02,5.543237412363930972e+00,6.928203299376701096e+00,5.488357425762135922e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220339198482166410e+01,4.381550429340139203e+02,5.543785972613550328e+00,6.928203299376701096e+00,5.471690759095469009e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220483536048024575e+01,4.381650279680485482e+02,5.544332868698433892e+00,6.928203299376701096e+00,5.455024092428802096e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220627873613882741e+01,4.381750130930938099e+02,5.544878100603390259e+00,6.928203299376701096e+00,5.438357425762135183e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220772211179740907e+01,4.381849983088723661e+02,5.545421668313274211e+00,6.928203299376701096e+00,5.421690759095468271e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.220916548745599073e+01,4.381949836151068780e+02,5.545963571812986714e+00,6.928203299376701096e+00,5.405024092428801358e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221060886311457239e+01,4.382049690115199496e+02,5.546503811087474922e+00,6.928203299376701096e+00,5.388357425762134445e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221205223877315404e+01,4.382149544978342419e+02,5.547042386121731283e+00,6.928203299376701096e+00,5.371690759095467532e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221349561443173570e+01,4.382249400737723022e+02,5.547579296900796209e+00,6.928203299376701096e+00,5.355024092428800619e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221493899009031736e+01,4.382349257390568482e+02,5.548114543409755406e+00,6.928203299376701096e+00,5.338357425762133707e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221638236574889902e+01,4.382449114934104273e+02,5.548648125633740769e+00,6.928203299376701096e+00,5.321690759095466794e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221782574140748068e+01,4.382548973365557003e+02,5.549180043557931263e+00,6.928203299376701096e+00,5.305024092428799881e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.221926911706606234e+01,4.382648832682152715e+02,5.549710297167550266e+00,6.928203299376701096e+00,5.288357425762132968e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222071249272464399e+01,4.382748692881117449e+02,5.550238886447869113e+00,6.928203299376701096e+00,5.271690759095466056e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222215586838322565e+01,4.382848553959677247e+02,5.550765811384205328e+00,6.928203299376701096e+00,5.255024092428799143e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222359924404180731e+01,4.382948415915058149e+02,5.551291071961921730e+00,6.928203299376701096e+00,5.238357425762132230e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222504261970038897e+01,4.383048278744486765e+02,5.551814668166427325e+00,6.928203299376701096e+00,5.221690759095465317e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222648599535897063e+01,4.383148142445188569e+02,5.552336599983178189e+00,6.928203299376701096e+00,5.205024092428798405e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222792937101755228e+01,4.383248007014389600e+02,5.552856867397675700e+00,6.928203299376701096e+00,5.188357425762131492e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.222937274667613394e+01,4.383347872449315901e+02,5.553375470395468305e+00,6.928203299376701096e+00,5.171690759095464579e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223081612233471560e+01,4.383447738747193512e+02,5.553892408962150640e+00,6.928203299376701096e+00,5.155024092428797666e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223225949799329726e+01,4.383547605905248474e+02,5.554407683083362635e+00,6.928203299376701096e+00,5.138357425762130753e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223370287365187892e+01,4.383647473920706830e+02,5.554921292744791295e+00,6.928203299376701096e+00,5.121690759095463841e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223514624931046058e+01,4.383747342790794050e+02,5.555433237932169810e+00,6.928203299376701096e+00,5.105024092428796928e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223658962496904223e+01,4.383847212512736178e+02,5.555943518631277556e+00,6.928203299376701096e+00,5.088357425762130015e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223803300062762389e+01,4.383947083083759253e+02,5.556452134827940093e+00,6.928203299376701096e+00,5.071690759095463102e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.223947637628620555e+01,4.384046954501088749e+02,5.556959086508029166e+00,6.928203299376701096e+00,5.055024092428796190e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224091975194478721e+01,4.384146826761950706e+02,5.557464373657462708e+00,6.928203299376701096e+00,5.038357425762129277e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224236312760336887e+01,4.384246699863570598e+02,5.557967996262205723e+00,6.928203299376701096e+00,5.021690759095462364e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224380650326195052e+01,4.384346573803174465e+02,5.558469954308267624e+00,6.928203299376701096e+00,5.005024092428795451e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224524987892053218e+01,4.384446448577987780e+02,5.558970247781705787e+00,6.928203299376701096e+00,4.988357425762128539e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224669325457911384e+01,4.384546324185236585e+02,5.559468876668622883e+00,6.928203299376701096e+00,4.971690759095461626e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224813663023769550e+01,4.384646200622146353e+02,5.559965840955167771e+00,6.928203299376701096e+00,4.955024092428794713e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.224958000589627716e+01,4.384746077885942555e+02,5.560461140627536381e+00,6.928203299376701096e+00,4.938357425762127800e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225102338155485882e+01,4.384845955973851233e+02,5.560954775671969941e+00,6.928203299376701096e+00,4.921690759095460888e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225246675721344047e+01,4.384945834883097859e+02,5.561446746074756753e+00,6.928203299376701096e+00,4.905024092428793975e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225391013287202213e+01,4.385045714610907908e+02,5.561937051822231304e+00,6.928203299376701096e+00,4.888357425762127062e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225535350853060379e+01,4.385145595154506850e+02,5.562425692900773377e+00,6.928203299376701096e+00,4.871690759095460149e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225679688418918545e+01,4.385245476511120160e+02,5.562912669296809831e+00,6.928203299376701096e+00,4.855024092428793236e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225824025984776711e+01,4.385345358677973877e+02,5.563397980996813708e+00,6.928203299376701096e+00,4.838357425762126324e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.225968363550634876e+01,4.385445241652292907e+02,5.563881627987304235e+00,6.928203299376701096e+00,4.821690759095459411e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226112701116493042e+01,4.385545125431303290e+02,5.564363610254845938e+00,6.928203299376701096e+00,4.805024092428792498e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226257038682351208e+01,4.385645010012229932e+02,5.564843927786051303e+00,6.928203299376701096e+00,4.788357425762125585e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226401376248209374e+01,4.385744895392298872e+02,5.565322580567578115e+00,6.928203299376701096e+00,4.771690759095458673e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226545713814067540e+01,4.385844781568735016e+02,5.565799568586129453e+00,6.928203299376701096e+00,4.755024092428791760e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226690051379925706e+01,4.385944668538763835e+02,5.566274891828456362e+00,6.928203299376701096e+00,4.738357425762124847e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226834388945783871e+01,4.386044556299610804e+02,5.566748550281356067e+00,6.928203299376701096e+00,4.721690759095457934e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.226978726511642037e+01,4.386144444848500825e+02,5.567220543931670207e+00,6.928203299376701096e+00,4.705024092428791022e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227123064077500203e+01,4.386244334182659941e+02,5.567690872766288379e+00,6.928203299376701096e+00,4.688357425762124109e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227267401643358369e+01,4.386344224299313055e+02,5.568159536772146367e+00,6.928203299376701096e+00,4.671690759095457196e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227411739209216535e+01,4.386444115195685640e+02,5.568626535936225252e+00,6.928203299376701096e+00,4.655024092428790283e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227556076775074700e+01,4.386544006869002601e+02,5.569091870245553189e+00,6.928203299376701096e+00,4.638357425762123371e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227700414340932866e+01,4.386643899316489410e+02,5.569555539687203627e+00,6.928203299376701096e+00,4.621690759095456458e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227844751906791032e+01,4.386743792535370972e+02,5.570017544248297092e+00,6.928203299376701096e+00,4.605024092428789545e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.227989089472649198e+01,4.386843686522872758e+02,5.570477883916000295e+00,6.928203299376701096e+00,4.588357425762122632e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228133427038507364e+01,4.386943581276220243e+02,5.570936558677526129e+00,6.928203299376701096e+00,4.571690759095455719e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228277764604365530e+01,4.387043476792637762e+02,5.571393568520132789e+00,6.928203299376701096e+00,4.555024092428788807e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228422102170223695e+01,4.387143373069351355e+02,5.571848913431126427e+00,6.928203299376701096e+00,4.538357425762121894e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228566439736081861e+01,4.387243270103585360e+02,5.572302593397858494e+00,6.928203299376701096e+00,4.521690759095454981e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228710777301940027e+01,4.387343167892565248e+02,5.572754608407726629e+00,6.928203299376701096e+00,4.505024092428788068e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228855114867798193e+01,4.387443066433515924e+02,5.573204958448174651e+00,6.928203299376701096e+00,4.488357425762121156e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.228999452433656359e+01,4.387542965723662860e+02,5.573653643506692568e+00,6.928203299376701096e+00,4.471690759095454243e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.229143789999514524e+01,4.387642865760230393e+02,5.574100663570817460e+00,6.928203299376701096e+00,4.455024092428787330e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.229288127565372690e+01,4.387742766540443995e+02,5.574546018628132593e+00,6.928203299376701096e+00,4.438357425762120417e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.229432465131230856e+01,4.387842668061528570e+02,5.574989708666265642e+00,6.928203299376701096e+00,4.421690759095453505e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.229576802697089022e+01,4.387942570320709024e+02,5.575431733672893131e+00,6.928203299376701096e+00,4.405024092428786592e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.229721140262947188e+01,4.388042473315210259e+02,5.575872093635735993e+00,6.928203299376701096e+00,4.388357425762119679e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.229865477828805354e+01,4.388142377042257181e+02,5.576310788542562236e+00,6.928203299376701096e+00,4.371690759095452766e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230009815394663519e+01,4.388242281499074693e+02,5.576747818381186050e+00,6.928203299376701096e+00,4.355024092428785853e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230154152960521685e+01,4.388342186682887700e+02,5.577183183139466927e+00,6.928203299376701096e+00,4.338357425762118941e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230298490526379851e+01,4.388442092590921106e+02,5.577616882805312315e+00,6.928203299376701096e+00,4.321690759095452028e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230442828092238017e+01,4.388541999220399816e+02,5.578048917366674075e+00,6.928203299376701096e+00,4.305024092428785115e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230587165658096183e+01,4.388641906568548166e+02,5.578479286811552029e+00,6.928203299376701096e+00,4.288357425762118202e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230731503223954348e+01,4.388741814632591627e+02,5.578907991127991295e+00,6.928203299376701096e+00,4.271690759095451290e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.230875840789812514e+01,4.388841723409754536e+02,5.579335030304083176e+00,6.928203299376701096e+00,4.255024092428784377e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231020178355670680e+01,4.388941632897261798e+02,5.579760404327965162e+00,6.928203299376701096e+00,4.238357425762117464e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231164515921528846e+01,4.389041543092338316e+02,5.580184113187821815e+00,6.928203299376701096e+00,4.221690759095450551e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231308853487387012e+01,4.389141453992208426e+02,5.580606156871883883e+00,6.928203299376701096e+00,4.205024092428783639e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231453191053245177e+01,4.389241365594097033e+02,5.581026535368427410e+00,6.928203299376701096e+00,4.188357425762116726e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231597528619103343e+01,4.389341277895229041e+02,5.581445248665775516e+00,6.928203299376701096e+00,4.171690759095449813e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231741866184961509e+01,4.389441190892828786e+02,5.581862296752296615e+00,6.928203299376701096e+00,4.155024092428782900e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.231886203750819675e+01,4.389541104584121172e+02,5.582277679616406196e+00,6.928203299376701096e+00,4.138357425762115988e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232030541316677841e+01,4.389641018966330535e+02,5.582691397246565934e+00,6.928203299376701096e+00,4.121690759095449075e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232174878882536007e+01,4.389740934036681210e+02,5.583103449631284576e+00,6.928203299376701096e+00,4.105024092428782162e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232319216448394172e+01,4.389840849792398103e+02,5.583513836759115279e+00,6.928203299376701096e+00,4.088357425762115249e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232463554014252338e+01,4.389940766230706117e+02,5.583922558618658272e+00,6.928203299376701096e+00,4.071690759095448336e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232607891580110504e+01,4.390040683348829589e+02,5.584329615198560859e+00,6.928203299376701096e+00,4.055024092428781424e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232752229145968670e+01,4.390140601143992853e+02,5.584735006487515641e+00,6.928203299376701096e+00,4.038357425762114511e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.232896566711826836e+01,4.390240519613420247e+02,5.585138732474261403e+00,6.928203299376701096e+00,4.021690759095447598e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233040904277685001e+01,4.390340438754336674e+02,5.585540793147584004e+00,6.928203299376701096e+00,4.005024092428780685e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233185241843543167e+01,4.390440358563966470e+02,5.585941188496314602e+00,6.928203299376701096e+00,3.988357425762113773e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233329579409401333e+01,4.390540279039533971e+02,5.586339918509331426e+00,6.928203299376701096e+00,3.971690759095446860e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233473916975259499e+01,4.390640200178264081e+02,5.586736983175558002e+00,6.928203299376701096e+00,3.955024092428779947e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233618254541117665e+01,4.390740121977380568e+02,5.587132382483965820e+00,6.928203299376701096e+00,3.938357425762113034e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233762592106975831e+01,4.390840044434108336e+02,5.587526116423570777e+00,6.928203299376701096e+00,3.921690759095446122e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.233906929672833996e+01,4.390939967545671152e+02,5.587918184983436731e+00,6.928203299376701096e+00,3.905024092428779209e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234051267238692162e+01,4.391039891309293921e+02,5.588308588152671952e+00,6.928203299376701096e+00,3.888357425762112296e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234195604804550328e+01,4.391139815722200979e+02,5.588697325920431780e+00,6.928203299376701096e+00,3.871690759095445383e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234339942370408494e+01,4.391239740781616092e+02,5.589084398275918630e+00,6.928203299376701096e+00,3.855024092428778471e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234484279936266660e+01,4.391339666484764166e+02,5.589469805208380215e+00,6.928203299376701096e+00,3.838357425762111558e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234628617502124825e+01,4.391439592828869536e+02,5.589853546707111320e+00,6.928203299376701096e+00,3.821690759095444645e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234772955067982991e+01,4.391539519811155969e+02,5.590235622761452028e+00,6.928203299376701096e+00,3.805024092428777732e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.234917292633841157e+01,4.391639447428847802e+02,5.590616033360788606e+00,6.928203299376701096e+00,3.788357425762110819e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235061630199699323e+01,4.391739375679169370e+02,5.590994778494554396e+00,6.928203299376701096e+00,3.771690759095443907e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235205967765557489e+01,4.391839304559345010e+02,5.591371858152228924e+00,6.928203299376701096e+00,3.755024092428776994e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235350305331415655e+01,4.391939234066599056e+02,5.591747272323337903e+00,6.928203299376701096e+00,3.738357425762110081e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235494642897273820e+01,4.392039164198155277e+02,5.592121020997453229e+00,6.928203299376701096e+00,3.721690759095443168e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235638980463131986e+01,4.392139094951238008e+02,5.592493104164192097e+00,6.928203299376701096e+00,3.705024092428776256e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235783318028990152e+01,4.392239026323071585e+02,5.592863521813219663e+00,6.928203299376701096e+00,3.688357425762109343e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.235927655594848318e+01,4.392338958310879775e+02,5.593232273934246379e+00,6.928203299376701096e+00,3.671690759095442430e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236071993160706484e+01,4.392438890911886915e+02,5.593599360517028884e+00,6.928203299376701096e+00,3.655024092428775517e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236216330726564649e+01,4.392538824123317340e+02,5.593964781551370891e+00,6.928203299376701096e+00,3.638357425762108605e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236360668292422815e+01,4.392638757942394818e+02,5.594328537027121406e+00,6.928203299376701096e+00,3.621690759095441692e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236505005858280981e+01,4.392738692366343116e+02,5.594690626934176514e+00,6.928203299376701096e+00,3.605024092428774779e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236649343424139147e+01,4.392838627392386570e+02,5.595051051262477593e+00,6.928203299376701096e+00,3.588357425762107866e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236793680989997313e+01,4.392938563017749516e+02,5.595409810002013096e+00,6.928203299376701096e+00,3.571690759095440953e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.236938018555855479e+01,4.393038499239655721e+02,5.595766903142817661e+00,6.928203299376701096e+00,3.555024092428774041e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237082356121713644e+01,4.393138436055328953e+02,5.596122330674972112e+00,6.928203299376701096e+00,3.538357425762107128e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237226693687571810e+01,4.393238373461993547e+02,5.596476092588602569e+00,6.928203299376701096e+00,3.521690759095440215e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237371031253429976e+01,4.393338311456873271e+02,5.596828188873883114e+00,6.928203299376701096e+00,3.505024092428773302e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237515368819288142e+01,4.393438250037191892e+02,5.597178619521033127e+00,6.928203299376701096e+00,3.488357425762106390e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237659706385146308e+01,4.393538189200173747e+02,5.597527384520318172e+00,6.928203299376701096e+00,3.471690759095439477e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237804043951004473e+01,4.393638128943042602e+02,5.597874483862050887e+00,6.928203299376701096e+00,3.455024092428772564e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.237948381516862639e+01,4.393738069263022226e+02,5.598219917536589207e+00,6.928203299376701096e+00,3.438357425762105651e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238092719082720805e+01,4.393838010157336953e+02,5.598563685534338141e+00,6.928203299376701096e+00,3.421690759095438739e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238237056648578971e+01,4.393937951623209983e+02,5.598905787845747994e+00,6.928203299376701096e+00,3.405024092428771826e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238381394214437137e+01,4.394037893657865652e+02,5.599246224461316146e+00,6.928203299376701096e+00,3.388357425762104913e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238525731780295303e+01,4.394137836258527159e+02,5.599584995371586160e+00,6.928203299376701096e+00,3.371690759095438000e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238670069346153468e+01,4.394237779422418839e+02,5.599922100567147787e+00,6.928203299376701096e+00,3.355024092428771088e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238814406912011634e+01,4.394337723146764461e+02,5.600257540038636961e+00,6.928203299376701096e+00,3.338357425762104175e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.238958744477869800e+01,4.394437667428787790e+02,5.600591313776735802e+00,6.928203299376701096e+00,3.321690759095437262e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239103082043727966e+01,4.394537612265712596e+02,5.600923421772173505e+00,6.928203299376701096e+00,3.305024092428770349e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239247419609586132e+01,4.394637557654762645e+02,5.601253864015723671e+00,6.928203299376701096e+00,3.288357425762103436e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239391757175444297e+01,4.394737503593161705e+02,5.601582640498207866e+00,6.928203299376701096e+00,3.271690759095436524e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239536094741302463e+01,4.394837450078133543e+02,5.601909751210493837e+00,6.928203299376701096e+00,3.255024092428769611e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239680432307160629e+01,4.394937397106901358e+02,5.602235196143494633e+00,6.928203299376701096e+00,3.238357425762102698e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239824769873018795e+01,4.395037344676689486e+02,5.602558975288170373e+00,6.928203299376701096e+00,3.221690759095435785e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.239969107438876961e+01,4.395137292784721126e+02,5.602881088635527362e+00,6.928203299376701096e+00,3.205024092428768873e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240113445004735127e+01,4.395237241428220614e+02,5.603201536176617203e+00,6.928203299376701096e+00,3.188357425762101960e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240257782570593292e+01,4.395337190604411148e+02,5.603520317902539460e+00,6.928203299376701096e+00,3.171690759095435047e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240402120136451458e+01,4.395437140310515929e+02,5.603837433804438994e+00,6.928203299376701096e+00,3.155024092428768134e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240546457702309624e+01,4.395537090543759291e+02,5.604152883873505964e+00,6.928203299376701096e+00,3.138357425762101222e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240690795268167790e+01,4.395637041301364434e+02,5.604466668100979376e+00,6.928203299376701096e+00,3.121690759095434656e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240835132834025956e+01,4.395736992580555125e+02,5.604778786478141761e+00,6.928203299376701096e+00,3.105024092428768090e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.240979470399884121e+01,4.395836944378555131e+02,5.605089238996323608e+00,6.928203299376701096e+00,3.088357425762101524e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241123807965742287e+01,4.395936896692587652e+02,5.605398025646901594e+00,6.928203299376701096e+00,3.071690759095434958e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241268145531600453e+01,4.396036849519876455e+02,5.605705146421298579e+00,6.928203299376701096e+00,3.055024092428768392e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241412483097458619e+01,4.396136802857644739e+02,5.606010601310982722e+00,6.928203299376701096e+00,3.038357425762101827e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241556820663316785e+01,4.396236756703116271e+02,5.606314390307469253e+00,6.928203299376701096e+00,3.021690759095435261e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241701158229174951e+01,4.396336711053514819e+02,5.606616513402319590e+00,6.928203299376701096e+00,3.005024092428768695e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241845495795033116e+01,4.396436665906063581e+02,5.606916970587141336e+00,6.928203299376701096e+00,2.988357425762102129e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.241989833360891282e+01,4.396536621257985757e+02,5.607215761853589164e+00,6.928203299376701096e+00,2.971690759095435563e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.242134170926749448e+01,4.396636577106505115e+02,5.607512887193362161e+00,6.928203299376701096e+00,2.955024092428768998e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.242278508492607614e+01,4.396736533448845421e+02,5.607808346598207372e+00,6.928203299376701096e+00,2.938357425762102432e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.242422846058465780e+01,4.396836490282229306e+02,5.608102140059918028e+00,6.928203299376701096e+00,2.921690759095435866e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.242567183624323945e+01,4.396936447603881106e+02,5.608394267570332659e+00,6.928203299376701096e+00,2.905024092428769300e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.242711521190182111e+01,4.397036405411023452e+02,5.608684729121336865e+00,6.928203299376701096e+00,2.888357425762102734e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.242855858756040277e+01,4.397136363700880111e+02,5.608973524704862434e+00,6.928203299376701096e+00,2.871690759095436168e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243000196321898443e+01,4.397236322470674281e+02,5.609260654312887340e+00,6.928203299376701096e+00,2.855024092428769603e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243144533887756609e+01,4.397336281717629731e+02,5.609546117937434850e+00,6.928203299376701096e+00,2.838357425762103037e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243288871453614775e+01,4.397436241438969660e+02,5.609829915570576198e+00,6.928203299376701096e+00,2.821690759095436471e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243433209019472940e+01,4.397536201631917265e+02,5.610112047204427910e+00,6.928203299376701096e+00,2.805024092428769905e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243577546585331106e+01,4.397636162293695747e+02,5.610392512831153589e+00,6.928203299376701096e+00,2.788357425762103339e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243721884151189272e+01,4.397736123421528873e+02,5.610671312442961245e+00,6.928203299376701096e+00,2.771690759095436773e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.243866221717047438e+01,4.397836085012639273e+02,5.610948446032107739e+00,6.928203299376701096e+00,2.755024092428770208e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244010559282905604e+01,4.397936047064250715e+02,5.611223913590894341e+00,6.928203299376701096e+00,2.738357425762103642e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244154896848763769e+01,4.398036009573586398e+02,5.611497715111669393e+00,6.928203299376701096e+00,2.721690759095437076e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244299234414621935e+01,4.398135972537869520e+02,5.611769850586826536e+00,6.928203299376701096e+00,2.705024092428770510e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244443571980480101e+01,4.398235935954323850e+02,5.612040320008807370e+00,6.928203299376701096e+00,2.688357425762103944e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244587909546338267e+01,4.398335899820172017e+02,5.612309123370097907e+00,6.928203299376701096e+00,2.671690759095437379e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244732247112196433e+01,4.398435864132637221e+02,5.612576260663232119e+00,6.928203299376701096e+00,2.655024092428770813e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.244876584678054598e+01,4.398535828888943229e+02,5.612841731880789276e+00,6.928203299376701096e+00,2.638357425762104247e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245020922243912764e+01,4.398635794086312671e+02,5.613105537015395718e+00,6.928203299376701096e+00,2.621690759095437681e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245165259809770930e+01,4.398735759721968748e+02,5.613367676059723088e+00,6.928203299376701096e+00,2.605024092428771115e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245309597375629096e+01,4.398835725793134657e+02,5.613628149006490098e+00,6.928203299376701096e+00,2.588357425762104549e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245453934941487262e+01,4.398935692297034166e+02,5.613886955848460758e+00,6.928203299376701096e+00,2.571690759095437984e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245598272507345428e+01,4.399035659230889905e+02,5.614144096578446153e+00,6.928203299376701096e+00,2.555024092428771418e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245742610073203593e+01,4.399135626591925075e+02,5.614399571189303551e+00,6.928203299376701096e+00,2.538357425762104852e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.245886947639061759e+01,4.399235594377362872e+02,5.614653379673936406e+00,6.928203299376701096e+00,2.521690759095438286e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246031285204919925e+01,4.399335562584426498e+02,5.614905522025294360e+00,6.928203299376701096e+00,2.505024092428771720e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246175622770778091e+01,4.399435531210338581e+02,5.615155998236374124e+00,6.928203299376701096e+00,2.488357425762105155e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246319960336636257e+01,4.399535500252322890e+02,5.615404808300217709e+00,6.928203299376701096e+00,2.471690759095438589e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246464297902494422e+01,4.399635469707602056e+02,5.615651952209913311e+00,6.928203299376701096e+00,2.455024092428772023e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246608635468352588e+01,4.399735439573399276e+02,5.615897429958596199e+00,6.928203299376701096e+00,2.438357425762105457e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246752973034210754e+01,4.399835409846937750e+02,5.616141241539446938e+00,6.928203299376701096e+00,2.421690759095438891e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.246897310600068920e+01,4.399935380525440110e+02,5.616383386945694056e+00,6.928203299376701096e+00,2.405024092428772325e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247041648165927086e+01,4.400035351606129552e+02,5.616623866170610491e+00,6.928203299376701096e+00,2.388357425762105760e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247185985731785252e+01,4.400135323086229278e+02,5.616862679207516251e+00,6.928203299376701096e+00,2.371690759095439194e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247330323297643417e+01,4.400235294962962485e+02,5.617099826049778422e+00,6.928203299376701096e+00,2.355024092428772628e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247474660863501583e+01,4.400335267233551804e+02,5.617335306690808494e+00,6.928203299376701096e+00,2.338357425762106062e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247618998429359749e+01,4.400435239895220434e+02,5.617569121124065923e+00,6.928203299376701096e+00,2.321690759095439496e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247763335995217915e+01,4.400535212945191006e+02,5.617801269343056347e+00,6.928203299376701096e+00,2.305024092428772930e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.247907673561076081e+01,4.400635186380686719e+02,5.618031751341330704e+00,6.928203299376701096e+00,2.288357425762106365e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248052011126934246e+01,4.400735160198930771e+02,5.618260567112486115e+00,6.928203299376701096e+00,2.271690759095439799e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248196348692792412e+01,4.400835134397145794e+02,5.618487716650167663e+00,6.928203299376701096e+00,2.255024092428773233e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248340686258650578e+01,4.400935108972554985e+02,5.618713199948064840e+00,6.928203299376701096e+00,2.238357425762106667e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248485023824508744e+01,4.401035083922380977e+02,5.618937016999914213e+00,6.928203299376701096e+00,2.221690759095440101e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248629361390366910e+01,4.401135059243846968e+02,5.619159167799499421e+00,6.928203299376701096e+00,2.205024092428773536e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248773698956225076e+01,4.401235034934175587e+02,5.619379652340649400e+00,6.928203299376701096e+00,2.188357425762106970e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.248918036522083241e+01,4.401335010990590035e+02,5.619598470617239272e+00,6.928203299376701096e+00,2.171690759095440404e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249062374087941407e+01,4.401434987410312942e+02,5.619815622623190343e+00,6.928203299376701096e+00,2.155024092428773838e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249206711653799573e+01,4.401534964190567507e+02,5.620031108352470994e+00,6.928203299376701096e+00,2.138357425762107272e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249351049219657739e+01,4.401634941328576360e+02,5.620244927799095791e+00,6.928203299376701096e+00,2.121690759095440706e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249495386785515905e+01,4.401734918821562133e+02,5.620457080957125484e+00,6.928203299376701096e+00,2.105024092428774141e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249639724351374070e+01,4.401834896666748023e+02,5.620667567820666122e+00,6.928203299376701096e+00,2.088357425762107575e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249784061917232236e+01,4.401934874861356661e+02,5.620876388383871713e+00,6.928203299376701096e+00,2.071690759095441009e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.249928399483090402e+01,4.402034853402611247e+02,5.621083542640940678e+00,6.928203299376701096e+00,2.055024092428774443e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250072737048948568e+01,4.402134832287734412e+02,5.621289030586119395e+00,6.928203299376701096e+00,2.038357425762107877e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250217074614806734e+01,4.402234811513948785e+02,5.621492852213700431e+00,6.928203299376701096e+00,2.021690759095441312e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250361412180664900e+01,4.402334791078476997e+02,5.621695007518020759e+00,6.928203299376701096e+00,2.005024092428774746e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250505749746523065e+01,4.402434770978542247e+02,5.621895496493466204e+00,6.928203299376701096e+00,1.988357425762108180e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250650087312381231e+01,4.402534751211367166e+02,5.622094319134467000e+00,6.928203299376701096e+00,1.971690759095441614e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250794424878239397e+01,4.402634731774174384e+02,5.622291475435500452e+00,6.928203299376701096e+00,1.955024092428775048e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.250938762444097563e+01,4.402734712664187100e+02,5.622486965391089164e+00,6.928203299376701096e+00,1.938357425762108482e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251083100009955729e+01,4.402834693878627945e+02,5.622680788995803702e+00,6.928203299376701096e+00,1.921690759095441917e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251227437575813894e+01,4.402934675414719550e+02,5.622872946244259929e+00,6.928203299376701096e+00,1.905024092428775351e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251371775141672060e+01,4.403034657269684544e+02,5.623063437131120779e+00,6.928203299376701096e+00,1.888357425762108785e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251516112707530226e+01,4.403134639440745559e+02,5.623252261651093598e+00,6.928203299376701096e+00,1.871690759095442219e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251660450273388392e+01,4.403234621925125225e+02,5.623439419798933692e+00,6.928203299376701096e+00,1.855024092428775653e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251804787839246558e+01,4.403334604720046741e+02,5.623624911569442553e+00,6.928203299376701096e+00,1.838357425762109087e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.251949125405104724e+01,4.403434587822732738e+02,5.623808736957467858e+00,6.928203299376701096e+00,1.821690759095442522e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252093462970962889e+01,4.403534571230405277e+02,5.623990895957902580e+00,6.928203299376701096e+00,1.805024092428775956e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252237800536821055e+01,4.403634554940287558e+02,5.624171388565687657e+00,6.928203299376701096e+00,1.788357425762109390e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252382138102679221e+01,4.403734538949602211e+02,5.624350214775808432e+00,6.928203299376701096e+00,1.771690759095442824e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252526475668537387e+01,4.403834523255571867e+02,5.624527374583298212e+00,6.928203299376701096e+00,1.755024092428776258e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252670813234395553e+01,4.403934507855419156e+02,5.624702867983235599e+00,6.928203299376701096e+00,1.738357425762109693e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252815150800253718e+01,4.404034492746366709e+02,5.624876694970746271e+00,6.928203299376701096e+00,1.721690759095443127e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.252959488366111884e+01,4.404134477925637725e+02,5.625048855541001203e+00,6.928203299376701096e+00,1.705024092428776561e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253103825931970050e+01,4.404234463390454266e+02,5.625219349689217552e+00,6.928203299376701096e+00,1.688357425762109995e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253248163497828216e+01,4.404334449138038963e+02,5.625388177410660440e+00,6.928203299376701096e+00,1.671690759095443429e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253392501063686382e+01,4.404434435165614445e+02,5.625555338700639396e+00,6.928203299376701096e+00,1.655024092428776863e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253536838629544548e+01,4.404534421470403345e+02,5.625720833554511913e+00,6.928203299376701096e+00,1.638357425762110298e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253681176195402713e+01,4.404634408049628291e+02,5.625884661967680778e+00,6.928203299376701096e+00,1.621690759095443732e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253825513761260879e+01,4.404734394900511916e+02,5.626046823935594077e+00,6.928203299376701096e+00,1.605024092428777166e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.253969851327119045e+01,4.404834382020276848e+02,5.626207319453748745e+00,6.928203299376701096e+00,1.588357425762110600e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254114188892977211e+01,4.404934369406145720e+02,5.626366148517686128e+00,6.928203299376701096e+00,1.571690759095444034e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254258526458835377e+01,4.405034357055340593e+02,5.626523311122993753e+00,6.928203299376701096e+00,1.555024092428777295e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254402864024693542e+01,4.405134344965084665e+02,5.626678807265306226e+00,6.928203299376701096e+00,1.538357425762110556e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254547201590551708e+01,4.405234333132600000e+02,5.626832636940304333e+00,6.928203299376701096e+00,1.521690759095443816e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254691539156409874e+01,4.405334321555109796e+02,5.626984800143715049e+00,6.928203299376701096e+00,1.505024092428777077e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254835876722268040e+01,4.405434310229836115e+02,5.627135296871311532e+00,6.928203299376701096e+00,1.488357425762110338e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.254980214288126206e+01,4.405534299154001587e+02,5.627284127118914014e+00,6.928203299376701096e+00,1.471690759095443599e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255124551853984372e+01,4.405634288324828844e+02,5.627431290882387138e+00,6.928203299376701096e+00,1.455024092428776859e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255268889419842537e+01,4.405734277739539948e+02,5.627576788157643506e+00,6.928203299376701096e+00,1.438357425762110120e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255413226985700703e+01,4.405834267395358097e+02,5.627720618940641906e+00,6.928203299376701096e+00,1.421690759095443381e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255557564551558869e+01,4.405934257289505354e+02,5.627862783227386423e+00,6.928203299376701096e+00,1.405024092428776641e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255701902117417035e+01,4.406034247419204348e+02,5.628003281013928216e+00,6.928203299376701096e+00,1.388357425762109902e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255846239683275201e+01,4.406134237781677712e+02,5.628142112296365518e+00,6.928203299376701096e+00,1.371690759095443163e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.255990577249133366e+01,4.406234228374147506e+02,5.628279277070840969e+00,6.928203299376701096e+00,1.355024092428776424e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.256134914814991532e+01,4.406334219193836361e+02,5.628414775333544284e+00,6.928203299376701096e+00,1.338357425762109684e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.256279252380849698e+01,4.406434210237966909e+02,5.628548607080712252e+00,6.928203299376701096e+00,1.321690759095442945e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.256423589946707864e+01,4.406534201503761778e+02,5.628680772308626956e+00,6.928203299376701096e+00,1.305024092428776206e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.256567927512566030e+01,4.406634192988443033e+02,5.628811271013616668e+00,6.928203299376701096e+00,1.288357425762109466e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.256712265078424196e+01,4.406734184689233302e+02,5.628940103192056732e+00,6.928203299376701096e+00,1.271690759095442727e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.256856602644282361e+01,4.406834176603355218e+02,5.629067268840368676e+00,6.928203299376701096e+00,1.255024092428775988e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257000940210140527e+01,4.406934168728031409e+02,5.629192767955020216e+00,6.928203299376701096e+00,1.238357425762109248e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257145277775998693e+01,4.407034161060483939e+02,5.629316600532525250e+00,6.928203299376701096e+00,1.221690759095442509e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257289615341856859e+01,4.407134153597935438e+02,5.629438766569443864e+00,6.928203299376701096e+00,1.205024092428775770e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257433952907715025e+01,4.407234146337607967e+02,5.629559266062383216e+00,6.928203299376701096e+00,1.188357425762109031e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257578290473573190e+01,4.407334139276724159e+02,5.629678099007994874e+00,6.928203299376701096e+00,1.171690759095442291e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257722628039431356e+01,4.407434132412506642e+02,5.629795265402978366e+00,6.928203299376701096e+00,1.155024092428775552e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.257866965605289522e+01,4.407534125742177480e+02,5.629910765244079407e+00,6.928203299376701096e+00,1.138357425762108813e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258011303171147688e+01,4.407634119262959302e+02,5.630024598528089896e+00,6.928203299376701096e+00,1.121690759095442073e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258155640737005854e+01,4.407734112972074740e+02,5.630136765251847031e+00,6.928203299376701096e+00,1.105024092428775334e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258299978302864019e+01,4.407834106866745856e+02,5.630247265412235080e+00,6.928203299376701096e+00,1.088357425762108595e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258444315868722185e+01,4.407934100944194711e+02,5.630356099006185389e+00,6.928203299376701096e+00,1.071690759095441856e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258588653434580351e+01,4.408034095201644504e+02,5.630463266030674596e+00,6.928203299376701096e+00,1.055024092428775116e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258732991000438517e+01,4.408134089636316730e+02,5.630568766482725529e+00,6.928203299376701096e+00,1.038357425762108377e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.258877328566296683e+01,4.408234084245434588e+02,5.630672600359407198e+00,6.928203299376701096e+00,1.021690759095441638e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259021666132154849e+01,4.408334079026220138e+02,5.630774767657835689e+00,6.928203299376701096e+00,1.005024092428774898e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259166003698013014e+01,4.408434073975895444e+02,5.630875268375173270e+00,6.928203299376701096e+00,9.883574257621081591e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259310341263871180e+01,4.408534069091683136e+02,5.630974102508628398e+00,6.928203299376701096e+00,9.716907590954414198e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259454678829729346e+01,4.408634064370805845e+02,5.631071270055455713e+00,6.928203299376701096e+00,9.550240924287746805e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259599016395587512e+01,4.408734059810485633e+02,5.631166771012955152e+00,6.928203299376701096e+00,9.383574257621079412e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259743353961445678e+01,4.408834055407944561e+02,5.631260605378474615e+00,6.928203299376701096e+00,9.216907590954412019e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.259887691527303843e+01,4.408934051160405261e+02,5.631352773149408186e+00,6.928203299376701096e+00,9.050240924287744626e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260032029093162009e+01,4.409034047065090363e+02,5.631443274323194359e+00,6.928203299376701096e+00,8.883574257621077233e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260176366659020175e+01,4.409134043119221928e+02,5.631532108897320477e+00,6.928203299376701096e+00,8.716907590954409840e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260320704224878341e+01,4.409234039320022021e+02,5.631619276869318291e+00,6.928203299376701096e+00,8.550240924287742447e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260465041790736507e+01,4.409334035664713269e+02,5.631704778236766629e+00,6.928203299376701096e+00,8.383574257621075054e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260609379356594673e+01,4.409434032150517737e+02,5.631788612997289611e+00,6.928203299376701096e+00,8.216907590954407661e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260753716922452838e+01,4.409534028774658054e+02,5.631870781148559324e+00,6.928203299376701096e+00,8.050240924287740268e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.260898054488311004e+01,4.409634025534356851e+02,5.631951282688293148e+00,6.928203299376701096e+00,7.883574257621072875e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261042392054169170e+01,4.409734022426835622e+02,5.632030117614255538e+00,6.928203299376701096e+00,7.716907590954406350e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261186729620027336e+01,4.409834019449316997e+02,5.632107285924255358e+00,6.928203299376701096e+00,7.550240924287739824e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261331067185885502e+01,4.409934016599023607e+02,5.632182787616150321e+00,6.928203299376701096e+00,7.383574257621073299e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261475404751743667e+01,4.410034013873177514e+02,5.632256622687842551e+00,6.928203299376701096e+00,7.216907590954406773e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261619742317601833e+01,4.410134011269000780e+02,5.632328791137281243e+00,6.928203299376701096e+00,7.050240924287740248e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261764079883459999e+01,4.410234008783716035e+02,5.632399292962460891e+00,6.928203299376701096e+00,6.883574257621073722e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.261908417449318165e+01,4.410334006414545911e+02,5.632468128161423948e+00,6.928203299376701096e+00,6.716907590954407196e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262052755015176331e+01,4.410434004158711900e+02,5.632535296732258168e+00,6.928203299376701096e+00,6.550240924287740671e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262197092581034497e+01,4.410534002013436634e+02,5.632600798673098375e+00,6.928203299376701096e+00,6.383574257621074145e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262341430146892662e+01,4.410633999975942743e+02,5.632664633982123803e+00,6.928203299376701096e+00,6.216907590954407620e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262485767712750828e+01,4.410733998043451720e+02,5.632726802657562537e+00,6.928203299376701096e+00,6.050240924287741094e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262630105278608994e+01,4.410833996213186765e+02,5.632787304697687070e+00,6.928203299376701096e+00,5.883574257621074569e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262774442844467160e+01,4.410933994482369371e+02,5.632846140100816079e+00,6.928203299376701096e+00,5.716907590954408043e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.262918780410325326e+01,4.411033992848222169e+02,5.632903308865316205e+00,6.928203299376701096e+00,5.550240924287741517e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263063117976183491e+01,4.411133991307967221e+02,5.632958810989599385e+00,6.928203299376701096e+00,5.383574257621074992e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263207455542041657e+01,4.411233989858827158e+02,5.633012646472123741e+00,6.928203299376701096e+00,5.216907590954408466e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263351793107899823e+01,4.411333988498024041e+02,5.633064815311393581e+00,6.928203299376701096e+00,5.050240924287741941e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263496130673757989e+01,4.411433987222779933e+02,5.633115317505960284e+00,6.928203299376701096e+00,4.883574257621075415e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263640468239616155e+01,4.411533986030317465e+02,5.633164153054420531e+00,6.928203299376701096e+00,4.716907590954408890e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263784805805474321e+01,4.411633984917858697e+02,5.633211321955418072e+00,6.928203299376701096e+00,4.550240924287742364e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.263929143371332486e+01,4.411733983882625694e+02,5.633256824207641955e+00,6.928203299376701096e+00,4.383574257621075838e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264073480937190652e+01,4.411833982921841084e+02,5.633300659809829192e+00,6.928203299376701096e+00,4.216907590954409313e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264217818503048818e+01,4.411933982032726931e+02,5.633342828760761201e+00,6.928203299376701096e+00,4.050240924287742787e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264362156068906984e+01,4.412033981212505296e+02,5.633383331059267363e+00,6.928203299376701096e+00,3.883574257621076262e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264506493634765150e+01,4.412133980458398810e+02,5.633422166704222356e+00,6.928203299376701096e+00,3.716907590954409736e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264650831200623315e+01,4.412233979767629535e+02,5.633459335694547931e+00,6.928203299376701096e+00,3.550240924287743211e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264795168766481481e+01,4.412333979137419533e+02,5.633494838029211138e+00,6.928203299376701096e+00,3.383574257621076685e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.264939506332339647e+01,4.412433978564991435e+02,5.633528673707225209e+00,6.928203299376701096e+00,3.216907590954410159e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265083843898197813e+01,4.412533978047567302e+02,5.633560842727651341e+00,6.928203299376701096e+00,3.050240924287743634e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265228181464055979e+01,4.412633977582369198e+02,5.633591345089595137e+00,6.928203299376701096e+00,2.883574257621077108e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265372519029914145e+01,4.412733977166619184e+02,5.633620180792210164e+00,6.928203299376701096e+00,2.716907590954410583e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265516856595772310e+01,4.412833976797539890e+02,5.633647349834694396e+00,6.928203299376701096e+00,2.550240924287744057e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265661194161630476e+01,4.412933976472353379e+02,5.633672852216293769e+00,6.928203299376701096e+00,2.383574257621077531e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265805531727488642e+01,4.413033976188282281e+02,5.633696687936299519e+00,6.928203299376701096e+00,2.216907590954411006e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.265949869293346808e+01,4.413133975942548659e+02,5.633718856994049951e+00,6.928203299376701096e+00,2.050240924287744480e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266094206859204974e+01,4.413233975732374574e+02,5.633739359388929557e+00,6.928203299376701096e+00,1.883574257621077738e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266238544425063139e+01,4.413333975554982089e+02,5.633758195120368129e+00,6.928203299376701096e+00,1.716907590954410995e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266382881990921305e+01,4.413433975407593266e+02,5.633775364187842527e+00,6.928203299376701096e+00,1.550240924287744253e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266527219556779471e+01,4.413533975287430735e+02,5.633790866590875801e+00,6.928203299376701096e+00,1.383574257621077511e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266671557122637637e+01,4.413633975191717127e+02,5.633804702329038072e+00,6.928203299376701096e+00,1.216907590954410768e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266815894688495803e+01,4.413733975117673936e+02,5.633816871401943871e+00,6.928203299376701096e+00,1.050240924287744026e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.266960232254353969e+01,4.413833975062523791e+02,5.633827373809255690e+00,6.928203299376701096e+00,8.835742576210773918e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267104569820212134e+01,4.413933975023488756e+02,5.633836209550682206e+00,6.928203299376701096e+00,7.169075909544107578e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267248907386070300e+01,4.414033974997790892e+02,5.633843378625977394e+00,6.928203299376701096e+00,5.502409242877441238e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267393244951928466e+01,4.414133974982652830e+02,5.633848881034942302e+00,6.928203299376701096e+00,3.835742576210774898e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267537582517786632e+01,4.414233974975296633e+02,5.633852716777424163e+00,6.928203299376701096e+00,2.169075909544108287e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267681920083644798e+01,4.414333974972944361e+02,5.633854885853316397e+00,6.928203299376701096e+00,5.024092428774416764e-05,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267826257649502963e+01,4.414433974972818078e+02,5.633855388262559494e+00,6.928203299376701096e+00,-1.164257423789224935e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.267970595215361129e+01,4.414533974972140413e+02,5.633854224005138356e+00,6.928203299376701096e+00,-2.830924090455891546e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268114932781219295e+01,4.414633974968133430e+02,5.633851393081085845e+00,6.928203299376701096e+00,-4.497590757122557886e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268259270347077461e+01,4.414733974958019189e+02,5.633846895490480122e+00,6.928203299376701096e+00,-6.164257423789224226e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268403607912935627e+01,4.414833974939020322e+02,5.633840731233446419e+00,6.928203299376701096e+00,-7.830924090455890565e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268547945478793793e+01,4.414933974908358891e+02,5.633832900310156155e+00,6.928203299376701096e+00,-9.497590757122556905e-04,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268692283044651958e+01,4.415033974863256958e+02,5.633823402720826934e+00,6.928203299376701096e+00,-1.116425742378922325e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268836620610510124e+01,4.415133974800936585e+02,5.633812238465722544e+00,6.928203299376701096e+00,-1.283092409045589067e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.268980958176368290e+01,4.415233974718620402e+02,5.633799407545152960e+00,6.928203299376701096e+00,-1.449759075712255809e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269125295742226456e+01,4.415333974613530472e+02,5.633784909959474341e+00,6.928203299376701096e+00,-1.616425742378922552e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269269633308084622e+01,4.415433974482888857e+02,5.633768745709089920e+00,6.928203299376701096e+00,-1.783092409045589294e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269413970873942787e+01,4.415533974323918187e+02,5.633750914794448228e+00,6.928203299376701096e+00,-1.949759075712256037e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269558308439800953e+01,4.415633974133839956e+02,5.633731417216044868e+00,6.928203299376701096e+00,-2.116425742378922562e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269702646005659119e+01,4.415733973909877363e+02,5.633710252974420740e+00,6.928203299376701096e+00,-2.283092409045589088e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269846983571517285e+01,4.415833973649251902e+02,5.633687422070164708e+00,6.928203299376701096e+00,-2.449759075712255613e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.269991321137375451e+01,4.415933973349186203e+02,5.633662924503910929e+00,6.928203299376701096e+00,-2.616425742378922139e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.270135658703233617e+01,4.416033973006902329e+02,5.633636760276338862e+00,6.928203299376701096e+00,-2.783092409045588665e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.270279996269091782e+01,4.416133972619622341e+02,5.633608929388175923e+00,6.928203299376701096e+00,-2.949759075712255190e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.270424333834949948e+01,4.416233972184568870e+02,5.633579431840195717e+00,6.928203299376701096e+00,-3.116425742378921716e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.270568671400808114e+01,4.416333971698963978e+02,5.633548267633217144e+00,6.928203299376701096e+00,-3.283092409045588241e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.270713008966666280e+01,4.416433971160029728e+02,5.633515436768106177e+00,6.928203299376701096e+00,-3.449759075712254767e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.270857346532524446e+01,4.416533970564988181e+02,5.633480939245774088e+00,6.928203299376701096e+00,-3.616425742378921292e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271001684098382611e+01,4.416633969911061968e+02,5.633444775067179222e+00,6.928203299376701096e+00,-3.783092409045587818e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271146021664240777e+01,4.416733969195473151e+02,5.633406944233326996e+00,6.928203299376701096e+00,-3.949759075712254777e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271290359230098943e+01,4.416833968415444360e+02,5.633367446745267237e+00,6.928203299376701096e+00,-4.116425742378921303e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271434696795957109e+01,4.416933967568197659e+02,5.633326282604097734e+00,6.928203299376701096e+00,-4.283092409045587828e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271579034361815275e+01,4.417033966650955108e+02,5.633283451810961573e+00,6.928203299376701096e+00,-4.449759075712254354e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271723371927673440e+01,4.417133965660938770e+02,5.633238954367048912e+00,6.928203299376701096e+00,-4.616425742378920880e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.271867709493531606e+01,4.417233964595371276e+02,5.633192790273596096e+00,6.928203299376701096e+00,-4.783092409045587405e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272012047059389772e+01,4.417333963451474688e+02,5.633144959531884766e+00,6.928203299376701096e+00,-4.949759075712253931e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272156384625247938e+01,4.417433962226471635e+02,5.633095462143243637e+00,6.928203299376701096e+00,-5.116425742378920456e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272300722191106104e+01,4.417533960917583613e+02,5.633044298109047610e+00,6.928203299376701096e+00,-5.283092409045586982e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272445059756964270e+01,4.417633959522033820e+02,5.632991467430717769e+00,6.928203299376701096e+00,-5.449759075712253507e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272589397322822435e+01,4.417733958037043749e+02,5.632936970109722274e+00,6.928203299376701096e+00,-5.616425742378920033e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272733734888680601e+01,4.417833956459836031e+02,5.632880806147574582e+00,6.928203299376701096e+00,-5.783092409045586559e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.272878072454538767e+01,4.417933954787632729e+02,5.632822975545834332e+00,6.928203299376701096e+00,-5.949759075712253084e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273022410020396933e+01,4.418033953017656472e+02,5.632763478306109128e+00,6.928203299376701096e+00,-6.116425742378919610e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273166747586255099e+01,4.418133951147129324e+02,5.632702314430050095e+00,6.928203299376701096e+00,-6.283092409045586135e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273311085152113264e+01,4.418233949173273345e+02,5.632639483919357204e+00,6.928203299376701096e+00,-6.449759075712252661e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273455422717971430e+01,4.418333947093311167e+02,5.632574986775775727e+00,6.928203299376701096e+00,-6.616425742378919186e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273599760283829596e+01,4.418433944904464852e+02,5.632508823001097120e+00,6.928203299376701096e+00,-6.783092409045585712e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273744097849687762e+01,4.418533942603956461e+02,5.632440992597159912e+00,6.928203299376701096e+00,-6.949759075712252238e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.273888435415545928e+01,4.418633940189008626e+02,5.632371495565847042e+00,6.928203299376701096e+00,-7.116425742378918763e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274032772981404094e+01,4.418733937656843409e+02,5.632300331909089408e+00,6.928203299376701096e+00,-7.283092409045585289e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274177110547262259e+01,4.418833935004683440e+02,5.632227501628864097e+00,6.928203299376701096e+00,-7.449759075712251814e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274321448113120425e+01,4.418933932229750781e+02,5.632153004727194379e+00,6.928203299376701096e+00,-7.616425742378918340e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274465785678978591e+01,4.419033929329267494e+02,5.632076841206148821e+00,6.928203299376701096e+00,-7.783092409045584865e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274610123244836757e+01,4.419133926300456210e+02,5.631999011067843952e+00,6.928203299376701096e+00,-7.949759075712251391e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274754460810694923e+01,4.419233923140539559e+02,5.631919514314441599e+00,6.928203299376701096e+00,-8.116425742378918784e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.274898798376553088e+01,4.419333919846739036e+02,5.631838350948148886e+00,6.928203299376701096e+00,-8.283092409045586177e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275043135942411254e+01,4.419433916416277839e+02,5.631755520971221785e+00,6.928203299376701096e+00,-8.449759075712253570e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275187473508269420e+01,4.419533912846377461e+02,5.631671024385960678e+00,6.928203299376701096e+00,-8.616425742378920963e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275331811074127586e+01,4.419633909134260534e+02,5.631584861194712133e+00,6.928203299376701096e+00,-8.783092409045588356e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275476148639985752e+01,4.419733905277149688e+02,5.631497031399869790e+00,6.928203299376701096e+00,-8.949759075712255749e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275620486205843918e+01,4.419833901272266985e+02,5.631407535003873477e+00,6.928203299376701096e+00,-9.116425742378923142e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275764823771702083e+01,4.419933897116835055e+02,5.631316372009209203e+00,6.928203299376701096e+00,-9.283092409045590535e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.275909161337560249e+01,4.420033892808075962e+02,5.631223542418409167e+00,6.928203299376701096e+00,-9.449759075712257927e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276053498903418415e+01,4.420133888343211765e+02,5.631129046234052637e+00,6.928203299376701096e+00,-9.616425742378925320e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276197836469276581e+01,4.420233883719465098e+02,5.631032883458764182e+00,6.928203299376701096e+00,-9.783092409045592713e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276342174035134747e+01,4.420333878934058589e+02,5.630935054095214554e+00,6.928203299376701096e+00,-9.949759075712260106e-03,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276486511600992912e+01,4.420433873984214301e+02,5.630835558146121578e+00,6.928203299376701096e+00,-1.011642574237892750e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276630849166851078e+01,4.420533868867154297e+02,5.630734395614249266e+00,6.928203299376701096e+00,-1.028309240904559489e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276775186732709244e+01,4.420633863580101206e+02,5.630631566502406926e+00,6.928203299376701096e+00,-1.044975907571226229e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.276919524298567410e+01,4.420733858120277660e+02,5.630527070813451829e+00,6.928203299376701096e+00,-1.061642574237892968e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277063861864425576e+01,4.420833852484905719e+02,5.630420908550285652e+00,6.928203299376701096e+00,-1.078309240904559707e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277208199430283742e+01,4.420933846671208016e+02,5.630313079715858038e+00,6.928203299376701096e+00,-1.094975907571226446e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277352536996141907e+01,4.421033840676406612e+02,5.630203584313163923e+00,6.928203299376701096e+00,-1.111642574237893186e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277496874562000073e+01,4.421133834497724138e+02,5.630092422345245318e+00,6.928203299376701096e+00,-1.128309240904559925e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277641212127858239e+01,4.421233828132383223e+02,5.629979593815189531e+00,6.928203299376701096e+00,-1.144975907571226664e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277785549693716405e+01,4.421333821577605931e+02,5.629865098726130945e+00,6.928203299376701096e+00,-1.161642574237893404e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.277929887259574571e+01,4.421433814830614324e+02,5.629748937081250126e+00,6.928203299376701096e+00,-1.178309240904560143e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278074224825432736e+01,4.421533807888631031e+02,5.629631108883772939e+00,6.928203299376701096e+00,-1.194975907571226882e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278218562391290902e+01,4.421633800748878684e+02,5.629511614136973208e+00,6.928203299376701096e+00,-1.211642574237893621e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278362899957149068e+01,4.421733793408579913e+02,5.629390452844170056e+00,6.928203299376701096e+00,-1.228309240904560361e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278507237523007234e+01,4.421833785864956781e+02,5.629267625008728793e+00,6.928203299376701096e+00,-1.244975907571227100e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278651575088865400e+01,4.421933778115231917e+02,5.629143130634061798e+00,6.928203299376701096e+00,-1.261642574237893839e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278795912654723566e+01,4.422033770156627384e+02,5.629016969723626751e+00,6.928203299376701096e+00,-1.278309240904560579e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.278940250220581731e+01,4.422133761986365812e+02,5.628889142280928404e+00,6.928203299376701096e+00,-1.294975907571227318e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279084587786439897e+01,4.422233753601669832e+02,5.628759648309517694e+00,6.928203299376701096e+00,-1.311642574237894057e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279228925352298063e+01,4.422333744999762075e+02,5.628628487812991743e+00,6.928203299376701096e+00,-1.328309240904560797e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279373262918156229e+01,4.422433736177864603e+02,5.628495660794993860e+00,6.928203299376701096e+00,-1.344975907571227536e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279517600484014395e+01,4.422533727133200046e+02,5.628361167259213538e+00,6.928203299376701096e+00,-1.361642574237894275e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279661938049872560e+01,4.422633717862991034e+02,5.628225007209386455e+00,6.928203299376701096e+00,-1.378309240904561014e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279806275615730726e+01,4.422733708364459631e+02,5.628087180649294474e+00,6.928203299376701096e+00,-1.394975907571227754e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.279950613181588892e+01,4.422833698634828465e+02,5.627947687582767422e+00,6.928203299376701096e+00,-1.411642574237894493e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280094950747447058e+01,4.422933688671320169e+02,5.627806528013678644e+00,6.928203299376701096e+00,-1.428309240904561232e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280239288313305224e+01,4.423033678471157373e+02,5.627663701945950336e+00,6.928203299376701096e+00,-1.444975907571227972e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280383625879163390e+01,4.423133668031562138e+02,5.627519209383549104e+00,6.928203299376701096e+00,-1.461642574237894711e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280527963445021555e+01,4.423233657349757095e+02,5.627373050330489512e+00,6.928203299376701096e+00,-1.478309240904561450e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280672301010879721e+01,4.423333646422964875e+02,5.627225224790830538e+00,6.928203299376701096e+00,-1.494975907571228189e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280816638576737887e+01,4.423433635248408109e+02,5.627075732768679117e+00,6.928203299376701096e+00,-1.511642574237894929e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.280960976142596053e+01,4.423533623823309426e+02,5.626924574268187484e+00,6.928203299376701096e+00,-1.528309240904561668e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281105313708454219e+01,4.423633612144890890e+02,5.626771749293554947e+00,6.928203299376701096e+00,-1.544975907571228407e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281249651274312384e+01,4.423733600210375698e+02,5.626617257849026110e+00,6.928203299376701096e+00,-1.561642574237895147e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281393988840170550e+01,4.423833588016985914e+02,5.626461099938892652e+00,6.928203299376701096e+00,-1.578309240904561886e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281538326406028716e+01,4.423933575561944167e+02,5.626303275567492435e+00,6.928203299376701096e+00,-1.594975907571228452e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281682663971886882e+01,4.424033562842473088e+02,5.626143784739209508e+00,6.928203299376701096e+00,-1.611642574237895018e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281827001537745048e+01,4.424133549855795309e+02,5.625982627458474106e+00,6.928203299376701096e+00,-1.628309240904561583e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.281971339103603214e+01,4.424233536599133458e+02,5.625819803729762647e+00,6.928203299376701096e+00,-1.644975907571228149e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282115676669461379e+01,4.424333523069709599e+02,5.625655313557597736e+00,6.928203299376701096e+00,-1.661642574237894715e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282260014235319545e+01,4.424433509264746931e+02,5.625489156946549052e+00,6.928203299376701096e+00,-1.678309240904561281e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282404351801177711e+01,4.424533495181468084e+02,5.625321333901231569e+00,6.928203299376701096e+00,-1.694975907571227847e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282548689367035877e+01,4.424633480817095119e+02,5.625151844426307335e+00,6.928203299376701096e+00,-1.711642574237894412e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282693026932894043e+01,4.424733466168851237e+02,5.624980688526484585e+00,6.928203299376701096e+00,-1.728309240904560978e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282837364498752208e+01,4.424833451233959067e+02,5.624807866206517737e+00,6.928203299376701096e+00,-1.744975907571227544e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.282981702064610374e+01,4.424933436009640673e+02,5.624633377471206508e+00,6.928203299376701096e+00,-1.761642574237894110e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283126039630468540e+01,4.425033420493119252e+02,5.624457222325398575e+00,6.928203299376701096e+00,-1.778309240904560676e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283270377196326706e+01,4.425133404681617435e+02,5.624279400773986914e+00,6.928203299376701096e+00,-1.794975907571227242e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283414714762184872e+01,4.425233388572357285e+02,5.624099912821911573e+00,6.928203299376701096e+00,-1.811642574237893807e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283559052328043038e+01,4.425333372162562000e+02,5.623918758474157009e+00,6.928203299376701096e+00,-1.828309240904560373e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283703389893901203e+01,4.425433355449454211e+02,5.623735937735756529e+00,6.928203299376701096e+00,-1.844975907571226939e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283847727459759369e+01,4.425533338430256549e+02,5.623551450611787850e+00,6.928203299376701096e+00,-1.861642574237893505e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.283992065025617535e+01,4.425633321102191644e+02,5.623365297107375760e+00,6.928203299376701096e+00,-1.878309240904560071e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.284136402591475701e+01,4.425733303462482127e+02,5.623177477227691234e+00,6.928203299376701096e+00,-1.894975907571226637e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.284280740157333867e+01,4.425833285508351196e+02,5.622987990977951434e+00,6.928203299376701096e+00,-1.911642574237893202e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.284425077723192032e+01,4.425933267237020914e+02,5.622796838363420591e+00,6.928203299376701096e+00,-1.928309240904559768e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.284569415289050198e+01,4.426033248645714480e+02,5.622604019389407348e+00,6.928203299376701096e+00,-1.944975907571226334e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.284713752854908364e+01,4.426133229731654524e+02,5.622409534061268310e+00,6.928203299376701096e+00,-1.961642574237892900e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.284858090420766530e+01,4.426233210492063677e+02,5.622213382384406266e+00,6.928203299376701096e+00,-1.978309240904559466e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285002427986624696e+01,4.426333190924164569e+02,5.622015564364269302e+00,6.928203299376701096e+00,-1.994975907571226031e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285146765552482861e+01,4.426433171025180400e+02,5.621816080006352578e+00,6.928203299376701096e+00,-2.011642574237892597e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285291103118341027e+01,4.426533150792333231e+02,5.621614929316197440e+00,6.928203299376701096e+00,-2.028309240904559163e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285435440684199193e+01,4.426633130222846830e+02,5.621412112299391417e+00,6.928203299376701096e+00,-2.044975907571225729e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285579778250057359e+01,4.426733109313943260e+02,5.621207628961567337e+00,6.928203299376701096e+00,-2.061642574237892295e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285724115815915525e+01,4.426833088062845718e+02,5.621001479308406878e+00,6.928203299376701096e+00,-2.078309240904558861e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.285868453381773691e+01,4.426933066466776836e+02,5.620793663345635238e+00,6.928203299376701096e+00,-2.094975907571225426e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286012790947631856e+01,4.427033044522959244e+02,5.620584181079025576e+00,6.928203299376701096e+00,-2.111642574237891992e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286157128513490022e+01,4.427133022228616142e+02,5.620373032514396350e+00,6.928203299376701096e+00,-2.128309240904558558e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286301466079348188e+01,4.427232999580970159e+02,5.620160217657613089e+00,6.928203299376701096e+00,-2.144975907571225124e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286445803645206354e+01,4.427332976577243926e+02,5.619945736514587509e+00,6.928203299376701096e+00,-2.161642574237891690e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286590141211064520e+01,4.427432953214660643e+02,5.619729589091277511e+00,6.928203299376701096e+00,-2.178309240904558255e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286734478776922685e+01,4.427532929490442939e+02,5.619511775393687181e+00,6.928203299376701096e+00,-2.194975907571224821e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.286878816342780851e+01,4.427632905401814014e+02,5.619292295427866790e+00,6.928203299376701096e+00,-2.211642574237891387e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287023153908639017e+01,4.427732880945996499e+02,5.619071149199912796e+00,6.928203299376701096e+00,-2.228309240904557953e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287167491474497183e+01,4.427832856120213592e+02,5.618848336715967839e+00,6.928203299376701096e+00,-2.244975907571224519e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287311829040355349e+01,4.427932830921687923e+02,5.618623857982221637e+00,6.928203299376701096e+00,-2.261642574237891085e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287456166606213515e+01,4.428032805347642125e+02,5.618397713004910088e+00,6.928203299376701096e+00,-2.278309240904557650e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287600504172071680e+01,4.428132779395299963e+02,5.618169901790314391e+00,6.928203299376701096e+00,-2.294975907571224216e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287744841737929846e+01,4.428232753061883500e+02,5.617940424344762818e+00,6.928203299376701096e+00,-2.311642574237890782e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.287889179303788012e+01,4.428332726344616503e+02,5.617709280674629824e+00,6.928203299376701096e+00,-2.328309240904557348e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288033516869646178e+01,4.428432699240721604e+02,5.617476470786336051e+00,6.928203299376701096e+00,-2.344975907571223914e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288177854435504344e+01,4.428532671747421432e+02,5.617241994686348328e+00,6.928203299376701096e+00,-2.361642574237890480e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288322192001362509e+01,4.428632643861939187e+02,5.617005852381179665e+00,6.928203299376701096e+00,-2.378309240904557045e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288466529567220675e+01,4.428732615581498067e+02,5.616768043877390149e+00,6.928203299376701096e+00,-2.394975907571223611e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288610867133078841e+01,4.428832586903320703e+02,5.616528569181585162e+00,6.928203299376701096e+00,-2.411642574237890177e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288755204698937007e+01,4.428932557824630294e+02,5.616287428300417162e+00,6.928203299376701096e+00,-2.428309240904556743e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.288899542264795173e+01,4.429032528342650039e+02,5.616044621240583901e+00,6.928203299376701096e+00,-2.444975907571223309e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289043879830653339e+01,4.429132498454603137e+02,5.615800148008830206e+00,6.928203299376701096e+00,-2.461642574237889874e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289188217396511504e+01,4.429232468157712219e+02,5.615554008611947090e+00,6.928203299376701096e+00,-2.478309240904556440e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289332554962369670e+01,4.429332437449200484e+02,5.615306203056771750e+00,6.928203299376701096e+00,-2.494975907571223006e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289476892528227836e+01,4.429432406326291130e+02,5.615056731350188457e+00,6.928203299376701096e+00,-2.511642574237889572e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289621230094086002e+01,4.429532374786207356e+02,5.614805593499125891e+00,6.928203299376701096e+00,-2.528309240904556138e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289765567659944168e+01,4.429632342826171794e+02,5.614552789510560693e+00,6.928203299376701096e+00,-2.544975907571222704e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.289909905225802333e+01,4.429732310443407641e+02,5.614298319391514802e+00,6.928203299376701096e+00,-2.561642574237889269e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290054242791660499e+01,4.429832277635138098e+02,5.614042183149057230e+00,6.928203299376701096e+00,-2.578309240904555835e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290198580357518665e+01,4.429932244398586931e+02,5.613784380790302286e+00,6.928203299376701096e+00,-2.594975907571222401e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290342917923376831e+01,4.430032210730976203e+02,5.613524912322411353e+00,6.928203299376701096e+00,-2.611642574237888967e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290487255489234997e+01,4.430132176629529681e+02,5.613263777752591999e+00,6.928203299376701096e+00,-2.628309240904555533e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290631593055093163e+01,4.430232142091470564e+02,5.613000977088097976e+00,6.928203299376701096e+00,-2.644975907571222098e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290775930620951328e+01,4.430332107114022051e+02,5.612736510336229223e+00,6.928203299376701096e+00,-2.661642574237888664e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.290920268186809494e+01,4.430432071694407341e+02,5.612470377504332752e+00,6.928203299376701096e+00,-2.678309240904555230e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291064605752667660e+01,4.430532035829849633e+02,5.612202578599799985e+00,6.928203299376701096e+00,-2.694975907571221796e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291208943318525826e+01,4.430631999517571558e+02,5.611933113630070302e+00,6.928203299376701096e+00,-2.711642574237888362e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291353280884383992e+01,4.430731962754796882e+02,5.611661982602629273e+00,6.928203299376701096e+00,-2.728309240904554928e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291497618450242157e+01,4.430831925538748806e+02,5.611389185525007761e+00,6.928203299376701096e+00,-2.744975907571221493e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291641956016100323e+01,4.430931887866650527e+02,5.611114722404783706e+00,6.928203299376701096e+00,-2.761642574237888059e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291786293581958489e+01,4.431031849735725245e+02,5.610838593249581230e+00,6.928203299376701096e+00,-2.778309240904554625e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.291930631147816655e+01,4.431131811143196728e+02,5.610560798067069754e+00,6.928203299376701096e+00,-2.794975907571221191e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292074968713674821e+01,4.431231772086287606e+02,5.610281336864966661e+00,6.928203299376701096e+00,-2.811642574237887757e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292219306279532987e+01,4.431331732562221646e+02,5.610000209651034631e+00,6.928203299376701096e+00,-2.828309240904554323e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292363643845391152e+01,4.431431692568222047e+02,5.609717416433082526e+00,6.928203299376701096e+00,-2.844975907571220888e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292507981411249318e+01,4.431531652101512009e+02,5.609432957218965399e+00,6.928203299376701096e+00,-2.861642574237887454e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292652318977107484e+01,4.431631611159314730e+02,5.609146832016585371e+00,6.928203299376701096e+00,-2.878309240904554020e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292796656542965650e+01,4.431731569738853977e+02,5.608859040833890752e+00,6.928203299376701096e+00,-2.894975907571220586e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.292940994108823816e+01,4.431831527837352951e+02,5.608569583678875148e+00,6.928203299376701096e+00,-2.911642574237887152e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293085331674681981e+01,4.431931485452034849e+02,5.608278460559579237e+00,6.928203299376701096e+00,-2.928309240904553717e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293229669240540147e+01,4.432031442580123439e+02,5.607985671484089885e+00,6.928203299376701096e+00,-2.944975907571220283e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293374006806398313e+01,4.432131399218841921e+02,5.607691216460540140e+00,6.928203299376701096e+00,-2.961642574237886849e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293518344372256479e+01,4.432231355365414061e+02,5.607395095497108350e+00,6.928203299376701096e+00,-2.978309240904553415e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293662681938114645e+01,4.432331311017062490e+02,5.607097308602020824e+00,6.928203299376701096e+00,-2.994975907571219981e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293807019503972811e+01,4.432431266171011544e+02,5.606797855783550055e+00,6.928203299376701096e+00,-3.011642574237886547e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.293951357069830976e+01,4.432531220824484421e+02,5.606496737050013834e+00,6.928203299376701096e+00,-3.028309240904553112e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294095694635689142e+01,4.432631174974704322e+02,5.606193952409776138e+00,6.928203299376701096e+00,-3.044975907571219678e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294240032201547308e+01,4.432731128618895013e+02,5.605889501871248015e+00,6.928203299376701096e+00,-3.061642574237886244e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294384369767405474e+01,4.432831081754279694e+02,5.605583385442885813e+00,6.928203299376701096e+00,-3.078309240904552810e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294528707333263640e+01,4.432931034378082131e+02,5.605275603133192952e+00,6.928203299376701096e+00,-3.094975907571219376e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294673044899121805e+01,4.433030986487525524e+02,5.604966154950719037e+00,6.928203299376701096e+00,-3.111642574237885941e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294817382464979971e+01,4.433130938079834209e+02,5.604655040904060748e+00,6.928203299376701096e+00,-3.128309240904552507e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.294961720030838137e+01,4.433230889152230816e+02,5.604342261001859171e+00,6.928203299376701096e+00,-3.144975907571219420e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295106057596696303e+01,4.433330839701939681e+02,5.604027815252802469e+00,6.928203299376701096e+00,-3.161642574237886333e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295250395162554469e+01,4.433430789726184003e+02,5.603711703665625876e+00,6.928203299376701096e+00,-3.178309240904553246e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295394732728412635e+01,4.433530739222187549e+02,5.603393926249109924e+00,6.928203299376701096e+00,-3.194975907571220158e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295539070294270800e+01,4.433630688187174087e+02,5.603074483012082219e+00,6.928203299376701096e+00,-3.211642574237887071e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295683407860128966e+01,4.433730636618366816e+02,5.602753373963415662e+00,6.928203299376701096e+00,-3.228309240904553984e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295827745425987132e+01,4.433830584512989503e+02,5.602430599112030229e+00,6.928203299376701096e+00,-3.244975907571220897e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.295972082991845298e+01,4.433930531868265916e+02,5.602106158466891195e+00,6.928203299376701096e+00,-3.261642574237887809e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296116420557703464e+01,4.434030478681419822e+02,5.601780052037011792e+00,6.928203299376701096e+00,-3.278309240904554722e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296260758123561629e+01,4.434130424949674989e+02,5.601452279831450554e+00,6.928203299376701096e+00,-3.294975907571221635e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296405095689419795e+01,4.434230370670255184e+02,5.601122841859311308e+00,6.928203299376701096e+00,-3.311642574237888548e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296549433255277961e+01,4.434330315840383605e+02,5.600791738129745845e+00,6.928203299376701096e+00,-3.328309240904555460e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296693770821136127e+01,4.434430260457284589e+02,5.600458968651951253e+00,6.928203299376701096e+00,-3.344975907571222373e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296838108386994293e+01,4.434530204518181336e+02,5.600124533435170804e+00,6.928203299376701096e+00,-3.361642574237889286e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.296982445952852459e+01,4.434630148020298179e+02,5.599788432488694845e+00,6.928203299376701096e+00,-3.378309240904556199e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297126783518710624e+01,4.434730090960858888e+02,5.599450665821859907e+00,6.928203299376701096e+00,-3.394975907571223112e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297271121084568790e+01,4.434830033337086661e+02,5.599111233444047819e+00,6.928203299376701096e+00,-3.411642574237890024e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297415458650426956e+01,4.434929975146205834e+02,5.598770135364686595e+00,6.928203299376701096e+00,-3.428309240904556937e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297559796216285122e+01,4.435029916385440174e+02,5.598427371593252211e+00,6.928203299376701096e+00,-3.444975907571223850e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297704133782143288e+01,4.435129857052013449e+02,5.598082942139265938e+00,6.928203299376701096e+00,-3.461642574237890763e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297848471348001453e+01,4.435229797143149426e+02,5.597736847012294348e+00,6.928203299376701096e+00,-3.478309240904557675e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.297992808913859619e+01,4.435329736656072441e+02,5.597389086221951970e+00,6.928203299376701096e+00,-3.494975907571224588e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.298137146479717785e+01,4.435429675588006262e+02,5.597039659777898635e+00,6.928203299376701096e+00,-3.511642574237891501e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.298281484045575951e+01,4.435529613936174655e+02,5.596688567689840355e+00,6.928203299376701096e+00,-3.528309240904558414e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.298425821611434117e+01,4.435629551697801389e+02,5.596335809967530217e+00,6.928203299376701096e+00,-3.544975907571225326e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.298570159177292282e+01,4.435729488870110231e+02,5.595981386620766607e+00,6.928203299376701096e+00,-3.561642574237892239e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.298714496743150448e+01,4.435829425450325516e+02,5.595625297659394981e+00,6.928203299376701096e+00,-3.578309240904559152e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.298858834309008614e+01,4.435929361435671581e+02,5.595267543093306095e+00,6.928203299376701096e+00,-3.594975907571226065e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299003171874866780e+01,4.436029296823371624e+02,5.594908122932438665e+00,6.928203299376701096e+00,-3.611642574237892978e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299147509440724946e+01,4.436129231610650550e+02,5.594547037186775817e+00,6.928203299376701096e+00,-3.628309240904559890e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299291847006583112e+01,4.436229165794731557e+02,5.594184285866347750e+00,6.928203299376701096e+00,-3.644975907571226803e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299436184572441277e+01,4.436329099372838982e+02,5.593819868981230847e+00,6.928203299376701096e+00,-3.661642574237893716e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299580522138299443e+01,4.436429032342197161e+02,5.593453786541547679e+00,6.928203299376701096e+00,-3.678309240904560629e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299724859704157609e+01,4.436528964700029860e+02,5.593086038557466999e+00,6.928203299376701096e+00,-3.694975907571227541e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.299869197270015775e+01,4.436628896443561416e+02,5.592716625039204636e+00,6.928203299376701096e+00,-3.711642574237894454e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300013534835873941e+01,4.436728827570015596e+02,5.592345545997021716e+00,6.928203299376701096e+00,-3.728309240904561367e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300157872401732106e+01,4.436828758076616737e+02,5.591972801441226437e+00,6.928203299376701096e+00,-3.744975907571228280e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300302209967590272e+01,4.436928687960589173e+02,5.591598391382172295e+00,6.928203299376701096e+00,-3.761642574237895192e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300446547533448438e+01,4.437028617219157240e+02,5.591222315830259859e+00,6.928203299376701096e+00,-3.778309240904562105e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300590885099306604e+01,4.437128545849544707e+02,5.590844574795935884e+00,6.928203299376701096e+00,-3.794975907571229018e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300735222665164770e+01,4.437228473848975909e+02,5.590465168289692421e+00,6.928203299376701096e+00,-3.811642574237895931e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.300879560231022936e+01,4.437328401214675182e+02,5.590084096322069485e+00,6.928203299376701096e+00,-3.828309240904562843e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301023897796881101e+01,4.437428327943866293e+02,5.589701358903651496e+00,6.928203299376701096e+00,-3.844975907571229756e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301168235362739267e+01,4.437528254033774147e+02,5.589316956045070839e+00,6.928203299376701096e+00,-3.861642574237896669e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301312572928597433e+01,4.437628179481622510e+02,5.588930887757005195e+00,6.928203299376701096e+00,-3.878309240904563582e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301456910494455599e+01,4.437728104284635720e+02,5.588543154050178430e+00,6.928203299376701096e+00,-3.894975907571230495e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301601248060313765e+01,4.437828028440038111e+02,5.588153754935360595e+00,6.928203299376701096e+00,-3.911642574237897407e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301745585626171930e+01,4.437927951945054588e+02,5.587762690423368817e+00,6.928203299376701096e+00,-3.928309240904564320e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.301889923192030096e+01,4.438027874796908918e+02,5.587369960525066404e+00,6.928203299376701096e+00,-3.944975907571231233e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302034260757888262e+01,4.438127796992825438e+02,5.586975565251361964e+00,6.928203299376701096e+00,-3.961642574237898146e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302178598323746428e+01,4.438227718530029051e+02,5.586579504613211178e+00,6.928203299376701096e+00,-3.978309240904565058e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302322935889604594e+01,4.438327639405743525e+02,5.586181778621615024e+00,6.928203299376701096e+00,-3.994975907571231971e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302467273455462760e+01,4.438427559617193765e+02,5.585782387287622441e+00,6.928203299376701096e+00,-4.011642574237898884e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302611611021320925e+01,4.438527479161604106e+02,5.585381330622326779e+00,6.928203299376701096e+00,-4.028309240904565797e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302755948587179091e+01,4.438627398036198883e+02,5.584978608636869346e+00,6.928203299376701096e+00,-4.044975907571232709e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.302900286153037257e+01,4.438727316238202434e+02,5.584574221342435862e+00,6.928203299376701096e+00,-4.061642574237899622e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303044623718895423e+01,4.438827233764839093e+02,5.584168168750260008e+00,6.928203299376701096e+00,-4.078309240904566535e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303188961284753589e+01,4.438927150613333765e+02,5.583760450871620762e+00,6.928203299376701096e+00,-4.094975907571233448e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303333298850611754e+01,4.439027066780911355e+02,5.583351067717844174e+00,6.928203299376701096e+00,-4.111642574237900361e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303477636416469920e+01,4.439126982264795629e+02,5.582940019300301593e+00,6.928203299376701096e+00,-4.128309240904567273e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303621973982328086e+01,4.439226897062211492e+02,5.582527305630410552e+00,6.928203299376701096e+00,-4.144975907571234186e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303766311548186252e+01,4.439326811170383849e+02,5.582112926719635659e+00,6.928203299376701096e+00,-4.161642574237901099e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.303910649114044418e+01,4.439426724586537034e+02,5.581696882579487706e+00,6.928203299376701096e+00,-4.178309240904568012e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304054986679902584e+01,4.439526637307895385e+02,5.581279173221523671e+00,6.928203299376701096e+00,-4.194975907571234924e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304199324245760749e+01,4.439626549331683805e+02,5.580859798657345827e+00,6.928203299376701096e+00,-4.211642574237901837e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304343661811618915e+01,4.439726460655127198e+02,5.580438758898604412e+00,6.928203299376701096e+00,-4.228309240904568750e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304487999377477081e+01,4.439826371275449901e+02,5.580016053956994071e+00,6.928203299376701096e+00,-4.244975907571235663e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304632336943335247e+01,4.439926281189876818e+02,5.579591683844256522e+00,6.928203299376701096e+00,-4.261642574237902575e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304776674509193413e+01,4.440026190395632284e+02,5.579165648572180558e+00,6.928203299376701096e+00,-4.278309240904569488e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.304921012075051578e+01,4.440126098889941204e+02,5.578737948152600268e+00,6.928203299376701096e+00,-4.294975907571236401e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305065349640909744e+01,4.440226006670028482e+02,5.578308582597395926e+00,6.928203299376701096e+00,-4.311642574237903314e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305209687206767910e+01,4.440325913733119023e+02,5.577877551918494881e+00,6.928203299376701096e+00,-4.328309240904570226e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305354024772626076e+01,4.440425820076437731e+02,5.577444856127869777e+00,6.928203299376701096e+00,-4.344975907571237139e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305498362338484242e+01,4.440525725697208941e+02,5.577010495237540333e+00,6.928203299376701096e+00,-4.361642574237904052e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305642699904342408e+01,4.440625630592657558e+02,5.576574469259571565e+00,6.928203299376701096e+00,-4.378309240904570965e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305787037470200573e+01,4.440725534760009054e+02,5.576136778206075562e+00,6.928203299376701096e+00,-4.394975907571237878e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.305931375036058739e+01,4.440825438196487767e+02,5.575697422089210598e+00,6.928203299376701096e+00,-4.411642574237904790e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306075712601916905e+01,4.440925340899318599e+02,5.575256400921181132e+00,6.928203299376701096e+00,-4.428309240904571703e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306220050167775071e+01,4.441025242865727023e+02,5.574813714714236923e+00,6.928203299376701096e+00,-4.444975907571238616e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306364387733633237e+01,4.441125144092937376e+02,5.574369363480675688e+00,6.928203299376701096e+00,-4.461642574237905529e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306508725299491402e+01,4.441225044578174561e+02,5.573923347232840442e+00,6.928203299376701096e+00,-4.478309240904572441e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306653062865349568e+01,4.441324944318664052e+02,5.573475665983120386e+00,6.928203299376701096e+00,-4.494975907571239354e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306797400431207734e+01,4.441424843311630752e+02,5.573026319743950907e+00,6.928203299376701096e+00,-4.511642574237906267e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.306941737997065900e+01,4.441524741554299567e+02,5.572575308527813576e+00,6.928203299376701096e+00,-4.528309240904573180e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307086075562924066e+01,4.441624639043895399e+02,5.572122632347237037e+00,6.928203299376701096e+00,-4.544975907571240092e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307230413128782232e+01,4.441724535777643723e+02,5.571668291214795232e+00,6.928203299376701096e+00,-4.561642574237907005e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307374750694640397e+01,4.441824431752768874e+02,5.571212285143109177e+00,6.928203299376701096e+00,-4.578309240904573918e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307519088260498563e+01,4.441924326966496892e+02,5.570754614144845185e+00,6.928203299376701096e+00,-4.594975907571240831e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307663425826356729e+01,4.442024221416052114e+02,5.570295278232716640e+00,6.928203299376701096e+00,-4.611642574237907743e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307807763392214895e+01,4.442124115098660013e+02,5.569834277419483115e+00,6.928203299376701096e+00,-4.628309240904574656e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.307952100958073061e+01,4.442224008011546061e+02,5.569371611717950366e+00,6.928203299376701096e+00,-4.644975907571241569e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308096438523931226e+01,4.442323900151935163e+02,5.568907281140969445e+00,6.928203299376701096e+00,-4.661642574237908482e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308240776089789392e+01,4.442423791517052791e+02,5.568441285701438481e+00,6.928203299376701096e+00,-4.678309240904575395e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308385113655647558e+01,4.442523682104123850e+02,5.567973625412302674e+00,6.928203299376701096e+00,-4.694975907571242307e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308529451221505724e+01,4.442623571910373812e+02,5.567504300286551633e+00,6.928203299376701096e+00,-4.711642574237909220e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308673788787363890e+01,4.442723460933027582e+02,5.567033310337222929e+00,6.928203299376701096e+00,-4.728309240904576133e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308818126353222056e+01,4.442823349169311200e+02,5.566560655577398542e+00,6.928203299376701096e+00,-4.744975907571243046e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.308962463919080221e+01,4.442923236616449572e+02,5.566086336020208414e+00,6.928203299376701096e+00,-4.761642574237909958e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309106801484938387e+01,4.443023123271667600e+02,5.565610351678828671e+00,6.928203299376701096e+00,-4.778309240904576871e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309251139050796553e+01,4.443123009132191328e+02,5.565132702566480738e+00,6.928203299376701096e+00,-4.794975907571243784e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309395476616654719e+01,4.443222894195245658e+02,5.564653388696432224e+00,6.928203299376701096e+00,-4.811642574237910697e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309539814182512885e+01,4.443322778458056632e+02,5.564172410081997810e+00,6.928203299376701096e+00,-4.828309240904577609e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309684151748371050e+01,4.443422661917849155e+02,5.563689766736537479e+00,6.928203299376701096e+00,-4.844975907571244522e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309828489314229216e+01,4.443522544571848698e+02,5.563205458673458281e+00,6.928203299376701096e+00,-4.861642574237911435e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.309972826880087382e+01,4.443622426417280735e+02,5.562719485906213457e+00,6.928203299376701096e+00,-4.878309240904578348e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310117164445945548e+01,4.443722307451371307e+02,5.562231848448302429e+00,6.928203299376701096e+00,-4.894975907571245261e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310261502011803714e+01,4.443822187671345318e+02,5.561742546313269919e+00,6.928203299376701096e+00,-4.911642574237912173e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310405839577661880e+01,4.443922067074428810e+02,5.561251579514708610e+00,6.928203299376701096e+00,-4.928309240904579086e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310550177143520045e+01,4.444021945657846686e+02,5.560758948066255591e+00,6.928203299376701096e+00,-4.944975907571245999e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310694514709378211e+01,4.444121823418824988e+02,5.560264651981595030e+00,6.928203299376701096e+00,-4.961642574237912912e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310838852275236377e+01,4.444221700354589188e+02,5.559768691274458163e+00,6.928203299376701096e+00,-4.978309240904579824e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.310983189841094543e+01,4.444321576462365329e+02,5.559271065958621527e+00,6.928203299376701096e+00,-4.994975907571246737e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311127527406952709e+01,4.444421451739378881e+02,5.558771776047907842e+00,6.928203299376701096e+00,-5.011642574237913650e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311271864972810874e+01,4.444521326182855319e+02,5.558270821556186014e+00,6.928203299376701096e+00,-5.028309240904580563e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311416202538669040e+01,4.444621199790020682e+02,5.557768202497371135e+00,6.928203299376701096e+00,-5.044975907571247475e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311560540104527206e+01,4.444721072558100445e+02,5.557263918885425369e+00,6.928203299376701096e+00,-5.061642574237914388e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311704877670385372e+01,4.444820944484320080e+02,5.556757970734357066e+00,6.928203299376701096e+00,-5.078309240904581301e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311849215236243538e+01,4.444920815565905627e+02,5.556250358058219874e+00,6.928203299376701096e+00,-5.094975907571248214e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.311993552802101703e+01,4.445020685800083129e+02,5.555741080871113624e+00,6.928203299376701096e+00,-5.111642574237915126e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.312137890367959869e+01,4.445120555184078057e+02,5.555230139187186111e+00,6.928203299376701096e+00,-5.128309240904582039e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.312282227933818035e+01,4.445220423715116453e+02,5.554717533020629538e+00,6.928203299376701096e+00,-5.144975907571248952e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.312426565499676201e+01,4.445320291390424359e+02,5.554203262385682294e+00,6.928203299376701096e+00,-5.161642574237915865e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.312570903065534367e+01,4.445420158207227246e+02,5.553687327296630727e+00,6.928203299376701096e+00,-5.178309240904582778e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.312715240631392533e+01,4.445520024162751724e+02,5.553169727767805597e+00,6.928203299376701096e+00,-5.194975907571249690e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.312859578197250698e+01,4.445619889254223267e+02,5.552650463813584736e+00,6.928203299376701096e+00,-5.211642574237916603e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313003915763108864e+01,4.445719753478867915e+02,5.552129535448393050e+00,6.928203299376701096e+00,-5.228309240904583516e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313148253328967030e+01,4.445819616833911141e+02,5.551606942686699853e+00,6.928203299376701096e+00,-5.244975907571250429e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313292590894825196e+01,4.445919479316579555e+02,5.551082685543021533e+00,6.928203299376701096e+00,-5.261642574237917341e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313436928460683362e+01,4.446019340924099197e+02,5.550556764031921553e+00,6.928203299376701096e+00,-5.278309240904584254e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313581266026541527e+01,4.446119201653696109e+02,5.550029178168007782e+00,6.928203299376701096e+00,-5.294975907571251167e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313725603592399693e+01,4.446219061502596333e+02,5.549499927965936052e+00,6.928203299376701096e+00,-5.311642574237918080e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.313869941158257859e+01,4.446318920468025908e+02,5.548969013440408382e+00,6.928203299376701096e+00,-5.328309240904584992e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314014278724116025e+01,4.446418778547210877e+02,5.548436434606171197e+00,6.928203299376701096e+00,-5.344975907571251905e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314158616289974191e+01,4.446518635737377849e+02,5.547902191478018885e+00,6.928203299376701096e+00,-5.361642574237918818e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314302953855832357e+01,4.446618492035752297e+02,5.547366284070792020e+00,6.928203299376701096e+00,-5.378309240904585731e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314447291421690522e+01,4.446718347439560830e+02,5.546828712399376471e+00,6.928203299376701096e+00,-5.394975907571252643e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314591628987548688e+01,4.446818201946030058e+02,5.546289476478704294e+00,6.928203299376701096e+00,-5.411642574237919556e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314735966553406854e+01,4.446918055552386022e+02,5.545748576323754619e+00,6.928203299376701096e+00,-5.428309240904586469e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.314880304119265020e+01,4.447017908255854763e+02,5.545206011949552760e+00,6.928203299376701096e+00,-5.444975907571253382e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315024641685123186e+01,4.447117760053662323e+02,5.544661783371170216e+00,6.928203299376701096e+00,-5.461642574237920295e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315168979250981351e+01,4.447217610943035879e+02,5.544115890603723784e+00,6.928203299376701096e+00,-5.478309240904587207e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315313316816839517e+01,4.447317460921200905e+02,5.543568333662377334e+00,6.928203299376701096e+00,-5.494975907571254120e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315457654382697683e+01,4.447417309985384577e+02,5.543019112562340922e+00,6.928203299376701096e+00,-5.511642574237921033e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315601991948555849e+01,4.447517158132812938e+02,5.542468227318869900e+00,6.928203299376701096e+00,-5.528309240904587946e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315746329514414015e+01,4.447617005360712596e+02,5.541915677947267582e+00,6.928203299376701096e+00,-5.544975907571254858e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.315890667080272181e+01,4.447716851666309594e+02,5.541361464462882580e+00,6.928203299376701096e+00,-5.561642574237921771e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316035004646130346e+01,4.447816697046830541e+02,5.540805586881108802e+00,6.928203299376701096e+00,-5.578309240904588684e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316179342211988512e+01,4.447916541499502046e+02,5.540248045217388118e+00,6.928203299376701096e+00,-5.594975907571255597e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316323679777846678e+01,4.448016385021550718e+02,5.539688839487207694e+00,6.928203299376701096e+00,-5.611642574237922509e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316468017343704844e+01,4.448116227610203168e+02,5.539127969706100885e+00,6.928203299376701096e+00,-5.628309240904589422e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316612354909563010e+01,4.448216069262686005e+02,5.538565435889647226e+00,6.928203299376701096e+00,-5.644975907571256335e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316756692475421175e+01,4.448315909976225839e+02,5.538001238053473330e+00,6.928203299376701096e+00,-5.661642574237923248e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.316901030041279341e+01,4.448415749748049279e+02,5.537435376213251104e+00,6.928203299376701096e+00,-5.678309240904590161e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317045367607137507e+01,4.448515588575382935e+02,5.536867850384698642e+00,6.928203299376701096e+00,-5.694975907571257073e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317189705172995673e+01,4.448615426455453985e+02,5.536298660583580222e+00,6.928203299376701096e+00,-5.711642574237923986e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317334042738853839e+01,4.448715263385488470e+02,5.535727806825707198e+00,6.928203299376701096e+00,-5.728309240904590899e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317478380304712005e+01,4.448815099362713568e+02,5.535155289126936218e+00,6.928203299376701096e+00,-5.744975907571257812e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317622717870570170e+01,4.448914934384355888e+02,5.534581107503171005e+00,6.928203299376701096e+00,-5.761642574237924724e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317767055436428336e+01,4.449014768447642041e+02,5.534005261970360579e+00,6.928203299376701096e+00,-5.778309240904591637e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.317911393002286502e+01,4.449114601549799204e+02,5.533427752544501033e+00,6.928203299376701096e+00,-5.794975907571258550e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318055730568144668e+01,4.449214433688053987e+02,5.532848579241634646e+00,6.928203299376701096e+00,-5.811642574237925463e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318200068134002834e+01,4.449314264859633568e+02,5.532267742077848993e+00,6.928203299376701096e+00,-5.828309240904592375e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318344405699860999e+01,4.449414095061764556e+02,5.531685241069278725e+00,6.928203299376701096e+00,-5.844975907571259288e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318488743265719165e+01,4.449513924291674130e+02,5.531101076232103786e+00,6.928203299376701096e+00,-5.861642574237926201e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318633080831577331e+01,4.449613752546588898e+02,5.530515247582552085e+00,6.928203299376701096e+00,-5.878309240904593114e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318777418397435497e+01,4.449713579823736040e+02,5.529927755136895939e+00,6.928203299376701096e+00,-5.894975907571260026e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.318921755963293663e+01,4.449813406120342734e+02,5.529338598911454739e+00,6.928203299376701096e+00,-5.911642574237926939e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319066093529151829e+01,4.449913231433636156e+02,5.528747778922593170e+00,6.928203299376701096e+00,-5.928309240904593852e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319210431095009994e+01,4.450013055760842917e+02,5.528155295186723883e+00,6.928203299376701096e+00,-5.944975907571260765e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319354768660868160e+01,4.450112879099190195e+02,5.527561147720304824e+00,6.928203299376701096e+00,-5.961642574237927678e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319499106226726326e+01,4.450212701445905168e+02,5.526965336539839235e+00,6.928203299376701096e+00,-5.978309240904594590e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319643443792584492e+01,4.450312522798215014e+02,5.526367861661878322e+00,6.928203299376701096e+00,-5.994975907571261503e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319787781358442658e+01,4.450412343153347479e+02,5.525768723103017699e+00,6.928203299376701096e+00,-6.011642574237928416e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.319932118924300823e+01,4.450512162508529173e+02,5.525167920879900940e+00,6.928203299376701096e+00,-6.028309240904595329e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320076456490158989e+01,4.450611980860987273e+02,5.524565455009216919e+00,6.928203299376701096e+00,-6.044975907571262241e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320220794056017155e+01,4.450711798207949528e+02,5.523961325507699804e+00,6.928203299376701096e+00,-6.061642574237929154e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320365131621875321e+01,4.450811614546642545e+02,5.523355532392131728e+00,6.928203299376701096e+00,-6.078309240904596067e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320509469187733487e+01,4.450911429874294072e+02,5.522748075679341007e+00,6.928203299376701096e+00,-6.094975907571262980e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320653806753591653e+01,4.451011244188131286e+02,5.522138955386200365e+00,6.928203299376701096e+00,-6.111642574237929892e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320798144319449818e+01,4.451111057485381934e+02,5.521528171529630491e+00,6.928203299376701096e+00,-6.128309240904596805e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.320942481885307984e+01,4.451210869763273195e+02,5.520915724126596480e+00,6.928203299376701096e+00,-6.144975907571263718e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321086819451166150e+01,4.451310681019032813e+02,5.520301613194112278e+00,6.928203299376701096e+00,-6.161642574237930631e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321231157017024316e+01,4.451410491249887968e+02,5.519685838749235351e+00,6.928203299376701096e+00,-6.178309240904597543e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321375494582882482e+01,4.451510300453065838e+02,5.519068400809071129e+00,6.928203299376701096e+00,-6.194975907571264456e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321519832148740647e+01,4.451610108625794169e+02,5.518449299390770335e+00,6.928203299376701096e+00,-6.211642574237931369e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321664169714598813e+01,4.451709915765300707e+02,5.517828534511530769e+00,6.928203299376701096e+00,-6.228309240904598282e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321808507280456979e+01,4.451809721868812630e+02,5.517206106188595527e+00,6.928203299376701096e+00,-6.244975907571265195e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.321952844846315145e+01,4.451909526933558254e+02,5.516582014439253889e+00,6.928203299376701096e+00,-6.261642574237931413e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322097182412173311e+01,4.452009330956764757e+02,5.515956259280842211e+00,6.928203299376701096e+00,-6.278309240904597632e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322241519978031477e+01,4.452109133935659884e+02,5.515328840730742144e+00,6.928203299376701096e+00,-6.294975907571263851e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322385857543889642e+01,4.452208935867470814e+02,5.514699758806382413e+00,6.928203299376701096e+00,-6.311642574237930070e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322530195109747808e+01,4.452308736749425861e+02,5.514069013525237928e+00,6.928203299376701096e+00,-6.328309240904596289e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322674532675605974e+01,4.452408536578752773e+02,5.513436604904828897e+00,6.928203299376701096e+00,-6.344975907571262508e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322818870241464140e+01,4.452508335352679296e+02,5.512802532962721713e+00,6.928203299376701096e+00,-6.361642574237928727e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.322963207807322306e+01,4.452608133068433176e+02,5.512166797716530731e+00,6.928203299376701096e+00,-6.378309240904594946e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323107545373180471e+01,4.452707929723242160e+02,5.511529399183913824e+00,6.928203299376701096e+00,-6.394975907571261164e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323251882939038637e+01,4.452807725314333993e+02,5.510890337382577719e+00,6.928203299376701096e+00,-6.411642574237927383e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323396220504896803e+01,4.452907519838936992e+02,5.510249612330273550e+00,6.928203299376701096e+00,-6.428309240904593602e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323540558070754969e+01,4.453007313294278902e+02,5.509607224044799523e+00,6.928203299376701096e+00,-6.444975907571259821e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323684895636613135e+01,4.453107105677587469e+02,5.508963172543999143e+00,6.928203299376701096e+00,-6.461642574237926040e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323829233202471301e+01,4.453206896986091010e+02,5.508317457845762988e+00,6.928203299376701096e+00,-6.478309240904592259e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.323973570768329466e+01,4.453306687217017270e+02,5.507670079968027821e+00,6.928203299376701096e+00,-6.494975907571258478e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324117908334187632e+01,4.453406476367594564e+02,5.507021038928776591e+00,6.928203299376701096e+00,-6.511642574237924697e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324262245900045798e+01,4.453506264435050639e+02,5.506370334746037543e+00,6.928203299376701096e+00,-6.528309240904590915e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324406583465903964e+01,4.453606051416613809e+02,5.505717967437886884e+00,6.928203299376701096e+00,-6.544975907571257134e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324550921031762130e+01,4.453705837309512390e+02,5.505063937022444343e+00,6.928203299376701096e+00,-6.561642574237923353e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324695258597620295e+01,4.453805622110974127e+02,5.504408243517878496e+00,6.928203299376701096e+00,-6.578309240904589572e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324839596163478461e+01,4.453905405818227905e+02,5.503750886942403220e+00,6.928203299376701096e+00,-6.594975907571255791e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.324983933729336627e+01,4.454005188428501469e+02,5.503091867314277685e+00,6.928203299376701096e+00,-6.611642574237922010e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325128271295194793e+01,4.454104969939023135e+02,5.502431184651808138e+00,6.928203299376701096e+00,-6.628309240904588229e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325272608861052959e+01,4.454204750347021218e+02,5.501768838973347009e+00,6.928203299376701096e+00,-6.644975907571254448e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325416946426911124e+01,4.454304529649724032e+02,5.501104830297292914e+00,6.928203299376701096e+00,-6.661642574237920666e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325561283992769290e+01,4.454404307844359892e+02,5.500439158642090653e+00,6.928203299376701096e+00,-6.678309240904586885e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325705621558627456e+01,4.454504084928157113e+02,5.499771824026231215e+00,6.928203299376701096e+00,-6.694975907571253104e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325849959124485622e+01,4.454603860898344010e+02,5.499102826468251770e+00,6.928203299376701096e+00,-6.711642574237919323e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.325994296690343788e+01,4.454703635752149466e+02,5.498432165986734788e+00,6.928203299376701096e+00,-6.728309240904585542e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.326138634256201954e+01,4.454803409486801229e+02,5.497759842600309810e+00,6.928203299376701096e+00,-6.744975907571251761e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.326282971822060119e+01,4.454903182099528749e+02,5.497085856327653453e+00,6.928203299376701096e+00,-6.761642574237917980e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.326427309387918285e+01,4.455002953587559773e+02,5.496410207187486741e+00,6.928203299376701096e+00,-6.778309240904584199e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.326571646953776451e+01,4.455102723948123185e+02,5.495732895198577772e+00,6.928203299376701096e+00,-6.794975907571250417e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.326715984519634617e+01,4.455202493178447867e+02,5.495053920379740831e+00,6.928203299376701096e+00,-6.811642574237916636e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.326860322085492783e+01,4.455302261275762135e+02,5.494373282749836385e+00,6.928203299376701096e+00,-6.828309240904582855e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327004659651350948e+01,4.455402028237294303e+02,5.493690982327771088e+00,6.928203299376701096e+00,-6.844975907571249074e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327148997217209114e+01,4.455501794060273824e+02,5.493007019132497781e+00,6.928203299376701096e+00,-6.861642574237915293e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327293334783067280e+01,4.455601558741929011e+02,5.492321393183015488e+00,6.928203299376701096e+00,-6.878309240904581512e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327437672348925446e+01,4.455701322279488750e+02,5.491634104498368529e+00,6.928203299376701096e+00,-6.894975907571247731e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327582009914783612e+01,4.455801084670181353e+02,5.490945153097649190e+00,6.928203299376701096e+00,-6.911642574237913950e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327726347480641778e+01,4.455900845911236274e+02,5.490254538999995049e+00,6.928203299376701096e+00,-6.928309240904580169e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.327870685046499943e+01,4.456000605999881827e+02,5.489562262224589873e+00,6.928203299376701096e+00,-6.944975907571246387e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328015022612358109e+01,4.456100364933347464e+02,5.488868322790662724e+00,6.928203299376701096e+00,-6.961642574237912606e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328159360178216275e+01,4.456200122708862068e+02,5.488172720717490627e+00,6.928203299376701096e+00,-6.978309240904578825e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328303697744074441e+01,4.456299879323653954e+02,5.487475456024395015e+00,6.928203299376701096e+00,-6.994975907571245044e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328448035309932607e+01,4.456399634774952574e+02,5.486776528730745284e+00,6.928203299376701096e+00,-7.011642574237911263e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328592372875790772e+01,4.456499389059986811e+02,5.486075938855955236e+00,6.928203299376701096e+00,-7.028309240904577482e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328736710441648938e+01,4.456599142175986117e+02,5.485373686419485750e+00,6.928203299376701096e+00,-7.044975907571243701e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.328881048007507104e+01,4.456698894120179375e+02,5.484669771440844777e+00,6.928203299376701096e+00,-7.061642574237909920e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329025385573365270e+01,4.456798644889795469e+02,5.483964193939584675e+00,6.928203299376701096e+00,-7.078309240904576138e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329169723139223436e+01,4.456898394482063281e+02,5.483256953935304878e+00,6.928203299376701096e+00,-7.094975907571242357e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329314060705081602e+01,4.456998142894212265e+02,5.482548051447651005e+00,6.928203299376701096e+00,-7.111642574237908576e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329458398270939767e+01,4.457097890123471871e+02,5.481837486496314860e+00,6.928203299376701096e+00,-7.128309240904574795e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329602735836797933e+01,4.457197636167071551e+02,5.481125259101034430e+00,6.928203299376701096e+00,-7.144975907571241014e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329747073402656099e+01,4.457297381022240188e+02,5.480411369281593892e+00,6.928203299376701096e+00,-7.161642574237907233e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.329891410968514265e+01,4.457397124686206666e+02,5.479695817057823604e+00,6.928203299376701096e+00,-7.178309240904573452e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330035748534372431e+01,4.457496867156201006e+02,5.478978602449599222e+00,6.928203299376701096e+00,-7.194975907571239671e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330180086100230596e+01,4.457596608429452658e+02,5.478259725476844366e+00,6.928203299376701096e+00,-7.211642574237905889e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330324423666088762e+01,4.457696348503190507e+02,5.477539186159527063e+00,6.928203299376701096e+00,-7.228309240904572108e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330468761231946928e+01,4.457796087374644003e+02,5.476816984517663300e+00,6.928203299376701096e+00,-7.244975907571238327e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330613098797805094e+01,4.457895825041043167e+02,5.476093120571313477e+00,6.928203299376701096e+00,-7.261642574237904546e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330757436363663260e+01,4.457995561499616883e+02,5.475367594340585065e+00,6.928203299376701096e+00,-7.278309240904570765e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.330901773929521426e+01,4.458095296747595171e+02,5.474640405845630831e+00,6.928203299376701096e+00,-7.294975907571236984e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331046111495379591e+01,4.458195030782207482e+02,5.473911555106651505e+00,6.928203299376701096e+00,-7.311642574237903203e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331190449061237757e+01,4.458294763600683268e+02,5.473181042143892228e+00,6.928203299376701096e+00,-7.328309240904569422e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331334786627095923e+01,4.458394495200252550e+02,5.472448866977646098e+00,6.928203299376701096e+00,-7.344975907571235640e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331479124192954089e+01,4.458494225578144210e+02,5.471715029628250626e+00,6.928203299376701096e+00,-7.361642574237901859e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331623461758812255e+01,4.458593954731588838e+02,5.470979530116089506e+00,6.928203299376701096e+00,-7.378309240904568078e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331767799324670420e+01,4.458693682657815884e+02,5.470242368461594396e+00,6.928203299376701096e+00,-7.394975907571234297e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.331912136890528586e+01,4.458793409354054802e+02,5.469503544685241359e+00,6.928203299376701096e+00,-7.411642574237900516e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332056474456386752e+01,4.458893134817535611e+02,5.468763058807553534e+00,6.928203299376701096e+00,-7.428309240904566735e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332200812022244918e+01,4.458992859045488331e+02,5.468020910849100247e+00,6.928203299376701096e+00,-7.444975907571232954e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332345149588103084e+01,4.459092582035142982e+02,5.467277100830496117e+00,6.928203299376701096e+00,-7.461642574237899173e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332489487153961250e+01,4.459192303783729017e+02,5.466531628772402840e+00,6.928203299376701096e+00,-7.478309240904565391e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332633824719819415e+01,4.459292024288476455e+02,5.465784494695528295e+00,6.928203299376701096e+00,-7.494975907571231610e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332778162285677581e+01,4.459391743546615317e+02,5.465035698620625659e+00,6.928203299376701096e+00,-7.511642574237897829e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.332922499851535747e+01,4.459491461555376191e+02,5.464285240568495183e+00,6.928203299376701096e+00,-7.528309240904564048e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333066837417393913e+01,4.459591178311988529e+02,5.463533120559982414e+00,6.928203299376701096e+00,-7.544975907571230267e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333211174983252079e+01,4.459690893813682351e+02,5.462779338615979974e+00,6.928203299376701096e+00,-7.561642574237896486e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333355512549110244e+01,4.459790608057688246e+02,5.462023894757425779e+00,6.928203299376701096e+00,-7.578309240904562705e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333499850114968410e+01,4.459890321041236234e+02,5.461266789005304823e+00,6.928203299376701096e+00,-7.594975907571228924e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333644187680826576e+01,4.459990032761556336e+02,5.460508021380648280e+00,6.928203299376701096e+00,-7.611642574237895142e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333788525246684742e+01,4.460089743215878570e+02,5.459747591904532626e+00,6.928203299376701096e+00,-7.628309240904561361e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.333932862812542908e+01,4.460189452401433527e+02,5.458985500598080520e+00,6.928203299376701096e+00,-7.644975907571227580e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334077200378401074e+01,4.460289160315451795e+02,5.458221747482461694e+00,6.928203299376701096e+00,-7.661642574237893799e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334221537944259239e+01,4.460388866955163394e+02,5.457456332578891178e+00,6.928203299376701096e+00,-7.678309240904560018e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334365875510117405e+01,4.460488572317798344e+02,5.456689255908630187e+00,6.928203299376701096e+00,-7.694975907571226237e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334510213075975571e+01,4.460588276400587802e+02,5.455920517492987010e+00,6.928203299376701096e+00,-7.711642574237892456e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334654550641833737e+01,4.460687979200761788e+02,5.455150117353315231e+00,6.928203299376701096e+00,-7.728309240904558675e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334798888207691903e+01,4.460787680715550323e+02,5.454378055511014622e+00,6.928203299376701096e+00,-7.744975907571224893e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.334943225773550068e+01,4.460887380942184564e+02,5.453604331987532028e+00,6.928203299376701096e+00,-7.761642574237891112e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335087563339408234e+01,4.460987079877895098e+02,5.452828946804359589e+00,6.928203299376701096e+00,-7.778309240904557331e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335231900905266400e+01,4.461086777519911948e+02,5.452051899983035632e+00,6.928203299376701096e+00,-7.794975907571223550e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335376238471124566e+01,4.461186473865466269e+02,5.451273191545144670e+00,6.928203299376701096e+00,-7.811642574237889769e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335520576036982732e+01,4.461286168911788650e+02,5.450492821512317398e+00,6.928203299376701096e+00,-7.828309240904555988e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335664913602840898e+01,4.461385862656109680e+02,5.449710789906230701e+00,6.928203299376701096e+00,-7.844975907571222207e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335809251168699063e+01,4.461485555095659947e+02,5.448927096748608534e+00,6.928203299376701096e+00,-7.861642574237888426e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.335953588734557229e+01,4.461585246227670041e+02,5.448141742061219261e+00,6.928203299376701096e+00,-7.878309240904554644e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336097926300415395e+01,4.461684936049371117e+02,5.447354725865878322e+00,6.928203299376701096e+00,-7.894975907571220863e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336242263866273561e+01,4.461784624557994334e+02,5.446566048184447340e+00,6.928203299376701096e+00,-7.911642574237887082e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336386601432131727e+01,4.461884311750769712e+02,5.445775709038834123e+00,6.928203299376701096e+00,-7.928309240904553301e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336530938997989892e+01,4.461983997624928975e+02,5.444983708450992665e+00,6.928203299376701096e+00,-7.944975907571219520e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336675276563848058e+01,4.462083682177702713e+02,5.444190046442923148e+00,6.928203299376701096e+00,-7.961642574237885739e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336819614129706224e+01,4.462183365406322082e+02,5.443394723036671934e+00,6.928203299376701096e+00,-7.978309240904551958e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.336963951695564390e+01,4.462283047308017672e+02,5.442597738254330686e+00,6.928203299376701096e+00,-7.994975907571218177e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337108289261422556e+01,4.462382727880021207e+02,5.441799092118038139e+00,6.928203299376701096e+00,-8.011642574237884395e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337252626827280721e+01,4.462482407119563277e+02,5.440998784649978326e+00,6.928203299376701096e+00,-8.028309240904550614e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337396964393138887e+01,4.462582085023875038e+02,5.440196815872383240e+00,6.928203299376701096e+00,-8.044975907571216833e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337541301958997053e+01,4.462681761590187648e+02,5.439393185807528397e+00,6.928203299376701096e+00,-8.061642574237883052e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337685639524855219e+01,4.462781436815732263e+02,5.438587894477738161e+00,6.928203299376701096e+00,-8.078309240904549271e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337829977090713385e+01,4.462881110697740610e+02,5.437780941905380416e+00,6.928203299376701096e+00,-8.094975907571215490e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.337974314656571551e+01,4.462980783233443844e+02,5.436972328112871899e+00,6.928203299376701096e+00,-8.111642574237881709e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338118652222429716e+01,4.463080454420072556e+02,5.436162053122672866e+00,6.928203299376701096e+00,-8.128309240904547928e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338262989788287882e+01,4.463180124254859038e+02,5.435350116957291533e+00,6.928203299376701096e+00,-8.144975907571214147e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338407327354146048e+01,4.463279792735033880e+02,5.434536519639282304e+00,6.928203299376701096e+00,-8.161642574237880365e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338551664920004214e+01,4.463379459857829374e+02,5.433721261191243990e+00,6.928203299376701096e+00,-8.178309240904546584e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338696002485862380e+01,4.463479125620476111e+02,5.432904341635823364e+00,6.928203299376701096e+00,-8.194975907571212803e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338840340051720545e+01,4.463578790020206384e+02,5.432085760995712498e+00,6.928203299376701096e+00,-8.211642574237879022e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.338984677617578711e+01,4.463678453054251349e+02,5.431265519293649646e+00,6.928203299376701096e+00,-8.228309240904545241e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339129015183436877e+01,4.463778114719842733e+02,5.430443616552419250e+00,6.928203299376701096e+00,-8.244975907571211460e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339273352749295043e+01,4.463877775014211693e+02,5.429620052794851937e+00,6.928203299376701096e+00,-8.261642574237877679e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339417690315153209e+01,4.463977433934590522e+02,5.428794828043824516e+00,6.928203299376701096e+00,-8.278309240904543898e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339562027881011375e+01,4.464077091478210377e+02,5.427967942322259987e+00,6.928203299376701096e+00,-8.294975907571210116e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339706365446869540e+01,4.464176747642302985e+02,5.427139395653127529e+00,6.928203299376701096e+00,-8.311642574237876335e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339850703012727706e+01,4.464276402424100638e+02,5.426309188059441624e+00,6.928203299376701096e+00,-8.328309240904542554e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.339995040578585872e+01,4.464376055820835063e+02,5.425477319564264711e+00,6.928203299376701096e+00,-8.344975907571208773e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.340139378144444038e+01,4.464475707829737985e+02,5.424643790190703641e+00,6.928203299376701096e+00,-8.361642574237874992e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.340283715710302204e+01,4.464575358448041129e+02,5.423808599961911447e+00,6.928203299376701096e+00,-8.378309240904541211e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.340428053276160369e+01,4.464675007672976221e+02,5.422971748901089128e+00,6.928203299376701096e+00,-8.394975907571207430e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.340572390842018535e+01,4.464774655501775555e+02,5.422133237031481201e+00,6.928203299376701096e+00,-8.411642574237873649e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.340716728407876701e+01,4.464874301931671425e+02,5.421293064376380144e+00,6.928203299376701096e+00,-8.428309240904539867e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.340861065973734867e+01,4.464973946959895557e+02,5.420451230959124622e+00,6.928203299376701096e+00,-8.444975907571206086e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341005403539593033e+01,4.465073590583679675e+02,5.419607736803098597e+00,6.928203299376701096e+00,-8.461642574237872305e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341149741105451199e+01,4.465173232800256642e+02,5.418762581931732214e+00,6.928203299376701096e+00,-8.478309240904538524e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341294078671309364e+01,4.465272873606858184e+02,5.417915766368502695e+00,6.928203299376701096e+00,-8.494975907571204743e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341438416237167530e+01,4.465372513000716594e+02,5.417067290136931668e+00,6.928203299376701096e+00,-8.511642574237870962e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341582753803025696e+01,4.465472150979064168e+02,5.416217153260588724e+00,6.928203299376701096e+00,-8.528309240904537181e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341727091368883862e+01,4.465571787539132629e+02,5.415365355763087862e+00,6.928203299376701096e+00,-8.544975907571203400e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.341871428934742028e+01,4.465671422678154840e+02,5.414511897668091045e+00,6.928203299376701096e+00,-8.561642574237869618e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342015766500600193e+01,4.465771056393363097e+02,5.413656778999305530e+00,6.928203299376701096e+00,-8.578309240904535837e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342160104066458359e+01,4.465870688681989691e+02,5.412799999780483873e+00,6.928203299376701096e+00,-8.594975907571202056e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342304441632316525e+01,4.465970319541267486e+02,5.411941560035425702e+00,6.928203299376701096e+00,-8.611642574237868275e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342448779198174691e+01,4.466069948968428776e+02,5.411081459787976833e+00,6.928203299376701096e+00,-8.628309240904534494e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342593116764032857e+01,4.466169576960705854e+02,5.410219699062029264e+00,6.928203299376701096e+00,-8.644975907571200713e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342737454329891023e+01,4.466269203515331014e+02,5.409356277881520292e+00,6.928203299376701096e+00,-8.661642574237866932e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.342881791895749188e+01,4.466368828629537120e+02,5.408491196270433399e+00,6.928203299376701096e+00,-8.678309240904533151e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343026129461607354e+01,4.466468452300557033e+02,5.407624454252799140e+00,6.928203299376701096e+00,-8.694975907571199369e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343170467027465520e+01,4.466568074525623047e+02,5.406756051852693368e+00,6.928203299376701096e+00,-8.711642574237865588e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343314804593323686e+01,4.466667695301968593e+02,5.405885989094239008e+00,6.928203299376701096e+00,-8.728309240904531807e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343459142159181852e+01,4.466767314626825396e+02,5.405014266001604284e+00,6.928203299376701096e+00,-8.744975907571198026e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343603479725040017e+01,4.466866932497426887e+02,5.404140882599003604e+00,6.928203299376701096e+00,-8.761642574237864245e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343747817290898183e+01,4.466966548911005930e+02,5.403265838910697560e+00,6.928203299376701096e+00,-8.778309240904530464e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.343892154856756349e+01,4.467066163864795385e+02,5.402389134960992934e+00,6.928203299376701096e+00,-8.794975907571196683e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344036492422614515e+01,4.467165777356028116e+02,5.401510770774242687e+00,6.928203299376701096e+00,-8.811642574237862902e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344180829988472681e+01,4.467265389381936984e+02,5.400630746374845081e+00,6.928203299376701096e+00,-8.828309240904529120e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344325167554330847e+01,4.467364999939754853e+02,5.399749061787246340e+00,6.928203299376701096e+00,-8.844975907571195339e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344469505120189012e+01,4.467464609026715152e+02,5.398865717035937095e+00,6.928203299376701096e+00,-8.861642574237861558e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344613842686047178e+01,4.467564216640050745e+02,5.397980712145455051e+00,6.928203299376701096e+00,-8.878309240904527777e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344758180251905344e+01,4.467663822776994493e+02,5.397094047140383211e+00,6.928203299376701096e+00,-8.894975907571193996e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.344902517817763510e+01,4.467763427434779828e+02,5.396205722045351649e+00,6.928203299376701096e+00,-8.911642574237860215e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345046855383621676e+01,4.467863030610640180e+02,5.395315736885035740e+00,6.928203299376701096e+00,-8.928309240904526434e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345191192949479841e+01,4.467962632301808412e+02,5.394424091684157929e+00,6.928203299376701096e+00,-8.944975907571192653e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345335530515338007e+01,4.468062232505517954e+02,5.393530786467485072e+00,6.928203299376701096e+00,-8.961642574237858871e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345479868081196173e+01,4.468161831219002238e+02,5.392635821259831985e+00,6.928203299376701096e+00,-8.978309240904525090e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345624205647054339e+01,4.468261428439494694e+02,5.391739196086058783e+00,6.928203299376701096e+00,-8.994975907571191309e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345768543212912505e+01,4.468361024164228184e+02,5.390840910971071764e+00,6.928203299376701096e+00,-9.011642574237857528e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.345912880778770671e+01,4.468460618390436707e+02,5.389940965939822526e+00,6.928203299376701096e+00,-9.028309240904523747e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346057218344628836e+01,4.468560211115353695e+02,5.389039361017309737e+00,6.928203299376701096e+00,-9.044975907571189966e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346201555910487002e+01,4.468659802336212579e+02,5.388136096228579142e+00,6.928203299376701096e+00,-9.061642574237856185e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346345893476345168e+01,4.468759392050246788e+02,5.387231171598720003e+00,6.928203299376701096e+00,-9.078309240904522404e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346490231042203334e+01,4.468858980254690323e+02,5.386324587152869547e+00,6.928203299376701096e+00,-9.094975907571188622e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346634568608061500e+01,4.468958566946776614e+02,5.385416342916211185e+00,6.928203299376701096e+00,-9.111642574237854841e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346778906173919665e+01,4.469058152123739092e+02,5.384506438913973625e+00,6.928203299376701096e+00,-9.128309240904521060e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.346923243739777831e+01,4.469157735782811756e+02,5.383594875171431759e+00,6.928203299376701096e+00,-9.144975907571187279e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347067581305635997e+01,4.469257317921228605e+02,5.382681651713906668e+00,6.928203299376701096e+00,-9.161642574237853498e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347211918871494163e+01,4.469356898536223071e+02,5.381766768566766501e+00,6.928203299376701096e+00,-9.178309240904519717e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347356256437352329e+01,4.469456477625029152e+02,5.380850225755423821e+00,6.928203299376701096e+00,-9.194975907571185936e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347500594003210495e+01,4.469556055184880847e+02,5.379932023305338262e+00,6.928203299376701096e+00,-9.211642574237852155e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347644931569068660e+01,4.469655631213012157e+02,5.379012161242016532e+00,6.928203299376701096e+00,-9.228309240904518373e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347789269134926826e+01,4.469755205706657080e+02,5.378090639591008859e+00,6.928203299376701096e+00,-9.244975907571184592e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.347933606700784992e+01,4.469854778663049615e+02,5.377167458377914322e+00,6.928203299376701096e+00,-9.261642574237850811e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348077944266643158e+01,4.469954350079423762e+02,5.376242617628375520e+00,6.928203299376701096e+00,-9.278309240904517030e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348222281832501324e+01,4.470053919953014088e+02,5.375316117368083013e+00,6.928203299376701096e+00,-9.294975907571183249e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348366619398359489e+01,4.470153488281054024e+02,5.374387957622773548e+00,6.928203299376701096e+00,-9.311642574237849468e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348510956964217655e+01,4.470253055060778138e+02,5.373458138418229169e+00,6.928203299376701096e+00,-9.328309240904515687e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348655294530075821e+01,4.470352620289420997e+02,5.372526659780277214e+00,6.928203299376701096e+00,-9.344975907571181906e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348799632095933987e+01,4.470452183964216601e+02,5.371593521734792986e+00,6.928203299376701096e+00,-9.361642574237848125e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.348943969661792153e+01,4.470551746082399518e+02,5.370658724307697085e+00,6.928203299376701096e+00,-9.378309240904514343e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349088307227650319e+01,4.470651306641203746e+02,5.369722267524955406e+00,6.928203299376701096e+00,-9.394975907571180562e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349232644793508484e+01,4.470750865637863853e+02,5.368784151412580918e+00,6.928203299376701096e+00,-9.411642574237846781e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349376982359366650e+01,4.470850423069614408e+02,5.367844375996632778e+00,6.928203299376701096e+00,-9.428309240904513000e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349521319925224816e+01,4.470949978933689977e+02,5.366902941303215435e+00,6.928203299376701096e+00,-9.444975907571179219e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349665657491082982e+01,4.471049533227325128e+02,5.365959847358480417e+00,6.928203299376701096e+00,-9.461642574237845438e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349809995056941148e+01,4.471149085947753861e+02,5.365015094188623657e+00,6.928203299376701096e+00,-9.478309240904511657e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.349954332622799313e+01,4.471248637092211311e+02,5.364068681819889051e+00,6.928203299376701096e+00,-9.494975907571177876e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350098670188657479e+01,4.471348186657932615e+02,5.363120610278565792e+00,6.928203299376701096e+00,-9.511642574237844094e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350243007754515645e+01,4.471447734642151772e+02,5.362170879590989259e+00,6.928203299376701096e+00,-9.528309240904510313e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350387345320373811e+01,4.471547281042103918e+02,5.361219489783541015e+00,6.928203299376701096e+00,-9.544975907571176532e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350531682886231977e+01,4.471646825855023621e+02,5.360266440882648808e+00,6.928203299376701096e+00,-9.561642574237842751e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350676020452090142e+01,4.471746369078146017e+02,5.359311732914785686e+00,6.928203299376701096e+00,-9.578309240904508970e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350820358017948308e+01,4.471845910708706242e+02,5.358355365906470880e+00,6.928203299376701096e+00,-9.594975907571175189e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.350964695583806474e+01,4.471945450743938864e+02,5.357397339884270693e+00,6.928203299376701096e+00,-9.611642574237841408e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351109033149664640e+01,4.472044989181079018e+02,5.356437654874796728e+00,6.928203299376701096e+00,-9.628309240904507627e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351253370715522806e+01,4.472144526017361272e+02,5.355476310904707660e+00,6.928203299376701096e+00,-9.644975907571173845e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351397708281380972e+01,4.472244061250021332e+02,5.354513308000706573e+00,6.928203299376701096e+00,-9.661642574237840064e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351542045847239137e+01,4.472343594876294333e+02,5.353548646189543625e+00,6.928203299376701096e+00,-9.678309240904506283e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351686383413097303e+01,4.472443126893414842e+02,5.352582325498015159e+00,6.928203299376701096e+00,-9.694975907571172502e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351830720978955469e+01,4.472542657298618565e+02,5.351614345952963703e+00,6.928203299376701096e+00,-9.711642574237838721e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.351975058544813635e+01,4.472642186089140637e+02,5.350644707581277082e+00,6.928203299376701096e+00,-9.728309240904504940e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352119396110671801e+01,4.472741713262216763e+02,5.349673410409890195e+00,6.928203299376701096e+00,-9.744975907571171159e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352263733676529966e+01,4.472841238815081510e+02,5.348700454465783238e+00,6.928203299376701096e+00,-9.761642574237837378e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352408071242388132e+01,4.472940762744971153e+02,5.347725839775982593e+00,6.928203299376701096e+00,-9.778309240904503596e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352552408808246298e+01,4.473040285049120257e+02,5.346749566367561712e+00,6.928203299376701096e+00,-9.794975907571169815e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352696746374104464e+01,4.473139805724765097e+02,5.345771634267638461e+00,6.928203299376701096e+00,-9.811642574237836034e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352841083939962630e+01,4.473239324769140808e+02,5.344792043503377776e+00,6.928203299376701096e+00,-9.828309240904502253e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.352985421505820796e+01,4.473338842179483095e+02,5.343810794101990780e+00,6.928203299376701096e+00,-9.844975907571168472e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353129759071678961e+01,4.473438357953027662e+02,5.342827886090733891e+00,6.928203299376701096e+00,-9.861642574237834691e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353274096637537127e+01,4.473537872087009646e+02,5.341843319496910603e+00,6.928203299376701096e+00,-9.878309240904500910e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353418434203395293e+01,4.473637384578665319e+02,5.340857094347869705e+00,6.928203299376701096e+00,-9.894975907571167129e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353562771769253459e+01,4.473736895425230387e+02,5.339869210671007060e+00,6.928203299376701096e+00,-9.911642574237833347e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353707109335111625e+01,4.473836404623940552e+02,5.338879668493762942e+00,6.928203299376701096e+00,-9.928309240904499566e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353851446900969790e+01,4.473935912172031522e+02,5.337888467843624696e+00,6.928203299376701096e+00,-9.944975907571165785e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.353995784466827956e+01,4.474035418066739567e+02,5.336895608748125852e+00,6.928203299376701096e+00,-9.961642574237832004e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.354140122032686122e+01,4.474134922305300393e+02,5.335901091234846128e+00,6.928203299376701096e+00,-9.978309240904498223e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.354284459598544288e+01,4.474234424884950272e+02,5.334904915331411424e+00,6.928203299376701096e+00,-9.994975907571164442e-02,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.354428797164402454e+01,4.474333925802924909e+02,5.333907081065492051e+00,6.928203299376701096e+00,-1.001164257423783066e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.354573134730260620e+01,4.474433425056460578e+02,5.332907588464806281e+00,6.928203299376701096e+00,-1.002830924090449688e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.354717472296118785e+01,4.474532922642792983e+02,5.331906437557117684e+00,6.928203299376701096e+00,-1.004497590757116310e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.354861809861976951e+01,4.474632418559158964e+02,5.330903628370236014e+00,6.928203299376701096e+00,-1.006164257423782932e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355006147427835117e+01,4.474731912802794227e+02,5.329899160932017210e+00,6.928203299376701096e+00,-1.007830924090449554e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355150484993693283e+01,4.474831405370935045e+02,5.328893035270363399e+00,6.928203299376701096e+00,-1.009497590757116176e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355294822559551449e+01,4.474930896260818258e+02,5.327885251413222001e+00,6.928203299376701096e+00,-1.011164257423782797e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355439160125409614e+01,4.475030385469679572e+02,5.326875809388587513e+00,6.928203299376701096e+00,-1.012830924090449419e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355583497691267780e+01,4.475129872994755829e+02,5.325864709224499727e+00,6.928203299376701096e+00,-1.014497590757116041e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355727835257125946e+01,4.475229358833283300e+02,5.324851950949044621e+00,6.928203299376701096e+00,-1.016164257423782663e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.355872172822984112e+01,4.475328842982498827e+02,5.323837534590354359e+00,6.928203299376701096e+00,-1.017830924090449285e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356016510388842278e+01,4.475428325439638684e+02,5.322821460176607289e+00,6.928203299376701096e+00,-1.019497590757115907e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356160847954700444e+01,4.475527806201939711e+02,5.321803727736027945e+00,6.928203299376701096e+00,-1.021164257423782529e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356305185520558609e+01,4.475627285266638182e+02,5.320784337296886157e+00,6.928203299376701096e+00,-1.022830924090449151e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356449523086416775e+01,4.475726762630970939e+02,5.319763288887498831e+00,6.928203299376701096e+00,-1.024497590757115772e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356593860652274941e+01,4.475826238292174821e+02,5.318740582536228167e+00,6.928203299376701096e+00,-1.026164257423782394e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356738198218133107e+01,4.475925712247486103e+02,5.317716218271482553e+00,6.928203299376701096e+00,-1.027830924090449016e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.356882535783991273e+01,4.476025184494142195e+02,5.316690196121716561e+00,6.928203299376701096e+00,-1.029497590757115638e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357026873349849438e+01,4.476124655029379937e+02,5.315662516115430947e+00,6.928203299376701096e+00,-1.031164257423782260e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357171210915707604e+01,4.476224123850436172e+02,5.314633178281172654e+00,6.928203299376701096e+00,-1.032830924090448882e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357315548481565770e+01,4.476323590954547740e+02,5.313602182647533922e+00,6.928203299376701096e+00,-1.034497590757115504e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357459886047423936e+01,4.476423056338952051e+02,5.312569529243154065e+00,6.928203299376701096e+00,-1.036164257423782126e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357604223613282102e+01,4.476522520000885379e+02,5.311535218096717692e+00,6.928203299376701096e+00,-1.037830924090448748e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357748561179140268e+01,4.476621981937585701e+02,5.310499249236955599e+00,6.928203299376701096e+00,-1.039497590757115369e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.357892898744998433e+01,4.476721442146289860e+02,5.309461622692643878e+00,6.928203299376701096e+00,-1.041164257423781991e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358037236310856599e+01,4.476820900624234696e+02,5.308422338492606585e+00,6.928203299376701096e+00,-1.042830924090448613e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358181573876714765e+01,4.476920357368658188e+02,5.307381396665712181e+00,6.928203299376701096e+00,-1.044497590757115235e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358325911442572931e+01,4.477019812376797177e+02,5.306338797240876204e+00,6.928203299376701096e+00,-1.046164257423781857e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358470249008431097e+01,4.477119265645889072e+02,5.305294540247059487e+00,6.928203299376701096e+00,-1.047830924090448479e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358614586574289262e+01,4.477218717173171285e+02,5.304248625713269050e+00,6.928203299376701096e+00,-1.049497590757115101e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358758924140147428e+01,4.477318166955881793e+02,5.303201053668558096e+00,6.928203299376701096e+00,-1.051164257423781723e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.358903261706005594e+01,4.477417614991257437e+02,5.302151824142026015e+00,6.928203299376701096e+00,-1.052830924090448345e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359047599271863760e+01,4.477517061276536197e+02,5.301100937162818383e+00,6.928203299376701096e+00,-1.054497590757114966e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359191936837721926e+01,4.477616505808955480e+02,5.300048392760126070e+00,6.928203299376701096e+00,-1.056164257423781588e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359336274403580092e+01,4.477715948585752699e+02,5.298994190963186135e+00,6.928203299376701096e+00,-1.057830924090448210e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359480611969438257e+01,4.477815389604165830e+02,5.297938331801282708e+00,6.928203299376701096e+00,-1.059497590757114832e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359624949535296423e+01,4.477914828861432284e+02,5.296880815303744328e+00,6.928203299376701096e+00,-1.061164257423781454e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359769287101154589e+01,4.478014266354790607e+02,5.295821641499946608e+00,6.928203299376701096e+00,-1.062830924090448076e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.359913624667012755e+01,4.478113702081478209e+02,5.294760810419311348e+00,6.928203299376701096e+00,-1.064497590757114698e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360057962232870921e+01,4.478213136038732500e+02,5.293698322091306530e+00,6.928203299376701096e+00,-1.066164257423781320e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360202299798729086e+01,4.478312568223792027e+02,5.292634176545445435e+00,6.928203299376701096e+00,-1.067830924090447942e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360346637364587252e+01,4.478411998633894768e+02,5.291568373811287529e+00,6.928203299376701096e+00,-1.069497590757114563e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360490974930445418e+01,4.478511427266278702e+02,5.290500913918438464e+00,6.928203299376701096e+00,-1.071164257423781185e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360635312496303584e+01,4.478610854118181805e+02,5.289431796896549187e+00,6.928203299376701096e+00,-1.072830924090447807e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360779650062161750e+01,4.478710279186842058e+02,5.288361022775318609e+00,6.928203299376701096e+00,-1.074497590757114429e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.360923987628019916e+01,4.478809702469498006e+02,5.287288591584489161e+00,6.928203299376701096e+00,-1.076164257423781051e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361068325193878081e+01,4.478909123963387628e+02,5.286214503353852123e+00,6.928203299376701096e+00,-1.077830924090447673e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361212662759736247e+01,4.479008543665749471e+02,5.285138758113242297e+00,6.928203299376701096e+00,-1.079497590757114295e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361357000325594413e+01,4.479107961573822081e+02,5.284061355892541556e+00,6.928203299376701096e+00,-1.081164257423780917e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361501337891452579e+01,4.479207377684843436e+02,5.282982296721677962e+00,6.928203299376701096e+00,-1.082830924090447539e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361645675457310745e+01,4.479306791996052084e+02,5.281901580630624871e+00,6.928203299376701096e+00,-1.084497590757114160e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361790013023168910e+01,4.479406204504686571e+02,5.280819207649402713e+00,6.928203299376701096e+00,-1.086164257423780782e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.361934350589027076e+01,4.479505615207984874e+02,5.279735177808077218e+00,6.928203299376701096e+00,-1.087830924090447404e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362078688154885242e+01,4.479605024103186111e+02,5.278649491136760297e+00,6.928203299376701096e+00,-1.089497590757114026e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362223025720743408e+01,4.479704431187528826e+02,5.277562147665610048e+00,6.928203299376701096e+00,-1.091164257423780648e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362367363286601574e+01,4.479803836458252135e+02,5.276473147424830756e+00,6.928203299376701096e+00,-1.092830924090447270e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362511700852459740e+01,4.479903239912594586e+02,5.275382490444672001e+00,6.928203299376701096e+00,-1.094497590757113892e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362656038418317905e+01,4.480002641547794724e+02,5.274290176755429549e+00,6.928203299376701096e+00,-1.096164257423780514e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362800375984176071e+01,4.480102041361091096e+02,5.273196206387446239e+00,6.928203299376701096e+00,-1.097830924090447136e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.362944713550034237e+01,4.480201439349723387e+02,5.272100579371109319e+00,6.928203299376701096e+00,-1.099497590757113757e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363089051115892403e+01,4.480300835510930142e+02,5.271003295736853111e+00,6.928203299376701096e+00,-1.101164257423780379e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363233388681750569e+01,4.480400229841949908e+02,5.269904355515158123e+00,6.928203299376701096e+00,-1.102830924090447001e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363377726247608734e+01,4.480499622340022370e+02,5.268803758736550158e+00,6.928203299376701096e+00,-1.104497590757113623e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363522063813466900e+01,4.480599013002386641e+02,5.267701505431601205e+00,6.928203299376701096e+00,-1.106164257423780245e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363666401379325066e+01,4.480698401826281270e+02,5.266597595630930329e+00,6.928203299376701096e+00,-1.107830924090446867e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363810738945183232e+01,4.480797788808945938e+02,5.265492029365200111e+00,6.928203299376701096e+00,-1.109497590757113489e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.363955076511041398e+01,4.480897173947619763e+02,5.264384806665121985e+00,6.928203299376701096e+00,-1.111164257423780111e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364099414076899563e+01,4.480996557239542426e+02,5.263275927561451795e+00,6.928203299376701096e+00,-1.112830924090446733e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364243751642757729e+01,4.481095938681952475e+02,5.262165392084991566e+00,6.928203299376701096e+00,-1.114497590757113354e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364388089208615895e+01,4.481195318272090162e+02,5.261053200266589513e+00,6.928203299376701096e+00,-1.116164257423779976e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364532426774474061e+01,4.481294696007194602e+02,5.259939352137140034e+00,6.928203299376701096e+00,-1.117830924090446598e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364676764340332227e+01,4.481394071884504910e+02,5.258823847727583711e+00,6.928203299376701096e+00,-1.119497590757113220e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364821101906190393e+01,4.481493445901261339e+02,5.257706687068905538e+00,6.928203299376701096e+00,-1.121164257423779842e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.364965439472048558e+01,4.481592818054703002e+02,5.256587870192139356e+00,6.928203299376701096e+00,-1.122830924090446464e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365109777037906724e+01,4.481692188342069585e+02,5.255467397128362528e+00,6.928203299376701096e+00,-1.124497590757113086e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365254114603764890e+01,4.481791556760600770e+02,5.254345267908698602e+00,6.928203299376701096e+00,-1.126164257423779708e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365398452169623056e+01,4.481890923307536809e+02,5.253221482564319089e+00,6.928203299376701096e+00,-1.127830924090446330e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365542789735481222e+01,4.481990287980117387e+02,5.252096041126439907e+00,6.928203299376701096e+00,-1.129497590757112951e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365687127301339387e+01,4.482089650775582186e+02,5.250968943626323160e+00,6.928203299376701096e+00,-1.131164257423779573e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365831464867197553e+01,4.482189011691170890e+02,5.249840190095277137e+00,6.928203299376701096e+00,-1.132830924090446195e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.365975802433055719e+01,4.482288370724123752e+02,5.248709780564656313e+00,6.928203299376701096e+00,-1.134497590757112817e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366120139998913885e+01,4.482387727871680454e+02,5.247577715065860460e+00,6.928203299376701096e+00,-1.136164257423779439e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366264477564772051e+01,4.482487083131081818e+02,5.246443993630336422e+00,6.928203299376701096e+00,-1.137830924090446061e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366408815130630217e+01,4.482586436499567526e+02,5.245308616289575454e+00,6.928203299376701096e+00,-1.139497590757112683e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366553152696488382e+01,4.482685787974377263e+02,5.244171583075116772e+00,6.928203299376701096e+00,-1.141164257423779305e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366697490262346548e+01,4.482785137552751848e+02,5.243032894018544887e+00,6.928203299376701096e+00,-1.142830924090445927e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366841827828204714e+01,4.482884485231931535e+02,5.241892549151488723e+00,6.928203299376701096e+00,-1.144497590757112548e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.366986165394062880e+01,4.482983831009156575e+02,5.240750548505626050e+00,6.928203299376701096e+00,-1.146164257423779170e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367130502959921046e+01,4.483083174881667787e+02,5.239606892112678160e+00,6.928203299376701096e+00,-1.147830924090445792e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367274840525779211e+01,4.483182516846704857e+02,5.238461580004413420e+00,6.928203299376701096e+00,-1.149497590757112414e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367419178091637377e+01,4.483281856901508604e+02,5.237314612212646381e+00,6.928203299376701096e+00,-1.151164257423779036e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367563515657495543e+01,4.483381195043319849e+02,5.236165988769236890e+00,6.928203299376701096e+00,-1.152830924090445658e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367707853223353709e+01,4.483480531269378844e+02,5.235015709706090981e+00,6.928203299376701096e+00,-1.154497590757112280e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367852190789211875e+01,4.483579865576926409e+02,5.233863775055161760e+00,6.928203299376701096e+00,-1.156164257423778902e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.367996528355070041e+01,4.483679197963203364e+02,5.232710184848446744e+00,6.928203299376701096e+00,-1.157830924090445524e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.368140865920928206e+01,4.483778528425450531e+02,5.231554939117989633e+00,6.928203299376701096e+00,-1.159497590757112145e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.368285203486786372e+01,4.483877856960908730e+02,5.230398037895881203e+00,6.928203299376701096e+00,-1.161164257423778767e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.368429541052644538e+01,4.483977183566818212e+02,5.229239481214257523e+00,6.928203299376701096e+00,-1.162830924090445389e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.368573878618502704e+01,4.484076508240420367e+02,5.228079269105300853e+00,6.928203299376701096e+00,-1.164497590757112011e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.368718216184360870e+01,4.484175830978956583e+02,5.226917401601239632e+00,6.928203299376701096e+00,-1.166164257423778633e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.368862553750219035e+01,4.484275151779667112e+02,5.225753878734347602e+00,6.928203299376701096e+00,-1.167830924090445255e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369006891316077201e+01,4.484374470639793344e+02,5.224588700536944685e+00,6.928203299376701096e+00,-1.169497590757111877e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369151228881935367e+01,4.484473787556576667e+02,5.223421867041396993e+00,6.928203299376701096e+00,-1.171164257423778499e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369295566447793533e+01,4.484573102527258470e+02,5.222253378280116820e+00,6.928203299376701096e+00,-1.172830924090445121e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369439904013651699e+01,4.484672415549079574e+02,5.221083234285561758e+00,6.928203299376701096e+00,-1.174497590757111742e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369584241579509865e+01,4.484771726619281367e+02,5.219911435090235585e+00,6.928203299376701096e+00,-1.176164257423778364e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369728579145368030e+01,4.484871035735105238e+02,5.218737980726689152e+00,6.928203299376701096e+00,-1.177830924090444986e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.369872916711226196e+01,4.484970342893792008e+02,5.217562871227517718e+00,6.928203299376701096e+00,-1.179497590757111608e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370017254277084362e+01,4.485069648092584202e+02,5.216386106625363617e+00,6.928203299376701096e+00,-1.181164257423778230e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370161591842942528e+01,4.485168951328722642e+02,5.215207686952914479e+00,6.928203299376701096e+00,-1.182830924090444852e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370305929408800694e+01,4.485268252599449283e+02,5.214027612242904119e+00,6.928203299376701096e+00,-1.184497590757111474e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370450266974658859e+01,4.485367551902005516e+02,5.212845882528112540e+00,6.928203299376701096e+00,-1.186164257423778096e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370594604540517025e+01,4.485466849233632729e+02,5.211662497841365926e+00,6.928203299376701096e+00,-1.187830924090444717e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370738942106375191e+01,4.485566144591573448e+02,5.210477458215535762e+00,6.928203299376701096e+00,-1.189497590757111339e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.370883279672233357e+01,4.485665437973068492e+02,5.209290763683539716e+00,6.928203299376701096e+00,-1.191164257423777961e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371027617238091523e+01,4.485764729375360389e+02,5.208102414278341641e+00,6.928203299376701096e+00,-1.192830924090444583e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371171954803949689e+01,4.485864018795691095e+02,5.206912410032951577e+00,6.928203299376701096e+00,-1.194497590757111205e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371316292369807854e+01,4.485963306231302568e+02,5.205720750980424860e+00,6.928203299376701096e+00,-1.196164257423777827e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371460629935666020e+01,4.486062591679436196e+02,5.204527437153863012e+00,6.928203299376701096e+00,-1.197830924090444449e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371604967501524186e+01,4.486161875137334505e+02,5.203332468586413739e+00,6.928203299376701096e+00,-1.199497590757111071e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371749305067382352e+01,4.486261156602240021e+02,5.202135845311270046e+00,6.928203299376701096e+00,-1.201164257423777693e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.371893642633240518e+01,4.486360436071394133e+02,5.200937567361672009e+00,6.928203299376701096e+00,-1.202830924090444314e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372037980199098683e+01,4.486459713542039367e+02,5.199737634770905004e+00,6.928203299376701096e+00,-1.204497590757110936e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372182317764956849e+01,4.486558989011418248e+02,5.198536047572300589e+00,6.928203299376701096e+00,-1.206164257423777558e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372326655330815015e+01,4.486658262476773302e+02,5.197332805799236510e+00,6.928203299376701096e+00,-1.207830924090444180e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372470992896673181e+01,4.486757533935346487e+02,5.196127909485135810e+00,6.928203299376701096e+00,-1.209497590757110802e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372615330462531347e+01,4.486856803384380328e+02,5.194921358663467714e+00,6.928203299376701096e+00,-1.211164257423777424e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372759668028389513e+01,4.486956070821117351e+02,5.193713153367747637e+00,6.928203299376701096e+00,-1.212830924090444046e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.372904005594247678e+01,4.487055336242800081e+02,5.192503293631537176e+00,6.928203299376701096e+00,-1.214497590757110668e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373048343160105844e+01,4.487154599646671613e+02,5.191291779488443225e+00,6.928203299376701096e+00,-1.216164257423777290e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373192680725964010e+01,4.487253861029973905e+02,5.190078610972118867e+00,6.928203299376701096e+00,-1.217830924090443911e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373337018291822176e+01,4.487353120389950050e+02,5.188863788116263365e+00,6.928203299376701096e+00,-1.219497590757110533e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373481355857680342e+01,4.487452377723843142e+02,5.187647310954622171e+00,6.928203299376701096e+00,-1.221164257423777155e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373625693423538507e+01,4.487551633028895708e+02,5.186429179520986033e+00,6.928203299376701096e+00,-1.222830924090443777e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373770030989396673e+01,4.487650886302350273e+02,5.185209393849191883e+00,6.928203299376701096e+00,-1.224497590757110399e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.373914368555254839e+01,4.487750137541450499e+02,5.183987953973122842e+00,6.928203299376701096e+00,-1.226164257423777021e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374058706121113005e+01,4.487849386743438913e+02,5.182764859926707324e+00,6.928203299376701096e+00,-1.227830924090443643e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374203043686971171e+01,4.487948633905559177e+02,5.181540111743919930e+00,6.928203299376701096e+00,-1.229497590757110265e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374347381252829337e+01,4.488047879025053817e+02,5.180313709458782334e+00,6.928203299376701096e+00,-1.231164257423776887e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374491718818687502e+01,4.488147122099166495e+02,5.179085653105360620e+00,6.928203299376701096e+00,-1.232830924090443508e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374636056384545668e+01,4.488246363125139737e+02,5.177855942717767945e+00,6.928203299376701096e+00,-1.234497590757110130e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374780393950403834e+01,4.488345602100217775e+02,5.176624578330162763e+00,6.928203299376701096e+00,-1.236164257423776752e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.374924731516262000e+01,4.488444839021643133e+02,5.175391559976749711e+00,6.928203299376701096e+00,-1.237830924090443374e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375069069082120166e+01,4.488544073886660044e+02,5.174156887691778728e+00,6.928203299376701096e+00,-1.239497590757109996e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375213406647978331e+01,4.488643306692511032e+02,5.172920561509546822e+00,6.928203299376701096e+00,-1.241164257423776618e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375357744213836497e+01,4.488742537436440330e+02,5.171682581464396300e+00,6.928203299376701096e+00,-1.242830924090443240e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375502081779694663e+01,4.488841766115691598e+02,5.170442947590715654e+00,6.928203299376701096e+00,-1.244497590757109862e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375646419345552829e+01,4.488940992727507933e+02,5.169201659922938674e+00,6.928203299376701096e+00,-1.246164257423776484e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375790756911410995e+01,4.489040217269133564e+02,5.167958718495545334e+00,6.928203299376701096e+00,-1.247830924090443105e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.375935094477269161e+01,4.489139439737812154e+02,5.166714123343062681e+00,6.928203299376701096e+00,-1.249497590757109727e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376079432043127326e+01,4.489238660130787366e+02,5.165467874500062173e+00,6.928203299376701096e+00,-1.251164257423776349e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376223769608985492e+01,4.489337878445302863e+02,5.164219972001162340e+00,6.928203299376701096e+00,-1.252830924090443110e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376368107174843658e+01,4.489437094678602875e+02,5.162970415881027009e+00,6.928203299376701096e+00,-1.254497590757109871e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376512444740701824e+01,4.489536308827931634e+02,5.161719206174366192e+00,6.928203299376701096e+00,-1.256164257423776631e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376656782306559990e+01,4.489635520890532803e+02,5.160466342915935201e+00,6.928203299376701096e+00,-1.257830924090443392e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376801119872418155e+01,4.489734730863650611e+02,5.159211826140536417e+00,6.928203299376701096e+00,-1.259497590757110153e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.376945457438276321e+01,4.489833938744529291e+02,5.157955655883016632e+00,6.928203299376701096e+00,-1.261164257423776913e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377089795004134487e+01,4.489933144530413074e+02,5.156697832178269714e+00,6.928203299376701096e+00,-1.262830924090443674e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377234132569992653e+01,4.490032348218546190e+02,5.155438355061235711e+00,6.928203299376701096e+00,-1.264497590757110435e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377378470135850819e+01,4.490131549806172870e+02,5.154177224566899973e+00,6.928203299376701096e+00,-1.266164257423777195e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377522807701708984e+01,4.490230749290537346e+02,5.152914440730294032e+00,6.928203299376701096e+00,-1.267830924090443956e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377667145267567150e+01,4.490329946668884418e+02,5.151650003586494719e+00,6.928203299376701096e+00,-1.269497590757110717e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377811482833425316e+01,4.490429141938458315e+02,5.150383913170625938e+00,6.928203299376701096e+00,-1.271164257423777477e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.377955820399283482e+01,4.490528335096503838e+02,5.149116169517856001e+00,6.928203299376701096e+00,-1.272830924090444238e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378100157965141648e+01,4.490627526140265786e+02,5.147846772663401183e+00,6.928203299376701096e+00,-1.274497590757110999e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378244495530999814e+01,4.490726715066988959e+02,5.146575722642521278e+00,6.928203299376701096e+00,-1.276164257423777759e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378388833096857979e+01,4.490825901873917587e+02,5.145303019490524044e+00,6.928203299376701096e+00,-1.277830924090444520e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378533170662716145e+01,4.490925086558296471e+02,5.144028663242761645e+00,6.928203299376701096e+00,-1.279497590757111281e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378677508228574311e+01,4.491024269117370977e+02,5.142752653934633322e+00,6.928203299376701096e+00,-1.281164257423778041e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378821845794432477e+01,4.491123449548385906e+02,5.141474991601584499e+00,6.928203299376701096e+00,-1.282830924090444802e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.378966183360290643e+01,4.491222627848586058e+02,5.140195676279105008e+00,6.928203299376701096e+00,-1.284497590757111563e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379110520926148808e+01,4.491321804015216230e+02,5.138914708002730869e+00,6.928203299376701096e+00,-1.286164257423778323e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379254858492006974e+01,4.491420978045521792e+02,5.137632086808045173e+00,6.928203299376701096e+00,-1.287830924090445084e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379399196057865140e+01,4.491520149936748112e+02,5.136347812730676310e+00,6.928203299376701096e+00,-1.289497590757111845e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379543533623723306e+01,4.491619319686140557e+02,5.135061885806298854e+00,6.928203299376701096e+00,-1.291164257423778605e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379687871189581472e+01,4.491718487290943926e+02,5.133774306070632676e+00,6.928203299376701096e+00,-1.292830924090445366e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379832208755439638e+01,4.491817652748403589e+02,5.132485073559443833e+00,6.928203299376701096e+00,-1.294497590757112127e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.379976546321297803e+01,4.491916816055765480e+02,5.131194188308543680e+00,6.928203299376701096e+00,-1.296164257423778887e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380120883887155969e+01,4.492015977210274400e+02,5.129901650353790643e+00,6.928203299376701096e+00,-1.297830924090445648e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380265221453014135e+01,4.492115136209176285e+02,5.128607459731089335e+00,6.928203299376701096e+00,-1.299497590757112409e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380409559018872301e+01,4.492214293049716503e+02,5.127311616476388778e+00,6.928203299376701096e+00,-1.301164257423779169e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380553896584730467e+01,4.492313447729140989e+02,5.126014120625684178e+00,6.928203299376701096e+00,-1.302830924090445930e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380698234150588632e+01,4.492412600244695113e+02,5.124714972215017816e+00,6.928203299376701096e+00,-1.304497590757112691e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380842571716446798e+01,4.492511750593624811e+02,5.123414171280477269e+00,6.928203299376701096e+00,-1.306164257423779451e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.380986909282304964e+01,4.492610898773176018e+02,5.122111717858195412e+00,6.928203299376701096e+00,-1.307830924090446212e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381131246848163130e+01,4.492710044780594103e+02,5.120807611984351304e+00,6.928203299376701096e+00,-1.309497590757112973e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381275584414021296e+01,4.492809188613125571e+02,5.119501853695171079e+00,6.928203299376701096e+00,-1.311164257423779733e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381419921979879462e+01,4.492908330268016357e+02,5.118194443026924390e+00,6.928203299376701096e+00,-1.312830924090446494e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381564259545737627e+01,4.493007469742512399e+02,5.116885380015929741e+00,6.928203299376701096e+00,-1.314497590757113255e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381708597111595793e+01,4.493106607033859632e+02,5.115574664698549157e+00,6.928203299376701096e+00,-1.316164257423780015e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381852934677453959e+01,4.493205742139304562e+02,5.114262297111190847e+00,6.928203299376701096e+00,-1.317830924090446776e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.381997272243312125e+01,4.493304875056093124e+02,5.112948277290310095e+00,6.928203299376701096e+00,-1.319497590757113537e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.382141609809170291e+01,4.493404005781471824e+02,5.111632605272407481e+00,6.928203299376701096e+00,-1.321164257423780297e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.382285947375028456e+01,4.493503134312687166e+02,5.110315281094029771e+00,6.928203299376701096e+00,-1.322830924090447058e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.382430284940886622e+01,4.493602260646985656e+02,5.108996304791769028e+00,6.928203299376701096e+00,-1.324497590757113819e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.382574622506744788e+01,4.493701384781613228e+02,5.107675676402263498e+00,6.928203299376701096e+00,-1.326164257423780579e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.382718960072602954e+01,4.493800506713816958e+02,5.106353395962196728e+00,6.928203299376701096e+00,-1.327830924090447340e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.382863297638461120e+01,4.493899626440843349e+02,5.105029463508299337e+00,6.928203299376701096e+00,-1.329497590757114101e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383007635204319286e+01,4.493998743959938906e+02,5.103703879077347239e+00,6.928203299376701096e+00,-1.331164257423780861e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383151972770177451e+01,4.494097859268350135e+02,5.102376642706162535e+00,6.928203299376701096e+00,-1.332830924090447622e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383296310336035617e+01,4.494196972363324676e+02,5.101047754431611736e+00,6.928203299376701096e+00,-1.334497590757114382e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383440647901893783e+01,4.494296083242108466e+02,5.099717214290609313e+00,6.928203299376701096e+00,-1.336164257423781143e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383584985467751949e+01,4.494395191901949147e+02,5.098385022320115034e+00,6.928203299376701096e+00,-1.337830924090447904e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383729323033610115e+01,4.494494298340093223e+02,5.097051178557133078e+00,6.928203299376701096e+00,-1.339497590757114664e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.383873660599468280e+01,4.494593402553787769e+02,5.095715683038715582e+00,6.928203299376701096e+00,-1.341164257423781425e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384017998165326446e+01,4.494692504540279856e+02,5.094378535801959096e+00,6.928203299376701096e+00,-1.342830924090448186e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384162335731184612e+01,4.494791604296817127e+02,5.093039736884007240e+00,6.928203299376701096e+00,-1.344497590757114946e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384306673297042778e+01,4.494890701820646655e+02,5.091699286322048046e+00,6.928203299376701096e+00,-1.346164257423781707e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384451010862900944e+01,4.494989797109015512e+02,5.090357184153317505e+00,6.928203299376701096e+00,-1.347830924090448468e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384595348428759110e+01,4.495088890159170774e+02,5.089013430415095129e+00,6.928203299376701096e+00,-1.349497590757115228e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384739685994617275e+01,4.495187980968360080e+02,5.087668025144707507e+00,6.928203299376701096e+00,-1.351164257423781989e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.384884023560475441e+01,4.495287069533831072e+02,5.086320968379527407e+00,6.928203299376701096e+00,-1.352830924090448750e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385028361126333607e+01,4.495386155852831394e+02,5.084972260156972901e+00,6.928203299376701096e+00,-1.354497590757115510e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385172698692191773e+01,4.495485239922608685e+02,5.083621900514508241e+00,6.928203299376701096e+00,-1.356164257423782271e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385317036258049939e+01,4.495584321740410019e+02,5.082269889489642978e+00,6.928203299376701096e+00,-1.357830924090449032e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385461373823908104e+01,4.495683401303483606e+02,5.080916227119933737e+00,6.928203299376701096e+00,-1.359497590757115792e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385605711389766270e+01,4.495782478609077089e+02,5.079560913442981551e+00,6.928203299376701096e+00,-1.361164257423782553e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385750048955624436e+01,4.495881553654438676e+02,5.078203948496434528e+00,6.928203299376701096e+00,-1.362830924090449314e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.385894386521482602e+01,4.495980626436816010e+02,5.076845332317985182e+00,6.928203299376701096e+00,-1.364497590757116074e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386038724087340768e+01,4.496079696953456732e+02,5.075485064945373992e+00,6.928203299376701096e+00,-1.366164257423782835e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386183061653198934e+01,4.496178765201609622e+02,5.074123146416385843e+00,6.928203299376701096e+00,-1.367830924090449596e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386327399219057099e+01,4.496277831178522320e+02,5.072759576768850920e+00,6.928203299376701096e+00,-1.369497590757116356e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386471736784915265e+01,4.496376894881443036e+02,5.071394356040647367e+00,6.928203299376701096e+00,-1.371164257423783117e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386616074350773431e+01,4.496475956307619981e+02,5.070027484269697737e+00,6.928203299376701096e+00,-1.372830924090449878e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386760411916631597e+01,4.496575015454301365e+02,5.068658961493969883e+00,6.928203299376701096e+00,-1.374497590757116638e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.386904749482489763e+01,4.496674072318735398e+02,5.067288787751479617e+00,6.928203299376701096e+00,-1.376164257423783399e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387049087048347928e+01,4.496773126898170858e+02,5.065916963080286273e+00,6.928203299376701096e+00,-1.377830924090450160e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387193424614206094e+01,4.496872179189855956e+02,5.064543487518496256e+00,6.928203299376701096e+00,-1.379497590757116920e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387337762180064260e+01,4.496971229191039470e+02,5.063168361104262161e+00,6.928203299376701096e+00,-1.381164257423783681e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387482099745922426e+01,4.497070276898970178e+02,5.061791583875780987e+00,6.928203299376701096e+00,-1.382830924090450442e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387626437311780592e+01,4.497169322310896291e+02,5.060413155871297697e+00,6.928203299376701096e+00,-1.384497590757117202e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387770774877638758e+01,4.497268365424067156e+02,5.059033077129101663e+00,6.928203299376701096e+00,-1.386164257423783963e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.387915112443496923e+01,4.497367406235730982e+02,5.057651347687527554e+00,6.928203299376701096e+00,-1.387830924090450724e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388059450009355089e+01,4.497466444743137117e+02,5.056267967584958001e+00,6.928203299376701096e+00,-1.389497590757117484e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388203787575213255e+01,4.497565480943533771e+02,5.054882936859819154e+00,6.928203299376701096e+00,-1.391164257423784245e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388348125141071421e+01,4.497664514834170291e+02,5.053496255550584237e+00,6.928203299376701096e+00,-1.392830924090451006e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388492462706929587e+01,4.497763546412296023e+02,5.052107923695772662e+00,6.928203299376701096e+00,-1.394497590757117766e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388636800272787752e+01,4.497862575675159746e+02,5.050717941333949135e+00,6.928203299376701096e+00,-1.396164257423784527e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388781137838645918e+01,4.497961602620010808e+02,5.049326308503724547e+00,6.928203299376701096e+00,-1.397830924090451288e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.388925475404504084e+01,4.498060627244098555e+02,5.047933025243755090e+00,6.928203299376701096e+00,-1.399497590757118048e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389069812970362250e+01,4.498159649544672334e+02,5.046538091592742248e+00,6.928203299376701096e+00,-1.401164257423784809e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389214150536220416e+01,4.498258669518981492e+02,5.045141507589435470e+00,6.928203299376701096e+00,-1.402830924090451570e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389358488102078582e+01,4.498357687164275376e+02,5.043743273272627725e+00,6.928203299376701096e+00,-1.404497590757118330e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389502825667936747e+01,4.498456702477803333e+02,5.042343388681159944e+00,6.928203299376701096e+00,-1.406164257423785091e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389647163233794913e+01,4.498555715456815278e+02,5.040941853853916577e+00,6.928203299376701096e+00,-1.407830924090451852e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389791500799653079e+01,4.498654726098560559e+02,5.039538668829830037e+00,6.928203299376701096e+00,-1.409497590757118612e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.389935838365511245e+01,4.498753734400289090e+02,5.038133833647877147e+00,6.928203299376701096e+00,-1.411164257423785373e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390080175931369411e+01,4.498852740359250220e+02,5.036727348347081801e+00,6.928203299376701096e+00,-1.412830924090452134e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390224513497227576e+01,4.498951743972694430e+02,5.035319212966512303e+00,6.928203299376701096e+00,-1.414497590757118894e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390368851063085742e+01,4.499050745237871070e+02,5.033909427545284032e+00,6.928203299376701096e+00,-1.416164257423785655e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390513188628943908e+01,4.499149744152030621e+02,5.032497992122557662e+00,6.928203299376701096e+00,-1.417830924090452416e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390657526194802074e+01,4.499248740712422432e+02,5.031084906737539164e+00,6.928203299376701096e+00,-1.419497590757119176e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390801863760660240e+01,4.499347734916297554e+02,5.029670171429481584e+00,6.928203299376701096e+00,-1.421164257423785937e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.390946201326518405e+01,4.499446726760905335e+02,5.028253786237682377e+00,6.928203299376701096e+00,-1.422830924090452698e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391090538892376571e+01,4.499545716243496258e+02,5.026835751201486069e+00,6.928203299376701096e+00,-1.424497590757119458e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391234876458234737e+01,4.499644703361320808e+02,5.025416066360282485e+00,6.928203299376701096e+00,-1.426164257423786219e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391379214024092903e+01,4.499743688111628899e+02,5.023994731753507637e+00,6.928203299376701096e+00,-1.427830924090452980e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391523551589951069e+01,4.499842670491671015e+02,5.022571747420642829e+00,6.928203299376701096e+00,-1.429497590757119740e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391667889155809235e+01,4.499941650498698209e+02,5.021147113401214668e+00,6.928203299376701096e+00,-1.431164257423786501e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391812226721667400e+01,4.500040628129960396e+02,5.019720829734796830e+00,6.928203299376701096e+00,-1.432830924090453262e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.391956564287525566e+01,4.500139603382708628e+02,5.018292896461009178e+00,6.928203299376701096e+00,-1.434497590757120022e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392100901853383732e+01,4.500238576254193390e+02,5.016863313619515097e+00,6.928203299376701096e+00,-1.436164257423786783e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392245239419241898e+01,4.500337546741665165e+02,5.015432081250025931e+00,6.928203299376701096e+00,-1.437830924090453544e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392389576985100064e+01,4.500436514842375573e+02,5.013999199392298323e+00,6.928203299376701096e+00,-1.439497590757120304e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392533914550958229e+01,4.500535480553574530e+02,5.012564668086134212e+00,6.928203299376701096e+00,-1.441164257423787065e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392678252116816395e+01,4.500634443872513657e+02,5.011128487371381723e+00,6.928203299376701096e+00,-1.442830924090453826e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392822589682674561e+01,4.500733404796444006e+02,5.009690657287935167e+00,6.928203299376701096e+00,-1.444497590757120586e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.392966927248532727e+01,4.500832363322616061e+02,5.008251177875734150e+00,6.928203299376701096e+00,-1.446164257423787347e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393111264814390893e+01,4.500931319448281442e+02,5.006810049174763577e+00,6.928203299376701096e+00,-1.447830924090454108e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393255602380249059e+01,4.501030273170691203e+02,5.005367271225055426e+00,6.928203299376701096e+00,-1.449497590757120868e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393399939946107224e+01,4.501129224487096963e+02,5.003922844066686970e+00,6.928203299376701096e+00,-1.451164257423787629e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393544277511965390e+01,4.501228173394749774e+02,5.002476767739780783e+00,6.928203299376701096e+00,-1.452830924090454390e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393688615077823556e+01,4.501327119890901258e+02,5.001029042284505621e+00,6.928203299376701096e+00,-1.454497590757121150e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393832952643681722e+01,4.501426063972802467e+02,4.999579667741076427e+00,6.928203299376701096e+00,-1.456164257423787911e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.393977290209539888e+01,4.501525005637705021e+02,4.998128644149752553e+00,6.928203299376701096e+00,-1.457830924090454672e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394121627775398053e+01,4.501623944882861110e+02,4.996675971550841311e+00,6.928203299376701096e+00,-1.459497590757121432e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394265965341256219e+01,4.501722881705521786e+02,4.995221649984694423e+00,6.928203299376701096e+00,-1.461164257423788193e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394410302907114385e+01,4.501821816102939238e+02,4.993765679491709797e+00,6.928203299376701096e+00,-1.462830924090454954e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394554640472972551e+01,4.501920748072365086e+02,4.992308060112330637e+00,6.928203299376701096e+00,-1.464497590757121714e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394698978038830717e+01,4.502019677611051520e+02,4.990848791887047220e+00,6.928203299376701096e+00,-1.466164257423788475e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394843315604688883e+01,4.502118604716250161e+02,4.989387874856394234e+00,6.928203299376701096e+00,-1.467830924090455236e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.394987653170547048e+01,4.502217529385213197e+02,4.987925309060952550e+00,6.928203299376701096e+00,-1.469497590757121996e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395131990736405214e+01,4.502316451615192250e+02,4.986461094541349226e+00,6.928203299376701096e+00,-1.471164257423788757e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395276328302263380e+01,4.502415371403440076e+02,4.984995231338256616e+00,6.928203299376701096e+00,-1.472830924090455518e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395420665868121546e+01,4.502514288747208866e+02,4.983527719492394148e+00,6.928203299376701096e+00,-1.474497590757122278e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395565003433979712e+01,4.502613203643750239e+02,4.982058559044524770e+00,6.928203299376701096e+00,-1.476164257423789039e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395709340999837877e+01,4.502712116090317522e+02,4.980587750035459393e+00,6.928203299376701096e+00,-1.477830924090455800e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395853678565696043e+01,4.502811026084162336e+02,4.979115292506053336e+00,6.928203299376701096e+00,-1.479497590757122560e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.395998016131554209e+01,4.502909933622537437e+02,4.977641186497208103e+00,6.928203299376701096e+00,-1.481164257423789321e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.396142353697412375e+01,4.503008838702695584e+02,4.976165432049871384e+00,6.928203299376701096e+00,-1.482830924090456082e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.396286691263270541e+01,4.503107741321889534e+02,4.974688029205036166e+00,6.928203299376701096e+00,-1.484497590757122842e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.396431028829128707e+01,4.503206641477371477e+02,4.973208978003741620e+00,6.928203299376701096e+00,-1.486164257423789603e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.396575366394986872e+01,4.503305539166394738e+02,4.971728278487072217e+00,6.928203299376701096e+00,-1.487830924090456364e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.396719703960845038e+01,4.503404434386212074e+02,4.970245930696158609e+00,6.928203299376701096e+00,-1.489497590757123124e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.396864041526703204e+01,4.503503327134076244e+02,4.968761934672177638e+00,6.928203299376701096e+00,-1.491164257423789885e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397008379092561370e+01,4.503602217407240005e+02,4.967276290456350551e+00,6.928203299376701096e+00,-1.492830924090456646e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397152716658419536e+01,4.503701105202956683e+02,4.965788998089945672e+00,6.928203299376701096e+00,-1.494497590757123406e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397297054224277701e+01,4.503799990518479035e+02,4.964300057614276618e+00,6.928203299376701096e+00,-1.496164257423790167e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397441391790135867e+01,4.503898873351060956e+02,4.962809469070703194e+00,6.928203299376701096e+00,-1.497830924090456928e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397585729355994033e+01,4.503997753697955204e+02,4.961317232500630503e+00,6.928203299376701096e+00,-1.499497590757123688e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397730066921852199e+01,4.504096631556415105e+02,4.959823347945508942e+00,6.928203299376701096e+00,-1.501164257423790449e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.397874404487710365e+01,4.504195506923693983e+02,4.958327815446835984e+00,6.928203299376701096e+00,-1.502830924090457210e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398018742053568531e+01,4.504294379797045735e+02,4.956830635046153510e+00,6.928203299376701096e+00,-1.504497590757123970e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398163079619426696e+01,4.504393250173723118e+02,4.955331806785050475e+00,6.928203299376701096e+00,-1.506164257423790731e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398307417185284862e+01,4.504492118050980594e+02,4.953831330705161129e+00,6.928203299376701096e+00,-1.507830924090457492e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398451754751143028e+01,4.504590983426071489e+02,4.952329206848165022e+00,6.928203299376701096e+00,-1.509497590757124252e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398596092317001194e+01,4.504689846296249129e+02,4.950825435255787887e+00,6.928203299376701096e+00,-1.511164257423791013e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398740429882859360e+01,4.504788706658767978e+02,4.949320015969800757e+00,6.928203299376701096e+00,-1.512830924090457774e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.398884767448717525e+01,4.504887564510881361e+02,4.947812949032021734e+00,6.928203299376701096e+00,-1.514497590757124534e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399029105014575691e+01,4.504986419849843742e+02,4.946304234484313334e+00,6.928203299376701096e+00,-1.516164257423791295e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399173442580433857e+01,4.505085272672909014e+02,4.944793872368583365e+00,6.928203299376701096e+00,-1.517830924090458056e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399317780146292023e+01,4.505184122977331072e+02,4.943281862726787601e+00,6.928203299376701096e+00,-1.519497590757124816e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399462117712150189e+01,4.505282970760363810e+02,4.941768205600926223e+00,6.928203299376701096e+00,-1.521164257423791577e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399606455278008355e+01,4.505381816019262260e+02,4.940252901033044708e+00,6.928203299376701096e+00,-1.522830924090458338e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399750792843866520e+01,4.505480658751279748e+02,4.938735949065234720e+00,6.928203299376701096e+00,-1.524497590757125098e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.399895130409724686e+01,4.505579498953671305e+02,4.937217349739634109e+00,6.928203299376701096e+00,-1.526164257423791859e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400039467975582852e+01,4.505678336623691393e+02,4.935697103098426908e+00,6.928203299376701096e+00,-1.527830924090458620e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400183805541441018e+01,4.505777171758594477e+02,4.934175209183841559e+00,6.928203299376701096e+00,-1.529497590757125380e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400328143107299184e+01,4.505876004355635018e+02,4.932651668038152692e+00,6.928203299376701096e+00,-1.531164257423792141e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400472480673157349e+01,4.505974834412067480e+02,4.931126479703681120e+00,6.928203299376701096e+00,-1.532830924090458902e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400616818239015515e+01,4.506073661925146894e+02,4.929599644222792953e+00,6.928203299376701096e+00,-1.534497590757125662e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400761155804873681e+01,4.506172486892127722e+02,4.928071161637900488e+00,6.928203299376701096e+00,-1.536164257423792423e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.400905493370731847e+01,4.506271309310264996e+02,4.926541031991461317e+00,6.928203299376701096e+00,-1.537830924090459184e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401049830936590013e+01,4.506370129176813748e+02,4.925009255325979218e+00,6.928203299376701096e+00,-1.539497590757125944e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401194168502448179e+01,4.506468946489029008e+02,4.923475831684004156e+00,6.928203299376701096e+00,-1.541164257423792705e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401338506068306344e+01,4.506567761244165808e+02,4.921940761108130502e+00,6.928203299376701096e+00,-1.542830924090459466e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401482843634164510e+01,4.506666573439479180e+02,4.920404043640998815e+00,6.928203299376701096e+00,-1.544497590757126226e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401627181200022676e+01,4.506765383072224154e+02,4.918865679325296725e+00,6.928203299376701096e+00,-1.546164257423792987e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401771518765880842e+01,4.506864190139656330e+02,4.917325668203756273e+00,6.928203299376701096e+00,-1.547830924090459748e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.401915856331739008e+01,4.506962994639031308e+02,4.915784010319154795e+00,6.928203299376701096e+00,-1.549497590757126508e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402060193897597173e+01,4.507061796567604119e+02,4.914240705714316704e+00,6.928203299376701096e+00,-1.551164257423793269e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402204531463455339e+01,4.507160595922630364e+02,4.912695754432111706e+00,6.928203299376701096e+00,-1.552830924090460030e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402348869029313505e+01,4.507259392701365641e+02,4.911149156515454806e+00,6.928203299376701096e+00,-1.554497590757126790e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402493206595171671e+01,4.507358186901065551e+02,4.909600912007307194e+00,6.928203299376701096e+00,-1.556164257423793551e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402637544161029837e+01,4.507456978518985693e+02,4.908051020950675358e+00,6.928203299376701096e+00,-1.557830924090460312e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402781881726888003e+01,4.507555767552381667e+02,4.906499483388611971e+00,6.928203299376701096e+00,-1.559497590757127072e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.402926219292746168e+01,4.507654553998509641e+02,4.904946299364215889e+00,6.928203299376701096e+00,-1.561164257423793833e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403070556858604334e+01,4.507753337854625784e+02,4.903391468920630381e+00,6.928203299376701096e+00,-1.562830924090460594e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403214894424462500e+01,4.507852119117985694e+02,4.901834992101044897e+00,6.928203299376701096e+00,-1.564497590757127354e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403359231990320666e+01,4.507950897785845541e+02,4.900276868948695963e+00,6.928203299376701096e+00,-1.566164257423794115e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403503569556178832e+01,4.508049673855462061e+02,4.898717099506864514e+00,6.928203299376701096e+00,-1.567830924090460876e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403647907122036997e+01,4.508148447324090853e+02,4.897155683818876781e+00,6.928203299376701096e+00,-1.569497590757127636e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403792244687895163e+01,4.508247218188988086e+02,4.895592621928106070e+00,6.928203299376701096e+00,-1.571164257423794397e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.403936582253753329e+01,4.508345986447410496e+02,4.894027913877970093e+00,6.928203299376701096e+00,-1.572830924090461158e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404080919819611495e+01,4.508444752096614252e+02,4.892461559711933639e+00,6.928203299376701096e+00,-1.574497590757127918e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404225257385469661e+01,4.508543515133856090e+02,4.890893559473506791e+00,6.928203299376701096e+00,-1.576164257423794679e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404369594951327826e+01,4.508642275556392747e+02,4.889323913206244043e+00,6.928203299376701096e+00,-1.577830924090461440e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404513932517185992e+01,4.508741033361480390e+02,4.887752620953747851e+00,6.928203299376701096e+00,-1.579497590757128200e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404658270083044158e+01,4.508839788546375758e+02,4.886179682759664189e+00,6.928203299376701096e+00,-1.581164257423794961e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404802607648902324e+01,4.508938541108336153e+02,4.884605098667686107e+00,6.928203299376701096e+00,-1.582830924090461722e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.404946945214760490e+01,4.509037291044618314e+02,4.883028868721552840e+00,6.928203299376701096e+00,-1.584497590757128482e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405091282780618656e+01,4.509136038352478977e+02,4.881450992965047142e+00,6.928203299376701096e+00,-1.586164257423795243e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405235620346476821e+01,4.509234783029174878e+02,4.879871471441999731e+00,6.928203299376701096e+00,-1.587830924090462004e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405379957912334987e+01,4.509333525071963891e+02,4.878290304196286620e+00,6.928203299376701096e+00,-1.589497590757128764e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405524295478193153e+01,4.509432264478102752e+02,4.876707491271828232e+00,6.928203299376701096e+00,-1.591164257423795525e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405668633044051319e+01,4.509531001244848767e+02,4.875123032712592064e+00,6.928203299376701096e+00,-1.592830924090462286e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405812970609909485e+01,4.509629735369458672e+02,4.873536928562590909e+00,6.928203299376701096e+00,-1.594497590757129046e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.405957308175767650e+01,4.509728466849190340e+02,4.871949178865882857e+00,6.928203299376701096e+00,-1.596164257423795807e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406101645741625816e+01,4.509827195681301646e+02,4.870359783666572184e+00,6.928203299376701096e+00,-1.597830924090462568e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406245983307483982e+01,4.509925921863049894e+02,4.868768743008809352e+00,6.928203299376701096e+00,-1.599497590757129328e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406390320873342148e+01,4.510024645391692388e+02,4.867176056936789230e+00,6.928203299376701096e+00,-1.601164257423796089e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406534658439200314e+01,4.510123366264487004e+02,4.865581725494753762e+00,6.928203299376701096e+00,-1.602830924090462850e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406678996005058480e+01,4.510222084478691045e+02,4.863985748726989300e+00,6.928203299376701096e+00,-1.604497590757129610e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406823333570916645e+01,4.510320800031562953e+02,4.862388126677828382e+00,6.928203299376701096e+00,-1.606164257423796371e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.406967671136774811e+01,4.510419512920360603e+02,4.860788859391649730e+00,6.928203299376701096e+00,-1.607830924090463132e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407112008702632977e+01,4.510518223142341299e+02,4.859187946912877365e+00,6.928203299376701096e+00,-1.609497590757129892e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407256346268491143e+01,4.510616930694764051e+02,4.857585389285981492e+00,6.928203299376701096e+00,-1.611164257423796653e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407400683834349309e+01,4.510715635574886164e+02,4.855981186555477613e+00,6.928203299376701096e+00,-1.612830924090463414e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407545021400207474e+01,4.510814337779966081e+02,4.854375338765926529e+00,6.928203299376701096e+00,-1.614497590757130174e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407689358966065640e+01,4.510913037307262243e+02,4.852767845961935222e+00,6.928203299376701096e+00,-1.616164257423796935e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407833696531923806e+01,4.511011734154033093e+02,4.851158708188155977e+00,6.928203299376701096e+00,-1.617830924090463696e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.407978034097781972e+01,4.511110428317537071e+02,4.849547925489287259e+00,6.928203299376701096e+00,-1.619497590757130456e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408122371663640138e+01,4.511209119795032052e+02,4.847935497910072833e+00,6.928203299376701096e+00,-1.621164257423797217e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408266709229498304e+01,4.511307808583777046e+02,4.846321425495302648e+00,6.928203299376701096e+00,-1.622830924090463978e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408411046795356469e+01,4.511406494681031063e+02,4.844705708289811952e+00,6.928203299376701096e+00,-1.624497590757130738e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408555384361214635e+01,4.511505178084051977e+02,4.843088346338482175e+00,6.928203299376701096e+00,-1.626164257423797499e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408699721927072801e+01,4.511603858790099366e+02,4.841469339686239159e+00,6.928203299376701096e+00,-1.627830924090464260e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408844059492930967e+01,4.511702536796431673e+02,4.839848688378055819e+00,6.928203299376701096e+00,-1.629497590757131020e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.408988397058789133e+01,4.511801212100307907e+02,4.838226392458950365e+00,6.928203299376701096e+00,-1.631164257423797781e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409132734624647298e+01,4.511899884698987080e+02,4.836602451973987193e+00,6.928203299376701096e+00,-1.632830924090464542e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409277072190505464e+01,4.511998554589728201e+02,4.834976866968274223e+00,6.928203299376701096e+00,-1.634497590757131302e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409421409756363630e+01,4.512097221769790849e+02,4.833349637486968220e+00,6.928203299376701096e+00,-1.636164257423798063e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409565747322221796e+01,4.512195886236434035e+02,4.831720763575268585e+00,6.928203299376701096e+00,-1.637830924090464824e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409710084888079962e+01,4.512294547986916768e+02,4.830090245278422678e+00,6.928203299376701096e+00,-1.639497590757131584e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409854422453938128e+01,4.512393207018499197e+02,4.828458082641722271e+00,6.928203299376701096e+00,-1.641164257423798345e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.409998760019796293e+01,4.512491863328440331e+02,4.826824275710505319e+00,6.928203299376701096e+00,-1.642830924090465106e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.410143097585654459e+01,4.512590516913999181e+02,4.825188824530155962e+00,6.928203299376701096e+00,-1.644497590757131866e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.410287435151512625e+01,4.512689167772435894e+02,4.823551729146102751e+00,6.928203299376701096e+00,-1.646164257423798627e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.410431772717370791e+01,4.512787815901010617e+02,4.821912989603820421e+00,6.928203299376701096e+00,-1.647830924090465388e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.410576110283228957e+01,4.512886461296982361e+02,4.820272605948829892e+00,6.928203299376701096e+00,-1.649497590757132148e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.410720447849087122e+01,4.512985103957611273e+02,4.818630578226696493e+00,6.928203299376701096e+00,-1.651164257423798909e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.410864785414945288e+01,4.513083743880157499e+02,4.816986906483033515e+00,6.928203299376701096e+00,-1.652830924090465670e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411009122980803454e+01,4.513182381061880619e+02,4.815341590763497770e+00,6.928203299376701096e+00,-1.654497590757132430e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411153460546661620e+01,4.513281015500040780e+02,4.813694631113792255e+00,6.928203299376701096e+00,-1.656164257423799191e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411297798112519786e+01,4.513379647191898698e+02,4.812046027579666152e+00,6.928203299376701096e+00,-1.657830924090465952e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411442135678377952e+01,4.513478276134713951e+02,4.810395780206913940e+00,6.928203299376701096e+00,-1.659497590757132712e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411586473244236117e+01,4.513576902325747255e+02,4.808743889041376285e+00,6.928203299376701096e+00,-1.661164257423799473e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411730810810094283e+01,4.513675525762258758e+02,4.807090354128938259e+00,6.928203299376701096e+00,-1.662830924090466234e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.411875148375952449e+01,4.513774146441509174e+02,4.805435175515532009e+00,6.928203299376701096e+00,-1.664497590757132994e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412019485941810615e+01,4.513872764360758651e+02,4.803778353247134092e+00,6.928203299376701096e+00,-1.666164257423799755e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412163823507668781e+01,4.513971379517267906e+02,4.802119887369768136e+00,6.928203299376701096e+00,-1.667830924090466516e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412308161073526946e+01,4.514069991908297652e+02,4.800459777929502181e+00,6.928203299376701096e+00,-1.669497590757133276e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412452498639385112e+01,4.514168601531108607e+02,4.798798024972450449e+00,6.928203299376701096e+00,-1.671164257423800037e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412596836205243278e+01,4.514267208382962053e+02,4.797134628544772461e+00,6.928203299376701096e+00,-1.672830924090466798e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412741173771101444e+01,4.514365812461118708e+02,4.795469588692673923e+00,6.928203299376701096e+00,-1.674497590757133558e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.412885511336959610e+01,4.514464413762839285e+02,4.793802905462405839e+00,6.928203299376701096e+00,-1.676164257423800319e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413029848902817776e+01,4.514563012285385071e+02,4.792134578900265396e+00,6.928203299376701096e+00,-1.677830924090467080e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413174186468675941e+01,4.514661608026017348e+02,4.790464609052594191e+00,6.928203299376701096e+00,-1.679497590757133840e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413318524034534107e+01,4.514760200981996832e+02,4.788792995965780896e+00,6.928203299376701096e+00,-1.681164257423800601e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413462861600392273e+01,4.514858791150585375e+02,4.787119739686259479e+00,6.928203299376701096e+00,-1.682830924090467362e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413607199166250439e+01,4.514957378529044263e+02,4.785444840260508315e+00,6.928203299376701096e+00,-1.684497590757134122e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413751536732108605e+01,4.515055963114634778e+02,4.783768297735052855e+00,6.928203299376701096e+00,-1.686164257423800883e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.413895874297966770e+01,4.515154544904618206e+02,4.782090112156463846e+00,6.928203299376701096e+00,-1.687830924090467644e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414040211863824936e+01,4.515253123896256966e+02,4.780410283571357333e+00,6.928203299376701096e+00,-1.689497590757134404e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414184549429683102e+01,4.515351700086811775e+02,4.778728812026395545e+00,6.928203299376701096e+00,-1.691164257423801165e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414328886995541268e+01,4.515450273473545053e+02,4.777045697568286009e+00,6.928203299376701096e+00,-1.692830924090467926e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414473224561399434e+01,4.515548844053718653e+02,4.775360940243781549e+00,6.928203299376701096e+00,-1.694497590757134686e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414617562127257600e+01,4.515647411824594428e+02,4.773674540099681174e+00,6.928203299376701096e+00,-1.696164257423801447e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414761899693115765e+01,4.515745976783434230e+02,4.771986497182830078e+00,6.928203299376701096e+00,-1.697830924090468208e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.414906237258973931e+01,4.515844538927500480e+02,4.770296811540116977e+00,6.928203299376701096e+00,-1.699497590757134968e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415050574824832097e+01,4.515943098254055030e+02,4.768605483218478547e+00,6.928203299376701096e+00,-1.701164257423801729e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415194912390690263e+01,4.516041654760359734e+02,4.766912512264895874e+00,6.928203299376701096e+00,-1.702830924090468490e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415339249956548429e+01,4.516140208443677579e+02,4.765217898726396228e+00,6.928203299376701096e+00,-1.704497590757135250e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415483587522406594e+01,4.516238759301270989e+02,4.763521642650051291e+00,6.928203299376701096e+00,-1.706164257423802011e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415627925088264760e+01,4.516337307330401813e+02,4.761823744082979815e+00,6.928203299376701096e+00,-1.707830924090468772e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415772262654122926e+01,4.516435852528333044e+02,4.760124203072345850e+00,6.928203299376701096e+00,-1.709497590757135532e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.415916600219981092e+01,4.516534394892327100e+02,4.758423019665358744e+00,6.928203299376701096e+00,-1.711164257423802293e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416060937785839258e+01,4.516632934419646972e+02,4.756720193909273142e+00,6.928203299376701096e+00,-1.712830924090469054e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416205275351697424e+01,4.516731471107555649e+02,4.755015725851390762e+00,6.928203299376701096e+00,-1.714497590757135814e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416349612917555589e+01,4.516830004953315552e+02,4.753309615539056843e+00,6.928203299376701096e+00,-1.716164257423802575e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416493950483413755e+01,4.516928535954189670e+02,4.751601863019663696e+00,6.928203299376701096e+00,-1.717830924090469336e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416638288049271921e+01,4.517027064107440992e+02,4.749892468340649820e+00,6.928203299376701096e+00,-1.719497590757136096e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416782625615130087e+01,4.517125589410333077e+02,4.748181431549497233e+00,6.928203299376701096e+00,-1.721164257423802857e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.416926963180988253e+01,4.517224111860128346e+02,4.746468752693735027e+00,6.928203299376701096e+00,-1.722830924090469618e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417071300746846418e+01,4.517322631454090924e+02,4.744754431820937590e+00,6.928203299376701096e+00,-1.724497590757136378e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417215638312704584e+01,4.517421148189483802e+02,4.743038468978725497e+00,6.928203299376701096e+00,-1.726164257423803139e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417359975878562750e+01,4.517519662063569967e+02,4.741320864214763731e+00,6.928203299376701096e+00,-1.727830924090469900e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417504313444420916e+01,4.517618173073613548e+02,4.739601617576763459e+00,6.928203299376701096e+00,-1.729497590757136660e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417648651010279082e+01,4.517716681216877532e+02,4.737880729112482037e+00,6.928203299376701096e+00,-1.731164257423803421e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417792988576137247e+01,4.517815186490626047e+02,4.736158198869722113e+00,6.928203299376701096e+00,-1.732830924090470182e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.417937326141995413e+01,4.517913688892122650e+02,4.734434026896330749e+00,6.928203299376701096e+00,-1.734497590757136942e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418081663707853579e+01,4.518012188418631467e+02,4.732708213240202078e+00,6.928203299376701096e+00,-1.736164257423803703e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418226001273711745e+01,4.518110685067416057e+02,4.730980757949275528e+00,6.928203299376701096e+00,-1.737830924090470464e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418370338839569911e+01,4.518209178835740545e+02,4.729251661071536716e+00,6.928203299376701096e+00,-1.739497590757137224e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418514676405428077e+01,4.518307669720869058e+02,4.727520922655014779e+00,6.928203299376701096e+00,-1.741164257423803985e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418659013971286242e+01,4.518406157720065153e+02,4.725788542747786813e+00,6.928203299376701096e+00,-1.742830924090470746e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418803351537144408e+01,4.518504642830593525e+02,4.724054521397973438e+00,6.928203299376701096e+00,-1.744497590757137506e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.418947689103002574e+01,4.518603125049718869e+02,4.722318858653742346e+00,6.928203299376701096e+00,-1.746164257423804267e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419092026668860740e+01,4.518701604374705312e+02,4.720581554563306526e+00,6.928203299376701096e+00,-1.747830924090471028e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419236364234718906e+01,4.518800080802816979e+02,4.718842609174925151e+00,6.928203299376701096e+00,-1.749497590757137788e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419380701800577071e+01,4.518898554331318564e+02,4.717102022536900918e+00,6.928203299376701096e+00,-1.751164257423804549e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419525039366435237e+01,4.518997024957474764e+02,4.715359794697584483e+00,6.928203299376701096e+00,-1.752830924090471310e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419669376932293403e+01,4.519095492678550272e+02,4.713615925705370913e+00,6.928203299376701096e+00,-1.754497590757138070e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419813714498151569e+01,4.519193957491809783e+02,4.711870415608700569e+00,6.928203299376701096e+00,-1.756164257423804831e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.419958052064009735e+01,4.519292419394518561e+02,4.710123264456059999e+00,6.928203299376701096e+00,-1.757830924090471592e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420102389629867901e+01,4.519390878383940731e+02,4.708374472295981050e+00,6.928203299376701096e+00,-1.759497590757138352e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420246727195726066e+01,4.519489334457342125e+02,4.706624039177041752e+00,6.928203299376701096e+00,-1.761164257423805113e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420391064761584232e+01,4.519587787611987437e+02,4.704871965147864543e+00,6.928203299376701096e+00,-1.762830924090471874e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420535402327442398e+01,4.519686237845141932e+02,4.703118250257118937e+00,6.928203299376701096e+00,-1.764497590757138634e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420679739893300564e+01,4.519784685154070871e+02,4.701362894553518856e+00,6.928203299376701096e+00,-1.766164257423805395e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420824077459158730e+01,4.519883129536040087e+02,4.699605898085823519e+00,6.928203299376701096e+00,-1.767830924090472156e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.420968415025016895e+01,4.519981570988314274e+02,4.697847260902839217e+00,6.928203299376701096e+00,-1.769497590757138916e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421112752590875061e+01,4.520080009508159264e+02,4.696086983053416652e+00,6.928203299376701096e+00,-1.771164257423805677e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421257090156733227e+01,4.520178445092840889e+02,4.694325064586452712e+00,6.928203299376701096e+00,-1.772830924090472438e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421401427722591393e+01,4.520276877739624410e+02,4.692561505550889578e+00,6.928203299376701096e+00,-1.774497590757139198e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421545765288449559e+01,4.520375307445775661e+02,4.690796305995714732e+00,6.928203299376701096e+00,-1.776164257423805959e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421690102854307725e+01,4.520473734208560472e+02,4.689029465969961841e+00,6.928203299376701096e+00,-1.777830924090472720e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421834440420165890e+01,4.520572158025245244e+02,4.687260985522708978e+00,6.928203299376701096e+00,-1.779497590757139480e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.421978777986024056e+01,4.520670578893095239e+02,4.685490864703081293e+00,6.928203299376701096e+00,-1.781164257423806241e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422123115551882222e+01,4.520768996809377427e+02,4.683719103560249231e+00,6.928203299376701096e+00,-1.782830924090473002e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422267453117740388e+01,4.520867411771357069e+02,4.681945702143427646e+00,6.928203299376701096e+00,-1.784497590757139762e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422411790683598554e+01,4.520965823776301136e+02,4.680170660501877578e+00,6.928203299376701096e+00,-1.786164257423806523e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422556128249456719e+01,4.521064232821475457e+02,4.678393978684906251e+00,6.928203299376701096e+00,-1.787830924090473284e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422700465815314885e+01,4.521162638904146434e+02,4.676615656741866189e+00,6.928203299376701096e+00,-1.789497590757140044e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422844803381173051e+01,4.521261042021581034e+02,4.674835694722154322e+00,6.928203299376701096e+00,-1.791164257423806805e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.422989140947031217e+01,4.521359442171045657e+02,4.673054092675214655e+00,6.928203299376701096e+00,-1.792830924090473566e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423133478512889383e+01,4.521457839349806704e+02,4.671270850650535600e+00,6.928203299376701096e+00,-1.794497590757140326e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423277816078747549e+01,4.521556233555131143e+02,4.669485968697652645e+00,6.928203299376701096e+00,-1.796164257423807087e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423422153644605714e+01,4.521654624784285943e+02,4.667699446866144797e+00,6.928203299376701096e+00,-1.797830924090473848e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423566491210463880e+01,4.521753013034537503e+02,4.665911285205638137e+00,6.928203299376701096e+00,-1.799497590757140608e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423710828776322046e+01,4.521851398303153360e+02,4.664121483765804044e+00,6.928203299376701096e+00,-1.801164257423807369e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423855166342180212e+01,4.521949780587400483e+02,4.662330042596359192e+00,6.928203299376701096e+00,-1.802830924090474130e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.423999503908038378e+01,4.522048159884545839e+02,4.660536961747065554e+00,6.928203299376701096e+00,-1.804497590757140890e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.424143841473896543e+01,4.522146536191856399e+02,4.658742241267730400e+00,6.928203299376701096e+00,-1.806164257423807651e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.424288179039754709e+01,4.522244909506600266e+02,4.656945881208208071e+00,6.928203299376701096e+00,-1.807830924090474412e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.424432516605612875e+01,4.522343279826044409e+02,4.655147881618397321e+00,6.928203299376701096e+00,-1.809497590757141172e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.424576854171471041e+01,4.522441647147456365e+02,4.653348242548242197e+00,6.928203299376701096e+00,-1.811164257423807933e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.424721191737329207e+01,4.522540011468103671e+02,4.651546964047732935e+00,6.928203299376701096e+00,-1.812830924090474694e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.424865529303187373e+01,4.522638372785253864e+02,4.649744046166904177e+00,6.928203299376701096e+00,-1.814497590757141454e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425009866869045538e+01,4.522736731096174481e+02,4.647939488955837639e+00,6.928203299376701096e+00,-1.816164257423808215e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425154204434903704e+01,4.522835086398133626e+02,4.646133292464660336e+00,6.928203299376701096e+00,-1.817830924090474976e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425298542000761870e+01,4.522933438688399406e+02,4.644325456743543690e+00,6.928203299376701096e+00,-1.819497590757141736e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425442879566620036e+01,4.523031787964239925e+02,4.642515981842706196e+00,6.928203299376701096e+00,-1.821164257423808497e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425587217132478202e+01,4.523130134222922720e+02,4.640704867812410761e+00,6.928203299376701096e+00,-1.822830924090475258e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425731554698336367e+01,4.523228477461716466e+02,4.638892114702965586e+00,6.928203299376701096e+00,-1.824497590757142018e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.425875892264194533e+01,4.523326817677889267e+02,4.637077722564725057e+00,6.928203299376701096e+00,-1.826164257423808779e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426020229830052699e+01,4.523425154868709228e+02,4.635261691448088861e+00,6.928203299376701096e+00,-1.827830924090475540e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426164567395910865e+01,4.523523489031445024e+02,4.633444021403502866e+00,6.928203299376701096e+00,-1.829497590757142300e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426308904961769031e+01,4.523621820163364760e+02,4.631624712481457351e+00,6.928203299376701096e+00,-1.831164257423809061e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426453242527627197e+01,4.523720148261737108e+02,4.629803764732489668e+00,6.928203299376701096e+00,-1.832830924090475821e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426597580093485362e+01,4.523818473323831313e+02,4.627981178207180690e+00,6.928203299376701096e+00,-1.834497590757142582e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426741917659343528e+01,4.523916795346915478e+02,4.626156952956158364e+00,6.928203299376701096e+00,-1.836164257423809343e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.426886255225201694e+01,4.524015114328258846e+02,4.624331089030095043e+00,6.928203299376701096e+00,-1.837830924090476103e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427030592791059860e+01,4.524113430265130091e+02,4.622503586479709270e+00,6.928203299376701096e+00,-1.839497590757142864e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427174930356918026e+01,4.524211743154797887e+02,4.620674445355765769e+00,6.928203299376701096e+00,-1.841164257423809625e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427319267922776191e+01,4.524310052994532043e+02,4.618843665709072788e+00,6.928203299376701096e+00,-1.842830924090476385e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427463605488634357e+01,4.524408359781601234e+02,4.617011247590486533e+00,6.928203299376701096e+00,-1.844497590757143146e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427607943054492523e+01,4.524506663513274702e+02,4.615177191050906735e+00,6.928203299376701096e+00,-1.846164257423809907e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427752280620350689e+01,4.524604964186822258e+02,4.613341496141279308e+00,6.928203299376701096e+00,-1.847830924090476667e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.427896618186208855e+01,4.524703261799513143e+02,4.611504162912596350e+00,6.928203299376701096e+00,-1.849497590757143428e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428040955752067021e+01,4.524801556348616600e+02,4.609665191415894370e+00,6.928203299376701096e+00,-1.851164257423810189e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428185293317925186e+01,4.524899847831402440e+02,4.607824581702256950e+00,6.928203299376701096e+00,-1.852830924090476949e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428329630883783352e+01,4.524998136245139904e+02,4.605982333822811192e+00,6.928203299376701096e+00,-1.854497590757143710e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428473968449641518e+01,4.525096421587099371e+02,4.604138447828730385e+00,6.928203299376701096e+00,-1.856164257423810471e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428618306015499684e+01,4.525194703854550653e+02,4.602292923771234001e+00,6.928203299376701096e+00,-1.857830924090477231e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428762643581357850e+01,4.525292983044762991e+02,4.600445761701586811e+00,6.928203299376701096e+00,-1.859497590757143992e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.428906981147216015e+01,4.525391259155007333e+02,4.598596961671098882e+00,6.928203299376701096e+00,-1.861164257423810753e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429051318713074181e+01,4.525489532182552921e+02,4.596746523731125578e+00,6.928203299376701096e+00,-1.862830924090477513e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429195656278932347e+01,4.525587802124670702e+02,4.594894447933067561e+00,6.928203299376701096e+00,-1.864497590757144274e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429339993844790513e+01,4.525686068978630487e+02,4.593040734328371677e+00,6.928203299376701096e+00,-1.866164257423811035e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429484331410648679e+01,4.525784332741702656e+02,4.591185382968530071e+00,6.928203299376701096e+00,-1.867830924090477795e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429628668976506845e+01,4.525882593411158155e+02,4.589328393905081072e+00,6.928203299376701096e+00,-1.869497590757144556e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429773006542365010e+01,4.525980850984266795e+02,4.587469767189606529e+00,6.928203299376701096e+00,-1.871164257423811317e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.429917344108223176e+01,4.526079105458300091e+02,4.585609502873735366e+00,6.928203299376701096e+00,-1.872830924090478077e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430061681674081342e+01,4.526177356830527856e+02,4.583747601009141803e+00,6.928203299376701096e+00,-1.874497590757144838e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430206019239939508e+01,4.526275605098221604e+02,4.581884061647544470e+00,6.928203299376701096e+00,-1.876164257423811599e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430350356805797674e+01,4.526373850258651714e+02,4.580018884840709070e+00,6.928203299376701096e+00,-1.877830924090478359e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430494694371655839e+01,4.526472092309089135e+02,4.578152070640446603e+00,6.928203299376701096e+00,-1.879497590757145120e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430639031937514005e+01,4.526570331246805381e+02,4.576283619098611588e+00,6.928203299376701096e+00,-1.881164257423811881e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430783369503372171e+01,4.526668567069071401e+02,4.574413530267106509e+00,6.928203299376701096e+00,-1.882830924090478641e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.430927707069230337e+01,4.526766799773158141e+02,4.572541804197878257e+00,6.928203299376701096e+00,-1.884497590757145402e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431072044635088503e+01,4.526865029356337118e+02,4.570668440942919020e+00,6.928203299376701096e+00,-1.886164257423812163e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431216382200946668e+01,4.526963255815879847e+02,4.568793440554266283e+00,6.928203299376701096e+00,-1.887830924090478923e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431360719766804834e+01,4.527061479149057277e+02,4.566916803084003718e+00,6.928203299376701096e+00,-1.889497590757145684e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431505057332663000e+01,4.527159699353141491e+02,4.565038528584260291e+00,6.928203299376701096e+00,-1.891164257423812445e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431649394898521166e+01,4.527257916425404005e+02,4.563158617107210269e+00,6.928203299376701096e+00,-1.892830924090479205e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431793732464379332e+01,4.527356130363116904e+02,4.561277068705073212e+00,6.928203299376701096e+00,-1.894497590757145966e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.431938070030237498e+01,4.527454341163551703e+02,4.559393883430114869e+00,6.928203299376701096e+00,-1.896164257423812727e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432082407596095663e+01,4.527552548823980487e+02,4.557509061334645395e+00,6.928203299376701096e+00,-1.897830924090479487e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432226745161953829e+01,4.527650753341674772e+02,4.555622602471021132e+00,6.928203299376701096e+00,-1.899497590757146248e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432371082727811995e+01,4.527748954713907210e+02,4.553734506891643719e+00,6.928203299376701096e+00,-1.901164257423813009e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432515420293670161e+01,4.527847152937949886e+02,4.551844774648960090e+00,6.928203299376701096e+00,-1.902830924090479769e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432659757859528327e+01,4.527945348011074884e+02,4.549953405795463368e+00,6.928203299376701096e+00,-1.904497590757146530e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432804095425386492e+01,4.528043539930554289e+02,4.548060400383691082e+00,6.928203299376701096e+00,-1.906164257423813291e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.432948432991244658e+01,4.528141728693661321e+02,4.546165758466226947e+00,6.928203299376701096e+00,-1.907830924090480051e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433092770557102824e+01,4.528239914297668065e+02,4.544269480095699087e+00,6.928203299376701096e+00,-1.909497590757146812e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433237108122960990e+01,4.528338096739847174e+02,4.542371565324782701e+00,6.928203299376701096e+00,-1.911164257423813573e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433381445688819156e+01,4.528436276017471300e+02,4.540472014206197393e+00,6.928203299376701096e+00,-1.912830924090480333e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433525783254677322e+01,4.528534452127813097e+02,4.538570826792708957e+00,6.928203299376701096e+00,-1.914497590757147094e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433670120820535487e+01,4.528632625068145785e+02,4.536668003137127592e+00,6.928203299376701096e+00,-1.916164257423813855e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433814458386393653e+01,4.528730794835742017e+02,4.534763543292309684e+00,6.928203299376701096e+00,-1.917830924090480615e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.433958795952251819e+01,4.528828961427875583e+02,4.532857447311156918e+00,6.928203299376701096e+00,-1.919497590757147376e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434103133518109985e+01,4.528927124841818568e+02,4.530949715246616272e+00,6.928203299376701096e+00,-1.921164257423814137e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434247471083968151e+01,4.529025285074844760e+02,4.529040347151680912e+00,6.928203299376701096e+00,-1.922830924090480897e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434391808649826316e+01,4.529123442124227950e+02,4.527129343079388413e+00,6.928203299376701096e+00,-1.924497590757147658e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434536146215684482e+01,4.529221595987240789e+02,4.525216703082821645e+00,6.928203299376701096e+00,-1.926164257423814419e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434680483781542648e+01,4.529319746661157069e+02,4.523302427215110555e+00,6.928203299376701096e+00,-1.927830924090481179e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434824821347400814e+01,4.529417894143250578e+02,4.521386515529428607e+00,6.928203299376701096e+00,-1.929497590757147940e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.434969158913258980e+01,4.529516038430794538e+02,4.519468968078995452e+00,6.928203299376701096e+00,-1.931164257423814701e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435113496479117146e+01,4.529614179521063306e+02,4.517549784917076927e+00,6.928203299376701096e+00,-1.932830924090481461e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435257834044975311e+01,4.529712317411330105e+02,4.515628966096983277e+00,6.928203299376701096e+00,-1.934497590757148222e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435402171610833477e+01,4.529810452098869291e+02,4.513706511672070931e+00,6.928203299376701096e+00,-1.936164257423814983e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435546509176691643e+01,4.529908583580954655e+02,4.511782421695741618e+00,6.928203299376701096e+00,-1.937830924090481743e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435690846742549809e+01,4.530006711854860555e+02,4.509856696221441474e+00,6.928203299376701096e+00,-1.939497590757148504e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435835184308407975e+01,4.530104836917861348e+02,4.507929335302663709e+00,6.928203299376701096e+00,-1.941164257423815265e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.435979521874266140e+01,4.530202958767230825e+02,4.506000338992945942e+00,6.928203299376701096e+00,-1.942830924090482025e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436123859440124306e+01,4.530301077400243912e+02,4.504069707345871088e+00,6.928203299376701096e+00,-1.944497590757148786e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436268197005982472e+01,4.530399192814174967e+02,4.502137440415067360e+00,6.928203299376701096e+00,-1.946164257423815547e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436412534571840638e+01,4.530497305006298348e+02,4.500203538254210045e+00,6.928203299376701096e+00,-1.947830924090482307e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436556872137698804e+01,4.530595413973888412e+02,4.498268000917017950e+00,6.928203299376701096e+00,-1.949497590757149068e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436701209703556970e+01,4.530693519714220656e+02,4.496330828457256068e+00,6.928203299376701096e+00,-1.951164257423815829e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436845547269415135e+01,4.530791622224569437e+02,4.494392020928734688e+00,6.928203299376701096e+00,-1.952830924090482589e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.436989884835273301e+01,4.530889721502209682e+02,4.492451578385309396e+00,6.928203299376701096e+00,-1.954497590757149350e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.437134222401131467e+01,4.530987817544416885e+02,4.490509500880881966e+00,6.928203299376701096e+00,-1.956164257423816111e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.437278559966989633e+01,4.531085910348465404e+02,4.488565788469398576e+00,6.928203299376701096e+00,-1.957830924090482871e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.437422897532847799e+01,4.531183999911631304e+02,4.486620441204850707e+00,6.928203299376701096e+00,-1.959497590757149632e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.437567235098705964e+01,4.531282086231188941e+02,4.484673459141276908e+00,6.928203299376701096e+00,-1.961164257423816393e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.437711572664564130e+01,4.531380169304414380e+02,4.482724842332759252e+00,6.928203299376701096e+00,-1.962830924090483153e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.437855910230422296e+01,4.531478249128583116e+02,4.480774590833425997e+00,6.928203299376701096e+00,-1.964497590757149914e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438000247796280462e+01,4.531576325700970074e+02,4.478822704697451584e+00,6.928203299376701096e+00,-1.966164257423816675e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438144585362138628e+01,4.531674399018851318e+02,4.476869183979053979e+00,6.928203299376701096e+00,-1.967830924090483435e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438288922927996794e+01,4.531772469079502912e+02,4.474914028732498217e+00,6.928203299376701096e+00,-1.969497590757150196e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438433260493854959e+01,4.531870535880200350e+02,4.472957239012093744e+00,6.928203299376701096e+00,-1.971164257423816957e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438577598059713125e+01,4.531968599418219696e+02,4.470998814872196192e+00,6.928203299376701096e+00,-1.972830924090483717e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438721935625571291e+01,4.532066659690836445e+02,4.469038756367206489e+00,6.928203299376701096e+00,-1.974497590757150478e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.438866273191429457e+01,4.532164716695327229e+02,4.467077063551570859e+00,6.928203299376701096e+00,-1.976164257423817239e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439010610757287623e+01,4.532262770428968111e+02,4.465113736479779938e+00,6.928203299376701096e+00,-1.977830924090483999e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439154948323145788e+01,4.532360820889035153e+02,4.463148775206371432e+00,6.928203299376701096e+00,-1.979497590757150760e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439299285889003954e+01,4.532458868072804989e+02,4.461182179785926571e+00,6.928203299376701096e+00,-1.981164257423817521e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439443623454862120e+01,4.532556911977554250e+02,4.459213950273073657e+00,6.928203299376701096e+00,-1.982830924090484281e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439587961020720286e+01,4.532654952600559000e+02,4.457244086722486287e+00,6.928203299376701096e+00,-1.984497590757151042e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439732298586578452e+01,4.532752989939096437e+02,4.455272589188881582e+00,6.928203299376701096e+00,-1.986164257423817803e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.439876636152436618e+01,4.532851023990443196e+02,4.453299457727024624e+00,6.928203299376701096e+00,-1.987830924090484563e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440020973718294783e+01,4.532949054751875906e+02,4.451324692391724014e+00,6.928203299376701096e+00,-1.989497590757151324e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440165311284152949e+01,4.533047082220671200e+02,4.449348293237834540e+00,6.928203299376701096e+00,-1.991164257423818085e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440309648850011115e+01,4.533145106394106847e+02,4.447370260320255397e+00,6.928203299376701096e+00,-1.992830924090484845e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440453986415869281e+01,4.533243127269459478e+02,4.445390593693932857e+00,6.928203299376701096e+00,-1.994497590757151606e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440598323981727447e+01,4.533341144844006294e+02,4.443409293413857597e+00,6.928203299376701096e+00,-1.996164257423818367e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440742661547585612e+01,4.533439159115024495e+02,4.441426359535065593e+00,6.928203299376701096e+00,-1.997830924090485127e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.440886999113443778e+01,4.533537170079791849e+02,4.439441792112638119e+00,6.928203299376701096e+00,-1.999497590757151888e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441031336679301944e+01,4.533635177735585557e+02,4.437455591201701743e+00,6.928203299376701096e+00,-2.001164257423818649e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441175674245160110e+01,4.533733182079682820e+02,4.435467756857429222e+00,6.928203299376701096e+00,-2.002830924090485409e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441320011811018276e+01,4.533831183109361973e+02,4.433478289135038608e+00,6.928203299376701096e+00,-2.004497590757152170e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441464349376876442e+01,4.533929180821900218e+02,4.431487188089792362e+00,6.928203299376701096e+00,-2.006164257423818931e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441608686942734607e+01,4.534027175214575891e+02,4.429494453776998242e+00,6.928203299376701096e+00,-2.007830924090485691e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441753024508592773e+01,4.534125166284666761e+02,4.427500086252011080e+00,6.928203299376701096e+00,-2.009497590757152452e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.441897362074450939e+01,4.534223154029450598e+02,4.425504085570229229e+00,6.928203299376701096e+00,-2.011164257423819213e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442041699640309105e+01,4.534321138446205737e+02,4.423506451787097227e+00,6.928203299376701096e+00,-2.012830924090485973e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442186037206167271e+01,4.534419119532210516e+02,4.421507184958105796e+00,6.928203299376701096e+00,-2.014497590757152734e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442330374772025436e+01,4.534517097284742704e+02,4.419506285138789181e+00,6.928203299376701096e+00,-2.016164257423819495e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442474712337883602e+01,4.534615071701081206e+02,4.417503752384727811e+00,6.928203299376701096e+00,-2.017830924090486255e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442619049903741768e+01,4.534713042778504359e+02,4.415499586751548300e+00,6.928203299376701096e+00,-2.019497590757153016e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442763387469599934e+01,4.534811010514291070e+02,4.413493788294921671e+00,6.928203299376701096e+00,-2.021164257423819777e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.442907725035458100e+01,4.534908974905719674e+02,4.411486357070564246e+00,6.928203299376701096e+00,-2.022830924090486537e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443052062601316265e+01,4.535006935950069078e+02,4.409477293134238529e+00,6.928203299376701096e+00,-2.024497590757153298e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443196400167174431e+01,4.535104893644617619e+02,4.407466596541751436e+00,6.928203299376701096e+00,-2.026164257423820059e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443340737733032597e+01,4.535202847986644770e+02,4.405454267348956066e+00,6.928203299376701096e+00,-2.027830924090486819e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443485075298890763e+01,4.535300798973429437e+02,4.403440305611749928e+00,6.928203299376701096e+00,-2.029497590757153580e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443629412864748929e+01,4.535398746602251094e+02,4.401424711386076716e+00,6.928203299376701096e+00,-2.031164257423820341e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443773750430607095e+01,4.535496690870388647e+02,4.399407484727924533e+00,6.928203299376701096e+00,-2.032830924090487101e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.443918087996465260e+01,4.535594631775121002e+02,4.397388625693328557e+00,6.928203299376701096e+00,-2.034497590757153862e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444062425562323426e+01,4.535692569313728200e+02,4.395368134338367483e+00,6.928203299376701096e+00,-2.036164257423820623e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444206763128181592e+01,4.535790503483489715e+02,4.393346010719166195e+00,6.928203299376701096e+00,-2.037830924090487383e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444351100694039758e+01,4.535888434281685022e+02,4.391322254891894872e+00,6.928203299376701096e+00,-2.039497590757154144e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444495438259897924e+01,4.535986361705593595e+02,4.389296866912768991e+00,6.928203299376701096e+00,-2.041164257423820905e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444639775825756089e+01,4.536084285752495475e+02,4.387269846838049325e+00,6.928203299376701096e+00,-2.042830924090487665e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444784113391614255e+01,4.536182206419670706e+02,4.385241194724041947e+00,6.928203299376701096e+00,-2.044497590757154426e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.444928450957472421e+01,4.536280123704398761e+02,4.383210910627098222e+00,6.928203299376701096e+00,-2.046164257423821187e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445072788523330587e+01,4.536378037603960252e+02,4.381178994603614818e+00,6.928203299376701096e+00,-2.047830924090487947e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445217126089188753e+01,4.536475948115635219e+02,4.379145446710033696e+00,6.928203299376701096e+00,-2.049497590757154708e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445361463655046919e+01,4.536573855236703707e+02,4.377110267002843003e+00,6.928203299376701096e+00,-2.051164257423821469e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445505801220905084e+01,4.536671758964446326e+02,4.375073455538575296e+00,6.928203299376701096e+00,-2.052830924090488229e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445650138786763250e+01,4.536769659296143686e+02,4.373035012373808428e+00,6.928203299376701096e+00,-2.054497590757154990e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445794476352621416e+01,4.536867556229075831e+02,4.370994937565165550e+00,6.928203299376701096e+00,-2.056164257423821751e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.445938813918479582e+01,4.536965449760523370e+02,4.368953231169315998e+00,6.928203299376701096e+00,-2.057830924090488511e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446083151484337748e+01,4.537063339887767484e+02,4.366909893242973517e+00,6.928203299376701096e+00,-2.059497590757155272e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446227489050195913e+01,4.537161226608088782e+02,4.364864923842897149e+00,6.928203299376701096e+00,-2.061164257423822033e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446371826616054079e+01,4.537259109918768445e+02,4.362818323025892120e+00,6.928203299376701096e+00,-2.062830924090488793e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446516164181912245e+01,4.537356989817087083e+02,4.360770090848808067e+00,6.928203299376701096e+00,-2.064497590757155554e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446660501747770411e+01,4.537454866300325875e+02,4.358720227368540812e+00,6.928203299376701096e+00,-2.066164257423822315e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446804839313628577e+01,4.537552739365766570e+02,4.356668732642030584e+00,6.928203299376701096e+00,-2.067830924090489075e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.446949176879486743e+01,4.537650609010689777e+02,4.354615606726263799e+00,6.928203299376701096e+00,-2.069497590757155836e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447093514445344908e+01,4.537748475232377245e+02,4.352560849678271282e+00,6.928203299376701096e+00,-2.071164257423822597e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447237852011203074e+01,4.537846338028110154e+02,4.350504461555130042e+00,6.928203299376701096e+00,-2.072830924090489357e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447382189577061240e+01,4.537944197395170818e+02,4.348446442413961499e+00,6.928203299376701096e+00,-2.074497590757156118e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447526527142919406e+01,4.538042053330840417e+02,4.346386792311933256e+00,6.928203299376701096e+00,-2.076164257423822879e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447670864708777572e+01,4.538139905832400700e+02,4.344325511306258214e+00,6.928203299376701096e+00,-2.077830924090489639e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447815202274635737e+01,4.538237754897133414e+02,4.342262599454192795e+00,6.928203299376701096e+00,-2.079497590757156400e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.447959539840493903e+01,4.538335600522320874e+02,4.340198056813041383e+00,6.928203299376701096e+00,-2.081164257423823161e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448103877406352069e+01,4.538433442705244829e+02,4.338131883440151881e+00,6.928203299376701096e+00,-2.082830924090489921e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448248214972210235e+01,4.538531281443187595e+02,4.336064079392918380e+00,6.928203299376701096e+00,-2.084497590757156682e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448392552538068401e+01,4.538629116733431488e+02,4.333994644728779377e+00,6.928203299376701096e+00,-2.086164257423823443e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448536890103926567e+01,4.538726948573258824e+02,4.331923579505219557e+00,6.928203299376701096e+00,-2.087830924090490203e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448681227669784732e+01,4.538824776959951919e+02,4.329850883779768012e+00,6.928203299376701096e+00,-2.089497590757156964e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448825565235642898e+01,4.538922601890793658e+02,4.327776557610000019e+00,6.928203299376701096e+00,-2.091164257423823725e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.448969902801501064e+01,4.539020423363066357e+02,4.325700601053535266e+00,6.928203299376701096e+00,-2.092830924090490485e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449114240367359230e+01,4.539118241374052900e+02,4.323623014168039624e+00,6.928203299376701096e+00,-2.094497590757157246e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449258577933217396e+01,4.539216055921035604e+02,4.321543797011224264e+00,6.928203299376701096e+00,-2.096164257423824007e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449402915499075561e+01,4.539313867001297922e+02,4.319462949640844762e+00,6.928203299376701096e+00,-2.097830924090490767e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449547253064933727e+01,4.539411674612122738e+02,4.317380472114701995e+00,6.928203299376701096e+00,-2.099497590757157528e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449691590630791893e+01,4.539509478750793505e+02,4.315296364490643022e+00,6.928203299376701096e+00,-2.101164257423824289e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449835928196650059e+01,4.539607279414593108e+02,4.313210626826559313e+00,6.928203299376701096e+00,-2.102830924090491049e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.449980265762508225e+01,4.539705076600805000e+02,4.311123259180388523e+00,6.928203299376701096e+00,-2.104497590757157810e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450124603328366391e+01,4.539802870306712634e+02,4.309034261610113603e+00,6.928203299376701096e+00,-2.106164257423824571e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450268940894224556e+01,4.539900660529599463e+02,4.306943634173761026e+00,6.928203299376701096e+00,-2.107830924090491331e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450413278460082722e+01,4.539998447266748940e+02,4.304851376929404339e+00,6.928203299376701096e+00,-2.109497590757158092e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450557616025940888e+01,4.540096230515445086e+02,4.302757489935162383e+00,6.928203299376701096e+00,-2.111164257423824853e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450701953591799054e+01,4.540194010272971354e+02,4.300661973249197523e+00,6.928203299376701096e+00,-2.112830924090491613e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450846291157657220e+01,4.540291786536611767e+02,4.298564826929719196e+00,6.928203299376701096e+00,-2.114497590757158374e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.450990628723515385e+01,4.540389559303650344e+02,4.296466051034982137e+00,6.928203299376701096e+00,-2.116164257423825135e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.451134966289373551e+01,4.540487328571371108e+02,4.294365645623284600e+00,6.928203299376701096e+00,-2.117830924090491895e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.451279303855231717e+01,4.540585094337058081e+02,4.292263610752971914e+00,6.928203299376701096e+00,-2.119497590757158656e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.451423641421089883e+01,4.540682856597995851e+02,4.290159946482432929e+00,6.928203299376701096e+00,-2.121164257423825417e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.451567978986948049e+01,4.540780615351469010e+02,4.288054652870103567e+00,6.928203299376701096e+00,-2.122830924090492177e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.451712316552806215e+01,4.540878370594761577e+02,4.285947729974464160e+00,6.928203299376701096e+00,-2.124497590757158938e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.451856654118664380e+01,4.540976122325158144e+02,4.283839177854040337e+00,6.928203299376701096e+00,-2.126164257423825699e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452000991684522546e+01,4.541073870539943869e+02,4.281728996567403023e+00,6.928203299376701096e+00,-2.127830924090492459e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452145329250380712e+01,4.541171615236402772e+02,4.279617186173168442e+00,6.928203299376701096e+00,-2.129497590757159220e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452289666816238878e+01,4.541269356411820581e+02,4.277503746729997225e+00,6.928203299376701096e+00,-2.131164257423825981e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452434004382097044e+01,4.541367094063481318e+02,4.275388678296597078e+00,6.928203299376701096e+00,-2.132830924090492741e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452578341947955209e+01,4.541464828188670708e+02,4.273271980931719227e+00,6.928203299376701096e+00,-2.134497590757159502e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452722679513813375e+01,4.541562558784673911e+02,4.271153654694161084e+00,6.928203299376701096e+00,-2.136164257423826263e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.452867017079671541e+01,4.541660285848776084e+02,4.269033699642764468e+00,6.928203299376701096e+00,-2.137830924090493023e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453011354645529707e+01,4.541758009378262386e+02,4.266912115836417385e+00,6.928203299376701096e+00,-2.139497590757159784e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453155692211387873e+01,4.541855729370418544e+02,4.264788903334053138e+00,6.928203299376701096e+00,-2.141164257423826545e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453300029777246039e+01,4.541953445822529716e+02,4.262664062194649439e+00,6.928203299376701096e+00,-2.142830924090493305e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453444367343104204e+01,4.542051158731882197e+02,4.260537592477230184e+00,6.928203299376701096e+00,-2.144497590757160066e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453588704908962370e+01,4.542148868095761145e+02,4.258409494240863680e+00,6.928203299376701096e+00,-2.146164257423826827e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453733042474820536e+01,4.542246573911452856e+02,4.256279767544663528e+00,6.928203299376701096e+00,-2.147830924090493587e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.453877380040678702e+01,4.542344276176243056e+02,4.254148412447788630e+00,6.928203299376701096e+00,-2.149497590757160348e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454021717606536868e+01,4.542441974887417473e+02,4.252015429009444070e+00,6.928203299376701096e+00,-2.151164257423827109e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454166055172395033e+01,4.542539670042262969e+02,4.249880817288878454e+00,6.928203299376701096e+00,-2.152830924090493869e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454310392738253199e+01,4.542637361638065272e+02,4.247744577345387462e+00,6.928203299376701096e+00,-2.154497590757160630e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454454730304111365e+01,4.542735049672110677e+02,4.245606709238310295e+00,6.928203299376701096e+00,-2.156164257423827391e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454599067869969531e+01,4.542832734141686046e+02,4.243467213027032336e+00,6.928203299376701096e+00,-2.157830924090494151e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454743405435827697e+01,4.542930415044077677e+02,4.241326088770984271e+00,6.928203299376701096e+00,-2.159497590757160912e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.454887743001685863e+01,4.543028092376571863e+02,4.239183336529642077e+00,6.928203299376701096e+00,-2.161164257423827673e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455032080567544028e+01,4.543125766136456036e+02,4.237038956362526143e+00,6.928203299376701096e+00,-2.162830924090494433e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455176418133402194e+01,4.543223436321016493e+02,4.234892948329203044e+00,6.928203299376701096e+00,-2.164497590757161194e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455320755699260360e+01,4.543321102927540664e+02,4.232745312489283762e+00,6.928203299376701096e+00,-2.166164257423827955e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455465093265118526e+01,4.543418765953314846e+02,4.230596048902424577e+00,6.928203299376701096e+00,-2.167830924090494715e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455609430830976692e+01,4.543516425395627039e+02,4.228445157628327067e+00,6.928203299376701096e+00,-2.169497590757161476e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455753768396834857e+01,4.543614081251764105e+02,4.226292638726738993e+00,6.928203299376701096e+00,-2.171164257423828237e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.455898105962693023e+01,4.543711733519012910e+02,4.224138492257452526e+00,6.928203299376701096e+00,-2.172830924090494997e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456042443528551189e+01,4.543809382194661453e+02,4.221982718280305136e+00,6.928203299376701096e+00,-2.174497590757161758e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456186781094409355e+01,4.543907027275997166e+02,4.219825316855178698e+00,6.928203299376701096e+00,-2.176164257423828519e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456331118660267521e+01,4.544004668760308050e+02,4.217666288042001277e+00,6.928203299376701096e+00,-2.177830924090495279e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456475456226125686e+01,4.544102306644880969e+02,4.215505631900746231e+00,6.928203299376701096e+00,-2.179497590757162040e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456619793791983852e+01,4.544199940927004491e+02,4.213343348491431328e+00,6.928203299376701096e+00,-2.181164257423828801e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456764131357842018e+01,4.544297571603966617e+02,4.211179437874120524e+00,6.928203299376701096e+00,-2.182830924090495561e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.456908468923700184e+01,4.544395198673054779e+02,4.209013900108922179e+00,6.928203299376701096e+00,-2.184497590757162322e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457052806489558350e+01,4.544492822131557546e+02,4.206846735255989955e+00,6.928203299376701096e+00,-2.186164257423829083e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457197144055416516e+01,4.544590441976762918e+02,4.204677943375523697e+00,6.928203299376701096e+00,-2.187830924090495843e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457341481621274681e+01,4.544688058205959464e+02,4.202507524527766769e+00,6.928203299376701096e+00,-2.189497590757162604e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457485819187132847e+01,4.544785670816435186e+02,4.200335478773008724e+00,6.928203299376701096e+00,-2.191164257423829365e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457630156752991013e+01,4.544883279805479219e+02,4.198161806171584409e+00,6.928203299376701096e+00,-2.192830924090496125e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457774494318849179e+01,4.544980885170379565e+02,4.195986506783873082e+00,6.928203299376701096e+00,-2.194497590757162886e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.457918831884707345e+01,4.545078486908425361e+02,4.193809580670300186e+00,6.928203299376701096e+00,-2.196164257423829647e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458063169450565510e+01,4.545176085016905745e+02,4.191631027891335570e+00,6.928203299376701096e+00,-2.197830924090496407e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458207507016423676e+01,4.545273679493109285e+02,4.189450848507495273e+00,6.928203299376701096e+00,-2.199497590757163168e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458351844582281842e+01,4.545371270334325118e+02,4.187269042579338851e+00,6.928203299376701096e+00,-2.201164257423829929e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458496182148140008e+01,4.545468857537842382e+02,4.185085610167472936e+00,6.928203299376701096e+00,-2.202830924090496689e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458640519713998174e+01,4.545566441100950215e+02,4.182900551332547678e+00,6.928203299376701096e+00,-2.204497590757163450e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458784857279856340e+01,4.545664021020937753e+02,4.180713866135260304e+00,6.928203299376701096e+00,-2.206164257423830211e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.458929194845714505e+01,4.545761597295094703e+02,4.178525554636350670e+00,6.928203299376701096e+00,-2.207830924090496971e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459073532411572671e+01,4.545859169920710769e+02,4.176335616896605707e+00,6.928203299376701096e+00,-2.209497590757163732e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459217869977430837e+01,4.545956738895075659e+02,4.174144052976857644e+00,6.928203299376701096e+00,-2.211164257423830493e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459362207543289003e+01,4.546054304215478510e+02,4.171950862937982230e+00,6.928203299376701096e+00,-2.212830924090497253e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459506545109147169e+01,4.546151865879209595e+02,4.169756046840902286e+00,6.928203299376701096e+00,-2.214497590757164014e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459650882675005334e+01,4.546249423883559189e+02,4.167559604746584156e+00,6.928203299376701096e+00,-2.216164257423830775e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459795220240863500e+01,4.546346978225816997e+02,4.165361536716041257e+00,6.928203299376701096e+00,-2.217830924090497535e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.459939557806721666e+01,4.546444528903272726e+02,4.163161842810329638e+00,6.928203299376701096e+00,-2.219497590757164296e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460083895372579832e+01,4.546542075913217218e+02,4.160960523090553309e+00,6.928203299376701096e+00,-2.221164257423831057e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460228232938437998e+01,4.546639619252940747e+02,4.158757577617858914e+00,6.928203299376701096e+00,-2.222830924090497817e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460372570504296164e+01,4.546737158919733588e+02,4.156553006453440169e+00,6.928203299376701096e+00,-2.224497590757164578e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460516908070154329e+01,4.546834694910886583e+02,4.154346809658534312e+00,6.928203299376701096e+00,-2.226164257423831339e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460661245636012495e+01,4.546932227223690575e+02,4.152138987294424766e+00,6.928203299376701096e+00,-2.227830924090498099e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460805583201870661e+01,4.547029755855435837e+02,4.149929539422440250e+00,6.928203299376701096e+00,-2.229497590757164860e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.460949920767728827e+01,4.547127280803413214e+02,4.147718466103954782e+00,6.928203299376701096e+00,-2.231164257423831621e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461094258333586993e+01,4.547224802064914115e+02,4.145505767400386787e+00,6.928203299376701096e+00,-2.232830924090498381e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461238595899445158e+01,4.547322319637229384e+02,4.143291443373199101e+00,6.928203299376701096e+00,-2.234497590757165142e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461382933465303324e+01,4.547419833517650432e+02,4.141075494083901631e+00,6.928203299376701096e+00,-2.236164257423831903e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461527271031161490e+01,4.547517343703468100e+02,4.138857919594048695e+00,6.928203299376701096e+00,-2.237830924090498663e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461671608597019656e+01,4.547614850191973801e+02,4.136638719965239019e+00,6.928203299376701096e+00,-2.239497590757165424e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461815946162877822e+01,4.547712352980459514e+02,4.134417895259117515e+00,6.928203299376701096e+00,-2.241164257423832185e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.461960283728735988e+01,4.547809852066216649e+02,4.132195445537373502e+00,6.928203299376701096e+00,-2.242830924090498945e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462104621294594153e+01,4.547907347446536619e+02,4.129971370861741597e+00,6.928203299376701096e+00,-2.244497590757165706e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462248958860452319e+01,4.548004839118711402e+02,4.127745671294001717e+00,6.928203299376701096e+00,-2.246164257423832467e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462393296426310485e+01,4.548102327080032978e+02,4.125518346895979072e+00,6.928203299376701096e+00,-2.247830924090499227e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462537633992168651e+01,4.548199811327792759e+02,4.123289397729544170e+00,6.928203299376701096e+00,-2.249497590757165988e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462681971558026817e+01,4.548297291859283860e+02,4.121058823856611930e+00,6.928203299376701096e+00,-2.251164257423832749e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462826309123884982e+01,4.548394768671797692e+02,4.118826625339142566e+00,6.928203299376701096e+00,-2.252830924090499509e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.462970646689743148e+01,4.548492241762626804e+02,4.116592802239141591e+00,6.928203299376701096e+00,-2.254497590757166270e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463114984255601314e+01,4.548589711129063744e+02,4.114357354618658924e+00,6.928203299376701096e+00,-2.256164257423833031e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463259321821459480e+01,4.548687176768401059e+02,4.112120282539791560e+00,6.928203299376701096e+00,-2.257830924090499791e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463403659387317646e+01,4.548784638677931298e+02,4.109881586064680015e+00,6.928203299376701096e+00,-2.259497590757166552e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463547996953175812e+01,4.548882096854947008e+02,4.107641265255510099e+00,6.928203299376701096e+00,-2.261164257423833313e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463692334519033977e+01,4.548979551296740738e+02,4.105399320174512923e+00,6.928203299376701096e+00,-2.262830924090500073e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463836672084892143e+01,4.549077002000606171e+02,4.103155750883964892e+00,6.928203299376701096e+00,-2.264497590757166834e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.463981009650750309e+01,4.549174448963835857e+02,4.100910557446186822e+00,6.928203299376701096e+00,-2.266164257423833595e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464125347216608475e+01,4.549271892183722912e+02,4.098663739923545712e+00,6.928203299376701096e+00,-2.267830924090500355e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464269684782466641e+01,4.549369331657561020e+02,4.096415298378452974e+00,6.928203299376701096e+00,-2.269497590757167116e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464414022348324806e+01,4.549466767382643297e+02,4.094165232873366200e+00,6.928203299376701096e+00,-2.271164257423833877e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464558359914182972e+01,4.549564199356262861e+02,4.091913543470786507e+00,6.928203299376701096e+00,-2.272830924090500637e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464702697480041138e+01,4.549661627575713965e+02,4.089660230233260307e+00,6.928203299376701096e+00,-2.274497590757167398e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464847035045899304e+01,4.549759052038289724e+02,4.087405293223380198e+00,6.928203299376701096e+00,-2.276164257423834159e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.464991372611757470e+01,4.549856472741283824e+02,4.085148732503783187e+00,6.928203299376701096e+00,-2.277830924090500919e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.465135710177615636e+01,4.549953889681990518e+02,4.082890548137151576e+00,6.928203299376701096e+00,-2.279497590757167680e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.465280047743473801e+01,4.550051302857703490e+02,4.080630740186212968e+00,6.928203299376701096e+00,-2.281164257423834441e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.465424385309331967e+01,4.550148712265716995e+02,4.078369308713739372e+00,6.928203299376701096e+00,-2.282830924090501201e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.465568722875190133e+01,4.550246117903325285e+02,4.076106253782548094e+00,6.928203299376701096e+00,-2.284497590757167962e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.465713060441048299e+01,4.550343519767822613e+02,4.073841575455502628e+00,6.928203299376701096e+00,-2.286164257423834723e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.465857398006906465e+01,4.550440917856503233e+02,4.071575273795509986e+00,6.928203299376701096e+00,-2.287830924090501483e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466001735572764630e+01,4.550538312166661399e+02,4.069307348865523366e+00,6.928203299376701096e+00,-2.289497590757168244e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466146073138622796e+01,4.550635702695591931e+02,4.067037800728540375e+00,6.928203299376701096e+00,-2.291164257423835005e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466290410704480962e+01,4.550733089440589652e+02,4.064766629447604807e+00,6.928203299376701096e+00,-2.292830924090501765e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466434748270339128e+01,4.550830472398949382e+02,4.062493835085803973e+00,6.928203299376701096e+00,-2.294497590757168526e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466579085836197294e+01,4.550927851567965945e+02,4.060219417706271372e+00,6.928203299376701096e+00,-2.296164257423835287e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466723423402055460e+01,4.551025226944934730e+02,4.057943377372184912e+00,6.928203299376701096e+00,-2.297830924090502047e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.466867760967913625e+01,4.551122598527149989e+02,4.055665714146767797e+00,6.928203299376701096e+00,-2.299497590757168808e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467012098533771791e+01,4.551219966311907683e+02,4.053386428093289418e+00,6.928203299376701096e+00,-2.301164257423835569e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467156436099629957e+01,4.551317330296503201e+02,4.051105519275062683e+00,6.928203299376701096e+00,-2.302830924090502329e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467300773665488123e+01,4.551414690478231364e+02,4.048822987755445801e+00,6.928203299376701096e+00,-2.304497590757169090e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467445111231346289e+01,4.551512046854388132e+02,4.046538833597843166e+00,6.928203299376701096e+00,-2.306164257423835851e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467589448797204454e+01,4.551609399422269462e+02,4.044253056865702689e+00,6.928203299376701096e+00,-2.307830924090502611e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467733786363062620e+01,4.551706748179170745e+02,4.041965657622518471e+00,6.928203299376701096e+00,-2.309497590757169372e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.467878123928920786e+01,4.551804093122387940e+02,4.039676635931829907e+00,6.928203299376701096e+00,-2.311164257423836133e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468022461494778952e+01,4.551901434249217004e+02,4.037385991857220802e+00,6.928203299376701096e+00,-2.312830924090502893e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468166799060637118e+01,4.551998771556953898e+02,4.035093725462319370e+00,6.928203299376701096e+00,-2.314497590757169654e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468311136626495284e+01,4.552096105042895147e+02,4.032799836810800009e+00,6.928203299376701096e+00,-2.316164257423836415e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468455474192353449e+01,4.552193434704336710e+02,4.030504325966382417e+00,6.928203299376701096e+00,-2.317830924090503175e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468599811758211615e+01,4.552290760538575114e+02,4.028207192992830699e+00,6.928203299376701096e+00,-2.319497590757169936e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468744149324069781e+01,4.552388082542906886e+02,4.025908437953953367e+00,6.928203299376701096e+00,-2.321164257423836697e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.468888486889927947e+01,4.552485400714628554e+02,4.023608060913605122e+00,6.928203299376701096e+00,-2.322830924090503457e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469032824455786113e+01,4.552582715051036644e+02,4.021306061935685960e+00,6.928203299376701096e+00,-2.324497590757170218e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469177162021644278e+01,4.552680025549428251e+02,4.019002441084139399e+00,6.928203299376701096e+00,-2.326164257423836979e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469321499587502444e+01,4.552777332207100471e+02,4.016697198422955140e+00,6.928203299376701096e+00,-2.327830924090503739e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469465837153360610e+01,4.552874635021349832e+02,4.014390334016168183e+00,6.928203299376701096e+00,-2.329497590757170500e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469610174719218776e+01,4.552971933989473996e+02,4.012081847927857048e+00,6.928203299376701096e+00,-2.331164257423837260e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469754512285076942e+01,4.553069229108770060e+02,4.009771740222147329e+00,6.928203299376701096e+00,-2.332830924090504021e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.469898849850935107e+01,4.553166520376535118e+02,4.007460010963208141e+00,6.928203299376701096e+00,-2.334497590757170782e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470043187416793273e+01,4.553263807790066835e+02,4.005146660215254784e+00,6.928203299376701096e+00,-2.336164257423837542e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470187524982651439e+01,4.553361091346662874e+02,4.002831688042546077e+00,6.928203299376701096e+00,-2.337830924090504303e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470331862548509605e+01,4.553458371043620900e+02,4.000515094509387914e+00,6.928203299376701096e+00,-2.339497590757171064e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470476200114367771e+01,4.553555646878238576e+02,3.998196879680129268e+00,6.928203299376701096e+00,-2.341164257423837824e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470620537680225937e+01,4.553652918847813567e+02,3.995877043619165292e+00,6.928203299376701096e+00,-2.342830924090504585e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470764875246084102e+01,4.553750186949644103e+02,3.993555586390935996e+00,6.928203299376701096e+00,-2.344497590757171346e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.470909212811942268e+01,4.553847451181028418e+02,3.991232508059925799e+00,6.928203299376701096e+00,-2.346164257423838106e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471053550377800434e+01,4.553944711539264745e+02,3.988907808690665302e+00,6.928203299376701096e+00,-2.347830924090504867e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471197887943658600e+01,4.554041968021651314e+02,3.986581488347729074e+00,6.928203299376701096e+00,-2.349497590757171628e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471342225509516766e+01,4.554139220625486359e+02,3.984253547095737424e+00,6.928203299376701096e+00,-2.351164257423838388e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471486563075374931e+01,4.554236469348068681e+02,3.981923984999355071e+00,6.928203299376701096e+00,-2.352830924090505149e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471630900641233097e+01,4.554333714186697080e+02,3.979592802123292028e+00,6.928203299376701096e+00,-2.354497590757171910e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471775238207091263e+01,4.554430955138669788e+02,3.977259998532303609e+00,6.928203299376701096e+00,-2.356164257423838670e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.471919575772949429e+01,4.554528192201286174e+02,3.974925574291189978e+00,6.928203299376701096e+00,-2.357830924090505431e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472063913338807595e+01,4.554625425371845040e+02,3.972589529464796154e+00,6.928203299376701096e+00,-2.359497590757172192e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472208250904665761e+01,4.554722654647645186e+02,3.970251864118012008e+00,6.928203299376701096e+00,-2.361164257423838952e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472352588470523926e+01,4.554819880025985981e+02,3.967912578315773153e+00,6.928203299376701096e+00,-2.362830924090505713e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472496926036382092e+01,4.554917101504166794e+02,3.965571672123059610e+00,6.928203299376701096e+00,-2.364497590757172474e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472641263602240258e+01,4.555014319079486995e+02,3.963229145604896253e+00,6.928203299376701096e+00,-2.366164257423839234e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472785601168098424e+01,4.555111532749246521e+02,3.960884998826353698e+00,6.928203299376701096e+00,-2.367830924090505995e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.472929938733956590e+01,4.555208742510744173e+02,3.958539231852546969e+00,6.928203299376701096e+00,-2.369497590757172756e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473074276299814755e+01,4.555305948361280457e+02,3.956191844748635944e+00,6.928203299376701096e+00,-2.371164257423839516e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473218613865672921e+01,4.555403150298154742e+02,3.953842837579826242e+00,6.928203299376701096e+00,-2.372830924090506277e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473362951431531087e+01,4.555500348318666965e+02,3.951492210411367889e+00,6.928203299376701096e+00,-2.374497590757173038e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473507288997389253e+01,4.555597542420117065e+02,3.949139963308556212e+00,6.928203299376701096e+00,-2.376164257423839798e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473651626563247419e+01,4.555694732599805548e+02,3.946786096336730942e+00,6.928203299376701096e+00,-2.377830924090506559e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473795964129105585e+01,4.555791918855032918e+02,3.944430609561278001e+00,6.928203299376701096e+00,-2.379497590757173320e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.473940301694963750e+01,4.555889101183099115e+02,3.942073503047626826e+00,6.928203299376701096e+00,-2.381164257423840080e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474084639260821916e+01,4.555986279581304643e+02,3.939714776861253043e+00,6.928203299376701096e+00,-2.382830924090506841e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474228976826680082e+01,4.556083454046950010e+02,3.937354431067676686e+00,6.928203299376701096e+00,-2.384497590757173602e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474373314392538248e+01,4.556180624577336289e+02,3.934992465732463085e+00,6.928203299376701096e+00,-2.386164257423840362e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474517651958396414e+01,4.556277791169763987e+02,3.932628880921222425e+00,6.928203299376701096e+00,-2.387830924090507123e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474661989524254579e+01,4.556374953821534177e+02,3.930263676699609743e+00,6.928203299376701096e+00,-2.389497590757173884e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474806327090112745e+01,4.556472112529947935e+02,3.927896853133324928e+00,6.928203299376701096e+00,-2.391164257423840644e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.474950664655970911e+01,4.556569267292306336e+02,3.925528410288113168e+00,6.928203299376701096e+00,-2.392830924090507405e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475095002221829077e+01,4.556666418105910452e+02,3.923158348229764947e+00,6.928203299376701096e+00,-2.394497590757174166e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475239339787687243e+01,4.556763564968061928e+02,3.920786667024114713e+00,6.928203299376701096e+00,-2.396164257423840926e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475383677353545409e+01,4.556860707876062406e+02,3.918413366737043102e+00,6.928203299376701096e+00,-2.397830924090507687e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475528014919403574e+01,4.556957846827212961e+02,3.916038447434474712e+00,6.928203299376701096e+00,-2.399497590757174448e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475672352485261740e+01,4.557054981818815804e+02,3.913661909182379439e+00,6.928203299376701096e+00,-2.401164257423841208e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475816690051119906e+01,4.557152112848172010e+02,3.911283752046772477e+00,6.928203299376701096e+00,-2.402830924090507969e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.475961027616978072e+01,4.557249239912584358e+02,3.908903976093713872e+00,6.928203299376701096e+00,-2.404497590757174730e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476105365182836238e+01,4.557346363009354491e+02,3.906522581389308080e+00,6.928203299376701096e+00,-2.406164257423841490e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476249702748694403e+01,4.557443482135784620e+02,3.904139567999705296e+00,6.928203299376701096e+00,-2.407830924090508251e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476394040314552569e+01,4.557540597289176389e+02,3.901754935991100570e+00,6.928203299376701096e+00,-2.409497590757175012e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476538377880410735e+01,4.557637708466833146e+02,3.899368685429733361e+00,6.928203299376701096e+00,-2.411164257423841772e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476682715446268901e+01,4.557734815666056534e+02,3.896980816381888424e+00,6.928203299376701096e+00,-2.412830924090508533e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476827053012127067e+01,4.557831918884149331e+02,3.894591328913895367e+00,6.928203299376701096e+00,-2.414497590757175294e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.476971390577985233e+01,4.557929018118414888e+02,3.892200223092128653e+00,6.928203299376701096e+00,-2.416164257423842054e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477115728143843398e+01,4.558026113366155414e+02,3.889807498983008038e+00,6.928203299376701096e+00,-2.417830924090508815e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477260065709701564e+01,4.558123204624673690e+02,3.887413156652998580e+00,6.928203299376701096e+00,-2.419497590757175576e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477404403275559730e+01,4.558220291891273064e+02,3.885017196168609299e+00,6.928203299376701096e+00,-2.421164257423842336e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477548740841417896e+01,4.558317375163256315e+02,3.882619617596394512e+00,6.928203299376701096e+00,-2.422830924090509097e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477693078407276062e+01,4.558414454437927361e+02,3.880220421002953834e+00,6.928203299376701096e+00,-2.424497590757175858e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477837415973134227e+01,4.558511529712588981e+02,3.877819606454931733e+00,6.928203299376701096e+00,-2.426164257423842618e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.477981753538992393e+01,4.558608600984544523e+02,3.875417174019017530e+00,6.928203299376701096e+00,-2.427830924090509379e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478126091104850559e+01,4.558705668251097904e+02,3.873013123761945398e+00,6.928203299376701096e+00,-2.429497590757176140e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478270428670708725e+01,4.558802731509552473e+02,3.870607455750494363e+00,6.928203299376701096e+00,-2.431164257423842900e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478414766236566891e+01,4.558899790757212713e+02,3.868200170051488751e+00,6.928203299376701096e+00,-2.432830924090509661e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478559103802425057e+01,4.558996845991381974e+02,3.865791266731797293e+00,6.928203299376701096e+00,-2.434497590757176422e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478703441368283222e+01,4.559093897209364172e+02,3.863380745858334020e+00,6.928203299376701096e+00,-2.436164257423843182e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478847778934141388e+01,4.559190944408463793e+02,3.860968607498058258e+00,6.928203299376701096e+00,-2.437830924090509943e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.478992116499999554e+01,4.559287987585984752e+02,3.858554851717973300e+00,6.928203299376701096e+00,-2.439497590757176704e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.479136454065857720e+01,4.559385026739232103e+02,3.856139478585128622e+00,6.928203299376701096e+00,-2.441164257423843464e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.479280791631715886e+01,4.559482061865509763e+02,3.853722488166617222e+00,6.928203299376701096e+00,-2.442830924090510225e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.479425129197574051e+01,4.559579092962122218e+02,3.851303880529578283e+00,6.928203299376701096e+00,-2.444497590757176986e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.479569466763432217e+01,4.559676120026374520e+02,3.848883655741194953e+00,6.928203299376701096e+00,-2.446164257423843746e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.479713804329290383e+01,4.559773143055571154e+02,3.846461813868695678e+00,6.928203299376701096e+00,-2.447830924090510507e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.479858141895148549e+01,4.559870162047017175e+02,3.844038354979354200e+00,6.928203299376701096e+00,-2.449497590757177268e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480002479461006715e+01,4.559967176998017635e+02,3.841613279140488224e+00,6.928203299376701096e+00,-2.451164257423844028e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480146817026864881e+01,4.560064187905877588e+02,3.839186586419461644e+00,6.928203299376701096e+00,-2.452830924090510789e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480291154592723046e+01,4.560161194767902089e+02,3.836758276883682317e+00,6.928203299376701096e+00,-2.454497590757177550e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480435492158581212e+01,4.560258197581396757e+02,3.834328350600602953e+00,6.928203299376701096e+00,-2.456164257423844310e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480579829724439378e+01,4.560355196343667217e+02,3.831896807637722002e+00,6.928203299376701096e+00,-2.457830924090511071e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480724167290297544e+01,4.560452191052018520e+02,3.829463648062581882e+00,6.928203299376701096e+00,-2.459497590757177832e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.480868504856155710e+01,4.560549181703756858e+02,3.827028871942770749e+00,6.928203299376701096e+00,-2.461164257423844592e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481012842422013875e+01,4.560646168296187852e+02,3.824592479345921170e+00,6.928203299376701096e+00,-2.462830924090511353e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481157179987872041e+01,4.560743150826617693e+02,3.822154470339710564e+00,6.928203299376701096e+00,-2.464497590757178114e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481301517553730207e+01,4.560840129292352003e+02,3.819714844991861646e+00,6.928203299376701096e+00,-2.466164257423844874e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481445855119588373e+01,4.560937103690697541e+02,3.817273603370141544e+00,6.928203299376701096e+00,-2.467830924090511635e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481590192685446539e+01,4.561034074018959927e+02,3.814830745542362678e+00,6.928203299376701096e+00,-2.469497590757178396e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481734530251304705e+01,4.561131040274445922e+02,3.812386271576382324e+00,6.928203299376701096e+00,-2.471164257423845156e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.481878867817162870e+01,4.561228002454461716e+02,3.809940181540102166e+00,6.928203299376701096e+00,-2.472830924090511917e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482023205383021036e+01,4.561324960556314068e+02,3.807492475501469631e+00,6.928203299376701096e+00,-2.474497590757178678e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482167542948879202e+01,4.561421914577309735e+02,3.805043153528476108e+00,6.928203299376701096e+00,-2.476164257423845438e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482311880514737368e+01,4.561518864514755478e+02,3.802592215689158284e+00,6.928203299376701096e+00,-2.477830924090512199e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482456218080595534e+01,4.561615810365958623e+02,3.800139662051598144e+00,6.928203299376701096e+00,-2.479497590757178960e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482600555646453699e+01,4.561712752128225929e+02,3.797685492683922082e+00,6.928203299376701096e+00,-2.481164257423845720e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482744893212311865e+01,4.561809689798864724e+02,3.795229707654301343e+00,6.928203299376701096e+00,-2.482830924090512481e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.482889230778170031e+01,4.561906623375181766e+02,3.792772307030952472e+00,6.928203299376701096e+00,-2.484497590757179242e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483033568344028197e+01,4.562003552854484951e+02,3.790313290882135977e+00,6.928203299376701096e+00,-2.486164257423846002e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483177905909886363e+01,4.562100478234081606e+02,3.787852659276158551e+00,6.928203299376701096e+00,-2.487830924090512763e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483322243475744528e+01,4.562197399511279627e+02,3.785390412281370853e+00,6.928203299376701096e+00,-2.489497590757179524e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483466581041602694e+01,4.562294316683386342e+02,3.782926549966168395e+00,6.928203299376701096e+00,-2.491164257423846284e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483610918607460860e+01,4.562391229747709644e+02,3.780461072398991984e+00,6.928203299376701096e+00,-2.492830924090513045e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483755256173319026e+01,4.562488138701558000e+02,3.777993979648326839e+00,6.928203299376701096e+00,-2.494497590757179806e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.483899593739177192e+01,4.562585043542239305e+02,3.775525271782703474e+00,6.928203299376701096e+00,-2.496164257423846566e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484043931305035358e+01,4.562681944267061454e+02,3.773054948870697256e+00,6.928203299376701096e+00,-2.497830924090513327e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484188268870893523e+01,4.562778840873332911e+02,3.770583010980928407e+00,6.928203299376701096e+00,-2.499497590757180088e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484332606436751689e+01,4.562875733358362140e+02,3.768109458182061555e+00,6.928203299376701096e+00,-2.501164257423846848e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484476944002609855e+01,4.562972621719457607e+02,3.765634290542806628e+00,6.928203299376701096e+00,-2.502830924090513331e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484621281568468021e+01,4.563069505953927774e+02,3.763157508131918405e+00,6.928203299376701096e+00,-2.504497590757179815e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484765619134326187e+01,4.563166386059081674e+02,3.760679111018196075e+00,6.928203299376701096e+00,-2.506164257423846298e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.484909956700184352e+01,4.563263262032228340e+02,3.758199099270484123e+00,6.928203299376701096e+00,-2.507830924090512781e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485054294266042518e+01,4.563360133870676805e+02,3.755717472957671887e+00,6.928203299376701096e+00,-2.509497590757179264e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485198631831900684e+01,4.563457001571736100e+02,3.753234232148693117e+00,6.928203299376701096e+00,-2.511164257423845747e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485342969397758850e+01,4.563553865132715259e+02,3.750749376912527300e+00,6.928203299376701096e+00,-2.512830924090512230e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485487306963617016e+01,4.563650724550923314e+02,3.748262907318197890e+00,6.928203299376701096e+00,-2.514497590757178713e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485631644529475182e+01,4.563747579823670435e+02,3.745774823434773193e+00,6.928203299376701096e+00,-2.516164257423845196e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485775982095333347e+01,4.563844430948265654e+02,3.743285125331366814e+00,6.928203299376701096e+00,-2.517830924090511679e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.485920319661191513e+01,4.563941277922019140e+02,3.740793813077137209e+00,6.928203299376701096e+00,-2.519497590757178163e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486064657227049679e+01,4.564038120742240494e+02,3.738300886741287687e+00,6.928203299376701096e+00,-2.521164257423844646e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486208994792907845e+01,4.564134959406239318e+02,3.735806346393065525e+00,6.928203299376701096e+00,-2.522830924090511129e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486353332358766011e+01,4.564231793911326349e+02,3.733310192101764180e+00,6.928203299376701096e+00,-2.524497590757177612e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486497669924624176e+01,4.564328624254811189e+02,3.730812423936721078e+00,6.928203299376701096e+00,-2.526164257423844095e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486642007490482342e+01,4.564425450434004006e+02,3.728313041967318497e+00,6.928203299376701096e+00,-2.527830924090510578e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486786345056340508e+01,4.564522272446215538e+02,3.725812046262983568e+00,6.928203299376701096e+00,-2.529497590757177061e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.486930682622198674e+01,4.564619090288755956e+02,3.723309436893188717e+00,6.928203299376701096e+00,-2.531164257423843544e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487075020188056840e+01,4.564715903958936565e+02,3.720805213927450783e+00,6.928203299376701096e+00,-2.532830924090510027e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487219357753915006e+01,4.564812713454067534e+02,3.718299377435331454e+00,6.928203299376701096e+00,-2.534497590757176511e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487363695319773171e+01,4.564909518771459602e+02,3.715791927486437718e+00,6.928203299376701096e+00,-2.536164257423842994e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487508032885631337e+01,4.565006319908424075e+02,3.713282864150420526e+00,6.928203299376701096e+00,-2.537830924090509477e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487652370451489503e+01,4.565103116862271690e+02,3.710772187496976127e+00,6.928203299376701096e+00,-2.539497590757175960e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487796708017347669e+01,4.565199909630313755e+02,3.708259897595845622e+00,6.928203299376701096e+00,-2.541164257423842443e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.487941045583205835e+01,4.565296698209861574e+02,3.705745994516814523e+00,6.928203299376701096e+00,-2.542830924090508926e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488085383149064000e+01,4.565393482598227024e+02,3.703230478329714082e+00,6.928203299376701096e+00,-2.544497590757175409e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488229720714922166e+01,4.565490262792721410e+02,3.700713349104419070e+00,6.928203299376701096e+00,-2.546164257423841892e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488374058280780332e+01,4.565587038790656038e+02,3.698194606910850446e+00,6.928203299376701096e+00,-2.547830924090508375e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488518395846638498e+01,4.565683810589342784e+02,3.695674251818972689e+00,6.928203299376701096e+00,-2.549497590757174859e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488662733412496664e+01,4.565780578186093521e+02,3.693152283898796018e+00,6.928203299376701096e+00,-2.551164257423841342e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488807070978354830e+01,4.565877341578220694e+02,3.690628703220375062e+00,6.928203299376701096e+00,-2.552830924090507825e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.488951408544212995e+01,4.565974100763036176e+02,3.688103509853808859e+00,6.928203299376701096e+00,-2.554497590757174308e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489095746110071161e+01,4.566070855737852412e+02,3.685576703869242188e+00,6.928203299376701096e+00,-2.556164257423840791e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489240083675929327e+01,4.566167606499981275e+02,3.683048285336863792e+00,6.928203299376701096e+00,-2.557830924090507274e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489384421241787493e+01,4.566264353046735209e+02,3.680518254326907712e+00,6.928203299376701096e+00,-2.559497590757173757e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489528758807645659e+01,4.566361095375427226e+02,3.677986610909652399e+00,6.928203299376701096e+00,-2.561164257423840240e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489673096373503824e+01,4.566457833483370337e+02,3.675453355155421598e+00,6.928203299376701096e+00,-2.562830924090506723e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489817433939361990e+01,4.566554567367876984e+02,3.672918487134583021e+00,6.928203299376701096e+00,-2.564497590757173207e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.489961771505220156e+01,4.566651297026259613e+02,3.670382006917550122e+00,6.928203299376701096e+00,-2.566164257423839690e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490106109071078322e+01,4.566748022455831801e+02,3.667843914574780761e+00,6.928203299376701096e+00,-2.567830924090506173e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490250446636936488e+01,4.566844743653907130e+02,3.665304210176777211e+00,6.928203299376701096e+00,-2.569497590757172656e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490394784202794654e+01,4.566941460617798043e+02,3.662762893794086594e+00,6.928203299376701096e+00,-2.571164257423839139e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490539121768652819e+01,4.567038173344818688e+02,3.660219965497301331e+00,6.928203299376701096e+00,-2.572830924090505622e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490683459334510985e+01,4.567134881832282076e+02,3.657675425357058252e+00,6.928203299376701096e+00,-2.574497590757172105e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490827796900369151e+01,4.567231586077502357e+02,3.655129273444039484e+00,6.928203299376701096e+00,-2.576164257423838588e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.490972134466227317e+01,4.567328286077792541e+02,3.652581509828970674e+00,6.928203299376701096e+00,-2.577830924090505071e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491116472032085483e+01,4.567424981830467345e+02,3.650032134582623655e+00,6.928203299376701096e+00,-2.579497590757171555e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491260809597943648e+01,4.567521673332840351e+02,3.647481147775814225e+00,6.928203299376701096e+00,-2.581164257423838038e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491405147163801814e+01,4.567618360582225705e+02,3.644928549479403035e+00,6.928203299376701096e+00,-2.582830924090504521e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491549484729659980e+01,4.567715043575937557e+02,3.642374339764295588e+00,6.928203299376701096e+00,-2.584497590757171004e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491693822295518146e+01,4.567811722311290623e+02,3.639818518701442240e+00,6.928203299376701096e+00,-2.586164257423837487e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491838159861376312e+01,4.567908396785599052e+02,3.637261086361837759e+00,6.928203299376701096e+00,-2.587830924090503970e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.491982497427234478e+01,4.568005066996177561e+02,3.634702042816522205e+00,6.928203299376701096e+00,-2.589497590757170453e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492126834993092643e+01,4.568101732940340867e+02,3.632141388136580051e+00,6.928203299376701096e+00,-2.591164257423836936e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492271172558950809e+01,4.568198394615403686e+02,3.629579122393140622e+00,6.928203299376701096e+00,-2.592830924090503419e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492415510124808975e+01,4.568295052018681304e+02,3.627015245657378095e+00,6.928203299376701096e+00,-2.594497590757169903e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492559847690667141e+01,4.568391705147488437e+02,3.624449758000511057e+00,6.928203299376701096e+00,-2.596164257423836386e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492704185256525307e+01,4.568488353999140372e+02,3.621882659493803391e+00,6.928203299376701096e+00,-2.597830924090502869e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492848522822383472e+01,4.568584998570952962e+02,3.619313950208562947e+00,6.928203299376701096e+00,-2.599497590757169352e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.492992860388241638e+01,4.568681638860240923e+02,3.616743630216142869e+00,6.928203299376701096e+00,-2.601164257423835835e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.493137197954099804e+01,4.568778274864320110e+02,3.614171699587941156e+00,6.928203299376701096e+00,-2.602830924090502318e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.493281535519957970e+01,4.568874906580505808e+02,3.611598158395400215e+00,6.928203299376701096e+00,-2.604497590757168801e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.493425873085816136e+01,4.568971534006114439e+02,3.609023006710007309e+00,6.928203299376701096e+00,-2.606164257423835284e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.493570210651674302e+01,4.569068157138461288e+02,3.606446244603294105e+00,6.928203299376701096e+00,-2.607830924090501767e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.493714548217532467e+01,4.569164775974862778e+02,3.603867872146837570e+00,6.928203299376701096e+00,-2.609497590757168251e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.493858885783390633e+01,4.569261390512634762e+02,3.601287889412259524e+00,6.928203299376701096e+00,-2.611164257423834734e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494003223349248799e+01,4.569358000749093662e+02,3.598706296471225752e+00,6.928203299376701096e+00,-2.612830924090501217e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494147560915106965e+01,4.569454606681555902e+02,3.596123093395447334e+00,6.928203299376701096e+00,-2.614497590757167700e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494291898480965131e+01,4.569551208307337902e+02,3.593538280256679762e+00,6.928203299376701096e+00,-2.616164257423834183e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494436236046823296e+01,4.569647805623756653e+02,3.590951857126723379e+00,6.928203299376701096e+00,-2.617830924090500666e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494580573612681462e+01,4.569744398628128579e+02,3.588363824077423381e+00,6.928203299376701096e+00,-2.619497590757167149e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494724911178539628e+01,4.569840987317770669e+02,3.585774181180669373e+00,6.928203299376701096e+00,-2.621164257423833632e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.494869248744397794e+01,4.569937571689999345e+02,3.583182928508396259e+00,6.928203299376701096e+00,-2.622830924090500115e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495013586310255960e+01,4.570034151742132167e+02,3.580590066132582905e+00,6.928203299376701096e+00,-2.624497590757166599e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495157923876114126e+01,4.570130727471486694e+02,3.577995594125253476e+00,6.928203299376701096e+00,-2.626164257423833082e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495302261441972291e+01,4.570227298875379915e+02,3.575399512558476545e+00,6.928203299376701096e+00,-2.627830924090499565e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495446599007830457e+01,4.570323865951128823e+02,3.572801821504365538e+00,6.928203299376701096e+00,-2.629497590757166048e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495590936573688623e+01,4.570420428696051545e+02,3.570202521035078735e+00,6.928203299376701096e+00,-2.631164257423832531e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495735274139546789e+01,4.570516987107465638e+02,3.567601611222818381e+00,6.928203299376701096e+00,-2.632830924090499014e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.495879611705404955e+01,4.570613541182689232e+02,3.564999092139832459e+00,6.928203299376701096e+00,-2.634497590757165497e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496023949271263120e+01,4.570710090919039885e+02,3.562394963858412922e+00,6.928203299376701096e+00,-2.636164257423831980e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496168286837121286e+01,4.570806636313835725e+02,3.559789226450897015e+00,6.928203299376701096e+00,-2.637830924090498463e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496312624402979452e+01,4.570903177364394878e+02,3.557181879989665951e+00,6.928203299376701096e+00,-2.639497590757164946e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496456961968837618e+01,4.570999714068036042e+02,3.554572924547146240e+00,6.928203299376701096e+00,-2.641164257423831430e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496601299534695784e+01,4.571096246422077343e+02,3.551962360195808799e+00,6.928203299376701096e+00,-2.642830924090497913e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496745637100553949e+01,4.571192774423837477e+02,3.549350187008169399e+00,6.928203299376701096e+00,-2.644497590757164396e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.496889974666412115e+01,4.571289298070634572e+02,3.546736405056788222e+00,6.928203299376701096e+00,-2.646164257423830879e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497034312232270281e+01,4.571385817359787893e+02,3.544121014414270299e+00,6.928203299376701096e+00,-2.647830924090497362e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497178649798128447e+01,4.571482332288616703e+02,3.541504015153265517e+00,6.928203299376701096e+00,-2.649497590757163845e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497322987363986613e+01,4.571578842854439131e+02,3.538885407346468170e+00,6.928203299376701096e+00,-2.651164257423830328e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497467324929844779e+01,4.571675349054575008e+02,3.536265191066617408e+00,6.928203299376701096e+00,-2.652830924090496811e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497611662495702944e+01,4.571771850886343600e+02,3.533643366386497231e+00,6.928203299376701096e+00,-2.654497590757163294e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497756000061561110e+01,4.571868348347064170e+02,3.531019933378935605e+00,6.928203299376701096e+00,-2.656164257423829778e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.497900337627419276e+01,4.571964841434055984e+02,3.528394892116806236e+00,6.928203299376701096e+00,-2.657830924090496261e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498044675193277442e+01,4.572061330144638873e+02,3.525768242673026798e+00,6.928203299376701096e+00,-2.659497590757162744e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498189012759135608e+01,4.572157814476132671e+02,3.523139985120559370e+00,6.928203299376701096e+00,-2.661164257423829227e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498333350324993773e+01,4.572254294425857211e+02,3.520510119532411331e+00,6.928203299376701096e+00,-2.662830924090495710e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498477687890851939e+01,4.572350769991132324e+02,3.517878645981634911e+00,6.928203299376701096e+00,-2.664497590757162193e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498622025456710105e+01,4.572447241169278414e+02,3.515245564541326306e+00,6.928203299376701096e+00,-2.666164257423828676e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498766363022568271e+01,4.572543707957615311e+02,3.512610875284626566e+00,6.928203299376701096e+00,-2.667830924090495159e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.498910700588426437e+01,4.572640170353463986e+02,3.509974578284721591e+00,6.928203299376701096e+00,-2.669497590757161642e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499055038154284603e+01,4.572736628354144273e+02,3.507336673614841693e+00,6.928203299376701096e+00,-2.671164257423828126e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499199375720142768e+01,4.572833081956977139e+02,3.504697161348262036e+00,6.928203299376701096e+00,-2.672830924090494609e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499343713286000934e+01,4.572929531159283556e+02,3.502056041558302635e+00,6.928203299376701096e+00,-2.674497590757161092e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499488050851859100e+01,4.573025975958383924e+02,3.499413314318327917e+00,6.928203299376701096e+00,-2.676164257423827575e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499632388417717266e+01,4.573122416351599213e+02,3.496768979701746716e+00,6.928203299376701096e+00,-2.677830924090494058e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499776725983575432e+01,4.573218852336250961e+02,3.494123037782012720e+00,6.928203299376701096e+00,-2.679497590757160541e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.499921063549433597e+01,4.573315283909660138e+02,3.491475488632624469e+00,6.928203299376701096e+00,-2.681164257423827024e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500065401115291763e+01,4.573411711069148282e+02,3.488826332327125357e+00,6.928203299376701096e+00,-2.682830924090493507e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500209738681149929e+01,4.573508133812036363e+02,3.486175568939102742e+00,6.928203299376701096e+00,-2.684497590757159990e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500354076247008095e+01,4.573604552135646486e+02,3.483523198542188837e+00,6.928203299376701096e+00,-2.686164257423826474e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500498413812866261e+01,4.573700966037300191e+02,3.480869221210060704e+00,6.928203299376701096e+00,-2.687830924090492957e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500642751378724427e+01,4.573797375514319015e+02,3.478213637016439819e+00,6.928203299376701096e+00,-2.689497590757159440e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500787088944582592e+01,4.573893780564025064e+02,3.475556446035092506e+00,6.928203299376701096e+00,-2.691164257423825923e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.500931426510440758e+01,4.573990181183741015e+02,3.472897648339829502e+00,6.928203299376701096e+00,-2.692830924090492406e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501075764076298924e+01,4.574086577370788405e+02,3.470237244004506394e+00,6.928203299376701096e+00,-2.694497590757158889e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501220101642157090e+01,4.574182969122489908e+02,3.467575233103023624e+00,6.928203299376701096e+00,-2.696164257423825372e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501364439208015256e+01,4.574279356436167632e+02,3.464911615709325599e+00,6.928203299376701096e+00,-2.697830924090491855e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501508776773873421e+01,4.574375739309144251e+02,3.462246391897401576e+00,6.928203299376701096e+00,-2.699497590757158338e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501653114339731587e+01,4.574472117738742440e+02,3.459579561741285669e+00,6.928203299376701096e+00,-2.701164257423824822e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501797451905589753e+01,4.574568491722285444e+02,3.456911125315056399e+00,6.928203299376701096e+00,-2.702830924090491305e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.501941789471447919e+01,4.574664861257095936e+02,3.454241082692837139e+00,6.928203299376701096e+00,-2.704497590757157788e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502086127037306085e+01,4.574761226340496592e+02,3.451569433948796117e+00,6.928203299376701096e+00,-2.706164257423824271e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502230464603164251e+01,4.574857586969811223e+02,3.448896179157145081e+00,6.928203299376701096e+00,-2.707830924090490754e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502374802169022416e+01,4.574953943142362505e+02,3.446221318392141519e+00,6.928203299376701096e+00,-2.709497590757157237e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502519139734880582e+01,4.575050294855474249e+02,3.443544851728087330e+00,6.928203299376701096e+00,-2.711164257423823720e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502663477300738748e+01,4.575146642106470267e+02,3.440866779239328377e+00,6.928203299376701096e+00,-2.712830924090490203e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502807814866596914e+01,4.575242984892673803e+02,3.438187101000255819e+00,6.928203299376701096e+00,-2.714497590757156686e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.502952152432455080e+01,4.575339323211409237e+02,3.435505817085304781e+00,6.928203299376701096e+00,-2.716164257423823170e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503096489998313245e+01,4.575435657059999812e+02,3.432822927568955684e+00,6.928203299376701096e+00,-2.717830924090489653e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503240827564171411e+01,4.575531986435769909e+02,3.430138432525733361e+00,6.928203299376701096e+00,-2.719497590757156136e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503385165130029577e+01,4.575628311336043907e+02,3.427452332030207049e+00,6.928203299376701096e+00,-2.721164257423822619e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503529502695887743e+01,4.575724631758146188e+02,3.424764626156990399e+00,6.928203299376701096e+00,-2.722830924090489102e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503673840261745909e+01,4.575820947699400563e+02,3.422075314980741911e+00,6.928203299376701096e+00,-2.724497590757155585e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503818177827604075e+01,4.575917259157131980e+02,3.419384398576164941e+00,6.928203299376701096e+00,-2.726164257423822068e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.503962515393462240e+01,4.576013566128665389e+02,3.416691877018006807e+00,6.928203299376701096e+00,-2.727830924090488551e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504106852959320406e+01,4.576109868611325169e+02,3.413997750381060126e+00,6.928203299376701096e+00,-2.729497590757155034e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504251190525178572e+01,4.576206166602436269e+02,3.411302018740161923e+00,6.928203299376701096e+00,-2.731164257423821518e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504395528091036738e+01,4.576302460099323639e+02,3.408604682170193190e+00,6.928203299376701096e+00,-2.732830924090488001e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504539865656894904e+01,4.576398749099312795e+02,3.405905740746080212e+00,6.928203299376701096e+00,-2.734497590757154484e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504684203222753069e+01,4.576495033599728686e+02,3.403205194542793244e+00,6.928203299376701096e+00,-2.736164257423820967e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504828540788611235e+01,4.576591313597897397e+02,3.400503043635347833e+00,6.928203299376701096e+00,-2.737830924090487450e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.504972878354469401e+01,4.576687589091143877e+02,3.397799288098803494e+00,6.928203299376701096e+00,-2.739497590757153933e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505117215920327567e+01,4.576783860076794213e+02,3.395093928008264594e+00,6.928203299376701096e+00,-2.741164257423820416e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505261553486185733e+01,4.576880126552173920e+02,3.392386963438880354e+00,6.928203299376701096e+00,-2.742830924090486899e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505405891052043899e+01,4.576976388514609084e+02,3.389678394465843958e+00,6.928203299376701096e+00,-2.744497590757153382e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505550228617902064e+01,4.577072645961425224e+02,3.386968221164393000e+00,6.928203299376701096e+00,-2.746164257423819866e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505694566183760230e+01,4.577168898889948991e+02,3.384256443609810816e+00,6.928203299376701096e+00,-2.747830924090486349e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505838903749618396e+01,4.577265147297507042e+02,3.381543061877424261e+00,6.928203299376701096e+00,-2.749497590757152832e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.505983241315476562e+01,4.577361391181425461e+02,3.378828076042605044e+00,6.928203299376701096e+00,-2.751164257423819315e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506127578881334728e+01,4.577457630539030902e+02,3.376111486180769283e+00,6.928203299376701096e+00,-2.752830924090485798e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506271916447192893e+01,4.577553865367649450e+02,3.373393292367377949e+00,6.928203299376701096e+00,-2.754497590757152281e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506416254013051059e+01,4.577650095664608898e+02,3.370673494677936421e+00,6.928203299376701096e+00,-2.756164257423818764e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506560591578909225e+01,4.577746321427235330e+02,3.367952093187994489e+00,6.928203299376701096e+00,-2.757830924090485247e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506704929144767391e+01,4.577842542652855968e+02,3.365229087973146793e+00,6.928203299376701096e+00,-2.759497590757151730e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506849266710625557e+01,4.577938759338798604e+02,3.362504479109032385e+00,6.928203299376701096e+00,-2.761164257423818214e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.506993604276483723e+01,4.578034971482389892e+02,3.359778266671334723e+00,6.928203299376701096e+00,-2.762830924090484697e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.507137941842341888e+01,4.578131179080957622e+02,3.357050450735782121e+00,6.928203299376701096e+00,-2.764497590757151180e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.507282279408200054e+01,4.578227382131829017e+02,3.354321031378147300e+00,6.928203299376701096e+00,-2.766164257423817663e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.507426616974058220e+01,4.578323580632332437e+02,3.351590008674247390e+00,6.928203299376701096e+00,-2.767830924090484146e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.507570954539916386e+01,4.578419774579795103e+02,3.348857382699943930e+00,6.928203299376701096e+00,-2.769497590757150629e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.507715292105774552e+01,4.578515963971545375e+02,3.346123153531143313e+00,6.928203299376701096e+00,-2.771164257423817112e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.507859629671632717e+01,4.578612148804911044e+02,3.343387321243796340e+00,6.928203299376701096e+00,-2.772830924090483595e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508003967237490883e+01,4.578708329077220469e+02,3.340649885913898220e+00,6.928203299376701096e+00,-2.774497590757150078e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508148304803349049e+01,4.578804504785801441e+02,3.337910847617489019e+00,6.928203299376701096e+00,-2.776164257423816561e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508292642369207215e+01,4.578900675927982888e+02,3.335170206430653206e+00,6.928203299376701096e+00,-2.777830924090483045e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508436979935065381e+01,4.578996842501093170e+02,3.332427962429519663e+00,6.928203299376701096e+00,-2.779497590757149528e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508581317500923547e+01,4.579093004502461213e+02,3.329684115690261681e+00,6.928203299376701096e+00,-2.781164257423816011e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508725655066781712e+01,4.579189161929415945e+02,3.326938666289097402e+00,6.928203299376701096e+00,-2.782830924090482494e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.508869992632639878e+01,4.579285314779286296e+02,3.324191614302288933e+00,6.928203299376701096e+00,-2.784497590757148977e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509014330198498044e+01,4.579381463049401191e+02,3.321442959806143680e+00,6.928203299376701096e+00,-2.786164257423815460e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509158667764356210e+01,4.579477606737090127e+02,3.318692702877013012e+00,6.928203299376701096e+00,-2.787830924090481943e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509303005330214376e+01,4.579573745839682033e+02,3.315940843591293152e+00,6.928203299376701096e+00,-2.789497590757148426e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509447342896072541e+01,4.579669880354506404e+02,3.313187382025424288e+00,6.928203299376701096e+00,-2.791164257423814909e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509591680461930707e+01,4.579766010278893305e+02,3.310432318255891460e+00,6.928203299376701096e+00,-2.792830924090481393e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509736018027788873e+01,4.579862135610171663e+02,3.307675652359224561e+00,6.928203299376701096e+00,-2.794497590757147876e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.509880355593647039e+01,4.579958256345672112e+02,3.304917384411997450e+00,6.928203299376701096e+00,-2.796164257423814359e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510024693159505205e+01,4.580054372482724148e+02,3.302157514490828838e+00,6.928203299376701096e+00,-2.797830924090480842e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510169030725363370e+01,4.580150484018658403e+02,3.299396042672381402e+00,6.928203299376701096e+00,-2.799497590757147325e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510313368291221536e+01,4.580246590950804375e+02,3.296632969033363114e+00,6.928203299376701096e+00,-2.801164257423813808e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510457705857079702e+01,4.580342693276492696e+02,3.293868293650525914e+00,6.928203299376701096e+00,-2.802830924090480291e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510602043422937868e+01,4.580438790993053999e+02,3.291102016600666147e+00,6.928203299376701096e+00,-2.804497590757146774e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510746380988796034e+01,4.580534884097818917e+02,3.288334137960625014e+00,6.928203299376701096e+00,-2.806164257423813257e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.510890718554654200e+01,4.580630972588118084e+02,3.285564657807287681e+00,6.928203299376701096e+00,-2.807830924090479741e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511035056120512365e+01,4.580727056461282700e+02,3.282793576217584608e+00,6.928203299376701096e+00,-2.809497590757146224e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511179393686370531e+01,4.580823135714643399e+02,3.280020893268490223e+00,6.928203299376701096e+00,-2.811164257423812707e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511323731252228697e+01,4.580919210345531383e+02,3.277246609037023362e+00,6.928203299376701096e+00,-2.812830924090479190e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511468068818086863e+01,4.581015280351278420e+02,3.274470723600247268e+00,6.928203299376701096e+00,-2.814497590757145673e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511612406383945029e+01,4.581111345729215145e+02,3.271693237035270041e+00,6.928203299376701096e+00,-2.816164257423812156e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511756743949803194e+01,4.581207406476673327e+02,3.268914149419244186e+00,6.928203299376701096e+00,-2.817830924090478639e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.511901081515661360e+01,4.581303462590984736e+02,3.266133460829366619e+00,6.928203299376701096e+00,-2.819497590757145122e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512045419081519526e+01,4.581399514069481143e+02,3.263351171342878665e+00,6.928203299376701096e+00,-2.821164257423811605e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512189756647377692e+01,4.581495560909494316e+02,3.260567281037066056e+00,6.928203299376701096e+00,-2.822830924090478089e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512334094213235858e+01,4.581591603108356594e+02,3.257781789989258936e+00,6.928203299376701096e+00,-2.824497590757144572e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512478431779094024e+01,4.581687640663399748e+02,3.254994698276832299e+00,6.928203299376701096e+00,-2.826164257423811055e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512622769344952189e+01,4.581783673571956115e+02,3.252206005977205550e+00,6.928203299376701096e+00,-2.827830924090477538e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512767106910810355e+01,4.581879701831358034e+02,3.249415713167842057e+00,6.928203299376701096e+00,-2.829497590757144021e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.512911444476668521e+01,4.581975725438938412e+02,3.246623819926250043e+00,6.928203299376701096e+00,-2.831164257423810504e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513055782042526687e+01,4.582071744392029586e+02,3.243830326329982139e+00,6.928203299376701096e+00,-2.832830924090476987e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513200119608384853e+01,4.582167758687964465e+02,3.241035232456634940e+00,6.928203299376701096e+00,-2.834497590757143470e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513344457174243018e+01,4.582263768324076523e+02,3.238238538383850340e+00,6.928203299376701096e+00,-2.836164257423809953e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513488794740101184e+01,4.582359773297698098e+02,3.235440244189314640e+00,6.928203299376701096e+00,-2.837830924090476437e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513633132305959350e+01,4.582455773606162666e+02,3.232640349950757663e+00,6.928203299376701096e+00,-2.839497590757142920e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513777469871817516e+01,4.582551769246803701e+02,3.229838855745954529e+00,6.928203299376701096e+00,-2.841164257423809403e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.513921807437675682e+01,4.582647760216954111e+02,3.227035761652724322e+00,6.928203299376701096e+00,-2.842830924090475886e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514066145003533848e+01,4.582743746513947940e+02,3.224231067748930979e+00,6.928203299376701096e+00,-2.844497590757142369e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514210482569392013e+01,4.582839728135118662e+02,3.221424774112482403e+00,6.928203299376701096e+00,-2.846164257423808852e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514354820135250179e+01,4.582935705077800321e+02,3.218616880821331350e+00,6.928203299376701096e+00,-2.847830924090475335e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514499157701108345e+01,4.583031677339326961e+02,3.215807387953474983e+00,6.928203299376701096e+00,-2.849497590757141818e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514643495266966511e+01,4.583127644917032626e+02,3.212996295586954432e+00,6.928203299376701096e+00,-2.851164257423808301e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514787832832824677e+01,4.583223607808251359e+02,3.210183603799856122e+00,6.928203299376701096e+00,-2.852830924090474785e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.514932170398682842e+01,4.583319566010317772e+02,3.207369312670310002e+00,6.928203299376701096e+00,-2.854497590757141268e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515076507964541008e+01,4.583415519520566477e+02,3.204553422276490871e+00,6.928203299376701096e+00,-2.856164257423807751e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515220845530399174e+01,4.583511468336331518e+02,3.201735932696617937e+00,6.928203299376701096e+00,-2.857830924090474234e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515365183096257340e+01,4.583607412454948076e+02,3.198916844008954818e+00,6.928203299376701096e+00,-2.859497590757140717e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515509520662115506e+01,4.583703351873750762e+02,3.196096156291809542e+00,6.928203299376701096e+00,-2.861164257423807200e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515653858227973672e+01,4.583799286590074757e+02,3.193273869623534544e+00,6.928203299376701096e+00,-2.862830924090473683e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515798195793831837e+01,4.583895216601255242e+02,3.190449984082526225e+00,6.928203299376701096e+00,-2.864497590757140166e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.515942533359690003e+01,4.583991141904627966e+02,3.187624499747226281e+00,6.928203299376701096e+00,-2.866164257423806649e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516086870925548169e+01,4.584087062497527540e+02,3.184797416696120376e+00,6.928203299376701096e+00,-2.867830924090473133e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516231208491406335e+01,4.584182978377289714e+02,3.181968735007738580e+00,6.928203299376701096e+00,-2.869497590757139616e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516375546057264501e+01,4.584278889541250237e+02,3.179138454760655375e+00,6.928203299376701096e+00,-2.871164257423806099e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516519883623122666e+01,4.584374795986744857e+02,3.176306576033490092e+00,6.928203299376701096e+00,-2.872830924090472582e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516664221188980832e+01,4.584470697711109892e+02,3.173473098904905587e+00,6.928203299376701096e+00,-2.874497590757139065e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516808558754838998e+01,4.584566594711681091e+02,3.170638023453609566e+00,6.928203299376701096e+00,-2.876164257423805548e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.516952896320697164e+01,4.584662486985794771e+02,3.167801349758354146e+00,6.928203299376701096e+00,-2.877830924090472031e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517097233886555330e+01,4.584758374530787250e+02,3.164963077897935406e+00,6.928203299376701096e+00,-2.879497590757138514e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517241571452413496e+01,4.584854257343994846e+02,3.162123207951194725e+00,6.928203299376701096e+00,-2.881164257423804997e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517385909018271661e+01,4.584950135422753874e+02,3.159281739997017446e+00,6.928203299376701096e+00,-2.882830924090471481e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517530246584129827e+01,4.585046008764401222e+02,3.156438674114332876e+00,6.928203299376701096e+00,-2.884497590757137964e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517674584149987993e+01,4.585141877366274343e+02,3.153594010382115620e+00,6.928203299376701096e+00,-2.886164257423804447e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517818921715846159e+01,4.585237741225709556e+02,3.150747748879383803e+00,6.928203299376701096e+00,-2.887830924090470930e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.517963259281704325e+01,4.585333600340044313e+02,3.147899889685199959e+00,6.928203299376701096e+00,-2.889497590757137413e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518107596847562490e+01,4.585429454706615502e+02,3.145050432878671476e+00,6.928203299376701096e+00,-2.891164257423803896e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518251934413420656e+01,4.585525304322760576e+02,3.142199378538950150e+00,6.928203299376701096e+00,-2.892830924090470379e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518396271979278822e+01,4.585621149185817558e+02,3.139346726745231742e+00,6.928203299376701096e+00,-2.894497590757136862e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518540609545136988e+01,4.585716989293123333e+02,3.136492477576756421e+00,6.928203299376701096e+00,-2.896164257423803345e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518684947110995154e+01,4.585812824642016494e+02,3.133636631112809212e+00,6.928203299376701096e+00,-2.897830924090469829e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518829284676853320e+01,4.585908655229834494e+02,3.130779187432719102e+00,6.928203299376701096e+00,-2.899497590757136312e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.518973622242711485e+01,4.586004481053915356e+02,3.127920146615859487e+00,6.928203299376701096e+00,-2.901164257423802795e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519117959808569651e+01,4.586100302111597102e+02,3.125059508741648173e+00,6.928203299376701096e+00,-2.902830924090469278e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519262297374427817e+01,4.586196118400218324e+02,3.122197273889547375e+00,6.928203299376701096e+00,-2.904497590757135761e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519406634940285983e+01,4.586291929917117614e+02,3.119333442139063273e+00,6.928203299376701096e+00,-2.906164257423802244e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519550972506144149e+01,4.586387736659632992e+02,3.116468013569747342e+00,6.928203299376701096e+00,-2.907830924090468727e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519695310072002314e+01,4.586483538625103620e+02,3.113600988261194136e+00,6.928203299376701096e+00,-2.909497590757135210e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519839647637860480e+01,4.586579335810868088e+02,3.110732366293043949e+00,6.928203299376701096e+00,-2.911164257423801693e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.519983985203718646e+01,4.586675128214265555e+02,3.107862147744980152e+00,6.928203299376701096e+00,-2.912830924090468177e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520128322769576812e+01,4.586770915832634614e+02,3.104990332696731414e+00,6.928203299376701096e+00,-2.914497590757134660e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520272660335434978e+01,4.586866698663314992e+02,3.102116921228070368e+00,6.928203299376701096e+00,-2.916164257423801143e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520416997901293144e+01,4.586962476703645848e+02,3.099241913418813610e+00,6.928203299376701096e+00,-2.917830924090467626e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520561335467151309e+01,4.587058249950966911e+02,3.096365309348822592e+00,6.928203299376701096e+00,-2.919497590757134109e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520705673033009475e+01,4.587154018402617908e+02,3.093487109098003174e+00,6.928203299376701096e+00,-2.921164257423800592e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520850010598867641e+01,4.587249782055938567e+02,3.090607312746305624e+00,6.928203299376701096e+00,-2.922830924090467075e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.520994348164725807e+01,4.587345540908268617e+02,3.087725920373723731e+00,6.928203299376701096e+00,-2.924497590757133558e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.521138685730583973e+01,4.587441294956947786e+02,3.084842932060296583e+00,6.928203299376701096e+00,-2.926164257423800041e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.521283023296442138e+01,4.587537044199316369e+02,3.081958347886106786e+00,6.928203299376701096e+00,-2.927830924090466524e-01,0.000000000000000000e+00,-4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.521427360862300304e+01,4.587632788632715233e+02,3.079072167931281800e+00,6.928203299376701096e+00,-2.929497590757133008e-01,0.000000000000000000e+00,-4.563496123041156649e-02,2.302158509785712017e-08,0.000000000000000000e+00 +7.521571698428158470e+01,4.587728528254484104e+02,3.076184392275993496e+00,6.928203299376701096e+00,-2.931164257423799491e-01,3.322879555212859642e-11,-4.563496123041156649e-02,7.849209439114438933e-05,0.000000000000000000e+00 +7.521716035994016636e+01,4.587824263061963848e+02,3.073295021000457705e+00,6.928203299376749058e+00,-2.932830924090465974e-01,1.133268072305353634e-07,-4.563496123041156649e-02,-8.005191438800863812e-01,0.000000000000000000e+00 +7.521860373559874802e+01,4.587919993052495329e+02,3.070404054184935116e+00,6.928203299540322213e+00,-2.934497590757132457e-01,-1.155336519694964226e-03,-4.563496123041156649e-02,-9.999828653303588499e-01,0.000000000000000000e+00 +7.522004711125728704e+01,4.588015718223419412e+02,3.067511491909729937e+00,6.928201631955712259e+00,-2.936164257423798940e-01,-2.598687446473782123e-03,-4.563496123041156649e-02,-9.999904987201896356e-01,0.000000000000000000e+00 +7.522149048726323883e+01,4.588111438572076395e+02,3.064617334255191228e+00,6.928197881072605036e+00,-2.937830924090465423e-01,-4.042049738511910295e-03,-4.563496123041156649e-02,-9.999928881646223955e-01,0.000000000000000000e+00 +7.522293386405063131e+01,4.588207154095808278e+02,3.061721581301712014e+00,6.928192046871838983e+00,-2.939497590757131906e-01,-5.485416260846007024e-03,-4.563496123041156649e-02,-9.999939200304879261e-01,0.000000000000000000e+00 +7.522437724205347820e+01,4.588302864791955926e+02,3.058824233129730175e+00,6.928184129342671582e+00,-2.941164257423798389e-01,-6.928785488005345140e-03,-4.563496123041156649e-02,-9.999943420728424348e-01,0.000000000000000000e+00 +7.522582062170582162e+01,4.588398570657860205e+02,3.055925289819727553e+00,6.928174128474682725e+00,-2.942830924090464872e-01,-8.372156973814454811e-03,-4.563496123041156649e-02,-9.999943661511366821e-01,0.000000000000000000e+00 +7.522726400344168951e+01,4.588494271690863116e+02,3.053024751452230401e+00,6.928162044256216845e+00,-2.944497590757131356e-01,-9.815530577894606562e-03,-4.563496123041156649e-02,-9.999939994849235125e-01,0.000000000000000000e+00 +7.522870738769513821e+01,4.588589967888306660e+02,3.050122618107809380e+00,6.928147876673941497e+00,-2.946164257423797839e-01,-1.125890617029139118e-02,-4.563496123041156649e-02,-9.999930685311398948e-01,0.000000000000000000e+00 +7.523015077490020985e+01,4.588685659247532271e+02,3.047218889867078673e+00,6.928131625712832253e+00,-2.947830924090464322e-01,-1.270228337056445410e-02,-4.563496123041156649e-02,-9.999909389001342408e-01,0.000000000000000000e+00 +7.523159416549096079e+01,4.588781345765881383e+02,3.044313566810698202e+00,6.928113291356534198e+00,-2.949497590757130805e-01,-1.414566088260363341e-02,-4.563496123041156649e-02,-9.999845982421089463e-01,0.000000000000000000e+00 +7.523303755990144737e+01,4.588877027440696565e+02,3.041406649019370967e+00,6.928092873588683531e+00,-2.951164257423797288e-01,-1.558903306228447486e-02,-4.563496123041156649e-02,-9.998753531359835245e-01,0.000000000000000000e+00 +7.523448095856576856e+01,4.588972704269319820e+02,3.038498136573844377e+00,6.928070372399183441e+00,-2.952830924090463771e-01,-1.703225181148414896e-02,-4.563496123041156649e-02,9.999834453612578278e-01,0.000000000000000000e+00 +7.523592436191799493e+01,4.589068376249093717e+02,3.035588029554911138e+00,6.928045787989822735e+00,-2.954497590757130254e-01,-1.558887235427611727e-02,-4.563496123041156649e-02,9.999928814644755137e-01,0.000000000000000000e+00 +7.523736777039219703e+01,4.589164043377360258e+02,3.032676328043407032e+00,6.928023286879363418e+00,-2.956164257423796737e-01,-1.414547415503496566e-02,-4.563496123041156649e-02,9.999956943442219748e-01,0.000000000000000000e+00 +7.523881118355434694e+01,4.589259705651462582e+02,3.029763032120212696e+00,6.928002869115783113e+00,-2.957830924090463220e-01,-1.270206720771990122e-02,-4.563496123041156649e-02,9.999970220166535251e-01,0.000000000000000000e+00 +7.524025460097043094e+01,4.589355363068742690e+02,3.026848141866253172e+00,6.927984534730755151e+00,-2.959497590757129704e-01,-1.125865409010339165e-02,-4.563496123041156649e-02,9.999977836803198850e-01,0.000000000000000000e+00 +7.524169802220642111e+01,4.589451015626544290e+02,3.023931657362497916e+00,6.927968283750352896e+00,-2.961164257423796187e-01,-9.815236053202154240e-03,-4.563496123041156649e-02,9.999982709904918776e-01,0.000000000000000000e+00 +7.524314144682824690e+01,4.589546663322209383e+02,3.021013578689959900e+00,6.927954116196964662e+00,-2.962830924090462670e-01,-8.371813927070309927e-03,-4.563496123041156649e-02,9.999986067744977003e-01,0.000000000000000000e+00 +7.524458487440185195e+01,4.589642306153081677e+02,3.018093905929696952e+00,6.927942032089901225e+00,-2.964497590757129153e-01,-6.928388364483822198e-03,-4.563496123041156649e-02,9.999988494794116445e-01,0.000000000000000000e+00 +7.524602830449316571e+01,4.589737944116504309e+02,3.015172639162811308e+00,6.927932031445651617e+00,-2.966164257423795636e-01,-5.484959933865517223e-03,-4.563496123041156649e-02,9.999990319667519945e-01,0.000000000000000000e+00 +7.524747173666810340e+01,4.589833577209820987e+02,3.012249778470449169e+00,6.927924114278004808e+00,-2.967830924090462119e-01,-4.041529156213845980e-03,-4.563496123041156649e-02,9.999991725968895295e-01,0.000000000000000000e+00 +7.524891517049258027e+01,4.589929205430374850e+02,3.009325323933801144e+00,6.927918280598118095e+00,-2.969497590757128602e-01,-2.598096526032525524e-03,-4.563496123041156649e-02,9.999992841815763533e-01,0.000000000000000000e+00 +7.525035860553251155e+01,4.590024828775509604e+02,3.006399275634101809e+00,6.927914530414555294e+00,-2.971164257423795085e-01,-1.154662519338032741e-03,-4.563496123041156649e-02,9.999993744104356264e-01,0.000000000000000000e+00 +7.525180204135379824e+01,4.590120447242568957e+02,3.003471633652630590e+00,6.927912863733313387e+00,-2.972830924090461568e-01,2.887723989484047133e-04,-4.563496123041156649e-02,9.999994479825342619e-01,0.000000000000000000e+00 +7.525324547752234139e+01,4.590216060828897184e+02,3.000542398070710881e+00,6.927913280557838505e+00,-2.974497590757128052e-01,1.732207770685535069e-03,-4.563496123041156649e-02,9.999995091641905587e-01,0.000000000000000000e+00 +7.525468891360402779e+01,4.590311669531837993e+02,2.997611568969710039e+00,6.927915780889035702e+00,-2.976164257423794535e-01,3.175643143888806814e-03,-4.563496123041156649e-02,9.999995613627240543e-01,0.000000000000000000e+00 +7.525613234916477268e+01,4.590407273348736226e+02,2.994679146431040273e+00,6.927920364725277835e+00,-2.977830924090461018e-01,4.619078071491805951e-03,-4.563496123041156649e-02,9.999996049950308219e-01,0.000000000000000000e+00 +7.525757578377047707e+01,4.590502872276935591e+02,2.991745130536157760e+00,6.927927032062412671e+00,-2.979497590757127501e-01,6.062512107031106136e-03,-4.563496123041156649e-02,9.999996426030863805e-01,0.000000000000000000e+00 +7.525901921698704200e+01,4.590598466313780932e+02,2.988809521366562638e+00,6.927935782893763772e+00,-2.981164257423793984e-01,7.505944807715009097e-03,-4.563496123041156649e-02,9.999996745910453289e-01,0.000000000000000000e+00 +7.526046264838036848e+01,4.590694055456616525e+02,2.985872319003799902e+00,6.927946617210135827e+00,-2.982830924090460467e-01,8.949375731339059489e-03,-4.563496123041156649e-02,9.999997039144679079e-01,0.000000000000000000e+00 +7.526190607751637174e+01,4.590789639702787213e+02,2.982933523529458508e+00,6.927959534999815538e+00,-2.984497590757126950e-01,1.039280443997013872e-02,-4.563496123041156649e-02,9.999997279807573136e-01,0.000000000000000000e+00 +7.526334950396098122e+01,4.590885219049637840e+02,2.979993135025171380e+00,6.927974536248577841e+00,-2.986164257423793433e-01,1.183623049193939861e-02,-4.563496123041156649e-02,9.999997501590804916e-01,0.000000000000000000e+00 +7.526479292728011217e+01,4.590980793494513250e+02,2.977051153572616293e+00,6.927991620939680573e+00,-2.987830924090459916e-01,1.327965345044895655e-02,-4.563496123041156649e-02,9.999997691230287922e-01,0.000000000000000000e+00 +7.526623634703970822e+01,4.591076363034758856e+02,2.974107579253514988e+00,6.928010789053871576e+00,-2.989497590757126400e-01,1.472307287679548195e-02,-4.563496123041156649e-02,9.999997873765352763e-01,0.000000000000000000e+00 +7.526767976280571304e+01,4.591171927667720070e+02,2.971162412149633170e+00,6.928032040569386041e+00,-2.991164257423792883e-01,1.616648833590030379e-02,-4.563496123041156649e-02,9.999998018752923601e-01,0.000000000000000000e+00 +7.526912317414408449e+01,4.591267487390742303e+02,2.968215652342781397e+00,6.928055375461951826e+00,-2.992830924090459366e-01,1.760989938830228793e-02,-4.563496123041156649e-02,9.999998159631823258e-01,0.000000000000000000e+00 +7.527056658062080885e+01,4.591363042201170970e+02,2.965267299914813748e+00,6.928080793704783247e+00,-2.994497590757125849e-01,1.905330559937995841e-02,-4.563496123041156649e-02,9.999998287147511267e-01,0.000000000000000000e+00 +7.527200998180185820e+01,4.591458592096351481e+02,2.962317354947628711e+00,6.928108295268588179e+00,-2.996164257423792332e-01,2.049670653319037722e-02,-4.563496123041156649e-02,9.999998400507948970e-01,0.000000000000000000e+00 +7.527345337725323304e+01,4.591554137073630386e+02,2.959365817523169628e+00,6.928137880121566283e+00,-2.997830924090458815e-01,2.194010175369194571e-02,-4.563496123041156649e-02,9.999998503121031446e-01,0.000000000000000000e+00 +7.527489676654094808e+01,4.591649677130353098e+02,2.956412687723423360e+00,6.928169548229409003e+00,-2.999497590757125298e-01,2.338349082535192899e-02,-4.563496123041156649e-02,9.999998598331468758e-01,0.000000000000000000e+00 +7.527634014923104644e+01,4.591745212263866165e+02,2.953457965630421622e+00,6.928203299555300454e+00,-3.001164257423791781e-01,2.482687331313863585e-02,-4.563496123041156649e-02,9.999998467730238927e-01,6.928203299555306671e-01 +7.527778352488958546e+01,4.591840742471515568e+02,2.950501651326239649e+00,6.928239134059918314e+00,-3.002830924090458264e-01,2.627024875051532302e-02,-4.463496123041156560e-02,9.999998319165817051e-01,6.928239134059924753e-01 +7.527922689308263671e+01,4.591936267750647289e+02,2.947543744892997530e+00,6.928277051701388523e+00,-3.004461019953525436e-01,2.771361670096680538e-02,-4.363496123041156471e-02,9.999998143001865847e-01,6.928277051701394740e-01 +7.528067025337631435e+01,4.592031788206838883e+02,2.944584281345437926e+00,6.928317052435328804e+00,-3.006054548279690763e-01,2.915697672660927733e-02,-4.263496123041156383e-02,9.999997938064721925e-01,6.928317052435335466e-01 +7.528211360533673258e+01,4.592127303945828771e+02,2.941623295689933748e+00,6.928359136214846892e+00,-3.007611512262088893e-01,3.060032838941311589e-02,-4.163496123041156294e-02,9.999997686063769597e-01,6.928359136214853331e-01 +7.528355694853003399e+01,4.592222815073512834e+02,2.938660822924671123e+00,6.928403302990540524e+00,-3.009131915020316628e-01,3.204367124873363365e-02,-4.063496123041156205e-02,9.999997385697648733e-01,6.928403302990546742e-01 +7.528500028252238963e+01,4.592318321695941563e+02,2.935696898039835023e+00,6.928449552710493897e+00,-3.010615759600459573e-01,3.348700486376457452e-02,-3.963496123041156116e-02,9.999997001492799686e-01,6.928449552710500559e-01 +7.528644360688001314e+01,4.592413823919314950e+02,2.932731556017793118e+00,6.928497885320277661e+00,-3.012063048975113788e-01,3.493032878860728024e-02,-3.863496123041156027e-02,9.999996502173383872e-01,6.928497885320283878e-01 +7.528788692116913239e+01,4.592509321849980211e+02,2.929764831833281402e+00,6.928548300762941814e+00,-3.013473786043412428e-01,3.637364257287801356e-02,-3.763496123041155939e-02,9.999995843606456214e-01,6.928548300762947809e-01 +7.528933022495600369e+01,4.592604815594427237e+02,2.926796760453588497e+00,6.928600798979009490e+00,-3.014847973631046840e-01,3.781694575985374701e-02,-3.663496123041155850e-02,9.999994917634705827e-01,6.928600798979015485e-01 +7.529077351780691174e+01,4.592700305259285756e+02,2.923827376838740832e+00,6.928655379906468070e+00,-3.016185614490290989e-01,3.926023787723310204e-02,-3.563496123041155761e-02,9.999993522223943332e-01,6.928655379906474288e-01 +7.529221679928819810e+01,4.592795790951321351e+02,2.920856715941688719e+00,6.928712043480746985e+00,-3.017486711300021995e-01,4.070351842358911620e-02,-3.463496123041155672e-02,9.999991195158458579e-01,6.928712043480752536e-01 +7.529366006896620434e+01,4.592891272777430913e+02,2.917884812708491538e+00,6.928770789634675964e+00,-3.018751266665741784e-01,4.214678683082036942e-02,-3.363496123041155583e-02,9.999986536038190099e-01,6.928770789634682847e-01 +7.529510332640732884e+01,4.592986750844640937e+02,2.914911702078504252e+00,6.928831618298389117e+00,-3.019979283119599844e-01,4.359004232875053619e-02,-3.263496123041155494e-02,9.999972537018083640e-01,6.928831618298395556e-01 +7.529654657117799843e+01,4.593082225260102405e+02,2.911937418984562598e+00,6.928894529399033608e+00,-3.021170763120410996e-01,4.503328313584550185e-02,-3.163496123041155406e-02,-7.063994335932374247e-01,6.928894529399038937e-01 +7.529798980284469678e+01,4.593177696131087373e+02,2.908961998353169154e+00,6.928959522859310383e+00,-3.022325709053676479e-01,4.401378510395020927e-02,-3.063496123041155317e-02,-9.999971633724124009e-01,6.928959522859315934e-01 +7.529943302097390756e+01,4.593273163564985566e+02,2.905985475104680749e+00,6.929023044351907856e+00,-3.023444123231603387e-01,4.257057106860576146e-02,-2.963496123041155228e-02,-9.999985626811946915e-01,6.929023044351914074e-01 +7.530087622587248575e+01,4.593368627669300963e+02,2.903007884153494533e+00,6.929084482408609524e+00,-3.024526007893121871e-01,4.112736824436875882e-02,-2.863496123041155139e-02,-9.999990288910989289e-01,6.929084482408615075e-01 +7.530231941797461559e+01,4.593464088551647819e+02,2.900029260408234499e+00,6.929143837101641168e+00,-3.025571365203904017e-01,3.968417754373598089e-02,-2.763496123041155050e-02,-9.999992614884044562e-01,6.929143837101646719e-01 +7.530376259771443870e+01,4.593559546319746687e+02,2.897049638771938440e+00,6.929201108502663686e+00,-3.026580197256381055e-01,3.824099886972148754e-02,-2.663496123041154962e-02,-9.999994009371568904e-01,6.929201108502669459e-01 +7.530520576552605405e+01,4.593655001081422142e+02,2.894069054142245356e+00,6.929256296681316485e+00,-3.027552506069760563e-01,3.679783192265441427e-02,-2.563496123041154873e-02,-9.999994930337036125e-01,6.929256296681323146e-01 +7.530664892184353221e+01,4.593750452944597669e+02,2.891087541411581974e+00,6.929309401704925264e+00,-3.028488293590040903e-01,3.535467633680512006e-02,-2.463496123041154784e-02,-9.999995588371211053e-01,6.929309401704931703e-01 +7.530809206710091530e+01,4.593845902017292815e+02,2.888105135467351037e+00,6.929360423638406985e+00,-3.029387561690029540e-01,3.391153171608566469e-02,-2.363496123041154695e-02,-9.999996078872241956e-01,6.929360423638413202e-01 +7.530953520173220284e+01,4.593941348407619785e+02,2.885121871192117826e+00,6.929409362544226347e+00,-3.030250312169355253e-01,3.246839765067338623e-02,-2.263496123041154606e-02,-9.999996463065147223e-01,6.929409362544233231e-01 +7.531097832617135168e+01,4.594036792223778889e+02,2.882137783463798453e+00,6.929456218482376251e+00,-3.031076546754484791e-01,3.102527372194167216e-02,-2.163496123041154517e-02,-9.999996755203490739e-01,6.929456218482381580e-01 +7.531242144085231871e+01,4.594132233574055704e+02,2.879152907155847263e+00,6.929500991510365360e+00,-3.031866267098735079e-01,2.958215950923746146e-02,-2.063496123041154429e-02,-9.999997007862940768e-01,6.929500991510371133e-01 +7.531386454620900395e+01,4.594227672566817091e+02,2.876167277137444689e+00,6.929543681683215439e+00,-3.032619474782287661e-01,2.813905458434974236e-02,-1.963496123041154340e-02,-9.999997205320643179e-01,6.929543681683221212e-01 +7.531530764267529321e+01,4.594323109310508357e+02,2.873180928273685097e+00,6.929584289053450696e+00,-3.033336171312200347e-01,2.669595852136459613e-02,-1.863496123041154251e-02,-9.999997374439583142e-01,6.929584289053456470e-01 +7.531675073068502968e+01,4.594418543913648705e+02,2.870193895425765529e+00,6.929622813671101333e+00,-3.034016358122419987e-01,2.525287089051833980e-02,-1.763496123041154162e-02,-9.999997516431069489e-01,6.929622813671106885e-01 +7.531819381067204233e+01,4.594513976484827822e+02,2.867206213451173547e+00,6.929659255583698219e+00,-3.034660036573793573e-01,2.380979126189806602e-02,-1.663496123041154073e-02,-9.999997632443310414e-01,6.929659255583704436e-01 +7.531963688307014593e+01,4.594609407132703041e+02,2.864217917203875086e+00,6.929693614836272886e+00,-3.035267207954079338e-01,2.236671920544945624e-02,-1.563496123041153985e-02,-9.999997744886868212e-01,6.929693614836278659e-01 +7.532107994831311260e+01,4.594704835965994221e+02,2.861229041534503192e+00,6.929725891471357535e+00,-3.035837873477956750e-01,2.092365428790719101e-02,-1.463496123041153896e-02,-9.999997824928579249e-01,6.929725891471363308e-01 +7.532252300683470025e+01,4.594800263093481476e+02,2.858239621290546761e+00,6.929756085528980591e+00,-3.036372034287037058e-01,1.948059608018848365e-02,-1.363496123041153807e-02,-9.999997911913703907e-01,6.929756085528986365e-01 +7.532396605906865261e+01,4.594895688624001764e+02,2.855249691316539273e+00,6.929784197046672922e+00,-3.036869691449871067e-01,1.803754414755320140e-02,-1.263496123041153718e-02,-9.999997972617146180e-01,6.929784197046678917e-01 +7.532540910544868495e+01,4.594991112666443769e+02,2.852259286454246645e+00,6.929810226059459843e+00,-3.037330845961959125e-01,1.659449806007490258e-02,-1.163496123041153629e-02,-9.999998029197647575e-01,6.929810226059465172e-01 +7.532685214640851257e+01,4.595086535329745629e+02,2.849268441542856412e+00,6.929834172599868225e+00,-3.037755498745757787e-01,1.515145738464734361e-02,-1.063496123041153540e-02,-9.999998086690501387e-01,6.929834172599874664e-01 +7.532829518238180810e+01,4.595181956722890959e+02,2.846277191419166908e+00,6.929856036697922050e+00,-3.038143650650688143e-01,1.370842168745420309e-02,-9.634961230411534516e-03,-9.999998124476009442e-01,6.929856036697927824e-01 +7.532973821380223001e+01,4.595277376954904867e+02,2.843285570917776006e+00,6.929875818381141528e+00,-3.038495302453143032e-01,1.226539053766988359e-02,-8.634961230411533628e-03,-9.999998164524006583e-01,6.929875818381141528e-01 +7.533118124110345093e+01,4.595372796134851114e+02,2.840293614871268968e+00,6.929893517674547532e+00,-3.038810454856490928e-01,1.082236350131238894e-02,-7.634961230411533607e-03,-9.999998198884327838e-01,6.929893517674547976e-01 +7.533262426471911510e+01,4.595468214371827571e+02,2.837301358110408955e+00,6.929909134600657161e+00,-3.039089108491084823e-01,9.379340145559585118e-03,-6.634961230411533586e-03,-9.999998215277965397e-01,6.929909134600656939e-01 +7.533406728508283834e+01,4.595563631774963937e+02,2.834308835464325327e+00,6.929922669179485517e+00,-3.039331263914264447e-01,7.936320039372547069e-03,-5.634961230411533566e-03,-9.999998252547136479e-01,6.929922669179485739e-01 +7.533551030262825066e+01,4.595659048453416631e+02,2.831316081760702819e+00,6.929934121428548366e+00,-3.039536921610362374e-01,6.493302746117360878e-03,-4.634961230411533545e-03,-9.999998255632843724e-01,6.929934121428548144e-01 +7.533695331778896787e+01,4.595754464516366511e+02,2.828323131825970282e+00,6.929943491362854147e+00,-3.039706081990707354e-01,5.050287837113950733e-03,-3.634961230411533524e-03,-9.999998280312619725e-01,6.929943491362854369e-01 +7.533839633099859157e+01,4.595849880073013765e+02,2.825330020485491200e+00,6.929950778994915517e+00,-3.039838745393627084e-01,3.607274875640868999e-03,-2.634961230411533503e-03,-9.999998279931597844e-01,6.929950778994915517e-01 +7.533983934269072336e+01,4.595945295232576768e+02,2.822336782563751090e+00,6.929955984334737806e+00,-3.039934912084452656e-01,2.164263431715152380e-03,-1.634961230411533482e-03,-9.999998293079644940e-01,6.929955984334738028e-01 +7.534128235329896484e+01,4.596040710104285267e+02,2.819343452884548018e+00,6.929959107389828787e+00,-3.039994582255519107e-01,7.212530697900866204e-04,-6.349612304115334616e-04,-9.999998294302401280e-01,6.929959107389828121e-01 +7.534272536325688918e+01,4.596136124797379807e+02,2.816350066271180896e+00,6.929960148165190681e+00,-3.040017756026166529e-01,-7.217566420044329526e-04,3.650387695884665593e-04,-9.999998292205588557e-01,6.929960148165190681e-01 +7.534416837299809799e+01,4.596231539421106049e+02,2.813356657546639550e+00,6.929959106663325485e+00,-3.040004433442742848e-01,-2.164766136778112967e-03,1.365038769588466580e-03,-9.999998282535511596e-01,6.929959106663325930e-01 +7.534561138295617866e+01,4.596326954084711929e+02,2.810363261533793899e+00,6.929955982884233201e+00,-3.039954614478603268e-01,-3.607775847025936500e-03,2.365038769588466601e-03,-9.999998278036983379e-01,6.929955982884232757e-01 +7.534705439356471857e+01,4.596422368897444812e+02,2.807369913055582256e+00,6.929950776825412717e+00,-3.039868299034109156e-01,-5.050786207082365829e-03,3.365038769588466622e-03,-9.999998257268326585e-01,6.929950776825412051e-01 +7.534849740525730510e+01,4.596517783968545814e+02,2.804376646935201833e+00,6.929943488481859148e+00,-3.039745486936628605e-01,-6.493797648189497673e-03,4.365038769588466643e-03,-9.999998249909579640e-01,6.929943488481858926e-01 +7.534994041846752566e+01,4.596613199407249226e+02,2.801383497996297489e+00,6.929934117846068276e+00,-3.039586177940534206e-01,-7.936810605875286445e-03,5.365038769588466663e-03,-9.999998217331182992e-01,6.929934117846068276e-01 +7.535138343362899604e+01,4.596708615322776268e+02,2.798390501063150460e+00,6.929922664908030328e+00,-3.039390371727201945e-01,-9.379825510097685934e-03,6.365038769588466684e-03,-9.999998197617532281e-01,6.929922664908030328e-01 +7.535282645117530365e+01,4.596804031824332242e+02,2.795397690960868431e+00,6.929909129655237976e+00,-3.039158067905007865e-01,-1.082284279631587874e-02,7.365038769588466705e-03,-9.999998164808989731e-01,6.929909129655243971e-01 +7.535426947154006427e+01,4.596899449021103692e+02,2.792405102515573834e+00,6.929893512072678341e+00,-3.038889266009325296e-01,-1.226586289624992908e-02,8.365038769588467593e-03,-9.999998127005815807e-01,6.929893512072684558e-01 +7.535571249515689374e+01,4.596994867022253857e+02,2.789412770554593912e+00,6.929875812142838321e+00,-3.038583965502520967e-01,-1.370888624279698043e-02,9.365038769588468481e-03,-9.999998083714404240e-01,6.929875812142843872e-01 +7.535715552245940785e+01,4.597090285936920395e+02,2.786420729906649907e+00,6.929856029845702814e+00,-3.038242165773950565e-01,-1.515191326879244786e-02,1.036503876958846937e-02,-9.999998030112553504e-01,6.929856029845709031e-01 +7.535859855388126505e+01,4.597185705874209702e+02,2.783429015402044904e+00,6.929834165158754722e+00,-3.037863866139954294e-01,-1.659494440638668855e-02,1.136503876958847026e-02,-9.999997974110977905e-01,6.929834165158760273e-01 +7.536004158985610957e+01,4.597281126943195204e+02,2.780437661872853905e+00,6.929810218056975835e+00,-3.037449065843850771e-01,-1.803798008888370108e-02,1.236503876958847115e-02,-9.999997906495816657e-01,6.929810218056982052e-01 +7.536148463081759985e+01,4.597376549252912810e+02,2.777446704153113011e+00,6.929784188512845056e+00,-3.036997764055932025e-01,-1.948102074827129382e-02,1.336503876958847203e-02,-9.999997830786111486e-01,6.929784188512850829e-01 +7.536292767719942276e+01,4.597471972912358069e+02,2.774456177079007713e+00,6.929756076496340178e+00,-3.036509959873455733e-01,-2.092406681705978599e-02,1.436503876958847292e-02,-9.999997741907153959e-01,6.929756076496346173e-01 +7.536437072943526516e+01,4.597567398030481058e+02,2.771466115489062076e+00,6.929725881974936996e+00,-3.035985652320639105e-01,-2.236711872704319135e-02,1.536503876958847381e-02,-9.999997634721343731e-01,6.929725881974942991e-01 +7.536581378795884234e+01,4.597662824716185241e+02,2.768476554224327479e+00,6.929693604913610194e+00,-3.035424840348649456e-01,-2.381017690929143268e-02,1.636503876958847470e-02,-9.999997516823295740e-01,6.929693604913615967e-01 +7.536725685320388379e+01,4.597758253078320649e+02,2.765487528128571793e+00,6.929659245274834234e+00,-3.034827522835596980e-01,-2.525324179598896837e-02,1.736503876958847559e-02,-9.999997370153937970e-01,6.929659245274840673e-01 +7.536869992560413323e+01,4.597853683225683881e+02,2.762499072048467674e+00,6.929622803018581578e+00,-3.034193698586526433e-01,-2.669631381673409978e-02,1.836503876958847647e-02,-9.999997210711786266e-01,6.929622803018588018e-01 +7.537014300559337698e+01,4.597949115267011280e+02,2.759511220833780865e+00,6.929584278102326245e+00,-3.033523366333405469e-01,-2.813939340345500070e-02,1.936503876958847736e-02,-9.999997003252153460e-01,6.929584278102332018e-01 +7.537158609360540140e+01,4.598044549310977231e+02,2.756524009337559367e+00,6.929543670481040252e+00,-3.032816524735116870e-01,-2.958248098301621831e-02,2.036503876958847825e-02,-9.999996755118139014e-01,6.929543670481046469e-01 +7.537302919007402124e+01,4.598139985466190183e+02,2.753537472416321297e+00,6.929500980107200725e+00,-3.032073172377446335e-01,-3.102557698336568318e-02,2.136503876958847914e-02,-9.999996465059569628e-01,6.929500980107206054e-01 +7.537447229543307969e+01,4.598235423841188663e+02,2.750551644930243622e+00,6.929456206930788120e+00,-3.031293307773071377e-01,-3.246868183229592586e-02,2.236503876958848003e-02,-9.999996076321283622e-01,6.929456206930794115e-01 +7.537591541011644836e+01,4.598330864544437873e+02,2.747566561743350455e+00,6.929409350899286224e+00,-3.030476929361549110e-01,-3.391179594943535824e-02,2.336503876958848092e-02,-9.999995591795108885e-01,6.929409350899292663e-01 +7.537735853455802726e+01,4.598426307684326844e+02,2.744582257723701346e+00,6.929360411957693699e+00,-3.029624035509305147e-01,-3.535491975485714755e-02,2.436503876958848180e-02,-9.999994929016764456e-01,6.929360411957699029e-01 +7.537880166919174485e+01,4.598521753369163321e+02,2.741598767743577802e+00,6.929309390048523198e+00,-3.028734624509618611e-01,-3.679805365676246803e-02,2.536503876958848269e-02,-9.999994009730187594e-01,6.929309390048529194e-01 +7.538024481445155800e+01,4.598617201707170921e+02,2.738616126679673357e+00,6.929256285111818237e+00,-3.027808694582610483e-01,-3.824119805208873318e-02,2.636503876958848358e-02,-9.999992614894037679e-01,6.929256285111824454e-01 +7.538168797077145200e+01,4.598712652806485721e+02,2.735634369413279643e+00,6.929201097085169181e+00,-3.026846243875227493e-01,-3.968435330619298623e-02,2.736503876958848447e-02,-9.999990286613992252e-01,6.929201097085175842e-01 +7.538313113858544057e+01,4.598808106775152851e+02,2.732653530830475574e+00,6.929143825903758547e+00,-3.025847270461227700e-01,-4.112751971838162629e-02,2.836503876958848536e-02,-9.999985628811227656e-01,6.929143825903764098e-01 +7.538457431832759426e+01,4.598903563721122509e+02,2.729673645822312977e+00,6.929084471500456033e+00,-3.024811772341166605e-01,-4.257069738651250018e-02,2.936503876958848624e-02,-9.999971633649222813e-01,6.929084471500461806e-01 +7.538601751043199783e+01,4.598999023752245421e+02,2.726694749285005770e+00,6.929023033806108955e+00,-3.023739747442379389e-01,-4.401388539710458098e-02,3.036503876958848713e-02,-7.060902367713790539e-01,6.929023033806114285e-01 +7.538746071533277870e+01,4.599094486976271128e+02,2.723716876120115593e+00,6.928959512751001526e+00,-3.022631193618964818e-01,-4.503291828720528550e-02,3.136503876958848802e-02,9.999972533130756513e-01,6.928959512751008409e-01 +7.538890393346410690e+01,4.599189953500842876e+02,2.720740061234740548e+00,6.928894520426823078e+00,-3.021486108651768587e-01,-4.358970411995140987e-02,3.236503876958848891e-02,9.999986533689062540e-01,6.928894520426829295e-01 +7.539034716513266687e+01,4.599285423433494771e+02,2.717764339541701268e+00,6.928831610385413953e+00,-3.020304490248364448e-01,-4.214647439489087322e-02,3.336503876958848980e-02,9.999991195669911681e-01,6.928831610385419726e-01 +7.539179040990498493e+01,4.599380896881647800e+02,2.714789745959726996e+00,6.928770782706571651e+00,-3.019086336043036445e-01,-4.070323089324750371e-02,3.436503876958849069e-02,9.999993523015132668e-01,6.928770782706578091e-01 +7.539323366734755894e+01,4.599476373952605854e+02,2.711816315413643430e+00,6.928712037465648343e+00,-3.017831643596761149e-01,-3.925997438547357277e-02,3.536503876958849157e-02,9.999994916266510270e-01,6.928712037465654117e-01 +7.539467693702681572e+01,4.599571854753553453e+02,2.708844082834558797e+00,6.928655374735009254e+00,-3.016540410397185457e-01,-3.781670543993311678e-02,3.636503876958849246e-02,9.999995842008317926e-01,6.928655374735015471e-01 +7.539612021850916790e+01,4.599667339391550627e+02,2.705873083160049486e+00,6.928600794584323985e+00,-3.015212633858609381e-01,-3.637342455768967364e-02,3.736503876958849335e-02,9.999996506633229698e-01,6.928600794584329758e-01 +7.539756351136099966e+01,4.599762827973529511e+02,2.702903351334347004e+00,6.928548297080663332e+00,-3.013848311321962736e-01,-3.493013221005584340e-02,3.836503876958849424e-02,9.999997001334156588e-01,6.928548297080669993e-01 +7.539900681514863834e+01,4.599858320606291500e+02,2.699934922308523166e+00,6.928497882288541909e+00,-3.012447440054785708e-01,-3.348682885521776786e-02,3.936503876958849513e-02,9.999997378860315811e-01,6.928497882288547904e-01 +7.540045012943838287e+01,4.599953817396503837e+02,2.696967831040676611e+00,6.928449550269936807e+00,-3.011010017251206095e-01,-3.204351494378199910e-02,4.036503876958849601e-02,9.999997691893275364e-01,6.928449550269942803e-01 +7.540189345379651797e+01,4.600049318450693931e+02,2.694002112496117096e+00,6.928403301084298249e+00,-3.009536040031916548e-01,-3.060019091878369776e-02,4.136503876958849690e-02,9.999997937621991628e-01,6.928403301084303800e-01 +7.540333678778927151e+01,4.600144823875248221e+02,2.691037801647552019e+00,6.928359134788560247e+00,-3.008025505444152370e-01,-2.915685722369452948e-02,4.236503876958849779e-02,9.999998143016070040e-01,6.928359134788566465e-01 +7.540478013098287136e+01,4.600240333776407056e+02,2.688074933475271155e+00,6.928317051437139718e+00,-3.006478410461667083e-01,-2.771351429812298275e-02,4.336503876958849868e-02,9.999998317926538371e-01,6.928317051437146157e-01 +7.540622348294348853e+01,4.600335848260261287e+02,2.685113542967331401e+00,6.928277051081941806e+00,-3.004894751984708567e-01,-2.627016258028376516e-02,4.436503876958849957e-02,9.999998467876947128e-01,6.928277051081948024e-01 +7.540766684323729407e+01,4.600431367432748857e+02,2.682153665119741071e+00,6.928239133772361669e+00,-3.003274526839994629e-01,-2.482680250762106522e-02,4.536503876958850046e-02,9.999998598327386468e-01,1.870087356158503245e-01 +7.540911021143041637e+01,4.600526891399651390e+02,2.679195334936645079e+00,6.928203299555285355e+00,-3.001617731780685805e-01,-2.338343451681638291e-02,4.563496123041156649e-02,9.999998505775553603e-01,0.000000000000000000e+00 +7.541055358708895540e+01,4.600622420266589643e+02,2.676238587430508353e+00,6.928169548475090700e+00,-2.999951065114019322e-01,-2.194005907394832450e-02,4.563496123041156649e-02,9.999998395932310213e-01,0.000000000000000000e+00 +7.541199696977901112e+01,4.600717954060113470e+02,2.673283432113212399e+00,6.928137880573604690e+00,-2.998284398447352839e-01,-2.049667661542674615e-02,4.563496123041156649e-02,9.999998286855666940e-01,0.000000000000000000e+00 +7.541344035906664089e+01,4.600813492777569422e+02,2.670329869066844886e+00,6.928108295890146096e+00,-2.996617731780686356e-01,-1.905328757507645035e-02,4.563496123041156649e-02,9.999998162434834414e-01,0.000000000000000000e+00 +7.541488375451788784e+01,4.600909036416303479e+02,2.667377898373449518e+00,6.928080794461529024e+00,-2.994951065114019872e-01,-1.760989238906774182e-02,4.563496123041156649e-02,9.999998019285433193e-01,0.000000000000000000e+00 +7.541632715569878087e+01,4.601004584973661622e+02,2.664427520115025150e+00,6.928055376322059367e+00,-2.993284398447353389e-01,-1.616649149407822783e-02,4.563496123041156649e-02,9.999997871012279438e-01,0.000000000000000000e+00 +7.541777056217532049e+01,4.601100138446989831e+02,2.661478734373527111e+00,6.928032041503533911e+00,-2.991617731780686906e-01,-1.472308532483928602e-02,4.563496123041156649e-02,9.999997692789019954e-01,0.000000000000000000e+00 +7.541921397351350720e+01,4.601195696833633519e+02,2.658531541230865880e+00,6.928010790035243005e+00,-2.989951065114020423e-01,-1.327967431968192502e-02,4.563496123041156649e-02,9.999997502356728907e-01,0.000000000000000000e+00 +7.542065738927931307e+01,4.601291260130938667e+02,2.655585940768907527e+00,6.927991621943965228e+00,-2.988284398447353940e-01,-1.183625891439127331e-02,4.563496123041156649e-02,9.999997283288786232e-01,0.000000000000000000e+00 +7.542210080903869596e+01,4.601386828336250687e+02,2.652641933069475044e+00,6.927974537253970944e+00,-2.986617731780687457e-01,-1.039283954713706923e-02,4.563496123041156649e-02,9.999997027621443380e-01,0.000000000000000000e+00 +7.542354423235762795e+01,4.601482401446914992e+02,2.649699518214345684e+00,6.927959535987018747e+00,-2.984951065114020974e-01,-8.949416657250824914e-03,4.563496123041156649e-02,9.999996757168280181e-01,0.000000000000000000e+00 +7.542498765880202427e+01,4.601577979460276424e+02,2.646758696285253620e+00,6.927946618162353687e+00,-2.983284398447354491e-01,-7.505990680926384433e-03,4.563496123041156649e-02,9.999996421209141895e-01,0.000000000000000000e+00 +7.542643108793782858e+01,4.601673562373680397e+02,2.643819467363888620e+00,6.927935783796711711e+00,-2.981617731780688008e-01,-6.062562061688314685e-03,4.563496123041156649e-02,9.999996049956644262e-01,0.000000000000000000e+00 +7.542787451933097032e+01,4.601769150184471755e+02,2.640881831531895596e+00,6.927927032904309002e+00,-2.979951065114021524e-01,-4.619131238708550601e-03,4.563496123041156649e-02,9.999995613878588374e-01,0.000000000000000000e+00 +7.542931795254735050e+01,4.601864742889995341e+02,2.637945788870875496e+00,6.927920365496848198e+00,-2.978284398447355041e-01,-3.175698655428813889e-03,4.563496123041156649e-02,9.999995087642378211e-01,0.000000000000000000e+00 +7.543076138715289858e+01,4.601960340487595431e+02,2.635011339462384861e+00,6.927915781583512178e+00,-2.976617731780688558e-01,-1.732264758953127193e-03,4.563496123041156649e-02,9.999994488480796750e-01,0.000000000000000000e+00 +7.543220482271350136e+01,4.602055942974616869e+02,2.632078483387936707e+00,6.927913281170958726e+00,-2.974951065114022075e-01,-2.888299939024614130e-04,4.563496123041156649e-02,9.999993735516009563e-01,0.000000000000000000e+00 +7.543364825879507407e+01,4.602151550348403930e+02,2.629147220728998757e+00,6.927912864263324089e+00,-2.973284398447355592e-01,1.154605183424961155e-03,4.563496123041156649e-02,9.999992845852971879e-01,0.000000000000000000e+00 +7.543509169496350353e+01,4.602247162606300890e+02,2.626217551566995212e+00,6.927914530862206099e+00,-2.971617731780689109e-01,2.598040319198181586e-03,4.563496123041156649e-02,9.999991729959804010e-01,0.000000000000000000e+00 +7.543653513078469075e+01,4.602342779745651455e+02,2.623289475983305863e+00,6.927918280966667730e+00,-2.969951065114022626e-01,4.041474946662511163e-03,4.563496123041156649e-02,9.999990311028467138e-01,0.000000000000000000e+00 +7.543797856582455097e+01,4.602438401763799902e+02,2.620362994059266093e+00,6.927924114573218439e+00,-2.968284398447356143e-01,5.484908587977510575e-03,4.563496123041156649e-02,9.999988499396538222e-01,0.000000000000000000e+00 +7.543942199964897100e+01,4.602534028658090506e+02,2.617438105876166876e+00,6.927932031675798186e+00,-2.966617731780689660e-01,6.928340752362955636e-03,4.563496123041156649e-02,9.999986064658448193e-01,0.000000000000000000e+00 +7.544086543182386606e+01,4.602629660425866405e+02,2.614514811515255222e+00,6.927942032265758776e+00,-2.964951065114023177e-01,8.371770915784976230e-03,4.563496123041156649e-02,9.999982712394741569e-01,0.000000000000000000e+00 +7.544230886191513719e+01,4.602725297064471306e+02,2.611593111057733729e+00,6.927954116331815904e+00,-2.963284398447356693e-01,9.815198511717715749e-03,4.563496123041156649e-02,9.999977832653841325e-01,0.000000000000000000e+00 +7.544375228948871381e+01,4.602820938571248917e+02,2.608673004584760591e+00,6.927968283859987864e+00,-2.961617731780690210e-01,1.125862288560034591e-02,4.563496123041156649e-02,9.999970218584286474e-01,0.000000000000000000e+00 +7.544519571411051118e+01,4.602916584943541807e+02,2.605754492177450476e+00,6.927984534833468544e+00,-2.959951065114023727e-01,1.270204320868137220e-02,4.563496123041156649e-02,9.999956940978895759e-01,0.000000000000000000e+00 +7.544663913534647293e+01,4.603012236178693684e+02,2.602837573916872760e+00,6.928002869232376071e+00,-2.958284398447357244e-01,1.414545822941355550e-02,4.563496123041156649e-02,9.999928799559436587e-01,0.000000000000000000e+00 +7.544808255276254272e+01,4.603107892274047686e+02,2.599922249884052849e+00,6.928023287033142630e+00,-2.956617731780690761e-01,1.558886536828320638e-02,4.563496123041156649e-02,9.999834397999445290e-01,0.000000000000000000e+00 +7.544952596592466421e+01,4.603203553226946383e+02,2.597008520159972189e+00,6.928045788206597777e+00,-2.954951065114024278e-01,1.703225462719572605e-02,4.563496123041156649e-02,-9.998756666034172014e-01,0.000000000000000000e+00 +7.545096937439880946e+01,4.603299219034732914e+02,2.594096384825567370e+00,6.928070372707260560e+00,-2.953284398447357795e-01,1.558902561692348566e-02,4.563496123041156649e-02,-9.999846029376721068e-01,0.000000000000000000e+00 +7.545241277775097899e+01,4.603394889694749281e+02,2.591185843961731461e+00,6.928092873959093012e+00,-2.951617731780691312e-01,1.414564448892996137e-02,4.563496123041156649e-02,-9.999909401730318059e-01,0.000000000000000000e+00 +7.545385617641521492e+01,4.603490565204338623e+02,2.588276897649312236e+00,6.928113291763453141e+00,-2.949951065114024829e-01,1.270225890163256995e-02,4.563496123041156649e-02,-9.999930693471639209e-01,0.000000000000000000e+00 +7.545529957082561623e+01,4.603586245560842940e+02,2.585369545969114391e+00,6.928131626132951304e+00,-2.948284398447358345e-01,1.125887449489081787e-02,4.563496123041156649e-02,-9.999940002158120844e-01,0.000000000000000000e+00 +7.545674296141626769e+01,4.603681930761604235e+02,2.582463789001897325e+00,6.928147877086458628e+00,-2.946617731780691862e-01,9.815492564264919825e-03,4.563496123041156649e-02,-9.999943663144910122e-01,0.000000000000000000e+00 +7.545818634862125407e+01,4.603777620803965078e+02,2.579559626828376917e+00,6.928162044642836470e+00,-2.944951065114025379e-01,8.372113490873914904e-03,4.563496123041156649e-02,-9.999943424701798200e-01,0.000000000000000000e+00 +7.545962973287461750e+01,4.603873315685266903e+02,2.576657059529223748e+00,6.928174128819616584e+00,-2.943284398447358896e-01,6.928737403498158413e-03,4.563496123041156649e-02,-9.999939201912094733e-01,0.000000000000000000e+00 +7.546107311461041434e+01,4.603969015402851710e+02,2.573756087185065322e+00,6.928184129632636967e+00,-2.941617731780692413e-01,5.485364443180281921e-03,4.563496123041156649e-02,-9.999928889045748281e-01,0.000000000000000000e+00 +7.546251649426270092e+01,4.604064719954061502e+02,2.570856709876483848e+00,6.928192047096059625e+00,-2.939951065114025930e-01,4.041995054905090506e-03,4.563496123041156649e-02,-9.999904987309691240e-01,0.000000000000000000e+00 +7.546395987226550517e+01,4.604160429336237712e+02,2.567958927684017567e+00,6.928197881222809329e+00,-2.938284398447359447e-01,2.598630766020931359e-03,4.563496123041156649e-02,-9.999828658673952653e-01,0.000000000000000000e+00 +7.546540324905286923e+01,4.604256143546721205e+02,2.565062740688160314e+00,6.928201632026135925e+00,-2.936617731780692964e-01,1.155278709669300572e-03,4.563496123041156649e-02,-8.004728505678059269e-01,0.000000000000000000e+00 +7.546684662505880681e+01,4.604351862582853983e+02,2.562168148969361958e+00,6.928203299527705639e+00,-2.934951065114026481e-01,-1.045962488755254204e-07,4.563496123041156649e-02,7.244338607266526250e-05,0.000000000000000000e+00 +7.546829000071736004e+01,4.604447586441976341e+02,2.559275152608027515e+00,6.928203299376733959e+00,-2.933284398447359997e-01,-3.322879555212875798e-11,4.563496123041156649e-02,2.302158509785734186e-08,0.000000000000000000e+00 +7.546973337637594170e+01,4.604543315121430282e+02,2.556383751684518479e+00,6.928203299376685997e+00,-2.931617731780693514e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547117675203452336e+01,4.604639048618556103e+02,2.553493946279151050e+00,6.928203299376685997e+00,-2.929951065114027031e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547262012769310502e+01,4.604734786930694668e+02,2.550605736472197904e+00,6.928203299376685997e+00,-2.928284398447360548e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547406350335168668e+01,4.604830530055186273e+02,2.547719122343887310e+00,6.928203299376685997e+00,-2.926617731780694065e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547550687901026834e+01,4.604926277989371783e+02,2.544834103974402684e+00,6.928203299376685997e+00,-2.924951065114027582e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547695025466884999e+01,4.605022030730591496e+02,2.541950681443883475e+00,6.928203299376685997e+00,-2.923284398447361099e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547839363032743165e+01,4.605117788276185138e+02,2.539068854832424726e+00,6.928203299376685997e+00,-2.921617731780694616e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.547983700598601331e+01,4.605213550623493575e+02,2.536188624220077070e+00,6.928203299376685997e+00,-2.919951065114028133e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548128038164459497e+01,4.605309317769855966e+02,2.533309989686847175e+00,6.928203299376685997e+00,-2.918284398447361649e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548272375730317663e+01,4.605405089712612607e+02,2.530432951312696854e+00,6.928203299376685997e+00,-2.916617731780695166e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548416713296175828e+01,4.605500866449102659e+02,2.527557509177543960e+00,6.928203299376685997e+00,-2.914951065114028683e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548561050862033994e+01,4.605596647976666418e+02,2.524683663361261932e+00,6.928203299376685997e+00,-2.913284398447362200e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548705388427892160e+01,4.605692434292643043e+02,2.521811413943679803e+00,6.928203299376685997e+00,-2.911617731780695717e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548849725993750326e+01,4.605788225394371125e+02,2.518940761004582196e+00,6.928203299376685997e+00,-2.909951065114029234e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.548994063559608492e+01,4.605884021279190392e+02,2.516071704623709326e+00,6.928203299376685997e+00,-2.908284398447362751e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.549138401125466658e+01,4.605979821944440005e+02,2.513204244880757443e+00,6.928203299376685997e+00,-2.906617731780696268e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.549282738691324823e+01,4.606075627387458553e+02,2.510338381855378387e+00,6.928203299376685997e+00,-2.904951065114029785e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.549427076257182989e+01,4.606171437605584629e+02,2.507474115627179145e+00,6.928203299376685997e+00,-2.903284398447363301e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.549571413823041155e+01,4.606267252596157391e+02,2.504611446275722741e+00,6.928203299376685997e+00,-2.901617731780696818e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.549715751388899321e+01,4.606363072356514863e+02,2.501750373880527789e+00,6.928203299376685997e+00,-2.899951065114030335e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.549860088954757487e+01,4.606458896883995635e+02,2.498890898521068493e+00,6.928203299376685997e+00,-2.898284398447363852e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550004426520615652e+01,4.606554726175937731e+02,2.496033020276774650e+00,6.928203299376685997e+00,-2.896617731780697369e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550148764086473818e+01,4.606650560229679172e+02,2.493176739227032090e+00,6.928203299376685997e+00,-2.894951065114030886e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550293101652331984e+01,4.606746399042557982e+02,2.490322055451181349e+00,6.928203299376685997e+00,-2.893284398447364403e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550437439218190150e+01,4.606842242611911615e+02,2.487468969028519883e+00,6.928203299376685997e+00,-2.891617731780697920e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550581776784048316e+01,4.606938090935078094e+02,2.484617480038299853e+00,6.928203299376685997e+00,-2.889951065114031437e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550726114349906481e+01,4.607033944009395441e+02,2.481767588559729010e+00,6.928203299376685997e+00,-2.888284398447364953e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.550870451915764647e+01,4.607129801832200542e+02,2.478919294671971141e+00,6.928203299376685997e+00,-2.886617731780698470e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551014789481622813e+01,4.607225664400830283e+02,2.476072598454145623e+00,6.928203299376685997e+00,-2.884951065114031987e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551159127047480979e+01,4.607321531712622686e+02,2.473227499985327427e+00,6.928203299376685997e+00,-2.883284398447365504e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551303464613339145e+01,4.607417403764914070e+02,2.470383999344547110e+00,6.928203299376685997e+00,-2.881617731780699021e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551447802179197311e+01,4.607513280555041888e+02,2.467542096610790381e+00,6.928203299376685997e+00,-2.879951065114032538e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551592139745055476e+01,4.607609162080342458e+02,2.464701791862999425e+00,6.928203299376685997e+00,-2.878284398447366055e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551736477310913642e+01,4.607705048338152665e+02,2.461863085180071575e+00,6.928203299376685997e+00,-2.876617731780699572e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.551880814876771808e+01,4.607800939325808827e+02,2.459025976640859312e+00,6.928203299376685997e+00,-2.874951065114033089e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552025152442629974e+01,4.607896835040647261e+02,2.456190466324171595e+00,6.928203299376685997e+00,-2.873284398447366605e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552169490008488140e+01,4.607992735480004285e+02,2.453356554308772530e+00,6.928203299376685997e+00,-2.871617731780700122e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552313827574346305e+01,4.608088640641216216e+02,2.450524240673381815e+00,6.928203299376685997e+00,-2.869951065114033639e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552458165140204471e+01,4.608184550521618803e+02,2.447693525496675182e+00,6.928203299376685997e+00,-2.868284398447367156e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552602502706062637e+01,4.608280465118547795e+02,2.444864408857283067e+00,6.928203299376685997e+00,-2.866617731780700673e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552746840271920803e+01,4.608376384429338941e+02,2.442036890833792384e+00,6.928203299376685997e+00,-2.864951065114034190e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.552891177837778969e+01,4.608472308451327990e+02,2.439210971504745196e+00,6.928203299376685997e+00,-2.863284398447367707e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553035515403637135e+01,4.608568237181850122e+02,2.436386650948639598e+00,6.928203299376685997e+00,-2.861617731780701224e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553179852969495300e+01,4.608664170618241087e+02,2.433563929243928392e+00,6.928203299376685997e+00,-2.859951065114034741e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553324190535353466e+01,4.608760108757835496e+02,2.430742806469020856e+00,6.928203299376685997e+00,-2.858284398447368257e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553468528101211632e+01,4.608856051597969099e+02,2.427923282702281416e+00,6.928203299376685997e+00,-2.856617731780701774e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553612865667069798e+01,4.608951999135976507e+02,2.425105358022030089e+00,6.928203299376685997e+00,-2.854951065114035291e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553757203232927964e+01,4.609047951369192333e+02,2.422289032506542927e+00,6.928203299376685997e+00,-2.853284398447368808e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.553901540798786129e+01,4.609143908294951189e+02,2.419474306234050687e+00,6.928203299376685997e+00,-2.851617731780702325e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554045878364644295e+01,4.609239869910587686e+02,2.416661179282740601e+00,6.928203299376685997e+00,-2.849951065114035842e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554190215930502461e+01,4.609335836213436437e+02,2.413849651730755053e+00,6.928203299376685997e+00,-2.848284398447369359e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554334553496360627e+01,4.609431807200831486e+02,2.411039723656191569e+00,6.928203299376685997e+00,-2.846617731780702876e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554478891062218793e+01,4.609527782870106876e+02,2.408231395137104158e+00,6.928203299376685997e+00,-2.844951065114036393e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554623228628076959e+01,4.609623763218596650e+02,2.405424666251501975e+00,6.928203299376685997e+00,-2.843284398447369909e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554767566193935124e+01,4.609719748243634854e+02,2.402619537077349321e+00,6.928203299376685997e+00,-2.841617731780703426e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.554911903759793290e+01,4.609815737942555529e+02,2.399816007692566977e+00,6.928203299376685997e+00,-2.839951065114036943e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555056241325651456e+01,4.609911732312692152e+02,2.397014078175030427e+00,6.928203299376685997e+00,-2.838284398447370460e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555200578891509622e+01,4.610007731351377629e+02,2.394213748602571190e+00,6.928203299376685997e+00,-2.836617731780703977e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555344916457367788e+01,4.610103735055946004e+02,2.391415019052975932e+00,6.928203299376685997e+00,-2.834951065114037494e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555489254023225953e+01,4.610199743423730183e+02,2.388617889603987354e+00,6.928203299376685997e+00,-2.833284398447371011e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555633591589084119e+01,4.610295756452063074e+02,2.385822360333303305e+00,6.928203299376685997e+00,-2.831617731780704528e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555777929154942285e+01,4.610391774138278151e+02,2.383028431318577667e+00,6.928203299376685997e+00,-2.829951065114038045e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.555922266720800451e+01,4.610487796479707754e+02,2.380236102637419471e+00,6.928203299376685997e+00,-2.828284398447371562e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556066604286658617e+01,4.610583823473684788e+02,2.377445374367393338e+00,6.928203299376685997e+00,-2.826617731780705078e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556210941852516783e+01,4.610679855117542161e+02,2.374656246586019481e+00,6.928203299376685997e+00,-2.824951065114038595e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556355279418374948e+01,4.610775891408611642e+02,2.371868719370773704e+00,6.928203299376685997e+00,-2.823284398447372112e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556499616984233114e+01,4.610871932344226138e+02,2.369082792799087400e+00,6.928203299376685997e+00,-2.821617731780705629e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556643954550091280e+01,4.610967977921717988e+02,2.366298466948347112e+00,6.928203299376685997e+00,-2.819951065114039146e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556788292115949446e+01,4.611064028138418394e+02,2.363515741895895861e+00,6.928203299376685997e+00,-2.818284398447372663e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.556932629681807612e+01,4.611160082991660261e+02,2.360734617719030926e+00,6.928203299376685997e+00,-2.816617731780706180e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557076967247665777e+01,4.611256142478774791e+02,2.357955094495006065e+00,6.928203299376685997e+00,-2.814951065114039697e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557221304813523943e+01,4.611352206597093755e+02,2.355177172301030186e+00,6.928203299376685997e+00,-2.813284398447373214e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557365642379382109e+01,4.611448275343948922e+02,2.352400851214267785e+00,6.928203299376685997e+00,-2.811617731780706730e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557509979945240275e+01,4.611544348716671493e+02,2.349626131311838950e+00,6.928203299376685997e+00,-2.809951065114040247e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557654317511098441e+01,4.611640426712592671e+02,2.346853012670818917e+00,6.928203299376685997e+00,-2.808284398447373764e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557798655076956607e+01,4.611736509329044225e+02,2.344081495368239398e+00,6.928203299376685997e+00,-2.806617731780707281e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.557942992642814772e+01,4.611832596563356788e+02,2.341311579481086369e+00,6.928203299376685997e+00,-2.804951065114040798e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558087330208672938e+01,4.611928688412860993e+02,2.338543265086302281e+00,6.928203299376685997e+00,-2.803284398447374315e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558231667774531104e+01,4.612024784874888041e+02,2.335776552260784733e+00,6.928203299376685997e+00,-2.801617731780707832e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558376005340389270e+01,4.612120885946768567e+02,2.333011441081386916e+00,6.928203299376685997e+00,-2.799951065114041349e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558520342906247436e+01,4.612216991625832634e+02,2.330247931624917168e+00,6.928203299376685997e+00,-2.798284398447374866e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558664680472105601e+01,4.612313101909410875e+02,2.327486023968139861e+00,6.928203299376685997e+00,-2.796617731780708382e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558809018037963767e+01,4.612409216794833924e+02,2.324725718187774515e+00,6.928203299376685997e+00,-2.794951065114041899e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.558953355603821933e+01,4.612505336279431845e+02,2.321967014360496240e+00,6.928203299376685997e+00,-2.793284398447375416e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559097693169680099e+01,4.612601460360534134e+02,2.319209912562936182e+00,6.928203299376685997e+00,-2.791617731780708933e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559242030735538265e+01,4.612697589035471424e+02,2.316454412871680191e+00,6.928203299376685997e+00,-2.789951065114042450e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559386368301396431e+01,4.612793722301572643e+02,2.313700515363269705e+00,6.928203299376685997e+00,-2.788284398447375967e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559530705867254596e+01,4.612889860156167856e+02,2.310948220114202201e+00,6.928203299376685997e+00,-2.786617731780709484e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559675043433112762e+01,4.612986002596586559e+02,2.308197527200929855e+00,6.928203299376685997e+00,-2.784951065114043001e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559819380998970928e+01,4.613082149620158248e+02,2.305448436699861325e+00,6.928203299376685997e+00,-2.783284398447376518e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.559963718564829094e+01,4.613178301224211850e+02,2.302700948687359972e+00,6.928203299376685997e+00,-2.781617731780710034e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560108056130687260e+01,4.613274457406076863e+02,2.299955063239745190e+00,6.928203299376685997e+00,-2.779951065114043551e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560252393696545425e+01,4.613370618163082213e+02,2.297210780433291077e+00,6.928203299376685997e+00,-2.778284398447377068e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560396731262403591e+01,4.613466783492556260e+02,2.294468100344228212e+00,6.928203299376685997e+00,-2.776617731780710585e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560541068828261757e+01,4.613562953391828501e+02,2.291727023048741874e+00,6.928203299376685997e+00,-2.774951065114044102e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560685406394119923e+01,4.613659127858227293e+02,2.288987548622973378e+00,6.928203299376685997e+00,-2.773284398447377619e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560829743959978089e+01,4.613755306889080998e+02,2.286249677143018744e+00,6.928203299376685997e+00,-2.771617731780711136e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.560974081525836255e+01,4.613851490481717974e+02,2.283513408684930468e+00,6.928203299376685997e+00,-2.769951065114044653e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561118419091694420e+01,4.613947678633466580e+02,2.280778743324715752e+00,6.928203299376685997e+00,-2.768284398447378170e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561262756657552586e+01,4.614043871341654608e+02,2.278045681138337386e+00,6.928203299376685997e+00,-2.766617731780711686e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561407094223410752e+01,4.614140068603610416e+02,2.275314222201714198e+00,6.928203299376685997e+00,-2.764951065114045203e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561551431789268918e+01,4.614236270416661228e+02,2.272584366590719718e+00,6.928203299376685997e+00,-2.763284398447378720e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561695769355127084e+01,4.614332476778135401e+02,2.269856114381183065e+00,6.928203299376685997e+00,-2.761617731780712237e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561840106920985249e+01,4.614428687685360728e+02,2.267129465648889397e+00,6.928203299376685997e+00,-2.759951065114045754e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.561984444486843415e+01,4.614524903135663862e+02,2.264404420469579016e+00,6.928203299376685997e+00,-2.758284398447379271e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562128782052701581e+01,4.614621123126372595e+02,2.261680978918947371e+00,6.928203299376685997e+00,-2.756617731780712788e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562273119618559747e+01,4.614717347654814148e+02,2.258959141072645505e+00,6.928203299376685997e+00,-2.754951065114046305e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562417457184417913e+01,4.614813576718315744e+02,2.256238907006280492e+00,6.928203299376685997e+00,-2.753284398447379822e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562561794750276079e+01,4.614909810314204606e+02,2.253520276795414112e+00,6.928203299376685997e+00,-2.751617731780713338e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562706132316134244e+01,4.615006048439806818e+02,2.250803250515563736e+00,6.928203299376685997e+00,-2.749951065114046855e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562850469881992410e+01,4.615102291092449605e+02,2.248087828242202324e+00,6.928203299376685997e+00,-2.748284398447380372e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.562994807447850576e+01,4.615198538269459618e+02,2.245374010050758429e+00,6.928203299376685997e+00,-2.746617731780713889e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.563139145013708742e+01,4.615294789968162945e+02,2.242661796016615749e+00,6.928203299376685997e+00,-2.744951065114047406e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.563283482579566908e+01,4.615391046185886239e+02,2.239951186215114021e+00,6.928203299376685997e+00,-2.743284398447380923e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.563427820145425073e+01,4.615487306919955586e+02,2.237242180721547236e+00,6.928203299376685997e+00,-2.741617731780714440e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.563572157711283239e+01,4.615583572167697071e+02,2.234534779611166311e+00,6.928203299376685997e+00,-2.739951065114047957e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.563716495277141405e+01,4.615679841926436779e+02,2.231828982959176422e+00,6.928203299376685997e+00,-2.738284398447381474e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.563860832842999571e+01,4.615776116193500229e+02,2.229124790840738335e+00,6.928203299376685997e+00,-2.736617731780714990e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564005170408857737e+01,4.615872394966213506e+02,2.226422203330968852e+00,6.928203299376685997e+00,-2.734951065114048507e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564149507974715902e+01,4.615968678241902126e+02,2.223721220504939922e+00,6.928203299376685997e+00,-2.733284398447382024e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564293845540574068e+01,4.616064966017891606e+02,2.221021842437678639e+00,6.928203299376685997e+00,-2.731617731780715541e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564438183106432234e+01,4.616161258291506897e+02,2.218324069204167692e+00,6.928203299376685997e+00,-2.729951065114049058e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564582520672290400e+01,4.616257555060073514e+02,2.215627900879345358e+00,6.928203299376685997e+00,-2.728284398447382575e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564726858238148566e+01,4.616353856320916975e+02,2.212933337538105061e+00,6.928203299376685997e+00,-2.726617731780716092e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.564871195804006732e+01,4.616450162071361660e+02,2.210240379255295817e+00,6.928203299376685997e+00,-2.724951065114049609e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565015533369864897e+01,4.616546472308732518e+02,2.207549026105722234e+00,6.928203299376685997e+00,-2.723284398447383126e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565159870935723063e+01,4.616642787030354498e+02,2.204859278164144065e+00,6.928203299376685997e+00,-2.721617731780716642e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565304208501581229e+01,4.616739106233551979e+02,2.202171135505276212e+00,6.928203299376685997e+00,-2.719951065114050159e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565448546067439395e+01,4.616835429915649343e+02,2.199484598203789609e+00,6.928203299376685997e+00,-2.718284398447383676e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565592883633297561e+01,4.616931758073970968e+02,2.196799666334310341e+00,6.928203299376685997e+00,-2.716617731780717193e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565737221199155726e+01,4.617028090705841237e+02,2.194116339971419638e+00,6.928203299376685997e+00,-2.714951065114050710e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.565881558765013892e+01,4.617124427808583960e+02,2.191434619189654320e+00,6.928203299376685997e+00,-2.713284398447384227e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566025896330872058e+01,4.617220769379523517e+02,2.188754504063506801e+00,6.928203299376685997e+00,-2.711617731780717744e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566170233896730224e+01,4.617317115415983153e+02,2.186075994667424638e+00,6.928203299376685997e+00,-2.709951065114051261e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566314571462588390e+01,4.617413465915287247e+02,2.183399091075810983e+00,6.928203299376685997e+00,-2.708284398447384778e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566458909028446556e+01,4.617509820874759043e+02,2.180723793363024132e+00,6.928203299376685997e+00,-2.706617731780718294e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566603246594304721e+01,4.617606180291721785e+02,2.178050101603377975e+00,6.928203299376685997e+00,-2.704951065114051811e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566747584160162887e+01,4.617702544163499283e+02,2.175378015871141546e+00,6.928203299376685997e+00,-2.703284398447385328e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.566891921726021053e+01,4.617798912487414782e+02,2.172707536240539916e+00,6.928203299376685997e+00,-2.701617731780718845e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567036259291879219e+01,4.617895285260790956e+02,2.170038662785752415e+00,6.928203299376685997e+00,-2.699951065114052362e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567180596857737385e+01,4.617991662480951049e+02,2.167371395580914850e+00,6.928203299376685997e+00,-2.698284398447385879e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567324934423595550e+01,4.618088044145217737e+02,2.164705734700118178e+00,6.928203299376685997e+00,-2.696617731780719396e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567469271989453716e+01,4.618184430250914261e+02,2.162041680217408057e+00,6.928203299376685997e+00,-2.694951065114052913e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567613609555311882e+01,4.618280820795362729e+02,2.159379232206786181e+00,6.928203299376685997e+00,-2.693284398447386430e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567757947121170048e+01,4.618377215775885816e+02,2.156718390742209390e+00,6.928203299376685997e+00,-2.691617731780719946e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.567902284687028214e+01,4.618473615189805628e+02,2.154059155897590117e+00,6.928203299376685997e+00,-2.689951065114053463e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568046622252886380e+01,4.618570019034444840e+02,2.151401527746795939e+00,6.928203299376685997e+00,-2.688284398447386980e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568190959818744545e+01,4.618666427307125559e+02,2.148745506363649582e+00,6.928203299376685997e+00,-2.686617731780720497e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568335297384602711e+01,4.618762840005169323e+02,2.146091091821929808e+00,6.928203299376685997e+00,-2.684951065114054014e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568479634950460877e+01,4.618859257125898239e+02,2.143438284195370080e+00,6.928203299376685997e+00,-2.683284398447387531e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568623972516319043e+01,4.618955678666633844e+02,2.140787083557659898e+00,6.928203299376685997e+00,-2.681617731780721048e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568768310082177209e+01,4.619052104624698245e+02,2.138137489982443462e+00,6.928203299376685997e+00,-2.679951065114054565e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.568912647648035374e+01,4.619148534997412412e+02,2.135489503543320566e+00,6.928203299376685997e+00,-2.678284398447388082e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569056985213893540e+01,4.619244969782097883e+02,2.132843124313846150e+00,6.928203299376685997e+00,-2.676617731780721599e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569201322779751706e+01,4.619341408976076195e+02,2.130198352367531189e+00,6.928203299376685997e+00,-2.674951065114055115e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569345660345609872e+01,4.619437852576668320e+02,2.127555187777841361e+00,6.928203299376685997e+00,-2.673284398447388632e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569489997911468038e+01,4.619534300581195225e+02,2.124913630618197935e+00,6.928203299376685997e+00,-2.671617731780722149e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569634335477326204e+01,4.619630752986977882e+02,2.122273680961977327e+00,6.928203299376685997e+00,-2.669951065114055666e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569778673043184369e+01,4.619727209791337259e+02,2.119635338882511544e+00,6.928203299376685997e+00,-2.668284398447389183e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.569923010609042535e+01,4.619823670991593190e+02,2.116998604453088184e+00,6.928203299376685997e+00,-2.666617731780722700e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570067348174900701e+01,4.619920136585067212e+02,2.114363477746949549e+00,6.928203299376685997e+00,-2.664951065114056217e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570211685740758867e+01,4.620016606569079158e+02,2.111729958837293530e+00,6.928203299376685997e+00,-2.663284398447389734e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570356023306617033e+01,4.620113080940949430e+02,2.109098047797273612e+00,6.928203299376685997e+00,-2.661617731780723251e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570500360872475198e+01,4.620209559697997861e+02,2.106467744699998423e+00,6.928203299376685997e+00,-2.659951065114056767e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570644698438333364e+01,4.620306042837544851e+02,2.103839049618531742e+00,6.928203299376685997e+00,-2.658284398447390284e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570789036004191530e+01,4.620402530356910233e+02,2.101211962625893381e+00,6.928203299376685997e+00,-2.656617731780723801e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.570933373570049696e+01,4.620499022253413841e+02,2.098586483795057411e+00,6.928203299376685997e+00,-2.654951065114057318e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571077711135907862e+01,4.620595518524375507e+02,2.095962613198953939e+00,6.928203299376685997e+00,-2.653284398447390835e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571222048701766028e+01,4.620692019167114495e+02,2.093340350910468661e+00,6.928203299376685997e+00,-2.651617731780724352e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571366386267624193e+01,4.620788524178950070e+02,2.090719697002441979e+00,6.928203299376685997e+00,-2.649951065114057869e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571510723833482359e+01,4.620885033557202064e+02,2.088100651547669440e+00,6.928203299376685997e+00,-2.648284398447391386e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571655061399340525e+01,4.620981547299189174e+02,2.085483214618902625e+00,6.928203299376685997e+00,-2.646617731780724903e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571799398965198691e+01,4.621078065402230663e+02,2.082867386288848266e+00,6.928203299376685997e+00,-2.644951065114058419e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.571943736531056857e+01,4.621174587863645797e+02,2.080253166630168238e+00,6.928203299376685997e+00,-2.643284398447391936e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572088074096915022e+01,4.621271114680753271e+02,2.077640555715479564e+00,6.928203299376685997e+00,-2.641617731780725453e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572232411662773188e+01,4.621367645850871213e+02,2.075029553617354861e+00,6.928203299376685997e+00,-2.639951065114058970e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572376749228631354e+01,4.621464181371318887e+02,2.072420160408321888e+00,6.928203299376685997e+00,-2.638284398447392487e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572521086794489520e+01,4.621560721239414420e+02,2.069812376160863554e+00,6.928203299376685997e+00,-2.636617731780726004e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572665424360347686e+01,4.621657265452475940e+02,2.067206200947418804e+00,6.928203299376685997e+00,-2.634951065114059521e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572809761926205852e+01,4.621753814007822143e+02,2.064601634840381283e+00,6.928203299376685997e+00,-2.633284398447393038e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.572954099492064017e+01,4.621850366902770588e+02,2.061998677912099787e+00,6.928203299376685997e+00,-2.631617731780726555e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573098437057922183e+01,4.621946924134639403e+02,2.059397330234878698e+00,6.928203299376685997e+00,-2.629951065114060071e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573242774623780349e+01,4.622043485700746714e+02,2.056797591880977993e+00,6.928203299376685997e+00,-2.628284398447393588e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573387112189638515e+01,4.622140051598410082e+02,2.054199462922612351e+00,6.928203299376685997e+00,-2.626617731780727105e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573531449755496681e+01,4.622236621824947633e+02,2.051602943431952042e+00,6.928203299376685997e+00,-2.624951065114060622e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573675787321354846e+01,4.622333196377676359e+02,2.049008033481122926e+00,6.928203299376685997e+00,-2.623284398447394139e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573820124887213012e+01,4.622429775253913249e+02,2.046414733142205566e+00,6.928203299376685997e+00,-2.621617731780727656e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.573964462453071178e+01,4.622526358450976431e+02,2.043823042487236119e+00,6.928203299376685997e+00,-2.619951065114061173e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574108800018929344e+01,4.622622945966182328e+02,2.041232961588205885e+00,6.928203299376685997e+00,-2.618284398447394690e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574253137584787510e+01,4.622719537796847931e+02,2.038644490517061758e+00,6.928203299376685997e+00,-2.616617731780728207e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574397475150645676e+01,4.622816133940290797e+02,2.036057629345705333e+00,6.928203299376685997e+00,-2.614951065114061723e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574541812716503841e+01,4.622912734393827350e+02,2.033472378145994242e+00,6.928203299376685997e+00,-2.613284398447395240e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574686150282362007e+01,4.623009339154774011e+02,2.030888736989740817e+00,6.928203299376685997e+00,-2.611617731780728757e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574830487848220173e+01,4.623105948220447772e+02,2.028306705948712985e+00,6.928203299376685997e+00,-2.609951065114062274e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.574974825414078339e+01,4.623202561588164485e+02,2.025726285094633816e+00,6.928203299376685997e+00,-2.608284398447395791e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575119162979936505e+01,4.623299179255240574e+02,2.023147474499181531e+00,6.928203299376685997e+00,-2.606617731780729308e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575263500545794670e+01,4.623395801218992460e+02,2.020570274233989938e+00,6.928203299376685997e+00,-2.604951065114062825e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575407838111652836e+01,4.623492427476736566e+02,2.017994684370647995e+00,6.928203299376685997e+00,-2.603284398447396342e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575552175677511002e+01,4.623589058025788177e+02,2.015420704980699806e+00,6.928203299376685997e+00,-2.601617731780729859e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575696513243369168e+01,4.623685692863463146e+02,2.012848336135644622e+00,6.928203299376685997e+00,-2.599951065114063375e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575840850809227334e+01,4.623782331987077328e+02,2.010277577906937285e+00,6.928203299376685997e+00,-2.598284398447396892e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.575985188375085500e+01,4.623878975393946575e+02,2.007708430365987784e+00,6.928203299376685997e+00,-2.596617731780730409e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576129525940943665e+01,4.623975623081386175e+02,2.005140893584161255e+00,6.928203299376685997e+00,-2.594951065114063926e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576273863506801831e+01,4.624072275046711411e+02,2.002574967632777980e+00,6.928203299376685997e+00,-2.593284398447397443e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576418201072659997e+01,4.624168931287237569e+02,2.000010652583113835e+00,6.928203299376685997e+00,-2.591617731780730960e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576562538638518163e+01,4.624265591800279367e+02,1.997447948506399840e+00,6.928203299376685997e+00,-2.589951065114064477e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576706876204376329e+01,4.624362256583152089e+02,1.994886855473822163e+00,6.928203299376685997e+00,-2.588284398447397994e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576851213770234494e+01,4.624458925633170452e+02,1.992327373556522341e+00,6.928203299376685997e+00,-2.586617731780731511e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.576995551336092660e+01,4.624555598947649742e+02,1.989769502825597058e+00,6.928203299376685997e+00,-2.584951065114065027e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.577139888901950826e+01,4.624652276523904106e+02,1.987213243352098369e+00,6.928203299376685997e+00,-2.583284398447398544e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.577284226467808992e+01,4.624748958359248263e+02,1.984658595207033249e+00,6.928203299376685997e+00,-2.581617731780732061e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.577428564033667158e+01,4.624845644450996360e+02,1.982105558461364270e+00,6.928203299376685997e+00,-2.579951065114065578e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.577572901599525323e+01,4.624942334796463115e+02,1.979554133186009146e+00,6.928203299376685997e+00,-2.578284398447399095e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.577717239165383489e+01,4.625039029392962107e+02,1.977004319451840963e+00,6.928203299376685997e+00,-2.576617731780732612e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.577861576731241655e+01,4.625135728237807484e+02,1.974456117329687732e+00,6.928203299376685997e+00,-2.574951065114066129e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578005914297099821e+01,4.625232431328313396e+02,1.971909526890332831e+00,6.928203299376685997e+00,-2.573284398447399646e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578150251862957987e+01,4.625329138661793991e+02,1.969364548204514787e+00,6.928203299376685997e+00,-2.571617731780733163e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578294589428816153e+01,4.625425850235562280e+02,1.966821181342927494e+00,6.928203299376685997e+00,-2.569951065114066679e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578438926994674318e+01,4.625522566046931843e+02,1.964279426376220217e+00,6.928203299376685997e+00,-2.568284398447400196e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578583264560532484e+01,4.625619286093216829e+02,1.961739283374997145e+00,6.928203299376685997e+00,-2.566617731780733713e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578727602126390650e+01,4.625716010371729681e+02,1.959200752409817614e+00,6.928203299376685997e+00,-2.564951065114067230e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.578871939692248816e+01,4.625812738879784547e+02,1.956663833551196552e+00,6.928203299376685997e+00,-2.563284398447400747e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579016277258106982e+01,4.625909471614693871e+02,1.954128526869604032e+00,6.928203299376685997e+00,-2.561617731780734264e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579160614823965147e+01,4.626006208573770664e+02,1.951594832435465054e+00,6.928203299376685997e+00,-2.559951065114067781e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579304952389823313e+01,4.626102949754327938e+02,1.949062750319160209e+00,6.928203299376685997e+00,-2.558284398447401298e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579449289955681479e+01,4.626199695153678704e+02,1.946532280591025010e+00,6.928203299376685997e+00,-2.556617731780734815e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579593627521539645e+01,4.626296444769134837e+02,1.944003423321350121e+00,6.928203299376685997e+00,-2.554951065114068331e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579737965087397811e+01,4.626393198598009349e+02,1.941476178580381795e+00,6.928203299376685997e+00,-2.553284398447401848e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.579882302653255977e+01,4.626489956637614682e+02,1.938950546438321210e+00,6.928203299376685997e+00,-2.551617731780735365e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580026640219114142e+01,4.626586718885263281e+02,1.936426526965324690e+00,6.928203299376685997e+00,-2.549951065114068882e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580170977784972308e+01,4.626683485338267019e+02,1.933904120231504153e+00,6.928203299376685997e+00,-2.548284398447402399e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580315315350830474e+01,4.626780255993937772e+02,1.931383326306926218e+00,6.928203299376685997e+00,-2.546617731780735916e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580459652916688640e+01,4.626877030849587982e+02,1.928864145261613094e+00,6.928203299376685997e+00,-2.544951065114069433e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580603990482546806e+01,4.626973809902528956e+02,1.926346577165541918e+00,6.928203299376685997e+00,-2.543284398447402950e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580748328048404971e+01,4.627070593150072568e+02,1.923830622088645192e+00,6.928203299376685997e+00,-2.541617731780736467e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.580892665614263137e+01,4.627167380589530694e+02,1.921316280100810570e+00,6.928203299376685997e+00,-2.539951065114069984e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581037003180121303e+01,4.627264172218214071e+02,1.918803551271880847e+00,6.928203299376685997e+00,-2.538284398447403500e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581181340745979469e+01,4.627360968033434574e+02,1.916292435671653971e+00,6.928203299376685997e+00,-2.536617731780737017e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581325678311837635e+01,4.627457768032503509e+02,1.913782933369883255e+00,6.928203299376685997e+00,-2.534951065114070534e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581470015877695801e+01,4.627554572212731614e+02,1.911275044436277160e+00,6.928203299376685997e+00,-2.533284398447404051e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581614353443553966e+01,4.627651380571430195e+02,1.908768768940499294e+00,6.928203299376685997e+00,-2.531617731780737568e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581758691009412132e+01,4.627748193105909991e+02,1.906264106952168191e+00,6.928203299376685997e+00,-2.529951065114071085e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.581903028575270298e+01,4.627845009813481738e+02,1.903761058540857976e+00,6.928203299376685997e+00,-2.528284398447404602e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582047366141128464e+01,4.627941830691456175e+02,1.901259623776097696e+00,6.928203299376685997e+00,-2.526617731780738119e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582191703706986630e+01,4.628038655737144040e+02,1.898759802727371548e+00,6.928203299376685997e+00,-2.524951065114071636e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582336041272844795e+01,4.628135484947855502e+02,1.896261595464119321e+00,6.928203299376685997e+00,-2.523284398447405152e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582480378838702961e+01,4.628232318320900731e+02,1.893765002055735280e+00,6.928203299376685997e+00,-2.521617731780738669e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582624716404561127e+01,4.628329155853589896e+02,1.891270022571569509e+00,6.928203299376685997e+00,-2.519951065114072186e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582769053970419293e+01,4.628425997543233166e+02,1.888776657080927013e+00,6.928203299376685997e+00,-2.518284398447405703e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.582913391536277459e+01,4.628522843387140711e+02,1.886284905653067723e+00,6.928203299376685997e+00,-2.516617731780739220e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583057729102135625e+01,4.628619693382622131e+02,1.883794768357207161e+00,6.928203299376685997e+00,-2.514951065114072737e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583202066667993790e+01,4.628716547526987597e+02,1.881306245262515775e+00,6.928203299376685997e+00,-2.513284398447406254e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583346404233851956e+01,4.628813405817546140e+02,1.878819336438119159e+00,6.928203299376685997e+00,-2.511617731780739771e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583490741799710122e+01,4.628910268251607363e+02,1.876334041953098053e+00,6.928203299376685997e+00,-2.509951065114073288e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583635079365568288e+01,4.629007134826480865e+02,1.873850361876488346e+00,6.928203299376685997e+00,-2.508284398447406804e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583779416931426454e+01,4.629104005539475679e+02,1.871368296277281296e+00,6.928203299376685997e+00,-2.506617731780740321e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.583923754497284619e+01,4.629200880387900838e+02,1.868887845224423305e+00,6.928203299376685997e+00,-2.504951065114073838e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584068092063142785e+01,4.629297759369065943e+02,1.866409008786815482e+00,6.928203299376685997e+00,-2.503284398447407355e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584212429629000951e+01,4.629394642480279458e+02,1.863931787033314524e+00,6.928203299376685997e+00,-2.501617731780740872e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584356767194859117e+01,4.629491529718850416e+02,1.861456180032732277e+00,6.928203299376685997e+00,-2.499951065114074111e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584501104760717283e+01,4.629588421082087280e+02,1.858982187853835510e+00,6.928203299376685997e+00,-2.498284398447407351e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584645442326575449e+01,4.629685316567298514e+02,1.856509810565346141e+00,6.928203299376685997e+00,-2.496617731780740590e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584789779892433614e+01,4.629782216171792584e+02,1.854039048235941456e+00,6.928203299376685997e+00,-2.494951065114073829e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.584934117458291780e+01,4.629879119892878521e+02,1.851569900934253665e+00,6.928203299376685997e+00,-2.493284398447407069e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585078455024149946e+01,4.629976027727863652e+02,1.849102368728870127e+00,6.928203299376685997e+00,-2.491617731780740308e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585222792590008112e+01,4.630072939674056443e+02,1.846636451688333569e+00,6.928203299376685997e+00,-2.489951065114073547e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585367130155866278e+01,4.630169855728765356e+02,1.844172149881141642e+00,6.928203299376685997e+00,-2.488284398447406787e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585511467721724443e+01,4.630266775889297719e+02,1.841709463375747147e+00,6.928203299376685997e+00,-2.486617731780740026e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585655805287582609e+01,4.630363700152961428e+02,1.839248392240558028e+00,6.928203299376685997e+00,-2.484951065114073265e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585800142853440775e+01,4.630460628517064379e+02,1.836788936543937378e+00,6.928203299376685997e+00,-2.483284398447406505e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.585944480419298941e+01,4.630557560978913898e+02,1.834331096354203217e+00,6.928203299376685997e+00,-2.481617731780739744e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586088817985157107e+01,4.630654497535817313e+02,1.831874871739629151e+00,6.928203299376685997e+00,-2.479951065114072983e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586233155551015273e+01,4.630751438185081952e+02,1.829420262768443495e+00,6.928203299376685997e+00,-2.478284398447406223e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586377493116873438e+01,4.630848382924015141e+02,1.826967269508829927e+00,6.928203299376685997e+00,-2.476617731780739462e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586521830682731604e+01,4.630945331749924208e+02,1.824515892028927277e+00,6.928203299376685997e+00,-2.474951065114072701e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586666168248589770e+01,4.631042284660115911e+02,1.822066130396829076e+00,6.928203299376685997e+00,-2.473284398447405941e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586810505814447936e+01,4.631139241651897009e+02,1.819617984680584444e+00,6.928203299376685997e+00,-2.471617731780739180e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.586954843380306102e+01,4.631236202722574262e+02,1.817171454948197429e+00,6.928203299376685997e+00,-2.469951065114072419e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587099180946164267e+01,4.631333167869454428e+02,1.814726541267627002e+00,6.928203299376685997e+00,-2.468284398447405659e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587243518512022433e+01,4.631430137089843697e+02,1.812283243706787506e+00,6.928203299376685997e+00,-2.466617731780738898e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587387856077880599e+01,4.631527110381048828e+02,1.809841562333548426e+00,6.928203299376685997e+00,-2.464951065114072137e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587532193643738765e+01,4.631624087740376012e+02,1.807401497215734176e+00,6.928203299376685997e+00,-2.463284398447405377e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587676531209596931e+01,4.631721069165131439e+02,1.804963048421124316e+00,6.928203299376685997e+00,-2.461617731780738616e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587820868775455097e+01,4.631818054652621299e+02,1.802526216017453775e+00,6.928203299376685997e+00,-2.459951065114071855e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.587965206341313262e+01,4.631915044200151215e+02,1.800091000072411962e+00,6.928203299376685997e+00,-2.458284398447405095e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588109543907171428e+01,4.632012037805027376e+02,1.797657400653644100e+00,6.928203299376685997e+00,-2.456617731780738334e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588253881473029594e+01,4.632109035464555404e+02,1.795225417828749892e+00,6.928203299376685997e+00,-2.454951065114071573e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588398219038887760e+01,4.632206037176040923e+02,1.792795051665284634e+00,6.928203299376685997e+00,-2.453284398447404813e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588542556604745926e+01,4.632303042936789552e+02,1.790366302230758322e+00,6.928203299376685997e+00,-2.451617731780738052e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588686894170604091e+01,4.632400052744106347e+02,1.787939169592636324e+00,6.928203299376685997e+00,-2.449951065114071291e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588831231736462257e+01,4.632497066595296928e+02,1.785513653818338931e+00,6.928203299376685997e+00,-2.448284398447404531e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.588975569302320423e+01,4.632594084487666350e+02,1.783089754975241581e+00,6.928203299376685997e+00,-2.446617731780737770e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589119906868178589e+01,4.632691106418519666e+02,1.780667473130674860e+00,6.928203299376685997e+00,-2.444951065114071009e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589264244434036755e+01,4.632788132385161930e+02,1.778246808351924502e+00,6.928203299376685997e+00,-2.443284398447404249e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589408581999894921e+01,4.632885162384898194e+02,1.775827760706230940e+00,6.928203299376685997e+00,-2.441617731780737488e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589552919565753086e+01,4.632982196415032945e+02,1.773410330260789980e+00,6.928203299376685997e+00,-2.439951065114070727e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589697257131611252e+01,4.633079234472870667e+02,1.770994517082752573e+00,6.928203299376685997e+00,-2.438284398447403967e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589841594697469418e+01,4.633176276555715845e+02,1.768580321239224595e+00,6.928203299376685997e+00,-2.436617731780737206e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.589985932263327584e+01,4.633273322660872964e+02,1.766167742797267071e+00,6.928203299376685997e+00,-2.434951065114070445e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590130269829185750e+01,4.633370372785645941e+02,1.763756781823895947e+00,6.928203299376685997e+00,-2.433284398447403685e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590274607395043915e+01,4.633467426927339261e+02,1.761347438386082542e+00,6.928203299376685997e+00,-2.431617731780736924e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590418944960902081e+01,4.633564485083257409e+02,1.758939712550753098e+00,6.928203299376685997e+00,-2.429951065114070163e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590563282526760247e+01,4.633661547250703734e+02,1.756533604384788561e+00,6.928203299376685997e+00,-2.428284398447403403e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590707620092618413e+01,4.633758613426982151e+02,1.754129113955025465e+00,6.928203299376685997e+00,-2.426617731780736642e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590851957658476579e+01,4.633855683609396579e+02,1.751726241328255274e+00,6.928203299376685997e+00,-2.424951065114069881e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.590996295224334744e+01,4.633952757795250363e+02,1.749324986571224372e+00,6.928203299376685997e+00,-2.423284398447403121e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.591140632790192910e+01,4.634049835981847423e+02,1.746925349750634293e+00,6.928203299376685997e+00,-2.421617731780736360e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.591284970356051076e+01,4.634146918166490536e+02,1.744527330933141718e+00,6.928203299376685997e+00,-2.419951065114069599e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.591429307921909242e+01,4.634244004346483621e+02,1.742130930185358251e+00,6.928203299376685997e+00,-2.418284398447402839e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.591573645487767408e+01,4.634341094519129456e+02,1.739736147573850422e+00,6.928203299376685997e+00,-2.416617731780736078e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.591717983053625574e+01,4.634438188681730821e+02,1.737342983165140131e+00,6.928203299376685997e+00,-2.414951065114069317e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.591862320619483739e+01,4.634535286831591065e+02,1.734951437025703980e+00,6.928203299376685997e+00,-2.413284398447402557e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592006658185341905e+01,4.634632388966012968e+02,1.732561509221973939e+00,6.928203299376685997e+00,-2.411617731780735796e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592150995751200071e+01,4.634729495082299309e+02,1.730173199820336905e+00,6.928203299376685997e+00,-2.409951065114069035e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592295333317058237e+01,4.634826605177752299e+02,1.727786508887134920e+00,6.928203299376685997e+00,-2.408284398447402275e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592439670882916403e+01,4.634923719249674718e+02,1.725401436488664730e+00,6.928203299376685997e+00,-2.406617731780735514e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592584008448774568e+01,4.635020837295369347e+02,1.723017982691178451e+00,6.928203299376685997e+00,-2.404951065114068753e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592728346014632734e+01,4.635117959312137828e+02,1.720636147560883122e+00,6.928203299376685997e+00,-2.403284398447401993e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.592872683580490900e+01,4.635215085297282940e+02,1.718255931163940708e+00,6.928203299376685997e+00,-2.401617731780735232e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593017021146349066e+01,4.635312215248106327e+02,1.715877333566468543e+00,6.928203299376685997e+00,-2.399951065114068471e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593161358712207232e+01,4.635409349161909631e+02,1.713500354834538664e+00,6.928203299376685997e+00,-2.398284398447401711e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593305696278065398e+01,4.635506487035995065e+02,1.711124995034178253e+00,6.928203299376685997e+00,-2.396617731780734950e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593450033843923563e+01,4.635603628867664838e+02,1.708751254231369643e+00,6.928203299376685997e+00,-2.394951065114068189e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593594371409781729e+01,4.635700774654220027e+02,1.706379132492049866e+00,6.928203299376685997e+00,-2.393284398447401429e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593738708975639895e+01,4.635797924392961704e+02,1.704008629882111325e+00,6.928203299376685997e+00,-2.391617731780734668e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.593883046541498061e+01,4.635895078081192082e+02,1.701639746467401348e+00,6.928203299376685997e+00,-2.389951065114067907e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594027384107356227e+01,4.635992235716212235e+02,1.699272482313722188e+00,6.928203299376685997e+00,-2.388284398447401147e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594171721673214392e+01,4.636089397295323238e+02,1.696906837486831243e+00,6.928203299376685997e+00,-2.386617731780734386e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594316059239072558e+01,4.636186562815826164e+02,1.694542812052440839e+00,6.928203299376685997e+00,-2.384951065114067625e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594460396804930724e+01,4.636283732275021521e+02,1.692180406076218224e+00,6.928203299376685997e+00,-2.383284398447400865e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594604734370788890e+01,4.636380905670210950e+02,1.689819619623786018e+00,6.928203299376685997e+00,-2.381617731780734104e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594749071936647056e+01,4.636478082998694390e+02,1.687460452760721541e+00,6.928203299376685997e+00,-2.379951065114067343e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.594893409502505222e+01,4.636575264257772915e+02,1.685102905552557040e+00,6.928203299376685997e+00,-2.378284398447400583e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595037747068363387e+01,4.636672449444747031e+02,1.682746978064780130e+00,6.928203299376685997e+00,-2.376617731780733822e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595182084634221553e+01,4.636769638556917243e+02,1.680392670362833130e+00,6.928203299376685997e+00,-2.374951065114067061e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595326422200079719e+01,4.636866831591584059e+02,1.678039982512113504e+00,6.928203299376685997e+00,-2.373284398447400301e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595470759765937885e+01,4.636964028546047416e+02,1.675688914577973643e+00,6.928203299376685997e+00,-2.371617731780733540e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595615097331796051e+01,4.637061229417607251e+02,1.673339466625721084e+00,6.928203299376685997e+00,-2.369951065114066779e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595759434897654216e+01,4.637158434203563502e+02,1.670991638720618289e+00,6.928203299376685997e+00,-2.368284398447400019e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.595903772463512382e+01,4.637255642901216106e+02,1.668645430927882645e+00,6.928203299376685997e+00,-2.366617731780733258e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596048110029370548e+01,4.637352855507865002e+02,1.666300843312686686e+00,6.928203299376685997e+00,-2.364951065114066497e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596192447595228714e+01,4.637450072020809557e+02,1.663957875940157649e+00,6.928203299376685997e+00,-2.363284398447399737e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596336785161086880e+01,4.637547292437349711e+02,1.661616528875378140e+00,6.928203299376685997e+00,-2.361617731780732976e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596481122726945046e+01,4.637644516754784831e+02,1.659276802183385469e+00,6.928203299376685997e+00,-2.359951065114066215e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596625460292803211e+01,4.637741744970413720e+02,1.656938695929172090e+00,6.928203299376685997e+00,-2.358284398447399455e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596769797858661377e+01,4.637838977081536314e+02,1.654602210177685384e+00,6.928203299376685997e+00,-2.356617731780732694e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.596914135424519543e+01,4.637936213085450845e+02,1.652267344993827658e+00,6.928203299376685997e+00,-2.354951065114065933e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597058472990377709e+01,4.638033452979457252e+02,1.649934100442456364e+00,6.928203299376685997e+00,-2.353284398447399173e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597202810556235875e+01,4.638130696760853766e+02,1.647602476588383880e+00,6.928203299376685997e+00,-2.351617731780732412e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597347148122094040e+01,4.638227944426939757e+02,1.645272473496377508e+00,6.928203299376685997e+00,-2.349951065114065651e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597491485687952206e+01,4.638325195975013457e+02,1.642944091231159476e+00,6.928203299376685997e+00,-2.348284398447398891e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597635823253810372e+01,4.638422451402373099e+02,1.640617329857407158e+00,6.928203299376685997e+00,-2.346617731780732130e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597780160819668538e+01,4.638519710706318051e+02,1.638292189439752855e+00,6.928203299376685997e+00,-2.344951065114065369e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.597924498385526704e+01,4.638616973884145978e+02,1.635968670042783790e+00,6.928203299376685997e+00,-2.343284398447398609e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598068835951384870e+01,4.638714240933155111e+02,1.633646771731042113e+00,6.928203299376685997e+00,-2.341617731780731848e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598213173517243035e+01,4.638811511850644251e+02,1.631326494569024899e+00,6.928203299376685997e+00,-2.339951065114065087e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598357511083101201e+01,4.638908786633911063e+02,1.629007838621184590e+00,6.928203299376685997e+00,-2.338284398447398327e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598501848648959367e+01,4.639006065280253210e+02,1.626690803951928110e+00,6.928203299376685997e+00,-2.336617731780731566e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598646186214817533e+01,4.639103347786968357e+02,1.624375390625617532e+00,6.928203299376685997e+00,-2.334951065114064805e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598790523780675699e+01,4.639200634151354734e+02,1.622061598706569852e+00,6.928203299376685997e+00,-2.333284398447398045e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.598934861346533864e+01,4.639297924370710007e+02,1.619749428259056989e+00,6.928203299376685997e+00,-2.331617731780731284e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599079198912392030e+01,4.639395218442331270e+02,1.617438879347306013e+00,6.928203299376685997e+00,-2.329951065114064523e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599223536478250196e+01,4.639492516363516188e+02,1.615129952035498917e+00,6.928203299376685997e+00,-2.328284398447397763e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599367874044108362e+01,4.639589818131561856e+02,1.612822646387772396e+00,6.928203299376685997e+00,-2.326617731780731002e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599512211609966528e+01,4.639687123743765369e+02,1.610516962468218516e+00,6.928203299376685997e+00,-2.324951065114064241e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599656549175824694e+01,4.639784433197423823e+02,1.608212900340883822e+00,6.928203299376685997e+00,-2.323284398447397481e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599800886741682859e+01,4.639881746489834313e+02,1.605910460069770229e+00,6.928203299376685997e+00,-2.321617731780730720e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.599945224307541025e+01,4.639979063618293935e+02,1.603609641718834133e+00,6.928203299376685997e+00,-2.319951065114063959e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600089561873399191e+01,4.640076384580099216e+02,1.601310445351987521e+00,6.928203299376685997e+00,-2.318284398447397199e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600233899439257357e+01,4.640173709372546682e+02,1.599012871033096639e+00,6.928203299376685997e+00,-2.316617731780730438e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600378237005115523e+01,4.640271037992932861e+02,1.596716918825983100e+00,6.928203299376685997e+00,-2.314951065114063677e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600522574570973688e+01,4.640368370438554280e+02,1.594422588794423445e+00,6.928203299376685997e+00,-2.313284398447396917e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600666912136831854e+01,4.640465706706706897e+02,1.592129881002148917e+00,6.928203299376685997e+00,-2.311617731780730156e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600811249702690020e+01,4.640563046794687239e+02,1.589838795512845904e+00,6.928203299376685997e+00,-2.309951065114063395e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.600955587268548186e+01,4.640660390699791833e+02,1.587549332390155721e+00,6.928203299376685997e+00,-2.308284398447396635e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601099924834406352e+01,4.640757738419316070e+02,1.585261491697674607e+00,6.928203299376685997e+00,-2.306617731780729874e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601244262400264518e+01,4.640855089950555907e+02,1.582975273498953506e+00,6.928203299376685997e+00,-2.304951065114063113e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601388599966122683e+01,4.640952445290807304e+02,1.580690677857498727e+00,6.928203299376685997e+00,-2.303284398447396353e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601532937531980849e+01,4.641049804437366220e+02,1.578407704836771064e+00,6.928203299376685997e+00,-2.301617731780729592e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601677275097839015e+01,4.641147167387528043e+02,1.576126354500186455e+00,6.928203299376685997e+00,-2.299951065114062831e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601821612663697181e+01,4.641244534138588165e+02,1.573846626911115765e+00,6.928203299376685997e+00,-2.298284398447396071e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.601965950229555347e+01,4.641341904687841975e+02,1.571568522132884782e+00,6.928203299376685997e+00,-2.296617731780729310e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602110287795413512e+01,4.641439279032584295e+02,1.569292040228774221e+00,6.928203299376685997e+00,-2.294951065114062549e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602254625361271678e+01,4.641536657170111084e+02,1.567017181262019720e+00,6.928203299376685997e+00,-2.293284398447395789e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602398962927129844e+01,4.641634039097716595e+02,1.564743945295811622e+00,6.928203299376685997e+00,-2.291617731780729028e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602543300492988010e+01,4.641731424812696218e+02,1.562472332393295638e+00,6.928203299376685997e+00,-2.289951065114062267e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602687638058846176e+01,4.641828814312344775e+02,1.560202342617571958e+00,6.928203299376685997e+00,-2.288284398447395507e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602831975624704341e+01,4.641926207593957088e+02,1.557933976031695922e+00,6.928203299376685997e+00,-2.286617731780728746e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.602976313190562507e+01,4.642023604654827409e+02,1.555667232698677571e+00,6.928203299376685997e+00,-2.284951065114061985e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603120650756420673e+01,4.642121005492250561e+02,1.553402112681482095e+00,6.928203299376685997e+00,-2.283284398447395225e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603264988322278839e+01,4.642218410103521364e+02,1.551138616043029606e+00,6.928203299376685997e+00,-2.281617731780728464e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603409325888137005e+01,4.642315818485933505e+02,1.548876742846194920e+00,6.928203299376685997e+00,-2.279951065114061703e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603553663453995171e+01,4.642413230636781236e+02,1.546616493153807781e+00,6.928203299376685997e+00,-2.278284398447394943e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603698001019853336e+01,4.642510646553358811e+02,1.544357867028652853e+00,6.928203299376685997e+00,-2.276617731780728182e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603842338585711502e+01,4.642608066232960482e+02,1.542100864533469951e+00,6.928203299376685997e+00,-2.274951065114061421e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.603986676151569668e+01,4.642705489672879935e+02,1.539845485730953367e+00,6.928203299376685997e+00,-2.273284398447394661e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604131013717427834e+01,4.642802916870410854e+02,1.537591730683752766e+00,6.928203299376685997e+00,-2.271617731780727900e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604275351283286000e+01,4.642900347822846925e+02,1.535339599454472292e+00,6.928203299376685997e+00,-2.269951065114061139e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604419688849144165e+01,4.642997782527481831e+02,1.533089092105671014e+00,6.928203299376685997e+00,-2.268284398447394379e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604564026415002331e+01,4.643095220981609259e+02,1.530840208699863370e+00,6.928203299376685997e+00,-2.266617731780727618e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604708363980860497e+01,4.643192663182522324e+02,1.528592949299518056e+00,6.928203299376685997e+00,-2.264951065114060857e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604852701546718663e+01,4.643290109127514143e+02,1.526347313967059138e+00,6.928203299376685997e+00,-2.263284398447394097e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.604997039112576829e+01,4.643387558813878400e+02,1.524103302764865164e+00,6.928203299376685997e+00,-2.261617731780727336e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.605141376678434995e+01,4.643485012238907643e+02,1.521860915755269827e+00,6.928203299376685997e+00,-2.259951065114060575e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.605285714244293160e+01,4.643582469399894990e+02,1.519620153000561746e+00,6.928203299376685997e+00,-2.258284398447393815e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.605430051810151326e+01,4.643679930294133555e+02,1.517381014562984465e+00,6.928203299376685997e+00,-2.256617731780727054e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.605574389376009492e+01,4.643777394918915888e+02,1.515143500504736007e+00,6.928203299376685997e+00,-2.254951065114060293e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.605718726941867658e+01,4.643874863271534537e+02,1.512907610887969545e+00,6.928203299376685997e+00,-2.253284398447393533e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.605863064507725824e+01,4.643972335349282048e+02,1.510673345774793397e+00,6.928203299376685997e+00,-2.251617731780726772e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606007402073583989e+01,4.644069811149450970e+02,1.508440705227270140e+00,6.928203299376685997e+00,-2.249951065114060011e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606151739639442155e+01,4.644167290669333283e+02,1.506209689307417943e+00,6.928203299376685997e+00,-2.248284398447393251e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606296077205300321e+01,4.644264773906222104e+02,1.503980298077209232e+00,6.928203299376685997e+00,-2.246617731780726490e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606440414771158487e+01,4.644362260857408842e+02,1.501752531598571583e+00,6.928203299376685997e+00,-2.244951065114059729e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606584752337016653e+01,4.644459751520185478e+02,1.499526389933387271e+00,6.928203299376685997e+00,-2.243284398447392969e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606729089902874819e+01,4.644557245891844559e+02,1.497301873143493722e+00,6.928203299376685997e+00,-2.241617731780726208e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.606873427468732984e+01,4.644654743969677497e+02,1.495078981290683062e+00,6.928203299376685997e+00,-2.239951065114059447e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607017765034591150e+01,4.644752245750975703e+02,1.492857714436702121e+00,6.928203299376685997e+00,-2.238284398447392687e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607162102600449316e+01,4.644849751233031157e+02,1.490638072643253098e+00,6.928203299376685997e+00,-2.236617731780725926e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607306440166307482e+01,4.644947260413135268e+02,1.488420055971992451e+00,6.928203299376685997e+00,-2.234951065114059165e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607450777732165648e+01,4.645044773288579449e+02,1.486203664484531783e+00,6.928203299376685997e+00,-2.233284398447392405e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607595115298023813e+01,4.645142289856655111e+02,1.483988898242437626e+00,6.928203299376685997e+00,-2.231617731780725644e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607739452863881979e+01,4.645239810114653665e+02,1.481775757307230990e+00,6.928203299376685997e+00,-2.229951065114058883e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.607883790429740145e+01,4.645337334059865952e+02,1.479564241740388253e+00,6.928203299376685997e+00,-2.228284398447392123e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608028127995598311e+01,4.645434861689582817e+02,1.477354351603340499e+00,6.928203299376685997e+00,-2.226617731780725362e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608172465561456477e+01,4.645532393001095670e+02,1.475146086957473290e+00,6.928203299376685997e+00,-2.224951065114058602e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608316803127314643e+01,4.645629927991694785e+02,1.472939447864127560e+00,6.928203299376685997e+00,-2.223284398447391841e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608461140693172808e+01,4.645727466658671005e+02,1.470734434384598721e+00,6.928203299376685997e+00,-2.221617731780725080e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608605478259030974e+01,4.645825008999315173e+02,1.468531046580137112e+00,6.928203299376685997e+00,-2.219951065114058320e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608749815824889140e+01,4.645922555010917563e+02,1.466329284511947995e+00,6.928203299376685997e+00,-2.218284398447391559e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.608894153390747306e+01,4.646020104690768449e+02,1.464129148241191336e+00,6.928203299376685997e+00,-2.216617731780724798e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609038490956605472e+01,4.646117658036158105e+02,1.461930637828982027e+00,6.928203299376685997e+00,-2.214951065114058038e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609182828522463637e+01,4.646215215044376805e+02,1.459733753336389883e+00,6.928203299376685997e+00,-2.213284398447391277e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609327166088321803e+01,4.646312775712714824e+02,1.457538494824439645e+00,6.928203299376685997e+00,-2.211617731780724516e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609471503654179969e+01,4.646410340038461868e+02,1.455344862354110536e+00,6.928203299376685997e+00,-2.209951065114057756e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609615841220038135e+01,4.646507908018908211e+02,1.453152855986336700e+00,6.928203299376685997e+00,-2.208284398447390995e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609760178785896301e+01,4.646605479651343558e+02,1.450962475782007433e+00,6.928203299376685997e+00,-2.206617731780724234e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.609904516351754467e+01,4.646703054933057047e+02,1.448773721801966508e+00,6.928203299376685997e+00,-2.204951065114057474e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610048853917612632e+01,4.646800633861338952e+02,1.446586594107012624e+00,6.928203299376685997e+00,-2.203284398447390713e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610193191483470798e+01,4.646898216433478410e+02,1.444401092757899185e+00,6.928203299376685997e+00,-2.201617731780723952e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610337529049328964e+01,4.646995802646764560e+02,1.442217217815334740e+00,6.928203299376685997e+00,-2.199951065114057192e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610481866615187130e+01,4.647093392498487106e+02,1.440034969339982540e+00,6.928203299376685997e+00,-2.198284398447390431e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610626204181045296e+01,4.647190985985934617e+02,1.437854347392460541e+00,6.928203299376685997e+00,-2.196617731780723670e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610770541746903461e+01,4.647288583106396800e+02,1.435675352033341623e+00,6.928203299376685997e+00,-2.194951065114056910e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.610914879312761627e+01,4.647386183857162223e+02,1.433497983323153369e+00,6.928203299376685997e+00,-2.193284398447390149e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611059216878619793e+01,4.647483788235520024e+02,1.431322241322378064e+00,6.928203299376685997e+00,-2.191617731780723388e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611203554444477959e+01,4.647581396238758771e+02,1.429148126091453364e+00,6.928203299376685997e+00,-2.189951065114056628e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611347892010336125e+01,4.647679007864167033e+02,1.426975637690770959e+00,6.928203299376685997e+00,-2.188284398447389867e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611492229576194291e+01,4.647776623109033949e+02,1.424804776180678134e+00,6.928203299376685997e+00,-2.186617731780723106e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611636567142052456e+01,4.647874241970647518e+02,1.422635541621476429e+00,6.928203299376685997e+00,-2.184951065114056346e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611780904707910622e+01,4.647971864446296308e+02,1.420467934073422311e+00,6.928203299376685997e+00,-2.183284398447389585e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.611925242273768788e+01,4.648069490533268322e+02,1.418301953596726950e+00,6.928203299376685997e+00,-2.181617731780722824e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612069579839626954e+01,4.648167120228851559e+02,1.416137600251556661e+00,6.928203299376685997e+00,-2.179951065114056064e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612213917405485120e+01,4.648264753530334588e+02,1.413974874098032464e+00,6.928203299376685997e+00,-2.178284398447389303e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612358254971343285e+01,4.648362390435005409e+02,1.411813775196229859e+00,6.928203299376685997e+00,-2.176617731780722542e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612502592537201451e+01,4.648460030940151455e+02,1.409654303606179715e+00,6.928203299376685997e+00,-2.174951065114055782e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612646930103059617e+01,4.648557675043060726e+02,1.407496459387866938e+00,6.928203299376685997e+00,-2.173284398447389021e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612791267668917783e+01,4.648655322741020655e+02,1.405340242601232026e+00,6.928203299376685997e+00,-2.171617731780722260e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.612935605234775949e+01,4.648752974031319241e+02,1.403185653306169511e+00,6.928203299376685997e+00,-2.169951065114055500e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613079942800634115e+01,4.648850628911243348e+02,1.401032691562529298e+00,6.928203299376685997e+00,-2.168284398447388739e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613224280366492280e+01,4.648948287378080977e+02,1.398881357430115990e+00,6.928203299376685997e+00,-2.166617731780721978e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613368617932350446e+01,4.649045949429118991e+02,1.396731650968688676e+00,6.928203299376685997e+00,-2.164951065114055218e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613512955498208612e+01,4.649143615061644823e+02,1.394583572237961588e+00,6.928203299376685997e+00,-2.163284398447388457e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613657293064066778e+01,4.649241284272945336e+02,1.392437121297603442e+00,6.928203299376685997e+00,-2.161617731780721696e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613801630629924944e+01,4.649338957060307393e+02,1.390292298207237875e+00,6.928203299376685997e+00,-2.159951065114054936e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.613945968195783109e+01,4.649436633421018428e+02,1.388149103026443454e+00,6.928203299376685997e+00,-2.158284398447388175e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614090305761641275e+01,4.649534313352364734e+02,1.386007535814753222e+00,6.928203299376685997e+00,-2.156617731780721414e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614234643327499441e+01,4.649631996851632607e+02,1.383867596631655150e+00,6.928203299376685997e+00,-2.154951065114054654e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614378980893357607e+01,4.649729683916109479e+02,1.381729285536592133e+00,6.928203299376685997e+00,-2.153284398447387893e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614523318459215773e+01,4.649827374543081078e+02,1.379592602588961547e+00,6.928203299376685997e+00,-2.151617731780721132e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614667656025073939e+01,4.649925068729834265e+02,1.377457547848115915e+00,6.928203299376685997e+00,-2.149951065114054372e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614811993590932104e+01,4.650022766473655338e+02,1.375324121373362019e+00,6.928203299376685997e+00,-2.148284398447387611e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.614956331156790270e+01,4.650120467771830022e+02,1.373192323223961786e+00,6.928203299376685997e+00,-2.146617731780720850e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615100668722648436e+01,4.650218172621644612e+02,1.371062153459132071e+00,6.928203299376685997e+00,-2.144951065114054090e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615245006288506602e+01,4.650315881020385405e+02,1.368933612138043987e+00,6.928203299376685997e+00,-2.143284398447387329e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615389343854364768e+01,4.650413592965337557e+02,1.366806699319823792e+00,6.928203299376685997e+00,-2.141617731780720568e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615533681420222933e+01,4.650511308453787365e+02,1.364681415063552450e+00,6.928203299376685997e+00,-2.139951065114053808e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615678018986081099e+01,4.650609027483020554e+02,1.362557759428265625e+00,6.928203299376685997e+00,-2.138284398447387047e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615822356551939265e+01,4.650706750050322285e+02,1.360435732472953685e+00,6.928203299376685997e+00,-2.136617731780720286e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.615966694117797431e+01,4.650804476152978850e+02,1.358315334256561702e+00,6.928203299376685997e+00,-2.134951065114053526e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.616111031683655597e+01,4.650902205788274841e+02,1.356196564837989893e+00,6.928203299376685997e+00,-2.133284398447386765e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.616255369249513762e+01,4.650999938953495985e+02,1.354079424276092736e+00,6.928203299376685997e+00,-2.131617731780720004e-01,0.000000000000000000e+00,4.563496123041156649e-02,0.000000000000000000e+00,0.000000000000000000e+00 +7.616399706815371928e+01,4.651097675645927438e+02,1.351963912629679854e+00,6.928203299376685997e+00,-2.129951065114053244e-01,0.000000000000000000e+00,4.563496123041156649e-02,-4.263256499603152078e-10,0.000000000000000000e+00 +7.616544044381230094e+01,4.651195415862853793e+02,1.349850029957515352e+00,6.928203299376685997e+00,-2.128284398447386483e-01,-6.153480657801578505e-13,4.563496123041156649e-02,-8.526512999206302088e-10,0.000000000000000000e+00 +7.616688381947088260e+01,4.651293159601560774e+02,1.347737776318318259e+00,6.928203299376685109e+00,-2.126617731780719722e-01,-1.846044197340473450e-12,4.563496123041156649e-02,8.511975294542650327e-05,0.000000000000000000e+00 +7.616832719512946426e+01,4.651390906859332404e+02,1.345627151770762309e+00,6.928203299376682445e+00,-2.124951065114052962e-01,1.228579334214031223e-07,4.563496123041156649e-02,-8.405351249484845576e-05,0.000000000000000000e+00 +7.616977057078804592e+01,4.651488657633454409e+02,1.343518156373475714e+00,6.928203299554012595e+00,-2.123284398447386201e-01,1.537139468358177225e-09,4.563496123041156649e-02,-9.999982857397541336e-01,0.000000000000000000e+00 +7.617121394644658494e+01,4.651586411921210811e+02,1.341410790185042057e+00,6.928203299556231265e+00,-2.121617731780719440e-01,-1.443371647080063293e-03,4.563496123041156649e-02,-9.999996462866358460e-01,0.000000000000000000e+00 +7.617265732210512397e+01,4.651684169719886768e+02,1.339305053263998957e+00,6.928201216228729642e+00,-2.119951065114052680e-01,-2.886746795079384205e-03,4.563496123041156649e-02,-9.999998061503858615e-01,0.000000000000000000e+00 +7.617410069819769092e+01,4.651781931026766301e+02,1.337200945668839402e+00,6.928197049567420329e+00,-2.118284398447385919e-01,-4.330122607848750985e-03,4.563496123041156649e-02,-9.999998682263722127e-01,0.000000000000000000e+00 +7.617554407515831372e+01,4.651879695839134001e+02,1.335098467458010640e+00,6.928190799568211489e+00,-2.116617731780719158e-01,-5.773499378272464212e-03,4.563496123041156649e-02,-9.999999007119316774e-01,0.000000000000000000e+00 +7.617698745342102029e+01,4.651977464154274458e+02,1.332997618689914843e+00,6.928182466224709124e+00,-2.114951065114052398e-01,-7.216877497671622677e-03,4.563496123041156649e-02,-9.999999219180258914e-01,0.000000000000000000e+00 +7.617843083341985277e+01,4.652075235969471123e+02,1.330898399422908884e+00,6.928172049528074972e+00,-2.113284398447385637e-01,-8.660257383800608680e-03,4.563496123041156649e-02,-9.999999352279379528e-01,0.000000000000000000e+00 +7.617987421558883909e+01,4.652173011282009156e+02,1.328800809715304565e+00,6.928159549466988310e+00,-2.111617731780718876e-01,-1.010363945930211824e-02,4.563496123041156649e-02,-9.999999457238996081e-01,0.000000000000000000e+00 +7.618131760036203559e+01,4.652270790089172010e+02,1.326704849625368166e+00,6.928144966027638851e+00,-2.109951065114052116e-01,-1.154702415416070278e-02,4.563496123041156649e-02,-9.999999529396175202e-01,0.000000000000000000e+00 +7.618276098817349862e+01,4.652368572388243138e+02,1.324610519211320891e+00,6.928128299193716089e+00,-2.108284398447385355e-01,-1.299041189769543914e-02,4.563496123041156649e-02,-9.999999593867107128e-01,0.000000000000000000e+00 +7.618420437945728452e+01,4.652466358176507129e+02,1.322517818531338429e+00,6.928109548946410179e+00,-2.106617731780718594e-01,-1.443380312285951275e-02,4.563496123041156649e-02,-9.999999637335972302e-01,0.000000000000000000e+00 +7.618564777464746385e+01,4.652564147451247436e+02,1.320426747643551391e+00,6.928088715264406616e+00,-2.104951065114051834e-01,-1.587719826069429463e-02,4.563496123041156649e-02,-9.999999680528922630e-01,0.000000000000000000e+00 +7.618709117417812138e+01,4.652661940209747513e+02,1.318337306606045312e+00,6.928065798123888896e+00,-2.103284398447385073e-01,-1.732059774524423792e-02,4.563496123041156649e-02,-9.999999714266661899e-01,0.000000000000000000e+00 +7.618853457848335609e+01,4.652759736449291381e+02,1.316249495476859988e+00,6.928040797498534076e+00,-2.101617731780718312e-01,-1.876400200924165096e-02,4.563496123041156649e-02,-9.999999737833037416e-01,0.000000000000000000e+00 +7.618997798799728116e+01,4.652857536167161925e+02,1.314163314313990139e+00,6.928013713359514547e+00,-2.099951065114051552e-01,-2.020741148532956277e-02,4.563496123041156649e-02,-9.999999767500594716e-01,0.000000000000000000e+00 +7.619142140315402401e+01,4.652955339360642597e+02,1.312078763175385410e+00,6.927984545675498040e+00,-2.098284398447384791e-01,-2.165082660851519805e-02,4.563496123041156649e-02,-9.999999789637168401e-01,0.000000000000000000e+00 +7.619286482438772623e+01,4.653053146027016851e+02,1.309995842118949927e+00,6.927953294412644070e+00,-2.096617731780718030e-01,-2.309424781185481085e-02,4.563496123041156649e-02,-9.999999799073640006e-01,0.000000000000000000e+00 +7.619430825213254366e+01,4.653150956163568139e+02,1.307914551202542519e+00,6.927919959534606598e+00,-2.094951065114051270e-01,-2.453767552767653626e-02,4.563496123041156649e-02,-9.999999824681018445e-01,0.000000000000000000e+00 +7.619575168682267474e+01,4.653248769767578779e+02,1.305834890483976940e+00,6.927884541002534924e+00,-2.093284398447384509e-01,-2.598111019249515000e-02,4.563496123041156649e-02,-9.999999835585503538e-01,0.000000000000000000e+00 +7.619719512889230373e+01,4.653346586836332222e+02,1.303756860021021424e+00,6.927847038775067467e+00,-2.091617731780717748e-01,-2.742455223838963924e-02,4.563496123041156649e-02,-9.999999847742426784e-01,0.000000000000000000e+00 +7.619863857877565749e+01,4.653444407367111353e+02,1.301680459871399131e+00,6.927807452808337985e+00,-2.089951065114050988e-01,-2.886800209976396817e-02,4.563496123041156649e-02,-9.999999859991889339e-01,0.000000000000000000e+00 +7.620008203690697712e+01,4.653542231357198489e+02,1.299605690092787924e+00,6.927765783055972015e+00,-2.088284398447384227e-01,-3.031146021087792117e-02,4.563496123041156649e-02,-9.999999875373200009e-01,0.000000000000000000e+00 +7.620152550372054634e+01,4.653640058803876514e+02,1.297532550742820145e+00,6.927722029469086884e+00,-2.086617731780717466e-01,-3.175492700645454747e-02,4.563496123041156649e-02,-9.999999875548977180e-01,0.000000000000000000e+00 +7.620296897965064886e+01,4.653737889704428312e+02,1.295461041879083064e+00,6.927676191996290811e+00,-2.084951065114050706e-01,-3.319840291859580544e-02,4.563496123041156649e-02,-9.999999893270489215e-01,0.000000000000000000e+00 +7.620441246513161104e+01,4.653835724056136200e+02,1.293391163559118651e+00,6.927628270583686465e+00,-2.083284398447383945e-01,-3.464188838415837440e-02,4.563496123041156649e-02,-9.999999893023081565e-01,0.000000000000000000e+00 +7.620585596059780187e+01,4.653933561856282495e+02,1.291322915840423358e+00,6.927578265174863859e+00,-2.081617731780717184e-01,-3.608538383490093177e-02,4.563496123041156649e-02,-9.999999911692726284e-01,0.000000000000000000e+00 +7.620729946648359032e+01,4.654031403102148943e+02,1.289256298780448562e+00,6.927526175710907452e+00,-2.079951065114050424e-01,-3.752888970793639284e-02,4.563496123041156649e-02,-9.999999905114062004e-01,0.000000000000000000e+00 +7.620874298322338802e+01,4.654129247791018429e+02,1.287191312436600343e+00,6.927472002130388162e+00,-2.078284398447383663e-01,-3.897240643403347693e-02,4.563496123041156649e-02,-9.999999922832388810e-01,0.000000000000000000e+00 +7.621018651125163501e+01,4.654227095920172701e+02,1.285127956866239485e+00,6.927415744369372241e+00,-2.076617731780716902e-01,-4.041593445114521899e-02,4.563496123041156649e-02,-9.999999924818415709e-01,0.000000000000000000e+00 +7.621163005100282817e+01,4.654324947486894075e+02,1.283066232126681472e+00,6.927357402361410621e+00,-2.074951065114050142e-01,-4.185947419148005472e-02,4.563496123041156649e-02,-9.999999926390805705e-01,0.000000000000000000e+00 +7.621307360291146438e+01,4.654422802488464299e+02,1.281006138275196271e+00,6.927296976037546905e+00,-2.073284398447383381e-01,-4.330302608949270632e-02,4.563496123041156649e-02,-9.999999938541584976e-01,0.000000000000000000e+00 +7.621451716741211158e+01,4.654520660922165121e+02,1.278947675369008774e+00,6.927234465326313817e+00,-2.071617731780716620e-01,-4.474659058126098654e-02,4.563496123041156649e-02,-9.999999938101419295e-01,0.000000000000000000e+00 +7.621596074493933770e+01,4.654618522785278287e+02,1.276890843465298575e+00,6.927169870153730535e+00,-2.069951065114049860e-01,-4.619016809955570763e-02,4.563496123041156649e-02,-9.999999944459389001e-01,0.000000000000000000e+00 +7.621740433592778174e+01,4.654716388075085547e+02,1.274835642621199749e+00,6.927103190443307135e+00,-2.068284398447383099e-01,-4.763375907998556452e-02,4.563496123041156649e-02,-9.999999947106109621e-01,0.000000000000000000e+00 +7.621884794081211112e+01,4.654814256788868079e+02,1.272782072893801297e+00,6.927034426116040144e+00,-2.066617731780716338e-01,-4.907736395668239188e-02,4.563496123041156649e-02,-9.999999952516330781e-01,0.000000000000000000e+00 +7.622029156002703587e+01,4.654912128923907630e+02,1.270730134340146700e+00,6.926963577090414326e+00,-2.064951065114049578e-01,-5.052098316475427814e-02,4.563496123041156649e-02,-9.999999958577410197e-01,0.000000000000000000e+00 +7.622173519400730868e+01,4.655010004477485381e+02,1.268679827017234363e+00,6.926890643282400895e+00,-2.063284398447382817e-01,-5.196461713904720892e-02,4.563496123041156649e-02,-9.999999958851379933e-01,0.000000000000000000e+00 +7.622317884318772485e+01,4.655107883446882511e+02,1.266631150982017395e+00,6.926815624605457522e+00,-2.061617731780716056e-01,-5.340826631352194043e-02,4.563496123041156649e-02,-9.999999963883489107e-01,0.000000000000000000e+00 +7.622462250800312233e+01,4.655205765829380198e+02,1.264584106291403165e+00,6.926738520970529223e+00,-2.059951065114049296e-01,-5.485193112370707891e-02,4.563496123041156649e-02,-9.999999967108164078e-01,0.000000000000000000e+00 +7.622606618888839591e+01,4.655303651622259622e+02,1.262538693002254186e+00,6.926659332286045689e+00,-2.058284398447382535e-01,-5.629561200423020134e-02,4.563496123041156649e-02,-9.999999966158448217e-01,0.000000000000000000e+00 +7.622750988627848301e+01,4.655401540822801962e+02,1.260494911171387677e+00,6.926578058457922182e+00,-2.056617731780715774e-01,-5.773930938942527930e-02,4.563496123041156649e-02,-9.999999975648219408e-01,0.000000000000000000e+00 +7.622895360060836367e+01,4.655499433428287830e+02,1.258452760855575114e+00,6.926494699389559528e+00,-2.054951065114049014e-01,-5.918302371578552240e-02,4.563496123041156649e-02,-9.999999976037639016e-01,0.000000000000000000e+00 +7.623039733231307480e+01,4.655597329435997835e+02,1.256412242111542898e+00,6.926409254981840569e+00,-2.053284398447382253e-01,-6.062675541703391180e-02,4.563496123041156649e-02,-9.999999973290545352e-01,0.000000000000000000e+00 +7.623184108182771013e+01,4.655695228843212590e+02,1.254373354995972134e+00,6.926321725133133711e+00,-2.051617731780715492e-01,-6.207050492780646911e-02,4.563496123041156649e-02,-9.999999981828583406e-01,0.000000000000000000e+00 +7.623328484958740603e+01,4.655793131647212704e+02,1.252336099565498628e+00,6.926232109739291154e+00,-2.049951065114048732e-01,-6.351427268487472300e-02,4.563496123041156649e-02,-9.999999986181817846e-01,0.000000000000000000e+00 +7.623472863602735572e+01,4.655891037845278788e+02,1.250300475876712891e+00,6.926140408693645334e+00,-2.048284398447381971e-01,-6.495805912283142414e-02,4.563496123041156649e-02,-9.999999979339987410e-01,0.000000000000000000e+00 +7.623617244158282347e+01,4.655988947434691454e+02,1.248266483986159914e+00,6.926046621887011590e+00,-2.046617731780715210e-01,-6.640186467531315750e-02,4.563496123041156649e-02,-9.999999992574329921e-01,0.000000000000000000e+00 +7.623761626668911617e+01,4.656086860412730744e+02,1.246234123950339390e+00,6.925950749207689050e+00,-2.044951065114048450e-01,-6.784568978052878119e-02,4.563496123041156649e-02,-9.999999984660836727e-01,0.000000000000000000e+00 +7.623906011178159758e+01,4.656184776776676699e+02,1.244203395825705938e+00,6.925852790541453530e+00,-2.043284398447381689e-01,-6.928953487079379803e-02,4.563496123041156649e-02,-9.999999991002823663e-01,0.000000000000000000e+00 +7.624050397729570250e+01,4.656282696523809363e+02,1.242174299668668436e+00,6.925752745771565522e+00,-2.041617731780714928e-01,-7.073340038359529625e-02,4.563496123041156649e-02,-9.999999991551545842e-01,0.000000000000000000e+00 +7.624194786366690835e+01,4.656380619651409347e+02,1.240146835535590908e+00,6.925650614778762204e+00,-2.039951065114048168e-01,-7.217728675358690837e-02,4.563496123041156649e-02,-1.000000000027822855e+00,0.000000000000000000e+00 +7.624339177133077783e+01,4.656478546156756124e+02,1.238121003482791638e+00,6.925546397441260993e+00,-2.038284398447381407e-01,-7.362119441750213100e-02,4.563496123041156649e-02,-9.999999992747876654e-01,0.000000000000000000e+00 +7.624483570072293048e+01,4.656576476037129169e+02,1.236096803566543834e+00,6.925440093634755989e+00,-2.036617731780714646e-01,-7.506512380861017630e-02,4.563496123041156649e-02,-9.999999995583001011e-01,0.000000000000000000e+00 +7.624627965227904269e+01,4.656674409289808523e+02,1.234074235843075407e+00,6.925331703232422420e+00,-2.034951065114047886e-01,-7.650907536408953213e-02,4.563496123041156649e-02,-1.000000000126027633e+00,0.000000000000000000e+00 +7.624772362643487611e+01,4.656772345912074229e+02,1.232053300368568527e+00,6.925221226104910421e+00,-2.033284398447381125e-01,-7.795304952009894650e-02,4.563496123041156649e-02,-1.000000000219339880e+00,0.000000000000000000e+00 +7.624916762362623501e+01,4.656870285901205193e+02,1.230033997199160511e+00,6.925108662120345926e+00,-2.031617731780714364e-01,-7.939704671176958661e-02,4.563496123041156649e-02,-1.000000000351105589e+00,0.000000000000000000e+00 +7.625061164428899474e+01,4.656968229254481457e+02,1.228016326390942936e+00,6.924994011144331552e+00,-2.029951065114047604e-01,-8.084106737504236084e-02,4.563496123041156649e-02,-1.000000000601751537e+00,0.000000000000000000e+00 +7.625205568885913010e+01,4.657066175969181927e+02,1.226000287999962302e+00,6.924877273039944825e+00,-2.028284398447380843e-01,-8.228511194604481993e-02,4.563496123041156649e-02,-1.000000000193447702e+00,0.000000000000000000e+00 +7.625349975777265854e+01,4.657164126042586076e+02,1.223985882082219590e+00,6.924758447667737293e+00,-2.026617731780714082e-01,-8.372918085985310566e-02,4.563496123041156649e-02,-1.000000000471502171e+00,0.000000000000000000e+00 +7.625494385146568277e+01,4.657262079471972811e+02,1.221973108693670484e+00,6.924637534885735413e+00,-2.024951065114047322e-01,-8.517327455355920562e-02,4.563496123041156649e-02,-1.000000001496951452e+00,0.000000000000000000e+00 +7.625638797037437655e+01,4.657360036254621605e+02,1.219961967890225596e+00,6.924514534549436995e+00,-2.023284398447380561e-01,-8.661739346441776899e-02,4.563496123041156649e-02,-1.000000000343265416e+00,0.000000000000000000e+00 +7.625783211493499891e+01,4.657457996387810795e+02,1.217952459727749792e+00,6.924389446511810320e+00,-2.021617731780713800e-01,-8.806153802553295940e-02,4.563496123041156649e-02,-1.000000001317426612e+00,0.000000000000000000e+00 +7.625927628558386573e+01,4.657555959868819855e+02,1.215944584262062644e+00,6.924262270623299464e+00,-2.019951065114047040e-01,-8.950570867630590344e-02,4.563496123041156649e-02,-1.000000001054222931e+00,0.000000000000000000e+00 +7.626072048275739235e+01,4.657653926694927691e+02,1.213938341548938649e+00,6.924133006731814532e+00,-2.018284398447380279e-01,-9.094990585135630246e-02,4.563496123041156649e-02,-1.000000001292380647e+00,0.000000000000000000e+00 +7.626216470689206517e+01,4.657751896863412640e+02,1.211933731644106782e+00,6.924001654682737872e+00,-2.016617731780713518e-01,-9.239412998789463261e-02,4.563496123041156649e-02,-1.000000001634789193e+00,0.000000000000000000e+00 +7.626360895842444165e+01,4.657849870371553038e+02,1.209930754603250502e+00,6.923868214318919634e+00,-2.014951065114046758e-01,-9.383838152263897225e-02,4.563496123041156649e-02,-1.000000001252187243e+00,0.000000000000000000e+00 +7.626505323779119294e+01,4.657947847216627792e+02,1.207929410482008192e+00,6.923732685480677773e+00,-2.013284398447379997e-01,-9.528266089119213911e-02,4.563496123041156649e-02,-1.000000001437904462e+00,0.000000000000000000e+00 +7.626649754542903281e+01,4.658045827395915239e+02,1.205929699335972716e+00,6.923595068005798936e+00,-2.011617731780713236e-01,-9.672696853110859805e-02,4.563496123041156649e-02,-1.000000002201122173e+00,0.000000000000000000e+00 +7.626794188177478873e+01,4.658143810906693716e+02,1.203931621220691417e+00,6.923455361729534907e+00,-2.009951065114046476e-01,-9.817130488004119360e-02,4.563496123041156649e-02,-1.000000001416065265e+00,0.000000000000000000e+00 +7.626938624726535920e+01,4.658241797746241559e+02,1.201935176191666788e+00,6.923313566484601722e+00,-2.008284398447379715e-01,-9.961567037265882385e-02,4.563496123041156649e-02,-1.000000002059294513e+00,0.000000000000000000e+00 +7.627083064233774223e+01,4.658339787911837107e+02,1.199940364304355356e+00,6.923169682101183220e+00,-2.006617731780712954e-01,-1.010600654480173083e-01,4.563496123041156649e-02,-1.000000001566331065e+00,0.000000000000000000e+00 +7.627227506742902108e+01,4.658437781400758126e+02,1.197947185614168575e+00,6.923023708406923937e+00,-2.004951065114046194e-01,-1.025044905415574553e-01,4.563496123041156649e-02,-1.000000002474820127e+00,0.000000000000000000e+00 +7.627371952297636426e+01,4.658535778210282388e+02,1.195955640176472823e+00,6.922875645226933550e+00,-2.003284398447379433e-01,-1.039489460924758746e-01,4.563496123041156649e-02,-1.000000002207479755e+00,0.000000000000000000e+00 +7.627516400941703978e+01,4.658633778337688227e+02,1.193965728046588515e+00,6.922725492383780654e+00,-2.001617731780712672e-01,-1.053934325363381774e-01,4.563496123041156649e-02,-1.000000002011736333e+00,0.000000000000000000e+00 +7.627660852718840090e+01,4.658731781780252845e+02,1.191977449279790990e+00,6.922573249697497211e+00,-1.999951065114045912e-01,-1.068379503106048484e-01,4.563496123041156649e-02,-1.000000002277136701e+00,0.000000000000000000e+00 +7.627805307672790036e+01,4.658829788535254579e+02,1.189990803931310293e+00,6.922418916985574988e+00,-1.998284398447379151e-01,-1.082824998533934852e-01,4.563496123041156649e-02,-1.000000002535335275e+00,0.000000000000000000e+00 +7.627949765847309038e+01,4.658927798599970629e+02,1.188005792056331167e+00,6.922262494062963789e+00,-1.996617731780712390e-01,-1.097270816022408862e-01,4.563496123041156649e-02,-1.000000002311522529e+00,0.000000000000000000e+00 +7.628094227286160844e+01,4.659025811971678195e+02,1.186022413709992618e+00,6.922103980742071450e+00,-1.994951065114045630e-01,-1.111716959940949878e-01,4.563496123041156649e-02,-1.000000002826805234e+00,0.000000000000000000e+00 +7.628238692033119150e+01,4.659123828647655046e+02,1.184040668947388575e+00,6.921943376832763839e+00,-1.993284398447378869e-01,-1.126163434677661390e-01,4.563496123041156649e-02,-1.000000002316601577e+00,0.000000000000000000e+00 +7.628383160131969021e+01,4.659221848625178950e+02,1.182060557823567448e+00,6.921780682142361307e+00,-1.991617731780712108e-01,-1.140610244596152317e-01,4.563496123041156649e-02,-1.000000002839936064e+00,0.000000000000000000e+00 +7.628527631626505467e+01,4.659319871901526540e+02,1.180082080393532351e+00,6.921615896475641350e+00,-1.989951065114045348e-01,-1.155057394090788225e-01,4.563496123041156649e-02,-1.000000002619283901e+00,0.000000000000000000e+00 +7.628672106560532029e+01,4.659417898473975015e+02,1.178105236712241100e+00,6.921449019634833277e+00,-1.988284398447378587e-01,-1.169504887531278986e-01,4.563496123041156649e-02,-1.000000002849342984e+00,0.000000000000000000e+00 +7.628816584977863613e+01,4.659515928339801576e+02,1.176130026834605768e+00,6.921280051419620882e+00,-1.986617731780711826e-01,-1.183952729305631918e-01,4.563496123041156649e-02,-1.000000003016106254e+00,0.000000000000000000e+00 +7.628961066922326495e+01,4.659613961496282855e+02,1.174156450815493580e+00,6.921108991627138884e+00,-1.984951065114045066e-01,-1.198400923795479162e-01,4.563496123041156649e-02,-1.000000002599156668e+00,0.000000000000000000e+00 +7.629105552437755478e+01,4.659711997940696051e+02,1.172184508709726014e+00,6.920935840051972932e+00,-1.983284398447378305e-01,-1.212849475375997743e-01,4.563496123041156649e-02,-1.000000003198702858e+00,0.000000000000000000e+00 +7.629250041567999574e+01,4.659810037670317797e+02,1.170214200572079033e+00,6.920760596486159599e+00,-1.981617731780711544e-01,-1.227298388446562971e-01,4.563496123041156649e-02,-1.000000003004818616e+00,0.000000000000000000e+00 +7.629394534356914903e+01,4.659908080682424725e+02,1.168245526457283523e+00,6.920583260719181951e+00,-1.979951065114044784e-01,-1.241747667381490200e-01,4.563496123041156649e-02,-1.000000003179045693e+00,0.000000000000000000e+00 +7.629539030848370373e+01,4.660006126974293466e+02,1.166278486420025073e+00,6.920403832537972200e+00,-1.978284398447378023e-01,-1.256197316572982281e-01,4.563496123041156649e-02,-1.000000003174680296e+00,0.000000000000000000e+00 +7.629683531086246262e+01,4.660104176543200083e+02,1.164313080514943533e+00,6.920222311726908160e+00,-1.976617731780711262e-01,-1.270647340406460546e-01,4.563496123041156649e-02,-1.000000003289158501e+00,0.000000000000000000e+00 +7.629828035114434215e+01,4.660202229386421777e+02,1.162349308796633451e+00,6.920038698067813243e+00,-1.974951065114044502e-01,-1.285097743272775594e-01,4.563496123041156649e-02,-1.000000003387959024e+00,0.000000000000000000e+00 +7.629972542976837246e+01,4.660300285501234612e+02,1.160387171319644084e+00,6.919852991339954684e+00,-1.973284398447377741e-01,-1.299548529561979082e-01,4.563496123041156649e-02,-1.000000002904696927e+00,0.000000000000000000e+00 +7.630117054717368319e+01,4.660398344884914650e+02,1.158426668138479387e+00,6.919665191320042652e+00,-1.971617731780710980e-01,-1.313999703657096063e-01,4.563496123041156649e-02,-1.000000003392854220e+00,0.000000000000000000e+00 +7.630261570379954605e+01,4.660496407534737955e+02,1.156467799307597577e+00,6.919475297782230250e+00,-1.969951065114044220e-01,-1.328451269964772974e-01,4.563496123041156649e-02,-1.000000003847418384e+00,0.000000000000000000e+00 +7.630406090008534647e+01,4.660594473447980590e+02,1.154510564881411794e+00,6.919283310498109074e+00,-1.968284398447377459e-01,-1.342903232878318309e-01,4.563496123041156649e-02,-1.000000003256982906e+00,0.000000000000000000e+00 +7.630550613647056934e+01,4.660692542621918619e+02,1.152554964914289659e+00,6.919089229236710104e+00,-1.966617731780710698e-01,-1.357355596777622131e-01,4.563496123041156649e-02,-1.000000003580171937e+00,0.000000000000000000e+00 +7.630695141339484167e+01,4.660790615053827537e+02,1.150600999460553275e+00,6.918893053764504586e+00,-1.964951065114043938e-01,-1.371808366072093111e-01,4.563496123041156649e-02,-1.000000003367126133e+00,0.000000000000000000e+00 +7.630839673129790413e+01,4.660888690740983407e+02,1.148648668574479670e+00,6.918694783845398710e+00,-1.963284398447377177e-01,-1.386261545151411811e-01,4.563496123041156649e-02,-1.000000003712449459e+00,0.000000000000000000e+00 +7.630984209061962531e+01,4.660986769680662292e+02,1.146697972310300129e+00,6.918494419240735382e+00,-1.961617731780710416e-01,-1.400715138422318484e-01,4.563496123041156649e-02,-1.000000003578358498e+00,0.000000000000000000e+00 +7.631128749180000170e+01,4.661084851870139119e+02,1.144748910722200641e+00,6.918291959709290673e+00,-1.959951065114043656e-01,-1.415169150277806875e-01,4.563496123041156649e-02,-1.000000003620973743e+00,0.000000000000000000e+00 +7.631273293527914348e+01,4.661182937306689951e+02,1.142801483864321899e+00,6.918087405007274704e+00,-1.958284398447376895e-01,-1.429623585121620466e-01,4.563496123041156649e-02,-1.000000004064479198e+00,0.000000000000000000e+00 +7.631417842149730291e+01,4.661281025987589715e+02,1.140855691790758852e+00,6.917880754888328987e+00,-1.956617731780710134e-01,-1.444078447362023565e-01,4.563496123041156649e-02,-1.000000003426239070e+00,0.000000000000000000e+00 +7.631562395089486017e+01,4.661379117910113905e+02,1.138911534555561600e+00,6.917672009103524644e+00,-1.954951065114043374e-01,-1.458533741387142701e-01,4.563496123041156649e-02,-1.000000004042429946e+00,0.000000000000000000e+00 +7.631706952391232335e+01,4.661477213071537449e+02,1.136969012212734276e+00,6.917461167401364186e+00,-1.953284398447376613e-01,-1.472989471620181345e-01,4.563496123041156649e-02,-1.000000003991924347e+00,0.000000000000000000e+00 +7.631851514099032840e+01,4.661575311469135841e+02,1.135028124816235939e+00,6.917248229527775294e+00,-1.951617731780709852e-01,-1.487445642457893291e-01,4.563496123041156649e-02,-1.000000003472347299e+00,0.000000000000000000e+00 +7.631996080256963921e+01,4.661673413100184007e+02,1.133088872419980131e+00,6.917033195226113484e+00,-1.949951065114043092e-01,-1.501902258301222870e-01,4.563496123041156649e-02,-1.000000004374329343e+00,0.000000000000000000e+00 +7.632140650909117596e+01,4.661771517961957443e+02,1.131151255077834872e+00,6.916816064237160333e+00,-1.948284398447376331e-01,-1.516359323579794804e-01,4.563496123041156649e-02,-1.000000003482165223e+00,0.000000000000000000e+00 +7.632285226099597253e+01,4.661869626051730506e+02,1.129215272843623108e+00,6.916596836299118145e+00,-1.946617731780709570e-01,-1.530816842678106304e-01,4.563496123041156649e-02,-1.000000004372653351e+00,0.000000000000000000e+00 +7.632429805872521911e+01,4.661967737366777556e+02,1.127280925771121822e+00,6.916375511147615285e+00,-1.944951065114042810e-01,-1.545274820033740726e-01,4.563496123041156649e-02,-1.000000003817060668e+00,0.000000000000000000e+00 +7.632574390272021958e+01,4.662065851904374085e+02,1.125348213914063145e+00,6.916152088515697294e+00,-1.943284398447376049e-01,-1.559733260038990432e-01,4.563496123041156649e-02,-1.000000004103565043e+00,0.000000000000000000e+00 +7.632718979342244836e+01,4.662163969661794454e+02,1.123417137326133242e+00,6.915926568133832220e+00,-1.941617731780709288e-01,-1.574192167120632979e-01,4.563496123041156649e-02,-1.000000004114617980e+00,0.000000000000000000e+00 +7.632863573127350776e+01,4.662262090636313019e+02,1.121487696060973427e+00,6.915698949729904399e+00,-1.939951065114042528e-01,-1.588651545690704381e-01,4.563496123041156649e-02,-1.000000004425321665e+00,0.000000000000000000e+00 +7.633008171671514219e+01,4.662360214825204139e+02,1.119559890172179051e+00,6.915469233029215346e+00,-1.938284398447375767e-01,-1.603111400170986189e-01,4.563496123041156649e-02,-1.000000003904746082e+00,0.000000000000000000e+00 +7.633152775018923819e+01,4.662458342225742172e+02,1.117633719713300389e+00,6.915237417754481086e+00,-1.936617731780709006e-01,-1.617571734968350494e-01,4.563496123041156649e-02,-1.000000003964052198e+00,0.000000000000000000e+00 +7.633297383213782439e+01,4.662556472835201475e+02,1.115709184737842197e+00,6.915003503625833048e+00,-1.934951065114042246e-01,-1.632032554511532174e-01,4.563496123041156649e-02,-1.000000004732897851e+00,0.000000000000000000e+00 +7.633441996300308574e+01,4.662654606650855840e+02,1.113786285299263712e+00,6.914767490360813618e+00,-1.933284398447375485e-01,-1.646493863232613153e-01,4.563496123041156649e-02,-1.000000003786277958e+00,0.000000000000000000e+00 +7.633586614322736352e+01,4.662752743669979623e+02,1.111865021450978874e+00,6.914529377674374366e+00,-1.931617731780708724e-01,-1.660955665530091385e-01,4.563496123041156649e-02,-1.000000004637970230e+00,0.000000000000000000e+00 +7.633731237325312691e+01,4.662850883889847182e+02,1.109945393246356105e+00,6.914289165278879601e+00,-1.929951065114041964e-01,-1.675417965854778257e-01,4.563496123041156649e-02,-1.000000004000173526e+00,0.000000000000000000e+00 +7.633875865352301560e+01,4.662949027307731740e+02,1.108027400738718304e+00,6.914046852884097483e+00,-1.928284398447375203e-01,-1.689880768611449480e-01,4.563496123041156649e-02,-1.000000004523366570e+00,0.000000000000000000e+00 +7.634020498447979719e+01,4.663047173920907085e+02,1.106111043981343078e+00,6.913802440197205357e+00,-1.926617731780708442e-01,-1.704344078244739435e-01,4.563496123041156649e-02,-1.000000004180356727e+00,0.000000000000000000e+00 +7.634165136656642403e+01,4.663145323726647575e+02,1.104196323027462734e+00,6.913555926922782646e+00,-1.924951065114041682e-01,-1.718807899171503339e-01,4.563496123041156649e-02,-1.000000004758396122e+00,0.000000000000000000e+00 +7.634309780022599057e+01,4.663243476722226433e+02,1.102283237930263837e+00,6.913307312762813517e+00,-1.923284398447374921e-01,-1.733272235836000319e-01,4.563496123041156649e-02,-1.000000004217017624e+00,0.000000000000000000e+00 +7.634454428590174757e+01,4.663341632904916878e+02,1.100371788742887658e+00,6.913056597416681548e+00,-1.921617731780708160e-01,-1.747737092654543523e-01,4.563496123041156649e-02,-1.000000004329585135e+00,0.000000000000000000e+00 +7.634599082403710213e+01,4.663439792271992701e+02,1.098461975518429945e+00,6.912803780581172397e+00,-1.919951065114041400e-01,-1.762202474070678204e-01,4.563496123041156649e-02,-1.000000004315470870e+00,0.000000000000000000e+00 +7.634743741507561765e+01,4.663537954820727691e+02,1.096553798309941152e+00,6.912548861950468471e+00,-1.918284398447374639e-01,-1.776668384518253485e-01,4.563496123041156649e-02,-1.000000005085097232e+00,0.000000000000000000e+00 +7.634888405946102807e+01,4.663636120548394501e+02,1.094647257170425991e+00,6.912291841216148924e+00,-1.916617731780707878e-01,-1.791134828445898053e-01,4.563496123041156649e-02,-1.000000003722384179e+00,0.000000000000000000e+00 +7.635033075763722366e+01,4.663734289452266353e+02,1.092742352152844099e+00,6.912032718067186110e+00,-1.914951065114041118e-01,-1.805601810261678042e-01,4.563496123041156649e-02,-1.000000004943262022e+00,0.000000000000000000e+00 +7.635177751004825097e+01,4.663832461529616467e+02,1.090839083310109592e+00,6.911771492189950017e+00,-1.913284398447374357e-01,-1.820069334443520925e-01,4.563496123041156649e-02,-1.000000004545030352e+00,0.000000000000000000e+00 +7.635322431713834135e+01,4.663930636777717496e+02,1.088937450695091069e+00,6.911508163268196725e+00,-1.911617731780707596e-01,-1.834537405410204269e-01,4.563496123041156649e-02,-1.000000004683326393e+00,0.000000000000000000e+00 +7.635467117935188242e+01,4.664028815193842661e+02,1.087037454360611388e+00,6.911242730983075511e+00,-1.909951065114040836e-01,-1.849006027613356862e-01,4.563496123041156649e-02,-1.000000004536650167e+00,0.000000000000000000e+00 +7.635611809713341813e+01,4.664126996775265184e+02,1.085139094359448553e+00,6.910975195013122629e+00,-1.908284398447374075e-01,-1.863475205494400655e-01,4.563496123041156649e-02,-1.000000004549392862e+00,0.000000000000000000e+00 +7.635756507092767720e+01,4.664225181519257148e+02,1.083242370744334604e+00,6.910705555034261316e+00,-1.906617731780707314e-01,-1.877944943502879993e-01,4.563496123041156649e-02,-1.000000004734738157e+00,0.000000000000000000e+00 +7.635901210117955884e+01,4.664323369423091776e+02,1.081347283567956286e+00,6.910433810719799119e+00,-1.904951065114040554e-01,-1.892415246090236869e-01,4.563496123041156649e-02,-1.000000004674687082e+00,0.000000000000000000e+00 +7.636045918833413282e+01,4.664421560484041152e+02,1.079453832882954822e+00,6.910159961740426127e+00,-1.903284398447373793e-01,-1.906886117703585348e-01,4.563496123041156649e-02,-1.000000004368703621e+00,0.000000000000000000e+00 +7.636190633283662521e+01,4.664519754699377927e+02,1.077562018741926364e+00,6.909884007764214076e+00,-1.901617731780707032e-01,-1.921357562791765894e-01,4.563496123041156649e-02,-1.000000005081275845e+00,0.000000000000000000e+00 +7.636335353513246105e+01,4.664617952066374187e+02,1.075671841197421097e+00,6.909605948456614577e+00,-1.899951065114040272e-01,-1.935829585823666821e-01,4.563496123041156649e-02,-1.000000004677377152e+00,0.000000000000000000e+00 +7.636480079566723589e+01,4.664716152582302584e+02,1.073783300301943910e+00,6.909325783480454675e+00,-1.898284398447373511e-01,-1.950302191239041416e-01,4.563496123041156649e-02,-1.000000004407747056e+00,0.000000000000000000e+00 +7.636624811488670161e+01,4.664814356244435203e+02,1.071896396107954397e+00,6.909043512495939510e+00,-1.896617731780706750e-01,-1.964775383497519845e-01,4.563496123041156649e-02,-1.000000005091537858e+00,0.000000000000000000e+00 +7.636769549323682327e+01,4.664912563050044128e+02,1.070011128667866629e+00,6.908759135160647880e+00,-1.894951065114039990e-01,-1.979249167072379412e-01,4.563496123041156649e-02,-1.000000004573339263e+00,0.000000000000000000e+00 +7.636914293116372221e+01,4.665010772996401442e+02,1.068127498034048939e+00,6.908472651129528685e+00,-1.893284398447373229e-01,-1.993723546407505653e-01,4.563496123041156649e-02,-1.000000004506365059e+00,0.000000000000000000e+00 +7.637059042911370454e+01,4.665108986080779232e+02,1.066245504258824583e+00,6.908184060054903597e+00,-1.891617731780706468e-01,-2.008198525972531012e-01,4.563496123041156649e-02,-1.000000005264744196e+00,0.000000000000000000e+00 +7.637203798753326112e+01,4.665207202300449012e+02,1.064365147394471078e+00,6.907893361586461722e+00,-1.889951065114039708e-01,-2.022674110244337409e-01,4.563496123041156649e-02,-1.000000004672444875e+00,0.000000000000000000e+00 +7.637348560686908172e+01,4.665305421652682867e+02,1.062486427493220420e+00,6.907600555371256945e+00,-1.888284398447372947e-01,-2.037150303670154650e-01,4.563496123041156649e-02,-1.000000004785047469e+00,0.000000000000000000e+00 +7.637493328756802669e+01,4.665403644134752312e+02,1.060609344607259530e+00,6.907305641053710588e+00,-1.886617731780706186e-01,-2.051627110728829473e-01,4.563496123041156649e-02,-1.000000004684130861e+00,0.000000000000000000e+00 +7.637638103007714108e+01,4.665501869743929433e+02,1.058733898788729366e+00,6.907008618275605194e+00,-1.884951065114039426e-01,-2.066104535887788862e-01,4.563496123041156649e-02,-1.000000005139267012e+00,0.000000000000000000e+00 +7.637782883484366891e+01,4.665600098477485176e+02,1.056860090089725812e+00,6.906709486676084531e+00,-1.883284398447372665e-01,-2.080582583627490767e-01,4.563496123041156649e-02,-1.000000004794498354e+00,0.000000000000000000e+00 +7.637927670231503896e+01,4.665698330332691057e+02,1.054987918562299010e+00,6.906408245891650033e+00,-1.881617731780705904e-01,-2.095061258410665372e-01,4.563496123041156649e-02,-1.000000004828854872e+00,0.000000000000000000e+00 +7.638072463293887893e+01,4.665796565306818593e+02,1.053117384258453804e+00,6.906104895556161694e+00,-1.879951065114039144e-01,-2.109540564719030731e-01,4.563496123041156649e-02,-1.000000005143226067e+00,0.000000000000000000e+00 +7.638217262716301548e+01,4.665894803397138730e+02,1.051248487230149520e+00,6.905799435300833622e+00,-1.878284398447372383e-01,-2.124020507034802552e-01,4.563496123041156649e-02,-1.000000004360715122e+00,0.000000000000000000e+00 +7.638362068543544581e+01,4.665993044600922985e+02,1.049381227529299965e+00,6.905491864754232267e+00,-1.876617731780705622e-01,-2.138501089822205103e-01,4.563496123041156649e-02,-1.000000005332948527e+00,0.000000000000000000e+00 +7.638506880820438028e+01,4.666091288915442306e+02,1.047515605207773204e+00,6.905182183542277308e+00,-1.874951065114038862e-01,-2.152982317588716110e-01,4.563496123041156649e-02,-1.000000004974585188e+00,0.000000000000000000e+00 +7.638651699591821398e+01,4.666189536337967638e+02,1.045651620317392450e+00,6.904870391288233655e+00,-1.873284398447372101e-01,-2.167464194799109956e-01,4.563496123041156649e-02,-1.000000004852371394e+00,0.000000000000000000e+00 +7.638796524902555518e+01,4.666287786865769931e+02,1.043789272909934729e+00,6.904556487612715898e+00,-1.871617731780705340e-01,-2.181946725942837950e-01,4.563496123041156649e-02,-1.000000004831478773e+00,0.000000000000000000e+00 +7.638941356797521109e+01,4.666386040496119563e+02,1.041928563037132216e+00,6.904240472133682971e+00,-1.869951065114038580e-01,-2.196429915509402475e-01,4.563496123041156649e-02,-1.000000005193372399e+00,0.000000000000000000e+00 +7.639086195321618789e+01,4.666484297226288049e+02,1.040069490750671122e+00,6.903922344466436378e+00,-1.868284398447371819e-01,-2.210913767994400481e-01,4.563496123041156649e-02,-1.000000004942309451e+00,0.000000000000000000e+00 +7.639231040519769067e+01,4.666582557053545770e+02,1.038212056102192360e+00,6.903602104223617530e+00,-1.866617731780705058e-01,-2.225398287881038828e-01,4.563496123041156649e-02,-1.000000004768915929e+00,0.000000000000000000e+00 +7.639375892436913773e+01,4.666680819975163104e+02,1.036356259143291325e+00,6.903279751015207744e+00,-1.864951065114038298e-01,-2.239883479664573351e-01,4.563496123041156649e-02,-1.000000005356241672e+00,0.000000000000000000e+00 +7.639520751118014630e+01,4.666779085988410429e+02,1.034502099925517893e+00,6.902955284448524687e+00,-1.863284398447371537e-01,-2.254369347852215322e-01,4.563496123041156649e-02,-1.000000004840620127e+00,0.000000000000000000e+00 +7.639665616608053256e+01,4.666877355090558126e+02,1.032649578500376641e+00,6.902628704128218828e+00,-1.861617731780704776e-01,-2.268855896926254556e-01,4.563496123041156649e-02,-1.000000004737325643e+00,0.000000000000000000e+00 +7.639810488952034007e+01,4.666975627278876573e+02,1.030798694919326408e+00,6.902300009656275215e+00,-1.859951065114038016e-01,-2.283343131393020253e-01,4.563496123041156649e-02,-1.000000005284370275e+00,0.000000000000000000e+00 +7.639955368194982555e+01,4.667073902550636149e+02,1.028949449233780511e+00,6.901969200632008139e+00,-1.858284398447371255e-01,-2.297831055764394670e-01,4.563496123041156649e-02,-1.000000005020030169e+00,0.000000000000000000e+00 +7.640100254381943046e+01,4.667172180903107233e+02,1.027101841495106971e+00,6.901636276652058477e+00,-1.856617731780704494e-01,-2.312319674533201419e-01,4.563496123041156649e-02,-1.000000005437197803e+00,0.000000000000000000e+00 +7.640245147557983785e+01,4.667270462333559635e+02,1.025255871754628290e+00,6.901301237310394576e+00,-1.854951065114037734e-01,-2.326808992216026217e-01,4.563496123041156649e-02,-1.000000004636992124e+00,0.000000000000000000e+00 +7.640390047768192971e+01,4.667368746839263167e+02,1.023411540063621450e+00,6.900964082198306926e+00,-1.853284398447370973e-01,-2.341299013304088683e-01,4.563496123041156649e-02,-1.000000004943555787e+00,0.000000000000000000e+00 +7.640534955057680122e+01,4.667467034417487639e+02,1.021568846473317693e+00,6.900624810904409934e+00,-1.851617731780704212e-01,-2.355789742324446157e-01,4.563496123041156649e-02,-1.000000005289422900e+00,0.000000000000000000e+00 +7.640679869471577490e+01,4.667565325065502861e+02,1.019727791034903186e+00,6.900283423014634820e+00,-1.849951065114037452e-01,-2.370281183790865498e-01,4.563496123041156649e-02,-1.000000005023026217e+00,0.000000000000000000e+00 +7.640824791055040066e+01,4.667663618780578645e+02,1.017888373799518131e+00,6.899939918112229620e+00,-1.848284398447370691e-01,-2.384773342209861868e-01,4.563496123041156649e-02,-1.000000005177324347e+00,0.000000000000000000e+00 +7.640969719853242736e+01,4.667761915559984800e+02,1.016050594818257657e+00,6.899594295777758290e+00,-1.846617731780703930e-01,-2.399266222105125024e-01,4.563496123041156649e-02,-1.000000005086109978e+00,0.000000000000000000e+00 +7.641114655911383124e+01,4.667860215400990569e+02,1.014214454142170929e+00,6.899246555589096275e+00,-1.844951065114037170e-01,-2.413759827992909834e-01,4.563496123041156649e-02,-1.000000004921672847e+00,0.000000000000000000e+00 +7.641259599274683012e+01,4.667958518300865762e+02,1.012379951822262036e+00,6.898896697121429611e+00,-1.843284398447370409e-01,-2.428254164394202386e-01,4.563496123041156649e-02,-1.000000005271696635e+00,0.000000000000000000e+00 +7.641404549988384076e+01,4.668056824256879054e+02,1.010547087909489328e+00,6.898544719947252268e+00,-1.841617731780703648e-01,-2.442749235840756261e-01,4.563496123041156649e-02,-1.000000005025404315e+00,0.000000000000000000e+00 +7.641549508097753574e+01,4.668155133266300254e+02,1.008715862454765633e+00,6.898190623636362595e+00,-1.839951065114036888e-01,-2.457245046850488335e-01,4.563496123041156649e-02,-1.000000005178211859e+00,0.000000000000000000e+00 +7.641694473648078656e+01,4.668253445326398605e+02,1.006886275508958484e+00,6.897834407755863317e+00,-1.838284398447370127e-01,-2.471741601958022672e-01,4.563496123041156649e-02,-1.000000005027639860e+00,0.000000000000000000e+00 +7.641839446684670634e+01,4.668351760434442781e+02,1.005058327122889672e+00,6.897476071870157099e+00,-1.836617731780703366e-01,-2.486238905690093259e-01,4.563496123041156649e-02,-1.000000005553818516e+00,0.000000000000000000e+00 +7.641984427252863554e+01,4.668450078587702592e+02,1.003232017347335470e+00,6.897115615540945655e+00,-1.834951065114036606e-01,-2.500736962589951151e-01,4.563496123041156649e-02,-1.000000004772039430e+00,0.000000000000000000e+00 +7.642129415398015624e+01,4.668548399783446143e+02,1.001407346233026852e+00,6.896753038327225305e+00,-1.833284398447369845e-01,-2.515235777174395504e-01,4.563496123041156649e-02,-1.000000004915085672e+00,0.000000000000000000e+00 +7.642274411165507786e+01,4.668646724018942678e+02,9.995843138306489406e-01,6.896388339785288757e+00,-1.831617731780703084e-01,-2.529735353994934099e-01,4.563496123041156649e-02,-1.000000005673242098e+00,0.000000000000000000e+00 +7.642419414600745142e+01,4.668745051291460868e+02,9.977629201908416734e-01,6.896021519468717997e+00,-1.829951065114036324e-01,-2.544235697600937818e-01,4.563496123041156649e-02,-1.000000004617294769e+00,0.000000000000000000e+00 +7.642564425749155532e+01,4.668843381598269389e+02,9.959431653641992455e-01,6.895652576928382516e+00,-1.828284398447369563e-01,-2.558736812508919378e-01,4.563496123041156649e-02,-1.000000005646697110e+00,0.000000000000000000e+00 +7.642709444656190954e+01,4.668941714936636913e+02,9.941250494012703331e-01,6.895281511712441969e+00,-1.826617731780702802e-01,-2.573238703294318253e-01,4.563496123041156649e-02,-1.000000005050442953e+00,0.000000000000000000e+00 +7.642854471367327562e+01,4.669040051303832115e+02,9.923085723525583157e-01,6.894908323366335523e+00,-1.824951065114036042e-01,-2.587741374481155598e-01,4.563496123041156649e-02,-1.000000005023276239e+00,0.000000000000000000e+00 +7.642999505928064252e+01,4.669138390697123100e+02,9.904937342685208312e-01,6.894533011432787184e+00,-1.823284398447369281e-01,-2.602244830627691297e-01,4.563496123041156649e-02,-1.000000004795665864e+00,0.000000000000000000e+00 +7.643144548383926917e+01,4.669236733113778541e+02,9.886805351995699986e-01,6.894155575451798690e+00,-1.821617731780702520e-01,-2.616749076283451103e-01,4.563496123041156649e-02,-1.000000005701970895e+00,0.000000000000000000e+00 +7.643289598780462768e+01,4.669335078551066545e+02,9.868689751960724177e-01,6.893776014960648624e+00,-1.819951065114035760e-01,-2.631254116019756117e-01,4.563496123041156649e-02,-1.000000004847213519e+00,0.000000000000000000e+00 +7.643434657163246015e+01,4.669433427006255215e+02,9.850590543083492800e-01,6.893394329493887085e+00,-1.818284398447368999e-01,-2.645759954368391842e-01,4.563496123041156649e-02,-1.000000005660977909e+00,0.000000000000000000e+00 +7.643579723577875029e+01,4.669531778476612658e+02,9.832507725866761472e-01,6.893010518583339241e+00,-1.816617731780702238e-01,-2.660266595913362009e-01,4.563496123041156649e-02,-1.000000004811742560e+00,0.000000000000000000e+00 +7.643724798069972337e+01,4.669630132959406978e+02,9.814441300812831726e-01,6.892624581758095559e+00,-1.814951065114035478e-01,-2.674774045192828131e-01,4.563496123041156649e-02,-1.000000004869113335e+00,0.000000000000000000e+00 +7.643869880685184626e+01,4.669728490451906282e+02,9.796391268423547682e-01,6.892236518544516244e+00,-1.813284398447368717e-01,-2.689282306784728793e-01,4.563496123041156649e-02,-1.000000005862487162e+00,0.000000000000000000e+00 +7.644014971469185582e+01,4.669826850951378105e+02,9.778357629200299383e-01,6.891846328466223248e+00,-1.811617731780701956e-01,-2.703791385269946890e-01,4.563496123041156649e-02,-1.000000004438911461e+00,0.000000000000000000e+00 +7.644160070467674473e+01,4.669925214455090554e+02,9.760340383644020568e-01,6.891454011044097605e+00,-1.809951065114035196e-01,-2.718301285183247207e-01,4.563496123041156649e-02,-1.000000005675394155e+00,0.000000000000000000e+00 +7.644305177726374723e+01,4.670023580960311165e+02,9.742339532255190893e-01,6.891059565796283870e+00,-1.808284398447368435e-01,-2.732812011135605235e-01,4.563496123041156649e-02,-1.000000004938349729e+00,0.000000000000000000e+00 +7.644450293291035337e+01,4.670121950464307474e+02,9.724355075533833714e-01,6.890662992238176798e+00,-1.806617731780701674e-01,-2.747323567673323197e-01,4.563496123041156649e-02,-1.000000005601459740e+00,0.000000000000000000e+00 +7.644595417207430899e+01,4.670220322964347019e+02,9.706387013979517198e-01,6.890264289882428450e+00,-1.804951065114034914e-01,-2.761835959394234319e-01,4.563496123041156649e-02,-1.000000004703951673e+00,0.000000000000000000e+00 +7.644740549521364414e+01,4.670318698457696769e+02,9.688435348091354316e-01,6.889863458238938421e+00,-1.803284398447368153e-01,-2.776349190855795790e-01,4.563496123041156649e-02,-1.000000005181492568e+00,0.000000000000000000e+00 +7.644885690278661627e+01,4.670417076941624828e+02,9.670500078368002850e-01,6.889460496814857393e+00,-1.801617731780701392e-01,-2.790863266660675301e-01,4.563496123041156649e-02,-1.000000005323304464e+00,0.000000000000000000e+00 +7.645030839525175281e+01,4.670515458413398164e+02,9.652581205307664280e-01,6.889055405114578257e+00,-1.799951065114034632e-01,-2.805378191389333309e-01,4.563496123041156649e-02,-1.000000005519282587e+00,0.000000000000000000e+00 +7.645175997306786542e+01,4.670613842870283747e+02,9.634678729408084896e-01,6.888648182639736994e+00,-1.798284398447367871e-01,-2.819893969630525299e-01,4.563496123041156649e-02,-1.000000004465734227e+00,0.000000000000000000e+00 +7.645321163669400732e+01,4.670712230309548545e+02,9.616792651166556904e-01,6.888238828889209131e+00,-1.796617731780701110e-01,-2.834410605956733109e-01,4.563496123041156649e-02,-1.000000005487019727e+00,0.000000000000000000e+00 +7.645466338658950178e+01,4.670810620728460094e+02,9.598922971079913991e-01,6.887827343359109733e+00,-1.794951065114034350e-01,-2.848928104991363397e-01,4.563496123041156649e-02,-1.000000005577936779e+00,0.000000000000000000e+00 +7.645611522321395626e+01,4.670909014124285363e+02,9.581069689644537979e-01,6.887413725542783638e+00,-1.793284398447367589e-01,-2.863446471316879460e-01,4.563496123041156649e-02,-1.000000004676036225e+00,0.000000000000000000e+00 +7.645756714702723400e+01,4.671007410494290752e+02,9.563232807356352172e-01,6.886997974930809008e+00,-1.791617731780700828e-01,-2.877965709517532611e-01,4.563496123041156649e-02,-1.000000005238715683e+00,0.000000000000000000e+00 +7.645901915848946828e+01,4.671105809835743230e+02,9.545412324710825791e-01,6.886580091010994664e+00,-1.789951065114034068e-01,-2.892485824215965673e-01,4.563496123041156649e-02,-1.000000005080859511e+00,0.000000000000000000e+00 +7.646047125806107658e+01,4.671204212145909196e+02,9.527608242202971756e-01,6.886160073268372095e+00,-1.788284398447367307e-01,-2.907006820005823000e-01,4.563496123041156649e-02,-1.000000005380051959e+00,0.000000000000000000e+00 +7.646192344620274639e+01,4.671302617422055619e+02,9.509820560327348904e-01,6.885737921185197230e+00,-1.786617731780700546e-01,-2.921528701500590852e-01,4.563496123041156649e-02,-1.000000005199728648e+00,0.000000000000000000e+00 +7.646337572337542099e+01,4.671401025661448898e+02,9.492049279578058663e-01,6.885313634240945113e+00,-1.784951065114033786e-01,-2.936051473302913606e-01,4.563496123041156649e-02,-1.000000004859207481e+00,0.000000000000000000e+00 +7.646482809004035630e+01,4.671499436861356003e+02,9.474294400448748377e-01,6.884887211912309013e+00,-1.783284398447367025e-01,-2.950575140022845821e-01,4.563496123041156649e-02,-1.000000005511748391e+00,0.000000000000000000e+00 +7.646628054665906404e+01,4.671597851019042764e+02,9.456555923432609090e-01,6.884458653673196871e+00,-1.781617731780700264e-01,-2.965099706289981429e-01,4.563496123041156649e-02,-1.000000004934294306e+00,0.000000000000000000e+00 +7.646773309369334015e+01,4.671696268131775014e+02,9.438833849022375544e-01,6.884027958994725971e+00,-1.779951065114033504e-01,-2.979625176704430722e-01,4.563496123041156649e-02,-1.000000005106400858e+00,0.000000000000000000e+00 +7.646918573160526478e+01,4.671794688196819720e+02,9.421128177710328400e-01,6.883595127345224718e+00,-1.778284398447366743e-01,-2.994151555897876515e-01,4.563496123041156649e-02,-1.000000005052228413e+00,0.000000000000000000e+00 +7.647063846085720229e+01,4.671893111211442715e+02,9.403438909988292016e-01,6.883160158190225530e+00,-1.776617731780699982e-01,-3.008678848490662916e-01,4.563496123041156649e-02,-1.000000005472002407e+00,0.000000000000000000e+00 +7.647209128191180127e+01,4.671991537172909830e+02,9.385766046347634450e-01,6.882723050992463953e+00,-1.774951065114033222e-01,-3.023207059116157502e-01,4.563496123041156649e-02,-1.000000004953853550e+00,0.000000000000000000e+00 +7.647354419523199454e+01,4.672089966078487464e+02,9.368109587279268569e-01,6.882283805211874217e+00,-1.773284398447366461e-01,-3.037736192390082524e-01,4.563496123041156649e-02,-1.000000005023421679e+00,0.000000000000000000e+00 +7.647499720128101330e+01,4.672188397925440881e+02,9.350469533273650935e-01,6.881842420305589236e+00,-1.771617731780699700e-01,-3.052266252953207415e-01,4.563496123041156649e-02,-1.000000005094230149e+00,0.000000000000000000e+00 +7.647645030052235882e+01,4.672286832711036482e+02,9.332845884820784033e-01,6.881398895727934395e+00,-1.769951065114032940e-01,-3.066797245440678887e-01,4.563496123041156649e-02,-1.000000005413459458e+00,0.000000000000000000e+00 +7.647790349341984495e+01,4.672385270432539528e+02,9.315238642410212933e-01,6.880953230930425768e+00,-1.768284398447366179e-01,-3.081329174494149004e-01,4.563496123041156649e-02,-1.000000004958438327e+00,0.000000000000000000e+00 +7.647935678043755559e+01,4.672483711087215852e+02,9.297647806531028625e-01,6.880505425361766569e+00,-1.766617731780699418e-01,-3.095862044743337149e-01,4.563496123041156649e-02,-1.000000005221744814e+00,0.000000000000000000e+00 +7.648081016203988725e+01,4.672582154672330716e+02,9.280073377671864687e-01,6.880055478467846264e+00,-1.764951065114032658e-01,-3.110395860842598004e-01,4.563496123041156649e-02,-1.000000004744312054e+00,0.000000000000000000e+00 +7.648226363869153488e+01,4.672680601185149953e+02,9.262515356320899507e-01,6.879603389691734350e+00,-1.763284398447365897e-01,-3.124930627428041396e-01,4.563496123041156649e-02,-1.000000005422387650e+00,0.000000000000000000e+00 +7.648371721085747765e+01,4.672779050622938826e+02,9.244973742965856278e-01,6.879149158473680359e+00,-1.761617731780699136e-01,-3.139466349166314396e-01,4.563496123041156649e-02,-1.000000004940297504e+00,0.000000000000000000e+00 +7.648517087900300737e+01,4.672877502982962596e+02,9.227448538094001895e-01,6.878692784251106751e+00,-1.759951065114032376e-01,-3.154003030693396936e-01,4.563496123041156649e-02,-1.000000004757608529e+00,0.000000000000000000e+00 +7.648662464359370006e+01,4.672975958262485960e+02,9.209939742192148060e-01,6.878234266458610691e+00,-1.758284398447365615e-01,-3.168540676669491796e-01,4.563496123041156649e-02,-1.000000005484471544e+00,0.000000000000000000e+00 +7.648807850509544437e+01,4.673074416458774749e+02,9.192447355746650173e-01,6.877773604527957829e+00,-1.756617731780698854e-01,-3.183079291766696683e-01,4.563496123041156649e-02,-1.000000005201818309e+00,0.000000000000000000e+00 +7.648953246397444161e+01,4.673172877569093657e+02,9.174971379243407332e-01,6.877310797888077865e+00,-1.754951065114032094e-01,-3.197618880632248639e-01,4.563496123041156649e-02,-1.000000004503982742e+00,0.000000000000000000e+00 +7.649098652069717730e+01,4.673271341590707948e+02,9.157511813167863446e-01,6.876845845965065429e+00,-1.753284398447365333e-01,-3.212159447925078681e-01,4.563496123041156649e-02,-1.000000005236618250e+00,0.000000000000000000e+00 +7.649244067573046379e+01,4.673369808520882316e+02,9.140068658005007229e-01,6.876378748182175649e+00,-1.751617731780698572e-01,-3.226700998334026127e-01,4.563496123041156649e-02,-1.000000005456555208e+00,0.000000000000000000e+00 +7.649389492954139769e+01,4.673468278356881456e+02,9.122641914239369987e-01,6.875909503959817037e+00,-1.749951065114031812e-01,-3.241243536522762647e-01,4.563496123041156649e-02,-1.000000004473218018e+00,0.000000000000000000e+00 +7.649534928259741662e+01,4.673566751095970631e+02,9.105231582355027831e-01,6.875438112715552386e+00,-1.748284398447365051e-01,-3.255787067148017688e-01,4.563496123041156649e-02,-1.000000005366838307e+00,0.000000000000000000e+00 +7.649680373536625666e+01,4.673665226735413967e+02,9.087837662835601682e-01,6.874964573864096984e+00,-1.746617731780698290e-01,-3.270331594914436257e-01,4.563496123041156649e-02,-1.000000004910522211e+00,0.000000000000000000e+00 +7.649825828831595231e+01,4.673763705272476159e+02,9.070460156164255050e-01,6.874488886817308853e+00,-1.744951065114031530e-01,-3.284877124482866728e-01,4.563496123041156649e-02,-1.000000004907938500e+00,0.000000000000000000e+00 +7.649971294191487914e+01,4.673862186704421333e+02,9.053099062823697363e-01,6.874011050984192295e+00,-1.743284398447364769e-01,-3.299423660543541192e-01,4.563496123041156649e-02,-1.000000005054924257e+00,0.000000000000000000e+00 +7.650116769663171112e+01,4.673960671028514753e+02,9.035754383296180636e-01,6.873531065770890791e+00,-1.741617731780698008e-01,-3.313971207785434969e-01,4.563496123041156649e-02,-1.000000004619562510e+00,0.000000000000000000e+00 +7.650262255293544911e+01,4.674059158242019976e+02,9.018426118063501695e-01,6.873048930580684335e+00,-1.739951065114031248e-01,-3.328519770890058238e-01,4.563496123041156649e-02,-1.000000005379354073e+00,0.000000000000000000e+00 +7.650407751129542078e+01,4.674157648342201696e+02,9.001114267607001063e-01,6.872564644813987655e+00,-1.738284398447364487e-01,-3.343069354567980156e-01,4.563496123041156649e-02,-1.000000004907240170e+00,0.000000000000000000e+00 +7.650553257218125225e+01,4.674256141326323473e+02,8.983818832407564070e-01,6.872078207868343114e+00,-1.736617731780697726e-01,-3.357619963497673332e-01,4.563496123041156649e-02,-1.000000004544498777e+00,0.000000000000000000e+00 +7.650698773606291070e+01,4.674354637191649999e+02,8.966539812945619747e-01,6.871589619138422478e+00,-1.734951065114030966e-01,-3.372171602380355515e-01,4.563496123041156649e-02,-1.000000005203312003e+00,0.000000000000000000e+00 +7.650844300341067594e+01,4.674453135935445403e+02,8.949277209701139713e-01,6.871098878016020706e+00,-1.733284398447364205e-01,-3.386724275933766792e-01,4.563496123041156649e-02,-1.000000005271452608e+00,0.000000000000000000e+00 +7.650989837469516885e+01,4.674551637554973240e+02,8.932031023153641502e-01,6.870605983890050616e+00,-1.731617731780697444e-01,-3.401277988855450074e-01,4.563496123041156649e-02,-1.000000004386556673e+00,0.000000000000000000e+00 +7.651135385038733716e+01,4.674650142047497070e+02,8.914801253782185242e-01,6.870110936146542890e+00,-1.729951065114030684e-01,-3.415832745840952089e-01,4.563496123041156649e-02,-1.000000005112893442e+00,0.000000000000000000e+00 +7.651280943095844123e+01,4.674748649410281018e+02,8.897587902065375864e-01,6.869613734168643404e+00,-1.728284398447363923e-01,-3.430388551626437632e-01,4.563496123041156649e-02,-1.000000004555246402e+00,0.000000000000000000e+00 +7.651426511688009668e+01,4.674847159640588643e+02,8.880390968481362002e-01,6.869114377336604349e+00,-1.726617731780697163e-01,-3.444945410909243666e-01,4.563496123041156649e-02,-1.000000005260206049e+00,0.000000000000000000e+00 +7.651572090862423181e+01,4.674945672735684070e+02,8.863210453507837094e-01,6.868612865027786896e+00,-1.724951065114030402e-01,-3.459503328427104840e-01,4.563496123041156649e-02,-1.000000004735690506e+00,0.000000000000000000e+00 +7.651717680666311594e+01,4.675044188692830289e+02,8.846046357622037171e-01,6.868109196616652312e+00,-1.723284398447363641e-01,-3.474062308884822703e-01,4.563496123041156649e-02,-1.000000004672406018e+00,0.000000000000000000e+00 +7.651863281146934526e+01,4.675142707509290858e+02,8.828898681300741957e-01,6.867603371474763740e+00,-1.721617731780696881e-01,-3.488622357015173092e-01,4.563496123041156649e-02,-1.000000005075663223e+00,0.000000000000000000e+00 +7.652008892351587122e+01,4.675241229182329334e+02,8.811767425020275990e-01,6.867095388970779091e+00,-1.719951065114030120e-01,-3.503183477554388525e-01,4.563496123041156649e-02,-1.000000004685770882e+00,0.000000000000000000e+00 +7.652154514327598633e+01,4.675339753709208708e+02,8.794652589256508612e-01,6.866585248470447489e+00,-1.718284398447363359e-01,-3.517745675223753477e-01,4.563496123041156649e-02,-1.000000004329118619e+00,0.000000000000000000e+00 +7.652300147122330998e+01,4.675438281087191967e+02,8.777554174484850646e-01,6.866072949336608389e+00,-1.716617731780696599e-01,-3.532308954759995623e-01,4.563496123041156649e-02,-1.000000005241324041e+00,0.000000000000000000e+00 +7.652445790783180257e+01,4.675536811313542671e+02,8.760472181180258833e-01,6.865558490929186242e+00,-1.714951065114029838e-01,-3.546873320921266060e-01,4.563496123041156649e-02,-1.000000004881172133e+00,0.000000000000000000e+00 +7.652591445357577982e+01,4.675635344385523808e+02,8.743406609817232500e-01,6.865041872605184281e+00,-1.713284398447363077e-01,-3.561438778432149954e-01,4.563496123041156649e-02,-1.000000004467365367e+00,0.000000000000000000e+00 +7.652737110892989847e+01,4.675733880300398368e+02,8.726357460869815785e-01,6.864523093718686297e+00,-1.711617731780696317e-01,-3.576005332038441065e-01,4.563496123041156649e-02,-1.000000004372181062e+00,0.000000000000000000e+00 +7.652882787436917056e+01,4.675832419055429341e+02,8.709324734811595414e-01,6.864002153620850422e+00,-1.709951065114029556e-01,-3.590572986494833252e-01,4.563496123041156649e-02,-1.000000005377238210e+00,0.000000000000000000e+00 +7.653028475036894918e+01,4.675930960647879147e+02,8.692308432115702921e-01,6.863479051659904684e+00,-1.708284398447362795e-01,-3.605141746570902361e-01,4.563496123041156649e-02,-1.000000004071128767e+00,0.000000000000000000e+00 +7.653174173740492847e+01,4.676029505075010775e+02,8.675308553254813537e-01,6.862953787181141685e+00,-1.706617731780696035e-01,-3.619711616990034520e-01,4.563496123041156649e-02,-1.000000004984126001e+00,0.000000000000000000e+00 +7.653319883595317208e+01,4.676128052334087215e+02,8.658325098701146194e-01,6.862426359526922148e+00,-1.704951065114029274e-01,-3.634282602545145791e-01,4.563496123041156649e-02,-1.000000004687553679e+00,0.000000000000000000e+00 +7.653465604649009890e+01,4.676226602422370320e+02,8.641358068926463520e-01,6.861896768036661598e+00,-1.703284398447362513e-01,-3.648854707982740475e-01,4.563496123041156649e-02,-1.000000004346662141e+00,0.000000000000000000e+00 +7.653611336949248312e+01,4.676325155337123078e+02,8.624407464402071843e-01,6.861365012046833911e+00,-1.701617731780695753e-01,-3.663427938069860890e-01,4.563496123041156649e-02,-1.000000004698716971e+00,0.000000000000000000e+00 +7.653757080543743996e+01,4.676423711075607912e+02,8.607473285598821189e-01,6.860831090890965100e+00,-1.699951065114028992e-01,-3.678002297587871783e-01,4.563496123041156649e-02,-1.000000004381291552e+00,0.000000000000000000e+00 +7.653902835480245415e+01,4.676522269635086673e+02,8.590555532987106391e-01,6.860295003899627986e+00,-1.698284398447362231e-01,-3.692577791301876466e-01,4.563496123041156649e-02,-1.000000004950233334e+00,0.000000000000000000e+00 +7.654048601806537988e+01,4.676620831012822350e+02,8.573654207036863761e-01,6.859756750400441305e+00,-1.696617731780695471e-01,-3.707154424003266113e-01,4.563496123041156649e-02,-1.000000004189664393e+00,0.000000000000000000e+00 +7.654194379570442663e+01,4.676719395206076797e+02,8.556769308217574421e-01,6.859216329718062610e+00,-1.694951065114028710e-01,-3.721732200454760386e-01,4.563496123041156649e-02,-1.000000004473224902e+00,0.000000000000000000e+00 +7.654340168819815915e+01,4.676817962212111865e+02,8.539900836998264300e-01,6.858673741174189153e+00,-1.693284398447361949e-01,-3.736311125457324467e-01,4.563496123041156649e-02,-1.000000004821242294e+00,0.000000000000000000e+00 +7.654485969602552586e+01,4.676916532028189977e+02,8.523048793847501914e-01,6.858128984087549007e+00,-1.691617731780695189e-01,-3.750891203801305362e-01,4.563496123041156649e-02,-1.000000004245991114e+00,0.000000000000000000e+00 +7.654631781966583048e+01,4.677015104651572983e+02,8.506213179233399480e-01,6.857582057773899287e+00,-1.689951065114028428e-01,-3.765472440266326992e-01,4.563496123041156649e-02,-1.000000004257282971e+00,0.000000000000000000e+00 +7.654777605959876041e+01,4.677113680079522737e+02,8.489393993623612911e-01,6.857032961546024374e+00,-1.688284398447361667e-01,-3.780054839657722709e-01,4.563496123041156649e-02,-1.000000004684494570e+00,0.000000000000000000e+00 +7.654923441630435832e+01,4.677212258309300523e+02,8.472591237485340709e-01,6.856481694713728814e+00,-1.686617731780694907e-01,-3.794638406782052664e-01,4.563496123041156649e-02,-1.000000004095527695e+00,0.000000000000000000e+00 +7.655069289026305057e+01,4.677310839338168762e+02,8.455804911285327297e-01,6.855928256583833758e+00,-1.684951065114028146e-01,-3.809223146428721840e-01,4.563496123041156649e-02,-1.000000004807353626e+00,0.000000000000000000e+00 +7.655215148195563302e+01,4.677409423163388738e+02,8.439035015489859681e-01,6.855372646460176078e+00,-1.683284398447361385e-01,-3.823809063424674082e-01,4.563496123041156649e-02,-1.000000003700083351e+00,0.000000000000000000e+00 +7.655361019186328519e+01,4.677508009782222302e+02,8.422281550564767461e-01,6.854814863643599487e+00,-1.681617731780694625e-01,-3.838396162555112179e-01,4.563496123041156649e-02,-1.000000004741620874e+00,0.000000000000000000e+00 +7.655506902046754192e+01,4.677606599191930741e+02,8.405544516975425040e-01,6.854254907431957200e+00,-1.679951065114027864e-01,-3.852984448666899042e-01,4.563496123041156649e-02,-1.000000003959662820e+00,0.000000000000000000e+00 +7.655652796825035011e+01,4.677705191389775337e+02,8.388823915186750524e-01,6.853692777120099500e+00,-1.678284398447361103e-01,-3.867573926552750341e-01,4.563496123041156649e-02,-1.000000004468286630e+00,0.000000000000000000e+00 +7.655798703569401198e+01,4.677803786373017374e+02,8.372119745663204604e-01,6.853128471999878180e+00,-1.676617731780694343e-01,-3.882164601054627906e-01,4.563496123041156649e-02,-1.000000004364142603e+00,0.000000000000000000e+00 +7.655944622328124183e+01,4.677902384138918706e+02,8.355432008868791671e-01,6.852561991360135885e+00,-1.674951065114027582e-01,-3.896756476990558271e-01,4.563496123041156649e-02,-1.000000003821940320e+00,0.000000000000000000e+00 +7.656090553149510924e+01,4.678000984684740047e+02,8.338760705267060924e-01,6.851993334486706111e+00,-1.673284398447360821e-01,-3.911349559184966185e-01,4.563496123041156649e-02,-1.000000004257442843e+00,0.000000000000000000e+00 +7.656236496081908172e+01,4.678099588007742113e+02,8.322105835321103040e-01,6.851422500662408765e+00,-1.671617731780694061e-01,-3.925943852486805108e-01,4.563496123041156649e-02,-1.000000004157954203e+00,0.000000000000000000e+00 +7.656382451173701043e+01,4.678198194105186758e+02,8.305467399493553504e-01,6.850849489167043060e+00,-1.669951065114027300e-01,-3.940539361726839163e-01,4.563496123041156649e-02,-1.000000004086896599e+00,0.000000000000000000e+00 +7.656528418473315867e+01,4.678296802974334128e+02,8.288845398246591500e-01,6.850274299277386625e+00,-1.668284398447360539e-01,-3.955136091747957772e-01,4.563496123041156649e-02,-1.000000004181091917e+00,0.000000000000000000e+00 +7.656674398029215922e+01,4.678395414612445506e+02,8.272239832041938801e-01,6.849696930267190176e+00,-1.666617731780693779e-01,-3.969734047398968402e-01,4.563496123041156649e-02,-1.000000003734466070e+00,0.000000000000000000e+00 +7.656820389889904277e+01,4.678494029016781610e+02,8.255650701340861985e-01,6.849117381407173077e+00,-1.664951065114027018e-01,-3.984333233522309170e-01,4.563496123041156649e-02,-1.000000004115428887e+00,0.000000000000000000e+00 +7.656966394103923790e+01,4.678592646184603154e+02,8.239078006604169113e-01,6.848535651965020676e+00,-1.663284398447360257e-01,-3.998933654984351271e-01,4.563496123041156649e-02,-1.000000004182548530e+00,0.000000000000000000e+00 +7.657112410719857110e+01,4.678691266113170855e+02,8.222521748292214161e-01,6.847951741205377196e+00,-1.661617731780693497e-01,-4.013535316638775496e-01,4.563496123041156649e-02,-1.000000003618851885e+00,0.000000000000000000e+00 +7.657258439786326676e+01,4.678789888799745427e+02,8.205981926864892584e-01,6.847365648389843962e+00,-1.659951065114026736e-01,-4.028138223338623702e-01,4.563496123041156649e-02,-1.000000003763864997e+00,0.000000000000000000e+00 +7.657404481351996139e+01,4.678888514241587018e+02,8.189458542781643535e-01,6.846777372776975845e+00,-1.658284398447359975e-01,-4.042742379960506671e-01,4.563496123041156649e-02,-1.000000003864739639e+00,0.000000000000000000e+00 +7.657550535465567521e+01,4.678987142435956343e+02,8.172951596501449867e-01,6.846186913622274162e+00,-1.656617731780693215e-01,-4.057347791374068535e-01,4.563496123041156649e-02,-1.000000003992583597e+00,0.000000000000000000e+00 +7.657696602175784051e+01,4.679085773380113551e+02,8.156461088482838129e-01,6.845594270178184004e+00,-1.654951065114026454e-01,-4.071954462454036028e-01,4.563496123041156649e-02,-1.000000003792454129e+00,0.000000000000000000e+00 +7.657842681531430173e+01,4.679184407071318788e+02,8.139987019183877459e-01,6.844999441694089803e+00,-1.653284398447359693e-01,-4.086562398074012892e-01,4.563496123041156649e-02,-1.000000003316440012e+00,0.000000000000000000e+00 +7.657988773581330122e+01,4.679283043506832200e+02,8.123529389062181805e-01,6.844402427416311774e+00,-1.651617731780692933e-01,-4.101171603112442332e-01,4.563496123041156649e-02,-1.000000003855136654e+00,0.000000000000000000e+00 +7.658134878374349341e+01,4.679381682683913937e+02,8.107088198574906590e-01,6.843803226588101474e+00,-1.649951065114026172e-01,-4.115782082470720304e-01,4.563496123041156649e-02,-1.000000003776734925e+00,0.000000000000000000e+00 +7.658280995959395909e+01,4.679480324599824144e+02,8.090663448178752049e-01,6.843201838449634700e+00,-1.648284398447359411e-01,-4.130393841030518542e-01,4.563496123041156649e-02,-1.000000003520525649e+00,0.000000000000000000e+00 +7.658427126385416273e+01,4.679578969251822400e+02,8.074255138329962111e-01,6.842598262238010598e+00,-1.646617731780692651e-01,-4.145006883684059229e-01,4.563496123041156649e-02,-1.000000003516021030e+00,0.000000000000000000e+00 +7.658573269701402353e+01,4.679677616637168853e+02,8.057863269484322188e-01,6.841992497187246336e+00,-1.644951065114025890e-01,-4.159621215333992317e-01,4.563496123041156649e-02,-1.000000003351026567e+00,0.000000000000000000e+00 +7.658719425956384441e+01,4.679776266753123650e+02,8.041487842097162497e-01,6.841384542528271773e+00,-1.643284398447359129e-01,-4.174236840881113686e-01,4.563496123041156649e-02,-1.000000003851039265e+00,0.000000000000000000e+00 +7.658865595199435461e+01,4.679874919596946370e+02,8.025128856623354734e-01,6.840774397488925906e+00,-1.641617731780692369e-01,-4.188853765242472327e-01,4.563496123041156649e-02,-1.000000002922032394e+00,0.000000000000000000e+00 +7.659011777479670968e+01,4.679973575165896023e+02,8.008786313517316513e-01,6.840162061293950657e+00,-1.639951065114025608e-01,-4.203471993308714461e-01,4.563496123041156649e-02,-1.000000003448333397e+00,0.000000000000000000e+00 +7.659157972846247731e+01,4.680072233457232755e+02,7.992460213233006927e-01,6.839547533164990867e+00,-1.638284398447358847e-01,-4.218091530016871982e-01,4.563496123041156649e-02,-1.000000003316469988e+00,0.000000000000000000e+00 +7.659304181348367990e+01,4.680170894468216147e+02,7.976150556223928767e-01,6.838930812320583641e+00,-1.636617731780692087e-01,-4.232712380277323660e-01,4.563496123041156649e-02,-1.000000003312871311e+00,0.000000000000000000e+00 +7.659450403035272359e+01,4.680269558196105208e+02,7.959857342943127412e-01,6.838311897976158349e+00,-1.634951065114025326e-01,-4.247334549016205107e-01,4.563496123041156649e-02,-1.000000002967354806e+00,0.000000000000000000e+00 +7.659596637956246923e+01,4.680368224638159518e+02,7.943580573843193049e-01,6.837690789344030406e+00,-1.633284398447358565e-01,-4.261958041157055121e-01,4.563496123041156649e-02,-1.000000003461258613e+00,0.000000000000000000e+00 +7.659742886160620401e+01,4.680466893791638086e+02,7.927320249376258454e-01,6.837067485633397723e+00,-1.631617731780691805e-01,-4.276582861644984690e-01,4.563496123041156649e-02,-1.000000002643830932e+00,0.000000000000000000e+00 +7.659889147697764145e+01,4.680565565653800491e+02,7.911076369993997881e-01,6.836441986050333597e+00,-1.629951065114025044e-01,-4.291209015397965953e-01,4.563496123041156649e-02,-1.000000003337179200e+00,0.000000000000000000e+00 +7.660035422617092138e+01,4.680664240221905743e+02,7.894848936147631502e-01,6.835814289797786714e+00,-1.628284398447358283e-01,-4.305836507379579570e-01,4.563496123041156649e-02,-1.000000002956072720e+00,0.000000000000000000e+00 +7.660181710968063840e+01,4.680762917493212854e+02,7.878637948287920967e-01,6.835184396075570490e+00,-1.626617731780691523e-01,-4.320465342519945184e-01,4.563496123041156649e-02,-1.000000002641795227e+00,0.000000000000000000e+00 +7.660328012800179920e+01,4.680861597464980832e+02,7.862443406865171625e-01,6.834552304080363960e+00,-1.624951065114024762e-01,-4.335095525770245595e-01,4.563496123041156649e-02,-1.000000002694992673e+00,0.000000000000000000e+00 +7.660474328162987945e+01,4.680960280134468121e+02,7.846265312329231412e-01,6.833918013005704672e+00,-1.623284398447358001e-01,-4.349727062090451568e-01,4.563496123041156649e-02,-1.000000002991339398e+00,0.000000000000000000e+00 +7.660620657106076692e+01,4.681058965498934299e+02,7.830103665129491963e-01,6.833281522041983358e+00,-1.621617731780691241e-01,-4.364359956443123467e-01,4.563496123041156649e-02,-1.000000002567019264e+00,0.000000000000000000e+00 +7.660766999679081835e+01,4.681157653555637808e+02,7.813958465714887502e-01,6.832642830376439491e+00,-1.619951065114024480e-01,-4.378994213781143841e-01,4.563496123041156649e-02,-1.000000002936821009e+00,0.000000000000000000e+00 +7.660913355931680258e+01,4.681256344301837089e+02,7.797829714533897061e-01,6.832001937193158625e+00,-1.618284398447357719e-01,-4.393629839084006727e-01,4.563496123041156649e-02,-1.000000002287763090e+00,0.000000000000000000e+00 +7.661059725913597163e+01,4.681355037734790585e+02,7.781717412034540038e-01,6.831358841673064397e+00,-1.616617731780690959e-01,-4.408266837309136044e-01,4.563496123041156649e-02,-1.000000002528428356e+00,0.000000000000000000e+00 +7.661206109674598963e+01,4.681453733851757306e+02,7.765621558664381752e-01,6.830713542993917642e+00,-1.614951065114024198e-01,-4.422905213446371997e-01,4.563496123041156649e-02,-1.000000002240628794e+00,0.000000000000000000e+00 +7.661352507264500389e+01,4.681552432649995126e+02,7.749542154870528998e-01,6.830066040330307509e+00,-1.613284398447357437e-01,-4.437544972469297244e-01,4.563496123041156649e-02,-1.000000002482799077e+00,0.000000000000000000e+00 +7.661498918733158803e+01,4.681651134126763054e+02,7.733479201099631162e-01,6.829416332853649685e+00,-1.611617731780690677e-01,-4.452186119371508433e-01,4.563496123041156649e-02,-1.000000002231439478e+00,0.000000000000000000e+00 +7.661645344130478463e+01,4.681749838279318965e+02,7.717432697797881325e-01,6.828764419732179292e+00,-1.609951065114023916e-01,-4.466828659136156121e-01,4.563496123041156649e-02,-1.000000002109903141e+00,0.000000000000000000e+00 +7.661791783506409104e+01,4.681848545104921300e+02,7.701402645411016268e-01,6.828110300130948218e+00,-1.608284398447357155e-01,-4.481472596760074367e-01,4.563496123041156649e-02,-1.000000001902948910e+00,0.000000000000000000e+00 +7.661938236910944511e+01,4.681947254600827932e+02,7.685389044384315360e-01,6.827453973211818905e+00,-1.606617731780690395e-01,-4.496117937241521645e-01,4.563496123041156649e-02,-1.000000002213028427e+00,0.000000000000000000e+00 +7.662084704394126788e+01,4.682045966764297305e+02,7.669391895162600559e-01,6.826795438133459903e+00,-1.604951065114023634e-01,-4.510764685592175138e-01,4.563496123041156649e-02,-1.000000001562070029e+00,0.000000000000000000e+00 +7.662231186006043515e+01,4.682144681592587290e+02,7.653411198190236409e-01,6.826134694051339658e+00,-1.603284398447356873e-01,-4.525412846806677325e-01,4.563496123041156649e-02,-1.000000002187594772e+00,0.000000000000000000e+00 +7.662377681796827744e+01,4.682243399082955762e+02,7.637446953911132264e-01,6.825471740117724728e+00,-1.601617731780690113e-01,-4.540062425917078537e-01,4.563496123041156649e-02,-1.000000001349712564e+00,0.000000000000000000e+00 +7.662524191816658004e+01,4.682342119232660025e+02,7.621499162768738955e-01,6.824806575481670023e+00,-1.599951065114023352e-01,-4.554713427919944713e-01,4.563496123041156649e-02,-1.000000001678114980e+00,0.000000000000000000e+00 +7.662670716115762559e+01,4.682440842038958522e+02,7.605567825206051014e-01,6.824139199289019686e+00,-1.598284398447356591e-01,-4.569365857855038349e-01,4.563496123041156649e-02,-1.000000001653905235e+00,0.000000000000000000e+00 +7.662817254744415152e+01,4.682539567499109125e+02,7.589652941665604446e-01,6.823469610682396436e+00,-1.596617731780689831e-01,-4.584019720744559878e-01,4.563496123041156649e-02,-1.000000001403071215e+00,0.000000000000000000e+00 +7.662963807752936418e+01,4.682638295610368573e+02,7.573754512589480070e-01,6.822797808801199793e+00,-1.594951065114023070e-01,-4.598675021617264491e-01,4.563496123041156649e-02,-1.000000001041071007e+00,0.000000000000000000e+00 +7.663110375191693890e+01,4.682737026369995306e+02,7.557872538419301289e-01,6.822123792781600748e+00,-1.593284398447356309e-01,-4.613331765508327797e-01,4.563496123041156649e-02,-1.000000001499127933e+00,0.000000000000000000e+00 +7.663256957111103418e+01,4.682835759775246629e+02,7.542007019596234096e-01,6.821447561756536437e+00,-1.591617731780689549e-01,-4.627989957471323468e-01,4.563496123041156649e-02,-1.000000000804448952e+00,0.000000000000000000e+00 +7.663403553561629167e+01,4.682934495823379279e+02,7.526157956560987072e-01,6.820769114855703030e+00,-1.589951065114022788e-01,-4.642649602535676157e-01,4.563496123041156649e-02,-1.000000000693957336e+00,0.000000000000000000e+00 +7.663550164593780778e+01,4.683033234511651131e+02,7.510325349753811386e-01,6.820088451205554847e+00,-1.588284398447356027e-01,-4.657310705761057990e-01,4.563496123041156649e-02,-1.000000001239976566e+00,0.000000000000000000e+00 +7.663696790258119051e+01,4.683131975837319487e+02,7.494509199614501904e-01,6.819405569929295474e+00,-1.586617731780689267e-01,-4.671973272213010842e-01,4.563496123041156649e-02,-1.000000000025920599e+00,0.000000000000000000e+00 +7.663843430605250262e+01,4.683230719797641655e+02,7.478709506582397193e-01,6.818720470146872437e+00,-1.584951065114022506e-01,-4.686637306926468849e-01,4.563496123041156649e-02,-1.000000001233644076e+00,0.000000000000000000e+00 +7.663990085685830422e+01,4.683329466389874369e+02,7.462926271096376185e-01,6.818033150974977197e+00,-1.583284398447355745e-01,-4.701302815002533220e-01,4.563496123041156649e-02,-9.999999999479771695e-01,0.000000000000000000e+00 +7.664136755550563862e+01,4.683428215611274936e+02,7.447159493594862623e-01,6.817343611527030944e+00,-1.581617731780688985e-01,-4.715969801475090595e-01,4.563496123041156649e-02,-1.000000000327837979e+00,0.000000000000000000e+00 +7.664283440250203228e+01,4.683526967459100092e+02,7.431409174515822835e-01,6.816651850913189925e+00,-1.579951065114022224e-01,-4.730638271443906584e-01,4.563496123041156649e-02,-1.000000000327858185e+00,0.000000000000000000e+00 +7.664430139835552325e+01,4.683625721930607142e+02,7.415675314296765741e-01,6.815957868240331230e+00,-1.578284398447355463e-01,-4.745308229983653536e-01,4.563496123041156649e-02,-9.999999995436376077e-01,0.000000000000000000e+00 +7.664576854357463276e+01,4.683724479023052254e+02,7.399957913374742846e-01,6.815261662612051907e+00,-1.576617731780688703e-01,-4.759979682167993498e-01,4.563496123041156649e-02,-1.000000000035691006e+00,0.000000000000000000e+00 +7.664723583866835099e+01,4.683823238733692733e+02,7.384256972186348245e-01,6.814563233128664521e+00,-1.574951065114021942e-01,-4.774652633105763155e-01,4.563496123041156649e-02,-9.999999993148324107e-01,0.000000000000000000e+00 +7.664870328414620815e+01,4.683922001059785316e+02,7.368572491167719729e-01,6.813862578887187382e+00,-1.573284398447355181e-01,-4.789327087874241662e-01,4.563496123041156649e-02,-9.999999994190241770e-01,0.000000000000000000e+00 +7.665017088051818916e+01,4.684020765998586171e+02,7.352904470754536570e-01,6.813159698981344548e+00,-1.571617731780688421e-01,-4.804003051585595818e-01,4.563496123041156649e-02,-9.999999994876522802e-01,0.000000000000000000e+00 +7.665163862829481900e+01,4.684119533547352034e+02,7.337252911382022846e-01,6.812454592501556050e+00,-1.569951065114021660e-01,-4.818680529344368524e-01,4.563496123041156649e-02,-9.999999990619193868e-01,0.000000000000000000e+00 +7.665310652798709157e+01,4.684218303703339075e+02,7.321617813484943005e-01,6.811747258534934346e+00,-1.568284398447354899e-01,-4.833359526253391825e-01,4.563496123041156649e-02,-9.999999984968324096e-01,0.000000000000000000e+00 +7.665457458010654079e+01,4.684317076463804028e+02,7.305999177497605190e-01,6.811037696165279876e+00,-1.566617731780688139e-01,-4.848040047425751231e-01,4.563496123041156649e-02,-9.999999985478678077e-01,0.000000000000000000e+00 +7.665604278516516956e+01,4.684415851826003063e+02,7.290397003853861246e-01,6.810325904473074843e+00,-1.564951065114021378e-01,-4.862722097990687664e-01,4.563496123041156649e-02,-9.999999987228408438e-01,0.000000000000000000e+00 +7.665751114367550656e+01,4.684514629787192916e+02,7.274811292987104494e-01,6.809611882535476113e+00,-1.563284398447354617e-01,-4.877405683075302090e-01,4.563496123041156649e-02,-9.999999981071434618e-01,0.000000000000000000e+00 +7.665897965615059206e+01,4.684613410344629187e+02,7.259242045330270843e-01,6.808895629426310769e+00,-1.561617731780687857e-01,-4.892090807798369356e-01,4.563496123041156649e-02,-9.999999978346392204e-01,0.000000000000000000e+00 +7.666044832310397794e+01,4.684712193495568044e+02,7.243689261315839900e-01,6.808177144216072563e+00,-1.559951065114021096e-01,-4.906777477300438006e-01,4.563496123041156649e-02,-9.999999973803006537e-01,0.000000000000000000e+00 +7.666191714504972765e+01,4.684810979237265656e+02,7.228152941375833862e-01,6.807456425971913916e+00,-1.558284398447354335e-01,-4.921465696719491412e-01,4.563496123041156649e-02,-9.999999978544650281e-01,0.000000000000000000e+00 +7.666338612250243045e+01,4.684909767566977621e+02,7.212633085941816402e-01,6.806733473757641484e+00,-1.556617731780687575e-01,-4.936155471214987989e-01,4.563496123041156649e-02,-9.999999966519529382e-01,0.000000000000000000e+00 +7.666485525597718720e+01,4.685008558481960108e+02,7.197129695444894892e-01,6.806008286633708160e+00,-1.554951065114020814e-01,-4.950846805913302617e-01,4.563496123041156649e-02,-9.999999973295999878e-01,0.000000000000000000e+00 +7.666632454598961033e+01,4.685107351979469286e+02,7.181642770315719293e-01,6.805280863657213075e+00,-1.553284398447354053e-01,-4.965539705998268660e-01,4.563496123041156649e-02,-9.999999960261031218e-01,0.000000000000000000e+00 +7.666779399305583809e+01,4.685206148056760185e+02,7.166172310984482152e-01,6.804551203881888277e+00,-1.551617731780687293e-01,-4.980234176602215124e-01,4.563496123041156649e-02,-9.999999962741838999e-01,0.000000000000000000e+00 +7.666926359769254873e+01,4.685304946711088974e+02,7.150718317880917496e-01,6.803819306358101393e+00,-1.549951065114020532e-01,-4.994930222914625850e-01,4.563496123041156649e-02,-9.999999958360898944e-01,0.000000000000000000e+00 +7.667073336041694631e+01,4.685403747939710684e+02,7.135280791434304160e-01,6.803085170132842308e+00,-1.548284398447353771e-01,-5.009627850097370105e-01,4.563496123041156649e-02,-9.999999953422337162e-01,0.000000000000000000e+00 +7.667220328174674648e+01,4.685502551739881483e+02,7.119859732073461345e-01,6.802348794249722275e+00,-1.546617731780687011e-01,-5.024327063326868847e-01,4.563496123041156649e-02,-9.999999949994118342e-01,0.000000000000000000e+00 +7.667367336220020491e+01,4.685601358108856402e+02,7.104455140226751952e-01,6.801610177748966812e+00,-1.544951065114020250e-01,-5.039027867787891912e-01,4.563496123041156649e-02,-9.999999945925008848e-01,0.000000000000000000e+00 +7.667514360229610304e+01,4.685700167043891042e+02,7.089067016322081471e-01,6.800869319667409485e+00,-1.543284398447353489e-01,-5.053730268667376846e-01,4.563496123041156649e-02,-9.999999943054206364e-01,0.000000000000000000e+00 +7.667661400255377657e+01,4.685798978542240434e+02,7.073695360786897979e-01,6.800126219038486575e+00,-1.541617731780686729e-01,-5.068434271160315863e-01,4.563496123041156649e-02,-9.999999934889980402e-01,0.000000000000000000e+00 +7.667808456349307278e+01,4.685897792601160177e+02,7.058340174048192139e-01,6.799380874892230864e+00,-1.539951065114019968e-01,-5.083139880457526738e-01,4.563496123041156649e-02,-9.999999931255836305e-01,0.000000000000000000e+00 +7.667955528563439316e+01,4.685996609217905302e+02,7.043001456532496096e-01,6.798633286255267194e+00,-1.538284398447353207e-01,-5.097847101769664713e-01,4.563496123041156649e-02,-9.999999929530452025e-01,0.000000000000000000e+00 +7.668102616949869343e+01,4.686095428389730841e+02,7.027679208665885691e-01,6.797883452150804473e+00,-1.536617731780686447e-01,-5.112555940308944891e-01,4.563496123041156649e-02,-9.999999918774462593e-01,0.000000000000000000e+00 +7.668249721560744092e+01,4.686194250113891826e+02,7.012373430873979352e-01,6.797131371598630345e+00,-1.534951065114019686e-01,-5.127266401276925345e-01,4.563496123041156649e-02,-9.999999912557812065e-01,0.000000000000000000e+00 +7.668396842448267137e+01,4.686293074387643287e+02,6.997084123581936987e-01,6.796377043615107638e+00,-1.533284398447352925e-01,-5.141978489900579374e-01,4.563496123041156649e-02,-9.999999907910730457e-01,0.000000000000000000e+00 +7.668543979664696053e+01,4.686391901208240256e+02,6.981811287214462203e-01,6.795620467213165483e+00,-1.531617731780686165e-01,-5.156692211407989390e-01,4.563496123041156649e-02,-9.999999897647249281e-01,0.000000000000000000e+00 +7.668691133262343840e+01,4.686490730572937196e+02,6.966554922195800081e-01,6.794861641402293984e+00,-1.529951065114019404e-01,-5.171407571022161864e-01,4.563496123041156649e-02,-9.999999890873108033e-01,0.000000000000000000e+00 +7.668838303293578917e+01,4.686589562478989137e+02,6.951315028949738295e-01,6.794100565188539775e+00,-1.528284398447352643e-01,-5.186124573985020358e-01,4.563496123041156649e-02,-9.999999884263572891e-01,0.000000000000000000e+00 +7.668985489810823708e+01,4.686688396923650544e+02,6.936091607899607103e-01,6.793337237574498033e+00,-1.526617731780685883e-01,-5.200843225539136805e-01,4.563496123041156649e-02,-9.999999874381335641e-01,0.000000000000000000e+00 +7.669132692866557477e+01,4.686787233904175878e+02,6.920884659468279354e-01,6.792571657559307141e+00,-1.524951065114019122e-01,-5.215563530927584956e-01,4.563496123041156649e-02,-9.999999861770723086e-01,0.000000000000000000e+00 +7.669279912513314912e+01,4.686886073417820171e+02,6.905694184078171594e-01,6.791803824138643364e+00,-1.523284398447352361e-01,-5.230285495399821238e-01,4.563496123041156649e-02,-9.999999846854175090e-01,0.000000000000000000e+00 +7.669427148803686123e+01,4.686984915461837318e+02,6.890520182151239625e-01,6.791033736304714630e+00,-1.521617731780685601e-01,-5.245009124211527096e-01,4.563496123041156649e-02,-9.999999842219507995e-01,0.000000000000000000e+00 +7.669574401790319484e+01,4.687083760033482349e+02,6.875362654108984062e-01,6.790261393046254312e+00,-1.519951065114018840e-01,-5.259734422642544649e-01,4.563496123041156649e-02,-9.999999819373867060e-01,0.000000000000000000e+00 +7.669721671525918794e+01,4.687182607130009160e+02,6.860221600372448103e-01,6.789486793348512350e+00,-1.518284398447352079e-01,-5.274461395936407282e-01,4.563496123041156649e-02,-9.999999807047748046e-01,0.000000000000000000e+00 +7.669868958063243269e+01,4.687281456748671644e+02,6.845097021362216427e-01,6.788709936193255245e+00,-1.516617731780685319e-01,-5.289190049384624448e-01,4.563496123041156649e-02,-9.999999788798059619e-01,0.000000000000000000e+00 +7.670016261455110396e+01,4.687380308886724833e+02,6.829988917498415191e-01,6.787930820558753631e+00,-1.514951065114018558e-01,-5.303920388260180419e-01,4.563496123041156649e-02,-9.999999764441945826e-01,0.000000000000000000e+00 +7.670163581754394500e+01,4.687479163541422054e+02,6.814897289200715358e-01,6.787149445419779603e+00,-1.513284398447351797e-01,-5.318652417841499558e-01,4.563496123041156649e-02,-9.999999737769510455e-01,0.000000000000000000e+00 +7.670310919014026751e+01,4.687578020710017768e+02,6.799822136888327151e-01,6.786365809747600508e+00,-1.511617731780685037e-01,-5.333386143418321623e-01,4.563496123041156649e-02,-9.999999716528683580e-01,0.000000000000000000e+00 +7.670458273286996587e+01,4.687676880389765870e+02,6.784763460980006711e-01,6.785579912509971834e+00,-1.509951065114018276e-01,-5.348121570297558192e-01,4.563496123041156649e-02,-9.999999679719163703e-01,0.000000000000000000e+00 +7.670605644626350283e+01,4.687775742577920255e+02,6.769721261894049436e-01,6.784791752671129217e+00,-1.508284398447351515e-01,-5.362858703760953194e-01,4.563496123041156649e-02,-9.999999638939738311e-01,0.000000000000000000e+00 +7.670753033085193806e+01,4.687874607271734817e+02,6.754695540048294422e-01,6.784001329191786667e+00,-1.506617731780684755e-01,-5.377597549113137809e-01,4.563496123041156649e-02,-9.999999585218495302e-01,0.000000000000000000e+00 +7.670900438716689962e+01,4.687973474468462882e+02,6.739686295860122245e-01,6.783208641029127683e+00,-1.504951065114017994e-01,-5.392338111651338028e-01,4.563496123041156649e-02,-9.999999525814582402e-01,0.000000000000000000e+00 +7.671047861574059823e+01,4.688072344165358913e+02,6.724693529746457177e-01,6.782413687136800817e+00,-1.503284398447351233e-01,-5.407080396689318835e-01,4.563496123041156649e-02,-9.999999443342683092e-01,0.000000000000000000e+00 +7.671195301710584147e+01,4.688171216359675668e+02,6.709717242123764969e-01,6.781616466464911674e+00,-1.501617731780684473e-01,-5.421824409521075472e-01,4.563496123041156649e-02,-9.999999340733926045e-01,0.000000000000000000e+00 +7.671342759179603377e+01,4.688270091048667041e+02,6.694757433408052849e-01,6.780816977960020253e+00,-1.499951065114017712e-01,-5.436570155450801689e-01,4.563496123041156649e-02,-9.999999188122148386e-01,0.000000000000000000e+00 +7.671490234034513378e+01,4.688368968229586926e+02,6.679814104014871745e-01,6.780015220565133838e+00,-1.498284398447350951e-01,-5.451317639744546195e-01,4.563496123041156649e-02,-9.999998963720064804e-01,0.000000000000000000e+00 +7.671637726328773965e+01,4.688467847899688081e+02,6.664887254359314062e-01,6.779211193219706999e+00,-1.496617731780684191e-01,-5.466066867642129790e-01,4.563496123041156649e-02,-9.999998588494125595e-01,0.000000000000000000e+00 +7.671785236115900375e+01,4.688566730056224401e+02,6.649976884856013681e-01,6.778404894859639818e+00,-1.494951065114017430e-01,-5.480817844272708461e-01,4.563496123041156649e-02,-9.999997840569974095e-01,0.000000000000000000e+00 +7.671932763449470372e+01,4.688665614696449211e+02,6.635082995919148185e-01,6.777596324417288542e+00,-1.493284398447350669e-01,-5.495570574444010870e-01,4.563496123041156649e-02,-9.999995592577926029e-01,0.000000000000000000e+00 +7.672080308383121405e+01,4.688764501817615269e+02,6.620205587962436633e-01,6.776785480821507335e+00,-1.491617731780683909e-01,-5.510325061306191596e-01,4.563496123041156649e-02,-5.791287887860665506e-01,0.000000000000000000e+00 +7.672227870970550612e+01,4.688863391416975901e+02,6.605344661399140671e-01,6.775972362997887188e+00,-1.489951065114017148e-01,-5.518870835558969956e-01,4.563496123041156649e-02,9.999995615863523923e-01,0.000000000000000000e+00 +7.672375451265514812e+01,4.688962283491783865e+02,6.590500216642063425e-01,6.775157886412106478e+00,-1.488284398447350387e-01,-5.504112812532678811e-01,4.563496123041156649e-02,9.999997870266447153e-01,0.000000000000000000e+00 +7.672523049301865683e+01,4.689061178039292486e+02,6.575672254103550607e-01,6.774345490169124240e+00,-1.486617731780683627e-01,-5.489353012041059410e-01,4.563496123041156649e-02,9.999998608535092259e-01,0.000000000000000000e+00 +7.672670665038536697e+01,4.689160075056754522e+02,6.560860774195490519e-01,6.773535175280400722e+00,-1.484951065114016866e-01,-5.474591440427909461e-01,4.563496123041156649e-02,9.999998992353918981e-01,0.000000000000000000e+00 +7.672818298434411588e+01,4.689258974541423299e+02,6.546065777329312940e-01,6.772726942755026514e+00,-1.483284398447350105e-01,-5.459828102328111443e-01,4.563496123041156649e-02,9.999999212485113365e-01,0.000000000000000000e+00 +7.672965949448317247e+01,4.689357876490551007e+02,6.531287263915990238e-01,6.771920793599970345e+00,-1.481617731780683345e-01,-5.445063002100377636e-01,4.563496123041156649e-02,9.999999365760172676e-01,0.000000000000000000e+00 +7.673113618039027983e+01,4.689456780901390971e+02,6.516525234366036257e-01,6.771116728820115505e+00,-1.479951065114016584e-01,-5.430296143965812616e-01,4.563496123041156649e-02,9.999999467440793266e-01,0.000000000000000000e+00 +7.673261304165268371e+01,4.689555687771195380e+02,6.501779689089507430e-01,6.770314749418275824e+00,-1.478284398447349823e-01,-5.415527532128303623e-01,4.563496123041156649e-02,9.999999549023314005e-01,0.000000000000000000e+00 +7.673409007785707558e+01,4.689654597097216993e+02,6.487050628496001670e-01,6.769514856395193902e+00,-1.476617731780683063e-01,-5.400757170750521974e-01,4.563496123041156649e-02,9.999999613458291359e-01,0.000000000000000000e+00 +7.673556728858962117e+01,4.689753508876707997e+02,6.472338052994660584e-01,6.768717050749542885e+00,-1.474951065114016302e-01,-5.385985063996060473e-01,4.563496123041156649e-02,9.999999663658195592e-01,0.000000000000000000e+00 +7.673704467343597457e+01,4.689852423106921151e+02,6.457641962994166152e-01,6.767921333477922019e+00,-1.473284398447349541e-01,-5.371211216029478930e-01,4.563496123041156649e-02,9.999999702513193700e-01,0.000000000000000000e+00 +7.673852223198124989e+01,4.689951339785109212e+02,6.442962358902742936e-01,6.767127705574852214e+00,-1.471617731780682781e-01,-5.356435631016326360e-01,4.563496123041156649e-02,9.999999741011219578e-01,0.000000000000000000e+00 +7.673999996381003541e+01,4.690050258908523801e+02,6.428299241128158092e-01,6.766336168032771603e+00,-1.469951065114016020e-01,-5.341658313111163903e-01,4.563496123041156649e-02,9.999999761640819829e-01,0.000000000000000000e+00 +7.674147786850640784e+01,4.690149180474417676e+02,6.413652610077721361e-01,6.765546721842032873e+00,-1.468284398447349259e-01,-5.326879266499667809e-01,4.563496123041156649e-02,9.999999791597560250e-01,0.000000000000000000e+00 +7.674295594565391809e+01,4.690248104480042457e+02,6.399022466158281741e-01,6.764759367990894390e+00,-1.466617731780682499e-01,-5.312098495332552295e-01,4.563496123041156649e-02,9.999999817379799927e-01,0.000000000000000000e+00 +7.674443419483560547e+01,4.690347030922650902e+02,6.384408809776233040e-01,6.763974107465521080e+00,-1.464951065114015738e-01,-5.297316003785702554e-01,4.563496123041156649e-02,9.999999825469653159e-01,0.000000000000000000e+00 +7.674591261563395506e+01,4.690445959799494631e+02,6.369811641337510544e-01,6.763190941249976440e+00,-1.463284398447348977e-01,-5.282531796060199181e-01,4.563496123041156649e-02,9.999999847022176258e-01,0.000000000000000000e+00 +7.674739120763096878e+01,4.690544891107825833e+02,6.355230961247591015e-01,6.762409870326214545e+00,-1.461617731780682217e-01,-5.267745876316265452e-01,4.563496123041156649e-02,9.999999864395363591e-01,0.000000000000000000e+00 +7.674886997040810854e+01,4.690643824844896130e+02,6.340666769911492695e-01,6.761630895674081820e+00,-1.459951065114015456e-01,-5.252958248745396297e-01,4.563496123041156649e-02,9.999999876177737557e-01,0.000000000000000000e+00 +7.675034890354632466e+01,4.690742761007957711e+02,6.326119067733777523e-01,6.760854018271308163e+00,-1.458284398447348695e-01,-5.238168917546357495e-01,4.563496123041156649e-02,9.999999889049878687e-01,0.000000000000000000e+00 +7.675182800662605587e+01,4.690841699594262195e+02,6.311587855118547807e-01,6.760079239093501613e+00,-1.456617731780681935e-01,-5.223377886913208590e-01,4.563496123041156649e-02,9.999999893420892239e-01,0.000000000000000000e+00 +7.675330727922720087e+01,4.690940640601061205e+02,6.297073132469447332e-01,6.759306559114144797e+00,-1.454951065114015174e-01,-5.208585161059359203e-01,4.563496123041156649e-02,9.999999908086265599e-01,0.000000000000000000e+00 +7.675478672092917520e+01,4.691039584025606359e+02,6.282574900189664691e-01,6.758535979304587826e+00,-1.453284398447348413e-01,-5.193790744175570406e-01,4.563496123041156649e-02,9.999999915278737772e-01,0.000000000000000000e+00 +7.675626633131086862e+01,4.691138529865149280e+02,6.268093158681926624e-01,6.757767500634047408e+00,-1.451617731780681653e-01,-5.178994640484031464e-01,4.563496123041156649e-02,9.999999929668290655e-01,0.000000000000000000e+00 +7.675774610995064506e+01,4.691237478116941588e+02,6.253627908348504683e-01,6.757001124069597964e+00,-1.449951065114014892e-01,-5.164196854190362673e-01,4.563496123041156649e-02,9.999999925331123363e-01,0.000000000000000000e+00 +7.675922605642637109e+01,4.691336428778234904e+02,6.239179149591211893e-01,6.756236850576169850e+00,-1.448284398447348131e-01,-5.149397389543672876e-01,4.563496123041156649e-02,9.999999941201186404e-01,0.000000000000000000e+00 +7.676070617031538745e+01,4.691435381846280279e+02,6.224746882811401649e-01,6.755474681116538704e+00,-1.446617731780681371e-01,-5.134596250740570689e-01,4.563496123041156649e-02,9.999999947242502740e-01,0.000000000000000000e+00 +7.676218645119453754e+01,4.691534337318329335e+02,6.210331108409971046e-01,6.754714616651328996e+00,-1.444951065114014610e-01,-5.119793442027223973e-01,4.563496123041156649e-02,9.999999949883877637e-01,0.000000000000000000e+00 +7.676366689864013892e+01,4.691633295191633124e+02,6.195931826787358654e-01,6.753956658139002478e+00,-1.443284398447347849e-01,-5.104988967645386344e-01,4.563496123041156649e-02,9.999999955523110051e-01,0.000000000000000000e+00 +7.676514751222802602e+01,4.691732255463442698e+02,6.181549038343543412e-01,6.753200806535854639e+00,-1.441617731780681089e-01,-5.090182831832429367e-01,4.563496123041156649e-02,9.999999962413893551e-01,0.000000000000000000e+00 +7.676662829153349321e+01,4.691831218131009109e+02,6.167182743478047957e-01,6.752447062796011146e+00,-1.439951065114014328e-01,-5.075375038833388475e-01,4.563496123041156649e-02,9.999999964732820823e-01,0.000000000000000000e+00 +7.676810923613135174e+01,4.691930183191583410e+02,6.152832942589935294e-01,6.751695427871422517e+00,-1.438284398447347567e-01,-5.060565592906992594e-01,4.563496123041156649e-02,9.999999972826529859e-01,0.000000000000000000e+00 +7.676959034559590123e+01,4.692029150642416653e+02,6.138499636077812127e-01,6.750945902711857904e+00,-1.436617731780680807e-01,-5.045754498301708857e-01,4.563496123041156649e-02,9.999999976754956332e-01,0.000000000000000000e+00 +7.677107161950094394e+01,4.692128120480759890e+02,6.124182824339824416e-01,6.750198488264902430e+00,-1.434951065114014046e-01,-5.030941759285776360e-01,4.563496123041156649e-02,9.999999978704621206e-01,0.000000000000000000e+00 +7.677255305741975633e+01,4.692227092703863605e+02,6.109882507773661819e-01,6.749453185475950079e+00,-1.433284398447347285e-01,-5.016127380129238311e-01,4.563496123041156649e-02,9.999999980820082346e-01,0.000000000000000000e+00 +7.677403465892511747e+01,4.692326067308978850e+02,6.095598686776556585e-01,6.748709995288199259e+00,-1.431617731780680525e-01,-5.001311365103993101e-01,4.563496123041156649e-02,9.999999985214801379e-01,0.000000000000000000e+00 +7.677551642358932327e+01,4.692425044293356109e+02,6.081331361745280217e-01,6.747968918642648362e+00,-1.429951065114013764e-01,-4.986493718483829274e-01,4.563496123041156649e-02,9.999999993965902334e-01,0.000000000000000000e+00 +7.677699835098415804e+01,4.692524023654246434e+02,6.067080533076147919e-01,6.747229956478091317e+00,-1.428284398447347003e-01,-4.971674444544468274e-01,4.563496123041156649e-02,9.999999988899137549e-01,0.000000000000000000e+00 +7.677848044068089450e+01,4.692623005388900310e+02,6.052846201165015261e-01,6.746493109731113158e+00,-1.426617731780680243e-01,-4.956853547593567666e-01,4.563496123041156649e-02,1.000000000033294922e+00,0.000000000000000000e+00 +7.677996269225032222e+01,4.692721989494567651e+02,6.038628366407281511e-01,6.745758379336081134e+00,-1.424951065114013482e-01,-4.942031031898844740e-01,4.563496123041156649e-02,9.999999997900345106e-01,0.000000000000000000e+00 +7.678144510526271915e+01,4.692820975968499511e+02,6.024427029197885197e-01,6.745025766225146491e+00,-1.423284398447346721e-01,-4.927206901778007908e-01,4.563496123041156649e-02,9.999999999717945620e-01,0.000000000000000000e+00 +7.678292767928788010e+01,4.692919964807946371e+02,6.010242189931308543e-01,6.744295271328232921e+00,-1.421617731780679961e-01,-4.912381161526885864e-01,4.563496123041156649e-02,1.000000000365049324e+00,0.000000000000000000e+00 +7.678441041389508825e+01,4.693018956010158149e+02,5.996073849001575251e-01,6.743566895573035680e+00,-1.419951065114013200e-01,-4.897553815449434134e-01,4.563496123041156649e-02,1.000000000752997442e+00,0.000000000000000000e+00 +7.678589330865314366e+01,4.693117949572384759e+02,5.981922006802250502e-01,6.742840639885016252e+00,-1.418284398447346439e-01,-4.882724867857775042e-01,4.563496123041156649e-02,1.000000000915823195e+00,0.000000000000000000e+00 +7.678737636313033477e+01,4.693216945491877254e+02,5.967786663726439844e-01,6.742116505187397024e+00,-1.416617731780679679e-01,-4.867894323072233798e-01,4.563496123041156649e-02,1.000000001034036856e+00,0.000000000000000000e+00 +7.678885957689448105e+01,4.693315943765884981e+02,5.953667820166792524e-01,6.741394492401155958e+00,-1.414951065114012918e-01,-4.853062185415392138e-01,4.563496123041156649e-02,1.000000001284246709e+00,0.000000000000000000e+00 +7.679034294951290462e+01,4.693414944391658423e+02,5.939565476515499265e-01,6.740674602445022146e+00,-1.413284398447346157e-01,-4.838228459212134958e-01,4.563496123041156649e-02,1.000000001839570496e+00,0.000000000000000000e+00 +7.679182648055241600e+01,4.693513947366447496e+02,5.925479633164290050e-01,6.739956836235471371e+00,-1.411617731780679397e-01,-4.823393148789690832e-01,4.563496123041156649e-02,1.000000001659171245e+00,0.000000000000000000e+00 +7.679331016957935674e+01,4.693612952687502116e+02,5.911410290504439669e-01,6.739241194686721670e+00,-1.409951065114012636e-01,-4.808556258495632063e-01,4.563496123041156649e-02,1.000000001716061293e+00,0.000000000000000000e+00 +7.679479401615957102e+01,4.693711960352072197e+02,5.897357448926763279e-01,6.738527678710726221e+00,-1.408284398447345875e-01,-4.793717792667988586e-01,4.563496123041156649e-02,1.000000002172487967e+00,0.000000000000000000e+00 +7.679627801985841984e+01,4.693810970357407086e+02,5.883321108821616408e-01,6.737816289217170684e+00,-1.406617731780679115e-01,-4.778877755647263359e-01,4.563496123041156649e-02,1.000000002380325048e+00,0.000000000000000000e+00 +7.679776218024076684e+01,4.693909982700757269e+02,5.869301270578898277e-01,6.737107027113468760e+00,-1.404951065114012354e-01,-4.764036151788448303e-01,4.563496123041156649e-02,1.000000002494752405e+00,0.000000000000000000e+00 +7.679924649687099247e+01,4.694008997379371522e+02,5.855297934588049591e-01,6.736399893304755970e+00,-1.403284398447345593e-01,-4.749192985449094406e-01,4.563496123041156649e-02,1.000000002264006538e+00,0.000000000000000000e+00 +7.680073096931300825e+01,4.694108014390500330e+02,5.841311101238050307e-01,6.735694888693885218e+00,-1.401617731780678833e-01,-4.734348260995341340e-01,4.563496123041156649e-02,1.000000003044533070e+00,0.000000000000000000e+00 +7.680221559713021406e+01,4.694207033731392471e+02,5.827340770917424084e-01,6.734992014181421460e+00,-1.399951065114012072e-01,-4.719501982778032678e-01,4.563496123041156649e-02,1.000000002965182544e+00,0.000000000000000000e+00 +7.680370037988555509e+01,4.694306055399297861e+02,5.813386944014236057e-01,6.734291270665639928e+00,-1.398284398447345311e-01,-4.704654155180619801e-01,4.563496123041156649e-02,1.000000002972085911e+00,0.000000000000000000e+00 +7.680518531714146491e+01,4.694405079391465847e+02,5.799449620916092840e-01,6.733592659042517248e+00,-1.396617731780678551e-01,-4.689804782577328135e-01,4.563496123041156649e-02,1.000000003201128251e+00,0.000000000000000000e+00 +7.680667040845992233e+01,4.694504105705145776e+02,5.785528802010141414e-01,6.732896180205728776e+00,-1.394951065114011790e-01,-4.674953869345173652e-01,4.563496123041156649e-02,1.000000002979414493e+00,0.000000000000000000e+00 +7.680815565340242301e+01,4.694603134337586425e+02,5.771624487683071347e-01,6.732201835046644156e+00,-1.393284398447345029e-01,-4.660101419875963824e-01,4.563496123041156649e-02,1.000000004045589419e+00,0.000000000000000000e+00 +7.680964105152996524e+01,4.694702165286037712e+02,5.757736678321113688e-01,6.731509624454321106e+00,-1.391617731780678269e-01,-4.645247438540470175e-01,4.563496123041156649e-02,1.000000003303953333e+00,0.000000000000000000e+00 +7.681112660240307832e+01,4.694801198547748413e+02,5.743865374310040961e-01,6.730819549315504524e+00,-1.389951065114011508e-01,-4.630391929760223624e-01,4.563496123041156649e-02,1.000000003692862682e+00,0.000000000000000000e+00 +7.681261230558182262e+01,4.694900234119967308e+02,5.730010576035168279e-01,6.730131610514614948e+00,-1.388284398447344747e-01,-4.615534897917874524e-01,4.563496123041156649e-02,1.000000003719301533e+00,0.000000000000000000e+00 +7.681409816062578955e+01,4.694999271999943744e+02,5.716172283881350014e-01,6.729445808933750328e+00,-1.386617731780677987e-01,-4.600676347423007795e-01,4.563496123041156649e-02,1.000000003898319445e+00,0.000000000000000000e+00 +7.681558416709407311e+01,4.695098312184927067e+02,5.702350498232983123e-01,6.728762145452678034e+00,-1.384951065114011226e-01,-4.585816282682301237e-01,4.563496123041156649e-02,1.000000004338682968e+00,0.000000000000000000e+00 +7.681707032454529838e+01,4.695197354672165488e+02,5.688545219474006043e-01,6.728080620948831303e+00,-1.383284398447344465e-01,-4.570954708105549602e-01,4.563496123041156649e-02,1.000000003939045312e+00,0.000000000000000000e+00 +7.681855663253763566e+01,4.695296399458908354e+02,5.674756447987898689e-01,6.727401236297304798e+00,-1.381617731780677705e-01,-4.556091628123639103e-01,4.563496123041156649e-02,1.000000004006609045e+00,0.000000000000000000e+00 +7.682004309062877212e+01,4.695395446542403874e+02,5.660984184157682453e-01,6.726723992370847505e+00,-1.379951065114010944e-01,-4.541227047152741059e-01,4.563496123041156649e-02,1.000000004637844109e+00,0.000000000000000000e+00 +7.682152969837592593e+01,4.695494495919901397e+02,5.647228428365921316e-01,6.726048890039860950e+00,-1.378284398447344183e-01,-4.526360969612291951e-01,4.563496123041156649e-02,1.000000004317910474e+00,0.000000000000000000e+00 +7.682301645533584633e+01,4.695593547588649130e+02,5.633489180994718515e-01,6.725375930172394767e+00,-1.376617731780677423e-01,-4.511493399948938166e-01,4.563496123041156649e-02,1.000000004742949367e+00,0.000000000000000000e+00 +7.682450336106481359e+01,4.695692601545895286e+02,5.619766442425719877e-01,6.724705113634138698e+00,-1.374951065114010662e-01,-4.496624342588789736e-01,4.563496123041156649e-02,1.000000004390502850e+00,0.000000000000000000e+00 +7.682599041511863902e+01,4.695791657788889211e+02,5.606060213040112705e-01,6.724036441288421706e+00,-1.373284398447343901e-01,-4.481753801985261521e-01,4.563496123041156649e-02,1.000000004947702470e+00,0.000000000000000000e+00 +7.682747761705267919e+01,4.695890716314878546e+02,5.592370493218625782e-01,6.723369913996203984e+00,-1.371617731780677141e-01,-4.466881782571338055e-01,4.563496123041156649e-02,1.000000004482807459e+00,0.000000000000000000e+00 +7.682896496642180750e+01,4.695989777121112070e+02,5.578697283341529367e-01,6.722705532616076063e+00,-1.369951065114010380e-01,-4.452008288813377734e-01,4.563496123041156649e-02,1.000000005075682319e+00,0.000000000000000000e+00 +7.683045246278045681e+01,4.696088840204837993e+02,5.565040583788634088e-01,6.722043298004249934e+00,-1.368284398447343619e-01,-4.437133325151440544e-01,4.563496123041156649e-02,1.000000005188099728e+00,0.000000000000000000e+00 +7.683194010568257681e+01,4.696187905563304525e+02,5.551400394939293159e-01,6.721383211014559045e+00,-1.366617731780676859e-01,-4.422256896053088915e-01,4.563496123041156649e-02,1.000000004884123328e+00,0.000000000000000000e+00 +7.683342789468166245e+01,4.696286973193760446e+02,5.537776717172401275e-01,6.720725272498450309e+00,-1.364951065114010098e-01,-4.407379005989546794e-01,4.563496123041156649e-02,1.000000005025823979e+00,0.000000000000000000e+00 +7.683491582933075392e+01,4.696386043093453395e+02,5.524169550866392386e-01,6.720069483304979663e+00,-1.363284398447343337e-01,-4.392499659423814151e-01,4.563496123041156649e-02,1.000000004866003600e+00,0.000000000000000000e+00 +7.683640390918243668e+01,4.696485115259631016e+02,5.510578896399245252e-01,6.719415844280809402e+00,-1.361617731780676577e-01,-4.377618860834597836e-01,4.563496123041156649e-02,1.000000005658598479e+00,0.000000000000000000e+00 +7.683789213378882721e+01,4.696584189689542086e+02,5.497004754148476779e-01,6.718764356270201965e+00,-1.359951065114009816e-01,-4.362736614686523184e-01,4.563496123041156649e-02,1.000000005444977802e+00,0.000000000000000000e+00 +7.683938050270158726e+01,4.696683266380433679e+02,5.483447124491146463e-01,6.718115020115018154e+00,-1.358284398447343055e-01,-4.347852925477930230e-01,4.563496123041156649e-02,1.000000005069892728e+00,0.000000000000000000e+00 +7.684086901547192383e+01,4.696782345329554573e+02,5.469906007803855275e-01,6.717467836654708258e+00,-1.356617731780676295e-01,-4.332967797699144863e-01,4.563496123041156649e-02,1.000000005773494349e+00,0.000000000000000000e+00 +7.684235767165058917e+01,4.696881426534151842e+02,5.456381404462745666e-01,6.716822806726309381e+00,-1.354951065114009534e-01,-4.318081235826576325e-01,4.563496123041156649e-02,1.000000005184555452e+00,0.000000000000000000e+00 +7.684384647078788078e+01,4.696980509991473696e+02,5.442873314843500454e-01,6.716179931164443673e+00,-1.353284398447342773e-01,-4.303193244376464777e-01,4.563496123041156649e-02,1.000000005736812358e+00,0.000000000000000000e+00 +7.684533541243365562e+01,4.697079595698767776e+02,5.429381739321345046e-01,6.715539210801308556e+00,-1.351617731780676013e-01,-4.288303827833340187e-01,4.563496123041156649e-02,1.000000005851920060e+00,0.000000000000000000e+00 +7.684682449613730171e+01,4.697178683653281155e+02,5.415906678271045216e-01,6.714900646466677614e+00,-1.349951065114009252e-01,-4.273412990709740122e-01,4.563496123041156649e-02,1.000000005550610194e+00,0.000000000000000000e+00 +7.684831372144776651e+01,4.697277773852262044e+02,5.402448132066908215e-01,6.714264238987892597e+00,-1.348284398447342491e-01,-4.258520737522393240e-01,4.563496123041156649e-02,1.000000006050024925e+00,0.000000000000000000e+00 +7.684980308791355696e+01,4.697376866292957516e+02,5.389006101082782774e-01,6.713629989189858982e+00,-1.346617731780675731e-01,-4.243627072774388553e-01,4.563496123041156649e-02,1.000000005359434896e+00,0.000000000000000000e+00 +7.685129259508272526e+01,4.697475960972615212e+02,5.375580585692057989e-01,6.712997897895044197e+00,-1.344951065114008970e-01,-4.228732001002938334e-01,4.563496123041156649e-02,1.000000006288130683e+00,0.000000000000000000e+00 +7.685278224250286883e+01,4.697575057888482775e+02,5.362171586267665546e-01,6.712367965923468738e+00,-1.343284398447342209e-01,-4.213835526707874202e-01,4.563496123041156649e-02,1.000000005636092038e+00,0.000000000000000000e+00 +7.685427202972114458e+01,4.697674157037807277e+02,5.348779103182077499e-01,6.711740194092707945e+00,-1.341617731780675449e-01,-4.198937654441145528e-01,4.563496123041156649e-02,1.000000006202595992e+00,0.000000000000000000e+00 +7.685576195628426888e+01,4.697773258417835791e+02,5.335403136807306268e-01,6.711114583217880458e+00,-1.339951065114008688e-01,-4.184038388717440382e-01,4.563496123041156649e-02,1.000000005980034912e+00,0.000000000000000000e+00 +7.685725202173851756e+01,4.697872362025815391e+02,5.322043687514907973e-01,6.710491134111649991e+00,-1.338284398447341927e-01,-4.169137734085783809e-01,4.563496123041156649e-02,1.000000006157271137e+00,0.000000000000000000e+00 +7.685874222562972591e+01,4.697971467858993719e+02,5.308700755675977989e-01,6.709869847584216451e+00,-1.336617731780675167e-01,-4.154235695081903157e-01,4.563496123041156649e-02,1.000000006318169987e+00,0.000000000000000000e+00 +7.686023256750328869e+01,4.698070575914617280e+02,5.295374341661152062e-01,6.709250724443314162e+00,-1.334951065114008406e-01,-4.139332276252129517e-01,4.563496123041156649e-02,1.000000006042297551e+00,0.000000000000000000e+00 +7.686172304690414592e+01,4.698169686189933714e+02,5.282064445840609634e-01,6.708633765494206536e+00,-1.333284398447341645e-01,-4.124427482153452118e-01,4.563496123041156649e-02,1.000000006104023953e+00,0.000000000000000000e+00 +7.686321366337682548e+01,4.698268798682189527e+02,5.268771068584069406e-01,6.708018971539680742e+00,-1.331617731780674885e-01,-4.109521317335698698e-01,4.563496123041156649e-02,1.000000006473013903e+00,0.000000000000000000e+00 +7.686470441646540053e+01,4.698367913388631223e+02,5.255494210260792665e-01,6.707406343380045044e+00,-1.329951065114008124e-01,-4.094613786353515361e-01,4.563496123041156649e-02,1.000000006315304057e+00,0.000000000000000000e+00 +7.686619530571350367e+01,4.698467030306506445e+02,5.242233871239581067e-01,6.706795881813124360e+00,-1.328284398447341363e-01,-4.079704893778335895e-01,4.563496123041156649e-02,1.000000006390767915e+00,0.000000000000000000e+00 +7.686768633066434120e+01,4.698566149433061128e+02,5.228990051888776636e-01,6.706187587634254044e+00,-1.326617731780674603e-01,-4.064794644174609672e-01,4.563496123041156649e-02,1.000000006654943929e+00,0.000000000000000000e+00 +7.686917749086070728e+01,4.698665270765542346e+02,5.215762752576262873e-01,6.705581461636277218e+00,-1.324951065114007842e-01,-4.049883042111779297e-01,4.563496123041156649e-02,1.000000006260143515e+00,0.000000000000000000e+00 +7.687066878584492713e+01,4.698764394301197171e+02,5.202551973669465868e-01,6.704977504609540340e+00,-1.323284398447341081e-01,-4.034970092176247136e-01,4.563496123041156649e-02,1.000000006350816539e+00,0.000000000000000000e+00 +7.687216021515891384e+01,4.698863520037271542e+02,5.189357715535350968e-01,6.704375717341886975e+00,-1.321617731780674321e-01,-4.020055798941656322e-01,4.563496123041156649e-02,1.000000006868188240e+00,0.000000000000000000e+00 +7.687365177834415420e+01,4.698962647971011961e+02,5.176179978540426108e-01,6.703776100618656031e+00,-1.319951065114007560e-01,-4.005140166986819183e-01,4.563496123041156649e-02,1.000000006550909815e+00,0.000000000000000000e+00 +7.687514347494169442e+01,4.699061778099665503e+02,5.163018763050738480e-01,6.703178655222677307e+00,-1.318284398447340799e-01,-3.990223200913644019e-01,4.563496123041156649e-02,1.000000006528714014e+00,0.000000000000000000e+00 +7.687663530449216864e+01,4.699160910420478103e+02,5.149874069431877865e-01,6.702583381934264395e+00,-1.316617731780674039e-01,-3.975304905311458636e-01,4.563496123041156649e-02,1.000000006728059221e+00,0.000000000000000000e+00 +7.687812726653578466e+01,4.699260044930696267e+02,5.136745898048974412e-01,6.701990281531212901e+00,-1.314951065114007278e-01,-3.960385284774944337e-01,4.563496123041156649e-02,1.000000006671945219e+00,0.000000000000000000e+00 +7.687961936061230972e+01,4.699359181627565931e+02,5.123634249266699747e-01,6.701399354788796003e+00,-1.313284398447340517e-01,-3.945464343910143890e-01,4.563496123041156649e-02,1.000000007075271480e+00,0.000000000000000000e+00 +7.688111158626109898e+01,4.699458320508333600e+02,5.110539123449266974e-01,6.700810602479759126e+00,-1.311617731780673757e-01,-3.930542087316665767e-01,4.563496123041156649e-02,1.000000006653366746e+00,0.000000000000000000e+00 +7.688260394302108125e+01,4.699557461570245209e+02,5.097460520960428454e-01,6.700224025374317272e+00,-1.309951065114006996e-01,-3.915618519617508619e-01,4.563496123041156649e-02,1.000000006510198602e+00,0.000000000000000000e+00 +7.688409643043077324e+01,4.699656604810546696e+02,5.084398442163480247e-01,6.699639624240147917e+00,-1.308284398447340235e-01,-3.900693645423405354e-01,4.563496123041156649e-02,1.000000007344914676e+00,0.000000000000000000e+00 +7.688558904802826532e+01,4.699755750226484565e+02,5.071352887421256561e-01,6.699057399842389238e+00,-1.306617731780673475e-01,-3.885767469338847202e-01,4.563496123041156649e-02,1.000000006662531193e+00,0.000000000000000000e+00 +7.688708179535123577e+01,4.699854897815304184e+02,5.058323857096134191e-01,6.698477352943637442e+00,-1.304951065114006714e-01,-3.870839996009747819e-01,4.563496123041156649e-02,1.000000006747198356e+00,0.000000000000000000e+00 +7.688857467193692230e+01,4.699954047574252058e+02,5.045311351550030299e-01,6.697899484303937001e+00,-1.303284398447339953e-01,-3.855911230052097016e-01,4.563496123041156649e-02,1.000000007087138654e+00,0.000000000000000000e+00 +7.689006767732217895e+01,4.700053199500573555e+02,5.032315371144404637e-01,6.697323794680781539e+00,-1.301617731780673193e-01,-3.840981176093679617e-01,4.563496123041156649e-02,1.000000007165700255e+00,0.000000000000000000e+00 +7.689156081104343343e+01,4.700152353591514611e+02,5.019335916240255102e-01,6.696750284829108502e+00,-1.299951065114006432e-01,-3.826049838774138179e-01,4.563496123041156649e-02,1.000000006859902646e+00,0.000000000000000000e+00 +7.689305407263670133e+01,4.700251509844321163e+02,5.006372987198123292e-01,6.696178955501293828e+00,-1.298284398447339671e-01,-3.811117222739084376e-01,4.563496123041156649e-02,1.000000007236545807e+00,0.000000000000000000e+00 +7.689454746163757193e+01,4.700350668256238578e+02,4.993426584378090061e-01,6.695609807447147510e+00,-1.296617731780672911e-01,-3.796183332622318773e-01,4.563496123041156649e-02,1.000000006967434407e+00,0.000000000000000000e+00 +7.689604097758123658e+01,4.700449828824512792e+02,4.980496708139777740e-01,6.695042841413911816e+00,-1.294951065114006150e-01,-3.781248173081582231e-01,4.563496123041156649e-02,1.000000007108541089e+00,0.000000000000000000e+00 +7.689753462000248874e+01,4.700548991546389175e+02,4.967583358842349583e-01,6.694478058146254185e+00,-1.293284398447339389e-01,-3.766311748762938838e-01,4.563496123041156649e-02,1.000000007516076428e+00,0.000000000000000000e+00 +7.689902838843568134e+01,4.700648156419113093e+02,4.954686536844509215e-01,6.693915458386265449e+00,-1.291617731780672629e-01,-3.751374064318679369e-01,4.563496123041156649e-02,1.000000006847066247e+00,0.000000000000000000e+00 +7.690052228241479781e+01,4.700747323439929914e+02,4.941806242504502289e-01,6.693355042873455396e+00,-1.289951065114005868e-01,-3.736435124425223631e-01,4.563496123041156649e-02,1.000000007335497321e+00,0.000000000000000000e+00 +7.690201630147339529e+01,4.700846492606085008e+02,4.928942476180114829e-01,6.692796812344745661e+00,-1.288284398447339107e-01,-3.721494933729673771e-01,4.563496123041156649e-02,1.000000007229988830e+00,0.000000000000000000e+00 +7.690351044514463297e+01,4.700945663914824308e+02,4.916095238228673225e-01,6.692240767534470613e+00,-1.286617731780672347e-01,-3.706553496909337220e-01,4.563496123041156649e-02,1.000000007161709892e+00,0.000000000000000000e+00 +7.690500471296125795e+01,4.701044837363392048e+02,4.903264529007045902e-01,6.691686909174369369e+00,-1.284951065114005586e-01,-3.691610818636120728e-01,4.563496123041156649e-02,1.000000007358710752e+00,0.000000000000000000e+00 +7.690649910445561943e+01,4.701144012949034163e+02,4.890450348871641095e-01,6.691135237993583118e+00,-1.283284398447338825e-01,-3.676666903582538337e-01,4.563496123041156649e-02,1.000000007247801026e+00,0.000000000000000000e+00 +7.690799361915966870e+01,4.701243190668995453e+02,4.877652698178407964e-01,6.690585754718651579e+00,-1.281617731780672065e-01,-3.661721756433671815e-01,4.563496123041156649e-02,1.000000007443847982e+00,0.000000000000000000e+00 +7.690948825660497334e+01,4.701342370520521285e+02,4.864871577282837145e-01,6.690038460073507665e+00,-1.279951065114005304e-01,-3.646775381869403199e-01,4.563496123041156649e-02,1.000000007363481380e+00,0.000000000000000000e+00 +7.691098301632267464e+01,4.701441552500856460e+02,4.852106986539959643e-01,6.689493354779474821e+00,-1.278284398447338543e-01,-3.631827784582309371e-01,4.563496123041156649e-02,1.000000007610263308e+00,0.000000000000000000e+00 +7.691247789784354438e+01,4.701540736607245776e+02,4.839358926304347386e-01,6.688950439555261696e+00,-1.276617731780671783e-01,-3.616878969259908483e-01,4.563496123041156649e-02,1.000000007192968665e+00,0.000000000000000000e+00 +7.691397290069792803e+01,4.701639922836934034e+02,4.826627396930113223e-01,6.688409715116959475e+00,-1.274951065114005022e-01,-3.601928940608485896e-01,4.563496123041156649e-02,1.000000007499050492e+00,0.000000000000000000e+00 +7.691546802441581576e+01,4.701739111187166600e+02,4.813912398770910372e-01,6.687871182178035667e+00,-1.273284398447338261e-01,-3.586977703317521526e-01,4.563496123041156649e-02,1.000000007526178125e+00,0.000000000000000000e+00 +7.691696326852677146e+01,4.701838301655187706e+02,4.801213932179933530e-01,6.687334841449333211e+00,-1.271617731780671501e-01,-3.572025262095402942e-01,4.563496123041156649e-02,1.000000007458951901e+00,0.000000000000000000e+00 +7.691845863255998950e+01,4.701937494238242152e+02,4.788531997509918314e-01,6.686800693639064264e+00,-1.269951065114004740e-01,-3.557071621651667903e-01,4.563496123041156649e-02,1.000000007476119279e+00,0.000000000000000000e+00 +7.691995411604426636e+01,4.702036688933574737e+02,4.775866595113140156e-01,6.686268739452806642e+00,-1.268284398447337979e-01,-3.542116786697077635e-01,4.563496123041156649e-02,1.000000007750982522e+00,0.000000000000000000e+00 +7.692144971850801483e+01,4.702135885738430261e+02,4.763217725341415965e-01,6.685738979593500275e+00,-1.266617731780671219e-01,-3.527160761943683998e-01,4.563496123041156649e-02,1.000000007656915102e+00,0.000000000000000000e+00 +7.692294543947924979e+01,4.702235084650052954e+02,4.750585388546103016e-01,6.685211414761443649e+00,-1.264951065114004458e-01,-3.512203552116779925e-01,4.563496123041156649e-02,1.000000007356482090e+00,0.000000000000000000e+00 +7.692444127848561664e+01,4.702334285665687048e+02,4.737969585078100065e-01,6.684686045654288478e+00,-1.263284398447337697e-01,-3.497245161943083880e-01,4.563496123041156649e-02,1.000000007799753288e+00,0.000000000000000000e+00 +7.692593723505436287e+01,4.702433488782577342e+02,4.725370315287845679e-01,6.684162872967036151e+00,-1.261617731780670937e-01,-3.482285596138944839e-01,4.563496123041156649e-02,1.000000007550105208e+00,0.000000000000000000e+00 +7.692743330871235230e+01,4.702532693997968067e+02,4.712787579525319348e-01,6.683641897392035958e+00,-1.259951065114004176e-01,-3.467324859446030971e-01,4.563496123041156649e-02,1.000000007546632874e+00,0.000000000000000000e+00 +7.692892949898609345e+01,4.702631901309103455e+02,4.700221378140042039e-01,6.683123119618977981e+00,-1.258284398447337415e-01,-3.452362956595777521e-01,4.563496123041156649e-02,1.000000007928565582e+00,0.000000000000000000e+00 +7.693042580540166853e+01,4.702731110713227736e+02,4.687671711481074532e-01,6.682606540334891321e+00,-1.256617731780670655e-01,-3.437399892321337247e-01,4.563496123041156649e-02,1.000000007243282862e+00,0.000000000000000000e+00 +7.693192222748481868e+01,4.702830322207585709e+02,4.675138579897019087e-01,6.682092160224140542e+00,-1.254951065114003894e-01,-3.422435671381386935e-01,4.563496123041156649e-02,1.000000008395316664e+00,0.000000000000000000e+00 +7.693341876476090135e+01,4.702929535789421038e+02,4.662621983736017772e-01,6.681579979968418570e+00,-1.253284398447337133e-01,-3.407470298494914007e-01,4.563496123041156649e-02,1.000000007144592029e+00,0.000000000000000000e+00 +7.693491541675489032e+01,4.703028751455977385e+02,4.650121923345754138e-01,6.681070000246749352e+00,-1.251617731780670373e-01,-3.392503778448119345e-01,4.563496123041156649e-02,1.000000007969992222e+00,0.000000000000000000e+00 +7.693641218299137563e+01,4.703127969204498982e+02,4.637638399073452100e-01,6.680562221735474537e+00,-1.249951065114003751e-01,-3.377536115963920560e-01,4.563496123041156649e-02,1.000000008206514357e+00,0.000000000000000000e+00 +7.693790906299459209e+01,4.703227189032230058e+02,4.625171411265875943e-01,6.680056645108259694e+00,-1.248284398447337129e-01,-3.362567315808853152e-01,4.563496123041156649e-02,1.000000007167133331e+00,0.000000000000000000e+00 +7.693940605628840501e+01,4.703326410936414277e+02,4.612720960269330872e-01,6.679553271036084539e+00,-1.246617731780670507e-01,-3.347597382763458640e-01,4.563496123041156649e-02,1.000000008121840311e+00,0.000000000000000000e+00 +7.694090316239628180e+01,4.703425634914295870e+02,4.600287046429663018e-01,6.679052100187237606e+00,-1.244951065114003885e-01,-3.332626321563033067e-01,4.563496123041156649e-02,1.000000007993422368e+00,0.000000000000000000e+00 +7.694240038084134881e+01,4.703524860963118499e+02,4.587869670092258878e-01,6.678553133227319805e+00,-1.243284398447337263e-01,-3.317654136992629899e-01,4.563496123041156649e-02,1.000000007662433354e+00,0.000000000000000000e+00 +7.694389771114636289e+01,4.703624089080125259e+02,4.575468831602045316e-01,6.678056370819233756e+00,-1.241617731780670641e-01,-3.302680833827799090e-01,4.563496123041156649e-02,1.000000008003042229e+00,0.000000000000000000e+00 +7.694539515283369724e+01,4.703723319262560381e+02,4.563084531303490121e-01,6.677561813623182019e+00,-1.239951065114004020e-01,-3.287706416834664802e-01,4.563496123041156649e-02,1.000000007902533294e+00,0.000000000000000000e+00 +7.694689270542536974e+01,4.703822551507667526e+02,4.550716769540602002e-01,6.677069462296665314e+00,-1.238284398447337398e-01,-3.272730890799662173e-01,4.563496123041156649e-02,1.000000007827303472e+00,0.000000000000000000e+00 +7.694839036844302882e+01,4.703921785812689791e+02,4.538365546656929483e-01,6.676579317494476307e+00,-1.236617731780670776e-01,-3.257754260505878463e-01,4.563496123041156649e-02,1.000000007841287175e+00,0.000000000000000000e+00 +7.694988814140796762e+01,4.704021022174870836e+02,4.526030862995562010e-01,6.676091379868696940e+00,-1.234951065114004154e-01,-3.242776530739064911e-01,4.563496123041156649e-02,1.000000008002680296e+00,0.000000000000000000e+00 +7.695138602384110982e+01,4.704120260591454326e+02,4.513712718899129950e-01,6.675605650068694885e+00,-1.233284398447337532e-01,-3.227797706287708346e-01,4.563496123041156649e-02,1.000000008363605364e+00,0.000000000000000000e+00 +7.695288401526303801e+01,4.704219501059683353e+02,4.501411114709804040e-01,6.675122128741119987e+00,-1.231617731780670910e-01,-3.212817791943107792e-01,4.563496123041156649e-02,1.000000007387150891e+00,0.000000000000000000e+00 +7.695438211519396532e+01,4.704318743576801580e+02,4.489126050769295384e-01,6.674640816529900711e+00,-1.229951065114004288e-01,-3.197836792523165439e-01,4.563496123041156649e-02,1.000000008279779529e+00,0.000000000000000000e+00 +7.695588032315374960e+01,4.704417988140052103e+02,4.476857527418856009e-01,6.674161714076237040e+00,-1.228284398447337666e-01,-3.182854712801313490e-01,4.563496123041156649e-02,1.000000008305232280e+00,0.000000000000000000e+00 +7.695737863866187922e+01,4.704517234746678014e+02,4.464605544999277753e-01,6.673684822018604024e+00,-1.226617731780671045e-01,-3.167871557595526855e-01,4.563496123041156649e-02,1.000000007492302556e+00,0.000000000000000000e+00 +7.695887706123751570e+01,4.704616483393922977e+02,4.452370103850893934e-01,6.673210140992742012e+00,-1.224951065114004423e-01,-3.152887331726888509e-01,4.563496123041156649e-02,1.000000008631989790e+00,0.000000000000000000e+00 +7.696037559039945108e+01,4.704715734079029517e+02,4.440151204313577682e-01,6.672737671631653100e+00,-1.223284398447337801e-01,-3.137902039978182622e-01,4.563496123041156649e-02,1.000000007784876299e+00,0.000000000000000000e+00 +7.696187422566613634e+01,4.704814986799240728e+02,4.427948846726742493e-01,6.672267414565603794e+00,-1.221617731780671179e-01,-3.122915687194732781e-01,4.563496123041156649e-02,1.000000007729713536e+00,0.000000000000000000e+00 +7.696337296655565297e+01,4.704914241551799705e+02,4.415763031429343344e-01,6.671799370422112574e+00,-1.219951065114004557e-01,-3.107928278183716420e-01,4.563496123041156649e-02,1.000000008469964508e+00,0.000000000000000000e+00 +7.696487181258575561e+01,4.705013498333949542e+02,4.403593758759874466e-01,6.671333539825952563e+00,-1.218284398447337935e-01,-3.092939817755736009e-01,4.563496123041156649e-02,1.000000008421734421e+00,0.000000000000000000e+00 +7.696637076327384364e+01,4.705112757142932765e+02,4.391441029056372125e-01,6.670869923399147972e+00,-1.216617731780671313e-01,-3.077950310748598373e-01,4.563496123041156649e-02,1.000000007577157346e+00,0.000000000000000000e+00 +7.696786981813697537e+01,4.705212017975992467e+02,4.379304842656411290e-01,6.670408521760966991e+00,-1.214951065114004691e-01,-3.062959762003681363e-01,4.563496123041156649e-02,1.000000008293060016e+00,0.000000000000000000e+00 +7.696936897669186806e+01,4.705311280830371174e+02,4.367185199897108960e-01,6.669949335527918244e+00,-1.213284398447338069e-01,-3.047968176330468904e-01,4.563496123041156649e-02,1.000000008572213606e+00,0.000000000000000000e+00 +7.697086823845488368e+01,4.705410545703311413e+02,4.355082101115121396e-01,6.669492365313752558e+00,-1.211617731780671448e-01,-3.032975558571805452e-01,4.563496123041156649e-02,1.000000007597933616e+00,0.000000000000000000e+00 +7.697236760294205737e+01,4.705509812592056278e+02,4.342995546646645777e-01,6.669037611729454973e+00,-1.209951065114004826e-01,-3.017981913586189058e-01,4.563496123041156649e-02,1.000000008497554882e+00,0.000000000000000000e+00 +7.697386706966906900e+01,4.705609081493848294e+02,4.330925536827419653e-01,6.668585075383239413e+00,-1.208284398447338204e-01,-3.002987246188620896e-01,4.563496123041156649e-02,1.000000008071270763e+00,0.000000000000000000e+00 +7.697536663815128577e+01,4.705708352405929986e+02,4.318872071992721495e-01,6.668134756880552239e+00,-1.206617731780671582e-01,-2.987991561245457728e-01,4.563496123041156649e-02,1.000000008248528749e+00,0.000000000000000000e+00 +7.697686630790371964e+01,4.705807625325543313e+02,4.306835152477369588e-01,6.667686656824061586e+00,-1.204951065114004960e-01,-2.972994863597488435e-01,4.563496123041156649e-02,1.000000008187367229e+00,0.000000000000000000e+00 +7.697836607844104151e+01,4.705906900249931368e+02,4.294814778615722584e-01,6.667240775813658260e+00,-1.203284398447338338e-01,-2.957997158101476343e-01,4.563496123041156649e-02,1.000000008619356340e+00,0.000000000000000000e+00 +7.697986594927760962e+01,4.706006177176336109e+02,4.282810950741680056e-01,6.666797114446450401e+00,-1.201617731780671716e-01,-2.942998449606546996e-01,4.563496123041156649e-02,1.000000007900706533e+00,0.000000000000000000e+00 +7.698136591992742694e+01,4.706105456102000062e+02,4.270823669188681393e-01,6.666355673316761710e+00,-1.199951065114005094e-01,-2.927998742989800229e-01,4.563496123041156649e-02,1.000000008329300805e+00,0.000000000000000000e+00 +7.698286598990419805e+01,4.706204737024165183e+02,4.258852934289706904e-01,6.665916453016124343e+00,-1.198284398447338472e-01,-2.912998043097174139e-01,4.563496123041156649e-02,1.000000008248850714e+00,0.000000000000000000e+00 +7.698436615872127220e+01,4.706304019940073999e+02,4.246898746377276712e-01,6.665479454133280690e+00,-1.196617731780671851e-01,-2.897996354802740426e-01,4.563496123041156649e-02,1.000000008365208970e+00,0.000000000000000000e+00 +7.698586642589167184e+01,4.706403304846968467e+02,4.234961105783451862e-01,6.665044677254176264e+00,-1.194951065114005229e-01,-2.882993682973257754e-01,4.563496123041156649e-02,1.000000008193813628e+00,0.000000000000000000e+00 +7.698736679092810675e+01,4.706502591742090544e+02,4.223040012839833213e-01,6.664612122961957930e+00,-1.193284398447338607e-01,-2.867990032486014695e-01,4.563496123041156649e-02,1.000000008427489151e+00,0.000000000000000000e+00 +7.698886725334294567e+01,4.706601880622682756e+02,4.211135467877562544e-01,6.664181791836969460e+00,-1.191617731780671985e-01,-2.852985408211150542e-01,4.563496123041156649e-02,1.000000008174375399e+00,0.000000000000000000e+00 +7.699036781264825891e+01,4.706701171485986492e+02,4.199247471227321449e-01,6.663753684456749760e+00,-1.189951065114005363e-01,-2.837979815035416853e-01,4.563496123041156649e-02,1.000000008508822535e+00,0.000000000000000000e+00 +7.699186846835576148e+01,4.706800464329244278e+02,4.187376023219332444e-01,6.663327801396027539e+00,-1.188284398447338741e-01,-2.822973257832659955e-01,4.563496123041156649e-02,1.000000008526150008e+00,0.000000000000000000e+00 +7.699336921997688421e+01,4.706899759149697502e+02,4.175521124183357302e-01,6.662904143226720421e+00,-1.186617731780672119e-01,-2.807965741493502199e-01,4.563496123041156649e-02,1.000000008104434235e+00,0.000000000000000000e+00 +7.699487006702271685e+01,4.706999055944588122e+02,4.163682774448699275e-01,6.662482710517929618e+00,-1.184951065114005497e-01,-2.792957270913582479e-01,4.563496123041156649e-02,1.000000008298137955e+00,0.000000000000000000e+00 +7.699637100900403652e+01,4.707098354711158095e+02,4.151860974344201427e-01,6.662063503835936373e+00,-1.183284398447338875e-01,-2.777947850975884814e-01,4.563496123041156649e-02,1.000000008577668353e+00,0.000000000000000000e+00 +7.699787204543129349e+01,4.707197655446648810e+02,4.140055724198246634e-01,6.661646523744201076e+00,-1.181617731780672254e-01,-2.762937486574496559e-01,4.563496123041156649e-02,1.000000008407202046e+00,0.000000000000000000e+00 +7.699937317581465379e+01,4.707296958148302224e+02,4.128267024338759250e-01,6.661231770803358820e+00,-1.179951065114005632e-01,-2.747926182614688906e-01,4.563496123041156649e-02,1.000000008427215814e+00,0.000000000000000000e+00 +7.700087439966394243e+01,4.707396262813359726e+02,4.116494875093202332e-01,6.660819245571214964e+00,-1.178284398447339010e-01,-2.732913943995244899e-01,4.563496123041156649e-02,1.000000008482722746e+00,0.000000000000000000e+00 +7.700237571648870016e+01,4.707495569439062706e+02,4.104739276788580415e-01,6.660408948602743351e+00,-1.176617731780672388e-01,-2.717900775620384346e-01,4.563496123041156649e-02,1.000000008412702091e+00,0.000000000000000000e+00 +7.700387712579812671e+01,4.707594878022652551e+02,4.093000229751437846e-01,6.660000880450082761e+00,-1.174951065114005766e-01,-2.702886682399839868e-01,4.563496123041156649e-02,1.000000008443240107e+00,0.000000000000000000e+00 +7.700537862710112336e+01,4.707694188561371220e+02,4.081277734307859340e-01,6.659595041662533355e+00,-1.173284398447339144e-01,-2.687871669243029893e-01,4.563496123041156649e-02,1.000000008399877460e+00,0.000000000000000000e+00 +7.700688021990630716e+01,4.707793501052459533e+02,4.069571790783469978e-01,6.659191432786554010e+00,-1.171617731780672522e-01,-2.672855741065057189e-01,4.563496123041156649e-02,1.000000008495547377e+00,0.000000000000000000e+00 +7.700838190372196834e+01,4.707892815493159446e+02,4.057882399503434656e-01,6.658790054365758770e+00,-1.169951065114005900e-01,-2.657838902780876866e-01,4.563496123041156649e-02,1.000000008148653308e+00,0.000000000000000000e+00 +7.700988367805609869e+01,4.707992131880711781e+02,4.046209560792458637e-01,6.658390906940914178e+00,-1.168284398447339278e-01,-2.642821159317212398e-01,4.563496123041156649e-02,1.000000008740189239e+00,0.000000000000000000e+00 +7.701138554241639156e+01,4.708091450212357927e+02,4.034553274974787551e-01,6.657993991049934834e+00,-1.166617731780672657e-01,-2.627802515583066989e-01,4.563496123041156649e-02,1.000000008887461878e+00,0.000000000000000000e+00 +7.701288749631022768e+01,4.708190770485338703e+02,4.022913542374206841e-01,6.657599307227883401e+00,-1.164951065114006035e-01,-2.612782976511212607e-01,4.563496123041156649e-02,1.000000007989616524e+00,0.000000000000000000e+00 +7.701438953924470354e+01,4.708290092696895499e+02,4.011290363314042318e-01,6.657206856006964379e+00,-1.163284398447339413e-01,-2.597762547046436055e-01,4.563496123041156649e-02,1.000000008981465793e+00,0.000000000000000000e+00 +7.701589167072661724e+01,4.708389416844269135e+02,3.999683738117160714e-01,6.656816637916519674e+00,-1.161617731780672791e-01,-2.582741232092415351e-01,4.563496123041156649e-02,1.000000008099084292e+00,0.000000000000000000e+00 +7.701739389026245419e+01,4.708488742924701000e+02,3.988093667105968021e-01,6.656428653483032143e+00,-1.159951065114006169e-01,-2.567719036612323702e-01,4.563496123041156649e-02,1.000000008657177863e+00,0.000000000000000000e+00 +7.701889619735842984e+01,4.708588070935431915e+02,3.976520150602410042e-01,6.656042903230114050e+00,-1.158284398447339547e-01,-2.552695965522484567e-01,4.563496123041156649e-02,1.000000008846596344e+00,0.000000000000000000e+00 +7.702039859152046120e+01,4.708687400873702700e+02,3.964963188927974058e-01,6.655659387678511507e+00,-1.156617731780672925e-01,-2.537672023769325103e-01,4.563496123041156649e-02,1.000000008032843724e+00,0.000000000000000000e+00 +7.702190107225415261e+01,4.708786732736754175e+02,3.953422782403686608e-01,6.655278107346097372e+00,-1.154951065114006303e-01,-2.522647216311718066e-01,4.563496123041156649e-02,1.000000009115284749e+00,0.000000000000000000e+00 +7.702340363906483844e+01,4.708886066521827161e+02,3.941898931350114599e-01,6.654899062747866800e+00,-1.153284398447339681e-01,-2.507621548067869854e-01,4.563496123041156649e-02,1.000000008298195020e+00,0.000000000000000000e+00 +7.702490629145756884e+01,4.708985402226161909e+02,3.930391636087364748e-01,6.654522254395940806e+00,-1.151617731780673060e-01,-2.492595024015898941e-01,4.563496123041156649e-02,1.000000008466964907e+00,0.000000000000000000e+00 +7.702640902893709551e+01,4.709084739846999810e+02,3.918900896935084144e-01,6.654147682799554708e+00,-1.149951065114006438e-01,-2.477567649093433688e-01,4.563496123041156649e-02,1.000000008959473830e+00,0.000000000000000000e+00 +7.702791185100788596e+01,4.709184079381581114e+02,3.907426714212460239e-01,6.653775348465061690e+00,-1.148284398447339816e-01,-2.462539428250899720e-01,4.563496123041156649e-02,1.000000008320567124e+00,0.000000000000000000e+00 +7.702941475717412345e+01,4.709283420827146642e+02,3.895969088238220301e-01,6.653405251895928352e+00,-1.146617731780673194e-01,-2.447510366463425124e-01,4.563496123041156649e-02,1.000000009020569847e+00,0.000000000000000000e+00 +7.703091774693972127e+01,4.709382764180936647e+02,3.884528019330631410e-01,6.653037393592728499e+00,-1.144951065114006572e-01,-2.432480468671830154e-01,4.563496123041156649e-02,1.000000008018068431e+00,0.000000000000000000e+00 +7.703242081980830847e+01,4.709482109440191948e+02,3.873103507807501567e-01,6.652671774053145803e+00,-1.143284398447339950e-01,-2.417449739865448755e-01,4.563496123041156649e-02,1.000000008948489727e+00,0.000000000000000000e+00 +7.703392397528322988e+01,4.709581456602152230e+02,3.861695553986178031e-01,6.652308393771964035e+00,-1.141617731780673328e-01,-2.402418184981759686e-01,4.563496123041156649e-02,1.000000008756827263e+00,0.000000000000000000e+00 +7.703542721286754613e+01,4.709680805664058312e+02,3.850304158183548431e-01,6.651947253241072389e+00,-1.139951065114006706e-01,-2.387385809006931925e-01,4.563496123041156649e-02,1.000000008705826060e+00,0.000000000000000000e+00 +7.703693053206406205e+01,4.709780156623151015e+02,3.838929320716040205e-01,6.651588352949455718e+00,-1.138284398447340084e-01,-2.372352616910909373e-01,4.563496123041156649e-02,1.000000008478529656e+00,0.000000000000000000e+00 +7.703843393237529824e+01,4.709879509476670023e+02,3.827571041899621163e-01,6.651231693383194532e+00,-1.136617731780673463e-01,-2.357318613671140206e-01,4.563496123041156649e-02,1.000000008537174523e+00,0.000000000000000000e+00 +7.703993741330349110e+01,4.709978864221855588e+02,3.816229322049799477e-01,6.650877275025461444e+00,-1.134951065114006841e-01,-2.342283804260847091e-01,4.563496123041156649e-02,1.000000008943799257e+00,0.000000000000000000e+00 +7.704144097435062122e+01,4.710078220855947393e+02,3.804904161481622582e-01,6.650525098356519393e+00,-1.133284398447340219e-01,-2.327248193655027109e-01,4.563496123041156649e-02,1.000000008574978505e+00,0.000000000000000000e+00 +7.704294461501839919e+01,4.710177579376186259e+02,3.793595560509678277e-01,6.650175163853718985e+00,-1.131617731780673597e-01,-2.312211786848260842e-01,4.563496123041156649e-02,1.000000008657439876e+00,0.000000000000000000e+00 +7.704444833480826560e+01,4.710276939779811869e+02,3.782303519448094176e-01,6.649827471991493155e+00,-1.129951065114006975e-01,-2.297174588819360375e-01,4.563496123041156649e-02,1.000000008839409427e+00,0.000000000000000000e+00 +7.704595213322140523e+01,4.710376302064064475e+02,3.771028038610538258e-01,6.649482023241357176e+00,-1.128284398447340353e-01,-2.282136604555086989e-01,4.563496123041156649e-02,1.000000008762076398e+00,0.000000000000000000e+00 +7.704745600975871866e+01,4.710475666226183762e+02,3.759769118310218317e-01,6.649138818071905099e+00,-1.126617731780673731e-01,-2.267097839050242203e-01,4.563496123041156649e-02,1.000000008452481381e+00,0.000000000000000000e+00 +7.704895996392085067e+01,4.710575032263409980e+02,3.748526758859881958e-01,6.648797856948806206e+00,-1.124951065114007109e-01,-2.252058297301849921e-01,4.563496123041156649e-02,1.000000009108415355e+00,0.000000000000000000e+00 +7.705046399520819023e+01,4.710674400172982246e+02,3.737300960571817154e-01,6.648459140334802342e+00,-1.123284398447340487e-01,-2.237017984291531925e-01,4.563496123041156649e-02,1.000000008386710215e+00,0.000000000000000000e+00 +7.705196810312085631e+01,4.710773769952140810e+02,3.726091723757851693e-01,6.648122668689707915e+00,-1.121617731780673866e-01,-2.221976905038748062e-01,4.563496123041156649e-02,1.000000009041245974e+00,0.000000000000000000e+00 +7.705347228715872632e+01,4.710873141598125358e+02,3.714899048729353170e-01,6.647788442470401904e+00,-1.119951065114007244e-01,-2.206935064524118417e-01,4.563496123041156649e-02,1.000000008322502465e+00,0.000000000000000000e+00 +7.705497654682140762e+01,4.710972515108175571e+02,3.703722935797229554e-01,6.647456462130831412e+00,-1.118284398447340622e-01,-2.191892467772184327e-01,4.563496123041156649e-02,1.000000008969474719e+00,0.000000000000000000e+00 +7.705648088160825182e+01,4.711071890479531135e+02,3.692563385271928067e-01,6.647126728122002781e+00,-1.116617731780674000e-01,-2.176849119768834995e-01,4.563496123041156649e-02,1.000000009003651158e+00,0.000000000000000000e+00 +7.705798529101836891e+01,4.711171267709431731e+02,3.681420397463436300e-01,6.646799240891985150e+00,-1.114951065114007378e-01,-2.161805025532253788e-01,4.563496123041156649e-02,1.000000008402240903e+00,0.000000000000000000e+00 +7.705948977455059890e+01,4.711270646795116477e+02,3.670293972681281658e-01,6.646474000885903344e+00,-1.113284398447340756e-01,-2.146760190083484565e-01,4.563496123041156649e-02,1.000000009096929210e+00,0.000000000000000000e+00 +7.706099433170355439e+01,4.711370027733825054e+02,3.659184111234531356e-01,6.646151008545935213e+00,-1.111617731780674134e-01,-2.131714618417009377e-01,4.563496123041156649e-02,1.000000008695945519e+00,0.000000000000000000e+00 +7.706249896197559224e+01,4.711469410522797148e+02,3.648090813431792978e-01,6.645830264311313407e+00,-1.109951065114007512e-01,-2.116668315565778669e-01,4.563496123041156649e-02,1.000000008724058365e+00,0.000000000000000000e+00 +7.706400366486481346e+01,4.711568795159271872e+02,3.637014079581213366e-01,6.645511768618317383e+00,-1.108284398447340890e-01,-2.101621286542269817e-01,4.563496123041156649e-02,1.000000009129240697e+00,0.000000000000000000e+00 +7.706550843986907751e+01,4.711668181640488342e+02,3.625953909990479729e-01,6.645195521900274294e+00,-1.106617731780674269e-01,-2.086573536362193726e-01,4.563496123041156649e-02,1.000000008283362884e+00,0.000000000000000000e+00 +7.706701328648601645e+01,4.711767569963686242e+02,3.614910304966819088e-01,6.644881524587556321e+00,-1.104951065114007647e-01,-2.071525070068196694e-01,4.563496123041156649e-02,1.000000009257731470e+00,0.000000000000000000e+00 +7.706851820421299237e+01,4.711866960126104686e+02,3.603883264816997722e-01,6.644569777107574460e+00,-1.103284398447341025e-01,-2.056475892659126170e-01,4.563496123041156649e-02,1.000000008448855615e+00,0.000000000000000000e+00 +7.707002319254713996e+01,4.711966352124982791e+02,3.592872789847322834e-01,6.644260279884782960e+00,-1.101617731780674403e-01,-2.041426009190460689e-01,4.563496123041156649e-02,1.000000009305153981e+00,0.000000000000000000e+00 +7.707152825098536653e+01,4.712065745957559670e+02,3.581878880363640882e-01,6.643953033340668668e+00,-1.099951065114007781e-01,-2.026375424668168390e-01,4.563496123041156649e-02,1.000000008601354962e+00,0.000000000000000000e+00 +7.707303337902432361e+01,4.712165141621073872e+02,3.570901536671338139e-01,6.643648037893756353e+00,-1.098284398447341159e-01,-2.011324144149128634e-01,4.563496123041156649e-02,1.000000008594429834e+00,0.000000000000000000e+00 +7.707453857616043535e+01,4.712264539112765078e+02,3.559940759075340688e-01,6.643345293959598941e+00,-1.096617731780674537e-01,-1.996272172658606070e-01,4.563496123041156649e-02,1.000000009181225780e+00,0.000000000000000000e+00 +7.707604384188989854e+01,4.712363938429871837e+02,3.548996547880114982e-01,6.643044801950780176e+00,-1.094951065114007915e-01,-1.981219515225754180e-01,4.563496123041156649e-02,1.000000008683401553e+00,0.000000000000000000e+00 +7.707754917570866837e+01,4.712463339569633263e+02,3.538068903389666731e-01,6.642746562276911959e+00,-1.093284398447341293e-01,-1.966166176907311047e-01,4.563496123041156649e-02,1.000000008943266128e+00,0.000000000000000000e+00 +7.707905457711247266e+01,4.712562742529288471e+02,3.527157825907541455e-01,6.642450575344628128e+00,-1.091617731780674672e-01,-1.951112162734587596e-01,4.563496123041156649e-02,1.000000009051792205e+00,0.000000000000000000e+00 +7.708056004559681185e+01,4.712662147306076008e+02,3.516263315736824491e-01,6.642156841557586233e+00,-1.089951065114008050e-01,-1.936057477754866696e-01,4.563496123041156649e-02,1.000000008484771108e+00,0.000000000000000000e+00 +7.708206558065695901e+01,4.712761553897234421e+02,3.505385373180141539e-01,6.641865361316463101e+00,-1.088284398447341428e-01,-1.921002127025595585e-01,4.563496123041156649e-02,1.000000009061668971e+00,0.000000000000000000e+00 +7.708357118178795986e+01,4.712860962300002825e+02,3.494523998539657561e-01,6.641576135018951277e+00,-1.086617731780674806e-01,-1.905946115579084388e-01,4.563496123041156649e-02,1.000000009067740336e+00,0.000000000000000000e+00 +7.708507684848464692e+01,4.712960372511619198e+02,3.483679192117077328e-01,6.641289163059760803e+00,-1.084951065114008184e-01,-1.890889448475698287e-01,4.563496123041156649e-02,1.000000008740411950e+00,0.000000000000000000e+00 +7.708658258024161114e+01,4.713059784529322656e+02,3.472850954213645425e-01,6.641004445830613001e+00,-1.083284398447341562e-01,-1.875832130774451045e-01,4.563496123041156649e-02,1.000000009092752773e+00,0.000000000000000000e+00 +7.708808837655323032e+01,4.713159198350351744e+02,3.462039285130146249e-01,6.640721983720238697e+00,-1.081617731780674940e-01,-1.860774167521308253e-01,4.563496123041156649e-02,1.000000008780065786e+00,0.000000000000000000e+00 +7.708959423691366908e+01,4.713258613971945010e+02,3.451244185166904010e-01,6.640441777114378219e+00,-1.079951065114008318e-01,-1.845715563784672830e-01,4.563496123041156649e-02,1.000000008800478124e+00,0.000000000000000000e+00 +7.709110016081687888e+01,4.713358031391341001e+02,3.440465654623782732e-01,6.640163826395776070e+00,-1.078284398447341697e-01,-1.830656324620090758e-01,4.563496123041156649e-02,1.000000008969492038e+00,0.000000000000000000e+00 +7.709260614775656961e+01,4.713457450605777694e+02,3.429703693800185693e-01,6.639888131944180927e+00,-1.076617731780675075e-01,-1.815596455088042127e-01,4.563496123041156649e-02,1.000000009095106224e+00,0.000000000000000000e+00 +7.709411219722626640e+01,4.713556871612493637e+02,3.418958302995056542e-01,6.639614694136342976e+00,-1.074951065114008453e-01,-1.800535960254038004e-01,4.563496123041156649e-02,1.000000008586484190e+00,0.000000000000000000e+00 +7.709561830871928123e+01,4.713656294408727376e+02,3.408229482506878183e-01,6.639343513346011250e+00,-1.073284398447341831e-01,-1.785474845194611193e-01,4.563496123041156649e-02,1.000000009194313533e+00,0.000000000000000000e+00 +7.709712448172868449e+01,4.713755718991716890e+02,3.397517232633673334e-01,6.639074589943930071e+00,-1.071617731780675209e-01,-1.770413114962033629e-01,4.563496123041156649e-02,1.000000009137989032e+00,0.000000000000000000e+00 +7.709863071574737603e+01,4.713855145358700725e+02,3.386821553673004526e-01,6.638807924297840835e+00,-1.069951065114008587e-01,-1.755350774637484956e-01,4.563496123041156649e-02,1.000000008587238254e+00,0.000000000000000000e+00 +7.710013701026802835e+01,4.713954573506916859e+02,3.376142445921974100e-01,6.638543516772475783e+00,-1.068284398447341965e-01,-1.740287829301662426e-01,4.563496123041156649e-02,1.000000009269738088e+00,0.000000000000000000e+00 +7.710164336478310076e+01,4.714054003433603270e+02,3.365479909677224213e-01,6.638281367729556237e+00,-1.066617731780675343e-01,-1.725224284011295517e-01,4.563496123041156649e-02,1.000000008599757351e+00,0.000000000000000000e+00 +7.710314977878486786e+01,4.714153435135997938e+02,3.354833945234935721e-01,6.638021477527794367e+00,-1.064951065114008721e-01,-1.710160143864102866e-01,4.563496123041156649e-02,1.000000009463883899e+00,0.000000000000000000e+00 +7.710465625176539106e+01,4.714252868611338840e+02,3.344204552890830406e-01,6.637763846522885203e+00,-1.063284398447342100e-01,-1.695095413916342664e-01,4.563496123041156649e-02,1.000000008478988400e+00,0.000000000000000000e+00 +7.710616278321653283e+01,4.714352303856863955e+02,3.333591732940168750e-01,6.637508475067511071e+00,-1.061617731780675478e-01,-1.680030099277244338e-01,4.563496123041156649e-02,1.000000009298672277e+00,0.000000000000000000e+00 +7.710766937262994247e+01,4.714451740869811829e+02,3.322995485677751604e-01,6.637255363511331829e+00,-1.059951065114008856e-01,-1.664964205002985032e-01,4.563496123041156649e-02,1.000000008916216432e+00,0.000000000000000000e+00 +7.710917601949711297e+01,4.714551179647419872e+02,3.312415811397919074e-01,6.637004512200991080e+00,-1.058284398447342234e-01,-1.649897736197011855e-01,4.563496123041156649e-02,1.000000009013149782e+00,0.000000000000000000e+00 +7.711068272330929574e+01,4.714650620186925494e+02,3.301852710394551083e-01,6.636755921480107290e+00,-1.056617731780675612e-01,-1.634830697939393951e-01,4.563496123041156649e-02,1.000000008915538086e+00,0.000000000000000000e+00 +7.711218948355757163e+01,4.714750062485566673e+02,3.291306182961067361e-01,6.636509591689275567e+00,-1.054951065114008990e-01,-1.619763095322293012e-01,4.563496123041156649e-02,1.000000009115521227e+00,0.000000000000000000e+00 +7.711369629973282258e+01,4.714849506540581388e+02,3.280776229390426346e-01,6.636265523166064106e+00,-1.053284398447342368e-01,-1.604694933432377346e-01,4.563496123041156649e-02,1.000000008923992434e+00,0.000000000000000000e+00 +7.711520317132574576e+01,4.714948952349207616e+02,3.270262849975127395e-01,6.636023716245013304e+00,-1.051617731780675746e-01,-1.589626217368603767e-01,4.563496123041156649e-02,1.000000008817795605e+00,0.000000000000000000e+00 +7.711671009782685360e+01,4.715048399908682200e+02,3.259766045007208568e-01,6.635784171257632202e+00,-1.049951065114009124e-01,-1.574556952224632211e-01,4.563496123041156649e-02,1.000000009265841205e+00,0.000000000000000000e+00 +7.711821707872645959e+01,4.715147849216243117e+02,3.249285814778247738e-01,6.635546888532397602e+00,-1.048284398447342503e-01,-1.559487143088927330e-01,4.563496123041156649e-02,1.000000009164978554e+00,0.000000000000000000e+00 +7.711972411351469248e+01,4.715247300269127777e+02,3.238822159579362037e-01,6.635311868394753176e+00,-1.046617731780675881e-01,-1.544416795068432047e-01,4.563496123041156649e-02,1.000000008968921605e+00,0.000000000000000000e+00 +7.712123120168151047e+01,4.715346753064573591e+02,3.228375079701208961e-01,6.635079111167105026e+00,-1.044951065114009259e-01,-1.529345913265089674e-01,4.563496123041156649e-02,1.000000008732351731e+00,0.000000000000000000e+00 +7.712273834271667283e+01,4.715446207599817967e+02,3.217944575433985266e-01,6.634848617168820795e+00,-1.043284398447342637e-01,-1.514274502781839948e-01,4.563496123041156649e-02,1.000000009284324864e+00,0.000000000000000000e+00 +7.712424553610976830e+01,4.715545663872098885e+02,3.207530647067426965e-01,6.634620386716227891e+00,-1.041617731780676015e-01,-1.499202568710930605e-01,4.563496123041156649e-02,1.000000009100039167e+00,0.000000000000000000e+00 +7.712575278135020085e+01,4.715645121878653185e+02,3.197133294890809885e-01,6.634394420122613489e+00,-1.039951065114009393e-01,-1.484130116169377067e-01,4.563496123041156649e-02,1.000000008993161771e+00,0.000000000000000000e+00 +7.712726007792721816e+01,4.715744581616717710e+02,3.186752519192949662e-01,6.634170717698219200e+00,-1.038284398447342771e-01,-1.469057150263700928e-01,4.563496123041156649e-02,1.000000008987263600e+00,0.000000000000000000e+00 +7.712876742532985475e+01,4.715844043083530437e+02,3.176388320262200637e-01,6.633949279750241068e+00,-1.036617731780676149e-01,-1.453983676101820721e-01,4.563496123041156649e-02,1.000000009098430453e+00,0.000000000000000000e+00 +7.713027482304700300e+01,4.715943506276328208e+02,3.166040698386457519e-01,6.633730106582827801e+00,-1.034951065114009527e-01,-1.438909698793147673e-01,4.563496123041156649e-02,1.000000008943925378e+00,0.000000000000000000e+00 +7.713178227056737057e+01,4.716042971192347864e+02,3.155709653853154273e-01,6.633513198497078989e+00,-1.033284398447342906e-01,-1.423835223454580634e-01,4.563496123041156649e-02,1.000000009305813231e+00,0.000000000000000000e+00 +7.713328976737950882e+01,4.716142437828826814e+02,3.145395186949264676e-01,6.633298555791042439e+00,-1.031617731780676284e-01,-1.408760255192930411e-01,4.563496123041156649e-02,1.000000009004305968e+00,0.000000000000000000e+00 +7.713479731297178432e+01,4.716241906183002470e+02,3.135097297961301210e-01,6.633086178759714180e+00,-1.029951065114009662e-01,-1.393684799134476959e-01,4.563496123041156649e-02,1.000000008805746798e+00,0.000000000000000000e+00 +7.713630490683239316e+01,4.716341376252111104e+02,3.124815987175316723e-01,6.632876067695034017e+00,-1.028284398447343040e-01,-1.378608860395614810e-01,4.563496123041156649e-02,1.000000009468652973e+00,0.000000000000000000e+00 +7.713781254844938928e+01,4.716440848033390125e+02,3.114551254876902764e-01,6.632668222885885534e+00,-1.026617731780676418e-01,-1.363532444082952433e-01,4.563496123041156649e-02,1.000000009008310320e+00,0.000000000000000000e+00 +7.713932023731064191e+01,4.716540321524076376e+02,3.104303101351190697e-01,6.632462644618096093e+00,-1.024951065114009796e-01,-1.348455555334653055e-01,4.563496123041156649e-02,1.000000008949117003e+00,0.000000000000000000e+00 +7.714082797290386395e+01,4.716639796721406697e+02,3.094071526882851697e-01,6.632259333174430616e+00,-1.023284398447343174e-01,-1.333378199267513109e-01,4.563496123041156649e-02,1.000000009244326193e+00,0.000000000000000000e+00 +7.714233575471661197e+01,4.716739273622617930e+02,3.083856531756096198e-01,6.632058288834593363e+00,-1.021617731780676552e-01,-1.318300381000631627e-01,4.563496123041156649e-02,1.000000009058227946e+00,0.000000000000000000e+00 +7.714384358223628624e+01,4.716838752224946347e+02,3.073658116254674444e-01,6.631859511875226154e+00,-1.019951065114009930e-01,-1.303222105667289354e-01,4.563496123041156649e-02,1.000000009109841104e+00,0.000000000000000000e+00 +7.714535145495013069e+01,4.716938232525629360e+02,3.063476280661875384e-01,6.631663002569904819e+00,-1.018284398447343309e-01,-1.288143378391489735e-01,4.563496123041156649e-02,1.000000008938383589e+00,0.000000000000000000e+00 +7.714685937234523294e+01,4.717037714521903240e+02,3.053311025260527778e-01,6.631468761189139194e+00,-1.016617731780676687e-01,-1.273064204305730807e-01,4.563496123041156649e-02,1.000000009247030475e+00,0.000000000000000000e+00 +7.714836733390852430e+01,4.717137198211004829e+02,3.043162350332999644e-01,6.631276788000370459e+00,-1.014951065114010065e-01,-1.257984588533436754e-01,4.563496123041156649e-02,1.000000009168589665e+00,0.000000000000000000e+00 +7.714987533912677975e+01,4.717236683590170401e+02,3.033030256161198812e-01,6.631087083267971138e+00,-1.013284398447343443e-01,-1.242904536212620648e-01,4.563496123041156649e-02,1.000000008999821333e+00,0.000000000000000000e+00 +7.715138338748663216e+01,4.717336170656636227e+02,3.022914743026572371e-01,6.630899647253241547e+00,-1.011617731780676821e-01,-1.227824052478315719e-01,4.563496123041156649e-02,1.000000009420075608e+00,0.000000000000000000e+00 +7.715289147847457230e+01,4.717435659407639150e+02,3.012815811210106665e-01,6.630714480214408901e+00,-1.009951065114010199e-01,-1.212743142456787770e-01,4.563496123041156649e-02,1.000000008757545134e+00,0.000000000000000000e+00 +7.715439961157694881e+01,4.717535149840416011e+02,3.002733460992327852e-01,6.630531582406627322e+00,-1.008284398447343577e-01,-1.197661811300975293e-01,4.563496123041156649e-02,1.000000009237692611e+00,0.000000000000000000e+00 +7.715590778627993984e+01,4.717634641952202514e+02,2.992667692653300793e-01,6.630350954081972503e+00,-1.006617731780676955e-01,-1.182580064131697334e-01,4.563496123041156649e-02,1.000000009563390746e+00,0.000000000000000000e+00 +7.715741600206960982e+01,4.717734135740235502e+02,2.982618506472630160e-01,6.630172595489445264e+00,-1.004951065114010333e-01,-1.167497906090760734e-01,4.563496123041156649e-02,1.000000008820342678e+00,0.000000000000000000e+00 +7.715892425843186686e+01,4.717833631201750677e+02,2.972585902729460439e-01,6.629996506874967110e+00,-1.003284398447343712e-01,-1.152415342335170872e-01,4.563496123041156649e-02,1.000000008819362129e+00,0.000000000000000000e+00 +7.716043255485247698e+01,4.717933128333984882e+02,2.962569881702474817e-01,6.629822688481376680e+00,-1.001617731780677090e-01,-1.137332377996013028e-01,4.563496123041156649e-02,1.000000009801287115e+00,0.000000000000000000e+00 +7.716194089081707830e+01,4.718032627134173822e+02,2.952570443669896294e-01,6.629651140548432409e+00,-9.999510651140104678e-02,-1.122249018202112619e-01,4.563496123041156649e-02,1.000000008485645742e+00,0.000000000000000000e+00 +7.716344926581118102e+01,4.718132127599553769e+02,2.942587588909487128e-01,6.629481863312811640e+00,-9.982843984473438459e-02,-1.107165268133132041e-01,4.563496123041156649e-02,1.000000009782036292e+00,0.000000000000000000e+00 +7.716495767932013905e+01,4.718231629727360996e+02,2.932621317698548280e-01,6.629314857008101747e+00,-9.966177317806772240e-02,-1.092081132896018242e-01,4.563496123041156649e-02,1.000000008832707232e+00,0.000000000000000000e+00 +7.716646613082919259e+01,4.718331133514831208e+02,2.922671630313921076e-01,6.629150121864809897e+00,-9.949510651140106021e-02,-1.076996617672313500e-01,4.563496123041156649e-02,1.000000009359881092e+00,0.000000000000000000e+00 +7.716797461982343975e+01,4.718430638959200678e+02,2.912738527031985547e-01,6.628987658110350623e+00,-9.932843984473439802e-02,-1.061911727588717436e-01,4.563496123041156649e-02,1.000000008832209186e+00,0.000000000000000000e+00 +7.716948314578785073e+01,4.718530146057705679e+02,2.902822008128661535e-01,6.628827465969052923e+00,-9.916177317806773583e-02,-1.046826467811400735e-01,4.563496123041156649e-02,1.000000009394189204e+00,0.000000000000000000e+00 +7.717099170820726783e+01,4.718629654807581346e+02,2.892922073879407585e-01,6.628669545662153162e+00,-9.899510651140107365e-02,-1.031740843475453390e-01,4.563496123041156649e-02,1.000000009279299107e+00,0.000000000000000000e+00 +7.717250030656643389e+01,4.718729165206063954e+02,2.883038724559221500e-01,6.628513897407798616e+00,-9.882843984473441146e-02,-1.016654859743865713e-01,4.563496123041156649e-02,1.000000009054757166e+00,0.000000000000000000e+00 +7.717400894034993541e+01,4.718828677250389774e+02,2.873171960442641448e-01,6.628360521421042151e+00,-9.866177317806774927e-02,-1.001568521772305820e-01,4.563496123041156649e-02,1.000000009279642610e+00,0.000000000000000000e+00 +7.717551760904224523e+01,4.718928190937793943e+02,2.863321781803743749e-01,6.628209417913842216e+00,-9.849510651140108708e-02,-9.864818347092241257e-02,4.563496123041156649e-02,1.000000009334261142e+00,0.000000000000000000e+00 +7.717702631212772246e+01,4.719027706265512165e+02,2.853488188916144530e-01,6.628060587095062850e+00,-9.832843984473442489e-02,-9.713948037136192759e-02,4.563496123041156649e-02,1.000000008981200006e+00,0.000000000000000000e+00 +7.717853504909061257e+01,4.719127223230780714e+02,2.843671182052999735e-01,6.627914029170471011e+00,-9.816177317806776270e-02,-9.563074339492538822e-02,4.563496123041156649e-02,1.000000009145481483e+00,0.000000000000000000e+00 +7.718004381941503311e+01,4.719226741830834726e+02,2.833870761487003453e-01,6.627769744342734803e+00,-9.799510651140110051e-02,-9.412197305670988445e-02,4.563496123041156649e-02,1.000000009183336758e+00,0.000000000000000000e+00 +7.718155262258498794e+01,4.719326262062909905e+02,2.824086927490389587e-01,6.627627732811424366e+00,-9.782843984473443832e-02,-9.261316987289845704e-02,4.563496123041156649e-02,1.000000009613398744e+00,0.000000000000000000e+00 +7.718306145808438146e+01,4.719425783924241955e+02,2.814319680334931295e-01,6.627487994773009206e+00,-9.766177317806777614e-02,-9.110433435900455734e-02,4.563496123041156649e-02,1.000000008605479884e+00,0.000000000000000000e+00 +7.718457032539699014e+01,4.719525307412066581e+02,2.804569020291940995e-01,6.627350530420858199e+00,-9.749510651140111395e-02,-8.959546703341428331e-02,4.563496123041156649e-02,1.000000009782995747e+00,0.000000000000000000e+00 +7.718607922400649102e+01,4.719624832523618920e+02,2.794834947632270916e-01,6.627215339945234263e+00,-9.732843984473445176e-02,-8.808656840915592146e-02,4.563496123041156649e-02,1.000000008958937148e+00,0.000000000000000000e+00 +7.718758815339644741e+01,4.719724359256134107e+02,2.785117462626311435e-01,6.627082423533301458e+00,-9.716177317806778957e-02,-8.657763900568311854e-02,4.563496123041156649e-02,1.000000009350282548e+00,0.000000000000000000e+00 +7.718909711305032317e+01,4.719823887606847848e+02,2.775416565543992742e-01,6.626951781369114336e+00,-9.699510651140112738e-02,-8.506867933770131951e-02,4.563496123041156649e-02,1.000000009094605735e+00,0.000000000000000000e+00 +7.719060610245146847e+01,4.719923417572995277e+02,2.765732256654784282e-01,6.626823413633624149e+00,-9.682843984473446519e-02,-8.355968992283038799e-02,4.563496123041156649e-02,1.000000009051949856e+00,0.000000000000000000e+00 +7.719211512108314821e+01,4.720022949151812099e+02,2.756064536227694206e-01,6.626697320504673527e+00,-9.666177317806780300e-02,-8.205067127749481048e-02,4.563496123041156649e-02,1.000000009684126168e+00,0.000000000000000000e+00 +7.719362416842849939e+01,4.720122482340532883e+02,2.746413404531271030e-01,6.626573502156997364e+00,-9.649510651140114081e-02,-8.054162391752278660e-02,4.563496123041156649e-02,1.000000008714628130e+00,0.000000000000000000e+00 +7.719513324397058796e+01,4.720222017136393333e+02,2.736778861833601417e-01,6.626451958762222816e+00,-9.632843984473447863e-02,-7.903254836227674440e-02,4.563496123041156649e-02,1.000000009709128834e+00,0.000000000000000000e+00 +7.719664234719238038e+01,4.720321553536628585e+02,2.727160908402311290e-01,6.626332690488863086e+00,-9.616177317806781644e-02,-7.752344512583538017e-02,4.563496123041156649e-02,1.000000009204938811e+00,0.000000000000000000e+00 +7.719815147757672946e+01,4.720421091538473775e+02,2.717559544504566382e-01,6.626215697502324531e+00,-9.599510651140115425e-02,-7.601431472759821728e-02,4.563496123041156649e-02,1.000000008801374518e+00,0.000000000000000000e+00 +7.719966063460640271e+01,4.720520631139163470e+02,2.707974770407071130e-01,6.626100979964897775e+00,-9.582843984473449206e-02,-7.450515768464485711e-02,4.563496123041156649e-02,1.000000009699338888e+00,0.000000000000000000e+00 +7.720116981776406817e+01,4.720620172335933376e+02,2.698406586376069227e-01,6.625988538035760378e+00,-9.566177317806782987e-02,-7.299597451233431900e-02,4.563496123041156649e-02,1.000000009192036465e+00,0.000000000000000000e+00 +7.720267902653232284e+01,4.720719715126018059e+02,2.688854992677343625e-01,6.625878371870978611e+00,-9.549510651140116768e-02,-7.148676573020068536e-02,4.563496123041156649e-02,1.000000009244067956e+00,0.000000000000000000e+00 +7.720418826039366422e+01,4.720819259506652088e+02,2.679319989576215977e-01,6.625770481623500352e+00,-9.532843984473450549e-02,-6.997753185490138139e-02,4.563496123041156649e-02,1.000000009082139929e+00,0.000000000000000000e+00 +7.720569751883050458e+01,4.720918805475071167e+02,2.669801577337548304e-01,6.625664867443158634e+00,-9.516177317806784330e-02,-6.846827340434739895e-02,4.563496123041156649e-02,1.000000009484516283e+00,0.000000000000000000e+00 +7.720720680132517089e+01,4.721018353028509296e+02,2.660299756225740220e-01,6.625561529476668987e+00,-9.499510651140118112e-02,-6.695899089535986559e-02,4.563496123041156649e-02,1.000000009271749368e+00,0.000000000000000000e+00 +7.720871610735991908e+01,4.721117902164201610e+02,2.650814526504731705e-01,6.625460467867630321e+00,-9.482843984473451893e-02,-6.544968484662298802e-02,4.563496123041156649e-02,1.000000008815858266e+00,0.000000000000000000e+00 +7.721022543641689140e+01,4.721217452879383245e+02,2.641345888438000888e-01,6.625361682756521375e+00,-9.466177317806785674e-02,-6.394035577634071821e-02,4.563496123041156649e-02,1.000000009650249710e+00,0.000000000000000000e+00 +7.721173478797818746e+01,4.721317005171288770e+02,2.631893842288565710e-01,6.625265174280700720e+00,-9.449510651140119455e-02,-6.243100420048200427e-02,4.563496123041156649e-02,1.000000009401381007e+00,0.000000000000000000e+00 +7.721324416152580739e+01,4.721416559037152183e+02,2.622458388318982814e-01,6.625170942574409416e+00,-9.432843984473453236e-02,-6.092163063867592904e-02,4.563496123041156649e-02,1.000000009196422068e+00,0.000000000000000000e+00 +7.721475355654168027e+01,4.721516114474208621e+02,2.613039526791348655e-01,6.625078987768764804e+00,-9.416177317806787017e-02,-5.941223560892618799e-02,4.563496123041156649e-02,1.000000009374523380e+00,0.000000000000000000e+00 +7.721626297250766413e+01,4.721615671479692651e+02,2.603637257967297836e-01,6.624989309991762276e+00,-9.399510651140120798e-02,-5.790281962879866712e-02,4.563496123041156649e-02,1.000000009097147480e+00,0.000000000000000000e+00 +7.721777240890553173e+01,4.721715230050838841e+02,2.594251582108004772e-01,6.624901909368275277e+00,-9.382843984473454579e-02,-5.639338321719728625e-02,4.563496123041156649e-02,1.000000009466680773e+00,0.000000000000000000e+00 +7.721928186521701321e+01,4.721814790184881758e+02,2.584882499474182582e-01,6.624816786020052639e+00,-9.366177317806788361e-02,-5.488392689143255232e-02,4.563496123041156649e-02,1.000000008848593414e+00,0.000000000000000000e+00 +7.722079134092373920e+01,4.721914351879055403e+02,2.575530010326083086e-01,6.624733940065720361e+00,-9.349510651140122142e-02,-5.337445117135100614e-02,4.563496123041156649e-02,1.000000009887997976e+00,0.000000000000000000e+00 +7.722230083550729773e+01,4.722013915130594341e+02,2.566194114923498470e-01,6.624653371620777165e+00,-9.332843984473455923e-02,-5.186495657287347461e-02,4.563496123041156649e-02,1.000000008985012512e+00,0.000000000000000000e+00 +7.722381034844919157e+01,4.722113479936733142e+02,2.556874813525758516e-01,6.624575080797599824e+00,-9.316177317806789704e-02,-5.035544361741999680e-02,4.563496123041156649e-02,1.000000009158036551e+00,0.000000000000000000e+00 +7.722531987923086660e+01,4.722213046294705805e+02,2.547572106391732816e-01,6.624499067705434285e+00,-9.299510651140123485e-02,-4.884591282191780987e-02,4.563496123041156649e-02,1.000000009519309563e+00,0.000000000000000000e+00 +7.722682942733371192e+01,4.722312614201746896e+02,2.538285993779830219e-01,6.624425332450401882e+00,-9.282843984473457266e-02,-4.733636470469589075e-02,4.563496123041156649e-02,1.000000009562664216e+00,0.000000000000000000e+00 +7.722833899223905973e+01,4.722412183655090416e+02,2.529016475947998277e-01,6.624353875135496672e+00,-9.266177317806791047e-02,-4.582679978490720313e-02,4.563496123041156649e-02,1.000000008773756610e+00,0.000000000000000000e+00 +7.722984857342818543e+01,4.722511754651970932e+02,2.519763553153723246e-01,6.624284695860583660e+00,-9.249510651140124828e-02,-4.431721858253929308e-02,4.563496123041156649e-02,1.000000009747988639e+00,0.000000000000000000e+00 +7.723135817038229334e+01,4.722611327189622443e+02,2.510527225654030636e-01,6.624217794722397024e+00,-9.232843984473458609e-02,-4.280762161371808039e-02,4.563496123041156649e-02,1.000000009226264419e+00,0.000000000000000000e+00 +7.723286778258254515e+01,4.722710901265278949e+02,2.501307493705485774e-01,6.624153171814545438e+00,-9.216177317806792391e-02,-4.129800939954393624e-02,4.563496123041156649e-02,1.000000009397710388e+00,0.000000000000000000e+00 +7.723437740951003150e+01,4.722810476876174448e+02,2.492104357564191852e-01,6.624090827227504086e+00,-9.199510651140126172e-02,-3.978838245786531919e-02,4.563496123041156649e-02,1.000000008935564288e+00,0.000000000000000000e+00 +7.723588705064582882e+01,4.722910054019542940e+02,2.482917817485791601e-01,6.624030761048619098e+00,-9.182843984473459953e-02,-3.827874130858459345e-02,4.563496123041156649e-02,1.000000009622565189e+00,0.000000000000000000e+00 +7.723739670547092828e+01,4.723009632692618425e+02,2.473747873725466728e-01,6.623972973362104000e+00,-9.166177317806793734e-02,-3.676908646896204919e-02,4.563496123041156649e-02,1.000000009336074802e+00,0.000000000000000000e+00 +7.723890637346629262e+01,4.723109212892634332e+02,2.464594526537937924e-01,6.623917464249043263e+00,-9.149510651140127515e-02,-3.525941845950984754e-02,4.563496123041156649e-02,1.000000009452592709e+00,0.000000000000000000e+00 +7.724041605411282774e+01,4.723208794616825230e+02,2.455457776177464857e-01,6.623864233787386979e+00,-9.132843984473461296e-02,-3.374973779870776847e-02,4.563496123041156649e-02,1.000000009002146584e+00,0.000000000000000000e+00 +7.724192574689139690e+01,4.723308377862425118e+02,2.446337622897846176e-01,6.623813282051953522e+00,-9.116177317806795077e-02,-3.224004500654380906e-02,4.563496123041156649e-02,1.000000009344649055e+00,0.000000000000000000e+00 +7.724343545128283495e+01,4.723407962626667427e+02,2.437234066952419231e-01,6.623764609114426882e+00,-9.099510651140128858e-02,-3.073034060099500905e-02,4.563496123041156649e-02,1.000000009493601461e+00,0.000000000000000000e+00 +7.724494516676793410e+01,4.723507548906785587e+02,2.428147108594060632e-01,6.623718215043359336e+00,-9.082843984473462640e-02,-2.922062510156801796e-02,4.563496123041156649e-02,1.000000009623321029e+00,0.000000000000000000e+00 +7.724645489282742972e+01,4.723607136700013598e+02,2.419076748075186245e-01,6.623674099904168777e+00,-9.066177317806796421e-02,-2.771089902754484205e-02,4.563496123041156649e-02,1.000000009120496358e+00,0.000000000000000000e+00 +7.724796462894202875e+01,4.723706726003585459e+02,2.410022985647750082e-01,6.623632263759138716e+00,-9.049510651140130202e-02,-2.620116289917016200e-02,4.563496123041156649e-02,1.000000009311925897e+00,0.000000000000000000e+00 +7.724947437459242394e+01,4.723806316814734600e+02,2.400985821563245692e-01,6.623592706667416508e+00,-9.032843984473463983e-02,-2.469141723472050021e-02,4.563496123041156649e-02,1.000000009178080296e+00,0.000000000000000000e+00 +7.725098412925923697e+01,4.723905909130694454e+02,2.391965256072705603e-01,6.623555428685016011e+00,-9.016177317806797764e-02,-2.318166255404476364e-02,4.563496123041156649e-02,1.000000009639491205e+00,0.000000000000000000e+00 +7.725249389242308951e+01,4.724005502948698449e+02,2.382961289426700768e-01,6.623520429864814929e+00,-8.999510651140131545e-02,-2.167189937563346325e-02,4.563496123041156649e-02,1.000000009270467949e+00,0.000000000000000000e+00 +7.725400366356456061e+01,4.724105098265980587e+02,2.373973921875341675e-01,6.623487710256556582e+00,-8.982843984473465326e-02,-2.016212822015915618e-02,4.563496123041156649e-02,1.000000009364632181e+00,0.000000000000000000e+00 +7.725551344216421512e+01,4.724204695079773728e+02,2.365003153668277236e-01,6.623457269906846356e+00,-8.966177317806799107e-02,-1.865234960636914449e-02,4.563496123041156649e-02,1.000000009259055522e+00,0.000000000000000000e+00 +7.725702322770256103e+01,4.724304293387311873e+02,2.356048985054695621e-01,6.623429108859154368e+00,-8.949510651140132889e-02,-1.714256405403762062e-02,4.563496123041156649e-02,1.000000009451472716e+00,0.000000000000000000e+00 +7.725853301966012054e+01,4.724403893185827883e+02,2.347111416283323426e-01,6.623403227153813688e+00,-8.932843984473466670e-02,-1.563277208221153930e-02,4.563496123041156649e-02,1.000000009262398182e+00,0.000000000000000000e+00 +7.726004281751735903e+01,4.724503494472555758e+02,2.338190447602426780e-01,6.623379624828021228e+00,-8.916177317806800451e-02,-1.412297421098618333e-02,4.563496123041156649e-02,1.000000009562637793e+00,0.000000000000000000e+00 +7.726155262075474184e+01,4.724603097244728360e+02,2.329286079259810238e-01,6.623358301915835966e+00,-8.899510651140134232e-02,-1.261317095916275610e-02,4.563496123041156649e-02,1.000000009266512224e+00,0.000000000000000000e+00 +7.726306242885272013e+01,4.724702701499578552e+02,2.320398311502817335e-01,6.623339258448180722e+00,-8.882843984473468013e-02,-1.110336284720049409e-02,4.563496123041156649e-02,1.000000009617870944e+00,0.000000000000000000e+00 +7.726457224129170243e+01,4.724802307234340333e+02,2.311527144578330584e-01,6.623322494452839493e+00,-8.866177317806801794e-02,-9.593550393697747314e-03,4.563496123041156649e-02,1.000000009124843769e+00,0.000000000000000000e+00 +7.726608205755209724e+01,4.724901914446246565e+02,2.302672578732771203e-01,6.623308009954460118e+00,-8.849510651140135575e-02,-8.083734119520605624e-03,4.563496123041156649e-02,1.000000009404324208e+00,0.000000000000000000e+00 +7.726759187711431309e+01,4.725001523132530110e+02,2.293834614212099388e-01,6.623295804974550727e+00,-8.832843984473469356e-02,-6.573914543107459325e-03,4.563496123041156649e-02,1.000000009337498774e+00,0.000000000000000000e+00 +7.726910169945873008e+01,4.725101133290424400e+02,2.285013251261814038e-01,6.623285879531483289e+00,-8.816177317806803138e-02,-5.064092184597621983e-03,4.563496123041156649e-02,1.000000009355784814e+00,0.000000000000000000e+00 +7.727061152406571409e+01,4.725200744917162297e+02,2.276208490126953032e-01,6.623278233640490953e+00,-8.799510651140136919e-02,-3.554267563488978845e-03,4.563496123041156649e-02,1.000000009492679531e+00,0.000000000000000000e+00 +7.727212135041563101e+01,4.725300358009976662e+02,2.267420331052093230e-01,6.623272867313668932e+00,-8.782843984473470700e-02,-2.044441199236984256e-03,4.563496123041156649e-02,1.000000009383763766e+00,0.000000000000000000e+00 +7.727363117798884673e+01,4.725399972566100928e+02,2.258648774281350191e-01,6.623269780559974507e+00,-8.766177317806804481e-02,-5.346136118536585309e-04,4.563496123041156649e-02,1.000000009435576320e+00,0.000000000000000000e+00 +7.727514100626571292e+01,4.725499588582767956e+02,2.249893820058378180e-01,6.623268973385226133e+00,-8.749510651140138262e-02,9.752146792582124663e-04,4.563496123041156649e-02,1.000000009267115297e+00,0.000000000000000000e+00 +7.727665083472658125e+01,4.725599206057210040e+02,2.241155468626370162e-01,6.623270445792104333e+00,-8.732843984473472043e-02,2.485043154117816747e-03,4.563496123041156649e-02,1.000000009657958433e+00,0.000000000000000000e+00 +7.727816066285180341e+01,4.725698824986660611e+02,2.232433720228058360e-01,6.623274197780150807e+00,-8.716177317806805824e-02,3.994871293920379887e-03,4.563496123041156649e-02,1.000000009041647431e+00,0.000000000000000000e+00 +7.727967049012173106e+01,4.725798445368352532e+02,2.223728575105713423e-01,6.623280229345770209e+00,-8.699510651140139605e-02,5.504698577496841723e-03,4.563496123041156649e-02,1.000000009739673512e+00,0.000000000000000000e+00 +7.728118031601671589e+01,4.725898067199518096e+02,2.215040033501145256e-01,6.623288540482226594e+00,-8.682843984473473387e-02,7.014524487185779845e-03,4.563496123041156649e-02,1.000000009000118428e+00,0.000000000000000000e+00 +7.728269014001712378e+01,4.725997690477390165e+02,2.206368095655701911e-01,6.623299131179648747e+00,-8.666177317806807168e-02,8.524348501175227355e-03,4.563496123041156649e-02,1.000000009907150655e+00,0.000000000000000000e+00 +7.728419996160330641e+01,4.726097315199201603e+02,2.197712761810270699e-01,6.623312001425023965e+00,-8.649510651140140949e-02,1.003417010231593375e-02,4.563496123041156649e-02,1.000000008912999228e+00,0.000000000000000000e+00 +7.728570978025564386e+01,4.726196941362185271e+02,2.189074032205277354e-01,6.623327151202205165e+00,-8.632843984473474730e-02,1.154398876811009618e-02,4.563496123041156649e-02,1.000000009864525641e+00,0.000000000000000000e+00 +7.728721959545451625e+01,4.726296568963573463e+02,2.180451907080686869e-01,6.623344580491902889e+00,-8.616177317806808511e-02,1.305380398187771900e-02,4.563496123041156649e-02,1.000000009197357986e+00,0.000000000000000000e+00 +7.728872940668031788e+01,4.726396198000598474e+02,2.171846386676002660e-01,6.623364289271694183e+00,-8.599510651140142292e-02,1.456361522156878439e-02,4.563496123041156649e-02,1.000000009572910908e+00,0.000000000000000000e+00 +7.729023921341345726e+01,4.726495828470493166e+02,2.163257471230266848e-01,6.623386277516014609e+00,-8.582843984473476073e-02,1.607342196916483265e-02,4.563496123041156649e-02,1.000000008968730425e+00,0.000000000000000000e+00 +7.729174901513435714e+01,4.726595460370490400e+02,2.154685160982060255e-01,6.623410545196164456e+00,-8.566177317806809854e-02,1.758322370360898904e-02,4.563496123041156649e-02,1.000000010029701514e+00,0.000000000000000000e+00 +7.729325881132345444e+01,4.726695093697821903e+02,2.146129456169502958e-01,6.623437092280304306e+00,-8.549510651140143636e-02,1.909301990785452346e-02,4.563496123041156649e-02,1.000000009158212633e+00,0.000000000000000000e+00 +7.729476860146121453e+01,4.726794728449720537e+02,2.137590357030253185e-01,6.623465918733461244e+00,-8.532843984473477417e-02,2.060281005944171809e-02,4.563496123041156649e-02,1.000000009372234322e+00,0.000000000000000000e+00 +7.729627838502811699e+01,4.726894364623418596e+02,2.129067863801508420e-01,6.623497024517520870e+00,-8.516177317806811198e-02,2.211259364048783968e-02,4.563496123041156649e-02,1.000000009395413336e+00,0.000000000000000000e+00 +7.729778816150465559e+01,4.726994002216148374e+02,2.120561976720004294e-01,6.623530409591234402e+00,-8.499510651140144979e-02,2.362237013120538007e-02,4.563496123041156649e-02,1.000000009501683218e+00,0.000000000000000000e+00 +7.729929793037135255e+01,4.727093641225142164e+02,2.112072696022015417e-01,6.623566073910216012e+00,-8.482843984473478760e-02,2.513213901224445324e-02,4.563496123041156649e-02,1.000000009567043602e+00,0.000000000000000000e+00 +7.730080769110875849e+01,4.727193281647632261e+02,2.103600021943355380e-01,6.623604017426943713e+00,-8.466177317806812541e-02,2.664189976409378838e-02,4.563496123041156649e-02,1.000000009069551998e+00,0.000000000000000000e+00 +7.730231744319745246e+01,4.727292923480850391e+02,2.095143954719376200e-01,6.623644240090759361e+00,-8.449510651140146322e-02,2.815165186648172641e-02,4.563496123041156649e-02,1.000000009816963020e+00,0.000000000000000000e+00 +7.730382718611804194e+01,4.727392566722029414e+02,2.086704494584968594e-01,6.623686741847867765e+00,-8.432843984473480103e-02,2.966139480189526959e-02,4.563496123041156649e-02,1.000000009322457029e+00,0.000000000000000000e+00 +7.730533691935117702e+01,4.727492211368401058e+02,2.078281641774561983e-01,6.623731522641341130e+00,-8.416177317806813885e-02,3.117112804909813809e-02,4.563496123041156649e-02,1.000000009377250976e+00,0.000000000000000000e+00 +7.730684664237750781e+01,4.727591857417197616e+02,2.069875396522124489e-01,6.623778582411113725e+00,-8.399510651140147666e-02,3.268085108959130347e-02,4.563496123041156649e-02,1.000000009426303071e+00,0.000000000000000000e+00 +7.730835635467775546e+01,4.727691504865650813e+02,2.061485759061162937e-01,6.623827921093986326e+00,-8.382843984473481447e-02,3.419056340407252564e-02,4.563496123041156649e-02,1.000000009295950454e+00,0.000000000000000000e+00 +7.730986605573266957e+01,4.727791153710992944e+02,2.053112729624722577e-01,6.623879538623625329e+00,-8.366177317806815228e-02,3.570026447301392902e-02,4.563496123041156649e-02,1.000000009973345261e+00,0.000000000000000000e+00 +7.731137574502301391e+01,4.727890803950456302e+02,2.044756308445387916e-01,6.623933434930562747e+00,-8.349510651140149009e-02,3.720995377841626595e-02,4.563496123041156649e-02,1.000000008930104878e+00,0.000000000000000000e+00 +7.731288542202962333e+01,4.727990455581272613e+02,2.036416495755281608e-01,6.623989609942198875e+00,-8.332843984473482790e-02,3.871963079850333084e-02,4.563496123041156649e-02,1.000000009475064955e+00,0.000000000000000000e+00 +7.731439508623334689e+01,4.728090108600673602e+02,2.028093291786065289e-01,6.624048063582796964e+00,-8.316177317806816571e-02,4.022929501653611101e-02,4.563496123041156649e-02,1.000000009842713977e+00,0.000000000000000000e+00 +7.731590473711510469e+01,4.728189763005890995e+02,2.019786696768938739e-01,6.624108795773491210e+00,-8.299510651140150352e-02,4.173894591315390618e-02,4.563496123041156649e-02,1.000000009038611859e+00,0.000000000000000000e+00 +7.731741437415584528e+01,4.728289418794156518e+02,2.011496710934640997e-01,6.624171806432283205e+00,-8.282843984473484134e-02,4.324858296754024306e-02,4.563496123041156649e-02,1.000000009957271452e+00,0.000000000000000000e+00 +7.731892399683657402e+01,4.728389075962702464e+02,2.003223334513449250e-01,6.624237095474040160e+00,-8.266177317806817915e-02,4.475820566329556660e-02,4.563496123041156649e-02,1.000000008859670775e+00,0.000000000000000000e+00 +7.732043360463832471e+01,4.728488734508760558e+02,1.994966567735179663e-01,6.624304662810502009e+00,-8.249510651140151696e-02,4.626781347842481851e-02,4.563496123041156649e-02,1.000000009793100997e+00,0.000000000000000000e+00 +7.732194319704221641e+01,4.728588394429561959e+02,1.986726410829186829e-01,6.624374508350273416e+00,-8.232843984473485477e-02,4.777740589709360275e-02,4.563496123041156649e-02,1.000000009391679212e+00,0.000000000000000000e+00 +7.732345277352938240e+01,4.728688055722338959e+02,1.978502864024364039e-01,6.624446631998833546e+00,-8.216177317806819258e-02,4.928698239843896239e-02,4.563496123041156649e-02,1.000000009737614937e+00,0.000000000000000000e+00 +7.732496233358104121e+01,4.728787718384322716e+02,1.970295927549143011e-01,6.624521033658528957e+00,-8.199510651140153039e-02,5.079654246479559793e-02,4.563496123041156649e-02,1.000000009397159939e+00,0.000000000000000000e+00 +7.732647187667845401e+01,4.728887382412744955e+02,1.962105601631494167e-01,6.624597713228578932e+00,-8.182843984473486820e-02,5.230608557639002121e-02,4.563496123041156649e-02,1.000000009266838852e+00,0.000000000000000000e+00 +7.732798140230293882e+01,4.728987047804837403e+02,1.953931886498926629e-01,6.624676670605072815e+00,-8.166177317806820601e-02,5.381561121486003879e-02,4.563496123041156649e-02,1.000000009455494610e+00,0.000000000000000000e+00 +7.732949090993587049e+01,4.729086714557831215e+02,1.945774782378488221e-01,6.624757905680972669e+00,-8.149510651140154383e-02,5.532511886206745860e-02,4.563496123041156649e-02,1.000000009673919887e+00,0.000000000000000000e+00 +7.733100039905869494e+01,4.729186382668958117e+02,1.937634289496764917e-01,6.624841418346114175e+00,-8.132843984473488164e-02,5.683460799949900666e-02,4.563496123041156649e-02,1.000000009234873977e+00,0.000000000000000000e+00 +7.733250986915292913e+01,4.729286052135449836e+02,1.929510408079881667e-01,6.624927208487206620e+00,-8.116177317806821945e-02,5.834407810766730623e-02,4.563496123041156649e-02,1.000000009391868172e+00,0.000000000000000000e+00 +7.733401931970013266e+01,4.729385722954537528e+02,1.921403138353501849e-01,6.625015275987832020e+00,-8.099510651140155726e-02,5.985352866904217889e-02,4.563496123041156649e-02,1.000000009831094605e+00,0.000000000000000000e+00 +7.733552875018193618e+01,4.729485395123452349e+02,1.913312480542827265e-01,6.625105620728448663e+00,-8.082843984473489507e-02,6.136295916568656333e-02,4.563496123041156649e-02,1.000000009450724425e+00,0.000000000000000000e+00 +7.733703816008005560e+01,4.729585068639426026e+02,1.905238434872598696e-01,6.625198242586391117e+00,-8.066177317806823288e-02,6.287236907806886821e-02,4.563496123041156649e-02,1.000000009089919484e+00,0.000000000000000000e+00 +7.733854754887626370e+01,4.729684743499689148e+02,1.897181001567094794e-01,6.625293141435868449e+00,-8.049510651140157069e-02,6.438175788799455068e-02,4.563496123041156649e-02,1.000000009969569614e+00,0.000000000000000000e+00 +7.734005691605240429e+01,4.729784419701473439e+02,1.889140180850133466e-01,6.625390317147966890e+00,-8.032843984473490850e-02,6.589112507918398753e-02,4.563496123041156649e-02,1.000000009013910507e+00,0.000000000000000000e+00 +7.734156626109040644e+01,4.729884097242010625e+02,1.881115972945070769e-01,6.625489769590653388e+00,-8.016177317806824631e-02,6.740047013078900862e-02,4.563496123041156649e-02,1.000000009766635722e+00,0.000000000000000000e+00 +7.734307558347225608e+01,4.729983776118531296e+02,1.873108378074801184e-01,6.625591498628769394e+00,-7.999510651140158413e-02,6.890979252738584082e-02,4.563496123041156649e-02,1.000000009525360278e+00,0.000000000000000000e+00 +7.734458488268003862e+01,4.730083456328266607e+02,1.865117396461758170e-01,6.625695504124039736e+00,-7.982843984473492194e-02,7.041909174954935624e-02,4.563496123041156649e-02,1.000000009478233975e+00,0.000000000000000000e+00 +7.734609415819591050e+01,4.730183137868447716e+02,1.857143028327913059e-01,6.625801785935067301e+00,-7.966177317806825975e-02,7.192836727972698463e-02,4.563496123041156649e-02,1.000000009635678033e+00,0.000000000000000000e+00 +7.734760340950209923e+01,4.730282820736305780e+02,1.849185273894776438e-01,6.625910343917336576e+00,-7.949510651140159756e-02,7.343761860046288392e-02,4.563496123041156649e-02,1.000000009219962349e+00,0.000000000000000000e+00 +7.734911263608093179e+01,4.730382504929071388e+02,1.841244133383397041e-01,6.626021177923214545e+00,-7.932843984473493537e-02,7.494684519321020977e-02,4.563496123041156649e-02,1.000000009784862032e+00,0.000000000000000000e+00 +7.735062183741480624e+01,4.730482190443976265e+02,1.833319607014361752e-01,6.626134287801949796e+00,-7.916177317806827318e-02,7.645604654185167437e-02,4.563496123041156649e-02,1.000000008976551502e+00,0.000000000000000000e+00 +7.735213101298620586e+01,4.730581877278251000e+02,1.825411695007796709e-01,6.626249673399676965e+00,-7.899510651140161099e-02,7.796522212680390140e-02,4.563496123041156649e-02,1.000000009892355823e+00,0.000000000000000000e+00 +7.735364016227771344e+01,4.730681565429126181e+02,1.817520397583365921e-01,6.626367334559412292e+00,-7.882843984473494880e-02,7.947437143324603825e-02,4.563496123041156649e-02,1.000000009772069154e+00,0.000000000000000000e+00 +7.735514928477199703e+01,4.730781254893833534e+02,1.809645714960272100e-01,6.626487271121061617e+00,-7.866177317806828662e-02,8.098349394228146481e-02,4.563496123041156649e-02,1.000000008966953180e+00,0.000000000000000000e+00 +7.735665837995182414e+01,4.730880945669603079e+02,1.801787647357256383e-01,6.626609482921415051e+00,-7.849510651140162443e-02,8.249258913563535522e-02,4.563496123041156649e-02,1.000000009770239062e+00,0.000000000000000000e+00 +7.735816744730003336e+01,4.730980637753665974e+02,1.793946194992598608e-01,6.626733969794148749e+00,-7.832843984473496224e-02,8.400165649858697126e-02,4.563496123041156649e-02,1.000000009396997847e+00,0.000000000000000000e+00 +7.735967648629957694e+01,4.731080331143252806e+02,1.786121358084116761e-01,6.626860731569831131e+00,-7.816177317806830005e-02,8.551069551230802701e-02,4.563496123041156649e-02,1.000000009734265616e+00,0.000000000000000000e+00 +7.736118549643349240e+01,4.731180025835594734e+02,1.778313136849167531e-01,6.626989768075917553e+00,-7.799510651140163786e-02,8.701970566091481174e-02,4.563496123041156649e-02,1.000000009150694646e+00,0.000000000000000000e+00 +7.736269447718493097e+01,4.731279721827922344e+02,1.770521531504645751e-01,6.627121079136755633e+00,-7.782843984473497567e-02,8.852868642616056050e-02,4.563496123041156649e-02,1.000000009907356269e+00,0.000000000000000000e+00 +7.736420342803712913e+01,4.731379419117466227e+02,1.762746542266985239e-01,6.627254664573582588e+00,-7.766177317806831348e-02,9.003763729331087928e-02,4.563496123041156649e-02,1.000000009186297500e+00,0.000000000000000000e+00 +7.736571234847343703e+01,4.731479117701456971e+02,1.754988169352157679e-01,6.627390524204531452e+00,-7.749510651140165129e-02,9.154655774348138819e-02,4.563496123041156649e-02,1.000000010012719098e+00,0.000000000000000000e+00 +7.736722123797730433e+01,4.731578817577125164e+02,1.747246412975673457e-01,6.627528657844625748e+00,-7.732843984473498911e-02,9.305544726245650045e-02,4.563496123041156649e-02,1.000000009162131498e+00,0.000000000000000000e+00 +7.736873009603228013e+01,4.731678518741701396e+02,1.739521273352581388e-01,6.627669065305787477e+00,-7.716177317806832692e-02,9.456430533126090887e-02,4.563496123041156649e-02,1.000000009253570132e+00,0.000000000000000000e+00 +7.737023892212204146e+01,4.731778221192415685e+02,1.731812750697468428e-01,6.627811746396830905e+00,-7.699510651140166473e-02,9.607313143497861474e-02,4.563496123041156649e-02,1.000000009777194832e+00,0.000000000000000000e+00 +7.737174771573035059e+01,4.731877924926499190e+02,1.724120845224460519e-01,6.627956700923469668e+00,-7.682843984473500254e-02,9.758192505803352235e-02,4.563496123041156649e-02,1.000000009824756564e+00,0.000000000000000000e+00 +7.737325647634108350e+01,4.731977629941181931e+02,1.716445557147221745e-01,6.628103928688316770e+00,-7.666177317806834035e-02,9.909068568359015450e-02,4.563496123041156649e-02,1.000000009260187284e+00,0.000000000000000000e+00 +7.737476520343824404e+01,4.732077336233695064e+02,1.708786886678954342e-01,6.628253429490883697e+00,-7.649510651140167816e-02,1.005994127947205385e-01,4.563496123041156649e-02,1.000000009500154441e+00,0.000000000000000000e+00 +7.737627389650593557e+01,4.732177043801268042e+02,1.701144834032399245e-01,6.628405203127581302e+00,-7.632843984473501597e-02,1.021081058767485811e-01,4.563496123041156649e-02,1.000000009612170393e+00,0.000000000000000000e+00 +7.737778255502838931e+01,4.732276752641132020e+02,1.693519399419835536e-01,6.628559249391724251e+00,-7.616177317806835378e-02,1.036167644137075544e-01,4.563496123041156649e-02,1.000000009435988435e+00,0.000000000000000000e+00 +7.737929117848995020e+01,4.732376462750516453e+02,1.685910583053081002e-01,6.628715568073530129e+00,-7.599510651140169160e-02,1.051253878895069965e-01,4.563496123041156649e-02,1.000000009583819960e+00,0.000000000000000000e+00 +7.738079976637509105e+01,4.732476174126652495e+02,1.678318385143491853e-01,6.628874158960120333e+00,-7.582843984473502941e-02,1.066339757890998052e-01,4.563496123041156649e-02,1.000000009489120822e+00,0.000000000000000000e+00 +7.738230831816838418e+01,4.732575886766769599e+02,1.670742805901962169e-01,6.629035021835522734e+00,-7.566177317806836722e-02,1.081425275967056870e-01,4.563496123041156649e-02,1.000000009357768782e+00,0.000000000000000000e+00 +7.738381683335454397e+01,4.732675600668098355e+02,1.663183845538924732e-01,6.629198156480671678e+00,-7.549510651140170503e-02,1.096510427969781959e-01,4.563496123041156649e-02,1.000000009778026389e+00,0.000000000000000000e+00 +7.738532531141839854e+01,4.732775315827868781e+02,1.655641504264350750e-01,6.629363562673409760e+00,-7.532843984473504284e-02,1.111595208755832703e-01,4.563496123041156649e-02,1.000000009768847509e+00,0.000000000000000000e+00 +7.738683375184491808e+01,4.732875032243311466e+02,1.648115782287749853e-01,6.629531240188490493e+00,-7.516177317806838065e-02,1.126679613168336813e-01,4.563496123041156649e-02,1.000000009121696509e+00,0.000000000000000000e+00 +7.738834215411918649e+01,4.732974749911656431e+02,1.640606679818169544e-01,6.629701188797577416e+00,-7.499510651140171846e-02,1.141763636048561820e-01,4.563496123041156649e-02,1.000000009571950343e+00,0.000000000000000000e+00 +7.738985051772641555e+01,4.733074468830133128e+02,1.633114197064196305e-01,6.629873408269244983e+00,-7.482843984473505627e-02,1.156847272265254106e-01,4.563496123041156649e-02,1.000000009724045791e+00,0.000000000000000000e+00 +7.739135884215195915e+01,4.733174188995972145e+02,1.625638334233954485e-01,6.630047898368983894e+00,-7.466177317806839409e-02,1.171930516667428895e-01,4.563496123041156649e-02,1.000000009735949380e+00,0.000000000000000000e+00 +7.739286712688131331e+01,4.733273910406402933e+02,1.618179091535106862e-01,6.630224658859199316e+00,-7.449510651140173190e-02,1.187013364107821489e-01,4.563496123041156649e-02,1.000000008976685395e+00,0.000000000000000000e+00 +7.739437537140008772e+01,4.733373633058656083e+02,1.610736469174854635e-01,6.630403689499212661e+00,-7.432843984473506971e-02,1.202095809431005247e-01,4.563496123041156649e-02,1.000000009930921641e+00,0.000000000000000000e+00 +7.739588357519404838e+01,4.733473356949961044e+02,1.603310467359937430e-01,6.630584990045261584e+00,-7.416177317806840752e-02,1.217177847520400230e-01,4.563496123041156649e-02,1.000000009609137930e+00,0.000000000000000000e+00 +7.739739173774908920e+01,4.733573082077547838e+02,1.595901086296633020e-01,6.630768560250507093e+00,-7.399510651140174533e-02,1.232259473215726875e-01,4.563496123041156649e-02,1.000000009308727122e+00,0.000000000000000000e+00 +7.739889985855124621e+01,4.733672808438646484e+02,1.588508326190757602e-01,6.630954399865028215e+00,-7.382843984473508314e-02,1.247340681377680088e-01,4.563496123041156649e-02,1.000000009928949218e+00,0.000000000000000000e+00 +7.740040793708669753e+01,4.733772536030487004e+02,1.581132187247665799e-01,6.631142508635826438e+00,-7.366177317806842095e-02,1.262421466881940291e-01,4.563496123041156649e-02,1.000000009236837739e+00,0.000000000000000000e+00 +7.740191597284176339e+01,4.733872264850298848e+02,1.573772669672250102e-01,6.631332886306829266e+00,-7.349510651140175876e-02,1.277501824571954103e-01,4.563496123041156649e-02,1.000000009677980861e+00,0.000000000000000000e+00 +7.740342396530292035e+01,4.733971994895312037e+02,1.566429773668941705e-01,6.631525532618886665e+00,-7.332843984473509658e-02,1.292581749329507756e-01,4.563496123041156649e-02,1.000000009393965827e+00,0.000000000000000000e+00 +7.740493191395678707e+01,4.734071726162756022e+02,1.559103499441709673e-01,6.631720447309778166e+00,-7.316177317806843439e-02,1.307661236009838024e-01,4.563496123041156649e-02,1.000000009642960208e+00,0.000000000000000000e+00 +7.740643981829012432e+01,4.734171458649860256e+02,1.551793847194061771e-01,6.631917630114210205e+00,-7.299510651140177220e-02,1.322740279488647808e-01,4.563496123041156649e-02,1.000000009722513905e+00,0.000000000000000000e+00 +7.740794767778984919e+01,4.734271192353854758e+02,1.544500817129043913e-01,6.632117080763820560e+00,-7.282843984473511001e-02,1.337818874632557831e-01,4.563496123041156649e-02,1.000000009312458582e+00,0.000000000000000000e+00 +7.740945549194303510e+01,4.734370927271968981e+02,1.537224409449240436e-01,6.632318798987178354e+00,-7.266177317806844782e-02,1.352897016304889233e-01,4.563496123041156649e-02,1.000000009647741717e+00,0.000000000000000000e+00 +7.741096326023691176e+01,4.734470663401432944e+02,1.529964624356773550e-01,6.632522784509784941e+00,-7.249510651140178563e-02,1.367974699389128967e-01,4.563496123041156649e-02,1.000000009611220930e+00,0.000000000000000000e+00 +7.741247098215885103e+01,4.734570400739475531e+02,1.522721462053303887e-01,6.632729037054078347e+00,-7.232843984473512344e-02,1.383051918753481768e-01,4.563496123041156649e-02,1.000000009640704679e+00,0.000000000000000000e+00 +7.741397865719639526e+01,4.734670139283326762e+02,1.515494922740030503e-01,6.632937556339432383e+00,-7.216177317806846125e-02,1.398128669274333047e-01,4.563496123041156649e-02,1.000000009384650390e+00,0.000000000000000000e+00 +7.741548628483724315e+01,4.734769879030216089e+02,1.508285006617690882e-01,6.633148342082159310e+00,-7.199510651140179907e-02,1.413204945824364789e-01,4.563496123041156649e-02,1.000000009655965805e+00,0.000000000000000000e+00 +7.741699386456926391e+01,4.734869619977372395e+02,1.501091713886560097e-01,6.633361393995510724e+00,-7.182843984473513688e-02,1.428280743290128441e-01,4.563496123041156649e-02,1.000000009696724090e+00,0.000000000000000000e+00 +7.741850139588046886e+01,4.734969362122025700e+02,1.493915044746451926e-01,6.633576711789681113e+00,-7.166177317806847469e-02,1.443356056548379673e-01,4.563496123041156649e-02,1.000000009522589384e+00,0.000000000000000000e+00 +7.742000887825905409e+01,4.735069105461405456e+02,1.486754999396718291e-01,6.633794295171807853e+00,-7.149510651140181250e-02,1.458430880477758762e-01,4.563496123041156649e-02,1.000000009532267420e+00,0.000000000000000000e+00 +7.742151631119337196e+01,4.735168849992740547e+02,1.479611578036249264e-01,6.634014143845972988e+00,-7.132843984473515031e-02,1.473505209964581786e-01,4.563496123041156649e-02,1.000000009335023865e+00,0.000000000000000000e+00 +7.742302369417193120e+01,4.735268595713260424e+02,1.472484780863473341e-01,6.634236257513205892e+00,-7.116177317806848812e-02,1.488579039890957079e-01,4.563496123041156649e-02,1.000000010095908776e+00,0.000000000000000000e+00 +7.742453102668343945e+01,4.735368342620194539e+02,1.465374608076357166e-01,6.634460635871484158e+00,-7.099510651140182593e-02,1.503652365158253956e-01,4.563496123041156649e-02,1.000000009063004347e+00,0.000000000000000000e+00 +7.742603830821676070e+01,4.735468090710772344e+02,1.458281059872405527e-01,6.634687278615738038e+00,-7.082843984473516374e-02,1.518725180628077709e-01,4.563496123041156649e-02,1.000000009731375927e+00,0.000000000000000000e+00 +7.742754553826092945e+01,4.735567839982222722e+02,1.451204136448661364e-01,6.634916185437846003e+00,-7.066177317806850156e-02,1.533797481216448710e-01,4.563496123041156649e-02,1.000000009724452132e+00,0.000000000000000000e+00 +7.742905271630516495e+01,4.735667590431774556e+02,1.444143838001705760e-01,6.635147356026644516e+00,-7.049510651140183937e-02,1.548869261805316255e-01,4.563496123041156649e-02,1.000000009394282241e+00,0.000000000000000000e+00 +7.743055984183884277e+01,4.735767342056657867e+02,1.437100164727658225e-01,6.635380790067924472e+00,-7.032843984473517718e-02,1.563940517283704257e-01,4.563496123041156649e-02,1.000000009867386686e+00,0.000000000000000000e+00 +7.743206691435153743e+01,4.735867094854100969e+02,1.430073116822176416e-01,6.635616487244433870e+00,-7.016177317806851499e-02,1.579011242559399397e-01,4.563496123041156649e-02,1.000000009525361611e+00,0.000000000000000000e+00 +7.743357393333300820e+01,4.735966848821333315e+02,1.423062694480456136e-01,6.635854447235882247e+00,-6.999510651140185280e-02,1.594081432517599206e-01,4.563496123041156649e-02,1.000000009479422358e+00,0.000000000000000000e+00 +7.743508089827317065e+01,4.736066603955583787e+02,1.416068897897231060e-01,6.636094669718938910e+00,-6.982843984473519061e-02,1.609151082062066918e-01,4.563496123041156649e-02,1.000000009268632972e+00,0.000000000000000000e+00 +7.743658780866213931e+01,4.736166360254081837e+02,1.409091727266773564e-01,6.636337154367237368e+00,-6.966177317806852842e-02,1.624220186091455131e-01,4.563496123041156649e-02,1.000000009989139516e+00,0.000000000000000000e+00 +7.743809466399021346e+01,4.736266117714055781e+02,1.402131182782893892e-01,6.636581900851376226e+00,-6.949510651140186623e-02,1.639288739522786753e-01,4.563496123041156649e-02,1.000000009600046980e+00,0.000000000000000000e+00 +7.743960146374789133e+01,4.736365876332735070e+02,1.395187264638940439e-01,6.636828908838923624e+00,-6.932843984473520405e-02,1.654356737244200570e-01,4.563496123041156649e-02,1.000000009573117632e+00,0.000000000000000000e+00 +7.744110820742584167e+01,4.736465636107348587e+02,1.388259973027800021e-01,6.637078177994414574e+00,-6.916177317806854186e-02,1.669424174167899455e-01,4.563496123041156649e-02,1.000000009416702751e+00,0.000000000000000000e+00 +7.744261489451491798e+01,4.736565397035125216e+02,1.381349308141897325e-01,6.637329707979356286e+00,-6.899510651140187967e-02,1.684491045200581516e-01,4.563496123041156649e-02,1.000000009805195544e+00,0.000000000000000000e+00 +7.744412152450618692e+01,4.736665159113293839e+02,1.374455270173195187e-01,6.637583498452229058e+00,-6.882843984473521748e-02,1.699557345261026031e-01,4.563496123041156649e-02,1.000000009449021121e+00,0.000000000000000000e+00 +7.744562809689089988e+01,4.736764922339082773e+02,1.367577859313194588e-01,6.637839549068489831e+00,-6.866177317806855529e-02,1.714623069250520160e-01,4.563496123041156649e-02,1.000000009398425815e+00,0.000000000000000000e+00 +7.744713461116050723e+01,4.736864686709721468e+02,1.360717075752934935e-01,6.638097859480571294e+00,-6.849510651140189310e-02,1.729688212088128507e-01,4.563496123041156649e-02,1.000000009913950993e+00,0.000000000000000000e+00 +7.744864106680664406e+01,4.736964452222438240e+02,1.353872919682993226e-01,6.638358429337886335e+00,-6.832843984473523091e-02,1.744752768698810963e-01,4.563496123041156649e-02,1.000000009291256431e+00,0.000000000000000000e+00 +7.745014746332114441e+01,4.737064218874462540e+02,1.347045391293485161e-01,6.638621258286830695e+00,-6.816177317806856872e-02,1.759816733983839976e-01,4.563496123041156649e-02,1.000000010123872851e+00,0.000000000000000000e+00 +7.745165380019606971e+01,4.737163986663022115e+02,1.340234490774064313e-01,6.638886345970781200e+00,-6.799510651140190653e-02,1.774880102885561806e-01,4.563496123041156649e-02,1.000000009126448042e+00,0.000000000000000000e+00 +7.745316007692365190e+01,4.737263755585346416e+02,1.333440218313922121e-01,6.639153692030103748e+00,-6.782843984473524435e-02,1.789942870298854849e-01,4.563496123041156649e-02,1.000000009660488631e+00,0.000000000000000000e+00 +7.745466629299633610e+01,4.737363525638663759e+02,1.326662574101788727e-01,6.639423296102147987e+00,-6.766177317806858216e-02,1.805005031171270369e-01,4.563496123041156649e-02,1.000000009991230288e+00,0.000000000000000000e+00 +7.745617244790679479e+01,4.737463296820202459e+02,1.319901558325931867e-01,6.639695157821257077e+00,-6.749510651140191997e-02,1.820066580426283331e-01,4.563496123041156649e-02,1.000000009158741321e+00,0.000000000000000000e+00 +7.745767854114787099e+01,4.737563069127191397e+02,1.313157171174157423e-01,6.639969276818765920e+00,-6.732843984473525778e-02,1.835127512974983055e-01,4.563496123041156649e-02,1.000000009719760330e+00,0.000000000000000000e+00 +7.745918457221263509e+01,4.737662842556859459e+02,1.306429412833809423e-01,6.640245652723001157e+00,-6.716177317806859559e-02,1.850187823769054440e-01,4.563496123041156649e-02,1.000000009524696143e+00,0.000000000000000000e+00 +7.746069054059437065e+01,4.737762617106434959e+02,1.299718283491770321e-01,6.640524285159289164e+00,-6.699510651140193340e-02,1.865247507729912435e-01,4.563496123041156649e-02,1.000000009940724910e+00,0.000000000000000000e+00 +7.746219644578657437e+01,4.737862392773146212e+02,1.293023783334460164e-01,6.640805173749953383e+00,-6.682843984473527121e-02,1.880306559801683264e-01,4.563496123041156649e-02,1.000000009586130778e+00,0.000000000000000000e+00 +7.746370228728295615e+01,4.737962169554221532e+02,1.286345912547837422e-01,6.641088318114319655e+00,-6.666177317806860902e-02,1.895364974909823641e-01,4.563496123041156649e-02,1.000000009421506908e+00,0.000000000000000000e+00 +7.746520806457742481e+01,4.738061947446889803e+02,1.279684671317398437e-01,6.641373717868715332e+00,-6.649510651140194684e-02,1.910422747996410875e-01,4.563496123041156649e-02,1.000000009616926144e+00,0.000000000000000000e+00 +7.746671377716413076e+01,4.738161726448378772e+02,1.273040059828177695e-01,6.641661372626473714e+00,-6.632843984473528465e-02,1.925479874008254044e-01,4.563496123041156649e-02,1.000000009551351488e+00,0.000000000000000000e+00 +7.746821942453742338e+01,4.738261506555917322e+02,1.266412078264747831e-01,6.641951281997936718e+00,-6.616177317806862246e-02,1.940536347884998791e-01,4.563496123041156649e-02,1.000000009379782062e+00,0.000000000000000000e+00 +7.746972500619187940e+01,4.738361287766733767e+02,1.259800726811219351e-01,6.642243445590455764e+00,-6.599510651140196027e-02,1.955592164570829350e-01,4.563496123041156649e-02,1.000000010033551101e+00,0.000000000000000000e+00 +7.747123052162230294e+01,4.738461070078055855e+02,1.253206005651240906e-01,6.642537863008394439e+00,-6.582843984473529808e-02,1.970647319026172517e-01,4.563496123041156649e-02,1.000000009693643221e+00,0.000000000000000000e+00 +7.747273597032372550e+01,4.738560853487112468e+02,1.246627914967999157e-01,6.642834533853132939e+00,-6.566177317806863589e-02,1.985701806186306595e-01,4.563496123041156649e-02,1.000000009276405866e+00,0.000000000000000000e+00 +7.747424135179139171e+01,4.738660637991131921e+02,1.240066454944218910e-01,6.643133457723066293e+00,-6.549510651140197370e-02,2.000755621002560380e-01,4.563496123041156649e-02,1.000000009691188296e+00,0.000000000000000000e+00 +7.747574666552077360e+01,4.738760423587341961e+02,1.233521625762162982e-01,6.643434634213608803e+00,-6.532843984473531151e-02,2.015808758442221849e-01,4.563496123041156649e-02,1.000000009880364749e+00,0.000000000000000000e+00 +7.747725191100757058e+01,4.738860210272970903e+02,1.226993427603632059e-01,6.643738062917198484e+00,-6.516177317806864933e-02,2.030861213458944325e-01,4.563496123041156649e-02,1.000000009170370019e+00,0.000000000000000000e+00 +7.747875708774772363e+01,4.738959998045247062e+02,1.220481860649965111e-01,6.644043743423297066e+00,-6.499510651140198714e-02,2.045912980998546571e-01,4.563496123041156649e-02,1.000000010016825591e+00,0.000000000000000000e+00 +7.748026219523740110e+01,4.739059786901398184e+02,1.213986925082038842e-01,6.644351675318390882e+00,-6.482843984473532495e-02,2.060964056046128701e-01,4.563496123041156649e-02,1.000000009379289123e+00,0.000000000000000000e+00 +7.748176723297301294e+01,4.739159576838652583e+02,1.207508621080268241e-01,6.644661858185998859e+00,-6.466177317806866276e-02,2.076014433543363902e-01,4.563496123041156649e-02,1.000000010091031566e+00,0.000000000000000000e+00 +7.748327220045118224e+01,4.739259367854238576e+02,1.201046948824606164e-01,6.644974291606668082e+00,-6.449510651140200057e-02,2.091064108476920758e-01,4.563496123041156649e-02,1.000000009096344344e+00,0.000000000000000000e+00 +7.748477709716878792e+01,4.739359159945383908e+02,1.194601908494543480e-01,6.645288975157982669e+00,-6.432843984473533838e-02,2.106113075789848577e-01,4.563496123041156649e-02,1.000000009998771811e+00,0.000000000000000000e+00 +7.748628192262293624e+01,4.739458953109316326e+02,1.188173500269109201e-01,6.645605908414559337e+00,-6.416177317806867619e-02,2.121161330481812490e-01,4.563496123041156649e-02,1.000000009335428874e+00,0.000000000000000000e+00 +7.748778667631098926e+01,4.739558747343264145e+02,1.181761724326870072e-01,6.645925090948058056e+00,-6.399510651140201400e-02,2.136208867502767117e-01,4.563496123041156649e-02,1.000000009519073529e+00,0.000000000000000000e+00 +7.748929135773052224e+01,4.739658542644455679e+02,1.175366580845931125e-01,6.646246522327176720e+00,-6.382843984473535182e-02,2.151255681841392486e-01,4.563496123041156649e-02,1.000000009817604285e+00,0.000000000000000000e+00 +7.749079596637939460e+01,4.739758339010118107e+02,1.168988070003935120e-01,6.646570202117659143e+00,-6.366177317806868963e-02,2.166301768477785494e-01,4.563496123041156649e-02,1.000000009883760699e+00,0.000000000000000000e+00 +7.749230050175567897e+01,4.739858136437479743e+02,1.162626191978062967e-01,6.646896129882295945e+00,-6.349510651140202744e-02,2.181347122389268312e-01,4.563496123041156649e-02,1.000000009362734810e+00,0.000000000000000000e+00 +7.749380496335768953e+01,4.739957934923768335e+02,1.156280946945033444e-01,6.647224305180926329e+00,-6.332843984473536525e-02,2.196391738550292072e-01,4.563496123041156649e-02,1.000000009854818961e+00,0.000000000000000000e+00 +7.749530935068402471e+01,4.740057734466211627e+02,1.149952335081103477e-01,6.647554727570439859e+00,-6.316177317806870306e-02,2.211435611961866388e-01,4.563496123041156649e-02,1.000000009421244007e+00,0.000000000000000000e+00 +7.749681366323349607e+01,4.740157535062037368e+02,1.143640356562067723e-01,6.647887396604782673e+00,-6.299510651140204087e-02,2.226478737598332203e-01,4.563496123041156649e-02,1.000000009648030153e+00,0.000000000000000000e+00 +7.749831790050518521e+01,4.740257336708473304e+02,1.137345011563258984e-01,6.648222311834955711e+00,-6.282843984473537868e-02,2.241521110460404920e-01,4.563496123041156649e-02,1.000000009366699638e+00,0.000000000000000000e+00 +7.749982206199842949e+01,4.740357139402747180e+02,1.131066300259547935e-01,6.648559472809020932e+00,-6.266177317806871649e-02,2.256562725533753644e-01,4.563496123041156649e-02,1.000000010149376894e+00,0.000000000000000000e+00 +7.750132614721280788e+01,4.740456943142086743e+02,1.124804222825343120e-01,6.648898879072101309e+00,-6.249510651140204737e-02,2.271603577830241805e-01,4.563496123041156649e-02,1.000000009242611565e+00,0.000000000000000000e+00 +7.750283015564816935e+01,4.740556747923719740e+02,1.118558779434591227e-01,6.649240530166387053e+00,-6.232843984473537824e-02,2.286643662322881410e-01,4.563496123041156649e-02,1.000000009774871357e+00,0.000000000000000000e+00 +7.750433408680461866e+01,4.740656553744873918e+02,1.112329970260776818e-01,6.649584425631132056e+00,-6.216177317806870911e-02,2.301682974034317541e-01,4.563496123041156649e-02,1.000000009763576836e+00,0.000000000000000000e+00 +7.750583794018250217e+01,4.740756360602777022e+02,1.106117795476922322e-01,6.649930565002663663e+00,-6.199510651140203998e-02,2.316721507959972060e-01,4.563496123041156649e-02,1.000000009574544269e+00,0.000000000000000000e+00 +7.750734171528245042e+01,4.740856168494656231e+02,1.099922255255588177e-01,6.650278947814380892e+00,-6.182843984473537086e-02,2.331759259103380333e-01,4.563496123041156649e-02,1.000000009566881065e+00,0.000000000000000000e+00 +7.750884541160533558e+01,4.740955977417739291e+02,1.093743349768872691e-01,6.650629573596757993e+00,-6.166177317806870173e-02,2.346796222476105198e-01,4.563496123041156649e-02,1.000000009699842929e+00,0.000000000000000000e+00 +7.751034902865231402e+01,4.741055787369253380e+02,1.087581079188412181e-01,6.650982441877347995e+00,-6.149510651140203260e-02,2.361832393091739535e-01,4.563496123041156649e-02,1.000000009925563926e+00,0.000000000000000000e+00 +7.751185256592479789e+01,4.741155598346426814e+02,1.081435443685380832e-01,6.651337552180785373e+00,-6.132843984473536347e-02,2.376867765965815227e-01,4.563496123041156649e-02,1.000000009403384738e+00,0.000000000000000000e+00 +7.751335602292446936e+01,4.741255410346486201e+02,1.075306443430490699e-01,6.651694904028788713e+00,-6.116177317806869435e-02,2.391902336103899906e-01,4.563496123041156649e-02,1.000000009642918020e+00,0.000000000000000000e+00 +7.751485939915328061e+01,4.741355223366659288e+02,1.069194078593991848e-01,6.652054496940161599e+00,-6.099510651140202522e-02,2.406936098536948954e-01,4.563496123041156649e-02,1.000000009396532663e+00,0.000000000000000000e+00 +7.751636269411343960e+01,4.741455037404173822e+02,1.063098349345672072e-01,6.652416330430798830e+00,-6.082843984473535609e-02,2.421969048279866976e-01,4.563496123041156649e-02,1.000000010160289055e+00,0.000000000000000000e+00 +7.751786590730745274e+01,4.741554852456256981e+02,1.057019255854857315e-01,6.652780404013686422e+00,-6.066177317806868696e-02,2.437001180372771192e-01,4.563496123041156649e-02,1.000000009099826226e+00,0.000000000000000000e+00 +7.751936903823808223e+01,4.741654668520135942e+02,1.050956798290411248e-01,6.653146717198907822e+00,-6.049510651140201783e-02,2.452032489815910432e-01,4.563496123041156649e-02,1.000000010056191657e+00,0.000000000000000000e+00 +7.752087208640837446e+01,4.741754485593037884e+02,1.044910976820735415e-01,6.653515269493640361e+00,-6.032843984473534871e-02,2.467062971670024862e-01,4.563496123041156649e-02,1.000000009394427458e+00,0.000000000000000000e+00 +7.752237505132164586e+01,4.741854303672190554e+02,1.038881791613769368e-01,6.653886060402166791e+00,-6.016177317806867958e-02,2.482092620943987249e-01,4.563496123041156649e-02,1.000000009762817443e+00,0.000000000000000000e+00 +7.752387793248149706e+01,4.741954122754821128e+02,1.032869242836990387e-01,6.654259089425869966e+00,-5.999510651140201045e-02,2.497121432689260456e-01,4.563496123041156649e-02,1.000000009871209405e+00,0.000000000000000000e+00 +7.752538072939181291e+01,4.742053942838156786e+02,1.026873330657413763e-01,6.654634356063241718e+00,-5.982843984473534132e-02,2.512149401940717564e-01,4.563496123041156649e-02,1.000000009208434903e+00,0.000000000000000000e+00 +7.752688344155673406e+01,4.742153763919424705e+02,1.020894055241592657e-01,6.655011859809882857e+00,-5.966177317806867220e-02,2.527176523728367763e-01,4.563496123041156649e-02,1.000000010010024587e+00,0.000000000000000000e+00 +7.752838606848071379e+01,4.742253585995852063e+02,1.014931416755617960e-01,6.655391600158504950e+00,-5.949510651140200307e-02,2.542202793118646387e-01,4.563496123041156649e-02,1.000000009391105893e+00,0.000000000000000000e+00 +7.752988860966848961e+01,4.742353409064666039e+02,1.008985415365118571e-01,6.655773576598938313e+00,-5.932843984473533394e-02,2.557228205137486721e-01,4.563496123041156649e-02,1.000000009967178638e+00,0.000000000000000000e+00 +7.753139106462506902e+01,4.742453233123093810e+02,1.003056051235261259e-01,6.656157788618128457e+00,-5.916177317806866481e-02,2.572252754852986101e-01,4.563496123041156649e-02,1.000000009625965358e+00,0.000000000000000000e+00 +7.753289343285574375e+01,4.742553058168362554e+02,9.971433245307505244e-02,6.656544235700144974e+00,-5.899510651140199569e-02,2.587276437304383836e-01,4.563496123041156649e-02,1.000000009395778600e+00,0.000000000000000000e+00 +7.753439571386611817e+01,4.742652884197699450e+02,9.912472354158287369e-02,6.656932917326179755e+00,-5.882843984473532656e-02,2.602299247549264560e-01,4.563496123041156649e-02,1.000000009905188447e+00,0.000000000000000000e+00 +7.753589790716206664e+01,4.742752711208331107e+02,9.853677840542761357e-02,6.657323832974552325e+00,-5.866177317806865743e-02,2.617321180657565249e-01,4.563496123041156649e-02,1.000000009414248270e+00,0.000000000000000000e+00 +7.753740001224977618e+01,4.742852539197485271e+02,9.795049706094108299e-02,6.657716982120714277e+00,-5.849510651140198830e-02,2.632342231676010891e-01,4.563496123041156649e-02,1.000000010112475302e+00,0.000000000000000000e+00 +7.753890202863570380e+01,4.742952368162387984e+02,9.736587952440887983e-02,6.658112364237248393e+00,-5.832843984473531918e-02,2.647362395687157255e-01,4.563496123041156649e-02,1.000000009064786033e+00,0.000000000000000000e+00 +7.754040395582661915e+01,4.743052198100266992e+02,9.678292581207038892e-02,6.658509978793876627e+00,-5.816177317806865005e-02,2.662381667732430790e-01,4.563496123041156649e-02,1.000000010022711994e+00,0.000000000000000000e+00 +7.754190579332957611e+01,4.743152029008348904e+02,9.620163594011875430e-02,6.658909825257456561e+00,-5.799510651140198092e-02,2.677400042912576605e-01,4.563496123041156649e-02,1.000000009643677634e+00,0.000000000000000000e+00 +7.754340754065195540e+01,4.743251860883860900e+02,9.562200992470092087e-02,6.659311903091992946e+00,-5.782843984473531179e-02,2.692417516281124801e-01,4.563496123041156649e-02,1.000000009697132208e+00,0.000000000000000000e+00 +7.754490919730139353e+01,4.743351693724029587e+02,9.504404778191760661e-02,6.659716211758633264e+00,-5.766177317806864266e-02,2.707434082921182927e-01,4.563496123041156649e-02,1.000000009583410288e+00,0.000000000000000000e+00 +7.754641076278586809e+01,4.743451527526082145e+02,9.446774952782331647e-02,6.660122750715674833e+00,-5.749510651140197354e-02,2.722449737909871104e-01,4.563496123041156649e-02,1.000000009877549889e+00,0.000000000000000000e+00 +7.754791223661364086e+01,4.743551362287245183e+02,9.389311517842634236e-02,6.660531519418566582e+00,-5.732843984473530441e-02,2.737464476335977337e-01,4.563496123041156649e-02,1.000000009178150462e+00,0.000000000000000000e+00 +7.754941361829328628e+01,4.743651198004745311e+02,9.332014474968874929e-02,6.660942517319913492e+00,-5.716177317806863528e-02,2.752478293270296805e-01,4.563496123041156649e-02,1.000000010017550123e+00,0.000000000000000000e+00 +7.755091490733369142e+01,4.743751034675809706e+02,9.274883825752637534e-02,6.661355743869476598e+00,-5.699510651140196615e-02,2.767491183824709045e-01,4.563496123041156649e-02,1.000000009798672540e+00,0.000000000000000000e+00 +7.755241610324402757e+01,4.743850872297664978e+02,9.217919571780884558e-02,6.661771198514181869e+00,-5.682843984473529703e-02,2.782503143075181207e-01,4.563496123041156649e-02,1.000000009464311779e+00,0.000000000000000000e+00 +7.755391720553379287e+01,4.743950710867537737e+02,9.161121714635957203e-02,6.662188880698117543e+00,-5.666177317806862790e-02,2.797514166114929979e-01,4.563496123041156649e-02,1.000000009557037162e+00,0.000000000000000000e+00 +7.755541821371279809e+01,4.744050550382654592e+02,9.104490255895572592e-02,6.662608789862539460e+00,-5.649510651140195877e-02,2.812524248048425823e-01,4.563496123041156649e-02,1.000000009824370650e+00,0.000000000000000000e+00 +7.755691912729115245e+01,4.744150390840242721e+02,9.048025197132827935e-02,6.663030925445875496e+00,-5.632843984473528964e-02,2.827533383979473069e-01,4.563496123041156649e-02,1.000000010007364493e+00,0.000000000000000000e+00 +7.755841994577929199e+01,4.744250232237528166e+02,8.991726539916196359e-02,6.663455286883728235e+00,-5.616177317806862052e-02,2.842541569011128866e-01,4.563496123041156649e-02,1.000000009051539962e+00,0.000000000000000000e+00 +7.755992066868797963e+01,4.744350074571738105e+02,8.935594285809529691e-02,6.663881873608877626e+00,-5.599510651140195139e-02,2.857548798233780496e-01,4.563496123041156649e-02,1.000000010234051828e+00,0.000000000000000000e+00 +7.756142129552826248e+01,4.744449917840099147e+02,8.879628436372057065e-02,6.664310685051281880e+00,-5.582843984473528226e-02,2.872555066790166145e-01,4.563496123041156649e-02,1.000000009332363771e+00,0.000000000000000000e+00 +7.756292182581152872e+01,4.744549762039837333e+02,8.823828993158386313e-02,6.664741720638088118e+00,-5.566177317806861313e-02,2.887560369762842138e-01,4.563496123041156649e-02,1.000000009610994223e+00,0.000000000000000000e+00 +7.756442225904947918e+01,4.744649607168179841e+02,8.768195957718501188e-02,6.665174979793626164e+00,-5.549510651140194400e-02,2.902564702286552500e-01,4.563496123041156649e-02,1.000000009989720384e+00,0.000000000000000000e+00 +7.756592259475414153e+01,4.744749453222352713e+02,8.712729331597762750e-02,6.665610461939419196e+00,-5.532843984473527488e-02,2.917568059483045539e-01,4.563496123041156649e-02,1.000000009381051491e+00,0.000000000000000000e+00 +7.756742283243785607e+01,4.744849300199582558e+02,8.657429116336912145e-02,6.666048166494184635e+00,-5.516177317806860575e-02,2.932570436460983920e-01,4.563496123041156649e-02,1.000000009848034388e+00,0.000000000000000000e+00 +7.756892297161330418e+01,4.744949148097095986e+02,8.602295313472066440e-02,6.666488092873835036e+00,-5.499510651140193662e-02,2.947571828363226287e-01,4.563496123041156649e-02,1.000000009895837927e+00,0.000000000000000000e+00 +7.757042301179347987e+01,4.745048996912119037e+02,8.547327924534718624e-02,6.666930240491486082e+00,-5.482843984473526749e-02,2.962572230313464394e-01,4.563496123041156649e-02,1.000000009206833740e+00,0.000000000000000000e+00 +7.757192295249171821e+01,4.745148846641878322e+02,8.492526951051741768e-02,6.667374608757456578e+00,-5.466177317806859837e-02,2.977571637433901186e-01,4.563496123041156649e-02,1.000000010220555513e+00,0.000000000000000000e+00 +7.757342279322166689e+01,4.745248697283600450e+02,8.437892394545384867e-02,6.667821197079271123e+00,-5.449510651140192924e-02,2.992570044886619929e-01,4.563496123041156649e-02,1.000000009053610528e+00,0.000000000000000000e+00 +7.757492253349730049e+01,4.745348548834512030e+02,8.383424256533275609e-02,6.668270004861668987e+00,-5.432843984473526011e-02,3.007567447778761727e-01,4.563496123041156649e-02,1.000000010107538806e+00,0.000000000000000000e+00 +7.757642217283294883e+01,4.745448401291839104e+02,8.329122538528416220e-02,6.668721031506598784e+00,-5.416177317806859098e-02,3.022563841286800002e-01,4.563496123041156649e-02,1.000000009485498831e+00,0.000000000000000000e+00 +7.757792171074325438e+01,4.745548254652807714e+02,8.274987242039189006e-02,6.669174276413231794e+00,-5.399510651140192186e-02,3.037559220532100035e-01,4.563496123041156649e-02,1.000000009997698669e+00,0.000000000000000000e+00 +7.757942114674320067e+01,4.745648108914644467e+02,8.221018368569350809e-02,6.669629738977956634e+00,-5.382843984473525273e-02,3.052553580681517387e-01,4.563496123041156649e-02,1.000000009313589455e+00,0.000000000000000000e+00 +7.758092048034811228e+01,4.745747964074575407e+02,8.167215919618038555e-02,6.670087418594389028e+00,-5.366177317806858360e-02,3.067546916870323992e-01,4.563496123041156649e-02,1.000000010231872682e+00,0.000000000000000000e+00 +7.758241971107365487e+01,4.745847820129827141e+02,8.113579896679763703e-02,6.670547314653370030e+00,-5.349510651140191447e-02,3.082539224279131629e-01,4.563496123041156649e-02,1.000000009223348529e+00,0.000000000000000000e+00 +7.758391883843582093e+01,4.745947677077625713e+02,8.060110301244415021e-02,6.671009426542975795e+00,-5.332843984473524535e-02,3.097530498039031688e-01,4.563496123041156649e-02,1.000000009865373185e+00,0.000000000000000000e+00 +7.758541786195094403e+01,4.746047534915197161e+02,8.006807134797259973e-02,6.671473753648513139e+00,-5.316177317806857622e-02,3.112520733338153267e-01,4.563496123041156649e-02,1.000000009406007973e+00,0.000000000000000000e+00 +7.758691678113571299e+01,4.746147393639768097e+02,7.953670398818941945e-02,6.671940295352531081e+00,-5.299510651140190709e-02,3.127509925326791840e-01,4.563496123041156649e-02,1.000000009830058101e+00,0.000000000000000000e+00 +7.758841559550714351e+01,4.746247253248563993e+02,7.900700094785481631e-02,6.672409051034818184e+00,-5.282843984473523796e-02,3.142498069188430221e-01,4.563496123041156649e-02,1.000000009953909030e+00,0.000000000000000000e+00 +7.758991430458260652e+01,4.746347113738811458e+02,7.847896224168277035e-02,6.672880020072410545e+00,-5.266177317806856883e-02,3.157485160092259324e-01,4.563496123041156649e-02,1.000000009378088084e+00,0.000000000000000000e+00 +7.759141290787982825e+01,4.746446975107736534e+02,7.795258788434100694e-02,6.673353201839592685e+00,-5.249510651140189971e-02,3.172471193204948747e-01,4.563496123041156649e-02,1.000000010070045908e+00,0.000000000000000000e+00 +7.759291140491686178e+01,4.746546837352565262e+02,7.742787789045105229e-02,6.673828595707900213e+00,-5.232843984473523058e-02,3.187456163726131164e-01,4.563496123041156649e-02,1.000000009245049171e+00,0.000000000000000000e+00 +7.759440979521211545e+01,4.746646700470523683e+02,7.690483227458817794e-02,6.674306201046127818e+00,-5.216177317806856145e-02,3.202440066817202058e-01,4.563496123041156649e-02,1.000000010045440257e+00,0.000000000000000000e+00 +7.759590807828435288e+01,4.746746564458837838e+02,7.638345105128142853e-02,6.674786017220326606e+00,-5.199510651140189232e-02,3.217422897690150330e-01,4.563496123041156649e-02,1.000000009673915002e+00,0.000000000000000000e+00 +7.759740625365270716e+01,4.746846429314733768e+02,7.586373423501360791e-02,6.675268043593814760e+00,-5.182843984473522320e-02,3.232404651518572813e-01,4.563496123041156649e-02,1.000000009282828506e+00,0.000000000000000000e+00 +7.759890432083662404e+01,4.746946295035437515e+02,7.534568184022130688e-02,6.675752279527174871e+00,-5.166177317806855407e-02,3.247385323496869147e-01,4.563496123041156649e-02,1.000000010019543639e+00,0.000000000000000000e+00 +7.760040227935594714e+01,4.747046161618174551e+02,7.482929388129486159e-02,6.676238724378260159e+00,-5.149510651140188494e-02,3.262364908840176270e-01,4.563496123041156649e-02,1.000000009858794892e+00,0.000000000000000000e+00 +7.760190012873084697e+01,4.747146029060171486e+02,7.431457037257838127e-02,6.676727377502200689e+00,-5.132843984473521581e-02,3.277343402736856426e-01,4.563496123041156649e-02,1.000000009539810941e+00,0.000000000000000000e+00 +7.760339786848186350e+01,4.747245897358653792e+02,7.380151132836974825e-02,6.677218238251402482e+00,-5.116177317806854669e-02,3.292320800389925139e-01,4.563496123041156649e-02,1.000000009400259904e+00,0.000000000000000000e+00 +7.760489549812989196e+01,4.747345766510847511e+02,7.329011676292059019e-02,6.677711305975552847e+00,-5.099510651140187756e-02,3.307297097011048237e-01,4.563496123041156649e-02,1.000000010168190290e+00,0.000000000000000000e+00 +7.760639301719619709e+01,4.747445636513978116e+02,7.278038669043632169e-02,6.678206580021624816e+00,-5.082843984473520843e-02,3.322272287826400494e-01,4.563496123041156649e-02,1.000000009397271850e+00,0.000000000000000000e+00 +7.760789042520239889e+01,4.747545507365271646e+02,7.227232112507611661e-02,6.678704059733882481e+00,-5.066177317806853930e-02,3.337246368029143095e-01,4.563496123041156649e-02,1.000000009783970079e+00,0.000000000000000000e+00 +7.760938772167048683e+01,4.747645379061954145e+02,7.176592008095289410e-02,6.679203744453879210e+00,-5.049510651140187018e-02,3.352219332856451461e-01,4.563496123041156649e-02,1.000000010058228250e+00,0.000000000000000000e+00 +7.761088490612279145e+01,4.747745251601251084e+02,7.126118357213336030e-02,6.679705633520467423e+00,-5.032843984473520105e-02,3.367191177530131085e-01,4.563496123041156649e-02,1.000000009339644613e+00,0.000000000000000000e+00 +7.761238197808204120e+01,4.747845124980388505e+02,7.075811161263796667e-02,6.680209726269799475e+00,-5.016177317806853192e-02,3.382161897262470629e-01,4.563496123041156649e-02,1.000000009515839006e+00,0.000000000000000000e+00 +7.761387893707131980e+01,4.747944999196592448e+02,7.025670421644093777e-02,6.680716022035329438e+00,-4.999510651140186279e-02,3.397131487297695984e-01,4.563496123041156649e-02,1.000000010091478986e+00,0.000000000000000000e+00 +7.761537578261408044e+01,4.748044874247087819e+02,6.975696139747025737e-02,6.681224520147821089e+00,-4.982843984473519366e-02,3.412099942876306580e-01,4.563496123041156649e-02,1.000000009772129328e+00,0.000000000000000000e+00 +7.761687251423413159e+01,4.748144750129100657e+02,6.925888316960766844e-02,6.681735219935350578e+00,-4.966177317806852454e-02,3.427067259223131046e-01,4.563496123041156649e-02,1.000000009239061294e+00,0.000000000000000000e+00 +7.761836913145567962e+01,4.748244626839857006e+02,6.876246954668867317e-02,6.682248120723307316e+00,-4.949510651140185541e-02,3.442033431576915770e-01,4.563496123041156649e-02,1.000000009962077829e+00,0.000000000000000000e+00 +7.761986563380330040e+01,4.748344504376582336e+02,6.826772054250254684e-02,6.682763221834399303e+00,-4.932843984473518628e-02,3.456998455202136000e-01,4.563496123041156649e-02,1.000000009835754655e+00,0.000000000000000000e+00 +7.762136202080192504e+01,4.748444382736502121e+02,6.777463617079231006e-02,6.683280522588660233e+00,-4.916177317806851715e-02,3.471962325335503641e-01,4.563496123041156649e-02,1.000000009524814937e+00,0.000000000000000000e+00 +7.762285829197686837e+01,4.748544261916841833e+02,6.728321644525475653e-02,6.683800022303448607e+00,-4.899510651140184803e-02,3.486925037227439628e-01,4.563496123041156649e-02,1.000000009688742475e+00,0.000000000000000000e+00 +7.762435444685382890e+01,4.748644141914826946e+02,6.679346137954043916e-02,6.684321720293453062e+00,-4.882843984473517890e-02,3.501886586142006208e-01,4.563496123041156649e-02,1.000000009791145006e+00,0.000000000000000000e+00 +7.762585048495888884e+01,4.748744022727683500e+02,6.630537098725365619e-02,6.684845615870697699e+00,-4.866177317806850977e-02,3.516846967339026797e-01,4.563496123041156649e-02,1.000000009686562663e+00,0.000000000000000000e+00 +7.762734640581848566e+01,4.748843904352636969e+02,6.581894528195247895e-02,6.685371708344544750e+00,-4.849510651140184064e-02,3.531806176079950177e-01,4.563496123041156649e-02,1.000000010017898955e+00,0.000000000000000000e+00 +7.762884220895946896e+01,4.748943786786912824e+02,6.533418427714872412e-02,6.685899997021698127e+00,-4.832843984473517152e-02,3.546764207639657163e-01,4.563496123041156649e-02,1.000000009437473247e+00,0.000000000000000000e+00 +7.763033789390905781e+01,4.749043670027735971e+02,6.485108798630798144e-02,6.686430481206208754e+00,-4.816177317806850239e-02,3.561721057276698299e-01,4.563496123041156649e-02,1.000000009767931353e+00,0.000000000000000000e+00 +7.763183346019485498e+01,4.749143554072332449e+02,6.436965642284958600e-02,6.686963160199475453e+00,-4.799510651140183326e-02,3.576676720280728139e-01,4.563496123041156649e-02,1.000000009650549915e+00,0.000000000000000000e+00 +7.763332890734484693e+01,4.749243438917927733e+02,6.388988960014664598e-02,6.687498033300252942e+00,-4.782843984473516413e-02,3.591631191924934408e-01,4.563496123041156649e-02,1.000000009705897863e+00,0.000000000000000000e+00 +7.763482423488740380e+01,4.749343324561747295e+02,6.341178753152601488e-02,6.688035099804652717e+00,-4.766177317806849500e-02,3.606584467495654867e-01,4.563496123041156649e-02,1.000000009755038333e+00,0.000000000000000000e+00 +7.763631944235129367e+01,4.749443211001016039e+02,6.293535023026830544e-02,6.688574359006148384e+00,-4.749510651140182588e-02,3.621536542280433535e-01,4.563496123041156649e-02,1.000000009613438490e+00,0.000000000000000000e+00 +7.763781452926566828e+01,4.749543098232959437e+02,6.246057770960788957e-02,6.689115810195579215e+00,-4.732843984473515675e-02,3.636487411567951300e-01,4.563496123041156649e-02,1.000000009885706032e+00,0.000000000000000000e+00 +7.763930949516007729e+01,4.749642986254803532e+02,6.198746998273288455e-02,6.689659452661153693e+00,-4.716177317806848762e-02,3.651437070659837580e-01,4.563496123041156649e-02,1.000000009581543114e+00,0.000000000000000000e+00 +7.764080433956445404e+01,4.749742875063772658e+02,6.151602706278518073e-02,6.690205285688454850e+00,-4.699510651140181849e-02,3.666385514846839389e-01,4.563496123041156649e-02,1.000000009692093572e+00,0.000000000000000000e+00 +7.764229906200912978e+01,4.749842764657092857e+02,6.104624896286040686e-02,6.690753308560442036e+00,-4.682843984473514937e-02,3.681332739438456514e-01,4.563496123041156649e-02,1.000000010011247609e+00,0.000000000000000000e+00 +7.764379366202483368e+01,4.749942655031989034e+02,6.057813569600795783e-02,6.691303520557457141e+00,-4.666177317806848024e-02,3.696278739745055830e-01,4.563496123041156649e-02,1.000000009531596845e+00,0.000000000000000000e+00 +7.764528813914267857e+01,4.750042546185686660e+02,6.011168727523098082e-02,6.691855920957228143e+00,-4.649510651140181111e-02,3.711223511065910308e-01,4.563496123041156649e-02,1.000000009626435871e+00,0.000000000000000000e+00 +7.764678249289417522e+01,4.750142438115411210e+02,5.964690371348638220e-02,6.692410509034870891e+00,-4.632843984473514198e-02,3.726167048724793318e-01,4.563496123041156649e-02,1.000000009675440671e+00,0.000000000000000000e+00 +7.764827672281126070e+01,4.750242330818387586e+02,5.918378502368480676e-02,6.692967284062896205e+00,-4.616177317806847286e-02,3.741109348040195792e-01,4.563496123041156649e-02,1.000000009848384774e+00,0.000000000000000000e+00 +7.764977082842624156e+01,4.750342224291841262e+02,5.872233121869066541e-02,6.693526245311212541e+00,-4.599510651140180373e-02,3.756050404337147319e-01,4.563496123041156649e-02,1.000000009911704568e+00,0.000000000000000000e+00 +7.765126480927183650e+01,4.750442118532997142e+02,5.826254231132212136e-02,6.694087392047130436e+00,-4.582843984473513460e-02,3.770990212941202624e-01,4.563496123041156649e-02,1.000000009626608843e+00,0.000000000000000000e+00 +7.765275866488117629e+01,4.750542013539080131e+02,5.780441831435109007e-02,6.694650723535366055e+00,-4.566177317806846547e-02,3.785928769178377729e-01,4.563496123041156649e-02,1.000000009544809831e+00,0.000000000000000000e+00 +7.765425239478777542e+01,4.750641909307315700e+02,5.734795924050323235e-02,6.695216239038044748e+00,-4.549510651140179635e-02,3.800866068386972163e-01,4.563496123041156649e-02,1.000000009815273039e+00,0.000000000000000000e+00 +7.765574599852557469e+01,4.750741805834928755e+02,5.689316510245796821e-02,6.695783937814706377e+00,-4.532843984473512722e-02,3.815802105911563769e-01,4.563496123041156649e-02,1.000000009785154020e+00,0.000000000000000000e+00 +7.765723947562891283e+01,4.750841703119144768e+02,5.644003591284847687e-02,6.696353819122309758e+00,-4.516177317806845809e-02,3.830736877091046044e-01,4.563496123041156649e-02,1.000000009592586725e+00,0.000000000000000000e+00 +7.765873282563252644e+01,4.750941601157188643e+02,5.598857168426166903e-02,6.696925882215235326e+00,-4.499510651140178896e-02,3.845670377270456464e-01,4.563496123041156649e-02,1.000000009769020703e+00,0.000000000000000000e+00 +7.766022604807157848e+01,4.751041499946285285e+02,5.553877242923822150e-02,6.697500126345289573e+00,-4.482843984473511983e-02,3.860602601806861767e-01,4.563496123041156649e-02,1.000000010044251653e+00,0.000000000000000000e+00 +7.766171914248162977e+01,4.751141399483660166e+02,5.509063816027256338e-02,6.698076550761710379e+00,-4.466177317806845071e-02,3.875533546057398637e-01,4.563496123041156649e-02,1.000000009345818563e+00,0.000000000000000000e+00 +7.766321210839866751e+01,4.751241299766538191e+02,5.464416888981286219e-02,6.698655154711170567e+00,-4.449510651140178158e-02,3.890463205367310495e-01,4.563496123041156649e-02,1.000000009783591270e+00,0.000000000000000000e+00 +7.766470494535907676e+01,4.751341200792143695e+02,5.419936463026104462e-02,6.699235937437779675e+00,-4.432843984473511245e-02,3.905391575117472813e-01,4.563496123041156649e-02,1.000000009876566676e+00,0.000000000000000000e+00 +7.766619765289966892e+01,4.751441102557702152e+02,5.375622539397278271e-02,6.699818898183092841e+00,-4.416177317806844332e-02,3.920318650670793770e-01,4.563496123041156649e-02,1.000000009732090467e+00,0.000000000000000000e+00 +7.766769023055765331e+01,4.751541005060438465e+02,5.331475119325750078e-02,6.700404036186111689e+00,-4.399510651140177420e-02,3.935244427395941935e-01,4.563496123041156649e-02,1.000000009452713723e+00,0.000000000000000000e+00 +7.766918267787067975e+01,4.751640908297577539e+02,5.287494204037836848e-02,6.700991350683288772e+00,-4.382843984473510507e-02,3.950168900667286875e-01,4.563496123041156649e-02,1.000000009933610157e+00,0.000000000000000000e+00 +7.767067499437679601e+01,4.751740812266344278e+02,5.243679794755230772e-02,6.701580840908532011e+00,-4.366177317806843594e-02,3.965092065876739680e-01,4.563496123041156649e-02,1.000000010071194101e+00,0.000000000000000000e+00 +7.767216717961449035e+01,4.751840716963963587e+02,5.200031892694999269e-02,6.702172506093210913e+00,-4.349510651140176681e-02,3.980013918403935702e-01,4.563496123041156649e-02,1.000000009154720759e+00,0.000000000000000000e+00 +7.767365923312264897e+01,4.751940622387660369e+02,5.156550499069583599e-02,6.702766345466158349e+00,-4.332843984473509769e-02,3.994934453622114301e-01,4.563496123041156649e-02,1.000000010059855615e+00,0.000000000000000000e+00 +7.767515115444059859e+01,4.752040528534659529e+02,5.113235615086800245e-02,6.703362358253673214e+00,-4.316177317806842856e-02,4.009853666951641582e-01,4.563496123041156649e-02,1.000000009672310730e+00,0.000000000000000000e+00 +7.767664294310806383e+01,4.752140435402185972e+02,5.070087241949840923e-02,6.703960543679531092e+00,-4.299510651140175943e-02,4.024771553770650212e-01,4.563496123041156649e-02,1.000000009661000888e+00,0.000000000000000000e+00 +7.767813459866522408e+01,4.752240342987464601e+02,5.027105380857271183e-02,6.704560900964981585e+00,-4.282843984473509030e-02,4.039688109486417322e-01,4.563496123041156649e-02,1.000000009694779424e+00,0.000000000000000000e+00 +7.767962612065267081e+01,4.752340251287719752e+02,4.984290033003031112e-02,6.705163429328756308e+00,-4.266177317806842118e-02,4.054603329505536702e-01,4.563496123041156649e-02,1.000000009836839565e+00,0.000000000000000000e+00 +7.768111750861142184e+01,4.752440160300176331e+02,4.941641199576436716e-02,6.705768127987072447e+00,-4.249510651140175205e-02,4.069517209239814082e-01,4.563496123041156649e-02,1.000000009746129237e+00,0.000000000000000000e+00 +7.768260876208293553e+01,4.752540070022059240e+02,4.899158881762177148e-02,6.706374996153637191e+00,-4.232843984473508292e-02,4.084429744100250836e-01,4.563496123041156649e-02,1.000000009875276819e+00,0.000000000000000000e+00 +7.768409988060906812e+01,4.752639980450593384e+02,4.856843080740317481e-02,6.706984033039651294e+00,-4.216177317806841379e-02,4.099340929508892839e-01,4.563496123041156649e-02,1.000000009474090623e+00,0.000000000000000000e+00 +7.768559086373214484e+01,4.752739891583003100e+02,4.814693797686295934e-02,6.707595237853814396e+00,-4.199510651140174466e-02,4.114250760880906466e-01,4.563496123041156649e-02,1.000000009784902444e+00,0.000000000000000000e+00 +7.768708171099490301e+01,4.752839803416513291e+02,4.772711033770926647e-02,6.708208609802327693e+00,-4.182843984473507554e-02,4.129159233654300376e-01,4.563496123041156649e-02,1.000000010047798149e+00,0.000000000000000000e+00 +7.768857242194050627e+01,4.752939715948348294e+02,4.730894790160396907e-02,6.708824148088901040e+00,-4.166177317806840641e-02,4.144066343260083274e-01,4.563496123041156649e-02,1.000000009497711062e+00,0.000000000000000000e+00 +7.769006299611255884e+01,4.753039629175733012e+02,4.689245068016269224e-02,6.709441851914755617e+00,-4.149510651140173728e-02,4.158972085122203399e-01,4.563496123041156649e-02,1.000000009763027053e+00,0.000000000000000000e+00 +7.769155343305510542e+01,4.753139543095892350e+02,4.647761868495480647e-02,6.710061720478626590e+00,-4.132843984473506815e-02,4.173876454693237759e-01,4.563496123041156649e-02,1.000000009669467671e+00,0.000000000000000000e+00 +7.769304373231263128e+01,4.753239457706050644e+02,4.606445192750342060e-02,6.710683752976771110e+00,-4.116177317806839903e-02,4.188779447412627199e-01,4.563496123041156649e-02,1.000000009637229015e+00,0.000000000000000000e+00 +7.769453389343004801e+01,4.753339373003432229e+02,4.565295041928538883e-02,6.711307948602970086e+00,-4.099510651140172990e-02,4.203681058730455167e-01,4.563496123041156649e-02,1.000000010081870672e+00,0.000000000000000000e+00 +7.769602391595272195e+01,4.753439288985262010e+02,4.524311417173130373e-02,6.711934306548533513e+00,-4.082843984473506077e-02,4.218581284107388307e-01,4.563496123041156649e-02,1.000000009414342195e+00,0.000000000000000000e+00 +7.769751379942644576e+01,4.753539205648764323e+02,4.483494319622551016e-02,6.712562826002305805e+00,-4.066177317806839164e-02,4.233480118984819796e-01,4.563496123041156649e-02,1.000000010041426579e+00,0.000000000000000000e+00 +7.769900354339745263e+01,4.753639122991164072e+02,4.442843750410609138e-02,6.713193506150666678e+00,-4.049510651140172252e-02,4.248377558844417812e-01,4.563496123041156649e-02,1.000000009564223413e+00,0.000000000000000000e+00 +7.770049314741241631e+01,4.753739041009685593e+02,4.402359710666486903e-02,6.713826346177540927e+00,-4.032843984473505339e-02,4.263273599136538361e-01,4.563496123041156649e-02,1.000000009580563010e+00,0.000000000000000000e+00 +7.770198261101846526e+01,4.753838959701553222e+02,4.362042201514741008e-02,6.714461345264397529e+00,-4.016177317806838426e-02,4.278168235339780412e-01,4.563496123041156649e-02,1.000000010083714530e+00,0.000000000000000000e+00 +7.770347193376318273e+01,4.753938879063991862e+02,4.321891224075302684e-02,6.715098502590257645e+00,-3.999510651140171513e-02,4.293061462937091677e-01,4.563496123041156649e-02,1.000000009459956152e+00,0.000000000000000000e+00 +7.770496111519456406e+01,4.754038799094225283e+02,4.281906779463476309e-02,6.715737817331699056e+00,-3.982843984473504600e-02,4.307953277391849412e-01,4.563496123041156649e-02,1.000000010095967395e+00,0.000000000000000000e+00 +7.770645015486108775e+01,4.754138719789478387e+02,4.242088868789941486e-02,6.716379288662857050e+00,-3.966177317806837688e-02,4.322843674207448861e-01,4.563496123041156649e-02,1.000000009567761250e+00,0.000000000000000000e+00 +7.770793905231165866e+01,4.754238641146975510e+02,4.202437493160750964e-02,6.717022915755434198e+00,-3.949510651140170775e-02,4.337732648855675555e-01,4.563496123041156649e-02,1.000000009853044824e+00,0.000000000000000000e+00 +7.770942780709565056e+01,4.754338563163941558e+02,4.162952653677332027e-02,6.717668697778699460e+00,-3.932843984473503862e-02,4.352620196842261202e-01,4.563496123041156649e-02,1.000000009319514493e+00,0.000000000000000000e+00 +7.771091641876286360e+01,4.754438485837600297e+02,4.123634351436485795e-02,6.718316633899497070e+00,-3.916177317806836949e-02,4.367506313653145011e-01,4.563496123041156649e-02,1.000000010338030654e+00,0.000000000000000000e+00 +7.771240488686356684e+01,4.754538409165176063e+02,4.084482587530386538e-02,6.718966723282247422e+00,-3.899510651140170037e-02,4.382390994814080454e-01,4.563496123041156649e-02,1.000000009262270284e+00,0.000000000000000000e+00 +7.771389321094848412e+01,4.754638333143893760e+02,4.045497363046584444e-02,6.719618965088956841e+00,-3.882843984473503124e-02,4.397274235801078013e-01,4.563496123041156649e-02,1.000000010058800237e+00,0.000000000000000000e+00 +7.771538139056877981e+01,4.754738257770977157e+02,4.006678679068001458e-02,6.720273358479214032e+00,-3.866177317806836211e-02,4.412156032153731200e-01,4.563496123041156649e-02,1.000000009472593376e+00,0.000000000000000000e+00 +7.771686942527608721e+01,4.754838183043650588e+02,3.968026536672934756e-02,6.720929902610203399e+00,-3.849510651140169298e-02,4.427036379367745300e-01,4.563496123041156649e-02,1.000000010259808558e+00,0.000000000000000000e+00 +7.771835731462249441e+01,4.754938108959138390e+02,3.929540936935054657e-02,6.721588596636702384e+00,-3.832843984473502386e-02,4.441915272984407470e-01,4.563496123041156649e-02,1.000000009155303848e+00,0.000000000000000000e+00 +7.771984505816053002e+01,4.755038035514665467e+02,3.891221880923406012e-02,6.722249439711092123e+00,-3.816177317806835473e-02,4.456792708501000622e-01,4.563496123041156649e-02,1.000000010111490312e+00,0.000000000000000000e+00 +7.772133265544320579e+01,4.755137962707455586e+02,3.853069369702406821e-02,6.722912430983354781e+00,-3.799510651140168560e-02,4.471668681478201957e-01,4.563496123041156649e-02,1.000000009854133509e+00,0.000000000000000000e+00 +7.772282010602398827e+01,4.755237890534733083e+02,3.815083404331849615e-02,6.723577569601086878e+00,-3.782843984473501647e-02,4.486543187432578406e-01,4.563496123041156649e-02,1.000000009518233979e+00,0.000000000000000000e+00 +7.772430740945679872e+01,4.755337818993721726e+02,3.777263985866899376e-02,6.724244854709496622e+00,-3.766177317806834735e-02,4.501416221902195813e-01,4.563496123041156649e-02,1.000000009834491665e+00,0.000000000000000000e+00 +7.772579456529601316e+01,4.755437748081646419e+02,3.739611115358095622e-02,6.724914285451411011e+00,-3.749510651140167822e-02,4.516287780440610966e-01,4.563496123041156649e-02,1.000000009521388122e+00,0.000000000000000000e+00 +7.772728157309649077e+01,4.755537677795730929e+02,3.702124793851351708e-02,6.725585860967282059e+00,-3.732843984473500909e-02,4.531157858586956633e-01,4.563496123041156649e-02,1.000000010104592718e+00,0.000000000000000000e+00 +7.772876843241354550e+01,4.755637608133199592e+02,3.664805022387954136e-02,6.726259580395188564e+00,-3.716177317806833996e-02,4.546026451907699273e-01,4.563496123041156649e-02,1.000000009490365160e+00,0.000000000000000000e+00 +7.773025514280294601e+01,4.755737539091276176e+02,3.627651802004563247e-02,6.726935442870844106e+00,-3.699510651140167083e-02,4.560893555942830968e-01,4.563496123041156649e-02,1.000000010000078321e+00,0.000000000000000000e+00 +7.773174170382094417e+01,4.755837470667185585e+02,3.590665133733212527e-02,6.727613447527597046e+00,-3.682843984473500171e-02,4.575759166271526346e-01,4.563496123041156649e-02,1.000000009531277767e+00,0.000000000000000000e+00 +7.773322811502426077e+01,4.755937402858151586e+02,3.553845018601309996e-02,6.728293593496440295e+00,-3.666177317806833258e-02,4.590623278446383515e-01,4.563496123041156649e-02,1.000000009996226957e+00,0.000000000000000000e+00 +7.773471437597007139e+01,4.756037335661397947e+02,3.517191457631636820e-02,6.728975879906011315e+00,-3.649510651140166345e-02,4.605485888053116872e-01,4.563496123041156649e-02,1.000000009685521052e+00,0.000000000000000000e+00 +7.773620048621603473e+01,4.756137269074149003e+02,3.480704451842346614e-02,6.729660305882601001e+00,-3.632843984473499432e-02,4.620346990656734598e-01,4.563496123041156649e-02,1.000000009699821835e+00,0.000000000000000000e+00 +7.773768644532027849e+01,4.756237203093629091e+02,3.444384002246968224e-02,6.730346870550154570e+00,-3.616177317806832520e-02,4.635206581843316354e-01,4.563496123041156649e-02,1.000000009527641787e+00,0.000000000000000000e+00 +7.773917225284139931e+01,4.756337137717061978e+02,3.408230109854402251e-02,6.731035573030278663e+00,-3.599510651140165607e-02,4.650064657196064100e-01,4.563496123041156649e-02,1.000000010262640071e+00,0.000000000000000000e+00 +7.774065790833846279e+01,4.756437072941671431e+02,3.372242775668923831e-02,6.731726412442244900e+00,-3.582843984473498694e-02,4.664921212319163013e-01,4.563496123041156649e-02,1.000000009372957077e+00,0.000000000000000000e+00 +7.774214341137101769e+01,4.756537008764681786e+02,3.336422000690181244e-02,6.732419387902996988e+00,-3.566177317806831781e-02,4.679776242783928453e-01,4.563496123041156649e-02,1.000000009956879543e+00,0.000000000000000000e+00 +7.774362876149908175e+01,4.756636945183317380e+02,3.300767785913195917e-02,6.733114498527149827e+00,-3.549510651140164869e-02,4.694629744212459599e-01,4.563496123041156649e-02,1.000000009474173446e+00,0.000000000000000000e+00 +7.774511395828315585e+01,4.756736882194801979e+02,3.265280132328363116e-02,6.733811743427001062e+00,-3.532843984473497956e-02,4.709481712193888114e-01,4.563496123041156649e-02,1.000000010211566925e+00,0.000000000000000000e+00 +7.774659900128420986e+01,4.756836819796359350e+02,3.229959040921450558e-02,6.734511121712530191e+00,-3.516177317806831043e-02,4.724332142356086894e-01,4.563496123041156649e-02,1.000000009619680386e+00,0.000000000000000000e+00 +7.774808389006369680e+01,4.756936757985213262e+02,3.194804512673599800e-02,6.735212632491408336e+00,-3.499510651140164130e-02,4.739181030293855845e-01,4.563496123041156649e-02,1.000000009575661153e+00,0.000000000000000000e+00 +7.774956862418356707e+01,4.757036696758588050e+02,3.159816548561324850e-02,6.735916274868997355e+00,-3.482843984473497218e-02,4.754028371634670402e-01,4.563496123041156649e-02,1.000000009938986523e+00,0.000000000000000000e+00 +7.775105320320621161e+01,4.757136636113707482e+02,3.124995149556514251e-02,6.736622047948358727e+00,-3.466177317806830305e-02,4.768874162008726603e-01,4.563496123041156649e-02,1.000000009356405428e+00,0.000000000000000000e+00 +7.775253762669454716e+01,4.757236576047795893e+02,3.090340316626428996e-02,6.737329950830257985e+00,-3.449510651140163392e-02,4.783718397030950475e-01,4.563496123041156649e-02,1.000000010097944703e+00,0.000000000000000000e+00 +7.775402189421194521e+01,4.757336516558076482e+02,3.055852050733703570e-02,6.738039982613166501e+00,-3.432843984473496479e-02,4.798561072354796120e-01,4.563496123041156649e-02,1.000000009996575123e+00,0.000000000000000000e+00 +7.775550600532227463e+01,4.757436457641773586e+02,3.021530352836344913e-02,6.738752142393271249e+00,-3.416177317806829566e-02,4.813402183606391160e-01,4.563496123041156649e-02,1.000000009702388448e+00,0.000000000000000000e+00 +7.775698995958987325e+01,4.757536399296110972e+02,2.987375223887733799e-02,6.739466429264474812e+00,-3.399510651140162654e-02,4.828241726426365510e-01,4.563496123041156649e-02,1.000000009459395489e+00,0.000000000000000000e+00 +7.775847375657959049e+01,4.757636341518312406e+02,2.953386664836623807e-02,6.740182842318401590e+00,-3.382843984473495741e-02,4.843079696463832295e-01,4.563496123041156649e-02,1.000000009911771182e+00,0.000000000000000000e+00 +7.775995739585673050e+01,4.757736284305601657e+02,2.919564676627141309e-02,6.740901380644403140e+00,-3.366177317806828828e-02,4.857916089382333658e-01,4.563496123041156649e-02,1.000000009682166846e+00,0.000000000000000000e+00 +7.776144087698712326e+01,4.757836227655202492e+02,2.885909260198786172e-02,6.741622043329564384e+00,-3.349510651140161915e-02,4.872750900829858067e-01,4.563496123041156649e-02,1.000000009811234714e+00,0.000000000000000000e+00 +7.776292419953705348e+01,4.757936171564338679e+02,2.852420416486431062e-02,6.742344829458705391e+00,-3.332843984473495003e-02,4.887584126474726065e-01,4.563496123041156649e-02,1.000000009721128125e+00,0.000000000000000000e+00 +7.776440736307331747e+01,4.758036116030234552e+02,2.819098146420321790e-02,6.743069738114388478e+00,-3.316177317806828090e-02,4.902415761981588904e-01,4.563496123041156649e-02,1.000000010042066512e+00,0.000000000000000000e+00 +7.776589036716320891e+01,4.758136061050113312e+02,2.785942450926076966e-02,6.743796768376921769e+00,-3.299510651140161177e-02,4.917245803029358098e-01,4.563496123041156649e-02,1.000000009381398769e+00,0.000000000000000000e+00 +7.776737321137449044e+01,4.758236006621198726e+02,2.752953330924687650e-02,6.744525919324365404e+00,-3.282843984473494264e-02,4.932074245281215519e-01,4.563496123041156649e-02,1.000000009977883852e+00,0.000000000000000000e+00 +7.776885589527542209e+01,4.758335952740714561e+02,2.720130787332518743e-02,6.745257190032533323e+00,-3.266177317806827352e-02,4.946901084438474760e-01,4.563496123041156649e-02,1.000000010027848774e+00,0.000000000000000000e+00 +7.777033841843477546e+01,4.758435899405885152e+02,2.687474821061307598e-02,6.745990579575003032e+00,-3.249510651140160439e-02,4.961726316180646856e-01,4.563496123041156649e-02,1.000000009339299334e+00,0.000000000000000000e+00 +7.777182078042180535e+01,4.758535846613933700e+02,2.654985433018164018e-02,6.746726087023116492e+00,-3.232843984473493526e-02,4.976549936189352819e-01,4.563496123041156649e-02,1.000000010142206408e+00,0.000000000000000000e+00 +7.777330298080626392e+01,4.758635794362083402e+02,2.622662624105571300e-02,6.747463711445984558e+00,-3.216177317806826613e-02,4.991371940184233247e-01,4.563496123041156649e-02,1.000000009408588575e+00,0.000000000000000000e+00 +7.777478501915840070e+01,4.758735742647558595e+02,2.590506395221385191e-02,6.748203451910496753e+00,-3.199510651140159700e-02,5.006192323845018999e-01,4.563496123041156649e-02,1.000000010170894793e+00,0.000000000000000000e+00 +7.777626689504896262e+01,4.758835691467583047e+02,2.558516747258834240e-02,6.748945307481319489e+00,-3.182843984473492788e-02,5.021011082901368772e-01,4.563496123041156649e-02,1.000000009393041678e+00,0.000000000000000000e+00 +7.777774860804920820e+01,4.758935640819379955e+02,2.526693681106519790e-02,6.749689277220907613e+00,-3.166177317806825875e-02,5.035828213042941037e-01,4.563496123041156649e-02,1.000000010102428227e+00,0.000000000000000000e+00 +7.777923015773087911e+01,4.759035590700173088e+02,2.495037197648415639e-02,6.750435360189502632e+00,-3.149510651140158962e-02,5.050643710009257159e-01,4.563496123041156649e-02,1.000000009254530919e+00,0.000000000000000000e+00 +7.778071154366621442e+01,4.759135541107186214e+02,2.463547297763869076e-02,6.751183555445144258e+00,-3.132843984473492049e-02,5.065457569499742796e-01,4.563496123041156649e-02,1.000000010276604012e+00,0.000000000000000000e+00 +7.778219276542797900e+01,4.759235492037642530e+02,2.432223982327599149e-02,6.751933862043668633e+00,-3.116177317806825484e-02,5.080269787269618975e-01,4.563496123041156649e-02,1.000000009711550675e+00,0.000000000000000000e+00 +7.778367382258942087e+01,4.759335443488765804e+02,2.401067252209698050e-02,6.752686279038720762e+00,-3.099510651140158918e-02,5.095080359027928107e-01,4.563496123041156649e-02,1.000000009766532028e+00,0.000000000000000000e+00 +7.778515471472431386e+01,4.759435395457779805e+02,2.370077108275630423e-02,6.753440805481751852e+00,-3.082843984473492352e-02,5.109889280521447974e-01,4.563496123041156649e-02,1.000000009406158075e+00,0.000000000000000000e+00 +7.778663544140691499e+01,4.759535347941908299e+02,2.339253551386233712e-02,6.754197440422029075e+00,-3.066177317806825786e-02,5.124696547486673470e-01,4.563496123041156649e-02,1.000000010022596308e+00,0.000000000000000000e+00 +7.778811600221199285e+01,4.759635300938374485e+02,2.308596582397717811e-02,6.754956182906638240e+00,-3.049510651140159220e-02,5.139502155685774509e-01,4.563496123041156649e-02,1.000000010168980769e+00,0.000000000000000000e+00 +7.778959639671481341e+01,4.759735254444401562e+02,2.278106202161665067e-02,6.755717031980491782e+00,-3.032843984473492654e-02,5.154306100864567419e-01,4.563496123041156649e-02,1.000000009204490947e+00,0.000000000000000000e+00 +7.779107662449118266e+01,4.759835208457213298e+02,2.247782411525030624e-02,6.756479986686330541e+00,-3.016177317806826089e-02,5.169108378764465384e-01,4.563496123041156649e-02,1.000000010134009854e+00,0.000000000000000000e+00 +7.779255668511737554e+01,4.759935162974033460e+02,2.217625211330142079e-02,6.757245046064727312e+00,-2.999510651140159523e-02,5.183908985176450823e-01,4.563496123041156649e-02,1.000000009473045237e+00,0.000000000000000000e+00 +7.779403657817022122e+01,4.760035117992085247e+02,2.187634602414699134e-02,6.758012209154098393e+00,-2.982843984473492957e-02,5.198707915845028893e-01,4.563496123041156649e-02,1.000000010221524294e+00,0.000000000000000000e+00 +7.779551630322701783e+01,4.760135073508592427e+02,2.157810585611774634e-02,6.758781474990700922e+00,-2.966177317806826391e-02,5.213505166564211812e-01,4.563496123041156649e-02,1.000000009292610015e+00,0.000000000000000000e+00 +7.779699585986558930e+01,4.760235029520778198e+02,2.128153161749813185e-02,6.759552842608644418e+00,-2.949510651140159825e-02,5.228300733087450913e-01,4.563496123041156649e-02,1.000000010087042757e+00,0.000000000000000000e+00 +7.779847524766428535e+01,4.760334986025866328e+02,2.098662331652632190e-02,6.760326311039889013e+00,-2.932843984473493260e-02,5.243094611223643176e-01,4.563496123041156649e-02,1.000000009511031074e+00,0.000000000000000000e+00 +7.779995446620195310e+01,4.760434943021080016e+02,2.069338096139421504e-02,6.761101879314257879e+00,-2.916177317806826694e-02,5.257886796741049196e-01,4.563496123041156649e-02,1.000000010149159957e+00,0.000000000000000000e+00 +7.780143351505796545e+01,4.760534900503642461e+02,2.040180456024743086e-02,6.761879546459435453e+00,-2.899510651140160128e-02,5.272677285451309315e-01,4.563496123041156649e-02,1.000000009712083804e+00,0.000000000000000000e+00 +7.780291239381220691e+01,4.760634858470777431e+02,2.011189412118531347e-02,6.762659311500978099e+00,-2.882843984473493562e-02,5.287466073137355727e-01,4.563496123041156649e-02,1.000000009561081482e+00,0.000000000000000000e+00 +7.780439110204507358e+01,4.760734816919708123e+02,1.982364965226093151e-02,6.763441173462314104e+00,-2.866177317806826996e-02,5.302253155607419277e-01,4.563496123041156649e-02,1.000000009837167747e+00,0.000000000000000000e+00 +7.780586963933748734e+01,4.760834775847657738e+02,1.953707116148107464e-02,6.764225131364751675e+00,-2.849510651140160430e-02,5.317038528676987230e-01,4.563496123041156649e-02,1.000000009865772421e+00,0.000000000000000000e+00 +7.780734800527088169e+01,4.760934735251850043e+02,1.925215865680625707e-02,6.765011184227484264e+00,-2.832843984473493865e-02,5.331822188156754017e-01,4.563496123041156649e-02,1.000000009781954802e+00,0.000000000000000000e+00 +7.780882619942720169e+01,4.761034695129508236e+02,1.896891214615071750e-02,6.765799331067594125e+00,-2.816177317806827299e-02,5.346604129864602761e-01,4.563496123041156649e-02,1.000000009717750160e+00,0.000000000000000000e+00 +7.781030422138893243e+01,4.761134655477855517e+02,1.868733163738241221e-02,6.766589570900057637e+00,-2.799510651140160733e-02,5.361384349625568646e-01,4.563496123041156649e-02,1.000000009802547885e+00,0.000000000000000000e+00 +7.781178207073907060e+01,4.761234616294115085e+02,1.840741713832302201e-02,6.767381902737750643e+00,-2.782843984473494167e-02,5.376162843271807823e-01,4.563496123041156649e-02,1.000000009756772501e+00,0.000000000000000000e+00 +7.781325974706112447e+01,4.761334577575510707e+02,1.812916865674794875e-02,6.768176325591453768e+00,-2.766177317806827601e-02,5.390939606636562242e-01,4.563496123041156649e-02,1.000000009704156811e+00,0.000000000000000000e+00 +7.781473724993914232e+01,4.761434539319265582e+02,1.785258620038631880e-02,6.768972838469856868e+00,-2.749510651140161036e-02,5.405714635560129322e-01,4.563496123041156649e-02,1.000000010173107912e+00,0.000000000000000000e+00 +7.781621457895768401e+01,4.761534501522602909e+02,1.757766977692097610e-02,6.769771440379564353e+00,-2.732843984473494470e-02,5.420487925895848269e-01,4.563496123041156649e-02,1.000000009247348887e+00,0.000000000000000000e+00 +7.781769173370183523e+01,4.761634464182745887e+02,1.730441939398848911e-02,6.770572130325101412e+00,-2.716177317806827904e-02,5.435259473473993408e-01,4.563496123041156649e-02,1.000000010299236797e+00,0.000000000000000000e+00 +7.781916871375722167e+01,4.761734427296917715e+02,1.703283505917914734e-02,6.771374907308914892e+00,-2.699510651140161338e-02,5.450029274179908345e-01,4.563496123041156649e-02,1.000000009370916265e+00,0.000000000000000000e+00 +7.782064551870996638e+01,4.761834390862341593e+02,1.676291678003695787e-02,6.772179770331385740e+00,-2.682843984473494772e-02,5.464797323845738131e-01,4.563496123041156649e-02,1.000000010238061288e+00,0.000000000000000000e+00 +7.782212214814674667e+01,4.761934354876240718e+02,1.649466456405965231e-02,6.772986718390825445e+00,-2.666177317806828206e-02,5.479563618364661215e-01,4.563496123041156649e-02,1.000000009343164686e+00,0.000000000000000000e+00 +7.782359860165475141e+01,4.762034319335838859e+02,1.622807841869868331e-02,6.773795750483489364e+00,-2.649510651140161641e-02,5.494328153582600516e-01,4.563496123041156649e-02,1.000000010050873023e+00,0.000000000000000000e+00 +7.782507487882169528e+01,4.762134284238358646e+02,1.596315835135921762e-02,6.774606865603574057e+00,-2.632843984473495075e-02,5.509090925400447203e-01,4.563496123041156649e-02,1.000000009612102003e+00,0.000000000000000000e+00 +7.782655097923584719e+01,4.762234249581023278e+02,1.569990436940014653e-02,6.775420062743229721e+00,-2.616177317806828509e-02,5.523851929683800677e-01,4.563496123041156649e-02,1.000000010165399411e+00,0.000000000000000000e+00 +7.782802690248597344e+01,4.762334215361056522e+02,1.543831648013408234e-02,6.776235340892559300e+00,-2.599510651140161943e-02,5.538611162335134175e-01,4.563496123041156649e-02,1.000000009362369546e+00,0.000000000000000000e+00 +7.782950264816139452e+01,4.762434181575681009e+02,1.517839469082735322e-02,6.777052699039628259e+00,-2.582843984473495377e-02,5.553368619227572189e-01,4.563496123041156649e-02,1.000000009745650065e+00,0.000000000000000000e+00 +7.783097821585197096e+01,4.762534148222119939e+02,1.492013900870001013e-02,6.777872136170464579e+00,-2.566177317806828811e-02,5.568124296277086049e-01,4.563496123041156649e-02,1.000000010185083887e+00,0.000000000000000000e+00 +7.783245360514806066e+01,4.762634115297596509e+02,1.466354944092582158e-02,6.778693651269069420e+00,-2.549510651140162246e-02,5.582878189388296164e-01,4.563496123041156649e-02,1.000000009547298285e+00,0.000000000000000000e+00 +7.783392881564058996e+01,4.762734082799333919e+02,1.440862599463227540e-02,6.779517243317419783e+00,-2.532843984473495680e-02,5.597630294454440936e-01,4.563496123041156649e-02,1.000000009960966940e+00,0.000000000000000000e+00 +7.783540384692101100e+01,4.762834050724555368e+02,1.415536867690057876e-02,6.780342911295471175e+00,-2.516177317806829114e-02,5.612380607405509370e-01,4.563496123041156649e-02,1.000000009471316620e+00,0.000000000000000000e+00 +7.783687869858128749e+01,4.762934019070484055e+02,1.390377749476565811e-02,6.781170654181167379e+00,-2.499510651140162548e-02,5.627129124148009254e-01,4.563496123041156649e-02,1.000000010203778045e+00,0.000000000000000000e+00 +7.783835337021395162e+01,4.763033987834342611e+02,1.365385245521615575e-02,6.782000470950441340e+00,-2.482843984473495982e-02,5.641875840625159011e-01,4.563496123041156649e-02,1.000000009380886068e+00,0.000000000000000000e+00 +7.783982786141206134e+01,4.763133957013354802e+02,1.340559356519443503e-02,6.782832360577224939e+00,-2.466177317806829417e-02,5.656620752744587755e-01,4.563496123041156649e-02,1.000000009940839041e+00,0.000000000000000000e+00 +7.784130217176921462e+01,4.763233926604743260e+02,1.315900083159657515e-02,6.783666322033448104e+00,-2.449510651140162851e-02,5.671363856462630082e-01,4.563496123041156649e-02,1.000000009918369459e+00,0.000000000000000000e+00 +7.784277630087953526e+01,4.763333896605731184e+02,1.291407426127237461e-02,6.784502354289050352e+00,-2.432843984473496285e-02,5.686105147712029462e-01,4.563496123041156649e-02,1.000000009796056188e+00,0.000000000000000000e+00 +7.784425024833770124e+01,4.763433867013541771e+02,1.267081386102534950e-02,6.785340456311981683e+00,-2.416177317806829719e-02,5.700844622438040465e-01,4.563496123041156649e-02,1.000000009646515808e+00,0.000000000000000000e+00 +7.784572401373891637e+01,4.763533837825397654e+02,1.242921963761273348e-02,6.786180627068208793e+00,-2.399510651140163153e-02,5.715582276592391375e-01,4.563496123041156649e-02,1.000000009948857960e+00,0.000000000000000000e+00 +7.784719759667893868e+01,4.763633809038522031e+02,1.218929159774547605e-02,6.787022865521720405e+00,-2.382843984473496587e-02,5.730318106139281609e-01,4.563496123041156649e-02,1.000000009544213642e+00,0.000000000000000000e+00 +7.784867099675406621e+01,4.763733780650138101e+02,1.195102974808824603e-02,6.787867170634533487e+00,-2.366177317806830022e-02,5.745052107031252131e-01,4.563496123041156649e-02,1.000000010134568296e+00,0.000000000000000000e+00 +7.785014421356115122e+01,4.763833752657468494e+02,1.171443409525942808e-02,6.788713541366695914e+00,-2.349510651140163456e-02,5.759784275251348395e-01,4.563496123041156649e-02,1.000000009328887218e+00,0.000000000000000000e+00 +7.785161724669755756e+01,4.763933725057736410e+02,1.147950464583112271e-02,6.789561976676295352e+00,-2.332843984473496890e-02,5.774514606752824131e-01,4.563496123041156649e-02,1.000000010053478716e+00,0.000000000000000000e+00 +7.785309009576121753e+01,4.764033697848165048e+02,1.124624140632914972e-02,6.790412475519459257e+00,-2.316177317806830324e-02,5.789243097537483118e-01,4.563496123041156649e-02,1.000000009912089149e+00,0.000000000000000000e+00 +7.785456276035060341e+01,4.764133671025977605e+02,1.101464438323304131e-02,6.791265036850366421e+00,-2.299510651140163758e-02,5.803969743577281903e-01,4.563496123041156649e-02,1.000000009780757759e+00,0.000000000000000000e+00 +7.785603524006472753e+01,4.764233644588396146e+02,1.078471358297604897e-02,6.792119659621246974e+00,-2.282843984473497193e-02,5.818694540862539011e-01,4.563496123041156649e-02,1.000000009715008575e+00,0.000000000000000000e+00 +7.785750753450315642e+01,4.764333618532644437e+02,1.055644901194514006e-02,6.792976342782389487e+00,-2.266177317806830627e-02,5.833417485389855717e-01,4.563496123041156649e-02,1.000000009768367226e+00,0.000000000000000000e+00 +7.785897964326599663e+01,4.764433592855945108e+02,1.032985067648099602e-02,6.793835085282146302e+00,-2.249510651140164061e-02,5.848138573162093845e-01,4.563496123041156649e-02,1.000000009992666250e+00,0.000000000000000000e+00 +7.786045156595390893e+01,4.764533567555521358e+02,1.010491858287801588e-02,6.794695886066938861e+00,-2.232843984473497495e-02,5.862857800188358004e-01,4.563496123041156649e-02,1.000000009617224350e+00,0.000000000000000000e+00 +7.786192330216810831e+01,4.764633542628595819e+02,9.881652737384314517e-03,6.795558744081263036e+00,-2.216177317806830929e-02,5.877575162471897485e-01,4.563496123041156649e-02,1.000000009919795652e+00,0.000000000000000000e+00 +7.786339485151034978e+01,4.764733518072391121e+02,9.660053146201719176e-03,6.796423658267692680e+00,-2.199510651140164363e-02,5.892290656040263253e-01,4.563496123041156649e-02,1.000000009715864557e+00,0.000000000000000000e+00 +7.786486621358294258e+01,4.764833493884131030e+02,9.440119815485774682e-03,6.797290627566887622e+00,-2.182843984473497798e-02,5.907004276909076923e-01,4.563496123041156649e-02,1.000000009869516537e+00,0.000000000000000000e+00 +7.786633738798873594e+01,4.764933470061037610e+02,9.221852751345739965e-03,6.798159650917596331e+00,-2.166177317806831232e-02,5.921716021112185535e-01,4.563496123041156649e-02,1.000000009602069584e+00,0.000000000000000000e+00 +7.786780837433114755e+01,4.765033446600334059e+02,9.005251959844588067e-03,6.799030727256663020e+00,-2.149510651140164666e-02,5.936425884677497544e-01,4.563496123041156649e-02,1.000000009774448362e+00,0.000000000000000000e+00 +7.786927917221413509e+01,4.765133423499243577e+02,8.790317446999007869e-03,6.799903855519031204e+00,-2.132843984473498100e-02,5.951133863651111300e-01,4.563496123041156649e-02,1.000000010014705731e+00,0.000000000000000000e+00 +7.787074978124221047e+01,4.765233400754988224e+02,8.577049218779404099e-03,6.800779034637750797e+00,-2.116177317806831534e-02,5.965839954079185103e-01,4.563496123041156649e-02,1.000000009948701418e+00,0.000000000000000000e+00 +7.787222020102045406e+01,4.765333378364791770e+02,8.365447281109893857e-03,6.801656263543982561e+00,-2.099510651140164968e-02,5.980544152007915004e-01,4.563496123041156649e-02,1.000000009610745533e+00,0.000000000000000000e+00 +7.787369043115448619e+01,4.765433356325876275e+02,8.155511639868306614e-03,6.802535541167002542e+00,-2.082843984473498403e-02,5.995246453489549987e-01,4.563496123041156649e-02,1.000000009855541494e+00,0.000000000000000000e+00 +7.787516047125049568e+01,4.765533334635464939e+02,7.947242300886189423e-03,6.803416866434207400e+00,-2.066177317806831837e-02,6.009946854594458987e-01,4.563496123041156649e-02,1.000000009481815777e+00,0.000000000000000000e+00 +7.787663032091519710e+01,4.765633313290780961e+02,7.740639269948802574e-03,6.804300238271121515e+00,-2.049510651140165271e-02,6.024645351380911729e-01,4.563496123041156649e-02,1.000000010163336395e+00,0.000000000000000000e+00 +7.787809997975590193e+01,4.765733292289046403e+02,7.535702552795117866e-03,6.805185655601399652e+00,-2.032843984473498705e-02,6.039341939937348247e-01,4.563496123041156649e-02,1.000000009872254125e+00,0.000000000000000000e+00 +7.787956944738046161e+01,4.765833271627484464e+02,7.332432155117822939e-03,6.806073117346835843e+00,-2.016177317806832139e-02,6.054036616327979070e-01,4.563496123041156649e-02,1.000000009456914807e+00,0.000000000000000000e+00 +7.788103872339728184e+01,4.765933251303318343e+02,7.130828082563316940e-03,6.806962622427364273e+00,-1.999510651140165574e-02,6.068729376635066952e-01,4.563496123041156649e-02,1.000000010176368415e+00,0.000000000000000000e+00 +7.788250780741532253e+01,4.766033231313770102e+02,6.930890340731713124e-03,6.807854169761066387e+00,-1.982843984473499008e-02,6.083420216964960936e-01,4.563496123041156649e-02,1.000000009584883109e+00,0.000000000000000000e+00 +7.788397669904411202e+01,4.766133211656062940e+02,6.732618935176837120e-03,6.808747758264178884e+00,-1.966177317806832442e-02,6.098109133393674330e-01,4.563496123041156649e-02,1.000000009761443875e+00,0.000000000000000000e+00 +7.788544539789374710e+01,4.766233192327419488e+02,6.536013871406228665e-03,6.809643386851093716e+00,-1.949510651140165876e-02,6.112796122033364865e-01,4.563496123041156649e-02,1.000000009902873854e+00,0.000000000000000000e+00 +7.788691390357486455e+01,4.766333173325062376e+02,6.341075154881139000e-03,6.810541054434367858e+00,-1.932843984473499310e-02,6.127481178990000776e-01,4.563496123041156649e-02,1.000000009615610752e+00,0.000000000000000000e+00 +7.788838221569868381e+01,4.766433154646214803e+02,6.147802791016533479e-03,6.811440759924726862e+00,-1.916177317806832744e-02,6.142164300369388208e-01,4.563496123041156649e-02,1.000000010152250374e+00,0.000000000000000000e+00 +7.788985033387697854e+01,4.766533136288098831e+02,5.956196785181088089e-03,6.812342502231069297e+00,-1.899510651140166179e-02,6.156845482301348538e-01,4.563496123041156649e-02,1.000000009468030138e+00,0.000000000000000000e+00 +7.789131825772207662e+01,4.766633118247937659e+02,5.766257142697192063e-03,6.813246280260474741e+00,-1.882843984473499613e-02,6.171524720891312654e-01,4.563496123041156649e-02,1.000000010049511889e+00,0.000000000000000000e+00 +7.789278598684687438e+01,4.766733100522953919e+02,5.577983868840946137e-03,6.814152092918204673e+00,-1.866177317806833047e-02,6.186202012286851071e-01,4.563496123041156649e-02,1.000000009848317717e+00,0.000000000000000000e+00 +7.789425352086485077e+01,4.766833083110370239e+02,5.391376968842163421e-03,6.815059939107713127e+00,-1.849510651140166481e-02,6.200877352611109394e-01,4.563496123041156649e-02,1.000000009699690606e+00,0.000000000000000000e+00 +7.789572085939002477e+01,4.766933066007409820e+02,5.206436447884369399e-03,6.815969817730647584e+00,-1.832843984473499915e-02,6.215550738005143350e-01,4.563496123041156649e-02,1.000000009613361218e+00,0.000000000000000000e+00 +7.789718800203698379e+01,4.767033049211294724e+02,5.023162311104801062e-03,6.816881727686856074e+00,-1.816177317806833350e-02,6.230222164615807356e-01,4.563496123041156649e-02,1.000000010010564155e+00,0.000000000000000000e+00 +7.789865494842089788e+01,4.767133032719247581e+02,4.841554563594406037e-03,6.817795667874392507e+00,-1.799510651140166784e-02,6.244891628601797473e-01,4.563496123041156649e-02,1.000000009659947731e+00,0.000000000000000000e+00 +7.790012169815749132e+01,4.767233016528491589e+02,4.661613210397844327e-03,6.818711637189522889e+00,-1.782843984473500218e-02,6.259559126109415228e-01,4.563496123041156649e-02,1.000000010218642599e+00,0.000000000000000000e+00 +7.790158825086305683e+01,4.767333000636249380e+02,4.483338256513486574e-03,6.819629634526727990e+00,-1.766177317806833652e-02,6.274224653314944833e-01,4.563496123041156649e-02,1.000000009212723917e+00,0.000000000000000000e+00 +7.790305460615445554e+01,4.767432985039743016e+02,4.306729706893414923e-03,6.820549658778712221e+00,-1.749510651140167086e-02,6.288888206364070532e-01,4.563496123041156649e-02,1.000000010363167879e+00,0.000000000000000000e+00 +7.790452076364913125e+01,4.767532969736195696e+02,4.131787566443422162e-03,6.821471708836403636e+00,-1.732843984473500520e-02,6.303549781462729484e-01,4.563496123041156649e-02,1.000000009540477075e+00,0.000000000000000000e+00 +7.790598672296506777e+01,4.767632954722830050e+02,3.958511840023012582e-03,6.822395783588967255e+00,-1.716177317806833955e-02,6.318209374762003838e-01,4.563496123041156649e-02,1.000000009637127540e+00,0.000000000000000000e+00 +7.790745248372084575e+01,4.767732939996868708e+02,3.786902532445400246e-03,6.823321881923801513e+00,-1.699510651140167389e-02,6.332866982461085037e-01,4.563496123041156649e-02,1.000000010240148063e+00,0.000000000000000000e+00 +7.790891804553561428e+01,4.767832925555534302e+02,3.616959648477510725e-03,6.824250002726549802e+00,-1.682843984473500823e-02,6.347522600758813693e-01,4.563496123041156649e-02,1.000000009693388314e+00,0.000000000000000000e+00 +7.791038340802907669e+01,4.767932911396048894e+02,3.448683192839979358e-03,6.825180144881104916e+00,-1.666177317806834257e-02,6.362176225835471932e-01,4.563496123041156649e-02,1.000000009648006172e+00,0.000000000000000000e+00 +7.791184857082151893e+01,4.768032897515635682e+02,3.282073170207152561e-03,6.826112307269610824e+00,-1.649510651140167691e-02,6.376827853901260168e-01,4.563496123041156649e-02,1.000000009686333291e+00,0.000000000000000000e+00 +7.791331353353379541e+01,4.768132883911517297e+02,3.117129585207086516e-03,6.827046488772471555e+00,-1.632843984473501125e-02,6.391477481165982466e-01,4.563496123041156649e-02,1.000000010217520163e+00,0.000000000000000000e+00 +7.791477829578734315e+01,4.768232870580916369e+02,2.953852442421547181e-03,6.827982688268355638e+00,-1.616177317806834560e-02,6.406125103851166847e-01,4.563496123041156649e-02,1.000000009579063098e+00,0.000000000000000000e+00 +7.791624285720416765e+01,4.768332857521054962e+02,2.792241746386010717e-03,6.828920904634202316e+00,-1.599510651140167994e-02,6.420770718159727330e-01,4.563496123041156649e-02,1.000000009833734493e+00,0.000000000000000000e+00 +7.791770721740684280e+01,4.768432844729156272e+02,2.632297501589663490e-03,6.829861136745223327e+00,-1.582843984473501428e-02,6.435414320330534732e-01,4.563496123041156649e-02,1.000000009730880324e+00,0.000000000000000000e+00 +7.791917137601852517e+01,4.768532832202442364e+02,2.474019712475400770e-03,6.830803383474912671e+00,-1.566177317806834862e-02,6.450055906589892141e-01,4.563496123041156649e-02,1.000000009675191981e+00,0.000000000000000000e+00 +7.792063533266295394e+01,4.768632819938135867e+02,2.317408383439828034e-03,6.831747643695049277e+00,-1.549510651140168123e-02,6.464695473175784413e-01,4.563496123041156649e-02,1.000000010071186107e+00,0.000000000000000000e+00 +7.792209908696442255e+01,4.768732807933459981e+02,2.162463518833260094e-03,6.832693916275703216e+00,-1.532843984473501384e-02,6.479333016337878171e-01,4.563496123041156649e-02,1.000000010078223811e+00,0.000000000000000000e+00 +7.792356263854782128e+01,4.768832796185636766e+02,2.009185122959720668e-03,6.833642200085241925e+00,-1.516177317806834644e-02,6.493968532319300824e-01,4.563496123041156649e-02,1.000000009268823709e+00,0.000000000000000000e+00 +7.792502598703859462e+01,4.768932784691888855e+02,1.857573200076943027e-03,6.834592493990333750e+00,-1.499510651140167905e-02,6.508602017362699055e-01,4.563496123041156649e-02,1.000000010118621274e+00,0.000000000000000000e+00 +7.792648913206279815e+01,4.769032773449438309e+02,1.707627754396369565e-03,6.835544796855952399e+00,-1.482843984473501166e-02,6.523233467752724835e-01,4.563496123041156649e-02,1.000000009709921533e+00,0.000000000000000000e+00 +7.792795207324702744e+01,4.769132762455508328e+02,1.559348790083151578e-03,6.836499107545387588e+00,-1.466177317806834426e-02,6.537862879737119659e-01,4.563496123041156649e-02,1.000000010101931958e+00,0.000000000000000000e+00 +7.792941481021848915e+01,4.769232751707320972e+02,1.412736311256149050e-03,6.837455424920244162e+00,-1.449510651140167687e-02,6.552490249599542960e-01,4.563496123041156649e-02,1.000000009618895902e+00,0.000000000000000000e+00 +7.793087734260495836e+01,4.769332741202099442e+02,1.267790321987930869e-03,6.838413747840451862e+00,-1.432843984473500948e-02,6.567115573604935808e-01,4.563496123041156649e-02,1.000000009488882124e+00,0.000000000000000000e+00 +7.793233967003479279e+01,4.769432730937065799e+02,1.124510826304774610e-03,6.839374075164267097e+00,-1.416177317806834209e-02,6.581738848042003598e-01,4.563496123041156649e-02,1.000000010110786430e+00,0.000000000000000000e+00 +7.793380179213691861e+01,4.769532720909442673e+02,9.828978281866661022e-04,6.840336405748280946e+00,-1.399510651140167469e-02,6.596360069211087973e-01,4.563496123041156649e-02,1.000000009804341339e+00,0.000000000000000000e+00 +7.793526370854085883e+01,4.769632711116452128e+02,8.429513315672996446e-04,6.841300738447425367e+00,-1.382843984473500730e-02,6.610979233393773358e-01,4.563496123041156649e-02,1.000000009796685685e+00,0.000000000000000000e+00 +7.793672541887670491e+01,4.769732701555316794e+02,7.046713403340781152e-04,6.842267072114974980e+00,-1.366177317806833991e-02,6.625596336895404059e-01,4.563496123041156649e-02,1.000000010068477163e+00,0.000000000000000000e+00 +7.793818692277513094e+01,4.769832692223259869e+02,5.680578583281123200e-04,6.843235405602555055e+00,-1.349510651140167251e-02,6.640211376026862178e-01,4.563496123041156649e-02,1.000000009351651009e+00,0.000000000000000000e+00 +7.793964821986740787e+01,4.769932683117502847e+02,4.331108893442212103e-04,6.844205737760146846e+00,-1.332843984473500512e-02,6.654824347086325531e-01,4.563496123041156649e-02,1.000000010120280169e+00,0.000000000000000000e+00 +7.794110930978538931e+01,4.770032674235268928e+02,2.998304371309316115e-04,6.845178067436090252e+00,-1.316177317806833773e-02,6.669435246413959462e-01,4.563496123041156649e-02,1.000000009857104688e+00,0.000000000000000000e+00 +7.794257019216149729e+01,4.770132665573780173e+02,1.682165053904783583e-04,6.846152393477094478e+00,-1.299510651140167034e-02,6.684044070318984065e-01,4.563496123041156649e-02,1.000000009787209487e+00,0.000000000000000000e+00 +7.794403086662873648e+01,4.770232657130259213e+02,3.826909777880399717e-05,6.847128714728238030e+00,-1.282843984473500294e-02,6.698650815134363778e-01,4.563496123041156649e-02,1.000000009887952457e+00,0.000000000000000000e+00 +7.794549133282072262e+01,4.770332648901928678e+02,-9.001178209444129553e-05,6.848107030032976716e+00,-1.266177317806833555e-02,6.713255477198579735e-01,4.563496123041156649e-02,1.000000009719078875e+00,0.000000000000000000e+00 +7.794695159037162568e+01,4.770432640886010631e+02,-2.166261306658997404e-04,6.849087338233148969e+00,-1.249510651140166816e-02,6.727858052849536863e-01,4.563496123041156649e-02,1.000000009672524781e+00,0.000000000000000000e+00 +7.794841163891622671e+01,4.770532633079727702e+02,-3.415739444185060905e-04,6.850069638168980291e+00,-1.232843984473500076e-02,6.742458538436723048e-01,4.563496123041156649e-02,1.000000009723954308e+00,0.000000000000000000e+00 +7.794987147808987515e+01,4.770632625480302522e+02,-4.648552198814877670e-04,6.851053928679089466e+00,-1.216177317806833337e-02,6.757056930315133991e-01,4.563496123041156649e-02,1.000000010264733064e+00,0.000000000000000000e+00 +7.795133110752851735e+01,4.770732618084957153e+02,-5.864699536303649404e-04,6.852040208600493898e+00,-1.199510651140166598e-02,6.771653224851346131e-01,4.563496123041156649e-02,1.000000009601333506e+00,0.000000000000000000e+00 +7.795279052686868226e+01,4.770832610890914225e+02,-7.064181422869505577e-04,6.853028476768615818e+00,-1.182843984473499858e-02,6.786247418393090980e-01,4.563496123041156649e-02,1.000000009791904843e+00,0.000000000000000000e+00 +7.795424973574748151e+01,4.770932603895396369e+02,-8.246997825193504508e-04,6.854018732017284066e+00,-1.166177317806833119e-02,6.800839507324019095e-01,4.563496123041156649e-02,1.000000009976144133e+00,0.000000000000000000e+00 +7.795570873380263777e+01,4.771032597095625647e+02,-9.413148710419635534e-04,6.855010973178743861e+00,-1.149510651140166380e-02,6.815429488021107485e-01,4.563496123041156649e-02,1.000000009708990945e+00,0.000000000000000000e+00 +7.795716752067244215e+01,4.771132590488824690e+02,-1.056263404615481738e-03,6.856005199083660351e+00,-1.132843984473499641e-02,6.830017356860729194e-01,4.563496123041156649e-02,1.000000009797681777e+00,0.000000000000000000e+00 +7.795862609599576842e+01,4.771232584072216127e+02,-1.169545380046890359e-03,6.857001408561123057e+00,-1.116177317806832901e-02,6.844603110236927579e-01,4.563496123041156649e-02,1.000000009796680578e+00,0.000000000000000000e+00 +7.796008445941210141e+01,4.771332577843022023e+02,-1.281160794189467817e-03,6.857999600438652976e+00,-1.099510651140166162e-02,6.859186744543144254e-01,4.563496123041156649e-02,1.000000009677338708e+00,0.000000000000000000e+00 +7.796154261056150858e+01,4.771432571798464437e+02,-1.391109643942785995e-03,6.858999773542207024e+00,-1.082843984473499423e-02,6.873768256178306446e-01,4.563496123041156649e-02,1.000000010246646864e+00,0.000000000000000000e+00 +7.796300054908464006e+01,4.771532565935766002e+02,-1.499391926252710040e-03,6.860001926696183361e+00,-1.066177317806832683e-02,6.888347641559015022e-01,4.563496123041156649e-02,1.000000009386163180e+00,0.000000000000000000e+00 +7.796445827462274281e+01,4.771632560252149347e+02,-1.606007638111398798e-03,6.861006058723428502e+00,-1.049510651140165944e-02,6.902924897076897492e-01,4.563496123041156649e-02,1.000000009991695915e+00,0.000000000000000000e+00 +7.796591578681766066e+01,4.771732554744837103e+02,-1.710956776557304810e-03,6.862012168445238203e+00,-1.032843984473499205e-02,6.917500019171713976e-01,4.563496123041156649e-02,1.000000009944048918e+00,0.000000000000000000e+00 +7.796737308531182009e+01,4.771832549411050763e+02,-1.814239338675174319e-03,6.863020254681369003e+00,-1.016177317806832466e-02,6.932073004258253457e-01,4.563496123041156649e-02,1.000000009630653830e+00,0.000000000000000000e+00 +7.796883016974824443e+01,4.771932544248013528e+02,-1.915855321596047264e-03,6.864030316250039121e+00,-9.995106511401657262e-03,6.946643848762880102e-01,4.563496123041156649e-02,1.000000009858147632e+00,0.000000000000000000e+00 +7.797028703977055386e+01,4.772032539252947458e+02,-2.015804722497257281e-03,6.865042351967934664e+00,-9.828439844734989869e-03,6.961212549129641713e-01,4.563496123041156649e-02,1.000000010178115240e+00,0.000000000000000000e+00 +7.797174369502296543e+01,4.772132534423074617e+02,-2.114087538602432356e-03,6.866056360650216739e+00,-9.661773178068322476e-03,6.975779101801985460e-01,4.563496123041156649e-02,1.000000009303671167e+00,0.000000000000000000e+00 +7.797320013515027881e+01,4.772232529755617634e+02,-2.210703767181494174e-03,6.867072341110525890e+00,-9.495106511401655083e-03,6.990343503210554310e-01,4.563496123041156649e-02,1.000000010134951767e+00,0.000000000000000000e+00 +7.797465635979787635e+01,4.772332525247799140e+02,-2.305653405550658550e-03,6.868090292160984767e+00,-9.328439844734987690e-03,7.004905749834174911e-01,4.563496123041156649e-02,1.000000009709878013e+00,0.000000000000000000e+00 +7.797611236861176565e+01,4.772432520896841197e+02,-2.398936451072435430e-03,6.869110212612209665e+00,-9.161773178068320297e-03,7.019465838114482548e-01,4.563496123041156649e-02,1.000000010091542046e+00,0.000000000000000000e+00 +7.797756816123853696e+01,4.772532516699966436e+02,-2.490552901155629328e-03,6.870132101273309644e+00,-8.995106511401652905e-03,7.034023764529107048e-01,4.563496123041156649e-02,1.000000009572840520e+00,0.000000000000000000e+00 +7.797902373732537740e+01,4.772632512654396919e+02,-2.580502753255338889e-03,6.871155956951896293e+00,-8.828439844734985512e-03,7.048579525536781132e-01,4.563496123041156649e-02,1.000000009798861500e+00,0.000000000000000000e+00 +7.798047909652005671e+01,4.772732508757354708e+02,-2.668786004872956887e-03,6.872181778454085510e+00,-8.661773178068318119e-03,7.063133117626145818e-01,4.563496123041156649e-02,1.000000009900348319e+00,0.000000000000000000e+00 +7.798193423847095573e+01,4.772832505006062433e+02,-2.755402653556170665e-03,6.873209564584506381e+00,-8.495106511401650726e-03,7.077684537279153032e-01,4.563496123041156649e-02,1.000000009845714688e+00,0.000000000000000000e+00 +7.798338916282703792e+01,4.772932501397742158e+02,-2.840352696898962564e-03,6.874239314146304736e+00,-8.328439844734983333e-03,7.092233780983264735e-01,4.563496123041156649e-02,1.000000010023136099e+00,0.000000000000000000e+00 +7.798484386923789202e+01,4.773032497929616511e+02,-2.923636132541609055e-03,6.875271025941148473e+00,-8.161773178068315940e-03,7.106780845237563593e-01,4.563496123041156649e-02,1.000000009562047820e+00,0.000000000000000000e+00 +7.798629835735367521e+01,4.773132494598908124e+02,-3.005252958170681610e-03,6.876304698769233781e+00,-7.995106511401648547e-03,7.121325726534445399e-01,4.563496123041156649e-02,1.000000009690195979e+00,0.000000000000000000e+00 +7.798775262682515574e+01,4.773232491402838491e+02,-3.085203171519045832e-03,6.877340331429288689e+00,-7.828439844734981154e-03,7.135868421390145766e-01,4.563496123041156649e-02,1.000000010377251725e+00,0.000000000000000000e+00 +7.798920667730369871e+01,4.773332488338630810e+02,-3.163486770365862323e-03,6.878377922718581061e+00,-7.661773178068314628e-03,7.150408926326440318e-01,4.563496123041156649e-02,1.000000009491026409e+00,0.000000000000000000e+00 +7.799066050844126607e+01,4.773432485403506575e+02,-3.240103752536587119e-03,6.879417471432923925e+00,-7.495106511401648103e-03,7.164947237840091354e-01,4.563496123041156649e-02,1.000000009521555766e+00,0.000000000000000000e+00 +7.799211411989041665e+01,4.773532482594688418e+02,-3.315054115902970385e-03,6.880458976366676360e+00,-7.328439844734981577e-03,7.179483352470059643e-01,4.563496123041156649e-02,1.000000010438534037e+00,0.000000000000000000e+00 +7.799356751130432031e+01,4.773632479909398967e+02,-3.388337858383058156e-03,6.881502436312754156e+00,-7.161773178068315052e-03,7.194017266760855955e-01,4.563496123041156649e-02,1.000000009267684620e+00,0.000000000000000000e+00 +7.799502068233674379e+01,4.773732477344860285e+02,-3.459954977941190161e-03,6.882547850062635142e+00,-6.995106511401648526e-03,7.208548977219764176e-01,4.563496123041156649e-02,1.000000010183953680e+00,0.000000000000000000e+00 +7.799647363264205069e+01,4.773832474898294436e+02,-3.529905472588002434e-03,6.883595216406358297e+00,-6.828439844734982000e-03,7.223078480420745962e-01,4.563496123041156649e-02,1.000000009791941924e+00,0.000000000000000000e+00 +7.799792636187518724e+01,4.773932472566924048e+02,-3.598189340380425569e-03,6.884644534132537963e+00,-6.661773178068315475e-03,7.237605772894430967e-01,4.563496123041156649e-02,1.000000009744136609e+00,0.000000000000000000e+00 +7.799937886969173917e+01,4.774032470347971184e+02,-3.664806579421685598e-03,6.885695802028362067e+00,-6.495106511401648949e-03,7.252130851201471495e-01,4.563496123041156649e-02,1.000000010010963170e+00,0.000000000000000000e+00 +7.800083115574786063e+01,4.774132468238657907e+02,-3.729757187861303547e-03,6.886749018879601003e+00,-6.328439844734982424e-03,7.266653711908103164e-01,4.563496123041156649e-02,1.000000009299031767e+00,0.000000000000000000e+00 +7.800228321970033107e+01,4.774232466236206847e+02,-3.793041163895095880e-03,6.887804183470612962e+00,-6.161773178068315898e-03,7.281174351567797354e-01,4.563496123041156649e-02,1.000000010527717365e+00,0.000000000000000000e+00 +7.800373506120651257e+01,4.774332464337840634e+02,-3.854658505765174055e-03,6.888861294584346595e+00,-5.995106511401649373e-03,7.295692766782438943e-01,4.563496123041156649e-02,1.000000009454740768e+00,0.000000000000000000e+00 +7.800518667992437827e+01,4.774432462540780762e+02,-3.914609211759945834e-03,6.889920351002352561e+00,-5.828439844734982847e-03,7.310208954098343925e-01,4.563496123041156649e-02,1.000000009843692084e+00,0.000000000000000000e+00 +7.800663807551251239e+01,4.774532460842249861e+02,-3.972893280214113108e-03,6.890981351504779973e+00,-5.661773178068316321e-03,7.324722910122497543e-01,4.563496123041156649e-02,1.000000009980472671e+00,0.000000000000000000e+00 +7.800808924763008179e+01,4.774632459239470563e+02,-4.029510709508674939e-03,6.892044294870389720e+00,-5.495106511401649796e-03,7.339234631443033452e-01,4.563496123041156649e-02,1.000000009836589099e+00,0.000000000000000000e+00 +7.800954019593687860e+01,4.774732457729664361e+02,-4.084461498070924082e-03,6.893109179876556247e+00,-5.328439844734983270e-03,7.353744114653709696e-01,4.563496123041156649e-02,1.000000009384216293e+00,0.000000000000000000e+00 +7.801099092009329183e+01,4.774832456310053885e+02,-4.137745644374450464e-03,6.894176005299272880e+00,-5.161773178068316745e-03,7.368251356353922032e-01,4.563496123041156649e-02,1.000000010284153529e+00,0.000000000000000000e+00 +7.801244141976030733e+01,4.774932454977861767e+02,-4.189363146939138575e-03,6.895244769913157157e+00,-4.995106511401650219e-03,7.382756353173201003e-01,4.563496123041156649e-02,1.000000009977198401e+00,0.000000000000000000e+00 +7.801389169459952200e+01,4.775032453730310067e+02,-4.239314004331168340e-03,6.896315472491459708e+00,-4.828439844734983694e-03,7.397259101709998674e-01,4.563496123041156649e-02,1.000000009280592295e+00,0.000000000000000000e+00 +7.801534174427312962e+01,4.775132452564620849e+02,-4.287598215163016847e-03,6.897388111806064259e+00,-4.661773178068317168e-03,7.411759598580675013e-01,4.563496123041156649e-02,1.000000010280655438e+00,0.000000000000000000e+00 +7.801679156844394925e+01,4.775232451478016173e+02,-4.334215778093455755e-03,6.898462686627494733e+00,-4.495106511401650642e-03,7.426257840437893165e-01,4.563496123041156649e-02,1.000000009572028503e+00,0.000000000000000000e+00 +7.801824116677538257e+01,4.775332450467718672e+02,-4.379166691827552152e-03,6.899539195724925023e+00,-4.328439844734984117e-03,7.440753823890996488e-01,4.563496123041156649e-02,1.000000010087906510e+00,0.000000000000000000e+00 +7.801969053893145656e+01,4.775432449530950407e+02,-4.422450955116670294e-03,6.900617637866177212e+00,-4.161773178068317591e-03,7.455247545597911696e-01,4.563496123041156649e-02,1.000000009690222180e+00,0.000000000000000000e+00 +7.802113968457678084e+01,4.775532448664934009e+02,-4.464068566758469005e-03,6.901698011817733125e+00,-3.995106511401651066e-03,7.469739002191635446e-01,4.563496123041156649e-02,1.000000010046590226e+00,0.000000000000000000e+00 +7.802258860337660451e+01,4.775632447866891539e+02,-4.504019525596904272e-03,6.902780316344735212e+00,-3.828439844734984540e-03,7.484228190335397990e-01,4.563496123041156649e-02,1.000000009441510240e+00,0.000000000000000000e+00 +7.802403729499674512e+01,4.775732447134045060e+02,-4.542303830522226651e-03,6.903864550210995432e+00,-3.661773178068318015e-03,7.498715106673640163e-01,4.563496123041156649e-02,1.000000010391408845e+00,0.000000000000000000e+00 +7.802548575910365969e+01,4.775832446463616634e+02,-4.578921480470982998e-03,6.904950712178997030e+00,-3.495106511401651489e-03,7.513199747893329894e-01,4.563496123041156649e-02,1.000000009488093644e+00,0.000000000000000000e+00 +7.802693399536440211e+01,4.775932445852828891e+02,-4.613872474426017334e-03,6.906038801009905193e+00,-3.328439844734984963e-03,7.527682110638139745e-01,4.563496123041156649e-02,1.000000009673260193e+00,0.000000000000000000e+00 +7.802838200344662312e+01,4.776032445298903895e+02,-4.647156811416467380e-03,6.907128815463565275e+00,-3.161773178068318438e-03,7.542162191600427779e-01,4.563496123041156649e-02,1.000000010080036361e+00,0.000000000000000000e+00 +7.802982978301859873e+01,4.776132444799063705e+02,-4.678774490517768891e-03,6.908220754298514343e+00,-2.995106511401651912e-03,7.556639987466073904e-01,4.563496123041156649e-02,1.000000009840579018e+00,0.000000000000000000e+00 +7.803127733374918762e+01,4.776232444350530955e+02,-4.708725510851653057e-03,6.909314616271984733e+00,-2.828439844734985387e-03,7.571115494914476551e-01,4.563496123041156649e-02,1.000000009783178490e+00,0.000000000000000000e+00 +7.803272465530788793e+01,4.776332443950527704e+02,-4.737009871586147364e-03,6.910410400139907594e+00,-2.661773178068318861e-03,7.585588710643111909e-01,4.563496123041156649e-02,1.000000009889077557e+00,0.000000000000000000e+00 +7.803417174736479467e+01,4.776432443596276016e+02,-4.763627571935574734e-03,6.911508104656920004e+00,-2.495106511401652336e-03,7.600059631355271517e-01,4.563496123041156649e-02,1.000000009716365934e+00,0.000000000000000000e+00 +7.803561860959059970e+01,4.776532443284998521e+02,-4.788578611160555255e-03,6.912607728576370292e+00,-2.328439844734985810e-03,7.614528253753942710e-01,4.563496123041156649e-02,1.000000009672010304e+00,0.000000000000000000e+00 +7.803706524165662017e+01,4.776632443013917282e+02,-4.811862988568003582e-03,6.913709270650322480e+00,-2.161773178068319284e-03,7.628994574554095465e-01,4.563496123041156649e-02,1.000000010164511899e+00,0.000000000000000000e+00 +7.803851164323478429e+01,4.776732442780254360e+02,-4.833480703511132404e-03,6.914812729629562504e+00,-1.995106511401652759e-03,7.643458590482703485e-01,4.563496123041156649e-02,1.000000009904766340e+00,0.000000000000000000e+00 +7.803995781399760290e+01,4.776832442581231817e+02,-4.853431755389448973e-03,6.915918104263604427e+00,-1.828439844734986016e-03,7.657920298254192737e-01,4.563496123041156649e-02,1.000000009726923045e+00,0.000000000000000000e+00 +7.804140375361824056e+01,4.776932442414072284e+02,-4.871716143648757713e-03,6.917025393300693104e+00,-1.661773178068319274e-03,7.672379694601156874e-01,4.563496123041156649e-02,1.000000009617142194e+00,0.000000000000000000e+00 +7.804284946177043025e+01,4.777032442275997823e+02,-4.888333867781158477e-03,6.918134595487811289e+00,-1.495106511401652532e-03,7.686836776262092608e-01,4.563496123041156649e-02,1.000000009987835670e+00,0.000000000000000000e+00 +7.804429493812854446e+01,4.777132442164230497e+02,-4.903284927325048288e-03,6.919245709570684966e+00,-1.328439844734985789e-03,7.701291539987563661e-01,4.563496123041156649e-02,1.000000009976852677e+00,0.000000000000000000e+00 +7.804574018236755251e+01,4.777232442075992935e+02,-4.916569321865119600e-03,6.920358734293789560e+00,-1.161773178068319047e-03,7.715743982521778843e-01,4.563496123041156649e-02,1.000000009572691528e+00,0.000000000000000000e+00 +7.804718519416303479e+01,4.777332442008507201e+02,-4.928187051032361168e-03,6.921473668400353496e+00,-9.951065114016523043e-04,7.730194100614894426e-01,4.563496123041156649e-02,1.000000010041360188e+00,0.000000000000000000e+00 +7.804862997319118278e+01,4.777432441958995355e+02,-4.938138114504058915e-03,6.922590510632363525e+00,-8.284398447349856703e-04,7.744641891041473825e-01,4.563496123041156649e-02,1.000000009671729861e+00,0.000000000000000000e+00 +7.805007451912881322e+01,4.777532441924679460e+02,-4.946422512003794195e-03,6.923709259730572718e+00,-6.617731780683190363e-04,7.759087350557472007e-01,4.563496123041156649e-02,1.000000010157994668e+00,0.000000000000000000e+00 +7.805151883165333970e+01,4.777632441902782148e+02,-4.953040243301444663e-03,6.924829914434502243e+00,-4.951065114016524023e-04,7.773530475949437246e-01,4.563496123041156649e-02,1.000000009790150024e+00,0.000000000000000000e+00 +7.805296291044278689e+01,4.777732441890525479e+02,-4.957991308213185143e-03,6.925952473482450245e+00,-3.284398447349857683e-04,7.787971263985338233e-01,4.563496123041156649e-02,1.000000009412870927e+00,0.000000000000000000e+00 +7.805440675517580473e+01,4.777832441885132084e+02,-4.961275706601485889e-03,6.927076935611493624e+00,-1.617731780683191072e-04,7.802409711451467889e-01,4.563496123041156649e-02,1.000000010299826547e+00,0.000000000000000000e+00 +7.805585036553165423e+01,4.777932441883823458e+02,-4.962893438375112591e-03,6.928203299557495143e+00,4.893488598347553887e-06,7.816845815158630639e-01,4.563496123041156649e-02,1.000000009890286590e+00,-6.928203299557500472e-01 +7.805729374119019326e+01,4.778032441883822230e+02,-4.962844503489128971e-03,6.929331564055111414e+00,1.715601552650142150e-04,7.831279571886787805e-01,4.463496123041156560e-02,1.000000009458875461e+00,-6.929331564055117854e-01 +7.805873688183190495e+01,4.778132441882350463e+02,-4.961128901944895052e-03,6.930461727837792907e+00,3.345697415717163075e-04,7.845710978440433303e-01,4.363496123041156471e-02,1.000000009857021865e+00,-6.930461727837798902e-01 +7.806017978713788352e+01,4.778232441876753569e+02,-4.957783204591595730e-03,6.931593789637791936e+00,4.939225741882299946e-04,7.860140031642477432e-01,4.263496123041156383e-02,1.000000010231530512e+00,-6.931593789637798819e-01 +7.806162245678983425e+01,4.778332441864555449e+02,-4.952843979050542203e-03,6.932727748186169769e+00,6.496189724280237651e-04,7.874566728309648767e-01,4.163496123041156294e-02,1.000000009728665207e+00,-6.932727748186175987e-01 +7.806306489047008768e+01,4.778432441843455081e+02,-4.946347789783166193e-03,6.933863602212800181e+00,8.016592482508203216e-04,7.888991065252496382e-01,4.063496123041156205e-02,1.000000009629996800e+00,-6.933863602212806398e-01 +7.806450708786157122e+01,4.778532441811321974e+02,-4.938331198159311673e-03,6.935001350446373003e+00,9.500437062650992715e-04,7.903413039306195209e-01,3.963496123041156116e-02,1.000000009938933454e+00,-6.935001350446379220e-01 +7.806594904864783757e+01,4.778632441766192755e+02,-4.928830762525816291e-03,6.936140991614402118e+00,1.094772643730540160e-03,7.917832647312105232e-01,3.863496123041156027e-02,1.000000009804906220e+00,-6.936140991614407891e-01 +7.806739077251303627e+01,4.778732441706266627e+02,-4.917883038275368615e-03,6.937282524443230791e+00,1.235846350560406304e-03,7.932249886105461334e-01,3.763496123041155939e-02,1.000000009660186651e+00,-6.937282524443236786e-01 +7.806883225914195634e+01,4.778832441629900813e+02,-4.905524577915644675e-03,6.938425947658035220e+00,1.373265109323869651e-03,7.946664752533875165e-01,3.663496123041155850e-02,1.000000009938515566e+00,-6.938425947658041215e-01 +7.807027350821998368e+01,4.778932441535607722e+02,-4.891791931138708173e-03,6.939571259982830753e+00,1.507029195248276972e-03,7.961077243457354014e-01,3.563496123041155761e-02,1.000000009792620714e+00,-6.939571259982837415e-01 +7.807171451943311524e+01,4.779032441422050965e+02,-4.876721644890674376e-03,6.940718460140478108e+00,1.637138876221355460e-03,7.975487355729838912e-01,3.463496123041155672e-02,1.000000010086844471e+00,-6.940718460140483659e-01 +7.807315529246798746e+01,4.779132441288039672e+02,-4.860350263441623811e-03,6.941867546852686921e+00,1.763594412793360747e-03,7.989895086223874898e-01,3.363496123041155583e-02,1.000000009547516777e+00,-6.941867546852693582e-01 +7.807459582701183365e+01,4.779232441132526219e+02,-4.842714328455765757e-03,6.943018518840022857e+00,1.886396058179164864e-03,8.004300431799805660e-01,3.263496123041155494e-02,1.000000010326347333e+00,-6.943018518840028408e-01 +7.807603612275249816e+01,4.779332440954601680e+02,-4.823850379061841998e-03,6.944171374821910270e+00,2.005544058260286516e-03,8.018703389355122946e-01,3.163496123041155406e-02,1.000000009439315329e+00,-6.944171374821915821e-01 +7.807747617937843643e+01,4.779432440753491278e+02,-4.803794951923758688e-03,6.945326113516641975e+00,2.121038651586859992e-03,8.033103955750490188e-01,3.063496123041155317e-02,1.000000009469708351e+00,-6.945326113516648858e-01 +7.807891599657874337e+01,4.779532440528550978e+02,-4.782584581311451546e-03,6.946482733641378360e+00,2.232880069379548135e-03,8.047502127889931689e-01,2.963496123041155228e-02,1.000000010433971687e+00,-6.946482733641384799e-01 +7.808035557404311078e+01,4.779632440279263506e+02,-4.760255799171967013e-03,6.947641233912158043e+00,2.341068535531393938e-03,8.061897902683857753e-01,2.863496123041155139e-02,1.000000009349477192e+00,-6.947641233912164038e-01 +7.808179491146185569e+01,4.779732440005233798e+02,-4.736845135200755050e-03,6.948801613043903203e+00,2.445604266609614254e-03,8.076291277005899216e-01,2.763496123041155050e-02,1.000000010091817604e+00,-6.948801613043908976e-01 +7.808323400852590623e+01,4.779832439706185028e+02,-4.712389116913169237e-03,6.949963869750418688e+00,2.546487471857335379e-03,8.090682247791634030e-01,2.663496123041154962e-02,1.000000010109247439e+00,-6.949963869750424017e-01 +7.808467286492680159e+01,4.779932439381955191e+02,-4.686924269716168101e-03,6.951128002744405343e+00,2.643718353195267934e-03,8.105070811946071263e-01,2.563496123041154873e-02,1.000000009422092662e+00,-6.951128002744411116e-01 +7.808611148035670624e+01,4.780032439032493130e+02,-4.660487116980204653e-03,6.952294010737460006e+00,2.737297105223325359e-03,8.119456966380679264e-01,2.463496123041154784e-02,1.000000009769451470e+00,-6.952294010737466445e-01 +7.808754985450839570e+01,4.780132438657853413e+02,-4.633114180111304152e-03,6.953461892440080838e+00,2.827223915222181264e-03,8.133840708038109213e-01,2.363496123041154695e-02,1.000000009889230324e+00,-6.953461892440085945e-01 +7.808898798707527078e+01,4.780232438258194065e+02,-4.604841978623321411e-03,6.954631646561676206e+00,2.913498963154769958e-03,8.148222033849018553e-01,2.263496123041154606e-02,1.000000009806371715e+00,-6.954631646561683089e-01 +7.809042587775132915e+01,4.780332437833770314e+02,-4.575707030210367232e-03,6.955803271810567345e+00,2.996122421667726278e-03,8.162600940750590617e-01,2.163496123041154517e-02,1.000000009978206483e+00,-6.955803271810573341e-01 +7.809186352623119376e+01,4.780432437384933451e+02,-4.545745850819403987e-03,6.956976766893993691e+00,3.075094456092769893e-03,8.176977425692751877e-01,2.063496123041154429e-02,1.000000009574192328e+00,-6.956976766893999686e-01 +7.809330093221012703e+01,4.780532436912123444e+02,-4.514994954722997313e-03,6.958152130518119094e+00,3.150415224448026730e-03,8.191351485619656758e-01,1.963496123041154340e-02,1.000000009914352672e+00,-6.958152130518124867e-01 +7.809473809538397404e+01,4.780632436415867801e+02,-4.483490854592219604e-03,6.959329361388035373e+00,3.222084877439296193e-03,8.205723117500604014e-01,1.863496123041154251e-02,1.000000009741144558e+00,-6.959329361388041368e-01 +7.809617501544921936e+01,4.780732435896776451e+02,-4.451270061569698351e-03,6.960508458207770310e+00,3.290103558461255923e-03,8.220092318292987477e-01,1.763496123041154162e-02,1.000000009948652346e+00,-6.960508458207776972e-01 +7.809761169210294440e+01,4.780832435355537768e+02,-4.418369085342806722e-03,6.961689419680290314e+00,3.354471403598609756e-03,8.234459084973221321e-01,1.663496123041154073e-02,1.000000009711628834e+00,-6.961689419680296975e-01 +7.809904812504287008e+01,4.780932434792914592e+02,-4.384824434216979920e-03,6.962872244507507524e+00,3.415188541627178428e-03,8.248823414512035379e-01,1.563496123041153985e-02,1.000000009927983102e+00,-6.962872244507514186e-01 +7.810048431396732838e+01,4.781032434209739677e+02,-4.350672615189161638e-03,6.964056931390283367e+00,3.472255094014928267e-03,8.263185303899232004e-01,1.463496123041153896e-02,1.000000009775716903e+00,-6.964056931390288918e-01 +7.810192025857526232e+01,4.781132433606912286e+02,-4.315950134021363273e-03,6.965243479028435658e+00,3.525671174922945239e-03,8.277544750118981387e-01,1.363496123041153807e-02,1.000000009725468209e+00,-6.965243479028442319e-01 +7.810335595856624025e+01,4.781232432985395349e+02,-4.280693495314341970e-03,6.966431886120742156e+00,3.575436891206346980e-03,8.291901750168388929e-01,1.263496123041153718e-02,1.000000009388773092e+00,-6.966431886120748596e-01 +7.810479141364044153e+01,4.781332432346208634e+02,-4.244939202581375810e-03,6.967622151364946781e+00,3.621552342415138882e-03,8.306256301045159551e-01,1.163496123041153629e-02,1.000000010534303874e+00,-6.967622151364952776e-01 +7.810622662349865664e+01,4.781432431690427052e+02,-4.208723758322142211e-03,6.968814273457764052e+00,3.664017620795010331e-03,8.320608399778561814e-01,1.063496123041153540e-02,1.000000009326780903e+00,-6.968814273457770714e-01 +7.810766158784231550e+01,4.781532431019176670e+02,-4.172083664096684803e-03,6.970008251094887974e+00,3.702832811288073265e-03,8.334958043348996704e-01,9.634961230411534516e-03,1.000000009694980818e+00,-6.970008251094893525e-01 +7.810909630637344492e+01,4.781632430333629031e+02,-4.135055420599467041e-03,6.971204082970989369e+00,3.737997991533541318e-03,8.349305228799428491e-01,8.634961230411533628e-03,1.000000009963062597e+00,-6.971204082970989813e-01 +7.811053077879471118e+01,4.781732429634998311e+02,-4.097675527733503006e-03,6.972401767779729198e+00,3.769513231868350852e-03,8.363649953154950190e-01,7.634961230411533607e-03,1.000000010182530596e+00,-6.972401767779728976e-01 +7.811196500480936322e+01,4.781832428924537908e+02,-4.059980484684556738e-03,6.973601304213760343e+00,3.797378595327724742e-03,8.377992213447574832e-01,6.634961230411533586e-03,1.000000009109751176e+00,-6.973601304213760121e-01 +7.811339898412130367e+01,4.781932428203534755e+02,-4.022006789995411814e-03,6.974802690964732932e+00,3.821594137645675879e-03,8.392332006697663660e-01,5.634961230411533566e-03,1.000000010255522209e+00,-6.974802690964732044e-01 +7.811483271643504622e+01,4.782032427473306484e+02,-3.983790941640193844e-03,6.976005926723297002e+00,3.842159907255452995e-03,8.406669329982104921e-01,4.634961230411533545e-03,1.000000009788275301e+00,-6.976005926723297668e-01 +7.811626620145570143e+01,4.782132426735198010e+02,-3.945369437098745005e-03,6.977211010179114936e+00,3.859075945289929237e-03,8.421004180329028088e-01,3.634961230411533524e-03,1.000000009494673492e+00,-6.977211010179115158e-01 +7.811769943888903356e+01,4.782232425990575848e+02,-3.906778773431043676e-03,6.978417940020858801e+00,3.872342285581930037e-03,8.435336554798364972e-01,2.634961230411533503e-03,1.000000009867717976e+00,-6.978417940020859023e-01 +7.811913242844138949e+01,4.782332425240825273e+02,-3.868055447351663977e-03,6.979626714936219223e+00,3.881958954664503723e-03,8.449666450463294565e-01,1.634961230411533482e-03,1.000000009672776802e+00,-6.979626714936219001e-01 +7.812056516981975562e+01,4.782432424487345770e+02,-3.829235955304260888e-03,6.980837333611911610e+00,3.887925971771135324e-03,8.463993864385486177e-01,6.349612304115334616e-04,1.000000010271758555e+00,-4.711794555997464440e-01 +7.812199766273172941e+01,4.782532423731548192e+02,-3.790356793536085300e-03,6.982049794733678816e+00,3.890243348835898795e-03,8.478318793652307450e-01,-3.999999999999999650e-05,1.000000009134071277e+00,-4.731220972407640470e-18 +7.812342990688551936e+01,4.782632422974849646e+02,-3.751454458172513370e-03,6.983264096986299130e+00,3.890097363434361077e-03,8.492641235321061188e-01,-4.000000000000000327e-05,1.000000010224331382e+00,0.000000000000000000e+00 +7.812486190198997349e+01,4.782732422218207944e+02,-3.712553582651910607e-03,6.984480239053586281e+00,3.889951378032823360e-03,8.506961186512022044e-01,-4.000000000000000327e-05,1.000000009282386415e+00,0.000000000000000000e+00 +7.812629364775455088e+01,4.782832421461623085e+02,-3.673654166974277876e-03,6.985698219618402760e+00,3.889805392631285642e-03,8.521278644290639637e-01,-4.000000000000000327e-05,1.000000010279375795e+00,0.000000000000000000e+00 +7.812772514388930745e+01,4.782932420705094501e+02,-3.634756211139615611e-03,6.986918037362656264e+00,3.889659407229747925e-03,8.535593605785412041e-01,-4.000000000000000327e-05,1.000000009389408140e+00,0.000000000000000000e+00 +7.812915639010495283e+01,4.783032419948622760e+02,-3.595859715147925115e-03,6.988139690967313022e+00,3.889513421828210207e-03,8.549906068076251753e-01,-4.000000000000000327e-05,1.000000010156699926e+00,0.000000000000000000e+00 +7.813058738611279352e+01,4.783132419192207863e+02,-3.556964678999206819e-03,6.989363179112395130e+00,3.889367436426672490e-03,8.564216028299990180e-01,-4.000000000000000327e-05,1.000000009190476824e+00,0.000000000000000000e+00 +7.813201813162476128e+01,4.783232418435849809e+02,-3.518071102693462026e-03,6.990588500476992984e+00,3.889221451025134772e-03,8.578523483551120377e-01,-4.000000000000000327e-05,1.000000010475907697e+00,0.000000000000000000e+00 +7.813344862635339894e+01,4.783332417679548598e+02,-3.479178986230691169e-03,6.991815653739263503e+00,3.889075465623597055e-03,8.592828430987343724e-01,-4.000000000000000327e-05,1.000000009321798222e+00,0.000000000000000000e+00 +7.813487887001187460e+01,4.783432416923304231e+02,-3.440288329610895115e-03,6.993044637576443456e+00,3.888929480222059337e-03,8.607130867705437005e-01,-4.000000000000000327e-05,1.000000009719675287e+00,0.000000000000000000e+00 +7.813630886231398165e+01,4.783532416167116708e+02,-3.401399132834075165e-03,6.994275450664845017e+00,3.888783494820521620e-03,8.621430790865461935e-01,-4.000000000000000327e-05,1.000000009585493510e+00,0.000000000000000000e+00 +7.813773860297411034e+01,4.783632415410986027e+02,-3.362511395900231754e-03,6.995508091679869089e+00,3.888637509418983902e-03,8.635728197603860234e-01,-4.000000000000000327e-05,1.000000009877299423e+00,0.000000000000000000e+00 +7.813916809170730460e+01,4.783732414654911622e+02,-3.323625118809365748e-03,6.996742559296006192e+00,3.888491524017446185e-03,8.650023085076961049e-01,-4.000000000000000327e-05,1.000000010252058313e+00,0.000000000000000000e+00 +7.814059732822919102e+01,4.783832413898894060e+02,-3.284740301561477581e-03,6.997978852186843568e+00,3.888345538615908467e-03,8.664315450442375832e-01,-4.000000000000000327e-05,1.000000009063422013e+00,0.000000000000000000e+00 +7.814202631225603568e+01,4.783932413142933342e+02,-3.245856944156568554e-03,6.999216969025069623e+00,3.888199553214370750e-03,8.678605290840377684e-01,-4.000000000000000327e-05,1.000000009886404140e+00,0.000000000000000000e+00 +7.814345504350472993e+01,4.784032412387029467e+02,-3.206975046594639535e-03,7.000456908482475704e+00,3.888053567812833032e-03,8.692892603468517221e-01,-4.000000000000000327e-05,1.000000009774445253e+00,0.000000000000000000e+00 +7.814488352169276197e+01,4.784132411631182435e+02,-3.168094608875690957e-03,7.001698669229968530e+00,3.887907582411295315e-03,8.707177385488427124e-01,-4.000000000000000327e-05,1.000000010133122119e+00,0.000000000000000000e+00 +7.814631174653824530e+01,4.784232410875392247e+02,-3.129215630999724121e-03,7.002942249937569308e+00,3.887761597009757597e-03,8.721459634088010171e-01,-4.000000000000000327e-05,1.000000009322604688e+00,0.000000000000000000e+00 +7.814773971775991868e+01,4.784332410119658903e+02,-3.090338112966739461e-03,7.004187649274421723e+00,3.887615611608219880e-03,8.735739346437937369e-01,-4.000000000000000327e-05,1.000000009625783504e+00,0.000000000000000000e+00 +7.814916743507714614e+01,4.784432409363981833e+02,-3.051462054776738278e-03,7.005434865908793718e+00,3.887469626206682162e-03,8.750016519747669808e-01,-4.000000000000000327e-05,1.000000009842900717e+00,0.000000000000000000e+00 +7.815059489820990279e+01,4.784532408608361607e+02,-3.012587456429721006e-03,7.006683898508087260e+00,3.887323640805144444e-03,8.764291151215721776e-01,-4.000000000000000327e-05,1.000000009647405319e+00,0.000000000000000000e+00 +7.815202210687877482e+01,4.784632407852798224e+02,-2.973714317925688511e-03,7.007934745738841009e+00,3.887177655403606727e-03,8.778563238042135231e-01,-4.000000000000000327e-05,1.000000010023288644e+00,0.000000000000000000e+00 +7.815344906080497367e+01,4.784732407097291684e+02,-2.934842639264641662e-03,7.009187406266734754e+00,3.887031670002069009e-03,8.792832777447183723e-01,-4.000000000000000327e-05,1.000000009339425677e+00,0.000000000000000000e+00 +7.815487575971033607e+01,4.784832406341841988e+02,-2.895972420446581326e-03,7.010441878756596523e+00,3.886885684600531292e-03,8.807099766634052251e-01,-4.000000000000000327e-05,1.000000009894038255e+00,0.000000000000000000e+00 +7.815630220331730982e+01,4.784932405586449136e+02,-2.857103661471508370e-03,7.011698161872404356e+00,3.886739699198993574e-03,8.821364202844903524e-01,-4.000000000000000327e-05,1.000000009624167685e+00,0.000000000000000000e+00 +7.815772839134895378e+01,4.785032404831112558e+02,-2.818236362339423661e-03,7.012956254277296075e+00,3.886593713797455857e-03,8.835626083298655509e-01,-4.000000000000000327e-05,1.000000009960591463e+00,0.000000000000000000e+00 +7.815915432352896630e+01,4.785132404075832824e+02,-2.779370523050327633e-03,7.014216154633570177e+00,3.886447728395918139e-03,8.849885405240820457e-01,-4.000000000000000327e-05,1.000000009279934154e+00,0.000000000000000000e+00 +7.816057999958164260e+01,4.785232403320609933e+02,-2.740506143604221588e-03,7.015477861602693821e+00,3.886301742994380422e-03,8.864142165899947523e-01,-4.000000000000000327e-05,1.000000009892868524e+00,0.000000000000000000e+00 +7.816200541923191736e+01,4.785332402565443886e+02,-2.701643224001106392e-03,7.016741373845304608e+00,3.886155757592842704e-03,8.878396362543715670e-01,-4.000000000000000327e-05,1.000000009743205132e+00,0.000000000000000000e+00 +7.816343058220532214e+01,4.785432401810334682e+02,-2.662781764240982479e-03,7.018006690021220351e+00,3.886009772191304987e-03,8.892647992416674585e-01,-4.000000000000000327e-05,1.000000009836167880e+00,0.000000000000000000e+00 +7.816485548822802798e+01,4.785532401055281753e+02,-2.623921764323850717e-03,7.019273808789439961e+00,3.885863786789767269e-03,8.906897052783887547e-01,-4.000000000000000327e-05,1.000000009430405568e+00,0.000000000000000000e+00 +7.816628013702680278e+01,4.785632400300285667e+02,-2.585063224249712407e-03,7.020542728808150557e+00,3.885717801388229552e-03,8.921143540906038005e-01,-4.000000000000000327e-05,1.000000009537102663e+00,0.000000000000000000e+00 +7.816770452832905391e+01,4.785732399545346425e+02,-2.546206144018567982e-03,7.021813448734731011e+00,3.885571815986691834e-03,8.935387454064399604e-01,-4.000000000000000327e-05,1.000000009857902272e+00,0.000000000000000000e+00 +7.816912866186278563e+01,4.785832398790464026e+02,-2.507350523630418309e-03,7.023085967225759063e+00,3.885425830585154117e-03,8.949628789542175555e-01,-4.000000000000000327e-05,1.000000009657790345e+00,0.000000000000000000e+00 +7.817055253735664166e+01,4.785932398035638471e+02,-2.468496363085264256e-03,7.024360282937015754e+00,3.885279845183616399e-03,8.963867544618283612e-01,-4.000000000000000327e-05,1.000000009518684285e+00,0.000000000000000000e+00 +7.817197615453987680e+01,4.786032397280869191e+02,-2.429643662383106691e-03,7.025636394523488981e+00,3.885133859782078682e-03,8.978103716586111060e-01,-4.000000000000000327e-05,1.000000010025390962e+00,0.000000000000000000e+00 +7.817339951314235691e+01,4.786132396526156754e+02,-2.390792421523946047e-03,7.026914300639379718e+00,3.884987874380540964e-03,8.992337302753549144e-01,-4.000000000000000327e-05,1.000000009573095205e+00,0.000000000000000000e+00 +7.817482261289455892e+01,4.786232395771501160e+02,-2.351942640507783625e-03,7.028193999938108227e+00,3.884841888979003247e-03,9.006568300411825767e-01,-4.000000000000000327e-05,1.000000009190269656e+00,0.000000000000000000e+00 +7.817624545352759924e+01,4.786332395016902410e+02,-2.313094319334620293e-03,7.029475491072315840e+00,3.884695903577465529e-03,9.020796706872988846e-01,-4.000000000000000327e-05,1.000000009909078891e+00,0.000000000000000000e+00 +7.817766803477320536e+01,4.786432394262360503e+02,-2.274247458004456483e-03,7.030758772693872061e+00,3.884549918175927812e-03,9.035022519469947389e-01,-4.000000000000000327e-05,1.000000009692201264e+00,0.000000000000000000e+00 +7.817909035636370163e+01,4.786532393507874872e+02,-2.235402056517293498e-03,7.032043843453881671e+00,3.884403932774390094e-03,9.049245735512801980e-01,-4.000000000000000327e-05,1.000000009577056037e+00,0.000000000000000000e+00 +7.818051241803206608e+01,4.786632392753446084e+02,-2.196558114873131771e-03,7.033330702002685619e+00,3.884257947372852376e-03,9.063466352332589793e-01,-4.000000000000000327e-05,1.000000009725682926e+00,0.000000000000000000e+00 +7.818193421951185940e+01,4.786732391999074139e+02,-2.157715633071972169e-03,7.034619346989868127e+00,3.884111961971314659e-03,9.077684367268826771e-01,-4.000000000000000327e-05,1.000000009424492742e+00,0.000000000000000000e+00 +7.818335576053728175e+01,4.786832391244759037e+02,-2.118874611113815559e-03,7.035909777064262016e+00,3.883965976569776941e-03,9.091899777657057591e-01,-4.000000000000000327e-05,1.000000009720370509e+00,0.000000000000000000e+00 +7.818477704084314439e+01,4.786932390490500211e+02,-2.080035048998663243e-03,7.037201990873952262e+00,3.883819991168239224e-03,9.106112580853883420e-01,-4.000000000000000327e-05,1.000000009904394194e+00,0.000000000000000000e+00 +7.818619806016488383e+01,4.787032389736298228e+02,-2.041196946726515221e-03,7.038495987066283099e+00,3.883674005766701506e-03,9.120322774211999661e-01,-4.000000000000000327e-05,1.000000009269927936e+00,0.000000000000000000e+00 +7.818761881823853344e+01,4.787132388982153088e+02,-2.002360304297372794e-03,7.039791764287861575e+00,3.883528020365163789e-03,9.134530355080234809e-01,-4.000000000000000327e-05,1.000000009312441707e+00,0.000000000000000000e+00 +7.818903931480076608e+01,4.787232388228064792e+02,-1.963525121711236828e-03,7.041089321184561101e+00,3.883382034963626071e-03,9.148735320834837648e-01,-4.000000000000000327e-05,1.000000010211544943e+00,0.000000000000000000e+00 +7.819045954958885147e+01,4.787332387474032771e+02,-1.924691398968108192e-03,7.042388656401529445e+00,3.883236049562088354e-03,9.162937668860772211e-01,-4.000000000000000327e-05,1.000000009066442708e+00,0.000000000000000000e+00 +7.819187952234069883e+01,4.787432386720057593e+02,-1.885859136067987536e-03,7.043689768583194066e+00,3.883090064160550636e-03,9.177137396507973888e-01,-4.000000000000000327e-05,1.000000010025240860e+00,0.000000000000000000e+00 +7.819329923279481420e+01,4.787532385966139259e+02,-1.847028333010875727e-03,7.044992656373261219e+00,3.882944078759012919e-03,9.191334501191452677e-01,-4.000000000000000327e-05,1.000000009309744531e+00,0.000000000000000000e+00 +7.819471868069032894e+01,4.787632385212277200e+02,-1.808198989796773633e-03,7.046297318414729283e+00,3.882798093357475201e-03,9.205528980278738782e-01,-4.000000000000000327e-05,1.000000009313396943e+00,0.000000000000000000e+00 +7.819613786576698544e+01,4.787732384458471984e+02,-1.769371106425682121e-03,7.047603753349886091e+00,3.882652107955937484e-03,9.219720831177508069e-01,-4.000000000000000327e-05,1.000000009789041355e+00,0.000000000000000000e+00 +7.819755678776515140e+01,4.787832383704723611e+02,-1.730544682897601841e-03,7.048911959820318707e+00,3.882506122554399766e-03,9.233910051298087618e-01,-4.000000000000000327e-05,1.000000009608939422e+00,0.000000000000000000e+00 +7.819897544642580556e+01,4.787932382951032082e+02,-1.691719719212533661e-03,7.050221936466917860e+00,3.882360137152862049e-03,9.248096638040964601e-01,-4.000000000000000327e-05,1.000000009412405522e+00,0.000000000000000000e+00 +7.820039384149053774e+01,4.788032382197396828e+02,-1.652896215370478449e-03,7.051533681929880615e+00,3.882214151751324331e-03,9.262280588821860672e-01,-4.000000000000000327e-05,1.000000009401302181e+00,0.000000000000000000e+00 +7.820181197270157725e+01,4.788132381443818417e+02,-1.614074171371437071e-03,7.052847194848716583e+00,3.882068166349786614e-03,9.276461901065520266e-01,-4.000000000000000327e-05,1.000000009780479093e+00,0.000000000000000000e+00 +7.820322983980173603e+01,4.788232380690296850e+02,-1.575253587215410395e-03,7.054162473862253258e+00,3.881922180948248896e-03,9.290640572205749459e-01,-4.000000000000000327e-05,1.000000009431949444e+00,0.000000000000000000e+00 +7.820464744253445133e+01,4.788332379936831558e+02,-1.536434462902399288e-03,7.055479517608641338e+00,3.881776195546711179e-03,9.304816599666659860e-01,-4.000000000000000327e-05,1.000000009449701688e+00,0.000000000000000000e+00 +7.820606478064379985e+01,4.788432379183423109e+02,-1.497616798432404401e-03,7.056798324725357396e+00,3.881630210145173461e-03,9.318989980894030190e-01,-4.000000000000000327e-05,1.000000009605376272e+00,0.000000000000000000e+00 +7.820748185387444096e+01,4.788532378430071503e+02,-1.458800593805426602e-03,7.058118893849210984e+00,3.881484224743635743e-03,9.333160713336554615e-01,-4.000000000000000327e-05,1.000000009230471942e+00,0.000000000000000000e+00 +7.820889866197167350e+01,4.788632377676776741e+02,-1.419985849021466757e-03,7.059441223616349070e+00,3.881338239342098026e-03,9.347328794439607735e-01,-4.000000000000000327e-05,1.000000009429261594e+00,0.000000000000000000e+00 +7.821031520468139320e+01,4.788732376923538254e+02,-1.381172564080525734e-03,7.060765312662259596e+00,3.881192253940560308e-03,9.361494221670362270e-01,-4.000000000000000327e-05,1.000000009539723678e+00,0.000000000000000000e+00 +7.821173148175012102e+01,4.788832376170356611e+02,-1.342360738982604400e-03,7.062091159621778580e+00,3.881046268539022591e-03,9.375656992492760189e-01,-4.000000000000000327e-05,1.000000009786760735e+00,0.000000000000000000e+00 +7.821314749292498902e+01,4.788932375417231810e+02,-1.303550373727703406e-03,7.063418763129093669e+00,3.880900283137484873e-03,9.389817104380077106e-01,-4.000000000000000327e-05,1.000000009070105778e+00,0.000000000000000000e+00 +7.821456323795375454e+01,4.789032374664163285e+02,-1.264741468315823620e-03,7.064748121817749471e+00,3.880754297735947156e-03,9.403974554796157292e-01,-4.000000000000000327e-05,1.000000009393058553e+00,0.000000000000000000e+00 +7.821597871658477175e+01,4.789132373911151603e+02,-1.225934022746965908e-03,7.066079234320650215e+00,3.880608312334409438e-03,9.418129341239354080e-01,-4.000000000000000327e-05,1.000000009218559693e+00,0.000000000000000000e+00 +7.821739392856703432e+01,4.789232373158196765e+02,-1.187128037021131137e-03,7.067412099270068637e+00,3.880462326932871721e-03,9.432281461192403293e-01,-4.000000000000000327e-05,1.000000009670325651e+00,0.000000000000000000e+00 +7.821880887365011858e+01,4.789332372405298202e+02,-1.148323511138320176e-03,7.068746715297647754e+00,3.880316341531334003e-03,9.446430912160086457e-01,-4.000000000000000327e-05,1.000000009215511465e+00,0.000000000000000000e+00 +7.822022355158424034e+01,4.789432371652456482e+02,-1.109520445098533892e-03,7.070083081034407968e+00,3.880170356129796286e-03,9.460577691631635311e-01,-4.000000000000000327e-05,1.000000009428823056e+00,0.000000000000000000e+00 +7.822163796212021225e+01,4.789532370899671605e+02,-1.070718838901772935e-03,7.071421195110748847e+00,3.880024370728258568e-03,9.474721797124699973e-01,-4.000000000000000327e-05,1.000000009225784359e+00,0.000000000000000000e+00 +7.822305210500947226e+01,4.789632370146943003e+02,-1.031918692548038172e-03,7.072761056156457116e+00,3.879878385326720851e-03,9.488863226147725705e-01,-4.000000000000000327e-05,1.000000009301037940e+00,0.000000000000000000e+00 +7.822446598000405515e+01,4.789732369394271245e+02,-9.931200060373304717e-04,7.074102662800709318e+00,3.879732399925183133e-03,9.503001976225117220e-01,-4.000000000000000327e-05,1.000000009463655415e+00,0.000000000000000000e+00 +7.822587958685663523e+01,4.789832368641655762e+02,-9.543227793696507002e-04,7.075446013672078038e+00,3.879586414523645416e-03,9.517138044884710935e-01,-4.000000000000000327e-05,1.000000009081618790e+00,0.000000000000000000e+00 +7.822729292532048362e+01,4.789932367889097122e+02,-9.155270125449996169e-04,7.076791107398536340e+00,3.879440429122107698e-03,9.531271429651541061e-01,-4.000000000000000327e-05,1.000000009303703363e+00,0.000000000000000000e+00 +7.822870599514948253e+01,4.790032367136595326e+02,-8.767327055633779807e-04,7.078137942607461319e+00,3.879294443720569981e-03,9.545402128073008363e-01,-4.000000000000000327e-05,1.000000009503950960e+00,0.000000000000000000e+00 +7.823011879609813946e+01,4.790132366384149805e+02,-8.379398584247867675e-04,7.079486517925641209e+00,3.879148458319032263e-03,9.559530137693792451e-01,-4.000000000000000327e-05,1.000000008613243230e+00,0.000000000000000000e+00 +7.823153132792155873e+01,4.790232365631761127e+02,-7.991484711292267361e-04,7.080836831979278934e+00,3.879002472917494546e-03,9.573655456049596779e-01,-4.000000000000000327e-05,1.000000009572231896e+00,0.000000000000000000e+00 +7.823294359037545576e+01,4.790332364879429292e+02,-7.603585436766987539e-04,7.082188883393994772e+00,3.878856487515956828e-03,9.587778080723786678e-01,-4.000000000000000327e-05,1.000000009092128606e+00,0.000000000000000000e+00 +7.823435558321618544e+01,4.790432364127153733e+02,-7.215700760672035799e-04,7.083542670794837015e+00,3.878710502114419111e-03,9.601898009259396405e-01,-4.000000000000000327e-05,1.000000008784152294e+00,0.000000000000000000e+00 +7.823576730620068531e+01,4.790532363374935017e+02,-6.827830683007420813e-04,7.084898192806280193e+00,3.878564516712881393e-03,9.616015239228337119e-01,-4.000000000000000327e-05,1.000000009374421683e+00,0.000000000000000000e+00 +7.823717875908650399e+01,4.790632362622772575e+02,-6.439975203773150173e-04,7.086255448052233064e+00,3.878418531311343675e-03,9.630129768218884667e-01,-4.000000000000000327e-05,1.000000008916679617e+00,0.000000000000000000e+00 +7.823858994163182956e+01,4.790732361870666978e+02,-6.052134322969233635e-04,7.087614435156044834e+00,3.878272545909805958e-03,9.644241593797957535e-01,-4.000000000000000327e-05,1.000000009034202941e+00,0.000000000000000000e+00 +7.824000085359543277e+01,4.790832361118618223e+02,-5.664308040595677704e-04,7.088975152740506047e+00,3.878126560508268240e-03,9.658350713561498768e-01,-4.000000000000000327e-05,1.000000009124751621e+00,0.000000000000000000e+00 +7.824141149473672385e+01,4.790932360366625744e+02,-5.276496356652492139e-04,7.090337599427856574e+00,3.877980575106730523e-03,9.672457125103062214e-01,-4.000000000000000327e-05,1.000000008588296962e+00,0.000000000000000000e+00 +7.824282186481569568e+01,4.791032359614690108e+02,-4.888699271139684529e-04,7.091701773839789169e+00,3.877834589705192805e-03,9.686560826013848047e-01,-4.000000000000000327e-05,1.000000009060068473e+00,0.000000000000000000e+00 +7.824423196359295218e+01,4.791132358862810747e+02,-4.500916784057263005e-04,7.093067674597453021e+00,3.877688604303655088e-03,9.700661813914226439e-01,-4.000000000000000327e-05,1.000000008607026647e+00,0.000000000000000000e+00 +7.824564179082973681e+01,4.791232358110988230e+02,-4.113148895405236241e-04,7.094435300321461746e+00,3.877542618902117370e-03,9.714760086403411155e-01,-4.000000000000000327e-05,1.000000008872029555e+00,0.000000000000000000e+00 +7.824705134628787562e+01,4.791332357359222556e+02,-3.725395605183611826e-04,7.095804649631894279e+00,3.877396633500579653e-03,9.728855641109882546e-01,-4.000000000000000327e-05,1.000000008820790542e+00,0.000000000000000000e+00 +7.824846062972981997e+01,4.791432356607513157e+02,-3.337656913392398434e-04,7.097175721148302863e+00,3.877250648099041935e-03,9.742948475653638862e-01,-4.000000000000000327e-05,1.000000008315463207e+00,0.000000000000000000e+00 +7.824986964091861807e+01,4.791532355855860601e+02,-2.949932820031604739e-04,7.098548513489715717e+00,3.877104662697504218e-03,9.757038587658836137e-01,-4.000000000000000327e-05,1.000000008564015719e+00,0.000000000000000000e+00 +7.825127837961794341e+01,4.791632355104264320e+02,-2.562223325101238331e-04,7.099923025274641475e+00,3.876958677295966500e-03,9.771125974772746359e-01,-4.000000000000000327e-05,1.000000008540830265e+00,0.000000000000000000e+00 +7.825268684559206633e+01,4.791732354352724883e+02,-2.174528428601307881e-04,7.101299255121076293e+00,3.876812691894428783e-03,9.785210634634282645e-01,-4.000000000000000327e-05,1.000000008566098497e+00,0.000000000000000000e+00 +7.825409503860586824e+01,4.791832353601241721e+02,-1.786848130531821523e-04,7.102677201646506511e+00,3.876666706492891065e-03,9.799292564892959634e-01,-4.000000000000000327e-05,1.000000007619099351e+00,0.000000000000000000e+00 +7.825550295842484161e+01,4.791932352849815402e+02,-1.399182430892787659e-04,7.104056863467913985e+00,3.876520721091353348e-03,9.813371763190008590e-01,-4.000000000000000327e-05,1.000000008267117435e+00,0.000000000000000000e+00 +7.825691060481508998e+01,4.792032352098445926e+02,-1.011531329684214420e-04,7.105438239201778750e+00,3.876374735689815630e-03,9.827448227208892551e-01,-4.000000000000000327e-05,1.000000008152927444e+00,0.000000000000000000e+00 +7.825831797754332797e+01,4.792132351347132726e+02,-6.238948269061100730e-05,7.106821327464088789e+00,3.876228750288277913e-03,9.841521954605969569e-01,-4.000000000000000327e-05,1.000000007608982111e+00,0.000000000000000000e+00 +7.825972507637686704e+01,4.792232350595876369e+02,-2.362729225584828856e-05,7.108206126870340036e+00,3.876082764886740195e-03,9.855592943048362420e-01,-4.000000000000000327e-05,1.000000006972984634e+00,0.000000000000000000e+00 +7.826113190108362971e+01,4.792332349844676287e+02,1.513343833586589432e-05,7.109592636035541702e+00,3.875936779485202478e-03,9.869661190214026325e-01,-4.000000000000000327e-05,1.000000007933142143e+00,0.000000000000000000e+00 +7.826253845143214960e+01,4.792432349093533048e+02,5.389270908453070786e-05,7.110980853574221605e+00,3.875790794083664760e-03,9.883726693810738206e-01,-4.000000000000000327e-05,1.000000006344925030e+00,0.000000000000000000e+00 +7.826394472719155715e+01,4.792532348342446085e+02,9.265051999014531857e-05,7.112370778100434165e+00,3.875644808682127043e-03,9.897789451494051205e-01,-4.000000000000000327e-05,1.000000006597302260e+00,0.000000000000000000e+00 +7.826535072813160809e+01,4.792632347591415964e+02,1.314068710527089201e-04,7.113762408227756850e+00,3.875498823280589325e-03,9.911849460987318672e-01,-4.000000000000000327e-05,1.000000005449024343e+00,0.000000000000000000e+00 +7.826675645402265502e+01,4.792732346840442119e+02,1.701617622722206586e-04,7.115155742569303499e+00,3.875352837879051607e-03,9.925906719974383341e-01,-4.000000000000000327e-05,1.000000005502136746e+00,0.000000000000000000e+00 +7.826816190463566159e+01,4.792832346089525117e+02,2.089151936486797481e-04,7.116550779737722543e+00,3.875206852477513890e-03,9.939961226181734943e-01,-4.000000000000000327e-05,1.000000003068749477e+00,0.000000000000000000e+00 +7.826956707974218830e+01,4.792932345338664391e+02,2.476671651820853211e-04,7.117947518345206781e+00,3.875060867075976172e-03,9.954012977290094266e-01,-4.000000000000000327e-05,1.000000001658722271e+00,0.000000000000000000e+00 +7.827097197911440674e+01,4.793032344587860507e+02,2.864176768724365917e-04,7.119345957003490710e+00,3.874914881674438455e-03,9.968061971035572233e-01,-4.000000000000000327e-05,9.999999975877427172e-01,0.000000000000000000e+00 +7.827237660252509954e+01,4.793132343837112899e+02,3.251667287197327195e-04,7.120746094323862074e+00,3.874768896272900737e-03,9.982108205108577437e-01,-4.000000000000000327e-05,9.999999844657100345e-01,0.000000000000000000e+00 +7.827378094974764622e+01,4.793232343086422134e+02,3.639143207239728373e-04,7.122147928917159199e+00,3.874622910871363020e-03,9.996151677115855394e-01,-4.000000000000000327e-05,2.740903454321298449e-01,0.000000000000000000e+00 +7.827518502055603733e+01,4.793332342335788212e+02,4.026604528851561861e-04,7.123551459393762997e+00,3.874476925469825302e-03,1.000000009964467251e+00,-4.000000000000000327e-05,2.182809713860620970e-11,0.000000000000000000e+00 +7.827658881472486030e+01,4.793432341585210565e+02,4.414051252032818984e-04,7.124955253576573000e+00,3.874330940068287585e-03,1.000000009964497893e+00,-4.000000000000000327e-05,-3.482109381530048813e-10,0.000000000000000000e+00 +7.827799233231115750e+01,4.793532340834689762e+02,4.801483376783491613e-04,7.126358771176859008e+00,3.874184954666749867e-03,1.000000009964009173e+00,-4.000000000000000327e-05,2.476408295513495513e-10,0.000000000000000000e+00 +7.827939557347836796e+01,4.793632340084225234e+02,5.188900903103571072e-04,7.127762012358047627e+00,3.874038969265212150e-03,1.000000009964356673e+00,-4.000000000000000327e-05,-1.071475104722807322e-10,0.000000000000000000e+00 +7.828079853838974600e+01,4.793732339333817549e+02,5.576303830993050315e-04,7.129164977283406479e+00,3.873892983863674432e-03,1.000000009964206349e+00,-4.000000000000000327e-05,2.798730953620834451e-10,0.000000000000000000e+00 +7.828220122720840379e+01,4.793832338583466139e+02,5.963692160451919584e-04,7.130567666116040648e+00,3.873746998462136715e-03,1.000000009964598924e+00,-4.000000000000000327e-05,-5.096655834530569018e-10,0.000000000000000000e+00 +7.828360364009728301e+01,4.793932337833171005e+02,6.351065891480171290e-04,7.131970079018896236e+00,3.873601013060598997e-03,1.000000009963884162e+00,-4.000000000000000327e-05,1.217800302991796434e-10,0.000000000000000000e+00 +7.828500577721916898e+01,4.794032337082932713e+02,6.738425024077797842e-04,7.133372216154756806e+00,3.873455027659061280e-03,1.000000009964054914e+00,-4.000000000000000327e-05,2.561209660694672404e-10,0.000000000000000000e+00 +7.828640763873669073e+01,4.794132336332750697e+02,7.125769558244789484e-04,7.134774077686248717e+00,3.873309042257523562e-03,1.000000009964413961e+00,-4.000000000000000327e-05,-2.195753994554548148e-10,0.000000000000000000e+00 +7.828780922481230675e+01,4.794232335582625524e+02,7.513099493981138625e-04,7.136175663775837563e+00,3.873163056855985845e-03,1.000000009964106207e+00,-4.000000000000000327e-05,3.921759532198354162e-10,0.000000000000000000e+00 +7.828921053560833343e+01,4.794332334832556626e+02,7.900414831286837677e-04,7.137576974585828182e+00,3.873017071454448127e-03,1.000000009964655767e+00,-4.000000000000000327e-05,-2.816297036431828971e-10,0.000000000000000000e+00 +7.829061157128691661e+01,4.794432334082544571e+02,8.287715570161877966e-04,7.138978010278368203e+00,3.872871086052910410e-03,1.000000009964261194e+00,-4.000000000000000327e-05,-9.098884707680684832e-11,0.000000000000000000e+00 +7.829201233201003163e+01,4.794532333332588792e+02,8.675001710606250818e-04,7.140378771015443604e+00,3.872725100651372692e-03,1.000000009964133740e+00,-4.000000000000000327e-05,-5.105253917985159242e-11,0.000000000000000000e+00 +7.829341281793951168e+01,4.794632332582689855e+02,9.062273252619948644e-04,7.141779256958883160e+00,3.872579115249834975e-03,1.000000009964062242e+00,-4.000000000000000327e-05,1.796704096198457065e-10,0.000000000000000000e+00 +7.829481302923703367e+01,4.794732331832847194e+02,9.449530196202962770e-04,7.143179468270356658e+00,3.872433129848297257e-03,1.000000009964313819e+00,-4.000000000000000327e-05,-4.161938110756361502e-10,0.000000000000000000e+00 +7.829621296606410397e+01,4.794832331083061376e+02,9.836772541355284522e-04,7.144579405111375792e+00,3.872287144446759539e-03,1.000000009963731173e+00,-4.000000000000000327e-05,3.169657792104214272e-10,0.000000000000000000e+00 +7.829761262858207260e+01,4.794932330333331834e+02,1.022400028807690740e-03,7.145979067643292382e+00,3.872141159045221822e-03,1.000000009964174819e+00,-4.000000000000000327e-05,2.062743928540617766e-12,0.000000000000000000e+00 +7.829901201695213331e+01,4.795032329583659134e+02,1.061121343636782163e-03,7.147378456027302818e+00,3.871995173643684104e-03,1.000000009964177705e+00,-4.000000000000000327e-05,3.421651395817374467e-10,0.000000000000000000e+00 +7.830041113133533770e+01,4.795132328834042710e+02,1.099841198622801856e-03,7.148777570424443617e+00,3.871849188242146387e-03,1.000000009964656433e+00,-4.000000000000000327e-05,-5.874773065382058466e-10,0.000000000000000000e+00 +7.830180997189255265e+01,4.795232328084482560e+02,1.138559593765749167e-03,7.150176410995594978e+00,3.871703202840608669e-03,1.000000009963834646e+00,-4.000000000000000327e-05,2.795865907626203258e-10,0.000000000000000000e+00 +7.830320853878450293e+01,4.795332327334979254e+02,1.177276529065623013e-03,7.151574977901477226e+00,3.871557217439070952e-03,1.000000009964225667e+00,-4.000000000000000327e-05,1.102050236548551897e-10,0.000000000000000000e+00 +7.830460683217174278e+01,4.795432326585532223e+02,1.215992004522422742e-03,7.152973271302657032e+00,3.871411232037533234e-03,1.000000009964379766e+00,-4.000000000000000327e-05,-2.979611636747266797e-10,0.000000000000000000e+00 +7.830600485221469853e+01,4.795532325836142036e+02,1.254706020136147704e-03,7.154371291359542084e+00,3.871265246635995517e-03,1.000000009963963210e+00,-4.000000000000000327e-05,-1.456736614486131460e-10,0.000000000000000000e+00 +7.830740259907361178e+01,4.795632325086808123e+02,1.293418575906796816e-03,7.155769038232382862e+00,3.871119261234457799e-03,1.000000009963759595e+00,-4.000000000000000327e-05,4.585565137457926717e-10,0.000000000000000000e+00 +7.830880007290858202e+01,4.795732324337531054e+02,1.332129671834369209e-03,7.157166512081274412e+00,3.870973275832920082e-03,1.000000009964400416e+00,-4.000000000000000327e-05,-4.147838649555729464e-10,0.000000000000000000e+00 +7.831019727387953822e+01,4.795832323588310260e+02,1.370839307918864233e-03,7.158563713066156353e+00,3.870827290431382364e-03,1.000000009963820879e+00,-4.000000000000000327e-05,3.101154400873456347e-10,0.000000000000000000e+00 +7.831159420214626721e+01,4.795932322839145741e+02,1.409547484160281021e-03,7.159960641346809318e+00,3.870681305029844647e-03,1.000000009964254089e+00,-4.000000000000000327e-05,-2.066779821452613834e-10,0.000000000000000000e+00 +7.831299085786839953e+01,4.796032322090038065e+02,1.448254200558618705e-03,7.161357297082861173e+00,3.870535319628306929e-03,1.000000009963965431e+00,-4.000000000000000327e-05,2.025839317739378538e-10,0.000000000000000000e+00 +7.831438724120540940e+01,4.796132321340986664e+02,1.486959457113876419e-03,7.162753680433781689e+00,3.870389334226769212e-03,1.000000009964248315e+00,-4.000000000000000327e-05,-3.930003954344812585e-10,0.000000000000000000e+00 +7.831578335231660049e+01,4.796232320591992107e+02,1.525663253826053511e-03,7.164149791558886982e+00,3.870243348825231494e-03,1.000000009963699643e+00,-4.000000000000000327e-05,1.762562977580205541e-10,0.000000000000000000e+00 +7.831717919136114858e+01,4.796332319843053824e+02,1.564365590695148897e-03,7.165545630617335959e+00,3.870097363423693777e-03,1.000000009963945669e+00,-4.000000000000000327e-05,-2.084302680695750829e-11,0.000000000000000000e+00 +7.831857475849804473e+01,4.796432319094171817e+02,1.603066467721161927e-03,7.166941197768134764e+00,3.869951378022156059e-03,1.000000009963916581e+00,-4.000000000000000327e-05,2.746722961821168663e-10,0.000000000000000000e+00 +7.831997005388613786e+01,4.796532318345346653e+02,1.641765884904091734e-03,7.168336493170133217e+00,3.869805392620618342e-03,1.000000009964299830e+00,-4.000000000000000327e-05,-4.136803465504085574e-10,0.000000000000000000e+00 +7.832136507768413480e+01,4.796632317596577764e+02,1.680463842243937666e-03,7.169731516982027486e+00,3.869659407219080624e-03,1.000000009963722736e+00,-4.000000000000000327e-05,5.441456690801109208e-10,0.000000000000000000e+00 +7.832275983005057185e+01,4.796732316847865718e+02,1.719160339740698640e-03,7.171126269362357419e+00,3.869513421817542907e-03,1.000000009964481684e+00,-4.000000000000000327e-05,-6.119246943194664330e-10,0.000000000000000000e+00 +7.832415431114382898e+01,4.796832316099209947e+02,1.757855377394374006e-03,7.172520750469511874e+00,3.869367436416005189e-03,1.000000009963628367e+00,-4.000000000000000327e-05,1.205612989020425854e-10,0.000000000000000000e+00 +7.832554852112214405e+01,4.796932315350610452e+02,1.796548955204962895e-03,7.173914960461721613e+00,3.869221451014467471e-03,1.000000009963796455e+00,-4.000000000000000327e-05,3.504444048955288047e-10,0.000000000000000000e+00 +7.832694246014359862e+01,4.797032314602067800e+02,1.835241073172464441e-03,7.175308899497067294e+00,3.869075465612929754e-03,1.000000009964284953e+00,-4.000000000000000327e-05,-4.880089923089307524e-10,0.000000000000000000e+00 +7.832833612836611792e+01,4.797132313853581422e+02,1.873931731296877776e-03,7.176702567733475036e+00,3.868929480211392036e-03,1.000000009963604830e+00,-4.000000000000000327e-05,2.419005995028958817e-10,0.000000000000000000e+00 +7.832972952594747085e+01,4.797232313105151320e+02,1.912620929578202032e-03,7.178095965328715522e+00,3.868783494809854319e-03,1.000000009963941894e+00,-4.000000000000000327e-05,1.464755026633810370e-10,0.000000000000000000e+00 +7.833112265304528421e+01,4.797332312356778061e+02,1.951308668016436560e-03,7.179489092440409337e+00,3.868637509408316601e-03,1.000000009964145953e+00,-4.000000000000000327e-05,3.331808651907509982e-11,0.000000000000000000e+00 +7.833251550981701428e+01,4.797432311608461077e+02,1.989994946611580492e-03,7.180881949226022520e+00,3.868491524006778884e-03,1.000000009964192360e+00,-4.000000000000000327e-05,-2.045712830435639016e-10,0.000000000000000000e+00 +7.833390809641998942e+01,4.797532310860200937e+02,2.028679765363632960e-03,7.182274535842868346e+00,3.868345538605241166e-03,1.000000009963907477e+00,-4.000000000000000327e-05,-2.160934097454233963e-10,0.000000000000000000e+00 +7.833530041301135327e+01,4.797632310111997072e+02,2.067363124272593097e-03,7.183666852448107321e+00,3.868199553203703449e-03,1.000000009963606606e+00,-4.000000000000000327e-05,3.510802924430907510e-10,0.000000000000000000e+00 +7.833669245974812156e+01,4.797732309363849481e+02,2.106045023338460036e-03,7.185058899198748072e+00,3.868053567802165731e-03,1.000000009964095327e+00,-4.000000000000000327e-05,-4.430435698993245538e-10,0.000000000000000000e+00 +7.833808423678715371e+01,4.797832308615758734e+02,2.144725462561233344e-03,7.186450676251648240e+00,3.867907582400628014e-03,1.000000009963478709e+00,-4.000000000000000327e-05,5.044047532461228688e-10,0.000000000000000000e+00 +7.833947574428515281e+01,4.797932307867724262e+02,2.183404441940911718e-03,7.187842183763510917e+00,3.867761596999090296e-03,1.000000009964180592e+00,-4.000000000000000327e-05,-5.815902630076193754e-10,0.000000000000000000e+00 +7.834086698239866564e+01,4.798032307119746065e+02,2.222081961477494726e-03,7.189233421890890874e+00,3.867615611597552579e-03,1.000000009963371461e+00,-4.000000000000000327e-05,3.219798608168106168e-10,0.000000000000000000e+00 +7.834225795128409686e+01,4.798132306371824711e+02,2.260758021170981066e-03,7.190624390790187448e+00,3.867469626196014861e-03,1.000000009963819325e+00,-4.000000000000000327e-05,3.563699033702615858e-10,0.000000000000000000e+00 +7.834364865109770903e+01,4.798232305623959633e+02,2.299432621021370304e-03,7.192015090617652540e+00,3.867323640794477144e-03,1.000000009964314929e+00,-4.000000000000000327e-05,-5.859202760189179393e-10,0.000000000000000000e+00 +7.834503908199559419e+01,4.798332304876150829e+02,2.338105761028661574e-03,7.193405521529385283e+00,3.867177655392939426e-03,1.000000009963500247e+00,-4.000000000000000327e-05,1.467879079238955050e-10,0.000000000000000000e+00 +7.834642924413368803e+01,4.798432304128398869e+02,2.376777441192854008e-03,7.194795683681332044e+00,3.867031669991401709e-03,1.000000009963704306e+00,-4.000000000000000327e-05,1.517687286844374911e-10,0.000000000000000000e+00 +7.834781913766779837e+01,4.798532303380703183e+02,2.415447661513946739e-03,7.196185577229291752e+00,3.866885684589863991e-03,1.000000009963915248e+00,-4.000000000000000327e-05,-2.174706763693260644e-10,0.000000000000000000e+00 +7.834920876275357671e+01,4.798632302633063773e+02,2.454116421991938898e-03,7.197575202328911459e+00,3.866739699188326274e-03,1.000000009963613046e+00,-4.000000000000000327e-05,3.143625453945413219e-10,0.000000000000000000e+00 +7.835059811954650399e+01,4.798732301885480638e+02,2.492783722626829620e-03,7.198964559135687225e+00,3.866593713786788556e-03,1.000000009964049807e+00,-4.000000000000000327e-05,-1.982129139339206462e-10,0.000000000000000000e+00 +7.835198720820194751e+01,4.798832301137954346e+02,2.531449563418618036e-03,7.200353647804966783e+00,3.866447728385250839e-03,1.000000009963774472e+00,-4.000000000000000327e-05,-1.966523607688255208e-11,0.000000000000000000e+00 +7.835337602887508979e+01,4.798932300390484329e+02,2.570113944367303713e-03,7.201742468491945992e+00,3.866301742983713121e-03,1.000000009963747161e+00,-4.000000000000000327e-05,-1.747825110878608483e-10,0.000000000000000000e+00 +7.835476458172098546e+01,4.799032299643070587e+02,2.608776865472885349e-03,7.203131021351672381e+00,3.866155757582175403e-03,1.000000009963504466e+00,-4.000000000000000327e-05,1.529042061057461440e-10,0.000000000000000000e+00 +7.835615286689451864e+01,4.799132298895713689e+02,2.647438326735362512e-03,7.204519306539043377e+00,3.866009772180637686e-03,1.000000009963716741e+00,-4.000000000000000327e-05,-6.254923354502320167e-11,0.000000000000000000e+00 +7.835754088455045974e+01,4.799232298148413065e+02,2.686098328154733900e-03,7.205907324208808085e+00,3.865863786779099968e-03,1.000000009963629921e+00,-4.000000000000000327e-05,4.574493903655825831e-10,0.000000000000000000e+00 +7.835892863484339443e+01,4.799332297401168717e+02,2.724756869730999079e-03,7.207295074515565503e+00,3.865717801377562251e-03,1.000000009964264747e+00,-4.000000000000000327e-05,-6.971085341109750978e-10,0.000000000000000000e+00 +7.836031611792776630e+01,4.799432296653981211e+02,2.763413951464157182e-03,7.208682557613767194e+00,3.865571815976024533e-03,1.000000009963297520e+00,-4.000000000000000327e-05,5.213314022733514681e-10,0.000000000000000000e+00 +7.836170333395789100e+01,4.799532295906849981e+02,2.802069573354207341e-03,7.210069773657712844e+00,3.865425830574486816e-03,1.000000009964020720e+00,-4.000000000000000327e-05,-6.054819730921471780e-10,0.000000000000000000e+00 +7.836309028308791369e+01,4.799632295159775026e+02,2.840723735401148690e-03,7.211456722801558250e+00,3.865279845172949098e-03,1.000000009963180947e+00,-4.000000000000000327e-05,4.352238430221840527e-10,0.000000000000000000e+00 +7.836447696547185160e+01,4.799732294412756346e+02,2.879376437604980361e-03,7.212843405199306446e+00,3.865133859771411381e-03,1.000000009963784464e+00,-4.000000000000000327e-05,-1.543916337579027906e-10,0.000000000000000000e+00 +7.836586338126355145e+01,4.799832293665794509e+02,2.918027679965701920e-03,7.214229821004816579e+00,3.864987874369873663e-03,1.000000009963570413e+00,-4.000000000000000327e-05,2.936247525542741020e-10,0.000000000000000000e+00 +7.836724953061671783e+01,4.799932292918888947e+02,2.956677462483312067e-03,7.215615970371796806e+00,3.864841888968335946e-03,1.000000009963977421e+00,-4.000000000000000327e-05,-1.725557119434212366e-10,0.000000000000000000e+00 +7.836863541368492747e+01,4.800032292172039661e+02,2.995325785157810367e-03,7.217001853453809623e+00,3.864695903566798228e-03,1.000000009963738279e+00,-4.000000000000000327e-05,-2.693796322818154705e-10,0.000000000000000000e+00 +7.837002103062158653e+01,4.800132291425246649e+02,3.033972647989195519e-03,7.218387470404268313e+00,3.864549918165260511e-03,1.000000009963365022e+00,-4.000000000000000327e-05,3.635159458531962512e-10,0.000000000000000000e+00 +7.837140638157995909e+01,4.800232290678510481e+02,3.072618050977467090e-03,7.219772821376439609e+00,3.864403932763722793e-03,1.000000009963868619e+00,-4.000000000000000327e-05,-2.279624700562376298e-10,0.000000000000000000e+00 +7.837279146671316710e+01,4.800332289931830587e+02,3.111261994122624212e-03,7.221157906523444581e+00,3.864257947362185076e-03,1.000000009963552872e+00,-4.000000000000000327e-05,1.675573016405751290e-10,0.000000000000000000e+00 +7.837417628617417620e+01,4.800432289185206969e+02,3.149904477424666019e-03,7.222542725998255086e+00,3.864111961960647358e-03,1.000000009963784908e+00,-4.000000000000000327e-05,-4.047806054878665537e-10,0.000000000000000000e+00 +7.837556084011582413e+01,4.800532288438639625e+02,3.188545500883591642e-03,7.223927279953698211e+00,3.863965976559109641e-03,1.000000009963224468e+00,-4.000000000000000327e-05,2.693173218447033012e-10,0.000000000000000000e+00 +7.837694512869079233e+01,4.800632287692129125e+02,3.227185064499400215e-03,7.225311568542452711e+00,3.863819991157571923e-03,1.000000009963597281e+00,-4.000000000000000327e-05,-2.299021301715183855e-10,0.000000000000000000e+00 +7.837832915205160589e+01,4.800732286945674900e+02,3.265823168272090869e-03,7.226695591917053463e+00,3.863674005756034206e-03,1.000000009963279091e+00,-4.000000000000000327e-05,3.135483691930823091e-10,0.000000000000000000e+00 +7.837971291035064780e+01,4.800832286199276950e+02,3.304459812201662738e-03,7.228079350229887012e+00,3.863528020354496488e-03,1.000000009963712966e+00,-4.000000000000000327e-05,-5.777841685278860224e-11,0.000000000000000000e+00 +7.838109640374017317e+01,4.800932285452935275e+02,3.343094996288115388e-03,7.229462843633196023e+00,3.863382034952958771e-03,1.000000009963633030e+00,-4.000000000000000327e-05,-5.393684422340680474e-11,0.000000000000000000e+00 +7.838247963237226656e+01,4.801032284706650444e+02,3.381728720531447518e-03,7.230846072279075720e+00,3.863236049551421053e-03,1.000000009963558423e+00,-4.000000000000000327e-05,-2.408355539089382433e-10,0.000000000000000000e+00 +7.838386259639888465e+01,4.801132283960421887e+02,3.420360984931658695e-03,7.232229036319476556e+00,3.863090064149883335e-03,1.000000009963225356e+00,-4.000000000000000327e-05,2.086034793386870668e-10,0.000000000000000000e+00 +7.838524529597184198e+01,4.801232283214249605e+02,3.458991789488748050e-03,7.233611735906203322e+00,3.862944078748345618e-03,1.000000009963513792e+00,-4.000000000000000327e-05,2.646991990212437921e-10,0.000000000000000000e+00 +7.838662773124278260e+01,4.801332282468133599e+02,3.497621134202714716e-03,7.234994171190916923e+00,3.862798093346807900e-03,1.000000009963879721e+00,-4.000000000000000327e-05,-1.755895124658051654e-10,0.000000000000000000e+00 +7.838800990236322264e+01,4.801432281722073867e+02,3.536249019073557827e-03,7.236376342325132605e+00,3.862652107945270183e-03,1.000000009963637027e+00,-4.000000000000000327e-05,-2.831178650447992771e-10,0.000000000000000000e+00 +7.838939180948453611e+01,4.801532280976070979e+02,3.574875444101276514e-03,7.237758249460219950e+00,3.862506122543732465e-03,1.000000009963245784e+00,-4.000000000000000327e-05,3.067963771523531614e-10,0.000000000000000000e+00 +7.839077345275795494e+01,4.801632280230124366e+02,3.613500409285869911e-03,7.239139892747404659e+00,3.862360137142194748e-03,1.000000009963669667e+00,-4.000000000000000327e-05,-3.685795618506526707e-10,0.000000000000000000e+00 +7.839215483233455473e+01,4.801732279484234027e+02,3.652123914627337150e-03,7.240521272337769432e+00,3.862214151740657030e-03,1.000000009963160519e+00,-4.000000000000000327e-05,3.827978189860076972e-10,0.000000000000000000e+00 +7.839353594836526895e+01,4.801832278738399964e+02,3.690745960125677363e-03,7.241902388382250422e+00,3.862068166339119313e-03,1.000000009963689207e+00,-4.000000000000000327e-05,-3.335044585718269202e-10,0.000000000000000000e+00 +7.839491680100090321e+01,4.801932277992622176e+02,3.729366545780890118e-03,7.243283241031642561e+00,3.861922180937581595e-03,1.000000009963228687e+00,-4.000000000000000327e-05,1.762731834314008600e-10,0.000000000000000000e+00 +7.839629739039210676e+01,4.802032277246901231e+02,3.767985671592974112e-03,7.244663830436594232e+00,3.861776195536043878e-03,1.000000009963472047e+00,-4.000000000000000327e-05,-5.099384102199345023e-11,0.000000000000000000e+00 +7.839767771668937257e+01,4.802132276501236561e+02,3.806603337561928913e-03,7.246044156747612597e+00,3.861630210134506160e-03,1.000000009963401659e+00,-4.000000000000000327e-05,-1.848677818850454207e-10,0.000000000000000000e+00 +7.839905778004306569e+01,4.802232275755628166e+02,3.845219543687753653e-03,7.247424220115060045e+00,3.861484224732968443e-03,1.000000009963146530e+00,-4.000000000000000327e-05,1.416141273958005468e-10,0.000000000000000000e+00 +7.840043758060340906e+01,4.802332275010076046e+02,3.883834289970447464e-03,7.248804020689155969e+00,3.861338239331430725e-03,1.000000009963341929e+00,-4.000000000000000327e-05,3.624724221793935599e-10,0.000000000000000000e+00 +7.840181711852048352e+01,4.802432274264580201e+02,3.922447576410009046e-03,7.250183558619977653e+00,3.861192253929893008e-03,1.000000009963841974e+00,-4.000000000000000327e-05,-5.566910209632932467e-10,0.000000000000000000e+00 +7.840319639394422779e+01,4.802532273519140631e+02,3.961059403006438398e-03,7.251562834057459384e+00,3.861046268528355290e-03,1.000000009963074143e+00,-4.000000000000000327e-05,8.566106552351389094e-11,0.000000000000000000e+00 +7.840457540702442429e+01,4.802632272773757904e+02,3.999669769759734220e-03,7.252941847151390675e+00,3.860900283126817573e-03,1.000000009963192271e+00,-4.000000000000000327e-05,3.227395120417894144e-10,0.000000000000000000e+00 +7.840595415791071332e+01,4.802732272028431453e+02,4.038278676669895643e-03,7.254320598051421598e+00,3.860754297725279855e-03,1.000000009963637249e+00,-4.000000000000000327e-05,-4.131657756812211592e-10,0.000000000000000000e+00 +7.840733264675262149e+01,4.802832271283161276e+02,4.076886123736921802e-03,7.255699086907059225e+00,3.860608312323742138e-03,1.000000009963067704e+00,-4.000000000000000327e-05,5.832141590690021384e-10,0.000000000000000000e+00 +7.840871087369949066e+01,4.802932270537947375e+02,4.115492110960811828e-03,7.257077313867666746e+00,3.860462326922204420e-03,1.000000009963871506e+00,-4.000000000000000327e-05,-5.277318183098202389e-10,0.000000000000000000e+00 +7.841008883890056325e+01,4.803032269792789748e+02,4.154096638341565721e-03,7.258455279082468792e+00,3.860316341520666703e-03,1.000000009963144310e+00,-4.000000000000000327e-05,-1.039547038452369001e-10,0.000000000000000000e+00 +7.841146654250491110e+01,4.803132269047688396e+02,4.192699705879181747e-03,7.259832982700544335e+00,3.860170356119128985e-03,1.000000009963001091e+00,-4.000000000000000327e-05,3.528682768012879000e-10,0.000000000000000000e+00 +7.841284398466147820e+01,4.803232268302643320e+02,4.231301313573659038e-03,7.261210424870833791e+00,3.860024370717591267e-03,1.000000009963487146e+00,-4.000000000000000327e-05,-1.925101244481147925e-10,0.000000000000000000e+00 +7.841422116551905219e+01,4.803332267557655086e+02,4.269901461424997595e-03,7.262587605742136354e+00,3.859878385316053550e-03,1.000000009963222025e+00,-4.000000000000000327e-05,3.386498630865927497e-11,0.000000000000000000e+00 +7.841559808522630703e+01,4.803432266812723128e+02,4.308500149433195682e-03,7.263964525463108224e+00,3.859732399914515832e-03,1.000000009963268655e+00,-4.000000000000000327e-05,-3.387140679816386375e-12,0.000000000000000000e+00 +7.841697474393174616e+01,4.803532266067847445e+02,4.347097377598253300e-03,7.265341184182266154e+00,3.859586414512978115e-03,1.000000009963263992e+00,-4.000000000000000327e-05,6.598109934709100376e-11,0.000000000000000000e+00 +7.841835114178375932e+01,4.803632265323028037e+02,4.385693145920168713e-03,7.266717582047985680e+00,3.859440429111440397e-03,1.000000009963354808e+00,-4.000000000000000327e-05,-3.252887436168969545e-10,0.000000000000000000e+00 +7.841972727893056572e+01,4.803732264578264903e+02,4.424287454398941923e-03,7.268093719208502002e+00,3.859294443709902680e-03,1.000000009962907166e+00,-4.000000000000000327e-05,6.008330037191201570e-10,0.000000000000000000e+00 +7.842110315552027089e+01,4.803832263833558045e+02,4.462880303034572060e-03,7.269469595811909102e+00,3.859148458308364962e-03,1.000000009963733838e+00,-4.000000000000000327e-05,-5.376722006211635712e-10,0.000000000000000000e+00 +7.842247877170082404e+01,4.803932263088907462e+02,4.501471691827058259e-03,7.270845212006163294e+00,3.859002472906827245e-03,1.000000009962994207e+00,-4.000000000000000327e-05,3.842395647118894612e-10,0.000000000000000000e+00 +7.842385412762003227e+01,4.804032262344313153e+02,4.540061620776398785e-03,7.272220567939077007e+00,3.858856487505289527e-03,1.000000009963522674e+00,-4.000000000000000327e-05,-4.862034359579450825e-10,0.000000000000000000e+00 +7.842522922342557479e+01,4.804132261599775688e+02,4.578650089882593636e-03,7.273595663758326779e+00,3.858710502103751810e-03,1.000000009962854097e+00,-4.000000000000000327e-05,4.021506062103660171e-11,0.000000000000000000e+00 +7.842660405926500289e+01,4.804232260855294498e+02,4.617237099145641947e-03,7.274970499611446151e+00,3.858564516702214092e-03,1.000000009962909386e+00,-4.000000000000000327e-05,4.576337403561054037e-10,0.000000000000000000e+00 +7.842797863528569735e+01,4.804332260110869584e+02,4.655822648565542850e-03,7.276345075645831884e+00,3.858418531300676375e-03,1.000000009963538439e+00,-4.000000000000000327e-05,-2.724024960607279338e-10,0.000000000000000000e+00 +7.842935295163491105e+01,4.804432259366500944e+02,4.694406738142295477e-03,7.277719392008741295e+00,3.858272545899138657e-03,1.000000009963164072e+00,-4.000000000000000327e-05,1.039074064359906238e-10,0.000000000000000000e+00 +7.843072700845976897e+01,4.804532258622188579e+02,4.732989367875898960e-03,7.279093448847290482e+00,3.858126560497600940e-03,1.000000009963306846e+00,-4.000000000000000327e-05,-3.922719882332697571e-10,0.000000000000000000e+00 +7.843210080590725397e+01,4.804632257877932489e+02,4.771570537766352434e-03,7.280467246308458762e+00,3.857980575096063222e-03,1.000000009962767944e+00,-4.000000000000000327e-05,4.954843670898029909e-10,0.000000000000000000e+00 +7.843347434412419261e+01,4.804732257133732674e+02,4.810150247813655029e-03,7.281840784539085121e+00,3.857834589694525505e-03,1.000000009963448511e+00,-4.000000000000000327e-05,-1.542516360963983084e-10,0.000000000000000000e+00 +7.843484762325729776e+01,4.804832256389589134e+02,4.848728498017806747e-03,7.283214063685872652e+00,3.857688604292987787e-03,1.000000009963236680e+00,-4.000000000000000327e-05,-8.457947576329585859e-11,0.000000000000000000e+00 +7.843622064345312594e+01,4.804932255645501868e+02,4.887305288378805852e-03,7.284587083895383230e+00,3.857542618891450070e-03,1.000000009963120551e+00,-4.000000000000000327e-05,-3.335291724358375851e-10,0.000000000000000000e+00 +7.843759340485810583e+01,4.805032254901470878e+02,4.925880618896651478e-03,7.285959845314041949e+00,3.857396633489912352e-03,1.000000009962662695e+00,-4.000000000000000327e-05,4.164237985957073821e-10,0.000000000000000000e+00 +7.843896590761852394e+01,4.805132254157496163e+02,4.964454489571343623e-03,7.287332348088135348e+00,3.857250648088374635e-03,1.000000009963234238e+00,-4.000000000000000327e-05,-2.888331405456705799e-10,0.000000000000000000e+00 +7.844033815188052472e+01,4.805232253413577723e+02,5.003026900402880554e-03,7.288704592363814072e+00,3.857104662686836917e-03,1.000000009962837888e+00,-4.000000000000000327e-05,2.840322768004831474e-10,0.000000000000000000e+00 +7.844171013779012469e+01,4.805332252669715558e+02,5.041597851391261403e-03,7.290076578287088438e+00,3.856958677285299199e-03,1.000000009963227576e+00,-4.000000000000000327e-05,1.524836287624439588e-10,0.000000000000000000e+00 +7.844308186549319828e+01,4.805432251925910236e+02,5.080167342536486171e-03,7.291448306003833757e+00,3.856812691883761482e-03,1.000000009963436742e+00,-4.000000000000000327e-05,-3.084245974824218571e-10,0.000000000000000000e+00 +7.844445333513549201e+01,4.805532251182161190e+02,5.118735373838553988e-03,7.292819775659786785e+00,3.856666706482223764e-03,1.000000009963013747e+00,-4.000000000000000327e-05,-2.503486167964037513e-10,0.000000000000000000e+00 +7.844582454686259609e+01,4.805632250438468418e+02,5.157301945297463122e-03,7.294190987400546611e+00,3.856520721080686047e-03,1.000000009962670466e+00,-4.000000000000000327e-05,2.317698766900507116e-10,0.000000000000000000e+00 +7.844719550081997284e+01,4.805732249694831921e+02,5.195867056913213572e-03,7.295561941371576431e+00,3.856374735679148329e-03,1.000000009962988212e+00,-4.000000000000000327e-05,9.735840415557454949e-11,0.000000000000000000e+00 +7.844856619715294244e+01,4.805832248951251700e+02,5.234430708685804470e-03,7.296932637718203551e+00,3.856228750277610612e-03,1.000000009963121661e+00,-4.000000000000000327e-05,-2.773858626297879313e-10,0.000000000000000000e+00 +7.844993663600669720e+01,4.805932248207727753e+02,5.272992900615234083e-03,7.298303076585617610e+00,3.856082764876072894e-03,1.000000009962741521e+00,-4.000000000000000327e-05,4.315521516350950891e-10,0.000000000000000000e+00 +7.845130681752630153e+01,4.806032247464260081e+02,5.311553632701502409e-03,7.299673258118871466e+00,3.855936779474535177e-03,1.000000009963332825e+00,-4.000000000000000327e-05,-2.363203768304636683e-10,0.000000000000000000e+00 +7.845267674185666351e+01,4.806132246720848684e+02,5.350112904944608581e-03,7.301043182462883863e+00,3.855790794072997459e-03,1.000000009963009084e+00,-4.000000000000000327e-05,-1.102386929313583754e-11,0.000000000000000000e+00 +7.845404640914256333e+01,4.806232245977493562e+02,5.388670717344551733e-03,7.302412849762434988e+00,3.855644808671459742e-03,1.000000009962993985e+00,-4.000000000000000327e-05,6.729064711333633230e-11,0.000000000000000000e+00 +7.845541581952865329e+01,4.806332245234194716e+02,5.427227069901330997e-03,7.303782260162170914e+00,3.855498823269922024e-03,1.000000009963086134e+00,-4.000000000000000327e-05,-9.779245641889453897e-11,0.000000000000000000e+00 +7.845678497315944355e+01,4.806432244490952144e+02,5.465781962614945505e-03,7.305151413806601823e+00,3.855352837868384307e-03,1.000000009962952241e+00,-4.000000000000000327e-05,-1.265214178485052288e-10,0.000000000000000000e+00 +7.845815387017930220e+01,4.806532243747765847e+02,5.504335395485394390e-03,7.306520310840102006e+00,3.855206852466846589e-03,1.000000009962779046e+00,-4.000000000000000327e-05,-1.135661391058045066e-10,0.000000000000000000e+00 +7.845952251073246941e+01,4.806632243004635825e+02,5.542887368512676785e-03,7.307888951406910749e+00,3.855060867065308872e-03,1.000000009962623615e+00,-4.000000000000000327e-05,3.208033051856120994e-10,0.000000000000000000e+00 +7.846089089496305746e+01,4.806732242261562078e+02,5.581437881696792690e-03,7.309257335651132337e+00,3.854914881663771154e-03,1.000000009963062597e+00,-4.000000000000000327e-05,1.337336473689395153e-10,0.000000000000000000e+00 +7.846225902301503652e+01,4.806832241518544606e+02,5.619986935037740369e-03,7.310625463716736938e+00,3.854768896262233437e-03,1.000000009963245562e+00,-4.000000000000000327e-05,-2.954378595979459118e-10,0.000000000000000000e+00 +7.846362689503223464e+01,4.806932240775583409e+02,5.658534528535518957e-03,7.311993335747558831e+00,3.854622910860695719e-03,1.000000009962841441e+00,-4.000000000000000327e-05,-1.112158239943612112e-10,0.000000000000000000e+00 +7.846499451115835200e+01,4.807032240032678487e+02,5.697080662190128451e-03,7.313360951887297290e+00,3.854476925459158002e-03,1.000000009962689340e+00,-4.000000000000000327e-05,1.183817518219019000e-10,0.000000000000000000e+00 +7.846636187153694664e+01,4.807132239289829840e+02,5.735625336001567119e-03,7.314728312279518363e+00,3.854330940057620284e-03,1.000000009962851211e+00,-4.000000000000000327e-05,-1.762252614683940653e-10,0.000000000000000000e+00 +7.846772897631146293e+01,4.807232238547037468e+02,5.774168549969834960e-03,7.316095417067653983e+00,3.854184954656082567e-03,1.000000009962610292e+00,-4.000000000000000327e-05,3.367587497656032235e-10,0.000000000000000000e+00 +7.846909582562518892e+01,4.807332237804301371e+02,5.812710304094930239e-03,7.317462266395001080e+00,3.854038969254544849e-03,1.000000009963070591e+00,-4.000000000000000327e-05,-3.374715868376657957e-10,0.000000000000000000e+00 +7.847046241962129898e+01,4.807432237061621549e+02,5.851250598376852956e-03,7.318828860404724246e+00,3.853892983853007131e-03,1.000000009962609404e+00,-4.000000000000000327e-05,8.450553606676917482e-11,0.000000000000000000e+00 +7.847182875844281114e+01,4.807532236318998002e+02,5.889789432815601376e-03,7.320195199239852180e+00,3.853746998451469414e-03,1.000000009962724867e+00,-4.000000000000000327e-05,8.338352535575231250e-11,0.000000000000000000e+00 +7.847319484223262975e+01,4.807632235576430730e+02,5.928326807411175500e-03,7.321561283043282131e+00,3.853601013049931696e-03,1.000000009962838776e+00,-4.000000000000000327e-05,4.080540088144654273e-11,0.000000000000000000e+00 +7.847456067113351708e+01,4.807732234833919733e+02,5.966862722163574460e-03,7.322927111957777235e+00,3.853455027648393979e-03,1.000000009962894509e+00,-4.000000000000000327e-05,-1.360975774901942273e-10,0.000000000000000000e+00 +7.847592624528810745e+01,4.807832234091465011e+02,6.005397177072796522e-03,7.324292686125967400e+00,3.853309042246856261e-03,1.000000009962708658e+00,-4.000000000000000327e-05,4.121094058594110053e-10,0.000000000000000000e+00 +7.847729156483889312e+01,4.807932233349066564e+02,6.043930172138841685e-03,7.325658005690349306e+00,3.853163056845318544e-03,1.000000009963271319e+00,-4.000000000000000327e-05,-3.127995716876728149e-10,0.000000000000000000e+00 +7.847865662992823843e+01,4.808032232606724392e+02,6.082461707361709081e-03,7.327023070793288184e+00,3.853017071443780826e-03,1.000000009962844327e+00,-4.000000000000000327e-05,-4.986528015389664203e-10,0.000000000000000000e+00 +7.848002144069836561e+01,4.808132231864438495e+02,6.120991782741397845e-03,7.328387881577014262e+00,3.852871086042243109e-03,1.000000009962163761e+00,-4.000000000000000327e-05,7.172825396304700600e-10,0.000000000000000000e+00 +7.848138599729138321e+01,4.808232231122208873e+02,6.159520398277907108e-03,7.329752438183626317e+00,3.852725100640705391e-03,1.000000009963142533e+00,-4.000000000000000327e-05,-5.737050244780057545e-10,0.000000000000000000e+00 +7.848275029984925766e+01,4.808332230380035526e+02,6.198047553971236003e-03,7.331116740755093453e+00,3.852579115239167674e-03,1.000000009962359826e+00,-4.000000000000000327e-05,3.063585320117986150e-10,0.000000000000000000e+00 +7.848411434851382751e+01,4.808432229637917885e+02,6.236573249821383662e-03,7.332480789433247992e+00,3.852433129837629956e-03,1.000000009962777714e+00,-4.000000000000000327e-05,-7.473152502046300552e-11,0.000000000000000000e+00 +7.848547814342678919e+01,4.808532228895856520e+02,6.275097485828350086e-03,7.333844584359794361e+00,3.852287144436092239e-03,1.000000009962675795e+00,-4.000000000000000327e-05,9.998625427158711624e-11,0.000000000000000000e+00 +7.848684168472971123e+01,4.808632228153851429e+02,6.313620261992133539e-03,7.335208125676302870e+00,3.852141159034554521e-03,1.000000009962812131e+00,-4.000000000000000327e-05,-2.167857452500845143e-10,0.000000000000000000e+00 +7.848820497256403428e+01,4.808732227411902613e+02,6.352141578312733156e-03,7.336571413524213270e+00,3.851995173633016804e-03,1.000000009962516589e+00,-4.000000000000000327e-05,3.165236574282369807e-10,0.000000000000000000e+00 +7.848956800707107107e+01,4.808832226670010073e+02,6.390661434790148067e-03,7.337934448044832969e+00,3.851849188231479086e-03,1.000000009962948022e+00,-4.000000000000000327e-05,-3.035476731462765989e-10,0.000000000000000000e+00 +7.849093078839200643e+01,4.808932225928173807e+02,6.429179831424378273e-03,7.339297229379339704e+00,3.851703202829941369e-03,1.000000009962534353e+00,-4.000000000000000327e-05,2.216325841065880706e-10,0.000000000000000000e+00 +7.849229331666786891e+01,4.809032225186393816e+02,6.467696768215422040e-03,7.340659757668777985e+00,3.851557217428403651e-03,1.000000009962836334e+00,-4.000000000000000327e-05,-1.124668188088641443e-10,0.000000000000000000e+00 +7.849365559203958753e+01,4.809132224444670101e+02,6.506212245163279367e-03,7.342022033054063535e+00,3.851411232026865934e-03,1.000000009962683123e+00,-4.000000000000000327e-05,3.765892241681642092e-11,0.000000000000000000e+00 +7.849501761464793503e+01,4.809232223703002660e+02,6.544726262267948520e-03,7.343384055675979738e+00,3.851265246625328216e-03,1.000000009962734415e+00,-4.000000000000000327e-05,-3.761699178027485170e-10,0.000000000000000000e+00 +7.849637938463357045e+01,4.809332222961391494e+02,6.583238819529429499e-03,7.344745825675180306e+00,3.851119261223790498e-03,1.000000009962222158e+00,-4.000000000000000327e-05,4.701772796749447012e-10,0.000000000000000000e+00 +7.849774090213701072e+01,4.809432222219836603e+02,6.621749916947720568e-03,7.346107343192187500e+00,3.850973275822252781e-03,1.000000009962862313e+00,-4.000000000000000327e-05,-3.885431463564745999e-10,0.000000000000000000e+00 +7.849910216729865908e+01,4.809532221478337988e+02,6.660259554522821729e-03,7.347468608367395682e+00,3.850827290420715063e-03,1.000000009962333403e+00,-4.000000000000000327e-05,3.106310815310991073e-10,0.000000000000000000e+00 +7.850046318025877667e+01,4.809632220736895647e+02,6.698767732254732113e-03,7.348829621341065987e+00,3.850681305019177346e-03,1.000000009962756176e+00,-4.000000000000000327e-05,8.093569130862940460e-11,0.000000000000000000e+00 +7.850182394115748252e+01,4.809732219995509013e+02,6.737274450143450853e-03,7.350190382253332544e+00,3.850535319617639628e-03,1.000000009962866310e+00,-4.000000000000000327e-05,-2.105370454221055856e-10,0.000000000000000000e+00 +7.850318445013479618e+01,4.809832219254178654e+02,6.775779708188977082e-03,7.351550891244198027e+00,3.850389334216101911e-03,1.000000009962579872e+00,-4.000000000000000327e-05,-1.743373523732395172e-10,0.000000000000000000e+00 +7.850454470733058088e+01,4.809932218512904569e+02,6.814283506391309933e-03,7.352911148453535439e+00,3.850243348814564193e-03,1.000000009962342729e+00,-4.000000000000000327e-05,9.991966416164207996e-11,0.000000000000000000e+00 +7.850590471288458616e+01,4.810032217771686760e+02,6.852785844750447670e-03,7.354271154021088996e+00,3.850097363413026476e-03,1.000000009962478620e+00,-4.000000000000000327e-05,4.082440582265416802e-11,0.000000000000000000e+00 +7.850726446693641947e+01,4.810132217030525226e+02,6.891286723266391162e-03,7.355630908086474129e+00,3.849951378011488758e-03,1.000000009962534131e+00,-4.000000000000000327e-05,3.903534799915380527e-11,0.000000000000000000e+00 +7.850862396962557455e+01,4.810232216289419966e+02,6.929786141939138673e-03,7.356990410789176593e+00,3.849805392609951041e-03,1.000000009962587200e+00,-4.000000000000000327e-05,3.593876064242038512e-12,0.000000000000000000e+00 +7.850998322109140304e+01,4.810332215548370982e+02,6.968284100768689336e-03,7.358349662268553359e+00,3.849659407208413323e-03,1.000000009962592085e+00,-4.000000000000000327e-05,-1.552187751475725419e-10,0.000000000000000000e+00 +7.851134222147314290e+01,4.810432214807378273e+02,7.006780599755042284e-03,7.359708662663832612e+00,3.849513421806875606e-03,1.000000009962381142e+00,-4.000000000000000327e-05,-4.624739594691594706e-11,0.000000000000000000e+00 +7.851270097090988997e+01,4.810532214066441270e+02,7.045275638898196649e-03,7.361067412114113750e+00,3.849367436405337888e-03,1.000000009962318304e+00,-4.000000000000000327e-05,2.405962369474318390e-10,0.000000000000000000e+00 +7.851405946954061221e+01,4.810632213325560542e+02,7.083769218198151564e-03,7.362425910758368275e+00,3.849221451003800171e-03,1.000000009962645153e+00,-4.000000000000000327e-05,1.345429662026140147e-10,0.000000000000000000e+00 +7.851541771750414966e+01,4.810732212584736089e+02,7.122261337654907029e-03,7.363784158735439789e+00,3.849075465602262453e-03,1.000000009962827896e+00,-4.000000000000000327e-05,-4.548816330185888062e-10,0.000000000000000000e+00 +7.851677571493922869e+01,4.810832211843967912e+02,7.160751997268461309e-03,7.365142156184043110e+00,3.848929480200724736e-03,1.000000009962210168e+00,-4.000000000000000327e-05,3.099064202143067227e-10,0.000000000000000000e+00 +7.851813346198441934e+01,4.810932211103256009e+02,7.199241197038814405e-03,7.366499903242764269e+00,3.848783494799187018e-03,1.000000009962630942e+00,-4.000000000000000327e-05,-6.902618386136365097e-11,0.000000000000000000e+00 +7.851949095877819218e+01,4.811032210362600381e+02,7.237728936965964581e-03,7.367857400050064065e+00,3.848637509397649301e-03,1.000000009962537240e+00,-4.000000000000000327e-05,-2.357465892160380197e-10,0.000000000000000000e+00 +7.852084820545887567e+01,4.811132209622001028e+02,7.276215217049911838e-03,7.369214646744273622e+00,3.848491523996111583e-03,1.000000009962217273e+00,-4.000000000000000327e-05,2.030641294361511341e-10,0.000000000000000000e+00 +7.852220520216468458e+01,4.811232208881457382e+02,7.314700037290654440e-03,7.370571643463597056e+00,3.848345538594573866e-03,1.000000009962492831e+00,-4.000000000000000327e-05,-2.886954759488921238e-10,0.000000000000000000e+00 +7.852356194903367737e+01,4.811332208140970010e+02,7.353183397688192388e-03,7.371928390346112359e+00,3.848199553193036148e-03,1.000000009962101144e+00,-4.000000000000000327e-05,1.301333056941169357e-10,0.000000000000000000e+00 +7.852491844620382722e+01,4.811432207400538914e+02,7.391665298242524815e-03,7.373284887529768739e+00,3.848053567791498430e-03,1.000000009962277669e+00,-4.000000000000000327e-05,4.060251362031102986e-10,0.000000000000000000e+00 +7.852627469381293679e+01,4.811532206660164093e+02,7.430145738953650852e-03,7.374641135152390170e+00,3.847907582389960713e-03,1.000000009962828340e+00,-4.000000000000000327e-05,-5.164672720663484703e-10,0.000000000000000000e+00 +7.852763069199870927e+01,4.811632205919845546e+02,7.468624719821568766e-03,7.375997133351673618e+00,3.847761596988422995e-03,1.000000009962128011e+00,-4.000000000000000327e-05,1.724603788981607127e-10,0.000000000000000000e+00 +7.852898644089871993e+01,4.811732205179583275e+02,7.507102240846278557e-03,7.377352882265187262e+00,3.847615611586885278e-03,1.000000009962361824e+00,-4.000000000000000327e-05,-3.112392671656717393e-11,0.000000000000000000e+00 +7.853034194065040197e+01,4.811832204439376710e+02,7.545578302027779356e-03,7.378708382030375823e+00,3.847469626185347560e-03,1.000000009962319636e+00,-4.000000000000000327e-05,2.342915414189281065e-10,0.000000000000000000e+00 +7.853169719139107485e+01,4.811932203699226420e+02,7.584052903366070297e-03,7.380063632784556127e+00,3.847323640783809843e-03,1.000000009962637160e+00,-4.000000000000000327e-05,-5.702687531548068351e-10,0.000000000000000000e+00 +7.853305219325794440e+01,4.812032202959132405e+02,7.622526044861150513e-03,7.381418634664919765e+00,3.847177655382272125e-03,1.000000009961864444e+00,-4.000000000000000327e-05,3.692676427724542179e-10,0.000000000000000000e+00 +7.853440694638806008e+01,4.812132202219094665e+02,7.660997726513019135e-03,7.382773387808530430e+00,3.847031669980734408e-03,1.000000009962364711e+00,-4.000000000000000327e-05,6.229359000558524318e-11,0.000000000000000000e+00 +7.853576145091837191e+01,4.812232201479113201e+02,7.699467948321676164e-03,7.384127892352329248e+00,3.846885684579196690e-03,1.000000009962449088e+00,-4.000000000000000327e-05,-1.275613281726009422e-10,0.000000000000000000e+00 +7.853711570698567357e+01,4.812332200739187442e+02,7.737936710287119865e-03,7.385482148433129446e+00,3.846739699177658973e-03,1.000000009962276337e+00,-4.000000000000000327e-05,1.962968039598157727e-10,0.000000000000000000e+00 +7.853846971472667349e+01,4.812432199999317959e+02,7.776404012409349371e-03,7.386836156187619018e+00,3.846593713776121255e-03,1.000000009962542125e+00,-4.000000000000000327e-05,-5.071520402506938766e-10,0.000000000000000000e+00 +7.853982347427792376e+01,4.812532199259504750e+02,7.814869854688363815e-03,7.388189915752361614e+00,3.846447728374583538e-03,1.000000009961855563e+00,-4.000000000000000327e-05,5.823802373887883400e-10,0.000000000000000000e+00 +7.854117698577587703e+01,4.812632198519747817e+02,7.853334237124162329e-03,7.389543427263793873e+00,3.846301742973045820e-03,1.000000009962643821e+00,-4.000000000000000327e-05,-5.006105973444493220e-10,0.000000000000000000e+00 +7.854253024935682959e+01,4.812732197780046590e+02,7.891797159716745780e-03,7.390896690858230755e+00,3.846155757571508103e-03,1.000000009961966363e+00,-4.000000000000000327e-05,3.544794869248808153e-11,0.000000000000000000e+00 +7.854388326515697827e+01,4.812832197040401638e+02,7.930258622466110699e-03,7.392249706671858434e+00,3.846009772169970385e-03,1.000000009962014325e+00,-4.000000000000000327e-05,1.636484938128255918e-10,0.000000000000000000e+00 +7.854523603331239201e+01,4.812932196300812961e+02,7.968718625372258821e-03,7.393602474840741401e+00,3.845863786768432668e-03,1.000000009962235703e+00,-4.000000000000000327e-05,2.825382119198342202e-10,0.000000000000000000e+00 +7.854658855395899764e+01,4.813032195561280560e+02,8.007177168435186676e-03,7.394954995500818917e+00,3.845717801366894950e-03,1.000000009962617842e+00,-4.000000000000000327e-05,-6.674770082584397449e-10,0.000000000000000000e+00 +7.854794082723260829e+01,4.813132194821804433e+02,8.045634251654895999e-03,7.396307268787905898e+00,3.845571815965357233e-03,1.000000009961715230e+00,-4.000000000000000327e-05,6.276909299287009990e-10,0.000000000000000000e+00 +7.854929285326892341e+01,4.813232194082384012e+02,8.084089875031385056e-03,7.397659294837691135e+00,3.845425830563819515e-03,1.000000009962563885e+00,-4.000000000000000327e-05,-2.912348124827707274e-10,0.000000000000000000e+00 +7.855064463220351456e+01,4.813332193343019867e+02,8.122544038564652111e-03,7.399011073785743520e+00,3.845279845162281798e-03,1.000000009962170200e+00,-4.000000000000000327e-05,-1.097464207797411037e-10,0.000000000000000000e+00 +7.855199616417181119e+01,4.813432192603711997e+02,8.160996742254697164e-03,7.400362605767504043e+00,3.845133859760744080e-03,1.000000009962021874e+00,-4.000000000000000327e-05,1.140388150223136580e-10,0.000000000000000000e+00 +7.855334744930914326e+01,4.813532191864460401e+02,8.199447986101518482e-03,7.401713890918292016e+00,3.844987874359206362e-03,1.000000009962175973e+00,-4.000000000000000327e-05,-1.927837976822201247e-10,0.000000000000000000e+00 +7.855469848775069863e+01,4.813632191125264512e+02,8.237897770105116063e-03,7.403064929373303293e+00,3.844841888957668645e-03,1.000000009961915515e+00,-4.000000000000000327e-05,3.428988968917125998e-10,0.000000000000000000e+00 +7.855604927963155149e+01,4.813732190386124898e+02,8.276346094265489908e-03,7.404415721267609385e+00,3.844695903556130927e-03,1.000000009962378700e+00,-4.000000000000000327e-05,-3.117233628452039986e-10,0.000000000000000000e+00 +7.855739982508664809e+01,4.813832189647041560e+02,8.314792958582638283e-03,7.405766266736160119e+00,3.844549918154593210e-03,1.000000009961957703e+00,-4.000000000000000327e-05,1.912449347377477012e-10,0.000000000000000000e+00 +7.855875012425082105e+01,4.813932188908014496e+02,8.353238363056559451e-03,7.407116565913780093e+00,3.844403932753055492e-03,1.000000009962215941e+00,-4.000000000000000327e-05,-1.819049560292249677e-10,0.000000000000000000e+00 +7.856010017725876082e+01,4.814032188169043138e+02,8.391682307687255149e-03,7.408466618935173109e+00,3.844257947351517775e-03,1.000000009961970360e+00,-4.000000000000000327e-05,4.316506354148573290e-10,0.000000000000000000e+00 +7.856144998424505843e+01,4.814132187430128056e+02,8.430124792474721906e-03,7.409816425934918627e+00,3.844111961949980057e-03,1.000000009962553005e+00,-4.000000000000000327e-05,-4.911249636178223967e-10,0.000000000000000000e+00 +7.856279954534417698e+01,4.814232186691269249e+02,8.468565817418959724e-03,7.411165987047475312e+00,3.843965976548442340e-03,1.000000009961890202e+00,-4.000000000000000327e-05,-1.104203923254244579e-10,0.000000000000000000e+00 +7.856414886069043746e+01,4.814332185952466716e+02,8.507005382519968600e-03,7.412515302407176598e+00,3.843819991146904622e-03,1.000000009961741210e+00,-4.000000000000000327e-05,5.136882088321925112e-10,0.000000000000000000e+00 +7.856549793041806140e+01,4.814432185213719890e+02,8.545443487777746802e-03,7.413864372148236015e+00,3.843674005745366905e-03,1.000000009962434211e+00,-4.000000000000000327e-05,-6.573310881827311778e-10,0.000000000000000000e+00 +7.856684675466112822e+01,4.814532184475029339e+02,8.583880133192294329e-03,7.415213196404745410e+00,3.843528020343829187e-03,1.000000009961547587e+00,-4.000000000000000327e-05,6.849473632063173079e-10,0.000000000000000000e+00 +7.856819533355361784e+01,4.814632183736395064e+02,8.622315318763609446e-03,7.416561775310671401e+00,3.843382034942291470e-03,1.000000009962471292e+00,-4.000000000000000327e-05,-4.271818731006655611e-10,0.000000000000000000e+00 +7.856954366722938232e+01,4.814732182997816494e+02,8.660749044491692153e-03,7.417910108999863361e+00,3.843236049540753752e-03,1.000000009961895309e+00,-4.000000000000000327e-05,-1.724520944739817191e-10,0.000000000000000000e+00 +7.857089175582213159e+01,4.814832182259294200e+02,8.699181310376540716e-03,7.419258197606044547e+00,3.843090064139216035e-03,1.000000009961662828e+00,-4.000000000000000327e-05,3.882936543799219488e-10,0.000000000000000000e+00 +7.857223959946547609e+01,4.814932181520828181e+02,8.737612116418155134e-03,7.420606041262819197e+00,3.842944078737678317e-03,1.000000009962186187e+00,-4.000000000000000327e-05,-2.970813082735915149e-10,0.000000000000000000e+00 +7.857358719829289839e+01,4.815032180782417868e+02,8.776041462616533673e-03,7.421953640103670757e+00,3.842798093336140600e-03,1.000000009961785841e+00,-4.000000000000000327e-05,1.316755806267185212e-10,0.000000000000000000e+00 +7.857493455243776737e+01,4.815132180044063830e+02,8.814469348971676332e-03,7.423300994261959218e+00,3.842652107934602882e-03,1.000000009961963254e+00,-4.000000000000000327e-05,1.226338128763803566e-10,0.000000000000000000e+00 +7.857628166203330977e+01,4.815232179305766067e+02,8.852895775483583113e-03,7.424648103870925553e+00,3.842506122533065165e-03,1.000000009962128455e+00,-4.000000000000000327e-05,8.078154969163872011e-11,0.000000000000000000e+00 +7.857762852721265290e+01,4.815332178567524579e+02,8.891320742152252279e-03,7.425994969063689055e+00,3.842360137131527447e-03,1.000000009962237257e+00,-4.000000000000000327e-05,-5.692010115067670890e-10,0.000000000000000000e+00 +7.857897514810879613e+01,4.815432177829338798e+02,8.929744248977682097e-03,7.427341589973248226e+00,3.842214151729989730e-03,1.000000009961470759e+00,-4.000000000000000327e-05,5.382992485019651170e-10,0.000000000000000000e+00 +7.858032152485461097e+01,4.815532177091209292e+02,8.968166295959872567e-03,7.428687966732479886e+00,3.842068166328452012e-03,1.000000009962195513e+00,-4.000000000000000327e-05,-1.101866056569211041e-10,0.000000000000000000e+00 +7.858166765758286942e+01,4.815632176353136060e+02,9.006586883098823687e-03,7.430034099474143616e+00,3.841922180926914294e-03,1.000000009962047187e+00,-4.000000000000000327e-05,-1.494717881494705803e-10,0.000000000000000000e+00 +7.858301354642618719e+01,4.815732175615118535e+02,9.045006010394533724e-03,7.431379988330875541e+00,3.841776195525376577e-03,1.000000009961846015e+00,-4.000000000000000327e-05,-1.532940887374186455e-10,0.000000000000000000e+00 +7.858435919151709470e+01,4.815832174877157286e+02,9.083423677847000943e-03,7.432725633435192769e+00,3.841630210123838859e-03,1.000000009961639735e+00,-4.000000000000000327e-05,2.851885371097043133e-10,0.000000000000000000e+00 +7.858570459298799449e+01,4.815932174139252311e+02,9.121839885456225344e-03,7.434071034919492504e+00,3.841484224722301142e-03,1.000000009962023428e+00,-4.000000000000000327e-05,1.006924173219323576e-10,0.000000000000000000e+00 +7.858704975097116119e+01,4.816032173401403043e+02,9.160254633222206927e-03,7.435416192916052935e+00,3.841338239320763424e-03,1.000000009962158876e+00,-4.000000000000000327e-05,-3.001507184734771548e-10,0.000000000000000000e+00 +7.858839466559874154e+01,4.816132172663610049e+02,9.198667921144943957e-03,7.436761107557031458e+00,3.841192253919225707e-03,1.000000009961755199e+00,-4.000000000000000327e-05,-1.898986584356740308e-11,0.000000000000000000e+00 +7.858973933700278280e+01,4.816232171925873331e+02,9.237079749224436434e-03,7.438105778974465565e+00,3.841046268517687989e-03,1.000000009961729663e+00,-4.000000000000000327e-05,-1.207313210389656477e-10,0.000000000000000000e+00 +7.859108376531520435e+01,4.816332171188192319e+02,9.275490117460682624e-03,7.439450207300274620e+00,3.840900283116150272e-03,1.000000009961567349e+00,-4.000000000000000327e-05,2.930452473515352053e-10,0.000000000000000000e+00 +7.859242795066779763e+01,4.816432170450567583e+02,9.313899025853682526e-03,7.440794392666258084e+00,3.840754297714612554e-03,1.000000009961961256e+00,-4.000000000000000327e-05,-3.350637773530878155e-10,0.000000000000000000e+00 +7.859377189319225465e+01,4.816532169712998552e+02,9.352306474403434405e-03,7.442138335204097288e+00,3.840608312313074837e-03,1.000000009961510949e+00,-4.000000000000000327e-05,3.699917646154287772e-10,0.000000000000000000e+00 +7.859511559302012529e+01,4.816632168975485797e+02,9.390712463109938263e-03,7.443482035045352774e+00,3.840462326911537119e-03,1.000000009962008107e+00,-4.000000000000000327e-05,-1.342061442523429405e-10,0.000000000000000000e+00 +7.859645905028285995e+01,4.816732168238029317e+02,9.429116991973192363e-03,7.444825492321468730e+00,3.840316341509999402e-03,1.000000009961827807e+00,-4.000000000000000327e-05,3.769030004206574646e-11,0.000000000000000000e+00 +7.859780226511178114e+01,4.816832167500628543e+02,9.467520060993196707e-03,7.446168707163768552e+00,3.840170356108461684e-03,1.000000009961878433e+00,-4.000000000000000327e-05,-1.820373129254828582e-10,0.000000000000000000e+00 +7.859914523763809768e+01,4.816932166763284044e+02,9.505921670169949558e-03,7.447511679703458398e+00,3.840024370706923967e-03,1.000000009961633962e+00,-4.000000000000000327e-05,1.089774980683650799e-10,0.000000000000000000e+00 +7.860048796799289050e+01,4.817032166025995821e+02,9.544321819503450918e-03,7.448854410071625409e+00,3.839878385305386249e-03,1.000000009961780290e+00,-4.000000000000000327e-05,-1.571279037897009450e-10,0.000000000000000000e+00 +7.860183045630712684e+01,4.817132165288763304e+02,9.582720508993700786e-03,7.450196898399239487e+00,3.839732399903848532e-03,1.000000009961569347e+00,-4.000000000000000327e-05,4.153887103592988155e-10,0.000000000000000000e+00 +7.860317270271167445e+01,4.817232164551587061e+02,9.621117738640697428e-03,7.451539144817151517e+00,3.839586414502310814e-03,1.000000009962126901e+00,-4.000000000000000327e-05,-2.273384765989209361e-10,0.000000000000000000e+00 +7.860451470733724477e+01,4.817332163814466526e+02,9.659513508444439109e-03,7.452881149456096033e+00,3.839440429100773097e-03,1.000000009961821812e+00,-4.000000000000000327e-05,-1.965987995856420220e-10,0.000000000000000000e+00 +7.860585647031446399e+01,4.817432163077402265e+02,9.697907818404925828e-03,7.454222912446687666e+00,3.839294443699235379e-03,1.000000009961558023e+00,-4.000000000000000327e-05,-6.637231626285537254e-11,0.000000000000000000e+00 +7.860719799177383038e+01,4.817532162340394279e+02,9.736300668522157586e-03,7.455564433919424694e+00,3.839148458297697662e-03,1.000000009961468983e+00,-4.000000000000000327e-05,8.045573795822580982e-11,0.000000000000000000e+00 +7.860853927184572854e+01,4.817632161603442000e+02,9.774692058796132649e-03,7.456905714004688157e+00,3.839002472896159944e-03,1.000000009961576897e+00,-4.000000000000000327e-05,1.624306135248021159e-10,0.000000000000000000e+00 +7.860988031066042936e+01,4.817732160866545996e+02,9.813081989226851015e-03,7.458246752832741855e+00,3.838856487494622226e-03,1.000000009961794722e+00,-4.000000000000000327e-05,9.687971203946940854e-11,0.000000000000000000e+00 +7.861122110834806165e+01,4.817832160129705699e+02,9.851470459814310951e-03,7.459587550533732347e+00,3.838710502093084509e-03,1.000000009961924619e+00,-4.000000000000000327e-05,-1.977695237650961792e-10,0.000000000000000000e+00 +7.861256166503866893e+01,4.817932159392921676e+02,9.889857470558510721e-03,7.460928107237688955e+00,3.838564516691546791e-03,1.000000009961659497e+00,-4.000000000000000327e-05,-3.091325384142590312e-10,0.000000000000000000e+00 +7.861390198086215264e+01,4.818032158656193928e+02,9.928243021459452061e-03,7.462268423074523760e+00,3.838418531290009074e-03,1.000000009961245162e+00,-4.000000000000000327e-05,1.753059917589193735e-10,0.000000000000000000e+00 +7.861524205594831471e+01,4.818132157919521887e+02,9.966627112517131501e-03,7.463608498174032491e+00,3.838272545888471356e-03,1.000000009961480085e+00,-4.000000000000000327e-05,1.861096242328094732e-10,0.000000000000000000e+00 +7.861658189042682920e+01,4.818232157182906121e+02,1.000500974373155078e-02,7.464948332665895414e+00,3.838126560486933639e-03,1.000000009961729441e+00,-4.000000000000000327e-05,1.354219578206369626e-10,0.000000000000000000e+00 +7.861792148442727068e+01,4.818332156446346062e+02,1.004339091510270641e-02,7.466287926679675557e+00,3.837980575085395921e-03,1.000000009961910852e+00,-4.000000000000000327e-05,-5.533899804900767017e-10,0.000000000000000000e+00 +7.861926083807907162e+01,4.818432155709842277e+02,1.008177062663060015e-02,7.467627280344819596e+00,3.837834589683858204e-03,1.000000009961169667e+00,-4.000000000000000327e-05,5.151860706938150318e-10,0.000000000000000000e+00 +7.862059995151156500e+01,4.818532154973394199e+02,1.012014887831523026e-02,7.468966393790656966e+00,3.837688604282320486e-03,1.000000009961859559e+00,-4.000000000000000327e-05,-2.074713058826585362e-10,0.000000000000000000e+00 +7.862193882485397012e+01,4.818632154237002396e+02,1.015852567015659499e-02,7.470305267146404304e+00,3.837542618880782769e-03,1.000000009961581782e+00,-4.000000000000000327e-05,-3.257767288084143238e-10,0.000000000000000000e+00 +7.862327745823539260e+01,4.818732153500666868e+02,1.019690100215469436e-02,7.471643900541159233e+00,3.837396633479245051e-03,1.000000009961145686e+00,-4.000000000000000327e-05,5.760180693021622359e-10,0.000000000000000000e+00 +7.862461585178481016e+01,4.818832152764387047e+02,1.023527487430952662e-02,7.472982294103904799e+00,3.837250648077707334e-03,1.000000009961916625e+00,-4.000000000000000327e-05,-5.578685618518559254e-10,0.000000000000000000e+00 +7.862595400563108683e+01,4.818932152028163500e+02,1.027364728662109178e-02,7.474320447963510361e+00,3.837104662676169616e-03,1.000000009961170111e+00,-4.000000000000000327e-05,6.548909967133200603e-10,0.000000000000000000e+00 +7.862729191990297295e+01,4.819032151291995660e+02,1.031201823908938983e-02,7.475658362248726263e+00,3.836958677274631899e-03,1.000000009962046299e+00,-4.000000000000000327e-05,-8.273089164278525335e-10,0.000000000000000000e+00 +7.862862959472911939e+01,4.819132150555884095e+02,1.035038773171441905e-02,7.476996037088191827e+00,3.836812691873094181e-03,1.000000009960939629e+00,-4.000000000000000327e-05,3.742150826457187632e-10,0.000000000000000000e+00 +7.862996703023803491e+01,4.819232149819828237e+02,1.038875576449617769e-02,7.478333472610426469e+00,3.836666706471556464e-03,1.000000009961440117e+00,-4.000000000000000327e-05,2.083957119786391515e-10,0.000000000000000000e+00 +7.863130422655812879e+01,4.819332149083828654e+02,1.042712233743466575e-02,7.479670668943839473e+00,3.836520721070018746e-03,1.000000009961718783e+00,-4.000000000000000327e-05,8.320710798461447990e-11,0.000000000000000000e+00 +7.863264118381769663e+01,4.819432148347884777e+02,1.046548745052988325e-02,7.481007626216722883e+00,3.836374735668481029e-03,1.000000009961830028e+00,-4.000000000000000327e-05,-5.779027374776642457e-10,0.000000000000000000e+00 +7.863397790214490612e+01,4.819532147611997175e+02,1.050385110378182843e-02,7.482344344557254168e+00,3.836228750266943311e-03,1.000000009961057534e+00,-4.000000000000000327e-05,1.332454183508006900e-10,0.000000000000000000e+00 +7.863531438166783971e+01,4.819632146876165280e+02,1.054221329719050131e-02,7.483680824093495332e+00,3.836082764865405594e-03,1.000000009961235614e+00,-4.000000000000000327e-05,1.480584458206047636e-10,0.000000000000000000e+00 +7.863665062251442350e+01,4.819732146140389659e+02,1.058057403075590014e-02,7.485017064953396471e+00,3.835936779463867876e-03,1.000000009961433456e+00,-4.000000000000000327e-05,3.815969580574617760e-10,0.000000000000000000e+00 +7.863798662481251256e+01,4.819832145404669745e+02,1.061893330447802493e-02,7.486353067264792216e+00,3.835790794062330158e-03,1.000000009961943270e+00,-4.000000000000000327e-05,-7.395591871408825641e-10,0.000000000000000000e+00 +7.863932238868981983e+01,4.819932144669006107e+02,1.065729111835687394e-02,7.487688831155403513e+00,3.835644808660792441e-03,1.000000009960955394e+00,-4.000000000000000327e-05,6.871529554067841413e-10,0.000000000000000000e+00 +7.864065791427394458e+01,4.820032143933398174e+02,1.069564747239244717e-02,7.489024356752834954e+00,3.835498823259254723e-03,1.000000009961873104e+00,-4.000000000000000327e-05,-3.966010429147351210e-10,0.000000000000000000e+00 +7.864199320169238661e+01,4.820132143197846517e+02,1.073400236658474290e-02,7.490359644184581889e+00,3.835352837857717006e-03,1.000000009961343528e+00,-4.000000000000000327e-05,-8.648608529284690598e-11,0.000000000000000000e+00 +7.864332825107253200e+01,4.820232142462350566e+02,1.077235580093376111e-02,7.491694693578021536e+00,3.835206852456179288e-03,1.000000009961228065e+00,-4.000000000000000327e-05,4.424884433288930615e-11,0.000000000000000000e+00 +7.864466306254163896e+01,4.820332141726910891e+02,1.081070777543950007e-02,7.493029505060420092e+00,3.835060867054641571e-03,1.000000009961287128e+00,-4.000000000000000327e-05,-8.402123219520856103e-11,0.000000000000000000e+00 +7.864599763622685202e+01,4.820432140991526921e+02,1.084905829010195978e-02,7.494364078758930070e+00,3.834914881653103853e-03,1.000000009961174996e+00,-4.000000000000000327e-05,4.466399070010888795e-10,0.000000000000000000e+00 +7.864733197225521621e+01,4.820532140256199227e+02,1.088740734492113851e-02,7.495698414800590292e+00,3.834768896251566136e-03,1.000000009961770964e+00,-4.000000000000000327e-05,-4.380646562774960217e-10,0.000000000000000000e+00 +7.864866607075366289e+01,4.820632139520927240e+02,1.092575493989703626e-02,7.497032513312327673e+00,3.834622910850028418e-03,1.000000009961186542e+00,-4.000000000000000327e-05,1.761226808635206256e-10,0.000000000000000000e+00 +7.864999993184899552e+01,4.820732138785711527e+02,1.096410107502965303e-02,7.498366374420953662e+00,3.834476925448490701e-03,1.000000009961421465e+00,-4.000000000000000327e-05,-2.843771833018979567e-10,0.000000000000000000e+00 +7.865133355566793227e+01,4.820832138050551521e+02,1.100244575031898708e-02,7.499699998253169575e+00,3.834330940046952983e-03,1.000000009961042213e+00,-4.000000000000000327e-05,9.808428067461774780e-11,0.000000000000000000e+00 +7.865266694233704925e+01,4.820932137315447790e+02,1.104078896576503668e-02,7.501033384935562154e+00,3.834184954645415266e-03,1.000000009961172998e+00,-4.000000000000000327e-05,2.465034711841481069e-10,0.000000000000000000e+00 +7.865400009198280884e+01,4.821032136580399765e+02,1.107913072136780183e-02,7.502366534594607117e+00,3.834038969243877548e-03,1.000000009961501624e+00,-4.000000000000000327e-05,-4.182974493087034556e-10,0.000000000000000000e+00 +7.865533300473158818e+01,4.821132135845408015e+02,1.111747101712728253e-02,7.503699447356667385e+00,3.833892983842339831e-03,1.000000009960944070e+00,-4.000000000000000327e-05,5.251723646641662700e-10,0.000000000000000000e+00 +7.865666568070963649e+01,4.821232135110471972e+02,1.115580985304347704e-02,7.505032123347992190e+00,3.833746998440802113e-03,1.000000009961643954e+00,-4.000000000000000327e-05,-5.022686004834319901e-10,0.000000000000000000e+00 +7.865799812004308933e+01,4.821332134375592204e+02,1.119414722911638536e-02,7.506364562694721521e+00,3.833601013039264396e-03,1.000000009960974712e+00,-4.000000000000000327e-05,4.230205799009390233e-10,0.000000000000000000e+00 +7.865933032285798276e+01,4.821432133640768143e+02,1.123248314534600577e-02,7.507696765522879900e+00,3.833455027637726678e-03,1.000000009961538261e+00,-4.000000000000000327e-05,-2.797299097367343504e-10,0.000000000000000000e+00 +7.866066228928022497e+01,4.821532132906000356e+02,1.127081760173233825e-02,7.509028731958383496e+00,3.833309042236188961e-03,1.000000009961165670e+00,-4.000000000000000327e-05,-1.869087375655575682e-10,0.000000000000000000e+00 +7.866199401943561043e+01,4.821632132171288276e+02,1.130915059827538108e-02,7.510360462127033898e+00,3.833163056834651243e-03,1.000000009960916758e+00,-4.000000000000000327e-05,1.242388091134891603e-10,0.000000000000000000e+00 +7.866332551344983415e+01,4.821732131436632471e+02,1.134748213497513425e-02,7.511691956154522565e+00,3.833017071433113526e-03,1.000000009961082181e+00,-4.000000000000000327e-05,7.405612186889528305e-11,0.000000000000000000e+00 +7.866465677144847746e+01,4.821832130702032373e+02,1.138581221183159603e-02,7.513023214166429931e+00,3.832871086031575808e-03,1.000000009961180769e+00,-4.000000000000000327e-05,8.591365297618195391e-11,0.000000000000000000e+00 +7.866598779355700799e+01,4.821932129967487981e+02,1.142414082884476642e-02,7.514354236288224520e+00,3.832725100630038090e-03,1.000000009961295122e+00,-4.000000000000000327e-05,8.225812561080336582e-11,0.000000000000000000e+00 +7.866731857990079391e+01,4.822032129232999864e+02,1.146246798601464369e-02,7.515685022645263835e+00,3.832579115228500373e-03,1.000000009961404590e+00,-4.000000000000000327e-05,-5.171664848630558450e-10,0.000000000000000000e+00 +7.866864913060507547e+01,4.822132128498567454e+02,1.150079368334122783e-02,7.517015573362794356e+00,3.832433129826962655e-03,1.000000009960716474e+00,-4.000000000000000327e-05,7.200552417316228780e-10,0.000000000000000000e+00 +7.866997944579497926e+01,4.822232127764191318e+02,1.153911792082451711e-02,7.518345888565950652e+00,3.832287144425424938e-03,1.000000009961674374e+00,-4.000000000000000327e-05,-8.011489675936011432e-10,0.000000000000000000e+00 +7.867130952559553236e+01,4.822332127029870890e+02,1.157744069846451153e-02,7.519675968379759823e+00,3.832141159023887220e-03,1.000000009960608782e+00,-4.000000000000000327e-05,3.638283881968073080e-10,0.000000000000000000e+00 +7.867263937013166242e+01,4.822432126295606736e+02,1.161576201626121109e-02,7.521005812929133505e+00,3.831995173622349503e-03,1.000000009961092617e+00,-4.000000000000000327e-05,1.215759100461879167e-10,0.000000000000000000e+00 +7.867396897952816914e+01,4.822532125561398288e+02,1.165408187421461406e-02,7.522335422338877642e+00,3.831849188220811785e-03,1.000000009961254266e+00,-4.000000000000000327e-05,-9.938249281952487594e-11,0.000000000000000000e+00 +7.867529835390973858e+01,4.822632124827245548e+02,1.169240027232471869e-02,7.523664796733685378e+00,3.831703202819274068e-03,1.000000009961122149e+00,-4.000000000000000327e-05,1.266306596453355586e-10,0.000000000000000000e+00 +7.867662749340095729e+01,4.822732124093149082e+02,1.173071721059152500e-02,7.524993936238139725e+00,3.831557217417736350e-03,1.000000009961290459e+00,-4.000000000000000327e-05,-2.822123592217943921e-10,0.000000000000000000e+00 +7.867795639812629815e+01,4.822832123359108323e+02,1.176903268901503298e-02,7.526322840976714446e+00,3.831411232016198633e-03,1.000000009960915426e+00,-4.000000000000000327e-05,1.051171831128872675e-10,0.000000000000000000e+00 +7.867928506821012036e+01,4.822932122625123839e+02,1.180734670759524090e-02,7.527651511073772284e+00,3.831265246614660915e-03,1.000000009961055092e+00,-4.000000000000000327e-05,-2.968538544682490857e-10,0.000000000000000000e+00 +7.868061350377668361e+01,4.823032121891195061e+02,1.184565926633214875e-02,7.528979946653567623e+00,3.831119261213123198e-03,1.000000009960660741e+00,-4.000000000000000327e-05,4.482013701729451807e-10,0.000000000000000000e+00 +7.868194170495013395e+01,4.823132121157321990e+02,1.188397036522575480e-02,7.530308147840243826e+00,3.830973275811585480e-03,1.000000009961256042e+00,-4.000000000000000327e-05,-2.536521539536462853e-10,0.000000000000000000e+00 +7.868326967185450371e+01,4.823232120423505194e+02,1.192228000427605905e-02,7.531636114757836786e+00,3.830827290410047763e-03,1.000000009960919201e+00,-4.000000000000000327e-05,3.896596855709369069e-11,0.000000000000000000e+00 +7.868459740461371155e+01,4.823332119689744104e+02,1.196058818348305977e-02,7.532963847530270485e+00,3.830681305008510045e-03,1.000000009960970937e+00,-4.000000000000000327e-05,2.425348273087133846e-10,0.000000000000000000e+00 +7.868592490335157663e+01,4.823432118956039290e+02,1.199889490284675696e-02,7.534291346281361434e+00,3.830535319606972328e-03,1.000000009961292902e+00,-4.000000000000000327e-05,-2.236732472566545068e-10,0.000000000000000000e+00 +7.868725216819180446e+01,4.823532118222390181e+02,1.203720016236714888e-02,7.535618611134816902e+00,3.830389334205434610e-03,1.000000009960996028e+00,-4.000000000000000327e-05,-4.280156763965617050e-10,0.000000000000000000e+00 +7.868857919925800104e+01,4.823632117488796780e+02,1.207550396204423553e-02,7.536945642214234020e+00,3.830243348803896893e-03,1.000000009960428038e+00,-4.000000000000000327e-05,5.629782227158637883e-10,0.000000000000000000e+00 +7.868990599667365871e+01,4.823732116755259653e+02,1.211380630187801517e-02,7.538272439643101563e+00,3.830097363402359175e-03,1.000000009961174996e+00,-4.000000000000000327e-05,-3.538482382082878543e-10,0.000000000000000000e+00 +7.869123256056214188e+01,4.823832116021778234e+02,1.215210718186848782e-02,7.539599003544801725e+00,3.829951378000821458e-03,1.000000009960705594e+00,-4.000000000000000327e-05,2.775703033614469905e-10,0.000000000000000000e+00 +7.869255889104672974e+01,4.823932115288352520e+02,1.219040660201565172e-02,7.540925334042604788e+00,3.829805392599283740e-03,1.000000009961073744e+00,-4.000000000000000327e-05,-1.421584096795085646e-10,0.000000000000000000e+00 +7.869388498825058775e+01,4.824032114554983082e+02,1.222870456231950689e-02,7.542251431259675343e+00,3.829659407197746022e-03,1.000000009960885228e+00,-4.000000000000000327e-05,3.309239288855429857e-10,0.000000000000000000e+00 +7.869521085229676771e+01,4.824132113821669350e+02,1.226700106278005332e-02,7.543577295319067844e+00,3.829513421796208305e-03,1.000000009961323988e+00,-4.000000000000000327e-05,-3.996575387661692762e-10,0.000000000000000000e+00 +7.869653648330822193e+01,4.824232113088411324e+02,1.230529610339728928e-02,7.544902926343730165e+00,3.829367436394670587e-03,1.000000009960794189e+00,-4.000000000000000327e-05,1.171038187644916524e-10,0.000000000000000000e+00 +7.869786188140778904e+01,4.824332112355209574e+02,1.234358968417121304e-02,7.546228324456500047e+00,3.829221450993132870e-03,1.000000009960949399e+00,-4.000000000000000327e-05,-2.156496282340717359e-10,0.000000000000000000e+00 +7.869918704671819398e+01,4.824432111622063530e+02,1.238188180510182458e-02,7.547553489780109537e+00,3.829075465591595152e-03,1.000000009960663627e+00,-4.000000000000000327e-05,4.290287443939240251e-11,0.000000000000000000e+00 +7.870051197936206222e+01,4.824532110888973762e+02,1.242017246618912392e-02,7.548878422437181435e+00,3.828929480190057435e-03,1.000000009960720471e+00,-4.000000000000000327e-05,3.129442486191673103e-10,0.000000000000000000e+00 +7.870183667946191974e+01,4.824632110155939699e+02,1.245846166743310932e-02,7.550203122550231960e+00,3.828783494788519717e-03,1.000000009961135028e+00,-4.000000000000000327e-05,-4.942268551139790869e-10,0.000000000000000000e+00 +7.870316114714016464e+01,4.824732109422961344e+02,1.249674940883378077e-02,7.551527590241669863e+00,3.828637509386982000e-03,1.000000009960480440e+00,-4.000000000000000327e-05,5.840210669918852470e-10,0.000000000000000000e+00 +7.870448538251909554e+01,4.824832108690039263e+02,1.253503569039113655e-02,7.552851825633794647e+00,3.828491523985444282e-03,1.000000009961253822e+00,-4.000000000000000327e-05,-5.779183218897822744e-10,0.000000000000000000e+00 +7.870580938572091156e+01,4.824932107957172889e+02,1.257332051210517665e-02,7.554175828848801899e+00,3.828345538583906565e-03,1.000000009960488656e+00,-4.000000000000000327e-05,5.032091962352859816e-10,0.000000000000000000e+00 +7.870713315686769818e+01,4.825032107224362221e+02,1.261160387397589934e-02,7.555499600008776184e+00,3.828199553182368847e-03,1.000000009961154790e+00,-4.000000000000000327e-05,-3.003007683414373741e-10,0.000000000000000000e+00 +7.870845669608144135e+01,4.825132106491607260e+02,1.264988577600330462e-02,7.556823139235699038e+00,3.828053567780831130e-03,1.000000009960757330e+00,-4.000000000000000327e-05,-2.265234941393899474e-11,0.000000000000000000e+00 +7.870978000348399917e+01,4.825232105758908574e+02,1.268816621818739075e-02,7.558146446651441863e+00,3.827907582379293412e-03,1.000000009960727354e+00,-4.000000000000000327e-05,-2.596246007728848877e-10,0.000000000000000000e+00 +7.871110307919714444e+01,4.825332105026265594e+02,1.272644520052815774e-02,7.559469522377771256e+00,3.827761596977755695e-03,1.000000009960383851e+00,-4.000000000000000327e-05,4.369238119472504649e-10,0.000000000000000000e+00 +7.871242592334255050e+01,4.825432104293678321e+02,1.276472272302560385e-02,7.560792366536346343e+00,3.827615611576217977e-03,1.000000009960961833e+00,-4.000000000000000327e-05,-3.777374596382449667e-11,0.000000000000000000e+00 +7.871374853604174859e+01,4.825532103561147323e+02,1.280299878567972907e-02,7.562114979248721447e+00,3.827469626174680260e-03,1.000000009960911873e+00,-4.000000000000000327e-05,-2.355814946649815826e-10,0.000000000000000000e+00 +7.871507091741619888e+01,4.825632102828672032e+02,1.284127338849053168e-02,7.563437360636342532e+00,3.827323640773142542e-03,1.000000009960600345e+00,-4.000000000000000327e-05,-2.310882553809980276e-10,0.000000000000000000e+00 +7.871639306758723365e+01,4.825732102096252447e+02,1.287954653145801168e-02,7.564759510820549870e+00,3.827177655371604825e-03,1.000000009960294811e+00,-4.000000000000000327e-05,4.108580534338171962e-10,0.000000000000000000e+00 +7.871771498667609990e+01,4.825832101363889137e+02,1.291781821458216906e-02,7.566081429922578039e+00,3.827031669970067107e-03,1.000000009960837932e+00,-4.000000000000000327e-05,9.105640985702739091e-11,0.000000000000000000e+00 +7.871903667480391675e+01,4.825932100631581534e+02,1.295608843786300209e-02,7.567403118063556811e+00,3.826885684568529390e-03,1.000000009960958280e+00,-4.000000000000000327e-05,-2.485165231739472693e-10,0.000000000000000000e+00 +7.872035813209170385e+01,4.826032099899329637e+02,1.299435720130050903e-02,7.568724575364508489e+00,3.826739699166991672e-03,1.000000009960629876e+00,-4.000000000000000327e-05,-1.727651102950636960e-10,0.000000000000000000e+00 +7.872167935866038135e+01,4.826132099167133447e+02,1.303262450489468989e-02,7.570045801946349684e+00,3.826593713765453954e-03,1.000000009960401615e+00,-4.000000000000000327e-05,2.450734455203335747e-10,0.000000000000000000e+00 +7.872300035463076995e+01,4.826232098434993532e+02,1.307089034864554467e-02,7.571366797929892201e+00,3.826447728363916237e-03,1.000000009960725356e+00,-4.000000000000000327e-05,-8.742141976821980406e-11,0.000000000000000000e+00 +7.872432112012356242e+01,4.826332097702909323e+02,1.310915473255307162e-02,7.572687563435843039e+00,3.826301742962378519e-03,1.000000009960609892e+00,-4.000000000000000327e-05,-2.256538669283192491e-10,0.000000000000000000e+00 +7.872564165525936630e+01,4.826432096970880821e+02,1.314741765661727076e-02,7.574008098584802617e+00,3.826155757560840802e-03,1.000000009960311909e+00,-4.000000000000000327e-05,2.668965238251459743e-10,0.000000000000000000e+00 +7.872696196015867542e+01,4.826532096238908593e+02,1.318567912083814034e-02,7.575328403497266549e+00,3.826009772159303084e-03,1.000000009960664293e+00,-4.000000000000000327e-05,2.975565559678964033e-10,0.000000000000000000e+00 +7.872828203494188415e+01,4.826632095506992073e+02,1.322393912521568037e-02,7.576648478293626532e+00,3.825863786757765367e-03,1.000000009961057090e+00,-4.000000000000000327e-05,-7.175239460349107030e-10,0.000000000000000000e+00 +7.872960187972927315e+01,4.826732094775131259e+02,1.326219766974988910e-02,7.577968323094168568e+00,3.825717801356227649e-03,1.000000009960110070e+00,-4.000000000000000327e-05,7.176489380088885135e-10,0.000000000000000000e+00 +7.873092149464103784e+01,4.826832094043326151e+02,1.330045475444076655e-02,7.579287938019072079e+00,3.825571815954689932e-03,1.000000009961057090e+00,-4.000000000000000327e-05,-5.696751885818541766e-10,0.000000000000000000e+00 +7.873224087979724573e+01,4.826932093311577319e+02,1.333871037928831098e-02,7.580607323188416125e+00,3.825425830553152214e-03,1.000000009960305469e+00,-4.000000000000000327e-05,-6.211129615644241169e-11,0.000000000000000000e+00 +7.873356003531786484e+01,4.827032092579884193e+02,1.337696454429252238e-02,7.581926478722170515e+00,3.825279845151614497e-03,1.000000009960223535e+00,-4.000000000000000327e-05,6.375512467942292978e-10,0.000000000000000000e+00 +7.873487896132276376e+01,4.827132091848246773e+02,1.341521724945339902e-02,7.583245404740203810e+00,3.825133859750076779e-03,1.000000009961064418e+00,-4.000000000000000327e-05,-5.861372998938884149e-10,0.000000000000000000e+00 +7.873619765793171155e+01,4.827232091116665060e+02,1.345346849477094091e-02,7.584564101362280653e+00,3.824987874348539062e-03,1.000000009960291480e+00,-4.000000000000000327e-05,2.783836374653925165e-10,0.000000000000000000e+00 +7.873751612526436361e+01,4.827332090385139622e+02,1.349171828024514803e-02,7.585882568708058216e+00,3.824841888947001344e-03,1.000000009960658520e+00,-4.000000000000000327e-05,-4.160478616001861742e-10,0.000000000000000000e+00 +7.873883436344026165e+01,4.827432089653669891e+02,1.352996660587601693e-02,7.587200806897093308e+00,3.824695903545463627e-03,1.000000009960110070e+00,-4.000000000000000327e-05,3.229564159839376915e-10,0.000000000000000000e+00 +7.874015237257887634e+01,4.827532088922255866e+02,1.356821347166354934e-02,7.588518816048836158e+00,3.824549918143925909e-03,1.000000009960535730e+00,-4.000000000000000327e-05,-1.322716885043448321e-10,0.000000000000000000e+00 +7.874147015279955042e+01,4.827632088190897548e+02,1.360645887760774352e-02,7.589836596282635739e+00,3.824403932742388192e-03,1.000000009960361425e+00,-4.000000000000000327e-05,1.906054245636315343e-10,0.000000000000000000e+00 +7.874278770422152718e+01,4.827732087459594936e+02,1.364470282370859773e-02,7.591154147717735334e+00,3.824257947340850474e-03,1.000000009960612557e+00,-4.000000000000000327e-05,1.965380244381726638e-10,0.000000000000000000e+00 +7.874410502696395042e+01,4.827832086728348600e+02,1.368294530996611372e-02,7.592471470473276085e+00,3.824111961939312757e-03,1.000000009960871461e+00,-4.000000000000000327e-05,-6.996349411473111681e-10,0.000000000000000000e+00 +7.874542212114585027e+01,4.827932085997157969e+02,1.372118633638028801e-02,7.593788564668295216e+00,3.823965976537775039e-03,1.000000009959949976e+00,-4.000000000000000327e-05,5.028128469106908493e-10,0.000000000000000000e+00 +7.874673898688615736e+01,4.828032085266023046e+02,1.375942590295112060e-02,7.595105430421725146e+00,3.823819991136237322e-03,1.000000009960612113e+00,-4.000000000000000327e-05,-3.659601240716435501e-10,0.000000000000000000e+00 +7.874805562430371708e+01,4.828132084534943829e+02,1.379766400967861149e-02,7.596422067852398818e+00,3.823674005734699604e-03,1.000000009960130276e+00,-4.000000000000000327e-05,2.083129503071592896e-10,0.000000000000000000e+00 +7.874937203351724690e+01,4.828232083803920318e+02,1.383590065656275896e-02,7.597738477079042596e+00,3.823528020333161886e-03,1.000000009960404501e+00,-4.000000000000000327e-05,1.040901729333969315e-10,0.000000000000000000e+00 +7.875068821464537905e+01,4.828332083072953083e+02,1.387413584360356299e-02,7.599054658220282477e+00,3.823382034931624169e-03,1.000000009960541503e+00,-4.000000000000000327e-05,-2.384196003305585020e-10,0.000000000000000000e+00 +7.875200416780663204e+01,4.828432082342041554e+02,1.391236957080102185e-02,7.600370611394640541e+00,3.823236049530086451e-03,1.000000009960227754e+00,-4.000000000000000327e-05,1.346721789173371365e-10,0.000000000000000000e+00 +7.875331989311942493e+01,4.828532081611185731e+02,1.395060183815513555e-02,7.601686336720535841e+00,3.823090064128548734e-03,1.000000009960404945e+00,-4.000000000000000327e-05,1.262559252672037707e-10,0.000000000000000000e+00 +7.875463539070207730e+01,4.828632080880385615e+02,1.398883264566590234e-02,7.603001834316286178e+00,3.822944078727011016e-03,1.000000009960571035e+00,-4.000000000000000327e-05,-3.364593638320281183e-10,0.000000000000000000e+00 +7.875595066067279504e+01,4.828732080149641206e+02,1.402706199333332224e-02,7.604317104300106323e+00,3.822798093325473299e-03,1.000000009960128500e+00,-4.000000000000000327e-05,2.162965409137836939e-10,0.000000000000000000e+00 +7.875726570314969877e+01,4.828832079418953072e+02,1.406528988115739350e-02,7.605632146790108017e+00,3.822652107923935581e-03,1.000000009960412939e+00,-4.000000000000000327e-05,1.724254166529148890e-10,0.000000000000000000e+00 +7.875858051825079542e+01,4.828932078688320644e+02,1.410351630913811612e-02,7.606946961904302640e+00,3.822506122522397864e-03,1.000000009960639646e+00,-4.000000000000000327e-05,-5.408439068159149647e-10,0.000000000000000000e+00 +7.875989510609399247e+01,4.829032077957743923e+02,1.414174127727549010e-02,7.608261549760598541e+00,3.822360137120860146e-03,1.000000009959928660e+00,-4.000000000000000327e-05,6.200000488037237930e-11,0.000000000000000000e+00 +7.876120946679709789e+01,4.829132077227222908e+02,1.417996478556951372e-02,7.609575910476801042e+00,3.822214151719322429e-03,1.000000009960010150e+00,-4.000000000000000327e-05,3.678401307351640626e-10,0.000000000000000000e+00 +7.876252360047782020e+01,4.829232076496757600e+02,1.421818683402018522e-02,7.610890044170615987e+00,3.822068166317784711e-03,1.000000009960493541e+00,-4.000000000000000327e-05,-2.093856813429305429e-10,0.000000000000000000e+00 +7.876383750725376842e+01,4.829332075766347998e+02,1.425640742262750463e-02,7.612203950959647081e+00,3.821922180916246994e-03,1.000000009960218428e+00,-4.000000000000000327e-05,3.170906784255643960e-10,0.000000000000000000e+00 +7.876515118724243791e+01,4.829432075035994671e+02,1.429462655139147192e-02,7.613517630961395000e+00,3.821776195514709276e-03,1.000000009960634983e+00,-4.000000000000000327e-05,-6.968408000590036113e-10,0.000000000000000000e+00 +7.876646464056122454e+01,4.829532074305697051e+02,1.433284422031208538e-02,7.614831084293260943e+00,3.821630210113171559e-03,1.000000009959719716e+00,-4.000000000000000327e-05,2.816926378031452536e-10,0.000000000000000000e+00 +7.876777786732742470e+01,4.829632073575455138e+02,1.437106042938934500e-02,7.616144311072542195e+00,3.821484224711633841e-03,1.000000009960089642e+00,-4.000000000000000327e-05,9.267358175230618239e-11,0.000000000000000000e+00 +7.876909086765824952e+01,4.829732072845268931e+02,1.440927517862324904e-02,7.617457311416438337e+00,3.821338239310096124e-03,1.000000009960211322e+00,-4.000000000000000327e-05,2.102429216963715520e-10,0.000000000000000000e+00 +7.877040364167078224e+01,4.829832072115138430e+02,1.444748846801379577e-02,7.618770085442045925e+00,3.821192253908558406e-03,1.000000009960487324e+00,-4.000000000000000327e-05,-4.667419043643451902e-10,0.000000000000000000e+00 +7.877171618948202081e+01,4.829932071385063637e+02,1.448570029756098693e-02,7.620082633266361150e+00,3.821046268507020689e-03,1.000000009959874703e+00,-4.000000000000000327e-05,5.683422080769264079e-10,0.000000000000000000e+00 +7.877302851120886373e+01,4.830032070655044549e+02,1.452391066726481904e-02,7.621394955006278060e+00,3.820900283105482971e-03,1.000000009960620551e+00,-4.000000000000000327e-05,-3.635038129024766812e-10,0.000000000000000000e+00 +7.877434060696811002e+01,4.830132069925081737e+02,1.456211957712529384e-02,7.622707050778593008e+00,3.820754297703945254e-03,1.000000009960143599e+00,-4.000000000000000327e-05,-2.395002080402377524e-10,0.000000000000000000e+00 +7.877565247687644501e+01,4.830232069195174631e+02,1.460032702714240786e-02,7.624018920699998425e+00,3.820608312302407536e-03,1.000000009959829406e+00,-4.000000000000000327e-05,3.565188998909495602e-10,0.000000000000000000e+00 +7.877696412105046875e+01,4.830332068465323232e+02,1.463853301731616284e-02,7.625330564887088158e+00,3.820462326900869818e-03,1.000000009960297032e+00,-4.000000000000000327e-05,-1.960683347710212100e-10,0.000000000000000000e+00 +7.877827553960668183e+01,4.830432067735527539e+02,1.467673754764655704e-02,7.626641983456356577e+00,3.820316341499332101e-03,1.000000009960039904e+00,-4.000000000000000327e-05,9.906710030809159383e-11,0.000000000000000000e+00 +7.877958673266145695e+01,4.830532067005787553e+02,1.471494061813358872e-02,7.627953176524195911e+00,3.820170356097794383e-03,1.000000009960169800e+00,-4.000000000000000327e-05,1.387177850714253345e-10,0.000000000000000000e+00 +7.878089770033110995e+01,4.830632066276103274e+02,1.475314222877725789e-02,7.629264144206899800e+00,3.820024370696256666e-03,1.000000009960351655e+00,-4.000000000000000327e-05,-1.473812140209141524e-10,0.000000000000000000e+00 +7.878220844273181456e+01,4.830732065546474701e+02,1.479134237957756282e-02,7.630574886620661523e+00,3.819878385294718948e-03,1.000000009960158476e+00,-4.000000000000000327e-05,-3.120952150305113556e-10,0.000000000000000000e+00 +7.878351895997967347e+01,4.830832064816901834e+02,1.482954107053450349e-02,7.631885403881573993e+00,3.819732399893181231e-03,1.000000009959749470e+00,-4.000000000000000327e-05,9.167888678218564840e-11,0.000000000000000000e+00 +7.878482925219067567e+01,4.830932064087384674e+02,1.486773830164807991e-02,7.633195696105630645e+00,3.819586414491643513e-03,1.000000009959869596e+00,-4.000000000000000327e-05,4.786425621584000532e-10,0.000000000000000000e+00 +7.878613931948072491e+01,4.831032063357923789e+02,1.490593407291829035e-02,7.634505763408726331e+00,3.819440429090105796e-03,1.000000009960496650e+00,-4.000000000000000327e-05,-7.753848532539355482e-10,0.000000000000000000e+00 +7.878744916196561121e+01,4.831132062628518611e+02,1.494412838434513308e-02,7.635815605906656423e+00,3.819294443688568078e-03,1.000000009959481018e+00,-4.000000000000000327e-05,4.023401707979100621e-10,0.000000000000000000e+00 +7.878875877976102515e+01,4.831232061899169139e+02,1.498232123592860981e-02,7.637125223715114153e+00,3.819148458287030361e-03,1.000000009960007930e+00,-4.000000000000000327e-05,3.181287881945839147e-10,0.000000000000000000e+00 +7.879006817298257204e+01,4.831332061169875374e+02,1.502051262766871710e-02,7.638434616949697720e+00,3.819002472885492643e-03,1.000000009960424485e+00,-4.000000000000000327e-05,-5.805658552530971402e-10,0.000000000000000000e+00 +7.879137734174574348e+01,4.831432060440637315e+02,1.505870255956545493e-02,7.639743785725904068e+00,3.818856487483954926e-03,1.000000009959664427e+00,-4.000000000000000327e-05,2.286698524569201357e-10,0.000000000000000000e+00 +7.879268628616593162e+01,4.831532059711454963e+02,1.509689103161882331e-02,7.641052730159129780e+00,3.818710502082417208e-03,1.000000009959963743e+00,-4.000000000000000327e-05,8.483272673397579083e-11,0.000000000000000000e+00 +7.879399500635844333e+01,4.831632058982328317e+02,1.513507804382882051e-02,7.642361450364675513e+00,3.818564516680879491e-03,1.000000009960074765e+00,-4.000000000000000327e-05,-4.412057335245335469e-11,0.000000000000000000e+00 +7.879530350243847181e+01,4.831732058253257378e+02,1.517326359619544651e-02,7.643669946457741560e+00,3.818418531279341773e-03,1.000000009960017033e+00,-4.000000000000000327e-05,-2.274295802407649535e-10,0.000000000000000000e+00 +7.879661177452112497e+01,4.831832057524242146e+02,1.521144768871869959e-02,7.644978218553429627e+00,3.818272545877804056e-03,1.000000009959719494e+00,-4.000000000000000327e-05,5.039955193383323505e-10,0.000000000000000000e+00 +7.879791982272141126e+01,4.831932056795282620e+02,1.524963032139857975e-02,7.646286266766742834e+00,3.818126560476266338e-03,1.000000009960378744e+00,-4.000000000000000327e-05,-5.137593071688187603e-10,0.000000000000000000e+00 +7.879922764715422545e+01,4.832032056066378800e+02,1.528781149423508699e-02,7.647594091212587486e+00,3.817980575074728621e-03,1.000000009959706837e+00,-4.000000000000000327e-05,2.844329239422257009e-10,0.000000000000000000e+00 +7.880053524793437703e+01,4.832132055337530687e+02,1.532599120722821784e-02,7.648901692005768638e+00,3.817834589673190903e-03,1.000000009960078762e+00,-4.000000000000000327e-05,-2.855005952598176475e-10,0.000000000000000000e+00 +7.880184262517659022e+01,4.832232054608738281e+02,1.536416946037797403e-02,7.650209069260996309e+00,3.817688604271653185e-03,1.000000009959705505e+00,-4.000000000000000327e-05,3.047445644778041276e-10,0.000000000000000000e+00 +7.880314977899546136e+01,4.832332053880001581e+02,1.540234625368435382e-02,7.651516223092880153e+00,3.817542618870115468e-03,1.000000009960103853e+00,-4.000000000000000327e-05,-6.116320428602853773e-10,0.000000000000000000e+00 +7.880445670950550152e+01,4.832432053151321156e+02,1.544052158714735550e-02,7.652823153615933904e+00,3.817396633468577750e-03,1.000000009959304492e+00,-4.000000000000000327e-05,5.367987908016565425e-10,0.000000000000000000e+00 +7.880576341682112229e+01,4.832532052422696438e+02,1.547869546076697904e-02,7.654129860944570929e+00,3.817250648067040033e-03,1.000000009960005931e+00,-4.000000000000000327e-05,4.095935360854155910e-11,0.000000000000000000e+00 +7.880706990105665000e+01,4.832632051694127426e+02,1.551686787454322446e-02,7.655436345193110448e+00,3.817104662665502315e-03,1.000000009960059444e+00,-4.000000000000000327e-05,-8.720221978029275984e-11,0.000000000000000000e+00 +7.880837616232629728e+01,4.832732050965614121e+02,1.555503882847609001e-02,7.656742606475771318e+00,3.816958677263964598e-03,1.000000009959945535e+00,-4.000000000000000327e-05,-4.357454686054174344e-10,0.000000000000000000e+00 +7.880968220074419150e+01,4.832832050237156523e+02,1.559320832256557571e-02,7.658048644906675584e+00,3.816812691862426880e-03,1.000000009959376435e+00,-4.000000000000000327e-05,4.893832894490615166e-10,0.000000000000000000e+00 +7.881098801642436058e+01,4.832932049508754631e+02,1.563137635681167981e-02,7.659354460599847592e+00,3.816666706460889163e-03,1.000000009960015479e+00,-4.000000000000000327e-05,1.615682418425435957e-11,0.000000000000000000e+00 +7.881229360948073293e+01,4.833032048780408445e+02,1.566954293121440231e-02,7.660660053669216651e+00,3.816520721059351445e-03,1.000000009960036573e+00,-4.000000000000000327e-05,-3.611240483078980789e-10,0.000000000000000000e+00 +7.881359898002712328e+01,4.833132048052117966e+02,1.570770804577373975e-02,7.661965424228612598e+00,3.816374735657813728e-03,1.000000009959565173e+00,-4.000000000000000327e-05,-1.888440874985022101e-10,0.000000000000000000e+00 +7.881490412817727531e+01,4.833232047323883194e+02,1.574587170048969559e-02,7.663270572391768454e+00,3.816228750256276010e-03,1.000000009959318703e+00,-4.000000000000000327e-05,4.658947633730795199e-10,0.000000000000000000e+00 +7.881620905404483324e+01,4.833332046595704128e+02,1.578403389536226636e-02,7.664575498272321319e+00,3.816082764854738293e-03,1.000000009959926661e+00,-4.000000000000000327e-05,-2.910210761718638662e-11,0.000000000000000000e+00 +7.881751375774332757e+01,4.833432045867580769e+02,1.582219463039145207e-02,7.665880201983812370e+00,3.815936779453200575e-03,1.000000009959888692e+00,-4.000000000000000327e-05,-1.778764871190460035e-10,0.000000000000000000e+00 +7.881881823938620357e+01,4.833532045139513116e+02,1.586035390557724925e-02,7.667184683639684195e+00,3.815790794051662858e-03,1.000000009959656655e+00,-4.000000000000000327e-05,-4.681756733406567664e-11,0.000000000000000000e+00 +7.882012249908680701e+01,4.833632044411501170e+02,1.589851172091966136e-02,7.668488943353283460e+00,3.815644808650125140e-03,1.000000009959595593e+00,-4.000000000000000327e-05,2.971292813158994270e-10,0.000000000000000000e+00 +7.882142653695839840e+01,4.833732043683544930e+02,1.593666807641868494e-02,7.669792981237860907e+00,3.815498823248587423e-03,1.000000009959983061e+00,-4.000000000000000327e-05,-2.590317987763498988e-10,0.000000000000000000e+00 +7.882273035311412457e+01,4.833832042955644397e+02,1.597482297207431998e-02,7.671096797406571355e+00,3.815352837847049705e-03,1.000000009959645331e+00,-4.000000000000000327e-05,-2.147893654387208586e-10,0.000000000000000000e+00 +7.882403394766704707e+01,4.833932042227799570e+02,1.601297640788656648e-02,7.672400391972471922e+00,3.815206852445511988e-03,1.000000009959365332e+00,-4.000000000000000327e-05,3.625292962298725050e-10,0.000000000000000000e+00 +7.882533732073011379e+01,4.834032041500010450e+02,1.605112838385542098e-02,7.673703765048524694e+00,3.815060867043974270e-03,1.000000009959837843e+00,-4.000000000000000327e-05,-1.618709294780828570e-10,0.000000000000000000e+00 +7.882664047241620153e+01,4.834132040772277037e+02,1.608927889998088348e-02,7.675006916747596719e+00,3.814914881642436553e-03,1.000000009959626901e+00,-4.000000000000000327e-05,2.358604328018525919e-10,0.000000000000000000e+00 +7.882794340283808765e+01,4.834232040044599330e+02,1.612742795626295397e-02,7.676309847182457347e+00,3.814768896240898835e-03,1.000000009959934211e+00,-4.000000000000000327e-05,-6.035574966228436171e-10,0.000000000000000000e+00 +7.882924611210843580e+01,4.834332039316977330e+02,1.616557555270163246e-02,7.677612556465781779e+00,3.814622910839361117e-03,1.000000009959147951e+00,-4.000000000000000327e-05,3.929500490030518764e-10,0.000000000000000000e+00 +7.883054860033982436e+01,4.834432038589411036e+02,1.620372168929691895e-02,7.678915044710147519e+00,3.814476925437823400e-03,1.000000009959659764e+00,-4.000000000000000327e-05,1.824415973370431771e-11,0.000000000000000000e+00 +7.883185086764474647e+01,4.834532037861900449e+02,1.624186636604880996e-02,7.680217312028039700e+00,3.814330940036285682e-03,1.000000009959683522e+00,-4.000000000000000327e-05,-2.244241677524550228e-10,0.000000000000000000e+00 +7.883315291413558157e+01,4.834632037134445568e+02,1.628000958295730549e-02,7.681519358531845754e+00,3.814184954634747965e-03,1.000000009959391312e+00,-4.000000000000000327e-05,1.226355110525022934e-10,0.000000000000000000e+00 +7.883445473992462382e+01,4.834732036407045825e+02,1.631815134002240555e-02,7.682821184333858078e+00,3.814038969233210247e-03,1.000000009959550962e+00,-4.000000000000000327e-05,-5.493091362563933742e-11,0.000000000000000000e+00 +7.883575634512408215e+01,4.834832035679701789e+02,1.635629163724411014e-02,7.684122789546274923e+00,3.813892983831672530e-03,1.000000009959479463e+00,-4.000000000000000327e-05,2.243676681835305120e-10,0.000000000000000000e+00 +7.883705772984605176e+01,4.834932034952413460e+02,1.639443047462241579e-02,7.685424174281198617e+00,3.813746998430134812e-03,1.000000009959771452e+00,-4.000000000000000327e-05,-1.544388811885896112e-10,0.000000000000000000e+00 +7.883835889420252840e+01,4.835032034225180837e+02,1.643256785215732249e-02,7.686725338650637340e+00,3.813601013028597095e-03,1.000000009959570502e+00,-4.000000000000000327e-05,-2.087411374678211703e-10,0.000000000000000000e+00 +7.883965983830543678e+01,4.835132033498003921e+02,1.647070376984883025e-02,7.688026282766503350e+00,3.813455027627059377e-03,1.000000009959298941e+00,-4.000000000000000327e-05,5.199780174726502100e-10,0.000000000000000000e+00 +7.884096056226658789e+01,4.835232032770882711e+02,1.650883822769693907e-02,7.689327006740614756e+00,3.813309042225521660e-03,1.000000009959975289e+00,-4.000000000000000327e-05,-6.588754634997869482e-10,0.000000000000000000e+00 +7.884226106619772168e+01,4.835332032043817208e+02,1.654697122570164547e-02,7.690627510684696411e+00,3.813163056823983942e-03,1.000000009959118419e+00,-4.000000000000000327e-05,3.893470151697077291e-10,0.000000000000000000e+00 +7.884356135021045020e+01,4.835432031316807411e+02,1.658510276386294946e-02,7.691927794710375466e+00,3.813017071422446225e-03,1.000000009959624681e+00,-4.000000000000000327e-05,-7.856574914126330873e-11,0.000000000000000000e+00 +7.884486141441631446e+01,4.835532030589853321e+02,1.662323284218085104e-02,7.693227858929188478e+00,3.812871086020908507e-03,1.000000009959522540e+00,-4.000000000000000327e-05,-2.613606803017289412e-11,0.000000000000000000e+00 +7.884616125892675598e+01,4.835632029862954937e+02,1.666136146065535020e-02,7.694527703452575196e+00,3.812725100619370790e-03,1.000000009959488567e+00,-4.000000000000000327e-05,-4.578856015514199563e-11,0.000000000000000000e+00 +7.884746088385311680e+01,4.835732029136112260e+02,1.669948861928644696e-02,7.695827328391882105e+00,3.812579115217833072e-03,1.000000009959429059e+00,-4.000000000000000327e-05,-2.026656889302985005e-10,0.000000000000000000e+00 +7.884876028930665370e+01,4.835832028409325289e+02,1.673761431807413783e-02,7.697126733858361547e+00,3.812433129816295355e-03,1.000000009959165714e+00,-4.000000000000000327e-05,-3.674576749056573876e-11,0.000000000000000000e+00 +7.885005947539852400e+01,4.835932027682594025e+02,1.677573855701842281e-02,7.698425919963171715e+00,3.812287144414757637e-03,1.000000009959117975e+00,-4.000000000000000327e-05,3.871777278500539537e-10,0.000000000000000000e+00 +7.885135844223979973e+01,4.836032026955918468e+02,1.681386133611930192e-02,7.699724886817377545e+00,3.812141159013219920e-03,1.000000009959620906e+00,-4.000000000000000327e-05,-5.009369345637652487e-11,0.000000000000000000e+00 +7.885265718994143924e+01,4.836132026229298617e+02,1.685198265537677167e-02,7.701023634531950712e+00,3.811995173611682202e-03,1.000000009959555847e+00,-4.000000000000000327e-05,-3.613168195696572689e-10,0.000000000000000000e+00 +7.885395571861432984e+01,4.836232025502733904e+02,1.689010251479083555e-02,7.702322163217767859e+00,3.811849188210144485e-03,1.000000009959086666e+00,-4.000000000000000327e-05,4.424440244453623870e-10,0.000000000000000000e+00 +7.885525402836924513e+01,4.836332024776224898e+02,1.692822091436149007e-02,7.703620472985612366e+00,3.811703202808606767e-03,1.000000009959661096e+00,-4.000000000000000327e-05,-3.386883781544616359e-10,0.000000000000000000e+00 +7.885655211931687347e+01,4.836432024049771599e+02,1.696633785408873524e-02,7.704918563946176135e+00,3.811557217407069049e-03,1.000000009959221448e+00,-4.000000000000000327e-05,-1.353270958422175892e-10,0.000000000000000000e+00 +7.885784999156783215e+01,4.836532023323374005e+02,1.700445333397256759e-02,7.706216436210055143e+00,3.811411232005531332e-03,1.000000009959045810e+00,-4.000000000000000327e-05,4.608056350433304898e-10,0.000000000000000000e+00 +7.885914764523261056e+01,4.836632022597032119e+02,1.704256735401299058e-02,7.707514089887753883e+00,3.811265246603993614e-03,1.000000009959643776e+00,-4.000000000000000327e-05,-1.974969356883897203e-10,0.000000000000000000e+00 +7.886044508042161283e+01,4.836732021870745939e+02,1.708067991421000076e-02,7.708811525089684480e+00,3.811119261202455897e-03,1.000000009959387537e+00,-4.000000000000000327e-05,-6.572928036595457747e-11,0.000000000000000000e+00 +7.886174229724517204e+01,4.836832021144515465e+02,1.711879101456359811e-02,7.710108741926164022e+00,3.810973275800918179e-03,1.000000009959302272e+00,-4.000000000000000327e-05,-2.639885572375298744e-10,0.000000000000000000e+00 +7.886303929581350758e+01,4.836932020418340699e+02,1.715690065507377918e-02,7.711405740507418116e+00,3.810827290399380462e-03,1.000000009958959879e+00,-4.000000000000000327e-05,1.991377035761605021e-10,0.000000000000000000e+00 +7.886433607623675357e+01,4.837032019692221070e+02,1.719500883574054742e-02,7.712702520943579110e+00,3.810681304997842744e-03,1.000000009959218117e+00,-4.000000000000000327e-05,2.024250629285642355e-10,0.000000000000000000e+00 +7.886563263862494466e+01,4.837132018966157148e+02,1.723311555656389937e-02,7.713999083344687868e+00,3.810535319596305027e-03,1.000000009959480574e+00,-4.000000000000000327e-05,-3.187617346546037231e-10,0.000000000000000000e+00 +7.886692898308804445e+01,4.837232018240148932e+02,1.727122081754383504e-02,7.715295427820691998e+00,3.810389334194767309e-03,1.000000009959067349e+00,-4.000000000000000327e-05,1.555530870436514068e-10,0.000000000000000000e+00 +7.886822510973588862e+01,4.837332017514196423e+02,1.730932461868035441e-02,7.716591554481445847e+00,3.810243348793229592e-03,1.000000009959268965e+00,-4.000000000000000327e-05,-2.381664257084905547e-11,0.000000000000000000e+00 +7.886952101867825604e+01,4.837432016788299620e+02,1.734742695997345402e-02,7.717887463436713169e+00,3.810097363391691874e-03,1.000000009959238101e+00,-4.000000000000000327e-05,1.355548780685653610e-10,0.000000000000000000e+00 +7.887081671002479766e+01,4.837532016062458524e+02,1.738552784142313734e-02,7.719183154796164459e+00,3.809951377990154157e-03,1.000000009959413738e+00,-4.000000000000000327e-05,-4.893478490629166639e-10,0.000000000000000000e+00 +7.887211218388510758e+01,4.837632015336673135e+02,1.742362726302940090e-02,7.720478628669378729e+00,3.809805392588616439e-03,1.000000009958779801e+00,-4.000000000000000327e-05,6.845162473351613221e-10,0.000000000000000000e+00 +7.887340744036866624e+01,4.837732014610942883e+02,1.746172522479224123e-02,7.721773885165841733e+00,3.809659407187078722e-03,1.000000009959666425e+00,-4.000000000000000327e-05,-6.427953790463622786e-10,0.000000000000000000e+00 +7.887470247958488301e+01,4.837832013885268339e+02,1.749982172671166181e-02,7.723068924394950407e+00,3.809513421785541004e-03,1.000000009958833980e+00,-4.000000000000000327e-05,2.296205290300798731e-10,0.000000000000000000e+00 +7.887599730164303935e+01,4.837932013159649500e+02,1.753791676878765915e-02,7.724363746466005765e+00,3.809367436384003287e-03,1.000000009959131297e+00,-4.000000000000000327e-05,6.105945735117352907e-11,0.000000000000000000e+00 +7.887729190665235990e+01,4.838032012434086369e+02,1.757601035102023673e-02,7.725658351488220887e+00,3.809221450982465569e-03,1.000000009959210345e+00,-4.000000000000000327e-05,-1.540465799284889603e-10,0.000000000000000000e+00 +7.887858629472196981e+01,4.838132011708578943e+02,1.761410247340938762e-02,7.726952739570715600e+00,3.809075465580927852e-03,1.000000009959010949e+00,-4.000000000000000327e-05,5.095712659947132803e-11,0.000000000000000000e+00 +7.887988046596088054e+01,4.838232010983127225e+02,1.765219313595511527e-02,7.728246910822518245e+00,3.808929480179390134e-03,1.000000009959076896e+00,-4.000000000000000327e-05,8.168233932684995864e-11,0.000000000000000000e+00 +7.888117442047804673e+01,4.838332010257730644e+02,1.769028233865741970e-02,7.729540865352566570e+00,3.808783494777852417e-03,1.000000009959182590e+00,-4.000000000000000327e-05,-1.251184775972640517e-10,0.000000000000000000e+00 +7.888246815838230930e+01,4.838432009532389770e+02,1.772837008151629742e-02,7.730834603269706840e+00,3.808637509376314699e-03,1.000000009959020719e+00,-4.000000000000000327e-05,-1.036820429595165086e-10,0.000000000000000000e+00 +7.888376167978240971e+01,4.838532008807104603e+02,1.776645636453174845e-02,7.732128124682693837e+00,3.808491523974776981e-03,1.000000009958886604e+00,-4.000000000000000327e-05,8.378361393213471563e-11,0.000000000000000000e+00 +7.888505498478703259e+01,4.838632008081875142e+02,1.780454118770376931e-02,7.733421429700191752e+00,3.808345538573239264e-03,1.000000009958994962e+00,-4.000000000000000327e-05,3.726246978186113498e-10,0.000000000000000000e+00 +7.888634807350473466e+01,4.838732007356701388e+02,1.784262455103236347e-02,7.734714518430774177e+00,3.808199553171701546e-03,1.000000009959476799e+00,-4.000000000000000327e-05,-3.623822938145545201e-10,0.000000000000000000e+00 +7.888764094604400157e+01,4.838832006631583340e+02,1.788070645451752747e-02,7.736007390982924115e+00,3.808053567770163829e-03,1.000000009959008285e+00,-4.000000000000000327e-05,-6.012085466897739299e-11,0.000000000000000000e+00 +7.888893360251323372e+01,4.838932005906520430e+02,1.791878689815926129e-02,7.737300047465032193e+00,3.807907582368626111e-03,1.000000009958930569e+00,-4.000000000000000327e-05,1.539351056074315771e-10,0.000000000000000000e+00 +7.889022604302073205e+01,4.839032005181513227e+02,1.795686588195756495e-02,7.738592487985400226e+00,3.807761596967088394e-03,1.000000009959129521e+00,-4.000000000000000327e-05,-3.156540451338769259e-10,0.000000000000000000e+00 +7.889151826767469800e+01,4.839132004456561731e+02,1.799494340591243496e-02,7.739884712652239429e+00,3.807615611565550676e-03,1.000000009958721625e+00,-4.000000000000000327e-05,6.341632683356915901e-11,0.000000000000000000e+00 +7.889281027658326195e+01,4.839232003731665941e+02,1.803301947002387481e-02,7.741176721573669539e+00,3.807469626164012959e-03,1.000000009958803560e+00,-4.000000000000000327e-05,1.644974406144417494e-10,0.000000000000000000e+00 +7.889410206985445484e+01,4.839332003006825289e+02,1.807109407429188103e-02,7.742468514857721473e+00,3.807323640762475241e-03,1.000000009959016056e+00,-4.000000000000000327e-05,-7.633129729615780316e-11,0.000000000000000000e+00 +7.889539364759620810e+01,4.839432002282040344e+02,1.810916721871645360e-02,7.743760092612335555e+00,3.807177655360937524e-03,1.000000009958917468e+00,-4.000000000000000327e-05,-1.887967245137366034e-10,0.000000000000000000e+00 +7.889668500991636790e+01,4.839532001557311105e+02,1.814723890329758907e-02,7.745051454945361513e+00,3.807031669959399806e-03,1.000000009958673663e+00,-4.000000000000000327e-05,2.961404145333171174e-10,0.000000000000000000e+00 +7.889797615692270938e+01,4.839632000832637573e+02,1.818530912803529090e-02,7.746342601964559371e+00,3.806885684557862089e-03,1.000000009959056024e+00,-4.000000000000000327e-05,2.507808963528718751e-10,0.000000000000000000e+00 +7.889926708872289396e+01,4.839732000108019747e+02,1.822337789292955562e-02,7.747633533777600334e+00,3.806739699156324371e-03,1.000000009959379765e+00,-4.000000000000000327e-05,-3.887923713272151901e-10,0.000000000000000000e+00 +7.890055780542449781e+01,4.839831999383457060e+02,1.826144519798038324e-02,7.748924250492065013e+00,3.806593713754786654e-03,1.000000009958877945e+00,-4.000000000000000327e-05,-8.499797709544853160e-11,0.000000000000000000e+00 +7.890184830713502606e+01,4.839931998658950079e+02,1.829951104318777028e-02,7.750214752215443426e+00,3.806447728353248936e-03,1.000000009958768254e+00,-4.000000000000000327e-05,3.269697408205672274e-11,0.000000000000000000e+00 +7.890313859396187013e+01,4.840031997934498804e+02,1.833757542855172021e-02,7.751505039055137658e+00,3.806301742951711219e-03,1.000000009958810443e+00,-4.000000000000000327e-05,-9.827937080376622518e-11,0.000000000000000000e+00 +7.890442866601235039e+01,4.840131997210103236e+02,1.837563835407222956e-02,7.752795111118460092e+00,3.806155757550173501e-03,1.000000009958683655e+00,-4.000000000000000327e-05,-6.541572044549447982e-12,0.000000000000000000e+00 +7.890571852339367354e+01,4.840231996485762807e+02,1.841369981974929834e-02,7.754084968512633402e+00,3.806009772148635784e-03,1.000000009958675218e+00,-4.000000000000000327e-05,2.455219397812017366e-10,0.000000000000000000e+00 +7.890700816621298941e+01,4.840331995761478083e+02,1.845175982558292654e-02,7.755374611344791447e+00,3.805863786747098066e-03,1.000000009958991853e+00,-4.000000000000000327e-05,6.130459166173154432e-11,0.000000000000000000e+00 +7.890829759457733417e+01,4.840431995037249067e+02,1.848981837157311070e-02,7.756664039721979265e+00,3.805717801345560349e-03,1.000000009959070901e+00,-4.000000000000000327e-05,-6.219317027475150076e-10,0.000000000000000000e+00 +7.890958680859367291e+01,4.840531994313075757e+02,1.852787545771985428e-02,7.757953253751152189e+00,3.805571815944022631e-03,1.000000009958269098e+00,-4.000000000000000327e-05,8.065267816728758357e-10,0.000000000000000000e+00 +7.891087580836885707e+01,4.840631993588957585e+02,1.856593108402315381e-02,7.759242253539175849e+00,3.805425830542484913e-03,1.000000009959308711e+00,-4.000000000000000327e-05,-5.265175923433611866e-10,0.000000000000000000e+00 +7.891216459400968120e+01,4.840731992864895119e+02,1.860398525048300583e-02,7.760531039192830605e+00,3.805279845140947196e-03,1.000000009958630143e+00,-4.000000000000000327e-05,1.282048932162874977e-10,0.000000000000000000e+00 +7.891345316562282619e+01,4.840831992140888360e+02,1.864203795709941380e-02,7.761819610818803561e+00,3.805133859739409478e-03,1.000000009958795344e+00,-4.000000000000000327e-05,3.567583249796096232e-11,0.000000000000000000e+00 +7.891474152331488767e+01,4.840931991416937308e+02,1.868008920387237426e-02,7.763107968523696556e+00,3.804987874337871761e-03,1.000000009958841307e+00,-4.000000000000000327e-05,-3.318230765582822281e-10,0.000000000000000000e+00 +7.891602966719239021e+01,4.841031990693041394e+02,1.871813899080188720e-02,7.764396112414021722e+00,3.804841888936334043e-03,1.000000009958413871e+00,-4.000000000000000327e-05,3.448084534524840817e-11,0.000000000000000000e+00 +7.891731759736174467e+01,4.841131989969201186e+02,1.875618731788795263e-02,7.765684042596202374e+00,3.804695903534796326e-03,1.000000009958458280e+00,-4.000000000000000327e-05,5.383352781548410765e-10,0.000000000000000000e+00 +7.891860531392929090e+01,4.841231989245416685e+02,1.879423418513057054e-02,7.766971759176574785e+00,3.804549918133258608e-03,1.000000009959151503e+00,-4.000000000000000327e-05,-4.897904259073876143e-10,0.000000000000000000e+00 +7.891989281700128345e+01,4.841331988521687322e+02,1.883227959252973746e-02,7.768259262261387299e+00,3.804403932731720891e-03,1.000000009958520897e+00,-4.000000000000000327e-05,1.031490235188738922e-10,0.000000000000000000e+00 +7.892118010668387740e+01,4.841431987798013665e+02,1.887032354008545687e-02,7.769546551956797664e+00,3.804257947330183173e-03,1.000000009958653679e+00,-4.000000000000000327e-05,1.124821203263477784e-10,0.000000000000000000e+00 +7.892246718308314257e+01,4.841531987074395715e+02,1.890836602779772183e-02,7.770833628368878365e+00,3.804111961928645456e-03,1.000000009958798453e+00,-4.000000000000000327e-05,-5.238532029434120831e-10,0.000000000000000000e+00 +7.892375404630506353e+01,4.841631986350833472e+02,1.894640705566653580e-02,7.772120491603613068e+00,3.803965976527107738e-03,1.000000009958124325e+00,-4.000000000000000327e-05,8.143849283798732721e-10,0.000000000000000000e+00 +7.892504069645553955e+01,4.841731985627326367e+02,1.898444662369189878e-02,7.773407141766896622e+00,3.803819991125570021e-03,1.000000009959172154e+00,-4.000000000000000327e-05,-7.617028278476503607e-10,0.000000000000000000e+00 +7.892632713364037045e+01,4.841831984903874968e+02,1.902248473187380731e-02,7.774693578964539498e+00,3.803674005724032303e-03,1.000000009958192271e+00,-4.000000000000000327e-05,5.885054757002208712e-10,0.000000000000000000e+00 +7.892761335796528499e+01,4.841931984180479276e+02,1.906052138021226139e-02,7.775979803302259796e+00,3.803528020322494586e-03,1.000000009958949221e+00,-4.000000000000000327e-05,-5.632216053180088211e-10,0.000000000000000000e+00 +7.892889936953591246e+01,4.842031983457138722e+02,1.909855656870726101e-02,7.777265814885693018e+00,3.803382034920956868e-03,1.000000009958224911e+00,-4.000000000000000327e-05,5.539894928164491416e-10,0.000000000000000000e+00 +7.893018516845779686e+01,4.842131982733853874e+02,1.913659029735880271e-02,7.778551613820383182e+00,3.803236049519419151e-03,1.000000009958937230e+00,-4.000000000000000327e-05,-4.174607160090962969e-10,0.000000000000000000e+00 +7.893147075483639696e+01,4.842231982010624733e+02,1.917462256616688648e-02,7.779837200211790815e+00,3.803090064117881433e-03,1.000000009958400549e+00,-4.000000000000000327e-05,2.224982490222690184e-10,0.000000000000000000e+00 +7.893275612877708625e+01,4.842331981287450731e+02,1.921265337513151580e-02,7.781122574165285855e+00,3.802944078716343716e-03,1.000000009958686542e+00,-4.000000000000000327e-05,-2.748860253975353959e-10,0.000000000000000000e+00 +7.893404129038515293e+01,4.842431980564332434e+02,1.925068272425268373e-02,7.782407735786153857e+00,3.802798093314805998e-03,1.000000009958333269e+00,-4.000000000000000327e-05,1.809259608657876745e-10,0.000000000000000000e+00 +7.893532623976579998e+01,4.842531979841269845e+02,1.928871061353039373e-02,7.783692685179591564e+00,3.802652107913268281e-03,1.000000009958565750e+00,-4.000000000000000327e-05,-8.468802138978936861e-11,0.000000000000000000e+00 +7.893661097702413088e+01,4.842631979118262393e+02,1.932673704296464234e-02,7.784977422450710449e+00,3.802506122511730563e-03,1.000000009958456948e+00,-4.000000000000000327e-05,-5.669848134468210040e-11,0.000000000000000000e+00 +7.893789550226516383e+01,4.842731978395310648e+02,1.936476201255542956e-02,7.786261947704534059e+00,3.802360137110192845e-03,1.000000009958384117e+00,-4.000000000000000327e-05,2.050472385212737648e-10,0.000000000000000000e+00 +7.893917981559384600e+01,4.842831977672414610e+02,1.940278552230275538e-02,7.787546261045999785e+00,3.802214151708655128e-03,1.000000009958647462e+00,-4.000000000000000327e-05,-4.374832061159490346e-10,0.000000000000000000e+00 +7.894046391711501087e+01,4.842931976949573709e+02,1.944080757220661981e-02,7.788830362579958866e+00,3.802068166307117410e-03,1.000000009958085689e+00,-4.000000000000000327e-05,6.483774634816145156e-10,0.000000000000000000e+00 +7.894174780693343507e+01,4.843031976226788515e+02,1.947882816226701938e-02,7.790114252411174611e+00,3.801922180905579693e-03,1.000000009958918135e+00,-4.000000000000000327e-05,-3.686103305231161576e-10,0.000000000000000000e+00 +7.894303148515380997e+01,4.843131975504059028e+02,1.951684729248395755e-02,7.791397930644326841e+00,3.801776195504041975e-03,1.000000009958444958e+00,-4.000000000000000327e-05,-3.165969311842236074e-10,0.000000000000000000e+00 +7.894431495188071324e+01,4.843231974781384679e+02,1.955486496285743087e-02,7.792681397384005670e+00,3.801630210102504258e-03,1.000000009958038616e+00,-4.000000000000000327e-05,2.066005497453394044e-10,0.000000000000000000e+00 +7.894559820721865151e+01,4.843331974058766036e+02,1.959288117338743584e-02,7.793964652734716836e+00,3.801484224700966540e-03,1.000000009958303737e+00,-4.000000000000000327e-05,6.178269853554616994e-11,0.000000000000000000e+00 +7.894688125127203193e+01,4.843431973336202532e+02,1.963089592407397596e-02,7.795247696800880810e+00,3.801338239299428823e-03,1.000000009958383007e+00,-4.000000000000000327e-05,2.674229213974168754e-10,0.000000000000000000e+00 +7.894816408414520481e+01,4.843531972613694734e+02,1.966890921491704775e-02,7.796530529686831024e+00,3.801192253897891105e-03,1.000000009958726066e+00,-4.000000000000000327e-05,-3.155936657699219121e-10,0.000000000000000000e+00 +7.894944670594242098e+01,4.843631971891242642e+02,1.970692104591665120e-02,7.797813151496815642e+00,3.801046268496353388e-03,1.000000009958321279e+00,-4.000000000000000327e-05,-1.284745056653466091e-10,0.000000000000000000e+00 +7.895072911676783178e+01,4.843731971168845689e+02,1.974493141707278632e-02,7.799095562334995790e+00,3.800900283094815670e-03,1.000000009958156522e+00,-4.000000000000000327e-05,2.301491886479036625e-10,0.000000000000000000e+00 +7.895201131672551753e+01,4.843831970446504442e+02,1.978294032838545310e-02,7.800377762305448215e+00,3.800754297693277953e-03,1.000000009958451619e+00,-4.000000000000000327e-05,1.596933318214338110e-10,0.000000000000000000e+00 +7.895329330591947326e+01,4.843931969724218902e+02,1.982094777985464809e-02,7.801659751512164398e+00,3.800608312291740235e-03,1.000000009958656344e+00,-4.000000000000000327e-05,-4.003383332783408199e-10,0.000000000000000000e+00 +7.895457508445359451e+01,4.844031969001988500e+02,1.985895377148037128e-02,7.802941530059049668e+00,3.800462326890202518e-03,1.000000009958143199e+00,-4.000000000000000327e-05,1.124458093972507630e-10,0.000000000000000000e+00 +7.895585665243170581e+01,4.844131968279813805e+02,1.989695830326262266e-02,7.804223098049923202e+00,3.800316341488664800e-03,1.000000009958287306e+00,-4.000000000000000327e-05,1.680899065516700169e-11,0.000000000000000000e+00 +7.895713800995754639e+01,4.844231967557694247e+02,1.993496137520139877e-02,7.805504455588520685e+00,3.800170356087127083e-03,1.000000009958308844e+00,-4.000000000000000327e-05,-2.067671992626497670e-10,0.000000000000000000e+00 +7.895841915713475601e+01,4.844331966835630396e+02,1.997296298729670308e-02,7.806785602778491651e+00,3.800024370685589365e-03,1.000000009958043945e+00,-4.000000000000000327e-05,4.650858758615748569e-10,0.000000000000000000e+00 +7.895970009406690338e+01,4.844431966113622252e+02,2.001096313954853212e-02,7.808066539723400368e+00,3.799878385284051648e-03,1.000000009958639691e+00,-4.000000000000000327e-05,-7.340651137874604281e-10,0.000000000000000000e+00 +7.896098082085747194e+01,4.844531965391669246e+02,2.004896183195688589e-02,7.809347266526727616e+00,3.799732399882513930e-03,1.000000009957699554e+00,-4.000000000000000327e-05,4.681863256999410855e-10,0.000000000000000000e+00 +7.896226133760985988e+01,4.844631964669771946e+02,2.008695906452176438e-02,7.810627783291866244e+00,3.799586414480976213e-03,1.000000009958299074e+00,-4.000000000000000327e-05,2.219913933257619977e-10,0.000000000000000000e+00 +7.896354164442736590e+01,4.844731963947929785e+02,2.012495483724316414e-02,7.811908090122128279e+00,3.799440429079438495e-03,1.000000009958583291e+00,-4.000000000000000327e-05,-4.496062582148087339e-10,0.000000000000000000e+00 +7.896482174141323185e+01,4.844831963226143330e+02,2.016294915012108516e-02,7.813188187120738704e+00,3.799294443677900777e-03,1.000000009958007752e+00,-4.000000000000000327e-05,2.047154015372692396e-11,0.000000000000000000e+00 +7.896610162867058591e+01,4.844931962504412013e+02,2.020094200315552743e-02,7.814468074390837238e+00,3.799148458276363060e-03,1.000000009958033953e+00,-4.000000000000000327e-05,4.896622864054776615e-10,0.000000000000000000e+00 +7.896738130630248520e+01,4.845031961782736403e+02,2.023893339634649097e-02,7.815747752035481000e+00,3.799002472874825342e-03,1.000000009958660563e+00,-4.000000000000000327e-05,-7.287131966914768443e-10,0.000000000000000000e+00 +7.896866077441190157e+01,4.845131961061116499e+02,2.027692332969397576e-02,7.817027220157642731e+00,3.798856487473287625e-03,1.000000009957728198e+00,-4.000000000000000327e-05,6.460382298773380577e-10,0.000000000000000000e+00 +7.896994003310172161e+01,4.845231960339551733e+02,2.031491180319797835e-02,7.818306478860208131e+00,3.798710502071749907e-03,1.000000009958554648e+00,-4.000000000000000327e-05,-3.279328128728427595e-10,0.000000000000000000e+00 +7.897121908247476085e+01,4.845331959618042674e+02,2.035289881685849872e-02,7.819585528245982964e+00,3.798564516670212190e-03,1.000000009958135205e+00,-4.000000000000000327e-05,-4.540416077861318977e-10,0.000000000000000000e+00 +7.897249792263372115e+01,4.845431958896588753e+02,2.039088437067553689e-02,7.820864368417685064e+00,3.798418531268674472e-03,1.000000009957554559e+00,-4.000000000000000327e-05,7.536760406641807086e-10,0.000000000000000000e+00 +7.897377655368124749e+01,4.845531958175190539e+02,2.042886846464908937e-02,7.822142999477949665e+00,3.798272545867136755e-03,1.000000009958518232e+00,-4.000000000000000327e-05,-5.665652494778921529e-10,0.000000000000000000e+00 +7.897505497571989963e+01,4.845631957453847463e+02,2.046685109877915965e-02,7.823421421529330289e+00,3.798126560465599037e-03,1.000000009957793923e+00,-4.000000000000000327e-05,4.167419296374510959e-10,0.000000000000000000e+00 +7.897633318885213782e+01,4.845731956732560093e+02,2.050483227306574424e-02,7.824699634674292525e+00,3.797980575064061320e-03,1.000000009958326608e+00,-4.000000000000000327e-05,-1.593225454898111880e-10,0.000000000000000000e+00 +7.897761119318033707e+01,4.845831956011327861e+02,2.054281198750884316e-02,7.825977639015222032e+00,3.797834589662523602e-03,1.000000009958122993e+00,-4.000000000000000327e-05,-1.789847596397482319e-10,0.000000000000000000e+00 +7.897888898880681552e+01,4.845931955290151336e+02,2.058079024210845293e-02,7.827255434654418309e+00,3.797688604260985885e-03,1.000000009957894287e+00,-4.000000000000000327e-05,2.998049725095624268e-10,0.000000000000000000e+00 +7.898016657583377764e+01,4.846031954569030518e+02,2.061876703686457701e-02,7.828533021694098260e+00,3.797542618859448167e-03,1.000000009958277314e+00,-4.000000000000000327e-05,-4.135376498706269115e-10,0.000000000000000000e+00 +7.898144395436335685e+01,4.846131953847964837e+02,2.065674237177721195e-02,7.829810400236396184e+00,3.797396633457910450e-03,1.000000009957749070e+00,-4.000000000000000327e-05,3.435408702149782264e-10,0.000000000000000000e+00 +7.898272112449760129e+01,4.846231953126954863e+02,2.069471624684635774e-02,7.831087570383361118e+00,3.797250648056372732e-03,1.000000009958187830e+00,-4.000000000000000327e-05,-2.086620894838916019e-10,0.000000000000000000e+00 +7.898399808633848806e+01,4.846331952406000028e+02,2.073268866207201439e-02,7.832364532236961274e+00,3.797104662654835015e-03,1.000000009957921376e+00,-4.000000000000000327e-05,4.956532721339743119e-11,0.000000000000000000e+00 +7.898527483998789478e+01,4.846431951685100898e+02,2.077065961745417841e-02,7.833641285899079598e+00,3.796958677253297297e-03,1.000000009957984659e+00,-4.000000000000000327e-05,-2.939616055723669151e-11,0.000000000000000000e+00 +7.898655138554761379e+01,4.846531950964256907e+02,2.080862911299285328e-02,7.834917831471517324e+00,3.796812691851759580e-03,1.000000009957947134e+00,-4.000000000000000327e-05,4.192679975167113757e-11,0.000000000000000000e+00 +7.898782772311938061e+01,4.846631950243468623e+02,2.084659714868803554e-02,7.836194169055992198e+00,3.796666706450221862e-03,1.000000009958000646e+00,-4.000000000000000327e-05,-3.406889921955621194e-10,0.000000000000000000e+00 +7.898910385280481705e+01,4.846731949522735476e+02,2.088456372453972171e-02,7.837470298754139364e+00,3.796520721048684145e-03,1.000000009957565883e+00,-4.000000000000000327e-05,4.021759338983702565e-10,0.000000000000000000e+00 +7.899037977470548810e+01,4.846831948802058037e+02,2.092252884054791526e-02,7.838746220667510478e+00,3.796374735647146427e-03,1.000000009958079028e+00,-4.000000000000000327e-05,3.028559275355717064e-11,0.000000000000000000e+00 +7.899165548892284505e+01,4.846931948081435735e+02,2.096049249671261272e-02,7.840021934897576372e+00,3.796228750245608709e-03,1.000000009958117664e+00,-4.000000000000000327e-05,-4.237191351017677559e-10,0.000000000000000000e+00 +7.899293099555829656e+01,4.847031947360869140e+02,2.099845469303381409e-02,7.841297441545723501e+00,3.796082764844070992e-03,1.000000009957577207e+00,-4.000000000000000327e-05,7.486806507783019611e-11,0.000000000000000000e+00 +7.899420629471312338e+01,4.847131946640357683e+02,2.103641542951151938e-02,7.842572740713255719e+00,3.795936779442533274e-03,1.000000009957672686e+00,-4.000000000000000327e-05,3.770133090973226484e-10,0.000000000000000000e+00 +7.899548138648856366e+01,4.847231945919901932e+02,2.107437470614572858e-02,7.843847832501396056e+00,3.795790794040995557e-03,1.000000009958153413e+00,-4.000000000000000327e-05,-1.215695496955765307e-10,0.000000000000000000e+00 +7.899675627098575603e+01,4.847331945199501320e+02,2.111233252293643822e-02,7.845122717011284941e+00,3.795644808639457839e-03,1.000000009957998426e+00,-4.000000000000000327e-05,-3.867167126917492764e-10,0.000000000000000000e+00 +7.899803094830575390e+01,4.847431944479156414e+02,2.115028887988364831e-02,7.846397394343979315e+00,3.795498823237920122e-03,1.000000009957505487e+00,-4.000000000000000327e-05,7.230338369474401376e-11,0.000000000000000000e+00 +7.899930541854953958e+01,4.847531943758866646e+02,2.118824377698735884e-02,7.847671864600454406e+00,3.795352837836382404e-03,1.000000009957597635e+00,-4.000000000000000327e-05,6.510104030554252008e-10,0.000000000000000000e+00 +7.900057968181799595e+01,4.847631943038632585e+02,2.122619721424756981e-02,7.848946127881604617e+00,3.795206852434844687e-03,1.000000009958427194e+00,-4.000000000000000327e-05,-8.959817786244734085e-10,0.000000000000000000e+00 +7.900185373821194901e+01,4.847731942318453662e+02,2.126414919166427775e-02,7.850220184288242642e+00,3.795060867033306969e-03,1.000000009957285663e+00,-4.000000000000000327e-05,2.971983862168115905e-10,0.000000000000000000e+00 +7.900312758783211109e+01,4.847831941598330445e+02,2.130209970923748614e-02,7.851494033921095905e+00,3.794914881631769252e-03,1.000000009957664249e+00,-4.000000000000000327e-05,3.446665998177335558e-10,0.000000000000000000e+00 +7.900440123077915189e+01,4.847931940878262367e+02,2.134004876696719150e-02,7.852767676880814562e+00,3.794768896230231534e-03,1.000000009958103231e+00,-4.000000000000000327e-05,-2.646883009106443450e-10,0.000000000000000000e+00 +7.900567466715362741e+01,4.848031940158249427e+02,2.137799636485339036e-02,7.854041113267965279e+00,3.794622910828693817e-03,1.000000009957766167e+00,-4.000000000000000327e-05,5.423676588348274988e-11,0.000000000000000000e+00 +7.900694789705602261e+01,4.848131939438292193e+02,2.141594250289608620e-02,7.855314343183032122e+00,3.794476925427156099e-03,1.000000009957835223e+00,-4.000000000000000327e-05,-3.976844787358338461e-10,0.000000000000000000e+00 +7.900822092058673718e+01,4.848231938718390097e+02,2.145388718109527554e-02,7.856587366726419219e+00,3.794330940025618382e-03,1.000000009957328961e+00,-4.000000000000000327e-05,5.146312871816090907e-10,0.000000000000000000e+00 +7.900949373784608554e+01,4.848331937998543708e+02,2.149183039945095838e-02,7.857860183998448100e+00,3.794184954624080664e-03,1.000000009957983993e+00,-4.000000000000000327e-05,-7.153661386459483557e-12,0.000000000000000000e+00 +7.901076634893432526e+01,4.848431937278752457e+02,2.152977215796313473e-02,7.859132795099361246e+00,3.794038969222542947e-03,1.000000009957974889e+00,-4.000000000000000327e-05,-3.746682544453944676e-10,0.000000000000000000e+00 +7.901203875395161447e+01,4.848531936559016913e+02,2.156771245663180459e-02,7.860405200129317649e+00,3.793892983821005229e-03,1.000000009957498159e+00,-4.000000000000000327e-05,-9.651843936689969945e-11,0.000000000000000000e+00 +7.901331095299802598e+01,4.848631935839336506e+02,2.160565129545696447e-02,7.861677399188395476e+00,3.793746998419467512e-03,1.000000009957375369e+00,-4.000000000000000327e-05,2.232677463700917724e-10,0.000000000000000000e+00 +7.901458294617356160e+01,4.848731935119711807e+02,2.164358867443861439e-02,7.862949392376592961e+00,3.793601013017929794e-03,1.000000009957659364e+00,-4.000000000000000327e-05,-2.199866119133477031e-11,0.000000000000000000e+00 +7.901585473357813783e+01,4.848831934400142245e+02,2.168152459357675435e-02,7.864221179793827510e+00,3.793455027616392077e-03,1.000000009957631386e+00,-4.000000000000000327e-05,2.098941877662281598e-10,0.000000000000000000e+00 +7.901712631531158593e+01,4.848931933680627822e+02,2.171945905287138434e-02,7.865492761539934818e+00,3.793309042214854359e-03,1.000000009957898284e+00,-4.000000000000000327e-05,-2.363001284947048492e-10,0.000000000000000000e+00 +7.901839769147366610e+01,4.849031932961169105e+02,2.175739205232250090e-02,7.866764137714670646e+00,3.793163056813316641e-03,1.000000009957597857e+00,-4.000000000000000327e-05,-3.186113103834999497e-10,0.000000000000000000e+00 +7.901966886216405328e+01,4.849131932241765526e+02,2.179532359193010749e-02,7.868035308417709039e+00,3.793017071411778924e-03,1.000000009957192848e+00,-4.000000000000000327e-05,4.572042389600992432e-10,0.000000000000000000e+00 +7.902093982748233714e+01,4.849231931522417653e+02,2.183325367169420064e-02,7.869306273748644109e+00,3.792871086010241206e-03,1.000000009957773939e+00,-4.000000000000000327e-05,-1.645991456438449961e-10,0.000000000000000000e+00 +7.902221058752803629e+01,4.849331930803124919e+02,2.187118229161477689e-02,7.870577033806990919e+00,3.792725100608703489e-03,1.000000009957564773e+00,-4.000000000000000327e-05,-4.071952661448616923e-11,0.000000000000000000e+00 +7.902348114240056987e+01,4.849431930083887323e+02,2.190910945169183971e-02,7.871847588692181930e+00,3.792579115207165771e-03,1.000000009957513036e+00,-4.000000000000000327e-05,2.228574142023050228e-10,0.000000000000000000e+00 +7.902475149219931438e+01,4.849531929364705434e+02,2.194703515192538562e-02,7.873117938503570556e+00,3.792433129805628054e-03,1.000000009957796143e+00,-4.000000000000000327e-05,-5.307484687588202065e-10,0.000000000000000000e+00 +7.902602163702353266e+01,4.849631928645578682e+02,2.198495939231541463e-02,7.874388083340430278e+00,3.792287144404090336e-03,1.000000009957122016e+00,-4.000000000000000327e-05,3.948034852859259243e-10,0.000000000000000000e+00 +7.902729157697241646e+01,4.849731927926507637e+02,2.202288217286192673e-02,7.875658023301952859e+00,3.792141159002552619e-03,1.000000009957623393e+00,-4.000000000000000327e-05,1.909632132745138892e-10,0.000000000000000000e+00 +7.902856131214507229e+01,4.849831927207491731e+02,2.206080349356491846e-02,7.876927758487252795e+00,3.791995173601014901e-03,1.000000009957865865e+00,-4.000000000000000327e-05,-6.485400689475613744e-10,0.000000000000000000e+00 +7.902983084264053559e+01,4.849931926488530962e+02,2.209872335442439328e-02,7.878197288995362868e+00,3.791849188199477184e-03,1.000000009957042524e+00,-4.000000000000000327e-05,5.762231107808874499e-10,0.000000000000000000e+00 +7.903110016855777076e+01,4.850031925769625900e+02,2.213664175544034773e-02,7.879466614925235035e+00,3.791703202797939466e-03,1.000000009957773939e+00,-4.000000000000000327e-05,-5.997604980648430713e-10,0.000000000000000000e+00 +7.903236928999564270e+01,4.850131925050775976e+02,2.217455869661278181e-02,7.880735736375744871e+00,3.791557217396401749e-03,1.000000009957012770e+00,-4.000000000000000327e-05,7.298728012288975131e-10,0.000000000000000000e+00 +7.903363820705294529e+01,4.850231924331981759e+02,2.221247417794169204e-02,7.882004653445684461e+00,3.791411231994864031e-03,1.000000009957938918e+00,-4.000000000000000327e-05,-4.546906870939590821e-10,0.000000000000000000e+00 +7.903490691982840133e+01,4.850331923613242679e+02,2.225038819942708190e-02,7.883273366233770396e+00,3.791265246593326314e-03,1.000000009957362046e+00,-4.000000000000000327e-05,-3.472869627120856046e-10,0.000000000000000000e+00 +7.903617542842063415e+01,4.850431922894558738e+02,2.228830076106894792e-02,7.884541874838635778e+00,3.791119261191788596e-03,1.000000009956921510e+00,-4.000000000000000327e-05,4.453831643400516316e-10,0.000000000000000000e+00 +7.903744373292821024e+01,4.850531922175930504e+02,2.232621186286729009e-02,7.885810179358836436e+00,3.790973275790250879e-03,1.000000009957486391e+00,-4.000000000000000327e-05,2.123964947822691418e-10,0.000000000000000000e+00 +7.903871183344959661e+01,4.850631921457357407e+02,2.236412150482210842e-02,7.887078279892850041e+00,3.790827290388713161e-03,1.000000009957755731e+00,-4.000000000000000327e-05,-5.514790735934878914e-10,0.000000000000000000e+00 +7.903997973008318922e+01,4.850731920738839449e+02,2.240202968693339944e-02,7.888346176539073440e+00,3.790681304987175444e-03,1.000000009957056513e+00,-4.000000000000000327e-05,3.093263278357128891e-10,0.000000000000000000e+00 +7.904124742292731298e+01,4.850831920020377197e+02,2.243993640920116314e-02,7.889613869395823542e+00,3.790535319585637726e-03,1.000000009957448643e+00,-4.000000000000000327e-05,-2.329955438872587492e-11,0.000000000000000000e+00 +7.904251491208020752e+01,4.850931919301970083e+02,2.247784167162539953e-02,7.890881358561340875e+00,3.790389334184100009e-03,1.000000009957419111e+00,-4.000000000000000327e-05,5.379031835680184843e-11,0.000000000000000000e+00 +7.904378219764002722e+01,4.851031918583618108e+02,2.251574547420610861e-02,7.892148644133785140e+00,3.790243348782562291e-03,1.000000009957487279e+00,-4.000000000000000327e-05,-6.215794821238804156e-10,0.000000000000000000e+00 +7.904504927970486960e+01,4.851131917865321839e+02,2.255364781694329038e-02,7.893415726211237882e+00,3.790097363381024573e-03,1.000000009956699687e+00,-4.000000000000000327e-05,6.625169622926581496e-10,0.000000000000000000e+00 +7.904631615837271852e+01,4.851231917147080708e+02,2.259154869983694136e-02,7.894682604891700706e+00,3.789951377979486856e-03,1.000000009957539016e+00,-4.000000000000000327e-05,-2.208744316814735435e-11,0.000000000000000000e+00 +7.904758283374150096e+01,4.851331916428894715e+02,2.262944812288706156e-02,7.895949280273099724e+00,3.789805392577949138e-03,1.000000009957511038e+00,-4.000000000000000327e-05,-5.179109180170445718e-10,0.000000000000000000e+00 +7.904884930590907288e+01,4.851431915710764429e+02,2.266734608609365098e-02,7.897215752453279336e+00,3.789659407176411421e-03,1.000000009956855118e+00,-4.000000000000000327e-05,2.290115602200156077e-10,0.000000000000000000e+00 +7.905011557497319075e+01,4.851531914992689281e+02,2.270524258945670962e-02,7.898482021530005781e+00,3.789513421774873703e-03,1.000000009957145108e+00,-4.000000000000000327e-05,5.017665630457323631e-10,0.000000000000000000e+00 +7.905138164103155418e+01,4.851631914274669271e+02,2.274313763297623400e-02,7.899748087600968915e+00,3.789367436373335986e-03,1.000000009957780378e+00,-4.000000000000000327e-05,-8.624892210814296968e-10,0.000000000000000000e+00 +7.905264750418176334e+01,4.851731913556704967e+02,2.278103121665222414e-02,7.901013950763779548e+00,3.789221450971798268e-03,1.000000009956688585e+00,-4.000000000000000327e-05,5.147343647214014810e-10,0.000000000000000000e+00 +7.905391316452134731e+01,4.851831912838795802e+02,2.281892334048468002e-02,7.902279611115967661e+00,3.789075465570260551e-03,1.000000009957340064e+00,-4.000000000000000327e-05,1.449347965816591767e-10,0.000000000000000000e+00 +7.905517862214776414e+01,4.851931912120941774e+02,2.285681400447360165e-02,7.903545068754989522e+00,3.788929480168722833e-03,1.000000009957523472e+00,-4.000000000000000327e-05,-3.637989671185579924e-10,0.000000000000000000e+00 +7.905644387715840082e+01,4.852031911403143454e+02,2.289470320861898556e-02,7.904810323778220571e+00,3.788783494767185116e-03,1.000000009957063174e+00,-4.000000000000000327e-05,4.300290189109077200e-11,0.000000000000000000e+00 +7.905770892965054486e+01,4.852131910685400271e+02,2.293259095292083174e-02,7.906075376282958089e+00,3.788637509365647398e-03,1.000000009957117575e+00,-4.000000000000000327e-05,2.027604097866578904e-10,0.000000000000000000e+00 +7.905897377972141271e+01,4.852231909967712227e+02,2.297047723737914021e-02,7.907340226366422975e+00,3.788491523964109681e-03,1.000000009957374036e+00,-4.000000000000000327e-05,-4.956573253840893212e-10,0.000000000000000000e+00 +7.906023842746814978e+01,4.852331909250079889e+02,2.300836206199391096e-02,7.908604874125757966e+00,3.788345538562571963e-03,1.000000009956747204e+00,-4.000000000000000327e-05,1.148465231288363779e-10,0.000000000000000000e+00 +7.906150287298783041e+01,4.852431908532502689e+02,2.304624542676514398e-02,7.909869319658026754e+00,3.788199553161034246e-03,1.000000009956892422e+00,-4.000000000000000327e-05,3.147368104101030135e-10,0.000000000000000000e+00 +7.906276711637742949e+01,4.852531907814980627e+02,2.308412733169283582e-02,7.911133563060217533e+00,3.788053567759496528e-03,1.000000009957290326e+00,-4.000000000000000327e-05,4.900982428987622628e-11,0.000000000000000000e+00 +7.906403115773386503e+01,4.852631907097514272e+02,2.312200777677698646e-02,7.912397604429240339e+00,3.787907582357958811e-03,1.000000009957352276e+00,-4.000000000000000327e-05,-1.813126166487982893e-10,0.000000000000000000e+00 +7.906529499715396980e+01,4.852731906380103055e+02,2.315988676201759591e-02,7.913661443861927047e+00,3.787761596956421093e-03,1.000000009957123126e+00,-4.000000000000000327e-05,-4.299833723104859193e-10,0.000000000000000000e+00 +7.906655863473449131e+01,4.852831905662746976e+02,2.319776428741466071e-02,7.914925081455032263e+00,3.787615611554883376e-03,1.000000009956579783e+00,-4.000000000000000327e-05,3.618623343796459107e-10,0.000000000000000000e+00 +7.906782207057210599e+01,4.852931904945446036e+02,2.323564035296818431e-02,7.916188517305233319e+00,3.787469626153345658e-03,1.000000009957036973e+00,-4.000000000000000327e-05,-8.525072716409982765e-11,0.000000000000000000e+00 +7.906908530476343344e+01,4.853031904228200801e+02,2.327351495867816325e-02,7.917451751509132052e+00,3.787323640751807940e-03,1.000000009956929281e+00,-4.000000000000000327e-05,4.003028494944670505e-10,0.000000000000000000e+00 +7.907034833740497959e+01,4.853131903511010705e+02,2.331138810454459753e-02,7.918714784163251252e+00,3.787177655350270223e-03,1.000000009957434877e+00,-4.000000000000000327e-05,-4.613799918483512295e-10,0.000000000000000000e+00 +7.907161116859319350e+01,4.853231902793875747e+02,2.334925979056748369e-02,7.919977615364038215e+00,3.787031669948732505e-03,1.000000009956852232e+00,-4.000000000000000327e-05,5.908856690078493901e-11,0.000000000000000000e+00 +7.907287379842443897e+01,4.853331902076795927e+02,2.338713001674682518e-02,7.921240245207861186e+00,3.786885684547194788e-03,1.000000009956926839e+00,-4.000000000000000327e-05,2.379749298012931183e-10,0.000000000000000000e+00 +7.907413622699502298e+01,4.853431901359771814e+02,2.342499878308261854e-02,7.922502673791013805e+00,3.786739699145657070e-03,1.000000009957227265e+00,-4.000000000000000327e-05,-5.361886079516822185e-10,0.000000000000000000e+00 +7.907539845440115300e+01,4.853531900642802839e+02,2.346286608957486378e-02,7.923764901209712441e+00,3.786593713744119353e-03,1.000000009956550473e+00,-4.000000000000000327e-05,4.701194948005216215e-10,0.000000000000000000e+00 +7.907666048073896548e+01,4.853631899925889002e+02,2.350073193622356088e-02,7.925026927560095302e+00,3.786447728342581635e-03,1.000000009957143776e+00,-4.000000000000000327e-05,-1.418325835359154696e-10,0.000000000000000000e+00 +7.907792230610452577e+01,4.853731899209030303e+02,2.353859632302870639e-02,7.926288752938226878e+00,3.786301742941043918e-03,1.000000009956964808e+00,-4.000000000000000327e-05,-1.953588516681355463e-10,0.000000000000000000e+00 +7.907918393059382822e+01,4.853831898492227310e+02,2.357645924999030029e-02,7.927550377440092610e+00,3.786155757539506200e-03,1.000000009956718339e+00,-4.000000000000000327e-05,2.569993895709673831e-10,0.000000000000000000e+00 +7.908044535430278188e+01,4.853931897775479456e+02,2.361432071710834260e-02,7.928811801161602446e+00,3.786009772137968483e-03,1.000000009957042524e+00,-4.000000000000000327e-05,4.542218700497743557e-11,0.000000000000000000e+00 +7.908170657732721054e+01,4.854031897058786740e+02,2.365218072438283331e-02,7.930073024198590836e+00,3.785863786736430765e-03,1.000000009957099811e+00,-4.000000000000000327e-05,-3.257535373616925351e-10,0.000000000000000000e+00 +7.908296759976288115e+01,4.854131896342149162e+02,2.369003927181377242e-02,7.931334046646814961e+00,3.785717801334893048e-03,1.000000009956689029e+00,-4.000000000000000327e-05,2.078109723201047281e-10,0.000000000000000000e+00 +7.908422842170546119e+01,4.854231895625567290e+02,2.372789635940115646e-02,7.932594868601955618e+00,3.785571815933355330e-03,1.000000009956951041e+00,-4.000000000000000327e-05,-8.313760297929125145e-11,0.000000000000000000e+00 +7.908548904325057549e+01,4.854331894909040557e+02,2.376575198714498544e-02,7.933855490159618995e+00,3.785425830531817613e-03,1.000000009956846236e+00,-4.000000000000000327e-05,-1.342392393577724688e-10,0.000000000000000000e+00 +7.908674946449373522e+01,4.854431894192568961e+02,2.380360615504525934e-02,7.935115911415334011e+00,3.785279845130279895e-03,1.000000009956677038e+00,-4.000000000000000327e-05,1.233364774309183259e-12,0.000000000000000000e+00 +7.908800968553040889e+01,4.854531893476152504e+02,2.384145886310197818e-02,7.936376132464554090e+00,3.785133859728742178e-03,1.000000009956678593e+00,-4.000000000000000327e-05,2.710308975413352084e-10,0.000000000000000000e+00 +7.908926970645596555e+01,4.854631892759791185e+02,2.387931011131513848e-02,7.937636153402657158e+00,3.784987874327204460e-03,1.000000009957020097e+00,-4.000000000000000327e-05,-4.975563707944208969e-10,0.000000000000000000e+00 +7.909052952736570319e+01,4.854731892043485573e+02,2.391715989968474024e-02,7.938895974324945648e+00,3.784841888925666743e-03,1.000000009956393265e+00,-4.000000000000000327e-05,4.408735339419920303e-10,0.000000000000000000e+00 +7.909178914835486296e+01,4.854831891327235098e+02,2.395500822821078346e-02,7.940155595326644722e+00,3.784695903524129025e-03,1.000000009956948599e+00,-4.000000000000000327e-05,-3.247572567886365204e-10,0.000000000000000000e+00 +7.909304856951858653e+01,4.854931890611039762e+02,2.399285509689326815e-02,7.941415016502906710e+00,3.784549918122591308e-03,1.000000009956539593e+00,-4.000000000000000327e-05,5.119000288746442371e-10,0.000000000000000000e+00 +7.909430779095194453e+01,4.855031889894899564e+02,2.403070050573219082e-02,7.942674237948805782e+00,3.784403932721053590e-03,1.000000009957184188e+00,-4.000000000000000327e-05,-4.624232519545971235e-10,0.000000000000000000e+00 +7.909556681274995071e+01,4.855131889178814504e+02,2.406854445472755497e-02,7.943933259759343279e+00,3.784257947319515872e-03,1.000000009956601987e+00,-4.000000000000000327e-05,6.085480951638573969e-11,0.000000000000000000e+00 +7.909682563500751940e+01,4.855231888462785150e+02,2.410638694387935710e-02,7.945192082029442382e+00,3.784111961917978155e-03,1.000000009956678593e+00,-4.000000000000000327e-05,-2.118788631326165094e-10,0.000000000000000000e+00 +7.909808425781949381e+01,4.855331887746810935e+02,2.414422797318759376e-02,7.946450704853953440e+00,3.783965976516440437e-03,1.000000009956411917e+00,-4.000000000000000327e-05,3.483056885440861670e-10,0.000000000000000000e+00 +7.909934268128066037e+01,4.855431887030891858e+02,2.418206754265226840e-02,7.947709128327650419e+00,3.783819991114902720e-03,1.000000009956850233e+00,-4.000000000000000327e-05,6.706034547142597120e-12,0.000000000000000000e+00 +7.910060090548572020e+01,4.855531886315027918e+02,2.421990565227337758e-02,7.948967352545233567e+00,3.783674005713365002e-03,1.000000009956858671e+00,-4.000000000000000327e-05,-1.676774049589984447e-10,0.000000000000000000e+00 +7.910185893052928918e+01,4.855631885599219117e+02,2.425774230205092127e-02,7.950225377601326748e+00,3.783528020311827285e-03,1.000000009956647729e+00,-4.000000000000000327e-05,-2.271947088455330069e-10,0.000000000000000000e+00 +7.910311675650591212e+01,4.855731884883466023e+02,2.429557749198489949e-02,7.951483203590479221e+00,3.783382034910289567e-03,1.000000009956361957e+00,-4.000000000000000327e-05,3.379327673618743452e-10,0.000000000000000000e+00 +7.910437438351007700e+01,4.855831884167768067e+02,2.433341122207531224e-02,7.952740830607165634e+00,3.783236049508751850e-03,1.000000009956786950e+00,-4.000000000000000327e-05,-2.097845476614360222e-10,0.000000000000000000e+00 +7.910563181163617230e+01,4.855931883452125248e+02,2.437124349232215603e-02,7.953998258745786920e+00,3.783090064107214132e-03,1.000000009956523161e+00,-4.000000000000000327e-05,-2.377227671662003166e-10,0.000000000000000000e+00 +7.910688904097852969e+01,4.856031882736537568e+02,2.440907430272543088e-02,7.955255488100667627e+00,3.782944078705676415e-03,1.000000009956224289e+00,-4.000000000000000327e-05,2.029618374661016801e-10,0.000000000000000000e+00 +7.910814607163140977e+01,4.856131882021005026e+02,2.444690365328513679e-02,7.956512518766058584e+00,3.782798093304138697e-03,1.000000009956479419e+00,-4.000000000000000327e-05,4.976795812209109042e-10,0.000000000000000000e+00 +7.910940290368897365e+01,4.856231881305527622e+02,2.448473154400127375e-02,7.957769350836136901e+00,3.782652107902600980e-03,1.000000009957104918e+00,-4.000000000000000327e-05,-5.304473214275980531e-10,0.000000000000000000e+00 +7.911065953724532562e+01,4.856331880590105357e+02,2.452255797487383829e-02,7.959025984405005083e+00,3.782506122501063262e-03,1.000000009956438340e+00,-4.000000000000000327e-05,-1.217641299623439412e-10,0.000000000000000000e+00 +7.911191597239449891e+01,4.856431879874738797e+02,2.456038294590283388e-02,7.960282419566689249e+00,3.782360137099525545e-03,1.000000009956285352e+00,-4.000000000000000327e-05,-1.467056344903816991e-11,0.000000000000000000e+00 +7.911317220923044147e+01,4.856531879159427376e+02,2.459820645708825707e-02,7.961538656415143578e+00,3.782214151697987827e-03,1.000000009956266922e+00,-4.000000000000000327e-05,3.010591849567088112e-10,0.000000000000000000e+00 +7.911442824784704442e+01,4.856631878444171093e+02,2.463602850843010436e-02,7.962794695044247639e+00,3.782068166296450110e-03,1.000000009956645064e+00,-4.000000000000000327e-05,-3.523814535105348474e-10,0.000000000000000000e+00 +7.911568408833809940e+01,4.856731877728969948e+02,2.467384909992837924e-02,7.964050535547807286e+00,3.781922180894912392e-03,1.000000009956202529e+00,-4.000000000000000327e-05,2.258214178739625996e-10,0.000000000000000000e+00 +7.911693973079734121e+01,4.856831877013823942e+02,2.471166823158307824e-02,7.965306178019552874e+00,3.781776195493374675e-03,1.000000009956486080e+00,-4.000000000000000327e-05,2.944807683569762343e-10,0.000000000000000000e+00 +7.911819517531843360e+01,4.856931876298733073e+02,2.474948590339420135e-02,7.966561622553142819e+00,3.781630210091836957e-03,1.000000009956855784e+00,-4.000000000000000327e-05,-1.984741735517797836e-10,0.000000000000000000e+00 +7.911945042199495504e+01,4.857031875583697342e+02,2.478730211536174857e-02,7.967816869242160926e+00,3.781484224690299240e-03,1.000000009956606650e+00,-4.000000000000000327e-05,-1.776287591841258798e-10,0.000000000000000000e+00 +7.912070547092041295e+01,4.857131874868717318e+02,2.482511686748571991e-02,7.969071918180116398e+00,3.781338239288761522e-03,1.000000009956383717e+00,-4.000000000000000327e-05,-2.579915582658156662e-10,0.000000000000000000e+00 +7.912196032218824371e+01,4.857231874153792432e+02,2.486293015976611190e-02,7.970326769460445604e+00,3.781192253887223804e-03,1.000000009956059976e+00,-4.000000000000000327e-05,7.291444401630772678e-11,0.000000000000000000e+00 +7.912321497589181263e+01,4.857331873438922685e+02,2.490074199220292453e-02,7.971581423176511194e+00,3.781046268485686087e-03,1.000000009956151459e+00,-4.000000000000000327e-05,2.000152711942750395e-10,0.000000000000000000e+00 +7.912446943212441397e+01,4.857431872724108075e+02,2.493855236479615781e-02,7.972835879421602989e+00,3.780900283084148369e-03,1.000000009956402369e+00,-4.000000000000000327e-05,7.187520283491834200e-11,0.000000000000000000e+00 +7.912572369097925673e+01,4.857531872009348604e+02,2.497636127754581173e-02,7.974090138288937091e+00,3.780754297682610652e-03,1.000000009956492519e+00,-4.000000000000000327e-05,2.009635193136004220e-10,0.000000000000000000e+00 +7.912697775254949306e+01,4.857631871294644270e+02,2.501416873045188283e-02,7.975344199871655881e+00,3.780608312281072934e-03,1.000000009956744540e+00,-4.000000000000000327e-05,-5.934226091357501659e-10,0.000000000000000000e+00 +7.912823161692817564e+01,4.857731870579995075e+02,2.505197472351437110e-02,7.976598064262828913e+00,3.780462326879535217e-03,1.000000009956000468e+00,-4.000000000000000327e-05,4.629813719066574022e-10,0.000000000000000000e+00 +7.912948528420831451e+01,4.857831869865401018e+02,2.508977925673327655e-02,7.977851731555451131e+00,3.780316341477997499e-03,1.000000009956580893e+00,-4.000000000000000327e-05,-6.371865852373694403e-10,0.000000000000000000e+00 +7.913073875448283445e+01,4.857931869150862099e+02,2.512758233010859918e-02,7.979105201842447315e+00,3.780170356076459782e-03,1.000000009955782199e+00,-4.000000000000000327e-05,5.772254840242284147e-10,0.000000000000000000e+00 +7.913199202784457498e+01,4.858031868436378318e+02,2.516538394364033551e-02,7.980358475216665859e+00,3.780024370674922064e-03,1.000000009956505620e+00,-4.000000000000000327e-05,-4.683384224878939135e-10,0.000000000000000000e+00 +7.913324510438631876e+01,4.858131867721949675e+02,2.520318409732848902e-02,7.981611551770885882e+00,3.779878385273384347e-03,1.000000009955918756e+00,-4.000000000000000327e-05,7.005798266879261674e-10,0.000000000000000000e+00 +7.913449798420076320e+01,4.858231867007576739e+02,2.524098279117305624e-02,7.982864431597810118e+00,3.779732399871846629e-03,1.000000009956796498e+00,-4.000000000000000327e-05,-4.940102365150322106e-10,0.000000000000000000e+00 +7.913575066738054886e+01,4.858331866293258940e+02,2.527878002517403716e-02,7.984117114790072023e+00,3.779586414470308912e-03,1.000000009956177660e+00,-4.000000000000000327e-05,-1.411172783821278894e-10,0.000000000000000000e+00 +7.913700315401823104e+01,4.858431865578996280e+02,2.531657579933142832e-02,7.985369601440228671e+00,3.779440429068771194e-03,1.000000009956000913e+00,-4.000000000000000327e-05,1.010671695849325731e-11,0.000000000000000000e+00 +7.913825544420630820e+01,4.858531864864788758e+02,2.535437011364522972e-02,7.986621891640766968e+00,3.779294443667233477e-03,1.000000009956013569e+00,-4.000000000000000327e-05,4.761542222521221944e-10,0.000000000000000000e+00 +7.913950753803717930e+01,4.858631864150636375e+02,2.539216296811544482e-02,7.987873985484100992e+00,3.779148458265695759e-03,1.000000009956609759e+00,-4.000000000000000327e-05,-4.943202469030836412e-10,0.000000000000000000e+00 +7.914075943560318649e+01,4.858731863436539129e+02,2.542995436274206669e-02,7.989125883062572875e+00,3.779002472864158042e-03,1.000000009955990921e+00,-4.000000000000000327e-05,-1.184993456667848451e-10,0.000000000000000000e+00 +7.914201113699660084e+01,4.858831862722497021e+02,2.546774429752509880e-02,7.990377584468450145e+00,3.778856487462620324e-03,1.000000009955842595e+00,-4.000000000000000327e-05,4.203127734215996234e-10,0.000000000000000000e+00 +7.914326264230962238e+01,4.858931862008510052e+02,2.550553277246453768e-02,7.991629089793930163e+00,3.778710502061082607e-03,1.000000009956368618e+00,-4.000000000000000327e-05,-6.317213321264423475e-11,0.000000000000000000e+00 +7.914451395163436587e+01,4.859031861294578221e+02,2.554331978756038679e-02,7.992880399131138347e+00,3.778564516659544889e-03,1.000000009956289571e+00,-4.000000000000000327e-05,-4.854012279148203624e-10,0.000000000000000000e+00 +7.914576506506290343e+01,4.859131860580701527e+02,2.558110534281264267e-02,7.994131512572126397e+00,3.778418531258007172e-03,1.000000009955682279e+00,-4.000000000000000327e-05,8.060519185135733912e-10,0.000000000000000000e+00 +7.914701598268719351e+01,4.859231859866879972e+02,2.561888943822130185e-02,7.995382430208874069e+00,3.778272545856469454e-03,1.000000009956690583e+00,-4.000000000000000327e-05,-7.793705429607767781e-10,0.000000000000000000e+00 +7.914826670459915192e+01,4.859331859153113555e+02,2.565667207378636780e-02,7.996633152133291844e+00,3.778126560454931736e-03,1.000000009955715807e+00,-4.000000000000000327e-05,3.844194024076002838e-10,0.000000000000000000e+00 +7.914951723089062341e+01,4.859431858439402276e+02,2.569445324950783704e-02,7.997883678437213817e+00,3.777980575053394019e-03,1.000000009956196534e+00,-4.000000000000000327e-05,-2.956851724488887076e-10,0.000000000000000000e+00 +7.915076756165336747e+01,4.859531857725746136e+02,2.573223296538570959e-02,7.999134009212406582e+00,3.777834589651856301e-03,1.000000009955826830e+00,-4.000000000000000327e-05,5.392435576283298009e-10,0.000000000000000000e+00 +7.915201769697907253e+01,4.859631857012145133e+02,2.577001122141998543e-02,8.000384144550562127e+00,3.777688604250318584e-03,1.000000009956500957e+00,-4.000000000000000327e-05,-5.711261469250063082e-10,0.000000000000000000e+00 +7.915326763695937018e+01,4.859731856298599268e+02,2.580778801761066110e-02,8.001634084543303160e+00,3.777542618848780866e-03,1.000000009955787084e+00,-4.000000000000000327e-05,-2.668632957943737429e-10,0.000000000000000000e+00 +7.915451738168580675e+01,4.859831855585108542e+02,2.584556335395774007e-02,8.002883829282177786e+00,3.777396633447243149e-03,1.000000009955453573e+00,-4.000000000000000327e-05,2.660164775666422213e-10,0.000000000000000000e+00 +7.915576693124985752e+01,4.859931854871672954e+02,2.588333723046121887e-02,8.004133378858664827e+00,3.777250648045705431e-03,1.000000009955785973e+00,-4.000000000000000327e-05,9.780342310219231307e-10,0.000000000000000000e+00 +7.915701628574292670e+01,4.860031854158292504e+02,2.592110964712109750e-02,8.005382733364172054e+00,3.777104662644167714e-03,1.000000009957007885e+00,-4.000000000000000327e-05,-1.596419492785186561e-09,0.000000000000000000e+00 +7.915826544525634745e+01,4.860131853444967192e+02,2.595888060393737248e-02,8.006631892890036184e+00,3.776958677242629996e-03,1.000000009955013702e+00,-4.000000000000000327e-05,1.599690908010144043e-09,0.000000000000000000e+00 +7.915951440988139609e+01,4.860231852731697018e+02,2.599665010091004730e-02,8.007880857527517549e+00,3.776812691841092279e-03,1.000000009957011660e+00,-4.000000000000000327e-05,-8.684273324491708125e-10,0.000000000000000000e+00 +7.916076317970926368e+01,4.860331852018481982e+02,2.603441813803911847e-02,8.009129627367814308e+00,3.776666706439554561e-03,1.000000009955927194e+00,-4.000000000000000327e-05,-1.080723971325397152e-09,0.000000000000000000e+00 +7.916201175483107022e+01,4.860431851305322084e+02,2.607218471532458601e-02,8.010378202502044687e+00,3.776520721038016844e-03,1.000000009954577829e+00,-4.000000000000000327e-05,2.056666018724476479e-09,0.000000000000000000e+00 +7.916326013533786465e+01,4.860531850592217324e+02,2.610994983276644643e-02,8.011626583021259407e+00,3.776374735636479126e-03,1.000000009957145330e+00,-4.000000000000000327e-05,-1.765774314834023609e-09,0.000000000000000000e+00 +7.916450832132062487e+01,4.860631849879167703e+02,2.614771349036470321e-02,8.012874769016443466e+00,3.776228750234941409e-03,1.000000009954941316e+00,-4.000000000000000327e-05,1.082652700145404715e-09,0.000000000000000000e+00 +7.916575631287025772e+01,4.860731849166173220e+02,2.618547568811935289e-02,8.014122760578500149e+00,3.776082764833403691e-03,1.000000009956292457e+00,-4.000000000000000327e-05,-8.500636733917653561e-10,0.000000000000000000e+00 +7.916700411007761318e+01,4.860831848453233874e+02,2.622323642603039545e-02,8.015370557798272344e+00,3.775936779431865974e-03,1.000000009955231750e+00,-4.000000000000000327e-05,3.703700930563648156e-10,0.000000000000000000e+00 +7.916825171303344177e+01,4.860931847740349667e+02,2.626099570409783091e-02,8.016618160766524781e+00,3.775790794030328256e-03,1.000000009955693825e+00,-4.000000000000000327e-05,1.317234641133253156e-10,0.000000000000000000e+00 +7.916949912182845139e+01,4.861031847027520598e+02,2.629875352232165578e-02,8.017865569573956464e+00,3.775644808628790539e-03,1.000000009955858138e+00,-4.000000000000000327e-05,6.669092927596773552e-10,0.000000000000000000e+00 +7.917074633655326465e+01,4.861131846314746667e+02,2.633650988070187354e-02,8.019112784311193565e+00,3.775498823227252821e-03,1.000000009956689917e+00,-4.000000000000000327e-05,-1.499978054987083104e-09,0.000000000000000000e+00 +7.917199335729844734e+01,4.861231845602027875e+02,2.637426477923848073e-02,8.020359805068792980e+00,3.775352837825715104e-03,1.000000009954819413e+00,-4.000000000000000327e-05,1.578213750630822440e-09,0.000000000000000000e+00 +7.917324018415447995e+01,4.861331844889364220e+02,2.641201821793147733e-02,8.021606631937236997e+00,3.775206852424177386e-03,1.000000009956787173e+00,-4.000000000000000327e-05,-1.573293748167206413e-09,0.000000000000000000e+00 +7.917448681721177195e+01,4.861431844176755703e+02,2.644977019678085989e-02,8.022853265006945733e+00,3.775060867022639668e-03,1.000000009954825853e+00,-4.000000000000000327e-05,1.568015815824688937e-09,0.000000000000000000e+00 +7.917573325656067595e+01,4.861531843464202325e+02,2.648752071578663186e-02,8.024099704368259367e+00,3.774914881621101951e-03,1.000000009956780289e+00,-4.000000000000000327e-05,-1.622245178373682360e-09,0.000000000000000000e+00 +7.917697950229145931e+01,4.861631842751704085e+02,2.652526977494878979e-02,8.025345950111457682e+00,3.774768896219564233e-03,1.000000009954758573e+00,-4.000000000000000327e-05,1.385849556312752702e-09,0.000000000000000000e+00 +7.917822555449433253e+01,4.861731842039260982e+02,2.656301737426733367e-02,8.026592002326740527e+00,3.774622910818026516e-03,1.000000009956485414e+00,-4.000000000000000327e-05,-8.955863786506562593e-10,0.000000000000000000e+00 +7.917947141325943505e+01,4.861831841326873018e+02,2.660076351374226003e-02,8.027837861104247352e+00,3.774476925416488798e-03,1.000000009955369640e+00,-4.000000000000000327e-05,6.381486348850541889e-10,0.000000000000000000e+00 +7.918071707867682107e+01,4.861931840614540192e+02,2.663850819337357234e-02,8.029083526534039450e+00,3.774330940014951081e-03,1.000000009956164559e+00,-4.000000000000000327e-05,-9.290247295183656527e-10,0.000000000000000000e+00 +7.918196255083650215e+01,4.862031839902262504e+02,2.667625141316126713e-02,8.030328998706114163e+00,3.774184954613413363e-03,1.000000009955007485e+00,-4.000000000000000327e-05,7.827770499417816070e-11,0.000000000000000000e+00 +7.918320782982839035e+01,4.862131839190039955e+02,2.671399317310534441e-02,8.031574277710394227e+00,3.774038969211875646e-03,1.000000009955104963e+00,-4.000000000000000327e-05,1.322367177297114045e-09,0.000000000000000000e+00 +7.918445291574234091e+01,4.862231838477872543e+02,2.675173347320580416e-02,8.032819363636736654e+00,3.773892983810337928e-03,1.000000009956751423e+00,-4.000000000000000327e-05,-1.830375680126121499e-09,0.000000000000000000e+00 +7.918569780866813801e+01,4.862331837765759701e+02,2.678947231346264293e-02,8.034064256574929175e+00,3.773746998408800211e-03,1.000000009954472802e+00,-4.000000000000000327e-05,8.857165897134705570e-10,0.000000000000000000e+00 +7.918694250869549478e+01,4.862431837053701997e+02,2.682720969387586418e-02,8.035308956614683140e+00,3.773601013007262493e-03,1.000000009955575253e+00,-4.000000000000000327e-05,2.538912334873509540e-10,0.000000000000000000e+00 +7.918818701591406750e+01,4.862531836341699432e+02,2.686494561444546444e-02,8.036553463845649503e+00,3.773455027605724776e-03,1.000000009955891223e+00,-4.000000000000000327e-05,-3.376223557082439978e-10,0.000000000000000000e+00 +7.918943133041344140e+01,4.862631835629752004e+02,2.690268007517144372e-02,8.037797778357404610e+00,3.773309042204187058e-03,1.000000009955471114e+00,-4.000000000000000327e-05,2.113143564480594386e-10,0.000000000000000000e+00 +7.919067545228310223e+01,4.862731834917859715e+02,2.694041307605379854e-02,8.039041900239455529e+00,3.773163056802649341e-03,1.000000009955734015e+00,-4.000000000000000327e-05,-4.432219266779961422e-10,0.000000000000000000e+00 +7.919191938161250732e+01,4.862831834206022563e+02,2.697814461709253236e-02,8.040285829581241828e+00,3.773017071401111623e-03,1.000000009955182678e+00,-4.000000000000000327e-05,1.095104302321100023e-09,0.000000000000000000e+00 +7.919316311849101453e+01,4.862931833494240550e+02,2.701587469828764174e-02,8.041529566472132018e+00,3.772871085999573906e-03,1.000000009956544700e+00,-4.000000000000000327e-05,-9.647479314900160347e-10,0.000000000000000000e+00 +7.919440666300792486e+01,4.863031832782513675e+02,2.705360331963912665e-02,8.042773111001428887e+00,3.772725100598036188e-03,1.000000009955344993e+00,-4.000000000000000327e-05,2.207316011126395719e-10,0.000000000000000000e+00 +7.919565001525248249e+01,4.863131832070841938e+02,2.709133048114698364e-02,8.044016463258360616e+00,3.772579115196498471e-03,1.000000009955619440e+00,-4.000000000000000327e-05,8.394813150694855193e-12,0.000000000000000000e+00 +7.919689317531383210e+01,4.863231831359225339e+02,2.712905618281121617e-02,8.045259623332091437e+00,3.772433129794960753e-03,1.000000009955629876e+00,-4.000000000000000327e-05,-5.012656623797316919e-10,0.000000000000000000e+00 +7.919813614328107576e+01,4.863331830647663878e+02,2.716678042463182077e-02,8.046502591311714525e+00,3.772287144393423036e-03,1.000000009955006819e+00,-4.000000000000000327e-05,-2.072551687142618440e-10,0.000000000000000000e+00 +7.919937891924324447e+01,4.863431829936156987e+02,2.720450320660879745e-02,8.047745367286253781e+00,3.772141158991885318e-03,1.000000009954749247e+00,-4.000000000000000327e-05,8.438017756590296514e-10,0.000000000000000000e+00 +7.920062150328928396e+01,4.863531829224705234e+02,2.724222452874214620e-02,8.048987951344665603e+00,3.771995173590347600e-03,1.000000009955797742e+00,-4.000000000000000327e-05,3.027574988396311671e-10,0.000000000000000000e+00 +7.920186389550808315e+01,4.863631828513308619e+02,2.727994439103186355e-02,8.050230343575838887e+00,3.771849188188809883e-03,1.000000009956173885e+00,-4.000000000000000327e-05,-7.291254171858573289e-10,0.000000000000000000e+00 +7.920310609598847407e+01,4.863731827801967142e+02,2.731766279347794951e-02,8.051472544068591475e+00,3.771703202787272165e-03,1.000000009955268165e+00,-4.000000000000000327e-05,3.039236268191159878e-12,0.000000000000000000e+00 +7.920434810481918930e+01,4.863831827090680804e+02,2.735537973608040407e-02,8.052714552911671930e+00,3.771557217385734448e-03,1.000000009955271940e+00,-4.000000000000000327e-05,1.493031620931894122e-10,0.000000000000000000e+00 +7.920558992208891880e+01,4.863931826379449603e+02,2.739309521883922724e-02,8.053956370193763092e+00,3.771411231984196730e-03,1.000000009955457347e+00,-4.000000000000000327e-05,-3.387111339214096293e-10,0.000000000000000000e+00 +7.920683154788626723e+01,4.864031825668273541e+02,2.743080924175441901e-02,8.055197996003478522e+00,3.771265246582659013e-03,1.000000009955036795e+00,-4.000000000000000327e-05,-3.571860673461145673e-10,0.000000000000000000e+00 +7.920807298229979665e+01,4.864131824957152048e+02,2.746852180482597591e-02,8.056439430429362503e+00,3.771119261181121295e-03,1.000000009954593372e+00,-4.000000000000000327e-05,1.199986681117874220e-09,0.000000000000000000e+00 +7.920931422541796962e+01,4.864231824246085694e+02,2.750623290805389795e-02,8.057680673559891815e+00,3.770973275779583578e-03,1.000000009956082847e+00,-4.000000000000000327e-05,-3.265225252235115985e-10,0.000000000000000000e+00 +7.921055527732920609e+01,4.864331823535074477e+02,2.754394255143818512e-02,8.058921725483477516e+00,3.770827290378045860e-03,1.000000009955677616e+00,-4.000000000000000327e-05,-3.734561469200596638e-10,0.000000000000000000e+00 +7.921179613812182652e+01,4.864431822824118399e+02,2.758165073497883743e-02,8.060162586288457831e+00,3.770681304976508143e-03,1.000000009955214209e+00,-4.000000000000000327e-05,-1.403137043809488260e-10,0.000000000000000000e+00 +7.921303680788412294e+01,4.864531822113217459e+02,2.761935745867585140e-02,8.061403256063105260e+00,3.770535319574970425e-03,1.000000009955040126e+00,-4.000000000000000327e-05,3.252413830760284285e-10,0.000000000000000000e+00 +7.921427728670428792e+01,4.864631821402371656e+02,2.765706272252922704e-02,8.062643734895624803e+00,3.770389334173432708e-03,1.000000009955443581e+00,-4.000000000000000327e-05,-1.783105476595112979e-10,0.000000000000000000e+00 +7.921551757467047139e+01,4.864731820691580992e+02,2.769476652653896434e-02,8.063884022874153956e+00,3.770243348771894990e-03,1.000000009955222424e+00,-4.000000000000000327e-05,-5.448619129567966462e-10,0.000000000000000000e+00 +7.921675767187073802e+01,4.864831819980844898e+02,2.773246887070506331e-02,8.065124120086760939e+00,3.770097363370357273e-03,1.000000009954546742e+00,-4.000000000000000327e-05,3.341665079777266321e-10,0.000000000000000000e+00 +7.921799757839308143e+01,4.864931819270163942e+02,2.777016975502752394e-02,8.066364026621446470e+00,3.769951377968819555e-03,1.000000009954961078e+00,-4.000000000000000327e-05,1.010176233998571128e-10,0.000000000000000000e+00 +7.921923729432543837e+01,4.865031818559538124e+02,2.780786917950634277e-02,8.067603742566145542e+00,3.769805392567281838e-03,1.000000009955086311e+00,-4.000000000000000327e-05,-1.366813696796580122e-10,0.000000000000000000e+00 +7.922047681975567457e+01,4.865131817848967444e+02,2.784556714414151979e-02,8.068843268008723868e+00,3.769659407165744120e-03,1.000000009954916891e+00,-4.000000000000000327e-05,7.306320625608447431e-10,0.000000000000000000e+00 +7.922171615477159889e+01,4.865231817138451902e+02,2.788326364893305501e-02,8.070082603036979663e+00,3.769513421764206403e-03,1.000000009955822389e+00,-4.000000000000000327e-05,-8.144268688515381610e-10,0.000000000000000000e+00 +7.922295529946093495e+01,4.865331816427990930e+02,2.792095869388094495e-02,8.071321747738645414e+00,3.769367436362668685e-03,1.000000009954813196e+00,-4.000000000000000327e-05,9.656338301592585359e-10,0.000000000000000000e+00 +7.922419425391133530e+01,4.865431815717585096e+02,2.795865227898519309e-02,8.072560702201382554e+00,3.769221450961130968e-03,1.000000009956009572e+00,-4.000000000000000327e-05,-9.193571202457316919e-10,0.000000000000000000e+00 +7.922543301821040984e+01,4.865531815007234400e+02,2.799634440424579596e-02,8.073799466512790346e+00,3.769075465559593250e-03,1.000000009954870706e+00,-4.000000000000000327e-05,-7.300051991263618896e-10,0.000000000000000000e+00 +7.922667159244568325e+01,4.865631814296938842e+02,2.803403506966275355e-02,8.075038040760395219e+00,3.768929480158055532e-03,1.000000009953966540e+00,-4.000000000000000327e-05,1.489281275336558950e-09,0.000000000000000000e+00 +7.922790997670462332e+01,4.865731813586698422e+02,2.807172427523606240e-02,8.076276425031659656e+00,3.768783494756517815e-03,1.000000009955810842e+00,-4.000000000000000327e-05,-1.259071442219978312e-09,0.000000000000000000e+00 +7.922914817107461261e+01,4.865831812876512572e+02,2.810941202096572597e-02,8.077514619413982189e+00,3.768637509354980097e-03,1.000000009954251867e+00,-4.000000000000000327e-05,1.404543525587851286e-09,0.000000000000000000e+00 +7.923038617564299102e+01,4.865931812166381860e+02,2.814709830685174080e-02,8.078752623994686743e+00,3.768491523953442380e-03,1.000000009955990699e+00,-4.000000000000000327e-05,-9.959418749354244434e-10,0.000000000000000000e+00 +7.923162399049701321e+01,4.866031811456306286e+02,2.818478313289410689e-02,8.079990438861038626e+00,3.768345538551904662e-03,1.000000009954757907e+00,-4.000000000000000327e-05,-3.939883753409665887e-10,0.000000000000000000e+00 +7.923286161572387698e+01,4.866131810746285851e+02,2.822246649909282423e-02,8.081228064100228536e+00,3.768199553150366945e-03,1.000000009954270297e+00,-4.000000000000000327e-05,8.465946611840831419e-10,0.000000000000000000e+00 +7.923409905141070908e+01,4.866231810036320553e+02,2.826014840544788936e-02,8.082465499799385000e+00,3.768053567748829227e-03,1.000000009955317903e+00,-4.000000000000000327e-05,3.587541049587577181e-10,0.000000000000000000e+00 +7.923533629764457942e+01,4.866331809326409825e+02,2.829782885195930228e-02,8.083702746045570819e+00,3.767907582347291510e-03,1.000000009955761771e+00,-4.000000000000000327e-05,-7.454396545442610944e-10,0.000000000000000000e+00 +7.923657335451247263e+01,4.866431808616554235e+02,2.833550783862706299e-02,8.084939802925779517e+00,3.767761596945753792e-03,1.000000009954839619e+00,-4.000000000000000327e-05,-1.906520734775080870e-10,0.000000000000000000e+00 +7.923781022210131653e+01,4.866531807906753784e+02,2.837318536545117148e-02,8.086176670526937116e+00,3.767615611544216075e-03,1.000000009954603808e+00,-4.000000000000000327e-05,8.173079147741594895e-10,0.000000000000000000e+00 +7.923904690049796784e+01,4.866631807197008470e+02,2.841086143243162776e-02,8.087413348935905688e+00,3.767469626142678357e-03,1.000000009955614555e+00,-4.000000000000000327e-05,-1.254163324947840435e-09,0.000000000000000000e+00 +7.924028338978924069e+01,4.866731806487317726e+02,2.844853603956842836e-02,8.088649838239481582e+00,3.767323640741140640e-03,1.000000009954063795e+00,-4.000000000000000327e-05,5.192354697836152813e-10,0.000000000000000000e+00 +7.924151969006184970e+01,4.866831805777682121e+02,2.848620918686157327e-02,8.089886138524390091e+00,3.767177655339602922e-03,1.000000009954705726e+00,-4.000000000000000327e-05,2.822011762853419226e-10,0.000000000000000000e+00 +7.924275580140245268e+01,4.866931805068101653e+02,2.852388087431106251e-02,8.091122249877296113e+00,3.767031669938065205e-03,1.000000009955054558e+00,-4.000000000000000327e-05,3.122473495384246002e-10,0.000000000000000000e+00 +7.924399172389765056e+01,4.867031804358576323e+02,2.856155110191689606e-02,8.092358172384795267e+00,3.766885684536527487e-03,1.000000009955440472e+00,-4.000000000000000327e-05,-6.006917934238658185e-10,0.000000000000000000e+00 +7.924522745763397324e+01,4.867131803649105564e+02,2.859921986967907045e-02,8.093593906133417448e+00,3.766739699134989770e-03,1.000000009954698177e+00,-4.000000000000000327e-05,-1.754007528639570668e-10,0.000000000000000000e+00 +7.924646300269787957e+01,4.867231802939689942e+02,2.863688717759758570e-02,8.094829451209625049e+00,3.766593713733452052e-03,1.000000009954481461e+00,-4.000000000000000327e-05,3.785352214846209449e-10,0.000000000000000000e+00 +7.924769835917577154e+01,4.867331802230329458e+02,2.867455302567244180e-02,8.096064807699816512e+00,3.766447728331914335e-03,1.000000009954949087e+00,-4.000000000000000327e-05,-1.490282947177045627e-10,0.000000000000000000e+00 +7.924893352715398009e+01,4.867431801521024113e+02,2.871221741390363874e-02,8.097299975690324558e+00,3.766301742930376617e-03,1.000000009954765012e+00,-4.000000000000000327e-05,-6.406137800981564660e-10,0.000000000000000000e+00 +7.925016850671877933e+01,4.867531800811773337e+02,2.874988034229117306e-02,8.098534955267414404e+00,3.766155757528838900e-03,1.000000009953973867e+00,-4.000000000000000327e-05,1.188274345240871160e-09,0.000000000000000000e+00 +7.925140329795635807e+01,4.867631800102577699e+02,2.878754181083504823e-02,8.099769746517285540e+00,3.766009772127301182e-03,1.000000009955441138e+00,-4.000000000000000327e-05,-5.339776704673630559e-10,0.000000000000000000e+00 +7.925263790095286254e+01,4.867731799393437200e+02,2.882520181953526078e-02,8.101004349526075288e+00,3.765863786725763464e-03,1.000000009954781888e+00,-4.000000000000000327e-05,-2.716164308532581103e-11,0.000000000000000000e+00 +7.925387231579435365e+01,4.867831798684351270e+02,2.886286036839180724e-02,8.102238764379849911e+00,3.765717801324225747e-03,1.000000009954748359e+00,-4.000000000000000327e-05,3.324659933262355330e-10,0.000000000000000000e+00 +7.925510654256683551e+01,4.867931797975320478e+02,2.890051745740469108e-02,8.103472991164613504e+00,3.765571815922688029e-03,1.000000009955158697e+00,-4.000000000000000327e-05,-6.680921419687060246e-10,0.000000000000000000e+00 +7.925634058135624116e+01,4.868031797266344824e+02,2.893817308657390883e-02,8.104707029966304432e+00,3.765425830521150312e-03,1.000000009954334246e+00,-4.000000000000000327e-05,4.257868909207712766e-10,0.000000000000000000e+00 +7.925757443224844678e+01,4.868131796557424309e+02,2.897582725589946048e-02,8.105940880870793563e+00,3.765279845119612594e-03,1.000000009954859603e+00,-4.000000000000000327e-05,6.749551651644809183e-11,0.000000000000000000e+00 +7.925880809532925753e+01,4.868231795848558363e+02,2.901347996538134605e-02,8.107174543963889590e+00,3.765133859718074877e-03,1.000000009954942870e+00,-4.000000000000000327e-05,-6.214132880658272537e-10,0.000000000000000000e+00 +7.926004157068442169e+01,4.868331795139747555e+02,2.905113121501956552e-02,8.108408019331333705e+00,3.764987874316537159e-03,1.000000009954176372e+00,-4.000000000000000327e-05,6.479741290548950513e-10,0.000000000000000000e+00 +7.926127485839961651e+01,4.868431794430991886e+02,2.908878100481411544e-02,8.109641307058801374e+00,3.764841888914999442e-03,1.000000009954975511e+00,-4.000000000000000327e-05,-8.405677403311547137e-10,0.000000000000000000e+00 +7.926250795856044817e+01,4.868531793722290786e+02,2.912642933476499579e-02,8.110874407231905892e+00,3.764695903513461724e-03,1.000000009953939006e+00,-4.000000000000000327e-05,7.076034324263549262e-10,0.000000000000000000e+00 +7.926374087125246604e+01,4.868631793013644824e+02,2.916407620487220659e-02,8.112107319936191274e+00,3.764549918111924007e-03,1.000000009954811420e+00,-4.000000000000000327e-05,-5.947726393713394035e-10,0.000000000000000000e+00 +7.926497359656114838e+01,4.868731792305054000e+02,2.920172161513574782e-02,8.113340045257141142e+00,3.764403932710386289e-03,1.000000009954078228e+00,-4.000000000000000327e-05,1.050648438115412247e-09,0.000000000000000000e+00 +7.926620613457190245e+01,4.868831791596517746e+02,2.923936556555561950e-02,8.114572583280169837e+00,3.764257947308848572e-03,1.000000009955373192e+00,-4.000000000000000327e-05,-1.416753030943506761e-09,0.000000000000000000e+00 +7.926743848537009285e+01,4.868931790888036630e+02,2.927700805613181814e-02,8.115804934090631306e+00,3.764111961907310854e-03,1.000000009953627256e+00,-4.000000000000000327e-05,1.313889747544090031e-09,0.000000000000000000e+00 +7.926867064904099891e+01,4.869031790179610653e+02,2.931464908686434376e-02,8.117037097773808441e+00,3.763965976505773137e-03,1.000000009955246183e+00,-4.000000000000000327e-05,-1.331571965542741686e-09,0.000000000000000000e+00 +7.926990262566985734e+01,4.869131789471239244e+02,2.935228865775319634e-02,8.118269074414927289e+00,3.763819991104235419e-03,1.000000009953605717e+00,-4.000000000000000327e-05,1.134026888996870898e-09,0.000000000000000000e+00 +7.927113441534180538e+01,4.869231788762922974e+02,2.938992676879837243e-02,8.119500864099141069e+00,3.763674005702697702e-03,1.000000009955002600e+00,-4.000000000000000327e-05,-6.989809808757822523e-10,0.000000000000000000e+00 +7.927236601814195183e+01,4.869331788054661843e+02,2.942756341999987202e-02,8.120732466911546155e+00,3.763528020301159984e-03,1.000000009954141733e+00,-4.000000000000000327e-05,1.485807821829413238e-10,0.000000000000000000e+00 +7.927359743415532023e+01,4.869431787346455280e+02,2.946519861135769858e-02,8.121963882937167867e+00,3.763382034899622267e-03,1.000000009954324698e+00,-4.000000000000000327e-05,1.193876129180627707e-10,0.000000000000000000e+00 +7.927482866346686308e+01,4.869531786638303856e+02,2.950283234287184517e-02,8.123195112260971129e+00,3.763236049498084549e-03,1.000000009954471691e+00,-4.000000000000000327e-05,3.389174189280722455e-10,0.000000000000000000e+00 +7.927605970616149023e+01,4.869631785930207570e+02,2.954046461454231526e-02,8.124426154967855140e+00,3.763090064096546832e-03,1.000000009954888913e+00,-4.000000000000000327e-05,-4.095045940516912761e-10,0.000000000000000000e+00 +7.927729056232404048e+01,4.869731785222165854e+02,2.957809542636910538e-02,8.125657011142655151e+00,3.762944078695009114e-03,1.000000009954384872e+00,-4.000000000000000327e-05,1.737500743666048692e-10,0.000000000000000000e+00 +7.927852123203928159e+01,4.869831784514179276e+02,2.961572477835221900e-02,8.126887680870140684e+00,3.762798093293471396e-03,1.000000009954598701e+00,-4.000000000000000327e-05,-3.017176775624824962e-10,0.000000000000000000e+00 +7.927975171539191024e+01,4.869931783806247836e+02,2.965335267049165266e-02,8.128118164235019094e+00,3.762652107891933679e-03,1.000000009954227442e+00,-4.000000000000000327e-05,4.660005958901885181e-10,0.000000000000000000e+00 +7.928098201246658050e+01,4.870031783098370965e+02,2.969097910278740288e-02,8.129348461321932007e+00,3.762506122490395961e-03,1.000000009954800761e+00,-4.000000000000000327e-05,-1.089184045524417085e-09,0.000000000000000000e+00 +7.928221212334786117e+01,4.870131782390549233e+02,2.972860407523947313e-02,8.130578572215458877e+00,3.762360137088858244e-03,1.000000009953460944e+00,-4.000000000000000327e-05,8.575417757677656408e-10,0.000000000000000000e+00 +7.928344204812027840e+01,4.870231781682782639e+02,2.976622758784785994e-02,8.131808497000111657e+00,3.762214151687320526e-03,1.000000009954515656e+00,-4.000000000000000327e-05,3.916398900736970674e-10,0.000000000000000000e+00 +7.928467178686827310e+01,4.870331780975070615e+02,2.980384964061256331e-02,8.133038235760343682e+00,3.762068166285782809e-03,1.000000009954997271e+00,-4.000000000000000327e-05,-1.359298869031813198e-09,0.000000000000000000e+00 +7.928590133967622933e+01,4.870431780267413728e+02,2.984147023353358325e-02,8.134267788580540781e+00,3.761922180884245091e-03,1.000000009953325941e+00,-4.000000000000000327e-05,1.435724753560723588e-09,0.000000000000000000e+00 +7.928713070662847429e+01,4.870531779559811412e+02,2.987908936661091627e-02,8.135497155545023062e+00,3.761776195482707374e-03,1.000000009955090974e+00,-4.000000000000000327e-05,-6.687452918058872711e-10,0.000000000000000000e+00 +7.928835988780926414e+01,4.870631778852264233e+02,2.991670703984456586e-02,8.136726336738053789e+00,3.761630210081169656e-03,1.000000009954268965e+00,-4.000000000000000327e-05,-6.663169289631274521e-10,0.000000000000000000e+00 +7.928958888330279819e+01,4.870731778144772193e+02,2.995432325323452855e-02,8.137955332243825168e+00,3.761484224679631939e-03,1.000000009953450064e+00,-4.000000000000000327e-05,1.401320028938687575e-09,0.000000000000000000e+00 +7.929081769319320472e+01,4.870831777437334722e+02,2.999193800678080432e-02,8.139184142146469014e+00,3.761338239278094221e-03,1.000000009955172020e+00,-4.000000000000000327e-05,-1.569426257628235488e-09,0.000000000000000000e+00 +7.929204631756455512e+01,4.870931776729952389e+02,3.002955130048338972e-02,8.140412766530056743e+00,3.761192253876556504e-03,1.000000009953243785e+00,-4.000000000000000327e-05,9.661273167505681047e-10,0.000000000000000000e+00 +7.929327475650086399e+01,4.871031776022624626e+02,3.006716313434228821e-02,8.141641205478588716e+00,3.761046268475018786e-03,1.000000009954430613e+00,-4.000000000000000327e-05,-4.505056302240327711e-10,0.000000000000000000e+00 +7.929450301008606061e+01,4.871131775315352002e+02,3.010477350835749633e-02,8.142869459076010230e+00,3.760900283073481069e-03,1.000000009953877278e+00,-4.000000000000000327e-05,1.199842041952967692e-09,0.000000000000000000e+00 +7.929573107840401747e+01,4.871231774608134515e+02,3.014238242252901406e-02,8.144097527406197301e+00,3.760754297671943351e-03,1.000000009955350766e+00,-4.000000000000000327e-05,-1.194236267010107424e-09,0.000000000000000000e+00 +7.929695896153856438e+01,4.871331773900971598e+02,3.017998987685683795e-02,8.145325410552967327e+00,3.760608312270405634e-03,1.000000009953884383e+00,-4.000000000000000327e-05,5.697170522731964072e-10,0.000000000000000000e+00 +7.929818665957344592e+01,4.871431773193863819e+02,3.021759587134097147e-02,8.146553108600068427e+00,3.760462326868867916e-03,1.000000009954583824e+00,-4.000000000000000327e-05,-6.222609692759614261e-10,0.000000000000000000e+00 +7.929941417259234981e+01,4.871531772486810610e+02,3.025520040598141114e-02,8.147780621631191877e+00,3.760316341467330199e-03,1.000000009953819990e+00,-4.000000000000000327e-05,-9.968530717594040404e-11,0.000000000000000000e+00 +7.930064150067890694e+01,4.871631771779812539e+02,3.029280348077815696e-02,8.149007949729961453e+00,3.760170356065792481e-03,1.000000009953697644e+00,-4.000000000000000327e-05,-2.647215475816130089e-10,0.000000000000000000e+00 +7.930186864391667712e+01,4.871731771072869037e+02,3.033040509573120894e-02,8.150235092979940532e+00,3.760024370664254764e-03,1.000000009953372793e+00,-4.000000000000000327e-05,1.198212785671785677e-09,0.000000000000000000e+00 +7.930309560238914912e+01,4.871831770365980674e+02,3.036800525084056360e-02,8.151462051464628544e+00,3.759878385262717046e-03,1.000000009954842950e+00,-4.000000000000000327e-05,-4.745788983782140675e-10,0.000000000000000000e+00 +7.930432237617976909e+01,4.871931769659147449e+02,3.040560394610622441e-02,8.152688825267464523e+00,3.759732399861179328e-03,1.000000009954260749e+00,-4.000000000000000327e-05,-6.077044731083808966e-10,0.000000000000000000e+00 +7.930554896537191212e+01,4.872031768952368793e+02,3.044320118152818791e-02,8.153915414471820000e+00,3.759586414459641611e-03,1.000000009953515345e+00,-4.000000000000000327e-05,7.569838166944603997e-10,0.000000000000000000e+00 +7.930677537004889643e+01,4.872131768245645276e+02,3.048079695710645409e-02,8.155141819161006111e+00,3.759440429058103893e-03,1.000000009954443714e+00,-4.000000000000000327e-05,-1.149499168474267671e-09,0.000000000000000000e+00 +7.930800159029395502e+01,4.872231767538976328e+02,3.051839127284101949e-02,8.156368039418273597e+00,3.759294443656566176e-03,1.000000009953034175e+00,-4.000000000000000327e-05,1.899639209611742373e-09,0.000000000000000000e+00 +7.930922762619027822e+01,4.872331766832362518e+02,3.055598412873188757e-02,8.157594075326805694e+00,3.759148458255028458e-03,1.000000009955363200e+00,-4.000000000000000327e-05,-1.956982273783732135e-09,0.000000000000000000e+00 +7.931045347782099952e+01,4.872431766125803279e+02,3.059357552477905487e-02,8.158819926969730574e+00,3.759002472853490741e-03,1.000000009952964231e+00,-4.000000000000000327e-05,1.420492768908091665e-09,0.000000000000000000e+00 +7.931167914526916718e+01,4.872531765419299177e+02,3.063116546098252138e-02,8.160045594430103577e+00,3.758856487451953023e-03,1.000000009954705282e+00,-4.000000000000000327e-05,-1.015929021973995605e-09,0.000000000000000000e+00 +7.931290462861778678e+01,4.872631764712849645e+02,3.066875393734228364e-02,8.161271077790928530e+00,3.758710502050415306e-03,1.000000009953460278e+00,-4.000000000000000327e-05,1.500473623663653797e-10,0.000000000000000000e+00 +7.931412992794980710e+01,4.872731764006455251e+02,3.070634095385834511e-02,8.162496377135138204e+00,3.758564516648877588e-03,1.000000009953644131e+00,-4.000000000000000327e-05,1.442700873477325010e-10,0.000000000000000000e+00 +7.931535504334807740e+01,4.872831763300115995e+02,3.074392651053070233e-02,8.163721492545608527e+00,3.758418531247339871e-03,1.000000009953820879e+00,-4.000000000000000327e-05,1.060435533415211668e-10,0.000000000000000000e+00 +7.931657997489543277e+01,4.872931762593831309e+02,3.078151060735935529e-02,8.164946424105151479e+00,3.758272545845802153e-03,1.000000009953950775e+00,-4.000000000000000327e-05,-8.521016823980034364e-12,0.000000000000000000e+00 +7.931780472267460880e+01,4.873031761887601760e+02,3.081909324434430400e-02,8.166171171896516867e+00,3.758126560444264436e-03,1.000000009953940339e+00,-4.000000000000000327e-05,-2.426134188659453964e-10,0.000000000000000000e+00 +7.931902928676829845e+01,4.873131761181426782e+02,3.085667442148554498e-02,8.167395736002392326e+00,3.757980575042726718e-03,1.000000009953643243e+00,-4.000000000000000327e-05,5.451459635357911992e-10,0.000000000000000000e+00 +7.932025366725912363e+01,4.873231760475306942e+02,3.089425413878308171e-02,8.168620116505403317e+00,3.757834589641189001e-03,1.000000009954310709e+00,-4.000000000000000327e-05,-5.822291665232258962e-11,0.000000000000000000e+00 +7.932147786422964941e+01,4.873331759769241671e+02,3.093183239623691072e-02,8.169844313488114906e+00,3.757688604239651283e-03,1.000000009954239433e+00,-4.000000000000000327e-05,-9.121143220318260504e-10,0.000000000000000000e+00 +7.932270187776238402e+01,4.873431759063231539e+02,3.096940919384703200e-02,8.171068327033028211e+00,3.757542618838113566e-03,1.000000009953122992e+00,-4.000000000000000327e-05,3.126110643120829025e-10,0.000000000000000000e+00 +7.932392570793975040e+01,4.873531758357275976e+02,3.100698453161344209e-02,8.172292157222582176e+00,3.757396633436575848e-03,1.000000009953505575e+00,-4.000000000000000327e-05,1.560567509708881155e-11,0.000000000000000000e+00 +7.932514935484414309e+01,4.873631757651375551e+02,3.104455840953614446e-02,8.173515804139157126e+00,3.757250648035038131e-03,1.000000009953524671e+00,-4.000000000000000327e-05,5.254092328539985519e-10,0.000000000000000000e+00 +7.932637281855787137e+01,4.873731756945529696e+02,3.108213082761513563e-02,8.174739267865069436e+00,3.757104662633500413e-03,1.000000009954167490e+00,-4.000000000000000327e-05,-5.744971117225926452e-10,0.000000000000000000e+00 +7.932759609916320187e+01,4.873831756239738979e+02,3.111970178585041560e-02,8.175962548482575087e+00,3.756958677231962695e-03,1.000000009953464719e+00,-4.000000000000000327e-05,2.336456317286089439e-10,0.000000000000000000e+00 +7.932881919674231597e+01,4.873931755534002832e+02,3.115727128424198092e-02,8.177185646073866110e+00,3.756812691830424978e-03,1.000000009953750491e+00,-4.000000000000000327e-05,5.330895071347734912e-10,0.000000000000000000e+00 +7.933004211137735240e+01,4.874031754828321823e+02,3.119483932278983504e-02,8.178408560721075915e+00,3.756666706428887260e-03,1.000000009954402413e+00,-4.000000000000000327e-05,-9.076225545908464036e-10,0.000000000000000000e+00 +7.933126484315037885e+01,4.874131754122695384e+02,3.123240590149397450e-02,8.179631292506275742e+00,3.756520721027349543e-03,1.000000009953292635e+00,-4.000000000000000327e-05,6.202469840823384574e-10,0.000000000000000000e+00 +7.933248739214340617e+01,4.874231753417124082e+02,3.126997102035439929e-02,8.180853841511472879e+00,3.756374735625811825e-03,1.000000009954050917e+00,-4.000000000000000327e-05,-8.666590484785182996e-10,0.000000000000000000e+00 +7.933370975843838835e+01,4.874331752711607351e+02,3.130753467937110596e-02,8.182076207818617775e+00,3.756228750224274108e-03,1.000000009952991542e+00,-4.000000000000000327e-05,5.312281910288349796e-10,0.000000000000000000e+00 +7.933493194211720834e+01,4.874431752006145189e+02,3.134509687854410143e-02,8.183298391509595149e+00,3.756082764822736390e-03,1.000000009953640800e+00,-4.000000000000000327e-05,1.599010387327224963e-11,0.000000000000000000e+00 +7.933615394326167802e+01,4.874531751300738165e+02,3.138265761787337876e-02,8.184520392666232880e+00,3.755936779421198673e-03,1.000000009953660340e+00,-4.000000000000000327e-05,-7.741819823605256644e-11,0.000000000000000000e+00 +7.933737576195358088e+01,4.874631750595385711e+02,3.142021689735893797e-02,8.185742211370294896e+00,3.755790794019660955e-03,1.000000009953565749e+00,-4.000000000000000327e-05,2.090239879643149573e-10,0.000000000000000000e+00 +7.933859739827461510e+01,4.874731749890088395e+02,3.145777471700077904e-02,8.186963847703484731e+00,3.755644808618123238e-03,1.000000009953821101e+00,-4.000000000000000327e-05,-3.577570429298505796e-10,0.000000000000000000e+00 +7.933981885230642206e+01,4.874831749184845648e+02,3.149533107679890198e-02,8.188185301747445521e+00,3.755498823216585520e-03,1.000000009953384117e+00,-4.000000000000000327e-05,5.603514785509494592e-10,0.000000000000000000e+00 +7.934104012413057205e+01,4.874931748479658040e+02,3.153288597675329985e-02,8.189406573583758231e+00,3.755352837815047803e-03,1.000000009954068458e+00,-4.000000000000000327e-05,-6.511738912529860971e-10,0.000000000000000000e+00 +7.934226121382860697e+01,4.875031747774525002e+02,3.157043941686397959e-02,8.190627663293945204e+00,3.755206852413510085e-03,1.000000009953273317e+00,-4.000000000000000327e-05,-4.621277780987290029e-10,0.000000000000000000e+00 +7.934348212148196922e+01,4.875131747069447101e+02,3.160799139713093425e-02,8.191848570959464837e+00,3.755060867011972368e-03,1.000000009952709101e+00,-4.000000000000000327e-05,1.086280391543901776e-09,0.000000000000000000e+00 +7.934470284717207278e+01,4.875231746364423771e+02,3.164554191755417079e-02,8.193069296661716905e+00,3.754914881610434650e-03,1.000000009954035152e+00,-4.000000000000000327e-05,-8.164690035931739044e-10,0.000000000000000000e+00 +7.934592339098024638e+01,4.875331745659455578e+02,3.168309097813368225e-02,8.194289840482042564e+00,3.754768896208896933e-03,1.000000009953038616e+00,-4.000000000000000327e-05,9.401345392350427037e-10,0.000000000000000000e+00 +7.934714375298777611e+01,4.875431744954541955e+02,3.172063857886946864e-02,8.195510202501717245e+00,3.754622910807359215e-03,1.000000009954185920e+00,-4.000000000000000327e-05,-8.412791278315054573e-10,0.000000000000000000e+00 +7.934836393327587700e+01,4.875531744249682902e+02,3.175818471976152996e-02,8.196730382801961312e+00,3.754476925405821498e-03,1.000000009953159408e+00,-4.000000000000000327e-05,-2.391532244017508146e-10,0.000000000000000000e+00 +7.934958393192570725e+01,4.875631743544878987e+02,3.179572940080986621e-02,8.197950381463929403e+00,3.754330940004283780e-03,1.000000009952867641e+00,-4.000000000000000327e-05,3.189184265189837969e-10,0.000000000000000000e+00 +7.935080374901835398e+01,4.875731742840129641e+02,3.183327262201447738e-02,8.199170198568719314e+00,3.754184954602746063e-03,1.000000009953256663e+00,-4.000000000000000327e-05,7.912247231396308291e-10,0.000000000000000000e+00 +7.935202338463486171e+01,4.875831742135435434e+02,3.187081438337535655e-02,8.200389834197368444e+00,3.754038969201208345e-03,1.000000009954221669e+00,-4.000000000000000327e-05,-1.254931419609489941e-09,0.000000000000000000e+00 +7.935324283885620389e+01,4.875931741430795796e+02,3.190835468489251064e-02,8.201609288430853795e+00,3.753892983799670627e-03,1.000000009952691338e+00,-4.000000000000000327e-05,1.306655820087851446e-09,0.000000000000000000e+00 +7.935446211176329712e+01,4.876031740726210728e+02,3.194589352656593273e-02,8.202828561350088421e+00,3.753746998398132910e-03,1.000000009954284508e+00,-4.000000000000000327e-05,-1.124528548896451724e-09,0.000000000000000000e+00 +7.935568120343700116e+01,4.876131740021680798e+02,3.198343090839562974e-02,8.204047653035932086e+00,3.753601012996595192e-03,1.000000009952913604e+00,-4.000000000000000327e-05,-2.257042340161667876e-10,0.000000000000000000e+00 +7.935690011395811894e+01,4.876231739317205438e+02,3.202096683038159475e-02,8.205266563569177052e+00,3.753455027595057475e-03,1.000000009952638491e+00,-4.000000000000000327e-05,3.762296131031373302e-10,0.000000000000000000e+00 +7.935811884340736810e+01,4.876331738612785216e+02,3.205850129252382774e-02,8.206485293030560513e+00,3.753309042193519757e-03,1.000000009953097013e+00,-4.000000000000000327e-05,6.392297892776889003e-10,0.000000000000000000e+00 +7.935933739186543789e+01,4.876431737908419564e+02,3.209603429482232873e-02,8.207703841500759268e+00,3.753163056791982040e-03,1.000000009953875946e+00,-4.000000000000000327e-05,-6.759564807473931956e-10,0.000000000000000000e+00 +7.936055575941294649e+01,4.876531737204108481e+02,3.213356583727709770e-02,8.208922209060389719e+00,3.753017071390444322e-03,1.000000009953052382e+00,-4.000000000000000327e-05,-2.132613859862221704e-11,0.000000000000000000e+00 +7.936177394613044100e+01,4.876631736499852536e+02,3.217109591988812772e-02,8.210140395790006096e+00,3.752871085988906605e-03,1.000000009953026403e+00,-4.000000000000000327e-05,1.682645042258940148e-10,0.000000000000000000e+00 +7.936299195209841173e+01,4.876731735795651161e+02,3.220862454265542574e-02,8.211358401770105786e+00,3.752725100587368887e-03,1.000000009953231350e+00,-4.000000000000000327e-05,-1.493272734587262555e-10,0.000000000000000000e+00 +7.936420977739730631e+01,4.876831735091504925e+02,3.224615170557899174e-02,8.212576227081125779e+00,3.752579115185831170e-03,1.000000009953049496e+00,-4.000000000000000327e-05,1.816264010783896907e-10,0.000000000000000000e+00 +7.936542742210750134e+01,4.876931734387413258e+02,3.228367740865881880e-02,8.213793871803442670e+00,3.752433129784293452e-03,1.000000009953270652e+00,-4.000000000000000327e-05,-7.824224759209023845e-11,0.000000000000000000e+00 +7.936664488630931658e+01,4.877031733683376160e+02,3.232120165189490690e-02,8.215011336017374433e+00,3.752287144382755735e-03,1.000000009953175395e+00,-4.000000000000000327e-05,2.274651386361107464e-10,0.000000000000000000e+00 +7.936786217008300071e+01,4.877131732979394201e+02,3.235872443528725606e-02,8.216228619803178645e+00,3.752141158981218017e-03,1.000000009953452285e+00,-4.000000000000000327e-05,-1.413886159339897123e-10,0.000000000000000000e+00 +7.936907927350875980e+01,4.877231732275466811e+02,3.239624575883586627e-02,8.217445723241054267e+00,3.751995173579680300e-03,1.000000009953280200e+00,-4.000000000000000327e-05,-2.755205628556021412e-11,0.000000000000000000e+00 +7.937029619666672886e+01,4.877331731571593991e+02,3.243376562254073753e-02,8.218662646411139860e+00,3.751849188178142582e-03,1.000000009953246671e+00,-4.000000000000000327e-05,-6.719317516631532394e-10,0.000000000000000000e+00 +7.937151293963700027e+01,4.877431730867776309e+02,3.247128402640186984e-02,8.219879389393515368e+00,3.751703202776604865e-03,1.000000009952429103e+00,-4.000000000000000327e-05,1.484236271543883153e-09,0.000000000000000000e+00 +7.937272950249958114e+01,4.877531730164013197e+02,3.250880097041926320e-02,8.221095952268200335e+00,3.751557217375067147e-03,1.000000009954234770e+00,-4.000000000000000327e-05,-2.002883743041621413e-09,0.000000000000000000e+00 +7.937394588533443596e+01,4.877631729460305223e+02,3.254631645459291067e-02,8.222312335115159243e+00,3.751411231973529430e-03,1.000000009951798496e+00,-4.000000000000000327e-05,2.031296176607605903e-09,0.000000000000000000e+00 +7.937516208822145813e+01,4.877731728756651819e+02,3.258383047892281920e-02,8.223528538014289069e+00,3.751265246571991712e-03,1.000000009954268965e+00,-4.000000000000000327e-05,-8.631455416895038355e-10,0.000000000000000000e+00 +7.937637811124049847e+01,4.877831728053052984e+02,3.262134304340898183e-02,8.224744561045438829e+00,3.751119261170453995e-03,1.000000009953219360e+00,-4.000000000000000327e-05,-1.121506362208980144e-09,0.000000000000000000e+00 +7.937759395447135091e+01,4.877931727349509288e+02,3.265885414805139858e-02,8.225960404288388261e+00,3.750973275768916277e-03,1.000000009951855784e+00,-4.000000000000000327e-05,1.218112942429333828e-09,0.000000000000000000e+00 +7.937880961799372415e+01,4.878031726646020161e+02,3.269636379285007638e-02,8.227176067822862038e+00,3.750827290367378559e-03,1.000000009953336599e+00,-4.000000000000000327e-05,1.048583234226701596e-10,0.000000000000000000e+00 +7.938002510188729843e+01,4.878131725942585604e+02,3.273387197780500829e-02,8.228391551728529762e+00,3.750681304965840842e-03,1.000000009953464053e+00,-4.000000000000000327e-05,-8.976394670599466039e-10,0.000000000000000000e+00 +7.938124040623166877e+01,4.878231725239206185e+02,3.277137870291618738e-02,8.229606856084997091e+00,3.750535319564303124e-03,1.000000009952373148e+00,-4.000000000000000327e-05,5.757947719403371925e-10,0.000000000000000000e+00 +7.938245553110638753e+01,4.878331724535881335e+02,3.280888396818362057e-02,8.230821980971811058e+00,3.750389334162765407e-03,1.000000009953072810e+00,-4.000000000000000327e-05,-3.271421210801937101e-10,0.000000000000000000e+00 +7.938367047659095022e+01,4.878431723832611056e+02,3.284638777360730788e-02,8.232036926468463633e+00,3.750243348761227689e-03,1.000000009952675351e+00,-4.000000000000000327e-05,-3.856825506709173720e-11,0.000000000000000000e+00 +7.938488524276478131e+01,4.878531723129395345e+02,3.288389011918724236e-02,8.233251692654384613e+00,3.750097363359689972e-03,1.000000009952628499e+00,-4.000000000000000327e-05,1.970744750652603653e-10,0.000000000000000000e+00 +7.938609982970724843e+01,4.878631722426234774e+02,3.292139100492343096e-02,8.234466279608946948e+00,3.749951377958152254e-03,1.000000009952867863e+00,-4.000000000000000327e-05,3.393545314745828643e-10,0.000000000000000000e+00 +7.938731423749767657e+01,4.878731721723128771e+02,3.295889043081586672e-02,8.235680687411464973e+00,3.749805392556614537e-03,1.000000009953279978e+00,-4.000000000000000327e-05,3.472679394132954286e-10,0.000000000000000000e+00 +7.938852846621531967e+01,4.878831721020077339e+02,3.299638839686454966e-02,8.236894916141194400e+00,3.749659407155076819e-03,1.000000009953701641e+00,-4.000000000000000327e-05,-1.025679689841570286e-09,0.000000000000000000e+00 +7.938974251593937481e+01,4.878931720317081044e+02,3.303388490306947978e-02,8.238108965877332324e+00,3.749513421753539102e-03,1.000000009952456415e+00,-4.000000000000000327e-05,-2.052393424037816520e-10,0.000000000000000000e+00 +7.939095638674898225e+01,4.879031719614139320e+02,3.307137994943065706e-02,8.239322836699015440e+00,3.749367436352001384e-03,1.000000009952207281e+00,-4.000000000000000327e-05,3.585814480884257366e-10,0.000000000000000000e+00 +7.939217007872321119e+01,4.879131718911252165e+02,3.310887353594808152e-02,8.240536528685325379e+00,3.749221450950463667e-03,1.000000009952642488e+00,-4.000000000000000327e-05,6.244993671612024231e-10,0.000000000000000000e+00 +7.939338359194108818e+01,4.879231718208420148e+02,3.314636566262175316e-02,8.241750041915285152e+00,3.749075465548925949e-03,1.000000009953400326e+00,-4.000000000000000327e-05,-6.551529352373624772e-10,0.000000000000000000e+00 +7.939459692648158295e+01,4.879331717505642700e+02,3.318385632945167196e-02,8.242963376467859149e+00,3.748929480147388232e-03,1.000000009952605406e+00,-4.000000000000000327e-05,9.865346894768869327e-11,0.000000000000000000e+00 +7.939581008242359417e+01,4.879431716802919823e+02,3.322134553643783100e-02,8.244176532421951364e+00,3.748783494745850514e-03,1.000000009952725089e+00,-4.000000000000000327e-05,4.323817963576425886e-10,0.000000000000000000e+00 +7.939702305984597785e+01,4.879531716100251515e+02,3.325883328358023722e-02,8.245389509856410726e+00,3.748637509344312797e-03,1.000000009953249558e+00,-4.000000000000000327e-05,-9.027893027169655320e-10,0.000000000000000000e+00 +7.939823585882751900e+01,4.879631715397638345e+02,3.329631957087888366e-02,8.246602308850027541e+00,3.748491523942775079e-03,1.000000009952154656e+00,-4.000000000000000327e-05,8.835122886674846682e-10,0.000000000000000000e+00 +7.939944847944695994e+01,4.879731714695079745e+02,3.333380439833377035e-02,8.247814929481531721e+00,3.748345538541237362e-03,1.000000009953226021e+00,-4.000000000000000327e-05,-1.497155445140652451e-09,0.000000000000000000e+00 +7.940066092178295776e+01,4.879831713992575715e+02,3.337128776594489726e-02,8.249027371829599886e+00,3.748199553139699644e-03,1.000000009951410807e+00,-4.000000000000000327e-05,1.581082026938698468e-09,0.000000000000000000e+00 +7.940187318591414112e+01,4.879931713290126822e+02,3.340876967371226441e-02,8.250239635972844709e+00,3.748053567738161927e-03,1.000000009953327496e+00,-4.000000000000000327e-05,-7.987176434208011228e-10,0.000000000000000000e+00 +7.940308527191906762e+01,4.880031712587732500e+02,3.344625012163587180e-02,8.251451721989829124e+00,3.747907582336624209e-03,1.000000009952359381e+00,-4.000000000000000327e-05,9.932303820493895250e-10,0.000000000000000000e+00 +7.940429717987622382e+01,4.880131711885392747e+02,3.348372910971571248e-02,8.252663629959050340e+00,3.747761596935086491e-03,1.000000009953563085e+00,-4.000000000000000327e-05,-1.548244976879420686e-09,0.000000000000000000e+00 +7.940550890986406785e+01,4.880231711183107564e+02,3.352120663795179339e-02,8.253875359958954050e+00,3.747615611533548774e-03,1.000000009951687030e+00,-4.000000000000000327e-05,1.214182626879180280e-09,0.000000000000000000e+00 +7.940672046196097256e+01,4.880331710480877518e+02,3.355868270634411454e-02,8.255086912067922000e+00,3.747469626132011056e-03,1.000000009953158076e+00,-4.000000000000000327e-05,-4.393695036292567982e-10,0.000000000000000000e+00 +7.940793183624528240e+01,4.880431709778702043e+02,3.359615731489266899e-02,8.256298286364286199e+00,3.747323640730473339e-03,1.000000009952625835e+00,-4.000000000000000327e-05,-4.986484855898000453e-10,0.000000000000000000e+00 +7.940914303279525654e+01,4.880531709076581137e+02,3.363363046359745673e-02,8.257509482926314703e+00,3.747177655328935621e-03,1.000000009952021873e+00,-4.000000000000000327e-05,9.976266278988639244e-10,0.000000000000000000e+00 +7.941035405168911154e+01,4.880631708374514801e+02,3.367110215245847776e-02,8.258720501832220506e+00,3.747031669927397904e-03,1.000000009953230018e+00,-4.000000000000000327e-05,-8.354812532107035939e-10,0.000000000000000000e+00 +7.941156489300500709e+01,4.880731707672503035e+02,3.370857238147573209e-02,8.259931343160161532e+00,3.746885684525860186e-03,1.000000009952218383e+00,-4.000000000000000327e-05,1.797391727963883600e-11,0.000000000000000000e+00 +7.941277555682103184e+01,4.880831706970546406e+02,3.374604115064921972e-02,8.261142006988233533e+00,3.746739699124322469e-03,1.000000009952240143e+00,-4.000000000000000327e-05,-1.155635468297907983e-10,0.000000000000000000e+00 +7.941398604321523180e+01,4.880931706268644348e+02,3.378350845997894064e-02,8.262352493394478969e+00,3.746593713722784751e-03,1.000000009952100255e+00,-4.000000000000000327e-05,1.147915974523555818e-09,0.000000000000000000e+00 +7.941519635226559615e+01,4.881031705566796859e+02,3.382097430946489486e-02,8.263562802456881684e+00,3.746447728321247034e-03,1.000000009953489588e+00,-4.000000000000000327e-05,-1.082578927269386623e-09,0.000000000000000000e+00 +7.941640648405004299e+01,4.881131704865003940e+02,3.385843869910707543e-02,8.264772934253370451e+00,3.746301742919709316e-03,1.000000009952179525e+00,-4.000000000000000327e-05,-7.836082988990499242e-10,0.000000000000000000e+00 +7.941761643864644782e+01,4.881231704163266159e+02,3.389590162890548930e-02,8.265982888861811873e+00,3.746155757518171599e-03,1.000000009951231394e+00,-4.000000000000000327e-05,2.008313177313557838e-09,0.000000000000000000e+00 +7.941882621613261506e+01,4.881331703461582947e+02,3.393336309886012953e-02,8.267192666360019260e+00,3.746009772116633881e-03,1.000000009953661007e+00,-4.000000000000000327e-05,-1.243860514749239580e-09,0.000000000000000000e+00 +7.942003581658630651e+01,4.881431702759954305e+02,3.397082310897099611e-02,8.268402266825752633e+00,3.745863786715096164e-03,1.000000009952156432e+00,-4.000000000000000327e-05,3.449757781518589477e-10,0.000000000000000000e+00 +7.942124524008522712e+01,4.881531702058380233e+02,3.400828165923808905e-02,8.269611690336706289e+00,3.745717801313558446e-03,1.000000009952573654e+00,-4.000000000000000327e-05,-5.501323091350046126e-10,0.000000000000000000e+00 +7.942245448670701080e+01,4.881631701356860731e+02,3.404573874966140834e-02,8.270820936970524784e+00,3.745571815912020729e-03,1.000000009951908408e+00,-4.000000000000000327e-05,-3.246916383884165839e-10,0.000000000000000000e+00 +7.942366355652924881e+01,4.881731700655396367e+02,3.408319438024095399e-02,8.272030006804792279e+00,3.745425830510483011e-03,1.000000009951515834e+00,-4.000000000000000327e-05,9.821153767216644552e-10,0.000000000000000000e+00 +7.942487244962946136e+01,4.881831699953986572e+02,3.412064855097672600e-02,8.273238899917037870e+00,3.745279845108945294e-03,1.000000009952703106e+00,-4.000000000000000327e-05,-3.159688268329864152e-10,0.000000000000000000e+00 +7.942608116608512603e+01,4.881931699252631347e+02,3.415810126186871742e-02,8.274447616384735582e+00,3.745133859707407576e-03,1.000000009952321189e+00,-4.000000000000000327e-05,6.044705326925421347e-10,0.000000000000000000e+00 +7.942728970597366356e+01,4.882031698551330692e+02,3.419555251291693521e-02,8.275656156285299048e+00,3.744987874305869859e-03,1.000000009953051716e+00,-4.000000000000000327e-05,-1.161708467645975624e-09,0.000000000000000000e+00 +7.942849806937242363e+01,4.882131697850084606e+02,3.423300230412137241e-02,8.276864519696088607e+00,3.744841888904332141e-03,1.000000009951647950e+00,-4.000000000000000327e-05,4.296853816543201118e-10,0.000000000000000000e+00 +7.942970625635871329e+01,4.882231697148893659e+02,3.427045063548203596e-02,8.278072706694404204e+00,3.744695903502794423e-03,1.000000009952167090e+00,-4.000000000000000327e-05,4.722082454721814787e-10,0.000000000000000000e+00 +7.943091426700978275e+01,4.882331696447757281e+02,3.430789750699891894e-02,8.279280717357494268e+00,3.744549918101256706e-03,1.000000009952737523e+00,-4.000000000000000327e-05,-1.074894714445424007e-09,0.000000000000000000e+00 +7.943212210140281115e+01,4.882431695746675473e+02,3.434534291867202133e-02,8.280488551762548610e+00,3.744403932699718988e-03,1.000000009951439228e+00,-4.000000000000000327e-05,6.196209416540152841e-10,0.000000000000000000e+00 +7.943332975961494924e+01,4.882531695045648235e+02,3.438278687050134313e-02,8.281696209986698420e+00,3.744257947298181271e-03,1.000000009952187519e+00,-4.000000000000000327e-05,6.460076648214412419e-10,0.000000000000000000e+00 +7.943453724172326247e+01,4.882631694344675566e+02,3.442022936248688436e-02,8.282903692107023375e+00,3.744111961896643553e-03,1.000000009952967561e+00,-4.000000000000000327e-05,-1.036742427738152937e-09,0.000000000000000000e+00 +7.943574454780477367e+01,4.882731693643757467e+02,3.445767039462863807e-02,8.284110998200544529e+00,3.743965976495105836e-03,1.000000009951715896e+00,-4.000000000000000327e-05,4.067006601942458360e-10,0.000000000000000000e+00 +7.943695167793643463e+01,4.882831692942894506e+02,3.449510996692661119e-02,8.285318128344224320e+00,3.743819991093568118e-03,1.000000009952206836e+00,-4.000000000000000327e-05,6.273411749558599769e-11,0.000000000000000000e+00 +7.943815863219516871e+01,4.882931692242086115e+02,3.453254807938079679e-02,8.286525082614973670e+00,3.743674005692030401e-03,1.000000009952282554e+00,-4.000000000000000327e-05,-8.905494430745725150e-10,0.000000000000000000e+00 +7.943936541065782819e+01,4.883031691541332293e+02,3.456998473199120181e-02,8.287731861089644880e+00,3.743528020290492683e-03,1.000000009951207858e+00,-4.000000000000000327e-05,1.168556303230855394e-09,0.000000000000000000e+00 +7.944057201340120855e+01,4.883131690840633041e+02,3.460741992475781931e-02,8.288938463845033411e+00,3.743382034888954966e-03,1.000000009952617841e+00,-4.000000000000000327e-05,1.004920680282991913e-10,0.000000000000000000e+00 +7.944177844050204840e+01,4.883231690139988359e+02,3.464485365768064928e-02,8.290144890957883206e+00,3.743236049487417248e-03,1.000000009952739077e+00,-4.000000000000000327e-05,-4.740013513741325270e-10,0.000000000000000000e+00 +7.944298469203704371e+01,4.883331689439398247e+02,3.468228593075969174e-02,8.291351142504877814e+00,3.743090064085879531e-03,1.000000009952167312e+00,-4.000000000000000327e-05,-5.937385568661353164e-10,0.000000000000000000e+00 +7.944419076808280522e+01,4.883431688738862704e+02,3.471971674399494667e-02,8.292557218562645716e+00,3.742944078684341813e-03,1.000000009951451219e+00,-4.000000000000000327e-05,9.250779579263730641e-10,0.000000000000000000e+00 +7.944539666871591521e+01,4.883531688038381731e+02,3.475714609738641409e-02,8.293763119207760326e+00,3.742798093282804096e-03,1.000000009952566771e+00,-4.000000000000000327e-05,-8.436302511925119493e-10,0.000000000000000000e+00 +7.944660239401289914e+01,4.883631687337955896e+02,3.479457399093409398e-02,8.294968844516741768e+00,3.742652107881266378e-03,1.000000009951549584e+00,-4.000000000000000327e-05,1.701872245870254812e-10,0.000000000000000000e+00 +7.944780794405021140e+01,4.883731686637584630e+02,3.483200042463797941e-02,8.296174394566049770e+00,3.742506122479728661e-03,1.000000009951754754e+00,-4.000000000000000327e-05,2.617653608245253382e-10,0.000000000000000000e+00 +7.944901331890426377e+01,4.883831685937267935e+02,3.486942539849807732e-02,8.297379769432092544e+00,3.742360137078190943e-03,1.000000009952070279e+00,-4.000000000000000327e-05,-6.079881762294438423e-10,0.000000000000000000e+00 +7.945021851865139695e+01,4.883931685237005809e+02,3.490684891251438077e-02,8.298584969191221461e+00,3.742214151676653226e-03,1.000000009951337532e+00,-4.000000000000000327e-05,1.190724320719064809e-09,0.000000000000000000e+00 +7.945142354336790902e+01,4.884031684536798252e+02,3.494427096668688976e-02,8.299789993919731046e+00,3.742068166275115508e-03,1.000000009952772384e+00,-4.000000000000000327e-05,-1.720369171414952563e-09,0.000000000000000000e+00 +7.945262839313005543e+01,4.884131683836645266e+02,3.498169156101560429e-02,8.300994843693864311e+00,3.741922180873577791e-03,1.000000009950699598e+00,-4.000000000000000327e-05,1.632330056361494232e-09,0.000000000000000000e+00 +7.945383306801400636e+01,4.884231683136546849e+02,3.501911069550052436e-02,8.302199518589802096e+00,3.741776195472040073e-03,1.000000009952666025e+00,-4.000000000000000327e-05,-1.028465559698432838e-09,0.000000000000000000e+00 +7.945503756809588936e+01,4.884331682436503002e+02,3.505652837014164996e-02,8.303404018683679055e+00,3.741630210070502355e-03,1.000000009951427238e+00,-4.000000000000000327e-05,5.107121199666451008e-11,0.000000000000000000e+00 +7.945624189345178934e+01,4.884431681736513724e+02,3.509394458493898111e-02,8.304608344051565894e+00,3.741484224668964638e-03,1.000000009951488744e+00,-4.000000000000000327e-05,1.160978294260065653e-09,0.000000000000000000e+00 +7.945744604415772017e+01,4.884531681036579585e+02,3.513135933989251086e-02,8.305812494769483578e+00,3.741338239267426920e-03,1.000000009952886737e+00,-4.000000000000000327e-05,-1.414548075004561123e-09,0.000000000000000000e+00 +7.945865002028965307e+01,4.884631680336700015e+02,3.516877263500224615e-02,8.307016470913398010e+00,3.741192253865889203e-03,1.000000009951183655e+00,-4.000000000000000327e-05,8.639770043785323248e-10,0.000000000000000000e+00 +7.945985382192348823e+01,4.884731679636875015e+02,3.520618447026818004e-02,8.308220272559214692e+00,3.741046268464351485e-03,1.000000009952223712e+00,-4.000000000000000327e-05,-6.209581612778139970e-10,0.000000000000000000e+00 +7.946105744913508317e+01,4.884831678937104584e+02,3.524359484569031947e-02,8.309423899782791167e+00,3.740900283062813768e-03,1.000000009951476310e+00,-4.000000000000000327e-05,2.214075296378259451e-10,0.000000000000000000e+00 +7.946226090200023862e+01,4.884931678237388724e+02,3.528100376126865750e-02,8.310627352659924583e+00,3.740754297661276050e-03,1.000000009951742763e+00,-4.000000000000000327e-05,-3.257007392108938497e-10,0.000000000000000000e+00 +7.946346418059469841e+01,4.885031677537727433e+02,3.531841121700319414e-02,8.311830631266360569e+00,3.740608312259738333e-03,1.000000009951350854e+00,-4.000000000000000327e-05,1.522617647696732941e-10,0.000000000000000000e+00 +7.946466728499414955e+01,4.885131676838120711e+02,3.535581721289392937e-02,8.313033735677787917e+00,3.740462326858200615e-03,1.000000009951534041e+00,-4.000000000000000327e-05,3.905848840955838851e-10,0.000000000000000000e+00 +7.946587021527423644e+01,4.885231676138568560e+02,3.539322174894086320e-02,8.314236665969842122e+00,3.740316341456662898e-03,1.000000009952003888e+00,-4.000000000000000327e-05,3.505803520526369555e-10,0.000000000000000000e+00 +7.946707297151053240e+01,4.885331675439070978e+02,3.543062482514398870e-02,8.315439422218103616e+00,3.740170356055125180e-03,1.000000009952425550e+00,-4.000000000000000327e-05,-1.234686651060911424e-09,0.000000000000000000e+00 +7.946827555377855390e+01,4.885431674739627965e+02,3.546802644150331280e-02,8.316642004498097762e+00,3.740024370653587463e-03,1.000000009950940738e+00,-4.000000000000000327e-05,5.098643412897285683e-10,0.000000000000000000e+00 +7.946947796215378901e+01,4.885531674040239523e+02,3.550542659801882855e-02,8.317844412885293082e+00,3.739878385252049745e-03,1.000000009951553803e+00,-4.000000000000000327e-05,6.333131461873902733e-10,0.000000000000000000e+00 +7.947068019671164052e+01,4.885631673340905650e+02,3.554282529469054291e-02,8.319046647455108356e+00,3.739732399850512028e-03,1.000000009952315194e+00,-4.000000000000000327e-05,-9.045735590038110312e-10,0.000000000000000000e+00 +7.947188225752746860e+01,4.885731672641626346e+02,3.558022253151844894e-02,8.320248708282905525e+00,3.739586414448974310e-03,1.000000009951227842e+00,-4.000000000000000327e-05,7.763053549371072539e-10,0.000000000000000000e+00 +7.947308414467659077e+01,4.885831671942401613e+02,3.561761830850254662e-02,8.321450595443989684e+00,3.739440429047436593e-03,1.000000009952160873e+00,-4.000000000000000327e-05,-5.101591392447003684e-10,0.000000000000000000e+00 +7.947428585823425351e+01,4.885931671243231449e+02,3.565501262564283597e-02,8.322652309013616190e+00,3.739294443645898875e-03,1.000000009951547808e+00,-4.000000000000000327e-05,-1.113789626448481783e-09,0.000000000000000000e+00 +7.947548739827566067e+01,4.886031670544115855e+02,3.569240548293931697e-02,8.323853849066981780e+00,3.739148458244361158e-03,1.000000009950209545e+00,-4.000000000000000327e-05,1.390635969941821808e-09,0.000000000000000000e+00 +7.947668876487595924e+01,4.886131669845054830e+02,3.572979688039198964e-02,8.325055215679229903e+00,3.739002472842823440e-03,1.000000009951880209e+00,-4.000000000000000327e-05,-4.192474196509475239e-10,0.000000000000000000e+00 +7.947788995811022517e+01,4.886231669146048944e+02,3.576718681800085398e-02,8.326256408925454267e+00,3.738856487441285723e-03,1.000000009951376612e+00,-4.000000000000000327e-05,8.033037367911853756e-10,0.000000000000000000e+00 +7.947909097805350598e+01,4.886331668447097627e+02,3.580457529576590303e-02,8.327457428880688184e+00,3.738710502039748005e-03,1.000000009952341395e+00,-4.000000000000000327e-05,-1.135696948222024260e-09,0.000000000000000000e+00 +7.948029182478077814e+01,4.886431667748200880e+02,3.584196231368714375e-02,8.328658275619915230e+00,3.738564516638210287e-03,1.000000009950977597e+00,-4.000000000000000327e-05,-1.161381523637607186e-10,0.000000000000000000e+00 +7.948149249836697550e+01,4.886531667049358703e+02,3.587934787176456919e-02,8.329858949218060360e+00,3.738418531236672570e-03,1.000000009950838153e+00,-4.000000000000000327e-05,1.361860656314663595e-09,0.000000000000000000e+00 +7.948269299888697503e+01,4.886631666350571095e+02,3.591673196999817935e-02,8.331059449749998791e+00,3.738272545835134852e-03,1.000000009952473068e+00,-4.000000000000000327e-05,-1.670799697487223789e-09,0.000000000000000000e+00 +7.948389332641558269e+01,4.886731665651838057e+02,3.595411460838797424e-02,8.332259777290552449e+00,3.738126560433597135e-03,1.000000009950467561e+00,-4.000000000000000327e-05,6.101739723597231320e-10,0.000000000000000000e+00 +7.948509348102757599e+01,4.886831664953159589e+02,3.599149578693395385e-02,8.333459931914482866e+00,3.737980575032059417e-03,1.000000009951199864e+00,-4.000000000000000327e-05,7.708765642790045942e-10,0.000000000000000000e+00 +7.948629346279766139e+01,4.886931664254535690e+02,3.602887550563611818e-02,8.334659913696505384e+00,3.737834589630521700e-03,1.000000009952124902e+00,-4.000000000000000327e-05,-1.229582668273989125e-09,0.000000000000000000e+00 +7.948749327180048851e+01,4.887031663555966361e+02,3.606625376449446724e-02,8.335859722711278508e+00,3.737688604228983982e-03,1.000000009950649638e+00,-4.000000000000000327e-05,7.420389109469186848e-10,0.000000000000000000e+00 +7.948869290811067856e+01,4.887131662857451602e+02,3.610363056350900102e-02,8.337059359033403894e+00,3.737542618827446265e-03,1.000000009951539814e+00,-4.000000000000000327e-05,4.777944752213429243e-10,0.000000000000000000e+00 +7.948989237180276746e+01,4.887231662158991412e+02,3.614100590267971258e-02,8.338258822737435239e+00,3.737396633425908547e-03,1.000000009952112912e+00,-4.000000000000000327e-05,-8.270495879518363726e-10,0.000000000000000000e+00 +7.949109166295126272e+01,4.887331661460585792e+02,3.617837978200660887e-02,8.339458113897869396e+00,3.737250648024370830e-03,1.000000009951121038e+00,-4.000000000000000327e-05,4.960789176585132344e-10,0.000000000000000000e+00 +7.949229078163061502e+01,4.887431660762234742e+02,3.621575220148968294e-02,8.340657232589148151e+00,3.737104662622833112e-03,1.000000009951715896e+00,-4.000000000000000327e-05,-5.317086085812815714e-10,0.000000000000000000e+00 +7.949348972791520396e+01,4.887531660063938261e+02,3.625312316112893479e-02,8.341856178885663553e+00,3.736958677221295395e-03,1.000000009951078406e+00,-4.000000000000000327e-05,-2.413500199935474071e-10,0.000000000000000000e+00 +7.949468850187936653e+01,4.887631659365695782e+02,3.629049266092436443e-02,8.343054952861750806e+00,3.736812691819757677e-03,1.000000009950789082e+00,-4.000000000000000327e-05,9.466430041876426934e-11,0.000000000000000000e+00 +7.949588710359738286e+01,4.887731658667507872e+02,3.632786070087597186e-02,8.344253554591693600e+00,3.736666706418219960e-03,1.000000009950902546e+00,-4.000000000000000327e-05,4.387422073931086579e-10,0.000000000000000000e+00 +7.949708553314349047e+01,4.887831657969374533e+02,3.636522728098375706e-02,8.345451984149722335e+00,3.736520721016682242e-03,1.000000009951428348e+00,-4.000000000000000327e-05,-4.834640294026165369e-10,0.000000000000000000e+00 +7.949828379059185579e+01,4.887931657271295762e+02,3.640259240124772006e-02,8.346650241610014120e+00,3.736374735615144525e-03,1.000000009950849034e+00,-4.000000000000000327e-05,1.002465469676495904e-09,0.000000000000000000e+00 +7.949948187601661687e+01,4.888031656573271562e+02,3.643995606166785389e-02,8.347848327046690997e+00,3.736228750213606807e-03,1.000000009952050073e+00,-4.000000000000000327e-05,-1.328285950377518740e-09,0.000000000000000000e+00 +7.950067978949182645e+01,4.888131655875301931e+02,3.647731826224416551e-02,8.349046240533825269e+00,3.736082764812069090e-03,1.000000009950458901e+00,-4.000000000000000327e-05,1.150876706406877848e-09,0.000000000000000000e+00 +7.950187753109150890e+01,4.888231655177386870e+02,3.651467900297664798e-02,8.350243982145430621e+00,3.735936779410531372e-03,1.000000009951837354e+00,-4.000000000000000327e-05,-1.500359265794078200e-09,0.000000000000000000e+00 +7.950307510088963170e+01,4.888331654479526378e+02,3.655203828386530823e-02,8.351441551955474552e+00,3.735790794008993655e-03,1.000000009950040569e+00,-4.000000000000000327e-05,1.825464016335092069e-09,0.000000000000000000e+00 +7.950427249896010551e+01,4.888431653781720456e+02,3.658939610491013933e-02,8.352638950037864163e+00,3.735644808607455937e-03,1.000000009952226376e+00,-4.000000000000000327e-05,-1.295293437554621880e-09,0.000000000000000000e+00 +7.950546972537678414e+01,4.888531653083969104e+02,3.662675246611114127e-02,8.353836176466462149e+00,3.735498823205918219e-03,1.000000009950675617e+00,-4.000000000000000327e-05,2.504147742106105180e-10,0.000000000000000000e+00 +7.950666678021347877e+01,4.888631652386272322e+02,3.666410736746831406e-02,8.355033231315069031e+00,3.735352837804380502e-03,1.000000009950975377e+00,-4.000000000000000327e-05,2.307856425910680492e-10,0.000000000000000000e+00 +7.950786366354394374e+01,4.888731651688630109e+02,3.670146080898165769e-02,8.356230114657439145e+00,3.735206852402842784e-03,1.000000009951251601e+00,-4.000000000000000327e-05,-1.530751046939202073e-10,0.000000000000000000e+00 +7.950906037544186233e+01,4.888831650991042466e+02,3.673881279065116523e-02,8.357426826567271760e+00,3.735060867001305067e-03,1.000000009951068414e+00,-4.000000000000000327e-05,-9.380672374059164734e-10,0.000000000000000000e+00 +7.951025691598090361e+01,4.888931650293509392e+02,3.677616331247684361e-02,8.358623367118212855e+00,3.734914881599767349e-03,1.000000009949945978e+00,-4.000000000000000327e-05,1.561627649658451323e-09,0.000000000000000000e+00 +7.951145328523463718e+01,4.889031649596030888e+02,3.681351237445868591e-02,8.359819736383855115e+00,3.734768896198229632e-03,1.000000009951814262e+00,-4.000000000000000327e-05,-1.377710880566617668e-09,0.000000000000000000e+00 +7.951264948327661841e+01,4.889131648898606954e+02,3.685085997659669904e-02,8.361015934437743269e+00,3.734622910796691914e-03,1.000000009950166246e+00,-4.000000000000000327e-05,1.378650623199077449e-09,0.000000000000000000e+00 +7.951384551018033164e+01,4.889231648201237590e+02,3.688820611889087608e-02,8.362211961353361644e+00,3.734476925395154197e-03,1.000000009951815150e+00,-4.000000000000000327e-05,-1.381261655730884459e-09,0.000000000000000000e+00 +7.951504136601921857e+01,4.889331647503922227e+02,3.692555080134121703e-02,8.363407817204150163e+00,3.734330939993616479e-03,1.000000009950163360e+00,-4.000000000000000327e-05,2.412307410392820171e-10,0.000000000000000000e+00 +7.951623705086666405e+01,4.889431646806661433e+02,3.696289402394772189e-02,8.364603502063488349e+00,3.734184954592078762e-03,1.000000009950451796e+00,-4.000000000000000327e-05,1.242729520008074566e-09,0.000000000000000000e+00 +7.951743256479599609e+01,4.889531646109455210e+02,3.700023578671039065e-02,8.365799016004709543e+00,3.734038969190541044e-03,1.000000009951937496e+00,-4.000000000000000327e-05,-9.012980767421040843e-10,0.000000000000000000e+00 +7.951862790788048585e+01,4.889631645412303556e+02,3.703757608962922332e-02,8.366994359101093792e+00,3.733892983789003327e-03,1.000000009950860136e+00,-4.000000000000000327e-05,-1.263335250676066096e-11,0.000000000000000000e+00 +7.951982308019336187e+01,4.889731644715206471e+02,3.707491493270421296e-02,8.368189531425864303e+00,3.733746998387465609e-03,1.000000009950845037e+00,-4.000000000000000327e-05,1.440036287293510157e-10,0.000000000000000000e+00 +7.952101808180779585e+01,4.889831644018163956e+02,3.711225231593536650e-02,8.369384533052196318e+00,3.733601012985927892e-03,1.000000009951017121e+00,-4.000000000000000327e-05,-4.696117875685002179e-10,0.000000000000000000e+00 +7.952221291279691684e+01,4.889931643321176011e+02,3.714958823932267701e-02,8.370579364053211791e+00,3.733455027584390174e-03,1.000000009950456015e+00,-4.000000000000000327e-05,5.994120410928529204e-10,0.000000000000000000e+00 +7.952340757323379705e+01,4.890031642624242636e+02,3.718692270286615142e-02,8.371774024501979383e+00,3.733309042182852457e-03,1.000000009951172109e+00,-4.000000000000000327e-05,-4.195553676322953263e-10,0.000000000000000000e+00 +7.952460206319145186e+01,4.890131641927363830e+02,3.722425570656578281e-02,8.372968514471518020e+00,3.733163056781314739e-03,1.000000009950670954e+00,-4.000000000000000327e-05,1.714157031949601329e-10,0.000000000000000000e+00 +7.952579638274283980e+01,4.890231641230539594e+02,3.726158725042157116e-02,8.374162834034791558e+00,3.733017071379777022e-03,1.000000009950875679e+00,-4.000000000000000327e-05,-1.537754959756559152e-10,0.000000000000000000e+00 +7.952699053196087675e+01,4.890331640533769360e+02,3.729891733443351648e-02,8.375356983264714117e+00,3.732871085978239304e-03,1.000000009950692048e+00,-4.000000000000000327e-05,-1.865281940952480694e-10,0.000000000000000000e+00 +7.952818451091842178e+01,4.890431639837053694e+02,3.733624595860161877e-02,8.376550962234146525e+00,3.732725100576701587e-03,1.000000009950469337e+00,-4.000000000000000327e-05,3.701336218596907061e-11,0.000000000000000000e+00 +7.952937831968829130e+01,4.890531639140392599e+02,3.737357312292587802e-02,8.377744771015898095e+00,3.732579115175163869e-03,1.000000009950513524e+00,-4.000000000000000327e-05,-7.660439608657358467e-10,0.000000000000000000e+00 +7.953057195834324489e+01,4.890631638443786073e+02,3.741089882740628730e-02,8.378938409682726629e+00,3.732433129773626151e-03,1.000000009949599145e+00,-4.000000000000000327e-05,1.108856849046025900e-09,0.000000000000000000e+00 +7.953176542695598528e+01,4.890731637747234117e+02,3.744822307204285355e-02,8.380131878307336635e+00,3.732287144372088434e-03,1.000000009950922530e+00,-4.000000000000000327e-05,6.376835048218341002e-10,0.000000000000000000e+00 +7.953295872559915836e+01,4.890831637050736731e+02,3.748554585683556983e-02,8.381325176962384660e+00,3.732141158970550716e-03,1.000000009951683477e+00,-4.000000000000000327e-05,-9.701539160357188130e-10,0.000000000000000000e+00 +7.953415185434536738e+01,4.890931636354293914e+02,3.752286718178444308e-02,8.382518305720472185e+00,3.731995173569012999e-03,1.000000009950525959e+00,-4.000000000000000327e-05,-7.259042565335125603e-12,0.000000000000000000e+00 +7.953534481326717298e+01,4.891031635657905099e+02,3.756018704688946636e-02,8.383711264654147399e+00,3.731849188167475281e-03,1.000000009950517299e+00,-4.000000000000000327e-05,-2.529857125713737964e-10,0.000000000000000000e+00 +7.953653760243706472e+01,4.891131634961570853e+02,3.759750545215063966e-02,8.384904053835910531e+00,3.731703202765937564e-03,1.000000009950215540e+00,-4.000000000000000327e-05,7.536658321855630470e-10,0.000000000000000000e+00 +7.953773022192748954e+01,4.891231634265291177e+02,3.763482239756796299e-02,8.386096673338208518e+00,3.731557217364399846e-03,1.000000009951114377e+00,-4.000000000000000327e-05,-7.709042343955237477e-10,0.000000000000000000e+00 +7.953892267181085174e+01,4.891331633569066071e+02,3.767213788314143635e-02,8.387289123233438559e+00,3.731411231962862129e-03,1.000000009950195112e+00,-4.000000000000000327e-05,1.340893655827474371e-10,0.000000000000000000e+00 +7.954011495215949878e+01,4.891431632872895534e+02,3.770945190887105281e-02,8.388481403593942787e+00,3.731265246561324411e-03,1.000000009950354984e+00,-4.000000000000000327e-05,-3.149685413256743488e-10,0.000000000000000000e+00 +7.954130706304570708e+01,4.891531632176779567e+02,3.774676447475681929e-02,8.389673514492015372e+00,3.731119261159786694e-03,1.000000009949979507e+00,-4.000000000000000327e-05,3.451919866027375822e-10,0.000000000000000000e+00 +7.954249900454172462e+01,4.891631631480717601e+02,3.778407558079872886e-02,8.390865455999897193e+00,3.730973275758248976e-03,1.000000009950390956e+00,-4.000000000000000327e-05,8.289138356541669024e-10,0.000000000000000000e+00 +7.954369077671974253e+01,4.891731630784710205e+02,3.782138522699678845e-02,8.392057228189779394e+00,3.730827290356711259e-03,1.000000009951378832e+00,-4.000000000000000327e-05,-1.402216801385593862e-09,0.000000000000000000e+00 +7.954488237965190933e+01,4.891831630088757379e+02,3.785869341335099114e-02,8.393248831133801602e+00,3.730681304955173541e-03,1.000000009949707946e+00,-4.000000000000000327e-05,1.122678193937743361e-09,0.000000000000000000e+00 +7.954607381341030248e+01,4.891931629392859122e+02,3.789600013986133692e-02,8.394440264904048377e+00,3.730535319553635824e-03,1.000000009951045543e+00,-4.000000000000000327e-05,-1.642690473748750964e-09,0.000000000000000000e+00 +7.954726507806695679e+01,4.892031628697015435e+02,3.793330540652782579e-02,8.395631529572559870e+00,3.730389334152098106e-03,1.000000009949088664e+00,-4.000000000000000327e-05,1.530325626803133876e-09,0.000000000000000000e+00 +7.954845617369386446e+01,4.892131628001225749e+02,3.797060921335045774e-02,8.396822625211317614e+00,3.730243348750560389e-03,1.000000009950911428e+00,-4.000000000000000327e-05,-6.603949773364644552e-10,0.000000000000000000e+00 +7.954964710036296083e+01,4.892231627305490633e+02,3.800791156032923279e-02,8.398013551892260509e+00,3.730097363349022671e-03,1.000000009950124946e+00,-4.000000000000000327e-05,5.135476337938824282e-10,0.000000000000000000e+00 +7.955083785814612440e+01,4.892331626609810087e+02,3.804521244746415093e-02,8.399204309687268832e+00,3.729951377947484954e-03,1.000000009950736457e+00,-4.000000000000000327e-05,7.646491810779433127e-12,0.000000000000000000e+00 +7.955202844711519106e+01,4.892431625914184110e+02,3.808251187475520522e-02,8.400394898668176680e+00,3.729805392545947236e-03,1.000000009950745561e+00,-4.000000000000000327e-05,-9.626619073449852479e-10,0.000000000000000000e+00 +7.955321886734193981e+01,4.892531625218612703e+02,3.811980984220240259e-02,8.401585318906764854e+00,3.729659407144409519e-03,1.000000009949599589e+00,-4.000000000000000327e-05,1.329374321346712430e-09,0.000000000000000000e+00 +7.955440911889809286e+01,4.892631624523095297e+02,3.815710634980573612e-02,8.402775570474762645e+00,3.729513421742871801e-03,1.000000009951181879e+00,-4.000000000000000327e-05,-1.929414454299827545e-09,0.000000000000000000e+00 +7.955559920185534395e+01,4.892731623827632461e+02,3.819440139756520580e-02,8.403965653443853157e+00,3.729367436341334083e-03,1.000000009948885715e+00,-4.000000000000000327e-05,1.766594489386385160e-09,0.000000000000000000e+00 +7.955678911628531580e+01,4.892831623132224195e+02,3.823169498548081163e-02,8.405155567885660872e+00,3.729221450939796366e-03,1.000000009950987812e+00,-4.000000000000000327e-05,-1.608767363662764225e-10,0.000000000000000000e+00 +7.955797886225958848e+01,4.892931622436870498e+02,3.826898711355255361e-02,8.406345313871769420e+00,3.729075465538258648e-03,1.000000009950796409e+00,-4.000000000000000327e-05,-1.476654305011306019e-09,0.000000000000000000e+00 +7.955916843984968523e+01,4.893031621741571371e+02,3.830627778178043175e-02,8.407534891473703809e+00,3.728929480136720931e-03,1.000000009949039814e+00,-4.000000000000000327e-05,1.551910545690058384e-09,0.000000000000000000e+00 +7.956035784912708664e+01,4.893131621046326245e+02,3.834356699016444603e-02,8.408724300762939308e+00,3.728783494735183213e-03,1.000000009950885671e+00,-4.000000000000000327e-05,-1.154621977493120400e-09,0.000000000000000000e+00 +7.956154709016321647e+01,4.893231620351135689e+02,3.838085473870459646e-02,8.409913541810906779e+00,3.728637509333645496e-03,1.000000009949512547e+00,-4.000000000000000327e-05,4.139972436466528479e-10,0.000000000000000000e+00 +7.956273616302945584e+01,4.893331619655999702e+02,3.841814102740087611e-02,8.411102614688978463e+00,3.728491523932107778e-03,1.000000009950004820e+00,-4.000000000000000327e-05,-5.771007467323162897e-11,0.000000000000000000e+00 +7.956392506779712903e+01,4.893431618960918286e+02,3.845542585625329191e-02,8.412291519468482193e+00,3.728345538530570061e-03,1.000000009949936208e+00,-4.000000000000000327e-05,1.165011691715565532e-09,0.000000000000000000e+00 +7.956511380453751769e+01,4.893531618265890870e+02,3.849270922526183691e-02,8.413480256220692510e+00,3.728199553129032343e-03,1.000000009951321100e+00,-4.000000000000000327e-05,-9.815354144167791972e-10,0.000000000000000000e+00 +7.956630237332183242e+01,4.893631617570918024e+02,3.852999113442651113e-02,8.414668825016835996e+00,3.728053567727494626e-03,1.000000009950154478e+00,-4.000000000000000327e-05,-2.470066859199761387e-10,0.000000000000000000e+00 +7.956749077422125538e+01,4.893731616875999748e+02,3.856727158374731457e-02,8.415857225928084162e+00,3.727907582325956908e-03,1.000000009949860935e+00,-4.000000000000000327e-05,-4.380222704009157103e-10,0.000000000000000000e+00 +7.956867900730691190e+01,4.893831616181136042e+02,3.860455057322424721e-02,8.417045459025562337e+00,3.727761596924419191e-03,1.000000009949340463e+00,-4.000000000000000327e-05,9.266301367516213448e-10,0.000000000000000000e+00 +7.956986707264987047e+01,4.893931615486326336e+02,3.864182810285730907e-02,8.418233524380344335e+00,3.727615611522881473e-03,1.000000009950441360e+00,-4.000000000000000327e-05,-1.222845907122765098e-09,0.000000000000000000e+00 +7.957105497032115693e+01,4.894031614791571201e+02,3.867910417264650014e-02,8.419421422063456006e+00,3.727469626121343756e-03,1.000000009948988744e+00,-4.000000000000000327e-05,1.890425358917051073e-09,0.000000000000000000e+00 +7.957224270039175451e+01,4.894131614096870635e+02,3.871637878259181348e-02,8.420609152145868137e+00,3.727323640719806038e-03,1.000000009951234059e+00,-4.000000000000000327e-05,-1.100161389793769855e-09,0.000000000000000000e+00 +7.957343026293257537e+01,4.894231613402224639e+02,3.875365193269325603e-02,8.421796714698508879e+00,3.727177655318268321e-03,1.000000009949927549e+00,-4.000000000000000327e-05,-1.563332142293195384e-10,0.000000000000000000e+00 +7.957461765801450326e+01,4.894331612707632644e+02,3.879092362295082086e-02,8.422984109792247764e+00,3.727031669916730603e-03,1.000000009949741919e+00,-4.000000000000000327e-05,-3.493679638276052128e-10,0.000000000000000000e+00 +7.957580488570835087e+01,4.894431612013095219e+02,3.882819385336451490e-02,8.424171337497909917e+00,3.726885684515192886e-03,1.000000009949327140e+00,-4.000000000000000327e-05,8.048941350147999296e-10,0.000000000000000000e+00 +7.957699194608490245e+01,4.894531611318612363e+02,3.886546262393433121e-02,8.425358397886268946e+00,3.726739699113655168e-03,1.000000009950282598e+00,-4.000000000000000327e-05,-5.094203041054859536e-10,0.000000000000000000e+00 +7.957817883921487123e+01,4.894631610624183509e+02,3.890272993466026979e-02,8.426545291028050499e+00,3.726593713712117450e-03,1.000000009949677970e+00,-4.000000000000000327e-05,7.153096481271655646e-10,0.000000000000000000e+00 +7.957936556516894200e+01,4.894731609929809224e+02,3.893999578554233065e-02,8.427732016993926933e+00,3.726447728310579733e-03,1.000000009950526847e+00,-4.000000000000000327e-05,-5.995749093312361404e-10,0.000000000000000000e+00 +7.958055212401772849e+01,4.894831609235489509e+02,3.897726017658051378e-02,8.428918575854524420e+00,3.726301742909042015e-03,1.000000009949815416e+00,-4.000000000000000327e-05,-7.057788120500821451e-10,0.000000000000000000e+00 +7.958173851583181602e+01,4.894931608541223795e+02,3.901452310777481225e-02,8.430104967680415839e+00,3.726155757507504298e-03,1.000000009948978086e+00,-4.000000000000000327e-05,3.635150813082825623e-10,0.000000000000000000e+00 +7.958292474068171884e+01,4.895031607847012651e+02,3.905178457912523299e-02,8.431291192542126112e+00,3.726009772105966580e-03,1.000000009949409296e+00,-4.000000000000000327e-05,1.312170815748809013e-09,0.000000000000000000e+00 +7.958411079863792281e+01,4.895131607152856077e+02,3.908904459063176906e-02,8.432477250510132194e+00,3.725863786704428863e-03,1.000000009950965607e+00,-4.000000000000000327e-05,-1.684585755842064158e-09,0.000000000000000000e+00 +7.958529668977085691e+01,4.895231606458754072e+02,3.912630314229442741e-02,8.433663141654861306e+00,3.725717801302891145e-03,1.000000009948967872e+00,-4.000000000000000327e-05,1.793998125544450931e-10,0.000000000000000000e+00 +7.958648241415087909e+01,4.895331605764706069e+02,3.916356023411320109e-02,8.434848866046685600e+00,3.725571815901353428e-03,1.000000009949180590e+00,-4.000000000000000327e-05,5.551313195564761077e-10,0.000000000000000000e+00 +7.958766797184833308e+01,4.895431605070712635e+02,3.920081586608809010e-02,8.436034423755934597e+00,3.725425830499815710e-03,1.000000009949838731e+00,-4.000000000000000327e-05,6.709716183971038739e-10,0.000000000000000000e+00 +7.958885336293349155e+01,4.895531604376773771e+02,3.923807003821909445e-02,8.437219814852886302e+00,3.725279845098277993e-03,1.000000009950634094e+00,-4.000000000000000327e-05,-7.731683332656360948e-10,0.000000000000000000e+00 +7.959003858747658455e+01,4.895631603682888908e+02,3.927532275050621413e-02,8.438405039407768982e+00,3.725133859696740275e-03,1.000000009949717716e+00,-4.000000000000000327e-05,-1.817491243777510818e-11,0.000000000000000000e+00 +7.959122364554778528e+01,4.895731602989058615e+02,3.931257400294944915e-02,8.439590097490759391e+00,3.724987874295202558e-03,1.000000009949696178e+00,-4.000000000000000327e-05,-8.918201571441412716e-10,0.000000000000000000e+00 +7.959240853721722431e+01,4.895831602295282892e+02,3.934982379554879950e-02,8.440774989171988096e+00,3.724841888893664840e-03,1.000000009948639468e+00,-4.000000000000000327e-05,1.631703373655287324e-09,0.000000000000000000e+00 +7.959359326255498956e+01,4.895931601601561169e+02,3.938707212830425825e-02,8.441959714521534153e+00,3.724695903492127123e-03,1.000000009950572588e+00,-4.000000000000000327e-05,-1.340448950027794855e-09,0.000000000000000000e+00 +7.959477782163109794e+01,4.896031600907894017e+02,3.942431900121583233e-02,8.443144273609432204e+00,3.724549918090589405e-03,1.000000009948984747e+00,-4.000000000000000327e-05,2.830879498183556555e-10,0.000000000000000000e+00 +7.959596221451553788e+01,4.896131600214281434e+02,3.946156441428351480e-02,8.444328666505660053e+00,3.724403932689051688e-03,1.000000009949320035e+00,-4.000000000000000327e-05,1.385638023109799165e-10,0.000000000000000000e+00 +7.959714644127825522e+01,4.896231599520722853e+02,3.949880836750730567e-02,8.445512893280152866e+00,3.724257947287513970e-03,1.000000009949484125e+00,-4.000000000000000327e-05,7.242333575929281639e-10,0.000000000000000000e+00 +7.959833050198911053e+01,4.896331598827218841e+02,3.953605086088720494e-02,8.446696954002794300e+00,3.724111961885976253e-03,1.000000009950341662e+00,-4.000000000000000327e-05,-5.283406005901685955e-10,0.000000000000000000e+00 +7.959951439671795015e+01,4.896431598133769398e+02,3.957329189442321260e-02,8.447880848743420046e+00,3.723965976484438535e-03,1.000000009949716162e+00,-4.000000000000000327e-05,-1.119856400211243718e-09,0.000000000000000000e+00 +7.960069812553456359e+01,4.896531597440373957e+02,3.961053146811532866e-02,8.449064577571814283e+00,3.723819991082900818e-03,1.000000009948390556e+00,-4.000000000000000327e-05,1.452452779372692343e-09,0.000000000000000000e+00 +7.960188168850868351e+01,4.896631596747033086e+02,3.964776958196355311e-02,8.450248140557713228e+00,3.723674005681363100e-03,1.000000009950109625e+00,-4.000000000000000327e-05,-4.531341803881012261e-10,0.000000000000000000e+00 +7.960306508570999995e+01,4.896731596053746216e+02,3.968500623596788596e-02,8.451431537770808688e+00,3.723528020279825382e-03,1.000000009949573387e+00,-4.000000000000000327e-05,-5.312639813277266581e-10,0.000000000000000000e+00 +7.960424831720816030e+01,4.896831595360513916e+02,3.972224143012832026e-02,8.452614769280737406e+00,3.723382034878287665e-03,1.000000009948944779e+00,-4.000000000000000327e-05,-8.352015906276496001e-11,0.000000000000000000e+00 +7.960543138307274091e+01,4.896931594667336185e+02,3.975947516444486296e-02,8.453797835157089935e+00,3.723236049476749947e-03,1.000000009948845969e+00,-4.000000000000000327e-05,8.569053714933464282e-10,0.000000000000000000e+00 +7.960661428337328971e+01,4.897031593974212456e+02,3.979670743891750712e-02,8.454980735469408870e+00,3.723090064075212230e-03,1.000000009949859603e+00,-4.000000000000000327e-05,-2.836725497011699399e-10,0.000000000000000000e+00 +7.960779701817929777e+01,4.897131593281143296e+02,3.983393825354625273e-02,8.456163470287188844e+00,3.722944078673674512e-03,1.000000009949524093e+00,-4.000000000000000327e-05,2.698176550364792357e-10,0.000000000000000000e+00 +7.960897958756021353e+01,4.897231592588128706e+02,3.987116760833109980e-02,8.457346039679872973e+00,3.722798093272136795e-03,1.000000009949843172e+00,-4.000000000000000327e-05,-1.327868789293171347e-09,0.000000000000000000e+00 +7.961016199158542861e+01,4.897331591895168117e+02,3.990839550327204832e-02,8.458528443716858192e+00,3.722652107870599077e-03,1.000000009948273094e+00,-4.000000000000000327e-05,1.243724575645655551e-09,0.000000000000000000e+00 +7.961134423032430618e+01,4.897431591202262098e+02,3.994562193836909830e-02,8.459710682467489917e+00,3.722506122469061360e-03,1.000000009949743474e+00,-4.000000000000000327e-05,3.253446157377146892e-10,0.000000000000000000e+00 +7.961252630384612416e+01,4.897531590509410080e+02,3.998284691362224974e-02,8.460892756001070936e+00,3.722360137067523642e-03,1.000000009950128055e+00,-4.000000000000000327e-05,-1.576037729879974944e-09,0.000000000000000000e+00 +7.961370821222014627e+01,4.897631589816612632e+02,4.002007042903149570e-02,8.462074664386850742e+00,3.722214151665985925e-03,1.000000009948265323e+00,-4.000000000000000327e-05,5.922475697006069692e-10,0.000000000000000000e+00 +7.961488995551556513e+01,4.897731589123869753e+02,4.005729248459684311e-02,8.463256407694029093e+00,3.722068166264448207e-03,1.000000009948965207e+00,-4.000000000000000327e-05,4.391738134219768235e-10,0.000000000000000000e+00 +7.961607153380154500e+01,4.897831588431180876e+02,4.009451308031828504e-02,8.464437985991763114e+00,3.721922180862910490e-03,1.000000009949484125e+00,-4.000000000000000327e-05,4.734417144261649149e-10,0.000000000000000000e+00 +7.961725294714717904e+01,4.897931587738546568e+02,4.013173221619582842e-02,8.465619399349158414e+00,3.721776195461372772e-03,1.000000009950043456e+00,-4.000000000000000327e-05,-6.114810859010958346e-10,0.000000000000000000e+00 +7.961843419562154622e+01,4.898031587045966262e+02,4.016894989222946633e-02,8.466800647835272642e+00,3.721630210059835055e-03,1.000000009949321145e+00,-4.000000000000000327e-05,-3.030571936582062379e-10,0.000000000000000000e+00 +7.961961527929364024e+01,4.898131586353440525e+02,4.020616610841919875e-02,8.467981731519113708e+00,3.721484224658297337e-03,1.000000009948963209e+00,-4.000000000000000327e-05,9.232124021209841738e-11,0.000000000000000000e+00 +7.962079619823242638e+01,4.898231585660969358e+02,4.024338086476502568e-02,8.469162650469643339e+00,3.721338239256759620e-03,1.000000009949072233e+00,-4.000000000000000327e-05,-7.335954843475284921e-10,0.000000000000000000e+00 +7.962197695250681306e+01,4.898331584968552193e+02,4.028059416126694714e-02,8.470343404755775296e+00,3.721192253855221902e-03,1.000000009948206037e+00,-4.000000000000000327e-05,1.008857931042105969e-09,0.000000000000000000e+00 +7.962315754218566610e+01,4.898431584276189596e+02,4.031780599792495617e-02,8.471523994446373607e+00,3.721046268453684185e-03,1.000000009949397084e+00,-4.000000000000000327e-05,1.886699367055147471e-10,0.000000000000000000e+00 +7.962433796733780866e+01,4.898531583583881002e+02,4.035501637473905973e-02,8.472704419610257887e+00,3.720900283052146467e-03,1.000000009949619795e+00,-4.000000000000000327e-05,-6.802846992684117922e-10,0.000000000000000000e+00 +7.962551822803200707e+01,4.898631582891626977e+02,4.039222529170925086e-02,8.473884680316196238e+00,3.720754297650608750e-03,1.000000009948816881e+00,-4.000000000000000327e-05,-3.550542169551787298e-10,0.000000000000000000e+00 +7.962669832433698502e+01,4.898731582199426953e+02,4.042943274883553650e-02,8.475064776632908803e+00,3.720608312249071032e-03,1.000000009948397883e+00,-4.000000000000000327e-05,1.131740025398959828e-09,0.000000000000000000e+00 +7.962787825632140937e+01,4.898831581507281498e+02,4.046663874611790973e-02,8.476244708629069535e+00,3.720462326847533314e-03,1.000000009949733260e+00,-4.000000000000000327e-05,-1.358126540506429374e-09,0.000000000000000000e+00 +7.962905802405390432e+01,4.898931580815190046e+02,4.050384328355637054e-02,8.477424476373306206e+00,3.720316341445995597e-03,1.000000009948130986e+00,-4.000000000000000327e-05,1.075584143039810953e-09,0.000000000000000000e+00 +7.963023762760305146e+01,4.899031580123153162e+02,4.054104636115091892e-02,8.478604079934193294e+00,3.720170356044457879e-03,1.000000009949399749e+00,-4.000000000000000327e-05,-5.352312237694813636e-10,0.000000000000000000e+00 +7.963141706703738976e+01,4.899131579431170849e+02,4.057824797890155488e-02,8.479783519380264423e+00,3.720024370642920162e-03,1.000000009948768476e+00,-4.000000000000000327e-05,1.587276422929120994e-10,0.000000000000000000e+00 +7.963259634242538709e+01,4.899231578739242536e+02,4.061544813680827842e-02,8.480962794779999925e+00,3.719878385241382444e-03,1.000000009948955659e+00,-4.000000000000000327e-05,5.715366420612721486e-10,0.000000000000000000e+00 +7.963377545383549716e+01,4.899331578047368794e+02,4.065264683487108954e-02,8.482141906201835724e+00,3.719732399839844727e-03,1.000000009949629565e+00,-4.000000000000000327e-05,-6.090960385986385154e-10,0.000000000000000000e+00 +7.963495440133608838e+01,4.899431577355549052e+02,4.068984407308998130e-02,8.483320853714159782e+00,3.719586414438307009e-03,1.000000009948911472e+00,-4.000000000000000327e-05,-8.606513941660230965e-10,0.000000000000000000e+00 +7.963613318499551497e+01,4.899531576663783881e+02,4.072703985146496064e-02,8.484499637385310322e+00,3.719440429036769292e-03,1.000000009947896951e+00,-4.000000000000000327e-05,1.062917464136957039e-09,0.000000000000000000e+00 +7.963731180488206007e+01,4.899631575972072710e+02,4.076423416999602062e-02,8.485678257283579384e+00,3.719294443635231574e-03,1.000000009949149726e+00,-4.000000000000000327e-05,1.450833288642784739e-11,0.000000000000000000e+00 +7.963849026106396423e+01,4.899731575280416109e+02,4.080142702868316124e-02,8.486856713477214598e+00,3.719148458233693857e-03,1.000000009949166824e+00,-4.000000000000000327e-05,-2.038986527171348163e-10,0.000000000000000000e+00 +7.963966855360943953e+01,4.899831574588813510e+02,4.083861842752638249e-02,8.488035006034412078e+00,3.719002472832156139e-03,1.000000009948926571e+00,-4.000000000000000327e-05,-9.046667421622784465e-10,0.000000000000000000e+00 +7.964084668258662703e+01,4.899931573897265480e+02,4.087580836652568439e-02,8.489213135023321755e+00,3.718856487430618422e-03,1.000000009947860757e+00,-4.000000000000000327e-05,1.720236377127878005e-09,0.000000000000000000e+00 +7.964202464806363935e+01,4.900031573205771451e+02,4.091299684568106693e-02,8.490391100512045597e+00,3.718710502029080704e-03,1.000000009949887136e+00,-4.000000000000000327e-05,-1.324384990144469813e-09,0.000000000000000000e+00 +7.964320245010851806e+01,4.900131572514331992e+02,4.095018386499253010e-02,8.491568902568642940e+00,3.718564516627542987e-03,1.000000009948327273e+00,-4.000000000000000327e-05,1.713925919507563217e-10,0.000000000000000000e+00 +7.964438008878927633e+01,4.900231571822946535e+02,4.098736942446006698e-02,8.492746541261118054e+00,3.718418531226005269e-03,1.000000009948529112e+00,-4.000000000000000327e-05,-2.278008408983163080e-10,0.000000000000000000e+00 +7.964555756417388466e+01,4.900331571131615647e+02,4.102455352408368450e-02,8.493924016657434350e+00,3.718272545824467552e-03,1.000000009948260882e+00,-4.000000000000000327e-05,1.288158491736141595e-09,0.000000000000000000e+00 +7.964673487633024251e+01,4.900431570440338760e+02,4.106173616386337571e-02,8.495101328825505504e+00,3.718126560422929834e-03,1.000000009949777446e+00,-4.000000000000000327e-05,-1.721806806676422760e-09,0.000000000000000000e+00 +7.964791202532622094e+01,4.900531569749116443e+02,4.109891734379914757e-02,8.496278477833200782e+00,3.717980575021392117e-03,1.000000009947750623e+00,-4.000000000000000327e-05,9.636511691895496503e-10,0.000000000000000000e+00 +7.964908901122964835e+01,4.900631569057948127e+02,4.113609706389099313e-02,8.497455463748336157e+00,3.717834589619854399e-03,1.000000009948884827e+00,-4.000000000000000327e-05,3.386831383662305997e-10,0.000000000000000000e+00 +7.965026583410829630e+01,4.900731568366834381e+02,4.117327532413891239e-02,8.498632286638688527e+00,3.717688604218316682e-03,1.000000009949283397e+00,-4.000000000000000327e-05,-1.067329873665832569e-09,0.000000000000000000e+00 +7.965144249402987953e+01,4.900831567675774636e+02,4.121045212454290535e-02,8.499808946571983270e+00,3.717542618816778964e-03,1.000000009948027513e+00,-4.000000000000000327e-05,5.628038097488830362e-10,0.000000000000000000e+00 +7.965261899106208432e+01,4.900931566984769461e+02,4.124762746510297201e-02,8.500985443615897807e+00,3.717396633415241246e-03,1.000000009948689650e+00,-4.000000000000000327e-05,6.436709024166866784e-11,0.000000000000000000e+00 +7.965379532527255435e+01,4.901031566293818287e+02,4.128480134581911237e-02,8.502161777838066925e+00,3.717250648013703529e-03,1.000000009948765367e+00,-4.000000000000000327e-05,-3.001696053220321081e-11,0.000000000000000000e+00 +7.965497149672886223e+01,4.901131565602921683e+02,4.132197376669131950e-02,8.503337949306075672e+00,3.717104662612165811e-03,1.000000009948730062e+00,-4.000000000000000327e-05,-1.036578053208233603e-09,0.000000000000000000e+00 +7.965614750549855216e+01,4.901231564912079079e+02,4.135914472771960032e-02,8.504513958087462910e+00,3.716958677210628094e-03,1.000000009947511037e+00,-4.000000000000000327e-05,8.656340529683099037e-10,0.000000000000000000e+00 +7.965732335164911149e+01,4.901331564221291046e+02,4.139631422890394791e-02,8.505689804249719543e+00,3.716812691809090376e-03,1.000000009948528890e+00,-4.000000000000000327e-05,5.059673343762448958e-10,0.000000000000000000e+00 +7.965849903524798492e+01,4.901431563530557014e+02,4.143348227024436226e-02,8.506865487860293840e+00,3.716666706407552659e-03,1.000000009949123747e+00,-4.000000000000000327e-05,-8.651178425722638027e-10,0.000000000000000000e+00 +7.965967455636257455e+01,4.901531562839876983e+02,4.147064885174085030e-02,8.508041008986584330e+00,3.716520721006014941e-03,1.000000009948106783e+00,-4.000000000000000327e-05,5.767619537619070830e-10,0.000000000000000000e+00 +7.966084991506023982e+01,4.901631562149251522e+02,4.150781397339340512e-02,8.509216367695941585e+00,3.716374735604477224e-03,1.000000009948784685e+00,-4.000000000000000327e-05,-3.433086290827952266e-10,0.000000000000000000e+00 +7.966202511140828335e+01,4.901731561458680062e+02,4.154497763520202669e-02,8.510391564055673541e+00,3.716228750202939506e-03,1.000000009948381230e+00,-4.000000000000000327e-05,1.995508978423552596e-10,0.000000000000000000e+00 +7.966320014547396511e+01,4.901831560768163172e+02,4.158213983716670809e-02,8.511566598133038397e+00,3.716082764801401789e-03,1.000000009948615709e+00,-4.000000000000000327e-05,-3.993458946162122726e-10,0.000000000000000000e+00 +7.966437501732448823e+01,4.901931560077700283e+02,4.161930057928745624e-02,8.512741469995249943e+00,3.715936779399864071e-03,1.000000009948146529e+00,-4.000000000000000327e-05,4.007241631052133860e-10,0.000000000000000000e+00 +7.966554972702702742e+01,4.902031559387291964e+02,4.165645986156427116e-02,8.513916179709474008e+00,3.715790793998326354e-03,1.000000009948617263e+00,-4.000000000000000327e-05,-1.294404230078222563e-09,0.000000000000000000e+00 +7.966672427464870054e+01,4.902131558696937645e+02,4.169361768399714591e-02,8.515090727342832011e+00,3.715644808596788636e-03,1.000000009947096924e+00,-4.000000000000000327e-05,9.211636347842116485e-10,0.000000000000000000e+00 +7.966789866025658284e+01,4.902231558006637897e+02,4.173077404658608741e-02,8.516265112962395634e+00,3.715498823195250919e-03,1.000000009948178725e+00,-4.000000000000000327e-05,5.763739722011025361e-10,0.000000000000000000e+00 +7.966907288391770692e+01,4.902331557316392150e+02,4.176792894933108874e-02,8.517439336635195701e+00,3.715352837793713201e-03,1.000000009948855517e+00,-4.000000000000000327e-05,-1.074798200442157708e-09,0.000000000000000000e+00 +7.967024694569904852e+01,4.902431556626200404e+02,4.180508239223214989e-02,8.518613398428213301e+00,3.715206852392175484e-03,1.000000009947593638e+00,-4.000000000000000327e-05,1.090835054922923025e-09,0.000000000000000000e+00 +7.967142084566754079e+01,4.902531555936063228e+02,4.184223437528927086e-02,8.519787298408381560e+00,3.715060866990637766e-03,1.000000009948874169e+00,-4.000000000000000327e-05,-6.923888465276623310e-10,0.000000000000000000e+00 +7.967259458389007420e+01,4.902631555245980053e+02,4.187938489850245166e-02,8.520961036642592745e+00,3.714914881589100049e-03,1.000000009948061486e+00,-4.000000000000000327e-05,-1.191981058986620690e-11,0.000000000000000000e+00 +7.967376816043349663e+01,4.902731554555951448e+02,4.191653396187169228e-02,8.522134613197687614e+00,3.714768896187562331e-03,1.000000009948047497e+00,-4.000000000000000327e-05,5.232192946789472586e-10,0.000000000000000000e+00 +7.967494157536459909e+01,4.902831553865976844e+02,4.195368156539698579e-02,8.523308028140464288e+00,3.714622910786024614e-03,1.000000009948661450e+00,-4.000000000000000327e-05,-4.106843403365269245e-10,0.000000000000000000e+00 +7.967611482875014417e+01,4.902931553176056241e+02,4.199082770907833911e-02,8.524481281537674704e+00,3.714476925384486896e-03,1.000000009948179613e+00,-4.000000000000000327e-05,-2.653726739846500250e-10,0.000000000000000000e+00 +7.967728792065682342e+01,4.903031552486190208e+02,4.202797239291574533e-02,8.525654373456022839e+00,3.714330939982949178e-03,1.000000009947868307e+00,-4.000000000000000327e-05,-3.627132767367977258e-10,0.000000000000000000e+00 +7.967846085115129995e+01,4.903131551796378176e+02,4.206511561690921136e-02,8.526827303962168259e+00,3.714184954581411461e-03,1.000000009947442869e+00,-4.000000000000000327e-05,5.558834495918524502e-10,0.000000000000000000e+00 +7.967963362030019425e+01,4.903231551106620714e+02,4.210225738105873028e-02,8.528000073122724345e+00,3.714038969179873743e-03,1.000000009948094792e+00,-4.000000000000000327e-05,1.168348983141935964e-09,0.000000000000000000e+00 +7.968080622817006997e+01,4.903331550416917253e+02,4.213939768536430208e-02,8.529172681004260070e+00,3.713892983778336026e-03,1.000000009949464808e+00,-4.000000000000000327e-05,-2.435878588237834181e-09,0.000000000000000000e+00 +7.968197867482744812e+01,4.903431549727267793e+02,4.217653652982592677e-02,8.530345127673298222e+00,3.713746998376798308e-03,1.000000009946608870e+00,-4.000000000000000327e-05,1.342171386802104363e-09,0.000000000000000000e+00 +7.968315096033879286e+01,4.903531549037672903e+02,4.221367391444360434e-02,8.531517413196310073e+00,3.713601012975260591e-03,1.000000009948182278e+00,-4.000000000000000327e-05,8.401563828536325195e-10,0.000000000000000000e+00 +7.968432308477055415e+01,4.903631548348132014e+02,4.225080983921733480e-02,8.532689537639731370e+00,3.713455027573722873e-03,1.000000009949167046e+00,-4.000000000000000327e-05,-1.391421910233474383e-09,0.000000000000000000e+00 +7.968549504818911089e+01,4.903731547658645127e+02,4.228794430414711120e-02,8.533861501069946343e+00,3.713309042172185156e-03,1.000000009947536350e+00,-4.000000000000000327e-05,-2.112811164621362351e-10,0.000000000000000000e+00 +7.968666685066079935e+01,4.903831546969212809e+02,4.232507730923294048e-02,8.535033303553291262e+00,3.713163056770647438e-03,1.000000009947288770e+00,-4.000000000000000327e-05,4.703782399011317547e-10,0.000000000000000000e+00 +7.968783849225191318e+01,4.903931546279834492e+02,4.236220885447481571e-02,8.536204945156061541e+00,3.713017071369109721e-03,1.000000009947839885e+00,-4.000000000000000327e-05,6.205599365580947679e-10,0.000000000000000000e+00 +7.968900997302870337e+01,4.904031545590510746e+02,4.239933893987274383e-02,8.537376425944506408e+00,3.712871085967572003e-03,1.000000009948566859e+00,-4.000000000000000327e-05,-1.087550684078922481e-09,0.000000000000000000e+00 +7.969018129305737830e+01,4.904131544901241000e+02,4.243646756542671789e-02,8.538547745984828907e+00,3.712725100566034286e-03,1.000000009947292989e+00,-4.000000000000000327e-05,4.927544059854975611e-10,0.000000000000000000e+00 +7.969135245240408949e+01,4.904231544212025256e+02,4.247359473113673789e-02,8.539718905343184119e+00,3.712579115164496568e-03,1.000000009947870083e+00,-4.000000000000000327e-05,1.513166411385182892e-10,0.000000000000000000e+00 +7.969252345113494584e+01,4.904331543522864081e+02,4.251072043700280384e-02,8.540889904085686268e+00,3.712433129762958851e-03,1.000000009948047275e+00,-4.000000000000000327e-05,4.458573991007563403e-10,0.000000000000000000e+00 +7.969369428931601362e+01,4.904431542833756907e+02,4.254784468302491574e-02,8.542060742278401619e+00,3.712287144361421133e-03,1.000000009948569302e+00,-4.000000000000000327e-05,-1.246713071867320896e-09,0.000000000000000000e+00 +7.969486496701331646e+01,4.904531542144703735e+02,4.258496746920307358e-02,8.543231419987352027e+00,3.712141158959883416e-03,1.000000009947109803e+00,-4.000000000000000327e-05,2.255507371621270557e-10,0.000000000000000000e+00 +7.969603548429283535e+01,4.904631541455705133e+02,4.262208879553727042e-02,8.544401937278511383e+00,3.711995173558345698e-03,1.000000009947373814e+00,-4.000000000000000327e-05,9.444452518663753878e-10,0.000000000000000000e+00 +7.969720584122049445e+01,4.904731540766760531e+02,4.265920866202751321e-02,8.545572294217812725e+00,3.711849188156807981e-03,1.000000009948479152e+00,-4.000000000000000327e-05,-4.206753562448127063e-10,0.000000000000000000e+00 +7.969837603786218949e+01,4.904831540077869931e+02,4.269632706867379501e-02,8.546742490871142905e+00,3.711703202755270263e-03,1.000000009947986879e+00,-4.000000000000000327e-05,-9.868341910863595448e-12,0.000000000000000000e+00 +7.969954607428374516e+01,4.904931539389033901e+02,4.273344401547611582e-02,8.547912527304340813e+00,3.711557217353732546e-03,1.000000009947975332e+00,-4.000000000000000327e-05,-4.492608274759695995e-10,0.000000000000000000e+00 +7.970071595055097191e+01,4.905031538700251872e+02,4.277055950243448257e-02,8.549082403583202705e+00,3.711411231952194828e-03,1.000000009947449753e+00,-4.000000000000000327e-05,-4.732406118564497615e-10,0.000000000000000000e+00 +7.970188566672960917e+01,4.905131538011523844e+02,4.280767352954888832e-02,8.550252119773478654e+00,3.711265246550657110e-03,1.000000009946896196e+00,-4.000000000000000327e-05,1.187155407421504207e-09,0.000000000000000000e+00 +7.970305522288536793e+01,4.905231537322850386e+02,4.284478609681933309e-02,8.551421675940874323e+00,3.711119261149119393e-03,1.000000009948284641e+00,-4.000000000000000327e-05,-6.955293585291549137e-10,0.000000000000000000e+00 +7.970422461908391654e+01,4.905331536634230929e+02,4.288189720424580992e-02,8.552591072151052742e+00,3.710973275747581675e-03,1.000000009947471291e+00,-4.000000000000000327e-05,3.414503956850632248e-10,0.000000000000000000e+00 +7.970539385539086652e+01,4.905431535945665473e+02,4.291900685182832575e-02,8.553760308469627205e+00,3.710827290346043958e-03,1.000000009947870527e+00,-4.000000000000000327e-05,-9.295254110786100381e-10,0.000000000000000000e+00 +7.970656293187177255e+01,4.905531535257154587e+02,4.295611503956688060e-02,8.554929384962170147e+00,3.710681304944506240e-03,1.000000009946783841e+00,-4.000000000000000327e-05,6.585829698849431164e-10,0.000000000000000000e+00 +7.970773184859217508e+01,4.905631534568697703e+02,4.299322176746146751e-02,8.556098301694206043e+00,3.710535319542968523e-03,1.000000009947553670e+00,-4.000000000000000327e-05,-1.248191901884319756e-10,0.000000000000000000e+00 +7.970890060561755774e+01,4.905731533880294819e+02,4.303032703551209343e-02,8.557267058731218512e+00,3.710389334141430805e-03,1.000000009947407786e+00,-4.000000000000000327e-05,5.888394353227975883e-10,0.000000000000000000e+00 +7.971006920301336152e+01,4.905831533191945937e+02,4.306743084371875141e-02,8.558435656138643211e+00,3.710243348739893088e-03,1.000000009948095903e+00,-4.000000000000000327e-05,-1.133371402355606709e-09,0.000000000000000000e+00 +7.971123764084497054e+01,4.905931532503651624e+02,4.310453319208144146e-02,8.559604093981873163e+00,3.710097363338355370e-03,1.000000009946771629e+00,-4.000000000000000327e-05,1.182561974405587296e-09,0.000000000000000000e+00 +7.971240591917772633e+01,4.906031531815411313e+02,4.314163408060016358e-02,8.560772372326253432e+00,3.709951377936817653e-03,1.000000009948153190e+00,-4.000000000000000327e-05,-3.024289450952693004e-10,0.000000000000000000e+00 +7.971357403807694197e+01,4.906131531127225003e+02,4.317873350927491777e-02,8.561940491237090001e+00,3.709805392535279935e-03,1.000000009947799917e+00,-4.000000000000000327e-05,-4.138765874333737239e-10,0.000000000000000000e+00 +7.971474199760787371e+01,4.906231530439093262e+02,4.321583147810570402e-02,8.563108450779639114e+00,3.709659407133742218e-03,1.000000009947316526e+00,-4.000000000000000327e-05,-4.839042723688664486e-10,0.000000000000000000e+00 +7.971590979783573516e+01,4.906331529751015523e+02,4.325292798709252234e-02,8.564276251019114383e+00,3.709513421732204500e-03,1.000000009946751423e+00,-4.000000000000000327e-05,7.589490484475832613e-10,0.000000000000000000e+00 +7.971707743882569730e+01,4.906431529062991785e+02,4.329002303623536579e-02,8.565443892020685013e+00,3.709367436330666783e-03,1.000000009947637603e+00,-4.000000000000000327e-05,-6.253482069277008697e-10,0.000000000000000000e+00 +7.971824492064287426e+01,4.906531528375022049e+02,4.332711662553424131e-02,8.566611373849477573e+00,3.709221450929129065e-03,1.000000009946907520e+00,-4.000000000000000327e-05,5.447814416182895935e-10,0.000000000000000000e+00 +7.971941224335235177e+01,4.906631527687106882e+02,4.336420875498914196e-02,8.567778696570570673e+00,3.709075465527591348e-03,1.000000009947543456e+00,-4.000000000000000327e-05,3.287397373802113879e-10,0.000000000000000000e+00 +7.972057940701917289e+01,4.906731526999245716e+02,4.340129942460006773e-02,8.568945860249002067e+00,3.708929480126053630e-03,1.000000009947927149e+00,-4.000000000000000327e-05,-1.306385716858696667e-09,0.000000000000000000e+00 +7.972174641170832388e+01,4.906831526311438552e+02,4.343838863436701864e-02,8.570112864949763321e+00,3.708783494724515913e-03,1.000000009946402590e+00,-4.000000000000000327e-05,8.266403180932472859e-10,0.000000000000000000e+00 +7.972291325748474833e+01,4.906931525623685388e+02,4.347547638428999467e-02,8.571279710737799817e+00,3.708637509322978195e-03,1.000000009947367152e+00,-4.000000000000000327e-05,1.745240284455676167e-10,0.000000000000000000e+00 +7.972407994441336143e+01,4.907031524935986795e+02,4.351256267436899583e-02,8.572446397678017860e+00,3.708491523921440478e-03,1.000000009947570767e+00,-4.000000000000000327e-05,-6.848668774061096559e-10,0.000000000000000000e+00 +7.972524647255902153e+01,4.907131524248342203e+02,4.354964750460402212e-02,8.573612925835275789e+00,3.708345538519902760e-03,1.000000009946771851e+00,-4.000000000000000327e-05,8.283105277297871855e-10,0.000000000000000000e+00 +7.972641284198653011e+01,4.907231523560751612e+02,4.358673087499507354e-02,8.574779295274387536e+00,3.708199553118365042e-03,1.000000009947737967e+00,-4.000000000000000327e-05,-5.386369267575128861e-10,0.000000000000000000e+00 +7.972757905276067447e+01,4.907331522873215022e+02,4.362381278554214314e-02,8.575945506060126178e+00,3.708053567716827325e-03,1.000000009947109803e+00,-4.000000000000000327e-05,4.063653349358166943e-10,0.000000000000000000e+00 +7.972874510494617084e+01,4.907431522185733002e+02,4.366089323624523788e-02,8.577111558257216828e+00,3.707907582315289607e-03,1.000000009947583646e+00,-4.000000000000000327e-05,-2.852943018332012716e-10,0.000000000000000000e+00 +7.972991099860770703e+01,4.907531521498304983e+02,4.369797222710435081e-02,8.578277451930343744e+00,3.707761596913751890e-03,1.000000009947251023e+00,-4.000000000000000327e-05,-3.238092387177001474e-11,0.000000000000000000e+00 +7.973107673380991400e+01,4.907631520810930965e+02,4.373504975811948192e-02,8.579443187144145000e+00,3.707615611512214172e-03,1.000000009947213275e+00,-4.000000000000000327e-05,-1.714517165669555583e-10,0.000000000000000000e+00 +7.973224231061739431e+01,4.907731520123610949e+02,4.377212582929063123e-02,8.580608763963216035e+00,3.707469626110676455e-03,1.000000009947013435e+00,-4.000000000000000327e-05,-7.342940961122364578e-10,0.000000000000000000e+00 +7.973340772909469365e+01,4.907831519436344934e+02,4.380920044061779872e-02,8.581774182452107880e+00,3.707323640709138737e-03,1.000000009946157675e+00,-4.000000000000000327e-05,8.653041963516688247e-10,0.000000000000000000e+00 +7.973457298930632930e+01,4.907931518749133488e+02,4.384627359210098441e-02,8.582939442675327157e+00,3.707177655307601020e-03,1.000000009947165980e+00,-4.000000000000000327e-05,6.725551958286774997e-10,0.000000000000000000e+00 +7.973573809131674750e+01,4.908031518061976044e+02,4.388334528374018828e-02,8.584104544697339634e+00,3.707031669906063302e-03,1.000000009947949575e+00,-4.000000000000000327e-05,-1.345674196197315544e-09,0.000000000000000000e+00 +7.973690303519038025e+01,4.908131517374872601e+02,4.392041551553541034e-02,8.585269488582564890e+00,3.706885684504525585e-03,1.000000009946381940e+00,-4.000000000000000327e-05,1.677555239155172381e-11,0.000000000000000000e+00 +7.973806782099160273e+01,4.908231516687823159e+02,4.395748428748664366e-02,8.586434274395376320e+00,3.706739699102987867e-03,1.000000009946401480e+00,-4.000000000000000327e-05,8.030478762800124476e-10,0.000000000000000000e+00 +7.973923244878474748e+01,4.908331516000827719e+02,4.399455159959389516e-02,8.587598902200108242e+00,3.706593713701450150e-03,1.000000009947336732e+00,-4.000000000000000327e-05,-3.277840779443593534e-10,0.000000000000000000e+00 +7.974039691863410440e+01,4.908431515313886848e+02,4.403161745185715792e-02,8.588763372061050561e+00,3.706447728299912432e-03,1.000000009946955037e+00,-4.000000000000000327e-05,5.225422681098219038e-10,0.000000000000000000e+00 +7.974156123060392076e+01,4.908531514626999979e+02,4.406868184427643192e-02,8.589927684042446998e+00,3.706301742898374715e-03,1.000000009947563440e+00,-4.000000000000000327e-05,-6.063456427523247835e-10,0.000000000000000000e+00 +7.974272538475838701e+01,4.908631513940167110e+02,4.410574477685171718e-02,8.591091838208500420e+00,3.706155757496836997e-03,1.000000009946857560e+00,-4.000000000000000327e-05,1.863730664448604970e-10,0.000000000000000000e+00 +7.974388938116167935e+01,4.908731513253388243e+02,4.414280624958301369e-02,8.592255834623367505e+00,3.706009772095299280e-03,1.000000009947074497e+00,-4.000000000000000327e-05,-1.062107917867389419e-09,0.000000000000000000e+00 +7.974505321987790296e+01,4.908831512566663378e+02,4.417986626247032145e-02,8.593419673351164079e+00,3.705863786693761562e-03,1.000000009945838375e+00,-4.000000000000000327e-05,8.630437960414586479e-10,0.000000000000000000e+00 +7.974621690097112037e+01,4.908931511879993081e+02,4.421692481551364046e-02,8.594583354455959778e+00,3.705717801292223845e-03,1.000000009946842683e+00,-4.000000000000000327e-05,6.858720830374913662e-10,0.000000000000000000e+00 +7.974738042450536568e+01,4.909031511193376787e+02,4.425398190871296378e-02,8.595746878001785163e+00,3.705571815890686127e-03,1.000000009947640711e+00,-4.000000000000000327e-05,-1.626351478988335208e-09,0.000000000000000000e+00 +7.974854379054463038e+01,4.909131510506814493e+02,4.429103754206829835e-02,8.596910244052624606e+00,3.705425830489148410e-03,1.000000009945748669e+00,-4.000000000000000327e-05,1.772029585190637672e-09,0.000000000000000000e+00 +7.974970699915284911e+01,4.909231509820306201e+02,4.432809171557963723e-02,8.598073452672416295e+00,3.705279845087610692e-03,1.000000009947809909e+00,-4.000000000000000327e-05,-9.635509438252238441e-10,0.000000000000000000e+00 +7.975087005039392807e+01,4.909331509133851910e+02,4.436514442924698043e-02,8.599236503925062891e+00,3.705133859686072974e-03,1.000000009946689250e+00,-4.000000000000000327e-05,-6.738322260691275550e-10,0.000000000000000000e+00 +7.975203294433171664e+01,4.909431508447451620e+02,4.440219568307033488e-02,8.600399397874415541e+00,3.704987874284535257e-03,1.000000009945905655e+00,-4.000000000000000327e-05,1.299913925419530002e-09,0.000000000000000000e+00 +7.975319568103002155e+01,4.909531507761105900e+02,4.443924547704969363e-02,8.601562134584286312e+00,3.704841888882997539e-03,1.000000009947417112e+00,-4.000000000000000327e-05,-3.279350609970692661e-10,0.000000000000000000e+00 +7.975435826055262112e+01,4.909631507074814181e+02,4.447629381118505670e-02,8.602724714118446414e+00,3.704695903481459822e-03,1.000000009947035862e+00,-4.000000000000000327e-05,-3.331368936581607130e-10,0.000000000000000000e+00 +7.975552068296323682e+01,4.909731506388576463e+02,4.451334068547641715e-02,8.603887136540619096e+00,3.704549918079922104e-03,1.000000009946648616e+00,-4.000000000000000327e-05,-5.788653561759743079e-11,0.000000000000000000e+00 +7.975668294832554750e+01,4.909831505702392747e+02,4.455038609992378190e-02,8.605049401914486751e+00,3.704403932678384387e-03,1.000000009946581336e+00,-4.000000000000000327e-05,-8.489261403334072990e-10,0.000000000000000000e+00 +7.975784505670318936e+01,4.909931505016263031e+02,4.458743005452715097e-02,8.606211510303689138e+00,3.704257947276846669e-03,1.000000009945594792e+00,-4.000000000000000327e-05,1.210977148353597504e-09,0.000000000000000000e+00 +7.975900700815977018e+01,4.910031504330187317e+02,4.462447254928651741e-02,8.607373461771821610e+00,3.704111961875308952e-03,1.000000009947001889e+00,-4.000000000000000327e-05,-4.864057037192567923e-10,0.000000000000000000e+00 +7.976016880275882670e+01,4.910131503644165605e+02,4.466151358420188816e-02,8.608535256382440437e+00,3.703965976473771234e-03,1.000000009946436785e+00,-4.000000000000000327e-05,6.074679658137548558e-10,0.000000000000000000e+00 +7.976133044056388144e+01,4.910231502958198462e+02,4.469855315927325629e-02,8.609696894199053929e+00,3.703819991072233517e-03,1.000000009947142443e+00,-4.000000000000000327e-05,-8.017823910193751935e-10,0.000000000000000000e+00 +7.976249192163840007e+01,4.910331502272285320e+02,4.473559127450062178e-02,8.610858375285131316e+00,3.703674005670695799e-03,1.000000009946211188e+00,-4.000000000000000327e-05,5.221657378241249875e-10,0.000000000000000000e+00 +7.976365324604581986e+01,4.910431501586426180e+02,4.477262792988398465e-02,8.612019699704095643e+00,3.703528020269158082e-03,1.000000009946817592e+00,-4.000000000000000327e-05,-7.182420434423649369e-10,0.000000000000000000e+00 +7.976481441384950699e+01,4.910531500900621040e+02,4.480966312542334490e-02,8.613180867519330874e+00,3.703382034867620364e-03,1.000000009945983592e+00,-4.000000000000000327e-05,7.162351234071249679e-10,0.000000000000000000e+00 +7.976597542511279926e+01,4.910631500214869902e+02,4.484669686111870252e-02,8.614341878794174789e+00,3.703236049466082647e-03,1.000000009946815149e+00,-4.000000000000000327e-05,-4.747490521410022776e-10,0.000000000000000000e+00 +7.976713627989900601e+01,4.910731499529172766e+02,4.488372913697005057e-02,8.615502733591926088e+00,3.703090064064544929e-03,1.000000009946264035e+00,-4.000000000000000327e-05,-3.674922755265727772e-10,0.000000000000000000e+00 +7.976829697827136556e+01,4.910831498843529630e+02,4.492075995297739599e-02,8.616663431975837284e+00,3.702944078663007212e-03,1.000000009945837487e+00,-4.000000000000000327e-05,1.008874456793953067e-09,0.000000000000000000e+00 +7.976945752029310199e+01,4.910931498157940496e+02,4.495778930914073185e-02,8.617823974009120036e+00,3.702798093261469494e-03,1.000000009947008328e+00,-4.000000000000000327e-05,-3.312340024266232860e-10,0.000000000000000000e+00 +7.977061790602738256e+01,4.911031497472405363e+02,4.499481720546006508e-02,8.618984359754945146e+00,3.702652107859931777e-03,1.000000009946623969e+00,-4.000000000000000327e-05,-4.625652127449631383e-10,0.000000000000000000e+00 +7.977177813553733188e+01,4.911131496786924231e+02,4.503184364193538874e-02,8.620144589276437230e+00,3.702506122458394059e-03,1.000000009946087287e+00,-4.000000000000000327e-05,-7.325094607138131936e-10,0.000000000000000000e+00 +7.977293820888603193e+01,4.911231496101497669e+02,4.506886861856670284e-02,8.621304662636680050e+00,3.702360137056856342e-03,1.000000009945237522e+00,-4.000000000000000327e-05,1.469619001938355728e-09,0.000000000000000000e+00 +7.977409812613653628e+01,4.911331495416125108e+02,4.510589213535400738e-02,8.622464579898714732e+00,3.702214151655318624e-03,1.000000009946942159e+00,-4.000000000000000327e-05,-4.878328796383152437e-10,0.000000000000000000e+00 +7.977525788735182743e+01,4.911431494730806548e+02,4.514291419229730234e-02,8.623624341125543324e+00,3.702068166253780906e-03,1.000000009946376389e+00,-4.000000000000000327e-05,-3.236061449141607006e-11,0.000000000000000000e+00 +7.977641749259487369e+01,4.911531494045541990e+02,4.517993478939658775e-02,8.624783946380119914e+00,3.701922180852243189e-03,1.000000009946338864e+00,-4.000000000000000327e-05,1.656550033506132890e-10,0.000000000000000000e+00 +7.977757694192858651e+01,4.911631493360331433e+02,4.521695392665185664e-02,8.625943395725359508e+00,3.701776195450705471e-03,1.000000009946530932e+00,-4.000000000000000327e-05,-1.245548328974210955e-09,0.000000000000000000e+00 +7.977873623541583470e+01,4.911731492675174877e+02,4.525397160406311597e-02,8.627102689224134480e+00,3.701630210049167754e-03,1.000000009945086976e+00,-4.000000000000000327e-05,9.915153924438894481e-10,0.000000000000000000e+00 +7.977989537311944446e+01,4.911831491990072323e+02,4.529098782163035880e-02,8.628261826939272794e+00,3.701484224647630036e-03,1.000000009946236279e+00,-4.000000000000000327e-05,2.383328581759259888e-10,0.000000000000000000e+00 +7.978105435510221355e+01,4.911931491305023769e+02,4.532800257935359206e-02,8.629420808933565112e+00,3.701338239246092319e-03,1.000000009946512503e+00,-4.000000000000000327e-05,-8.917605419606470321e-10,0.000000000000000000e+00 +7.978221318142688290e+01,4.912031490620029217e+02,4.536501587723280882e-02,8.630579635269755912e+00,3.701192253844554601e-03,1.000000009945479107e+00,-4.000000000000000327e-05,1.541147685620622368e-09,0.000000000000000000e+00 +7.978337185215615079e+01,4.912131489935088666e+02,4.540202771526800907e-02,8.631738306010547035e+00,3.701046268443016884e-03,1.000000009947264790e+00,-4.000000000000000327e-05,-1.754100619790944000e-09,0.000000000000000000e+00 +7.978453036735268711e+01,4.912231489250202117e+02,4.543903809345919281e-02,8.632896821218603023e+00,3.700900283041479166e-03,1.000000009945232637e+00,-4.000000000000000327e-05,1.102977449580585168e-09,0.000000000000000000e+00 +7.978568872707910486e+01,4.912331488565369568e+02,4.547604701180636005e-02,8.634055180956538678e+00,3.700754297639941449e-03,1.000000009946510282e+00,-4.000000000000000327e-05,-5.057429490165820949e-10,0.000000000000000000e+00 +7.978684693139797446e+01,4.912431487880591021e+02,4.551305447030951079e-02,8.635213385286935051e+00,3.700608312238403731e-03,1.000000009945924528e+00,-4.000000000000000327e-05,9.778752977354835186e-12,0.000000000000000000e+00 +7.978800498037185207e+01,4.912531487195866475e+02,4.555006046896863808e-02,8.636371434272325232e+00,3.700462326836866014e-03,1.000000009945935853e+00,-4.000000000000000327e-05,-2.818959734169972102e-11,0.000000000000000000e+00 +7.978916287406320862e+01,4.912631486511195931e+02,4.558706500778374887e-02,8.637529327975203230e+00,3.700316341435328296e-03,1.000000009945903212e+00,-4.000000000000000327e-05,6.762574591521312450e-10,0.000000000000000000e+00 +7.979032061253451502e+01,4.912731485826579387e+02,4.562406808675483622e-02,8.638687066458020425e+00,3.700170356033790579e-03,1.000000009946686141e+00,-4.000000000000000327e-05,-1.882687640392909624e-09,0.000000000000000000e+00 +7.979147819584817114e+01,4.912831485142017414e+02,4.566106970588190705e-02,8.639844649783187336e+00,3.700024370632252861e-03,1.000000009944506774e+00,-4.000000000000000327e-05,1.544720554137551206e-09,0.000000000000000000e+00 +7.979263562406654842e+01,4.912931484457509441e+02,4.569806986516495445e-02,8.641002078013068299e+00,3.699878385230715144e-03,1.000000009946294677e+00,-4.000000000000000327e-05,3.238745162656110919e-10,0.000000000000000000e+00 +7.979379289725196145e+01,4.913031483773055470e+02,4.573506856460397840e-02,8.642159351209993901e+00,3.699732399829177426e-03,1.000000009946669488e+00,-4.000000000000000327e-05,-1.598481067412543739e-09,0.000000000000000000e+00 +7.979495001546671062e+01,4.913131483088655500e+02,4.577206580419897891e-02,8.643316469436246763e+00,3.699586414427639709e-03,1.000000009944819856e+00,-4.000000000000000327e-05,1.055944825242032906e-09,0.000000000000000000e+00 +7.979610697877302528e+01,4.913231482404309531e+02,4.580906158394995598e-02,8.644473432754066877e+00,3.699440429026101991e-03,1.000000009946041546e+00,-4.000000000000000327e-05,2.978999884025571059e-10,0.000000000000000000e+00 +7.979726378723310631e+01,4.913331481720017564e+02,4.584605590385690266e-02,8.645630241225658708e+00,3.699294443624564274e-03,1.000000009946386159e+00,-4.000000000000000327e-05,-1.249734823857796412e-09,0.000000000000000000e+00 +7.979842044090912623e+01,4.913431481035779598e+02,4.588304876391982590e-02,8.646786894913180532e+00,3.699148458223026556e-03,1.000000009944940649e+00,-4.000000000000000327e-05,1.696487594925530108e-09,0.000000000000000000e+00 +7.979957693986318645e+01,4.913531480351595633e+02,4.592004016413871875e-02,8.647943393878747997e+00,3.699002472821488838e-03,1.000000009946902635e+00,-4.000000000000000327e-05,-1.517173070620625208e-09,0.000000000000000000e+00 +7.980073328415737421e+01,4.913631479667465669e+02,4.595703010451358816e-02,8.649099738184441222e+00,3.698856487419951121e-03,1.000000009945148260e+00,-4.000000000000000327e-05,1.034757821412885346e-09,0.000000000000000000e+00 +7.980188947385371989e+01,4.913731478983389707e+02,4.599401858504442719e-02,8.650255927892290586e+00,3.698710502018413403e-03,1.000000009946344637e+00,-4.000000000000000327e-05,-1.305144637476287971e-09,0.000000000000000000e+00 +7.980304550901422544e+01,4.913831478299367745e+02,4.603100560573123584e-02,8.651411963064292721e+00,3.698564516616875686e-03,1.000000009944835844e+00,-4.000000000000000327e-05,7.361269514496975925e-10,0.000000000000000000e+00 +7.980420138970083599e+01,4.913931477615399785e+02,4.606799116657401411e-02,8.652567843762396294e+00,3.698418531215337968e-03,1.000000009945686719e+00,-4.000000000000000327e-05,4.847328909332598995e-10,0.000000000000000000e+00 +7.980535711597545401e+01,4.914031476931485827e+02,4.610497526757276199e-02,8.653723570048514446e+00,3.698272545813800251e-03,1.000000009946246937e+00,-4.000000000000000327e-05,-7.605346994455257476e-10,0.000000000000000000e+00 +7.980651268789996777e+01,4.914131476247625869e+02,4.614195790872747949e-02,8.654879141984515911e+00,3.698126560412262533e-03,1.000000009945368085e+00,-4.000000000000000327e-05,-3.682109825052200744e-10,0.000000000000000000e+00 +7.980766810553619450e+01,4.914231475563819913e+02,4.617893909003816660e-02,8.656034559632226788e+00,3.697980575010724816e-03,1.000000009944942647e+00,-4.000000000000000327e-05,1.634490718218916060e-09,0.000000000000000000e+00 +7.980882336894590878e+01,4.914331474880067958e+02,4.621591881150481640e-02,8.657189823053434097e+00,3.697834589609187098e-03,1.000000009946830914e+00,-4.000000000000000327e-05,-1.436713786551221834e-09,0.000000000000000000e+00 +7.980997847819087099e+01,4.914431474196369436e+02,4.625289707312743581e-02,8.658344932309885777e+00,3.697688604207649381e-03,1.000000009945171353e+00,-4.000000000000000327e-05,-2.935716716753676788e-10,0.000000000000000000e+00 +7.981113343333278465e+01,4.914531473512724915e+02,4.628987387490601790e-02,8.659499887463281809e+00,3.697542618806111663e-03,1.000000009944832291e+00,-4.000000000000000327e-05,1.043500972059146549e-09,0.000000000000000000e+00 +7.981228823443331066e+01,4.914631472829134395e+02,4.632684921684056267e-02,8.660654688575286642e+00,3.697396633404573946e-03,1.000000009946037327e+00,-4.000000000000000327e-05,-1.196138125501861737e-10,0.000000000000000000e+00 +7.981344288155406730e+01,4.914731472145597877e+02,4.636382309893107706e-02,8.661809335707523871e+00,3.697250648003036228e-03,1.000000009945899215e+00,-4.000000000000000327e-05,-1.148214895034225526e-09,0.000000000000000000e+00 +7.981459737475663019e+01,4.914831471462115360e+02,4.640079552117755413e-02,8.662963828921572684e+00,3.697104662601498511e-03,1.000000009944573609e+00,-4.000000000000000327e-05,5.951508194420217921e-10,0.000000000000000000e+00 +7.981575171410254654e+01,4.914931470778686844e+02,4.643776648357999387e-02,8.664118168278971410e+00,3.696958677199960793e-03,1.000000009945260615e+00,-4.000000000000000327e-05,1.084650108235259635e-09,0.000000000000000000e+00 +7.981690589965332094e+01,4.915031470095312329e+02,4.647473598613838935e-02,8.665272353841221076e+00,3.696812691798423076e-03,1.000000009946512503e+00,-4.000000000000000327e-05,-1.044196575079510169e-09,0.000000000000000000e+00 +7.981805993147040112e+01,4.915131469411991816e+02,4.651170402885274752e-02,8.666426385669780075e+00,3.696666706396885358e-03,1.000000009945307466e+00,-4.000000000000000327e-05,-4.855092721421895091e-10,0.000000000000000000e+00 +7.981921380961520640e+01,4.915231468728725304e+02,4.654867061172306836e-02,8.667580263826062392e+00,3.696520720995347641e-03,1.000000009944747248e+00,-4.000000000000000327e-05,6.543604080146673137e-11,0.000000000000000000e+00 +7.982036753414911345e+01,4.915331468045512793e+02,4.658563573474934494e-02,8.668733988371444710e+00,3.696374735593809923e-03,1.000000009944822743e+00,-4.000000000000000327e-05,5.807259216376403291e-10,0.000000000000000000e+00 +7.982152110513345633e+01,4.915431467362354283e+02,4.662259939793157726e-02,8.669887559367262853e+00,3.696228750192272205e-03,1.000000009945492652e+00,-4.000000000000000327e-05,-3.043585879183217649e-10,0.000000000000000000e+00 +7.982267452262954066e+01,4.915531466679249775e+02,4.665956160126977226e-02,8.671040976874811790e+00,3.696082764790734488e-03,1.000000009945141599e+00,-4.000000000000000327e-05,5.179212664917108854e-11,0.000000000000000000e+00 +7.982382778669860102e+01,4.915631465996199267e+02,4.669652234476392300e-02,8.672194240955343858e+00,3.695936779389196770e-03,1.000000009945201329e+00,-4.000000000000000327e-05,2.865313548770298617e-10,0.000000000000000000e+00 +7.982498089740185776e+01,4.915731465313202762e+02,4.673348162841402947e-02,8.673347351670072314e+00,3.695790793987659053e-03,1.000000009945531732e+00,-4.000000000000000327e-05,3.699596243258043395e-10,0.000000000000000000e+00 +7.982613385480048862e+01,4.915831464630260257e+02,4.677043945222009169e-02,8.674500309080169558e+00,3.695644808586121335e-03,1.000000009945958279e+00,-4.000000000000000327e-05,-1.062065873120144958e-09,0.000000000000000000e+00 +7.982728665895561448e+01,4.915931463947371753e+02,4.680739581618210271e-02,8.675653113246767134e+00,3.695498823184583618e-03,1.000000009944733925e+00,-4.000000000000000327e-05,-2.889572951996244526e-11,0.000000000000000000e+00 +7.982843930992834203e+01,4.916031463264536683e+02,4.684435072030006947e-02,8.676805764230953955e+00,3.695352837783045900e-03,1.000000009944700619e+00,-4.000000000000000327e-05,7.691138528456146633e-10,0.000000000000000000e+00 +7.982959180777970687e+01,4.916131462581755613e+02,4.688130416457399197e-02,8.677958262093781627e+00,3.695206852381508183e-03,1.000000009945587021e+00,-4.000000000000000327e-05,-3.506946741229795682e-11,0.000000000000000000e+00 +7.983074415257073042e+01,4.916231461899028545e+02,4.691825614900386326e-02,8.679110606896260904e+00,3.695060866979970465e-03,1.000000009945546608e+00,-4.000000000000000327e-05,-1.132585870349907451e-09,0.000000000000000000e+00 +7.983189634436237725e+01,4.916331461216355478e+02,4.695520667358968336e-02,8.680262798699359905e+00,3.694914881578432748e-03,1.000000009944241652e+00,-4.000000000000000327e-05,1.462900792551028305e-09,0.000000000000000000e+00 +7.983304838321556929e+01,4.916431460533736413e+02,4.699215573833145920e-02,8.681414837564005893e+00,3.694768896176895030e-03,1.000000009945926971e+00,-4.000000000000000327e-05,-1.644873411009354547e-09,0.000000000000000000e+00 +7.983420026919120005e+01,4.916531459851171348e+02,4.702910334322918384e-02,8.682566723551090604e+00,3.694622910775357313e-03,1.000000009944032264e+00,-4.000000000000000327e-05,1.563155182949854320e-09,0.000000000000000000e+00 +7.983535200235012042e+01,4.916631459168660285e+02,4.706604948828285728e-02,8.683718456721457812e+00,3.694476925373819595e-03,1.000000009945832602e+00,-4.000000000000000327e-05,-9.916592885277010284e-10,0.000000000000000000e+00 +7.983650358275312442e+01,4.916731458486203223e+02,4.710299417349247952e-02,8.684870037135919318e+00,3.694330939972281878e-03,1.000000009944690627e+00,-4.000000000000000327e-05,3.664014218820065658e-11,0.000000000000000000e+00 +7.983765501046099189e+01,4.916831457803800163e+02,4.713993739885804363e-02,8.686021464855238960e+00,3.694184954570744160e-03,1.000000009944732815e+00,-4.000000000000000327e-05,6.027138139169135042e-10,0.000000000000000000e+00 +7.983880628553444581e+01,4.916931457121450535e+02,4.717687916437955653e-02,8.687172739940145050e+00,3.694038969169206443e-03,1.000000009945426704e+00,-4.000000000000000327e-05,-6.631695166329046839e-10,0.000000000000000000e+00 +7.983995740803418073e+01,4.917031456439154908e+02,4.721381947005701823e-02,8.688323862451325041e+00,3.693892983767668725e-03,1.000000009944663315e+00,-4.000000000000000327e-05,2.324680504595965394e-10,0.000000000000000000e+00 +7.984110837802083438e+01,4.917131455756913283e+02,4.725075831589042180e-02,8.689474832449423758e+00,3.693746998366131008e-03,1.000000009944930879e+00,-4.000000000000000327e-05,5.805718077587299250e-10,0.000000000000000000e+00 +7.984225919555501605e+01,4.917231455074725659e+02,4.728769570187976723e-02,8.690625649995048718e+00,3.693601012964593290e-03,1.000000009945599011e+00,-4.000000000000000327e-05,-9.891675718937035967e-10,0.000000000000000000e+00 +7.984340986069729240e+01,4.917331454392592036e+02,4.732463162802505452e-02,8.691776315148766585e+00,3.693455027563055573e-03,1.000000009944460810e+00,-4.000000000000000327e-05,-4.801745550528952344e-10,0.000000000000000000e+00 +7.984456037350818747e+01,4.917431453710512415e+02,4.736156609432628367e-02,8.692926827971101389e+00,3.693309042161517855e-03,1.000000009943908363e+00,-4.000000000000000327e-05,7.386942384589679235e-10,0.000000000000000000e+00 +7.984571073404818264e+01,4.917531453028486794e+02,4.739849910078345469e-02,8.694077188522539856e+00,3.693163056759980137e-03,1.000000009944758128e+00,-4.000000000000000327e-05,1.298243048460136491e-09,0.000000000000000000e+00 +7.984686094237773091e+01,4.917631452346515175e+02,4.743543064739656756e-02,8.695227396863529634e+00,3.693017071358442420e-03,1.000000009946251378e+00,-4.000000000000000327e-05,-1.518131687506539410e-09,0.000000000000000000e+00 +7.984801099855724260e+01,4.917731451664596989e+02,4.747236073416562230e-02,8.696377453054477513e+00,3.692871085956904702e-03,1.000000009944505441e+00,-4.000000000000000327e-05,3.211225886185963126e-10,0.000000000000000000e+00 +7.984916090264707123e+01,4.917831450982732804e+02,4.750928936109061890e-02,8.697527357155745875e+00,3.692725100555366985e-03,1.000000009944874702e+00,-4.000000000000000327e-05,-1.271914022421055418e-09,0.000000000000000000e+00 +7.985031065470755607e+01,4.917931450300922620e+02,4.754621652817155042e-02,8.698677109227663351e+00,3.692579115153829267e-03,1.000000009943412316e+00,-4.000000000000000327e-05,1.737765441583356084e-09,0.000000000000000000e+00 +7.985146025479897958e+01,4.918031449619166438e+02,4.758314223540842380e-02,8.699826709330514163e+00,3.692433129752291550e-03,1.000000009945410051e+00,-4.000000000000000327e-05,-8.557650659731613142e-11,0.000000000000000000e+00 +7.985260970298158156e+01,4.918131448937464256e+02,4.762006648280123211e-02,8.700976157524548782e+00,3.692287144350753832e-03,1.000000009945311685e+00,-4.000000000000000327e-05,-1.395100675727007054e-09,0.000000000000000000e+00 +7.985375899931557342e+01,4.918231448255816076e+02,4.765698927034997534e-02,8.702125453869971494e+00,3.692141158949216115e-03,1.000000009943708301e+00,-4.000000000000000327e-05,4.726307980577260487e-10,0.000000000000000000e+00 +7.985490814386112390e+01,4.918331447574221329e+02,4.769391059805465349e-02,8.703274598426947506e+00,3.691995173547678397e-03,1.000000009944251422e+00,-4.000000000000000327e-05,1.456150180415495259e-09,0.000000000000000000e+00 +7.985605713667835914e+01,4.918431446892680583e+02,4.773083046591526657e-02,8.704423591255606496e+00,3.691849188146140680e-03,1.000000009945924528e+00,-4.000000000000000327e-05,-1.165073935285061166e-09,0.000000000000000000e+00 +7.985720597782736263e+01,4.918531446211193838e+02,4.776774887393181457e-02,8.705572432416037287e+00,3.691703202744602962e-03,1.000000009944586044e+00,-4.000000000000000327e-05,-6.912498799653775794e-10,0.000000000000000000e+00 +7.985835466736818944e+01,4.918631445529761095e+02,4.780466582210429749e-02,8.706721121968284294e+00,3.691557217343065245e-03,1.000000009943792012e+00,-4.000000000000000327e-05,1.602689494475774647e-10,0.000000000000000000e+00 +7.985950320536083780e+01,4.918731444848382353e+02,4.784158131043270840e-02,8.707869659972356402e+00,3.691411231941527527e-03,1.000000009943976087e+00,-4.000000000000000327e-05,1.361789037428125048e-09,0.000000000000000000e+00 +7.986065159186529172e+01,4.918831444167057043e+02,4.787849533891705422e-02,8.709018046488223419e+00,3.691265246539989810e-03,1.000000009945539947e+00,-4.000000000000000327e-05,-1.156213322860490632e-09,0.000000000000000000e+00 +7.986179982694146418e+01,4.918931443485785735e+02,4.791540790755732804e-02,8.710166281575816072e+00,3.691119261138452092e-03,1.000000009944212342e+00,-4.000000000000000327e-05,-6.863927233993776850e-10,0.000000000000000000e+00 +7.986294791064925391e+01,4.919031442804568428e+02,4.795231901635352983e-02,8.711314365295020679e+00,3.690973275736914375e-03,1.000000009943424306e+00,-4.000000000000000327e-05,1.399079447943016596e-09,0.000000000000000000e+00 +7.986409584304850284e+01,4.919131442123405122e+02,4.798922866530565962e-02,8.712462297705688030e+00,3.690827290335376657e-03,1.000000009945030355e+00,-4.000000000000000327e-05,-3.207492602540725221e-10,0.000000000000000000e+00 +7.986524362419903866e+01,4.919231441442295818e+02,4.802613685441371738e-02,8.713610078867631614e+00,3.690681304933838940e-03,1.000000009944662205e+00,-4.000000000000000327e-05,-4.808003116970841420e-10,0.000000000000000000e+00 +7.986639125416061802e+01,4.919331440761239946e+02,4.806304358367770313e-02,8.714757708840620509e+00,3.690535319532301222e-03,1.000000009944110424e+00,-4.000000000000000327e-05,8.924519468583400703e-10,0.000000000000000000e+00 +7.986753873299296913e+01,4.919431440080238076e+02,4.809994885309761686e-02,8.715905187684386490e+00,3.690389334130763505e-03,1.000000009945134494e+00,-4.000000000000000327e-05,-1.625862100101661175e-09,0.000000000000000000e+00 +7.986868606075579180e+01,4.919531439399290207e+02,4.813685266267345858e-02,8.717052515458624029e+00,3.690243348729225787e-03,1.000000009943269097e+00,-4.000000000000000327e-05,1.383548639666237570e-09,0.000000000000000000e+00 +7.986983323750874320e+01,4.919631438718396339e+02,4.817375501240522134e-02,8.718199692222983188e+00,3.690097363327688069e-03,1.000000009944856272e+00,-4.000000000000000327e-05,-9.042258222707556212e-10,0.000000000000000000e+00 +7.987098026331143785e+01,4.919731438037555904e+02,4.821065590229291209e-02,8.719346718037082056e+00,3.689951377926150352e-03,1.000000009943819101e+00,-4.000000000000000327e-05,9.324180048967753837e-10,0.000000000000000000e+00 +7.987212713822344767e+01,4.919831437356769470e+02,4.824755533233652388e-02,8.720493592960492535e+00,3.689805392524612634e-03,1.000000009944888468e+00,-4.000000000000000327e-05,-1.235577631690374370e-09,0.000000000000000000e+00 +7.987327386230430193e+01,4.919931436676037038e+02,4.828445330253606366e-02,8.721640317052752778e+00,3.689659407123074917e-03,1.000000009943471602e+00,-4.000000000000000327e-05,6.685119652175796922e-10,0.000000000000000000e+00 +7.987442043561350147e+01,4.920031435995358606e+02,4.832134981289152448e-02,8.722786890373356528e+00,3.689513421721537199e-03,1.000000009944238100e+00,-4.000000000000000327e-05,-1.369351372625163381e-10,0.000000000000000000e+00 +7.987556685821050451e+01,4.920131435314734176e+02,4.835824486340290634e-02,8.723933312981763777e+00,3.689367436319999482e-03,1.000000009944081114e+00,-4.000000000000000327e-05,3.736670386609702199e-10,0.000000000000000000e+00 +7.987671313015474084e+01,4.920231434634163179e+02,4.839513845407020926e-02,8.725079584937391886e+00,3.689221450918461764e-03,1.000000009944509438e+00,-4.000000000000000327e-05,-5.300608339895141218e-10,0.000000000000000000e+00 +7.987785925150556920e+01,4.920331433953646183e+02,4.843203058489342627e-02,8.726225706299620910e+00,3.689075465516924047e-03,1.000000009943901924e+00,-4.000000000000000327e-05,-1.714786035406127170e-10,0.000000000000000000e+00 +7.987900522232234835e+01,4.920431433273183188e+02,4.846892125587256434e-02,8.727371677127790051e+00,3.688929480115386329e-03,1.000000009943705415e+00,-4.000000000000000327e-05,1.423362427222043990e-09,0.000000000000000000e+00 +7.988015104266436595e+01,4.920531432592774195e+02,4.850581046700762344e-02,8.728517497481201204e+00,3.688783494713848612e-03,1.000000009945336332e+00,-4.000000000000000327e-05,-1.185354326129651177e-09,0.000000000000000000e+00 +7.988129671259089548e+01,4.920631431912418634e+02,4.854269821829859666e-02,8.729663167419118963e+00,3.688637509312310894e-03,1.000000009943978307e+00,-4.000000000000000327e-05,9.381733108228771674e-11,0.000000000000000000e+00 +7.988244223216115358e+01,4.920731431232117075e+02,4.857958450974548398e-02,8.730808687000763513e+00,3.688491523910773177e-03,1.000000009944085777e+00,-4.000000000000000327e-05,-1.791293164196951048e-10,0.000000000000000000e+00 +7.988358760143432846e+01,4.920831430551869516e+02,4.861646934134829234e-02,8.731954056285321286e+00,3.688345538509235459e-03,1.000000009943880608e+00,-4.000000000000000327e-05,-6.782213743702593189e-10,0.000000000000000000e+00 +7.988473282046955148e+01,4.920931429871675391e+02,4.865335271310701482e-02,8.733099275331937861e+00,3.688199553107697742e-03,1.000000009943103896e+00,-4.000000000000000327e-05,1.278861232929842675e-09,0.000000000000000000e+00 +7.988587788932595402e+01,4.921031429191535267e+02,4.869023462502165139e-02,8.734244344199719734e+00,3.688053567706160024e-03,1.000000009944568280e+00,-4.000000000000000327e-05,-1.109138190280094481e-09,0.000000000000000000e+00 +7.988702280806258216e+01,4.921131428511449144e+02,4.872711507709220208e-02,8.735389262947737876e+00,3.687907582304622307e-03,1.000000009943298407e+00,-4.000000000000000327e-05,2.604944655568444780e-10,0.000000000000000000e+00 +7.988816757673848201e+01,4.921231427831417022e+02,4.876399406931865993e-02,8.736534031635018849e+00,3.687761596903084589e-03,1.000000009943596613e+00,-4.000000000000000327e-05,1.296435335383190927e-09,0.000000000000000000e+00 +7.988931219541264284e+01,4.921331427151438334e+02,4.880087160170103189e-02,8.737678650320555462e+00,3.687615611501546872e-03,1.000000009945080537e+00,-4.000000000000000327e-05,-2.098082972347514231e-09,0.000000000000000000e+00 +7.989045666414401126e+01,4.921431426471513646e+02,4.883774767423931795e-02,8.738823119063301448e+00,3.687469626100009154e-03,1.000000009942679347e+00,-4.000000000000000327e-05,8.993793522562221297e-10,0.000000000000000000e+00 +7.989160098299149126e+01,4.921531425791642960e+02,4.887462228693351118e-02,8.739967437922166127e+00,3.687323640698471437e-03,1.000000009943708523e+00,-4.000000000000000327e-05,7.686964625188630806e-10,0.000000000000000000e+00 +7.989274515201397264e+01,4.921631425111825706e+02,4.891149543978361158e-02,8.741111606956028623e+00,3.687177655296933719e-03,1.000000009944588042e+00,-4.000000000000000327e-05,-1.162609087349922035e-09,0.000000000000000000e+00 +7.989388917127028833e+01,4.921731424432062454e+02,4.894836713278961915e-02,8.742255626223725429e+00,3.687031669895396001e-03,1.000000009943257995e+00,-4.000000000000000327e-05,5.076161371814223057e-10,0.000000000000000000e+00 +7.989503304081924284e+01,4.921831423752353203e+02,4.898523736595154082e-02,8.743399495784052178e+00,3.686885684493858284e-03,1.000000009943838641e+00,-4.000000000000000327e-05,3.236354952800727285e-10,0.000000000000000000e+00 +7.989617676071958385e+01,4.921931423072697953e+02,4.902210613926936966e-02,8.744543215695770755e+00,3.686739699092320566e-03,1.000000009944208790e+00,-4.000000000000000327e-05,-3.852290428860796204e-10,0.000000000000000000e+00 +7.989732033103004483e+01,4.922031422393096136e+02,4.905897345274309873e-02,8.745686786017602188e+00,3.686593713690782849e-03,1.000000009943768253e+00,-4.000000000000000327e-05,-2.870176334320632446e-10,0.000000000000000000e+00 +7.989846375180930238e+01,4.922131421713548320e+02,4.909583930637273497e-02,8.746830206808228425e+00,3.686447728289245131e-03,1.000000009943440071e+00,-4.000000000000000327e-05,5.921726509274425028e-10,0.000000000000000000e+00 +7.989960702311600471e+01,4.922231421034054506e+02,4.913270370015827837e-02,8.747973478126294111e+00,3.686301742887707414e-03,1.000000009944117085e+00,-4.000000000000000327e-05,-4.931855959391974647e-10,0.000000000000000000e+00 +7.990075014500874317e+01,4.922331420354614124e+02,4.916956663409972200e-02,8.749116600030406588e+00,3.686155757486169696e-03,1.000000009943553314e+00,-4.000000000000000327e-05,-8.516771104923504620e-10,0.000000000000000000e+00 +7.990189311754610912e+01,4.922431419675227744e+02,4.920642810819707280e-02,8.750259572579132339e+00,3.686009772084631979e-03,1.000000009942579871e+00,-4.000000000000000327e-05,8.508168984527668417e-10,0.000000000000000000e+00 +7.990303594078660865e+01,4.922531418995895365e+02,4.924328812245032383e-02,8.751402395831000547e+00,3.685863786683094261e-03,1.000000009943552204e+00,-4.000000000000000327e-05,5.075642807808160974e-10,0.000000000000000000e+00 +7.990417861478874784e+01,4.922631418316616418e+02,4.928014667685947509e-02,8.752545069844504866e+00,3.685717801281556544e-03,1.000000009944132184e+00,-4.000000000000000327e-05,-5.490261539245084012e-10,0.000000000000000000e+00 +7.990532113961097593e+01,4.922731417637391473e+02,4.931700377142452657e-02,8.753687594678098094e+00,3.685571815880018826e-03,1.000000009943504908e+00,-4.000000000000000327e-05,3.763020824564655415e-10,0.000000000000000000e+00 +7.990646351531171376e+01,4.922831416958220530e+02,4.935385940614547828e-02,8.754829970390193949e+00,3.685425830478481109e-03,1.000000009943934787e+00,-4.000000000000000327e-05,-8.267673626620618632e-10,0.000000000000000000e+00 +7.990760574194932531e+01,4.922931416279103018e+02,4.939071358102233023e-02,8.755972197039170624e+00,3.685279845076943391e-03,1.000000009942990431e+00,-4.000000000000000327e-05,-9.973830066470000357e-11,0.000000000000000000e+00 +7.990874781958216033e+01,4.923031415600039509e+02,4.942756629605508240e-02,8.757114274683365451e+00,3.685133859675405674e-03,1.000000009942876522e+00,-4.000000000000000327e-05,1.169209798616479086e-09,0.000000000000000000e+00 +7.990988974826852598e+01,4.923131414921029432e+02,4.946441755124372786e-02,8.758256203381080240e+00,3.684987874273867956e-03,1.000000009944211676e+00,-4.000000000000000327e-05,-1.133773822952470611e-09,0.000000000000000000e+00 +7.991103152806667254e+01,4.923231414242073356e+02,4.950126734658827354e-02,8.759397983190579495e+00,3.684841888872330239e-03,1.000000009942917156e+00,-4.000000000000000327e-05,1.139756559831379419e-09,0.000000000000000000e+00 +7.991217315903482188e+01,4.923331413563171282e+02,4.953811568208871252e-02,8.760539614170085088e+00,3.684695903470792521e-03,1.000000009944218338e+00,-4.000000000000000327e-05,-1.576803889956906302e-09,0.000000000000000000e+00 +7.991331464123116746e+01,4.923431412884322640e+02,4.957496255774505173e-02,8.761681096377786915e+00,3.684549918069254804e-03,1.000000009942418444e+00,-4.000000000000000327e-05,1.596464184780457597e-09,0.000000000000000000e+00 +7.991445597471386009e+01,4.923531412205528000e+02,4.961180797355728422e-02,8.762822429871830465e+00,3.684403932667717086e-03,1.000000009944240542e+00,-4.000000000000000327e-05,-1.639478370709658085e-09,0.000000000000000000e+00 +7.991559715954100795e+01,4.923631411526787360e+02,4.964865192952541001e-02,8.763963614710331029e+00,3.684257947266179369e-03,1.000000009942369594e+00,-4.000000000000000327e-05,9.632654650108239538e-10,0.000000000000000000e+00 +7.991673819577069082e+01,4.923731410848100154e+02,4.968549442564942908e-02,8.765104650951357712e+00,3.684111961864641651e-03,1.000000009943468715e+00,-4.000000000000000327e-05,-1.693232453431932253e-10,0.000000000000000000e+00 +7.991787908346093161e+01,4.923831410169466949e+02,4.972233546192934145e-02,8.766245538652949421e+00,3.683965976463103933e-03,1.000000009943275536e+00,-4.000000000000000327e-05,3.929978507630839116e-10,0.000000000000000000e+00 +7.991901982266973903e+01,4.923931409490887177e+02,4.975917503836514016e-02,8.767386277873102429e+00,3.683819991061566216e-03,1.000000009943723844e+00,-4.000000000000000327e-05,-1.471938296737607793e-09,0.000000000000000000e+00 +7.992016041345507915e+01,4.924031408812361406e+02,4.979601315495683217e-02,8.768526868669777485e+00,3.683674005660028498e-03,1.000000009942044965e+00,-4.000000000000000327e-05,1.038142577763850814e-09,0.000000000000000000e+00 +7.992130085587486121e+01,4.924131408133889636e+02,4.983284981170441053e-02,8.769667311100894480e+00,3.683528020258490781e-03,1.000000009943228907e+00,-4.000000000000000327e-05,-2.975409174901725682e-10,0.000000000000000000e+00 +7.992244114998696602e+01,4.924231407455471299e+02,4.986968500860788217e-02,8.770807605224341330e+00,3.683382034856953063e-03,1.000000009942889623e+00,-4.000000000000000327e-05,1.324307146511339371e-09,0.000000000000000000e+00 +7.992358129584924598e+01,4.924331406777106963e+02,4.990651874566724017e-02,8.771947751097963319e+00,3.683236049455415346e-03,1.000000009944399526e+00,-4.000000000000000327e-05,-2.321344745261589367e-09,0.000000000000000000e+00 +7.992472129351952503e+01,4.924431406098796060e+02,4.994335102288248451e-02,8.773087748779571982e+00,3.683090064053877628e-03,1.000000009941753198e+00,-4.000000000000000327e-05,2.406969561972624877e-09,0.000000000000000000e+00 +7.992586114305555611e+01,4.924531405420539159e+02,4.998018184025361521e-02,8.774227598326934441e+00,3.682944078652339911e-03,1.000000009944496782e+00,-4.000000000000000327e-05,-2.288242998246255583e-09,0.000000000000000000e+00 +7.992700084451507792e+01,4.924631404742336258e+02,5.001701119778063226e-02,8.775367299797791176e+00,3.682798093250802193e-03,1.000000009941888868e+00,-4.000000000000000327e-05,1.341363209213142207e-09,0.000000000000000000e+00 +7.992814039795578651e+01,4.924731404064186790e+02,5.005383909546353566e-02,8.776506853249832929e+00,3.682652107849264476e-03,1.000000009943417423e+00,-4.000000000000000327e-05,-4.057351625445216477e-10,0.000000000000000000e+00 +7.992927980343534955e+01,4.924831403386091324e+02,5.009066553330232541e-02,8.777646258740723795e+00,3.682506122447726758e-03,1.000000009942955126e+00,-4.000000000000000327e-05,6.515603932604249792e-10,0.000000000000000000e+00 +7.993041906101137783e+01,4.924931402708049291e+02,5.012749051129699457e-02,8.778785516328083460e+00,3.682360137046189041e-03,1.000000009943697421e+00,-4.000000000000000327e-05,-9.867265290098350425e-10,0.000000000000000000e+00 +7.993155817074146796e+01,4.925031402030061258e+02,5.016431402944755008e-02,8.779924626069497862e+00,3.682214151644651323e-03,1.000000009942573431e+00,-4.000000000000000327e-05,1.280844425927720547e-10,0.000000000000000000e+00 +7.993269713268315968e+01,4.925131401352127227e+02,5.020113608775398500e-02,8.781063588022512079e+00,3.682068166243113606e-03,1.000000009942719315e+00,-4.000000000000000327e-05,-1.360951881066377350e-10,0.000000000000000000e+00 +7.993383594689396432e+01,4.925231400674246629e+02,5.023795668621629934e-02,8.782202402244637440e+00,3.681922180841575888e-03,1.000000009942564327e+00,-4.000000000000000327e-05,9.327044490067515749e-10,0.000000000000000000e+00 +7.993497461343135058e+01,4.925331399996420032e+02,5.027477582483449309e-02,8.783341068793346196e+00,3.681776195440038171e-03,1.000000009943626367e+00,-4.000000000000000327e-05,-8.009855394405078828e-10,0.000000000000000000e+00 +7.993611313235275873e+01,4.925431399318646868e+02,5.031159350360856625e-02,8.784479587726075067e+00,3.681630210038500453e-03,1.000000009942714430e+00,-4.000000000000000327e-05,1.170327779717183036e-10,0.000000000000000000e+00 +7.993725150371558641e+01,4.925531398640927705e+02,5.034840972253851882e-02,8.785617959100219920e+00,3.681484224636962736e-03,1.000000009942847656e+00,-4.000000000000000327e-05,-4.508296647882794413e-10,0.000000000000000000e+00 +7.993838972757718864e+01,4.925631397963261975e+02,5.038522448162435080e-02,8.786756182973142870e+00,3.681338239235425018e-03,1.000000009942334511e+00,-4.000000000000000327e-05,2.124695415885502802e-10,0.000000000000000000e+00 +7.993952780399489200e+01,4.925731397285650246e+02,5.042203778086606220e-02,8.787894259402166952e+00,3.681192253833887301e-03,1.000000009942576318e+00,-4.000000000000000327e-05,7.092991890040172927e-10,0.000000000000000000e+00 +7.994066573302599465e+01,4.925831396608091950e+02,5.045884962026364606e-02,8.789032188444579674e+00,3.681046268432349583e-03,1.000000009943383450e+00,-4.000000000000000327e-05,-1.731616685775455852e-09,0.000000000000000000e+00 +7.994180351472773793e+01,4.925931395930587655e+02,5.049565999981710934e-02,8.790169970157631241e+00,3.680900283030811865e-03,1.000000009941413248e+00,-4.000000000000000327e-05,1.098283384727882538e-09,0.000000000000000000e+00 +7.994294114915733473e+01,4.926031395253136793e+02,5.053246891952644509e-02,8.791307604598531000e+00,3.680754297629274148e-03,1.000000009942662693e+00,-4.000000000000000327e-05,9.391372321082232243e-10,0.000000000000000000e+00 +7.994407863637195533e+01,4.926131394575739932e+02,5.056927637939165332e-02,8.792445091824458103e+00,3.680608312227736430e-03,1.000000009943730950e+00,-4.000000000000000327e-05,-8.642898490564404253e-10,0.000000000000000000e+00 +7.994521597642874156e+01,4.926231393898397073e+02,5.060608237941273402e-02,8.793582431892550844e+00,3.680462326826198713e-03,1.000000009942747958e+00,-4.000000000000000327e-05,-2.181017938790214654e-10,0.000000000000000000e+00 +7.994635316938479264e+01,4.926331393221107646e+02,5.064288691958968719e-02,8.794719624859908436e+00,3.680316341424660995e-03,1.000000009942499934e+00,-4.000000000000000327e-05,1.056475644089884882e-10,0.000000000000000000e+00 +7.994749021529717936e+01,4.926431392543872221e+02,5.067968999992251283e-02,8.795856670783596343e+00,3.680170356023123278e-03,1.000000009942620061e+00,-4.000000000000000327e-05,-1.293129315122114408e-09,0.000000000000000000e+00 +7.994862711422291568e+01,4.926531391866690228e+02,5.071649162041121095e-02,8.796993569720642725e+00,3.680024370621585560e-03,1.000000009941149903e+00,-4.000000000000000327e-05,2.432084909833414402e-09,0.000000000000000000e+00 +7.994976386621901554e+01,4.926631391189562237e+02,5.075329178105578154e-02,8.798130321728036662e+00,3.679878385220047843e-03,1.000000009943914581e+00,-4.000000000000000327e-05,-2.491592579441523624e-09,0.000000000000000000e+00 +7.995090047134240763e+01,4.926731390512487678e+02,5.079009048185621766e-02,8.799266926862737037e+00,3.679732399818510125e-03,1.000000009941082624e+00,-4.000000000000000327e-05,1.784041943268724888e-09,0.000000000000000000e+00 +7.995203692965003484e+01,4.926831389835467121e+02,5.082688772281252626e-02,8.800403385181654770e+00,3.679586414416972408e-03,1.000000009943110113e+00,-4.000000000000000327e-05,-1.268980911092613582e-09,0.000000000000000000e+00 +7.995317324119875479e+01,4.926931389158499996e+02,5.086368350392470039e-02,8.801539696741675911e+00,3.679440429015434690e-03,1.000000009941668155e+00,-4.000000000000000327e-05,7.031695188092557183e-10,0.000000000000000000e+00 +7.995430940604542513e+01,4.927031388481586873e+02,5.090047782519274006e-02,8.802675861599640328e+00,3.679294443613896973e-03,1.000000009942467072e+00,-4.000000000000000327e-05,7.966895323869877952e-10,0.000000000000000000e+00 +7.995544542424684664e+01,4.927131387804727183e+02,5.093727068661664525e-02,8.803811879812357688e+00,3.679148458212359255e-03,1.000000009943372126e+00,-4.000000000000000327e-05,-1.016516243957360596e-09,0.000000000000000000e+00 +7.995658129585979168e+01,4.927231387127921494e+02,5.097406208819641599e-02,8.804947751436598580e+00,3.679002472810821538e-03,1.000000009942217494e+00,-4.000000000000000327e-05,-6.311034215586394262e-10,0.000000000000000000e+00 +7.995771702094098998e+01,4.927331386451169237e+02,5.101085202993205225e-02,8.806083476529094511e+00,3.678856487409283820e-03,1.000000009941500734e+00,-4.000000000000000327e-05,5.510157494028385828e-10,0.000000000000000000e+00 +7.995885259954714286e+01,4.927431385774470982e+02,5.104764051182355405e-02,8.807219055146543241e+00,3.678710502007746103e-03,1.000000009942126455e+00,-4.000000000000000327e-05,1.127791910771727375e-09,0.000000000000000000e+00 +7.995998803173492320e+01,4.927531385097826160e+02,5.108442753387092139e-02,8.808354487345606998e+00,3.678564516606208385e-03,1.000000009943406987e+00,-4.000000000000000327e-05,-1.684962700665036021e-09,0.000000000000000000e+00 +7.996112331756093283e+01,4.927631384421235339e+02,5.112121309607414732e-02,8.809489773182910710e+00,3.678418531204670668e-03,1.000000009941494072e+00,-4.000000000000000327e-05,3.579662407587830704e-10,0.000000000000000000e+00 +7.996225845708177360e+01,4.927731383744697951e+02,5.115799719843323184e-02,8.810624912715038448e+00,3.678272545803132950e-03,1.000000009941900414e+00,-4.000000000000000327e-05,3.388401192699330356e-10,0.000000000000000000e+00 +7.996339345035399049e+01,4.927831383068213995e+02,5.119477984094818190e-02,8.811759905998544085e+00,3.678126560401595233e-03,1.000000009942284995e+00,-4.000000000000000327e-05,9.900414959929688725e-10,0.000000000000000000e+00 +7.996452829743410007e+01,4.927931382391784041e+02,5.123156102361899056e-02,8.812894753089942412e+00,3.677980575000057515e-03,1.000000009943408541e+00,-4.000000000000000327e-05,-1.853142379809863568e-09,0.000000000000000000e+00 +7.996566299837859049e+01,4.928031381715407520e+02,5.126834074644565781e-02,8.814029454045712697e+00,3.677834589598519797e-03,1.000000009941305779e+00,-4.000000000000000327e-05,1.441801233691525739e-09,0.000000000000000000e+00 +7.996679755324389305e+01,4.928131381039084999e+02,5.130511900942818365e-02,8.815164008922293348e+00,3.677688604196982080e-03,1.000000009942941581e+00,-4.000000000000000327e-05,-1.569410935065883684e-09,0.000000000000000000e+00 +7.996793196208641064e+01,4.928231380362815912e+02,5.134189581256656809e-02,8.816298417776094354e+00,3.677542618795444362e-03,1.000000009941161228e+00,-4.000000000000000327e-05,1.509514226937712972e-09,0.000000000000000000e+00 +7.996906622496251771e+01,4.928331379686600826e+02,5.137867115586081113e-02,8.817432680663481293e+00,3.677396633393906645e-03,1.000000009942873413e+00,-4.000000000000000327e-05,-1.771670550872435781e-09,0.000000000000000000e+00 +7.997020034192854610e+01,4.928431379010439173e+02,5.141544503931090582e-02,8.818566797640791322e+00,3.677250647992368927e-03,1.000000009940864132e+00,-4.000000000000000327e-05,9.892397892326273203e-10,0.000000000000000000e+00 +7.997133431304079920e+01,4.928531378334331521e+02,5.145221746291685910e-02,8.819700768764317189e+00,3.677104662590831210e-03,1.000000009941985901e+00,-4.000000000000000327e-05,9.987671561062066225e-11,0.000000000000000000e+00 +7.997246813835553780e+01,4.928631377658277302e+02,5.148898842667866405e-02,8.820834594090323222e+00,3.676958677189293492e-03,1.000000009942099144e+00,-4.000000000000000327e-05,-3.221927815051058183e-10,0.000000000000000000e+00 +7.997360181792898004e+01,4.928731376982277084e+02,5.152575793059632064e-02,8.821968273675032890e+00,3.676812691787755775e-03,1.000000009941733881e+00,-4.000000000000000327e-05,1.080904719822113977e-09,0.000000000000000000e+00 +7.997473535181731563e+01,4.928831376306330299e+02,5.156252597466983584e-02,8.823101807574634137e+00,3.676666706386218057e-03,1.000000009942959123e+00,-4.000000000000000327e-05,-1.246197602843995795e-09,0.000000000000000000e+00 +7.997586874007669167e+01,4.928931375630436946e+02,5.159929255889920269e-02,8.824235195845281154e+00,3.676520720984680340e-03,1.000000009941546697e+00,-4.000000000000000327e-05,-4.159750615246767397e-10,0.000000000000000000e+00 +7.997700198276322681e+01,4.929031374954597595e+02,5.163605768328442119e-02,8.825368438543087279e+00,3.676374735583142622e-03,1.000000009941075296e+00,-4.000000000000000327e-05,7.826744040327035996e-10,0.000000000000000000e+00 +7.997813507993301130e+01,4.929131374278811677e+02,5.167282134782548442e-02,8.826501535724133873e+00,3.676228750181604905e-03,1.000000009941962142e+00,-4.000000000000000327e-05,9.401530191437118490e-10,0.000000000000000000e+00 +7.997926803164207854e+01,4.929231373603079760e+02,5.170958355252239930e-02,8.827634487444466771e+00,3.676082764780067187e-03,1.000000009943027290e+00,-4.000000000000000327e-05,-1.353664819576471970e-09,0.000000000000000000e+00 +7.998040083794644772e+01,4.929331372927401276e+02,5.174634429737516583e-02,8.828767293760094503e+00,3.675936779378529470e-03,1.000000009941493850e+00,-4.000000000000000327e-05,-5.875259296716839520e-10,0.000000000000000000e+00 +7.998153349890208119e+01,4.929431372251776224e+02,5.178310358238377709e-02,8.829899954726986522e+00,3.675790793976991752e-03,1.000000009940828383e+00,-4.000000000000000327e-05,1.831229958274561751e-09,0.000000000000000000e+00 +7.998266601456491287e+01,4.929531371576205174e+02,5.181986140754824000e-02,8.831032470401080303e+00,3.675644808575454035e-03,1.000000009942902279e+00,-4.000000000000000327e-05,-1.047503760551350776e-09,0.000000000000000000e+00 +7.998379838499084826e+01,4.929631370900687557e+02,5.185661777286854762e-02,8.832164840838279574e+00,3.675498823173916317e-03,1.000000009941716117e+00,-4.000000000000000327e-05,-9.401679045723800335e-10,0.000000000000000000e+00 +7.998493061023576445e+01,4.929731370225223941e+02,5.189337267834469997e-02,8.833297066094445427e+00,3.675352837772378600e-03,1.000000009940651635e+00,-4.000000000000000327e-05,7.457189409374694501e-10,0.000000000000000000e+00 +7.998606269035546745e+01,4.929831369549813758e+02,5.193012612397669703e-02,8.834429146225406981e+00,3.675206852370840882e-03,1.000000009941495849e+00,-4.000000000000000327e-05,1.213076524570098562e-09,0.000000000000000000e+00 +7.998719462540576330e+01,4.929931368874457007e+02,5.196687810976453881e-02,8.835561081286959606e+00,3.675060866969303165e-03,1.000000009942868973e+00,-4.000000000000000327e-05,-2.337590349810938873e-09,0.000000000000000000e+00 +7.998832641544241540e+01,4.930031368199154258e+02,5.200362863570822530e-02,8.836692871334861366e+00,3.674914881567765447e-03,1.000000009940223311e+00,-4.000000000000000327e-05,1.162371722646942597e-09,0.000000000000000000e+00 +7.998945806052113028e+01,4.930131367523904942e+02,5.204037770180775652e-02,8.837824516424829469e+00,3.674768896166227729e-03,1.000000009941538703e+00,-4.000000000000000327e-05,5.944083105780163759e-10,0.000000000000000000e+00 +7.999058956069760029e+01,4.930231366848709627e+02,5.207712530806312551e-02,8.838956016612554478e+00,3.674622910764690012e-03,1.000000009942211276e+00,-4.000000000000000327e-05,-1.294951519295253811e-09,0.000000000000000000e+00 +7.999172091602748935e+01,4.930331366173567744e+02,5.211387145447433922e-02,8.840087371953686102e+00,3.674476925363152294e-03,1.000000009940746226e+00,-4.000000000000000327e-05,1.021686175018275765e-09,0.000000000000000000e+00 +7.999285212656639033e+01,4.930431365498479295e+02,5.215061614104139071e-02,8.841218582503836743e+00,3.674330939961614577e-03,1.000000009941901968e+00,-4.000000000000000327e-05,5.801093141699373086e-10,0.000000000000000000e+00 +7.999398319236989607e+01,4.930531364823444846e+02,5.218735936776427997e-02,8.842349648318588606e+00,3.674184954560076859e-03,1.000000009942558110e+00,-4.000000000000000327e-05,-1.258340518363572733e-09,0.000000000000000000e+00 +7.999511411349354262e+01,4.930631364148463831e+02,5.222410113464300702e-02,8.843480569453484819e+00,3.674038969158539142e-03,1.000000009941135026e+00,-4.000000000000000327e-05,-3.514928397079616913e-10,0.000000000000000000e+00 +7.999624488999285177e+01,4.930731363473536248e+02,5.226084144167757184e-02,8.844611345964031202e+00,3.673892983757001424e-03,1.000000009940737566e+00,-4.000000000000000327e-05,4.984373712892223579e-10,0.000000000000000000e+00 +7.999737552192328849e+01,4.930831362798662667e+02,5.229758028886797444e-02,8.845741977905701603e+00,3.673746998355463707e-03,1.000000009941301116e+00,-4.000000000000000327e-05,-1.229557451003275738e-10,0.000000000000000000e+00 +7.999850600934028932e+01,4.930931362123842518e+02,5.233431767621421482e-02,8.846872465333934343e+00,3.673601012953925989e-03,1.000000009941162116e+00,-4.000000000000000327e-05,5.392278827307894244e-10,0.000000000000000000e+00 +7.999963635229924819e+01,4.931031361449075803e+02,5.237105360371629298e-02,8.848002808304130440e+00,3.673455027552388272e-03,1.000000009941771628e+00,-4.000000000000000327e-05,-3.212204855790824111e-10,0.000000000000000000e+00 +8.000076655085554478e+01,4.931131360774363088e+02,5.240778807137420198e-02,8.849133006871657159e+00,3.673309042150850554e-03,1.000000009941408585e+00,-4.000000000000000327e-05,5.285587032163254007e-11,0.000000000000000000e+00 +8.000189660506450195e+01,4.931231360099703807e+02,5.244452107918794875e-02,8.850263061091844463e+00,3.673163056749312837e-03,1.000000009941468315e+00,-4.000000000000000327e-05,-1.145684295126635481e-09,0.000000000000000000e+00 +8.000302651498141415e+01,4.931331359425097958e+02,5.248125262715752637e-02,8.851392971019988565e+00,3.673017071347775119e-03,1.000000009940173795e+00,-4.000000000000000327e-05,1.624799532505210979e-09,0.000000000000000000e+00 +8.000415628066154738e+01,4.931431358750546110e+02,5.251798271528293482e-02,8.852522736711348372e+00,3.672871085946237402e-03,1.000000009942009438e+00,-4.000000000000000327e-05,-1.402691346389865610e-09,0.000000000000000000e+00 +8.000528590216012503e+01,4.931531358076047695e+02,5.255471134356418106e-02,8.853652358221152596e+00,3.672725100544699684e-03,1.000000009940424928e+00,-4.000000000000000327e-05,8.828882678451320367e-10,0.000000000000000000e+00 +8.000641537953232785e+01,4.931631357401602713e+02,5.259143851200125813e-02,8.854781835604587314e+00,3.672579115143161967e-03,1.000000009941422130e+00,-4.000000000000000327e-05,1.042062963223606879e-10,0.000000000000000000e+00 +8.000754471283332236e+01,4.931731356727211733e+02,5.262816422059415911e-02,8.855911168916810183e+00,3.672433129741624249e-03,1.000000009941539814e+00,-4.000000000000000327e-05,-9.800573967018472877e-10,0.000000000000000000e+00 +8.000867390211823249e+01,4.931831356052874185e+02,5.266488846934289092e-02,8.857040358212939779e+00,3.672287144340086532e-03,1.000000009940433143e+00,-4.000000000000000327e-05,1.786118820252589471e-09,0.000000000000000000e+00 +8.000980294744212529e+01,4.931931355378590069e+02,5.270161125824745357e-02,8.858169403548059151e+00,3.672141158938548814e-03,1.000000009942449752e+00,-4.000000000000000327e-05,-1.375459271790981249e-09,0.000000000000000000e+00 +8.001093184886006782e+01,4.932031354704359956e+02,5.273833258730784707e-02,8.859298304977221150e+00,3.671995173537011097e-03,1.000000009940896994e+00,-4.000000000000000327e-05,-7.351274648059708310e-10,0.000000000000000000e+00 +8.001206060642705609e+01,4.932131354030183275e+02,5.277505245652406446e-02,8.860427062555435995e+00,3.671849188135473379e-03,1.000000009940067214e+00,-4.000000000000000327e-05,8.967454901115984516e-10,0.000000000000000000e+00 +8.001318922019808610e+01,4.932231353356060026e+02,5.281177086589610575e-02,8.861555676337683707e+00,3.671703202733935661e-03,1.000000009941079293e+00,-4.000000000000000327e-05,7.069804640620634977e-10,0.000000000000000000e+00 +8.001431769022809704e+01,4.932331352681990779e+02,5.284848781542397789e-02,8.862684146378910555e+00,3.671557217332397944e-03,1.000000009941877099e+00,-4.000000000000000327e-05,-1.331291926703966475e-09,0.000000000000000000e+00 +8.001544601657199962e+01,4.932431352007974965e+02,5.288520330510767392e-02,8.863812472734025505e+00,3.671411231930860226e-03,1.000000009940374968e+00,-4.000000000000000327e-05,3.393110837411552513e-10,0.000000000000000000e+00 +8.001657419928466197e+01,4.932531351334012584e+02,5.292191733494719386e-02,8.864940655457900220e+00,3.671265246529322509e-03,1.000000009940757772e+00,-4.000000000000000327e-05,1.133805453422398504e-10,0.000000000000000000e+00 +8.001770223842092378e+01,4.932631350660103635e+02,5.295862990494253075e-02,8.866068694605376166e+00,3.671119261127784791e-03,1.000000009940885670e+00,-4.000000000000000327e-05,-6.396185179007944144e-10,0.000000000000000000e+00 +8.001883013403559630e+01,4.932731349986248688e+02,5.299534101509369155e-02,8.867196590231257503e+00,3.670973275726247074e-03,1.000000009940164247e+00,-4.000000000000000327e-05,8.501767040729150554e-10,0.000000000000000000e+00 +8.001995788618344818e+01,4.932831349312447173e+02,5.303205066540067625e-02,8.868324342390312864e+00,3.670827290324709356e-03,1.000000009941123036e+00,-4.000000000000000327e-05,3.682335885162287972e-10,0.000000000000000000e+00 +8.002108549491920542e+01,4.932931348638699092e+02,5.306875885586347791e-02,8.869451951137278911e+00,3.670681304923171639e-03,1.000000009941538259e+00,-4.000000000000000327e-05,-7.137156170715974338e-10,0.000000000000000000e+00 +8.002221296029757980e+01,4.933031347965005011e+02,5.310546558648210347e-02,8.870579416526854999e+00,3.670535319521633921e-03,1.000000009940733570e+00,-4.000000000000000327e-05,3.746301502401756381e-10,0.000000000000000000e+00 +8.002334028237322627e+01,4.933131347291364364e+02,5.314217085725654599e-02,8.871706738613704957e+00,3.670389334120096204e-03,1.000000009941155898e+00,-4.000000000000000327e-05,-5.830947268647205509e-10,0.000000000000000000e+00 +8.002446746120077137e+01,4.933231346617777149e+02,5.317887466818680547e-02,8.872833917452460639e+00,3.670243348718558486e-03,1.000000009940498646e+00,-4.000000000000000327e-05,-8.166333517820689517e-10,0.000000000000000000e+00 +8.002559449683482740e+01,4.933331345944243367e+02,5.321557701927288886e-02,8.873960953097716597e+00,3.670097363317020769e-03,1.000000009939578272e+00,-4.000000000000000327e-05,1.050428318571137746e-09,0.000000000000000000e+00 +8.002672138932994983e+01,4.933431345270763586e+02,5.325227791051478921e-02,8.875087845604033632e+00,3.669951377915483051e-03,1.000000009940761991e+00,-4.000000000000000327e-05,7.973312104628575859e-10,0.000000000000000000e+00 +8.002784813874065151e+01,4.933531344597337238e+02,5.328897734191249957e-02,8.876214595025940568e+00,3.669805392513945334e-03,1.000000009941660384e+00,-4.000000000000000327e-05,-1.602945627373530437e-09,0.000000000000000000e+00 +8.002897474512144527e+01,4.933631343923964323e+02,5.332567531346602691e-02,8.877341201417928929e+00,3.669659407112407616e-03,1.000000009939854495e+00,-4.000000000000000327e-05,8.249328537587092644e-10,0.000000000000000000e+00 +8.003010120852677289e+01,4.933731343250644841e+02,5.336237182517537120e-02,8.878467664834452933e+00,3.669513421710869899e-03,1.000000009940783752e+00,-4.000000000000000327e-05,-3.420406491036537397e-10,0.000000000000000000e+00 +8.003122752901106196e+01,4.933831342577379360e+02,5.339906687704052551e-02,8.879593985329938377e+00,3.669367436309332181e-03,1.000000009940398504e+00,-4.000000000000000327e-05,4.722139922389612548e-10,0.000000000000000000e+00 +8.003235370662869741e+01,4.933931341904167311e+02,5.343576046906149679e-02,8.880720162958771979e+00,3.669221450907794464e-03,1.000000009940930301e+00,-4.000000000000000327e-05,-9.583511760164948199e-10,0.000000000000000000e+00 +8.003347974143403576e+01,4.934031341231008696e+02,5.347245260123827809e-02,8.881846197775308482e+00,3.669075465506256746e-03,1.000000009939851164e+00,-4.000000000000000327e-05,9.462452611891586675e-10,0.000000000000000000e+00 +8.003460563348140511e+01,4.934131340557903513e+02,5.350914327357086941e-02,8.882972089833865326e+00,3.668929480104719029e-03,1.000000009940916534e+00,-4.000000000000000327e-05,-8.443913016926435758e-10,0.000000000000000000e+00 +8.003573138282507671e+01,4.934231339884852332e+02,5.354583248605927076e-02,8.884097839188729751e+00,3.668783494703181311e-03,1.000000009939965961e+00,-4.000000000000000327e-05,6.531497108842350998e-10,0.000000000000000000e+00 +8.003685698951930760e+01,4.934331339211854583e+02,5.358252023870348213e-02,8.885223445894149918e+00,3.668637509301643593e-03,1.000000009940701151e+00,-4.000000000000000327e-05,-1.921620115541622742e-10,0.000000000000000000e+00 +8.003798245361831221e+01,4.934431338538910268e+02,5.361920653150350352e-02,8.886348910004343793e+00,3.668491523900105876e-03,1.000000009940484880e+00,-4.000000000000000327e-05,-6.006316795493398644e-10,0.000000000000000000e+00 +8.003910777517627650e+01,4.934531337866019385e+02,5.365589136445933494e-02,8.887474231573492034e+00,3.668345538498568158e-03,1.000000009939808976e+00,-4.000000000000000327e-05,8.071270231532330139e-10,0.000000000000000000e+00 +8.004023295424734386e+01,4.934631337193181935e+02,5.369257473757097637e-02,8.888599410655741551e+00,3.668199553097030441e-03,1.000000009940717138e+00,-4.000000000000000327e-05,-2.017086186454390389e-10,0.000000000000000000e+00 +8.004135799088562919e+01,4.934731336520398486e+02,5.372925665083842089e-02,8.889724447305207278e+00,3.668053567695492723e-03,1.000000009940490209e+00,-4.000000000000000327e-05,-8.458227286723477608e-10,0.000000000000000000e+00 +8.004248288514520482e+01,4.934831335847668470e+02,5.376593710426166850e-02,8.890849341575966847e+00,3.667907582293955006e-03,1.000000009939538748e+00,-4.000000000000000327e-05,1.660075457395045048e-09,0.000000000000000000e+00 +8.004360763708012882e+01,4.934931335174991887e+02,5.380261609784072613e-02,8.891974093522064138e+00,3.667761596892417288e-03,1.000000009941405921e+00,-4.000000000000000327e-05,-1.133314138020239492e-09,0.000000000000000000e+00 +8.004473224674440246e+01,4.935031334502368736e+02,5.383929363157558684e-02,8.893098703197512833e+00,3.667615611490879571e-03,1.000000009940131385e+00,-4.000000000000000327e-05,-8.242249990774478562e-10,0.000000000000000000e+00 +8.004585671419199855e+01,4.935131333829799019e+02,5.387596970546625064e-02,8.894223170656285760e+00,3.667469626089341853e-03,1.000000009939204570e+00,-4.000000000000000327e-05,1.160854607931530694e-09,0.000000000000000000e+00 +8.004698103947686150e+01,4.935231333157283302e+02,5.391264431951271752e-02,8.895347495952325545e+00,3.667323640687804136e-03,1.000000009940509749e+00,-4.000000000000000327e-05,-8.238408712028444487e-10,0.000000000000000000e+00 +8.004810522265290729e+01,4.935331332484821019e+02,5.394931747371498748e-02,8.896471679139542843e+00,3.667177655286266418e-03,1.000000009939583601e+00,-4.000000000000000327e-05,2.249996021173026262e-10,0.000000000000000000e+00 +8.004922926377399506e+01,4.935431331812412168e+02,5.398598916807305359e-02,8.897595720271809228e+00,3.667031669884728701e-03,1.000000009939836509e+00,-4.000000000000000327e-05,1.473844692361840692e-09,0.000000000000000000e+00 +8.005035316289398395e+01,4.935531331140056750e+02,5.402265940258692278e-02,8.898719619402966075e+00,3.666885684483190983e-03,1.000000009941492962e+00,-4.000000000000000327e-05,-1.321885584411172051e-09,0.000000000000000000e+00 +8.005147692006666205e+01,4.935631330467754765e+02,5.405932817725659506e-02,8.899843376586821009e+00,3.666739699081653266e-03,1.000000009940007484e+00,-4.000000000000000327e-05,-1.153881112345499508e-09,0.000000000000000000e+00 +8.005260053534581743e+01,4.935731329795506781e+02,5.409599549208206348e-02,8.900966991877142576e+00,3.666593713680115548e-03,1.000000009938710965e+00,-4.000000000000000327e-05,1.956647582170483706e-09,0.000000000000000000e+00 +8.005372400878518135e+01,4.935831329123312230e+02,5.413266134706332805e-02,8.902090465327669122e+00,3.666447728278577831e-03,1.000000009940909207e+00,-4.000000000000000327e-05,-1.865375137051144425e-09,0.000000000000000000e+00 +8.005484734043845663e+01,4.935931328451171112e+02,5.416932574220038876e-02,8.903213796992108797e+00,3.666301742877040113e-03,1.000000009938813772e+00,-4.000000000000000327e-05,1.431085576185117694e-09,0.000000000000000000e+00 +8.005597053035931765e+01,4.936031327779083426e+02,5.420598867749324562e-02,8.904336986924127118e+00,3.666155757475502396e-03,1.000000009940421153e+00,-4.000000000000000327e-05,-8.480039190165729897e-10,0.000000000000000000e+00 +8.005709357860139619e+01,4.936131327107049174e+02,5.424265015294189862e-02,8.905460035177364730e+00,3.666009772073964678e-03,1.000000009939468804e+00,-4.000000000000000327e-05,1.131275892102261472e-09,0.000000000000000000e+00 +8.005821648521829559e+01,4.936231326435068354e+02,5.427931016854634777e-02,8.906582941805421427e+00,3.665863786672426961e-03,1.000000009940739121e+00,-4.000000000000000327e-05,-1.106895569098152986e-09,0.000000000000000000e+00 +8.005933925026357656e+01,4.936331325763140967e+02,5.431596872430659306e-02,8.907705706861868578e+00,3.665717801270889243e-03,1.000000009939496337e+00,-4.000000000000000327e-05,8.683016095717112386e-10,0.000000000000000000e+00 +8.006046187379078560e+01,4.936431325091267581e+02,5.435262582022263450e-02,8.908828330400238471e+00,3.665571815869351525e-03,1.000000009940471113e+00,-4.000000000000000327e-05,-1.423086337857244795e-09,0.000000000000000000e+00 +8.006158435585342659e+01,4.936531324419447628e+02,5.438928145629446514e-02,8.909950812474034976e+00,3.665425830467813808e-03,1.000000009938873724e+00,-4.000000000000000327e-05,4.532529309959179452e-10,0.000000000000000000e+00 +8.006270669650496075e+01,4.936631323747681108e+02,5.442593563252208499e-02,8.911073153136722880e+00,3.665279845066276090e-03,1.000000009939382428e+00,-4.000000000000000327e-05,8.349927128889372889e-10,0.000000000000000000e+00 +8.006382889579882089e+01,4.936731323075968021e+02,5.446258834890550099e-02,8.912195352441738549e+00,3.665133859664738373e-03,1.000000009940319456e+00,-4.000000000000000327e-05,-3.023766681160772306e-10,0.000000000000000000e+00 +8.006495095378841143e+01,4.936831322404308366e+02,5.449923960544470619e-02,8.913317410442482824e+00,3.664987874263200655e-03,1.000000009939980172e+00,-4.000000000000000327e-05,-1.616968853109026054e-10,0.000000000000000000e+00 +8.006607287052709410e+01,4.936931321732702145e+02,5.453588940213970060e-02,8.914439327192321016e+00,3.664841888861662938e-03,1.000000009939798762e+00,-4.000000000000000327e-05,-1.767607020571380665e-10,0.000000000000000000e+00 +8.006719464606820225e+01,4.937031321061149356e+02,5.457253773899048421e-02,8.915561102744586464e+00,3.664695903460125220e-03,1.000000009939600476e+00,-4.000000000000000327e-05,-3.711847955144808666e-10,0.000000000000000000e+00 +8.006831628046504079e+01,4.937131320389650568e+02,5.460918461599705703e-02,8.916682737152578753e+00,3.664549918058587503e-03,1.000000009939184142e+00,-4.000000000000000327e-05,6.440618914628734521e-10,0.000000000000000000e+00 +8.006943777377087201e+01,4.937231319718205214e+02,5.464583003315941212e-02,8.917804230469563720e+00,3.664403932657049785e-03,1.000000009939906453e+00,-4.000000000000000327e-05,2.098959336182590349e-11,0.000000000000000000e+00 +8.007055912603894399e+01,4.937331319046813292e+02,5.468247399047755641e-02,8.918925582748775227e+00,3.664257947255512068e-03,1.000000009939929990e+00,-4.000000000000000327e-05,-8.527599417566250488e-10,0.000000000000000000e+00 +8.007168033732243373e+01,4.937431318375474802e+02,5.471911648795148297e-02,8.920046794043411609e+00,3.664111961853974350e-03,1.000000009938973866e+00,-4.000000000000000327e-05,8.267225863520178727e-10,0.000000000000000000e+00 +8.007280140767451826e+01,4.937531317704189746e+02,5.475575752558119874e-02,8.921167864406637449e+00,3.663965976452436633e-03,1.000000009939900680e+00,-4.000000000000000327e-05,-6.170494759067208448e-10,0.000000000000000000e+00 +8.007392233714833196e+01,4.937631317032958123e+02,5.479239710336669678e-02,8.922288793891587133e+00,3.663819991050898915e-03,1.000000009939209011e+00,-4.000000000000000327e-05,4.465503287461123183e-10,0.000000000000000000e+00 +8.007504312579696659e+01,4.937731316361779932e+02,5.482903522130797708e-02,8.923409582551357744e+00,3.663674005649361198e-03,1.000000009939709500e+00,-4.000000000000000327e-05,-2.474762299221976303e-10,0.000000000000000000e+00 +8.007616377367348548e+01,4.937831315690655174e+02,5.486567187940503965e-02,8.924530230439016165e+00,3.663528020247823480e-03,1.000000009939432166e+00,-4.000000000000000327e-05,-1.309073887118653512e-09,0.000000000000000000e+00 +8.007728428083092354e+01,4.937931315019583849e+02,5.490230707765788448e-02,8.925650737607593754e+00,3.663382034846285763e-03,1.000000009937965340e+00,-4.000000000000000327e-05,1.484041172688092162e-09,0.000000000000000000e+00 +8.007840464732228725e+01,4.938031314348565957e+02,5.493894081606651159e-02,8.926771104110088118e+00,3.663236049444748045e-03,1.000000009939628010e+00,-4.000000000000000327e-05,-3.813639982543428481e-10,0.000000000000000000e+00 +8.007952487320052626e+01,4.938131313677602066e+02,5.497557309463092096e-02,8.927891329999468439e+00,3.663090064043210328e-03,1.000000009939200796e+00,-4.000000000000000327e-05,1.464986286252491467e-10,0.000000000000000000e+00 +8.008064495851859022e+01,4.938231313006691607e+02,5.501220391335110566e-02,8.929011415328664825e+00,3.662944078641672610e-03,1.000000009939364887e+00,-4.000000000000000327e-05,2.143232555866855409e-10,0.000000000000000000e+00 +8.008176490332937192e+01,4.938331312335834582e+02,5.504883327222707262e-02,8.930131360150577180e+00,3.662798093240134892e-03,1.000000009939604917e+00,-4.000000000000000327e-05,-2.018579464609545954e-10,0.000000000000000000e+00 +8.008288470768573575e+01,4.938431311665030989e+02,5.508546117125881492e-02,8.931251164518071661e+00,3.662652107838597175e-03,1.000000009939378876e+00,-4.000000000000000327e-05,2.917193256514424142e-10,0.000000000000000000e+00 +8.008400437164051766e+01,4.938531310994280830e+02,5.512208761044633254e-02,8.932370828483980674e+00,3.662506122437059457e-03,1.000000009939705503e+00,-4.000000000000000327e-05,-1.162263464469595563e-09,0.000000000000000000e+00 +8.008512389524651098e+01,4.938631310323584103e+02,5.515871258978962549e-02,8.933490352101104648e+00,3.662360137035521740e-03,1.000000009938404322e+00,-4.000000000000000327e-05,1.082071984697375372e-09,0.000000000000000000e+00 +8.008624327855649483e+01,4.938731309652940809e+02,5.519533610928869377e-02,8.934609735422208487e+00,3.662214151633984022e-03,1.000000009939615575e+00,-4.000000000000000327e-05,-1.503187307190102891e-09,0.000000000000000000e+00 +8.008736252162319147e+01,4.938831308982350947e+02,5.523195816894353738e-02,8.935728978500028674e+00,3.662068166232446305e-03,1.000000009937933143e+00,-4.000000000000000327e-05,9.829382054846545154e-10,0.000000000000000000e+00 +8.008848162449930896e+01,4.938931308311814519e+02,5.526857876875415632e-02,8.936848081387262610e+00,3.661922180830908587e-03,1.000000009939033152e+00,-4.000000000000000327e-05,1.012033239768395984e-11,0.000000000000000000e+00 +8.008960058723751274e+01,4.939031307641331523e+02,5.530519790872055058e-02,8.937967044136581052e+00,3.661776195429370870e-03,1.000000009939044476e+00,-4.000000000000000327e-05,1.227492022870196960e-09,0.000000000000000000e+00 +8.009071940989042560e+01,4.939131306970901960e+02,5.534181558884271324e-02,8.939085866800617453e+00,3.661630210027833152e-03,1.000000009940417822e+00,-4.000000000000000327e-05,-2.482285662579653129e-09,0.000000000000000000e+00 +8.009183809251065611e+01,4.939231306300525830e+02,5.537843180912065122e-02,8.940204549431975067e+00,3.661484224626295435e-03,1.000000009937640932e+00,-4.000000000000000327e-05,1.630978032144028366e-09,0.000000000000000000e+00 +8.009295663515078445e+01,4.939331305630203133e+02,5.541504656955435759e-02,8.941323092083218071e+00,3.661338239224757717e-03,1.000000009939465251e+00,-4.000000000000000327e-05,-6.500109740121930231e-10,0.000000000000000000e+00 +8.009407503786333393e+01,4.939431304959933868e+02,5.545165987014383235e-02,8.942441494806887547e+00,3.661192253823220000e-03,1.000000009938738277e+00,-4.000000000000000327e-05,5.891337177009078787e-10,0.000000000000000000e+00 +8.009519330070081367e+01,4.939531304289718037e+02,5.548827171088907551e-02,8.943559757655483722e+00,3.661046268421682282e-03,1.000000009939397083e+00,-4.000000000000000327e-05,-3.538818901947420612e-10,0.000000000000000000e+00 +8.009631142371569013e+01,4.939631303619555638e+02,5.552488209179008705e-02,8.944677880681478399e+00,3.660900283020144565e-03,1.000000009939001400e+00,-4.000000000000000327e-05,-6.627673984701341885e-10,0.000000000000000000e+00 +8.009742940696040137e+01,4.939731302949446672e+02,5.556149101284686698e-02,8.945795863937307857e+00,3.660754297618606847e-03,1.000000009938260437e+00,-4.000000000000000327e-05,1.062705653966147199e-09,0.000000000000000000e+00 +8.009854725048735702e+01,4.939831302279391139e+02,5.559809847405941530e-02,8.946913707475376398e+00,3.660608312217069130e-03,1.000000009939448375e+00,-4.000000000000000327e-05,-8.868244536535135767e-10,0.000000000000000000e+00 +8.009966495434892408e+01,4.939931301609389038e+02,5.563470447542773201e-02,8.948031411348058128e+00,3.660462326815531412e-03,1.000000009938457168e+00,-4.000000000000000327e-05,5.738057743614620662e-10,0.000000000000000000e+00 +8.010078251859745535e+01,4.940031300939440371e+02,5.567130901695181017e-02,8.949148975607689849e+00,3.660316341413993695e-03,1.000000009939098433e+00,-4.000000000000000327e-05,-2.652792182019917556e-10,0.000000000000000000e+00 +8.010189994328523255e+01,4.940131300269545136e+02,5.570791209863165672e-02,8.950266400306579939e+00,3.660170356012455977e-03,1.000000009938802004e+00,-4.000000000000000327e-05,-5.836871523379289100e-10,0.000000000000000000e+00 +8.010301722846455164e+01,4.940231299599703334e+02,5.574451372046726472e-02,8.951383685497001252e+00,3.660024370610918260e-03,1.000000009938149859e+00,-4.000000000000000327e-05,-4.030865888668504068e-10,0.000000000000000000e+00 +8.010413437418763749e+01,4.940331298929914965e+02,5.578111388245863417e-02,8.952500831231194667e+00,3.659878385209380542e-03,1.000000009937699552e+00,-4.000000000000000327e-05,1.677550421125496757e-09,0.000000000000000000e+00 +8.010525138050671501e+01,4.940431298260180029e+02,5.581771258460576507e-02,8.953617837561369086e+00,3.659732399807842824e-03,1.000000009939573387e+00,-4.000000000000000327e-05,-1.483522111908784561e-09,0.000000000000000000e+00 +8.010636824747395224e+01,4.940531297590498525e+02,5.585430982690865742e-02,8.954734704539703216e+00,3.659586414406305107e-03,1.000000009937916490e+00,-4.000000000000000327e-05,1.482514154927905712e-09,0.000000000000000000e+00 +8.010748497514148880e+01,4.940631296920870454e+02,5.589090560936731122e-02,8.955851432218336683e+00,3.659440429004767389e-03,1.000000009939572054e+00,-4.000000000000000327e-05,-8.413760224027684942e-10,0.000000000000000000e+00 +8.010860156356143591e+01,4.940731296251295817e+02,5.592749993198172648e-02,8.956968020649384243e+00,3.659294443603229672e-03,1.000000009938632584e+00,-4.000000000000000327e-05,-1.355199954316097554e-09,0.000000000000000000e+00 +8.010971801278587634e+01,4.940831295581774611e+02,5.596409279475190318e-02,8.958084469884921575e+00,3.659148458201691954e-03,1.000000009937119572e+00,-4.000000000000000327e-05,1.344031036754343290e-09,0.000000000000000000e+00 +8.011083432286685024e+01,4.940931294912306839e+02,5.600068419767783440e-02,8.959200779976994156e+00,3.659002472800154237e-03,1.000000009938619927e+00,-4.000000000000000327e-05,1.082202155512908983e-10,0.000000000000000000e+00 +8.011195049385638356e+01,4.941031294242892500e+02,5.603727414075952706e-02,8.960316950977619044e+00,3.658856487398616519e-03,1.000000009938740719e+00,-4.000000000000000327e-05,6.151812395587885632e-10,0.000000000000000000e+00 +8.011306652580644538e+01,4.941131293573531593e+02,5.607386262399697424e-02,8.961432982938775993e+00,3.658710501997078802e-03,1.000000009939427281e+00,-4.000000000000000327e-05,-1.435270038506461835e-09,0.000000000000000000e+00 +8.011418241876899060e+01,4.941231292904224119e+02,5.611044964739017593e-02,8.962548875912414559e+00,3.658564516595541084e-03,1.000000009937825673e+00,-4.000000000000000327e-05,-3.608025236807411838e-10,0.000000000000000000e+00 +8.011529817279593146e+01,4.941331292234970078e+02,5.614703521093913213e-02,8.963664629950448770e+00,3.658418531194003367e-03,1.000000009937423107e+00,-4.000000000000000327e-05,9.647145851359133481e-10,0.000000000000000000e+00 +8.011641378793916601e+01,4.941431291565769470e+02,5.618361931464384285e-02,8.964780245104764234e+00,3.658272545792465649e-03,1.000000009938499357e+00,-4.000000000000000327e-05,-3.368063200496708967e-10,0.000000000000000000e+00 +8.011752926425053545e+01,4.941531290896622295e+02,5.622020195850430807e-02,8.965895721427214582e+00,3.658126560390927932e-03,1.000000009938123657e+00,-4.000000000000000327e-05,-6.171569197116336978e-12,0.000000000000000000e+00 +8.011864460178185254e+01,4.941631290227528552e+02,5.625678314252052781e-02,8.967011058969617920e+00,3.657980574989390214e-03,1.000000009938116774e+00,-4.000000000000000327e-05,5.069280585553814495e-10,0.000000000000000000e+00 +8.011975980058491587e+01,4.941731289558488243e+02,5.629336286669250206e-02,8.968126257783762156e+00,3.657834589587852497e-03,1.000000009938682100e+00,-4.000000000000000327e-05,-2.479198444525106491e-10,0.000000000000000000e+00 +8.012087486071148135e+01,4.941831288889501366e+02,5.632994113102022388e-02,8.969241317921403223e+00,3.657688604186314779e-03,1.000000009938405654e+00,-4.000000000000000327e-05,5.630173040175058616e-10,0.000000000000000000e+00 +8.012198978221326229e+01,4.941931288220567922e+02,5.636651793550369327e-02,8.970356239434263301e+00,3.657542618784777062e-03,1.000000009939033374e+00,-4.000000000000000327e-05,-1.369375704965104638e-09,0.000000000000000000e+00 +8.012310456514195778e+01,4.942031287551687910e+02,5.640309328014291718e-02,8.971471022374034376e+00,3.657396633383239344e-03,1.000000009937506817e+00,-4.000000000000000327e-05,1.079301759059847783e-09,0.000000000000000000e+00 +8.012421920954922427e+01,4.942131286882861332e+02,5.643966716493788865e-02,8.972585666792372905e+00,3.657250647981701627e-03,1.000000009938709855e+00,-4.000000000000000327e-05,-6.913330411200021641e-10,0.000000000000000000e+00 +8.012533371548668981e+01,4.942231286214088186e+02,5.647623958988860771e-02,8.973700172740908698e+00,3.657104662580163909e-03,1.000000009937939360e+00,-4.000000000000000327e-05,-9.845247406994956166e-10,0.000000000000000000e+00 +8.012644808300593979e+01,4.942331285545368473e+02,5.651281055499507433e-02,8.974814540271234264e+00,3.656958677178626192e-03,1.000000009936842238e+00,-4.000000000000000327e-05,1.609193387712486721e-09,0.000000000000000000e+00 +8.012756231215854541e+01,4.942431284876701625e+02,5.654938006025728853e-02,8.975928769434911914e+00,3.656812691777088474e-03,1.000000009938635248e+00,-4.000000000000000327e-05,-8.610004328159795951e-11,0.000000000000000000e+00 +8.012867640299603522e+01,4.942531284208088209e+02,5.658594810567525030e-02,8.977042860283475534e+00,3.656666706375550756e-03,1.000000009938539325e+00,-4.000000000000000327e-05,-1.802345418304333670e-09,0.000000000000000000e+00 +8.012979035556990937e+01,4.942631283539528226e+02,5.662251469124895270e-02,8.978156812868421710e+00,3.656520720974013039e-03,1.000000009936531598e+00,-4.000000000000000327e-05,2.166591533786599634e-09,0.000000000000000000e+00 +8.013090416993163956e+01,4.942731282871021676e+02,5.665907981697840268e-02,8.979270627241215053e+00,3.656374735572475321e-03,1.000000009938944778e+00,-4.000000000000000327e-05,-1.087617135722159250e-09,0.000000000000000000e+00 +8.013201784613265488e+01,4.942831282202568559e+02,5.669564348286359329e-02,8.980384303453295303e+00,3.656228750170937604e-03,1.000000009937733525e+00,-4.000000000000000327e-05,-1.330028605118404698e-10,0.000000000000000000e+00 +8.013313138422435600e+01,4.942931281534168875e+02,5.673220568890452453e-02,8.981497841556061346e+00,3.656082764769399886e-03,1.000000009937585421e+00,-4.000000000000000327e-05,7.141563733850608849e-10,0.000000000000000000e+00 +8.013424478425811515e+01,4.943031280865822623e+02,5.676876643510120335e-02,8.982611241600885421e+00,3.655936779367862169e-03,1.000000009938380563e+00,-4.000000000000000327e-05,-1.436667424431518438e-09,0.000000000000000000e+00 +8.013535804628527615e+01,4.943131280197529804e+02,5.680532572145362280e-02,8.983724503639107795e+00,3.655790793966324451e-03,1.000000009936781176e+00,-4.000000000000000327e-05,1.992992249363519317e-09,0.000000000000000000e+00 +8.013647117035714018e+01,4.943231279529290418e+02,5.684188354796178289e-02,8.984837627722033204e+00,3.655644808564786734e-03,1.000000009938999623e+00,-4.000000000000000327e-05,-1.921617443616932427e-09,0.000000000000000000e+00 +8.013758415652498002e+01,4.943331278861104465e+02,5.687843991462568360e-02,8.985950613900941519e+00,3.655498823163249016e-03,1.000000009936860890e+00,-4.000000000000000327e-05,1.135115846706168688e-09,0.000000000000000000e+00 +8.013869700484005421e+01,4.943431278192971376e+02,5.691499482144531802e-02,8.987063462227071753e+00,3.655352837761711299e-03,1.000000009938124101e+00,-4.000000000000000327e-05,-3.302600422025082027e-10,0.000000000000000000e+00 +8.013980971535356446e+01,4.943531277524891721e+02,5.695154826842069307e-02,8.988176172751639825e+00,3.655206852360173581e-03,1.000000009937756618e+00,-4.000000000000000327e-05,-6.043209810589358992e-10,0.000000000000000000e+00 +8.014092228811669827e+01,4.943631276856865497e+02,5.698810025555180181e-02,8.989288745525824353e+00,3.655060866958635864e-03,1.000000009937084267e+00,-4.000000000000000327e-05,2.922177771635904786e-10,0.000000000000000000e+00 +8.014203472318058630e+01,4.943731276188892707e+02,5.702465078283865119e-02,8.990401180600773756e+00,3.654914881557098146e-03,1.000000009937409340e+00,-4.000000000000000327e-05,9.025137023831697551e-10,0.000000000000000000e+00 +8.014314702059635920e+01,4.943831275520973350e+02,5.706119985028123426e-02,8.991513478027606254e+00,3.654768896155560429e-03,1.000000009938413204e+00,-4.000000000000000327e-05,-1.668888608704238967e-09,0.000000000000000000e+00 +8.014425918041510499e+01,4.943931274853107425e+02,5.709774745787955103e-02,8.992625637857408094e+00,3.654622910754022711e-03,1.000000009936557133e+00,-4.000000000000000327e-05,1.173498206911993345e-09,0.000000000000000000e+00 +8.014537120268788328e+01,4.944031274185294933e+02,5.713429360563360149e-02,8.993737660141229995e+00,3.654476925352484994e-03,1.000000009937862089e+00,-4.000000000000000327e-05,-6.472312409692754453e-10,0.000000000000000000e+00 +8.014648308746569683e+01,4.944131273517535874e+02,5.717083829354338564e-02,8.994849544930097807e+00,3.654330939950947276e-03,1.000000009937142442e+00,-4.000000000000000327e-05,1.467385315625545156e-09,0.000000000000000000e+00 +8.014759483479954838e+01,4.944231272849829679e+02,5.720738152160890350e-02,8.995961292275000076e+00,3.654184954549409559e-03,1.000000009938773804e+00,-4.000000000000000327e-05,-2.564995748113380545e-09,0.000000000000000000e+00 +8.014870644474039807e+01,4.944331272182176917e+02,5.724392328983015504e-02,8.997072902226898705e+00,3.654038969147871841e-03,1.000000009935922529e+00,-4.000000000000000327e-05,1.607790405636013313e-09,0.000000000000000000e+00 +8.014981791733917760e+01,4.944431271514577588e+02,5.728046359820713335e-02,8.998184374836716515e+00,3.653892983746334124e-03,1.000000009937709544e+00,-4.000000000000000327e-05,-4.125866478252375687e-10,0.000000000000000000e+00 +8.015092925264677604e+01,4.944531270847031692e+02,5.731700244673984534e-02,8.999295710155355010e+00,3.653746998344796406e-03,1.000000009937251022e+00,-4.000000000000000327e-05,-2.058192412381923842e-11,0.000000000000000000e+00 +8.015204045071405403e+01,4.944631270179539229e+02,5.735353983542828410e-02,9.000406908233676617e+00,3.653601012943258688e-03,1.000000009937228151e+00,-4.000000000000000327e-05,-1.151131274555483119e-10,0.000000000000000000e+00 +8.015315151159185802e+01,4.944731269512100198e+02,5.739007576427245655e-02,9.001517969122515339e+00,3.653455027541720971e-03,1.000000009937100254e+00,-4.000000000000000327e-05,7.217444727758736786e-10,0.000000000000000000e+00 +8.015426243533097761e+01,4.944831268844714032e+02,5.742661023327235575e-02,9.002628892872673205e+00,3.653309042140183253e-03,1.000000009937902057e+00,-4.000000000000000327e-05,-4.115910476981640253e-10,0.000000000000000000e+00 +8.015537322198218817e+01,4.944931268177381298e+02,5.746314324242798172e-02,9.003739679534922047e+00,3.653163056738645536e-03,1.000000009937444867e+00,-4.000000000000000327e-05,-6.577472687767625873e-10,0.000000000000000000e+00 +8.015648387159622246e+01,4.945031267510101998e+02,5.749967479173933443e-02,9.004850329159999944e+00,3.653017071337107818e-03,1.000000009936714340e+00,-4.000000000000000327e-05,1.402034277743656022e-09,0.000000000000000000e+00 +8.015759438422379901e+01,4.945131266842876130e+02,5.753620488120641391e-02,9.005960841798614780e+00,3.652871085935570101e-03,1.000000009938271317e+00,-4.000000000000000327e-05,-1.455999784941391060e-09,0.000000000000000000e+00 +8.015870475991559374e+01,4.945231266175703695e+02,5.757273351082921320e-02,9.007071217501446014e+00,3.652725100534032383e-03,1.000000009936654610e+00,-4.000000000000000327e-05,8.303881958730220183e-10,0.000000000000000000e+00 +8.015981499872225413e+01,4.945331265508584124e+02,5.760926068060773925e-02,9.008181456319135805e+00,3.652579115132494666e-03,1.000000009937576539e+00,-4.000000000000000327e-05,-4.056442291714469721e-10,0.000000000000000000e+00 +8.016092510069438504e+01,4.945431264841517986e+02,5.764578639054198511e-02,9.009291558302301439e+00,3.652433129730956948e-03,1.000000009937126233e+00,-4.000000000000000327e-05,-8.630004218471959758e-10,0.000000000000000000e+00 +8.016203506588257710e+01,4.945531264174505282e+02,5.768231064063195773e-02,9.010401523501524679e+00,3.652287144329419231e-03,1.000000009936168333e+00,-4.000000000000000327e-05,8.793125049375393113e-10,0.000000000000000000e+00 +8.016314489433737833e+01,4.945631263507546009e+02,5.771883343087765017e-02,9.011511351967357086e+00,3.652141158927881513e-03,1.000000009937144219e+00,-4.000000000000000327e-05,4.734265392770612891e-10,0.000000000000000000e+00 +8.016425458610932253e+01,4.945731262840640170e+02,5.775535476127906243e-02,9.012621043750321803e+00,3.651995173526343796e-03,1.000000009937669576e+00,-4.000000000000000327e-05,-6.613978820090252292e-10,0.000000000000000000e+00 +8.016536414124888665e+01,4.945831262173787195e+02,5.779187463183619450e-02,9.013730598900908220e+00,3.651849188124806078e-03,1.000000009936935719e+00,-4.000000000000000327e-05,-1.104200102778037080e-09,0.000000000000000000e+00 +8.016647355980653344e+01,4.945931261506987653e+02,5.782839304254904639e-02,9.014840017469573752e+00,3.651703202723268361e-03,1.000000009935710699e+00,-4.000000000000000327e-05,2.011905242751114857e-09,0.000000000000000000e+00 +8.016758284183268302e+01,4.946031260840241544e+02,5.786490999341761809e-02,9.015949299506745618e+00,3.651557217321730643e-03,1.000000009937942469e+00,-4.000000000000000327e-05,-1.440598111007729972e-09,0.000000000000000000e+00 +8.016869198737774127e+01,4.946131260173548867e+02,5.790142548444190962e-02,9.017058445062824390e+00,3.651411231920192926e-03,1.000000009936344636e+00,-4.000000000000000327e-05,6.587202402265444108e-11,0.000000000000000000e+00 +8.016980099649207148e+01,4.946231259506909623e+02,5.793793951562191402e-02,9.018167454188171561e+00,3.651265246518655208e-03,1.000000009936417689e+00,-4.000000000000000327e-05,7.354945332601204475e-10,0.000000000000000000e+00 +8.017090986922600848e+01,4.946331258840323244e+02,5.797445208695763824e-02,9.019276326933123755e+00,3.651119261117117491e-03,1.000000009937233258e+00,-4.000000000000000327e-05,-8.998048647714923843e-10,0.000000000000000000e+00 +8.017201860562985871e+01,4.946431258173790297e+02,5.801096319844907534e-02,9.020385063347985621e+00,3.650973275715579773e-03,1.000000009936235612e+00,-4.000000000000000327e-05,9.187429991359066579e-10,0.000000000000000000e+00 +8.017312720575388596e+01,4.946531257507310784e+02,5.804747285009622532e-02,9.021493663483028058e+00,3.650827290314042056e-03,1.000000009937254131e+00,-4.000000000000000327e-05,-1.056674283070279648e-09,0.000000000000000000e+00 +8.017423566964833981e+01,4.946631256840884703e+02,5.808398104189908817e-02,9.022602127388495319e+00,3.650681304912504338e-03,1.000000009936082845e+00,-4.000000000000000327e-05,3.792474296192876271e-10,0.000000000000000000e+00 +8.017534399736342721e+01,4.946731256174511486e+02,5.812048777385766390e-02,9.023710455114596130e+00,3.650535319510966620e-03,1.000000009936503176e+00,-4.000000000000000327e-05,8.691904075216941348e-10,0.000000000000000000e+00 +8.017645218894932668e+01,4.946831255508191703e+02,5.815699304597195252e-02,9.024818646711512571e+00,3.650389334109428903e-03,1.000000009937466405e+00,-4.000000000000000327e-05,-1.056662951006921437e-09,0.000000000000000000e+00 +8.017756024445620255e+01,4.946931254841925352e+02,5.819349685824195401e-02,9.025926702229394749e+00,3.650243348707891185e-03,1.000000009936295564e+00,-4.000000000000000327e-05,3.671618058139591936e-10,0.000000000000000000e+00 +8.017866816393416229e+01,4.947031254175712434e+02,5.822999921066766837e-02,9.027034621718359020e+00,3.650097363306353468e-03,1.000000009936702350e+00,-4.000000000000000327e-05,-6.682684056970923344e-10,0.000000000000000000e+00 +8.017977594743328495e+01,4.947131253509552380e+02,5.826650010324908868e-02,9.028142405228495093e+00,3.649951377904815750e-03,1.000000009935962053e+00,-4.000000000000000327e-05,1.605123506080209512e-09,0.000000000000000000e+00 +8.018088359500364959e+01,4.947231252843445759e+02,5.830299953598622187e-02,9.029250052809858929e+00,3.649805392503278033e-03,1.000000009937739964e+00,-4.000000000000000327e-05,-1.521114793027598057e-09,0.000000000000000000e+00 +8.018199110669526419e+01,4.947331252177392571e+02,5.833949750887906099e-02,9.030357564512479840e+00,3.649659407101740315e-03,1.000000009936055312e+00,-4.000000000000000327e-05,6.717226295442204461e-11,0.000000000000000000e+00 +8.018309848255813677e+01,4.947431251511392816e+02,5.837599402192761300e-02,9.031464940386349838e+00,3.649513421700202598e-03,1.000000009936129697e+00,-4.000000000000000327e-05,5.572973431474373978e-10,0.000000000000000000e+00 +8.018420572264221846e+01,4.947531250845445925e+02,5.841248907513187094e-02,9.032572180481436064e+00,3.649367436298664880e-03,1.000000009936746759e+00,-4.000000000000000327e-05,-7.360676491067611813e-11,0.000000000000000000e+00 +8.018531282699746043e+01,4.947631250179552467e+02,5.844898266849183482e-02,9.033679284847673685e+00,3.649221450897127163e-03,1.000000009936665268e+00,-4.000000000000000327e-05,-3.985683058925177452e-10,0.000000000000000000e+00 +8.018641979567375699e+01,4.947731249513712442e+02,5.848547480200750465e-02,9.034786253534965894e+00,3.649075465495589445e-03,1.000000009936224066e+00,-4.000000000000000327e-05,-4.381378188638233364e-10,0.000000000000000000e+00 +8.018752662872097403e+01,4.947831248847925849e+02,5.852196547567887347e-02,9.035893086593185686e+00,3.648929480094051728e-03,1.000000009935739120e+00,-4.000000000000000327e-05,-2.136785445743636814e-10,0.000000000000000000e+00 +8.018863332618896322e+01,4.947931248182192121e+02,5.855845468950594823e-02,9.036999784072175856e+00,3.648783494692514010e-03,1.000000009935502643e+00,-4.000000000000000327e-05,1.704621181224233652e-09,0.000000000000000000e+00 +8.018973988812754783e+01,4.948031247516511826e+02,5.859494244348872893e-02,9.038106346021749005e+00,3.648637509290976293e-03,1.000000009937388912e+00,-4.000000000000000327e-05,-1.958898733079156934e-09,0.000000000000000000e+00 +8.019084631458649426e+01,4.948131246850884963e+02,5.863142873762720864e-02,9.039212772491689307e+00,3.648491523889438575e-03,1.000000009935221534e+00,-4.000000000000000327e-05,1.832891417272588634e-09,0.000000000000000000e+00 +8.019195260561555472e+01,4.948231246185310965e+02,5.866791357192138734e-02,9.040319063531743637e+00,3.648345538487900858e-03,1.000000009937249246e+00,-4.000000000000000327e-05,-1.453123614789803808e-09,0.000000000000000000e+00 +8.019305876126445298e+01,4.948331245519790400e+02,5.870439694637127198e-02,9.041425219191637552e+00,3.648199553086363140e-03,1.000000009935641865e+00,-4.000000000000000327e-05,-2.270595250243476924e-10,0.000000000000000000e+00 +8.019416478158288442e+01,4.948431244854323268e+02,5.874087886097685562e-02,9.042531239521057529e+00,3.648053567684825423e-03,1.000000009935390732e+00,-4.000000000000000327e-05,1.136440426556566130e-09,0.000000000000000000e+00 +8.019527066662050174e+01,4.948531244188909000e+02,5.877735931573813827e-02,9.043637124569665175e+00,3.647907582283287705e-03,1.000000009936647505e+00,-4.000000000000000327e-05,-2.899683162000642991e-10,0.000000000000000000e+00 +8.019637641642694348e+01,4.948631243523548164e+02,5.881383831065511991e-02,9.044742874387091902e+00,3.647761596881749988e-03,1.000000009936326872e+00,-4.000000000000000327e-05,-1.699052559030240716e-10,0.000000000000000000e+00 +8.019748203105180551e+01,4.948731242858240762e+02,5.885031584572780056e-02,9.045848489022935368e+00,3.647615611480212270e-03,1.000000009936139023e+00,-4.000000000000000327e-05,2.329954950589875230e-11,0.000000000000000000e+00 +8.019858751054465529e+01,4.948831242192986792e+02,5.888679192095617326e-02,9.046953968526764811e+00,3.647469626078674552e-03,1.000000009936164780e+00,-4.000000000000000327e-05,-1.186011649560603552e-09,0.000000000000000000e+00 +8.019969285495503186e+01,4.948931241527785687e+02,5.892326653634024497e-02,9.048059312948119270e+00,3.647323640677136835e-03,1.000000009934853828e+00,-4.000000000000000327e-05,1.997621040775569149e-09,0.000000000000000000e+00 +8.020079806433243164e+01,4.949031240862638015e+02,5.895973969188000874e-02,9.049164522336505811e+00,3.647177655275599117e-03,1.000000009937061618e+00,-4.000000000000000327e-05,-2.080849887804811166e-09,0.000000000000000000e+00 +8.020190313872635102e+01,4.949131240197543775e+02,5.899621138757547151e-02,9.050269596741406630e+00,3.647031669874061400e-03,1.000000009934762124e+00,-4.000000000000000327e-05,1.101441774669967778e-09,0.000000000000000000e+00 +8.020300807818622957e+01,4.949231239532502400e+02,5.903268162342662634e-02,9.051374536212264843e+00,3.646885684472523682e-03,1.000000009935979151e+00,-4.000000000000000327e-05,-1.135542018850783698e-10,0.000000000000000000e+00 +8.020411288276149264e+01,4.949331238867514458e+02,5.906915039943347323e-02,9.052479340798502250e+00,3.646739699070985965e-03,1.000000009935853695e+00,-4.000000000000000327e-05,7.296496741715187834e-11,0.000000000000000000e+00 +8.020521755250152296e+01,4.949431238202579948e+02,5.910561771559601218e-02,9.053584010549505123e+00,3.646593713669448247e-03,1.000000009935934298e+00,-4.000000000000000327e-05,1.839424028571911297e-10,0.000000000000000000e+00 +8.020632208745567482e+01,4.949531237537698303e+02,5.914208357191424320e-02,9.054688545514631315e+00,3.646447728267910530e-03,1.000000009936137468e+00,-4.000000000000000327e-05,1.988428748659114577e-10,0.000000000000000000e+00 +8.020742648767327410e+01,4.949631236872870090e+02,5.917854796838816628e-02,9.055792945743208477e+00,3.646301742866372812e-03,1.000000009936357070e+00,-4.000000000000000327e-05,-1.360299412621675131e-09,0.000000000000000000e+00 +8.020853075320363246e+01,4.949731236208094742e+02,5.921501090501777448e-02,9.056897211284534066e+00,3.646155757464835095e-03,1.000000009934854939e+00,-4.000000000000000327e-05,1.312401547456218213e-09,0.000000000000000000e+00 +8.020963488409600473e+01,4.949831235543372827e+02,5.925147238180307474e-02,9.058001342187873561e+00,3.646009772063297377e-03,1.000000009936304002e+00,-4.000000000000000327e-05,-5.450569692772941843e-10,0.000000000000000000e+00 +8.021073888039963151e+01,4.949931234878704345e+02,5.928793239874406013e-02,9.059105338502467575e+00,3.645863786661759660e-03,1.000000009935702261e+00,-4.000000000000000327e-05,-1.126051955789560208e-09,0.000000000000000000e+00 +8.021184274216371080e+01,4.950031234214088727e+02,5.932439095584073757e-02,9.060209200277521191e+00,3.645717801260221942e-03,1.000000009934459255e+00,-4.000000000000000327e-05,1.007092348550326280e-09,0.000000000000000000e+00 +8.021294646943744056e+01,4.950131233549526542e+02,5.936084805309310014e-02,9.061312927562211073e+00,3.645571815858684225e-03,1.000000009935570811e+00,-4.000000000000000327e-05,2.213217214012892884e-12,0.000000000000000000e+00 +8.021405006226994772e+01,4.950231232885017789e+02,5.939730369050114783e-02,9.062416520405687237e+00,3.645425830457146507e-03,1.000000009935573253e+00,-4.000000000000000327e-05,2.116898252128414723e-10,0.000000000000000000e+00 +8.021515352071035920e+01,4.950331232220561901e+02,5.943375786806488065e-02,9.063519978857065951e+00,3.645279845055608790e-03,1.000000009935806844e+00,-4.000000000000000327e-05,1.573779467515518191e-10,0.000000000000000000e+00 +8.021625684480775931e+01,4.950431231556159446e+02,5.947021058578429858e-02,9.064623302965435059e+00,3.645133859654071072e-03,1.000000009935980483e+00,-4.000000000000000327e-05,-1.829590386391983718e-10,0.000000000000000000e+00 +8.021736003461121811e+01,4.950531230891809855e+02,5.950666184365940165e-02,9.065726492779852208e+00,3.644987874252533355e-03,1.000000009935778644e+00,-4.000000000000000327e-05,-8.299581095656833946e-10,0.000000000000000000e+00 +8.021846309016974885e+01,4.950631230227513697e+02,5.954311164169018289e-02,9.066829548349344847e+00,3.644841888850995637e-03,1.000000009934863154e+00,-4.000000000000000327e-05,-3.444654640910755510e-10,0.000000000000000000e+00 +8.021956601153235056e+01,4.950731229563270972e+02,5.957955997987664926e-02,9.067932469722910227e+00,3.644695903449457920e-03,1.000000009934483236e+00,-4.000000000000000327e-05,1.253998758642056124e-09,0.000000000000000000e+00 +8.022066879874800804e+01,4.950831228899081111e+02,5.961600685821879381e-02,9.069035256949517176e+00,3.644549918047920202e-03,1.000000009935866130e+00,-4.000000000000000327e-05,-4.379863512730164136e-10,0.000000000000000000e+00 +8.022177145186563507e+01,4.950931228234944683e+02,5.965245227671662348e-02,9.070137910078106103e+00,3.644403932646382484e-03,1.000000009935383183e+00,-4.000000000000000327e-05,4.011838576206813846e-10,0.000000000000000000e+00 +8.022287397093415962e+01,4.951031227570861688e+02,5.968889623537013134e-02,9.071240429157583662e+00,3.644257947244844767e-03,1.000000009935825496e+00,-4.000000000000000327e-05,-6.318608131443101886e-10,0.000000000000000000e+00 +8.022397635600245280e+01,4.951131226906831557e+02,5.972533873417931738e-02,9.072342814236829867e+00,3.644111961843307049e-03,1.000000009935128942e+00,-4.000000000000000327e-05,-6.351607438512534583e-10,0.000000000000000000e+00 +8.022507860711937155e+01,4.951231226242854859e+02,5.976177977314418160e-02,9.073445065364692752e+00,3.643965976441769332e-03,1.000000009934428835e+00,-4.000000000000000327e-05,3.709080235244943574e-10,0.000000000000000000e+00 +8.022618072433371594e+01,4.951331225578931026e+02,5.979821935226472401e-02,9.074547182589991934e+00,3.643819991040231614e-03,1.000000009934837619e+00,-4.000000000000000327e-05,9.041099692970464722e-10,0.000000000000000000e+00 +8.022728270769430026e+01,4.951431224915060625e+02,5.983465747154093767e-02,9.075649165961518605e+00,3.643674005638693897e-03,1.000000009935833933e+00,-4.000000000000000327e-05,-5.205258845215300222e-10,0.000000000000000000e+00 +8.022838455724986773e+01,4.951531224251243088e+02,5.987109413097282951e-02,9.076751015528033761e+00,3.643528020237156179e-03,1.000000009935260392e+00,-4.000000000000000327e-05,-9.978461230159951286e-10,0.000000000000000000e+00 +8.022948627304916158e+01,4.951631223587478985e+02,5.990752933056039953e-02,9.077852731338266423e+00,3.643382034835618462e-03,1.000000009934161049e+00,-4.000000000000000327e-05,9.165334351334285104e-10,0.000000000000000000e+00 +8.023058785514086821e+01,4.951731222923768314e+02,5.994396307030364079e-02,9.078954313440917190e+00,3.643236049434080744e-03,1.000000009935170686e+00,-4.000000000000000327e-05,8.104049951114796827e-10,0.000000000000000000e+00 +8.023168930357367401e+01,4.951831222260110508e+02,5.998039535020255331e-02,9.080055761884660015e+00,3.643090064032543027e-03,1.000000009936063305e+00,-4.000000000000000327e-05,-1.338136936626732346e-09,0.000000000000000000e+00 +8.023279061839620852e+01,4.951931221596506134e+02,6.001682617025714400e-02,9.081157076718136878e+00,3.642944078631005309e-03,1.000000009934589595e+00,-4.000000000000000327e-05,3.081092717233183499e-10,0.000000000000000000e+00 +8.023389179965708706e+01,4.952031220932954625e+02,6.005325553046740594e-02,9.082258257989957784e+00,3.642798093229467592e-03,1.000000009934928880e+00,-4.000000000000000327e-05,-1.294699858795834132e-10,0.000000000000000000e+00 +8.023499284740489657e+01,4.952131220269456549e+02,6.008968343083333913e-02,9.083359305748707868e+00,3.642652107827929874e-03,1.000000009934786327e+00,-4.000000000000000327e-05,2.585679810256334576e-10,0.000000000000000000e+00 +8.023609376168819551e+01,4.952231219606011337e+02,6.012610987135494356e-02,9.084460220042940293e+00,3.642506122426392157e-03,1.000000009935070988e+00,-4.000000000000000327e-05,-1.432180320166784255e-11,0.000000000000000000e+00 +8.023719454255549977e+01,4.952331218942619557e+02,6.016253485203221230e-02,9.085561000921179797e+00,3.642360137024854439e-03,1.000000009935055223e+00,-4.000000000000000327e-05,-9.693606053279572162e-10,0.000000000000000000e+00 +8.023829519005531097e+01,4.952431218279280642e+02,6.019895837286515228e-02,9.086661648431920923e+00,3.642214151623316722e-03,1.000000009933988299e+00,-4.000000000000000327e-05,3.064801533440705730e-10,0.000000000000000000e+00 +8.023939570423608814e+01,4.952531217615995160e+02,6.023538043385375657e-02,9.087762162623628015e+00,3.642068166221779004e-03,1.000000009934325584e+00,-4.000000000000000327e-05,8.598223150122324587e-10,0.000000000000000000e+00 +8.024049608514626186e+01,4.952631216952763111e+02,6.027180103499803210e-02,9.088862543544738770e+00,3.641922180820241287e-03,1.000000009935271716e+00,-4.000000000000000327e-05,-7.975661191947659895e-10,0.000000000000000000e+00 +8.024159633283424853e+01,4.952731216289583926e+02,6.030822017629797194e-02,9.089962791243660689e+00,3.641776195418703569e-03,1.000000009934394196e+00,-4.000000000000000327e-05,-2.849948601832086186e-10,0.000000000000000000e+00 +8.024269644734842188e+01,4.952831215626458174e+02,6.034463785775357608e-02,9.091062905768769298e+00,3.641630210017165852e-03,1.000000009934080669e+00,-4.000000000000000327e-05,9.106001456854011974e-10,0.000000000000000000e+00 +8.024379642873714147e+01,4.952931214963385287e+02,6.038105407936484453e-02,9.092162887168413477e+00,3.641484224615628134e-03,1.000000009935082312e+00,-4.000000000000000327e-05,-1.669601947293548018e-10,0.000000000000000000e+00 +8.024489627704870998e+01,4.953031214300365832e+02,6.041746884113177729e-02,9.093262735490913684e+00,3.641338239214090416e-03,1.000000009934898682e+00,-4.000000000000000327e-05,-6.031081365634207443e-10,0.000000000000000000e+00 +8.024599599233143010e+01,4.953131213637399242e+02,6.045388214305437435e-02,9.094362450784558405e+00,3.641192253812552699e-03,1.000000009934235434e+00,-4.000000000000000327e-05,1.051881559769024922e-09,0.000000000000000000e+00 +8.024709557463356191e+01,4.953231212974486084e+02,6.049029398513263572e-02,9.095462033097607701e+00,3.641046268411014981e-03,1.000000009935392065e+00,-4.000000000000000327e-05,-1.099267340402005445e-09,0.000000000000000000e+00 +8.024819502400332283e+01,4.953331212311625791e+02,6.052670436736656140e-02,9.096561482478294991e+00,3.640900283009477264e-03,1.000000009934183476e+00,-4.000000000000000327e-05,2.702549131940114481e-10,0.000000000000000000e+00 +8.024929434048893029e+01,4.953431211648818930e+02,6.056311328975614444e-02,9.097660798974819940e+00,3.640754297607939546e-03,1.000000009934480572e+00,-4.000000000000000327e-05,-7.393516582132129362e-10,0.000000000000000000e+00 +8.025039352413854488e+01,4.953531210986064934e+02,6.059952075230139179e-02,9.098759982635357346e+00,3.640608312206401829e-03,1.000000009933667888e+00,-4.000000000000000327e-05,2.626429735347538234e-10,0.000000000000000000e+00 +8.025149257500031297e+01,4.953631210323364371e+02,6.063592675500229651e-02,9.099859033508050032e+00,3.640462326804864111e-03,1.000000009933956546e+00,-4.000000000000000327e-05,3.150075807587315770e-10,0.000000000000000000e+00 +8.025259149312236673e+01,4.953731209660716672e+02,6.067233129785885859e-02,9.100957951641014176e+00,3.640316341403326394e-03,1.000000009934302714e+00,-4.000000000000000327e-05,8.681436760637993445e-10,0.000000000000000000e+00 +8.025369027855276727e+01,4.953831208998122406e+02,6.070873438087107804e-02,9.102056737082335758e+00,3.640170356001788676e-03,1.000000009935256617e+00,-4.000000000000000327e-05,-1.041655660015069578e-09,0.000000000000000000e+00 +8.025478893133958991e+01,4.953931208335581005e+02,6.074513600403895486e-02,9.103155389880072335e+00,3.640024370600250959e-03,1.000000009934112200e+00,-4.000000000000000327e-05,4.517620121631695934e-10,0.000000000000000000e+00 +8.025588745153085313e+01,4.954031207673093036e+02,6.078153616736248904e-02,9.104253910082249490e+00,3.639878385198713241e-03,1.000000009934608469e+00,-4.000000000000000327e-05,-5.581500827242422393e-10,0.000000000000000000e+00 +8.025698583917456119e+01,4.954131207010657931e+02,6.081793487084168059e-02,9.105352297736867939e+00,3.639732399797175524e-03,1.000000009933995404e+00,-4.000000000000000327e-05,3.234870965846734516e-10,0.000000000000000000e+00 +8.025808409431867574e+01,4.954231206348276260e+02,6.085433211447652257e-02,9.106450552891896422e+00,3.639586414395637806e-03,1.000000009934350675e+00,-4.000000000000000327e-05,-1.340813540556288574e-09,0.000000000000000000e+00 +8.025918221701114419e+01,4.954331205685947452e+02,6.089072789826702192e-02,9.107548675595277032e+00,3.639440428994100089e-03,1.000000009932878298e+00,-4.000000000000000327e-05,1.794573088958639424e-09,0.000000000000000000e+00 +8.026028020729988555e+01,4.954431205023672078e+02,6.092712222221317170e-02,9.108646665894919892e+00,3.639294443592562371e-03,1.000000009934848721e+00,-4.000000000000000327e-05,-6.047352292487720126e-10,0.000000000000000000e+00 +8.026137806523277618e+01,4.954531204361449568e+02,6.096351508631497884e-02,9.109744523838712027e+00,3.639148458191024654e-03,1.000000009934184808e+00,-4.000000000000000327e-05,2.829854703645464113e-10,0.000000000000000000e+00 +8.026247579085766404e+01,4.954631203699280491e+02,6.099990649057243641e-02,9.110842249474504939e+00,3.639002472789486936e-03,1.000000009934495449e+00,-4.000000000000000327e-05,-1.458997240870954531e-09,0.000000000000000000e+00 +8.026357338422238286e+01,4.954731203037164278e+02,6.103629643498554441e-02,9.111939842850125260e+00,3.638856487387949219e-03,1.000000009932894063e+00,-4.000000000000000327e-05,1.522096303169495551e-09,0.000000000000000000e+00 +8.026467084537472374e+01,4.954831202375100929e+02,6.107268491955430284e-02,9.113037304013367645e+00,3.638710501986411501e-03,1.000000009934564504e+00,-4.000000000000000327e-05,-1.116972423845869910e-09,0.000000000000000000e+00 +8.026576817436246358e+01,4.954931201713091014e+02,6.110907194427871170e-02,9.114134633012003661e+00,3.638564516584873784e-03,1.000000009933338818e+00,-4.000000000000000327e-05,9.282915672065531385e-10,0.000000000000000000e+00 +8.026686537123333665e+01,4.955031201051133962e+02,6.114545750915876404e-02,9.115231829893769344e+00,3.638418531183336066e-03,1.000000009934357337e+00,-4.000000000000000327e-05,2.619040537306669125e-10,0.000000000000000000e+00 +8.026796243603504877e+01,4.955131200389230344e+02,6.118184161419446682e-02,9.116328894706377639e+00,3.638272545781798348e-03,1.000000009934644662e+00,-4.000000000000000327e-05,-1.662299029166564412e-09,0.000000000000000000e+00 +8.026905936881527737e+01,4.955231199727379590e+02,6.121822425938582002e-02,9.117425827497509516e+00,3.638126560380260631e-03,1.000000009932821232e+00,-4.000000000000000327e-05,1.041592498529080023e-09,0.000000000000000000e+00 +8.027015616962168565e+01,4.955331199065582268e+02,6.125460544473281671e-02,9.118522628314815748e+00,3.637980574978722913e-03,1.000000009933963652e+00,-4.000000000000000327e-05,-5.053698011242286374e-10,0.000000000000000000e+00 +8.027125283850189419e+01,4.955431198403837811e+02,6.129098517023545689e-02,9.119619297205924013e+00,3.637834589577185196e-03,1.000000009933409428e+00,-4.000000000000000327e-05,1.060877730064953718e-09,0.000000000000000000e+00 +8.027234937550350935e+01,4.955531197742146787e+02,6.132736343589374056e-02,9.120715834218428242e+00,3.637688604175647478e-03,1.000000009934572720e+00,-4.000000000000000327e-05,-1.666744327346984066e-09,0.000000000000000000e+00 +8.027344578067408065e+01,4.955631197080508628e+02,6.136374024170767466e-02,9.121812239399897493e+00,3.637542618774109761e-03,1.000000009932745293e+00,-4.000000000000000327e-05,1.635955314719005629e-09,0.000000000000000000e+00 +8.027454205406115761e+01,4.955731196418923332e+02,6.140011558767725225e-02,9.122908512797867076e+00,3.637396633372572043e-03,1.000000009934538747e+00,-4.000000000000000327e-05,-8.744915025393405751e-10,0.000000000000000000e+00 +8.027563819571224712e+01,4.955831195757391470e+02,6.143648947380246639e-02,9.124004654459850983e+00,3.637250647971034326e-03,1.000000009933580181e+00,-4.000000000000000327e-05,-3.498791487255772784e-10,0.000000000000000000e+00 +8.027673420567484186e+01,4.955931195095912472e+02,6.147286190008332402e-02,9.125100664433327680e+00,3.637104662569496608e-03,1.000000009933196710e+00,-4.000000000000000327e-05,2.344289533329071561e-10,0.000000000000000000e+00 +8.027783008399637765e+01,4.956031194434486906e+02,6.150923286651982513e-02,9.126196542765750763e+00,3.636958677167958891e-03,1.000000009933453615e+00,-4.000000000000000327e-05,-6.215038438708866142e-10,0.000000000000000000e+00 +8.027892583072429034e+01,4.956131193773114205e+02,6.154560237311196280e-02,9.127292289504545408e+00,3.636812691766421173e-03,1.000000009932772604e+00,-4.000000000000000327e-05,1.501556847148570043e-09,0.000000000000000000e+00 +8.028002144590597311e+01,4.956231193111794369e+02,6.158197041985974396e-02,9.128387904697106592e+00,3.636666706364883456e-03,1.000000009934417733e+00,-4.000000000000000327e-05,-8.158309875751136542e-10,0.000000000000000000e+00 +8.028111692958879075e+01,4.956331192450527965e+02,6.161833700676316167e-02,9.129483388390804421e+00,3.636520720963345738e-03,1.000000009933524003e+00,-4.000000000000000327e-05,-1.939984973262642614e-10,0.000000000000000000e+00 +8.028221228182007962e+01,4.956431191789314425e+02,6.165470213382221593e-02,9.130578740632975254e+00,3.636374735561808021e-03,1.000000009933311507e+00,-4.000000000000000327e-05,3.880435463970213650e-10,0.000000000000000000e+00 +8.028330750264716187e+01,4.956531191128154319e+02,6.169106580103690673e-02,9.131673961470930578e+00,3.636228750160270303e-03,1.000000009933736500e+00,-4.000000000000000327e-05,-5.715914163625724206e-10,0.000000000000000000e+00 +8.028440259211730279e+01,4.956631190467047077e+02,6.172742800840723409e-02,9.132769050951953460e+00,3.636082764758732586e-03,1.000000009933110556e+00,-4.000000000000000327e-05,-1.297844541305714830e-10,0.000000000000000000e+00 +8.028549755027776769e+01,4.956731189805992699e+02,6.176378875593319800e-02,9.133864009123296768e+00,3.635936779357194868e-03,1.000000009932968448e+00,-4.000000000000000327e-05,2.119390860485258748e-10,0.000000000000000000e+00 +8.028659237717577923e+01,4.956831189144991754e+02,6.180014804361479847e-02,9.134958836032186724e+00,3.635790793955657151e-03,1.000000009933200484e+00,-4.000000000000000327e-05,4.342736585437581569e-10,0.000000000000000000e+00 +8.028768707285854589e+01,4.956931188484043673e+02,6.183650587145202854e-02,9.136053531725821131e+00,3.635644808554119433e-03,1.000000009933675882e+00,-4.000000000000000327e-05,-9.654161638446718127e-10,0.000000000000000000e+00 +8.028878163737321927e+01,4.957031187823149025e+02,6.187286223944489516e-02,9.137148096251369367e+00,3.635498823152581716e-03,1.000000009932619172e+00,-4.000000000000000327e-05,4.400585278567619480e-10,0.000000000000000000e+00 +8.028987607076695099e+01,4.957131187162307242e+02,6.190921714759339139e-02,9.138242529655970614e+00,3.635352837751043998e-03,1.000000009933100786e+00,-4.000000000000000327e-05,1.842420486603573548e-10,0.000000000000000000e+00 +8.029097037308685003e+01,4.957231186501518323e+02,6.194557059589751724e-02,9.139336831986739185e+00,3.635206852349506280e-03,1.000000009933302403e+00,-4.000000000000000327e-05,-2.709169482240602243e-10,0.000000000000000000e+00 +8.029206454437999696e+01,4.957331185840782837e+02,6.198192258435727964e-02,9.140431003290759193e+00,3.635060866947968563e-03,1.000000009933005973e+00,-4.000000000000000327e-05,5.388543903025891498e-10,0.000000000000000000e+00 +8.029315858469345812e+01,4.957431185180100215e+02,6.201827311297267165e-02,9.141525043615086332e+00,3.634914881546430845e-03,1.000000009933595502e+00,-4.000000000000000327e-05,-1.858305992958800122e-09,0.000000000000000000e+00 +8.029425249407425724e+01,4.957531184519470457e+02,6.205462218174369327e-02,9.142618953006749649e+00,3.634768896144893128e-03,1.000000009931562683e+00,-4.000000000000000327e-05,1.424093553200441701e-09,0.000000000000000000e+00 +8.029534627256938961e+01,4.957631183858894133e+02,6.209096979067033756e-02,9.143712731512746217e+00,3.634622910743355410e-03,1.000000009933120326e+00,-4.000000000000000327e-05,-2.517586980460740987e-11,0.000000000000000000e+00 +8.029643992022583632e+01,4.957731183198370672e+02,6.212731593975261146e-02,9.144806379180051792e+00,3.634476925341817693e-03,1.000000009933092793e+00,-4.000000000000000327e-05,-2.877296321046193147e-10,0.000000000000000000e+00 +8.029753343709053581e+01,4.957831182537900077e+02,6.216366062899051498e-02,9.145899896055608380e+00,3.634330939940279975e-03,1.000000009932778156e+00,-4.000000000000000327e-05,6.183779085120317225e-10,0.000000000000000000e+00 +8.029862682321039813e+01,4.957931181877482913e+02,6.220000385838404117e-02,9.146993282186331342e+00,3.634184954538742258e-03,1.000000009933454281e+00,-4.000000000000000327e-05,-2.991722670633404856e-10,0.000000000000000000e+00 +8.029972007863231909e+01,4.958031181217118615e+02,6.223634562793319697e-02,9.148086537619109393e+00,3.634038969137204540e-03,1.000000009933127210e+00,-4.000000000000000327e-05,-8.693892357360908503e-11,0.000000000000000000e+00 +8.030081320340315187e+01,4.958131180556807180e+02,6.227268593763797544e-02,9.149179662400801050e+00,3.633892983735666823e-03,1.000000009933032175e+00,-4.000000000000000327e-05,-2.515029167605085762e-10,0.000000000000000000e+00 +8.030190619756973547e+01,4.958231179896549179e+02,6.230902478749837659e-02,9.150272656578238184e+00,3.633746998334129105e-03,1.000000009932757283e+00,-4.000000000000000327e-05,-8.125042939267939949e-10,0.000000000000000000e+00 +8.030299906117886621e+01,4.958331179236344042e+02,6.234536217751440040e-02,9.151365520198224246e+00,3.633601012932591388e-03,1.000000009931869327e+00,-4.000000000000000327e-05,1.186085020008432207e-09,0.000000000000000000e+00 +8.030409179427732624e+01,4.958431178576191769e+02,6.238169810768604689e-02,9.152458253307534264e+00,3.633455027531053670e-03,1.000000009933165401e+00,-4.000000000000000327e-05,-2.261898676343695718e-10,0.000000000000000000e+00 +8.030518439691185506e+01,4.958531177916092929e+02,6.241803257801331606e-02,9.153550855952918397e+00,3.633309042129515953e-03,1.000000009932918266e+00,-4.000000000000000327e-05,-6.062937308494732873e-10,0.000000000000000000e+00 +8.030627686912917795e+01,4.958631177256046954e+02,6.245436558849620790e-02,9.154643328181094830e+00,3.633163056727978235e-03,1.000000009932255907e+00,-4.000000000000000327e-05,2.764525259008341212e-11,0.000000000000000000e+00 +8.030736921097599179e+01,4.958731176596053842e+02,6.249069713913471547e-02,9.155735670038755103e+00,3.633017071326440518e-03,1.000000009932286105e+00,-4.000000000000000327e-05,1.673143947043408587e-10,0.000000000000000000e+00 +8.030846142249895081e+01,4.958831175936114164e+02,6.252702722992883877e-02,9.156827881572564110e+00,3.632871085924902800e-03,1.000000009932468847e+00,-4.000000000000000327e-05,-2.067789041228906269e-10,0.000000000000000000e+00 +8.030955350374469504e+01,4.958931175276227350e+02,6.256335586087859169e-02,9.157919962829158322e+00,3.632725100523365083e-03,1.000000009932243028e+00,-4.000000000000000327e-05,3.749712631830208037e-10,0.000000000000000000e+00 +8.031064545475983607e+01,4.959031174616393400e+02,6.259968303198396034e-02,9.159011913855145792e+00,3.632579115121827365e-03,1.000000009932652478e+00,-4.000000000000000327e-05,4.038946435284422783e-10,0.000000000000000000e+00 +8.031173727559095710e+01,4.959131173956612315e+02,6.263600874324494472e-02,9.160103734697107924e+00,3.632433129720289647e-03,1.000000009933093459e+00,-4.000000000000000327e-05,-1.630619009619731667e-09,0.000000000000000000e+00 +8.031282896628459866e+01,4.959231173296884663e+02,6.267233299466154484e-02,9.161195425401597703e+00,3.632287144318751930e-03,1.000000009931313327e+00,-4.000000000000000327e-05,1.705061426620439937e-09,0.000000000000000000e+00 +8.031392052688730132e+01,4.959331172637209875e+02,6.270865578623376069e-02,9.162286986015137913e+00,3.632141158917214212e-03,1.000000009933174505e+00,-4.000000000000000327e-05,-1.534168484730095164e-09,0.000000000000000000e+00 +8.031501195744554877e+01,4.959431171977587951e+02,6.274497711796159227e-02,9.163378416584230024e+00,3.631995173515676495e-03,1.000000009931500067e+00,-4.000000000000000327e-05,5.593331857054473296e-10,0.000000000000000000e+00 +8.031610325800582473e+01,4.959531171318019460e+02,6.278129698984503959e-02,9.164469717155339978e+00,3.631849188114138777e-03,1.000000009932110467e+00,-4.000000000000000327e-05,5.117826460098323904e-10,0.000000000000000000e+00 +8.031719442861455605e+01,4.959631170658503834e+02,6.281761540188408877e-02,9.165560887774912402e+00,3.631703202712601060e-03,1.000000009932668910e+00,-4.000000000000000327e-05,-2.065690796435934158e-10,0.000000000000000000e+00 +8.031828546931816959e+01,4.959731169999041072e+02,6.285393235407875367e-02,9.166651928489361723e+00,3.631557217311063342e-03,1.000000009932443534e+00,-4.000000000000000327e-05,-1.225314174779911504e-10,0.000000000000000000e+00 +8.031937638016304959e+01,4.959831169339631174e+02,6.289024784642903432e-02,9.167742839345073946e+00,3.631411231909525625e-03,1.000000009932309863e+00,-4.000000000000000327e-05,-7.478970152464415186e-10,0.000000000000000000e+00 +8.032046716119555185e+01,4.959931168680274709e+02,6.292656187893491682e-02,9.168833620388408434e+00,3.631265246507987907e-03,1.000000009931494072e+00,-4.000000000000000327e-05,8.841870438779789159e-10,0.000000000000000000e+00 +8.032155781246200377e+01,4.960031168020971108e+02,6.296287445159641505e-02,9.169924271665696125e+00,3.631119261106450190e-03,1.000000009932458411e+00,-4.000000000000000327e-05,2.754886882963811032e-10,0.000000000000000000e+00 +8.032264833400871851e+01,4.960131167361720372e+02,6.299918556441352901e-02,9.171014793223243089e+00,3.630973275704912472e-03,1.000000009932758838e+00,-4.000000000000000327e-05,-1.102085801750178696e-09,0.000000000000000000e+00 +8.032373872588196662e+01,4.960231166702522501e+02,6.303549521738624484e-02,9.172105185107325198e+00,3.630827290303374755e-03,1.000000009931557132e+00,-4.000000000000000327e-05,-2.782018100967810404e-10,0.000000000000000000e+00 +8.032482898812800443e+01,4.960331166043378062e+02,6.307180341051456252e-02,9.173195447364189903e+00,3.630681304901837037e-03,1.000000009931253819e+00,-4.000000000000000327e-05,1.234336286760106955e-09,0.000000000000000000e+00 +8.032591912079304564e+01,4.960431165384286487e+02,6.310811014379849593e-02,9.174285580040059784e+00,3.630535319500299320e-03,1.000000009932599410e+00,-4.000000000000000327e-05,-1.069070403848520701e-09,0.000000000000000000e+00 +8.032700912392328974e+01,4.960531164725247777e+02,6.314441541723803120e-02,9.175375583181130779e+00,3.630389334098761602e-03,1.000000009931434120e+00,-4.000000000000000327e-05,2.677068237377790162e-10,0.000000000000000000e+00 +8.032809899756490779e+01,4.960631164066261931e+02,6.318071923083316832e-02,9.176465456833566847e+00,3.630243348697223885e-03,1.000000009931725886e+00,-4.000000000000000327e-05,7.400507437797968786e-10,0.000000000000000000e+00 +8.032918874176402824e+01,4.960731163407329518e+02,6.321702158458390730e-02,9.177555201043508859e+00,3.630097363295686167e-03,1.000000009932532352e+00,-4.000000000000000327e-05,-1.167878435230481740e-09,0.000000000000000000e+00 +8.033027835656676530e+01,4.960831162748449970e+02,6.325332247849026202e-02,9.178644815857069261e+00,3.629951377894148450e-03,1.000000009931259815e+00,-4.000000000000000327e-05,5.095171404710424383e-10,0.000000000000000000e+00 +8.033136784201920477e+01,4.960931162089623285e+02,6.328962191255221859e-02,9.179734301320330303e+00,3.629805392492610732e-03,1.000000009931814926e+00,-4.000000000000000327e-05,-2.321635632452657964e-10,0.000000000000000000e+00 +8.033245719816740404e+01,4.961031161430849465e+02,6.332591988676977701e-02,9.180823657479351141e+00,3.629659407091073015e-03,1.000000009931562017e+00,-4.000000000000000327e-05,1.077782633742548391e-09,0.000000000000000000e+00 +8.033354642505739207e+01,4.961131160772129078e+02,6.336221640114293729e-02,9.181912884380160733e+00,3.629513421689535297e-03,1.000000009932735967e+00,-4.000000000000000327e-05,-1.568240513153455843e-09,0.000000000000000000e+00 +8.033463552273518360e+01,4.961231160113461556e+02,6.339851145567169943e-02,9.183001982068763169e+00,3.629367436287997579e-03,1.000000009931028000e+00,-4.000000000000000327e-05,7.952240583823528367e-10,0.000000000000000000e+00 +8.033572449124673653e+01,4.961331159454846897e+02,6.343480505035604955e-02,9.184090950591130564e+00,3.629221450886459862e-03,1.000000009931893974e+00,-4.000000000000000327e-05,-8.371235560783804921e-10,0.000000000000000000e+00 +8.033681333063800878e+01,4.961431158796285104e+02,6.347109718519600152e-02,9.185179789993213717e+00,3.629075465484922144e-03,1.000000009930982481e+00,-4.000000000000000327e-05,1.006095027379061952e-09,0.000000000000000000e+00 +8.033790204095491561e+01,4.961531158137776174e+02,6.350738786019155535e-02,9.186268500320931452e+00,3.628929480083384427e-03,1.000000009932077827e+00,-4.000000000000000327e-05,-1.186529183047443499e-09,0.000000000000000000e+00 +8.033899062224335808e+01,4.961631157479320677e+02,6.354367707534271104e-02,9.187357081620179500e+00,3.628783494681846709e-03,1.000000009930786193e+00,-4.000000000000000327e-05,1.558970348763764256e-09,0.000000000000000000e+00 +8.034007907454919462e+01,4.961731156820918045e+02,6.357996483064945470e-02,9.188445533936821619e+00,3.628637509280308992e-03,1.000000009932483058e+00,-4.000000000000000327e-05,-1.270664435567748278e-09,0.000000000000000000e+00 +8.034116739791826944e+01,4.961831156162568277e+02,6.361625112611180022e-02,9.189533857316700249e+00,3.628491523878771274e-03,1.000000009931100164e+00,-4.000000000000000327e-05,8.021152096551619274e-10,0.000000000000000000e+00 +8.034225559239638415e+01,4.961931155504271374e+02,6.365253596172973372e-02,9.190622051805624082e+00,3.628345538477233557e-03,1.000000009931973022e+00,-4.000000000000000327e-05,-1.241374868257896632e-09,0.000000000000000000e+00 +8.034334365802934030e+01,4.962031154846027334e+02,6.368881933750326907e-02,9.191710117449380490e+00,3.628199553075695839e-03,1.000000009930622324e+00,-4.000000000000000327e-05,8.163878566457842867e-11,0.000000000000000000e+00 +8.034443159486288266e+01,4.962131154187836728e+02,6.372510125343239240e-02,9.192798054293724874e+00,3.628053567674158122e-03,1.000000009930711142e+00,-4.000000000000000327e-05,1.752379825606090173e-09,0.000000000000000000e+00 +8.034551940294274175e+01,4.962231153529698986e+02,6.376138170951711759e-02,9.193885862384389540e+00,3.627907582272620404e-03,1.000000009932617395e+00,-4.000000000000000327e-05,-2.254376276285237126e-09,0.000000000000000000e+00 +8.034660708231463389e+01,4.962331152871614108e+02,6.379766070575743075e-02,9.194973541767080150e+00,3.627761596871082687e-03,1.000000009930165357e+00,-4.000000000000000327e-05,1.554954354034922749e-09,0.000000000000000000e+00 +8.034769463302421855e+01,4.962431152213582095e+02,6.383393824215333190e-02,9.196061092487468613e+00,3.627615611469544969e-03,1.000000009931856448e+00,-4.000000000000000327e-05,-3.522339172455009898e-10,0.000000000000000000e+00 +8.034878205511715521e+01,4.962531151555602946e+02,6.387021431870482102e-02,9.197148514591209079e+00,3.627469626068007252e-03,1.000000009931473421e+00,-4.000000000000000327e-05,-4.860381755894999272e-10,0.000000000000000000e+00 +8.034986934863907493e+01,4.962631150897676662e+02,6.390648893541189812e-02,9.198235808123921942e+00,3.627323640666469534e-03,1.000000009930944955e+00,-4.000000000000000327e-05,-3.678395963475896096e-10,0.000000000000000000e+00 +8.035095651363556613e+01,4.962731150239803810e+02,6.394276209227457708e-02,9.199322973131202730e+00,3.627177655264931817e-03,1.000000009930545053e+00,-4.000000000000000327e-05,-1.552421626711478462e-11,0.000000000000000000e+00 +8.035204355015218880e+01,4.962831149581983823e+02,6.397903378929284401e-02,9.200410009658620325e+00,3.627031669863394099e-03,1.000000009930528178e+00,-4.000000000000000327e-05,5.519919598317455881e-10,0.000000000000000000e+00 +8.035313045823448874e+01,4.962931148924216700e+02,6.401530402646669893e-02,9.201496917751716964e+00,3.626885684461856382e-03,1.000000009931128142e+00,-4.000000000000000327e-05,-1.879691327995387321e-10,0.000000000000000000e+00 +8.035421723792798332e+01,4.963031148266502441e+02,6.405157280379612794e-02,9.202583697456008238e+00,3.626739699060318664e-03,1.000000009930923861e+00,-4.000000000000000327e-05,7.536000418410573736e-10,0.000000000000000000e+00 +8.035530388927816148e+01,4.963131147608841047e+02,6.408784012128114493e-02,9.203670348816981317e+00,3.626593713658780947e-03,1.000000009931742762e+00,-4.000000000000000327e-05,-1.155057045821052351e-09,0.000000000000000000e+00 +8.035639041233048374e+01,4.963231146951232517e+02,6.412410597892174990e-02,9.204756871880098501e+00,3.626447728257243229e-03,1.000000009930487765e+00,-4.000000000000000327e-05,8.522923734708424017e-11,0.000000000000000000e+00 +8.035747680713038221e+01,4.963331146293676852e+02,6.416037037671794285e-02,9.205843266690791893e+00,3.626301742855705511e-03,1.000000009930580358e+00,-4.000000000000000327e-05,-5.805266240477691121e-11,0.000000000000000000e+00 +8.035856307372327478e+01,4.963431145636174620e+02,6.419663331466970990e-02,9.206929533294470502e+00,3.626155757454167794e-03,1.000000009930517297e+00,-4.000000000000000327e-05,1.407125437894803662e-09,0.000000000000000000e+00 +8.035964921215453671e+01,4.963531144978725251e+02,6.423289479277706493e-02,9.208015671736514918e+00,3.626009772052630076e-03,1.000000009932045630e+00,-4.000000000000000327e-05,-1.561453537247720161e-09,0.000000000000000000e+00 +8.036073522246951484e+01,4.963631144321328748e+02,6.426915481104000794e-02,9.209101682062280858e+00,3.625863786651092359e-03,1.000000009930349876e+00,-4.000000000000000327e-05,5.234768242452379069e-11,0.000000000000000000e+00 +8.036182110471354179e+01,4.963731143663985108e+02,6.430541336945852504e-02,9.210187564317092068e+00,3.625717801249554641e-03,1.000000009930406719e+00,-4.000000000000000327e-05,2.073703473430283914e-10,0.000000000000000000e+00 +8.036290685893192176e+01,4.963831143006694333e+02,6.434167046803263013e-02,9.211273318546250977e+00,3.625571815848016924e-03,1.000000009930631872e+00,-4.000000000000000327e-05,3.898367616528098594e-10,0.000000000000000000e+00 +8.036399248516991634e+01,4.963931142349456422e+02,6.437792610676230931e-02,9.212358944795031590e+00,3.625425830446479206e-03,1.000000009931055089e+00,-4.000000000000000327e-05,-9.260225684723424192e-10,0.000000000000000000e+00 +8.036507798347278708e+01,4.964031141692271376e+02,6.441418028564756260e-02,9.213444443108681270e+00,3.625279845044941489e-03,1.000000009930049893e+00,-4.000000000000000327e-05,7.634909296268333111e-10,0.000000000000000000e+00 +8.036616335388575294e+01,4.964131141035139194e+02,6.445043300468840386e-02,9.214529813532418956e+00,3.625133859643403771e-03,1.000000009930878564e+00,-4.000000000000000327e-05,-5.906907756629407929e-10,0.000000000000000000e+00 +8.036724859645399022e+01,4.964231140378059877e+02,6.448668426388481922e-02,9.215615056111440495e+00,3.624987874241866054e-03,1.000000009930237521e+00,-4.000000000000000327e-05,1.024571196460710342e-09,0.000000000000000000e+00 +8.036833371122268943e+01,4.964331139721033992e+02,6.452293406323680869e-02,9.216700170890911537e+00,3.624841888840328336e-03,1.000000009931349298e+00,-4.000000000000000327e-05,-1.951355435668596651e-09,0.000000000000000000e+00 +8.036941869823697004e+01,4.964431139064060972e+02,6.455918240274437225e-02,9.217785157915974636e+00,3.624695903438790619e-03,1.000000009929232103e+00,-4.000000000000000327e-05,1.024198435622104131e-09,0.000000000000000000e+00 +8.037050355754196573e+01,4.964531138407140816e+02,6.459542928240750992e-02,9.218870017231740377e+00,3.624549918037252901e-03,1.000000009930343214e+00,-4.000000000000000327e-05,8.791866506821027573e-10,0.000000000000000000e+00 +8.037158828918275333e+01,4.964631137750273524e+02,6.463167470222622168e-02,9.219954748883299800e+00,3.624403932635715184e-03,1.000000009931296896e+00,-4.000000000000000327e-05,-8.971010980653252286e-10,0.000000000000000000e+00 +8.037267289320439545e+01,4.964731137093459097e+02,6.466791866220050755e-02,9.221039352915713749e+00,3.624257947234177466e-03,1.000000009930323897e+00,-4.000000000000000327e-05,2.063861896437266752e-10,0.000000000000000000e+00 +8.037375736965192630e+01,4.964831136436697534e+02,6.470416116233036752e-02,9.222123829374014647e+00,3.624111961832639749e-03,1.000000009930547717e+00,-4.000000000000000327e-05,-3.587610419644898384e-10,0.000000000000000000e+00 +8.037484171857035165e+01,4.964931135779988836e+02,6.474040220261580159e-02,9.223208178303211824e+00,3.623965976431102031e-03,1.000000009930158695e+00,-4.000000000000000327e-05,-1.101190036373020400e-09,0.000000000000000000e+00 +8.037592594000466306e+01,4.965031135123333002e+02,6.477664178305680975e-02,9.224292399748286186e+00,3.623819991029564314e-03,1.000000009928964761e+00,-4.000000000000000327e-05,9.837525548837215123e-10,0.000000000000000000e+00 +8.037701003399980948e+01,4.965131134466730032e+02,6.481287990365339202e-02,9.225376493754191998e+00,3.623674005628026596e-03,1.000000009930031242e+00,-4.000000000000000327e-05,1.343575127211365959e-09,0.000000000000000000e+00 +8.037809400060071141e+01,4.965231133810179927e+02,6.484911656440553451e-02,9.226460460365860428e+00,3.623528020226488879e-03,1.000000009931487632e+00,-4.000000000000000327e-05,-1.553313549129552444e-09,0.000000000000000000e+00 +8.037917783985227516e+01,4.965331133153682686e+02,6.488535176531325110e-02,9.227544299628194224e+00,3.623382034824951161e-03,1.000000009929804090e+00,-4.000000000000000327e-05,-1.653483627750407827e-10,0.000000000000000000e+00 +8.038026155179939281e+01,4.965431132497238309e+02,6.492158550637652792e-02,9.228628011586065938e+00,3.623236049423413443e-03,1.000000009929624900e+00,-4.000000000000000327e-05,9.536823501115410492e-10,0.000000000000000000e+00 +8.038134513648689961e+01,4.965531131840846797e+02,6.495781778759537883e-02,9.229711596284326802e+00,3.623090064021875726e-03,1.000000009930658296e+00,-4.000000000000000327e-05,-1.241121281905186029e-09,0.000000000000000000e+00 +8.038242859395961659e+01,4.965631131184508718e+02,6.499404860896978997e-02,9.230795053767801406e+00,3.622944078620338008e-03,1.000000009929313594e+00,-4.000000000000000327e-05,7.969032360455143623e-10,0.000000000000000000e+00 +8.038351192426233638e+01,4.965731130528223503e+02,6.503027797049977521e-02,9.231878384081284139e+00,3.622798093218800291e-03,1.000000009930176903e+00,-4.000000000000000327e-05,-5.165719747043348518e-10,0.000000000000000000e+00 +8.038459512743983737e+01,4.965831129871991152e+02,6.506650587218532067e-02,9.232961587269548076e+00,3.622652107817262573e-03,1.000000009929617351e+00,-4.000000000000000327e-05,8.536738438234081382e-10,0.000000000000000000e+00 +8.038567820353686955e+01,4.965931129215811666e+02,6.510273231402642635e-02,9.234044663377336093e+00,3.622506122415724856e-03,1.000000009930541944e+00,-4.000000000000000327e-05,-1.165840267790841440e-09,0.000000000000000000e+00 +8.038676115259814026e+01,4.966031128559685044e+02,6.513895729602310614e-02,9.235127612449367973e+00,3.622360137014187138e-03,1.000000009929279399e+00,-4.000000000000000327e-05,9.775259119614551432e-10,0.000000000000000000e+00 +8.038784397466835685e+01,4.966131127903611286e+02,6.517518081817534614e-02,9.236210434530333302e+00,3.622214151612649421e-03,1.000000009930337885e+00,-4.000000000000000327e-05,-1.822796099440040446e-09,0.000000000000000000e+00 +8.038892666979216983e+01,4.966231127247590393e+02,6.521140288048314637e-02,9.237293129664900349e+00,3.622068166211111703e-03,1.000000009928364353e+00,-4.000000000000000327e-05,2.536994585984889625e-09,0.000000000000000000e+00 +8.039000923801422971e+01,4.966331126591622365e+02,6.524762348294650682e-02,9.238375697897705408e+00,3.621922180809573986e-03,1.000000009931110823e+00,-4.000000000000000327e-05,-2.633294223428902170e-09,0.000000000000000000e+00 +8.039109167937914435e+01,4.966431125935707200e+02,6.528384262556542750e-02,9.239458139273367010e+00,3.621776195408036268e-03,1.000000009928260436e+00,-4.000000000000000327e-05,2.354999306247029306e-09,0.000000000000000000e+00 +8.039217399393149321e+01,4.966531125279844900e+02,6.532006030833990839e-02,9.240540453836466384e+00,3.621630210006498551e-03,1.000000009930809286e+00,-4.000000000000000327e-05,-2.227652455995044233e-09,0.000000000000000000e+00 +8.039325618171585575e+01,4.966631124624035465e+02,6.535627653126994951e-02,9.241622641631570545e+00,3.621484224604960833e-03,1.000000009928398548e+00,-4.000000000000000327e-05,1.799444791938215055e-09,0.000000000000000000e+00 +8.039433824277675456e+01,4.966731123968278894e+02,6.539249129435555086e-02,9.242704702703209207e+00,3.621338239203423116e-03,1.000000009930345657e+00,-4.000000000000000327e-05,-7.507286748362393765e-10,0.000000000000000000e+00 +8.039542017715869804e+01,4.966831123312575187e+02,6.542870459759671242e-02,9.243786637095896097e+00,3.621192253801885398e-03,1.000000009929533418e+00,-4.000000000000000327e-05,-7.937144924785549779e-10,0.000000000000000000e+00 +8.039650198490616617e+01,4.966931122656924344e+02,6.546491644099342033e-02,9.244868444854111189e+00,3.621046268400347681e-03,1.000000009928674771e+00,-4.000000000000000327e-05,1.653714058841176170e-09,0.000000000000000000e+00 +8.039758366606362472e+01,4.967031122001326366e+02,6.550112682454568847e-02,9.245950126022311366e+00,3.620900282998809963e-03,1.000000009930463563e+00,-4.000000000000000327e-05,-1.017268111401582482e-09,0.000000000000000000e+00 +8.039866522067549681e+01,4.967131121345781253e+02,6.553733574825351682e-02,9.247031680644930418e+00,3.620754297597272246e-03,1.000000009929363332e+00,-4.000000000000000327e-05,2.839649585324885756e-10,0.000000000000000000e+00 +8.039974664878620558e+01,4.967231120690289004e+02,6.557354321211689152e-02,9.248113108766370161e+00,3.620608312195734528e-03,1.000000009929670419e+00,-4.000000000000000327e-05,-5.339083415998882986e-10,0.000000000000000000e+00 +8.040082795044010311e+01,4.967331120034849619e+02,6.560974921613582644e-02,9.249194410431011093e+00,3.620462326794196811e-03,1.000000009929093103e+00,-4.000000000000000327e-05,-4.518214181225715986e-10,0.000000000000000000e+00 +8.040190912568155568e+01,4.967431119379463098e+02,6.564595376031030771e-02,9.250275585683205293e+00,3.620316341392659093e-03,1.000000009928604605e+00,-4.000000000000000327e-05,5.128772548313112636e-10,0.000000000000000000e+00 +8.040299017455490116e+01,4.967531118724129442e+02,6.568215684464034920e-02,9.251356634567279968e+00,3.620170355991121375e-03,1.000000009929159051e+00,-4.000000000000000327e-05,8.227126384916950061e-10,0.000000000000000000e+00 +8.040407109710442057e+01,4.967631118068848650e+02,6.571835846912593704e-02,9.252437557127537460e+00,3.620024370589583658e-03,1.000000009930048339e+00,-4.000000000000000327e-05,-1.062358081680569789e-09,0.000000000000000000e+00 +8.040515189337440916e+01,4.967731117413620723e+02,6.575455863376707122e-02,9.253518353408253461e+00,3.619878385188045940e-03,1.000000009928900147e+00,-4.000000000000000327e-05,-5.985323117902616771e-10,0.000000000000000000e+00 +8.040623256340910530e+01,4.967831116758445660e+02,6.579075733856375174e-02,9.254599023453675244e+00,3.619732399786508223e-03,1.000000009928253331e+00,-4.000000000000000327e-05,6.764842016606542286e-10,0.000000000000000000e+00 +8.040731310725273318e+01,4.967931116103323461e+02,6.582695458351599249e-02,9.255679567308026989e+00,3.619586414384970505e-03,1.000000009928984301e+00,-4.000000000000000327e-05,-2.982057057324449538e-10,0.000000000000000000e+00 +8.040839352494948855e+01,4.968031115448254127e+02,6.586315036862377958e-02,9.256759985015508008e+00,3.619440428983432788e-03,1.000000009928662115e+00,-4.000000000000000327e-05,1.023801521013162319e-09,0.000000000000000000e+00 +8.040947381654353876e+01,4.968131114793237657e+02,6.589934469388711302e-02,9.257840276620289188e+00,3.619294443581895070e-03,1.000000009929768119e+00,-4.000000000000000327e-05,-1.463830847865678766e-09,0.000000000000000000e+00 +8.041055398207903693e+01,4.968231114138273483e+02,6.593553755930599281e-02,9.258920442166518328e+00,3.619148458180357353e-03,1.000000009928186939e+00,-4.000000000000000327e-05,1.355656062865718093e-09,0.000000000000000000e+00 +8.041163402160010776e+01,4.968331113483362174e+02,6.597172896488041893e-02,9.260000481698313024e+00,3.619002472778819635e-03,1.000000009929651101e+00,-4.000000000000000327e-05,-1.194818972630715567e-09,0.000000000000000000e+00 +8.041271393515084753e+01,4.968431112828503728e+02,6.600791891061039141e-02,9.261080395259771336e+00,3.618856487377281918e-03,1.000000009928360800e+00,-4.000000000000000327e-05,1.527885092595495511e-09,0.000000000000000000e+00 +8.041379372277530990e+01,4.968531112173698148e+02,6.604410739649591022e-02,9.262160182894959348e+00,3.618710501975744200e-03,1.000000009930010592e+00,-4.000000000000000327e-05,-1.157667288021262916e-09,0.000000000000000000e+00 +8.041487338451754852e+01,4.968631111518945431e+02,6.608029442253696151e-02,9.263239844647923604e+00,3.618564516574206483e-03,1.000000009928760702e+00,-4.000000000000000327e-05,-1.279362212474268425e-10,0.000000000000000000e+00 +8.041595292042158860e+01,4.968731110864245579e+02,6.611647998873355914e-02,9.264319380562678674e+00,3.618418531172668765e-03,1.000000009928622591e+00,-4.000000000000000327e-05,2.777074384621073678e-11,0.000000000000000000e+00 +8.041703233053141275e+01,4.968831110209598592e+02,6.615266409508570311e-02,9.265398790683217811e+00,3.618272545771131048e-03,1.000000009928652567e+00,-4.000000000000000327e-05,-7.081336103616305083e-10,0.000000000000000000e+00 +8.041811161489098936e+01,4.968931109555004468e+02,6.618884674159337955e-02,9.266478075053507624e+00,3.618126560369593330e-03,1.000000009927888289e+00,-4.000000000000000327e-05,6.950476402762972734e-10,0.000000000000000000e+00 +8.041919077354425838e+01,4.969031108900463209e+02,6.622502792825660234e-02,9.267557233717488074e+00,3.617980574968055613e-03,1.000000009928638356e+00,-4.000000000000000327e-05,-3.549724120902079099e-10,0.000000000000000000e+00 +8.042026980653513135e+01,4.969131108245974815e+02,6.626120765507535759e-02,9.268636266719076033e+00,3.617834589566517895e-03,1.000000009928255329e+00,-4.000000000000000327e-05,6.997372305327344766e-10,0.000000000000000000e+00 +8.042134871390750561e+01,4.969231107591539285e+02,6.629738592204965919e-02,9.269715174102159949e+00,3.617688604164980178e-03,1.000000009929010281e+00,-4.000000000000000327e-05,-7.362504201361070128e-10,0.000000000000000000e+00 +8.042242749570523586e+01,4.969331106937156619e+02,6.633356272917949326e-02,9.270793955910605177e+00,3.617542618763442460e-03,1.000000009928216027e+00,-4.000000000000000327e-05,-1.027206360859487708e-10,0.000000000000000000e+00 +8.042350615197217678e+01,4.969431106282826818e+02,6.636973807646487367e-02,9.271872612188248652e+00,3.617396633361904743e-03,1.000000009928105227e+00,-4.000000000000000327e-05,1.057589784832192184e-09,0.000000000000000000e+00 +8.042458468275212624e+01,4.969531105628549881e+02,6.640591196390578654e-02,9.272951142978904215e+00,3.617250647960367025e-03,1.000000009929245870e+00,-4.000000000000000327e-05,-1.855578706256319472e-09,0.000000000000000000e+00 +8.042566308808888209e+01,4.969631104974325240e+02,6.644208439150223189e-02,9.274029548326360839e+00,3.617104662558829307e-03,1.000000009927244804e+00,-4.000000000000000327e-05,1.831495373201589311e-09,0.000000000000000000e+00 +8.042674136802619955e+01,4.969731104320153463e+02,6.647825535925420970e-02,9.275107828274377297e+00,3.616958677157291590e-03,1.000000009929219669e+00,-4.000000000000000327e-05,-1.647178225162326074e-09,0.000000000000000000e+00 +8.042781952260780542e+01,4.969831103666034551e+02,6.651442486716173386e-02,9.276185982866694602e+00,3.616812691755753872e-03,1.000000009927443756e+00,-4.000000000000000327e-05,1.441602963538546123e-09,0.000000000000000000e+00 +8.042889755187742651e+01,4.969931103011968503e+02,6.655059291522479048e-02,9.277264012147020011e+00,3.616666706354216155e-03,1.000000009928997846e+00,-4.000000000000000327e-05,-1.145753324117964619e-09,0.000000000000000000e+00 +8.042997545587874697e+01,4.970031102357955319e+02,6.658675950344337957e-02,9.278341916159043024e+00,3.616520720952678437e-03,1.000000009927762834e+00,-4.000000000000000327e-05,1.272795121699101113e-09,0.000000000000000000e+00 +8.043105323465542256e+01,4.970131101703995000e+02,6.662292463181750113e-02,9.279419694946421160e+00,3.616374735551140720e-03,1.000000009929134626e+00,-4.000000000000000327e-05,-2.022944979640150275e-09,0.000000000000000000e+00 +8.043213088825109480e+01,4.970231101050087545e+02,6.665908830034714128e-02,9.280497348552792403e+00,3.616228750149603002e-03,1.000000009926954592e+00,-4.000000000000000327e-05,1.183657100558282735e-09,0.000000000000000000e+00 +8.043320841670936261e+01,4.970331100396232955e+02,6.669525050903231389e-02,9.281574877021762759e+00,3.616082764748065285e-03,1.000000009928230016e+00,-4.000000000000000327e-05,1.683774602973371266e-10,0.000000000000000000e+00 +8.043428582007382488e+01,4.970431099742430661e+02,6.673141125787301897e-02,9.282652280396920474e+00,3.615936779346527567e-03,1.000000009928411426e+00,-4.000000000000000327e-05,-4.983891791265848919e-10,0.000000000000000000e+00 +8.043536309838803788e+01,4.970531099088681231e+02,6.676757054686925652e-02,9.283729558721823594e+00,3.615790793944989850e-03,1.000000009927874522e+00,-4.000000000000000327e-05,6.977845980199097960e-10,0.000000000000000000e+00 +8.043644025169552947e+01,4.970631098434984665e+02,6.680372837602102654e-02,9.284806712040005294e+00,3.615644808543452132e-03,1.000000009928626143e+00,-4.000000000000000327e-05,-8.543441291018756859e-10,0.000000000000000000e+00 +8.043751728003981327e+01,4.970731097781340964e+02,6.683988474532831514e-02,9.285883740394975661e+00,3.615498823141914415e-03,1.000000009927705991e+00,-4.000000000000000327e-05,-5.789760125336294114e-10,0.000000000000000000e+00 +8.043859418346436030e+01,4.970831097127750127e+02,6.687603965479113621e-02,9.286960643830216355e+00,3.615352837740376697e-03,1.000000009927082489e+00,-4.000000000000000327e-05,1.508234207502882982e-09,0.000000000000000000e+00 +8.043967096201264155e+01,4.970931096474212154e+02,6.691219310440947587e-02,9.288037422389185949e+00,3.615206852338838980e-03,1.000000009928706524e+00,-4.000000000000000327e-05,-7.399742656740126689e-10,0.000000000000000000e+00 +8.044074761572808541e+01,4.971031095820727046e+02,6.694834509418334800e-02,9.289114076115319918e+00,3.615060866937301262e-03,1.000000009927909828e+00,-4.000000000000000327e-05,-1.212807427099129291e-09,0.000000000000000000e+00 +8.044182414465410602e+01,4.971131095167294234e+02,6.698449562411273872e-02,9.290190605052023542e+00,3.614914881535763545e-03,1.000000009926604205e+00,-4.000000000000000327e-05,1.607568642318266934e-09,0.000000000000000000e+00 +8.044290054883407493e+01,4.971231094513914286e+02,6.702064469419764803e-02,9.291267009242679009e+00,3.614768896134225827e-03,1.000000009928334599e+00,-4.000000000000000327e-05,3.734167039299684840e-11,0.000000000000000000e+00 +8.044397682831136365e+01,4.971331093860587202e+02,6.705679230443808980e-02,9.292343288730647188e+00,3.614622910732688110e-03,1.000000009928374789e+00,-4.000000000000000327e-05,-1.342805203098574898e-09,0.000000000000000000e+00 +8.044505298312928687e+01,4.971431093207312983e+02,6.709293845483405017e-02,9.293419443559258752e+00,3.614476925331150392e-03,1.000000009926929723e+00,-4.000000000000000327e-05,5.189837426600515640e-10,0.000000000000000000e+00 +8.044612901333115929e+01,4.971531092554091629e+02,6.712908314538552912e-02,9.294495473771819505e+00,3.614330939929612675e-03,1.000000009927488165e+00,-4.000000000000000327e-05,-5.312202089211274107e-10,0.000000000000000000e+00 +8.044720491896026715e+01,4.971631091900923138e+02,6.716522637609252666e-02,9.295571379411613933e+00,3.614184954528074957e-03,1.000000009926916622e+00,-4.000000000000000327e-05,1.626663205048627005e-09,0.000000000000000000e+00 +8.044828070005986831e+01,4.971731091247806944e+02,6.720136814695504279e-02,9.296647160521898101e+00,3.614038969126537239e-03,1.000000009928666556e+00,-4.000000000000000327e-05,-2.234366222386464171e-09,0.000000000000000000e+00 +8.044935635667319218e+01,4.971831090594743614e+02,6.723750845797307751e-02,9.297722817145906760e+00,3.613892983724999522e-03,1.000000009926263145e+00,-4.000000000000000327e-05,1.684639498742659342e-09,0.000000000000000000e+00 +8.045043188884345398e+01,4.971931089941733148e+02,6.727364730914663082e-02,9.298798349326842683e+00,3.613746998323461804e-03,1.000000009928075029e+00,-4.000000000000000327e-05,-4.515603888583586334e-10,0.000000000000000000e+00 +8.045150729661382627e+01,4.972031089288775547e+02,6.730978470047570272e-02,9.299873757107892658e+00,3.613601012921924087e-03,1.000000009927589417e+00,-4.000000000000000327e-05,-9.843792048188264989e-10,0.000000000000000000e+00 +8.045258258002746743e+01,4.972131088635870810e+02,6.734592063196029321e-02,9.300949040532211498e+00,3.613455027520386369e-03,1.000000009926530931e+00,-4.000000000000000327e-05,1.607778094670903192e-09,0.000000000000000000e+00 +8.045365773912750740e+01,4.972231087983018938e+02,6.738205510360040229e-02,9.302024199642930924e+00,3.613309042118848652e-03,1.000000009928259548e+00,-4.000000000000000327e-05,-1.912826477499089248e-09,0.000000000000000000e+00 +8.045473277395706191e+01,4.972331087330219361e+02,6.741818811539602996e-02,9.303099234483161339e+00,3.613163056717310934e-03,1.000000009926203193e+00,-4.000000000000000327e-05,7.306391490128781325e-10,0.000000000000000000e+00 +8.045580768455921827e+01,4.972431086677472649e+02,6.745431966734716234e-02,9.304174145095981174e+00,3.613017071315773217e-03,1.000000009926988565e+00,-4.000000000000000327e-05,2.991483541347812892e-10,0.000000000000000000e+00 +8.045688247097702117e+01,4.972531086024778801e+02,6.749044975945381331e-02,9.305248931524451095e+00,3.612871085914235499e-03,1.000000009927310085e+00,-4.000000000000000327e-05,-1.506245455269744335e-10,0.000000000000000000e+00 +8.045795713325350107e+01,4.972631085372137818e+02,6.752657839171596899e-02,9.306323593811603345e+00,3.612725100512697782e-03,1.000000009927148215e+00,-4.000000000000000327e-05,9.019918697947304379e-10,0.000000000000000000e+00 +8.045903167143167423e+01,4.972731084719549131e+02,6.756270556413364325e-02,9.307398132000445301e+00,3.612579115111160064e-03,1.000000009928117439e+00,-4.000000000000000327e-05,-1.175514809377687551e-09,0.000000000000000000e+00 +8.046010608555452848e+01,4.972831084067013308e+02,6.759883127670682224e-02,9.308472546133961245e+00,3.612433129709622347e-03,1.000000009926854450e+00,-4.000000000000000327e-05,-2.461673265773522757e-10,0.000000000000000000e+00 +8.046118037566500902e+01,4.972931083414530349e+02,6.763495552943551981e-02,9.309546836255107038e+00,3.612287144308084629e-03,1.000000009926589994e+00,-4.000000000000000327e-05,5.957482059246115306e-10,0.000000000000000000e+00 +8.046225454180606107e+01,4.973031082762100255e+02,6.767107832231972209e-02,9.310621002406817226e+00,3.612141158906546912e-03,1.000000009927229927e+00,-4.000000000000000327e-05,-2.069440535248206808e-10,0.000000000000000000e+00 +8.046332858402058719e+01,4.973131082109723025e+02,6.770719965535942908e-02,9.311695044632001483e+00,3.611995173505009194e-03,1.000000009927007660e+00,-4.000000000000000327e-05,-1.132224138098543880e-09,0.000000000000000000e+00 +8.046440250235146152e+01,4.973231081457398091e+02,6.774331952855465466e-02,9.312768962973542841e+00,3.611849188103471477e-03,1.000000009925791744e+00,-4.000000000000000327e-05,2.423727108236415379e-09,0.000000000000000000e+00 +8.046547629684155822e+01,4.973331080805126021e+02,6.777943794190538496e-02,9.313842757474299461e+00,3.611703202701933759e-03,1.000000009928394329e+00,-4.000000000000000327e-05,-1.880099287547817379e-09,0.000000000000000000e+00 +8.046654996753370881e+01,4.973431080152906816e+02,6.781555489541161996e-02,9.314916428177109964e+00,3.611557217300396042e-03,1.000000009926375721e+00,-4.000000000000000327e-05,-1.962842264355852356e-10,0.000000000000000000e+00 +8.046762351447071637e+01,4.973531079500740475e+02,6.785167038907335968e-02,9.315989975124779221e+00,3.611411231898858324e-03,1.000000009926165001e+00,-4.000000000000000327e-05,1.297611021166161320e-09,0.000000000000000000e+00 +8.046869693769536980e+01,4.973631078848626430e+02,6.788778442289060411e-02,9.317063398360094340e+00,3.611265246497320607e-03,1.000000009927557887e+00,-4.000000000000000327e-05,-2.043357376315727394e-09,0.000000000000000000e+00 +8.046977023725044376e+01,4.973731078196565250e+02,6.792389699686335325e-02,9.318136697925817558e+00,3.611119261095782889e-03,1.000000009925364752e+00,-4.000000000000000327e-05,2.099456898859781105e-09,0.000000000000000000e+00 +8.047084341317865608e+01,4.973831077544556933e+02,6.796000811099160710e-02,9.319209873864680915e+00,3.610973275694245171e-03,1.000000009927617839e+00,-4.000000000000000327e-05,-1.712743283332550787e-09,0.000000000000000000e+00 +8.047191646552272459e+01,4.973931076892601482e+02,6.799611776527536566e-02,9.320282926219400466e+00,3.610827290292707454e-03,1.000000009925779976e+00,-4.000000000000000327e-05,3.845165447583652884e-10,0.000000000000000000e+00 +8.047298939432533871e+01,4.974031076240698326e+02,6.803222595971462894e-02,9.321355855032658511e+00,3.610681304891169736e-03,1.000000009926192535e+00,-4.000000000000000327e-05,6.610803149559155264e-10,0.000000000000000000e+00 +8.047406219962914520e+01,4.974131075588848034e+02,6.806833269430938305e-02,9.322428660347119589e+00,3.610535319489632019e-03,1.000000009926901745e+00,-4.000000000000000327e-05,-9.012758181359571804e-10,0.000000000000000000e+00 +8.047513488147680505e+01,4.974231074937050607e+02,6.810443796905964187e-02,9.323501342205421594e+00,3.610389334088094301e-03,1.000000009925934963e+00,-4.000000000000000327e-05,1.855342968789419438e-09,0.000000000000000000e+00 +8.047620743991090819e+01,4.974331074285305476e+02,6.814054178396540540e-02,9.324573900650175773e+00,3.610243348686556584e-03,1.000000009927924927e+00,-4.000000000000000327e-05,-1.894688312128462190e-09,0.000000000000000000e+00 +8.047727987497405877e+01,4.974431073633613209e+02,6.817664413902665976e-02,9.325646335723973834e+00,3.610097363285018866e-03,1.000000009925892996e+00,-4.000000000000000327e-05,1.859497091745183281e-10,0.000000000000000000e+00 +8.047835218670881829e+01,4.974531072981973807e+02,6.821274503424341884e-02,9.326718647469375512e+00,3.609951377883481149e-03,1.000000009926092392e+00,-4.000000000000000327e-05,3.576526431498997137e-10,0.000000000000000000e+00 +8.047942437515771985e+01,4.974631072330387269e+02,6.824884446961566875e-02,9.327790835928922775e+00,3.609805392481943431e-03,1.000000009926475864e+00,-4.000000000000000327e-05,1.485040097417797316e-10,0.000000000000000000e+00 +8.048049644036328232e+01,4.974731071678853027e+02,6.828494244514342337e-02,9.328862901145130948e+00,3.609659407080405714e-03,1.000000009926635069e+00,-4.000000000000000327e-05,-4.596489139894420642e-10,0.000000000000000000e+00 +8.048156838236799615e+01,4.974831071027371650e+02,6.832103896082666883e-02,9.329934843160490487e+00,3.609513421678867996e-03,1.000000009926142353e+00,-4.000000000000000327e-05,-1.484552771515447761e-09,0.000000000000000000e+00 +8.048264020121433759e+01,4.974931070375943136e+02,6.835713401666540512e-02,9.331006662017466979e+00,3.609367436277330279e-03,1.000000009924551181e+00,-4.000000000000000327e-05,1.697714604200120548e-09,0.000000000000000000e+00 +8.048371189694474026e+01,4.975031069724566919e+02,6.839322761265963224e-02,9.332078357758501141e+00,3.609221450875792561e-03,1.000000009926370614e+00,-4.000000000000000327e-05,-2.099075441554934434e-10,0.000000000000000000e+00 +8.048478346960160934e+01,4.975131069073243566e+02,6.842931974880936408e-02,9.333149930426014151e+00,3.609075465474254844e-03,1.000000009926145683e+00,-4.000000000000000327e-05,5.087682071013479751e-10,0.000000000000000000e+00 +8.048585491922735002e+01,4.975231068421973077e+02,6.846541042511458675e-02,9.334221380062396989e+00,3.608929480072717126e-03,1.000000009926690803e+00,-4.000000000000000327e-05,-8.039667761142073961e-10,0.000000000000000000e+00 +8.048692624586433908e+01,4.975331067770755453e+02,6.850149964157530025e-02,9.335292706710019317e+00,3.608783494671179409e-03,1.000000009925829492e+00,-4.000000000000000327e-05,4.763412473356349272e-10,0.000000000000000000e+00 +8.048799744955491065e+01,4.975431067119590125e+02,6.853758739819150458e-02,9.336363910411224154e+00,3.608637509269641691e-03,1.000000009926339750e+00,-4.000000000000000327e-05,-3.093049139997982589e-10,0.000000000000000000e+00 +8.048906853034138464e+01,4.975531066468477661e+02,6.857367369496319975e-02,9.337434991208333201e+00,3.608491523868103974e-03,1.000000009926008460e+00,-4.000000000000000327e-05,-1.631708399081545642e-09,0.000000000000000000e+00 +8.049013948826606679e+01,4.975631065817418062e+02,6.860975853189038576e-02,9.338505949143641516e+00,3.608345538466566256e-03,1.000000009924260969e+00,-4.000000000000000327e-05,2.689620985182154484e-09,0.000000000000000000e+00 +8.049121032337122017e+01,4.975731065166410758e+02,6.864584190897306260e-02,9.339576784259419284e+00,3.608199553065028539e-03,1.000000009927141109e+00,-4.000000000000000327e-05,-1.305043999607503116e-09,0.000000000000000000e+00 +8.049228103569909365e+01,4.975831064515456319e+02,6.868192382621121639e-02,9.340647496597918931e+00,3.608053567663490821e-03,1.000000009925743782e+00,-4.000000000000000327e-05,-1.239031724879512813e-09,0.000000000000000000e+00 +8.049335162529190768e+01,4.975931063864554744e+02,6.871800428360486102e-02,9.341718086201359128e+00,3.607907582261953103e-03,1.000000009924417288e+00,-4.000000000000000327e-05,1.322767145499749618e-09,0.000000000000000000e+00 +8.049442209219186850e+01,4.976031063213705465e+02,6.875408328115399648e-02,9.342788553111939009e+00,3.607761596860415386e-03,1.000000009925833266e+00,-4.000000000000000327e-05,1.640941992400511478e-10,0.000000000000000000e+00 +8.049549243644113972e+01,4.976131062562909051e+02,6.879016081885860889e-02,9.343858897371836392e+00,3.607615611458877668e-03,1.000000009926008904e+00,-4.000000000000000327e-05,-8.278266294795250652e-11,0.000000000000000000e+00 +8.049656265808188493e+01,4.976231061912165501e+02,6.882623689671871214e-02,9.344929119023200670e+00,3.607469626057339951e-03,1.000000009925920308e+00,-4.000000000000000327e-05,-9.852057715669581458e-10,0.000000000000000000e+00 +8.049763275715622513e+01,4.976331061261474247e+02,6.886231151473430623e-02,9.345999218108158146e+00,3.607323640655802233e-03,1.000000009924866040e+00,-4.000000000000000327e-05,5.426723060997858202e-10,0.000000000000000000e+00 +8.049870273370625284e+01,4.976431060610835857e+02,6.889838467290537727e-02,9.347069194668810255e+00,3.607177655254264516e-03,1.000000009925446687e+00,-4.000000000000000327e-05,-1.697731422387402125e-10,0.000000000000000000e+00 +8.049977258777406064e+01,4.976531059960249763e+02,6.893445637123192526e-02,9.348139048747237112e+00,3.607031669852726798e-03,1.000000009925265054e+00,-4.000000000000000327e-05,-3.715509876935375195e-11,0.000000000000000000e+00 +8.050084231940169843e+01,4.976631059309716534e+02,6.897052660971396409e-02,9.349208780385492190e+00,3.606885684451189081e-03,1.000000009925225308e+00,-4.000000000000000327e-05,9.252470686100386428e-10,0.000000000000000000e+00 +8.050191192863120193e+01,4.976731058659236169e+02,6.900659538835147988e-02,9.350278389625605868e+00,3.606739699049651363e-03,1.000000009926214961e+00,-4.000000000000000327e-05,-4.054777334991667758e-10,0.000000000000000000e+00 +8.050298141550456421e+01,4.976831058008808100e+02,6.904266270714447262e-02,9.351347876509585433e+00,3.606593713648113646e-03,1.000000009925781308e+00,-4.000000000000000327e-05,-9.408242458089893109e-10,0.000000000000000000e+00 +8.050405078006377835e+01,4.976931057358432895e+02,6.907872856609294232e-02,9.352417241079411525e+00,3.606447728246575928e-03,1.000000009924775224e+00,-4.000000000000000327e-05,8.564120235690419229e-10,0.000000000000000000e+00 +8.050512002235079478e+01,4.977031056708110555e+02,6.911479296519690285e-02,9.353486483377041694e+00,3.606301742845038211e-03,1.000000009925690936e+00,-4.000000000000000327e-05,-1.244888591797321563e-09,0.000000000000000000e+00 +8.050618914240754975e+01,4.977131056057840510e+02,6.915085590445634034e-02,9.354555603444412171e+00,3.606155757443500493e-03,1.000000009924360000e+00,-4.000000000000000327e-05,5.078579434863248142e-10,0.000000000000000000e+00 +8.050725814027596527e+01,4.977231055407623330e+02,6.918691738387125478e-02,9.355624601323430767e+00,3.606009772041962776e-03,1.000000009924902900e+00,-4.000000000000000327e-05,-1.186175967972253861e-10,0.000000000000000000e+00 +8.050832701599790653e+01,4.977331054757458446e+02,6.922297740344164618e-02,9.356693477055985753e+00,3.605863786640425058e-03,1.000000009924776112e+00,-4.000000000000000327e-05,-3.220285125102146362e-11,0.000000000000000000e+00 +8.050939576961525290e+01,4.977431054107346426e+02,6.925903596316751454e-02,9.357762230683938753e+00,3.605717801238887341e-03,1.000000009924741695e+00,-4.000000000000000327e-05,7.505160310390477327e-10,0.000000000000000000e+00 +8.051046440116984115e+01,4.977531053457287271e+02,6.929509306304884597e-02,9.358830862249128302e+00,3.605571815837349623e-03,1.000000009925543720e+00,-4.000000000000000327e-05,-8.983530767615151868e-10,0.000000000000000000e+00 +8.051153291070347962e+01,4.977631052807280412e+02,6.933114870308565436e-02,9.359899371793369838e+00,3.605425830435811906e-03,1.000000009924583821e+00,-4.000000000000000327e-05,1.227868595433783716e-09,0.000000000000000000e+00 +8.051260129825796241e+01,4.977731052157326417e+02,6.936720288327793971e-02,9.360967759358452156e+00,3.605279845034274188e-03,1.000000009925895661e+00,-4.000000000000000327e-05,-6.680467374526448178e-10,0.000000000000000000e+00 +8.051366956387505525e+01,4.977831051507424718e+02,6.940325560362570201e-02,9.362036024986144511e+00,3.605133859632736471e-03,1.000000009925182010e+00,-4.000000000000000327e-05,-3.775081896278917408e-10,0.000000000000000000e+00 +8.051473770759649540e+01,4.977931050857575883e+02,6.943930686412892739e-02,9.363104168718187736e+00,3.604987874231198753e-03,1.000000009924778777e+00,-4.000000000000000327e-05,-1.030781470590209047e-09,0.000000000000000000e+00 +8.051580572946400594e+01,4.978031050207779913e+02,6.947535666478762972e-02,9.364172190596301348e+00,3.604841888829661035e-03,1.000000009923677879e+00,-4.000000000000000327e-05,4.707453502452725132e-10,0.000000000000000000e+00 +8.051687362951928151e+01,4.978131049558036239e+02,6.951140500560179514e-02,9.365240090662179995e+00,3.604695903428123318e-03,1.000000009924180588e+00,-4.000000000000000327e-05,9.954571459136443474e-10,0.000000000000000000e+00 +8.051794140780400255e+01,4.978231048908345429e+02,6.954745188657143751e-02,9.366307868957497007e+00,3.604549918026585600e-03,1.000000009925243516e+00,-4.000000000000000327e-05,-1.031966060289037927e-09,0.000000000000000000e+00 +8.051900906435980687e+01,4.978331048258706915e+02,6.958349730769654296e-02,9.367375525523900848e+00,3.604403932625047883e-03,1.000000009924141731e+00,-4.000000000000000327e-05,6.048567875055144280e-10,0.000000000000000000e+00 +8.052007659922831806e+01,4.978431047609121265e+02,6.961954126897712536e-02,9.368443060403013334e+00,3.604257947223510165e-03,1.000000009924787436e+00,-4.000000000000000327e-05,-3.444831466309891677e-10,0.000000000000000000e+00 +8.052114401245114550e+01,4.978531046959588480e+02,6.965558377041317084e-02,9.369510473636436743e+00,3.604111961821972448e-03,1.000000009924419730e+00,-4.000000000000000327e-05,7.799604243721835575e-10,0.000000000000000000e+00 +8.052221130406987015e+01,4.978631046310107990e+02,6.969162481200467940e-02,9.370577765265746706e+00,3.603965976420434730e-03,1.000000009925252176e+00,-4.000000000000000327e-05,-7.167964089247580333e-10,0.000000000000000000e+00 +8.052327847412603035e+01,4.978731045660680365e+02,6.972766439375165104e-02,9.371644935332497539e+00,3.603819991018897013e-03,1.000000009924487232e+00,-4.000000000000000327e-05,-1.718842560857112723e-10,0.000000000000000000e+00 +8.052434552266116441e+01,4.978831045011305036e+02,6.976370251565408576e-02,9.372711983878216913e+00,3.603674005617359295e-03,1.000000009924303823e+00,-4.000000000000000327e-05,-7.219544489361580984e-10,0.000000000000000000e+00 +8.052541244971676804e+01,4.978931044361982572e+02,6.979973917771199743e-02,9.373778910944411180e+00,3.603528020215821578e-03,1.000000009923533550e+00,-4.000000000000000327e-05,7.378552488845432313e-10,0.000000000000000000e+00 +8.052647925533433693e+01,4.979031043712712403e+02,6.983577437992537218e-02,9.374845716572561827e+00,3.603382034814283860e-03,1.000000009924320699e+00,-4.000000000000000327e-05,1.069335341297900018e-09,0.000000000000000000e+00 +8.052754593955532414e+01,4.979131043063495099e+02,6.987180812229421001e-02,9.375912400804129021e+00,3.603236049412746143e-03,1.000000009925461342e+00,-4.000000000000000327e-05,-1.305749343712825326e-09,0.000000000000000000e+00 +8.052861250242115432e+01,4.979231042414330091e+02,6.990784040481849704e-02,9.376978963680548063e+00,3.603090064011208425e-03,1.000000009924068678e+00,-4.000000000000000327e-05,-1.586565983108151948e-10,0.000000000000000000e+00 +8.052967894397325210e+01,4.979331041765217947e+02,6.994387122749824715e-02,9.378045405243227606e+00,3.602944078609670708e-03,1.000000009923899480e+00,-4.000000000000000327e-05,-1.897015736535352378e-10,0.000000000000000000e+00 +8.053074526425299950e+01,4.979431041116158099e+02,6.997990059033346033e-02,9.379111725533556765e+00,3.602798093208132990e-03,1.000000009923697197e+00,-4.000000000000000327e-05,1.459889391508322936e-10,0.000000000000000000e+00 +8.053181146330176432e+01,4.979531040467151115e+02,7.001592849332413659e-02,9.380177924592899785e+00,3.602652107806595273e-03,1.000000009923852851e+00,-4.000000000000000327e-05,8.327105969768135732e-10,0.000000000000000000e+00 +8.053287754116088593e+01,4.979631039818196427e+02,7.005195493647027594e-02,9.381244002462597820e+00,3.602506122405057555e-03,1.000000009924740585e+00,-4.000000000000000327e-05,-1.272746371739829595e-09,0.000000000000000000e+00 +8.053394349787167528e+01,4.979731039169294604e+02,7.008797991977186448e-02,9.382309959183968928e+00,3.602360137003519838e-03,1.000000009923383892e+00,-4.000000000000000327e-05,6.583200533820962892e-11,0.000000000000000000e+00 +8.053500933347542912e+01,4.979831038520445645e+02,7.012400344322891610e-02,9.383375794798304526e+00,3.602214151601982120e-03,1.000000009923454058e+00,-4.000000000000000327e-05,1.707034466819801467e-09,0.000000000000000000e+00 +8.053607504801342998e+01,4.979931037871648982e+02,7.016002550684141692e-02,9.384441509346876487e+00,3.602068166200444402e-03,1.000000009925273270e+00,-4.000000000000000327e-05,-2.623876393619181209e-09,0.000000000000000000e+00 +8.053714064152691776e+01,4.980031037222905184e+02,7.019604611060938082e-02,9.385507102870933593e+00,3.601922180798906685e-03,1.000000009922477284e+00,-4.000000000000000327e-05,1.135989063211205790e-09,0.000000000000000000e+00 +8.053820611405710395e+01,4.980131036574213681e+02,7.023206525453279392e-02,9.386572575411694430e+00,3.601776195397368967e-03,1.000000009923687649e+00,-4.000000000000000327e-05,4.549891115451505469e-10,0.000000000000000000e+00 +8.053927146564520001e+01,4.980231035925575043e+02,7.026808293861167010e-02,9.387637927010363370e+00,3.601630209995831250e-03,1.000000009924172373e+00,-4.000000000000000327e-05,1.000547690247482839e-11,0.000000000000000000e+00 +8.054033669633237480e+01,4.980331035276988700e+02,7.030409916284599547e-02,9.388703157708116365e+00,3.601484224594293532e-03,1.000000009924183031e+00,-4.000000000000000327e-05,-2.153506342564278275e-10,0.000000000000000000e+00 +8.054140180615979716e+01,4.980431034628455222e+02,7.034011392723577005e-02,9.389768267546106273e+00,3.601338239192755815e-03,1.000000009923953659e+00,-4.000000000000000327e-05,-2.372670124476942964e-10,0.000000000000000000e+00 +8.054246679516857910e+01,4.980531033979974040e+02,7.037612723178099383e-02,9.390833256565462861e+00,3.601192253791218097e-03,1.000000009923700972e+00,-4.000000000000000327e-05,-7.193884318279685690e-11,0.000000000000000000e+00 +8.054353166339984682e+01,4.980631033331545723e+02,7.041213907648166681e-02,9.391898124807292803e+00,3.601046268389680380e-03,1.000000009923624367e+00,-4.000000000000000327e-05,-1.302136440701689534e-09,0.000000000000000000e+00 +8.054459641089466970e+01,4.980731032683169701e+02,7.044814946133780287e-02,9.392962872312679679e+00,3.600900282988142662e-03,1.000000009922237920e+00,-4.000000000000000327e-05,2.323838728630797751e-09,0.000000000000000000e+00 +8.054566103769410290e+01,4.980831032034845975e+02,7.048415838634938813e-02,9.394027499122682201e+00,3.600754297586604945e-03,1.000000009924711941e+00,-4.000000000000000327e-05,-1.747978438496568502e-09,0.000000000000000000e+00 +8.054672554383920158e+01,4.980931031386575114e+02,7.052016585151642258e-02,9.395092005278341318e+00,3.600608312185067227e-03,1.000000009922851207e+00,-4.000000000000000327e-05,5.722253198054636998e-10,0.000000000000000000e+00 +8.054778992937096405e+01,4.981031030738356549e+02,7.055617185683889236e-02,9.396156390820666005e+00,3.600462326783529510e-03,1.000000009923460276e+00,-4.000000000000000327e-05,-1.366569621016896947e-10,0.000000000000000000e+00 +8.054885419433038862e+01,4.981131030090190848e+02,7.059217640231681135e-02,9.397220655790649246e+00,3.600316341381991792e-03,1.000000009923314837e+00,-4.000000000000000327e-05,-7.563932786167871756e-10,0.000000000000000000e+00 +8.054991833875843099e+01,4.981231029442077443e+02,7.062817948795017953e-02,9.398284800229257385e+00,3.600170355980454075e-03,1.000000009922509925e+00,-4.000000000000000327e-05,1.836000455499964432e-09,0.000000000000000000e+00 +8.055098236269604683e+01,4.981331028794016902e+02,7.066418111373899691e-02,9.399348824177433670e+00,3.600024370578916357e-03,1.000000009924463473e+00,-4.000000000000000327e-05,-1.790918796823838501e-09,0.000000000000000000e+00 +8.055204626618414920e+01,4.981431028146008657e+02,7.070018127968326349e-02,9.400412727676101809e+00,3.599878385177378640e-03,1.000000009922558108e+00,-4.000000000000000327e-05,9.008833974955012570e-10,0.000000000000000000e+00 +8.055311004926365115e+01,4.981531027498053277e+02,7.073617998578296540e-02,9.401476510766155315e+00,3.599732399775840922e-03,1.000000009923516453e+00,-4.000000000000000327e-05,-1.091578398222297641e-09,0.000000000000000000e+00 +8.055417371197540888e+01,4.981631026850150192e+02,7.077217723203811650e-02,9.402540173488471709e+00,3.599586414374303205e-03,1.000000009922355382e+00,-4.000000000000000327e-05,1.635569451410494317e-09,0.000000000000000000e+00 +8.055523725436027860e+01,4.981731026202299972e+02,7.080817301844870293e-02,9.403603715883900094e+00,3.599440428972765487e-03,1.000000009924094879e+00,-4.000000000000000327e-05,-1.926406764834906053e-09,0.000000000000000000e+00 +8.055630067645910231e+01,4.981831025554502048e+02,7.084416734501473856e-02,9.404667137993271808e+00,3.599294443571227770e-03,1.000000009922046296e+00,-4.000000000000000327e-05,7.709839671903564172e-10,0.000000000000000000e+00 +8.055736397831266515e+01,4.981931024906756988e+02,7.088016021173620951e-02,9.405730439857387992e+00,3.599148458169690052e-03,1.000000009922866084e+00,-4.000000000000000327e-05,2.871676086880527797e-10,0.000000000000000000e+00 +8.055842715996176651e+01,4.982031024259064225e+02,7.091615161861312966e-02,9.406793621517033799e+00,3.599002472768152334e-03,1.000000009923171396e+00,-4.000000000000000327e-05,-2.527360605694275905e-10,0.000000000000000000e+00 +8.055949022144714888e+01,4.982131023611423757e+02,7.095214156564548513e-02,9.407856683012967736e+00,3.598856487366614617e-03,1.000000009922902722e+00,-4.000000000000000327e-05,-8.644132288694907388e-10,0.000000000000000000e+00 +8.056055316280955481e+01,4.982231022963836153e+02,7.098813005283327593e-02,9.408919624385925218e+00,3.598710501965076899e-03,1.000000009921983901e+00,-4.000000000000000327e-05,1.580270759557026209e-09,0.000000000000000000e+00 +8.056161598408969837e+01,4.982331022316300846e+02,7.102411708017650205e-02,9.409982445676618568e+00,3.598564516563539182e-03,1.000000009923663447e+00,-4.000000000000000327e-05,-7.958661093617144594e-10,0.000000000000000000e+00 +8.056267868532827947e+01,4.982431021668818403e+02,7.106010264767516349e-02,9.411045146925740568e+00,3.598418531162001464e-03,1.000000009922817679e+00,-4.000000000000000327e-05,-1.479487635519177623e-10,0.000000000000000000e+00 +8.056374126656595536e+01,4.982531021021388256e+02,7.109608675532927413e-02,9.412107728173955579e+00,3.598272545760463747e-03,1.000000009922660471e+00,-4.000000000000000327e-05,3.648978917556827963e-10,0.000000000000000000e+00 +8.056480372784336907e+01,4.982631020374010404e+02,7.113206940313882010e-02,9.413170189461908421e+00,3.598126560358926029e-03,1.000000009923048161e+00,-4.000000000000000327e-05,-8.485983242593274140e-10,0.000000000000000000e+00 +8.056586606920113525e+01,4.982731019726685417e+02,7.116805059110380138e-02,9.414232530830220824e+00,3.597980574957388312e-03,1.000000009922146660e+00,-4.000000000000000327e-05,9.176766193684719184e-10,0.000000000000000000e+00 +8.056692829067986850e+01,4.982831019079412727e+02,7.120403031922420412e-02,9.415294752319489646e+00,3.597834589555850594e-03,1.000000009923121436e+00,-4.000000000000000327e-05,-6.493451443368844783e-10,0.000000000000000000e+00 +8.056799039232012660e+01,4.982931018432192900e+02,7.124000858750004217e-02,9.416356853970292207e+00,3.597688604154312877e-03,1.000000009922431765e+00,-4.000000000000000327e-05,-8.428221338253438588e-10,0.000000000000000000e+00 +8.056905237416248156e+01,4.983031017785025369e+02,7.127598539593131555e-02,9.417418835823179180e+00,3.597542618752775159e-03,1.000000009921536703e+00,-4.000000000000000327e-05,3.226547310147856880e-10,0.000000000000000000e+00 +8.057011423624744850e+01,4.983131017137910703e+02,7.131196074451802425e-02,9.418480697918679923e+00,3.597396633351237442e-03,1.000000009921879318e+00,-4.000000000000000327e-05,1.256466753598482477e-09,0.000000000000000000e+00 +8.057117597861554259e+01,4.983231016490848333e+02,7.134793463326016827e-02,9.419542440297302477e+00,3.597250647949699724e-03,1.000000009923213362e+00,-4.000000000000000327e-05,-1.210803261805916886e-09,0.000000000000000000e+00 +8.057223760130723633e+01,4.983331015843838259e+02,7.138390706215773374e-02,9.420604062999531791e+00,3.597104662548162007e-03,1.000000009921927946e+00,-4.000000000000000327e-05,7.856779418308476999e-10,0.000000000000000000e+00 +8.057329910436300224e+01,4.983431015196881049e+02,7.141987803121073453e-02,9.421665566065826170e+00,3.596958677146624289e-03,1.000000009922761945e+00,-4.000000000000000327e-05,-6.516673476019152760e-10,0.000000000000000000e+00 +8.057436048782327020e+01,4.983531014549976135e+02,7.145584754041915676e-02,9.422726949536626151e+00,3.596812691745086572e-03,1.000000009922070277e+00,-4.000000000000000327e-05,-8.088699129806496241e-10,0.000000000000000000e+00 +8.057542175172845589e+01,4.983631013903123517e+02,7.149181558978301432e-02,9.423788213452345630e+00,3.596666706343548854e-03,1.000000009921211852e+00,-4.000000000000000327e-05,1.876136693153312621e-09,0.000000000000000000e+00 +8.057648289611896075e+01,4.983731013256323763e+02,7.152778217930229332e-02,9.424849357853377185e+00,3.596520720942011137e-03,1.000000009923202704e+00,-4.000000000000000327e-05,-2.077878519782276434e-09,0.000000000000000000e+00 +8.057754392103514363e+01,4.983831012609576305e+02,7.156374730897700764e-02,9.425910382780093855e+00,3.596374735540473419e-03,1.000000009920998023e+00,-4.000000000000000327e-05,1.512800556973881532e-09,0.000000000000000000e+00 +8.057860482651736334e+01,4.983931011962881712e+02,7.159971097880714341e-02,9.426971288272838478e+00,3.596228750138935702e-03,1.000000009922602962e+00,-4.000000000000000327e-05,-1.570324728131185780e-09,0.000000000000000000e+00 +8.057966561260593608e+01,4.984031011316239415e+02,7.163567318879270063e-02,9.428032074371939686e+00,3.596082764737397984e-03,1.000000009920937183e+00,-4.000000000000000327e-05,1.284746372407954294e-09,0.000000000000000000e+00 +8.058072627934116383e+01,4.984131010669649413e+02,7.167163393893367929e-02,9.429092741117695908e+00,3.595936779335860266e-03,1.000000009922299871e+00,-4.000000000000000327e-05,5.902081587285841535e-10,0.000000000000000000e+00 +8.058178682676333437e+01,4.984231010023112276e+02,7.170759322923009327e-02,9.430153288550389590e+00,3.595790793934322549e-03,1.000000009922925814e+00,-4.000000000000000327e-05,-2.093495878406388272e-09,0.000000000000000000e+00 +8.058284725491269285e+01,4.984331009376627435e+02,7.174355105968192869e-02,9.431213716710276529e+00,3.595644808532784831e-03,1.000000009920705812e+00,-4.000000000000000327e-05,1.117019675976496469e-09,0.000000000000000000e+00 +8.058390756382948439e+01,4.984431008730194890e+02,7.177950743028918557e-02,9.432274025637587656e+00,3.595498823131247114e-03,1.000000009921890198e+00,-4.000000000000000327e-05,7.286367361734750320e-10,0.000000000000000000e+00 +8.058496775355391151e+01,4.984531008083815209e+02,7.181546234105186388e-02,9.433334215372537912e+00,3.595352837729709396e-03,1.000000009922662692e+00,-4.000000000000000327e-05,-1.697271371163015502e-09,0.000000000000000000e+00 +8.058602782412617671e+01,4.984631007437487824e+02,7.185141579196996364e-02,9.434394285955315596e+00,3.595206852328171679e-03,1.000000009920863464e+00,-4.000000000000000327e-05,1.462209733648480938e-10,0.000000000000000000e+00 +8.058708777558642566e+01,4.984731006791212735e+02,7.188736778304348485e-02,9.435454237426084134e+00,3.595060866926633961e-03,1.000000009921018451e+00,-4.000000000000000327e-05,1.503228300803897199e-09,0.000000000000000000e+00 +8.058814760797481824e+01,4.984831006144990511e+02,7.192331831427241362e-02,9.436514069824989193e+00,3.594914881525096244e-03,1.000000009922611621e+00,-4.000000000000000327e-05,-8.069104425278091034e-10,0.000000000000000000e+00 +8.058920732133147169e+01,4.984931005498820582e+02,7.195926738565676384e-02,9.437573783192153343e+00,3.594768896123558526e-03,1.000000009921756527e+00,-4.000000000000000327e-05,-4.742257580262220074e-10,0.000000000000000000e+00 +8.059026691569647483e+01,4.985031004852702949e+02,7.199521499719653550e-02,9.438633377567672511e+00,3.594622910722020809e-03,1.000000009921254041e+00,-4.000000000000000327e-05,-6.767330512894800067e-10,0.000000000000000000e+00 +8.059132639110991647e+01,4.985131004206638181e+02,7.203116114889171473e-02,9.439692852991623084e+00,3.594476925320483091e-03,1.000000009920537059e+00,-4.000000000000000327e-05,1.734676803341243536e-09,0.000000000000000000e+00 +8.059238574761184282e+01,4.985231003560625709e+02,7.206710584074231540e-02,9.440752209504058357e+00,3.594330939918945374e-03,1.000000009922374700e+00,-4.000000000000000327e-05,-1.169927223570835653e-09,0.000000000000000000e+00 +8.059344498524228584e+01,4.985331002914665532e+02,7.210304907274833752e-02,9.441811447145012082e+00,3.594184954517407656e-03,1.000000009921135469e+00,-4.000000000000000327e-05,9.161719388478250199e-11,0.000000000000000000e+00 +8.059450410404124909e+01,4.985431002268758220e+02,7.213899084490976721e-02,9.442870565954489592e+00,3.594038969115869939e-03,1.000000009921232502e+00,-4.000000000000000327e-05,-8.294697364278560010e-10,0.000000000000000000e+00 +8.059556310404873614e+01,4.985531001622903204e+02,7.217493115722661834e-02,9.443929565972478457e+00,3.593892983714332221e-03,1.000000009920354094e+00,-4.000000000000000327e-05,8.025118003235726943e-10,0.000000000000000000e+00 +8.059662198530469368e+01,4.985631000977100484e+02,7.221087000969887704e-02,9.444988447238941376e+00,3.593746998312794504e-03,1.000000009921203858e+00,-4.000000000000000327e-05,2.202069164703088512e-10,0.000000000000000000e+00 +8.059768074784906844e+01,4.985731000331350060e+02,7.224680740232654330e-02,9.446047209793821509e+00,3.593601012911256786e-03,1.000000009921437005e+00,-4.000000000000000327e-05,-1.009709455334017158e-09,0.000000000000000000e+00 +8.059873939172177870e+01,4.985830999685652500e+02,7.228274333510961713e-02,9.447105853677037146e+00,3.593455027509719069e-03,1.000000009920368083e+00,-4.000000000000000327e-05,1.854138368188070326e-09,0.000000000000000000e+00 +8.059979791696272855e+01,4.985930999040007237e+02,7.231867780804811241e-02,9.448164378928483487e+00,3.593309042108181351e-03,1.000000009922330735e+00,-4.000000000000000327e-05,-2.302040951862199801e-09,0.000000000000000000e+00 +8.060085632361177943e+01,4.986030998394414269e+02,7.235461082114201525e-02,9.449222785588037965e+00,3.593163056706643634e-03,1.000000009919894239e+00,-4.000000000000000327e-05,7.761052930075374371e-10,0.000000000000000000e+00 +8.060191461170879279e+01,4.986130997748874165e+02,7.239054237439132566e-02,9.450281073695547818e+00,3.593017071305105916e-03,1.000000009920715582e+00,-4.000000000000000327e-05,-2.685931427122212460e-11,0.000000000000000000e+00 +8.060297278129358745e+01,4.986230997103386358e+02,7.242647246779604364e-02,9.451339243290846071e+00,3.592871085903568198e-03,1.000000009920687161e+00,-4.000000000000000327e-05,3.105955954667660794e-11,0.000000000000000000e+00 +8.060403083240598221e+01,4.986330996457950846e+02,7.246240110135616919e-02,9.452397294413739104e+00,3.592725100502030481e-03,1.000000009920720023e+00,-4.000000000000000327e-05,9.350393780718935235e-10,0.000000000000000000e+00 +8.060508876508575327e+01,4.986430995812567630e+02,7.249832827507170230e-02,9.453455227104011982e+00,3.592579115100492763e-03,1.000000009921709232e+00,-4.000000000000000327e-05,-5.054605664437708268e-10,0.000000000000000000e+00 +8.060614657937267680e+01,4.986530995167237279e+02,7.253425398894264298e-02,9.454513041401428453e+00,3.592433129698955046e-03,1.000000009921174549e+00,-4.000000000000000327e-05,-1.131535427426693138e-09,0.000000000000000000e+00 +8.060720427530648635e+01,4.986630994521959224e+02,7.257017824296899122e-02,9.455570737345727395e+00,3.592287144297417328e-03,1.000000009919977728e+00,-4.000000000000000327e-05,6.300774964612571182e-10,0.000000000000000000e+00 +8.060826185292690127e+01,4.986730993876733464e+02,7.260610103715073316e-02,9.456628314976626370e+00,3.592141158895879611e-03,1.000000009920644084e+00,-4.000000000000000327e-05,-4.199586596243699064e-13,0.000000000000000000e+00 +8.060931931227361247e+01,4.986830993231560001e+02,7.264202237148788266e-02,9.457685774333823403e+00,3.591995173494341893e-03,1.000000009920643640e+00,-4.000000000000000327e-05,1.379718462532447136e-10,0.000000000000000000e+00 +8.061037665338629665e+01,4.986930992586439402e+02,7.267794224598043973e-02,9.458743115456991646e+00,3.591849188092804176e-03,1.000000009920789523e+00,-4.000000000000000327e-05,-5.595100307415596577e-10,0.000000000000000000e+00 +8.061143387630460211e+01,4.987030991941371099e+02,7.271386066062839049e-02,9.459800338385782936e+00,3.591703202691266458e-03,1.000000009920197996e+00,-4.000000000000000327e-05,-5.188229143152174256e-10,0.000000000000000000e+00 +8.061249098106816291e+01,4.987130991296355091e+02,7.274977761543174881e-02,9.460857443159826019e+00,3.591557217289728741e-03,1.000000009919649546e+00,-4.000000000000000327e-05,1.834569564065685881e-09,0.000000000000000000e+00 +8.061354796771658471e+01,4.987230990651391380e+02,7.278569311039050083e-02,9.461914429818728323e+00,3.591411231888191023e-03,1.000000009921588662e+00,-4.000000000000000327e-05,-1.464374034828276131e-09,0.000000000000000000e+00 +8.061460483628944473e+01,4.987330990006480533e+02,7.282160714550466041e-02,9.462971298402077736e+00,3.591265246486653306e-03,1.000000009920041011e+00,-4.000000000000000327e-05,-8.917500113984825081e-10,0.000000000000000000e+00 +8.061566158682632022e+01,4.987430989361621982e+02,7.285751972077421368e-02,9.464028048949433725e+00,3.591119261085115588e-03,1.000000009919098654e+00,-4.000000000000000327e-05,1.949712663277321580e-09,0.000000000000000000e+00 +8.061671821936674576e+01,4.987530988716815727e+02,7.289343083619917452e-02,9.465084681500337993e+00,3.590973275683577871e-03,1.000000009921158783e+00,-4.000000000000000327e-05,-9.117048748918602674e-10,0.000000000000000000e+00 +8.061777473395024174e+01,4.987630988072061768e+02,7.292934049177952904e-02,9.466141196094312704e+00,3.590827290282040153e-03,1.000000009920195554e+00,-4.000000000000000327e-05,5.570049792436011240e-11,0.000000000000000000e+00 +8.061883113061630013e+01,4.987730987427360674e+02,7.296524868751527726e-02,9.467197592770851600e+00,3.590681304880502436e-03,1.000000009920254396e+00,-4.000000000000000327e-05,6.222334841732673268e-11,0.000000000000000000e+00 +8.061988740940439868e+01,4.987830986782711875e+02,7.300115542340641916e-02,9.468253871569430657e+00,3.590535319478964718e-03,1.000000009920320121e+00,-4.000000000000000327e-05,-9.080156287157496828e-10,0.000000000000000000e+00 +8.062094357035398673e+01,4.987930986138115372e+02,7.303706069945295476e-02,9.469310032529502763e+00,3.590389334077427001e-03,1.000000009919361110e+00,-4.000000000000000327e-05,3.149708589218302016e-10,0.000000000000000000e+00 +8.062199961350449939e+01,4.988030985493571166e+02,7.307296451565488404e-02,9.470366075690497709e+00,3.590243348675889283e-03,1.000000009919693733e+00,-4.000000000000000327e-05,5.309680326774591422e-10,0.000000000000000000e+00 +8.062305553889535759e+01,4.988130984849079255e+02,7.310886687201220702e-02,9.471422001091825749e+00,3.590097363274351566e-03,1.000000009920254396e+00,-4.000000000000000327e-05,-2.769753931861170654e-10,0.000000000000000000e+00 +8.062411134656592537e+01,4.988230984204640208e+02,7.314476776852492368e-02,9.472477808772874042e+00,3.589951377872813848e-03,1.000000009919961963e+00,-4.000000000000000327e-05,-5.302451046222159798e-10,0.000000000000000000e+00 +8.062516703655558103e+01,4.988330983560253458e+02,7.318066720519303403e-02,9.473533498773006656e+00,3.589805392471276130e-03,1.000000009919402189e+00,-4.000000000000000327e-05,-2.440114523455757978e-10,0.000000000000000000e+00 +8.062622260890367443e+01,4.988430982915919003e+02,7.321656518201653807e-02,9.474589071131566342e+00,3.589659407069738413e-03,1.000000009919144617e+00,-4.000000000000000327e-05,5.665483275531470960e-10,0.000000000000000000e+00 +8.062727806364951277e+01,4.988530982271636844e+02,7.325246169899543580e-02,9.475644525887874536e+00,3.589513421668200695e-03,1.000000009919742583e+00,-4.000000000000000327e-05,2.920373854283202635e-10,0.000000000000000000e+00 +8.062833340083240330e+01,4.988630981627406982e+02,7.328835675612971334e-02,9.476699863081231356e+00,3.589367436266662978e-03,1.000000009920050781e+00,-4.000000000000000327e-05,-1.084320064724976937e-09,0.000000000000000000e+00 +8.062938862049162481e+01,4.988730980983229983e+02,7.332425035341938457e-02,9.477755082750913829e+00,3.589221450865125260e-03,1.000000009918906585e+00,-4.000000000000000327e-05,1.209026277990776725e-09,0.000000000000000000e+00 +8.063044372266642767e+01,4.988830980339105281e+02,7.336014249086444949e-02,9.478810184936175887e+00,3.589075465463587543e-03,1.000000009920182231e+00,-4.000000000000000327e-05,-8.212612221752060147e-10,0.000000000000000000e+00 +8.063149870739603386e+01,4.988930979695032875e+02,7.339603316846489423e-02,9.479865169676253700e+00,3.588929480062049825e-03,1.000000009919315813e+00,-4.000000000000000327e-05,7.891468483371137877e-10,0.000000000000000000e+00 +8.063255357471967955e+01,4.989030979051012764e+02,7.343192238622073265e-02,9.480920037010356793e+00,3.588783494660512108e-03,1.000000009920148258e+00,-4.000000000000000327e-05,-1.957403006438924856e-09,0.000000000000000000e+00 +8.063360832467652983e+01,4.989130978407044950e+02,7.346781014413195088e-02,9.481974786977676928e+00,3.588637509258974390e-03,1.000000009918083688e+00,-4.000000000000000327e-05,2.101210502792599157e-09,0.000000000000000000e+00 +8.063466295730577826e+01,4.989230977763129431e+02,7.350369644219856280e-02,9.483029419617379219e+00,3.588491523857436673e-03,1.000000009920299693e+00,-4.000000000000000327e-05,-1.421528042207785284e-09,0.000000000000000000e+00 +8.063571747264654732e+01,4.989330977119266777e+02,7.353958128042055453e-02,9.484083934968614571e+00,3.588345538455898955e-03,1.000000009918800670e+00,-4.000000000000000327e-05,2.339643423832111917e-10,0.000000000000000000e+00 +8.063677187073797370e+01,4.989430976475456418e+02,7.357546465879792608e-02,9.485138333070503691e+00,3.588199553054361238e-03,1.000000009919047361e+00,-4.000000000000000327e-05,6.653245064696049995e-10,0.000000000000000000e+00 +8.063782615161916567e+01,4.989530975831698356e+02,7.361134657733069131e-02,9.486192613962151299e+00,3.588053567652823520e-03,1.000000009919748800e+00,-4.000000000000000327e-05,-1.440748797587623638e-10,0.000000000000000000e+00 +8.063888031532920309e+01,4.989630975187992590e+02,7.364722703601883635e-02,9.487246777682639021e+00,3.587907582251285803e-03,1.000000009919596922e+00,-4.000000000000000327e-05,-6.113329875397924729e-10,0.000000000000000000e+00 +8.063993436190713737e+01,4.989730974544339119e+02,7.368310603486236121e-02,9.488300824271025391e+00,3.587761596849748085e-03,1.000000009918952548e+00,-4.000000000000000327e-05,-7.523475674336274024e-10,0.000000000000000000e+00 +8.064098829139200575e+01,4.989830973900737945e+02,7.371898357386126588e-02,9.489354753766347628e+00,3.587615611448210368e-03,1.000000009918159627e+00,-4.000000000000000327e-05,1.018974229199144485e-09,0.000000000000000000e+00 +8.064204210382283122e+01,4.989930973257189066e+02,7.375485965301555036e-02,9.490408566207621632e+00,3.587469626046672650e-03,1.000000009919233435e+00,-4.000000000000000327e-05,-1.116865830950173219e-10,0.000000000000000000e+00 +8.064309579923860838e+01,4.990030972613693052e+02,7.379073427232521465e-02,9.491462261633843767e+00,3.587323640645134933e-03,1.000000009919115751e+00,-4.000000000000000327e-05,-9.610327625486708844e-10,0.000000000000000000e+00 +8.064414937767830338e+01,4.990130971970249334e+02,7.382660743179025875e-02,9.492515840083985523e+00,3.587177655243597215e-03,1.000000009918103228e+00,-4.000000000000000327e-05,1.657333205131292394e-09,0.000000000000000000e+00 +8.064520283918086818e+01,4.990230971326857912e+02,7.386247913141068266e-02,9.493569301596997079e+00,3.587031669842059498e-03,1.000000009919849164e+00,-4.000000000000000327e-05,-1.874851504455403700e-09,0.000000000000000000e+00 +8.064625618378522631e+01,4.990330970683518785e+02,7.389834937118647251e-02,9.494622646211810846e+00,3.586885684440521780e-03,1.000000009917874300e+00,-4.000000000000000327e-05,1.232892748671480642e-09,0.000000000000000000e+00 +8.064730941153030130e+01,4.990430970040231955e+02,7.393421815111764217e-02,9.495675873967330816e+00,3.586739699038984062e-03,1.000000009919172816e+00,-4.000000000000000327e-05,-2.405756965239530617e-10,0.000000000000000000e+00 +8.064836252245497406e+01,4.990530969396997421e+02,7.397008547120419164e-02,9.496728984902446769e+00,3.586593713637446345e-03,1.000000009918919464e+00,-4.000000000000000327e-05,9.341529639410115326e-11,0.000000000000000000e+00 +8.064941551659811125e+01,4.990630968753815182e+02,7.400595133144610704e-02,9.497781979056021839e+00,3.586447728235908627e-03,1.000000009919017829e+00,-4.000000000000000327e-05,-9.831837474463074022e-10,0.000000000000000000e+00 +8.065046839399855116e+01,4.990730968110685239e+02,7.404181573184340226e-02,9.498834856466899623e+00,3.586301742834370910e-03,1.000000009917982657e+00,-4.000000000000000327e-05,-2.805189493826571233e-10,0.000000000000000000e+00 +8.065152115469511784e+01,4.990830967467608161e+02,7.407767867239606341e-02,9.499887617173900622e+00,3.586155757432833192e-03,1.000000009917687338e+00,-4.000000000000000327e-05,5.836706459643222886e-10,0.000000000000000000e+00 +8.065257379872660692e+01,4.990930966824583379e+02,7.411354015310410437e-02,9.500940261215825799e+00,3.586009772031295475e-03,1.000000009918301735e+00,-4.000000000000000327e-05,-8.016603601528367288e-12,0.000000000000000000e+00 +8.065362632613179983e+01,4.991030966181610893e+02,7.414940017396751126e-02,9.501992788631454800e+00,3.585863786629757757e-03,1.000000009918293298e+00,-4.000000000000000327e-05,1.134897047673191157e-09,0.000000000000000000e+00 +8.065467873694944956e+01,4.991130965538690702e+02,7.418525873498629797e-02,9.503045199459544179e+00,3.585717801228220040e-03,1.000000009919487676e+00,-4.000000000000000327e-05,-8.132325079727627190e-10,0.000000000000000000e+00 +8.065573103121829490e+01,4.991230964895822808e+02,7.422111583616045061e-02,9.504097493738830948e+00,3.585571815826682322e-03,1.000000009918631916e+00,-4.000000000000000327e-05,-1.056432986727009191e-09,0.000000000000000000e+00 +8.065678320897706044e+01,4.991330964253007210e+02,7.425697147748996918e-02,9.505149671508027254e+00,3.585425830425144605e-03,1.000000009917520361e+00,-4.000000000000000327e-05,3.919323297017031598e-10,0.000000000000000000e+00 +8.065783527026442812e+01,4.991430963610243907e+02,7.429282565897485369e-02,9.506201732805825699e+00,3.585279845023606887e-03,1.000000009917932697e+00,-4.000000000000000327e-05,3.079658379015736872e-10,0.000000000000000000e+00 +8.065888721511906567e+01,4.991530962967532901e+02,7.432867838061510413e-02,9.507253677670899350e+00,3.585133859622069170e-03,1.000000009918256660e+00,-4.000000000000000327e-05,2.799231596870924277e-10,0.000000000000000000e+00 +8.065993904357962663e+01,4.991630962324874190e+02,7.436452964241073438e-02,9.508305506141898178e+00,3.584987874220531452e-03,1.000000009918551092e+00,-4.000000000000000327e-05,-1.312153024472448809e-09,0.000000000000000000e+00 +8.066099075568475030e+01,4.991730961682267775e+02,7.440037944436173056e-02,9.509357218257450839e+00,3.584841888818993735e-03,1.000000009917171084e+00,-4.000000000000000327e-05,3.344618323124449086e-10,0.000000000000000000e+00 +8.066204235147303336e+01,4.991830961039713657e+02,7.443622778646807880e-02,9.510408814056162896e+00,3.584695903417456017e-03,1.000000009917522803e+00,-4.000000000000000327e-05,3.870810195963902127e-10,0.000000000000000000e+00 +8.066309383098305830e+01,4.991930960397211834e+02,7.447207466872979298e-02,9.511460293576622149e+00,3.584549918015918300e-03,1.000000009917929811e+00,-4.000000000000000327e-05,4.371774677315000118e-10,0.000000000000000000e+00 +8.066414519425340757e+01,4.992030959754762875e+02,7.450792009114687309e-02,9.512511656857393305e+00,3.584403932614380582e-03,1.000000009918389443e+00,-4.000000000000000327e-05,-1.138899260539340452e-09,0.000000000000000000e+00 +8.066519644132260680e+01,4.992130959112366213e+02,7.454376405371931913e-02,9.513562903937019755e+00,3.584257947212842865e-03,1.000000009917192179e+00,-4.000000000000000327e-05,4.670594484635860123e-10,0.000000000000000000e+00 +8.066624757222918163e+01,4.992230958470021847e+02,7.457960655644713110e-02,9.514614034854021796e+00,3.584111961811305147e-03,1.000000009917683119e+00,-4.000000000000000327e-05,4.183084054478972129e-10,0.000000000000000000e+00 +8.066729858701164346e+01,4.992330957827729776e+02,7.461544759933029514e-02,9.515665049646901963e+00,3.583965976409767430e-03,1.000000009918122768e+00,-4.000000000000000327e-05,3.065820927580821143e-10,0.000000000000000000e+00 +8.066834948570846109e+01,4.992430957185490001e+02,7.465128718236882510e-02,9.516715948354139698e+00,3.583819991008229712e-03,1.000000009918444954e+00,-4.000000000000000327e-05,-1.491450988566256653e-09,0.000000000000000000e+00 +8.066940026835808908e+01,4.992530956543302523e+02,7.468712530556272100e-02,9.517766731014193127e+00,3.583674005606691994e-03,1.000000009916877763e+00,-4.000000000000000327e-05,1.444487543055972497e-09,0.000000000000000000e+00 +8.067045093499896780e+01,4.992630955901167340e+02,7.472296196891196896e-02,9.518817397665497282e+00,3.583528020205154277e-03,1.000000009918395438e+00,-4.000000000000000327e-05,-2.163483056760818254e-09,0.000000000000000000e+00 +8.067150148566952339e+01,4.992730955259084453e+02,7.475879717241658284e-02,9.519867948346471209e+00,3.583382034803616559e-03,1.000000009916122590e+00,-4.000000000000000327e-05,2.153998188562112984e-09,0.000000000000000000e+00 +8.067255192040813938e+01,4.992830954617053862e+02,7.479463091607654879e-02,9.520918383095505533e+00,3.583236049402078842e-03,1.000000009918385224e+00,-4.000000000000000327e-05,-1.714509602888204489e-09,0.000000000000000000e+00 +8.067360223925319929e+01,4.992930953975075568e+02,7.483046319989186679e-02,9.521968701950978442e+00,3.583090064000541124e-03,1.000000009916584442e+00,-4.000000000000000327e-05,7.055425034965349419e-10,0.000000000000000000e+00 +8.067465244224304399e+01,4.993030953333149569e+02,7.486629402386255072e-02,9.523018904951237928e+00,3.582944078599003407e-03,1.000000009917325405e+00,-4.000000000000000327e-05,-2.619908828379498547e-10,0.000000000000000000e+00 +8.067570252941601439e+01,4.993130952691275866e+02,7.490212338798858671e-02,9.524068992134617773e+00,3.582798093197465689e-03,1.000000009917050292e+00,-4.000000000000000327e-05,1.998455889122222235e-10,0.000000000000000000e+00 +8.067675250081040872e+01,4.993230952049454459e+02,7.493795129226997476e-02,9.525118963539426886e+00,3.582652107795927972e-03,1.000000009917260124e+00,-4.000000000000000327e-05,4.657232812224924522e-10,0.000000000000000000e+00 +8.067780235646452525e+01,4.993330951407685347e+02,7.497377773670671486e-02,9.526168819203954641e+00,3.582506122394390254e-03,1.000000009917749066e+00,-4.000000000000000327e-05,-1.091672469664386621e-09,0.000000000000000000e+00 +8.067885209641663380e+01,4.993430950765968532e+02,7.500960272129880702e-02,9.527218559166469092e+00,3.582360136992852537e-03,1.000000009916603094e+00,-4.000000000000000327e-05,3.490521343657498535e-10,0.000000000000000000e+00 +8.067990172070497579e+01,4.993530950124304013e+02,7.504542624604625123e-02,9.528268183465215202e+00,3.582214151591314819e-03,1.000000009916969468e+00,-4.000000000000000327e-05,-6.347101633251839261e-11,0.000000000000000000e+00 +8.068095122936777841e+01,4.993630949482691790e+02,7.508124831094904750e-02,9.529317692138420171e+00,3.582068166189777102e-03,1.000000009916902854e+00,-4.000000000000000327e-05,8.823443037590462974e-10,0.000000000000000000e+00 +8.068200062244324045e+01,4.993730948841131863e+02,7.511706891600719582e-02,9.530367085224288104e+00,3.581922180788239384e-03,1.000000009917828780e+00,-4.000000000000000327e-05,-1.669867059506221645e-09,0.000000000000000000e+00 +8.068304989996954646e+01,4.993830948199624231e+02,7.515288806122069620e-02,9.531416362761003569e+00,3.581776195386701667e-03,1.000000009916076626e+00,-4.000000000000000327e-05,3.337562138677552669e-10,0.000000000000000000e+00 +8.068409906198486681e+01,4.993930947558168896e+02,7.518870574658954864e-02,9.532465524786726263e+00,3.581630209985163949e-03,1.000000009916426791e+00,-4.000000000000000327e-05,4.241731612991150265e-10,0.000000000000000000e+00 +8.068514810852734342e+01,4.994030946916765856e+02,7.522452197211375313e-02,9.533514571339599897e+00,3.581484224583626232e-03,1.000000009916871768e+00,-4.000000000000000327e-05,2.000437875330423568e-10,0.000000000000000000e+00 +8.068619703963508982e+01,4.994130946275415113e+02,7.526033673779329580e-02,9.534563502457745088e+00,3.581338239182088514e-03,1.000000009917081600e+00,-4.000000000000000327e-05,-3.539788501451945965e-10,0.000000000000000000e+00 +8.068724585534620530e+01,4.994230945634116665e+02,7.529615004362819053e-02,9.535612318179261138e+00,3.581192253780550797e-03,1.000000009916710342e+00,-4.000000000000000327e-05,3.633340459162773247e-10,0.000000000000000000e+00 +8.068829455569877496e+01,4.994330944992870513e+02,7.533196188961843731e-02,9.536661018542226032e+00,3.581046268379013079e-03,1.000000009917091370e+00,-4.000000000000000327e-05,-8.938238184989340352e-10,0.000000000000000000e+00 +8.068934314073084124e+01,4.994430944351676658e+02,7.536777227576402227e-02,9.537709603584698215e+00,3.580900282977475362e-03,1.000000009916154120e+00,-4.000000000000000327e-05,7.069206255209286413e-10,0.000000000000000000e+00 +8.069039161048046083e+01,4.994530943710535098e+02,7.540358120206495929e-02,9.538758073344713040e+00,3.580754297575937644e-03,1.000000009916895305e+00,-4.000000000000000327e-05,-1.312754850126618952e-09,0.000000000000000000e+00 +8.069143996498563354e+01,4.994630943069445834e+02,7.543938866852123448e-02,9.539806427860288096e+00,3.580608312174399926e-03,1.000000009915519072e+00,-4.000000000000000327e-05,1.113994274695545541e-09,0.000000000000000000e+00 +8.069248820428437341e+01,4.994730942428408866e+02,7.547519467513284785e-02,9.540854667169416103e+00,3.580462326772862209e-03,1.000000009916686805e+00,-4.000000000000000327e-05,-1.099499063408543792e-10,0.000000000000000000e+00 +8.069353632841463764e+01,4.994830941787424194e+02,7.551099922189981328e-02,9.541902791310073795e+00,3.580316341371324491e-03,1.000000009916571564e+00,-4.000000000000000327e-05,-1.500059449154885200e-10,0.000000000000000000e+00 +8.069458433741438341e+01,4.994930941146491818e+02,7.554680230882211689e-02,9.542950800320213034e+00,3.580170355969786774e-03,1.000000009916414356e+00,-4.000000000000000327e-05,-6.367477024529719388e-10,0.000000000000000000e+00 +8.069563223132153951e+01,4.995030940505611738e+02,7.558260393589975867e-02,9.543998694237766145e+00,3.580024370568249056e-03,1.000000009915747112e+00,-4.000000000000000327e-05,3.284749800173910684e-11,0.000000000000000000e+00 +8.069668001017403469e+01,4.995130939864783954e+02,7.561840410313273864e-02,9.545046473100644135e+00,3.579878385166711339e-03,1.000000009915781529e+00,-4.000000000000000327e-05,2.257188767862891402e-10,0.000000000000000000e+00 +8.069772767400974089e+01,4.995230939224007898e+02,7.565420281052105678e-02,9.546094136946738473e+00,3.579732399765173621e-03,1.000000009916018007e+00,-4.000000000000000327e-05,-7.206839584132687495e-11,0.000000000000000000e+00 +8.069877522286653004e+01,4.995330938583284137e+02,7.569000005806471310e-02,9.547141685813919310e+00,3.579586414363635904e-03,1.000000009915942512e+00,-4.000000000000000327e-05,7.434458802390999701e-10,0.000000000000000000e+00 +8.069982265678225986e+01,4.995430937942612672e+02,7.572579584576370759e-02,9.548189119740035480e+00,3.579440428962098186e-03,1.000000009916721222e+00,-4.000000000000000327e-05,-5.804899185745830162e-10,0.000000000000000000e+00 +8.070086997579475963e+01,4.995530937301993504e+02,7.576159017361804027e-02,9.549236438762916279e+00,3.579294443560560469e-03,1.000000009916113264e+00,-4.000000000000000327e-05,-8.203659036881410642e-10,0.000000000000000000e+00 +8.070191717994183023e+01,4.995630936661426631e+02,7.579738304162771112e-02,9.550283642920367910e+00,3.579148458159022751e-03,1.000000009915254173e+00,-4.000000000000000327e-05,9.966768104546936767e-12,0.000000000000000000e+00 +8.070296426926125832e+01,4.995730936020912054e+02,7.583317444979272015e-02,9.551330732250177036e+00,3.579002472757485034e-03,1.000000009915264609e+00,-4.000000000000000327e-05,1.897498959323281506e-09,0.000000000000000000e+00 +8.070401124379081637e+01,4.995830935380449773e+02,7.586896439811306736e-02,9.552377706790110778e+00,3.578856487355947316e-03,1.000000009917251242e+00,-4.000000000000000327e-05,-1.655906806272930933e-09,0.000000000000000000e+00 +8.070505810356823417e+01,4.995930934740039788e+02,7.590475288658873887e-02,9.553424566577916721e+00,3.578710501954409599e-03,1.000000009915517740e+00,-4.000000000000000327e-05,-9.410026397502689320e-10,0.000000000000000000e+00 +8.070610484863125578e+01,4.996030934099682099e+02,7.594053991521974856e-02,9.554471311651315801e+00,3.578564516552871881e-03,1.000000009914532750e+00,-4.000000000000000327e-05,7.881442370468648110e-10,0.000000000000000000e+00 +8.070715147901758257e+01,4.996130933459376706e+02,7.597632548400609642e-02,9.555517942048012969e+00,3.578418531151334164e-03,1.000000009915357646e+00,-4.000000000000000327e-05,2.732815553709375762e-10,0.000000000000000000e+00 +8.070819799476488754e+01,4.996230932819123609e+02,7.601210959294776859e-02,9.556564457805693635e+00,3.578272545749796446e-03,1.000000009915643640e+00,-4.000000000000000327e-05,7.435430462477110857e-10,0.000000000000000000e+00 +8.070924439591084365e+01,4.996330932178922808e+02,7.604789224204477893e-02,9.557610858962020117e+00,3.578126560348258729e-03,1.000000009916421684e+00,-4.000000000000000327e-05,-1.060683520417264505e-09,0.000000000000000000e+00 +8.071029068249308125e+01,4.996430931538773734e+02,7.608367343129711358e-02,9.558657145554635193e+00,3.577980574946721011e-03,1.000000009915311905e+00,-4.000000000000000327e-05,-2.861060240323986873e-10,0.000000000000000000e+00 +8.071133685454923068e+01,4.996530930898676957e+02,7.611945316070477252e-02,9.559703317621158547e+00,3.577834589545183294e-03,1.000000009915012589e+00,-4.000000000000000327e-05,-1.921025894457339789e-10,0.000000000000000000e+00 +8.071238291211689386e+01,4.996630930258632475e+02,7.615523143026776964e-02,9.560749375199192102e+00,3.577688604143645576e-03,1.000000009914811638e+00,-4.000000000000000327e-05,8.302712030428880440e-10,0.000000000000000000e+00 +8.071342885523364430e+01,4.996730929618640289e+02,7.619100823998609107e-02,9.561795318326316462e+00,3.577542618742107858e-03,1.000000009915680055e+00,-4.000000000000000327e-05,-4.811046714642815754e-10,0.000000000000000000e+00 +8.071447468393705549e+01,4.996830928978700399e+02,7.622678358985973679e-02,9.562841147040092693e+00,3.577396633340570141e-03,1.000000009915176902e+00,-4.000000000000000327e-05,7.317158122233137112e-10,0.000000000000000000e+00 +8.071552039826465830e+01,4.996930928338812805e+02,7.626255747988870681e-02,9.563886861378058768e+00,3.577250647939032423e-03,1.000000009915942067e+00,-4.000000000000000327e-05,-2.044186485142267317e-09,0.000000000000000000e+00 +8.071656599825396938e+01,4.997030927698977507e+02,7.629832991007300114e-02,9.564932461377734896e+00,3.577104662537494706e-03,1.000000009913804666e+00,-4.000000000000000327e-05,9.257825750263026643e-10,0.000000000000000000e+00 +8.071761148394249119e+01,4.997130927059194505e+02,7.633410088041263364e-02,9.565977947076616417e+00,3.576958677135956988e-03,1.000000009914772559e+00,-4.000000000000000327e-05,1.503844246137974122e-09,0.000000000000000000e+00 +8.071865685536769774e+01,4.997230926419463799e+02,7.636987039090759044e-02,9.567023318512184460e+00,3.576812691734419271e-03,1.000000009916344634e+00,-4.000000000000000327e-05,-1.952449564700430999e-09,0.000000000000000000e+00 +8.071970211256704886e+01,4.997330925779784820e+02,7.640563844155785767e-02,9.568068575721897062e+00,3.576666706332881553e-03,1.000000009914303822e+00,-4.000000000000000327e-05,2.974353209508486076e-10,0.000000000000000000e+00 +8.072074725557797592e+01,4.997430925140158138e+02,7.644140503236344919e-02,9.569113718743187391e+00,3.576520720931343836e-03,1.000000009914614685e+00,-4.000000000000000327e-05,1.102755669008573624e-10,0.000000000000000000e+00 +8.072179228443789611e+01,4.997530924500583751e+02,7.647717016332436502e-02,9.570158747613474404e+00,3.576374735529806118e-03,1.000000009914729926e+00,-4.000000000000000327e-05,7.239882216651750920e-10,0.000000000000000000e+00 +8.072283719918421241e+01,4.997630923861061660e+02,7.651293383444060514e-02,9.571203662370153964e+00,3.576228750128268401e-03,1.000000009915486432e+00,-4.000000000000000327e-05,-1.130199513454599033e-09,0.000000000000000000e+00 +8.072388199985429935e+01,4.997730923221591866e+02,7.654869604571216957e-02,9.572248463050602396e+00,3.576082764726730683e-03,1.000000009914305599e+00,-4.000000000000000327e-05,-5.847157318739572327e-10,0.000000000000000000e+00 +8.072492668648551728e+01,4.997830922582174367e+02,7.658445679713904441e-02,9.573293149692172932e+00,3.575936779325192966e-03,1.000000009913694754e+00,-4.000000000000000327e-05,7.197613750533115093e-10,0.000000000000000000e+00 +8.072597125911518390e+01,4.997930921942808595e+02,7.662021608872124356e-02,9.574337722332201039e+00,3.575790793923655248e-03,1.000000009914446597e+00,-4.000000000000000327e-05,1.140986650843987448e-09,0.000000000000000000e+00 +8.072701571778063112e+01,4.998030921303495120e+02,7.665597392045875313e-02,9.575382181008002647e+00,3.575644808522117531e-03,1.000000009915638310e+00,-4.000000000000000327e-05,-9.648522944475227810e-10,0.000000000000000000e+00 +8.072806006251914823e+01,4.998130920664233940e+02,7.669173029235158701e-02,9.576426525756872365e+00,3.575498823120579813e-03,1.000000009914630672e+00,-4.000000000000000327e-05,-7.265887766674524881e-10,0.000000000000000000e+00 +8.072910429336801030e+01,4.998230920025025057e+02,7.672748520439973130e-02,9.577470756616081715e+00,3.575352837719042096e-03,1.000000009913871946e+00,-4.000000000000000327e-05,2.143638716016529355e-10,0.000000000000000000e+00 +8.073014841036446398e+01,4.998330919385868469e+02,7.676323865660319989e-02,9.578514873622884451e+00,3.575206852317504378e-03,1.000000009914095767e+00,-4.000000000000000327e-05,2.141745553738304433e-10,0.000000000000000000e+00 +8.073119241354574172e+01,4.998430918746764178e+02,7.679899064896197891e-02,9.579558876814514790e+00,3.575060866915966661e-03,1.000000009914319365e+00,-4.000000000000000327e-05,-7.423541887892660539e-10,0.000000000000000000e+00 +8.073223630294906172e+01,4.998530918107711614e+02,7.683474118147606835e-02,9.580602766228185629e+00,3.574914881514428943e-03,1.000000009913544430e+00,-4.000000000000000327e-05,5.916080135310993221e-10,0.000000000000000000e+00 +8.073328007861161382e+01,4.998630917468711345e+02,7.687049025414548209e-02,9.581646541901088554e+00,3.574768896112891226e-03,1.000000009914161936e+00,-4.000000000000000327e-05,9.416549228026086288e-10,0.000000000000000000e+00 +8.073432374057057359e+01,4.998730916829763373e+02,7.690623786697020625e-02,9.582690203870397383e+00,3.574622910711353508e-03,1.000000009915144705e+00,-4.000000000000000327e-05,-1.339227665279280759e-09,0.000000000000000000e+00 +8.073536728886308822e+01,4.998830916190867697e+02,7.694198401995024084e-02,9.583733752173264620e+00,3.574476925309815790e-03,1.000000009913747157e+00,-4.000000000000000327e-05,2.600436009893176528e-10,0.000000000000000000e+00 +8.073641072352630488e+01,4.998930915552024317e+02,7.697772871308558584e-02,9.584777186846819674e+00,3.574330939908278073e-03,1.000000009914018495e+00,-4.000000000000000327e-05,-7.993699727436943700e-10,0.000000000000000000e+00 +8.073745404459731390e+01,4.999030914913232664e+02,7.701347194637624127e-02,9.585820507928175971e+00,3.574184954506740355e-03,1.000000009913184496e+00,-4.000000000000000327e-05,3.624800976043492411e-10,0.000000000000000000e+00 +8.073849725211321982e+01,4.999130914274493307e+02,7.704921371982220712e-02,9.586863715454423840e+00,3.574038969105202638e-03,1.000000009913562637e+00,-4.000000000000000327e-05,4.687422428302366476e-10,0.000000000000000000e+00 +8.073954034611108455e+01,4.999230913635806246e+02,7.708495403342348340e-02,9.587906809462635849e+00,3.573892983703664920e-03,1.000000009914051580e+00,-4.000000000000000327e-05,-4.964695028345926444e-10,0.000000000000000000e+00 +8.074058332662797000e+01,4.999330912997171481e+02,7.712069288718007010e-02,9.588949789989863248e+00,3.573746998302127203e-03,1.000000009913533772e+00,-4.000000000000000327e-05,7.194480864475438227e-10,0.000000000000000000e+00 +8.074162619370090965e+01,4.999430912358589012e+02,7.715643028109195334e-02,9.589992657073135973e+00,3.573601012900589485e-03,1.000000009914284060e+00,-4.000000000000000327e-05,-7.972496553616941589e-10,0.000000000000000000e+00 +8.074266894736690858e+01,4.999530911720058270e+02,7.719216621515914700e-02,9.591035410749466195e+00,3.573455027499051768e-03,1.000000009913452725e+00,-4.000000000000000327e-05,-1.610006077462999081e-10,0.000000000000000000e+00 +8.074371158766294343e+01,4.999630911081579825e+02,7.722790068938165109e-02,9.592078051055842991e+00,3.573309042097514050e-03,1.000000009913284860e+00,-4.000000000000000327e-05,9.820826794774916485e-10,0.000000000000000000e+00 +8.074475411462600505e+01,4.999730910443153675e+02,7.726363370375945172e-02,9.593120578029237677e+00,3.573163056695976333e-03,1.000000009914308707e+00,-4.000000000000000327e-05,-2.286876077966446545e-09,0.000000000000000000e+00 +8.074579652829304166e+01,4.999830909804779822e+02,7.729936525829256277e-02,9.594162991706602028e+00,3.573017071294438615e-03,1.000000009911924836e+00,-4.000000000000000327e-05,1.461620875133884181e-09,0.000000000000000000e+00 +8.074683882870097307e+01,4.999930909166457695e+02,7.733509535298097037e-02,9.595205292124862950e+00,3.572871085892900898e-03,1.000000009913448284e+00,-4.000000000000000327e-05,7.697726172139402100e-10,0.000000000000000000e+00 +8.074788101588671907e+01,5.000030908528187865e+02,7.737082398782468839e-02,9.596247479320934914e+00,3.572725100491363180e-03,1.000000009914250532e+00,-4.000000000000000327e-05,-1.108226469258525845e-09,0.000000000000000000e+00 +8.074892308988715683e+01,5.000130907889970331e+02,7.740655116282370296e-02,9.597289553331707523e+00,3.572579115089825463e-03,1.000000009913095678e+00,-4.000000000000000327e-05,7.222048358510846626e-10,0.000000000000000000e+00 +8.074996505073916353e+01,5.000230907251805093e+02,7.744227687797802795e-02,9.598331514194049063e+00,3.572433129688287745e-03,1.000000009913848187e+00,-4.000000000000000327e-05,-1.934329514848291652e-09,0.000000000000000000e+00 +8.075100689847960211e+01,5.000330906613691582e+02,7.747800113328764948e-02,9.599373361944811833e+00,3.572287144286750028e-03,1.000000009911832910e+00,-4.000000000000000327e-05,2.364460820559828243e-09,0.000000000000000000e+00 +8.075204863314529291e+01,5.000430905975630367e+02,7.751372392875256756e-02,9.600415096620823263e+00,3.572141158885212310e-03,1.000000009914296051e+00,-4.000000000000000327e-05,-2.763562297061036618e-09,0.000000000000000000e+00 +8.075309025477304203e+01,5.000530905337621448e+02,7.754944526437278218e-02,9.601456718258898348e+00,3.571995173483674593e-03,1.000000009911417465e+00,-4.000000000000000327e-05,2.312101579294129473e-09,0.000000000000000000e+00 +8.075413176339964139e+01,5.000630904699664825e+02,7.758516514014829335e-02,9.602498226895821887e+00,3.571849188082136875e-03,1.000000009913825538e+00,-4.000000000000000327e-05,-4.319802606220987174e-10,0.000000000000000000e+00 +8.075517315906186866e+01,5.000730904061759929e+02,7.762088355607911494e-02,9.603539622568369793e+00,3.571703202680599157e-03,1.000000009913375676e+00,-4.000000000000000327e-05,-1.186688480805230770e-09,0.000000000000000000e+00 +8.075621444179645891e+01,5.000830903423907330e+02,7.765660051216523307e-02,9.604580905313289563e+00,3.571557217279061440e-03,1.000000009912139998e+00,-4.000000000000000327e-05,3.625497133404341429e-11,0.000000000000000000e+00 +8.075725561164016142e+01,5.000930902786107026e+02,7.769231600840664775e-02,9.605622075167310925e+00,3.571411231877523722e-03,1.000000009912177745e+00,-4.000000000000000327e-05,1.585153858455333968e-09,0.000000000000000000e+00 +8.075829666862968281e+01,5.001030902148359019e+02,7.772803004480334510e-02,9.606663132167145847e+00,3.571265246475986005e-03,1.000000009913827981e+00,-4.000000000000000327e-05,-1.472057637454626303e-09,0.000000000000000000e+00 +8.075933761280170131e+01,5.001130901510662738e+02,7.776374262135533899e-02,9.607704076349486755e+00,3.571119261074448287e-03,1.000000009912295651e+00,-4.000000000000000327e-05,6.862951099332615486e-10,0.000000000000000000e+00 +8.076037844419289513e+01,5.001230900873018754e+02,7.779945373806262943e-02,9.608744907751001207e+00,3.570973275672910570e-03,1.000000009913009968e+00,-4.000000000000000327e-05,-1.791131987184827653e-09,0.000000000000000000e+00 +8.076141916283991407e+01,5.001330900235427066e+02,7.783516339492521641e-02,9.609785626408342551e+00,3.570827290271372852e-03,1.000000009911145904e+00,-4.000000000000000327e-05,2.562268304238365883e-09,0.000000000000000000e+00 +8.076245976877939370e+01,5.001430899597887105e+02,7.787087159194308605e-02,9.610826232358139265e+00,3.570681304869835135e-03,1.000000009913812216e+00,-4.000000000000000327e-05,-2.670954593590890032e-09,0.000000000000000000e+00 +8.076350026204794119e+01,5.001530898960399441e+02,7.790657832911625225e-02,9.611866725637007391e+00,3.570535319468297417e-03,1.000000009911033105e+00,-4.000000000000000327e-05,2.182284070554061467e-09,0.000000000000000000e+00 +8.076454064268214950e+01,5.001630898322964072e+02,7.794228360644471498e-02,9.612907106281532776e+00,3.570389334066759700e-03,1.000000009913303511e+00,-4.000000000000000327e-05,-9.408850259904119998e-10,0.000000000000000000e+00 +8.076558091071859735e+01,5.001730897685580999e+02,7.797798742392846039e-02,9.613947374328292383e+00,3.570243348665221982e-03,1.000000009912324739e+00,-4.000000000000000327e-05,-5.671964714257853284e-10,0.000000000000000000e+00 +8.076662106619383508e+01,5.001830897048249653e+02,7.801368978156750233e-02,9.614987529813834755e+00,3.570097363263684265e-03,1.000000009911734766e+00,-4.000000000000000327e-05,7.045355154474831240e-12,0.000000000000000000e+00 +8.076766110914438457e+01,5.001930896410970604e+02,7.804939067936182695e-02,9.616027572774692445e+00,3.569951377862146547e-03,1.000000009911742094e+00,-4.000000000000000327e-05,7.695214104215250577e-10,0.000000000000000000e+00 +8.076870103960676772e+01,5.002030895773743850e+02,7.808509011731143423e-02,9.617067503247378468e+00,3.569805392460608830e-03,1.000000009912542343e+00,-4.000000000000000327e-05,6.214066247001131261e-11,0.000000000000000000e+00 +8.076974085761746380e+01,5.002130895136568824e+02,7.812078809541633806e-02,9.618107321268386301e+00,3.569659407059071112e-03,1.000000009912606957e+00,-4.000000000000000327e-05,-4.858601111631516912e-10,0.000000000000000000e+00 +8.077078056321296629e+01,5.002230894499446094e+02,7.815648461367652455e-02,9.619147026874188100e+00,3.569513421657533395e-03,1.000000009912101806e+00,-4.000000000000000327e-05,-8.883123677698666989e-10,0.000000000000000000e+00 +8.077182015642971180e+01,5.002330893862375660e+02,7.819217967209199371e-02,9.620186620101236485e+00,3.569367436255995677e-03,1.000000009911178322e+00,-4.000000000000000327e-05,4.848970919819574352e-10,0.000000000000000000e+00 +8.077285963730413698e+01,5.002430893225356954e+02,7.822787327066274554e-02,9.621226100985964536e+00,3.569221450854457960e-03,1.000000009911682364e+00,-4.000000000000000327e-05,3.330556162292523190e-10,0.000000000000000000e+00 +8.077389900587266425e+01,5.002530892588390543e+02,7.826356540938878004e-02,9.622265469564787566e+00,3.569075465452920242e-03,1.000000009912028531e+00,-4.000000000000000327e-05,2.852323799788834336e-10,0.000000000000000000e+00 +8.077493826217167339e+01,5.002630891951476428e+02,7.829925608827009720e-02,9.623304725874099574e+00,3.568929480051382525e-03,1.000000009912324961e+00,-4.000000000000000327e-05,-1.316484264182411852e-09,0.000000000000000000e+00 +8.077597740623754419e+01,5.002730891314614041e+02,7.833494530730669703e-02,9.624343869950275021e+00,3.568783494649844807e-03,1.000000009910956944e+00,-4.000000000000000327e-05,4.487770627758086613e-10,0.000000000000000000e+00 +8.077701643810664223e+01,5.002830890677803950e+02,7.837063306649857952e-02,9.625382901829667048e+00,3.568637509248307089e-03,1.000000009911423238e+00,-4.000000000000000327e-05,6.326302457319202926e-10,0.000000000000000000e+00 +8.077805535781529045e+01,5.002930890041046155e+02,7.840631936584574468e-02,9.626421821548612812e+00,3.568491523846769372e-03,1.000000009912080490e+00,-4.000000000000000327e-05,-7.801856860257235855e-10,0.000000000000000000e+00 +8.077909416539981180e+01,5.003030889404340087e+02,7.844200420534819251e-02,9.627460629143428150e+00,3.568345538445231654e-03,1.000000009911270027e+00,-4.000000000000000327e-05,-5.111302129164204401e-10,0.000000000000000000e+00 +8.078013286089650080e+01,5.003130888767686315e+02,7.847768758500592301e-02,9.628499324650407587e+00,3.568199553043693937e-03,1.000000009910739118e+00,-4.000000000000000327e-05,1.427299644948612432e-09,0.000000000000000000e+00 +8.078117144434162356e+01,5.003230888131084839e+02,7.851336950481892230e-02,9.629537908105827881e+00,3.568053567642156219e-03,1.000000009912221488e+00,-4.000000000000000327e-05,-1.566649571242781909e-09,0.000000000000000000e+00 +8.078220991577144616e+01,5.003330887494535091e+02,7.854904996478720425e-02,9.630576379545948029e+00,3.567907582240618502e-03,1.000000009910594567e+00,-4.000000000000000327e-05,3.755061178108462044e-10,0.000000000000000000e+00 +8.078324827522220630e+01,5.003430886858037638e+02,7.858472896491076887e-02,9.631614739007002157e+00,3.567761596839080784e-03,1.000000009910984478e+00,-4.000000000000000327e-05,6.525015321103913381e-10,0.000000000000000000e+00 +8.078428652273012744e+01,5.003530886221591913e+02,7.862040650518960228e-02,9.632652986525210181e+00,3.567615611437543067e-03,1.000000009911661936e+00,-4.000000000000000327e-05,-7.518158373106790495e-10,0.000000000000000000e+00 +8.078532465833140463e+01,5.003630885585198484e+02,7.865608258562371835e-02,9.633691122136770701e+00,3.567469626036005349e-03,1.000000009910881449e+00,-4.000000000000000327e-05,-5.542431779627404276e-10,0.000000000000000000e+00 +8.078636268206220450e+01,5.003730884948857351e+02,7.869175720621310322e-02,9.634729145877861001e+00,3.567323640634467632e-03,1.000000009910306131e+00,-4.000000000000000327e-05,1.232901426899560091e-09,0.000000000000000000e+00 +8.078740059395869366e+01,5.003830884312567946e+02,7.872743036695775687e-02,9.635767057784640599e+00,3.567177655232929914e-03,1.000000009911585774e+00,-4.000000000000000327e-05,-3.513174086951482513e-10,0.000000000000000000e+00 +8.078843839405702454e+01,5.003930883676330836e+02,7.876310206785769319e-02,9.636804857893251253e+00,3.567031669831392197e-03,1.000000009911221177e+00,-4.000000000000000327e-05,-3.733951920331373606e-10,0.000000000000000000e+00 +8.078947608239330691e+01,5.004030883040146023e+02,7.879877230891289830e-02,9.637842546239811625e+00,3.566885684429854479e-03,1.000000009910833709e+00,-4.000000000000000327e-05,-4.964871781981986485e-10,0.000000000000000000e+00 +8.079051365900363635e+01,5.004130882404012937e+02,7.883444109012337220e-02,9.638880122860422617e+00,3.566739699028316762e-03,1.000000009910318566e+00,-4.000000000000000327e-05,9.162458748593998133e-10,0.000000000000000000e+00 +8.079155112392409421e+01,5.004230881767932146e+02,7.887010841148911489e-02,9.639917587791165587e+00,3.566593713626779044e-03,1.000000009911269139e+00,-4.000000000000000327e-05,-1.099356533160631960e-09,0.000000000000000000e+00 +8.079258847719074765e+01,5.004330881131903084e+02,7.890577427301012636e-02,9.640954941068104134e+00,3.566447728225241327e-03,1.000000009910128718e+00,-4.000000000000000327e-05,4.452701824458151102e-11,0.000000000000000000e+00 +8.079362571883964961e+01,5.004430880495926317e+02,7.894143867468640663e-02,9.641992182727278760e+00,3.566301742823703609e-03,1.000000009910174903e+00,-4.000000000000000327e-05,1.033865887354102297e-09,0.000000000000000000e+00 +8.079466284890681038e+01,5.004530879860001846e+02,7.897710161651795568e-02,9.643029312804713982e+00,3.566155757422165892e-03,1.000000009911247156e+00,-4.000000000000000327e-05,-1.448510051929560917e-09,0.000000000000000000e+00 +8.079569986742822607e+01,5.004630879224129103e+02,7.901276309850477353e-02,9.644066331336414777e+00,3.566009772020628174e-03,1.000000009909745025e+00,-4.000000000000000327e-05,8.417894103659106890e-10,0.000000000000000000e+00 +8.079673677443989277e+01,5.004730878588308656e+02,7.904842312064686016e-02,9.645103238358363029e+00,3.565863786619090457e-03,1.000000009910617882e+00,-4.000000000000000327e-05,-3.677201267984500250e-10,0.000000000000000000e+00 +8.079777356997777815e+01,5.004830877952539936e+02,7.908408168294421559e-02,9.646140033906526412e+00,3.565717801217552739e-03,1.000000009910236631e+00,-4.000000000000000327e-05,-1.342954592255949651e-10,0.000000000000000000e+00 +8.079881025407782147e+01,5.004930877316823512e+02,7.911973878539683980e-02,9.647176718016849506e+00,3.565571815816015021e-03,1.000000009910097409e+00,-4.000000000000000327e-05,-1.235993744307544645e-10,0.000000000000000000e+00 +8.079984682677596197e+01,5.005030876681158816e+02,7.915539442800473280e-02,9.648213290725259128e+00,3.565425830414477304e-03,1.000000009909969290e+00,-4.000000000000000327e-05,1.303824294914910986e-09,0.000000000000000000e+00 +8.080088328810809628e+01,5.005130876045546415e+02,7.919104861076788071e-02,9.649249752067662556e+00,3.565279845012939586e-03,1.000000009911320653e+00,-4.000000000000000327e-05,-2.480231911626501632e-09,0.000000000000000000e+00 +8.080191963811010680e+01,5.005230875409986311e+02,7.922670133368629741e-02,9.650286102079949302e+00,3.565133859611401869e-03,1.000000009908750265e+00,-4.000000000000000327e-05,1.742091493504238115e-09,0.000000000000000000e+00 +8.080295587681787595e+01,5.005330874774477934e+02,7.926235259675996903e-02,9.651322340797984012e+00,3.564987874209864151e-03,1.000000009910555487e+00,-4.000000000000000327e-05,-9.292152307538449219e-10,0.000000000000000000e+00 +8.080399200426724349e+01,5.005430874139021853e+02,7.929800239998890943e-02,9.652358468257620672e+00,3.564841888808326434e-03,1.000000009909592702e+00,-4.000000000000000327e-05,1.071841386751789824e-09,0.000000000000000000e+00 +8.080502802049404920e+01,5.005530873503617499e+02,7.933365074337310474e-02,9.653394484494686623e+00,3.564695903406788716e-03,1.000000009910703147e+00,-4.000000000000000327e-05,-5.408010547021135249e-10,0.000000000000000000e+00 +8.080606392553409023e+01,5.005630872868265442e+02,7.936929762691256884e-02,9.654430389544994995e+00,3.564549918005250999e-03,1.000000009910142929e+00,-4.000000000000000327e-05,-8.165407317800996059e-10,0.000000000000000000e+00 +8.080709971942316372e+01,5.005730872232965112e+02,7.940494305060728786e-02,9.655466183444335826e+00,3.564403932603713281e-03,1.000000009909297161e+00,-4.000000000000000327e-05,2.328323373039908499e-10,0.000000000000000000e+00 +8.080813540219705260e+01,5.005830871597717078e+02,7.944058701445726178e-02,9.656501866228481390e+00,3.564257947202175564e-03,1.000000009909538301e+00,-4.000000000000000327e-05,-7.189415897604710881e-10,0.000000000000000000e+00 +8.080917097389149717e+01,5.005930870962520771e+02,7.947622951846250450e-02,9.657537437933186197e+00,3.564111961800637846e-03,1.000000009908793785e+00,-4.000000000000000327e-05,1.284283606479294100e-09,0.000000000000000000e+00 +8.081020643454223773e+01,5.006030870327376761e+02,7.951187056262300212e-02,9.658572898594183442e+00,3.563965976399100129e-03,1.000000009910123611e+00,-4.000000000000000327e-05,-3.976151442318357786e-10,0.000000000000000000e+00 +8.081124178418498616e+01,5.006130869692284477e+02,7.954751014693875466e-02,9.659608248247190332e+00,3.563819990997562411e-03,1.000000009909711940e+00,-4.000000000000000327e-05,-8.081847164697157028e-10,0.000000000000000000e+00 +8.081227702285544012e+01,5.006230869057244490e+02,7.958314827140976211e-02,9.660643486927900980e+00,3.563674005596024694e-03,1.000000009908875276e+00,-4.000000000000000327e-05,4.011325343124022238e-11,0.000000000000000000e+00 +8.081331215058926887e+01,5.006330868422256799e+02,7.961878493603602447e-02,9.661678614671991738e+00,3.563528020194486976e-03,1.000000009908916798e+00,-4.000000000000000327e-05,4.773345034269111868e-10,0.000000000000000000e+00 +8.081434716742214164e+01,5.006430867787320835e+02,7.965442014081754174e-02,9.662713631515121193e+00,3.563382034792949259e-03,1.000000009909410847e+00,-4.000000000000000327e-05,4.883279608531502779e-10,0.000000000000000000e+00 +8.081538207338969926e+01,5.006530867152437168e+02,7.969005388575431392e-02,9.663748537492928392e+00,3.563236049391411541e-03,1.000000009909916221e+00,-4.000000000000000327e-05,-1.598608503446337657e-09,0.000000000000000000e+00 +8.081641686852755413e+01,5.006630866517605227e+02,7.972568617084634102e-02,9.664783332641032843e+00,3.563090063989873824e-03,1.000000009908261989e+00,-4.000000000000000327e-05,8.388764804422032458e-10,0.000000000000000000e+00 +8.081745155287130444e+01,5.006730865882825583e+02,7.976131699609360914e-02,9.665818016995032735e+00,3.562944078588336106e-03,1.000000009909129961e+00,-4.000000000000000327e-05,1.152317728642023614e-09,0.000000000000000000e+00 +8.081848612645653418e+01,5.006830865248097666e+02,7.979694636149613218e-02,9.666852590590512051e+00,3.562798093186798389e-03,1.000000009910322119e+00,-4.000000000000000327e-05,-2.334288804976477219e-09,0.000000000000000000e+00 +8.081952058931879890e+01,5.006930864613422045e+02,7.983257426705391013e-02,9.667887053463033453e+00,3.562652107785260671e-03,1.000000009907907383e+00,-4.000000000000000327e-05,1.986987520449320059e-09,0.000000000000000000e+00 +8.082055494149365416e+01,5.007030863978798152e+02,7.986820071276692912e-02,9.668921405648136513e+00,3.562506122383722953e-03,1.000000009909962628e+00,-4.000000000000000327e-05,-2.499672733823593448e-09,0.000000000000000000e+00 +8.082158918301661288e+01,5.007130863344226555e+02,7.990382569863520301e-02,9.669955647181350145e+00,3.562360136982185236e-03,1.000000009907377363e+00,-4.000000000000000327e-05,2.458285179964364884e-09,0.000000000000000000e+00 +8.082262331392318799e+01,5.007230862709706685e+02,7.993944922465871794e-02,9.670989778098174838e+00,3.562214151580647518e-03,1.000000009909919552e+00,-4.000000000000000327e-05,-1.421358172076377045e-09,0.000000000000000000e+00 +8.082365733424886400e+01,5.007330862075239111e+02,7.997507129083748778e-02,9.672023798434102204e+00,3.562068166179109801e-03,1.000000009908449838e+00,-4.000000000000000327e-05,-8.644173330173923294e-10,0.000000000000000000e+00 +8.082469124402911120e+01,5.007430861440823264e+02,8.001069189717149865e-02,9.673057708224595430e+00,3.561922180777572083e-03,1.000000009907556109e+00,-4.000000000000000327e-05,2.457570287217732590e-09,0.000000000000000000e+00 +8.082572504329937146e+01,5.007530860806459714e+02,8.004631104366076444e-02,9.674091507505103493e+00,3.561776195376034366e-03,1.000000009910096743e+00,-4.000000000000000327e-05,-3.104404965680623898e-09,0.000000000000000000e+00 +8.082675873209508666e+01,5.007630860172147891e+02,8.008192873030527126e-02,9.675125196311059383e+00,3.561630209974496648e-03,1.000000009906887755e+00,-4.000000000000000327e-05,2.383764056774040629e-09,0.000000000000000000e+00 +8.082779231045165602e+01,5.007730859537887795e+02,8.011754495710501911e-02,9.676158774677867669e+00,3.561484224572958931e-03,1.000000009909351562e+00,-4.000000000000000327e-05,-1.040752220061493551e-09,0.000000000000000000e+00 +8.082882577840447880e+01,5.007830858903679996e+02,8.015315972406000800e-02,9.677192242640925812e+00,3.561338239171421213e-03,1.000000009908275977e+00,-4.000000000000000327e-05,-9.003339295580276935e-11,0.000000000000000000e+00 +8.082985913598891159e+01,5.007930858269523924e+02,8.018877303117023791e-02,9.678225600235602855e+00,3.561192253769883496e-03,1.000000009908182941e+00,-4.000000000000000327e-05,2.351003571078924376e-10,0.000000000000000000e+00 +8.083089238324032522e+01,5.008030857635420148e+02,8.022438487843570887e-02,9.679258847497253626e+00,3.561046268368345778e-03,1.000000009908425858e+00,-4.000000000000000327e-05,-8.038109753281059866e-11,0.000000000000000000e+00 +8.083192552019404786e+01,5.008130857001368099e+02,8.025999526585642085e-02,9.680291984461213417e+00,3.560900282966808061e-03,1.000000009908342813e+00,-4.000000000000000327e-05,-1.048934825313335089e-09,0.000000000000000000e+00 +8.083295854688539350e+01,5.008230856367368347e+02,8.029560419343237387e-02,9.681325011162797978e+00,3.560754297565270343e-03,1.000000009907259235e+00,-4.000000000000000327e-05,6.453357333737912382e-10,0.000000000000000000e+00 +8.083399146334966190e+01,5.008330855733420321e+02,8.033121166116356793e-02,9.682357927637303519e+00,3.560608312163732626e-03,1.000000009907925813e+00,-4.000000000000000327e-05,-4.944805283805430829e-12,0.000000000000000000e+00 +8.083502426962213860e+01,5.008430855099524592e+02,8.036681766905000301e-02,9.683390733920010263e+00,3.560462326762194908e-03,1.000000009907920706e+00,-4.000000000000000327e-05,3.169313243355919047e-10,0.000000000000000000e+00 +8.083605696573806654e+01,5.008530854465680591e+02,8.040242221709167914e-02,9.684423430046177117e+00,3.560316341360657191e-03,1.000000009908248000e+00,-4.000000000000000327e-05,-6.773678019521656900e-11,0.000000000000000000e+00 +8.083708955173270283e+01,5.008630853831888885e+02,8.043802530528859629e-02,9.685456016051045225e+00,3.560170355959119473e-03,1.000000009908178056e+00,-4.000000000000000327e-05,-1.172508894409458448e-09,0.000000000000000000e+00 +8.083812202764126198e+01,5.008730853198148907e+02,8.047362693364074060e-02,9.686488491969836190e+00,3.560024370557581756e-03,1.000000009906967469e+00,-4.000000000000000327e-05,1.989520072037031596e-09,0.000000000000000000e+00 +8.083915439349894427e+01,5.008830852564460656e+02,8.050922710214812594e-02,9.687520857837752075e+00,3.559878385156044038e-03,1.000000009909021381e+00,-4.000000000000000327e-05,-2.262486739795510267e-09,0.000000000000000000e+00 +8.084018664934095000e+01,5.008930851930824701e+02,8.054482581081075232e-02,9.688553113689980734e+00,3.559732399754506321e-03,1.000000009906685916e+00,-4.000000000000000327e-05,1.061662083047477713e-09,0.000000000000000000e+00 +8.084121879520242260e+01,5.009030851297240474e+02,8.058042305962860585e-02,9.689585259561683372e+00,3.559586414352968603e-03,1.000000009907781706e+00,-4.000000000000000327e-05,2.786218569446580973e-10,0.000000000000000000e+00 +8.084225083111851973e+01,5.009130850663708543e+02,8.061601884860170042e-02,9.690617295488010541e+00,3.559440428951430885e-03,1.000000009908069254e+00,-4.000000000000000327e-05,-1.291479923171557734e-09,0.000000000000000000e+00 +8.084328275712437062e+01,5.009230850030228339e+02,8.065161317773002214e-02,9.691649221504089695e+00,3.559294443549893168e-03,1.000000009906736542e+00,-4.000000000000000327e-05,-3.247335439493441863e-10,0.000000000000000000e+00 +8.084431457325509029e+01,5.009330849396800431e+02,8.068720604701357102e-02,9.692681037645028752e+00,3.559148458148355450e-03,1.000000009906401477e+00,-4.000000000000000327e-05,1.498797325053757444e-09,0.000000000000000000e+00 +8.084534627954576536e+01,5.009430848763424251e+02,8.072279745645236093e-02,9.693712743945919641e+00,3.559002472746817733e-03,1.000000009907947796e+00,-4.000000000000000327e-05,-8.411722297228119930e-10,0.000000000000000000e+00 +8.084637787603146819e+01,5.009530848130099798e+02,8.075838740604637800e-02,9.694744340441836528e+00,3.558856487345280015e-03,1.000000009907080045e+00,-4.000000000000000327e-05,9.865666797336233712e-10,0.000000000000000000e+00 +8.084740936274724277e+01,5.009630847496827641e+02,8.079397589579562222e-02,9.695775827167830485e+00,3.558710501943742298e-03,1.000000009908097676e+00,-4.000000000000000327e-05,-1.376560879482704449e-09,0.000000000000000000e+00 +8.084844073972813305e+01,5.009730846863607212e+02,8.082956292570009360e-02,9.696807204158938376e+00,3.558564516542204580e-03,1.000000009906677922e+00,-4.000000000000000327e-05,4.034953860053447902e-10,0.000000000000000000e+00 +8.084947200700915459e+01,5.009830846230439079e+02,8.086514849575979214e-02,9.697838471450173969e+00,3.558418531140666863e-03,1.000000009907094034e+00,-4.000000000000000327e-05,-3.643472788737709722e-10,0.000000000000000000e+00 +8.085050316462530873e+01,5.009930845597322673e+02,8.090073260597471783e-02,9.698869629076536825e+00,3.558272545739129145e-03,1.000000009906718335e+00,-4.000000000000000327e-05,-3.542641855387641415e-10,0.000000000000000000e+00 +8.085153421261156836e+01,5.010030844964257994e+02,8.093631525634487067e-02,9.699900677073005184e+00,3.558126560337591428e-03,1.000000009906353071e+00,-4.000000000000000327e-05,4.219314992145676296e-10,0.000000000000000000e+00 +8.085256515100289221e+01,5.010130844331245612e+02,8.097189644687025067e-02,9.700931615474539527e+00,3.557980574936053710e-03,1.000000009906788057e+00,-4.000000000000000327e-05,2.802405425879589673e-10,0.000000000000000000e+00 +8.085359597983422475e+01,5.010230843698284957e+02,8.100747617755085783e-02,9.701962444316082568e+00,3.557834589534515993e-03,1.000000009907076937e+00,-4.000000000000000327e-05,-7.938479120129741087e-10,0.000000000000000000e+00 +8.085462669914048206e+01,5.010330843065376030e+02,8.104305444838669215e-02,9.702993163632557483e+00,3.557688604132978275e-03,1.000000009906258702e+00,-4.000000000000000327e-05,5.319453793230796451e-10,0.000000000000000000e+00 +8.085565730895658021e+01,5.010430842432519398e+02,8.107863125937775362e-02,9.704023773458867907e+00,3.557542618731440558e-03,1.000000009906806930e+00,-4.000000000000000327e-05,-7.731157336359298897e-10,0.000000000000000000e+00 +8.085668780931740685e+01,5.010530841799714494e+02,8.111420661052402836e-02,9.705054273829901490e+00,3.557396633329902840e-03,1.000000009906010234e+00,-4.000000000000000327e-05,2.969527910087777901e-10,0.000000000000000000e+00 +8.085771820025782120e+01,5.010630841166961886e+02,8.114978050182553027e-02,9.706084664780524562e+00,3.557250647928365123e-03,1.000000009906316212e+00,-4.000000000000000327e-05,3.823295945464411198e-10,0.000000000000000000e+00 +8.085874848181268248e+01,5.010730840534261006e+02,8.118535293328225932e-02,9.707114946345587470e+00,3.557104662526827405e-03,1.000000009906710119e+00,-4.000000000000000327e-05,-5.293693107916111538e-10,0.000000000000000000e+00 +8.085977865401680731e+01,5.010830839901611853e+02,8.122092390489420166e-02,9.708145118559921016e+00,3.556958677125289688e-03,1.000000009906164777e+00,-4.000000000000000327e-05,8.961000665464699043e-10,0.000000000000000000e+00 +8.086080871690501226e+01,5.010930839269014996e+02,8.125649341666137115e-02,9.709175181458336468e+00,3.556812691723751970e-03,1.000000009907087817e+00,-4.000000000000000327e-05,-2.051310273900066204e-09,0.000000000000000000e+00 +8.086183867051209972e+01,5.011030838636469866e+02,8.129206146858375392e-02,9.710205135075629101e+00,3.556666706322214253e-03,1.000000009904975062e+00,-4.000000000000000327e-05,2.338073390112607382e-09,0.000000000000000000e+00 +8.086286851487284366e+01,5.011130838003976464e+02,8.132762806066134997e-02,9.711234979446571103e+00,3.556520720920676535e-03,1.000000009907382914e+00,-4.000000000000000327e-05,-2.697134229799173984e-09,0.000000000000000000e+00 +8.086389825002198961e+01,5.011230837371535358e+02,8.136319319289417318e-02,9.712264714605923999e+00,3.556374735519138817e-03,1.000000009904605580e+00,-4.000000000000000327e-05,1.255331236820669059e-09,0.000000000000000000e+00 +8.086492787599428311e+01,5.011330836739145980e+02,8.139875686528220966e-02,9.713294340588420894e+00,3.556228750117601100e-03,1.000000009905898102e+00,-4.000000000000000327e-05,7.820500975469182770e-10,0.000000000000000000e+00 +8.086595739282445550e+01,5.011430836106808329e+02,8.143431907782545942e-02,9.714323857428786013e+00,3.556082764716063382e-03,1.000000009906703236e+00,-4.000000000000000327e-05,-7.817015847804569886e-10,0.000000000000000000e+00 +8.086698680054719546e+01,5.011530835474522974e+02,8.146987983052392246e-02,9.715353265161720486e+00,3.555936779314525665e-03,1.000000009905898546e+00,-4.000000000000000327e-05,-9.491863820867767000e-11,0.000000000000000000e+00 +8.086801609919719169e+01,5.011630834842289346e+02,8.150543912337761265e-02,9.716382563821905904e+00,3.555790793912987947e-03,1.000000009905800846e+00,-4.000000000000000327e-05,-5.240495425945159768e-10,0.000000000000000000e+00 +8.086904528880910448e+01,5.011730834210107446e+02,8.154099695638651613e-02,9.717411753444007871e+00,3.555644808511450230e-03,1.000000009905261500e+00,-4.000000000000000327e-05,-4.043527651810056955e-10,0.000000000000000000e+00 +8.087007436941757987e+01,5.011830833577977842e+02,8.157655332955063288e-02,9.718440834062672451e+00,3.555498823109912512e-03,1.000000009904845388e+00,-4.000000000000000327e-05,1.929187055805143535e-09,0.000000000000000000e+00 +8.087110334105724974e+01,5.011930832945899965e+02,8.161210824286996290e-02,9.719469805712527943e+00,3.555352837708374795e-03,1.000000009906830467e+00,-4.000000000000000327e-05,-1.925506634283084533e-09,0.000000000000000000e+00 +8.087213220376271750e+01,5.012030832313873816e+02,8.164766169634449233e-02,9.720498668428186662e+00,3.555206852306837077e-03,1.000000009904849385e+00,-4.000000000000000327e-05,-2.367747562296456355e-10,0.000000000000000000e+00 +8.087316095756857237e+01,5.012130831681899963e+02,8.168321368997423504e-02,9.721527422244236050e+00,3.555060866905299360e-03,1.000000009904605802e+00,-4.000000000000000327e-05,1.951170033757457928e-09,0.000000000000000000e+00 +8.087418960250940358e+01,5.012230831049977837e+02,8.171876422375919102e-02,9.722556067195251117e+00,3.554914881503761642e-03,1.000000009906612863e+00,-4.000000000000000327e-05,-2.091701161944898822e-09,0.000000000000000000e+00 +8.087521813861975772e+01,5.012330830418107439e+02,8.175431329769936029e-02,9.723584603315789110e+00,3.554768896102223925e-03,1.000000009904461473e+00,-4.000000000000000327e-05,1.053841823778975242e-09,0.000000000000000000e+00 +8.087624656593416717e+01,5.012430829786288768e+02,8.178986091179472895e-02,9.724613030640382405e+00,3.554622910700686207e-03,1.000000009905545273e+00,-4.000000000000000327e-05,-3.787408443699120921e-10,0.000000000000000000e+00 +8.087727488448715008e+01,5.012530829154522394e+02,8.182540706604531089e-02,9.725641349203552721e+00,3.554476925299148490e-03,1.000000009905155807e+00,-4.000000000000000327e-05,3.148589186516566036e-10,0.000000000000000000e+00 +8.087830309431321041e+01,5.012630828522807747e+02,8.186095176045110611e-02,9.726669559039798685e+00,3.554330939897610772e-03,1.000000009905479548e+00,-4.000000000000000327e-05,-1.918077970982256207e-09,0.000000000000000000e+00 +8.087933119544683791e+01,5.012730827891144827e+02,8.189649499501210073e-02,9.727697660183602935e+00,3.554184954496073055e-03,1.000000009903507570e+00,-4.000000000000000327e-05,1.312837535984899623e-09,0.000000000000000000e+00 +8.088035918792247969e+01,5.012830827259534203e+02,8.193203676972829475e-02,9.728725652669426793e+00,3.554038969094535337e-03,1.000000009904857157e+00,-4.000000000000000327e-05,-8.986477942919360777e-11,0.000000000000000000e+00 +8.088138707177459708e+01,5.012930826627975307e+02,8.196757708459970204e-02,9.729753536531719149e+00,3.553892983692997620e-03,1.000000009904764786e+00,-4.000000000000000327e-05,5.846148691780424043e-10,0.000000000000000000e+00 +8.088241484703760875e+01,5.013030825996468138e+02,8.200311593962630874e-02,9.730781311804905798e+00,3.553746998291459902e-03,1.000000009905365639e+00,-4.000000000000000327e-05,-3.824381460825128193e-11,0.000000000000000000e+00 +8.088344251374591920e+01,5.013130825365012697e+02,8.203865333480812871e-02,9.731808978523396547e+00,3.553601012889922185e-03,1.000000009905326337e+00,-4.000000000000000327e-05,-1.973329934831805715e-09,0.000000000000000000e+00 +8.088447007193393290e+01,5.013230824733609552e+02,8.207418927014514809e-02,9.732836536721581666e+00,3.553455027488384467e-03,1.000000009903298626e+00,-4.000000000000000327e-05,1.497442711227843974e-09,0.000000000000000000e+00 +8.088549752163601170e+01,5.013330824102258134e+02,8.210972374563736687e-02,9.733863986433831883e+00,3.553309042086846749e-03,1.000000009904837173e+00,-4.000000000000000327e-05,2.667108347344926006e-10,0.000000000000000000e+00 +8.088652486288650323e+01,5.013430823470958444e+02,8.214525676128478504e-02,9.734891327694505492e+00,3.553163056685309032e-03,1.000000009905111176e+00,-4.000000000000000327e-05,-6.318298628926974160e-10,0.000000000000000000e+00 +8.088755209571975513e+01,5.013530822839710481e+02,8.218078831708740262e-02,9.735918560537937694e+00,3.553017071283771314e-03,1.000000009904462139e+00,-4.000000000000000327e-05,-1.209964044142771384e-09,0.000000000000000000e+00 +8.088857922017008661e+01,5.013630822208514815e+02,8.221631841304521959e-02,9.736945684998445927e+00,3.552871085882233597e-03,1.000000009903219356e+00,-4.000000000000000327e-05,1.887890060312678449e-09,0.000000000000000000e+00 +8.088960623627180269e+01,5.013730821577370875e+02,8.225184704915823597e-02,9.737972701110329865e+00,3.552725100480695879e-03,1.000000009905158249e+00,-4.000000000000000327e-05,-1.454987648269932138e-09,0.000000000000000000e+00 +8.089063314405917993e+01,5.013830820946278664e+02,8.228737422542645175e-02,9.738999608907874972e+00,3.552579115079158162e-03,1.000000009903664111e+00,-4.000000000000000327e-05,5.371630924184059815e-10,0.000000000000000000e+00 +8.089165994356648071e+01,5.013930820315238179e+02,8.232289994184986692e-02,9.740026408425341842e+00,3.552433129677620444e-03,1.000000009904215670e+00,-4.000000000000000327e-05,-5.694442591549259235e-10,0.000000000000000000e+00 +8.089268663482795318e+01,5.014030819684249991e+02,8.235842419842848150e-02,9.741053099696978634e+00,3.552287144276082727e-03,1.000000009903631026e+00,-4.000000000000000327e-05,2.664752289677591355e-10,0.000000000000000000e+00 +8.089371321787781710e+01,5.014130819053313530e+02,8.239394699516228160e-02,9.742079682757012193e+00,3.552141158874545009e-03,1.000000009903904585e+00,-4.000000000000000327e-05,-3.381044454220208289e-10,0.000000000000000000e+00 +8.089473969275029219e+01,5.014230818422428797e+02,8.242946833205128110e-02,9.743106157639653375e+00,3.551995173473007292e-03,1.000000009903557530e+00,-4.000000000000000327e-05,9.763442962868518742e-10,0.000000000000000000e+00 +8.089576605947956978e+01,5.014330817791595791e+02,8.246498820909548000e-02,9.744132524379093496e+00,3.551849188071469574e-03,1.000000009904559617e+00,-4.000000000000000327e-05,-8.626401010114348477e-10,0.000000000000000000e+00 +8.089679231809981275e+01,5.014430817160815081e+02,8.250050662629486442e-02,9.745158783009507886e+00,3.551703202669931857e-03,1.000000009903674325e+00,-4.000000000000000327e-05,-8.075525265869627002e-10,0.000000000000000000e+00 +8.089781846864519821e+01,5.014530816530086099e+02,8.253602358364944824e-02,9.746184933565050557e+00,3.551557217268394139e-03,1.000000009902845655e+00,-4.000000000000000327e-05,1.129437413999756394e-09,0.000000000000000000e+00 +8.089884451114984643e+01,5.014630815899408844e+02,8.257153908115921759e-02,9.747210976079859535e+00,3.551411231866856422e-03,1.000000009904004505e+00,-4.000000000000000327e-05,-1.255303053976657030e-10,0.000000000000000000e+00 +8.089987044564787766e+01,5.014730815268783317e+02,8.260705311882418633e-02,9.748236910588056858e+00,3.551265246465318704e-03,1.000000009903875720e+00,-4.000000000000000327e-05,-1.211278494209783395e-09,0.000000000000000000e+00 +8.090089627217339796e+01,5.014830814638209517e+02,8.264256569664434060e-02,9.749262737123743250e+00,3.551119261063780987e-03,1.000000009902633158e+00,-4.000000000000000327e-05,1.236517305313063331e-09,0.000000000000000000e+00 +8.090192199076049917e+01,5.014930814007688014e+02,8.267807681461968039e-02,9.750288455721001668e+00,3.550973275662243269e-03,1.000000009903901477e+00,-4.000000000000000327e-05,-1.236214399339783696e-09,0.000000000000000000e+00 +8.090294760144324471e+01,5.015030813377218237e+02,8.271358647275021958e-02,9.751314066413900861e+00,3.550827290260705552e-03,1.000000009902633602e+00,-4.000000000000000327e-05,1.489675955411221097e-09,0.000000000000000000e+00 +8.090397310425566957e+01,5.015130812746800189e+02,8.274909467103594429e-02,9.752339569236486483e+00,3.550681304859167834e-03,1.000000009904161269e+00,-4.000000000000000327e-05,-7.317070372814280034e-10,0.000000000000000000e+00 +8.090499849923182296e+01,5.015230812116433867e+02,8.278460140947685453e-02,9.753364964222791755e+00,3.550535319457630117e-03,1.000000009903410980e+00,-4.000000000000000327e-05,-1.157340498299110704e-09,0.000000000000000000e+00 +8.090602378640569725e+01,5.015330811486119273e+02,8.282010668807295029e-02,9.754390251406826806e+00,3.550389334056092399e-03,1.000000009902224374e+00,-4.000000000000000327e-05,2.016461958311789487e-10,0.000000000000000000e+00 +8.090704896581129901e+01,5.015430810855856976e+02,8.285561050682423156e-02,9.755415430822585776e+00,3.550243348654554681e-03,1.000000009902431097e+00,-4.000000000000000327e-05,1.644098260199365461e-09,0.000000000000000000e+00 +8.090807403748260640e+01,5.015530810225646405e+02,8.289111286573069837e-02,9.756440502504046819e+00,3.550097363253016964e-03,1.000000009904116416e+00,-4.000000000000000327e-05,-1.916149822026553489e-09,0.000000000000000000e+00 +8.090909900145358336e+01,5.015630809595487563e+02,8.292661376479235069e-02,9.757465466485170325e+00,3.549951377851479246e-03,1.000000009902152431e+00,-4.000000000000000327e-05,-3.468714695885112451e-10,0.000000000000000000e+00 +8.091012385775816540e+01,5.015730808965380447e+02,8.296211320400918854e-02,9.758490322799893590e+00,3.549805392449941529e-03,1.000000009901796938e+00,-4.000000000000000327e-05,1.268023139134321636e-09,0.000000000000000000e+00 +8.091114860643025963e+01,5.015830808335325059e+02,8.299761118338121191e-02,9.759515071482141479e+00,3.549659407048403811e-03,1.000000009903096343e+00,-4.000000000000000327e-05,-4.678655915875116508e-10,0.000000000000000000e+00 +8.091217324750378737e+01,5.015930807705321399e+02,8.303310770290840692e-02,9.760539712565821091e+00,3.549513421646866094e-03,1.000000009902616949e+00,-4.000000000000000327e-05,-4.919714668433086326e-10,0.000000000000000000e+00 +8.091319778101264149e+01,5.016030807075370035e+02,8.306860276259078746e-02,9.761564246084818208e+00,3.549367436245328376e-03,1.000000009902112907e+00,-4.000000000000000327e-05,1.183673211621476388e-09,0.000000000000000000e+00 +8.091422220699068646e+01,5.016130806445470398e+02,8.310409636242835352e-02,9.762588672073002627e+00,3.549221450843790659e-03,1.000000009903325493e+00,-4.000000000000000327e-05,-5.304435664169079042e-10,0.000000000000000000e+00 +8.091524652547177254e+01,5.016230805815622489e+02,8.313958850242109122e-02,9.763612990564228156e+00,3.549075465442252941e-03,1.000000009902782150e+00,-4.000000000000000327e-05,-5.697392544235578174e-10,0.000000000000000000e+00 +8.091627073648973578e+01,5.016330805185826307e+02,8.317507918256901445e-02,9.764637201592327287e+00,3.548929480040715224e-03,1.000000009902198617e+00,-4.000000000000000327e-05,-6.391809408488976285e-10,0.000000000000000000e+00 +8.091729484007838380e+01,5.016430804556081853e+02,8.321056840287210932e-02,9.765661305191116526e+00,3.548783494639177506e-03,1.000000009901544029e+00,-4.000000000000000327e-05,9.441267617216668094e-10,0.000000000000000000e+00 +8.091831883627152422e+01,5.016530803926389126e+02,8.324605616333038971e-02,9.766685301394394614e+00,3.548637509237639789e-03,1.000000009902510811e+00,-4.000000000000000327e-05,-9.160334427236165647e-10,0.000000000000000000e+00 +8.091934272510293624e+01,5.016630803296748127e+02,8.328154246394384175e-02,9.767709190235944305e+00,3.548491523836102071e-03,1.000000009901572895e+00,-4.000000000000000327e-05,5.459038561600209842e-10,0.000000000000000000e+00 +8.092036650660638486e+01,5.016730802667159423e+02,8.331702730471246543e-02,9.768732971749527039e+00,3.548345538434564354e-03,1.000000009902131781e+00,-4.000000000000000327e-05,2.336114726236680270e-10,0.000000000000000000e+00 +8.092139018081560664e+01,5.016830802037622448e+02,8.335251068563627463e-02,9.769756645968890041e+00,3.548199553033026636e-03,1.000000009902370923e+00,-4.000000000000000327e-05,-1.865833641189826974e-09,0.000000000000000000e+00 +8.092241374776433815e+01,5.016930801408137199e+02,8.338799260671525548e-02,9.770780212927760999e+00,3.548053567631488919e-03,1.000000009900461118e+00,-4.000000000000000327e-05,2.713021064752166652e-09,0.000000000000000000e+00 +8.092343720748628755e+01,5.017030800778703679e+02,8.342347306794940798e-02,9.771803672659848061e+00,3.547907582229951201e-03,1.000000009903237785e+00,-4.000000000000000327e-05,-3.000149670514933377e-09,0.000000000000000000e+00 +8.092446056001514876e+01,5.017130800149321885e+02,8.345895206933873212e-02,9.772827025198848716e+00,3.547761596828413484e-03,1.000000009900167575e+00,-4.000000000000000327e-05,1.334769162575313632e-09,0.000000000000000000e+00 +8.092548380538460151e+01,5.017230799519991820e+02,8.349442961088322790e-02,9.773850270578432031e+00,3.547615611426875766e-03,1.000000009901533371e+00,-4.000000000000000327e-05,4.394717211902171486e-10,0.000000000000000000e+00 +8.092650694362829711e+01,5.017330798890713481e+02,8.352990569258289533e-02,9.774873408832259969e+00,3.547469626025338049e-03,1.000000009901983011e+00,-4.000000000000000327e-05,-6.101157168864608644e-10,0.000000000000000000e+00 +8.092752997477987265e+01,5.017430798261486871e+02,8.356538031443773440e-02,9.775896439993971399e+00,3.547323640623800331e-03,1.000000009901358844e+00,-4.000000000000000327e-05,-1.282874872118630373e-10,0.000000000000000000e+00 +8.092855289887296522e+01,5.017530797632312556e+02,8.360085347644774512e-02,9.776919364097187426e+00,3.547177655222262613e-03,1.000000009901227616e+00,-4.000000000000000327e-05,1.751926143450972584e-10,0.000000000000000000e+00 +8.092957571594116928e+01,5.017630797003189969e+02,8.363632517861292748e-02,9.777942181175513170e+00,3.547031669820724896e-03,1.000000009901406806e+00,-4.000000000000000327e-05,2.883273001819359910e-10,0.000000000000000000e+00 +8.093059842601806508e+01,5.017730796374119109e+02,8.367179542093328148e-02,9.778964891262535986e+00,3.546885684419187178e-03,1.000000009901701681e+00,-4.000000000000000327e-05,-1.500414179536593776e-09,0.000000000000000000e+00 +8.093162102913723288e+01,5.017830795745099977e+02,8.370726420340879326e-02,9.779987494391825464e+00,3.546739699017649461e-03,1.000000009900167353e+00,-4.000000000000000327e-05,1.591778005713797273e-09,0.000000000000000000e+00 +8.093264352533221029e+01,5.017930795116132572e+02,8.374273152603947667e-02,9.781009990596931658e+00,3.546593713616111743e-03,1.000000009901794940e+00,-4.000000000000000327e-05,-6.404698651934016311e-10,0.000000000000000000e+00 +8.093366591463654913e+01,5.018030794487216895e+02,8.377819738882533174e-02,9.782032379911392184e+00,3.546447728214574026e-03,1.000000009901140130e+00,-4.000000000000000327e-05,2.858414529952256141e-10,0.000000000000000000e+00 +8.093468819708375861e+01,5.018130793858352945e+02,8.381366179176634457e-02,9.783054662368721566e+00,3.546301742813036308e-03,1.000000009901432341e+00,-4.000000000000000327e-05,-7.400939246935464217e-10,0.000000000000000000e+00 +8.093571037270733370e+01,5.018230793229540723e+02,8.384912473486252904e-02,9.784076838002420118e+00,3.546155757411498591e-03,1.000000009900675835e+00,-4.000000000000000327e-05,-3.306547246548704156e-10,0.000000000000000000e+00 +8.093673244154076940e+01,5.018330792600780228e+02,8.388458621811387128e-02,9.785098906845968614e+00,3.546009772009960873e-03,1.000000009900337883e+00,-4.000000000000000327e-05,-1.977182863039901637e-10,0.000000000000000000e+00 +8.093775440361751805e+01,5.018430791972071461e+02,8.392004624152037129e-02,9.786120868932831840e+00,3.545863786608423156e-03,1.000000009900135822e+00,-4.000000000000000327e-05,1.347232312096292664e-09,0.000000000000000000e+00 +8.093877625897103201e+01,5.018530791343414421e+02,8.395550480508204294e-02,9.787142724296456819e+00,3.545717801206885438e-03,1.000000009901512499e+00,-4.000000000000000327e-05,-2.513502578276601424e-09,0.000000000000000000e+00 +8.093979800763473520e+01,5.018630790714809109e+02,8.399096190879887236e-02,9.788164472970274588e+00,3.545571815805347721e-03,1.000000009898944331e+00,-4.000000000000000327e-05,1.820012791512517146e-09,0.000000000000000000e+00 +8.094081964964203735e+01,5.018730790086255524e+02,8.402641755267085955e-02,9.789186114987693088e+00,3.545425830403810003e-03,1.000000009900803732e+00,-4.000000000000000327e-05,-9.798750923187721088e-10,0.000000000000000000e+00 +8.094184118502634817e+01,5.018830789457754236e+02,8.406187173669800450e-02,9.790207650382111382e+00,3.545279845002272286e-03,1.000000009899802755e+00,-4.000000000000000327e-05,9.888901831087309195e-10,0.000000000000000000e+00 +8.094286261382103476e+01,5.018930788829304674e+02,8.409732446088032110e-02,9.791229079186903661e+00,3.545133859600734568e-03,1.000000009900812836e+00,-4.000000000000000327e-05,-7.981082894502638096e-10,0.000000000000000000e+00 +8.094388393605944998e+01,5.019030788200906841e+02,8.413277572521779546e-02,9.792250401435431684e+00,3.544987874199196851e-03,1.000000009899997711e+00,-4.000000000000000327e-05,4.579110278829072310e-10,0.000000000000000000e+00 +8.094490515177494672e+01,5.019130787572560735e+02,8.416822552971042759e-02,9.793271617161035891e+00,3.544841888797659133e-03,1.000000009900465336e+00,-4.000000000000000327e-05,-3.644534281113530964e-10,0.000000000000000000e+00 +8.094592626100084942e+01,5.019230786944266356e+02,8.420367387435821749e-02,9.794292726397042514e+00,3.544695903396121416e-03,1.000000009900093190e+00,-4.000000000000000327e-05,1.296162835935951671e-10,0.000000000000000000e+00 +8.094694726377045413e+01,5.019330786316023705e+02,8.423912075916116515e-02,9.795313729176758244e+00,3.544549917994583698e-03,1.000000009900225528e+00,-4.000000000000000327e-05,-1.479867664262860912e-09,0.000000000000000000e+00 +8.094796816011705687e+01,5.019430785687832781e+02,8.427456618411925671e-02,9.796334625533473783e+00,3.544403932593045981e-03,1.000000009898714737e+00,-4.000000000000000327e-05,1.612275474115556718e-09,0.000000000000000000e+00 +8.094898895007393946e+01,5.019530785059693585e+02,8.431001014923250603e-02,9.797355415500460296e+00,3.544257947191508263e-03,1.000000009900360531e+00,-4.000000000000000327e-05,-8.334148614959572317e-10,0.000000000000000000e+00 +8.095000963367435531e+01,5.019630784431606116e+02,8.434545265450091311e-02,9.798376099110976511e+00,3.544111961789970545e-03,1.000000009899509879e+00,-4.000000000000000327e-05,-3.054649875966888683e-10,0.000000000000000000e+00 +8.095103021095152940e+01,5.019730783803570375e+02,8.438089369992447797e-02,9.799396676398258066e+00,3.543965976388432828e-03,1.000000009899198128e+00,-4.000000000000000327e-05,1.480266922138925311e-09,0.000000000000000000e+00 +8.095205068193870090e+01,5.019830783175586362e+02,8.441633328550318671e-02,9.800417147395526385e+00,3.543819990986895110e-03,1.000000009900708697e+00,-4.000000000000000327e-05,-2.312790702119641685e-09,0.000000000000000000e+00 +8.095307104666905218e+01,5.019930782547654076e+02,8.445177141123705322e-02,9.801437512135986907e+00,3.543674005585357393e-03,1.000000009898348807e+00,-4.000000000000000327e-05,1.952844526007440479e-09,0.000000000000000000e+00 +8.095409130517579399e+01,5.020030781919773517e+02,8.448720807712606362e-02,9.802457770652821978e+00,3.543528020183819675e-03,1.000000009900341214e+00,-4.000000000000000327e-05,-1.092426938929114543e-09,0.000000000000000000e+00 +8.095511145749208026e+01,5.020130781291944686e+02,8.452264328317023179e-02,9.803477922979205061e+00,3.543382034782281958e-03,1.000000009899226772e+00,-4.000000000000000327e-05,4.854284922527179779e-10,0.000000000000000000e+00 +8.095613150365106492e+01,5.020230780664167582e+02,8.455807702936954384e-02,9.804497969148284753e+00,3.543236049380744240e-03,1.000000009899721931e+00,-4.000000000000000327e-05,-1.860494861379652054e-09,0.000000000000000000e+00 +8.095715144368587346e+01,5.020330780036442206e+02,8.459350931572401366e-02,9.805517909193197212e+00,3.543090063979206523e-03,1.000000009897824338e+00,-4.000000000000000327e-05,2.103235430324230376e-09,0.000000000000000000e+00 +8.095817127762964560e+01,5.020430779408768558e+02,8.462894014223362738e-02,9.806537743147057284e+00,3.542944078577668805e-03,1.000000009899969289e+00,-4.000000000000000327e-05,-1.298872068519689571e-09,0.000000000000000000e+00 +8.095919100551546421e+01,5.020530778781146637e+02,8.466436950889838498e-02,9.807557471042969155e+00,3.542798093176131088e-03,1.000000009898644793e+00,-4.000000000000000327e-05,-1.219520525404874102e-10,0.000000000000000000e+00 +8.096021062737641216e+01,5.020630778153576443e+02,8.469979741571828646e-02,9.808577092914012141e+00,3.542652107774593370e-03,1.000000009898520448e+00,-4.000000000000000327e-05,4.976596614205356202e-10,0.000000000000000000e+00 +8.096123014324555811e+01,5.020730777526057977e+02,8.473522386269333184e-02,9.809596608793253125e+00,3.542506122373055653e-03,1.000000009899027820e+00,-4.000000000000000327e-05,-1.162270446653419456e-09,0.000000000000000000e+00 +8.096224955315595651e+01,5.020830776898591239e+02,8.477064884982353499e-02,9.810616018713741227e+00,3.542360136971517935e-03,1.000000009897842990e+00,-4.000000000000000327e-05,1.723981294878841362e-09,0.000000000000000000e+00 +8.096326885714063337e+01,5.020930776271176228e+02,8.480607237710888202e-02,9.811635322708506024e+00,3.542214151569980218e-03,1.000000009899600251e+00,-4.000000000000000327e-05,-1.112839447889758328e-09,0.000000000000000000e+00 +8.096428805523260053e+01,5.021030775643812945e+02,8.484149444454937294e-02,9.812654520810564662e+00,3.542068166168442500e-03,1.000000009898466047e+00,-4.000000000000000327e-05,5.739082988357462989e-10,0.000000000000000000e+00 +8.096530714746485557e+01,5.021130775016501389e+02,8.487691505214500776e-02,9.813673613052911193e+00,3.541922180766904783e-03,1.000000009899050912e+00,-4.000000000000000327e-05,-1.779431240671371289e-09,0.000000000000000000e+00 +8.096632613387038191e+01,5.021230774389241560e+02,8.491233419989577258e-02,9.814692599468527234e+00,3.541776195365367065e-03,1.000000009897237696e+00,-4.000000000000000327e-05,2.080795201469542824e-09,0.000000000000000000e+00 +8.096734501448214871e+01,5.021330773762033459e+02,8.494775188780168129e-02,9.815711480090373087e+00,3.541630209963829348e-03,1.000000009899357778e+00,-4.000000000000000327e-05,-1.546591491823818636e-09,0.000000000000000000e+00 +8.096836378933308254e+01,5.021430773134877086e+02,8.498316811586273389e-02,9.816730254951398393e+00,3.541484224562291630e-03,1.000000009897782149e+00,-4.000000000000000327e-05,-6.953408851660949849e-10,0.000000000000000000e+00 +8.096938245845612414e+01,5.021530772507772440e+02,8.501858288407893038e-02,9.817748924084527928e+00,3.541338239160753912e-03,1.000000009897073827e+00,-4.000000000000000327e-05,1.202039969059367212e-09,0.000000000000000000e+00 +8.097040102188418587e+01,5.021630771880719522e+02,8.505399619245025689e-02,9.818767487522674031e+00,3.541192253759216195e-03,1.000000009898298181e+00,-4.000000000000000327e-05,7.087844334105189077e-10,0.000000000000000000e+00 +8.097141947965016584e+01,5.021730771253718331e+02,8.508940804097672728e-02,9.819785945298733054e+00,3.541046268357678477e-03,1.000000009899020048e+00,-4.000000000000000327e-05,-2.189588298733055391e-09,0.000000000000000000e+00 +8.097243783178693377e+01,5.021830770626768299e+02,8.512481842965832768e-02,9.820804297445581810e+00,3.540900282956140760e-03,1.000000009896790276e+00,-4.000000000000000327e-05,1.061107506558527202e-09,0.000000000000000000e+00 +8.097345607832734515e+01,5.021930769999869995e+02,8.516022735849507197e-02,9.821822543996077570e+00,3.540754297554603042e-03,1.000000009897870745e+00,-4.000000000000000327e-05,1.703269393718217876e-10,0.000000000000000000e+00 +8.097447421930425548e+01,5.022030769373023418e+02,8.519563482748694627e-02,9.822840684983066950e+00,3.540608312153065325e-03,1.000000009898044162e+00,-4.000000000000000327e-05,2.660952710549078431e-10,0.000000000000000000e+00 +8.097549225475049184e+01,5.022130768746228568e+02,8.523104083663396446e-02,9.823858720439375247e+00,3.540462326751527607e-03,1.000000009898315056e+00,-4.000000000000000327e-05,-3.782434592479039525e-10,0.000000000000000000e+00 +8.097651018469885287e+01,5.022230768119485447e+02,8.526644538593611267e-02,9.824876650397811773e+00,3.540316341349989890e-03,1.000000009897930031e+00,-4.000000000000000327e-05,-1.773827130610796678e-09,0.000000000000000000e+00 +8.097752800918213723e+01,5.022330767492794052e+02,8.530184847539339088e-02,9.825894474891168073e+00,3.540170355948452172e-03,1.000000009896124586e+00,-4.000000000000000327e-05,1.211109884160974133e-09,0.000000000000000000e+00 +8.097854572823311514e+01,5.022430766866154386e+02,8.533725010500581298e-02,9.826912193952217933e+00,3.540024370546914455e-03,1.000000009897357156e+00,-4.000000000000000327e-05,-8.728051342956371014e-12,0.000000000000000000e+00 +8.097956334188454264e+01,5.022530766239566447e+02,8.537265027477336510e-02,9.827929807613722701e+00,3.539878385145376737e-03,1.000000009897348274e+00,-4.000000000000000327e-05,-3.013671770871651209e-10,0.000000000000000000e+00 +8.098058085016917573e+01,5.022630765613030235e+02,8.540804898469604722e-02,9.828947315908422411e+00,3.539732399743839020e-03,1.000000009897041631e+00,-4.000000000000000327e-05,3.227865326189362057e-10,0.000000000000000000e+00 +8.098159825311972781e+01,5.022730764986545751e+02,8.544344623477385936e-02,9.829964718869041107e+00,3.539586414342301302e-03,1.000000009897370035e+00,-4.000000000000000327e-05,1.353268192105528975e-10,0.000000000000000000e+00 +8.098261555076889806e+01,5.022830764360112994e+02,8.547884202500680151e-02,9.830982016528286849e+00,3.539440428940763585e-03,1.000000009897507702e+00,-4.000000000000000327e-05,-8.762226902790835928e-10,0.000000000000000000e+00 +8.098363274314939986e+01,5.022930763733731965e+02,8.551423635539487367e-02,9.831999208918849931e+00,3.539294443539225867e-03,1.000000009896616415e+00,-4.000000000000000327e-05,7.106128446794558771e-10,0.000000000000000000e+00 +8.098464983029388975e+01,5.023030763107402095e+02,8.554962922593807584e-02,9.833016296073402884e+00,3.539148458137688150e-03,1.000000009897339170e+00,-4.000000000000000327e-05,-2.670259331449325437e-10,0.000000000000000000e+00 +8.098566681223502428e+01,5.023130762481123952e+02,8.558502063663640802e-02,9.834033278024604030e+00,3.539002472736150432e-03,1.000000009897067610e+00,-4.000000000000000327e-05,-3.869328628316370348e-10,0.000000000000000000e+00 +8.098668368900544579e+01,5.023230761854897537e+02,8.562041058748985634e-02,9.835050154805092149e+00,3.538856487334612715e-03,1.000000009896674147e+00,-4.000000000000000327e-05,3.395839829494633072e-10,0.000000000000000000e+00 +8.098770046063778238e+01,5.023330761228722849e+02,8.565579907849843466e-02,9.836066926447490033e+00,3.538710501933074997e-03,1.000000009897019426e+00,-4.000000000000000327e-05,-1.536039266751947377e-09,0.000000000000000000e+00 +8.098871712716463378e+01,5.023430760602599889e+02,8.569118610966214300e-02,9.837083592984404490e+00,3.538564516531537280e-03,1.000000009895457787e+00,-4.000000000000000327e-05,8.488078427312782962e-10,0.000000000000000000e+00 +8.098973368861859967e+01,5.023530759976528657e+02,8.572657168098096747e-02,9.838100154448422785e+00,3.538418531129999562e-03,1.000000009896320652e+00,-4.000000000000000327e-05,6.079455323566564833e-10,0.000000000000000000e+00 +8.099075014503223713e+01,5.023630759350509152e+02,8.576195579245492195e-02,9.839116610872119750e+00,3.538272545728461844e-03,1.000000009896938602e+00,-4.000000000000000327e-05,-5.529533307261877378e-10,0.000000000000000000e+00 +8.099176649643810322e+01,5.023730758724541374e+02,8.579733844408399257e-02,9.840132962288050678e+00,3.538126560326924127e-03,1.000000009896376607e+00,-4.000000000000000327e-05,-9.257626523421095162e-10,0.000000000000000000e+00 +8.099278274286875501e+01,5.023830758098625324e+02,8.583271963586819320e-02,9.841149208728753095e+00,3.537980574925386409e-03,1.000000009895435804e+00,-4.000000000000000327e-05,1.198786504709968553e-09,0.000000000000000000e+00 +8.099379888435669272e+01,5.023930757472760433e+02,8.586809936780750996e-02,9.842165350226748544e+00,3.537834589523848692e-03,1.000000009896653941e+00,-4.000000000000000327e-05,-1.073249800919463910e-09,0.000000000000000000e+00 +8.099481492093443080e+01,5.024030756846947270e+02,8.590347763990195673e-02,9.843181386814544354e+00,3.537688604122310974e-03,1.000000009895563480e+00,-4.000000000000000327e-05,8.502082503516157262e-10,0.000000000000000000e+00 +8.099583085263445525e+01,5.024130756221185834e+02,8.593885445215151964e-02,9.844197318524626539e+00,3.537542618720773257e-03,1.000000009896427233e+00,-4.000000000000000327e-05,7.322600529726109495e-11,0.000000000000000000e+00 +8.099684667948923789e+01,5.024230755595476126e+02,8.597422980455619868e-02,9.845213145389468679e+00,3.537396633319235539e-03,1.000000009896501618e+00,-4.000000000000000327e-05,-1.695520904912777891e-09,0.000000000000000000e+00 +8.099786240153123629e+01,5.024330754969818145e+02,8.600960369711599385e-02,9.846228867441524812e+00,3.537250647917697822e-03,1.000000009894779440e+00,-4.000000000000000327e-05,6.987421188396483475e-10,0.000000000000000000e+00 +8.099887801879289384e+01,5.024430754344211891e+02,8.604497612983091903e-02,9.847244484713231216e+00,3.537104662516160104e-03,1.000000009895489095e+00,-4.000000000000000327e-05,3.561853315758390558e-10,0.000000000000000000e+00 +8.099989353130662550e+01,5.024530753718656797e+02,8.608034710270096035e-02,9.848259997237011731e+00,3.536958677114622387e-03,1.000000009895850805e+00,-4.000000000000000327e-05,-1.013122665032263863e-09,0.000000000000000000e+00 +8.100090893910483203e+01,5.024630753093153430e+02,8.611571661572611780e-02,9.849275405045270659e+00,3.536812691713084669e-03,1.000000009894822073e+00,-4.000000000000000327e-05,1.746958398729550710e-09,0.000000000000000000e+00 +8.100192424221991416e+01,5.024730752467701791e+02,8.615108466890639138e-02,9.850290708170394538e+00,3.536666706311546952e-03,1.000000009896595765e+00,-4.000000000000000327e-05,-1.712799380897020142e-09,0.000000000000000000e+00 +8.100293944068423002e+01,5.024830751842301879e+02,8.618645126224176722e-02,9.851305906644757471e+00,3.536520720910009234e-03,1.000000009894856934e+00,-4.000000000000000327e-05,6.586349706718090463e-10,0.000000000000000000e+00 +8.100395453453013772e+01,5.024930751216953695e+02,8.622181639573225920e-02,9.852321000500710468e+00,3.536374735508471517e-03,1.000000009895525510e+00,-4.000000000000000327e-05,-1.491980521870824767e-09,0.000000000000000000e+00 +8.100496952378998117e+01,5.025030750591657238e+02,8.625718006937786730e-02,9.853335989770593883e+00,3.536228750106933799e-03,1.000000009894011166e+00,-4.000000000000000327e-05,2.168407964178528478e-09,0.000000000000000000e+00 +8.100598440849607584e+01,5.025130749966411940e+02,8.629254228317859154e-02,9.854350874486726752e+00,3.536082764705396082e-03,1.000000009896211850e+00,-4.000000000000000327e-05,-2.167537255518892070e-09,0.000000000000000000e+00 +8.100699918868072302e+01,5.025230749341218370e+02,8.632790303713443192e-02,9.855365654681417453e+00,3.535936779303858364e-03,1.000000009894012276e+00,-4.000000000000000327e-05,1.011008817211681402e-09,0.000000000000000000e+00 +8.100801386437620977e+01,5.025330748716076528e+02,8.636326233124537455e-02,9.856380330386949495e+00,3.535790793902320647e-03,1.000000009895038122e+00,-4.000000000000000327e-05,-3.827784577713882914e-10,0.000000000000000000e+00 +8.100902843561482314e+01,5.025430748090986413e+02,8.639862016551143331e-02,9.857394901635597506e+00,3.535644808500782929e-03,1.000000009894649766e+00,-4.000000000000000327e-05,5.408478731970048553e-10,0.000000000000000000e+00 +8.101004290242880757e+01,5.025530747465948025e+02,8.643397653993259433e-02,9.858409368459614797e+00,3.535498823099245212e-03,1.000000009895198438e+00,-4.000000000000000327e-05,3.198138662190318952e-10,0.000000000000000000e+00 +8.101105726485039327e+01,5.025630746840960796e+02,8.646933145450887148e-02,9.859423730891240467e+00,3.535352837697707494e-03,1.000000009895522846e+00,-4.000000000000000327e-05,-1.059588214003284242e-09,0.000000000000000000e+00 +8.101207152291181046e+01,5.025730746216025295e+02,8.650468490924025089e-02,9.860437988962695854e+00,3.535206852296169776e-03,1.000000009894448150e+00,-4.000000000000000327e-05,-1.547946139756423263e-10,0.000000000000000000e+00 +8.101308567664526095e+01,5.025830745591141522e+02,8.654003690412674643e-02,9.861452142706184532e+00,3.535060866894632059e-03,1.000000009894291164e+00,-4.000000000000000327e-05,-4.307104975943124429e-10,0.000000000000000000e+00 +8.101409972608293231e+01,5.025930744966309476e+02,8.657538743916834423e-02,9.862466192153895861e+00,3.534914881493094341e-03,1.000000009893854402e+00,-4.000000000000000327e-05,-1.723457131058729194e-10,0.000000000000000000e+00 +8.101511367125701213e+01,5.026030744341529157e+02,8.661073651436504428e-02,9.863480137338001441e+00,3.534768896091556624e-03,1.000000009893679653e+00,-4.000000000000000327e-05,6.095138887432329143e-10,0.000000000000000000e+00 +8.101612751219963116e+01,5.026130743716799998e+02,8.664608412971684659e-02,9.864493978290656884e+00,3.534622910690018906e-03,1.000000009894297603e+00,-4.000000000000000327e-05,1.752286134555919458e-10,0.000000000000000000e+00 +8.101714124894294855e+01,5.026230743092122566e+02,8.668143028522376503e-02,9.865507715044001813e+00,3.534476925288481189e-03,1.000000009894475239e+00,-4.000000000000000327e-05,2.407450456506001166e-10,0.000000000000000000e+00 +8.101815488151908085e+01,5.026330742467496862e+02,8.671677498088578573e-02,9.866521347630158090e+00,3.534330939886943471e-03,1.000000009894719266e+00,-4.000000000000000327e-05,-9.339413798980480542e-10,0.000000000000000000e+00 +8.101916840996013036e+01,5.026430741842922885e+02,8.675211821670290868e-02,9.867534876081231587e+00,3.534184954485405754e-03,1.000000009893772690e+00,-4.000000000000000327e-05,9.772006658819675880e-11,0.000000000000000000e+00 +8.102018183429818521e+01,5.026530741218400635e+02,8.678745999267513389e-02,9.868548300429310416e+00,3.534038969083868036e-03,1.000000009893871722e+00,-4.000000000000000327e-05,-1.341049840034078184e-10,0.000000000000000000e+00 +8.102119515456531929e+01,5.026630740593929545e+02,8.682280030880246136e-02,9.869561620706468474e+00,3.533892983682330319e-03,1.000000009893735831e+00,-4.000000000000000327e-05,8.853590959846198963e-11,0.000000000000000000e+00 +8.102220837079359228e+01,5.026730739969510182e+02,8.685813916508489108e-02,9.870574836944761898e+00,3.533746998280792601e-03,1.000000009893825537e+00,-4.000000000000000327e-05,-9.764058650183241467e-10,0.000000000000000000e+00 +8.102322148301503546e+01,5.026830739345142547e+02,8.689347656152240917e-02,9.871587949176230836e+00,3.533601012879254884e-03,1.000000009892836328e+00,-4.000000000000000327e-05,1.212138863925117489e-10,0.000000000000000000e+00 +8.102423449126168009e+01,5.026930738720826639e+02,8.692881249811502953e-02,9.872600957432897673e+00,3.533455027477717166e-03,1.000000009892959119e+00,-4.000000000000000327e-05,-9.185141094746071065e-11,0.000000000000000000e+00 +8.102524739556552902e+01,5.027030738096561890e+02,8.696414697486275214e-02,9.873613861746770581e+00,3.533309042076179449e-03,1.000000009892866082e+00,-4.000000000000000327e-05,1.835901263863958407e-09,0.000000000000000000e+00 +8.102626019595858509e+01,5.027130737472348869e+02,8.699947999176556312e-02,9.874626662149839973e+00,3.533163056674641731e-03,1.000000009894725483e+00,-4.000000000000000327e-05,-2.767070760885803434e-09,0.000000000000000000e+00 +8.102727289247280851e+01,5.027230736848187576e+02,8.703481154882347637e-02,9.875639358674082047e+00,3.533017071273104014e-03,1.000000009891923280e+00,-4.000000000000000327e-05,1.676639683454928623e-09,0.000000000000000000e+00 +8.102828548514015949e+01,5.027330736224078009e+02,8.707014164603649187e-02,9.876651951351449910e+00,3.532871085871566296e-03,1.000000009893621034e+00,-4.000000000000000327e-05,-4.340060358148827127e-10,0.000000000000000000e+00 +8.102929797399258405e+01,5.027430735600019602e+02,8.710547028340459574e-02,9.877664440213889563e+00,3.532725100470028579e-03,1.000000009893181607e+00,-4.000000000000000327e-05,-4.489648455034484792e-10,0.000000000000000000e+00 +8.103031035906199975e+01,5.027530734976012923e+02,8.714079746092780188e-02,9.878676825293323915e+00,3.532579115068490861e-03,1.000000009892727082e+00,-4.000000000000000327e-05,-1.127462542927119808e-10,0.000000000000000000e+00 +8.103132264038032417e+01,5.027630734352057971e+02,8.717612317860609639e-02,9.879689106621661665e+00,3.532433129666953144e-03,1.000000009892612951e+00,-4.000000000000000327e-05,5.648859035989501795e-10,0.000000000000000000e+00 +8.103233481797944648e+01,5.027730733728154178e+02,8.721144743643947927e-02,9.880701284230795522e+00,3.532287144265415426e-03,1.000000009893184716e+00,-4.000000000000000327e-05,-1.623527745649064547e-10,0.000000000000000000e+00 +8.103334689189124163e+01,5.027830733104302112e+02,8.724677023442796442e-02,9.881713358152602211e+00,3.532141158863877708e-03,1.000000009893020403e+00,-4.000000000000000327e-05,-5.722424409451584811e-10,0.000000000000000000e+00 +8.103435886214757033e+01,5.027930732480501774e+02,8.728209157257153794e-02,9.882725328418940691e+00,3.531995173462339991e-03,1.000000009892441311e+00,-4.000000000000000327e-05,-6.756575584843530440e-10,0.000000000000000000e+00 +8.103537072878027914e+01,5.028030731856753164e+02,8.731741145087019984e-02,9.883737195061653935e+00,3.531849188060802273e-03,1.000000009891757635e+00,-4.000000000000000327e-05,1.251378322880504113e-09,0.000000000000000000e+00 +8.103638249182118614e+01,5.028130731233055712e+02,8.735272986932395012e-02,9.884748958112568928e+00,3.531703202659264556e-03,1.000000009893023734e+00,-4.000000000000000327e-05,-1.744031923792965040e-09,0.000000000000000000e+00 +8.103739415130210944e+01,5.028230730609409989e+02,8.738804682793278877e-02,9.885760617603498446e+00,3.531557217257726838e-03,1.000000009891259367e+00,-4.000000000000000327e-05,7.399614041934430162e-10,0.000000000000000000e+00 +8.103840570725483872e+01,5.028330729985815992e+02,8.742336232669671581e-02,9.886772173566233946e+00,3.531411231856189121e-03,1.000000009892007879e+00,-4.000000000000000327e-05,1.339135696970617401e-11,0.000000000000000000e+00 +8.103941715971114945e+01,5.028430729362273155e+02,8.745867636561573122e-02,9.887783626032556228e+00,3.531265246454651403e-03,1.000000009892021424e+00,-4.000000000000000327e-05,1.272967719317658068e-09,0.000000000000000000e+00 +8.104042850870281711e+01,5.028530728738782045e+02,8.749398894468983501e-02,9.888794975034226553e+00,3.531119261053113686e-03,1.000000009893308839e+00,-4.000000000000000327e-05,-2.439482220065297535e-09,0.000000000000000000e+00 +8.104143975426157454e+01,5.028630728115342663e+02,8.752930006391902717e-02,9.889806220602991971e+00,3.530973275651575968e-03,1.000000009890841923e+00,-4.000000000000000327e-05,1.023106203796627308e-09,0.000000000000000000e+00 +8.104245089641915456e+01,5.028730727491954440e+02,8.756460972330330772e-02,9.890817362770578214e+00,3.530827290250038251e-03,1.000000009891876429e+00,-4.000000000000000327e-05,-5.099582515456120230e-10,0.000000000000000000e+00 +8.104346193520727581e+01,5.028830726868617944e+02,8.759991792284266277e-02,9.891828401568702134e+00,3.530681304848500533e-03,1.000000009891360842e+00,-4.000000000000000327e-05,1.636997139551155784e-09,0.000000000000000000e+00 +8.104447287065762850e+01,5.028930726245333176e+02,8.763522466253710619e-02,9.892839337029059266e+00,3.530535319446962816e-03,1.000000009893015740e+00,-4.000000000000000327e-05,-2.975803925469759604e-09,0.000000000000000000e+00 +8.104548370280190284e+01,5.029030725622099567e+02,8.767052994238663799e-02,9.893850169183332710e+00,3.530389334045425098e-03,1.000000009890007702e+00,-4.000000000000000327e-05,3.024658948398787045e-09,0.000000000000000000e+00 +8.104649443167176059e+01,5.029130724998917685e+02,8.770583376239124429e-02,9.894860898063182475e+00,3.530243348643887381e-03,1.000000009893064812e+00,-4.000000000000000327e-05,-2.976412018763906338e-09,0.000000000000000000e+00 +8.104750505729884935e+01,5.029230724375787531e+02,8.774113612255093897e-02,9.895871523700263239e+00,3.530097363242349663e-03,1.000000009890056774e+00,-4.000000000000000327e-05,1.617231113791504750e-09,0.000000000000000000e+00 +8.104851557971478826e+01,5.029330723752708536e+02,8.777643702286570815e-02,9.896882046126201260e+00,3.529951377840811946e-03,1.000000009891691022e+00,-4.000000000000000327e-05,-5.990519293450630299e-10,0.000000000000000000e+00 +8.104952599895121068e+01,5.029430723129681269e+02,8.781173646333556571e-02,9.897892465372617465e+00,3.529805392439274228e-03,1.000000009891085728e+00,-4.000000000000000327e-05,8.015280399667797833e-10,0.000000000000000000e+00 +8.105053631503970735e+01,5.029530722506705729e+02,8.784703444396049776e-02,9.898902781471109691e+00,3.529659407037736511e-03,1.000000009891895525e+00,-4.000000000000000327e-05,-1.153069728401177818e-09,0.000000000000000000e+00 +8.105154652801186899e+01,5.029630721883781348e+02,8.788233096474050432e-02,9.899912994453263337e+00,3.529513421636198793e-03,1.000000009890730679e+00,-4.000000000000000327e-05,-1.253206515924932829e-09,0.000000000000000000e+00 +8.105255663789925791e+01,5.029730721260908695e+02,8.791762602567559926e-02,9.900923104350644266e+00,3.529367436234661076e-03,1.000000009889464803e+00,-4.000000000000000327e-05,2.232522480764682510e-09,0.000000000000000000e+00 +8.105356664473343642e+01,5.029830720638087769e+02,8.795291962676576869e-02,9.901933111194804127e+00,3.529221450833123358e-03,1.000000009891719666e+00,-4.000000000000000327e-05,-1.155401518889236344e-09,0.000000000000000000e+00 +8.105457654854592420e+01,5.029930720015318002e+02,8.798821176801101263e-02,9.902943015017282136e+00,3.529075465431585640e-03,1.000000009890552821e+00,-4.000000000000000327e-05,7.625768100556470492e-10,0.000000000000000000e+00 +8.105558634936825513e+01,5.030030719392599963e+02,8.802350244941133106e-02,9.903952815849594415e+00,3.528929480030047923e-03,1.000000009891322872e+00,-4.000000000000000327e-05,-2.477087968471676728e-09,0.000000000000000000e+00 +8.105659604723192047e+01,5.030130718769933651e+02,8.805879167096672400e-02,9.904962513723246431e+00,3.528783494628510205e-03,1.000000009888821761e+00,-4.000000000000000327e-05,3.054448236352334867e-09,0.000000000000000000e+00 +8.105760564216841146e+01,5.030230718147318498e+02,8.809407943267719143e-02,9.905972108669722331e+00,3.528637509226972488e-03,1.000000009891905517e+00,-4.000000000000000327e-05,-1.823441592849128610e-09,0.000000000000000000e+00 +8.105861513420920517e+01,5.030330717524755073e+02,8.812936573454273337e-02,9.906981600720499159e+00,3.528491523825434770e-03,1.000000009890064767e+00,-4.000000000000000327e-05,3.059910415404368712e-10,0.000000000000000000e+00 +8.105962452338575019e+01,5.030430716902243375e+02,8.816465057656334980e-02,9.907990989907027313e+00,3.528345538423897053e-03,1.000000009890373631e+00,-4.000000000000000327e-05,-1.026747441510347185e-09,0.000000000000000000e+00 +8.106063380972949517e+01,5.030530716279782837e+02,8.819993395873904074e-02,9.909000276260748308e+00,3.528199553022359335e-03,1.000000009889337349e+00,-4.000000000000000327e-05,1.141484538741205675e-09,0.000000000000000000e+00 +8.106164299327184608e+01,5.030630715657374026e+02,8.823521588106980618e-02,9.910009459813084121e+00,3.528053567620821618e-03,1.000000009890489316e+00,-4.000000000000000327e-05,-1.755970379975400190e-10,0.000000000000000000e+00 +8.106265207404422313e+01,5.030730715035016374e+02,8.827049634355563223e-02,9.911018540595444293e+00,3.527907582219283900e-03,1.000000009890312125e+00,-4.000000000000000327e-05,-1.503070038039553031e-09,0.000000000000000000e+00 +8.106366105207801809e+01,5.030830714412710449e+02,8.830577534619653279e-02,9.912027518639218826e+00,3.527761596817746183e-03,1.000000009888795560e+00,-4.000000000000000327e-05,6.395850953114916398e-10,0.000000000000000000e+00 +8.106466992740460853e+01,5.030930713790456252e+02,8.834105288899250785e-02,9.913036393975781735e+00,3.527615611416208465e-03,1.000000009889440822e+00,-4.000000000000000327e-05,1.006139379741439606e-09,0.000000000000000000e+00 +8.106567870005534360e+01,5.031030713168253214e+02,8.837632897194354353e-02,9.914045166636494599e+00,3.527469626014670748e-03,1.000000009890455788e+00,-4.000000000000000327e-05,-2.161735757874491334e-09,0.000000000000000000e+00 +8.106668737006157244e+01,5.031130712546101904e+02,8.841160359504965371e-02,9.915053836652701236e+00,3.527323640613133030e-03,1.000000009888275310e+00,-4.000000000000000327e-05,1.600551722102164373e-09,0.000000000000000000e+00 +8.106769593745462998e+01,5.031230711924001753e+02,8.844687675831082452e-02,9.916062404055725921e+00,3.527177655211595313e-03,1.000000009889889574e+00,-4.000000000000000327e-05,5.988918192263787406e-11,0.000000000000000000e+00 +8.106870440226580854e+01,5.031330711301953329e+02,8.848214846172705594e-02,9.917070868876884049e+00,3.527031669810057595e-03,1.000000009889949970e+00,-4.000000000000000327e-05,-1.558378105205131781e-09,0.000000000000000000e+00 +8.106971276452641462e+01,5.031430710679956633e+02,8.851741870529836187e-02,9.918079231147469699e+00,3.526885684408519878e-03,1.000000009888378560e+00,-4.000000000000000327e-05,1.978506776470575994e-09,0.000000000000000000e+00 +8.107072102426774052e+01,5.031530710058011095e+02,8.855268748902472842e-02,9.919087490898760961e+00,3.526739699006982160e-03,1.000000009890373409e+00,-4.000000000000000327e-05,-1.572790870263586326e-09,0.000000000000000000e+00 +8.107172918152103591e+01,5.031630709436117286e+02,8.858795481290615559e-02,9.920095648162025270e+00,3.526593713605444443e-03,1.000000009888787789e+00,-4.000000000000000327e-05,9.031085247960102864e-12,0.000000000000000000e+00 +8.107273723631755047e+01,5.031730708814274635e+02,8.862322067694264338e-02,9.921103702968506965e+00,3.526447728203906725e-03,1.000000009888796892e+00,-4.000000000000000327e-05,-2.777891643255989040e-10,0.000000000000000000e+00 +8.107374518868851965e+01,5.031830708192483712e+02,8.865848508113420567e-02,9.922111655349439729e+00,3.526301742802369008e-03,1.000000009888516894e+00,-4.000000000000000327e-05,-6.959755154245268612e-10,0.000000000000000000e+00 +8.107475303866515048e+01,5.031930707570743948e+02,8.869374802548082859e-02,9.923119505336039481e+00,3.526155757400831290e-03,1.000000009887815455e+00,-4.000000000000000327e-05,2.241273202769415831e-09,0.000000000000000000e+00 +8.107576078627865002e+01,5.032030706949055912e+02,8.872900950998251213e-02,9.924127252959506151e+00,3.526009771999293572e-03,1.000000009890074093e+00,-4.000000000000000327e-05,-1.972882108697203776e-09,0.000000000000000000e+00 +8.107676843156021107e+01,5.032130706327419034e+02,8.876426953463925629e-02,9.925134898251027238e+00,3.525863786597755855e-03,1.000000009888086128e+00,-4.000000000000000327e-05,6.457200385917684256e-10,0.000000000000000000e+00 +8.107777597454098384e+01,5.032230705705833884e+02,8.879952809945104719e-02,9.926142441241767145e+00,3.525717801196218137e-03,1.000000009888736718e+00,-4.000000000000000327e-05,-4.112750539099682162e-10,0.000000000000000000e+00 +8.107878341525213273e+01,5.032330705084300462e+02,8.883478520441789872e-02,9.927149881962881395e+00,3.525571815794680420e-03,1.000000009888322383e+00,-4.000000000000000327e-05,9.456318615623961730e-11,0.000000000000000000e+00 +8.107979075372479372e+01,5.032430704462818198e+02,8.887004084953981087e-02,9.928157220445505970e+00,3.525425830393142702e-03,1.000000009888417640e+00,-4.000000000000000327e-05,-1.348709274810691202e-09,0.000000000000000000e+00 +8.108079798999008858e+01,5.032530703841387663e+02,8.890529503481678364e-02,9.929164456720762644e+00,3.525279844991604985e-03,1.000000009887059171e+00,-4.000000000000000327e-05,5.002503778395042683e-10,0.000000000000000000e+00 +8.108180512407912488e+01,5.032630703220008286e+02,8.894054776024881703e-02,9.930171590819755423e+00,3.525133859590067267e-03,1.000000009887562991e+00,-4.000000000000000327e-05,3.779268921514380517e-10,0.000000000000000000e+00 +8.108281215602298175e+01,5.032730702598680637e+02,8.897579902583589717e-02,9.931178622773575881e+00,3.524987874188529550e-03,1.000000009887943575e+00,-4.000000000000000327e-05,2.425681097107042405e-11,0.000000000000000000e+00 +8.108381908585275255e+01,5.032830701977404146e+02,8.901104883157803793e-02,9.932185552613297830e+00,3.524841888786991832e-03,1.000000009887968000e+00,-4.000000000000000327e-05,1.179221079668464398e-09,0.000000000000000000e+00 +8.108482591359947378e+01,5.032930701356179384e+02,8.904629717747522544e-02,9.933192380369979091e+00,3.524695903385454115e-03,1.000000009889155272e+00,-4.000000000000000327e-05,-3.176742643484082782e-09,0.000000000000000000e+00 +8.108583263929419616e+01,5.033030700735005780e+02,8.908154406352747356e-02,9.934199106074663277e+00,3.524549917983916397e-03,1.000000009885957164e+00,-4.000000000000000327e-05,2.718912610199548552e-09,0.000000000000000000e+00 +8.108683926296795619e+01,5.033130700113883904e+02,8.911678948973476844e-02,9.935205729758372684e+00,3.524403932582378680e-03,1.000000009888694086e+00,-4.000000000000000327e-05,-2.179586125139747949e-09,0.000000000000000000e+00 +8.108784578465174775e+01,5.033230699492813187e+02,8.915203345609711005e-02,9.936212251452124278e+00,3.524257947180840962e-03,1.000000009886500285e+00,-4.000000000000000327e-05,1.401651160325986101e-09,0.000000000000000000e+00 +8.108885220437657892e+01,5.033330698871794198e+02,8.918727596261451229e-02,9.937218671186908381e+00,3.524111961779303245e-03,1.000000009887910934e+00,-4.000000000000000327e-05,-5.754567110484266335e-10,0.000000000000000000e+00 +8.108985852217342938e+01,5.033430698250826367e+02,8.922251700928696128e-02,9.938224988993708209e+00,3.523965976377765527e-03,1.000000009887331842e+00,-4.000000000000000327e-05,-1.108881443771933879e-09,0.000000000000000000e+00 +8.109086473807326456e+01,5.033530697629910264e+02,8.925775659611445700e-02,9.939231204903485661e+00,3.523819990976227810e-03,1.000000009886216068e+00,-4.000000000000000327e-05,1.547735904771932792e-09,0.000000000000000000e+00 +8.109187085210702151e+01,5.033630697009045321e+02,8.929299472309699948e-02,9.940237318947188427e+00,3.523674005574690092e-03,1.000000009887773267e+00,-4.000000000000000327e-05,-1.391403793485747685e-09,0.000000000000000000e+00 +8.109287686430563724e+01,5.033730696388232104e+02,8.932823139023458869e-02,9.941243331155751761e+00,3.523528020173152375e-03,1.000000009886373498e+00,-4.000000000000000327e-05,5.926867517692267774e-10,0.000000000000000000e+00 +8.109388277470003459e+01,5.033830695767470047e+02,8.936346659752723853e-02,9.942249241560089601e+00,3.523382034771614657e-03,1.000000009886969687e+00,-4.000000000000000327e-05,4.682367969210721927e-10,0.000000000000000000e+00 +8.109488858332110794e+01,5.033930695146759717e+02,8.939870034497492124e-02,9.943255050191105227e+00,3.523236049370076940e-03,1.000000009887440644e+00,-4.000000000000000327e-05,-1.776433003671532305e-09,0.000000000000000000e+00 +8.109589429019973750e+01,5.034030694526100547e+02,8.943393263257765069e-02,9.944260757079684154e+00,3.523090063968539222e-03,1.000000009885654073e+00,-4.000000000000000327e-05,8.724082401206219654e-10,0.000000000000000000e+00 +8.109689989536680343e+01,5.034130693905493104e+02,8.946916346033542689e-02,9.945266362256694137e+00,3.522944078567001504e-03,1.000000009886531371e+00,-4.000000000000000327e-05,-3.773972293141067739e-10,0.000000000000000000e+00 +8.109790539885315752e+01,5.034230693284936820e+02,8.950439282824824982e-02,9.946271865752992269e+00,3.522798093165463787e-03,1.000000009886151897e+00,-4.000000000000000327e-05,1.489202343458116509e-09,0.000000000000000000e+00 +8.109891080068963731e+01,5.034330692664432263e+02,8.953962073631611951e-02,9.947277267599416106e+00,3.522652107763926069e-03,1.000000009887649144e+00,-4.000000000000000327e-05,-2.324035439864170455e-09,0.000000000000000000e+00 +8.109991610090706615e+01,5.034430692043978866e+02,8.957484718453903594e-02,9.948282567826790768e+00,3.522506122362388352e-03,1.000000009885312791e+00,-4.000000000000000327e-05,4.733806578472513060e-10,0.000000000000000000e+00 +8.110092129953625317e+01,5.034530691423577196e+02,8.961007217291698523e-02,9.949287766465920058e+00,3.522360136960850634e-03,1.000000009885788632e+00,-4.000000000000000327e-05,1.084047408951255789e-09,0.000000000000000000e+00 +8.110192639660799330e+01,5.034630690803226685e+02,8.964529570144998127e-02,9.950292863547598898e+00,3.522214151559312917e-03,1.000000009886878205e+00,-4.000000000000000327e-05,-5.050708626013158319e-10,0.000000000000000000e+00 +8.110293139215306724e+01,5.034730690182927901e+02,8.968051777013801018e-02,9.951297859102604448e+00,3.522068166157775199e-03,1.000000009886370611e+00,-4.000000000000000327e-05,-7.881757349763372441e-10,0.000000000000000000e+00 +8.110393628620222728e+01,5.034830689562680277e+02,8.971573837898108583e-02,9.952302753161696103e+00,3.521922180756237482e-03,1.000000009885578578e+00,-4.000000000000000327e-05,2.254052235578491983e-10,0.000000000000000000e+00 +8.110494107878621151e+01,5.034930688942484380e+02,8.975095752797919435e-02,9.953307545755619046e+00,3.521776195354699764e-03,1.000000009885805063e+00,-4.000000000000000327e-05,-9.945352087625877692e-10,0.000000000000000000e+00 +8.110594576993575799e+01,5.035030688322339643e+02,8.978617521713234961e-02,9.954312236915104251e+00,3.521630209953162047e-03,1.000000009884805863e+00,-4.000000000000000327e-05,8.200217926680473249e-10,0.000000000000000000e+00 +8.110695035968159061e+01,5.035130687702246064e+02,8.982139144644053774e-02,9.955316826670864927e+00,3.521484224551624329e-03,1.000000009885629648e+00,-4.000000000000000327e-05,3.795470380517390164e-10,0.000000000000000000e+00 +8.110795484805439060e+01,5.035230687082204213e+02,8.985660621590375874e-02,9.956321315053601850e+00,3.521338239150086612e-03,1.000000009886010899e+00,-4.000000000000000327e-05,-2.329464570054891113e-09,0.000000000000000000e+00 +8.110895923508485339e+01,5.035330686462213521e+02,8.989181952552202648e-02,9.957325702093998032e+00,3.521192253748548894e-03,1.000000009883671215e+00,-4.000000000000000327e-05,1.487983113947879392e-09,0.000000000000000000e+00 +8.110996352080364602e+01,5.035430685842274556e+02,8.992703137529532709e-02,9.958329987822718721e+00,3.521046268347011177e-03,1.000000009885165575e+00,-4.000000000000000327e-05,1.255073401004874867e-09,0.000000000000000000e+00 +8.111096770524142130e+01,5.035530685222386751e+02,8.996224176522366056e-02,9.959334172270420282e+00,3.520900282945473459e-03,1.000000009886425900e+00,-4.000000000000000327e-05,-1.279525541536689004e-09,0.000000000000000000e+00 +8.111197178842881783e+01,5.035630684602550673e+02,8.999745069530702690e-02,9.960338255467739543e+00,3.520754297543935742e-03,1.000000009885141150e+00,-4.000000000000000327e-05,-8.415287813713311756e-10,0.000000000000000000e+00 +8.111297577039644580e+01,5.035730683982765754e+02,9.003265816554542611e-02,9.961342237445295567e+00,3.520608312142398024e-03,1.000000009884296270e+00,-4.000000000000000327e-05,7.984822908908010207e-10,0.000000000000000000e+00 +8.111397965117492959e+01,5.035830683363031994e+02,9.006786417593885818e-02,9.962346118233694980e+00,3.520462326740860307e-03,1.000000009885097851e+00,-4.000000000000000327e-05,-1.659727531524599928e-09,0.000000000000000000e+00 +8.111498343079483675e+01,5.035930682743349962e+02,9.010306872648732313e-02,9.963349897863530202e+00,3.520316341339322589e-03,1.000000009883431851e+00,-4.000000000000000327e-05,2.351241039966058629e-09,0.000000000000000000e+00 +8.111598710928676326e+01,5.036030682123719089e+02,9.013827181719082093e-02,9.964353576365374110e+00,3.520170355937784872e-03,1.000000009885791741e+00,-4.000000000000000327e-05,-1.284816724521714146e-09,0.000000000000000000e+00 +8.111699068668126245e+01,5.036130681504139943e+02,9.017347344804933773e-02,9.965357153769790699e+00,3.520024370536247154e-03,1.000000009884502328e+00,-4.000000000000000327e-05,-2.354370034842969024e-10,0.000000000000000000e+00 +8.111799416300887344e+01,5.036230680884611957e+02,9.020867361906288739e-02,9.966360630107320873e+00,3.519878385134709436e-03,1.000000009884266072e+00,-4.000000000000000327e-05,-1.566123545943420932e-09,0.000000000000000000e+00 +8.111899753830013537e+01,5.036330680265135129e+02,9.024387233023146992e-02,9.967364005408494876e+00,3.519732399733171719e-03,1.000000009882694663e+00,-4.000000000000000327e-05,1.770116882299380581e-09,0.000000000000000000e+00 +8.112000081258554474e+01,5.036430679645710029e+02,9.027906958155507144e-02,9.968367279703825190e+00,3.519586414331634001e-03,1.000000009884470575e+00,-4.000000000000000327e-05,-8.251637866049290968e-10,0.000000000000000000e+00 +8.112100398589561223e+01,5.036530679026336088e+02,9.031426537303370583e-02,9.969370453023813639e+00,3.519440428930096284e-03,1.000000009883642793e+00,-4.000000000000000327e-05,1.226359287670495855e-09,0.000000000000000000e+00 +8.112200705826082014e+01,5.036630678407013875e+02,9.034945970466737308e-02,9.970373525398940728e+00,3.519294443528558566e-03,1.000000009884872920e+00,-4.000000000000000327e-05,-9.123348587307463889e-10,0.000000000000000000e+00 +8.112301002971163655e+01,5.036730677787742820e+02,9.038465257645605933e-02,9.971376496859676308e+00,3.519148458127020849e-03,1.000000009883957874e+00,-4.000000000000000327e-05,-1.901903614776592829e-10,0.000000000000000000e+00 +8.112401290027851530e+01,5.036830677168522925e+02,9.041984398839976456e-02,9.972379367436470687e+00,3.519002472725483131e-03,1.000000009883767138e+00,-4.000000000000000327e-05,-1.485804047696131260e-10,0.000000000000000000e+00 +8.112501566999189606e+01,5.036930676549354757e+02,9.045503394049850265e-02,9.973382137159761740e+00,3.518856487323945414e-03,1.000000009883618146e+00,-4.000000000000000327e-05,-7.992259328350920715e-10,0.000000000000000000e+00 +8.112601833888219005e+01,5.037030675930237749e+02,9.049022243275225974e-02,9.974384806059971353e+00,3.518710501922407696e-03,1.000000009882816787e+00,-4.000000000000000327e-05,-3.853679500519368632e-10,0.000000000000000000e+00 +8.112702090697982271e+01,5.037130675311172467e+02,9.052540946516103582e-02,9.975387374167505428e+00,3.518564516520869979e-03,1.000000009882430430e+00,-4.000000000000000327e-05,1.082239691423013327e-09,0.000000000000000000e+00 +8.112802337431516264e+01,5.037230674692158345e+02,9.056059503772483088e-02,9.976389841512755652e+00,3.518418531119332261e-03,1.000000009883515339e+00,-4.000000000000000327e-05,5.848137348073140525e-11,0.000000000000000000e+00 +8.112902574091859265e+01,5.037330674073195382e+02,9.059577915044365881e-02,9.977392208126099504e+00,3.518272545717794544e-03,1.000000009883573959e+00,-4.000000000000000327e-05,6.668432594216690388e-11,0.000000000000000000e+00 +8.113002800682048132e+01,5.037430673454284147e+02,9.063096180331750573e-02,9.978394474037896700e+00,3.518126560316256826e-03,1.000000009883640795e+00,-4.000000000000000327e-05,-6.708984138767249180e-10,0.000000000000000000e+00 +8.113103017205116885e+01,5.037530672835424070e+02,9.066614299634637164e-02,9.979396639278492742e+00,3.517980574914719109e-03,1.000000009882968444e+00,-4.000000000000000327e-05,-3.968625290828371941e-10,0.000000000000000000e+00 +8.113203223664099539e+01,5.037630672216615153e+02,9.070132272953025654e-02,9.980398703878217148e+00,3.517834589513181391e-03,1.000000009882570762e+00,-4.000000000000000327e-05,-8.906480528844473685e-10,0.000000000000000000e+00 +8.113303420062025850e+01,5.037730671597857963e+02,9.073650100286916043e-02,9.981400667867385224e+00,3.517688604111643674e-03,1.000000009881678364e+00,-4.000000000000000327e-05,1.376553971879619951e-09,0.000000000000000000e+00 +8.113403606401926993e+01,5.037830670979151932e+02,9.077167781636308330e-02,9.982402531276296287e+00,3.517542618710105956e-03,1.000000009883057484e+00,-4.000000000000000327e-05,-6.849104355143021718e-10,0.000000000000000000e+00 +8.113503782686831300e+01,5.037930670360497061e+02,9.080685317001201129e-02,9.983404294135237222e+00,3.517396633308568239e-03,1.000000009882371366e+00,-4.000000000000000327e-05,-7.093635399353983880e-12,0.000000000000000000e+00 +8.113603948919765685e+01,5.038030669741893917e+02,9.084202706381595827e-02,9.984405956474475374e+00,3.517250647907030521e-03,1.000000009882364260e+00,-4.000000000000000327e-05,-1.392265622938364605e-10,0.000000000000000000e+00 +8.113704105103755637e+01,5.038130669123341931e+02,9.087719949777492423e-02,9.985407518324265652e+00,3.517104662505492804e-03,1.000000009882224816e+00,-4.000000000000000327e-05,6.780215542575707631e-10,0.000000000000000000e+00 +8.113804251241823806e+01,5.038230668504841105e+02,9.091237047188889531e-02,9.986408979714846978e+00,3.516958677103955086e-03,1.000000009882903829e+00,-4.000000000000000327e-05,-1.109157603907588169e-09,0.000000000000000000e+00 +8.113904387336994262e+01,5.038330667886392007e+02,9.094753998615788537e-02,9.987410340676444065e+00,3.516812691702417368e-03,1.000000009881793162e+00,-4.000000000000000327e-05,-1.962620766237910773e-10,0.000000000000000000e+00 +8.114004513392286810e+01,5.038430667267994068e+02,9.098270804058189443e-02,9.988411601239263859e+00,3.516666706300879651e-03,1.000000009881596652e+00,-4.000000000000000327e-05,-1.368427584128501009e-10,0.000000000000000000e+00 +8.114104629410721259e+01,5.038530666649647287e+02,9.101787463516090859e-02,9.989412761433500876e+00,3.516520720899341933e-03,1.000000009881459651e+00,-4.000000000000000327e-05,8.300112275990515173e-10,0.000000000000000000e+00 +8.114204735395315993e+01,5.038630666031352234e+02,9.105303976989494175e-02,9.990413821289333640e+00,3.516374735497804216e-03,1.000000009882290541e+00,-4.000000000000000327e-05,-8.511684209075369296e-10,0.000000000000000000e+00 +8.114304831349086555e+01,5.038730665413108341e+02,9.108820344478398001e-02,9.991414780836926468e+00,3.516228750096266498e-03,1.000000009881438556e+00,-4.000000000000000327e-05,1.275660354900505627e-10,0.000000000000000000e+00 +8.114404917275047069e+01,5.038830664794915606e+02,9.112336565982802339e-02,9.992415640106425911e+00,3.516082764694728781e-03,1.000000009881566232e+00,-4.000000000000000327e-05,2.087855026053941146e-10,0.000000000000000000e+00 +8.114504993176211656e+01,5.038930664176774599e+02,9.115852641502708575e-02,9.993416399127966088e+00,3.515936779293191063e-03,1.000000009881775176e+00,-4.000000000000000327e-05,-6.173214033816432043e-10,0.000000000000000000e+00 +8.114605059055593017e+01,5.039030663558684751e+02,9.119368571038115323e-02,9.994417057931665127e+00,3.515790793891653346e-03,1.000000009881157448e+00,-4.000000000000000327e-05,-5.878677719386655282e-10,0.000000000000000000e+00 +8.114705114916201012e+01,5.039130662940646062e+02,9.122884354589022582e-02,9.995417616547625173e+00,3.515644808490115628e-03,1.000000009880569252e+00,-4.000000000000000327e-05,2.867501693999304063e-10,0.000000000000000000e+00 +8.114805160761044078e+01,5.039230662322658532e+02,9.126399992155430352e-02,9.996418075005934156e+00,3.515498823088577911e-03,1.000000009880856133e+00,-4.000000000000000327e-05,2.219650702130134263e-10,0.000000000000000000e+00 +8.114905196593129233e+01,5.039330661704722729e+02,9.129915483737338633e-02,9.997418433336665800e+00,3.515352837687040193e-03,1.000000009881078178e+00,-4.000000000000000327e-05,-7.938265226850463060e-10,0.000000000000000000e+00 +8.115005222415462072e+01,5.039430661086838086e+02,9.133430829334747425e-02,9.998418691569877836e+00,3.515206852285502476e-03,1.000000009880284146e+00,-4.000000000000000327e-05,7.803633672780056512e-10,0.000000000000000000e+00 +8.115105238231046769e+01,5.039530660469004602e+02,9.136946028947656728e-02,9.999418849735612014e+00,3.515060866883964758e-03,1.000000009881064633e+00,-4.000000000000000327e-05,-3.934401738121874504e-10,0.000000000000000000e+00 +8.115205244042887500e+01,5.039630659851222845e+02,9.140461082576066543e-02,1.000041890786389764e+01,3.514914881482427041e-03,1.000000009880671170e+00,-4.000000000000000327e-05,-7.743019721333824395e-10,0.000000000000000000e+00 +8.115305239853984176e+01,5.039730659233492247e+02,9.143975990219976868e-02,1.000141886598474628e+01,3.514768896080889323e-03,1.000000009879896901e+00,-4.000000000000000327e-05,1.405297624578227393e-09,0.000000000000000000e+00 +8.115405225667336708e+01,5.039830658615812808e+02,9.147490751879387705e-02,1.000241872412815525e+01,3.514622910679351606e-03,1.000000009881301999e+00,-4.000000000000000327e-05,-2.750465488246046937e-09,0.000000000000000000e+00 +8.115505201485943587e+01,5.039930657998184529e+02,9.151005367554297665e-02,1.000341848232410946e+01,3.514476925277813888e-03,1.000000009878552198e+00,-4.000000000000000327e-05,2.742966183926674378e-09,0.000000000000000000e+00 +8.115605167312801882e+01,5.040030657380607977e+02,9.154519837244708136e-02,1.000441814060257251e+01,3.514330939876276171e-03,1.000000009881294227e+00,-4.000000000000000327e-05,-1.677177440518860582e-09,0.000000000000000000e+00 +8.115705123150907241e+01,5.040130656763082584e+02,9.158034160950619118e-02,1.000541769899350264e+01,3.514184954474738453e-03,1.000000009879617791e+00,-4.000000000000000327e-05,-2.221649020082928259e-11,0.000000000000000000e+00 +8.115805069003252470e+01,5.040230656145608350e+02,9.161548338672029224e-02,1.000641715752683325e+01,3.514038969073200736e-03,1.000000009879595586e+00,-4.000000000000000327e-05,5.867961164313842918e-10,0.000000000000000000e+00 +8.115905004872830375e+01,5.040330655528185275e+02,9.165062370408939840e-02,1.000741651623248885e+01,3.513892983671663018e-03,1.000000009880182006e+00,-4.000000000000000327e-05,1.379919657780254273e-10,0.000000000000000000e+00 +8.116004930762632341e+01,5.040430654910813928e+02,9.168576256161349580e-02,1.000841577514037795e+01,3.513746998270125300e-03,1.000000009880319896e+00,-4.000000000000000327e-05,-1.379168519400257586e-09,0.000000000000000000e+00 +8.116104846675646911e+01,5.040530654293493740e+02,9.172089995929259831e-02,1.000941493428039308e+01,3.513601012868587583e-03,1.000000009878941887e+00,-4.000000000000000327e-05,-4.169478632733984494e-10,0.000000000000000000e+00 +8.116204752614861206e+01,5.040630653676224711e+02,9.175603589712669206e-02,1.001041399368241080e+01,3.513455027467049865e-03,1.000000009878525331e+00,-4.000000000000000327e-05,1.236742785090093318e-09,0.000000000000000000e+00 +8.116304648583262349e+01,5.040730653059006841e+02,9.179117037511577704e-02,1.001141295337629522e+01,3.513309042065512148e-03,1.000000009879760787e+00,-4.000000000000000327e-05,1.000341105288201265e-11,0.000000000000000000e+00 +8.116404534583836039e+01,5.040830652441840698e+02,9.182630339325986712e-02,1.001241181339189623e+01,3.513163056663974430e-03,1.000000009879770779e+00,-4.000000000000000327e-05,-5.471300184635697472e-10,0.000000000000000000e+00 +8.116504410619563714e+01,5.040930651824725715e+02,9.186143495155894845e-02,1.001341057375904597e+01,3.513017071262436713e-03,1.000000009879224327e+00,-4.000000000000000327e-05,-4.453517860989324063e-10,0.000000000000000000e+00 +8.116604276693428233e+01,5.041030651207661890e+02,9.189656505001302100e-02,1.001440923450756237e+01,3.512871085860898995e-03,1.000000009878779572e+00,-4.000000000000000327e-05,3.061959911380565532e-10,0.000000000000000000e+00 +8.116704132808411032e+01,5.041130650590649225e+02,9.193169368862208479e-02,1.001540779566724915e+01,3.512725100459361278e-03,1.000000009879085328e+00,-4.000000000000000327e-05,-1.866936570774114897e-09,0.000000000000000000e+00 +8.116803978967489286e+01,5.041230649973687719e+02,9.196682086738613982e-02,1.001640625726789580e+01,3.512579115057823560e-03,1.000000009877221263e+00,-4.000000000000000327e-05,1.934290177351336579e-09,0.000000000000000000e+00 +8.116903815173641590e+01,5.041330649356777940e+02,9.200194658630518607e-02,1.001740461933927406e+01,3.512433129656285843e-03,1.000000009879152385e+00,-4.000000000000000327e-05,-7.742825376393372511e-10,0.000000000000000000e+00 +8.117003641429842276e+01,5.041430648739919320e+02,9.203707084537922356e-02,1.001840288191114681e+01,3.512287144254748125e-03,1.000000009878379448e+00,-4.000000000000000327e-05,6.898274692980535862e-10,0.000000000000000000e+00 +8.117103457739067096e+01,5.041530648123111860e+02,9.207219364460825228e-02,1.001940104501325557e+01,3.512141158853210408e-03,1.000000009879068008e+00,-4.000000000000000327e-05,-8.138149936755764351e-10,0.000000000000000000e+00 +8.117203264104288962e+01,5.041630647506355558e+02,9.210731498399227224e-02,1.002039910867533123e+01,3.511995173451672690e-03,1.000000009878255769e+00,-4.000000000000000327e-05,5.295441835839140633e-11,0.000000000000000000e+00 +8.117303060528479364e+01,5.041730646889650416e+02,9.214243486353126955e-02,1.002139707292708692e+01,3.511849188050134973e-03,1.000000009878308616e+00,-4.000000000000000327e-05,-2.861603539857478925e-10,0.000000000000000000e+00 +8.117402847014606948e+01,5.041830646272997001e+02,9.217755328322525810e-02,1.002239493779822332e+01,3.511703202648597255e-03,1.000000009878023066e+00,-4.000000000000000327e-05,-5.830597057839025278e-11,0.000000000000000000e+00 +8.117502623565641784e+01,5.041930645656394745e+02,9.221267024307423787e-02,1.002339270331842513e+01,3.511557217247059538e-03,1.000000009877964890e+00,-4.000000000000000327e-05,-1.058069385697097877e-09,0.000000000000000000e+00 +8.117602390184549677e+01,5.042030645039843648e+02,9.224778574307819501e-02,1.002439036951736284e+01,3.511411231845521820e-03,1.000000009876909290e+00,-4.000000000000000327e-05,2.737810013032939010e-10,0.000000000000000000e+00 +8.117702146874297853e+01,5.042130644423343711e+02,9.228289978323714338e-02,1.002538793642469095e+01,3.511265246443984103e-03,1.000000009877182405e+00,-4.000000000000000327e-05,3.572863702219570890e-10,0.000000000000000000e+00 +8.117801893637849275e+01,5.042230643806894932e+02,9.231801236355106910e-02,1.002638540407005152e+01,3.511119261042446385e-03,1.000000009877538787e+00,-4.000000000000000327e-05,9.675520599403339205e-10,0.000000000000000000e+00 +8.117901630478165487e+01,5.042330643190497881e+02,9.235312348401998606e-02,1.002738277248307064e+01,3.510973275640908667e-03,1.000000009878503793e+00,-4.000000000000000327e-05,-1.478413427442317472e-09,0.000000000000000000e+00 +8.118001357398209450e+01,5.042430642574151989e+02,9.238823314464388037e-02,1.002838004169336017e+01,3.510827290239370950e-03,1.000000009877029417e+00,-4.000000000000000327e-05,1.534229154548755186e-10,0.000000000000000000e+00 +8.118101074400939865e+01,5.042530641957857256e+02,9.242334134542276591e-02,1.002937721173051422e+01,3.510681304837833232e-03,1.000000009877182405e+00,-4.000000000000000327e-05,-1.291642078361232018e-09,0.000000000000000000e+00 +8.118200781489315432e+01,5.042630641341613682e+02,9.245844808635662881e-02,1.003037428262411623e+01,3.510535319436295515e-03,1.000000009875894547e+00,-4.000000000000000327e-05,1.322282996783816347e-09,0.000000000000000000e+00 +8.118300478666292008e+01,5.042730640725421267e+02,9.249355336744546907e-02,1.003137125440373190e+01,3.510389334034757797e-03,1.000000009877212825e+00,-4.000000000000000327e-05,-9.497684201060233703e-10,0.000000000000000000e+00 +8.118400165934825452e+01,5.042830640109280012e+02,9.252865718868928668e-02,1.003236812709891623e+01,3.510243348633220080e-03,1.000000009876266027e+00,-4.000000000000000327e-05,8.184324440155026314e-10,0.000000000000000000e+00 +8.118499843297870200e+01,5.042930639493190483e+02,9.256375955008808165e-02,1.003336490073920473e+01,3.510097363231682362e-03,1.000000009877081819e+00,-4.000000000000000327e-05,-5.344623054542497113e-10,0.000000000000000000e+00 +8.118599510758377846e+01,5.043030638877152114e+02,9.259886045164185397e-02,1.003436157535412221e+01,3.509951377830144645e-03,1.000000009876549134e+00,-4.000000000000000327e-05,3.457973721798701067e-10,0.000000000000000000e+00 +8.118699168319298565e+01,5.043130638261164904e+02,9.263395989335060365e-02,1.003535815097317574e+01,3.509805392428606927e-03,1.000000009876893747e+00,-4.000000000000000327e-05,-1.281270853150568282e-10,0.000000000000000000e+00 +8.118798815983582529e+01,5.043230637645228853e+02,9.266905787521433069e-02,1.003635462762585995e+01,3.509659407027069210e-03,1.000000009876766072e+00,-4.000000000000000327e-05,-1.773900644950240200e-10,0.000000000000000000e+00 +8.118898453754178490e+01,5.043330637029343961e+02,9.270415439723303508e-02,1.003735100534165348e+01,3.509513421625531492e-03,1.000000009876589324e+00,-4.000000000000000327e-05,-1.602463800063491528e-09,0.000000000000000000e+00 +8.118998081634030939e+01,5.043430636413510229e+02,9.273924945940671682e-02,1.003834728415002076e+01,3.509367436223993775e-03,1.000000009874992823e+00,-4.000000000000000327e-05,9.564471036568931580e-10,0.000000000000000000e+00 +8.119097699626085785e+01,5.043530635797727655e+02,9.277434306173537593e-02,1.003934346408041023e+01,3.509221450822456057e-03,1.000000009875945617e+00,-4.000000000000000327e-05,3.299189438718876570e-10,0.000000000000000000e+00 +8.119197307733287516e+01,5.043630635181996809e+02,9.280943520421901238e-02,1.004033954516225968e+01,3.509075465420918340e-03,1.000000009876274243e+00,-4.000000000000000327e-05,-1.704378767514513506e-09,0.000000000000000000e+00 +8.119296905958576360e+01,5.043730634566317121e+02,9.284452588685761232e-02,1.004133552742498914e+01,3.508929480019380622e-03,1.000000009874576712e+00,-4.000000000000000327e-05,2.007999716724150625e-09,0.000000000000000000e+00 +8.119396494304893963e+01,5.043830633950688593e+02,9.287961510965118961e-02,1.004233141089800263e+01,3.508783494617842905e-03,1.000000009876576446e+00,-4.000000000000000327e-05,-1.080137165363258062e-09,0.000000000000000000e+00 +8.119496072775179130e+01,5.043930633335111224e+02,9.291470287259974425e-02,1.004332719561069531e+01,3.508637509216305187e-03,1.000000009875500862e+00,-4.000000000000000327e-05,-2.323729417292051590e-10,0.000000000000000000e+00 +8.119595641372370665e+01,5.044030632719585014e+02,9.294978917570326238e-02,1.004432288159244102e+01,3.508491523814767470e-03,1.000000009875269491e+00,-4.000000000000000327e-05,-8.336815444963129912e-10,0.000000000000000000e+00 +8.119695200099403110e+01,5.044130632104109964e+02,9.298487401896175786e-02,1.004531846887260293e+01,3.508345538413229752e-03,1.000000009874439488e+00,-4.000000000000000327e-05,6.910116171835973089e-10,0.000000000000000000e+00 +8.119794748959212427e+01,5.044230631488686072e+02,9.301995740237521682e-02,1.004631395748052825e+01,3.508199553011692035e-03,1.000000009875127382e+00,-4.000000000000000327e-05,7.466252686258407865e-10,0.000000000000000000e+00 +8.119894287954731737e+01,5.044330630873313339e+02,9.305503932594363925e-02,1.004730934744555171e+01,3.508053567610154317e-03,1.000000009875870566e+00,-4.000000000000000327e-05,-6.777628635554662561e-10,0.000000000000000000e+00 +8.119993817088892740e+01,5.044430630257991766e+02,9.309011978966703904e-02,1.004830463879699209e+01,3.507907582208616599e-03,1.000000009875195994e+00,-4.000000000000000327e-05,-1.800332552602877356e-09,0.000000000000000000e+00 +8.120093336364625713e+01,5.044530629642721351e+02,9.312519879354540231e-02,1.004929983156415219e+01,3.507761596807078882e-03,1.000000009873404316e+00,-4.000000000000000327e-05,9.577137944266253287e-10,0.000000000000000000e+00 +8.120192845784859514e+01,5.044630629027502664e+02,9.316027633757872906e-02,1.005029492577632055e+01,3.507615611405541164e-03,1.000000009874357332e+00,-4.000000000000000327e-05,4.112864171058773883e-10,0.000000000000000000e+00 +8.120292345352523000e+01,5.044730628412335136e+02,9.319535242176701928e-02,1.005128992146277511e+01,3.507469626004003447e-03,1.000000009874766560e+00,-4.000000000000000327e-05,1.372578340252862680e-10,0.000000000000000000e+00 +8.120391835070540765e+01,5.044830627797218767e+02,9.323042704611027298e-02,1.005228481865277601e+01,3.507323640602465729e-03,1.000000009874903117e+00,-4.000000000000000327e-05,-1.669800802702546103e-09,0.000000000000000000e+00 +8.120491314941837402e+01,5.044930627182153557e+02,9.326550021060849016e-02,1.005327961737556919e+01,3.507177655200928012e-03,1.000000009873242002e+00,-4.000000000000000327e-05,2.161290108114283350e-09,0.000000000000000000e+00 +8.120590784969337506e+01,5.045030626567139507e+02,9.330057191526167082e-02,1.005427431766038460e+01,3.507031669799390294e-03,1.000000009875391838e+00,-4.000000000000000327e-05,-2.741953268203919488e-09,0.000000000000000000e+00 +8.120690245155961406e+01,5.045130625952176615e+02,9.333564216006981495e-02,1.005526891953644331e+01,3.506885684397852577e-03,1.000000009872664686e+00,-4.000000000000000327e-05,1.564912196650579235e-09,0.000000000000000000e+00 +8.120789695504629435e+01,5.045230625337264883e+02,9.337071094503292257e-02,1.005626342303294329e+01,3.506739698996314859e-03,1.000000009874220996e+00,-4.000000000000000327e-05,-1.089227663121465810e-09,0.000000000000000000e+00 +8.120889136018260501e+01,5.045330624722404309e+02,9.340577827015099366e-02,1.005725782817907721e+01,3.506593713594777142e-03,1.000000009873137863e+00,-4.000000000000000327e-05,1.857988987784551578e-09,0.000000000000000000e+00 +8.120988566699772093e+01,5.045430624107594895e+02,9.344084413542402823e-02,1.005825213500401638e+01,3.506447728193239424e-03,1.000000009874985274e+00,-4.000000000000000327e-05,-2.179779486636039769e-09,0.000000000000000000e+00 +8.121087987552081700e+01,5.045530623492836639e+02,9.347590854085202627e-02,1.005924634353692326e+01,3.506301742791701707e-03,1.000000009872818119e+00,-4.000000000000000327e-05,1.162142798115053643e-09,0.000000000000000000e+00 +8.121187398578101124e+01,5.045630622878129543e+02,9.351097148643497392e-02,1.006024045380693899e+01,3.506155757390163989e-03,1.000000009873973417e+00,-4.000000000000000327e-05,-7.049942601303692644e-10,0.000000000000000000e+00 +8.121286799780745014e+01,5.045730622263473606e+02,9.354603297217288504e-02,1.006123446584319758e+01,3.506009771988626272e-03,1.000000009873272644e+00,-4.000000000000000327e-05,-6.034149689302932372e-10,0.000000000000000000e+00 +8.121386191162925172e+01,5.045830621648868828e+02,9.358109299806574577e-02,1.006222837967481354e+01,3.505863786587088554e-03,1.000000009872672901e+00,-4.000000000000000327e-05,-3.396080558350104449e-10,0.000000000000000000e+00 +8.121485572727551983e+01,5.045930621034315209e+02,9.361615156411356997e-02,1.006322219533088891e+01,3.505717801185550837e-03,1.000000009872335394e+00,-4.000000000000000327e-05,7.664280794458232270e-11,0.000000000000000000e+00 +8.121584944477532986e+01,5.046030620419812749e+02,9.365120867031634377e-02,1.006421591284051154e+01,3.505571815784013119e-03,1.000000009872411555e+00,-4.000000000000000327e-05,6.353265877879892014e-10,0.000000000000000000e+00 +8.121684306415775723e+01,5.046130619805361448e+02,9.368626431667408105e-02,1.006520953223275505e+01,3.505425830382475402e-03,1.000000009873042828e+00,-4.000000000000000327e-05,-4.742511855981381230e-10,0.000000000000000000e+00 +8.121783658545187734e+01,5.046230619190961306e+02,9.372131850318676793e-02,1.006620305353667888e+01,3.505279844980937684e-03,1.000000009872571649e+00,-4.000000000000000327e-05,3.381776019218073542e-10,0.000000000000000000e+00 +8.121883000868672298e+01,5.046330618576612324e+02,9.375637122985440441e-02,1.006719647678132645e+01,3.505133859579399967e-03,1.000000009872907603e+00,-4.000000000000000327e-05,-5.371586094528153155e-10,0.000000000000000000e+00 +8.121982333389131270e+01,5.046430617962314500e+02,9.379142249667700437e-02,1.006818980199572877e+01,3.504987874177862249e-03,1.000000009872374029e+00,-4.000000000000000327e-05,-1.311842584741616826e-09,0.000000000000000000e+00 +8.122081656109467929e+01,5.046530617348068404e+02,9.382647230365455393e-02,1.006918302920890085e+01,3.504841888776324531e-03,1.000000009871071072e+00,-4.000000000000000327e-05,1.607769365708859959e-09,0.000000000000000000e+00 +8.122180969032581288e+01,5.046630616733873467e+02,9.386152065078705309e-02,1.007017615844984348e+01,3.504695903374786814e-03,1.000000009872667794e+00,-4.000000000000000327e-05,-7.935664389244421163e-10,0.000000000000000000e+00 +8.122280272161371784e+01,5.046730616119729689e+02,9.389656753807450185e-02,1.007116918974754682e+01,3.504549917973249096e-03,1.000000009871879758e+00,-4.000000000000000327e-05,4.796753641402526385e-10,0.000000000000000000e+00 +8.122379565498735587e+01,5.046830615505637070e+02,9.393161296551690020e-02,1.007216212313098147e+01,3.504403932571711379e-03,1.000000009872356044e+00,-4.000000000000000327e-05,-1.788951760571249373e-09,0.000000000000000000e+00 +8.122478849047567451e+01,5.046930614891595610e+02,9.396665693311424816e-02,1.007315495862910737e+01,3.504257947170173661e-03,1.000000009870579909e+00,-4.000000000000000327e-05,1.400615098366652634e-09,0.000000000000000000e+00 +8.122578122810763546e+01,5.047030614277605309e+02,9.400169944086654572e-02,1.007414769627086670e+01,3.504111961768635944e-03,1.000000009871970352e+00,-4.000000000000000327e-05,-7.746419832740605378e-10,0.000000000000000000e+00 +8.122677386791215781e+01,5.047130613663666168e+02,9.403674048877379288e-02,1.007514033608519277e+01,3.503965976367098226e-03,1.000000009871201412e+00,-4.000000000000000327e-05,6.876939327577132097e-10,0.000000000000000000e+00 +8.122776640991816066e+01,5.047230613049778185e+02,9.407178007683598964e-02,1.007613287810099933e+01,3.503819990965560509e-03,1.000000009871883977e+00,-4.000000000000000327e-05,-1.434589425350543146e-09,0.000000000000000000e+00 +8.122875885415454889e+01,5.047330612435941362e+02,9.410681820505312212e-02,1.007712532234718950e+01,3.503674005564022791e-03,1.000000009870460227e+00,-4.000000000000000327e-05,6.220448244526096284e-11,0.000000000000000000e+00 +8.122975120065021315e+01,5.047430611822155129e+02,9.414185487342520420e-02,1.007811766885264859e+01,3.503528020162485074e-03,1.000000009870521955e+00,-4.000000000000000327e-05,-2.421290571974169284e-10,0.000000000000000000e+00 +8.123074344943401570e+01,5.047530611208420055e+02,9.417689008195223588e-02,1.007910991764625130e+01,3.503382034760947356e-03,1.000000009870281703e+00,-4.000000000000000327e-05,1.250377293035889232e-09,0.000000000000000000e+00 +8.123173560053483300e+01,5.047630610594736140e+02,9.421192383063420328e-02,1.008010206875685633e+01,3.503236049359409639e-03,1.000000009871522266e+00,-4.000000000000000327e-05,-8.847732208615756187e-10,0.000000000000000000e+00 +8.123272765398149886e+01,5.047730609981103385e+02,9.424695611947112028e-02,1.008109412221330992e+01,3.503090063957871921e-03,1.000000009870644524e+00,-4.000000000000000327e-05,5.627469739809379006e-10,0.000000000000000000e+00 +8.123371960980283291e+01,5.047830609367521788e+02,9.428198694846297301e-02,1.008208607804444057e+01,3.502944078556334204e-03,1.000000009871202744e+00,-4.000000000000000327e-05,-1.638260769690296759e-09,0.000000000000000000e+00 +8.123471146802766896e+01,5.047930608753991351e+02,9.431701631760977533e-02,1.008307793627906612e+01,3.502798093154796486e-03,1.000000009869577822e+00,-4.000000000000000327e-05,-2.760555139021312046e-10,0.000000000000000000e+00 +8.123570322868479820e+01,5.048030608140512072e+02,9.435204422691151338e-02,1.008406969694598665e+01,3.502652107753258769e-03,1.000000009869304041e+00,-4.000000000000000327e-05,1.030216016398821266e-09,0.000000000000000000e+00 +8.123669489180301184e+01,5.048130607527083953e+02,9.438707067636818715e-02,1.008506136007399157e+01,3.502506122351721051e-03,1.000000009870325668e+00,-4.000000000000000327e-05,4.624223605931908206e-10,0.000000000000000000e+00 +8.123768645741108685e+01,5.048230606913706993e+02,9.442209566597981052e-02,1.008605292569185607e+01,3.502360136950183334e-03,1.000000009870784190e+00,-4.000000000000000327e-05,-1.990067361961007998e-09,0.000000000000000000e+00 +8.123867792553778600e+01,5.048330606300381191e+02,9.445711919574636961e-02,1.008704439382833939e+01,3.502214151548645616e-03,1.000000009868811102e+00,-4.000000000000000327e-05,8.916539447196973521e-10,0.000000000000000000e+00 +8.123966929621184363e+01,5.048430605687106549e+02,9.449214126566786442e-02,1.008803576451218476e+01,3.502068166147107899e-03,1.000000009869695061e+00,-4.000000000000000327e-05,6.227183085925928904e-11,0.000000000000000000e+00 +8.124066056946200831e+01,5.048530605073883066e+02,9.452716187574429496e-02,1.008902703777212650e+01,3.501922180745570181e-03,1.000000009869756790e+00,-4.000000000000000327e-05,-8.745795544542995158e-10,0.000000000000000000e+00 +8.124165174531698597e+01,5.048630604460710742e+02,9.456218102597566122e-02,1.009001821363688123e+01,3.501776195344032463e-03,1.000000009868889927e+00,-4.000000000000000327e-05,1.688167100327795421e-09,0.000000000000000000e+00 +8.124264282380546831e+01,5.048730603847589578e+02,9.459719871636196320e-02,1.009100929213515130e+01,3.501630209942494746e-03,1.000000009870563034e+00,-4.000000000000000327e-05,-3.110476120969267370e-09,0.000000000000000000e+00 +8.124363380495616127e+01,5.048830603234519572e+02,9.463221494690320090e-02,1.009200027329562843e+01,3.501484224540957028e-03,1.000000009867480610e+00,-4.000000000000000327e-05,2.808039477046165240e-09,0.000000000000000000e+00 +8.124462468879774235e+01,5.048930602621500725e+02,9.466722971759937433e-02,1.009299115714698303e+01,3.501338239139419311e-03,1.000000009870263051e+00,-4.000000000000000327e-05,-2.275158866357344696e-09,0.000000000000000000e+00 +8.124561547535886064e+01,5.049030602008533037e+02,9.470224302845048348e-02,1.009398194371788193e+01,3.501192253737881593e-03,1.000000009868008854e+00,-4.000000000000000327e-05,1.532834803820972501e-09,0.000000000000000000e+00 +8.124660616466816521e+01,5.049130601395616509e+02,9.473725487945652834e-02,1.009497263303696712e+01,3.501046268336343876e-03,1.000000009869527418e+00,-4.000000000000000327e-05,-2.065125467702202031e-09,0.000000000000000000e+00 +8.124759675675429094e+01,5.049230600782751139e+02,9.477226527061749506e-02,1.009596322513287525e+01,3.500900282934806158e-03,1.000000009867481721e+00,-4.000000000000000327e-05,1.401768879788620182e-09,0.000000000000000000e+00 +8.124858725164585849e+01,5.049330600169936361e+02,9.480727420193339749e-02,1.009695372003422165e+01,3.500754297533268441e-03,1.000000009868870166e+00,-4.000000000000000327e-05,-7.483709544836398294e-10,0.000000000000000000e+00 +8.124957764937147431e+01,5.049430599557172741e+02,9.484228167340423565e-02,1.009794411776961454e+01,3.500608312131730723e-03,1.000000009868128981e+00,-4.000000000000000327e-05,5.271398122647399528e-10,0.000000000000000000e+00 +8.125056794995973064e+01,5.049530598944460280e+02,9.487728768502999566e-02,1.009893441836764261e+01,3.500462326730193006e-03,1.000000009868651007e+00,-4.000000000000000327e-05,-2.026245202832344408e-09,0.000000000000000000e+00 +8.125155815343920551e+01,5.049630598331798979e+02,9.491229223681069138e-02,1.009992462185688389e+01,3.500316341328655288e-03,1.000000009866644612e+00,-4.000000000000000327e-05,2.452768556909761794e-09,0.000000000000000000e+00 +8.125254825983844853e+01,5.049730597719188836e+02,9.494729532874630895e-02,1.010091472826589865e+01,3.500170355927117571e-03,1.000000009869073114e+00,-4.000000000000000327e-05,-2.354772015868171246e-09,0.000000000000000000e+00 +8.125353826918602351e+01,5.049830597106629853e+02,9.498229696083686224e-02,1.010190473762324004e+01,3.500024370525579853e-03,1.000000009866741868e+00,-4.000000000000000327e-05,1.665033419304180552e-09,0.000000000000000000e+00 +8.125452818151045165e+01,5.049930596494122028e+02,9.501729713308233738e-02,1.010289464995743813e+01,3.499878385124042136e-03,1.000000009868390105e+00,-4.000000000000000327e-05,-1.811234970977712152e-09,0.000000000000000000e+00 +8.125551799684026832e+01,5.050030595881665363e+02,9.505229584548273436e-02,1.010388446529701767e+01,3.499732399722504418e-03,1.000000009866597317e+00,-4.000000000000000327e-05,1.709556932140438622e-09,0.000000000000000000e+00 +8.125650771520396631e+01,5.050130595269259857e+02,9.508729309803805319e-02,1.010487418367048207e+01,3.499586414320966701e-03,1.000000009868289297e+00,-4.000000000000000327e-05,-2.287261212171307369e-09,0.000000000000000000e+00 +8.125749733663005259e+01,5.050230594656905510e+02,9.512228889074830773e-02,1.010586380510632765e+01,3.499440428919428983e-03,1.000000009866025774e+00,-4.000000000000000327e-05,6.956252861696124917e-10,0.000000000000000000e+00 +8.125848686114699149e+01,5.050330594044601753e+02,9.515728322361348412e-02,1.010685332963302940e+01,3.499294443517891266e-03,1.000000009866714112e+00,-4.000000000000000327e-05,1.581468187826206285e-09,0.000000000000000000e+00 +8.125947628878326157e+01,5.050430593432349156e+02,9.519227609663358236e-02,1.010784275727905523e+01,3.499148458116353548e-03,1.000000009868278861e+00,-4.000000000000000327e-05,-3.271425708775133139e-09,0.000000000000000000e+00 +8.126046561956729875e+01,5.050530592820147717e+02,9.522726750980860244e-02,1.010883208807285705e+01,3.499002472714815831e-03,1.000000009865042339e+00,-4.000000000000000327e-05,2.461216649279204403e-09,0.000000000000000000e+00 +8.126145485352755315e+01,5.050630592207997438e+02,9.526225746313854437e-02,1.010982132204286721e+01,3.498856487313278113e-03,1.000000009867477058e+00,-4.000000000000000327e-05,-1.195597140428723953e-09,0.000000000000000000e+00 +8.126244399069244650e+01,5.050730591595898318e+02,9.529724595662340814e-02,1.011081045921751453e+01,3.498710501911740395e-03,1.000000009866294448e+00,-4.000000000000000327e-05,2.707531402149926152e-10,0.000000000000000000e+00 +8.126343303109037208e+01,5.050830590983850357e+02,9.533223299026319375e-02,1.011179949962520475e+01,3.498564516510202678e-03,1.000000009866562234e+00,-4.000000000000000327e-05,-4.124561954379824640e-10,0.000000000000000000e+00 +8.126442197474975160e+01,5.050930590371853555e+02,9.536721856405788733e-02,1.011278844329433468e+01,3.498418531108664960e-03,1.000000009866154338e+00,-4.000000000000000327e-05,3.779159862841023368e-10,0.000000000000000000e+00 +8.126541082169894992e+01,5.051030589759907343e+02,9.540220267800750276e-02,1.011377729025328520e+01,3.498272545707127243e-03,1.000000009866528039e+00,-4.000000000000000327e-05,-1.001361947522192412e-09,0.000000000000000000e+00 +8.126639957196633191e+01,5.051130589148012291e+02,9.543718533211204003e-02,1.011476604053042472e+01,3.498126560305589525e-03,1.000000009865537942e+00,-4.000000000000000327e-05,-9.264458071187142279e-10,0.000000000000000000e+00 +8.126738822558026243e+01,5.051230588536168398e+02,9.547216652637149914e-02,1.011575469415410566e+01,3.497980574904051808e-03,1.000000009864622008e+00,-4.000000000000000327e-05,2.411465302919212921e-09,0.000000000000000000e+00 +8.126837678256907793e+01,5.051330587924375664e+02,9.550714626078586622e-02,1.011674325115266804e+01,3.497834589502514090e-03,1.000000009867005879e+00,-4.000000000000000327e-05,-1.903797098934819557e-09,0.000000000000000000e+00 +8.126936524296110065e+01,5.051430587312634088e+02,9.554212453535515515e-02,1.011773171155444118e+01,3.497688604100976373e-03,1.000000009865124051e+00,-4.000000000000000327e-05,-1.157442003972352605e-09,0.000000000000000000e+00 +8.127035360678463860e+01,5.051530586700943672e+02,9.557710135007935204e-02,1.011872007538773310e+01,3.497542618699438655e-03,1.000000009863980077e+00,-4.000000000000000327e-05,1.006120264825633302e-09,0.000000000000000000e+00 +8.127134187406799981e+01,5.051630586089303847e+02,9.561207670495847077e-02,1.011970834268084296e+01,3.497396633297900938e-03,1.000000009864974393e+00,-4.000000000000000327e-05,9.403806492196260370e-10,0.000000000000000000e+00 +8.127233004483946388e+01,5.051730585477715181e+02,9.564705059999249748e-02,1.012069651346205745e+01,3.497250647896363220e-03,1.000000009865903650e+00,-4.000000000000000327e-05,-1.366550328415767171e-09,0.000000000000000000e+00 +8.127331811912731041e+01,5.051830584866177674e+02,9.568202303518143215e-02,1.012168458775964730e+01,3.497104662494825503e-03,1.000000009864553396e+00,-4.000000000000000327e-05,-4.654500958267744046e-10,0.000000000000000000e+00 +8.127430609695979058e+01,5.051930584254691325e+02,9.571699401052528866e-02,1.012267256560186723e+01,3.496958677093287785e-03,1.000000009864093542e+00,-4.000000000000000327e-05,1.815455037687347439e-09,0.000000000000000000e+00 +8.127529397836514136e+01,5.052030583643256136e+02,9.575196352602405314e-02,1.012366044701696133e+01,3.496812691691750068e-03,1.000000009865886996e+00,-4.000000000000000327e-05,-1.814733048028214769e-09,0.000000000000000000e+00 +8.127628176337159971e+01,5.052130583031871538e+02,9.578693158167772559e-02,1.012464823203316122e+01,3.496666706290212350e-03,1.000000009864094430e+00,-4.000000000000000327e-05,-4.440043945456271585e-10,0.000000000000000000e+00 +8.127726945200737418e+01,5.052230582420538099e+02,9.582189817748630600e-02,1.012563592067867901e+01,3.496520720888674633e-03,1.000000009863655892e+00,-4.000000000000000327e-05,4.575377654210368704e-10,0.000000000000000000e+00 +8.127825704430067333e+01,5.052330581809255818e+02,9.585686331344979438e-02,1.012662351298171792e+01,3.496374735487136915e-03,1.000000009864107753e+00,-4.000000000000000327e-05,8.798623564464917148e-10,0.000000000000000000e+00 +8.127924454027967727e+01,5.052430581198024697e+02,9.589182698956819073e-02,1.012761100897046695e+01,3.496228750085599198e-03,1.000000009864976613e+00,-4.000000000000000327e-05,-2.830990885980915102e-09,0.000000000000000000e+00 +8.128023193997256612e+01,5.052530580586844735e+02,9.592678920584149505e-02,1.012859840867310091e+01,3.496082764684061480e-03,1.000000009862181294e+00,-4.000000000000000327e-05,2.069305481593479790e-09,0.000000000000000000e+00 +8.128121924340750581e+01,5.052630579975715364e+02,9.596174996226970733e-02,1.012958571211777681e+01,3.495936779282523763e-03,1.000000009864224326e+00,-4.000000000000000327e-05,-8.277129075605274989e-10,0.000000000000000000e+00 +8.128220645061263383e+01,5.052730579364637151e+02,9.599670925885282757e-02,1.013057291933264636e+01,3.495790793880986045e-03,1.000000009863407202e+00,-4.000000000000000327e-05,-5.983507903689585461e-10,0.000000000000000000e+00 +8.128319356161608766e+01,5.052830578753610098e+02,9.603166709559085579e-02,1.013156003034583996e+01,3.495644808479448327e-03,1.000000009862816563e+00,-4.000000000000000327e-05,9.261842991422369966e-10,0.000000000000000000e+00 +8.128418057644599060e+01,5.052930578142634204e+02,9.606662347248377809e-02,1.013254704518547733e+01,3.495498823077910610e-03,1.000000009863730721e+00,-4.000000000000000327e-05,9.022008396185334760e-11,0.000000000000000000e+00 +8.128516749513043749e+01,5.053030577531709469e+02,9.610157838953160836e-02,1.013353396387966576e+01,3.495352837676372892e-03,1.000000009863819761e+00,-4.000000000000000327e-05,-1.293805513664826762e-09,0.000000000000000000e+00 +8.128615431769753741e+01,5.053130576920835324e+02,9.613653184673434660e-02,1.013452078645649657e+01,3.495206852274835175e-03,1.000000009862543005e+00,-4.000000000000000327e-05,4.133829875012780400e-10,0.000000000000000000e+00 +8.128714104417535680e+01,5.053230576310012339e+02,9.617148384409197892e-02,1.013550751294404684e+01,3.495060866873297457e-03,1.000000009862950900e+00,-4.000000000000000327e-05,-2.705142783234469346e-10,0.000000000000000000e+00 +8.128812767459196209e+01,5.053330575699240512e+02,9.620643438160451921e-02,1.013649414337038301e+01,3.494914881471759740e-03,1.000000009862684003e+00,-4.000000000000000327e-05,2.939484511630779027e-10,0.000000000000000000e+00 +8.128911420897540552e+01,5.053430575088519845e+02,9.624138345927195359e-02,1.013748067776355555e+01,3.494768896070222022e-03,1.000000009862973993e+00,-4.000000000000000327e-05,-1.552946198210908555e-09,0.000000000000000000e+00 +8.129010064735372509e+01,5.053530574477849768e+02,9.627633107709429594e-02,1.013846711615160245e+01,3.494622910668684305e-03,1.000000009861442107e+00,-4.000000000000000327e-05,1.481284286881157851e-09,0.000000000000000000e+00 +8.129108698975494463e+01,5.053630573867230851e+02,9.631127723507153238e-02,1.013945345856254576e+01,3.494476925267146587e-03,1.000000009862903161e+00,-4.000000000000000327e-05,-1.567882576779079756e-09,0.000000000000000000e+00 +8.129207323620707371e+01,5.053730573256663092e+02,9.634622193320366290e-02,1.014043970502439862e+01,3.494330939865608870e-03,1.000000009861356842e+00,-4.000000000000000327e-05,2.470038031090862833e-10,0.000000000000000000e+00 +8.129305938673810772e+01,5.053830572646146493e+02,9.638116517149070139e-02,1.014142585556515463e+01,3.494184954464071152e-03,1.000000009861600425e+00,-4.000000000000000327e-05,-3.897950441530025083e-10,0.000000000000000000e+00 +8.129404544137602784e+01,5.053930572035680484e+02,9.641610694993263397e-02,1.014241191021279853e+01,3.494038969062533435e-03,1.000000009861216066e+00,-4.000000000000000327e-05,1.666530205736698134e-10,0.000000000000000000e+00 +8.129503140014880103e+01,5.054030571425265634e+02,9.645104726852946064e-02,1.014339786899529905e+01,3.493892983660995717e-03,1.000000009861380379e+00,-4.000000000000000327e-05,7.860480835740445276e-11,0.000000000000000000e+00 +8.129601726308439424e+01,5.054130570814901944e+02,9.648598612728118140e-02,1.014438373194061249e+01,3.493746998259458000e-03,1.000000009861457873e+00,-4.000000000000000327e-05,1.165446437779954154e-09,0.000000000000000000e+00 +8.129700303021074603e+01,5.054230570204589412e+02,9.652092352618779625e-02,1.014536949907668095e+01,3.493601012857920282e-03,1.000000009862606731e+00,-4.000000000000000327e-05,-2.067775875680962787e-09,0.000000000000000000e+00 +8.129798870155578072e+01,5.054330569594327471e+02,9.655585946524930518e-02,1.014635517043143409e+01,3.493455027456382565e-03,1.000000009860568584e+00,-4.000000000000000327e-05,-4.893393119637562580e-10,0.000000000000000000e+00 +8.129897427714740843e+01,5.054430568984116690e+02,9.659079394446570821e-02,1.014734074603278380e+01,3.493309042054844847e-03,1.000000009860086303e+00,-4.000000000000000327e-05,2.236939498670175827e-09,0.000000000000000000e+00 +8.129995975701353927e+01,5.054530568373957067e+02,9.662572696383700532e-02,1.014832622590863309e+01,3.493163056653307130e-03,1.000000009862290762e+00,-4.000000000000000327e-05,-3.046345892167208680e-09,0.000000000000000000e+00 +8.130094514118205495e+01,5.054630567763848035e+02,9.666065852336319653e-02,1.014931161008687255e+01,3.493017071251769412e-03,1.000000009859288941e+00,-4.000000000000000327e-05,1.945307422219097551e-09,0.000000000000000000e+00 +8.130193042968083716e+01,5.054730567153790162e+02,9.669558862304428182e-02,1.015029689859537143e+01,3.492871085850231695e-03,1.000000009861205630e+00,-4.000000000000000327e-05,-1.092425906789967951e-09,0.000000000000000000e+00 +8.130291562253773918e+01,5.054830566543783448e+02,9.673051726288024732e-02,1.015128209146199545e+01,3.492725100448693977e-03,1.000000009860129380e+00,-4.000000000000000327e-05,6.383433977634827479e-10,0.000000000000000000e+00 +8.130390071978061428e+01,5.054930565933827893e+02,9.676544444287110691e-02,1.015226718871458900e+01,3.492579115047156259e-03,1.000000009860758210e+00,-4.000000000000000327e-05,-2.022293198455006775e-09,0.000000000000000000e+00 +8.130488572143730153e+01,5.055030565323922929e+02,9.680037016301686059e-02,1.015325219038098759e+01,3.492433129645618542e-03,1.000000009858766248e+00,-4.000000000000000327e-05,1.900747764007661971e-09,0.000000000000000000e+00 +8.130587062753561156e+01,5.055130564714069124e+02,9.683529442331749448e-02,1.015423709648900896e+01,3.492287144244080824e-03,1.000000009860638306e+00,-4.000000000000000327e-05,-4.193730029793298713e-10,0.000000000000000000e+00 +8.130685543810335503e+01,5.055230564104266477e+02,9.687021722377302246e-02,1.015522190706646377e+01,3.492141158842543107e-03,1.000000009860225303e+00,-4.000000000000000327e-05,-1.667507598729500648e-09,0.000000000000000000e+00 +8.130784015316832836e+01,5.055330563494514422e+02,9.690513856438343065e-02,1.015620662214114311e+01,3.491995173441005389e-03,1.000000009858583283e+00,-4.000000000000000327e-05,-2.119823033733297902e-11,0.000000000000000000e+00 +8.130882477275829956e+01,5.055430562884813526e+02,9.694005844514871906e-02,1.015719124174082566e+01,3.491849188039467672e-03,1.000000009858562411e+00,-4.000000000000000327e-05,8.477858832224018886e-10,0.000000000000000000e+00 +8.130980929690105086e+01,5.055530562275163788e+02,9.697497686606890155e-02,1.015817576589327942e+01,3.491703202637929954e-03,1.000000009859397077e+00,-4.000000000000000327e-05,9.292940673750817454e-10,0.000000000000000000e+00 +8.131079372562432184e+01,5.055630561665564642e+02,9.700989382714396425e-02,1.015916019462625819e+01,3.491557217236392237e-03,1.000000009860311900e+00,-4.000000000000000327e-05,-1.621008331089341833e-09,0.000000000000000000e+00 +8.131177805895586630e+01,5.055730561056016654e+02,9.704480932837390716e-02,1.016014452796750156e+01,3.491411231834854519e-03,1.000000009858716288e+00,-4.000000000000000327e-05,-1.312092669506692301e-09,0.000000000000000000e+00 +8.131276229692339541e+01,5.055830560446519826e+02,9.707972336975874417e-02,1.016112876594473313e+01,3.491265246433316802e-03,1.000000009857424876e+00,-4.000000000000000327e-05,1.848749800096330754e-09,0.000000000000000000e+00 +8.131374643955462034e+01,5.055930559837073588e+02,9.711463595129846138e-02,1.016211290858566585e+01,3.491119261031779084e-03,1.000000009859244310e+00,-4.000000000000000327e-05,-1.319116195466025903e-09,0.000000000000000000e+00 +8.131473048687725225e+01,5.056030559227678509e+02,9.714954707299305880e-02,1.016309695591800200e+01,3.490973275630241367e-03,1.000000009857946237e+00,-4.000000000000000327e-05,1.805328678713280721e-10,0.000000000000000000e+00 +8.131571443891897388e+01,5.056130558618334589e+02,9.718445673484253644e-02,1.016408090796942432e+01,3.490827290228703649e-03,1.000000009858123873e+00,-4.000000000000000327e-05,8.352710398983295063e-10,0.000000000000000000e+00 +8.131669829570745378e+01,5.056230558009041260e+02,9.721936493684689429e-02,1.016506476476760668e+01,3.490681304827165932e-03,1.000000009858945660e+00,-4.000000000000000327e-05,-1.200550314357482509e-09,0.000000000000000000e+00 +8.131768205727036047e+01,5.056330557399799090e+02,9.725427167900613235e-02,1.016604852634020872e+01,3.490535319425628214e-03,1.000000009857764605e+00,-4.000000000000000327e-05,-4.300187415635225264e-10,0.000000000000000000e+00 +8.131866572363533407e+01,5.056430556790608080e+02,9.728917696132025061e-02,1.016703219271487413e+01,3.490389334024090497e-03,1.000000009857341610e+00,-4.000000000000000327e-05,1.303500504884162632e-09,0.000000000000000000e+00 +8.131964929483000049e+01,5.056530556181467659e+02,9.732408078378923522e-02,1.016801576391923589e+01,3.490243348622552779e-03,1.000000009858623695e+00,-4.000000000000000327e-05,-1.519242022749723637e-09,0.000000000000000000e+00 +8.132063277088198561e+01,5.056630555572378398e+02,9.735898314641310003e-02,1.016899923998091460e+01,3.490097363221015062e-03,1.000000009857129557e+00,-4.000000000000000327e-05,2.741177302331550218e-10,0.000000000000000000e+00 +8.132161615181888692e+01,5.056730554963340296e+02,9.739388404919184505e-02,1.016998262092751304e+01,3.489951377819477344e-03,1.000000009857399119e+00,-4.000000000000000327e-05,-6.713598195599578746e-10,0.000000000000000000e+00 +8.132259943766830190e+01,5.056830554354352785e+02,9.742878349212545641e-02,1.017096590678662515e+01,3.489805392417939627e-03,1.000000009856738981e+00,-4.000000000000000327e-05,1.146142114037787474e-09,0.000000000000000000e+00 +8.132358262845781383e+01,5.056930553745416432e+02,9.746368147521394798e-02,1.017194909758582888e+01,3.489659407016401909e-03,1.000000009857865857e+00,-4.000000000000000327e-05,-1.633438625997312508e-09,0.000000000000000000e+00 +8.132456572421499175e+01,5.057030553136530671e+02,9.749857799845731976e-02,1.017293219335269150e+01,3.489513421614864191e-03,1.000000009856260030e+00,-4.000000000000000327e-05,1.696392377061399851e-10,0.000000000000000000e+00 +8.132554872496737630e+01,5.057130552527696068e+02,9.753347306185555787e-02,1.017391519411476253e+01,3.489367436213326474e-03,1.000000009856426786e+00,-4.000000000000000327e-05,-8.058077649010754054e-10,0.000000000000000000e+00 +8.132653163074250813e+01,5.057230551918912624e+02,9.756836666540866232e-02,1.017489809989958260e+01,3.489221450811788756e-03,1.000000009855634753e+00,-4.000000000000000327e-05,9.466388348440101056e-10,0.000000000000000000e+00 +8.132751444156791365e+01,5.057330551310179771e+02,9.760325880911664698e-02,1.017588091073467638e+01,3.489075465410251039e-03,1.000000009856565120e+00,-4.000000000000000327e-05,-9.964392603554178846e-11,0.000000000000000000e+00 +8.132849715747110508e+01,5.057430550701498078e+02,9.763814949297949797e-02,1.017686362664755784e+01,3.488929480008713321e-03,1.000000009856467198e+00,-4.000000000000000327e-05,-2.754595831629596694e-10,0.000000000000000000e+00 +8.132947977847958043e+01,5.057530550092866974e+02,9.767303871699721529e-02,1.017784624766572499e+01,3.488783494607175604e-03,1.000000009856196526e+00,-4.000000000000000327e-05,-1.430313398864155333e-09,0.000000000000000000e+00 +8.133046230462083770e+01,5.057630549484287030e+02,9.770792648116981283e-02,1.017882877381666340e+01,3.488637509205637886e-03,1.000000009854791205e+00,-4.000000000000000327e-05,1.948252759793592442e-09,0.000000000000000000e+00 +8.133144473592233226e+01,5.057730548875758245e+02,9.774281278549727670e-02,1.017981120512784443e+01,3.488491523804100169e-03,1.000000009856705230e+00,-4.000000000000000327e-05,-1.191668201304318786e-09,0.000000000000000000e+00 +8.133242707241153369e+01,5.057830548267280051e+02,9.777769762997960690e-02,1.018079354162673056e+01,3.488345538402562451e-03,1.000000009855534611e+00,-4.000000000000000327e-05,1.831078126616792254e-10,0.000000000000000000e+00 +8.133340931411588315e+01,5.057930547658853015e+02,9.781258101461680343e-02,1.018177578334076472e+01,3.488199553001024734e-03,1.000000009855714467e+00,-4.000000000000000327e-05,-1.299512657540862611e-09,0.000000000000000000e+00 +8.133439146106282180e+01,5.058030547050476571e+02,9.784746293940886630e-02,1.018275793029738097e+01,3.488053567599487016e-03,1.000000009854438154e+00,-4.000000000000000327e-05,-1.245825580385741343e-10,0.000000000000000000e+00 +8.133537351327976239e+01,5.058130546442151285e+02,9.788234340435579550e-02,1.018373998252399737e+01,3.487907582197949299e-03,1.000000009854315808e+00,-4.000000000000000327e-05,1.857612374066222784e-09,0.000000000000000000e+00 +8.133635547079410344e+01,5.058230545833877159e+02,9.791722240945759104e-02,1.018472194004802134e+01,3.487761596796411581e-03,1.000000009856139904e+00,-4.000000000000000327e-05,-2.731620625558762485e-09,0.000000000000000000e+00 +8.133733733363325769e+01,5.058330545225653623e+02,9.795209995471425291e-02,1.018570380289684785e+01,3.487615611394873864e-03,1.000000009853457827e+00,-4.000000000000000327e-05,8.370479814727990270e-10,0.000000000000000000e+00 +8.133831910182459524e+01,5.058430544617481246e+02,9.798697604012578111e-02,1.018668557109785233e+01,3.487469625993336146e-03,1.000000009854279615e+00,-4.000000000000000327e-05,1.500995893129027988e-09,0.000000000000000000e+00 +8.133930077539547199e+01,5.058530544009359460e+02,9.802185066569216176e-02,1.018766724467840490e+01,3.487323640591798429e-03,1.000000009855753103e+00,-4.000000000000000327e-05,-2.595778739349012659e-09,0.000000000000000000e+00 +8.134028235437325804e+01,5.058630543401288833e+02,9.805672383141340875e-02,1.018864882366585967e+01,3.487177655190260711e-03,1.000000009853205141e+00,-4.000000000000000327e-05,1.443143179317474812e-09,0.000000000000000000e+00 +8.134126383878528088e+01,5.058730542793268796e+02,9.809159553728952208e-02,1.018963030808755299e+01,3.487031669788722994e-03,1.000000009854621563e+00,-4.000000000000000327e-05,-1.140552683033687690e-09,0.000000000000000000e+00 +8.134224522865886797e+01,5.058830542185299919e+02,9.812646578332048786e-02,1.019061169797081590e+01,3.486885684387185276e-03,1.000000009853502236e+00,-4.000000000000000327e-05,7.064369027768277769e-10,0.000000000000000000e+00 +8.134322652402134679e+01,5.058930541577382201e+02,9.816133456950631997e-02,1.019159299334295987e+01,3.486739698985647559e-03,1.000000009854195460e+00,-4.000000000000000327e-05,-2.246015827965327908e-09,0.000000000000000000e+00 +8.134420772490000218e+01,5.059030540969515073e+02,9.819620189584700454e-02,1.019257419423128752e+01,3.486593713584109841e-03,1.000000009851991667e+00,-4.000000000000000327e-05,1.061443665649635907e-09,0.000000000000000000e+00 +8.134518883132213318e+01,5.059130540361699104e+02,9.823106776234255544e-02,1.019355530066308368e+01,3.486447728182572123e-03,1.000000009853033056e+00,-4.000000000000000327e-05,1.395174528646397683e-09,0.000000000000000000e+00 +8.134616984331501044e+01,5.059230539753933726e+02,9.826593216899295880e-02,1.019453631266562610e+01,3.486301742781034406e-03,1.000000009854401739e+00,-4.000000000000000327e-05,-1.256321192306547009e-09,0.000000000000000000e+00 +8.134715076090589037e+01,5.059330539146219508e+02,9.830079511579821461e-02,1.019551723026617651e+01,3.486155757379496688e-03,1.000000009853169392e+00,-4.000000000000000327e-05,-1.364428178148063554e-09,0.000000000000000000e+00 +8.134813158412202938e+01,5.059430538538555879e+02,9.833565660275832288e-02,1.019649805349198068e+01,3.486009771977958971e-03,1.000000009851831129e+00,-4.000000000000000327e-05,1.063437146281472548e-09,0.000000000000000000e+00 +8.134911231299065548e+01,5.059530537930943410e+02,9.837051662987329748e-02,1.019747878237027372e+01,3.485863786576421253e-03,1.000000009852874072e+00,-4.000000000000000327e-05,-1.369672134700245860e-09,0.000000000000000000e+00 +8.135009294753899667e+01,5.059630537323381532e+02,9.840537519714312453e-02,1.019845941692828006e+01,3.485717801174883536e-03,1.000000009851530924e+00,-4.000000000000000327e-05,2.410347522325486947e-09,0.000000000000000000e+00 +8.135107348779426673e+01,5.059730536715870812e+02,9.844023230456780404e-02,1.019943995719320640e+01,3.485571815773345818e-03,1.000000009853894367e+00,-4.000000000000000327e-05,-2.385893703694251336e-09,0.000000000000000000e+00 +8.135205393378365102e+01,5.059830536108410683e+02,9.847508795214733601e-02,1.020042040319225229e+01,3.485425830371808101e-03,1.000000009851555127e+00,-4.000000000000000327e-05,-9.868379823687298843e-10,0.000000000000000000e+00 +8.135303428553433491e+01,5.059930535501001714e+02,9.850994213988172044e-02,1.020140075495259602e+01,3.485279844970270383e-03,1.000000009850587679e+00,-4.000000000000000327e-05,2.906207978404613583e-09,0.000000000000000000e+00 +8.135401454307348956e+01,5.060030534893643335e+02,9.854479486777095731e-02,1.020238101250140872e+01,3.485133859568732666e-03,1.000000009853436511e+00,-4.000000000000000327e-05,-3.659047689595301412e-09,0.000000000000000000e+00 +8.135499470642827191e+01,5.060130534286336115e+02,9.857964613581504665e-02,1.020336117586585090e+01,3.484987874167194948e-03,1.000000009849850047e+00,-4.000000000000000327e-05,1.495296858793673573e-09,0.000000000000000000e+00 +8.135597477562582469e+01,5.060230533679079485e+02,9.861449594401398844e-02,1.020434124507305995e+01,3.484841888765657231e-03,1.000000009851315541e+00,-4.000000000000000327e-05,-1.300580060242125980e-10,0.000000000000000000e+00 +8.135695475069327642e+01,5.060330533071874015e+02,9.864934429236776881e-02,1.020532122015017151e+01,3.484695903364119513e-03,1.000000009851188087e+00,-4.000000000000000327e-05,7.017915097674593866e-10,0.000000000000000000e+00 +8.135793463165775563e+01,5.060430532464719136e+02,9.868419118087640163e-02,1.020630110112430167e+01,3.484549917962581796e-03,1.000000009851875760e+00,-4.000000000000000327e-05,-1.568021208846005231e-09,0.000000000000000000e+00 +8.135891441854636241e+01,5.060530531857615415e+02,9.871903660953988691e-02,1.020728088802255584e+01,3.484403932561044078e-03,1.000000009850339433e+00,-4.000000000000000327e-05,4.523877417671023644e-10,0.000000000000000000e+00 +8.135989411138618266e+01,5.060630531250562285e+02,9.875388057835821076e-02,1.020826058087202348e+01,3.484257947159506361e-03,1.000000009850782634e+00,-4.000000000000000327e-05,-6.473664319932681115e-10,0.000000000000000000e+00 +8.136087371020428805e+01,5.060730530643560314e+02,9.878872308733138707e-02,1.020924017969978514e+01,3.484111961757968643e-03,1.000000009850148475e+00,-4.000000000000000327e-05,6.755381972812859085e-10,0.000000000000000000e+00 +8.136185321502776446e+01,5.060830530036608934e+02,9.882356413645940196e-02,1.021021968453290540e+01,3.483965976356430926e-03,1.000000009850810168e+00,-4.000000000000000327e-05,-1.141270320291512828e-09,0.000000000000000000e+00 +8.136283262588365517e+01,5.060930529429708713e+02,9.885840372574226931e-02,1.021119909539843817e+01,3.483819990954893208e-03,1.000000009849692395e+00,-4.000000000000000327e-05,1.299186776307538398e-09,0.000000000000000000e+00 +8.136381194279898921e+01,5.061030528822859083e+02,9.889324185517997523e-02,1.021217841232342138e+01,3.483674005553355491e-03,1.000000009850964711e+00,-4.000000000000000327e-05,-1.272100666874429470e-09,0.000000000000000000e+00 +8.136479116580080984e+01,5.061130528216060611e+02,9.892807852477253361e-02,1.021315763533488408e+01,3.483528020151817773e-03,1.000000009849719040e+00,-4.000000000000000327e-05,-1.455912546496350967e-09,0.000000000000000000e+00 +8.136577029491611768e+01,5.061230527609312730e+02,9.896291373451993056e-02,1.021413676445983754e+01,3.483382034750280055e-03,1.000000009848293514e+00,-4.000000000000000327e-05,2.594811892513093815e-09,0.000000000000000000e+00 +8.136674933017192757e+01,5.061330527002616009e+02,9.899774748442216610e-02,1.021511579972528239e+01,3.483236049348742338e-03,1.000000009850833926e+00,-4.000000000000000327e-05,-2.103539207857269638e-09,0.000000000000000000e+00 +8.136772827159521171e+01,5.061430526395969878e+02,9.903257977447924021e-02,1.021609474115821037e+01,3.483090063947204620e-03,1.000000009848774685e+00,-4.000000000000000327e-05,-7.324756339066564808e-10,0.000000000000000000e+00 +8.136870711921295651e+01,5.061530525789374906e+02,9.906741060469115290e-02,1.021707358878559191e+01,3.482944078545666903e-03,1.000000009848057703e+00,-4.000000000000000327e-05,1.139314055606660298e-09,0.000000000000000000e+00 +8.136968587305211997e+01,5.061630525182830524e+02,9.910223997505791804e-02,1.021805234263439033e+01,3.482798093144129185e-03,1.000000009849172811e+00,-4.000000000000000327e-05,-2.062396826530901523e-10,0.000000000000000000e+00 +8.137066453313964587e+01,5.061730524576336734e+02,9.913706788557952176e-02,1.021903100273155651e+01,3.482652107742591468e-03,1.000000009848970972e+00,-4.000000000000000327e-05,-1.070098458930291295e-09,0.000000000000000000e+00 +8.137164309950247798e+01,5.061830523969894102e+02,9.917189433625596406e-02,1.022000956910402536e+01,3.482506122341053750e-03,1.000000009847923810e+00,-4.000000000000000327e-05,3.946309199569930443e-10,0.000000000000000000e+00 +8.137262157216753167e+01,5.061930523363502061e+02,9.920671932708723106e-02,1.022098804177871934e+01,3.482360136939516033e-03,1.000000009848309945e+00,-4.000000000000000327e-05,4.686548994719665061e-10,0.000000000000000000e+00 +8.137359995116172229e+01,5.062030522757161179e+02,9.924154285807333664e-02,1.022196642078255024e+01,3.482214151537978315e-03,1.000000009848768467e+00,-4.000000000000000327e-05,-8.579588832837279238e-10,0.000000000000000000e+00 +8.137457823651195099e+01,5.062130522150870888e+02,9.927636492921428080e-02,1.022294470614241568e+01,3.482068166136440598e-03,1.000000009847929139e+00,-4.000000000000000327e-05,1.180373853591833251e-10,0.000000000000000000e+00 +8.137555642824510471e+01,5.062230521544631756e+02,9.931118554051006353e-02,1.022392289788519903e+01,3.481922180734902880e-03,1.000000009848044602e+00,-4.000000000000000327e-05,-3.248608863442852477e-10,0.000000000000000000e+00 +8.137653452638804197e+01,5.062330520938443215e+02,9.934600469196068484e-02,1.022490099603777303e+01,3.481776195333365163e-03,1.000000009847726856e+00,-4.000000000000000327e-05,-3.389683464379710237e-10,0.000000000000000000e+00 +8.137751253096763548e+01,5.062430520332305832e+02,9.938082238356613085e-02,1.022587900062699617e+01,3.481630209931827445e-03,1.000000009847395344e+00,-4.000000000000000327e-05,6.675567712353862602e-11,0.000000000000000000e+00 +8.137849044201072957e+01,5.062530519726219040e+02,9.941563861532641544e-02,1.022685691167971456e+01,3.481484224530289728e-03,1.000000009847460625e+00,-4.000000000000000327e-05,-9.744081765465406994e-10,0.000000000000000000e+00 +8.137946825954415431e+01,5.062630519120182839e+02,9.945045338724152473e-02,1.022783472922276182e+01,3.481338239128752010e-03,1.000000009846507831e+00,-4.000000000000000327e-05,2.445905256858818705e-10,0.000000000000000000e+00 +8.138044598359472559e+01,5.062730518514197797e+02,9.948526669931147259e-02,1.022881245328295741e+01,3.481192253727214293e-03,1.000000009846746973e+00,-4.000000000000000327e-05,-1.817002096033163721e-12,0.000000000000000000e+00 +8.138142361418924509e+01,5.062830517908263346e+02,9.952007855153624516e-02,1.022979008388711009e+01,3.481046268325676575e-03,1.000000009846745197e+00,-4.000000000000000327e-05,1.365153288283272417e-10,0.000000000000000000e+00 +8.138240115135452868e+01,5.062930517302380053e+02,9.955488894391585630e-02,1.023076762106201443e+01,3.480900282924138858e-03,1.000000009846878646e+00,-4.000000000000000327e-05,-1.209218859419560722e-09,0.000000000000000000e+00 +8.138337859511733541e+01,5.063030516696547352e+02,9.958969787645029215e-02,1.023174506483445256e+01,3.480754297522601140e-03,1.000000009845696702e+00,-4.000000000000000327e-05,-3.298804303972696759e-10,0.000000000000000000e+00 +8.138435594550445273e+01,5.063130516090765241e+02,9.962450534913955269e-02,1.023272241523119241e+01,3.480608312121063423e-03,1.000000009845374294e+00,-4.000000000000000327e-05,9.083938982378093771e-10,0.000000000000000000e+00 +8.138533320254262549e+01,5.063230515485034289e+02,9.965931136198365181e-02,1.023369967227899124e+01,3.480462326719525705e-03,1.000000009846262028e+00,-4.000000000000000327e-05,-1.225471775891953048e-09,0.000000000000000000e+00 +8.138631036625861270e+01,5.063330514879353927e+02,9.969411591498257563e-02,1.023467683600459388e+01,3.480316341317987987e-03,1.000000009845064541e+00,-4.000000000000000327e-05,7.015376589147010456e-10,0.000000000000000000e+00 +8.138728743667913079e+01,5.063430514273724725e+02,9.972891900813632415e-02,1.023565390643472917e+01,3.480170355916450270e-03,1.000000009845749993e+00,-4.000000000000000327e-05,-7.622876375053450682e-10,0.000000000000000000e+00 +8.138826441383089616e+01,5.063530513668146114e+02,9.976372064144489737e-02,1.023663088359611706e+01,3.480024370514912552e-03,1.000000009845005255e+00,-4.000000000000000327e-05,-4.250488794782455485e-11,0.000000000000000000e+00 +8.138924129774062521e+01,5.063630513062618093e+02,9.979852081490829530e-02,1.023760776751546153e+01,3.479878385113374835e-03,1.000000009844963733e+00,-4.000000000000000327e-05,9.904356677706807194e-10,0.000000000000000000e+00 +8.139021808843500594e+01,5.063730512457141231e+02,9.983331952852651792e-02,1.023858455821945590e+01,3.479732399711837117e-03,1.000000009845931181e+00,-4.000000000000000327e-05,-1.396108734664240462e-09,0.000000000000000000e+00 +8.139119478594071211e+01,5.063830511851714959e+02,9.986811678229956524e-02,1.023956125573478104e+01,3.479586414310299400e-03,1.000000009844567606e+00,-4.000000000000000327e-05,2.373679464315239118e-10,0.000000000000000000e+00 +8.139217139028441750e+01,5.063930511246339279e+02,9.990291257622743726e-02,1.024053786008810185e+01,3.479440428908761682e-03,1.000000009844799420e+00,-4.000000000000000327e-05,-1.568051224047185496e-09,0.000000000000000000e+00 +8.139314790149278167e+01,5.064030510641014757e+02,9.993770691031012010e-02,1.024151437130607434e+01,3.479294443507223965e-03,1.000000009843268201e+00,-4.000000000000000327e-05,2.493975872710801263e-09,0.000000000000000000e+00 +8.139412431959243577e+01,5.064130510035740826e+02,9.997249978454762764e-02,1.024249078941533853e+01,3.479148458105686247e-03,1.000000009845703364e+00,-4.000000000000000327e-05,-2.491484498668873196e-09,0.000000000000000000e+00 +8.139510064461001093e+01,5.064230509430517486e+02,1.000072911989399599e-01,1.024346711444252733e+01,3.479002472704148530e-03,1.000000009843270865e+00,-4.000000000000000327e-05,2.370035886045476769e-10,0.000000000000000000e+00 +8.139607687657212409e+01,5.064330508825345305e+02,1.000420811534871030e-01,1.024444334641425236e+01,3.478856487302610812e-03,1.000000009843502236e+00,-4.000000000000000327e-05,-5.104479254692502459e-10,0.000000000000000000e+00 +8.139705301550537797e+01,5.064430508220223714e+02,1.000768696481890707e-01,1.024541948535711988e+01,3.478710501901073095e-03,1.000000009843003967e+00,-4.000000000000000327e-05,8.490076534995509734e-10,0.000000000000000000e+00 +8.139802906143637529e+01,5.064530507615152715e+02,1.001116566830458632e-01,1.024639553129772018e+01,3.478564516499535377e-03,1.000000009843832638e+00,-4.000000000000000327e-05,-1.287283744401845805e-09,0.000000000000000000e+00 +8.139900501439167613e+01,5.064630507010132874e+02,1.001464422580574665e-01,1.024737148426263289e+01,3.478418531097997660e-03,1.000000009842576310e+00,-4.000000000000000327e-05,5.312997245655204166e-10,0.000000000000000000e+00 +8.139998087439785479e+01,5.064730506405163624e+02,1.001812263732238806e-01,1.024834734427842164e+01,3.478272545696459942e-03,1.000000009843094784e+00,-4.000000000000000327e-05,7.011093520797165947e-10,0.000000000000000000e+00 +8.140095664148147137e+01,5.064830505800244964e+02,1.002160090285451194e-01,1.024932311137164120e+01,3.478126560294922225e-03,1.000000009843778903e+00,-4.000000000000000327e-05,-7.878843491308766917e-10,0.000000000000000000e+00 +8.140193231566905752e+01,5.064930505195377464e+02,1.002507902240211690e-01,1.025029878556883212e+01,3.477980574893384507e-03,1.000000009843010185e+00,-4.000000000000000327e-05,-2.078919905276992578e-09,0.000000000000000000e+00 +8.140290789698714491e+01,5.065030504590560554e+02,1.002855699596520295e-01,1.025127436689652072e+01,3.477834589491846790e-03,1.000000009840982029e+00,-4.000000000000000327e-05,2.419643297282503598e-09,0.000000000000000000e+00 +8.140388338546225100e+01,5.065130503985794235e+02,1.003203482354377146e-01,1.025224985538122091e+01,3.477688604090309072e-03,1.000000009843342363e+00,-4.000000000000000327e-05,-2.234797609863058264e-09,0.000000000000000000e+00 +8.140485878112086482e+01,5.065230503381079075e+02,1.003551250513782106e-01,1.025322525104943949e+01,3.477542618688771354e-03,1.000000009841162552e+00,-4.000000000000000327e-05,7.510745381902794000e-10,0.000000000000000000e+00 +8.140583408398948961e+01,5.065330502776414505e+02,1.003899004074735174e-01,1.025420055392766194e+01,3.477396633287233637e-03,1.000000009841895077e+00,-4.000000000000000327e-05,1.657575855076162624e-10,0.000000000000000000e+00 +8.140680929409460020e+01,5.065430502171800526e+02,1.004246743037236350e-01,1.025517576404236841e+01,3.477250647885695919e-03,1.000000009842056725e+00,-4.000000000000000327e-05,-2.648274802470601315e-10,0.000000000000000000e+00 +8.140778441146265720e+01,5.065530501567237707e+02,1.004594467401285635e-01,1.025615088142002307e+01,3.477104662484158202e-03,1.000000009841798487e+00,-4.000000000000000327e-05,-2.418972459282542177e-09,0.000000000000000000e+00 +8.140875943612012122e+01,5.065630500962725478e+02,1.004942177166883027e-01,1.025712590608707764e+01,3.476958677082620484e-03,1.000000009839439929e+00,-4.000000000000000327e-05,3.039148668078660716e-09,0.000000000000000000e+00 +8.140973436809342445e+01,5.065730500358263839e+02,1.005289872334028528e-01,1.025810083806996964e+01,3.476812691681082767e-03,1.000000009842402893e+00,-4.000000000000000327e-05,-2.587986307970324779e-09,0.000000000000000000e+00 +8.141070920740898487e+01,5.065830499753853360e+02,1.005637552902722137e-01,1.025907567739513127e+01,3.476666706279545049e-03,1.000000009839880022e+00,-4.000000000000000327e-05,1.250151256238939930e-09,0.000000000000000000e+00 +8.141168395409323466e+01,5.065930499149493471e+02,1.005985218872963716e-01,1.026005042408897161e+01,3.476520720878007332e-03,1.000000009841098603e+00,-4.000000000000000327e-05,-4.091627161898213065e-10,0.000000000000000000e+00 +8.141265860817256339e+01,5.066030498545184173e+02,1.006332870244753402e-01,1.026102507817789622e+01,3.476374735476469614e-03,1.000000009840699811e+00,-4.000000000000000327e-05,-1.967630782199065778e-09,0.000000000000000000e+00 +8.141363316967337482e+01,5.066130497940925466e+02,1.006680507018091197e-01,1.026199963968829287e+01,3.476228750074931897e-03,1.000000009838782233e+00,-4.000000000000000327e-05,2.179273751545337186e-09,0.000000000000000000e+00 +8.141460763862203009e+01,5.066230497336717917e+02,1.007028129192976962e-01,1.026297410864653692e+01,3.476082764673394179e-03,1.000000009840905868e+00,-4.000000000000000327e-05,-1.072193293731470442e-09,0.000000000000000000e+00 +8.141558201504490455e+01,5.066330496732560960e+02,1.007375736769410834e-01,1.026394848507899660e+01,3.475936779271856462e-03,1.000000009839861148e+00,-4.000000000000000327e-05,-5.068616955220691993e-10,0.000000000000000000e+00 +8.141655629896834512e+01,5.066430496128454593e+02,1.007723329747392677e-01,1.026492276901202061e+01,3.475790793870318744e-03,1.000000009839367321e+00,-4.000000000000000327e-05,1.264995250061333954e-10,0.000000000000000000e+00 +8.141753049041868451e+01,5.066530495524399385e+02,1.008070908126922627e-01,1.026589696047194877e+01,3.475644808468781027e-03,1.000000009839490556e+00,-4.000000000000000327e-05,-1.054262753589946575e-09,0.000000000000000000e+00 +8.141850458942225544e+01,5.066630494920394767e+02,1.008418471908000547e-01,1.026687105948510847e+01,3.475498823067243309e-03,1.000000009838463599e+00,-4.000000000000000327e-05,1.558861135836568411e-09,0.000000000000000000e+00 +8.141947859600537640e+01,5.066730494316440740e+02,1.008766021090626575e-01,1.026784506607781289e+01,3.475352837665705592e-03,1.000000009839981940e+00,-4.000000000000000327e-05,-1.403974490375041008e-09,0.000000000000000000e+00 +8.142045251019435170e+01,5.066830493712537304e+02,1.009113555674800572e-01,1.026881898027636630e+01,3.475206852264167874e-03,1.000000009838614590e+00,-4.000000000000000327e-05,-5.903271724768790980e-10,0.000000000000000000e+00 +8.142142633201545721e+01,5.066930493108685027e+02,1.009461075660522539e-01,1.026979280210705525e+01,3.475060866862630157e-03,1.000000009838039716e+00,-4.000000000000000327e-05,2.476462364750689455e-10,0.000000000000000000e+00 +8.142240006149498299e+01,5.067030492504883341e+02,1.009808581047792475e-01,1.027076653159615738e+01,3.474914881461092439e-03,1.000000009838280857e+00,-4.000000000000000327e-05,-7.740248799289996815e-10,0.000000000000000000e+00 +8.142337369865919072e+01,5.067130491901132245e+02,1.010156071836610520e-01,1.027174016876993790e+01,3.474768896059554722e-03,1.000000009837527237e+00,-4.000000000000000327e-05,1.959193874906034897e-09,0.000000000000000000e+00 +8.142434724353432784e+01,5.067230491297431740e+02,1.010503548026976534e-01,1.027271371365464780e+01,3.474622910658017004e-03,1.000000009839434600e+00,-4.000000000000000327e-05,-2.808368010199036528e-09,0.000000000000000000e+00 +8.142532069614662760e+01,5.067330490693782394e+02,1.010851009618890517e-01,1.027368716627652923e+01,3.474476925256479286e-03,1.000000009836700787e+00,-4.000000000000000327e-05,1.785964638951286041e-09,0.000000000000000000e+00 +8.142629405652232322e+01,5.067430490090183639e+02,1.011198456612352470e-01,1.027466052666180474e+01,3.474330939854941569e-03,1.000000009838439174e+00,-4.000000000000000327e-05,-3.014913626749565786e-09,0.000000000000000000e+00 +8.142726732468763373e+01,5.067530489486635474e+02,1.011545889007362392e-01,1.027563379483669337e+01,3.474184954453403851e-03,1.000000009835504855e+00,-4.000000000000000327e-05,3.407186520882817509e-09,0.000000000000000000e+00 +8.142824050066876396e+01,5.067630488883137900e+02,1.011893306803920145e-01,1.027660697082739283e+01,3.474038969051866134e-03,1.000000009838820647e+00,-4.000000000000000327e-05,-3.336999573142036357e-09,0.000000000000000000e+00 +8.142921358449189029e+01,5.067730488279690917e+02,1.012240710002025867e-01,1.027758005466009905e+01,3.473892983650328416e-03,1.000000009835573467e+00,-4.000000000000000327e-05,1.127119906073975141e-09,0.000000000000000000e+00 +8.143018657618320333e+01,5.067830487676295093e+02,1.012588098601679559e-01,1.027855304636098310e+01,3.473746998248790699e-03,1.000000009836670145e+00,-4.000000000000000327e-05,-9.129189001520805915e-11,0.000000000000000000e+00 +8.143115947576886526e+01,5.067930487072949859e+02,1.012935472602881221e-01,1.027952594595621427e+01,3.473601012847252981e-03,1.000000009836581327e+00,-4.000000000000000327e-05,5.028376750302663068e-10,0.000000000000000000e+00 +8.143213228327502407e+01,5.068030486469655216e+02,1.013282832005630713e-01,1.028049875347194408e+01,3.473455027445715264e-03,1.000000009837070492e+00,-4.000000000000000327e-05,-2.729915950911342900e-09,0.000000000000000000e+00 +8.143310499872782771e+01,5.068130485866411163e+02,1.013630176809928174e-01,1.028147146893431341e+01,3.473309042044177546e-03,1.000000009834415060e+00,-4.000000000000000327e-05,1.466107452630009002e-09,0.000000000000000000e+00 +8.143407762215339574e+01,5.068230485263217702e+02,1.013977507015773605e-01,1.028244409236944712e+01,3.473163056642639829e-03,1.000000009835841031e+00,-4.000000000000000327e-05,-5.959050826361667778e-11,0.000000000000000000e+00 +8.143505015357784771e+01,5.068330484660075399e+02,1.014324822623166866e-01,1.028341662380346477e+01,3.473017071241102111e-03,1.000000009835783077e+00,-4.000000000000000327e-05,1.938587227103636741e-10,0.000000000000000000e+00 +8.143602259302728896e+01,5.068430484056983687e+02,1.014672123632107958e-01,1.028438906326246816e+01,3.472871085839564394e-03,1.000000009835971593e+00,-4.000000000000000327e-05,-1.538456675813631864e-09,0.000000000000000000e+00 +8.143699494052781063e+01,5.068530483453942566e+02,1.015019410042597020e-01,1.028536141077254840e+01,3.472725100438026676e-03,1.000000009834475678e+00,-4.000000000000000327e-05,3.715757260841930787e-10,0.000000000000000000e+00 +8.143796719610548962e+01,5.068630482850952035e+02,1.015366681854633912e-01,1.028633366635978241e+01,3.472579115036488959e-03,1.000000009834836945e+00,-4.000000000000000327e-05,2.784226347095092220e-10,0.000000000000000000e+00 +8.143893935978638865e+01,5.068730482248012095e+02,1.015713939068218635e-01,1.028730583005023824e+01,3.472433129634951241e-03,1.000000009835107617e+00,-4.000000000000000327e-05,5.253753745185895802e-11,0.000000000000000000e+00 +8.143991143159655621e+01,5.068830481645123314e+02,1.016061181683351328e-01,1.028827790186996971e+01,3.472287144233413524e-03,1.000000009835158687e+00,-4.000000000000000327e-05,-2.195362794598541019e-09,0.000000000000000000e+00 +8.144088341156204081e+01,5.068930481042285123e+02,1.016408409700031851e-01,1.028924988184501821e+01,3.472141158831875806e-03,1.000000009833024839e+00,-4.000000000000000327e-05,1.047293839615050154e-09,0.000000000000000000e+00 +8.144185529970887671e+01,5.069030480439497524e+02,1.016755623118260204e-01,1.029022177000141092e+01,3.471995173430338089e-03,1.000000009834042691e+00,-4.000000000000000327e-05,3.710658481477733594e-10,0.000000000000000000e+00 +8.144282709606308401e+01,5.069130479836760514e+02,1.017102821938036389e-01,1.029119356636516791e+01,3.471849188028800371e-03,1.000000009834403292e+00,-4.000000000000000327e-05,-4.732450403986345968e-10,0.000000000000000000e+00 +8.144379880065065436e+01,5.069230479234074096e+02,1.017450006159360404e-01,1.029216527096229328e+01,3.471703202627262654e-03,1.000000009833943437e+00,-4.000000000000000327e-05,-1.493913534573299288e-09,0.000000000000000000e+00 +8.144477041349757940e+01,5.069330478631438268e+02,1.017797175782232250e-01,1.029313688381877867e+01,3.471557217225724936e-03,1.000000009832491932e+00,-4.000000000000000327e-05,1.064602441865411537e-09,0.000000000000000000e+00 +8.144574193462985079e+01,5.069430478028853599e+02,1.018144330806651926e-01,1.029410840496060331e+01,3.471411231824187218e-03,1.000000009833526216e+00,-4.000000000000000327e-05,-3.341768303866654953e-10,0.000000000000000000e+00 +8.144671336407343176e+01,5.069530477426319521e+02,1.018491471232619433e-01,1.029507983441373753e+01,3.471265246422649501e-03,1.000000009833201586e+00,-4.000000000000000327e-05,-5.234864280014286050e-11,0.000000000000000000e+00 +8.144768470185428555e+01,5.069630476823836034e+02,1.018838597060134771e-01,1.029605117220413568e+01,3.471119261021111783e-03,1.000000009833150738e+00,-4.000000000000000327e-05,-1.864381922385687734e-09,0.000000000000000000e+00 +8.144865594799834696e+01,5.069730476221403137e+02,1.019185708289197800e-01,1.029702241835774146e+01,3.470973275619574066e-03,1.000000009831339964e+00,-4.000000000000000327e-05,1.754353396245166321e-09,0.000000000000000000e+00 +8.144962710253153659e+01,5.069830475619020831e+02,1.019532804919808661e-01,1.029799357290048434e+01,3.470827290218036348e-03,1.000000009833043713e+00,-4.000000000000000327e-05,-5.046556909114345660e-10,0.000000000000000000e+00 +8.145059816547978926e+01,5.069930475016689115e+02,1.019879886951967352e-01,1.029896463585828670e+01,3.470681304816498631e-03,1.000000009832553660e+00,-4.000000000000000327e-05,-1.116430178355279995e-09,0.000000000000000000e+00 +8.145156913686901134e+01,5.070030474414408559e+02,1.020226954385673734e-01,1.029993560725705315e+01,3.470535319414960913e-03,1.000000009831469638e+00,-4.000000000000000327e-05,-8.942346468726620051e-11,0.000000000000000000e+00 +8.145254001672509503e+01,5.070130473812178593e+02,1.020574007220927948e-01,1.030090648712267765e+01,3.470389334013423196e-03,1.000000009831382819e+00,-4.000000000000000327e-05,-1.200354421291734073e-09,0.000000000000000000e+00 +8.145351080507391828e+01,5.070230473209999218e+02,1.020921045457729853e-01,1.030187727548104348e+01,3.470243348611885478e-03,1.000000009830217529e+00,-4.000000000000000327e-05,1.197493827146251152e-09,0.000000000000000000e+00 +8.145448150194135906e+01,5.070330472607870433e+02,1.021268069096079589e-01,1.030284797235801975e+01,3.470097363210347761e-03,1.000000009831379932e+00,-4.000000000000000327e-05,-4.463286716676172787e-10,0.000000000000000000e+00 +8.145545210735326691e+01,5.070430472005792240e+02,1.021615078135977017e-01,1.030381857777946664e+01,3.469951377808810043e-03,1.000000009830946723e+00,-4.000000000000000327e-05,-4.836636085731214211e-10,0.000000000000000000e+00 +8.145642262133549139e+01,5.070530471403764636e+02,1.021962072577422276e-01,1.030478909177122837e+01,3.469805392407272326e-03,1.000000009830477321e+00,-4.000000000000000327e-05,1.077248224935688393e-09,0.000000000000000000e+00 +8.145739304391386781e+01,5.070630470801787624e+02,1.022309052420415226e-01,1.030575951435913851e+01,3.469659407005734608e-03,1.000000009831522707e+00,-4.000000000000000327e-05,-1.430669105046374461e-09,0.000000000000000000e+00 +8.145836337511420311e+01,5.070730470199861202e+02,1.022656017664955869e-01,1.030672984556901994e+01,3.469513421604196891e-03,1.000000009830134484e+00,-4.000000000000000327e-05,-4.707555077384622437e-10,0.000000000000000000e+00 +8.145933361496231839e+01,5.070830469597985370e+02,1.023002968311044203e-01,1.030770008542667959e+01,3.469367436202659173e-03,1.000000009829677738e+00,-4.000000000000000327e-05,1.762352278728794410e-10,0.000000000000000000e+00 +8.146030376348402058e+01,5.070930468996160698e+02,1.023349904358680229e-01,1.030867023395791549e+01,3.469221450801121456e-03,1.000000009829848713e+00,-4.000000000000000327e-05,-1.386666876375498547e-09,0.000000000000000000e+00 +8.146127382070508816e+01,5.071030468394386617e+02,1.023696825807863947e-01,1.030964029118851322e+01,3.469075465399583738e-03,1.000000009828503567e+00,-4.000000000000000327e-05,2.383972885598710348e-09,0.000000000000000000e+00 +8.146224378665128540e+01,5.071130467792663126e+02,1.024043732658595357e-01,1.031061025714424417e+01,3.468929479998046021e-03,1.000000009830815939e+00,-4.000000000000000327e-05,-1.736750508089995527e-09,0.000000000000000000e+00 +8.146321366134837660e+01,5.071230467190990225e+02,1.024390624910874459e-01,1.031158013185087263e+01,3.468783494596508303e-03,1.000000009829131509e+00,-4.000000000000000327e-05,-5.410397430419513311e-10,0.000000000000000000e+00 +8.146418344482211182e+01,5.071330466589367916e+02,1.024737502564701253e-01,1.031254991533414334e+01,3.468637509194970586e-03,1.000000009828606817e+00,-4.000000000000000327e-05,-1.590069112202392200e-09,0.000000000000000000e+00 +8.146515313709822692e+01,5.071430465987796197e+02,1.025084365620075738e-01,1.031351960761979392e+01,3.468491523793432868e-03,1.000000009827064940e+00,-4.000000000000000327e-05,2.664715429518159009e-09,0.000000000000000000e+00 +8.146612273820245775e+01,5.071530465386275068e+02,1.025431214076997916e-01,1.031448920873354780e+01,3.468345538391895150e-03,1.000000009829648651e+00,-4.000000000000000327e-05,-2.902009582947124355e-09,0.000000000000000000e+00 +8.146709224816049755e+01,5.071630464784804531e+02,1.025778047935467785e-01,1.031545871870112130e+01,3.468199552990357433e-03,1.000000009826835123e+00,-4.000000000000000327e-05,2.489077608383573851e-09,0.000000000000000000e+00 +8.146806166699805374e+01,5.071730464183384584e+02,1.026124867195485207e-01,1.031642813754820942e+01,3.468053567588819715e-03,1.000000009829248082e+00,-4.000000000000000327e-05,-1.961303513235707178e-09,0.000000000000000000e+00 +8.146903099474081955e+01,5.071830463582015227e+02,1.026471671857050322e-01,1.031739746530050539e+01,3.467907582187281998e-03,1.000000009827346936e+00,-4.000000000000000327e-05,-1.139733915908492177e-09,0.000000000000000000e+00 +8.147000023141447400e+01,5.071930462980696461e+02,1.026818461920162989e-01,1.031836670198368111e+01,3.467761596785744280e-03,1.000000009826242264e+00,-4.000000000000000327e-05,1.166647295358667111e-09,0.000000000000000000e+00 +8.147096937704466768e+01,5.072030462379428286e+02,1.027165237384823349e-01,1.031933584762340139e+01,3.467615611384206563e-03,1.000000009827372915e+00,-4.000000000000000327e-05,-7.256714480302252787e-10,0.000000000000000000e+00 +8.147193843165706539e+01,5.072130461778211270e+02,1.027511998251031261e-01,1.032030490224532038e+01,3.467469625982668845e-03,1.000000009826669700e+00,-4.000000000000000327e-05,7.410930991960410642e-10,0.000000000000000000e+00 +8.147290739527730352e+01,5.072230461177044845e+02,1.027858744518786865e-01,1.032127386587507623e+01,3.467323640581131128e-03,1.000000009827387792e+00,-4.000000000000000327e-05,-1.171101203892225104e-10,0.000000000000000000e+00 +8.147387626793100424e+01,5.072330460575929010e+02,1.028205476188090023e-01,1.032224273853829821e+01,3.467177655179593410e-03,1.000000009827274328e+00,-4.000000000000000327e-05,-1.416913355748311811e-09,0.000000000000000000e+00 +8.147484504964378971e+01,5.072430459974863766e+02,1.028552193258940872e-01,1.032321152026060140e+01,3.467031669778055693e-03,1.000000009825901648e+00,-4.000000000000000327e-05,6.188976243649251269e-10,0.000000000000000000e+00 +8.147581374044125369e+01,5.072530459373849112e+02,1.028898895731339275e-01,1.032418021106758843e+01,3.466885684376517975e-03,1.000000009826501168e+00,-4.000000000000000327e-05,-1.589799175944011784e-09,0.000000000000000000e+00 +8.147678234034900413e+01,5.072630458772885049e+02,1.029245583605285230e-01,1.032514881098485304e+01,3.466739698974980258e-03,1.000000009824961289e+00,-4.000000000000000327e-05,-4.789332456433505781e-10,0.000000000000000000e+00 +8.147775084939260637e+01,5.072730458171971577e+02,1.029592256880778739e-01,1.032611732003797300e+01,3.466593713573442540e-03,1.000000009824497438e+00,-4.000000000000000327e-05,2.051879197595858594e-09,0.000000000000000000e+00 +8.147871926759763994e+01,5.072830457571108695e+02,1.029938915557819801e-01,1.032708573825251719e+01,3.466447728171904823e-03,1.000000009826484515e+00,-4.000000000000000327e-05,-1.584284600521771108e-09,0.000000000000000000e+00 +8.147968759498965596e+01,5.072930456970296405e+02,1.030285559636408416e-01,1.032805406565404382e+01,3.466301742770367105e-03,1.000000009824950409e+00,-4.000000000000000327e-05,-2.935409516355219871e-11,0.000000000000000000e+00 +8.148065583159419134e+01,5.073030456369534704e+02,1.030632189116544584e-01,1.032902230226809337e+01,3.466155757368829388e-03,1.000000009824921987e+00,-4.000000000000000327e-05,-8.703846451820188802e-10,0.000000000000000000e+00 +8.148162397743678298e+01,5.073130455768823595e+02,1.030978803998228305e-01,1.032999044812019918e+01,3.466009771967291670e-03,1.000000009824079328e+00,-4.000000000000000327e-05,-3.247905605471990365e-10,0.000000000000000000e+00 +8.148259203254295358e+01,5.073230455168163076e+02,1.031325404281459579e-01,1.033095850323588039e+01,3.465863786565753953e-03,1.000000009823764913e+00,-4.000000000000000327e-05,-2.975231878354231395e-10,0.000000000000000000e+00 +8.148355999693821161e+01,5.073330454567553147e+02,1.031671989966238406e-01,1.033192646764064548e+01,3.465717801164216235e-03,1.000000009823476921e+00,-4.000000000000000327e-05,1.100732464992311462e-09,0.000000000000000000e+00 +8.148452787064805136e+01,5.073430453966993809e+02,1.032018561052564787e-01,1.033289434135999052e+01,3.465571815762678518e-03,1.000000009824542291e+00,-4.000000000000000327e-05,-1.828837099426394262e-09,0.000000000000000000e+00 +8.148549565369795289e+01,5.073530453366485062e+02,1.032365117540438720e-01,1.033386212441940089e+01,3.465425830361140800e-03,1.000000009822772373e+00,-4.000000000000000327e-05,3.880131960708067602e-10,0.000000000000000000e+00 +8.148646334611339626e+01,5.073630452766026906e+02,1.032711659429860068e-01,1.033482981684434598e+01,3.465279844959603082e-03,1.000000009823147851e+00,-4.000000000000000327e-05,1.571933344499315827e-10,0.000000000000000000e+00 +8.148743094791983310e+01,5.073730452165619340e+02,1.033058186720828969e-01,1.033579741866028812e+01,3.465133859558065365e-03,1.000000009823299951e+00,-4.000000000000000327e-05,-6.338812246284789258e-10,0.000000000000000000e+00 +8.148839845914271507e+01,5.073830451565262365e+02,1.033404699413345285e-01,1.033676492989267537e+01,3.464987874156527647e-03,1.000000009822686664e+00,-4.000000000000000327e-05,-9.594031659554721138e-11,0.000000000000000000e+00 +8.148936587980747959e+01,5.073930450964955980e+02,1.033751197507409153e-01,1.033773235056694340e+01,3.464841888754989930e-03,1.000000009822593849e+00,-4.000000000000000327e-05,-1.340535614231773545e-10,0.000000000000000000e+00 +8.149033320993954987e+01,5.074030450364700187e+02,1.034097681003020436e-01,1.033869968070851719e+01,3.464695903353452212e-03,1.000000009822464175e+00,-4.000000000000000327e-05,-7.582540161394975839e-10,0.000000000000000000e+00 +8.149130044956433494e+01,5.074130449764494983e+02,1.034444149900179272e-01,1.033966692034280932e+01,3.464549917951914495e-03,1.000000009821730762e+00,-4.000000000000000327e-05,-7.691155308886179732e-11,0.000000000000000000e+00 +8.149226759870724379e+01,5.074230449164340371e+02,1.034790604198885522e-01,1.034063406949521990e+01,3.464403932550376777e-03,1.000000009821656377e+00,-4.000000000000000327e-05,2.296082006635384774e-12,0.000000000000000000e+00 +8.149323465739367123e+01,5.074330448564236349e+02,1.035137043899139186e-01,1.034160112819113841e+01,3.464257947148839060e-03,1.000000009821658598e+00,-4.000000000000000327e-05,-5.288371384853760337e-10,0.000000000000000000e+00 +8.149420162564898362e+01,5.074430447964182918e+02,1.035483469000940404e-01,1.034256809645594188e+01,3.464111961747301342e-03,1.000000009821147229e+00,-4.000000000000000327e-05,2.206947500459168779e-10,0.000000000000000000e+00 +8.149516850349854735e+01,5.074530447364180077e+02,1.035829879504289036e-01,1.034353497431499491e+01,3.463965976345763625e-03,1.000000009821360614e+00,-4.000000000000000327e-05,3.433605574665525312e-10,0.000000000000000000e+00 +8.149613529096771458e+01,5.074630446764227827e+02,1.036176275409185082e-01,1.034450176179365144e+01,3.463819990944225907e-03,1.000000009821692570e+00,-4.000000000000000327e-05,-2.070921831450335683e-09,0.000000000000000000e+00 +8.149710198808182327e+01,5.074730446164326167e+02,1.036522656715628543e-01,1.034546845891725297e+01,3.463674005542688190e-03,1.000000009819690616e+00,-4.000000000000000327e-05,5.733700019984735878e-10,0.000000000000000000e+00 +8.149806859486621136e+01,5.074830445564475099e+02,1.036869023423619418e-01,1.034643506571112681e+01,3.463528020141150472e-03,1.000000009820244840e+00,-4.000000000000000327e-05,-1.237363528614923870e-09,0.000000000000000000e+00 +8.149903511134618839e+01,5.074930444964674621e+02,1.037215375533157707e-01,1.034740158220059314e+01,3.463382034739612755e-03,1.000000009819048907e+00,-4.000000000000000327e-05,1.996141584163141399e-09,0.000000000000000000e+00 +8.150000153754706389e+01,5.075030444364924733e+02,1.037561713044243411e-01,1.034836800841095616e+01,3.463236049338075037e-03,1.000000009820978031e+00,-4.000000000000000327e-05,-1.145223164165547474e-09,0.000000000000000000e+00 +8.150096787349413319e+01,5.075130443765224868e+02,1.037908035956876529e-01,1.034933434436751298e+01,3.463090063936537320e-03,1.000000009819871361e+00,-4.000000000000000327e-05,-1.160496997144731912e-09,0.000000000000000000e+00 +8.150193411921267739e+01,5.075230443165575593e+02,1.038254344271057061e-01,1.035030059009554293e+01,3.462944078534999602e-03,1.000000009818750035e+00,-4.000000000000000327e-05,4.067864277528057378e-11,0.000000000000000000e+00 +8.150290027472796339e+01,5.075330442565976909e+02,1.038600637986785008e-01,1.035126674562031646e+01,3.462798093133461885e-03,1.000000009818789337e+00,-4.000000000000000327e-05,-1.355391798772376254e-09,0.000000000000000000e+00 +8.150386634006525810e+01,5.075430441966428816e+02,1.038946917104060230e-01,1.035223281096709336e+01,3.462652107731924167e-03,1.000000009817479940e+00,-4.000000000000000327e-05,2.256132281877976648e-09,0.000000000000000000e+00 +8.150483231524979999e+01,5.075530441366931313e+02,1.039293181622882867e-01,1.035319878616111922e+01,3.462506122330386450e-03,1.000000009819659308e+00,-4.000000000000000327e-05,-2.458643533609209776e-09,0.000000000000000000e+00 +8.150579820030682754e+01,5.075630440767484401e+02,1.039639431543252918e-01,1.035416467122763251e+01,3.462360136928848732e-03,1.000000009817284541e+00,-4.000000000000000327e-05,1.627063447934905579e-09,0.000000000000000000e+00 +8.150676399526156501e+01,5.075730440168088080e+02,1.039985666865170244e-01,1.035513046619185218e+01,3.462214151527311014e-03,1.000000009818855951e+00,-4.000000000000000327e-05,-2.632699477043069996e-09,0.000000000000000000e+00 +8.150772970013922247e+01,5.075830439568742349e+02,1.040331887588634985e-01,1.035609617107899361e+01,3.462068166125773297e-03,1.000000009816313540e+00,-4.000000000000000327e-05,1.894800593087240347e-09,0.000000000000000000e+00 +8.150869531496499576e+01,5.075930438969447209e+02,1.040678093713647001e-01,1.035706178591425264e+01,3.461922180724235579e-03,1.000000009818143187e+00,-4.000000000000000327e-05,-1.942351698232686582e-09,0.000000000000000000e+00 +8.150966083976408072e+01,5.076030438370202660e+02,1.041024285240206293e-01,1.035802731072282157e+01,3.461776195322697862e-03,1.000000009816267799e+00,-4.000000000000000327e-05,1.088793528424544080e-09,0.000000000000000000e+00 +8.151062627456165899e+01,5.076130437771008701e+02,1.041370462168312999e-01,1.035899274552987315e+01,3.461630209921160144e-03,1.000000009817318958e+00,-4.000000000000000327e-05,-4.526711832753613596e-10,0.000000000000000000e+00 +8.151159161938288378e+01,5.076230437171865333e+02,1.041716624497966981e-01,1.035995809036057480e+01,3.461484224519622427e-03,1.000000009816881974e+00,-4.000000000000000327e-05,-8.580390548528203688e-10,0.000000000000000000e+00 +8.151255687425290830e+01,5.076330436572772555e+02,1.042062772229168238e-01,1.036092334524007796e+01,3.461338239118084709e-03,1.000000009816053748e+00,-4.000000000000000327e-05,-1.350444645810339426e-10,0.000000000000000000e+00 +8.151352203919688577e+01,5.076430435973729800e+02,1.042408905361916910e-01,1.036188851019352342e+01,3.461192253716546992e-03,1.000000009815923407e+00,-4.000000000000000327e-05,-1.983290841730948484e-10,0.000000000000000000e+00 +8.151448711423992677e+01,5.076530435374737635e+02,1.042755023896212857e-01,1.036285358524604128e+01,3.461046268315009274e-03,1.000000009815732005e+00,-4.000000000000000327e-05,-1.056626423322489089e-09,0.000000000000000000e+00 +8.151545209940715608e+01,5.076630434775796061e+02,1.043101127832056080e-01,1.036381857042274923e+01,3.460900282913471557e-03,1.000000009814712376e+00,-4.000000000000000327e-05,1.097686709992473883e-09,0.000000000000000000e+00 +8.151641699472368430e+01,5.076730434176905078e+02,1.043447217169446578e-01,1.036478346574875253e+01,3.460754297511933839e-03,1.000000009815771529e+00,-4.000000000000000327e-05,-1.375573228096899932e-09,0.000000000000000000e+00 +8.151738180021460778e+01,5.076830433578064685e+02,1.043793291908384352e-01,1.036574827124914755e+01,3.460608312110396122e-03,1.000000009814444368e+00,-4.000000000000000327e-05,1.056231076307641764e-09,0.000000000000000000e+00 +8.151834651590500869e+01,5.076930432979274883e+02,1.044139352048869401e-01,1.036671298694901466e+01,3.460462326708858404e-03,1.000000009815463331e+00,-4.000000000000000327e-05,-1.156921213771994036e-09,0.000000000000000000e+00 +8.151931114181995497e+01,5.077030432380535672e+02,1.044485397590901726e-01,1.036767761287342715e+01,3.460316341307320687e-03,1.000000009814347335e+00,-4.000000000000000327e-05,-3.892828913303107126e-10,0.000000000000000000e+00 +8.152027567798450036e+01,5.077130431781847051e+02,1.044831428534481188e-01,1.036864214904744230e+01,3.460170355905782969e-03,1.000000009813971857e+00,-4.000000000000000327e-05,-4.657555023329201930e-10,0.000000000000000000e+00 +8.152124012442369860e+01,5.077230431183208452e+02,1.045177444879607925e-01,1.036960659549610853e+01,3.460024370504245252e-03,1.000000009813522661e+00,-4.000000000000000327e-05,5.143818956185498426e-10,0.000000000000000000e+00 +8.152220448116258922e+01,5.077330430584620444e+02,1.045523446626281938e-01,1.037057095224446179e+01,3.459878385102707534e-03,1.000000009814018709e+00,-4.000000000000000327e-05,-1.277093686383685351e-09,0.000000000000000000e+00 +8.152316874822619752e+01,5.077430429986083027e+02,1.045869433774503088e-01,1.037153521931752742e+01,3.459732399701169817e-03,1.000000009812787249e+00,-4.000000000000000327e-05,-1.172198211081858701e-10,0.000000000000000000e+00 +8.152413292563952041e+01,5.077530429387596200e+02,1.046215406324271513e-01,1.037249939674031651e+01,3.459586414299632099e-03,1.000000009812674229e+00,-4.000000000000000327e-05,1.651363949464813927e-10,0.000000000000000000e+00 +8.152509701342756898e+01,5.077630428789159964e+02,1.046561364275587214e-01,1.037346348453783129e+01,3.459440428898094382e-03,1.000000009812833435e+00,-4.000000000000000327e-05,-4.392529643351937341e-10,0.000000000000000000e+00 +8.152606101161534013e+01,5.077730428190774319e+02,1.046907307628450051e-01,1.037442748273506155e+01,3.459294443496556664e-03,1.000000009812409996e+00,-4.000000000000000327e-05,-2.626087642969114748e-11,0.000000000000000000e+00 +8.152702492022780234e+01,5.077830427592439264e+02,1.047253236382860164e-01,1.037539139135698463e+01,3.459148458095018946e-03,1.000000009812384683e+00,-4.000000000000000327e-05,-5.162815088340045596e-10,0.000000000000000000e+00 +8.152798873928992407e+01,5.077930426994154232e+02,1.047599150538817414e-01,1.037635521042856723e+01,3.459002472693481229e-03,1.000000009811887081e+00,-4.000000000000000327e-05,-5.068830125175082786e-12,0.000000000000000000e+00 +8.152895246882665958e+01,5.078030426395919790e+02,1.047945050096321801e-01,1.037731893997476362e+01,3.458856487291943511e-03,1.000000009811882196e+00,-4.000000000000000327e-05,-4.131480237784479571e-10,0.000000000000000000e+00 +8.152991610886296314e+01,5.078130425797735938e+02,1.048290935055373463e-01,1.037828258002051740e+01,3.458710501890405794e-03,1.000000009811484070e+00,-4.000000000000000327e-05,-1.749532104689327945e-09,0.000000000000000000e+00 +8.153087965942374638e+01,5.078230425199602678e+02,1.048636805415972262e-01,1.037924613059075973e+01,3.458564516488868076e-03,1.000000009809798307e+00,-4.000000000000000327e-05,1.718812151317769693e-09,0.000000000000000000e+00 +8.153184312053394933e+01,5.078330424601520008e+02,1.048982661178118198e-01,1.038020959171040936e+01,3.458418531087330359e-03,1.000000009811454316e+00,-4.000000000000000327e-05,-1.497934712635949893e-09,0.000000000000000000e+00 +8.153280649221846943e+01,5.078430424003487929e+02,1.049328502341811270e-01,1.038117296340437790e+01,3.458272545685792641e-03,1.000000009810011248e+00,-4.000000000000000327e-05,7.445419541295659252e-11,0.000000000000000000e+00 +8.153376977450220409e+01,5.078530423405505871e+02,1.049674328907051479e-01,1.038213624569755922e+01,3.458126560284254924e-03,1.000000009810082968e+00,-4.000000000000000327e-05,6.865175481360303473e-10,0.000000000000000000e+00 +8.153473296741003651e+01,5.078630422807574405e+02,1.050020140873838825e-01,1.038309943861484008e+01,3.457980574882717206e-03,1.000000009810744217e+00,-4.000000000000000327e-05,-1.585269509883150125e-09,0.000000000000000000e+00 +8.153569607096683569e+01,5.078730422209693529e+02,1.050365938242173308e-01,1.038406254218109481e+01,3.457834589481179489e-03,1.000000009809217438e+00,-4.000000000000000327e-05,-1.004604410687793260e-09,0.000000000000000000e+00 +8.153665908519748484e+01,5.078830421611863244e+02,1.050711721012054928e-01,1.038502555642118352e+01,3.457688604079641771e-03,1.000000009808249990e+00,-4.000000000000000327e-05,5.063841817398921880e-10,0.000000000000000000e+00 +8.153762201012681032e+01,5.078930421014083549e+02,1.051057489183483684e-01,1.038598848135995745e+01,3.457542618678104054e-03,1.000000009808737600e+00,-4.000000000000000327e-05,1.024623648652906852e-09,0.000000000000000000e+00 +8.153858484577966692e+01,5.079030420416353877e+02,1.051403242756459577e-01,1.038695131702225716e+01,3.457396633276566336e-03,1.000000009809724144e+00,-4.000000000000000327e-05,-1.376208891483084137e-09,0.000000000000000000e+00 +8.153954759218088100e+01,5.079130419818674795e+02,1.051748981730982468e-01,1.038791406343291079e+01,3.457250647875028619e-03,1.000000009808399204e+00,-4.000000000000000327e-05,-9.544629174681548387e-10,0.000000000000000000e+00 +8.154051024935526470e+01,5.079230419221046304e+02,1.052094706107052496e-01,1.038887672061673229e+01,3.457104662473490901e-03,1.000000009807480383e+00,-4.000000000000000327e-05,3.658575326892096918e-10,0.000000000000000000e+00 +8.154147281732761599e+01,5.079330418623468404e+02,1.052440415884669661e-01,1.038983928859852668e+01,3.456958677071953184e-03,1.000000009807832546e+00,-4.000000000000000327e-05,6.604963217084498308e-10,0.000000000000000000e+00 +8.154243529612273278e+01,5.079430418025941094e+02,1.052786111063833824e-01,1.039080176740308836e+01,3.456812691670415466e-03,1.000000009808468260e+00,-4.000000000000000327e-05,-1.998515240170152018e-09,0.000000000000000000e+00 +8.154339768576539882e+01,5.079530417428463807e+02,1.053131791644545123e-01,1.039176415705519929e+01,3.456666706268877749e-03,1.000000009806544909e+00,-4.000000000000000327e-05,5.330175235140346508e-11,0.000000000000000000e+00 +8.154435998628038362e+01,5.079630416831037110e+02,1.053477457626803421e-01,1.039272645757962721e+01,3.456520720867340031e-03,1.000000009806596202e+00,-4.000000000000000327e-05,1.054595520047805204e-09,0.000000000000000000e+00 +8.154532219769245671e+01,5.079730416233661003e+02,1.053823109010608855e-01,1.039368866900113275e+01,3.456374735465802314e-03,1.000000009807610946e+00,-4.000000000000000327e-05,-2.841901875385132043e-09,0.000000000000000000e+00 +8.154628432002634497e+01,5.079830415636335488e+02,1.054168745795961287e-01,1.039465079134446412e+01,3.456228750064264596e-03,1.000000009804876688e+00,-4.000000000000000327e-05,1.789451422269242187e-09,0.000000000000000000e+00 +8.154724635330680371e+01,5.079930415039059994e+02,1.054514367982860856e-01,1.039561282463435354e+01,3.456082764662726878e-03,1.000000009806598200e+00,-4.000000000000000327e-05,-4.131838639253147634e-10,0.000000000000000000e+00 +8.154820829755854561e+01,5.080030414441835092e+02,1.054859975571307423e-01,1.039657476889552967e+01,3.455936779261189161e-03,1.000000009806200740e+00,-4.000000000000000327e-05,-1.780779474264362602e-09,0.000000000000000000e+00 +8.154917015280628334e+01,5.080130413844660779e+02,1.055205568561300988e-01,1.039753662415270341e+01,3.455790793859651443e-03,1.000000009804487888e+00,-4.000000000000000327e-05,1.519828343106094179e-09,0.000000000000000000e+00 +8.155013191907472958e+01,5.080230413247537058e+02,1.055551146952841551e-01,1.039849839043057500e+01,3.455644808458113726e-03,1.000000009805949608e+00,-4.000000000000000327e-05,-2.041556318847773674e-09,0.000000000000000000e+00 +8.155109359638856859e+01,5.080330412650463359e+02,1.055896710745929112e-01,1.039946006775383758e+01,3.455498823056576008e-03,1.000000009803986289e+00,-4.000000000000000327e-05,9.714568817163015761e-10,0.000000000000000000e+00 +8.155205518477247040e+01,5.080430412053440250e+02,1.056242259940563671e-01,1.040042165614716652e+01,3.455352837655038291e-03,1.000000009804920431e+00,-4.000000000000000327e-05,-9.747798082181888539e-10,0.000000000000000000e+00 +8.155301668425110506e+01,5.080530411456467732e+02,1.056587794536745228e-01,1.040138315563523186e+01,3.455206852253500573e-03,1.000000009803983181e+00,-4.000000000000000327e-05,-2.030112920837405354e-10,0.000000000000000000e+00 +8.155397809484912841e+01,5.080630410859545805e+02,1.056933314534473783e-01,1.040234456624268766e+01,3.455060866851962856e-03,1.000000009803788004e+00,-4.000000000000000327e-05,-5.649732861330217693e-10,0.000000000000000000e+00 +8.155493941659119628e+01,5.080730410262673900e+02,1.057278819933749336e-01,1.040330588799417910e+01,3.454914881450425138e-03,1.000000009803244883e+00,-4.000000000000000327e-05,-1.457608703808583242e-10,0.000000000000000000e+00 +8.155590064950193607e+01,5.080830409665852585e+02,1.057624310734571887e-01,1.040426712091433892e+01,3.454768896048887421e-03,1.000000009803104772e+00,-4.000000000000000327e-05,1.046294735088016786e-09,0.000000000000000000e+00 +8.155686179360596100e+01,5.080930409069081861e+02,1.057969786936941436e-01,1.040522826502778919e+01,3.454622910647349703e-03,1.000000009804110412e+00,-4.000000000000000327e-05,-2.765578484717648568e-09,0.000000000000000000e+00 +8.155782284892788425e+01,5.081030408472361728e+02,1.058315248540857983e-01,1.040618932035914135e+01,3.454476925245811986e-03,1.000000009801452538e+00,-4.000000000000000327e-05,1.872772258193730026e-09,0.000000000000000000e+00 +8.155878381549231904e+01,5.081130407875691617e+02,1.058660695546321390e-01,1.040715028693299082e+01,3.454330939844274268e-03,1.000000009803252210e+00,-4.000000000000000327e-05,-4.330535849408883954e-10,0.000000000000000000e+00 +8.155974469332383592e+01,5.081230407279072097e+02,1.059006127953331794e-01,1.040811116477392950e+01,3.454184954442736551e-03,1.000000009802836098e+00,-4.000000000000000327e-05,-1.998608952845980311e-09,0.000000000000000000e+00 +8.156070548244701968e+01,5.081330406682503167e+02,1.059351545761889196e-01,1.040907195390653150e+01,3.454038969041198833e-03,1.000000009800915857e+00,-4.000000000000000327e-05,1.019042589084892970e-09,0.000000000000000000e+00 +8.156166618288642667e+01,5.081430406085984259e+02,1.059696948971993458e-01,1.041003265435536029e+01,3.453892983639661116e-03,1.000000009801894851e+00,-4.000000000000000327e-05,-1.011277569746942266e-09,0.000000000000000000e+00 +8.156262679466662746e+01,5.081530405489515942e+02,1.060042337583644717e-01,1.041099326614497222e+01,3.453746998238123398e-03,1.000000009800923406e+00,-4.000000000000000327e-05,-3.985379224598946138e-10,0.000000000000000000e+00 +8.156358731781214999e+01,5.081630404893098216e+02,1.060387711596842836e-01,1.041195378929990767e+01,3.453601012836585681e-03,1.000000009800540601e+00,-4.000000000000000327e-05,-1.000829373906759798e-09,0.000000000000000000e+00 +8.156454775234752219e+01,5.081730404296731081e+02,1.060733071011587814e-01,1.041291422384469811e+01,3.453455027435047963e-03,1.000000009799579370e+00,-4.000000000000000327e-05,1.025661500108634059e-09,0.000000000000000000e+00 +8.156550809829727200e+01,5.081830403700413967e+02,1.061078415827879790e-01,1.041387456980386261e+01,3.453309042033510246e-03,1.000000009800564360e+00,-4.000000000000000327e-05,-1.049804477724281854e-10,0.000000000000000000e+00 +8.156646835568591314e+01,5.081930403104147445e+02,1.061423746045718625e-01,1.041483482720191134e+01,3.453163056631972528e-03,1.000000009800463552e+00,-4.000000000000000327e-05,-5.487699860073943101e-10,0.000000000000000000e+00 +8.156742852453793091e+01,5.082030402507931512e+02,1.061769061665104319e-01,1.041579499606334025e+01,3.453017071230434810e-03,1.000000009799936640e+00,-4.000000000000000327e-05,-2.240843904141203109e-09,0.000000000000000000e+00 +8.156838860487781062e+01,5.082130401911765603e+02,1.062114362686036872e-01,1.041675507641263465e+01,3.452871085828897093e-03,1.000000009797785250e+00,-4.000000000000000327e-05,2.521152849441714922e-09,0.000000000000000000e+00 +8.156934859673003757e+01,5.082230401315650283e+02,1.062459649108516285e-01,1.041771506827426741e+01,3.452725100427359375e-03,1.000000009800205536e+00,-4.000000000000000327e-05,-1.690484679327493995e-09,0.000000000000000000e+00 +8.157030850011906864e+01,5.082330400719585555e+02,1.062804920932542557e-01,1.041867497167270606e+01,3.452579115025821658e-03,1.000000009798582834e+00,-4.000000000000000327e-05,-1.391747797665110459e-09,0.000000000000000000e+00 +8.157126831506936071e+01,5.082430400123570848e+02,1.063150178158115688e-01,1.041963478663239862e+01,3.452433129624283940e-03,1.000000009797247014e+00,-4.000000000000000327e-05,1.484652321655402058e-09,0.000000000000000000e+00 +8.157222804160534224e+01,5.082530399527606733e+02,1.063495420785235679e-01,1.042059451317778596e+01,3.452287144222746223e-03,1.000000009798671874e+00,-4.000000000000000327e-05,-2.713205022020719649e-09,0.000000000000000000e+00 +8.157318767975145590e+01,5.082630398931693207e+02,1.063840648813902529e-01,1.042155415133330010e+01,3.452141158821208505e-03,1.000000009796068179e+00,-4.000000000000000327e-05,1.437256376888987222e-09,0.000000000000000000e+00 +8.157414722953211594e+01,5.082730398335829705e+02,1.064185862244116237e-01,1.042251370112335529e+01,3.451995173419670788e-03,1.000000009797447298e+00,-4.000000000000000327e-05,4.260558067185748443e-10,0.000000000000000000e+00 +8.157510669097172240e+01,5.082830397740016792e+02,1.064531061075876806e-01,1.042347316257236223e+01,3.451849188018133070e-03,1.000000009797856082e+00,-4.000000000000000327e-05,-1.898796094262770496e-09,0.000000000000000000e+00 +8.157606606409467531e+01,5.082930397144254471e+02,1.064876245309184233e-01,1.042443253570471562e+01,3.451703202616595353e-03,1.000000009796034428e+00,-4.000000000000000327e-05,2.458199722203603924e-10,0.000000000000000000e+00 +8.157702534892536050e+01,5.083030396548542171e+02,1.065221414944038381e-01,1.042539182054479774e+01,3.451557217215057635e-03,1.000000009796270239e+00,-4.000000000000000327e-05,-8.680882529930708540e-10,0.000000000000000000e+00 +8.157798454548814959e+01,5.083130395952880463e+02,1.065566569980439388e-01,1.042635101711698375e+01,3.451411231813519918e-03,1.000000009795437572e+00,-4.000000000000000327e-05,5.426629542198348824e-10,0.000000000000000000e+00 +8.157894365380739998e+01,5.083230395357269344e+02,1.065911710418387254e-01,1.042731012544563463e+01,3.451265246411982200e-03,1.000000009795958045e+00,-4.000000000000000327e-05,-1.322283796377110920e-09,0.000000000000000000e+00 +8.157990267390746908e+01,5.083330394761708249e+02,1.066256836257881840e-01,1.042826914555510243e+01,3.451119261010444483e-03,1.000000009794689948e+00,-4.000000000000000327e-05,1.254096952781368031e-09,0.000000000000000000e+00 +8.158086160581270008e+01,5.083430394166197743e+02,1.066601947498923286e-01,1.042922807746972502e+01,3.450973275608906765e-03,1.000000009795892542e+00,-4.000000000000000327e-05,-1.394083804537154915e-09,0.000000000000000000e+00 +8.158182044954742196e+01,5.083530393570737260e+02,1.066947044141511453e-01,1.043018692121383317e+01,3.450827290207369048e-03,1.000000009794555833e+00,-4.000000000000000327e-05,-1.547297375129144621e-09,0.000000000000000000e+00 +8.158277920513593529e+01,5.083630392975327368e+02,1.067292126185646339e-01,1.043114567681174165e+01,3.450681304805831330e-03,1.000000009793072353e+00,-4.000000000000000327e-05,7.875010710458579358e-10,0.000000000000000000e+00 +8.158373787260255483e+01,5.083730392379968066e+02,1.067637193631328085e-01,1.043210434428775635e+01,3.450535319404293613e-03,1.000000009793827305e+00,-4.000000000000000327e-05,-1.952718867100817500e-10,0.000000000000000000e+00 +8.158469645197158115e+01,5.083830391784658786e+02,1.067982246478556552e-01,1.043306292366617427e+01,3.450389334002755895e-03,1.000000009793640121e+00,-4.000000000000000327e-05,-6.382247698044698526e-10,0.000000000000000000e+00 +8.158565494326730061e+01,5.083930391189400098e+02,1.068327284727331739e-01,1.043402141497127822e+01,3.450243348601218178e-03,1.000000009793028388e+00,-4.000000000000000327e-05,1.384762215945374926e-09,0.000000000000000000e+00 +8.158661334651397112e+01,5.084030390594191999e+02,1.068672308377653646e-01,1.043497981822734033e+01,3.450097363199680460e-03,1.000000009794355549e+00,-4.000000000000000327e-05,-1.869380587514916540e-09,0.000000000000000000e+00 +8.158757166173586484e+01,5.084130389999033923e+02,1.069017317429522274e-01,1.043593813345862387e+01,3.449951377798142742e-03,1.000000009792564093e+00,-4.000000000000000327e-05,-7.389690350212318915e-10,0.000000000000000000e+00 +8.158852988895723968e+01,5.084230389403926438e+02,1.069362311882937622e-01,1.043689636068937610e+01,3.449805392396605025e-03,1.000000009791855993e+00,-4.000000000000000327e-05,-1.033817357610440522e-09,0.000000000000000000e+00 +8.158948802820232515e+01,5.084330388808868975e+02,1.069707291737899690e-01,1.043785449994383718e+01,3.449659406995067307e-03,1.000000009790865452e+00,-4.000000000000000327e-05,1.108541216004596496e-09,0.000000000000000000e+00 +8.159044607949533656e+01,5.084430388213862102e+02,1.070052256994408479e-01,1.043881255124623486e+01,3.449513421593529590e-03,1.000000009791927491e+00,-4.000000000000000327e-05,-1.260927812802393020e-10,0.000000000000000000e+00 +8.159140404286050341e+01,5.084530387618905820e+02,1.070397207652463989e-01,1.043977051462078798e+01,3.449367436191991872e-03,1.000000009791806699e+00,-4.000000000000000327e-05,-8.748489471117360499e-10,0.000000000000000000e+00 +8.159236191832204099e+01,5.084630387023999560e+02,1.070742143712066219e-01,1.044072839009170117e+01,3.449221450790454155e-03,1.000000009790968702e+00,-4.000000000000000327e-05,-1.145475691531740891e-09,0.000000000000000000e+00 +8.159331970590413619e+01,5.084730386429143891e+02,1.071087065173215169e-01,1.044168617768316842e+01,3.449075465388916437e-03,1.000000009789871580e+00,-4.000000000000000327e-05,9.913991870951927579e-10,0.000000000000000000e+00 +8.159427740563096165e+01,5.084830385834338244e+02,1.071431972035910840e-01,1.044264387741937306e+01,3.448929479987378720e-03,1.000000009790821043e+00,-4.000000000000000327e-05,-2.219259099840016827e-09,0.000000000000000000e+00 +8.159523501752670427e+01,5.084930385239583188e+02,1.071776864300153093e-01,1.044360148932448951e+01,3.448783494585841002e-03,1.000000009788695854e+00,-4.000000000000000327e-05,8.369073828389713058e-10,0.000000000000000000e+00 +8.159619254161552249e+01,5.085030384644878154e+02,1.072121741965942066e-01,1.044455901342267623e+01,3.448637509184303285e-03,1.000000009789497213e+00,-4.000000000000000327e-05,4.663826697280493805e-10,0.000000000000000000e+00 +8.159714997792156055e+01,5.085130384050223711e+02,1.072466605033277620e-01,1.044551644973808635e+01,3.448491523782765567e-03,1.000000009789943745e+00,-4.000000000000000327e-05,-1.402059511571945399e-09,0.000000000000000000e+00 +8.159810732646896270e+01,5.085230383455619858e+02,1.072811453502159895e-01,1.044647379829485878e+01,3.448345538381227850e-03,1.000000009788601485e+00,-4.000000000000000327e-05,-9.006941361362249402e-10,0.000000000000000000e+00 +8.159906458728185896e+01,5.085330382861066028e+02,1.073156287372588752e-01,1.044743105911712000e+01,3.448199552979690132e-03,1.000000009787739286e+00,-4.000000000000000327e-05,2.574973229223509938e-11,0.000000000000000000e+00 +8.160002176038435096e+01,5.085430382266562788e+02,1.073501106644564329e-01,1.044838823222898760e+01,3.448053567578152415e-03,1.000000009787763933e+00,-4.000000000000000327e-05,-5.690980205676533146e-10,0.000000000000000000e+00 +8.160097884580056871e+01,5.085530381672109570e+02,1.073845911318086488e-01,1.044934531765456853e+01,3.447907582176614697e-03,1.000000009787219257e+00,-4.000000000000000327e-05,1.184704716371425820e-09,0.000000000000000000e+00 +8.160193584355458540e+01,5.085630381077706943e+02,1.074190701393155367e-01,1.045030231541795729e+01,3.447761596775076980e-03,1.000000009788353017e+00,-4.000000000000000327e-05,-2.478918839879052711e-09,0.000000000000000000e+00 +8.160289275367050266e+01,5.085730380483354338e+02,1.074535476869770828e-01,1.045125922554323949e+01,3.447615611373539262e-03,1.000000009785980915e+00,-4.000000000000000327e-05,7.124382377913849993e-11,0.000000000000000000e+00 +8.160384957617237944e+01,5.085830379889052324e+02,1.074880237747932871e-01,1.045221604805448479e+01,3.447469625972001545e-03,1.000000009786049082e+00,-4.000000000000000327e-05,1.068291021626306189e-09,0.000000000000000000e+00 +8.160480631108428895e+01,5.085930379294800332e+02,1.075224984027641495e-01,1.045317278297575747e+01,3.447323640570463827e-03,1.000000009787071154e+00,-4.000000000000000327e-05,-1.437206928404896977e-09,0.000000000000000000e+00 +8.160576295843027594e+01,5.086030378700598931e+02,1.075569715708896701e-01,1.045412943033110942e+01,3.447177655168926109e-03,1.000000009785696253e+00,-4.000000000000000327e-05,3.103555423401059330e-10,0.000000000000000000e+00 +8.160671951823438519e+01,5.086130378106447552e+02,1.075914432791698488e-01,1.045508599014457829e+01,3.447031669767388392e-03,1.000000009785993127e+00,-4.000000000000000327e-05,-1.461381378308426730e-09,0.000000000000000000e+00 +8.160767599052064725e+01,5.086230377512346763e+02,1.076259135276046858e-01,1.045604246244019464e+01,3.446885684365850674e-03,1.000000009784595356e+00,-4.000000000000000327e-05,-9.356482505137095910e-10,0.000000000000000000e+00 +8.160863237531306424e+01,5.086330376918296565e+02,1.076603823161941809e-01,1.045699884724197481e+01,3.446739698964312957e-03,1.000000009783700516e+00,-4.000000000000000327e-05,1.881451920020576349e-09,0.000000000000000000e+00 +8.160958867263565253e+01,5.086430376324296390e+02,1.076948496449383341e-01,1.045795514457392628e+01,3.446593713562775239e-03,1.000000009785499744e+00,-4.000000000000000327e-05,-2.731060054890964581e-09,0.000000000000000000e+00 +8.161054488251241423e+01,5.086530375730346805e+02,1.077293155138371455e-01,1.045891135446004760e+01,3.446447728161237522e-03,1.000000009782888277e+00,-4.000000000000000327e-05,7.603357005004295436e-10,0.000000000000000000e+00 +8.161150100496733728e+01,5.086630375136447242e+02,1.077637799228906151e-01,1.045986747692431962e+01,3.446301742759699804e-03,1.000000009783615251e+00,-4.000000000000000327e-05,6.923542838757378362e-10,0.000000000000000000e+00 +8.161245704002438117e+01,5.086730374542598270e+02,1.077982428720987290e-01,1.046082351199071958e+01,3.446155757358162087e-03,1.000000009784277166e+00,-4.000000000000000327e-05,-2.946200737288024678e-09,0.000000000000000000e+00 +8.161341298770751962e+01,5.086830373948799320e+02,1.078327043614615011e-01,1.046177945968321055e+01,3.446009771956624369e-03,1.000000009781460752e+00,-4.000000000000000327e-05,1.501343064268136663e-09,0.000000000000000000e+00 +8.161436884804069791e+01,5.086930373355050961e+02,1.078671643909789313e-01,1.046273532002574136e+01,3.445863786555086652e-03,1.000000009782895827e+00,-4.000000000000000327e-05,-1.524712176633279153e-09,0.000000000000000000e+00 +8.161532462104786134e+01,5.087030372761352623e+02,1.079016229606510058e-01,1.046369109304225731e+01,3.445717801153548934e-03,1.000000009781438548e+00,-4.000000000000000327e-05,1.578057460348403392e-09,0.000000000000000000e+00 +8.161628030675294099e+01,5.087130372167704877e+02,1.079360800704777384e-01,1.046464677875668592e+01,3.445571815752011217e-03,1.000000009782946675e+00,-4.000000000000000327e-05,-2.812042938871459713e-09,0.000000000000000000e+00 +8.161723590517985372e+01,5.087230371574107153e+02,1.079705357204591154e-01,1.046560237719294939e+01,3.445425830350473499e-03,1.000000009780259491e+00,-4.000000000000000327e-05,8.588877694860639080e-10,0.000000000000000000e+00 +8.161819141635251640e+01,5.087330370980560019e+02,1.080049899105951505e-01,1.046655788837495216e+01,3.445279844948935782e-03,1.000000009781080168e+00,-4.000000000000000327e-05,-1.033966602234762893e-09,0.000000000000000000e+00 +8.161914684029481748e+01,5.087430370387062908e+02,1.080394426408858299e-01,1.046751331232659510e+01,3.445133859547398064e-03,1.000000009780092292e+00,-4.000000000000000327e-05,1.229530819873041141e-09,0.000000000000000000e+00 +8.162010217703064541e+01,5.087530369793616387e+02,1.080738939113311536e-01,1.046846864907176311e+01,3.444987874145860347e-03,1.000000009781266908e+00,-4.000000000000000327e-05,-2.088766033038399734e-09,0.000000000000000000e+00 +8.162105742658387442e+01,5.087630369200219889e+02,1.081083437219311355e-01,1.046942389863433398e+01,3.444841888744322629e-03,1.000000009779271615e+00,-4.000000000000000327e-05,6.822933139026104079e-10,0.000000000000000000e+00 +8.162201258897836453e+01,5.087730368606873412e+02,1.081427920726857617e-01,1.047037906103816951e+01,3.444695903342784912e-03,1.000000009779923316e+00,-4.000000000000000327e-05,-2.145642071889525741e-09,0.000000000000000000e+00 +8.162296766423797578e+01,5.087830368013577527e+02,1.081772389635950321e-01,1.047133413630712617e+01,3.444549917941247194e-03,1.000000009777874066e+00,-4.000000000000000327e-05,1.103028982432996542e-09,0.000000000000000000e+00 +8.162392265238655398e+01,5.087930367420331663e+02,1.082116843946589468e-01,1.047228912446504445e+01,3.444403932539709477e-03,1.000000009778927446e+00,-4.000000000000000327e-05,-1.264273929318192606e-09,0.000000000000000000e+00 +8.162487755344793072e+01,5.088030366827136390e+02,1.082461283658775059e-01,1.047324402553575950e+01,3.444257947138171759e-03,1.000000009777720189e+00,-4.000000000000000327e-05,4.837096850421746518e-10,0.000000000000000000e+00 +8.162583236744592341e+01,5.088130366233991140e+02,1.082805708772507092e-01,1.047419883954309050e+01,3.444111961736634041e-03,1.000000009778182042e+00,-4.000000000000000327e-05,-1.453587089520354157e-09,0.000000000000000000e+00 +8.162678709440434943e+01,5.088230365640896480e+02,1.083150119287785568e-01,1.047515356651084950e+01,3.443965976335096324e-03,1.000000009776794263e+00,-4.000000000000000327e-05,7.112759183056688604e-10,0.000000000000000000e+00 +8.162774173434699776e+01,5.088330365047851842e+02,1.083494515204610487e-01,1.047610820646283436e+01,3.443819990933558606e-03,1.000000009777473275e+00,-4.000000000000000327e-05,-8.255553579580654706e-10,0.000000000000000000e+00 +8.162869628729767157e+01,5.088430364454857795e+02,1.083838896522981848e-01,1.047706275942283582e+01,3.443674005532020889e-03,1.000000009776685239e+00,-4.000000000000000327e-05,-2.242625751787933088e-10,0.000000000000000000e+00 +8.162965075328013143e+01,5.088530363861913770e+02,1.084183263242899514e-01,1.047801722541463043e+01,3.443528020130483171e-03,1.000000009776471188e+00,-4.000000000000000327e-05,-1.390833825299445816e-09,0.000000000000000000e+00 +8.163060513231815207e+01,5.088630363269020336e+02,1.084527615364363623e-01,1.047897160446198583e+01,3.443382034728945454e-03,1.000000009775143806e+00,-4.000000000000000327e-05,1.517073019676565789e-09,0.000000000000000000e+00 +8.163155942443549407e+01,5.088730362676176924e+02,1.084871952887374175e-01,1.047992589658865725e+01,3.443236049327407736e-03,1.000000009776591536e+00,-4.000000000000000327e-05,-1.260076459397909092e-09,0.000000000000000000e+00 +8.163251362965590374e+01,5.088830362083383534e+02,1.085216275811931030e-01,1.048088010181839280e+01,3.443090063925870019e-03,1.000000009775389165e+00,-4.000000000000000327e-05,-1.928336879590091206e-09,0.000000000000000000e+00 +8.163346774800311323e+01,5.088930361490640735e+02,1.085560584138034329e-01,1.048183422017492461e+01,3.442944078524332301e-03,1.000000009773549303e+00,-4.000000000000000327e-05,1.458370607024052546e-09,0.000000000000000000e+00 +8.163442177950084044e+01,5.089030360897947958e+02,1.085904877865683932e-01,1.048278825168197592e+01,3.442798093122794584e-03,1.000000009774940635e+00,-4.000000000000000327e-05,-8.661172908765698380e-10,0.000000000000000000e+00 +8.163537572417280330e+01,5.089130360305305771e+02,1.086249156994879977e-01,1.048374219636326288e+01,3.442652107721256866e-03,1.000000009774114407e+00,-4.000000000000000327e-05,-1.102706521298130742e-09,0.000000000000000000e+00 +8.163632958204270551e+01,5.089230359712713607e+02,1.086593421525622327e-01,1.048469605424248563e+01,3.442506122319719149e-03,1.000000009773062581e+00,-4.000000000000000327e-05,-1.210363693404807381e-09,0.000000000000000000e+00 +8.163728335313423656e+01,5.089330359120172034e+02,1.086937671457911120e-01,1.048564982534333545e+01,3.442360136918181431e-03,1.000000009771908172e+00,-4.000000000000000327e-05,7.562259847818698726e-10,0.000000000000000000e+00 +8.163823703747107174e+01,5.089430358527680482e+02,1.087281906791746217e-01,1.048660350968949295e+01,3.442214151516643714e-03,1.000000009772629372e+00,-4.000000000000000327e-05,-1.069244322337995533e-09,0.000000000000000000e+00 +8.163919063507688634e+01,5.089530357935238953e+02,1.087626127527127617e-01,1.048755710730462987e+01,3.442068166115105996e-03,1.000000009771609744e+00,-4.000000000000000327e-05,1.118244368864581166e-09,0.000000000000000000e+00 +8.164014414597534142e+01,5.089630357342848015e+02,1.087970333664055322e-01,1.048851061821240371e+01,3.441922180713568279e-03,1.000000009772676002e+00,-4.000000000000000327e-05,-5.025803309988666608e-10,0.000000000000000000e+00 +8.164109757019008384e+01,5.089730356750507099e+02,1.088314525202529331e-01,1.048946404243646491e+01,3.441776195312030561e-03,1.000000009772196830e+00,-4.000000000000000327e-05,-2.033096616092586740e-09,0.000000000000000000e+00 +8.164205090774474627e+01,5.089830356158216773e+02,1.088658702142549783e-01,1.049041738000044965e+01,3.441630209910492844e-03,1.000000009770258602e+00,-4.000000000000000327e-05,4.295304034389786203e-10,0.000000000000000000e+00 +8.164300415866296134e+01,5.089930355565976470e+02,1.089002864484116540e-01,1.049137063092798350e+01,3.441484224508955126e-03,1.000000009770668052e+00,-4.000000000000000327e-05,-9.411391077340581200e-10,0.000000000000000000e+00 +8.164395732296834751e+01,5.090030354973786189e+02,1.089347012227229600e-01,1.049232379524268488e+01,3.441338239107417409e-03,1.000000009769770992e+00,-4.000000000000000327e-05,-2.877258406447306003e-10,0.000000000000000000e+00 +8.164491040068450900e+01,5.090130354381646498e+02,1.089691145371888825e-01,1.049327687296815803e+01,3.441192253705879691e-03,1.000000009769496767e+00,-4.000000000000000327e-05,4.270845123810625213e-10,0.000000000000000000e+00 +8.164586339183503583e+01,5.090230353789556830e+02,1.090035263918094355e-01,1.049422986412799830e+01,3.441046268304341973e-03,1.000000009769903775e+00,-4.000000000000000327e-05,-2.716765168073028281e-09,0.000000000000000000e+00 +8.164681629644351801e+01,5.090330353197517184e+02,1.090379367865846189e-01,1.049518276874579037e+01,3.440900282902804256e-03,1.000000009767314957e+00,-4.000000000000000327e-05,2.011367127897510047e-09,0.000000000000000000e+00 +8.164776911453353136e+01,5.090430352605528128e+02,1.090723457215144326e-01,1.049613558684510473e+01,3.440754297501266538e-03,1.000000009769231424e+00,-4.000000000000000327e-05,-1.047842381717414128e-09,0.000000000000000000e+00 +8.164872184612862327e+01,5.090530352013589095e+02,1.091067531965988768e-01,1.049708831844950829e+01,3.440608312099728821e-03,1.000000009768233111e+00,-4.000000000000000327e-05,-2.119649370868166690e-09,0.000000000000000000e+00 +8.164967449125235532e+01,5.090630351421700652e+02,1.091411592118379376e-01,1.049804096358255023e+01,3.440462326698191103e-03,1.000000009766213838e+00,-4.000000000000000327e-05,7.475623979893261675e-10,0.000000000000000000e+00 +8.165062704992827491e+01,5.090730350829862232e+02,1.091755637672316287e-01,1.049899352226777083e+01,3.440316341296653386e-03,1.000000009766925935e+00,-4.000000000000000327e-05,-4.278094575926514320e-01,0.000000000000000000e+00 +8.165157952217990101e+01,5.090830350238073834e+02,1.092099668627799364e-01,1.049994599452870325e+01,3.440170355895115668e-03,9.995925331295841820e-01,-4.000000000000000327e-05,-9.999997658662448385e-01,0.000000000000000000e+00 +8.165253190803076677e+01,5.090930349646336026e+02,1.092443684984828745e-01,1.050089799231388277e+01,3.440024370493577951e-03,9.986401475017082641e-01,-4.000000000000000327e-05,-9.999998882124145894e-01,0.000000000000000000e+00 +8.165348420753956304e+01,5.091030349054648241e+02,1.092787686743404291e-01,1.050184899683581286e+01,3.439878385092040233e-03,9.976878480993672804e-01,-4.000000000000000327e-05,-9.999999283130458494e-01,0.000000000000000000e+00 +8.165443642081200437e+01,5.091130348463010478e+02,1.093131673903526141e-01,1.050279900844653014e+01,3.439732399690502516e-03,9.967356348951835754e-01,-4.000000000000000327e-05,-9.999999475678335026e-01,0.000000000000000000e+00 +8.165538854795372004e+01,5.091230347871423305e+02,1.093475646465194157e-01,1.050374802749763603e+01,3.439586414288964798e-03,9.957835078033829834e-01,-4.000000000000000327e-05,-9.999999603914024870e-01,0.000000000000000000e+00 +8.165634058907026827e+01,5.091330347279886155e+02,1.093819604428408337e-01,1.050469605434024167e+01,3.439440428887427081e-03,9.948314667245475862e-01,-4.000000000000000327e-05,-9.999999694477019752e-01,0.000000000000000000e+00 +8.165729254426709360e+01,5.091430346688399027e+02,1.094163547793168823e-01,1.050564308932495550e+01,3.439294443485889363e-03,9.938795115568066496e-01,-4.000000000000000327e-05,-9.999999754399058194e-01,0.000000000000000000e+00 +8.165824441364956954e+01,5.091530346096962489e+02,1.094507476559475473e-01,1.050658913280188145e+01,3.439148458084351646e-03,9.929276421977037970e-01,-4.000000000000000327e-05,-9.999999771104601809e-01,0.000000000000000000e+00 +8.165919619732299850e+01,5.091630345505575974e+02,1.094851390727328289e-01,1.050753418512061899e+01,3.439002472682813928e-03,9.919758585460632938e-01,-4.000000000000000327e-05,-9.999999849673542052e-01,0.000000000000000000e+00 +8.166014789539256924e+01,5.091730344914239481e+02,1.095195290296727270e-01,1.050847824663026486e+01,3.438856487281276211e-03,9.910241604907922275e-01,-4.000000000000000327e-05,-9.999999840232264292e-01,0.000000000000000000e+00 +8.166109950796341366e+01,5.091830344322953579e+02,1.095539175267672416e-01,1.050942131767940424e+01,3.438710501879738493e-03,9.900725479351456526e-01,-4.000000000000000327e-05,-9.999999887077550831e-01,0.000000000000000000e+00 +8.166205103514057839e+01,5.091930343731717699e+02,1.095883045640163728e-01,1.051036339861612490e+01,3.438564516478200776e-03,9.891210207687302081e-01,-4.000000000000000327e-05,-9.999999879506946687e-01,0.000000000000000000e+00 +8.166300247702899640e+01,5.092030343140531841e+02,1.096226901414201205e-01,1.051130448978800480e+01,3.438418531076663058e-03,9.881695788917705947e-01,-4.000000000000000327e-05,-9.999999902977998456e-01,0.000000000000000000e+00 +8.166395383373355799e+01,5.092130342549396573e+02,1.096570742589784847e-01,1.051224459154212276e+01,3.438272545675125341e-03,9.872182221964438398e-01,-4.000000000000000327e-05,-9.999999944852766554e-01,0.000000000000000000e+00 +8.166490510535903979e+01,5.092230341958311328e+02,1.096914569166914655e-01,1.051318370422505133e+01,3.438126560273587623e-03,9.862669505762136080e-01,-4.000000000000000327e-05,-9.999999913930156525e-01,0.000000000000000000e+00 +8.166585629201013319e+01,5.092330341367276105e+02,1.097258381145590489e-01,1.051412182818285856e+01,3.437980574872049905e-03,9.853157639333024465e-01,-4.000000000000000327e-05,-9.999999954576206385e-01,0.000000000000000000e+00 +8.166680739379147269e+01,5.092430340776290905e+02,1.097602178525812489e-01,1.051505896376111693e+01,3.437834589470512188e-03,9.843646621562837096e-01,-4.000000000000000327e-05,-9.999999955923269956e-01,0.000000000000000000e+00 +8.166775841080759335e+01,5.092530340185356295e+02,1.097945961307580653e-01,1.051599511130489084e+01,3.437688604068974470e-03,9.834136451443594718e-01,-4.000000000000000327e-05,-9.999999964155770193e-01,0.000000000000000000e+00 +8.166870934316294495e+01,5.092630339594471707e+02,1.098289729490894845e-01,1.051693027115874735e+01,3.437542618667436753e-03,9.824627127924220327e-01,-4.000000000000000327e-05,-9.999999966535429996e-01,0.000000000000000000e+00 +8.166966019096189200e+01,5.092730339003637141e+02,1.098633483075755202e-01,1.051786444366675255e+01,3.437396633265899035e-03,9.815118649966579900e-01,-4.000000000000000327e-05,-9.999999969956586687e-01,0.000000000000000000e+00 +8.167061095430872797e+01,5.092830338412853166e+02,1.098977222062161585e-01,1.051879762917247341e+01,3.437250647864361318e-03,9.805611016526810664e-01,-4.000000000000000327e-05,-9.999999981298164364e-01,0.000000000000000000e+00 +8.167156163330764684e+01,5.092930337822119213e+02,1.099320946450114134e-01,1.051972982801897771e+01,3.437104662462823600e-03,9.796104226555336636e-01,-4.000000000000000327e-05,-9.999999987776829746e-01,0.000000000000000000e+00 +8.167251222806278577e+01,5.093030337231435283e+02,1.099664656239612709e-01,1.052066104054883411e+01,3.436958677061285883e-03,9.786598279015560342e-01,-4.000000000000000327e-05,-9.999999976583344719e-01,0.000000000000000000e+00 +8.167346273867818240e+01,5.093130336640801374e+02,1.100008351430657449e-01,1.052159126710411385e+01,3.436812691659748165e-03,9.777093172883881689e-01,-4.000000000000000327e-05,-1.000000001354804269e+00,0.000000000000000000e+00 +8.167441316525778916e+01,5.093230336050218057e+02,1.100352032023248217e-01,1.052252050802639260e+01,3.436666706258210448e-03,9.767588907074951088e-01,-4.000000000000000327e-05,-9.999999987510964639e-01,0.000000000000000000e+00 +8.167536350790548738e+01,5.093330335459684761e+02,1.100695698017385010e-01,1.052344876365674509e+01,3.436520720856672730e-03,9.758085480609891560e-01,-4.000000000000000327e-05,-1.000000002329075155e+00,0.000000000000000000e+00 +8.167631376672505894e+01,5.093430334869201488e+02,1.101039349413067830e-01,1.052437603433575575e+01,3.436374735455135013e-03,9.748582892392019250e-01,-4.000000000000000327e-05,-9.999999989995655980e-01,0.000000000000000000e+00 +8.167726394182022887e+01,5.093530334278768237e+02,1.101382986210296816e-01,1.052530232040350811e+01,3.436228750053597295e-03,9.739081141449853485e-01,-4.000000000000000327e-05,-1.000000001244888637e+00,0.000000000000000000e+00 +8.167821403329462271e+01,5.093630333688385576e+02,1.101726608409071828e-01,1.052622762219959718e+01,3.436082764652059578e-03,9.729580226694118927e-01,-4.000000000000000327e-05,-1.000000001873596833e+00,0.000000000000000000e+00 +8.167916404125178076e+01,5.093730333098052938e+02,1.102070216009392867e-01,1.052715194006311883e+01,3.435936779250521860e-03,9.720080147104688262e-01,-4.000000000000000327e-05,-1.000000001561098362e+00,0.000000000000000000e+00 +8.168011396579518646e+01,5.093830332507770322e+02,1.102413809011259932e-01,1.052807527433267687e+01,3.435790793848984143e-03,9.710580901655827546e-01,-4.000000000000000327e-05,-1.000000000982189219e+00,0.000000000000000000e+00 +8.168106380702820957e+01,5.093930331917537728e+02,1.102757387414672885e-01,1.052899762534638306e+01,3.435644808447446425e-03,9.701082489316202873e-01,-4.000000000000000327e-05,-1.000000002779803276e+00,0.000000000000000000e+00 +8.168201356505417721e+01,5.094030331327355725e+02,1.103100951219631864e-01,1.052991899344185711e+01,3.435498823045908708e-03,9.691584909030188655e-01,-4.000000000000000327e-05,-1.000000001719500542e+00,0.000000000000000000e+00 +8.168296323997628861e+01,5.094130330737223744e+02,1.103444500426136871e-01,1.053083937895622491e+01,3.435352837644370990e-03,9.682088159792684445e-01,-4.000000000000000327e-05,-1.000000002410924793e+00,0.000000000000000000e+00 +8.168391283189770036e+01,5.094230330147141785e+02,1.103788035034187903e-01,1.053175878222612383e+01,3.435206852242833273e-03,9.672592240555617504e-01,-4.000000000000000327e-05,-1.000000003555041816e+00,0.000000000000000000e+00 +8.168486234092148379e+01,5.094330329557109849e+02,1.104131555043784962e-01,1.053267720358769921e+01,3.435060866841295555e-03,9.663097150284060133e-01,-4.000000000000000327e-05,-1.000000003850576524e+00,0.000000000000000000e+00 +8.168581176715061076e+01,5.094430328967128503e+02,1.104475060454927909e-01,1.053359464337660611e+01,3.434914881439757837e-03,9.653602887956245215e-01,-4.000000000000000327e-05,-1.000000001993314402e+00,0.000000000000000000e+00 +8.168676111068798207e+01,5.094530328377197179e+02,1.104818551267616883e-01,1.053451110192801110e+01,3.434768896038220120e-03,9.644109452563588425e-01,-4.000000000000000327e-05,-1.000000002591295845e+00,0.000000000000000000e+00 +8.168771037163642745e+01,5.094630327787315878e+02,1.105162027481851744e-01,1.053542657957659401e+01,3.434622910636682402e-03,9.634616843054559787e-01,-4.000000000000000327e-05,-1.000000004339828275e+00,0.000000000000000000e+00 +8.168865955009867719e+01,5.094730327197484598e+02,1.105505489097632632e-01,1.053634107665654440e+01,3.434476925235144685e-03,9.625125058390819888e-01,-4.000000000000000327e-05,-1.000000001987050746e+00,0.000000000000000000e+00 +8.168960864617740469e+01,5.094830326607703341e+02,1.105848936114959408e-01,1.053725459350156335e+01,3.434330939833606967e-03,9.615634097584676576e-01,-4.000000000000000327e-05,-1.000000006055419499e+00,0.000000000000000000e+00 +8.169055765997518392e+01,5.094930326017972675e+02,1.106192368533832210e-01,1.053816713044486875e+01,3.434184954432069250e-03,9.606143959549365841e-01,-4.000000000000000327e-05,-1.000000003400962179e+00,0.000000000000000000e+00 +8.169150659159453198e+01,5.095030325428292031e+02,1.106535786354250900e-01,1.053907868781918644e+01,3.434038969030531532e-03,9.596654643323663247e-01,-4.000000000000000327e-05,-1.000000002572018820e+00,0.000000000000000000e+00 +8.169245544113785229e+01,5.095130324838661409e+02,1.106879189576215478e-01,1.053998926595676267e+01,3.433892983628993815e-03,9.587166147866011956e-01,-4.000000000000000327e-05,-1.000000006202289571e+00,0.000000000000000000e+00 +8.169340420870750563e+01,5.095230324249080809e+02,1.107222578199726082e-01,1.054089886518935693e+01,3.433746998227456097e-03,9.577678472110665586e-01,-4.000000000000000327e-05,-1.000000003109503544e+00,0.000000000000000000e+00 +8.169435289440573911e+01,5.095330323659550231e+02,1.107565952224782574e-01,1.054180748584824023e+01,3.433601012825918380e-03,9.568191615098765590e-01,-4.000000000000000327e-05,-1.000000005790991908e+00,0.000000000000000000e+00 +8.169530149833475718e+01,5.095430323070070244e+02,1.107909311651384954e-01,1.054271512826420576e+01,3.433455027424380662e-03,9.558705575753677630e-01,-4.000000000000000327e-05,-1.000000003058506559e+00,0.000000000000000000e+00 +8.169625002059665064e+01,5.095530322480640280e+02,1.108252656479533221e-01,1.054362179276755818e+01,3.433309042022842945e-03,9.549220353105694059e-01,-4.000000000000000327e-05,-1.000000005436817663e+00,0.000000000000000000e+00 +8.169719846129345342e+01,5.095630321891260337e+02,1.108595986709227377e-01,1.054452747968812432e+01,3.433163056621305227e-03,9.539735946086060903e-01,-4.000000000000000327e-05,-1.000000003706358553e+00,0.000000000000000000e+00 +8.169814682052711419e+01,5.095730321301930417e+02,1.108939302340467420e-01,1.054543218935524429e+01,3.433017071219767510e-03,9.530252353714258051e-01,-4.000000000000000327e-05,-1.000000004442262558e+00,0.000000000000000000e+00 +8.169909509839951056e+01,5.095830320712650519e+02,1.109282603373253351e-01,1.054633592209778037e+01,3.432871085818229792e-03,9.520769574948190206e-01,-4.000000000000000327e-05,-1.000000006320804768e+00,0.000000000000000000e+00 +8.170004329501242069e+01,5.095930320123420643e+02,1.109625889807585170e-01,1.054723867824411165e+01,3.432725100416692075e-03,9.511287608759103618e-01,-4.000000000000000327e-05,-1.000000004063733572e+00,0.000000000000000000e+00 +8.170099141046756586e+01,5.096030319534241357e+02,1.109969161643462876e-01,1.054814045812213585e+01,3.432579115015154357e-03,9.501806454169073879e-01,-4.000000000000000327e-05,-1.000000006221522630e+00,0.000000000000000000e+00 +8.170193944486658211e+01,5.096130318945112094e+02,1.110312418880886332e-01,1.054904126205927462e+01,3.432433129613616640e-03,9.492326110119886362e-01,-4.000000000000000327e-05,-1.000000005537097447e+00,0.000000000000000000e+00 +8.170288739831103442e+01,5.096230318356032853e+02,1.110655661519855675e-01,1.054994109038246641e+01,3.432287144212078922e-03,9.482846575622910779e-01,-4.000000000000000327e-05,-1.000000004630730022e+00,0.000000000000000000e+00 +8.170383527090238829e+01,5.096330317767003635e+02,1.110998889560370906e-01,1.055083994341817366e+01,3.432141158810541205e-03,9.473367849665451645e-01,-4.000000000000000327e-05,-1.000000004146743393e+00,0.000000000000000000e+00 +8.170478306274205238e+01,5.096430317178024438e+02,1.111342103002431886e-01,1.055173782149238093e+01,3.431995173409003487e-03,9.463889931229483299e-01,-4.000000000000000327e-05,-1.000000006706523559e+00,0.000000000000000000e+00 +8.170573077393135009e+01,5.096530316589095264e+02,1.111685301846038754e-01,1.055263472493059496e+01,3.431849188007465769e-03,9.454412819272913771e-01,-4.000000000000000327e-05,-1.000000005040807327e+00,0.000000000000000000e+00 +8.170667840457153375e+01,5.096630316000216681e+02,1.112028486091191370e-01,1.055353065405784285e+01,3.431703202605928052e-03,9.444936512823318697e-01,-4.000000000000000327e-05,-1.000000005723311158e+00,0.000000000000000000e+00 +8.170762595476377044e+01,5.096730315411388119e+02,1.112371655737889875e-01,1.055442560919867923e+01,3.431557217204390334e-03,9.435461010846747376e-01,-4.000000000000000327e-05,-1.000000005436883388e+00,0.000000000000000000e+00 +8.170857342460914197e+01,5.096830314822609580e+02,1.112714810786134129e-01,1.055531959067718084e+01,3.431411231802852617e-03,9.425986312341455564e-01,-4.000000000000000327e-05,-1.000000006798890562e+00,0.000000000000000000e+00 +8.170952081420867330e+01,5.096930314233881063e+02,1.113057951235924270e-01,1.055621259881695018e+01,3.431265246401314899e-03,9.416512416281670461e-01,-4.000000000000000327e-05,-1.000000004508407647e+00,0.000000000000000000e+00 +8.171046812366330414e+01,5.097030313645202568e+02,1.113401077087260160e-01,1.055710463394111365e+01,3.431119260999777182e-03,9.407039321692608480e-01,-4.000000000000000327e-05,-1.000000007118366341e+00,0.000000000000000000e+00 +8.171141535307390313e+01,5.097130313056574096e+02,1.113744188340141800e-01,1.055799569637232693e+01,3.430973275598239464e-03,9.397567027519229121e-01,-4.000000000000000327e-05,-1.000000005365659028e+00,0.000000000000000000e+00 +8.171236250254123945e+01,5.097230312467995645e+02,1.114087284994569188e-01,1.055888578643276787e+01,3.430827290196701747e-03,9.388095532795005527e-01,-4.000000000000000327e-05,-1.000000005822708760e+00,0.000000000000000000e+00 +8.171330957216603963e+01,5.097330311879467217e+02,1.114430367050542325e-01,1.055977490444414535e+01,3.430681304795164029e-03,9.378624836491920025e-01,-4.000000000000000327e-05,-1.000000005161116867e+00,0.000000000000000000e+00 +8.171425656204891652e+01,5.097430311290988811e+02,1.114773434508061212e-01,1.056066305072769396e+01,3.430535319393626312e-03,9.369154937614243561e-01,-4.000000000000000327e-05,-1.000000007973832261e+00,0.000000000000000000e+00 +8.171520347229044035e+01,5.097530310702560996e+02,1.115116487367125847e-01,1.056155022560417756e+01,3.430389333992088594e-03,9.359685835123515707e-01,-4.000000000000000327e-05,-1.000000004985138302e+00,0.000000000000000000e+00 +8.171615030299108184e+01,5.097630310114183203e+02,1.115459525627736231e-01,1.056243642939388572e+01,3.430243348590550877e-03,9.350217528069870720e-01,-4.000000000000000327e-05,-1.000000006729662161e+00,0.000000000000000000e+00 +8.171709705425125492e+01,5.097730309525855432e+02,1.115802549289892365e-01,1.056332166241664261e+01,3.430097363189013159e-03,9.340750015404452045e-01,-4.000000000000000327e-05,-1.000000003926296621e+00,0.000000000000000000e+00 +8.171804372617127399e+01,5.097830308937577684e+02,1.116145558353594247e-01,1.056420592499179811e+01,3.429951377787475442e-03,9.331283296167034447e-01,-4.000000000000000327e-05,-1.000000009094430986e+00,0.000000000000000000e+00 +8.171899031885141085e+01,5.097930308349349957e+02,1.116488552818841878e-01,1.056508921743823670e+01,3.429805392385937724e-03,9.321817369279631338e-01,-4.000000000000000327e-05,-1.000000005018028881e+00,0.000000000000000000e+00 +8.171993683239182360e+01,5.098030307761172253e+02,1.116831532685635259e-01,1.056597154007436679e+01,3.429659406984400007e-03,9.312352233827982939e-01,-4.000000000000000327e-05,-1.000000006197475422e+00,0.000000000000000000e+00 +8.172088326689262772e+01,5.098130307173044571e+02,1.117174497953974249e-01,1.056685289321813670e+01,3.429513421582862289e-03,9.302887888761325330e-01,-4.000000000000000327e-05,-1.000000007308937233e+00,0.000000000000000000e+00 +8.172182962245383919e+01,5.098230306584966911e+02,1.117517448623858989e-01,1.056773327718702227e+01,3.429367436181324572e-03,9.293424333080042565e-01,-4.000000000000000327e-05,-1.000000006989330004e+00,0.000000000000000000e+00 +8.172277589917541718e+01,5.098330305996939273e+02,1.117860384695289477e-01,1.056861269229803213e+01,3.429221450779786854e-03,9.283961565798168891e-01,-4.000000000000000327e-05,-1.000000005858763030e+00,0.000000000000000000e+00 +8.172372209715723557e+01,5.098430305408961658e+02,1.118203306168265576e-01,1.056949113886770952e+01,3.429075465378249137e-03,9.274499585924618206e-01,-4.000000000000000327e-05,-1.000000006520073148e+00,0.000000000000000000e+00 +8.172466821649908297e+01,5.098530304821034065e+02,1.118546213042787424e-01,1.057036861721213228e+01,3.428929479976711419e-03,9.265038392444425730e-01,-4.000000000000000327e-05,-1.000000005623539634e+00,0.000000000000000000e+00 +8.172561425730070539e+01,5.098630304233156494e+02,1.118889105318854882e-01,1.057124512764691104e+01,3.428783494575173701e-03,9.255577984375068512e-01,-4.000000000000000327e-05,-1.000000007754840547e+00,0.000000000000000000e+00 +8.172656021966173512e+01,5.098730303645329514e+02,1.119231982996468089e-01,1.057212067048719284e+01,3.428637509173635984e-03,9.246118360691387705e-01,-4.000000000000000327e-05,-1.000000005589911423e+00,0.000000000000000000e+00 +8.172750610368176183e+01,5.098830303057552555e+02,1.119574846075626906e-01,1.057299524604765750e+01,3.428491523772098266e-03,9.236659520438254001e-01,-4.000000000000000327e-05,-1.000000007683921499e+00,0.000000000000000000e+00 +8.172845190946028993e+01,5.098930302469825619e+02,1.119917694556331333e-01,1.057386885464252479e+01,3.428345538370560549e-03,9.227201462580356672e-01,-4.000000000000000327e-05,-1.000000006708570810e+00,0.000000000000000000e+00 +8.172939763709673855e+01,5.099030301882148706e+02,1.120260528438581371e-01,1.057474149658554730e+01,3.428199552969022831e-03,9.217744186152443397e-01,-4.000000000000000327e-05,-1.000000007246961475e+00,0.000000000000000000e+00 +8.173034328669046999e+01,5.099130301294521814e+02,1.120603347722377158e-01,1.057561317219001751e+01,3.428053567567485114e-03,9.208287690146655935e-01,-4.000000000000000327e-05,-1.000000005938006531e+00,0.000000000000000000e+00 +8.173128885834076129e+01,5.099230300706944945e+02,1.120946152407718555e-01,1.057648388176876431e+01,3.427907582165947396e-03,9.198831973587661137e-01,-4.000000000000000327e-05,-1.000000007364536092e+00,0.000000000000000000e+00 +8.173223435214680421e+01,5.099330300119418098e+02,1.121288942494605562e-01,1.057735362563415649e+01,3.427761596764409679e-03,9.189377035457529930e-01,-4.000000000000000327e-05,-1.000000006174813549e+00,0.000000000000000000e+00 +8.173317976820774788e+01,5.099430299531941273e+02,1.121631717983038179e-01,1.057822240409809922e+01,3.427615611362871961e-03,9.179922874789673282e-01,-4.000000000000000327e-05,-1.000000006950551468e+00,0.000000000000000000e+00 +8.173412510662265618e+01,5.099530298944514470e+02,1.121974478873016406e-01,1.057909021747203937e+01,3.427469625961334244e-03,9.170469490574919558e-01,-4.000000000000000327e-05,-1.000000008311350053e+00,0.000000000000000000e+00 +8.173507036749050769e+01,5.099630298357137690e+02,1.122317225164540244e-01,1.057995706606696196e+01,3.427323640559796526e-03,9.161016881817884983e-01,-4.000000000000000327e-05,-1.000000004897928285e+00,0.000000000000000000e+00 +8.173601555091020998e+01,5.099730297769810932e+02,1.122659956857609692e-01,1.058082295019339192e+01,3.427177655158258809e-03,9.151565047574575784e-01,-4.000000000000000327e-05,-1.000000009244136345e+00,0.000000000000000000e+00 +8.173696065698059954e+01,5.099830297182534196e+02,1.123002673952224612e-01,1.058168787016139945e+01,3.427031669756721091e-03,9.142113986783261259e-01,-4.000000000000000327e-05,-1.000000004055891845e+00,0.000000000000000000e+00 +8.173790568580045601e+01,5.099930296595307482e+02,1.123345376448385141e-01,1.058255182628058932e+01,3.426885684355183374e-03,9.132663698546393816e-01,-4.000000000000000327e-05,-1.000000009823957869e+00,0.000000000000000000e+00 +8.173885063746845958e+01,5.100030296008130790e+02,1.123688064346091281e-01,1.058341481886011692e+01,3.426739698953645656e-03,9.123214181773505738e-01,-4.000000000000000327e-05,-1.000000005268351089e+00,0.000000000000000000e+00 +8.173979551208323358e+01,5.100130295421004121e+02,1.124030737645342892e-01,1.058427684820867043e+01,3.426593713552107939e-03,9.113765435575952312e-01,-4.000000000000000327e-05,-1.000000008893758841e+00,0.000000000000000000e+00 +8.174074030974333027e+01,5.100230294833927474e+02,1.124373396346140114e-01,1.058513791463449039e+01,3.426447728150570221e-03,9.104317458890960335e-01,-4.000000000000000327e-05,-1.000000005379731993e+00,0.000000000000000000e+00 +8.174168503054721668e+01,5.100330294246900849e+02,1.124716040448482945e-01,1.058599801844535371e+01,3.426301742749032504e-03,9.094870250801236899e-01,-4.000000000000000327e-05,-1.000000009255447520e+00,0.000000000000000000e+00 +8.174262967459330298e+01,5.100430293659924246e+02,1.125058669952371249e-01,1.058685715994858789e+01,3.426155757347494786e-03,9.085423810252948318e-01,-4.000000000000000327e-05,-1.000000005192917207e+00,0.000000000000000000e+00 +8.174357424197991406e+01,5.100530293072997665e+02,1.125401284857805162e-01,1.058771533945105858e+01,3.426009771945957069e-03,9.075978136337784496e-01,-4.000000000000000327e-05,-1.000000007722157802e+00,0.000000000000000000e+00 +8.174451873280530378e+01,5.100630292486121107e+02,1.125743885164784547e-01,1.058857255725918378e+01,3.425863786544419351e-03,9.066533228010904555e-01,-4.000000000000000327e-05,-1.000000009475057405e+00,0.000000000000000000e+00 +8.174546314716766915e+01,5.100730291899294571e+02,1.126086470873309403e-01,1.058942881367892141e+01,3.425717801142881633e-03,9.057089084297789139e-01,-4.000000000000000327e-05,-1.000000005067381181e+00,0.000000000000000000e+00 +8.174640748516510769e+01,5.100830291312518057e+02,1.126429041983379870e-01,1.059028410901577644e+01,3.425571815741343916e-03,9.047645704275482093e-01,-4.000000000000000327e-05,-1.000000007041917272e+00,0.000000000000000000e+00 +8.174735174689567430e+01,5.100930290725791565e+02,1.126771598494995807e-01,1.059113844357480616e+01,3.425425830339806198e-03,9.038203086903294770e-01,-4.000000000000000327e-05,-1.000000008022548181e+00,0.000000000000000000e+00 +8.174829593245733861e+01,5.101030290139115095e+02,1.127114140408157217e-01,1.059199181766060960e+01,3.425279844938268481e-03,9.028761231210914451e-01,-4.000000000000000327e-05,-1.000000006605278102e+00,0.000000000000000000e+00 +8.174924004194799920e+01,5.101130289552488648e+02,1.127456667722864098e-01,1.059284423157733457e+01,3.425133859536730763e-03,9.019320136241997243e-01,-4.000000000000000327e-05,-1.000000009357444819e+00,0.000000000000000000e+00 +8.175018407546546939e+01,5.101230288965912223e+02,1.127799180439116450e-01,1.059369568562867947e+01,3.424987874135193046e-03,9.009879800978910502e-01,-4.000000000000000327e-05,-1.000000004906875128e+00,0.000000000000000000e+00 +8.175112803310751985e+01,5.101330288379385820e+02,1.128141678556914274e-01,1.059454618011788796e+01,3.424841888733655328e-03,9.000440224512092913e-01,-4.000000000000000327e-05,-1.000000009787568311e+00,0.000000000000000000e+00 +8.175207191497183601e+01,5.101430287792909439e+02,1.128484162076257569e-01,1.059539571534775959e+01,3.424695903332117611e-03,8.991001405776617439e-01,-4.000000000000000327e-05,-1.000000004647487950e+00,0.000000000000000000e+00 +8.175301572115601800e+01,5.101530287206483081e+02,1.128826630997146335e-01,1.059624429162063564e+01,3.424549917930579893e-03,8.981563343890934803e-01,-4.000000000000000327e-05,-1.000000010010995810e+00,0.000000000000000000e+00 +8.175395945175760914e+01,5.101630286620106745e+02,1.129169085319580573e-01,1.059709190923841682e+01,3.424403932529042176e-03,8.972126037780487895e-01,-4.000000000000000327e-05,-1.000000006517675288e+00,0.000000000000000000e+00 +8.175490310687409590e+01,5.101730286033780430e+02,1.129511525043560283e-01,1.059793856850254556e+01,3.424257947127504458e-03,8.962689486554147322e-01,-4.000000000000000327e-05,-1.000000006716498246e+00,0.000000000000000000e+00 +8.175584668660286525e+01,5.101830285447504139e+02,1.129853950169085325e-01,1.059878426971402376e+01,3.424111961725966741e-03,8.953253689203061194e-01,-4.000000000000000327e-05,-1.000000009194282891e+00,0.000000000000000000e+00 +8.175679019104124734e+01,5.101930284861277300e+02,1.130196360696155838e-01,1.059962901317340211e+01,3.423965976324429023e-03,8.943818644732425271e-01,-4.000000000000000327e-05,-1.000000006549023102e+00,0.000000000000000000e+00 +8.175773362028651547e+01,5.102030284275100485e+02,1.130538756624771823e-01,1.060047279918078189e+01,3.423819990922891306e-03,8.934384352217977776e-01,-4.000000000000000327e-05,-1.000000007341192099e+00,0.000000000000000000e+00 +8.175867697443584348e+01,5.102130283688973691e+02,1.130881137954933141e-01,1.060131562803582206e+01,3.423674005521353588e-03,8.924950810655393196e-01,-4.000000000000000327e-05,-1.000000008157001963e+00,0.000000000000000000e+00 +8.175962025358636254e+01,5.102230283102896919e+02,1.131223504686639930e-01,1.060215750003773216e+01,3.423528020119815871e-03,8.915518019073257472e-01,-4.000000000000000327e-05,-1.000000007576709482e+00,0.000000000000000000e+00 +8.176056345783511858e+01,5.102330282516870170e+02,1.131565856819892052e-01,1.060299841548527588e+01,3.423382034718278153e-03,8.906085976514248603e-01,-4.000000000000000327e-05,-1.000000006174468492e+00,0.000000000000000000e+00 +8.176150658727908649e+01,5.102430281930893443e+02,1.131908194354689645e-01,1.060383837467677282e+01,3.423236049316740436e-03,8.896654682016326143e-01,-4.000000000000000327e-05,-1.000000008519289940e+00,0.000000000000000000e+00 +8.176244964201518428e+01,5.102530281344966738e+02,1.132250517291032571e-01,1.060467737791009846e+01,3.423090063915202718e-03,8.887224134575057999e-01,-4.000000000000000327e-05,-1.000000009193405370e+00,0.000000000000000000e+00 +8.176339262214024473e+01,5.102630280759090056e+02,1.132592825628920968e-01,1.060551542548268067e+01,3.422944078513665001e-03,8.877794333237806201e-01,-4.000000000000000327e-05,-1.000000004771680828e+00,0.000000000000000000e+00 +8.176433552775102953e+01,5.102730280173263395e+02,1.132935119368354698e-01,1.060635251769150500e+01,3.422798093112127283e-03,8.868365277084920839e-01,-4.000000000000000327e-05,-1.000000009810954493e+00,0.000000000000000000e+00 +8.176527835894425777e+01,5.102830279587486757e+02,1.133277398509333761e-01,1.060718865483311824e+01,3.422652107710589565e-03,8.858936965060189017e-01,-4.000000000000000327e-05,-1.000000006898809302e+00,0.000000000000000000e+00 +8.176622111581654906e+01,5.102930279001760141e+02,1.133619663051858156e-01,1.060802383720361597e+01,3.422506122309051848e-03,8.849509396272269290e-01,-4.000000000000000327e-05,-1.000000008593075584e+00,0.000000000000000000e+00 +8.176716379846446614e+01,5.103030278416083547e+02,1.133961912995927884e-01,1.060885806509865859e+01,3.422360136907514130e-03,8.840082569712114369e-01,-4.000000000000000327e-05,-1.000000007467454655e+00,0.000000000000000000e+00 +8.176810640698450072e+01,5.103130277830456407e+02,1.134304148341543084e-01,1.060969133881346060e+01,3.422214151505976413e-03,8.830656484441379295e-01,-4.000000000000000327e-05,-1.000000006086590121e+00,0.000000000000000000e+00 +8.176904894147307346e+01,5.103230277244879289e+02,1.134646369088703616e-01,1.061052365864279778e+01,3.422068166104438695e-03,8.821231139498230123e-01,-4.000000000000000327e-05,-1.000000009015939106e+00,0.000000000000000000e+00 +8.176999140202654814e+01,5.103330276659352194e+02,1.134988575237409481e-01,1.061135502488100535e+01,3.421922180702900978e-03,8.811806533878493441e-01,-4.000000000000000327e-05,-1.000000008822046649e+00,0.000000000000000000e+00 +8.177093378874120333e+01,5.103430276073875120e+02,1.135330766787660539e-01,1.061218543782197443e+01,3.421776195301363260e-03,8.802382666648744802e-01,-4.000000000000000327e-05,-1.000000006065958846e+00,0.000000000000000000e+00 +8.177187610171326071e+01,5.103530275488448069e+02,1.135672943739456930e-01,1.061301489775915918e+01,3.421630209899825543e-03,8.792959536870952331e-01,-4.000000000000000327e-05,-1.000000009312837168e+00,0.000000000000000000e+00 +8.177281834103887093e+01,5.103630274903071040e+02,1.136015106092798654e-01,1.061384340498557677e+01,3.421484224498287825e-03,8.783537143527059277e-01,-4.000000000000000327e-05,-1.000000007120316337e+00,0.000000000000000000e+00 +8.177376050681411357e+01,5.103730274317744033e+02,1.136357253847685711e-01,1.061467095979380026e+01,3.421338239096750108e-03,8.774115485707512097e-01,-4.000000000000000327e-05,-1.000000008051726619e+00,0.000000000000000000e+00 +8.177470259913499717e+01,5.103830273732467049e+02,1.136699387004118100e-01,1.061549756247596932e+01,3.421192253695212390e-03,8.764694562422753465e-01,-4.000000000000000327e-05,-1.000000006662610907e+00,0.000000000000000000e+00 +8.177564461809747343e+01,5.103930273147239518e+02,1.137041505562095683e-01,1.061632321332378304e+01,3.421046268293674673e-03,8.755274372735202260e-01,-4.000000000000000327e-05,-1.000000009516764710e+00,0.000000000000000000e+00 +8.177658656379742297e+01,5.104030272562062009e+02,1.137383609521618599e-01,1.061714791262850532e+01,3.420900282892136955e-03,8.745854915646125161e-01,-4.000000000000000327e-05,-1.000000007161172100e+00,0.000000000000000000e+00 +8.177752843633064117e+01,5.104130271976934523e+02,1.137725698882686709e-01,1.061797166068095954e+01,3.420754297490599238e-03,8.736436190246512634e-01,-4.000000000000000327e-05,-1.000000008160435438e+00,0.000000000000000000e+00 +8.177847023579286656e+01,5.104230271391857059e+02,1.138067773645300151e-01,1.061879445777153741e+01,3.420608312089061520e-03,8.727018195547360246e-01,-4.000000000000000327e-05,-1.000000007062290086e+00,0.000000000000000000e+00 +8.177941196227978082e+01,5.104330270806829617e+02,1.138409833809458788e-01,1.061961630419019187e+01,3.420462326687523803e-03,8.717600930611693055e-01,-4.000000000000000327e-05,-1.000000008426493947e+00,0.000000000000000000e+00 +8.178035361588699459e+01,5.104430270221852197e+02,1.138751879375162757e-01,1.062043720022644244e+01,3.420316341285986085e-03,8.708184394460269928e-01,-4.000000000000000327e-05,-1.000000008799947437e+00,0.000000000000000000e+00 +8.178129519671003322e+01,5.104530269636924800e+02,1.139093910342411919e-01,1.062125714616937167e+01,3.420170355884448368e-03,8.698768586147043180e-01,-4.000000000000000327e-05,-1.000000006730395796e+00,0.000000000000000000e+00 +8.178223670484436525e+01,5.104630269052046856e+02,1.139435926711206276e-01,1.062207614230762864e+01,3.420024370482910650e-03,8.689353504740309209e-01,-4.000000000000000327e-05,-1.000000006775839223e+00,0.000000000000000000e+00 +8.178317814038540234e+01,5.104730268467218934e+02,1.139777928481545966e-01,1.062289418892943083e+01,3.419878385081372933e-03,8.679939149266120424e-01,-4.000000000000000327e-05,-1.000000009487676866e+00,0.000000000000000000e+00 +8.178411950342848513e+01,5.104830267882441035e+02,1.140119915653430849e-01,1.062371128632256045e+01,3.419732399679835215e-03,8.670525518746013960e-01,-4.000000000000000327e-05,-1.000000009401234458e+00,0.000000000000000000e+00 +8.178506079406886897e+01,5.104930267297713158e+02,1.140461888226860926e-01,1.062452743477436456e+01,3.419586414278297497e-03,8.661112612253640819e-01,-4.000000000000000327e-05,-1.000000007062953111e+00,0.000000000000000000e+00 +8.178600201240176659e+01,5.105030266713035303e+02,1.140803846201836197e-01,1.062534263457176031e+01,3.419440428876759780e-03,8.651700428858171144e-01,-4.000000000000000327e-05,-1.000000007029656857e+00,0.000000000000000000e+00 +8.178694315852231966e+01,5.105130266128407470e+02,1.141145789578356662e-01,1.062615688600123498e+01,3.419294443475222062e-03,8.642288967586551074e-01,-4.000000000000000327e-05,-1.000000007842295480e+00,0.000000000000000000e+00 +8.178788423252558459e+01,5.105230265543829091e+02,1.141487718356422321e-01,1.062697018934884241e+01,3.419148458073684345e-03,8.632878227480128563e-01,-4.000000000000000327e-05,-1.000000008040066168e+00,0.000000000000000000e+00 +8.178882523450656095e+01,5.105330264959300735e+02,1.141829632536033173e-01,1.062778254490020480e+01,3.419002472672146627e-03,8.623468207594664481e-01,-4.000000000000000327e-05,-1.000000010173088816e+00,0.000000000000000000e+00 +8.178976616456019144e+01,5.105430264374822400e+02,1.142171532117189220e-01,1.062859395294051446e+01,3.418856487270608910e-03,8.614058906962587248e-01,-4.000000000000000327e-05,-1.000000006757915560e+00,0.000000000000000000e+00 +8.179070702278134775e+01,5.105530263790394088e+02,1.142513417099890460e-01,1.062940441375453204e+01,3.418710501869071192e-03,8.604650324687400653e-01,-4.000000000000000327e-05,-1.000000006361013050e+00,0.000000000000000000e+00 +8.179164780926483047e+01,5.105630263206015798e+02,1.142855287484136756e-01,1.063021392762659367e+01,3.418564516467533475e-03,8.595242459792665768e-01,-4.000000000000000327e-05,-1.000000009525568556e+00,0.000000000000000000e+00 +8.179258852410538339e+01,5.105730262621686961e+02,1.143197143269928245e-01,1.063102249484060380e+01,3.418418531065995757e-03,8.585835311297500549e-01,-4.000000000000000327e-05,-1.000000008762054637e+00,0.000000000000000000e+00 +8.179352916739767920e+01,5.105830262037408147e+02,1.143538984457264929e-01,1.063183011568003522e+01,3.418272545664458040e-03,8.576428878292139402e-01,-4.000000000000000327e-05,-1.000000006614758297e+00,0.000000000000000000e+00 +8.179446973923631958e+01,5.105930261453179355e+02,1.143880811046146667e-01,1.063263679042793619e+01,3.418126560262920322e-03,8.567023159843535351e-01,-4.000000000000000327e-05,-1.000000009645604981e+00,0.000000000000000000e+00 +8.179541023971584934e+01,5.106030260869000585e+02,1.144222623036573599e-01,1.063344251936692864e+01,3.417980574861382605e-03,8.557618154957580270e-01,-4.000000000000000327e-05,-1.000000008351229042e+00,0.000000000000000000e+00 +8.179635066893072803e+01,5.106130260284871838e+02,1.144564420428545587e-01,1.063424730277920283e+01,3.417834589459844887e-03,8.548213862730205115e-01,-4.000000000000000327e-05,-1.000000007282180636e+00,0.000000000000000000e+00 +8.179729102697538679e+01,5.106230259700792544e+02,1.144906203222062768e-01,1.063505114094652626e+01,3.417688604058307170e-03,8.538810282215194558e-01,-4.000000000000000327e-05,-1.000000006973430944e+00,0.000000000000000000e+00 +8.179823131394415725e+01,5.106330259116763273e+02,1.145247971417125005e-01,1.063585403415024011e+01,3.417542618656769452e-03,8.529407412461956772e-01,-4.000000000000000327e-05,-1.000000009968676329e+00,0.000000000000000000e+00 +8.179917152993131424e+01,5.106430258532784023e+02,1.145589725013732296e-01,1.063665598267125922e+01,3.417396633255231735e-03,8.520005252496637427e-01,-4.000000000000000327e-05,-1.000000006752963966e+00,0.000000000000000000e+00 +8.180011167503107572e+01,5.106530257948854796e+02,1.145931464011884782e-01,1.063745698679007035e+01,3.417250647853694017e-03,8.510603801435494553e-01,-4.000000000000000327e-05,-1.000000007905105237e+00,0.000000000000000000e+00 +8.180105174933760281e+01,5.106630257364975023e+02,1.146273188411582322e-01,1.063825704678674100e+01,3.417104662452156300e-03,8.501203058295974113e-01,-4.000000000000000327e-05,-1.000000009937079382e+00,0.000000000000000000e+00 +8.180199175294495717e+01,5.106730256781145272e+02,1.146614898212824918e-01,1.063905616294091061e+01,3.416958677050618582e-03,8.491803022128967537e-01,-4.000000000000000327e-05,-1.000000007346974584e+00,0.000000000000000000e+00 +8.180293168594717201e+01,5.106830256197365543e+02,1.146956593415612569e-01,1.063985433553179405e+01,3.416812691649080864e-03,8.482403692037729925e-01,-4.000000000000000327e-05,-1.000000008704651444e+00,0.000000000000000000e+00 +8.180387154843820952e+01,5.106930255613635836e+02,1.147298274019945274e-01,1.064065156483818697e+01,3.416666706247543147e-03,8.473005067045608074e-01,-4.000000000000000327e-05,-1.000000006494682570e+00,0.000000000000000000e+00 +8.180481134051194658e+01,5.107030255029955583e+02,1.147639940025823035e-01,1.064144785113845870e+01,3.416520720846005429e-03,8.463607146247231761e-01,-4.000000000000000327e-05,-1.000000009288090519e+00,0.000000000000000000e+00 +8.180575106226220328e+01,5.107130254446325353e+02,1.147981591433245852e-01,1.064224319471055935e+01,3.416374735444467712e-03,8.454209928657323569e-01,-4.000000000000000327e-05,-1.000000009565479742e+00,0.000000000000000000e+00 +8.180669071378275703e+01,5.107230253862745144e+02,1.148323228242213723e-01,1.064303759583201270e+01,3.416228750042929994e-03,8.444813413361915710e-01,-4.000000000000000327e-05,-1.000000005837818451e+00,0.000000000000000000e+00 +8.180763029516730001e+01,5.107330253279214958e+02,1.148664850452726649e-01,1.064383105477992331e+01,3.416082764641392277e-03,8.435417599461667582e-01,-4.000000000000000327e-05,-1.000000008689085895e+00,0.000000000000000000e+00 +8.180856980650945331e+01,5.107430252695734225e+02,1.149006458064784630e-01,1.064462357183097829e+01,3.415936779239854559e-03,8.426022485958433172e-01,-4.000000000000000327e-05,-1.000000010594290778e+00,0.000000000000000000e+00 +8.180950924790280965e+01,5.107530252112303515e+02,1.149348051078387667e-01,1.064541514726143845e+01,3.415790793838316842e-03,8.416628071925412735e-01,-4.000000000000000327e-05,-1.000000006034562405e+00,0.000000000000000000e+00 +8.181044861944084801e+01,5.107630251528922827e+02,1.149689629493535620e-01,1.064620578134714535e+01,3.415644808436779124e-03,8.407234356488285654e-01,-4.000000000000000327e-05,-1.000000007608341734e+00,0.000000000000000000e+00 +8.181138792121703318e+01,5.107730250945592161e+02,1.150031193310228628e-01,1.064699547436352667e+01,3.415498823035241407e-03,8.397841338655017696e-01,-4.000000000000000327e-05,-1.000000009797041178e+00,0.000000000000000000e+00 +8.181232715332473049e+01,5.107830250362310949e+02,1.150372742528466691e-01,1.064778422658558554e+01,3.415352837633703689e-03,8.388449017486055981e-01,-4.000000000000000327e-05,-1.000000009091373210e+00,0.000000000000000000e+00 +8.181326631585724840e+01,5.107930249779079759e+02,1.150714277148249670e-01,1.064857203828790588e+01,3.415206852232165972e-03,8.379057392075441868e-01,-4.000000000000000327e-05,-1.000000006007326636e+00,0.000000000000000000e+00 +8.181420540890785276e+01,5.108030249195898591e+02,1.151055797169577705e-01,1.064935890974465593e+01,3.415060866830628254e-03,8.369666461512998978e-01,-4.000000000000000327e-05,-1.000000009119475619e+00,0.000000000000000000e+00 +8.181514443256972413e+01,5.108130248612766877e+02,1.151397302592450655e-01,1.065014484122958827e+01,3.414914881429090537e-03,8.360276224808661505e-01,-4.000000000000000327e-05,-1.000000008871466006e+00,0.000000000000000000e+00 +8.181608338693598625e+01,5.108230248029685185e+02,1.151738793416868661e-01,1.065092983301603269e+01,3.414768896027552819e-03,8.350886681062738015e-01,-4.000000000000000327e-05,-1.000000007791896239e+00,0.000000000000000000e+00 +8.181702227209970602e+01,5.108330247446653516e+02,1.152080269642831584e-01,1.065171388537690511e+01,3.414622910626015102e-03,8.341497829352420013e-01,-4.000000000000000327e-05,-1.000000008409519525e+00,0.000000000000000000e+00 +8.181796108815387925e+01,5.108430246863671869e+02,1.152421731270339422e-01,1.065249699858470578e+01,3.414476925224477384e-03,8.332109668731786378e-01,-4.000000000000000327e-05,-1.000000009221774011e+00,0.000000000000000000e+00 +8.181889983519143072e+01,5.108530246280739675e+02,1.152763178299392316e-01,1.065327917291151749e+01,3.414330939822939667e-03,8.322722198269653093e-01,-4.000000000000000327e-05,-1.000000006708945177e+00,0.000000000000000000e+00 +8.181983851330524260e+01,5.108630245697857504e+02,1.153104610729990126e-01,1.065406040862900738e+01,3.414184954421401949e-03,8.313335417068502542e-01,-4.000000000000000327e-05,-1.000000009445162652e+00,0.000000000000000000e+00 +8.182077712258812596e+01,5.108730245115025355e+02,1.153446028562132852e-01,1.065484070600843047e+01,3.414038969019864232e-03,8.303949324150958766e-01,-4.000000000000000327e-05,-1.000000007859818130e+00,0.000000000000000000e+00 +8.182171566313283506e+01,5.108830244532242659e+02,1.153787431795820495e-01,1.065562006532062256e+01,3.413892983618326514e-03,8.294563918630105670e-01,-4.000000000000000327e-05,-1.000000008510808058e+00,0.000000000000000000e+00 +8.182265413503205309e+01,5.108930243949509986e+02,1.154128820431053054e-01,1.065639848683600910e+01,3.413746998216788796e-03,8.285179199558098118e-01,-4.000000000000000327e-05,-1.000000007871920227e+00,0.000000000000000000e+00 +8.182359253837839219e+01,5.109030243366827335e+02,1.154470194467830529e-01,1.065717597082459989e+01,3.413601012815251079e-03,8.275795166020808447e-01,-4.000000000000000327e-05,-1.000000010485347035e+00,0.000000000000000000e+00 +8.182453087326442187e+01,5.109130242784194138e+02,1.154811553906152921e-01,1.065795251755599260e+01,3.413455027413713361e-03,8.266411817062107037e-01,-4.000000000000000327e-05,-1.000000006768842375e+00,0.000000000000000000e+00 +8.182546913978264058e+01,5.109230242201610963e+02,1.155152898746020229e-01,1.065872812729936925e+01,3.413309042012175644e-03,8.257029151816398516e-01,-4.000000000000000327e-05,-1.000000007315019257e+00,0.000000000000000000e+00 +8.182640733802548993e+01,5.109330241619077810e+02,1.155494228987432453e-01,1.065950280032350506e+01,3.413163056610637926e-03,8.247647169319314298e-01,-4.000000000000000327e-05,-1.000000008593767697e+00,0.000000000000000000e+00 +8.182734546808534049e+01,5.109430241036594111e+02,1.155835544630389455e-01,1.066027653689675958e+01,3.413017071209100209e-03,8.238265868640229916e-01,-4.000000000000000327e-05,-1.000000011108126419e+00,0.000000000000000000e+00 +8.182828353005450595e+01,5.109530240454160435e+02,1.156176845674891374e-01,1.066104933728708026e+01,3.412871085807562491e-03,8.228885248844420852e-01,-4.000000000000000327e-05,-1.000000005265762049e+00,0.000000000000000000e+00 +8.182922152402522897e+01,5.109630239871776780e+02,1.156518132120938208e-01,1.066182120176200243e+01,3.412725100406024774e-03,8.219505309087756784e-01,-4.000000000000000327e-05,-1.000000009737608053e+00,0.000000000000000000e+00 +8.183015945008970959e+01,5.109730239289442579e+02,1.156859403968529820e-01,1.066259213058865818e+01,3.412579115004487056e-03,8.210126048351585881e-01,-4.000000000000000327e-05,-1.000000008872356405e+00,0.000000000000000000e+00 +8.183109730834007678e+01,5.109830238707158401e+02,1.157200661217666349e-01,1.066336212403376038e+01,3.412433129602949339e-03,8.200747465764678390e-01,-4.000000000000000327e-05,-1.000000007206039765e+00,0.000000000000000000e+00 +8.183203509886840266e+01,5.109930238124924244e+02,1.157541903868347655e-01,1.066413118236361690e+01,3.412287144201411621e-03,8.191369560413868101e-01,-4.000000000000000327e-05,-1.000000009277544732e+00,0.000000000000000000e+00 +8.183297282176668830e+01,5.110030237542739542e+02,1.157883131920573877e-01,1.066489930584412704e+01,3.412141158799873904e-03,8.181992331344036806e-01,-4.000000000000000327e-05,-1.000000007503665911e+00,0.000000000000000000e+00 +8.183391047712687794e+01,5.110130236960604861e+02,1.158224345374344877e-01,1.066566649474077799e+01,3.411995173398336186e-03,8.172615777671788928e-01,-4.000000000000000327e-05,-1.000000010462347211e+00,0.000000000000000000e+00 +8.183484806504085896e+01,5.110230236378519635e+02,1.158565544229660793e-01,1.066643274931865193e+01,3.411849187996798469e-03,8.163239898433904962e-01,-4.000000000000000327e-05,-1.000000006525307850e+00,0.000000000000000000e+00 +8.183578558560044769e+01,5.110330235796484430e+02,1.158906728486521487e-01,1.066719806984241892e+01,3.411703202595260751e-03,8.153864692776801038e-01,-4.000000000000000327e-05,-1.000000008311066724e+00,0.000000000000000000e+00 +8.183672303889741784e+01,5.110430235214499248e+02,1.159247898144926958e-01,1.066796245657634756e+01,3.411557217193723034e-03,8.144490159729194101e-01,-4.000000000000000327e-05,-1.000000010252032112e+00,0.000000000000000000e+00 +8.183766042502347204e+01,5.110530234632563520e+02,1.159589053204877207e-01,1.066872590978429436e+01,3.411411231792185316e-03,8.135116298372608856e-01,-4.000000000000000327e-05,-1.000000006774635297e+00,0.000000000000000000e+00 +8.183859774407024190e+01,5.110630234050677814e+02,1.159930193666372233e-01,1.066948842972970901e+01,3.411265246390647599e-03,8.125743107841417734e-01,-4.000000000000000327e-05,-1.000000010501503445e+00,0.000000000000000000e+00 +8.183953499612931637e+01,5.110730233468842130e+02,1.160271319529412037e-01,1.067025001667563977e+01,3.411119260989109881e-03,8.116370587152280658e-01,-4.000000000000000327e-05,-1.000000005746910281e+00,0.000000000000000000e+00 +8.184047218129221335e+01,5.110830232887055899e+02,1.160612430793996758e-01,1.067101067088472277e+01,3.410973275587572164e-03,8.106998735469479467e-01,-4.000000000000000327e-05,-1.000000011201472194e+00,0.000000000000000000e+00 +8.184140929965039390e+01,5.110930232305319691e+02,1.160953527460126256e-01,1.067177039261919624e+01,3.410827290186034446e-03,8.097627551782727862e-01,-4.000000000000000327e-05,-1.000000007128922563e+00,0.000000000000000000e+00 +8.184234635129526225e+01,5.111030231723632937e+02,1.161294609527800392e-01,1.067252918214088453e+01,3.410681304784496728e-03,8.088257035267299999e-01,-4.000000000000000327e-05,-1.000000008175458088e+00,0.000000000000000000e+00 +8.184328333631815156e+01,5.111130231141996205e+02,1.161635676997019306e-01,1.067328703971121584e+01,3.410535319382959011e-03,8.078887184961818235e-01,-4.000000000000000327e-05,-1.000000008760640213e+00,0.000000000000000000e+00 +8.184422025481035234e+01,5.111230230560408927e+02,1.161976729867782998e-01,1.067404396559120983e+01,3.410389333981421293e-03,8.069517999957798171e-01,-4.000000000000000327e-05,-1.000000007345270614e+00,0.000000000000000000e+00 +8.184515710686306988e+01,5.111330229978871671e+02,1.162317768140091467e-01,1.067479996004148290e+01,3.410243348579883576e-03,8.060149479361772284e-01,-4.000000000000000327e-05,-1.000000010487550606e+00,0.000000000000000000e+00 +8.184609389256748102e+01,5.111430229397384437e+02,1.162658791813944714e-01,1.067555502332225004e+01,3.410097363178345858e-03,8.050781622219429501e-01,-4.000000000000000327e-05,-1.000000006526135188e+00,0.000000000000000000e+00 +8.184703061201467733e+01,5.111530228815946657e+02,1.162999800889342600e-01,1.067630915569331940e+01,3.409951377776808141e-03,8.041414427686297550e-01,-4.000000000000000327e-05,-1.000000010114856064e+00,0.000000000000000000e+00 +8.184796726529570776e+01,5.111630228234558899e+02,1.163340795366285263e-01,1.067706235741410303e+01,3.409805392375270423e-03,8.032047894781229047e-01,-4.000000000000000327e-05,-1.000000009589348871e+00,0.000000000000000000e+00 +8.184890385250155020e+01,5.111730227653220595e+02,1.163681775244772565e-01,1.067781462874360443e+01,3.409659406973732706e-03,8.022682022632932064e-01,-4.000000000000000327e-05,-1.000000005428818506e+00,0.000000000000000000e+00 +8.184984037372313992e+01,5.111830227071932313e+02,1.164022740524804644e-01,1.067856596994042917e+01,3.409513421572194988e-03,8.013316810366211129e-01,-4.000000000000000327e-05,-1.000000010266489880e+00,0.000000000000000000e+00 +8.185077682905132690e+01,5.111930226490694054e+02,1.164363691206381363e-01,1.067931638126278493e+01,3.409367436170657271e-03,8.003952256988150493e-01,-4.000000000000000327e-05,-1.000000008378939320e+00,0.000000000000000000e+00 +8.185171321857693272e+01,5.112030225909505248e+02,1.164704627289502858e-01,1.068006586296847082e+01,3.409221450769119553e-03,7.994588361653675035e-01,-4.000000000000000327e-05,-1.000000008346412450e+00,0.000000000000000000e+00 +8.185264954239069368e+01,5.112130225328366464e+02,1.165045548774168993e-01,1.068081441531489162e+01,3.409075465367581836e-03,7.985225123437946770e-01,-4.000000000000000327e-05,-1.000000008621209080e+00,0.000000000000000000e+00 +8.185358580058328926e+01,5.112230224747277134e+02,1.165386455660379766e-01,1.068156203855905062e+01,3.408929479966044118e-03,7.975862541431210095e-01,-4.000000000000000327e-05,-1.000000009680702684e+00,0.000000000000000000e+00 +8.185452199324537048e+01,5.112330224166237826e+02,1.165727347948135317e-01,1.068230873295755146e+01,3.408783494564506401e-03,7.966500614719828066e-01,-4.000000000000000327e-05,-1.000000007946729497e+00,0.000000000000000000e+00 +8.185545812046748892e+01,5.112430223585247973e+02,1.166068225637435507e-01,1.068305449876659807e+01,3.408637509162968683e-03,7.957139342424247586e-01,-4.000000000000000327e-05,-1.000000007948258052e+00,0.000000000000000000e+00 +8.185639418234016773e+01,5.112530223004308141e+02,1.166409088728280335e-01,1.068379933624199829e+01,3.408491523761430966e-03,7.947778723623101227e-01,-4.000000000000000327e-05,-1.000000008132408968e+00,0.000000000000000000e+00 +8.185733017895384478e+01,5.112630222423417763e+02,1.166749937220669803e-01,1.068454324563916025e+01,3.408345538359893248e-03,7.938418757410143911e-01,-4.000000000000000327e-05,-1.000000008973012111e+00,0.000000000000000000e+00 +8.185826611039892953e+01,5.112730221842577407e+02,1.167090771114603909e-01,1.068528622721309418e+01,3.408199552958355531e-03,7.929059442875279196e-01,-4.000000000000000327e-05,-1.000000008914386562e+00,0.000000000000000000e+00 +8.185920197676576038e+01,5.112830221261786505e+02,1.167431590410082654e-01,1.068602828121841242e+01,3.408053567556817813e-03,7.919700779123552969e-01,-4.000000000000000327e-05,-1.000000010456210564e+00,0.000000000000000000e+00 +8.186013777814460468e+01,5.112930220681045625e+02,1.167772395107106037e-01,1.068676940790933116e+01,3.407907582155280096e-03,7.910342765237198259e-01,-4.000000000000000327e-05,-1.000000005954665649e+00,0.000000000000000000e+00 +8.186107351462570136e+01,5.113030220100354200e+02,1.168113185205674059e-01,1.068750960753966872e+01,3.407761596753742378e-03,7.900985400370557077e-01,-4.000000000000000327e-05,-1.000000008050775158e+00,0.000000000000000000e+00 +8.186200918629920409e+01,5.113130219519712796e+02,1.168453960705786721e-01,1.068824888036285259e+01,3.407615611352204660e-03,7.891628683560260038e-01,-4.000000000000000327e-05,-1.000000011129148048e+00,0.000000000000000000e+00 +8.186294479325520967e+01,5.113230218939121414e+02,1.168794721607444020e-01,1.068898722663190881e+01,3.407469625950666943e-03,7.882272613896066371e-01,-4.000000000000000327e-05,-1.000000007539288305e+00,0.000000000000000000e+00 +8.186388033558377231e+01,5.113330218358579486e+02,1.169135467910645820e-01,1.068972464659946731e+01,3.407323640549129225e-03,7.872917190539887589e-01,-4.000000000000000327e-05,-1.000000007894601639e+00,0.000000000000000000e+00 +8.186481581337488933e+01,5.113430217778087581e+02,1.169476199615392259e-01,1.069046114051776897e+01,3.407177655147591508e-03,7.863562412554911951e-01,-4.000000000000000327e-05,-1.000000008602940138e+00,0.000000000000000000e+00 +8.186575122671848703e+01,5.113530217197645129e+02,1.169816916721683336e-01,1.069119670863865679e+01,3.407031669746053790e-03,7.854208279038511487e-01,-4.000000000000000327e-05,-1.000000010129629802e+00,0.000000000000000000e+00 +8.186668657570443486e+01,5.113630216617252700e+02,1.170157619229518914e-01,1.069193135121357940e+01,3.406885684344516073e-03,7.844854789084280133e-01,-4.000000000000000327e-05,-1.000000006846924583e+00,0.000000000000000000e+00 +8.186762186042255962e+01,5.113730216036909724e+02,1.170498307138899130e-01,1.069266506849359111e+01,3.406739698942978355e-03,7.835501941839021489e-01,-4.000000000000000327e-05,-1.000000009371811771e+00,0.000000000000000000e+00 +8.186855708096261708e+01,5.113830215456616770e+02,1.170838980449823846e-01,1.069339786072935716e+01,3.406593713541440638e-03,7.826149736350809238e-01,-4.000000000000000327e-05,-1.000000008012656316e+00,0.000000000000000000e+00 +8.186949223741430615e+01,5.113930214876373270e+02,1.171179639162293201e-01,1.069412972817114493e+01,3.406447728139902920e-03,7.816798171758930769e-01,-4.000000000000000327e-05,-1.000000009324264472e+00,0.000000000000000000e+00 +8.187042732986728311e+01,5.114030214296179793e+02,1.171520283276307056e-01,1.069486067106883276e+01,3.406301742738365203e-03,7.807447247141942048e-01,-4.000000000000000327e-05,-1.000000009704957060e+00,0.000000000000000000e+00 +8.187136235841113319e+01,5.114130213716035769e+02,1.171860912791865411e-01,1.069559068967190463e+01,3.406155757336827485e-03,7.798096961612649425e-01,-4.000000000000000327e-05,-1.000000007582022565e+00,0.000000000000000000e+00 +8.187229732313539898e+01,5.114230213135941199e+02,1.172201527708968405e-01,1.069631978422945373e+01,3.406009771935289768e-03,7.788747314299129254e-01,-4.000000000000000327e-05,-1.000000007478398789e+00,0.000000000000000000e+00 +8.187323222412955204e+01,5.114330212555896651e+02,1.172542128027615899e-01,1.069704795499018424e+01,3.405863786533752050e-03,7.779398304287734600e-01,-4.000000000000000327e-05,-1.000000009853072802e+00,0.000000000000000000e+00 +8.187416706148300705e+01,5.114430211975901557e+02,1.172882713747807892e-01,1.069777520220240774e+01,3.405717801132214333e-03,7.770049930661097060e-01,-4.000000000000000327e-05,-1.000000009065775908e+00,0.000000000000000000e+00 +8.187510183528512187e+01,5.114530211395956485e+02,1.173223284869544386e-01,1.069850152611404326e+01,3.405571815730676615e-03,7.760702192555141155e-01,-4.000000000000000327e-05,-1.000000007604422647e+00,0.000000000000000000e+00 +8.187603654562521172e+01,5.114630210816060867e+02,1.173563841392825380e-01,1.069922692697262256e+01,3.405425830329138898e-03,7.751355089083094008e-01,-4.000000000000000327e-05,-1.000000009991813155e+00,0.000000000000000000e+00 +8.187697119259253498e+01,5.114730210236215271e+02,1.173904383317650874e-01,1.069995140502528841e+01,3.405279844927601180e-03,7.742008619316471663e-01,-4.000000000000000327e-05,-1.000000006514840445e+00,0.000000000000000000e+00 +8.187790577627627897e+01,5.114830209656419129e+02,1.174244910644020867e-01,1.070067496051879097e+01,3.405133859526063463e-03,7.732662782418135983e-01,-4.000000000000000327e-05,-1.000000011863616312e+00,0.000000000000000000e+00 +8.187884029676558839e+01,5.114930209076673009e+02,1.174585423371935361e-01,1.070139759369949672e+01,3.404987874124525745e-03,7.723317577414215984e-01,-4.000000000000000327e-05,-1.000000006151221088e+00,0.000000000000000000e+00 +8.187977475414953688e+01,5.115030208496976343e+02,1.174925921501394355e-01,1.070211930481337603e+01,3.404841888722988028e-03,7.713973003517251570e-01,-4.000000000000000327e-05,-1.000000008136672891e+00,0.000000000000000000e+00 +8.188070914851715543e+01,5.115130207917329699e+02,1.175266405032397710e-01,1.070284009410602089e+01,3.404695903321450310e-03,7.704629059765036869e-01,-4.000000000000000327e-05,-1.000000010135073225e+00,0.000000000000000000e+00 +8.188164347995741821e+01,5.115230207337732509e+02,1.175606873964945565e-01,1.070355996182262892e+01,3.404549917919912592e-03,7.695285745267740340e-01,-4.000000000000000327e-05,-1.000000008526060302e+00,0.000000000000000000e+00 +8.188257774855924254e+01,5.115330206758185341e+02,1.175947328299037919e-01,1.070427890820801053e+01,3.404403932518374875e-03,7.685943059169910718e-01,-4.000000000000000327e-05,-1.000000009864340234e+00,0.000000000000000000e+00 +8.188351195441147468e+01,5.115430206178687627e+02,1.176287768034674636e-01,1.070499693350659243e+01,3.404257947116837157e-03,7.676601000555410836e-01,-4.000000000000000327e-05,-1.000000006456593704e+00,0.000000000000000000e+00 +8.188444609760293247e+01,5.115530205599239366e+02,1.176628193171855852e-01,1.070571403796241228e+01,3.404111961715299440e-03,7.667259568580530038e-01,-4.000000000000000327e-05,-1.000000008928232820e+00,0.000000000000000000e+00 +8.188538017822236270e+01,5.115630205019841128e+02,1.176968603710581568e-01,1.070643022181912585e+01,3.403965976313761722e-03,7.657918762302852178e-01,-4.000000000000000327e-05,-1.000000009584449234e+00,0.000000000000000000e+00 +8.188631419635845532e+01,5.115730204440492344e+02,1.177308999650851645e-01,1.070714548531999810e+01,3.403819990912224005e-03,7.648578580852395392e-01,-4.000000000000000327e-05,-1.000000008869892598e+00,0.000000000000000000e+00 +8.188724815209985763e+01,5.115830203861193581e+02,1.177649380992666084e-01,1.070785982870791031e+01,3.403674005510686287e-03,7.639239023355572922e-01,-4.000000000000000327e-05,-1.000000009266015732e+00,0.000000000000000000e+00 +8.188818204553514590e+01,5.115930203281944273e+02,1.177989747736025022e-01,1.070857325222536005e+01,3.403528020109148570e-03,7.629900088916171663e-01,-4.000000000000000327e-05,-1.000000007143573511e+00,0.000000000000000000e+00 +8.188911587675285375e+01,5.116030202702744418e+02,1.178330099880928322e-01,1.070928575611445943e+01,3.403382034707610852e-03,7.620561776672420962e-01,-4.000000000000000327e-05,-1.000000009056723371e+00,0.000000000000000000e+00 +8.189004964584144375e+01,5.116130202123594586e+02,1.178670437427375983e-01,1.070999734061693864e+01,3.403236049306073135e-03,7.611224085701893127e-01,-4.000000000000000327e-05,-1.000000009337483897e+00,0.000000000000000000e+00 +8.189098335288935004e+01,5.116230201544494207e+02,1.179010760375368144e-01,1.071070800597414063e+01,3.403090063904535417e-03,7.601887015135637693e-01,-4.000000000000000327e-05,-1.000000008426354059e+00,0.000000000000000000e+00 +8.189191699798493573e+01,5.116330200965443851e+02,1.179351068724904666e-01,1.071141775242702643e+01,3.402944078502997700e-03,7.592550564101134825e-01,-4.000000000000000327e-05,-1.000000008802501172e+00,0.000000000000000000e+00 +8.189285058121650707e+01,5.116430200386442948e+02,1.179691362475985550e-01,1.071212658021617514e+01,3.402798093101459982e-03,7.583214731703262768e-01,-4.000000000000000327e-05,-1.000000008867347301e+00,0.000000000000000000e+00 +8.189378410267231345e+01,5.116530199807491499e+02,1.180031641628610795e-01,1.071283448958178219e+01,3.402652107699922265e-03,7.573879517062369615e-01,-4.000000000000000327e-05,-1.000000007021785597e+00,0.000000000000000000e+00 +8.189471756244056166e+01,5.116630199228590072e+02,1.180371906182780400e-01,1.071354148076366108e+01,3.402506122298384547e-03,7.564544919314273308e-01,-4.000000000000000327e-05,-1.000000011859105031e+00,0.000000000000000000e+00 +8.189565096060940164e+01,5.116730198649738099e+02,1.180712156138494368e-01,1.071424755400124518e+01,3.402360136896846830e-03,7.555210937515121072e-01,-4.000000000000000327e-05,-1.000000005466650022e+00,0.000000000000000000e+00 +8.189658429726692646e+01,5.116830198070936149e+02,1.181052391495752696e-01,1.071495270953358059e+01,3.402214151495309112e-03,7.545877570888799291e-01,-4.000000000000000327e-05,-1.000000010710547338e+00,0.000000000000000000e+00 +8.189751757250118658e+01,5.116930197492183652e+02,1.181392612254555385e-01,1.071565694759934217e+01,3.402068166093771395e-03,7.536544818446310190e-01,-4.000000000000000327e-05,-1.000000009674050450e+00,0.000000000000000000e+00 +8.189845078640014719e+01,5.117030196913480609e+02,1.181732818414902297e-01,1.071636026843681400e+01,3.401922180692233677e-03,7.527212679366418469e-01,-4.000000000000000327e-05,-1.000000006869260494e+00,0.000000000000000000e+00 +8.189938393905174507e+01,5.117130196334827588e+02,1.182073009976793571e-01,1.071706267228390530e+01,3.401776195290695960e-03,7.517881152786310972e-01,-4.000000000000000327e-05,-1.000000008850517874e+00,0.000000000000000000e+00 +8.190031703054386014e+01,5.117230195756224020e+02,1.182413186940229205e-01,1.071776415937814697e+01,3.401630209889158242e-03,7.508550237782550818e-01,-4.000000000000000327e-05,-1.000000009931497846e+00,0.000000000000000000e+00 +8.190125006096431548e+01,5.117330195177669907e+02,1.182753349305209062e-01,1.071846472995668620e+01,3.401484224487620524e-03,7.499219933485301581e-01,-4.000000000000000327e-05,-1.000000006462731017e+00,0.000000000000000000e+00 +8.190218303040089154e+01,5.117430194599165816e+02,1.183093497071733280e-01,1.071916438425629181e+01,3.401338239086082807e-03,7.489890239059309174e-01,-4.000000000000000327e-05,-1.000000011120211640e+00,0.000000000000000000e+00 +8.190311593894128350e+01,5.117530194020711178e+02,1.183433630239801859e-01,1.071986312251335782e+01,3.401192253684545089e-03,7.480561153551590348e-01,-4.000000000000000327e-05,-1.000000008007782437e+00,0.000000000000000000e+00 +8.190404878667317234e+01,5.117630193442306563e+02,1.183773748809414661e-01,1.072056094496389278e+01,3.401046268283007372e-03,7.471232676157997243e-01,-4.000000000000000327e-05,-1.000000009801419454e+00,0.000000000000000000e+00 +8.190498157368416798e+01,5.117730192863951402e+02,1.184113852780571685e-01,1.072125785184353397e+01,3.400900282881469654e-03,7.461904805956660613e-01,-4.000000000000000327e-05,-1.000000006722930213e+00,0.000000000000000000e+00 +8.190591430006182350e+01,5.117830192285645694e+02,1.184453942153273071e-01,1.072195384338753676e+01,3.400754297479931937e-03,7.452577542117455600e-01,-4.000000000000000327e-05,-1.000000009409399482e+00,0.000000000000000000e+00 +8.190684696589363512e+01,5.117930191707390009e+02,1.184794016927518678e-01,1.072264891983078350e+01,3.400608312078394219e-03,7.443250883711570731e-01,-4.000000000000000327e-05,-1.000000010121283145e+00,0.000000000000000000e+00 +8.190777957126705644e+01,5.118030191129183777e+02,1.185134077103308509e-01,1.072334308140777459e+01,3.400462326676856502e-03,7.433924829882914143e-01,-4.000000000000000327e-05,-1.000000007241607980e+00,0.000000000000000000e+00 +8.190871211626949844e+01,5.118130190551026999e+02,1.185474122680642700e-01,1.072403632835263565e+01,3.400316341275318784e-03,7.424599379790998155e-01,-4.000000000000000327e-05,-1.000000009366147413e+00,0.000000000000000000e+00 +8.190964460098830102e+01,5.118230189972920243e+02,1.185814153659521114e-01,1.072472866089911925e+01,3.400170355873781067e-03,7.415274532515702122e-01,-4.000000000000000327e-05,-1.000000008749583058e+00,0.000000000000000000e+00 +8.191057702551074726e+01,5.118330189394862941e+02,1.186154170039943750e-01,1.072542007928059782e+01,3.400024370472243349e-03,7.405950287209660532e-01,-4.000000000000000327e-05,-1.000000007858124818e+00,0.000000000000000000e+00 +8.191150938992407760e+01,5.118430188816855093e+02,1.186494171821910609e-01,1.072611058373007076e+01,3.399878385070705632e-03,7.396626643003034740e-01,-4.000000000000000327e-05,-1.000000009158754422e+00,0.000000000000000000e+00 +8.191244169431548983e+01,5.118530188238897267e+02,1.186834159005421691e-01,1.072680017448016265e+01,3.399732399669167914e-03,7.387303599003510746e-01,-4.000000000000000327e-05,-1.000000011031411118e+00,0.000000000000000000e+00 +8.191337393877211071e+01,5.118630187660988895e+02,1.187174131590476994e-01,1.072748885176312150e+01,3.399586414267630197e-03,7.377981154334405378e-01,-4.000000000000000327e-05,-1.000000005720245611e+00,0.000000000000000000e+00 +8.191430612338103856e+01,5.118730187083129977e+02,1.187514089577076520e-01,1.072817661581082049e+01,3.399440428866092479e-03,7.368659308191858326e-01,-4.000000000000000327e-05,-1.000000009999720607e+00,0.000000000000000000e+00 +8.191523824822928646e+01,5.118830186505320512e+02,1.187854032965220269e-01,1.072886346685476511e+01,3.399294443464554762e-03,7.359338059616159500e-01,-4.000000000000000327e-05,-1.000000009980492433e+00,0.000000000000000000e+00 +8.191617031340383903e+01,5.118930185927561070e+02,1.188193961754908101e-01,1.072954940512607891e+01,3.399148458063017044e-03,7.350017407777594824e-01,-4.000000000000000327e-05,-1.000000008124997342e+00,0.000000000000000000e+00 +8.191710231899162409e+01,5.119030185349851081e+02,1.188533875946140156e-01,1.073023443085551598e+01,3.399002472661479327e-03,7.340697351824012618e-01,-4.000000000000000327e-05,-1.000000006896082150e+00,0.000000000000000000e+00 +8.191803426507951258e+01,5.119130184772190546e+02,1.188873775538916433e-01,1.073091854427345915e+01,3.398856487259941609e-03,7.331377890880824699e-01,-4.000000000000000327e-05,-1.000000010802943651e+00,0.000000000000000000e+00 +8.191896615175433283e+01,5.119230184194580033e+02,1.189213660533236933e-01,1.073160174560991820e+01,3.398710501858403892e-03,7.322059024031941643e-01,-4.000000000000000327e-05,-1.000000007989510609e+00,0.000000000000000000e+00 +8.191989797910285631e+01,5.119330183617018974e+02,1.189553530929101516e-01,1.073228403509452633e+01,3.398564516456866174e-03,7.312740750472278561e-01,-4.000000000000000327e-05,-1.000000009099455411e+00,0.000000000000000000e+00 +8.192082974721179767e+01,5.119430183039507369e+02,1.189893386726510321e-01,1.073296541295655082e+01,3.398418531055328456e-03,7.303423069298080605e-01,-4.000000000000000327e-05,-1.000000008410542929e+00,0.000000000000000000e+00 +8.192176145616782890e+01,5.119530182462045218e+02,1.190233227925463211e-01,1.073364587942488413e+01,3.398272545653790739e-03,7.294105979659429861e-01,-4.000000000000000327e-05,-1.000000010429624053e+00,0.000000000000000000e+00 +8.192269310605756516e+01,5.119630181884633089e+02,1.190573054525960323e-01,1.073432543472804923e+01,3.398126560252253021e-03,7.284789480664931594e-01,-4.000000000000000327e-05,-1.000000007384089340e+00,0.000000000000000000e+00 +8.192362469696756477e+01,5.119730181307270414e+02,1.190912866528001518e-01,1.073500407909419607e+01,3.397980574850715304e-03,7.275473571496118286e-01,-4.000000000000000327e-05,-1.000000007872669183e+00,0.000000000000000000e+00 +8.192455622898434342e+01,5.119830180729957192e+02,1.191252663931586797e-01,1.073568181275110867e+01,3.397834589449177586e-03,7.266158251254926093e-01,-4.000000000000000327e-05,-1.000000010262037220e+00,0.000000000000000000e+00 +8.192548770219437415e+01,5.119930180152693993e+02,1.191592446736716299e-01,1.073635863592619799e+01,3.397688604047639869e-03,7.256843519059023029e-01,-4.000000000000000327e-05,-1.000000008821055664e+00,0.000000000000000000e+00 +8.192641911668405896e+01,5.120030179575479679e+02,1.191932214943389884e-01,1.073703454884650377e+01,3.397542618646102151e-03,7.247529374079971776e-01,-4.000000000000000327e-05,-1.000000008053773426e+00,0.000000000000000000e+00 +8.192735047253977143e+01,5.120130178998315387e+02,1.192271968551607553e-01,1.073770955173869979e+01,3.397396633244564434e-03,7.238215815447889279e-01,-4.000000000000000327e-05,-1.000000010418991669e+00,0.000000000000000000e+00 +8.192828176984779986e+01,5.120230178421201117e+02,1.192611707561369305e-01,1.073838364482909036e+01,3.397250647843026716e-03,7.228902842270503726e-01,-4.000000000000000327e-05,-1.000000008132643670e+00,0.000000000000000000e+00 +8.192921300869441836e+01,5.120330177844135733e+02,1.192951431972675141e-01,1.073905682834360853e+01,3.397104662441488999e-03,7.219590453728544910e-01,-4.000000000000000327e-05,-1.000000007746667974e+00,0.000000000000000000e+00 +8.193014418916582997e+01,5.120430177267120371e+02,1.193291141785525061e-01,1.073972910250782320e+01,3.396958677039951281e-03,7.210278648942231028e-01,-4.000000000000000327e-05,-1.000000009669534284e+00,0.000000000000000000e+00 +8.193107531134819510e+01,5.120530176690155031e+02,1.193630836999919065e-01,1.074040046754693378e+01,3.396812691638413564e-03,7.200967427028486245e-01,-4.000000000000000327e-05,-1.000000008160740972e+00,0.000000000000000000e+00 +8.193200637532763153e+01,5.120630176113238576e+02,1.193970517615857152e-01,1.074107092368577021e+01,3.396666706236875846e-03,7.191656787158191566e-01,-4.000000000000000327e-05,-1.000000009772671117e+00,0.000000000000000000e+00 +8.193293738119018599e+01,5.120730175536372144e+02,1.194310183633339323e-01,1.074174047114879826e+01,3.396520720835338129e-03,7.182346728441723060e-01,-4.000000000000000327e-05,-1.000000008762507830e+00,0.000000000000000000e+00 +8.193386832902186256e+01,5.120830174959554597e+02,1.194649835052365577e-01,1.074240911016011424e+01,3.396374735433800411e-03,7.173037250043428070e-01,-4.000000000000000327e-05,-1.000000007583322414e+00,0.000000000000000000e+00 +8.193479921890860851e+01,5.120930174382787072e+02,1.194989471872935777e-01,1.074307684094345028e+01,3.396228750032262694e-03,7.163728351105316250e-01,-4.000000000000000327e-05,-1.000000010738031575e+00,0.000000000000000000e+00 +8.193573005093634265e+01,5.121030173806069570e+02,1.195329094095050060e-01,1.074374366372217260e+01,3.396082764630724976e-03,7.154420030727983715e-01,-4.000000000000000327e-05,-1.000000008379217764e+00,0.000000000000000000e+00 +8.193666082519092697e+01,5.121130173229400953e+02,1.195668701718708427e-01,1.074440957871927793e+01,3.395936779229187259e-03,7.145112288104191745e-01,-4.000000000000000327e-05,-1.000000007058153617e+00,0.000000000000000000e+00 +8.193759154175815240e+01,5.121230172652782358e+02,1.196008294743910738e-01,1.074507458615740241e+01,3.395790793827649541e-03,7.135805122366217779e-01,-4.000000000000000327e-05,-1.000000011277685008e+00,0.000000000000000000e+00 +8.193852220072378145e+01,5.121330172076212648e+02,1.196347873170657133e-01,1.074573868625881623e+01,3.395644808426111824e-03,7.126498532604933489e-01,-4.000000000000000327e-05,-1.000000007082482822e+00,0.000000000000000000e+00 +8.193945280217351979e+01,5.121430171499692960e+02,1.196687436998947474e-01,1.074640187924542012e+01,3.395498823024574106e-03,7.117192518041586258e-01,-4.000000000000000327e-05,-1.000000009227893116e+00,0.000000000000000000e+00 +8.194038334619303043e+01,5.121530170923223295e+02,1.197026986228781897e-01,1.074706416533875775e+01,3.395352837623036388e-03,7.107887077760600691e-01,-4.000000000000000327e-05,-1.000000009908408094e+00,0.000000000000000000e+00 +8.194131383286791959e+01,5.121630170346802515e+02,1.197366520860160266e-01,1.074772554476000330e+01,3.395206852221498671e-03,7.098582210919537339e-01,-4.000000000000000327e-05,-1.000000007469184604e+00,0.000000000000000000e+00 +8.194224426228373659e+01,5.121730169770431758e+02,1.197706040893082718e-01,1.074838601772996860e+01,3.395060866819960953e-03,7.089277916691846260e-01,-4.000000000000000327e-05,-1.000000010514840332e+00,0.000000000000000000e+00 +8.194317463452600236e+01,5.121830169194109885e+02,1.198045546327549116e-01,1.074904558446910485e+01,3.394914881418423236e-03,7.079974194171411161e-01,-4.000000000000000327e-05,-1.000000007128910129e+00,0.000000000000000000e+00 +8.194410494968016678e+01,5.121930168617838035e+02,1.198385037163559458e-01,1.074970424519749557e+01,3.394768896016885518e-03,7.070671042563478892e-01,-4.000000000000000327e-05,-1.000000010020321906e+00,0.000000000000000000e+00 +8.194503520783163708e+01,5.122030168041616207e+02,1.198724513401113745e-01,1.075036200013486720e+01,3.394622910615347801e-03,7.061368460955551596e-01,-4.000000000000000327e-05,-1.000000009321701411e+00,0.000000000000000000e+00 +8.194596540906577786e+01,5.122130167465443265e+02,1.199063975040211977e-01,1.075101884950057851e+01,3.394476925213810083e-03,7.052066448527419817e-01,-4.000000000000000327e-05,-1.000000007478277331e+00,0.000000000000000000e+00 +8.194689555346789689e+01,5.122230166889320344e+02,1.199403422080854154e-01,1.075167479351362942e+01,3.394330939812272366e-03,7.042765004436614129e-01,-4.000000000000000327e-05,-1.000000008989856859e+00,0.000000000000000000e+00 +8.194782564112327350e+01,5.122330166313246309e+02,1.199742854523040414e-01,1.075232983239265927e+01,3.394184954410734648e-03,7.033464127799300414e-01,-4.000000000000000327e-05,-1.000000010142586326e+00,0.000000000000000000e+00 +8.194875567211710177e+01,5.122430165737222296e+02,1.200082272366770481e-01,1.075298396635594322e+01,3.394038969009196931e-03,7.024163817766678752e-01,-4.000000000000000327e-05,-1.000000007219818077e+00,0.000000000000000000e+00 +8.194968564653456156e+01,5.122530165161248306e+02,1.200421675612044492e-01,1.075363719562139586e+01,3.393892983607659213e-03,7.014864073525000077e-01,-4.000000000000000327e-05,-1.000000010882083235e+00,0.000000000000000000e+00 +8.195061556446076168e+01,5.122630164585323200e+02,1.200761064258862448e-01,1.075428952040657471e+01,3.393746998206121496e-03,7.005564894161860900e-01,-4.000000000000000327e-05,-1.000000007139992375e+00,0.000000000000000000e+00 +8.195154542598076830e+01,5.122730164009448117e+02,1.201100438307224350e-01,1.075494094092867137e+01,3.393601012804583778e-03,6.996266278895436619e-01,-4.000000000000000327e-05,-1.000000008708914034e+00,0.000000000000000000e+00 +8.195247523117960498e+01,5.122830163433621919e+02,1.201439797757130196e-01,1.075559145740452394e+01,3.393455027403046061e-03,6.986968226826146822e-01,-4.000000000000000327e-05,-1.000000009813890811e+00,0.000000000000000000e+00 +8.195340498014223840e+01,5.122930162857845744e+02,1.201779142608579987e-01,1.075624107005060637e+01,3.393309042001508343e-03,6.977670737108596644e-01,-4.000000000000000327e-05,-1.000000008787653716e+00,0.000000000000000000e+00 +8.195433467295359264e+01,5.123030162282118454e+02,1.202118472861573584e-01,1.075688977908303379e+01,3.393163056599970626e-03,6.968373808913373990e-01,-4.000000000000000327e-05,-1.000000010127175987e+00,0.000000000000000000e+00 +8.195526430969853493e+01,5.123130161706441186e+02,1.202457788516111126e-01,1.075753758471756427e+01,3.393017071198432908e-03,6.959077441369739825e-01,-4.000000000000000327e-05,-1.000000005996131369e+00,0.000000000000000000e+00 +8.195619389046190406e+01,5.123230161130813940e+02,1.202797089572192474e-01,1.075818448716959530e+01,3.392871085796895191e-03,6.949781633680285342e-01,-4.000000000000000327e-05,-1.000000011170113501e+00,0.000000000000000000e+00 +8.195712341532848200e+01,5.123330160555235580e+02,1.203136376029817767e-01,1.075883048665417085e+01,3.392725100395357473e-03,6.940486384910730111e-01,-4.000000000000000327e-05,-1.000000007531270274e+00,0.000000000000000000e+00 +8.195805288438297964e+01,5.123430159979707241e+02,1.203475647888986866e-01,1.075947558338596899e+01,3.392579114993819756e-03,6.931191694295688599e-01,-4.000000000000000327e-05,-1.000000009855100958e+00,0.000000000000000000e+00 +8.195898229771009369e+01,5.123530159404227788e+02,1.203814905149699910e-01,1.076011977757931781e+01,3.392433129592282038e-03,6.921897560932913640e-01,-4.000000000000000327e-05,-1.000000010300670095e+00,0.000000000000000000e+00 +8.195991165539446399e+01,5.123630158828798358e+02,1.204154147811956760e-01,1.076076306944818306e+01,3.392287144190744320e-03,6.912603983993516055e-01,-4.000000000000000327e-05,-1.000000007192029861e+00,0.000000000000000000e+00 +8.196084095752067356e+01,5.123730158253417812e+02,1.204493375875757416e-01,1.076140545920617519e+01,3.392141158789206603e-03,6.903310962664654937e-01,-4.000000000000000327e-05,-1.000000007081379927e+00,0.000000000000000000e+00 +8.196177020417324854e+01,5.123830157678087289e+02,1.204832589341102017e-01,1.076204694706655118e+01,3.391995173387668885e-03,6.894018496073073266e-01,-4.000000000000000327e-05,-1.000000012408240435e+00,0.000000000000000000e+00 +8.196269939543668670e+01,5.123930157102806788e+02,1.205171788207990424e-01,1.076268753324220917e+01,3.391849187986131168e-03,6.884726583323326210e-01,-4.000000000000000327e-05,-1.000000007093124310e+00,0.000000000000000000e+00 +8.196362853139544313e+01,5.124030156527575173e+02,1.205510972476422638e-01,1.076332721794568670e+01,3.391703202584593450e-03,6.875435223669852380e-01,-4.000000000000000327e-05,-1.000000007974506389e+00,0.000000000000000000e+00 +8.196455761213391611e+01,5.124130155952393579e+02,1.205850142146398657e-01,1.076396600138917492e+01,3.391557217183055733e-03,6.866144416211102941e-01,-4.000000000000000327e-05,-1.000000011317610404e+00,0.000000000000000000e+00 +8.196548663773644705e+01,5.124230155377260871e+02,1.206189297217918482e-01,1.076460388378450439e+01,3.391411231781518015e-03,6.856854160080708693e-01,-4.000000000000000327e-05,-1.000000007208668329e+00,0.000000000000000000e+00 +8.196641560828733475e+01,5.124330154802178185e+02,1.206528437690982114e-01,1.076524086534314861e+01,3.391265246379980298e-03,6.847564454504871945e-01,-4.000000000000000327e-05,-1.000000008373710170e+00,0.000000000000000000e+00 +8.196734452387083536e+01,5.124430154227144385e+02,1.206867563565589552e-01,1.076587694627623293e+01,3.391119260978442580e-03,6.838275298592039197e-01,-4.000000000000000327e-05,-1.000000011074093198e+00,0.000000000000000000e+00 +8.196827338457116241e+01,5.124530153652160607e+02,1.207206674841740796e-01,1.076651212679452385e+01,3.390973275576904863e-03,6.828986691485862126e-01,-4.000000000000000327e-05,-1.000000007448480721e+00,0.000000000000000000e+00 +8.196920219047248679e+01,5.124630153077225714e+02,1.207545771519435845e-01,1.076714640710843263e+01,3.390827290175367145e-03,6.819698632403480287e-01,-4.000000000000000327e-05,-1.000000008166728183e+00,0.000000000000000000e+00 +8.197013094165890834e+01,5.124730152502340843e+02,1.207884853598674563e-01,1.076777978742802233e+01,3.390681304773829428e-03,6.810411120463394363e-01,-4.000000000000000327e-05,-1.000000011545036704e+00,0.000000000000000000e+00 +8.197105963821449848e+01,5.124830151927504858e+02,1.208223921079457086e-01,1.076841226796299900e+01,3.390535319372291710e-03,6.801124154800216592e-01,-4.000000000000000327e-05,-1.000000005598155273e+00,0.000000000000000000e+00 +8.197198828022328598e+01,5.124930151352718894e+02,1.208562973961783416e-01,1.076904384892271338e+01,3.390389333970753993e-03,6.791837734660329806e-01,-4.000000000000000327e-05,-1.000000011296663383e+00,0.000000000000000000e+00 +8.197291686776924280e+01,5.125030150777982954e+02,1.208902012245653412e-01,1.076967453051617163e+01,3.390243348569216275e-03,6.782551859095836688e-01,-4.000000000000000327e-05,-1.000000008413394648e+00,0.000000000000000000e+00 +8.197384540093629823e+01,5.125130150203295898e+02,1.209241035931067215e-01,1.077030431295201751e+01,3.390097363167678558e-03,6.773266527347139299e-01,-4.000000000000000327e-05,-1.000000009679424373e+00,0.000000000000000000e+00 +8.197477387980833896e+01,5.125230149628658864e+02,1.209580045018024824e-01,1.077093319643855018e+01,3.389951377766140840e-03,6.763981738536883892e-01,-4.000000000000000327e-05,-1.000000007223405873e+00,0.000000000000000000e+00 +8.197570230446919481e+01,5.125330149054070716e+02,1.209919039506526101e-01,1.077156118118371353e+01,3.389805392364603123e-03,6.754697491861265668e-01,-4.000000000000000327e-05,-1.000000009658151390e+00,0.000000000000000000e+00 +8.197663067500265299e+01,5.125430148479532590e+02,1.210258019396571044e-01,1.077218826739510327e+01,3.389659406963065405e-03,6.745413786436976755e-01,-4.000000000000000327e-05,-1.000000009109302868e+00,0.000000000000000000e+00 +8.197755899149247227e+01,5.125530147905043350e+02,1.210596984688159794e-01,1.077281445527995984e+01,3.389513421561527688e-03,6.736130621454277101e-01,-4.000000000000000327e-05,-1.000000010066492084e+00,0.000000000000000000e+00 +8.197848725402234038e+01,5.125630147330604132e+02,1.210935935381292211e-01,1.077343974504517554e+01,3.389367436159989970e-03,6.726847996062206292e-01,-4.000000000000000327e-05,-1.000000006712858491e+00,0.000000000000000000e+00 +8.197941546267590240e+01,5.125730146756213799e+02,1.211274871475968296e-01,1.077406413689729092e+01,3.389221450758452252e-03,6.717565909464258134e-01,-4.000000000000000327e-05,-1.000000009723249761e+00,0.000000000000000000e+00 +8.198034361753677501e+01,5.125830146181873488e+02,1.211613792972188186e-01,1.077468763104250016e+01,3.389075465356914535e-03,6.708284360765298660e-01,-4.000000000000000327e-05,-1.000000009155227909e+00,0.000000000000000000e+00 +8.198127171868851804e+01,5.125930145607582062e+02,1.211952699869951744e-01,1.077531022768664215e+01,3.388929479955376817e-03,6.699003349162937493e-01,-4.000000000000000327e-05,-1.000000009497196363e+00,0.000000000000000000e+00 +8.198219976621463445e+01,5.126030145033340659e+02,1.212291592169258969e-01,1.077593192703520941e+01,3.388783494553839100e-03,6.689722873813580550e-01,-4.000000000000000327e-05,-1.000000009051720928e+00,0.000000000000000000e+00 +8.198312776019861303e+01,5.126130144459148141e+02,1.212630469870109862e-01,1.077655272929334451e+01,3.388637509152301382e-03,6.680442933889843005e-01,-4.000000000000000327e-05,-1.000000008181867406e+00,0.000000000000000000e+00 +8.198405570072385729e+01,5.126230143885005646e+02,1.212969332972504422e-01,1.077717263466584185e+01,3.388491523750763665e-03,6.671163528561424583e-01,-4.000000000000000327e-05,-1.000000009314067295e+00,0.000000000000000000e+00 +8.198498358787375651e+01,5.126330143310912035e+02,1.213308181476442649e-01,1.077779164335714768e+01,3.388345538349225947e-03,6.661884656975963770e-01,-4.000000000000000327e-05,-1.000000008684615249e+00,0.000000000000000000e+00 +8.198591142173164314e+01,5.126430142736868447e+02,1.213647015381924543e-01,1.077840975557135828e+01,3.388199552947688230e-03,6.652606318316476308e-01,-4.000000000000000327e-05,-1.000000008717771394e+00,0.000000000000000000e+00 +8.198683920238080702e+01,5.126530142162873744e+02,1.213985834688949966e-01,1.077902697151222355e+01,3.388053567546150512e-03,6.643328511743935572e-01,-4.000000000000000327e-05,-1.000000007711037808e+00,0.000000000000000000e+00 +8.198776692990449533e+01,5.126630141588929064e+02,1.214324639397519057e-01,1.077964329138314525e+01,3.387907582144612795e-03,6.634051236435561938e-01,-4.000000000000000327e-05,-1.000000010152381158e+00,0.000000000000000000e+00 +8.198869460438589840e+01,5.126730141015033269e+02,1.214663429507631814e-01,1.078025871538717873e+01,3.387761596743075077e-03,6.624774491527390952e-01,-4.000000000000000327e-05,-1.000000010209673329e+00,0.000000000000000000e+00 +8.198962222590816395e+01,5.126830140441187496e+02,1.215002205019288239e-01,1.078087324372702938e+01,3.387615611341537360e-03,6.615498276210013406e-01,-4.000000000000000327e-05,-1.000000008240416127e+00,0.000000000000000000e+00 +8.199054979455441128e+01,5.126930139867390608e+02,1.215340965932488193e-01,1.078148687660505800e+01,3.387469625939999642e-03,6.606222589671149059e-01,-4.000000000000000327e-05,-1.000000008731583234e+00,0.000000000000000000e+00 +8.199147731040768861e+01,5.127030139293643742e+02,1.215679712247231814e-01,1.078209961422328078e+01,3.387323640538461925e-03,6.596947431057345046e-01,-4.000000000000000327e-05,-1.000000007911288069e+00,0.000000000000000000e+00 +8.199240477355102996e+01,5.127130138719945762e+02,1.216018443963518963e-01,1.078271145678336573e+01,3.387177655136924207e-03,6.587672799550582381e-01,-4.000000000000000327e-05,-1.000000010266473671e+00,0.000000000000000000e+00 +8.199333218406739832e+01,5.127230138146297804e+02,1.216357161081349780e-01,1.078332240448663626e+01,3.387031669735386490e-03,6.578398694291673898e-01,-4.000000000000000327e-05,-1.000000009957335401e+00,0.000000000000000000e+00 +8.199425954203972822e+01,5.127330137572698732e+02,1.216695863600724126e-01,1.078393245753406759e+01,3.386885684333848772e-03,6.569125114476038751e-01,-4.000000000000000327e-05,-1.000000007337980001e+00,0.000000000000000000e+00 +8.199518684755089737e+01,5.127430136999149681e+02,1.217034551521642138e-01,1.078454161612629214e+01,3.386739698932311055e-03,6.559852059296252813e-01,-4.000000000000000327e-05,-1.000000008959736730e+00,0.000000000000000000e+00 +8.199611410068375505e+01,5.127530136425649516e+02,1.217373224844103680e-01,1.078514988046359946e+01,3.386593713530773337e-03,6.550579527884584641e-01,-4.000000000000000327e-05,-1.000000008979799793e+00,0.000000000000000000e+00 +8.199704130152109371e+01,5.127630135852199373e+02,1.217711883568108749e-01,1.078575725074593095e+01,3.386447728129235619e-03,6.541307519427926875e-01,-4.000000000000000327e-05,-1.000000009816663482e+00,0.000000000000000000e+00 +8.199796845014566316e+01,5.127730135278798116e+02,1.218050527693657348e-01,1.078636372717288516e+01,3.386301742727697902e-03,6.532036033091188632e-01,-4.000000000000000327e-05,-1.000000007689439308e+00,0.000000000000000000e+00 +8.199889554664017055e+01,5.127830134705446881e+02,1.218389157220749613e-01,1.078696930994371606e+01,3.386155757326160184e-03,6.522765068074773964e-01,-4.000000000000000327e-05,-1.000000009149740077e+00,0.000000000000000000e+00 +8.199982259108728044e+01,5.127930134132144531e+02,1.218727772149385408e-01,1.078757399925733651e+01,3.386009771924622467e-03,6.513494623518786275e-01,-4.000000000000000327e-05,-1.000000010415219576e+00,0.000000000000000000e+00 +8.200074958356961474e+01,5.128030133558892203e+02,1.219066372479564730e-01,1.078817779531231302e+01,3.385863786523084749e-03,6.504224698598836119e-01,-4.000000000000000327e-05,-1.000000007701035365e+00,0.000000000000000000e+00 +8.200167652416975272e+01,5.128130132985688761e+02,1.219404958211287582e-01,1.078878069830686925e+01,3.385717801121547032e-03,6.494955292526055635e-01,-4.000000000000000327e-05,-1.000000009626015096e+00,0.000000000000000000e+00 +8.200260341297021682e+01,5.128230132412535340e+02,1.219743529344553962e-01,1.078938270843888958e+01,3.385571815720009314e-03,6.485686404432121632e-01,-4.000000000000000327e-05,-1.000000008268706164e+00,0.000000000000000000e+00 +8.200353025005350105e+01,5.128330131839430805e+02,1.220082085879363870e-01,1.078998382590591198e+01,3.385425830318471597e-03,6.476418033522574058e-01,-4.000000000000000327e-05,-1.000000010180970067e+00,0.000000000000000000e+00 +8.200445703550205678e+01,5.128430131266376293e+02,1.220420627815717168e-01,1.079058405090513517e+01,3.385279844916933879e-03,6.467150178942662198e-01,-4.000000000000000327e-05,-1.000000007437183980e+00,0.000000000000000000e+00 +8.200538376939827856e+01,5.128530130693370666e+02,1.220759155153613995e-01,1.079118338363341323e+01,3.385133859515396162e-03,6.457882839911525119e-01,-4.000000000000000327e-05,-1.000000010725719646e+00,0.000000000000000000e+00 +8.200631045182451828e+01,5.128630130120415060e+02,1.221097667893054350e-01,1.079178182428726274e+01,3.384987874113858444e-03,6.448616015549681890e-01,-4.000000000000000327e-05,-1.000000007981536987e+00,0.000000000000000000e+00 +8.200723708286309943e+01,5.128730129547508341e+02,1.221436166034038234e-01,1.079237937306285389e+01,3.384841888712320727e-03,6.439349705089892906e-01,-4.000000000000000327e-05,-1.000000007823903969e+00,0.000000000000000000e+00 +8.200816366259628865e+01,5.128830128974651643e+02,1.221774649576565508e-01,1.079297603015602114e+01,3.384695903310783009e-03,6.430083907685477662e-01,-4.000000000000000327e-05,-1.000000010598716793e+00,0.000000000000000000e+00 +8.200909019110632414e+01,5.128930128401843831e+02,1.222113118520636310e-01,1.079357179576225612e+01,3.384549917909245292e-03,6.420818622486986760e-01,-4.000000000000000327e-05,-1.000000008372254667e+00,0.000000000000000000e+00 +8.201001666847537308e+01,5.129030127829084904e+02,1.222451572866250502e-01,1.079416667007670760e+01,3.384403932507707574e-03,6.411553848718910542e-01,-4.000000000000000327e-05,-1.000000009765358078e+00,0.000000000000000000e+00 +8.201094309478558841e+01,5.129130127256375999e+02,1.222790012613408223e-01,1.079476065329418866e+01,3.384257947106169857e-03,6.402289585526296234e-01,-4.000000000000000327e-05,-1.000000006841208045e+00,0.000000000000000000e+00 +8.201186947011906625e+01,5.129230126683715980e+02,1.223128437762109333e-01,1.079535374560916949e+01,3.384111961704632139e-03,6.393025832128150787e-01,-4.000000000000000327e-05,-1.000000012361834667e+00,0.000000000000000000e+00 +8.201279579455786006e+01,5.129330126111105983e+02,1.223466848312353972e-01,1.079594594721578460e+01,3.383965976303094422e-03,6.383762587625685381e-01,-4.000000000000000327e-05,-1.000000005966887651e+00,0.000000000000000000e+00 +8.201372206818398070e+01,5.129430125538544871e+02,1.223805244264142000e-01,1.079653725830782207e+01,3.383819990901556704e-03,6.374499851309144427e-01,-4.000000000000000327e-05,-1.000000010769487080e+00,0.000000000000000000e+00 +8.201464829107941057e+01,5.129530124966033782e+02,1.224143625617473419e-01,1.079712767907874138e+01,3.383674005500018987e-03,6.365237622255102146e-01,-4.000000000000000327e-05,-1.000000008475598223e+00,0.000000000000000000e+00 +8.201557446332607526e+01,5.129630124393571577e+02,1.224481992372348366e-01,1.079771720972165383e+01,3.383528020098481269e-03,6.355975899710010202e-01,-4.000000000000000327e-05,-1.000000007705867500e+00,0.000000000000000000e+00 +8.201650058500584350e+01,5.129730123821159395e+02,1.224820344528766702e-01,1.079830585042933855e+01,3.383382034696943551e-03,6.346714682840897126e-01,-4.000000000000000327e-05,-1.000000010870760292e+00,0.000000000000000000e+00 +8.201742665620056982e+01,5.129830123248796099e+02,1.225158682086728429e-01,1.079889360139423538e+01,3.383236049295405834e-03,6.337453970792895630e-01,-4.000000000000000327e-05,-1.000000007951393988e+00,0.000000000000000000e+00 +8.201835267699206611e+01,5.129930122676482824e+02,1.225497005046233545e-01,1.079948046280844309e+01,3.383090063893868116e-03,6.328193762804344980e-01,-4.000000000000000327e-05,-1.000000009641210497e+00,0.000000000000000000e+00 +8.201927864746207320e+01,5.130030122104218435e+02,1.225835313407282051e-01,1.080006643486372830e+01,3.382944078492330399e-03,6.318934058014979982e-01,-4.000000000000000327e-05,-1.000000007990207385e+00,0.000000000000000000e+00 +8.202020456769231771e+01,5.130130121532002931e+02,1.226173607169873947e-01,1.080065151775151655e+01,3.382798093090792681e-03,6.309674855638575108e-01,-4.000000000000000327e-05,-1.000000009549362412e+00,0.000000000000000000e+00 +8.202113043776446943e+01,5.130230120959837450e+02,1.226511886334009233e-01,1.080123571166289942e+01,3.382652107689254964e-03,6.300416154828667459e-01,-4.000000000000000327e-05,-1.000000010510206261e+00,0.000000000000000000e+00 +8.202205625776015552e+01,5.130330120387720854e+02,1.226850150899687908e-01,1.080181901678862921e+01,3.382506122287717246e-03,6.291157954774478922e-01,-4.000000000000000327e-05,-1.000000007060597440e+00,0.000000000000000000e+00 +8.202298202776097469e+01,5.130430119815654280e+02,1.227188400866909973e-01,1.080240143331912250e+01,3.382360136886179529e-03,6.281900254700941710e-01,-4.000000000000000327e-05,-1.000000009897426878e+00,0.000000000000000000e+00 +8.202390774784846883e+01,5.130530119243636591e+02,1.227526636235675289e-01,1.080298296144446368e+01,3.382214151484641811e-03,6.272643053734376917e-01,-4.000000000000000327e-05,-1.000000006916861972e+00,0.000000000000000000e+00 +8.202483341810415141e+01,5.130630118671668924e+02,1.227864857005983995e-01,1.080356360135439608e+01,3.382068166083104094e-03,6.263386351113574557e-01,-4.000000000000000327e-05,-1.000000010889048996e+00,0.000000000000000000e+00 +8.202575903860947903e+01,5.130730118099750143e+02,1.228203063177836091e-01,1.080414335323833264e+01,3.381922180681566376e-03,6.254130145959529985e-01,-4.000000000000000327e-05,-1.000000009706743853e+00,0.000000000000000000e+00 +8.202668460944587991e+01,5.130830117527880248e+02,1.228541254751231437e-01,1.080472221728534521e+01,3.381776195280028659e-03,6.244874437505726350e-01,-4.000000000000000327e-05,-1.000000007846042926e+00,0.000000000000000000e+00 +8.202761013069472540e+01,5.130930116956060374e+02,1.228879431726170174e-01,1.080530019368417527e+01,3.381630209878490941e-03,6.235619224944627392e-01,-4.000000000000000327e-05,-1.000000009784995925e+00,0.000000000000000000e+00 +8.202853560243737263e+01,5.131030116384289386e+02,1.229217594102652161e-01,1.080587728262323033e+01,3.381484224476953224e-03,6.226364507427667450e-01,-4.000000000000000327e-05,-1.000000007557262149e+00,0.000000000000000000e+00 +8.202946102475510770e+01,5.131130115812568420e+02,1.229555741880677538e-01,1.080645348429058039e+01,3.381338239075415506e-03,6.217110284180422664e-01,-4.000000000000000327e-05,-1.000000009788436062e+00,0.000000000000000000e+00 +8.203038639772918827e+01,5.131230115240896339e+02,1.229893875060246167e-01,1.080702879887396506e+01,3.381192253673877789e-03,6.207856554349057143e-01,-4.000000000000000327e-05,-1.000000010583468102e+00,0.000000000000000000e+00 +8.203131172144082939e+01,5.131330114669274280e+02,1.230231993641358046e-01,1.080760322656078642e+01,3.381046268272340071e-03,6.198603317134702140e-01,-4.000000000000000327e-05,-1.000000006119966978e+00,0.000000000000000000e+00 +8.203223699597120344e+01,5.131430114097701107e+02,1.230570097624013315e-01,1.080817676753811440e+01,3.380900282870802354e-03,6.189350571774265841e-01,-4.000000000000000327e-05,-1.000000011248123544e+00,0.000000000000000000e+00 +8.203316222140145442e+01,5.131530113526176820e+02,1.230908187008211835e-01,1.080874942199269029e+01,3.380754297469264636e-03,6.180098317367661576e-01,-4.000000000000000327e-05,-1.000000007619734843e+00,0.000000000000000000e+00 +8.203408739781266945e+01,5.131630112954702554e+02,1.231246261793953606e-01,1.080932119011091430e+01,3.380608312067726919e-03,6.170846553184979877e-01,-4.000000000000000327e-05,-1.000000010085716706e+00,0.000000000000000000e+00 +8.203501252528590726e+01,5.131730112383277174e+02,1.231584321981238628e-01,1.080989207207886160e+01,3.380462326666189201e-03,6.161595278359317529e-01,-4.000000000000000327e-05,-1.000000008594274403e+00,0.000000000000000000e+00 +8.203593760390216971e+01,5.131830111811901816e+02,1.231922367570066901e-01,1.081046206808226984e+01,3.380316341264651483e-03,6.152344492117175490e-01,-4.000000000000000327e-05,-1.000000009695602321e+00,0.000000000000000000e+00 +8.203686263374243026e+01,5.131930111240575343e+02,1.232260398560438425e-01,1.081103117830654803e+01,3.380170355863113766e-03,6.143094193624865085e-01,-4.000000000000000327e-05,-1.000000007485794429e+00,0.000000000000000000e+00 +8.203778761488761972e+01,5.132030110669297756e+02,1.232598414952353200e-01,1.081159940293677124e+01,3.380024370461576048e-03,6.133844382103718074e-01,-4.000000000000000327e-05,-1.000000010591754140e+00,0.000000000000000000e+00 +8.203871254741862629e+01,5.132130110098070190e+02,1.232936416745811226e-01,1.081216674215768592e+01,3.379878385060038331e-03,6.124595056695674167e-01,-4.000000000000000327e-05,-1.000000006877736158e+00,0.000000000000000000e+00 +8.203963743141629550e+01,5.132230109526891511e+02,1.233274403940812503e-01,1.081273319615370276e+01,3.379732399658500613e-03,6.115346216655327405e-01,-4.000000000000000327e-05,-1.000000011200584016e+00,0.000000000000000000e+00 +8.204056226696144449e+01,5.132330108955762853e+02,1.233612376537357030e-01,1.081329876510890742e+01,3.379586414256962896e-03,6.106097861100264756e-01,-4.000000000000000327e-05,-1.000000007267103364e+00,0.000000000000000000e+00 +8.204148705413483356e+01,5.132430108384683081e+02,1.233950334535444809e-01,1.081386344920704801e+01,3.379440428855425178e-03,6.096849989299165662e-01,-4.000000000000000327e-05,-1.000000009935776202e+00,0.000000000000000000e+00 +8.204241179301719455e+01,5.132530107813652194e+02,1.234288277935075839e-01,1.081442724863154936e+01,3.379294443453887461e-03,6.087602600383698048e-01,-4.000000000000000327e-05,-1.000000009140481261e+00,0.000000000000000000e+00 +8.204333648368921672e+01,5.132630107242671329e+02,1.234626206736249981e-01,1.081499016356550058e+01,3.379148458052349743e-03,6.078355693579021723e-01,-4.000000000000000327e-05,-1.000000009354170105e+00,0.000000000000000000e+00 +8.204426112623153244e+01,5.132730106671739350e+02,1.234964120938967375e-01,1.081555219419166392e+01,3.379002472650812026e-03,6.069109268069333707e-01,-4.000000000000000327e-05,-1.000000008817336195e+00,0.000000000000000000e+00 +8.204518572072475990e+01,5.132830106100857392e+02,1.235302020543227880e-01,1.081611334069247121e+01,3.378856487249274308e-03,6.059863323055501017e-01,-4.000000000000000327e-05,-1.000000007846976846e+00,0.000000000000000000e+00 +8.204611026724947465e+01,5.132930105530024321e+02,1.235639905549031636e-01,1.081667360325002569e+01,3.378710501847736591e-03,6.050617857735858252e-01,-4.000000000000000327e-05,-1.000000010916837434e+00,0.000000000000000000e+00 +8.204703476588619537e+01,5.133030104959240134e+02,1.235977775956378505e-01,1.081723298204610195e+01,3.378564516446198873e-03,6.041372871267778333e-01,-4.000000000000000327e-05,-1.000000007950863301e+00,0.000000000000000000e+00 +8.204795921671539816e+01,5.133130104388505970e+02,1.236315631765268624e-01,1.081779147726214241e+01,3.378418531044661156e-03,6.032128362902186014e-01,-4.000000000000000327e-05,-1.000000007577858563e+00,0.000000000000000000e+00 +8.204888361981754485e+01,5.133230103817820691e+02,1.236653472975701856e-01,1.081834908907926618e+01,3.378272545643123438e-03,6.022884331810629543e-01,-4.000000000000000327e-05,-1.000000012192566956e+00,0.000000000000000000e+00 +8.204980797527304048e+01,5.133330103247185434e+02,1.236991299587678200e-01,1.081890581767826198e+01,3.378126560241585721e-03,6.013640777142921223e-01,-4.000000000000000327e-05,-1.000000005476741283e+00,0.000000000000000000e+00 +8.205073228316226164e+01,5.133430102676599063e+02,1.237329111601197795e-01,1.081946166323958636e+01,3.377980574840048003e-03,6.004397698200106825e-01,-4.000000000000000327e-05,-1.000000012693327944e+00,0.000000000000000000e+00 +8.205165654356552807e+01,5.133530102106061577e+02,1.237666909016260502e-01,1.082001662594337787e+01,3.377834589438510286e-03,5.995155094050115263e-01,-4.000000000000000327e-05,-1.000000007124515200e+00,0.000000000000000000e+00 +8.205258075656313110e+01,5.133630101535574113e+02,1.238004691832866322e-01,1.082057070596943582e+01,3.377688604036972568e-03,5.985912964008218706e-01,-4.000000000000000327e-05,-1.000000007796490786e+00,0.000000000000000000e+00 +8.205350492223531944e+01,5.133730100965135534e+02,1.238342460051015254e-01,1.082112390349724329e+01,3.377542618635434851e-03,5.976671307214230788e-01,-4.000000000000000327e-05,-1.000000010863064004e+00,0.000000000000000000e+00 +8.205442904066231335e+01,5.133830100394745841e+02,1.238680213670707297e-01,1.082167621870595120e+01,3.377396633233897133e-03,5.967430122843909723e-01,-4.000000000000000327e-05,-1.000000008314635203e+00,0.000000000000000000e+00 +8.205535311192427628e+01,5.133930099824406170e+02,1.239017952691942454e-01,1.082222765177438184e+01,3.377250647832359415e-03,5.958189410147423093e-01,-4.000000000000000327e-05,-1.000000008781261052e+00,0.000000000000000000e+00 +8.205627713610134322e+01,5.134030099254115385e+02,1.239355677114720722e-01,1.082277820288103598e+01,3.377104662430821698e-03,5.948949168295577516e-01,-4.000000000000000327e-05,-1.000000010493285352e+00,0.000000000000000000e+00 +8.205720111327360655e+01,5.134130098683874621e+02,1.239693386939042102e-01,1.082332787220408576e+01,3.376958677029283980e-03,5.939709396475925107e-01,-4.000000000000000327e-05,-1.000000007516353762e+00,0.000000000000000000e+00 +8.205812504352113024e+01,5.134230098113682743e+02,1.240031082164906595e-01,1.082387665992137649e+01,3.376812691627746263e-03,5.930470093931238251e-01,-4.000000000000000327e-05,-1.000000008482571756e+00,0.000000000000000000e+00 +8.205904892692392139e+01,5.134330097543539750e+02,1.240368762792314200e-01,1.082442456621043192e+01,3.376666706226208545e-03,5.921231259824920601e-01,-4.000000000000000327e-05,-1.000000011619014861e+00,0.000000000000000000e+00 +8.205997276356195869e+01,5.134430096973446780e+02,1.240706428821264778e-01,1.082497159124844721e+01,3.376520720824670828e-03,5.911992893337147947e-01,-4.000000000000000327e-05,-1.000000006825550569e+00,0.000000000000000000e+00 +8.206089655351519241e+01,5.134530096403402695e+02,1.241044080251758469e-01,1.082551773521229066e+01,3.376374735423133110e-03,5.902754993741790024e-01,-4.000000000000000327e-05,-1.000000008978467525e+00,0.000000000000000000e+00 +8.206182029686351598e+01,5.134630095833407495e+02,1.241381717083795272e-01,1.082606299827851259e+01,3.376228750021595393e-03,5.893517560175672854e-01,-4.000000000000000327e-05,-1.000000010057597644e+00,0.000000000000000000e+00 +8.206274399368678019e+01,5.134730095263462317e+02,1.241719339317375048e-01,1.082660738062333294e+01,3.376082764620057675e-03,5.884280591850099551e-01,-4.000000000000000327e-05,-1.000000008285314879e+00,0.000000000000000000e+00 +8.206366764406482162e+01,5.134830094693566025e+02,1.242056946952497937e-01,1.082715088242264834e+01,3.375936779218519958e-03,5.875044087993175346e-01,-4.000000000000000327e-05,-1.000000010212593438e+00,0.000000000000000000e+00 +8.206459124807742000e+01,5.134930094123718618e+02,1.242394539989163799e-01,1.082769350385203388e+01,3.375790793816982240e-03,5.865808047772880229e-01,-4.000000000000000327e-05,-1.000000007813705016e+00,0.000000000000000000e+00 +8.206551480580432667e+01,5.135030093553921233e+02,1.242732118427372773e-01,1.082823524508673785e+01,3.375644808415444523e-03,5.856572470431704591e-01,-4.000000000000000327e-05,-1.000000009721459415e+00,0.000000000000000000e+00 +8.206643831732523608e+01,5.135130092984172734e+02,1.243069682267124720e-01,1.082877610630168874e+01,3.375498823013906805e-03,5.847337355132790071e-01,-4.000000000000000327e-05,-1.000000009990919425e+00,0.000000000000000000e+00 +8.206736178271982851e+01,5.135230092414473120e+02,1.243407231508419641e-01,1.082931608767148823e+01,3.375352837612369088e-03,5.838102701094565194e-01,-4.000000000000000327e-05,-1.000000006839905975e+00,0.000000000000000000e+00 +8.206828520206774158e+01,5.135330091844823528e+02,1.243744766151257675e-01,1.082985518937041647e+01,3.375206852210831370e-03,5.828868507552293909e-01,-4.000000000000000327e-05,-1.000000010985610643e+00,0.000000000000000000e+00 +8.206920857544855608e+01,5.135430091275222821e+02,1.244082286195638681e-01,1.083039341157243385e+01,3.375060866809293653e-03,5.819634773642655690e-01,-4.000000000000000327e-05,-1.000000008145815578e+00,0.000000000000000000e+00 +8.207013190294183858e+01,5.135530090705672137e+02,1.244419791641562661e-01,1.083093075445117215e+01,3.374914881407755935e-03,5.810401498634590878e-01,-4.000000000000000327e-05,-1.000000006952988629e+00,0.000000000000000000e+00 +8.207105518462711302e+01,5.135630090136170338e+02,1.244757282489029615e-01,1.083146721817994695e+01,3.374768896006218218e-03,5.801168681717706610e-01,-4.000000000000000327e-05,-1.000000011875650463e+00,0.000000000000000000e+00 +8.207197842058384651e+01,5.135730089566717425e+02,1.245094758738039542e-01,1.083200280293175055e+01,3.374622910604680500e-03,5.791936322040734941e-01,-4.000000000000000327e-05,-1.000000008624098990e+00,0.000000000000000000e+00 +8.207290161089149194e+01,5.135830088997314533e+02,1.245432220388592442e-01,1.083253750887924838e+01,3.374476925203142783e-03,5.782704418884714315e-01,-4.000000000000000327e-05,-1.000000007916102218e+00,0.000000000000000000e+00 +8.207382475562944535e+01,5.135930088427960527e+02,1.245769667440688316e-01,1.083307133619479146e+01,3.374330939801605065e-03,5.773472971432107581e-01,-4.000000000000000327e-05,-1.000000010049958421e+00,0.000000000000000000e+00 +8.207474785487707436e+01,5.136030087858655406e+02,1.246107099894327164e-01,1.083360428505040751e+01,3.374184954400067347e-03,5.764241978863002824e-01,-4.000000000000000327e-05,-1.000000009068926721e+00,0.000000000000000000e+00 +8.207567090871371818e+01,5.136130087289400308e+02,1.246444517749508984e-01,1.083413635561780097e+01,3.374038968998529630e-03,5.755011440412850510e-01,-4.000000000000000327e-05,-1.000000009437539195e+00,0.000000000000000000e+00 +8.207659391721865916e+01,5.136230086720194095e+02,1.246781921006233779e-01,1.083466754806835830e+01,3.373892983596991912e-03,5.745781355276262659e-01,-4.000000000000000327e-05,-1.000000007281730552e+00,0.000000000000000000e+00 +8.207751688047116545e+01,5.136330086151036767e+02,1.247119309664501408e-01,1.083519786257314443e+01,3.373746998195454195e-03,5.736551722683982391e-01,-4.000000000000000327e-05,-1.000000011237498709e+00,0.000000000000000000e+00 +8.207843979855044836e+01,5.136430085581928324e+02,1.247456683724312010e-01,1.083572729930290635e+01,3.373601012793916477e-03,5.727322541787418508e-01,-4.000000000000000327e-05,-1.000000007000617197e+00,0.000000000000000000e+00 +8.207936267153569077e+01,5.136530085012869904e+02,1.247794043185665586e-01,1.083625585842806593e+01,3.373455027392378760e-03,5.718093811870369469e-01,-4.000000000000000327e-05,-1.000000009463960060e+00,0.000000000000000000e+00 +8.208028549950603292e+01,5.136630084443860369e+02,1.248131388048561996e-01,1.083678354011873246e+01,3.373309041990841042e-03,5.708865532079557825e-01,-4.000000000000000327e-05,-1.000000010577953624e+00,0.000000000000000000e+00 +8.208120828254058665e+01,5.136730083874899719e+02,1.248468718313001380e-01,1.083731034454469011e+01,3.373163056589303325e-03,5.699637701636365295e-01,-4.000000000000000327e-05,-1.000000006461846391e+00,0.000000000000000000e+00 +8.208213102071842115e+01,5.136830083305989092e+02,1.248806033978983598e-01,1.083783627187540510e+01,3.373017071187765607e-03,5.690410319798350214e-01,-4.000000000000000327e-05,-1.000000012011237782e+00,0.000000000000000000e+00 +8.208305371411857720e+01,5.136930082737127350e+02,1.249143335046508790e-01,1.083836132228002924e+01,3.372871085786227890e-03,5.681183385685991682e-01,-4.000000000000000327e-05,-1.000000006653302576e+00,0.000000000000000000e+00 +8.208397636282003873e+01,5.137030082168314493e+02,1.249480621515576817e-01,1.083888549592738748e+01,3.372725100384690172e-03,5.671956898609964437e-01,-4.000000000000000327e-05,-1.000000009457101102e+00,0.000000000000000000e+00 +8.208489896690177545e+01,5.137130081599551659e+02,1.249817893386187678e-01,1.083940879298599569e+01,3.372579114983152455e-03,5.662730857705363663e-01,-4.000000000000000327e-05,-1.000000010279487483e+00,0.000000000000000000e+00 +8.208582152644270025e+01,5.137230081030837709e+02,1.250155150658341374e-01,1.083993121362404466e+01,3.372433129581614737e-03,5.653505262201238279e-01,-4.000000000000000327e-05,-1.000000009409393709e+00,0.000000000000000000e+00 +8.208674404152171178e+01,5.137330080462172646e+02,1.250492393332038044e-01,1.084045275800940900e+01,3.372287144180077020e-03,5.644280111324334603e-01,-4.000000000000000327e-05,-1.000000007134404179e+00,0.000000000000000000e+00 +8.208766651221765187e+01,5.137430079893557604e+02,1.250829621407277548e-01,1.084097342630964711e+01,3.372141158778539302e-03,5.635055404299108561e-01,-4.000000000000000327e-05,-1.000000010005438478e+00,0.000000000000000000e+00 +8.208858893860933392e+01,5.137530079324991448e+02,1.251166834884059886e-01,1.084149321869200122e+01,3.371995173377001585e-03,5.625831140289950794e-01,-4.000000000000000327e-05,-1.000000007871816310e+00,0.000000000000000000e+00 +8.208951132077554291e+01,5.137630078756474177e+02,1.251504033762385060e-01,1.084201213532339203e+01,3.371849187975463867e-03,5.616607318555250083e-01,-4.000000000000000327e-05,-1.000000011459456939e+00,0.000000000000000000e+00 +8.209043365879502119e+01,5.137730078188006928e+02,1.251841218042253068e-01,1.084253017637042760e+01,3.371703202573926150e-03,5.607383938254821842e-01,-4.000000000000000327e-05,-1.000000006437884892e+00,0.000000000000000000e+00 +8.209135595274646846e+01,5.137830077619588565e+02,1.252178387723663910e-01,1.084304734199939446e+01,3.371557217172388432e-03,5.598160998681019906e-01,-4.000000000000000327e-05,-1.000000011886555074e+00,0.000000000000000000e+00 +8.209227820270855602e+01,5.137930077051219087e+02,1.252515542806617588e-01,1.084356363237627008e+01,3.371411231770850715e-03,5.588938498950587475e-01,-4.000000000000000327e-05,-1.000000007206754749e+00,0.000000000000000000e+00 +8.209320040875991253e+01,5.138030076482898494e+02,1.252852683291114100e-01,1.084407904766670683e+01,3.371265246369312997e-03,5.579716438370604381e-01,-4.000000000000000327e-05,-1.000000009390553224e+00,0.000000000000000000e+00 +8.209412257097913823e+01,5.138130075914627923e+02,1.253189809177153446e-01,1.084459358803604978e+01,3.371119260967775279e-03,5.570494816091802193e-01,-4.000000000000000327e-05,-1.000000008278339569e+00,0.000000000000000000e+00 +8.209504468944479072e+01,5.138230075346406238e+02,1.253526920464735628e-01,1.084510725364932249e+01,3.370973275566237562e-03,5.561273631358963909e-01,-4.000000000000000327e-05,-1.000000010420089014e+00,0.000000000000000000e+00 +8.209596676423539918e+01,5.138330074778233438e+02,1.253864017153860644e-01,1.084562004467123586e+01,3.370827290164699844e-03,5.552052883356830559e-01,-4.000000000000000327e-05,-1.000000007741145724e+00,0.000000000000000000e+00 +8.209688879542945017e+01,5.138430074210110661e+02,1.254201099244528494e-01,1.084613196126618284e+01,3.370681304763162127e-03,5.542832571344955550e-01,-4.000000000000000327e-05,-1.000000008880830071e+00,0.000000000000000000e+00 +8.209781078310540181e+01,5.138530073642036768e+02,1.254538166736738902e-01,1.084664300359824551e+01,3.370535319361624409e-03,5.533612694503589058e-01,-4.000000000000000327e-05,-1.000000009941561352e+00,0.000000000000000000e+00 +8.209873272734166960e+01,5.138630073074011761e+02,1.254875219630492145e-01,1.084715317183118799e+01,3.370389333960086692e-03,5.524393252049275560e-01,-4.000000000000000327e-05,-1.000000009114000443e+00,0.000000000000000000e+00 +8.209965462821664062e+01,5.138730072506035640e+02,1.255212257925788222e-01,1.084766246612845997e+01,3.370243348558548974e-03,5.515174243215594796e-01,-4.000000000000000327e-05,-1.000000008767662596e+00,0.000000000000000000e+00 +8.210057648580865930e+01,5.138830071938109540e+02,1.255549281622627134e-01,1.084817088665319851e+01,3.370097363157011257e-03,5.505955667214634808e-01,-4.000000000000000327e-05,-1.000000009182211658e+00,0.000000000000000000e+00 +8.210149830019602746e+01,5.138930071370232326e+02,1.255886290721008602e-01,1.084867843356822625e+01,3.369951377755473539e-03,5.496737523256259861e-01,-4.000000000000000327e-05,-1.000000010636560743e+00,0.000000000000000000e+00 +8.210242007145703269e+01,5.139030070802403998e+02,1.256223285220932906e-01,1.084918510703605143e+01,3.369805392353935822e-03,5.487519810548117105e-01,-4.000000000000000327e-05,-1.000000007136671254e+00,0.000000000000000000e+00 +8.210334179966991996e+01,5.139130070234624554e+02,1.256560265122400044e-01,1.084969090721886786e+01,3.369659406952398104e-03,5.478302528353455880e-01,-4.000000000000000327e-05,-1.000000009413793967e+00,0.000000000000000000e+00 +8.210426348491289161e+01,5.139230069666895133e+02,1.256897230425409739e-01,1.085019583427856027e+01,3.369513421550860387e-03,5.469085675836962146e-01,-4.000000000000000327e-05,-1.000000009382022936e+00,0.000000000000000000e+00 +8.210518512726412155e+01,5.139330069099214597e+02,1.257234181129962269e-01,1.085069988837669541e+01,3.369367436149322669e-03,5.459869252238203075e-01,-4.000000000000000327e-05,-1.000000007316442119e+00,0.000000000000000000e+00 +8.210610672680174105e+01,5.139430068531582947e+02,1.257571117236057356e-01,1.085120306967452919e+01,3.369221450747784952e-03,5.450653256794557588e-01,-4.000000000000000327e-05,-1.000000009767523901e+00,0.000000000000000000e+00 +8.210702828360385297e+01,5.139530067964001319e+02,1.257908038743695278e-01,1.085170537833300664e+01,3.369075465346247234e-03,5.441437688683384843e-01,-4.000000000000000327e-05,-1.000000010736186606e+00,0.000000000000000000e+00 +8.210794979774853175e+01,5.139630067396468576e+02,1.258244945652876035e-01,1.085220681451275659e+01,3.368929479944709517e-03,5.432222547137680602e-01,-4.000000000000000327e-05,-1.000000008404507756e+00,0.000000000000000000e+00 +8.210887126931379498e+01,5.139730066828984718e+02,1.258581837963599348e-01,1.085270737837409705e+01,3.368783494543171799e-03,5.423007831407538060e-01,-4.000000000000000327e-05,-1.000000009322010053e+00,0.000000000000000000e+00 +8.210979269837766026e+01,5.139830066261549746e+02,1.258918715675865219e-01,1.085320707007703689e+01,3.368637509141634082e-03,5.413793540683043970e-01,-4.000000000000000327e-05,-1.000000007485834397e+00,0.000000000000000000e+00 +8.211071408501807412e+01,5.139930065694164796e+02,1.259255578789673924e-01,1.085370588978127060e+01,3.368491523740096364e-03,5.404579674209945006e-01,-4.000000000000000327e-05,-1.000000009445783489e+00,0.000000000000000000e+00 +8.211163542931296888e+01,5.140030065126828731e+02,1.259592427305025186e-01,1.085420383764618357e+01,3.368345538338558647e-03,5.395366231173983618e-01,-4.000000000000000327e-05,-1.000000009196675199e+00,0.000000000000000000e+00 +8.211255673134023425e+01,5.140130064559541552e+02,1.259929261221919283e-01,1.085470091383084679e+01,3.368199552937020929e-03,5.386153210816577719e-01,-4.000000000000000327e-05,-1.000000011195547600e+00,0.000000000000000000e+00 +8.211347799117773150e+01,5.140230063992303258e+02,1.260266080540355937e-01,1.085519711849402213e+01,3.368053567535483211e-03,5.376940612338425574e-01,-4.000000000000000327e-05,-1.000000007341110164e+00,0.000000000000000000e+00 +8.211439920890329347e+01,5.140330063425114986e+02,1.260602885260335149e-01,1.085569245179415887e+01,3.367907582133945494e-03,5.367728435015202137e-01,-4.000000000000000327e-05,-1.000000008368766791e+00,0.000000000000000000e+00 +8.211532038459469618e+01,5.140430062857975599e+02,1.260939675381857195e-01,1.085618691388940071e+01,3.367761596732407776e-03,5.358516678024025648e-01,-4.000000000000000327e-05,-1.000000010362986247e+00,0.000000000000000000e+00 +8.211624151832971563e+01,5.140530062290885098e+02,1.261276450904921798e-01,1.085668050493757697e+01,3.367615611330870059e-03,5.349305340578429657e-01,-4.000000000000000327e-05,-1.000000007311608430e+00,0.000000000000000000e+00 +8.211716261018605678e+01,5.140630061723843482e+02,1.261613211829528958e-01,1.085717322509620608e+01,3.367469625929332341e-03,5.340094421947667591e-01,-4.000000000000000327e-05,-1.000000009951621527e+00,0.000000000000000000e+00 +8.211808366024141037e+01,5.140730061156851889e+02,1.261949958155678952e-01,1.085766507452250096e+01,3.367323640527794624e-03,5.330883921302433937e-01,-4.000000000000000327e-05,-1.000000010175988274e+00,0.000000000000000000e+00 +8.211900466857343872e+01,5.140830060589909181e+02,1.262286689883371504e-01,1.085815605337336009e+01,3.367177655126256906e-03,5.321673837888436509e-01,-4.000000000000000327e-05,-1.000000008251678008e+00,0.000000000000000000e+00 +8.211992563525976152e+01,5.140930060023015358e+02,1.262623407012606613e-01,1.085864616180537467e+01,3.367031669724719189e-03,5.312464170949260378e-01,-4.000000000000000327e-05,-1.000000008633598947e+00,0.000000000000000000e+00 +8.212084656037795583e+01,5.141030059456170420e+02,1.262960109543384279e-01,1.085913539997482857e+01,3.366885684323181471e-03,5.303254919687799829e-01,-4.000000000000000327e-05,-1.000000009494006026e+00,0.000000000000000000e+00 +8.212176744400558448e+01,5.141130058889375505e+02,1.263296797475704503e-01,1.085962376803769480e+01,3.366739698921643754e-03,5.294046083324120966e-01,-4.000000000000000327e-05,-1.000000009003902512e+00,0.000000000000000000e+00 +8.212268828622015349e+01,5.141230058322629475e+02,1.263633470809567283e-01,1.086011126614963729e+01,3.366593713520106036e-03,5.284837661095469485e-01,-4.000000000000000327e-05,-1.000000009522898692e+00,0.000000000000000000e+00 +8.212360908709916885e+01,5.141330057755932330e+02,1.263970129544972620e-01,1.086059789446601265e+01,3.366447728118568319e-03,5.275629652217698196e-01,-4.000000000000000327e-05,-1.000000007125037449e+00,0.000000000000000000e+00 +8.212452984672006551e+01,5.141430057189284071e+02,1.264306773681920515e-01,1.086108365314186841e+01,3.366301742717030601e-03,5.266422055943145164e-01,-4.000000000000000327e-05,-1.000000010455607935e+00,0.000000000000000000e+00 +8.212545056516026420e+01,5.141530056622684697e+02,1.264643403220410967e-01,1.086156854233194657e+01,3.366155757315492884e-03,5.257214871444880755e-01,-4.000000000000000327e-05,-1.000000009300736181e+00,0.000000000000000000e+00 +8.212637124249715725e+01,5.141630056056135345e+02,1.264980018160443975e-01,1.086205256219067650e+01,3.366009771913955166e-03,5.248008097990353171e-01,-4.000000000000000327e-05,-1.000000010209969981e+00,0.000000000000000000e+00 +8.212729187880809434e+01,5.141730055489634879e+02,1.265316618502019541e-01,1.086253571287218378e+01,3.365863786512417449e-03,5.238801734787040809e-01,-4.000000000000000327e-05,-1.000000007157225035e+00,0.000000000000000000e+00 +8.212821247417038251e+01,5.141830054923183297e+02,1.265653204245137664e-01,1.086301799453028494e+01,3.365717801110879731e-03,5.229595781098232976e-01,-4.000000000000000327e-05,-1.000000008788158645e+00,0.000000000000000000e+00 +8.212913302866131460e+01,5.141930054356780602e+02,1.265989775389798344e-01,1.086349940731849273e+01,3.365571815709342014e-03,5.220390236107957938e-01,-4.000000000000000327e-05,-1.000000011172047953e+00,0.000000000000000000e+00 +8.213005354235815503e+01,5.142030053790427928e+02,1.266326331936001581e-01,1.086397995139000905e+01,3.365425830307804296e-03,5.211185099036763635e-01,-4.000000000000000327e-05,-1.000000006183390466e+00,0.000000000000000000e+00 +8.213097401533811137e+01,5.142130053224124140e+02,1.266662873883747376e-01,1.086445962689772848e+01,3.365279844906266579e-03,5.201980369180322361e-01,-4.000000000000000327e-05,-1.000000010853792975e+00,0.000000000000000000e+00 +8.213189444767836278e+01,5.142230052657869237e+02,1.266999401233035727e-01,1.086493843399424541e+01,3.365133859504728861e-03,5.192776045677862662e-01,-4.000000000000000327e-05,-1.000000008669433393e+00,0.000000000000000000e+00 +8.213281483945607420e+01,5.142330052091663219e+02,1.267335913983866635e-01,1.086541637283183981e+01,3.364987874103191143e-03,5.183572127820945674e-01,-4.000000000000000327e-05,-1.000000010372944503e+00,0.000000000000000000e+00 +8.213373519074836793e+01,5.142430051525506087e+02,1.267672412136240101e-01,1.086589344356249143e+01,3.364841888701653426e-03,5.174368614802582478e-01,-4.000000000000000327e-05,-1.000000007833878657e+00,0.000000000000000000e+00 +8.213465550163232365e+01,5.142530050959398977e+02,1.268008895690155846e-01,1.086636964633787095e+01,3.364695903300115708e-03,5.165165505890941811e-01,-4.000000000000000327e-05,-1.000000007601199004e+00,0.000000000000000000e+00 +8.213557577218499262e+01,5.142630050393340753e+02,1.268345364645614148e-01,1.086684498130934706e+01,3.364549917898577991e-03,5.155962800294245918e-01,-4.000000000000000327e-05,-1.000000012030192176e+00,0.000000000000000000e+00 +8.213649600248341187e+01,5.142730049827331413e+02,1.268681819002615008e-01,1.086731944862798116e+01,3.364403932497040273e-03,5.146760497199371898e-01,-4.000000000000000327e-05,-1.000000006692891796e+00,0.000000000000000000e+00 +8.213741619260456162e+01,5.142830049261370959e+02,1.269018258761158147e-01,1.086779304844452554e+01,3.364257947095502556e-03,5.137558595926292604e-01,-4.000000000000000327e-05,-1.000000010725200728e+00,0.000000000000000000e+00 +8.213833634262539363e+01,5.142930048695459391e+02,1.269354683921243843e-01,1.086826578090943585e+01,3.364111961693964838e-03,5.128357095619214823e-01,-4.000000000000000327e-05,-1.000000007598837559e+00,0.000000000000000000e+00 +8.213925645262284547e+01,5.143030048129597844e+02,1.269691094482872096e-01,1.086873764617285509e+01,3.363965976292427121e-03,5.119155995574758977e-01,-4.000000000000000327e-05,-1.000000010156832930e+00,0.000000000000000000e+00 +8.214017652267381209e+01,5.143130047563785183e+02,1.270027490446042628e-01,1.086920864438462786e+01,3.363819990890889403e-03,5.109955294971695317e-01,-4.000000000000000327e-05,-1.000000008161661569e+00,0.000000000000000000e+00 +8.214109655285514577e+01,5.143230046998021407e+02,1.270363871810755718e-01,1.086967877569428964e+01,3.363674005489351686e-03,5.100754993083311817e-01,-4.000000000000000327e-05,-1.000000010260847505e+00,0.000000000000000000e+00 +8.214201654324367041e+01,5.143330046432306517e+02,1.270700238577011365e-01,1.087014804025107573e+01,3.363528020087813968e-03,5.091555089103656506e-01,-4.000000000000000327e-05,-1.000000008312363242e+00,0.000000000000000000e+00 +8.214293649391618146e+01,5.143430045866640512e+02,1.271036590744809291e-01,1.087061643820391410e+01,3.363382034686276251e-03,5.082355582302006125e-01,-4.000000000000000327e-05,-1.000000008864542211e+00,0.000000000000000000e+00 +8.214385640494946017e+01,5.143530045301024529e+02,1.271372928314149775e-01,1.087108396970143254e+01,3.363236049284738533e-03,5.073156471887714236e-01,-4.000000000000000327e-05,-1.000000010070742684e+00,0.000000000000000000e+00 +8.214477627642021673e+01,5.143630044735457432e+02,1.271709251285032538e-01,1.087155063489195328e+01,3.363090063883200816e-03,5.063957757087443889e-01,-4.000000000000000327e-05,-1.000000007983171901e+00,0.000000000000000000e+00 +8.214569610840517555e+01,5.143730044169939220e+02,1.272045559657457858e-01,1.087201643392349482e+01,3.362944078481663098e-03,5.054759437164491054e-01,-4.000000000000000327e-05,-1.000000009150516567e+00,0.000000000000000000e+00 +8.214661590098098998e+01,5.143830043604469893e+02,1.272381853431425458e-01,1.087248136694377543e+01,3.362798093080125381e-03,5.045561511322231851e-01,-4.000000000000000327e-05,-1.000000009623861708e+00,0.000000000000000000e+00 +8.214753565422429915e+01,5.143930043039049451e+02,1.272718132606935337e-01,1.087294543410020786e+01,3.362652107678587663e-03,5.036363978800684205e-01,-4.000000000000000327e-05,-1.000000009652455502e+00,0.000000000000000000e+00 +8.214845536821169958e+01,5.144030042473679032e+02,1.273054397183987774e-01,1.087340863553990289e+01,3.362506122277049946e-03,5.027166838837889840e-01,-4.000000000000000327e-05,-1.000000007384637568e+00,0.000000000000000000e+00 +8.214937504301977356e+01,5.144130041908357498e+02,1.273390647162582490e-01,1.087387097140966929e+01,3.362360136875512228e-03,5.017970090689235496e-01,-4.000000000000000327e-05,-1.000000009369435450e+00,0.000000000000000000e+00 +8.215029467872506075e+01,5.144230041343084849e+02,1.273726882542719485e-01,1.087433244185601566e+01,3.362214151473974511e-03,5.008773733550193619e-01,-4.000000000000000327e-05,-1.000000009553978053e+00,0.000000000000000000e+00 +8.215121427540407240e+01,5.144330040777861086e+02,1.274063103324399038e-01,1.087479304702514504e+01,3.362068166072436793e-03,4.999577766672218537e-01,-4.000000000000000327e-05,-1.000000010285597707e+00,0.000000000000000000e+00 +8.215213383313329132e+01,5.144430040212686208e+02,1.274399309507620870e-01,1.087525278706296028e+01,3.361922180670899075e-03,4.990382189285491599e-01,-4.000000000000000327e-05,-1.000000007608981667e+00,0.000000000000000000e+00 +8.215305335198915770e+01,5.144530039647560216e+02,1.274735501092384982e-01,1.087571166211506224e+01,3.361776195269361358e-03,4.981187000656878139e-01,-4.000000000000000327e-05,-1.000000008072738700e+00,0.000000000000000000e+00 +8.215397283204808332e+01,5.144630039082484245e+02,1.275071678078691650e-01,1.087616967232675336e+01,3.361630209867823640e-03,4.971992199993339190e-01,-4.000000000000000327e-05,-1.000000009821781166e+00,0.000000000000000000e+00 +8.215489227338646572e+01,5.144730038517457160e+02,1.275407840466540599e-01,1.087662681784303231e+01,3.361484224466285923e-03,4.962797786519207999e-01,-4.000000000000000327e-05,-1.000000011000090172e+00,0.000000000000000000e+00 +8.215581167608065982e+01,5.144830037952478961e+02,1.275743988255931827e-01,1.087708309880859581e+01,3.361338239064748205e-03,4.953603759476195023e-01,-4.000000000000000327e-05,-1.000000007647983136e+00,0.000000000000000000e+00 +8.215673104020697792e+01,5.144930037387549646e+02,1.276080121446865334e-01,1.087753851536784033e+01,3.361192253663210488e-03,4.944410118142724686e-01,-4.000000000000000327e-05,-1.000000008415798947e+00,0.000000000000000000e+00 +8.215765036584171810e+01,5.145030036822669217e+02,1.276416240039341121e-01,1.087799306766486573e+01,3.361046268261672770e-03,4.935216861718001446e-01,-4.000000000000000327e-05,-1.000000009343540830e+00,0.000000000000000000e+00 +8.215856965306113580e+01,5.145130036257837673e+02,1.276752344033359188e-01,1.087844675584346810e+01,3.360900282860135053e-03,4.926023989437947614e-01,-4.000000000000000327e-05,-1.000000010673929296e+00,0.000000000000000000e+00 +8.215948890194145804e+01,5.145230035693056152e+02,1.277088433428919534e-01,1.087889958004714330e+01,3.360754297458597335e-03,4.916831500536563149e-01,-4.000000000000000327e-05,-1.000000006342212977e+00,0.000000000000000000e+00 +8.216040811255889764e+01,5.145330035128323516e+02,1.277424508226022160e-01,1.087935154041908703e+01,3.360608312057059618e-03,4.907639394303904279e-01,-4.000000000000000327e-05,-1.000000011305803183e+00,0.000000000000000000e+00 +8.216132728498961058e+01,5.145430034563639765e+02,1.277760568424667065e-01,1.087980263710220008e+01,3.360462326655521900e-03,4.898447669892843637e-01,-4.000000000000000327e-05,-1.000000006884121939e+00,0.000000000000000000e+00 +8.216224641930973860e+01,5.145530033999004900e+02,1.278096614024854250e-01,1.088025287023907595e+01,3.360316341253984183e-03,4.889256326628270699e-01,-4.000000000000000327e-05,-1.000000012240568781e+00,0.000000000000000000e+00 +8.216316551559539505e+01,5.145630033434418920e+02,1.278432645026583714e-01,1.088070223997201680e+01,3.360170355852446465e-03,4.880065363659240041e-01,-4.000000000000000327e-05,-1.000000006587502988e+00,0.000000000000000000e+00 +8.216408457392265063e+01,5.145730032869881825e+02,1.278768661429855458e-01,1.088115074644301750e+01,3.360024370450908748e-03,4.870874780326173159e-01,-4.000000000000000327e-05,-1.000000009089741404e+00,0.000000000000000000e+00 +8.216500359436754763e+01,5.145830032305393615e+02,1.279104663234669481e-01,1.088159838979378335e+01,3.359878385049371030e-03,4.861684575793654983e-01,-4.000000000000000327e-05,-1.000000009471733176e+00,0.000000000000000000e+00 +8.216592257700611412e+01,5.145930031740955428e+02,1.279440650441025784e-01,1.088204517016571415e+01,3.359732399647833313e-03,4.852494749321014100e-01,-4.000000000000000327e-05,-1.000000010074136192e+00,0.000000000000000000e+00 +8.216684152191432133e+01,5.146030031176566126e+02,1.279776623048924367e-01,1.088249108769991302e+01,3.359586414246295595e-03,4.843305300146370507e-01,-4.000000000000000327e-05,-1.000000006927555640e+00,0.000000000000000000e+00 +8.216776042916812628e+01,5.146130030612225710e+02,1.280112581058365229e-01,1.088293614253718467e+01,3.359440428844757878e-03,4.834116227544622002e-01,-4.000000000000000327e-05,-1.000000010787281290e+00,0.000000000000000000e+00 +8.216867929884345756e+01,5.146230030047934179e+02,1.280448524469348370e-01,1.088338033481803890e+01,3.359294443443220160e-03,4.824927530692136868e-01,-4.000000000000000327e-05,-1.000000009267394852e+00,0.000000000000000000e+00 +8.216959813101621535e+01,5.146330029483691533e+02,1.280784453281873514e-01,1.088382366468268181e+01,3.359148458041682443e-03,4.815739208879398214e-01,-4.000000000000000327e-05,-1.000000008914983418e+00,0.000000000000000000e+00 +8.217051692576225719e+01,5.146430028919497772e+02,1.281120367495940937e-01,1.088426613227102635e+01,3.359002472640144725e-03,4.806551261337029257e-01,-4.000000000000000327e-05,-1.000000007861405749e+00,0.000000000000000000e+00 +8.217143568315742641e+01,5.146530028355352897e+02,1.281456267111550640e-01,1.088470773772268707e+01,3.358856487238607007e-03,4.797363687313122571e-01,-4.000000000000000327e-05,-1.000000010550500917e+00,0.000000000000000000e+00 +8.217235440327752372e+01,5.146630027791258044e+02,1.281792152128702622e-01,1.088514848117698186e+01,3.358710501837069290e-03,4.788176486015242594e-01,-4.000000000000000327e-05,-1.000000006693517518e+00,0.000000000000000000e+00 +8.217327308619832138e+01,5.146730027227212076e+02,1.282128022547396606e-01,1.088558836277292841e+01,3.358564516435531572e-03,4.778989656745777359e-01,-4.000000000000000327e-05,-1.000000011257367039e+00,0.000000000000000000e+00 +8.217419173199556326e+01,5.146830026663214994e+02,1.282463878367632870e-01,1.088602738264925307e+01,3.358418531033993855e-03,4.769803198669912425e-01,-4.000000000000000327e-05,-1.000000007636361099e+00,0.000000000000000000e+00 +8.217511034074496479e+01,5.146930026099266797e+02,1.282799719589411414e-01,1.088646554094437846e+01,3.358272545632456137e-03,4.760617111105681087e-01,-4.000000000000000327e-05,-1.000000010797972738e+00,0.000000000000000000e+00 +8.217602891252222719e+01,5.147030025535367486e+02,1.283135546212731959e-01,1.088690283779643764e+01,3.358126560230918420e-03,4.751431393233916944e-01,-4.000000000000000327e-05,-1.000000008343423508e+00,0.000000000000000000e+00 +8.217694744740299484e+01,5.147130024971517059e+02,1.283471358237594784e-01,1.088733927334326168e+01,3.357980574829380702e-03,4.742246044349643919e-01,-4.000000000000000327e-05,-1.000000008925054473e+00,0.000000000000000000e+00 +8.217786594546289791e+01,5.147230024407715518e+02,1.283807155663999611e-01,1.088777484772239035e+01,3.357834589427842985e-03,4.733061063668703161e-01,-4.000000000000000327e-05,-1.000000008563319165e+00,0.000000000000000000e+00 +8.217878440677752394e+01,5.147330023843962863e+02,1.284142938491946717e-01,1.088820956107106497e+01,3.357688604026305267e-03,4.723876450443784125e-01,-4.000000000000000327e-05,-1.000000009594057770e+00,0.000000000000000000e+00 +8.217970283142244625e+01,5.147430023280260230e+02,1.284478706721435826e-01,1.088864341352623200e+01,3.357542618624767550e-03,4.714692203906415968e-01,-4.000000000000000327e-05,-1.000000008035731636e+00,0.000000000000000000e+00 +8.218062121947320975e+01,5.147530022716606481e+02,1.284814460352467214e-01,1.088907640522454123e+01,3.357396633223229832e-03,4.705508323324988362e-01,-4.000000000000000327e-05,-1.000000010435574627e+00,0.000000000000000000e+00 +8.218153957100531670e+01,5.147630022153001619e+02,1.285150199385040604e-01,1.088950853630234938e+01,3.357250647821692115e-03,4.696324807908053844e-01,-4.000000000000000327e-05,-1.000000008597573320e+00,0.000000000000000000e+00 +8.218245788609425517e+01,5.147730021589445641e+02,1.285485923819156273e-01,1.088993980689571472e+01,3.357104662420154397e-03,4.687141656939726175e-01,-4.000000000000000327e-05,-1.000000009068777063e+00,0.000000000000000000e+00 +8.218337616481547059e+01,5.147830021025938549e+02,1.285821633654813945e-01,1.089037021714040421e+01,3.356958677018616680e-03,4.677958869644285311e-01,-4.000000000000000327e-05,-1.000000009970921422e+00,0.000000000000000000e+00 +8.218429440724439416e+01,5.147930020462480343e+02,1.286157328892013896e-01,1.089079976717188813e+01,3.356812691617078962e-03,4.668776445263551067e-01,-4.000000000000000327e-05,-1.000000007317146666e+00,0.000000000000000000e+00 +8.218521261345640028e+01,5.148030019899071021e+02,1.286493009530755849e-01,1.089122845712534193e+01,3.356666706215541245e-03,4.659594383076240964e-01,-4.000000000000000327e-05,-1.000000009761696562e+00,0.000000000000000000e+00 +8.218613078352687751e+01,5.148130019335710585e+02,1.286828675571039804e-01,1.089165628713564971e+01,3.356520720814003527e-03,4.650412682281896970e-01,-4.000000000000000327e-05,-1.000000009102896881e+00,0.000000000000000000e+00 +8.218704891753114339e+01,5.148230018772399035e+02,1.287164327012866039e-01,1.089208325733739713e+01,3.356374735412465810e-03,4.641231342155657247e-01,-4.000000000000000327e-05,-1.000000009780326327e+00,0.000000000000000000e+00 +8.218796701554451545e+01,5.148330018209137506e+02,1.287499963856234275e-01,1.089250936786487856e+01,3.356228750010928092e-03,4.632050361932184557e-01,-4.000000000000000327e-05,-1.000000007804137780e+00,0.000000000000000000e+00 +8.218888507764226858e+01,5.148430017645924863e+02,1.287835586101144514e-01,1.089293461885209346e+01,3.356082764609390374e-03,4.622869740883059353e-01,-4.000000000000000327e-05,-1.000000009721534244e+00,0.000000000000000000e+00 +8.218980310389964927e+01,5.148530017082761105e+02,1.288171193747596754e-01,1.089335901043275001e+01,3.355936779207852657e-03,4.613689478220040496e-01,-4.000000000000000327e-05,-1.000000009433367421e+00,0.000000000000000000e+00 +8.219072109439187557e+01,5.148630016519646233e+02,1.288506786795590997e-01,1.089378254274025970e+01,3.355790793806314939e-03,4.604509573211166273e-01,-4.000000000000000327e-05,-1.000000009270924917e+00,0.000000000000000000e+00 +8.219163904919415131e+01,5.148730015956580246e+02,1.288842365245127519e-01,1.089420521590774271e+01,3.355644808404777222e-03,4.595330025103357419e-01,-4.000000000000000327e-05,-1.000000007348560649e+00,0.000000000000000000e+00 +8.219255696838162351e+01,5.148830015393563144e+02,1.289177929096206043e-01,1.089462703006802613e+01,3.355498823003239504e-03,4.586150833161127816e-01,-4.000000000000000327e-05,-1.000000010213405011e+00,0.000000000000000000e+00 +8.219347485202943915e+01,5.148930014830594928e+02,1.289513478348826570e-01,1.089504798535364571e+01,3.355352837601701787e-03,4.576971996589178082e-01,-4.000000000000000327e-05,-1.000000009654313127e+00,0.000000000000000000e+00 +8.219439270021270261e+01,5.149030014267675597e+02,1.289849013002989098e-01,1.089546808189684057e+01,3.355206852200164069e-03,4.567793514667862764e-01,-4.000000000000000327e-05,-1.000000008000205831e+00,0.000000000000000000e+00 +8.219531051300650404e+01,5.149130013704805151e+02,1.290184533058693628e-01,1.089588731982956027e+01,3.355060866798626352e-03,4.558615386656439949e-01,-4.000000000000000327e-05,-1.000000009689441693e+00,0.000000000000000000e+00 +8.219622829048589097e+01,5.149230013141983591e+02,1.290520038515940160e-01,1.089630569928346304e+01,3.354914881397088634e-03,4.549437611773713974e-01,-4.000000000000000327e-05,-1.000000008615747005e+00,0.000000000000000000e+00 +8.219714603272586828e+01,5.149330012579210916e+02,1.290855529374728694e-01,1.089672322038991226e+01,3.354768895995550917e-03,4.540260189294813564e-01,-4.000000000000000327e-05,-1.000000009216577057e+00,0.000000000000000000e+00 +8.219806373980145509e+01,5.149430012016488263e+02,1.291191005635059230e-01,1.089713988327998173e+01,3.354622910594013199e-03,4.531083118454422021e-01,-4.000000000000000327e-05,-1.000000009602063367e+00,0.000000000000000000e+00 +8.219898141178759943e+01,5.149530011453814495e+02,1.291526467296931768e-01,1.089755568808445219e+01,3.354476925192475482e-03,4.521906398504846880e-01,-4.000000000000000327e-05,-1.000000007881189923e+00,0.000000000000000000e+00 +8.219989904875924935e+01,5.149630010891189613e+02,1.291861914360346308e-01,1.089797063493381302e+01,3.354330939790937764e-03,4.512730028716027131e-01,-4.000000000000000327e-05,-1.000000008490813830e+00,0.000000000000000000e+00 +8.220081665079131028e+01,5.149730010328613616e+02,1.292197346825302851e-01,1.089838472395826408e+01,3.354184954389400047e-03,4.503554008317465218e-01,-4.000000000000000327e-05,-1.000000011649131659e+00,0.000000000000000000e+00 +8.220173421795867341e+01,5.149830009766086505e+02,1.292532764691801395e-01,1.089879795528771211e+01,3.354038968987862329e-03,4.494378336536941632e-01,-4.000000000000000327e-05,-1.000000007023439608e+00,0.000000000000000000e+00 +8.220265175033618732e+01,5.149930009203608279e+02,1.292868167959841941e-01,1.089921032905177078e+01,3.353892983586324612e-03,4.485203012697322467e-01,-4.000000000000000327e-05,-1.000000009599684825e+00,0.000000000000000000e+00 +8.220356924799868636e+01,5.150030008641178938e+02,1.293203556629424489e-01,1.089962184537976952e+01,3.353746998184786894e-03,4.476028035984246367e-01,-4.000000000000000327e-05,-1.000000009043859439e+00,0.000000000000000000e+00 +8.220448671102096228e+01,5.150130008078798483e+02,1.293538930700548761e-01,1.090003250440074112e+01,3.353601012783249177e-03,4.466853405678445910e-01,-4.000000000000000327e-05,-1.000000009791493394e+00,0.000000000000000000e+00 +8.220540413947780678e+01,5.150230007516466912e+02,1.293874290173215036e-01,1.090044230624343058e+01,3.353455027381711459e-03,4.457679121020232671e-01,-4.000000000000000327e-05,-1.000000007836534976e+00,0.000000000000000000e+00 +8.220632153344394055e+01,5.150330006954184228e+02,1.294209635047423312e-01,1.090085125103629160e+01,3.353309041980173742e-03,4.448505181286945276e-01,-4.000000000000000327e-05,-1.000000009724985928e+00,0.000000000000000000e+00 +8.220723889299409848e+01,5.150430006391950428e+02,1.294544965323173591e-01,1.090125933890749010e+01,3.353163056578636024e-03,4.439331585696142946e-01,-4.000000000000000327e-05,-1.000000009338692708e+00,0.000000000000000000e+00 +8.220815621820297281e+01,5.150530005829765514e+02,1.294880281000465594e-01,1.090166656998489891e+01,3.353017071177098306e-03,4.430158333521785341e-01,-4.000000000000000327e-05,-1.000000006890406468e+00,0.000000000000000000e+00 +8.220907350914521317e+01,5.150630005267629485e+02,1.295215582079299599e-01,1.090207294439610308e+01,3.352871085775560589e-03,4.420985424036150691e-01,-4.000000000000000327e-05,-1.000000011037613712e+00,0.000000000000000000e+00 +8.220999076589546917e+01,5.150730004705542342e+02,1.295550868559675606e-01,1.090247846226839989e+01,3.352725100374022871e-03,4.411812856432375529e-01,-4.000000000000000327e-05,-1.000000009325331174e+00,0.000000000000000000e+00 +8.221090798852834780e+01,5.150830004143504084e+02,1.295886140441593337e-01,1.090288312372879176e+01,3.352579114972485154e-03,4.402640630018114232e-01,-4.000000000000000327e-05,-1.000000008298562282e+00,0.000000000000000000e+00 +8.221182517711842763e+01,5.150930003581514711e+02,1.296221397725053071e-01,1.090328692890399687e+01,3.352433129570947436e-03,4.393468744041255647e-01,-4.000000000000000327e-05,-1.000000010280719165e+00,0.000000000000000000e+00 +8.221274233174025881e+01,5.151030003019575361e+02,1.296556640410054528e-01,1.090368987792044386e+01,3.352287144169409719e-03,4.384297197728649897e-01,-4.000000000000000327e-05,-1.000000007035107830e+00,0.000000000000000000e+00 +8.221365945246837725e+01,5.151130002457684895e+02,1.296891868496597988e-01,1.090409197090427007e+01,3.352141158767872001e-03,4.375125990382959795e-01,-4.000000000000000327e-05,-1.000000009331215578e+00,0.000000000000000000e+00 +8.221457653937727628e+01,5.151230001895843316e+02,1.297227081984683450e-01,1.090449320798132860e+01,3.351995173366334284e-03,4.365955121208345835e-01,-4.000000000000000327e-05,-1.000000011043298720e+00,0.000000000000000000e+00 +8.221549359254143496e+01,5.151330001334050621e+02,1.297562280874310636e-01,1.090489358927717944e+01,3.351849187964796566e-03,4.356784589465418356e-01,-4.000000000000000327e-05,-1.000000008155351061e+00,0.000000000000000000e+00 +8.221641061203530398e+01,5.151430000772306812e+02,1.297897465165479824e-01,1.090529311491709485e+01,3.351703202563258849e-03,4.347614394451881914e-01,-4.000000000000000327e-05,-1.000000007212517028e+00,0.000000000000000000e+00 +8.221732759793330558e+01,5.151530000210611888e+02,1.298232634858190737e-01,1.090569178502606285e+01,3.351557217161721131e-03,4.338444535405684976e-01,-4.000000000000000327e-05,-1.000000010536133743e+00,0.000000000000000000e+00 +8.221824455030983358e+01,5.151629999648965850e+02,1.298567789952443374e-01,1.090608959972878189e+01,3.351411231760183414e-03,4.329275011543758378e-01,-4.000000000000000327e-05,-1.000000009883226015e+00,0.000000000000000000e+00 +8.221916146923925339e+01,5.151729999087368697e+02,1.298902930448238013e-01,1.090648655914965914e+01,3.351265246358645696e-03,4.320105822158883946e-01,-4.000000000000000327e-05,-1.000000007572693139e+00,0.000000000000000000e+00 +8.222007835479591620e+01,5.151829998525820429e+02,1.299238056345574377e-01,1.090688266341281754e+01,3.351119260957107979e-03,4.310936966522842528e-01,-4.000000000000000327e-05,-1.000000010150375207e+00,0.000000000000000000e+00 +8.222099520705413056e+01,5.151929997964321046e+02,1.299573167644452465e-01,1.090727791264209401e+01,3.350973275555570261e-03,4.301768443847661660e-01,-4.000000000000000327e-05,-1.000000007256599766e+00,0.000000000000000000e+00 +8.222191202608817662e+01,5.152029997402870549e+02,1.299908264344872555e-01,1.090767230696103418e+01,3.350827290154032544e-03,4.292600253440616576e-01,-4.000000000000000327e-05,-1.000000011776502884e+00,0.000000000000000000e+00 +8.222282881197233451e+01,5.152129996841468937e+02,1.300243346446834369e-01,1.090806584649290123e+01,3.350681304752494826e-03,4.283432394491110684e-01,-4.000000000000000327e-05,-1.000000007007525005e+00,0.000000000000000000e+00 +8.222374556478082752e+01,5.152229996280116211e+02,1.300578413950337908e-01,1.090845853136066523e+01,3.350535319350957109e-03,4.274264866341938029e-01,-4.000000000000000327e-05,-1.000000010062341627e+00,0.000000000000000000e+00 +8.222466228458786475e+01,5.152329995718812370e+02,1.300913466855383449e-01,1.090885036168701738e+01,3.350389333949419391e-03,4.265097668179269608e-01,-4.000000000000000327e-05,-1.000000008462952561e+00,0.000000000000000000e+00 +8.222557897146764105e+01,5.152429995157557414e+02,1.301248505161970714e-01,1.090924133759435577e+01,3.350243348547881674e-03,4.255930799303929146e-01,-4.000000000000000327e-05,-1.000000008753933356e+00,0.000000000000000000e+00 +8.222649562549430868e+01,5.152529994596351344e+02,1.301583528870099704e-01,1.090963145920479604e+01,3.350097363146343956e-03,4.246764258957004823e-01,-4.000000000000000327e-05,-1.000000009024406555e+00,0.000000000000000000e+00 +8.222741224674200566e+01,5.152629994035194159e+02,1.301918537979770418e-01,1.091002072664016609e+01,3.349951377744806238e-03,4.237598046397361706e-01,-4.000000000000000327e-05,-1.000000009476549989e+00,0.000000000000000000e+00 +8.222832883528482739e+01,5.152729993474085859e+02,1.302253532490982857e-01,1.091040914002200779e+01,3.349805392343268521e-03,4.228432160882270585e-01,-4.000000000000000327e-05,-1.000000010312439791e+00,0.000000000000000000e+00 +8.222924539119685505e+01,5.152829992913026445e+02,1.302588512403737020e-01,1.091079669947157704e+01,3.349659406941730803e-03,4.219266601667408523e-01,-4.000000000000000327e-05,-1.000000007503923705e+00,0.000000000000000000e+00 +8.223016191455215562e+01,5.152929992352015915e+02,1.302923477718033185e-01,1.091118340510984375e+01,3.349513421540193086e-03,4.210101368045629511e-01,-4.000000000000000327e-05,-1.000000007595477136e+00,0.000000000000000000e+00 +8.223107840542475344e+01,5.153029991791054272e+02,1.303258428433871075e-01,1.091156925705749536e+01,3.349367436138655368e-03,4.200936459250061428e-01,-4.000000000000000327e-05,-1.000000010788126836e+00,0.000000000000000000e+00 +8.223199486388864443e+01,5.153129991230141513e+02,1.303593364551250688e-01,1.091195425543493158e+01,3.349221450737117651e-03,4.191771874512248974e-01,-4.000000000000000327e-05,-1.000000008821888109e+00,0.000000000000000000e+00 +8.223291129001781030e+01,5.153229990669277640e+02,1.303928286070172027e-01,1.091233840036226432e+01,3.349075465335579933e-03,4.182607613139692204e-01,-4.000000000000000327e-05,-1.000000010355954982e+00,0.000000000000000000e+00 +8.223382768388620434e+01,5.153329990108462653e+02,1.304263192990635090e-01,1.091272169195932484e+01,3.348929479934042216e-03,4.173443674360788891e-01,-4.000000000000000327e-05,-1.000000007127907153e+00,0.000000000000000000e+00 +8.223474404556776562e+01,5.153429989547696550e+02,1.304598085312639877e-01,1.091310413034565663e+01,3.348783494532504498e-03,4.164280057479908259e-01,-4.000000000000000327e-05,-1.000000009913084131e+00,0.000000000000000000e+00 +8.223566037513637639e+01,5.153529988986979333e+02,1.304932963036186389e-01,1.091348571564052250e+01,3.348637509130966781e-03,4.155116761702931094e-01,-4.000000000000000327e-05,-1.000000008331814350e+00,0.000000000000000000e+00 +8.223657667266591886e+01,5.153629988426311002e+02,1.305267826161274347e-01,1.091386644796289573e+01,3.348491523729429063e-03,4.145953786331105784e-01,-4.000000000000000327e-05,-1.000000011043830295e+00,0.000000000000000000e+00 +8.223749293823024686e+01,5.153729987865691555e+02,1.305602674687904030e-01,1.091424632743146894e+01,3.348345538327891346e-03,4.136791130586582876e-01,-4.000000000000000327e-05,-1.000000007666840718e+00,0.000000000000000000e+00 +8.223840917190318578e+01,5.153829987305120994e+02,1.305937508616075438e-01,1.091462535416464696e+01,3.348199552926353628e-03,4.127628793786894956e-01,-4.000000000000000327e-05,-1.000000008976185351e+00,0.000000000000000000e+00 +8.223932537375854679e+01,5.153929986744599319e+02,1.306272327945788569e-01,1.091500352828055576e+01,3.348053567524815911e-03,4.118466775151096160e-01,-4.000000000000000327e-05,-1.000000008820147279e+00,0.000000000000000000e+00 +8.224024154387008423e+01,5.154029986184126528e+02,1.306607132677043426e-01,1.091538084989703350e+01,3.347907582123278193e-03,4.109305073954855891e-01,-4.000000000000000327e-05,-1.000000009509652399e+00,0.000000000000000000e+00 +8.224115768231156665e+01,5.154129985623702623e+02,1.306941922809840007e-01,1.091575731913163594e+01,3.347761596721740476e-03,4.100143689452920848e-01,-4.000000000000000327e-05,-1.000000007006470293e+00,0.000000000000000000e+00 +8.224207378915670574e+01,5.154229985063327604e+02,1.307276698344178034e-01,1.091613293610163460e+01,3.347615611320202758e-03,4.090982620937282377e-01,-4.000000000000000327e-05,-1.000000012087882473e+00,0.000000000000000000e+00 +8.224298986447921322e+01,5.154329984503001469e+02,1.307611459280057786e-01,1.091650770092402034e+01,3.347469625918665041e-03,4.081821867601449494e-01,-4.000000000000000327e-05,-1.000000008014127584e+00,0.000000000000000000e+00 +8.224390590835275816e+01,5.154429983942724220e+02,1.307946205617479263e-01,1.091688161371549448e+01,3.347323640517127323e-03,4.072661428792530014e-01,-4.000000000000000327e-05,-1.000000007678416347e+00,0.000000000000000000e+00 +8.224482192085099541e+01,5.154529983382495857e+02,1.308280937356442186e-01,1.091725467459248300e+01,3.347177655115589606e-03,4.063501303739767145e-01,-4.000000000000000327e-05,-1.000000009157149039e+00,0.000000000000000000e+00 +8.224573790204755142e+01,5.154629982822316379e+02,1.308615654496946834e-01,1.091762688367112588e+01,3.347031669714051888e-03,4.054341491690274246e-01,-4.000000000000000327e-05,-1.000000010525484040e+00,0.000000000000000000e+00 +8.224665385201603840e+01,5.154729982262185786e+02,1.308950357038993206e-01,1.091799824106727890e+01,3.346885684312514170e-03,4.045181991909043151e-01,-4.000000000000000327e-05,-1.000000007740273311e+00,0.000000000000000000e+00 +8.224756977083002596e+01,5.154829981702104078e+02,1.309285044982581026e-01,1.091836874689651538e+01,3.346739698910976453e-03,4.036022803698343098e-01,-4.000000000000000327e-05,-1.000000011579712744e+00,0.000000000000000000e+00 +8.224848565856305527e+01,5.154929981142071256e+02,1.309619718327710569e-01,1.091873840127412976e+01,3.346593713509438735e-03,4.026863926261968207e-01,-4.000000000000000327e-05,-1.000000005293674832e+00,0.000000000000000000e+00 +8.224940151528866750e+01,5.155029980582087319e+02,1.309954377074381560e-01,1.091910720431512871e+01,3.346447728107901018e-03,4.017705358957370243e-01,-4.000000000000000327e-05,-1.000000012367238567e+00,0.000000000000000000e+00 +8.225031734108036119e+01,5.155129980022152267e+02,1.310289021222594275e-01,1.091947515613424535e+01,3.346301742706363300e-03,4.008547100927152829e-01,-4.000000000000000327e-05,-1.000000007576461902e+00,0.000000000000000000e+00 +8.225123313601162067e+01,5.155229979462266101e+02,1.310623650772348436e-01,1.091984225684591969e+01,3.346155757304825583e-03,3.999389151545174603e-01,-4.000000000000000327e-05,-1.000000008053124612e+00,0.000000000000000000e+00 +8.225214890015590186e+01,5.155329978902428820e+02,1.310958265723644323e-01,1.092020850656431996e+01,3.346009771903287865e-03,3.990231510028638962e-01,-4.000000000000000327e-05,-1.000000009750603880e+00,0.000000000000000000e+00 +8.225306463358663223e+01,5.155429978342640425e+02,1.311292866076481656e-01,1.092057390540332840e+01,3.345863786501750148e-03,3.981074175632052237e-01,-4.000000000000000327e-05,-1.000000008620270942e+00,0.000000000000000000e+00 +8.225398033637722506e+01,5.155529977782900914e+02,1.311627451830860713e-01,1.092093845347654479e+01,3.345717801100212430e-03,3.971917147647236468e-01,-4.000000000000000327e-05,-1.000000011205065986e+00,0.000000000000000000e+00 +8.225489600860105099e+01,5.155629977223210290e+02,1.311962022986781218e-01,1.092130215089729006e+01,3.345571815698674713e-03,3.962760425306339762e-01,-4.000000000000000327e-05,-1.000000007099022259e+00,0.000000000000000000e+00 +8.225581165033148068e+01,5.155729976663568550e+02,1.312296579544243447e-01,1.092166499777860089e+01,3.345425830297136995e-03,3.953604007937034925e-01,-4.000000000000000327e-05,-1.000000009200749274e+00,0.000000000000000000e+00 +8.225672726164184212e+01,5.155829976103975696e+02,1.312631121503247122e-01,1.092202699423323864e+01,3.345279844895599278e-03,3.944447894749126826e-01,-4.000000000000000327e-05,-1.000000009221729602e+00,0.000000000000000000e+00 +8.225764284260546333e+01,5.155929975544431727e+02,1.312965648863792245e-01,1.092238814037367867e+01,3.345133859494061560e-03,3.935292085028552767e-01,-4.000000000000000327e-05,-1.000000009466165851e+00,0.000000000000000000e+00 +8.225855839329561547e+01,5.156029974984936644e+02,1.313300161625879092e-01,1.092274843631211745e+01,3.344987874092523843e-03,3.926136578040390068e-01,-4.000000000000000327e-05,-1.000000007999978457e+00,0.000000000000000000e+00 +8.225947391378556972e+01,5.156129974425490445e+02,1.313634659789507386e-01,1.092310788216047079e+01,3.344841888690986125e-03,3.916981373067660588e-01,-4.000000000000000327e-05,-1.000000009246511334e+00,0.000000000000000000e+00 +8.226038940414855460e+01,5.156229973866093133e+02,1.313969143354677127e-01,1.092346647803037563e+01,3.344695903289448408e-03,3.907826469353126164e-01,-4.000000000000000327e-05,-1.000000009151116309e+00,0.000000000000000000e+00 +8.226130486445779866e+01,5.156329973306743568e+02,1.314303612321388315e-01,1.092382422403318643e+01,3.344549917887910690e-03,3.898671866176905976e-01,-4.000000000000000327e-05,-1.000000010017132457e+00,0.000000000000000000e+00 +8.226222029478648778e+01,5.156429972747442889e+02,1.314638066689640949e-01,1.092418112027997878e+01,3.344403932486372973e-03,3.889517562798268102e-01,-4.000000000000000327e-05,-1.000000007787882117e+00,0.000000000000000000e+00 +8.226313569520779367e+01,5.156529972188191095e+02,1.314972506459435309e-01,1.092453716688154763e+01,3.344257947084835255e-03,3.880363558513851285e-01,-4.000000000000000327e-05,-1.000000009005580726e+00,0.000000000000000000e+00 +8.226405106579487381e+01,5.156629971628988187e+02,1.315306931630771115e-01,1.092489236394841079e+01,3.344111961683297538e-03,3.871209852560640319e-01,-4.000000000000000327e-05,-1.000000009612969754e+00,0.000000000000000000e+00 +8.226496640662084303e+01,5.156729971069834164e+02,1.315641342203648367e-01,1.092524671159080363e+01,3.343965976281759820e-03,3.862056444212994544e-01,-4.000000000000000327e-05,-1.000000007671089541e+00,0.000000000000000000e+00 +8.226588171775880198e+01,5.156829970510729027e+02,1.315975738178067067e-01,1.092560020991868264e+01,3.343819990880222102e-03,3.852903332763253363e-01,-4.000000000000000327e-05,-1.000000011842458347e+00,0.000000000000000000e+00 +8.226679699928182288e+01,5.156929969951672774e+02,1.316310119554027214e-01,1.092595285904172719e+01,3.343674005478684385e-03,3.843750517424699975e-01,-4.000000000000000327e-05,-1.000000005344547027e+00,0.000000000000000000e+00 +8.226771225126294951e+01,5.157029969392665407e+02,1.316644486331528807e-01,1.092630465906933246e+01,3.343528020077146667e-03,3.834597997564457295e-01,-4.000000000000000327e-05,-1.000000011682861123e+00,0.000000000000000000e+00 +8.226862747377522567e+01,5.157129968833706926e+02,1.316978838510571848e-01,1.092665561011062358e+01,3.343382034675608950e-03,3.825445772334742367e-01,-4.000000000000000327e-05,-1.000000007710853511e+00,0.000000000000000000e+00 +8.226954266689165252e+01,5.157229968274797329e+02,1.317313176091156335e-01,1.092700571227443618e+01,3.343236049274071232e-03,3.816293841099849815e-01,-4.000000000000000327e-05,-1.000000010573243836e+00,0.000000000000000000e+00 +8.227045783068521700e+01,5.157329967715936618e+02,1.317647499073282269e-01,1.092735496566933584e+01,3.343090063872533515e-03,3.807142203067392927e-01,-4.000000000000000327e-05,-1.000000007723450102e+00,0.000000000000000000e+00 +8.227137296522887766e+01,5.157429967157124793e+02,1.317981807456949650e-01,1.092770337040360396e+01,3.342944078470995797e-03,3.797990857560038513e-01,-4.000000000000000327e-05,-1.000000009944872037e+00,0.000000000000000000e+00 +8.227228807059557880e+01,5.157529966598361852e+02,1.318316101242158478e-01,1.092805092658524835e+01,3.342798093069458080e-03,3.788839803801997697e-01,-4.000000000000000327e-05,-1.000000006809503850e+00,0.000000000000000000e+00 +8.227320314685823632e+01,5.157629966039647798e+02,1.318650380428908753e-01,1.092839763432199440e+01,3.342652107667920362e-03,3.779689041113138415e-01,-4.000000000000000327e-05,-1.000000011222356822e+00,0.000000000000000000e+00 +8.227411819408973770e+01,5.157729965480982628e+02,1.318984645017200474e-01,1.092874349372129394e+01,3.342506122266382645e-03,3.770538568695464554e-01,-4.000000000000000327e-05,-1.000000008510559146e+00,0.000000000000000000e+00 +8.227503321236295619e+01,5.157829964922366344e+02,1.319318895007033365e-01,1.092908850489031458e+01,3.342360136864844927e-03,3.761388385885472974e-01,-4.000000000000000327e-05,-1.000000009457510108e+00,0.000000000000000000e+00 +8.227594820175072243e+01,5.157929964363797808e+02,1.319653130398407703e-01,1.092943266793595214e+01,3.342214151463307210e-03,3.752238491921213726e-01,-4.000000000000000327e-05,-1.000000007874229269e+00,0.000000000000000000e+00 +8.227686316232588126e+01,5.158029963805278157e+02,1.319987351191323488e-01,1.092977598296482178e+01,3.342068166061769492e-03,3.743088886097592494e-01,-4.000000000000000327e-05,-1.000000008179344757e+00,0.000000000000000000e+00 +8.227777809416122068e+01,5.158129963246807392e+02,1.320321557385780720e-01,1.093011845008326333e+01,3.341922180660231775e-03,3.733939567669310455e-01,-4.000000000000000327e-05,-1.000000010548591778e+00,0.000000000000000000e+00 +8.227869299732952868e+01,5.158229962688385513e+02,1.320655748981779121e-01,1.093046006939733772e+01,3.341776195258694057e-03,3.724790535889687115e-01,-4.000000000000000327e-05,-1.000000008789263539e+00,0.000000000000000000e+00 +8.227960787190356484e+01,5.158329962130012518e+02,1.320989925979318969e-01,1.093080084101282701e+01,3.341630209857156340e-03,3.715641790068923145e-01,-4.000000000000000327e-05,-1.000000009442029381e+00,0.000000000000000000e+00 +8.228052271795606032e+01,5.158429961571688409e+02,1.321324088378400263e-01,1.093114076503523968e+01,3.341484224455618622e-03,3.706493329457601904e-01,-4.000000000000000327e-05,-1.000000008435494081e+00,0.000000000000000000e+00 +8.228143753555973205e+01,5.158529961013413185e+02,1.321658236179023005e-01,1.093147984156980534e+01,3.341338239054080905e-03,3.697345153343777335e-01,-4.000000000000000327e-05,-1.000000010187511945e+00,0.000000000000000000e+00 +8.228235232478725436e+01,5.158629960455186847e+02,1.321992369381186916e-01,1.093181807072147826e+01,3.341192253652543187e-03,3.688197260975309977e-01,-4.000000000000000327e-05,-1.000000006379924811e+00,0.000000000000000000e+00 +8.228326708571131576e+01,5.158729959897009394e+02,1.322326487984892274e-01,1.093215545259493382e+01,3.341046268251005470e-03,3.679049651676375432e-01,-4.000000000000000327e-05,-1.000000009921200084e+00,0.000000000000000000e+00 +8.228418181840454793e+01,5.158829959338880826e+02,1.322660591990138801e-01,1.093249198729457561e+01,3.340900282849467752e-03,3.669902324653287473e-01,-4.000000000000000327e-05,-1.000000010368772729e+00,0.000000000000000000e+00 +8.228509652293958254e+01,5.158929958780801144e+02,1.322994681396926775e-01,1.093282767492452479e+01,3.340754297447930034e-03,3.660755279208104951e-01,-4.000000000000000327e-05,-1.000000007892994702e+00,0.000000000000000000e+00 +8.228601119938902286e+01,5.159029958222769210e+02,1.323328756205255918e-01,1.093316251558862895e+01,3.340608312046392317e-03,3.651608514641545566e-01,-4.000000000000000327e-05,-1.000000009033720438e+00,0.000000000000000000e+00 +8.228692584782544373e+01,5.159129957664786161e+02,1.323662816415126509e-01,1.093349650939046214e+01,3.340462326644854599e-03,3.642462030194726919e-01,-4.000000000000000327e-05,-1.000000009715041438e+00,0.000000000000000000e+00 +8.228784046832140575e+01,5.159229957106851998e+02,1.323996862026538268e-01,1.093382965643331950e+01,3.340316341243316882e-03,3.633315825146267164e-01,-4.000000000000000327e-05,-1.000000007982258410e+00,0.000000000000000000e+00 +8.228875506094944114e+01,5.159329956548966720e+02,1.324330893039491475e-01,1.093416195682022085e+01,3.340170355841779164e-03,3.624169898792879430e-01,-4.000000000000000327e-05,-1.000000010375491577e+00,0.000000000000000000e+00 +8.228966962578206790e+01,5.159429955991130328e+02,1.324664909453985850e-01,1.093449341065391245e+01,3.340024370440241447e-03,3.615024250371678405e-01,-4.000000000000000327e-05,-1.000000008568551646e+00,0.000000000000000000e+00 +8.229058416289178979e+01,5.159529955433342820e+02,1.324998911270021673e-01,1.093482401803686166e+01,3.339878385038703729e-03,3.605878879196144915e-01,-4.000000000000000327e-05,-1.000000006976416556e+00,0.000000000000000000e+00 +8.229149867235106797e+01,5.159629954875604199e+02,1.325332898487598665e-01,1.093515377907126407e+01,3.339732399637166012e-03,3.596733784539596912e-01,-4.000000000000000327e-05,-1.000000010015504426e+00,0.000000000000000000e+00 +8.229241315423234937e+01,5.159729954317914462e+02,1.325666871106716826e-01,1.093548269385903993e+01,3.339586414235628294e-03,3.587588965635180593e-01,-4.000000000000000327e-05,-1.000000011480630002e+00,0.000000000000000000e+00 +8.229332760860806673e+01,5.159829953760273611e+02,1.326000829127376435e-01,1.093581076250183060e+01,3.339440428834090577e-03,3.578444421773004369e-01,-4.000000000000000327e-05,-1.000000005165006201e+00,0.000000000000000000e+00 +8.229424203555062434e+01,5.159929953202680508e+02,1.326334772549577212e-01,1.093613798510100388e+01,3.339294443432552859e-03,3.569300152300146078e-01,-4.000000000000000327e-05,-1.000000012478516442e+00,0.000000000000000000e+00 +8.229515643513241230e+01,5.160029952645136291e+02,1.326668701373319159e-01,1.093646436175765935e+01,3.339148458031015142e-03,3.560156156368118885e-01,-4.000000000000000327e-05,-1.000000005969070571e+00,0.000000000000000000e+00 +8.229607080742579228e+01,5.160129952087640959e+02,1.327002615598602275e-01,1.093678989257261058e+01,3.339002472629477424e-03,3.551012433379674427e-01,-4.000000000000000327e-05,-1.000000011296530600e+00,0.000000000000000000e+00 +8.229698515250311175e+01,5.160229951530194512e+02,1.327336515225426838e-01,1.093711457764640826e+01,3.338856487227939707e-03,3.541868982503145746e-01,-4.000000000000000327e-05,-1.000000007378786027e+00,0.000000000000000000e+00 +8.229789947043668974e+01,5.160329950972796951e+02,1.327670400253792571e-01,1.093743841707931885e+01,3.338710501826401989e-03,3.532725803099844852e-01,-4.000000000000000327e-05,-1.000000009253474209e+00,0.000000000000000000e+00 +8.229881376129883108e+01,5.160429950415448275e+02,1.328004270683699473e-01,1.093776141097134236e+01,3.338564516424864272e-03,3.523582894393799680e-01,-4.000000000000000327e-05,-1.000000008584962519e+00,0.000000000000000000e+00 +8.229972802516181218e+01,5.160529949858148484e+02,1.328338126515147544e-01,1.093808355942219990e+01,3.338418531023326554e-03,3.514440255685463144e-01,-4.000000000000000327e-05,-1.000000009786553790e+00,0.000000000000000000e+00 +8.230064226209789524e+01,5.160629949300897579e+02,1.328671967748136784e-01,1.093840486253134081e+01,3.338272545621788837e-03,3.505297886235148042e-01,-4.000000000000000327e-05,-1.000000008770672411e+00,0.000000000000000000e+00 +8.230155647217931403e+01,5.160729948743694422e+02,1.329005794382667194e-01,1.093872532039793910e+01,3.338126560220251119e-03,3.496155785340747113e-01,-4.000000000000000327e-05,-1.000000009950172020e+00,0.000000000000000000e+00 +8.230247065547828811e+01,5.160829948186540150e+02,1.329339606418738773e-01,1.093904493312089699e+01,3.337980574818713402e-03,3.487013952260018534e-01,-4.000000000000000327e-05,-1.000000007110401157e+00,0.000000000000000000e+00 +8.230338481206702284e+01,5.160929947629434764e+02,1.329673403856351521e-01,1.093936370079884135e+01,3.337834589417175684e-03,3.477872386307742092e-01,-4.000000000000000327e-05,-1.000000011041047632e+00,0.000000000000000000e+00 +8.230429894201768093e+01,5.161029947072378263e+02,1.330007186695505439e-01,1.093968162353012907e+01,3.337688604015637966e-03,3.468731086700270194e-01,-4.000000000000000327e-05,-1.000000007022671333e+00,0.000000000000000000e+00 +8.230521304540241090e+01,5.161129946515370648e+02,1.330340954936200526e-01,1.093999870141283814e+01,3.337542618614100249e-03,3.459590052788718562e-01,-4.000000000000000327e-05,-1.000000010096765424e+00,0.000000000000000000e+00 +8.230612712229336125e+01,5.161229945958411918e+02,1.330674708578436782e-01,1.094031493454478010e+01,3.337396633212562531e-03,3.450449283786912180e-01,-4.000000000000000327e-05,-1.000000007667422253e+00,0.000000000000000000e+00 +8.230704117276263787e+01,5.161329945401502073e+02,1.331008447622214208e-01,1.094063032302348759e+01,3.337250647811024814e-03,3.441308779024020437e-01,-4.000000000000000327e-05,-1.000000010524767946e+00,0.000000000000000000e+00 +8.230795519688234663e+01,5.161429944844639977e+02,1.331342172067532803e-01,1.094094486694622503e+01,3.337104662409487096e-03,3.432168537730789226e-01,-4.000000000000000327e-05,-1.000000008196552548e+00,0.000000000000000000e+00 +8.230886919472455077e+01,5.161529944287826766e+02,1.331675881914392567e-01,1.094125856640997974e+01,3.336958677007949379e-03,3.423028559233889379e-01,-4.000000000000000327e-05,-1.000000009346622365e+00,0.000000000000000000e+00 +8.230978316636129932e+01,5.161629943731062440e+02,1.332009577162793501e-01,1.094157142151147077e+01,3.336812691606411661e-03,3.413888842781006572e-01,-4.000000000000000327e-05,-1.000000009880415597e+00,0.000000000000000000e+00 +8.231069711186462712e+01,5.161729943174347000e+02,1.332343257812735604e-01,1.094188343234714189e+01,3.336666706204873944e-03,3.404749387657454718e-01,-4.000000000000000327e-05,-1.000000007828541815e+00,0.000000000000000000e+00 +8.231161103130654055e+01,5.161829942617680445e+02,1.332676923864218876e-01,1.094219459901316505e+01,3.336520720803336226e-03,3.395610193166748725e-01,-4.000000000000000327e-05,-1.000000007601475671e+00,0.000000000000000000e+00 +8.231252492475903182e+01,5.161929942061062775e+02,1.333010575317243041e-01,1.094250492160544219e+01,3.336374735401798509e-03,3.386471258572296694e-01,-4.000000000000000327e-05,-1.000000011483452189e+00,0.000000000000000000e+00 +8.231343879229407889e+01,5.162029941504493991e+02,1.333344212171808374e-01,1.094281440021960172e+01,3.336228750000260791e-03,3.377332583116834930e-01,-4.000000000000000327e-05,-1.000000006868398295e+00,0.000000000000000000e+00 +8.231435263398363134e+01,5.162129940947972955e+02,1.333677834427914877e-01,1.094312303495099670e+01,3.336082764598723074e-03,3.368194166158503533e-01,-4.000000000000000327e-05,-1.000000008801304130e+00,0.000000000000000000e+00 +8.231526644989962449e+01,5.162229940391500804e+02,1.334011442085562549e-01,1.094343082589471550e+01,3.335936779197185356e-03,3.359056006918152981e-01,-4.000000000000000327e-05,-1.000000011056580318e+00,0.000000000000000000e+00 +8.231618024011396528e+01,5.162329939835077539e+02,1.334345035144751113e-01,1.094373777314556939e+01,3.335790793795647639e-03,3.349918104673727526e-01,-4.000000000000000327e-05,-1.000000007406594005e+00,0.000000000000000000e+00 +8.231709400469854643e+01,5.162429939278703159e+02,1.334678613605480846e-01,1.094404387679809787e+01,3.335644808394109921e-03,3.340780458760276850e-01,-4.000000000000000327e-05,-1.000000010770352166e+00,0.000000000000000000e+00 +8.231800774372523222e+01,5.162529938722377665e+02,1.335012177467751471e-01,1.094434913694657396e+01,3.335498822992572204e-03,3.331643068394998797e-01,-4.000000000000000327e-05,-1.000000006408641617e+00,0.000000000000000000e+00 +8.231892145726587273e+01,5.162629938166101056e+02,1.335345726731563265e-01,1.094465355368499360e+01,3.335352837591034486e-03,3.322505932929968875e-01,-4.000000000000000327e-05,-1.000000009368551490e+00,0.000000000000000000e+00 +8.231983514539231805e+01,5.162729937609872195e+02,1.335679261396916229e-01,1.094495712710708801e+01,3.335206852189496769e-03,3.313369051579970748e-01,-4.000000000000000327e-05,-1.000000011292619062e+00,0.000000000000000000e+00 +8.232074880817636142e+01,5.162829937053692220e+02,1.336012781463810084e-01,1.094525985730631135e+01,3.335060866787959051e-03,3.304232423636349614e-01,-4.000000000000000327e-05,-1.000000005948568083e+00,0.000000000000000000e+00 +8.232166244568979607e+01,5.162929936497561130e+02,1.336346286932245109e-01,1.094556174437584772e+01,3.334914881386421334e-03,3.295096048447586634e-01,-4.000000000000000327e-05,-1.000000010512951176e+00,0.000000000000000000e+00 +8.232257605800440103e+01,5.163029935941478925e+02,1.336679777802221025e-01,1.094586278840861659e+01,3.334768895984883616e-03,3.285959925205426124e-01,-4.000000000000000327e-05,-1.000000008112417849e+00,0.000000000000000000e+00 +8.232348964519194112e+01,5.163129935385445606e+02,1.337013254073738111e-01,1.094616298949725852e+01,3.334622910583345898e-03,3.276824053255967817e-01,-4.000000000000000327e-05,-1.000000009538978940e+00,0.000000000000000000e+00 +8.232440320732413852e+01,5.163229934829461172e+02,1.337346715746796089e-01,1.094646234773414939e+01,3.334476925181808181e-03,3.267688431846909047e-01,-4.000000000000000327e-05,-1.000000010686899587e+00,0.000000000000000000e+00 +8.232531674447270120e+01,5.163329934273524486e+02,1.337680162821395236e-01,1.094676086321139152e+01,3.334330939780270463e-03,3.258553060263651435e-01,-4.000000000000000327e-05,-1.000000007448835992e+00,0.000000000000000000e+00 +8.232623025670933714e+01,5.163429933717636686e+02,1.338013595297535274e-01,1.094705853602081724e+01,3.334184954378732746e-03,3.249417937829310876e-01,-4.000000000000000327e-05,-1.000000008488746817e+00,0.000000000000000000e+00 +8.232714374410571168e+01,5.163529933161797771e+02,1.338347013175216205e-01,1.094735536625399241e+01,3.334038968977195028e-03,3.240283063788048645e-01,-4.000000000000000327e-05,-1.000000007570109872e+00,0.000000000000000000e+00 +8.232805720673347594e+01,5.163629932606007742e+02,1.338680416454438304e-01,1.094765135400220935e+01,3.333892983575657311e-03,3.231148437441189736e-01,-4.000000000000000327e-05,-1.000000011228287855e+00,0.000000000000000000e+00 +8.232897064466428105e+01,5.163729932050266598e+02,1.339013805135201296e-01,1.094794649935649211e+01,3.333746998174119593e-03,3.222014058030552852e-01,-4.000000000000000327e-05,-1.000000008966713816e+00,0.000000000000000000e+00 +8.232988405796974973e+01,5.163829931494573202e+02,1.339347179217505179e-01,1.094824080240759123e+01,3.333601012772581876e-03,3.212879924894028183e-01,-4.000000000000000327e-05,-1.000000007319986617e+00,0.000000000000000000e+00 +8.233079744672146205e+01,5.163929930938928692e+02,1.339680538701350232e-01,1.094853426324599255e+01,3.333455027371044158e-03,3.203746037310005734e-01,-4.000000000000000327e-05,-1.000000010694098274e+00,0.000000000000000000e+00 +8.233171081099101229e+01,5.164029930383333067e+02,1.340013883586736176e-01,1.094882688196191189e+01,3.333309041969506441e-03,3.194612394516823106e-01,-4.000000000000000327e-05,-1.000000006460230351e+00,0.000000000000000000e+00 +8.233262415084995212e+01,5.164129929827786327e+02,1.340347213873663013e-01,1.094911865864529155e+01,3.333163056567968723e-03,3.185478995868354923e-01,-4.000000000000000327e-05,-1.000000011799983657e+00,0.000000000000000000e+00 +8.233353746636983317e+01,5.164229929272288473e+02,1.340680529562130741e-01,1.094940959338581088e+01,3.333017071166431006e-03,3.176345840561736744e-01,-4.000000000000000327e-05,-1.000000007694027637e+00,0.000000000000000000e+00 +8.233445075762217868e+01,5.164329928716838367e+02,1.341013830652139360e-01,1.094969968627287216e+01,3.332871085764893288e-03,3.167212927968001135e-01,-4.000000000000000327e-05,-1.000000007064685725e+00,0.000000000000000000e+00 +8.233536402467849769e+01,5.164429928161437147e+02,1.341347117143688872e-01,1.094998893739561652e+01,3.332725100363355571e-03,3.158080257340346031e-01,-4.000000000000000327e-05,-1.000000012187879816e+00,0.000000000000000000e+00 +8.233627726761027077e+01,5.164529927606084811e+02,1.341680389036779553e-01,1.095027734684291332e+01,3.332579114961817853e-03,3.148947827911374175e-01,-4.000000000000000327e-05,-1.000000006168817457e+00,0.000000000000000000e+00 +8.233719048648896432e+01,5.164629927050781362e+02,1.342013646331411125e-01,1.095056491470335835e+01,3.332433129560280136e-03,3.139815639068165298e-01,-4.000000000000000327e-05,-1.000000010451157495e+00,0.000000000000000000e+00 +8.233810368138601632e+01,5.164729926495526797e+02,1.342346889027583590e-01,1.095085164106528808e+01,3.332287144158742418e-03,3.130683690002154518e-01,-4.000000000000000327e-05,-1.000000008138477448e+00,0.000000000000000000e+00 +8.233901685237287893e+01,5.164829925940319981e+02,1.342680117125296946e-01,1.095113752601676183e+01,3.332141158757204701e-03,3.121551980059262821e-01,-4.000000000000000327e-05,-1.000000010024353125e+00,0.000000000000000000e+00 +8.233992999952094749e+01,5.164929925385162051e+02,1.343013330624551194e-01,1.095142256964557603e+01,3.331995173355666983e-03,3.112420508487029891e-01,-4.000000000000000327e-05,-1.000000007730712515e+00,0.000000000000000000e+00 +8.234084312290161733e+01,5.165029924830053005e+02,1.343346529525346333e-01,1.095170677203925536e+01,3.331849187954129266e-03,3.103289274609684623e-01,-4.000000000000000327e-05,-1.000000009921346855e+00,0.000000000000000000e+00 +8.234175622258626959e+01,5.165129924274992845e+02,1.343679713827682365e-01,1.095199013328505977e+01,3.331703202552591548e-03,3.094158277672527380e-01,-4.000000000000000327e-05,-1.000000008216183733e+00,0.000000000000000000e+00 +8.234266929864627116e+01,5.165229923719981571e+02,1.344012883531559288e-01,1.095227265346997747e+01,3.331557217151053830e-03,3.085027516997561059e-01,-4.000000000000000327e-05,-1.000000009148169777e+00,0.000000000000000000e+00 +8.234358235115294633e+01,5.165329923165018045e+02,1.344346038636977103e-01,1.095255433268073197e+01,3.331411231749516113e-03,3.075896991847318906e-01,-4.000000000000000327e-05,-1.000000008597133450e+00,0.000000000000000000e+00 +8.234449538017761938e+01,5.165429922610103404e+02,1.344679179143935532e-01,1.095283517100377679e+01,3.331265246347978395e-03,3.066766701522136152e-01,-4.000000000000000327e-05,-1.000000008834184717e+00,0.000000000000000000e+00 +8.234540838579158617e+01,5.165529922055237648e+02,1.345012305052434853e-01,1.095311516852529898e+01,3.331119260946440678e-03,3.057636645301792799e-01,-4.000000000000000327e-05,-1.000000007868382834e+00,0.000000000000000000e+00 +8.234632136806614255e+01,5.165629921500420778e+02,1.345345416362475066e-01,1.095339432533121737e+01,3.330973275544902960e-03,3.048506822484426948e-01,-4.000000000000000327e-05,-1.000000012232874713e+00,0.000000000000000000e+00 +8.234723432707254176e+01,5.165729920945651656e+02,1.345678513074056171e-01,1.095367264150718434e+01,3.330827290143365243e-03,3.039377232308710930e-01,-4.000000000000000327e-05,-1.000000005016786764e+00,0.000000000000000000e+00 +8.234814726288205122e+01,5.165829920390931420e+02,1.346011595187178167e-01,1.095395011713858047e+01,3.330681304741827525e-03,3.030247874167885658e-01,-4.000000000000000327e-05,-1.000000011934439881e+00,0.000000000000000000e+00 +8.234906017556588154e+01,5.165929919836260069e+02,1.346344662701841055e-01,1.095422675231052878e+01,3.330535319340289808e-03,3.021118747220613576e-01,-4.000000000000000327e-05,-1.000000007547575898e+00,0.000000000000000000e+00 +8.234997306519525750e+01,5.166029919281637603e+02,1.346677715618044557e-01,1.095450254710787341e+01,3.330389333938752090e-03,3.011989850857968443e-01,-4.000000000000000327e-05,-1.000000009045339810e+00,0.000000000000000000e+00 +8.235088593184137551e+01,5.166129918727064023e+02,1.347010753935788951e-01,1.095477750161520092e+01,3.330243348537214373e-03,3.002861184314279952e-01,-4.000000000000000327e-05,-1.000000008039213295e+00,0.000000000000000000e+00 +8.235179877557540351e+01,5.166229918172538191e+02,1.347343777655074237e-01,1.095505161591682608e+01,3.330097363135676655e-03,2.993732746900633068e-01,-4.000000000000000327e-05,-1.000000008928997763e+00,0.000000000000000000e+00 +8.235271159646850947e+01,5.166329917618061245e+02,1.347676786775900137e-01,1.095532489009679900e+01,3.329951377734138938e-03,2.984604537888125297e-01,-4.000000000000000327e-05,-1.000000009719887561e+00,0.000000000000000000e+00 +8.235362439459181871e+01,5.166429917063633184e+02,1.348009781298266929e-01,1.095559732423890154e+01,3.329805392332601220e-03,2.975476556566239994e-01,-4.000000000000000327e-05,-1.000000010547372753e+00,0.000000000000000000e+00 +8.235453717001647078e+01,5.166529916509254008e+02,1.348342761222174335e-01,1.095586891842664912e+01,3.329659406931063503e-03,2.966348802223399139e-01,-4.000000000000000327e-05,-1.000000005150558424e+00,0.000000000000000000e+00 +8.235544992281357679e+01,5.166629915954922581e+02,1.348675726547622633e-01,1.095613967274329070e+01,3.329513421529525785e-03,2.957221274205346084e-01,-4.000000000000000327e-05,-1.000000012854272979e+00,0.000000000000000000e+00 +8.235636265305421944e+01,5.166729915400640039e+02,1.349008677274611823e-01,1.095640958727181413e+01,3.329367436127988068e-03,2.948093971681610692e-01,-4.000000000000000327e-05,-1.000000006073890280e+00,0.000000000000000000e+00 +8.235727536080946720e+01,5.166829914846406382e+02,1.349341613403141626e-01,1.095667866209493013e+01,3.329221450726450350e-03,2.938966894073672398e-01,-4.000000000000000327e-05,-1.000000008398610474e+00,0.000000000000000000e+00 +8.235818804615037436e+01,5.166929914292221611e+02,1.349674534933212322e-01,1.095694689729509541e+01,3.329075465324912633e-03,2.929840040587878836e-01,-4.000000000000000327e-05,-1.000000011433598734e+00,0.000000000000000000e+00 +8.235910070914799519e+01,5.167029913738084588e+02,1.350007441864823632e-01,1.095721429295449312e+01,3.328929479923374915e-03,2.920713410507372876e-01,-4.000000000000000327e-05,-1.000000006780942252e+00,0.000000000000000000e+00 +8.236001334987332712e+01,5.167129913183996450e+02,1.350340334197975833e-01,1.095748084915503995e+01,3.328783494521837198e-03,2.911587003192112610e-01,-4.000000000000000327e-05,-1.000000009502163945e+00,0.000000000000000000e+00 +8.236092596839739599e+01,5.167229912629957198e+02,1.350673211932668649e-01,1.095774656597839325e+01,3.328637509120299480e-03,2.902460817864768172e-01,-4.000000000000000327e-05,-1.000000009065955764e+00,0.000000000000000000e+00 +8.236183856479117082e+01,5.167329912075966831e+02,1.351006075068902079e-01,1.095801144350593859e+01,3.328491523718761762e-03,2.893334853844293786e-01,-4.000000000000000327e-05,-1.000000009870082529e+00,0.000000000000000000e+00 +8.236275113912562063e+01,5.167429911522024213e+02,1.351338923606676401e-01,1.095827548181879862e+01,3.328345538317224045e-03,2.884209110409678978e-01,-4.000000000000000327e-05,-1.000000007779653144e+00,0.000000000000000000e+00 +8.236366369147171440e+01,5.167529910968130480e+02,1.351671757545991337e-01,1.095853868099782957e+01,3.328199552915686327e-03,2.875083586877816844e-01,-4.000000000000000327e-05,-1.000000007191749196e+00,0.000000000000000000e+00 +8.236457622190036432e+01,5.167629910414285632e+02,1.352004576886846887e-01,1.095880104112362474e+01,3.328053567514148610e-03,2.865958282525642997e-01,-4.000000000000000327e-05,-1.000000010370501791e+00,0.000000000000000000e+00 +8.236548873048251096e+01,5.167729909860489670e+02,1.352337381629243329e-01,1.095906256227651099e+01,3.327907582112610892e-03,2.856833196609602221e-01,-4.000000000000000327e-05,-1.000000008912956151e+00,0.000000000000000000e+00 +8.236640121728903807e+01,5.167829909306741456e+02,1.352670171773180385e-01,1.095932324453654694e+01,3.327761596711073175e-03,2.847708328462985605e-01,-4.000000000000000327e-05,-1.000000009348577690e+00,0.000000000000000000e+00 +8.236731368239084361e+01,5.167929908753042128e+02,1.353002947318658056e-01,1.095958308798353009e+01,3.327615611309535457e-03,2.838583677359669544e-01,-4.000000000000000327e-05,-1.000000009673232215e+00,0.000000000000000000e+00 +8.236822612585878289e+01,5.168029908199391684e+02,1.353335708265676340e-01,1.095984209269699150e+01,3.327469625907997740e-03,2.829459242591985113e-01,-4.000000000000000327e-05,-1.000000005748105991e+00,0.000000000000000000e+00 +8.236913854776371124e+01,5.168129907645788990e+02,1.353668454614235517e-01,1.096010025875619753e+01,3.327323640506460022e-03,2.820335023490193049e-01,-4.000000000000000327e-05,-1.000000012637838109e+00,0.000000000000000000e+00 +8.237005094817646977e+01,5.168229907092235180e+02,1.354001186364335307e-01,1.096035758624015344e+01,3.327177655104922305e-03,2.811211019247267240e-01,-4.000000000000000327e-05,-1.000000004864697090e+00,0.000000000000000000e+00 +8.237096332716787117e+01,5.168329906538730256e+02,1.354333903515975712e-01,1.096061407522759090e+01,3.327031669703384587e-03,2.802087229288807158e-01,-4.000000000000000327e-05,-1.000000012430344754e+00,0.000000000000000000e+00 +8.237187568480872812e+01,5.168429905985274218e+02,1.354666606069156731e-01,1.096086972579698937e+01,3.326885684301846870e-03,2.792963652766844995e-01,-4.000000000000000327e-05,-1.000000005586306973e+00,0.000000000000000000e+00 +8.237278802116981069e+01,5.168529905431865927e+02,1.354999294023878365e-01,1.096112453802655118e+01,3.326739698900309152e-03,2.783840289104992927e-01,-4.000000000000000327e-05,-1.000000012201718746e+00,0.000000000000000000e+00 +8.237370033632190314e+01,5.168629904878506522e+02,1.355331967380140612e-01,1.096137851199422641e+01,3.326593713498771435e-03,2.774717137472763051e-01,-4.000000000000000327e-05,-1.000000006793054563e+00,0.000000000000000000e+00 +8.237461263033574710e+01,5.168729904325196003e+02,1.355664626137943474e-01,1.096163164777768984e+01,3.326447728097233717e-03,2.765594197272323584e-01,-4.000000000000000327e-05,-1.000000008693694209e+00,0.000000000000000000e+00 +8.237552490328208421e+01,5.168829903771933232e+02,1.355997270297286950e-01,1.096188394545436218e+01,3.326301742695696000e-03,2.756471467729624258e-01,-4.000000000000000327e-05,-1.000000009492108877e+00,0.000000000000000000e+00 +8.237643715523164190e+01,5.168929903218719346e+02,1.356329899858171040e-01,1.096213540510139417e+01,3.326155757294158282e-03,2.747348948147515513e-01,-4.000000000000000327e-05,-1.000000009312687954e+00,0.000000000000000000e+00 +8.237734938625510495e+01,5.169029902665554346e+02,1.356662514820595744e-01,1.096238602679567364e+01,3.326009771892620565e-03,2.738226637827873566e-01,-4.000000000000000327e-05,-1.000000006144969866e+00,0.000000000000000000e+00 +8.237826159642317236e+01,5.169129902112438231e+02,1.356995115184561063e-01,1.096263581061382553e+01,3.325863786491082847e-03,2.729104536091074285e-01,-4.000000000000000327e-05,-1.000000010786430860e+00,0.000000000000000000e+00 +8.237917378580652894e+01,5.169229901559369864e+02,1.357327700950066995e-01,1.096288475663221362e+01,3.325717801089545130e-03,2.719982642159158304e-01,-4.000000000000000327e-05,-1.000000010552384966e+00,0.000000000000000000e+00 +8.238008595447581683e+01,5.169329901006350383e+02,1.357660272117113542e-01,1.096313286492693173e+01,3.325571815688007412e-03,2.710860955370036351e-01,-4.000000000000000327e-05,-1.000000005564781747e+00,0.000000000000000000e+00 +8.238099810250167820e+01,5.169429900453379787e+02,1.357992828685700704e-01,1.096338013557381430e+01,3.325425830286469694e-03,2.701739475060662699e-01,-4.000000000000000327e-05,-1.000000010891272328e+00,0.000000000000000000e+00 +8.238191022995474100e+01,5.169529899900456940e+02,1.358325370655828479e-01,1.096362656864843643e+01,3.325279844884931977e-03,2.692618200430710873e-01,-4.000000000000000327e-05,-1.000000007438852645e+00,0.000000000000000000e+00 +8.238282233690560474e+01,5.169629899347582977e+02,1.358657898027496591e-01,1.096387216422610145e+01,3.325133859483394259e-03,2.683497130854167190e-01,-4.000000000000000327e-05,-1.000000010274787021e+00,0.000000000000000000e+00 +8.238373442342486896e+01,5.169729898794757901e+02,1.358990410800705317e-01,1.096411692238185687e+01,3.324987874081856542e-03,2.674376265567743327e-01,-4.000000000000000327e-05,-1.000000008844395660e+00,0.000000000000000000e+00 +8.238464648958311898e+01,5.169829898241981709e+02,1.359322908975454658e-01,1.096436084319048199e+01,3.324841888680318824e-03,2.665255603904577164e-01,-4.000000000000000327e-05,-1.000000007538715652e+00,0.000000000000000000e+00 +8.238555853545091168e+01,5.169929897689253266e+02,1.359655392551744613e-01,1.096460392672649675e+01,3.324695903278781107e-03,2.656135145157911825e-01,-4.000000000000000327e-05,-1.000000008613699531e+00,0.000000000000000000e+00 +8.238647056109878974e+01,5.170029897136573709e+02,1.359987861529574904e-01,1.096484617306415821e+01,3.324549917877243389e-03,2.647014888600571214e-01,-4.000000000000000327e-05,-1.000000010053964772e+00,0.000000000000000000e+00 +8.238738256659728165e+01,5.170129896583943037e+02,1.360320315908945810e-01,1.096508758227745872e+01,3.324403932475705672e-03,2.637894833523916072e-01,-4.000000000000000327e-05,-1.000000007707406491e+00,0.000000000000000000e+00 +8.238829455201691587e+01,5.170229896031360113e+02,1.360652755689857329e-01,1.096532815444012776e+01,3.324257947074167954e-03,2.628774979257328392e-01,-4.000000000000000327e-05,-1.000000010236107739e+00,0.000000000000000000e+00 +8.238920651742817824e+01,5.170329895478826074e+02,1.360985180872309186e-01,1.096556788962563544e+01,3.324111961672630237e-03,2.619655325051346573e-01,-4.000000000000000327e-05,-1.000000007079320685e+00,0.000000000000000000e+00 +8.239011846290155461e+01,5.170429894926340921e+02,1.361317591456301657e-01,1.096580678790718544e+01,3.323965976271092519e-03,2.610535870252973512e-01,-4.000000000000000327e-05,-1.000000011170924630e+00,0.000000000000000000e+00 +8.239103038850751659e+01,5.170529894373903517e+02,1.361649987441834742e-01,1.096604484935772383e+01,3.323819990869554802e-03,2.601416614091414115e-01,-4.000000000000000327e-05,-1.000000005540403247e+00,0.000000000000000000e+00 +8.239194229431652161e+01,5.170629893821514997e+02,1.361982368828908163e-01,1.096628207404992850e+01,3.323674005468017084e-03,2.592297555950784926e-01,-4.000000000000000327e-05,-1.000000011665998834e+00,0.000000000000000000e+00 +8.239285418039901288e+01,5.170729893269175363e+02,1.362314735617522199e-01,1.096651846205622327e+01,3.323528020066479367e-03,2.583178695019491267e-01,-4.000000000000000327e-05,-1.000000006166525512e+00,0.000000000000000000e+00 +8.239376604682540517e+01,5.170829892716883478e+02,1.362647087807676571e-01,1.096675401344876022e+01,3.323382034664941649e-03,2.574060030699301671e-01,-4.000000000000000327e-05,-1.000000010521091109e+00,0.000000000000000000e+00 +8.239467789366611328e+01,5.170929892164640478e+02,1.362979425399371558e-01,1.096698872829943916e+01,3.323236049263403932e-03,2.564941562196271785e-01,-4.000000000000000327e-05,-1.000000009891383268e+00,0.000000000000000000e+00 +8.239558972099152356e+01,5.171029891612446363e+02,1.363311748392606881e-01,1.096722260667988991e+01,3.323090063861866214e-03,2.555823288851912789e-01,-4.000000000000000327e-05,-1.000000006528810603e+00,0.000000000000000000e+00 +8.239650152887202239e+01,5.171129891060299997e+02,1.363644056787382819e-01,1.096745564866148470e+01,3.322944078460328497e-03,2.546705209987353835e-01,-4.000000000000000327e-05,-1.000000009094834219e+00,0.000000000000000000e+00 +8.239741331737798191e+01,5.171229890508202516e+02,1.363976350583699093e-01,1.096768785431533644e+01,3.322798093058790779e-03,2.537587324844897130e-01,-4.000000000000000327e-05,-1.000000009157802516e+00,0.000000000000000000e+00 +8.239832508657973165e+01,5.171329889956153920e+02,1.364308629781555704e-01,1.096791922371229155e+01,3.322652107657253061e-03,2.528469632743873818e-01,-4.000000000000000327e-05,-1.000000008968513932e+00,0.000000000000000000e+00 +8.239923683654761533e+01,5.171429889404153073e+02,1.364640894380952929e-01,1.096814975692293714e+01,3.322506122255715344e-03,2.519352132983239678e-01,-4.000000000000000327e-05,-1.000000008640573368e+00,0.000000000000000000e+00 +8.240014856735194826e+01,5.171529888852201111e+02,1.364973144381890491e-01,1.096837945401759917e+01,3.322360136854177626e-03,2.510234824861061753e-01,-4.000000000000000327e-05,-1.000000008287472708e+00,0.000000000000000000e+00 +8.240106027906304575e+01,5.171629888300298035e+02,1.365305379784368389e-01,1.096860831506634248e+01,3.322214151452639909e-03,2.501117707674518909e-01,-4.000000000000000327e-05,-1.000000010159122210e+00,0.000000000000000000e+00 +8.240197197175119470e+01,5.171729887748442707e+02,1.365637600588386902e-01,1.096883634013897080e+01,3.322068166051102191e-03,2.492000780700423801e-01,-4.000000000000000327e-05,-1.000000007956612480e+00,0.000000000000000000e+00 +8.240288364548666777e+01,5.171829887196636264e+02,1.365969806793945751e-01,1.096906352930502493e+01,3.321922180649564474e-03,2.482884043273161367e-01,-4.000000000000000327e-05,-1.000000008203448809e+00,0.000000000000000000e+00 +8.240379530033972344e+01,5.171929886644878707e+02,1.366301998401044937e-01,1.096928988263378812e+01,3.321776195248026756e-03,2.473767494667787337e-01,-4.000000000000000327e-05,-1.000000008874104118e+00,0.000000000000000000e+00 +8.240470693638062016e+01,5.172029886093168898e+02,1.366634175409684460e-01,1.096951540019428073e+01,3.321630209846489039e-03,2.464651134177968661e-01,-4.000000000000000327e-05,-1.000000007942244418e+00,0.000000000000000000e+00 +8.240561855367957378e+01,5.172129885541507974e+02,1.366966337819864319e-01,1.096974008205526196e+01,3.321484224444951321e-03,2.455534961115988790e-01,-4.000000000000000327e-05,-1.000000009793721167e+00,0.000000000000000000e+00 +8.240653015230681433e+01,5.172229884989895936e+02,1.367298485631584792e-01,1.096996392828523170e+01,3.321338239043413604e-03,2.446418974754292208e-01,-4.000000000000000327e-05,-1.000000008126086248e+00,0.000000000000000000e+00 +8.240744173233254344e+01,5.172329884438331646e+02,1.367630618844845602e-01,1.097018693895242691e+01,3.321192253641875886e-03,2.437303174422919549e-01,-4.000000000000000327e-05,-1.000000009461938566e+00,0.000000000000000000e+00 +8.240835329382694852e+01,5.172429883886816242e+02,1.367962737459646749e-01,1.097040911412482700e+01,3.321046268240338169e-03,2.428187559392594175e-01,-4.000000000000000327e-05,-1.000000009635680698e+00,0.000000000000000000e+00 +8.240926483686020276e+01,5.172529883335349723e+02,1.368294841475988233e-01,1.097063045387014846e+01,3.320900282838800451e-03,2.419072128972153957e-01,-4.000000000000000327e-05,-1.000000006617875137e+00,0.000000000000000000e+00 +8.241017636150247938e+01,5.172629882783930952e+02,1.368626930893870053e-01,1.097085095825584844e+01,3.320754297437262734e-03,2.409956882489076024e-01,-4.000000000000000327e-05,-1.000000011206994666e+00,0.000000000000000000e+00 +8.241108786782392315e+01,5.172729882232561067e+02,1.368959005713292210e-01,1.097107062734912653e+01,3.320608312035725016e-03,2.400841819172547520e-01,-4.000000000000000327e-05,-1.000000006407279596e+00,0.000000000000000000e+00 +8.241199935589465042e+01,5.172829881681240067e+02,1.369291065934254703e-01,1.097128946121691584e+01,3.320462326634187299e-03,2.391726938406814051e-01,-4.000000000000000327e-05,-1.000000009430734416e+00,0.000000000000000000e+00 +8.241291082578479177e+01,5.172929881129966816e+02,1.369623111556757533e-01,1.097150745992589727e+01,3.320316341232649581e-03,2.382612239419373279e-01,-4.000000000000000327e-05,-1.000000007555913895e+00,0.000000000000000000e+00 +8.241382227756446355e+01,5.173029880578742450e+02,1.369955142580800700e-01,1.097172462354248523e+01,3.320170355831111864e-03,2.373497721553815831e-01,-4.000000000000000327e-05,-1.000000011581078541e+00,0.000000000000000000e+00 +8.241473371130373948e+01,5.173129880027565832e+02,1.370287159006384203e-01,1.097194095213283838e+01,3.320024370429574146e-03,2.364383384055449011e-01,-4.000000000000000327e-05,-1.000000006643999795e+00,0.000000000000000000e+00 +8.241564512707270751e+01,5.173229879476438100e+02,1.370619160833508043e-01,1.097215644576285065e+01,3.319878385028036429e-03,2.355269226305177765e-01,-4.000000000000000327e-05,-1.000000007819334069e+00,0.000000000000000000e+00 +8.241655652494142714e+01,5.173329878925359253e+02,1.370951148062171943e-01,1.097237110449816377e+01,3.319732399626498711e-03,2.346155247546649336e-01,-4.000000000000000327e-05,-1.000000010936199057e+00,0.000000000000000000e+00 +8.241746790497995789e+01,5.173429878374328155e+02,1.371283120692376178e-01,1.097258492840415478e+01,3.319586414224960993e-03,2.337041447061663502e-01,-4.000000000000000327e-05,-1.000000007545152281e+00,0.000000000000000000e+00 +8.241837926725833086e+01,5.173529877823345942e+02,1.371615078724120751e-01,1.097279791754593958e+01,3.319440428823423276e-03,2.327927824209162222e-01,-4.000000000000000327e-05,-1.000000008443931332e+00,0.000000000000000000e+00 +8.241929061184657712e+01,5.173629877272412614e+02,1.371947022157405660e-01,1.097301007198838008e+01,3.319294443421885558e-03,2.318814378249814956e-01,-4.000000000000000327e-05,-1.000000009459719008e+00,0.000000000000000000e+00 +8.242020193881468515e+01,5.173729876721527035e+02,1.372278950992230906e-01,1.097322139179607525e+01,3.319148458020347841e-03,2.309701108482456466e-01,-4.000000000000000327e-05,-1.000000008557289988e+00,0.000000000000000000e+00 +8.242111324823267182e+01,5.173829876170690341e+02,1.372610865228596211e-01,1.097343187703336476e+01,3.319002472618810123e-03,2.300588014224603239e-01,-4.000000000000000327e-05,-1.000000007978882666e+00,0.000000000000000000e+00 +8.242202454017051139e+01,5.173929875619902532e+02,1.372942764866501852e-01,1.097364152776433066e+01,3.318856487217272406e-03,2.291475094773471333e-01,-4.000000000000000327e-05,-1.000000009966725001e+00,0.000000000000000000e+00 +8.242293581469817809e+01,5.174029875069162472e+02,1.373274649905947831e-01,1.097385034405279569e+01,3.318710501815734688e-03,2.282362349405977486e-01,-4.000000000000000327e-05,-1.000000008205947255e+00,0.000000000000000000e+00 +8.242384707188563198e+01,5.174129874518471297e+02,1.373606520346933868e-01,1.097405832596232145e+01,3.318564516414196971e-03,2.273249777456717302e-01,-4.000000000000000327e-05,-1.000000007076771391e+00,0.000000000000000000e+00 +8.242475831180280466e+01,5.174229873967827871e+02,1.373938376189460242e-01,1.097426547355621373e+01,3.318418531012659253e-03,2.264137378220502372e-01,-4.000000000000000327e-05,-1.000000010959814167e+00,0.000000000000000000e+00 +8.242566953451962775e+01,5.174329873417233330e+02,1.374270217433526953e-01,1.097447178689751901e+01,3.318272545611121536e-03,2.255025150952359170e-01,-4.000000000000000327e-05,-1.000000007120238843e+00,0.000000000000000000e+00 +8.242658074010603286e+01,5.174429872866687674e+02,1.374602044079133722e-01,1.097467726604902083e+01,3.318126560209583818e-03,2.245913095023488459e-01,-4.000000000000000327e-05,-1.000000008494991821e+00,0.000000000000000000e+00 +8.242749192863190899e+01,5.174529872316189767e+02,1.374933856126280829e-01,1.097488191107325051e+01,3.317980574808046101e-03,2.236801209687337699e-01,-4.000000000000000327e-05,-1.000000008766414483e+00,0.000000000000000000e+00 +8.242840310016714511e+01,5.174629871765740745e+02,1.375265653574967994e-01,1.097508572203247645e+01,3.317834589406508383e-03,2.227689494255051805e-01,-4.000000000000000327e-05,-1.000000010174030285e+00,0.000000000000000000e+00 +8.242931425478163021e+01,5.174729871215339472e+02,1.375597436425195497e-01,1.097528869898870951e+01,3.317688604004970666e-03,2.218577948017499135e-01,-4.000000000000000327e-05,-1.000000006398225949e+00,0.000000000000000000e+00 +8.243022539254522485e+01,5.174829870664987084e+02,1.375929204676963058e-01,1.097549084200370118e+01,3.317542618603432948e-03,2.209466570323257995e-01,-4.000000000000000327e-05,-1.000000010376479453e+00,0.000000000000000000e+00 +8.243113651352777538e+01,5.174929870114683581e+02,1.376260958330270956e-01,1.097569215113894892e+01,3.317396633201895231e-03,2.200355360403156435e-01,-4.000000000000000327e-05,-1.000000009369093945e+00,0.000000000000000000e+00 +8.243204761779912815e+01,5.175029869564427827e+02,1.376592697385118913e-01,1.097589262645568553e+01,3.317250647800357513e-03,2.191244317604226222e-01,-4.000000000000000327e-05,-1.000000005613538523e+00,0.000000000000000000e+00 +8.243295870542911530e+01,5.175129869014220958e+02,1.376924421841507207e-01,1.097609226801488980e+01,3.317104662398819796e-03,2.182133441253238659e-01,-4.000000000000000327e-05,-1.000000012047928211e+00,0.000000000000000000e+00 +8.243386977648754055e+01,5.175229868464061838e+02,1.377256131699435560e-01,1.097629107587728470e+01,3.316958676997282078e-03,2.173022730559215077e-01,-4.000000000000000327e-05,-1.000000005229195521e+00,0.000000000000000000e+00 +8.243478083104420762e+01,5.175329867913951603e+02,1.377587826958903972e-01,1.097648905010332676e+01,3.316812691595744361e-03,2.163912184944887240e-01,-4.000000000000000327e-05,-1.000000010935473860e+00,0.000000000000000000e+00 +8.243569186916890601e+01,5.175429867363890253e+02,1.377919507619912720e-01,1.097668619075322560e+01,3.316666706194206643e-03,2.154801803598257459e-01,-4.000000000000000327e-05,-1.000000007861872042e+00,0.000000000000000000e+00 +8.243660289093141103e+01,5.175529866813876652e+02,1.378251173682461528e-01,1.097688249788692261e+01,3.316520720792668925e-03,2.145691585901551568e-01,-4.000000000000000327e-05,-1.000000008945654884e+00,0.000000000000000000e+00 +8.243751389640149796e+01,5.175629866263911936e+02,1.378582825146550395e-01,1.097707797156410869e+01,3.316374735391131208e-03,2.136581531119256527e-01,-4.000000000000000327e-05,-1.000000007861838736e+00,0.000000000000000000e+00 +8.243842488564889948e+01,5.175729865713994968e+02,1.378914462012179598e-01,1.097727261184421366e+01,3.316228749989593490e-03,2.127471638573605328e-01,-4.000000000000000327e-05,-1.000000008986344779e+00,0.000000000000000000e+00 +8.243933585874336245e+01,5.175829865164126886e+02,1.379246084279348861e-01,1.097746641878641150e+01,3.316082764588055773e-03,2.118361907547089973e-01,-4.000000000000000327e-05,-1.000000010273968565e+00,0.000000000000000000e+00 +8.244024681575461955e+01,5.175929864614307689e+02,1.379577691948058182e-01,1.097765939244961686e+01,3.315936779186518055e-03,2.109252337340957462e-01,-4.000000000000000327e-05,-1.000000007537503066e+00,0.000000000000000000e+00 +8.244115775675237501e+01,5.176029864064536241e+02,1.379909285018307563e-01,1.097785153289248683e+01,3.315790793784980338e-03,2.100142927294720296e-01,-4.000000000000000327e-05,-1.000000007293014859e+00,0.000000000000000000e+00 +8.244206868180633307e+01,5.176129863514813678e+02,1.380240863490097003e-01,1.097804284017342447e+01,3.315644808383442620e-03,2.091033676688654475e-01,-4.000000000000000327e-05,-1.000000009634338438e+00,0.000000000000000000e+00 +8.244297959098619799e+01,5.176229862965138864e+02,1.380572427363426502e-01,1.097823331435057348e+01,3.315498822981904903e-03,2.081924584802303801e-01,-4.000000000000000327e-05,-1.000000008232269755e+00,0.000000000000000000e+00 +8.244389048436163137e+01,5.176329862415512935e+02,1.380903976638296338e-01,1.097842295548181824e+01,3.315352837580367185e-03,2.072815650972986423e-01,-4.000000000000000327e-05,-1.000000007461046225e+00,0.000000000000000000e+00 +8.244480136200230902e+01,5.176429861865934754e+02,1.381235511314706232e-01,1.097861176362478908e+01,3.315206852178829468e-03,2.063706874498295041e-01,-4.000000000000000327e-05,-1.000000009554201430e+00,0.000000000000000000e+00 +8.244571222397787835e+01,5.176529861316405459e+02,1.381567031392656186e-01,1.097879973883685878e+01,3.315060866777291750e-03,2.054598254655597978e-01,-4.000000000000000327e-05,-1.000000010321712374e+00,0.000000000000000000e+00 +8.244662307035798676e+01,5.176629860766925049e+02,1.381898536872146199e-01,1.097898688117514077e+01,3.314914881375754033e-03,2.045489790760548765e-01,-4.000000000000000327e-05,-1.000000005572538875e+00,0.000000000000000000e+00 +8.244753390121225323e+01,5.176729860217492387e+02,1.382230027753176271e-01,1.097917319069649267e+01,3.314768895974216315e-03,2.036381482167092249e-01,-4.000000000000000327e-05,-1.000000010385989180e+00,0.000000000000000000e+00 +8.244844471661031093e+01,5.176829859668108611e+02,1.382561504035746403e-01,1.097935866745751987e+01,3.314622910572678598e-03,2.027273328091944160e-01,-4.000000000000000327e-05,-1.000000007723118367e+00,0.000000000000000000e+00 +8.244935551662176465e+01,5.176929859118772583e+02,1.382892965719856593e-01,1.097954331151456309e+01,3.314476925171140880e-03,2.018165327907132933e-01,-4.000000000000000327e-05,-1.000000010521820082e+00,0.000000000000000000e+00 +8.245026630131620493e+01,5.177029858569485441e+02,1.383224412805506842e-01,1.097972712292371256e+01,3.314330939769603163e-03,2.009057480866964229e-01,-4.000000000000000327e-05,-1.000000006023478383e+00,0.000000000000000000e+00 +8.245117707076320812e+01,5.177129858020246047e+02,1.383555845292696873e-01,1.097991010174079740e+01,3.314184954368065445e-03,1.999949786342064273e-01,-4.000000000000000327e-05,-1.000000009307726589e+00,0.000000000000000000e+00 +8.245208782503235057e+01,5.177229857471055539e+02,1.383887263181426963e-01,1.098009224802139627e+01,3.314038968966527728e-03,1.990842243565833503e-01,-4.000000000000000327e-05,-1.000000009756236485e+00,0.000000000000000000e+00 +8.245299856419319440e+01,5.177329856921912778e+02,1.384218666471697112e-01,1.098027356182082492e+01,3.313892983564990010e-03,1.981734851868496572e-01,-4.000000000000000327e-05,-1.000000007457182649e+00,0.000000000000000000e+00 +8.245390928831528754e+01,5.177429856372818904e+02,1.384550055163507321e-01,1.098045404319414509e+01,3.313746998163452293e-03,1.972627610579588686e-01,-4.000000000000000327e-05,-1.000000008923762840e+00,0.000000000000000000e+00 +8.245481999746817792e+01,5.177529855823773914e+02,1.384881429256857588e-01,1.098063369219616447e+01,3.313601012761914575e-03,1.963520518969441853e-01,-4.000000000000000327e-05,-1.000000007818542036e+00,0.000000000000000000e+00 +8.245573069172138503e+01,5.177629855274776673e+02,1.385212788751747914e-01,1.098081250888143146e+01,3.313455027360376857e-03,1.954413576366218208e-01,-4.000000000000000327e-05,-1.000000008512409888e+00,0.000000000000000000e+00 +8.245664137114441417e+01,5.177729854725828318e+02,1.385544133648178022e-01,1.098099049330424037e+01,3.313309041958839140e-03,1.945306782058387196e-01,-4.000000000000000327e-05,-1.000000008950421959e+00,0.000000000000000000e+00 +8.245755203580677062e+01,5.177829854176927711e+02,1.385875463946148189e-01,1.098116764551862801e+01,3.313163056557301422e-03,1.936200135353245422e-01,-4.000000000000000327e-05,-1.000000009219099262e+00,0.000000000000000000e+00 +8.245846268577795968e+01,5.177929853628075989e+02,1.386206779645658416e-01,1.098134396557837533e+01,3.313017071155763705e-03,1.927093635557413642e-01,-4.000000000000000327e-05,-1.000000007262180191e+00,0.000000000000000000e+00 +8.245937332112745821e+01,5.178029853079272016e+02,1.386538080746708423e-01,1.098151945353700754e+01,3.312871085754225987e-03,1.917987281996349214e-01,-4.000000000000000327e-05,-1.000000007449521000e+00,0.000000000000000000e+00 +8.246028394192472888e+01,5.178129852530516928e+02,1.386869367249298490e-01,1.098169410944779578e+01,3.312725100352688270e-03,1.908881073955826790e-01,-4.000000000000000327e-05,-1.000000009866579553e+00,0.000000000000000000e+00 +8.246119454823923434e+01,5.178229851981809588e+02,1.387200639153428616e-01,1.098186793336375366e+01,3.312579114951150552e-03,1.899775010720954338e-01,-4.000000000000000327e-05,-1.000000010313705223e+00,0.000000000000000000e+00 +8.246210514014042303e+01,5.178329851433151134e+02,1.387531896459098524e-01,1.098204092533763720e+01,3.312433129549612835e-03,1.890669091615192476e-01,-4.000000000000000327e-05,-1.000000006732691293e+00,0.000000000000000000e+00 +8.246301571769772920e+01,5.178429850884540429e+02,1.387863139166308490e-01,1.098221308542194841e+01,3.312287144148075117e-03,1.881563315980852025e-01,-4.000000000000000327e-05,-1.000000007776770117e+00,0.000000000000000000e+00 +8.246392628098057287e+01,5.178529850335978608e+02,1.388194367275058239e-01,1.098238441366893703e+01,3.312141158746537400e-03,1.872457683081557855e-01,-4.000000000000000327e-05,-1.000000009245053834e+00,0.000000000000000000e+00 +8.246483683005837406e+01,5.178629849787465673e+02,1.388525580785348046e-01,1.098255491013059348e+01,3.311995173344999682e-03,1.863352192219296377e-01,-4.000000000000000327e-05,-1.000000006935478192e+00,0.000000000000000000e+00 +8.246574736500055280e+01,5.178729849239000487e+02,1.388856779697177635e-01,1.098272457485865239e+01,3.311849187943461965e-03,1.854246842734423306e-01,-4.000000000000000327e-05,-1.000000011643661146e+00,0.000000000000000000e+00 +8.246665788587648649e+01,5.178829848690584186e+02,1.389187964010547283e-01,1.098289340790459612e+01,3.311703202541924247e-03,1.845141633869103737e-01,-4.000000000000000327e-05,-1.000000006310749479e+00,0.000000000000000000e+00 +8.246756839275555251e+01,5.178929848142215633e+02,1.389519133725456712e-01,1.098306140931964592e+01,3.311557217140386530e-03,1.836036565020934541e-01,-4.000000000000000327e-05,-1.000000008159895204e+00,0.000000000000000000e+00 +8.246847888570714247e+01,5.179029847593895965e+02,1.389850288841906201e-01,1.098322857915477613e+01,3.311411231738848812e-03,1.826931635430799061e-01,-4.000000000000000327e-05,-1.000000008701956489e+00,0.000000000000000000e+00 +8.246938936480060534e+01,5.179129847045624047e+02,1.390181429359895471e-01,1.098339491746069996e+01,3.311265246337311095e-03,1.817826844416981225e-01,-4.000000000000000327e-05,-1.000000008017779995e+00,0.000000000000000000e+00 +8.247029983010529008e+01,5.179229846497401013e+02,1.390512555279424523e-01,1.098356042428787660e+01,3.311119260935773377e-03,1.808722191297133519e-01,-4.000000000000000327e-05,-1.000000010473811152e+00,0.000000000000000000e+00 +8.247121028169054568e+01,5.179329845949225728e+02,1.390843666600493633e-01,1.098372509968651123e+01,3.310973275534235660e-03,1.799617675349258206e-01,-4.000000000000000327e-05,-1.000000005435350836e+00,0.000000000000000000e+00 +8.247212071962569269e+01,5.179429845401099328e+02,1.391174763323102526e-01,1.098388894370655144e+01,3.310827290132697942e-03,1.790513295948285288e-01,-4.000000000000000327e-05,-1.000000010126253169e+00,0.000000000000000000e+00 +8.247303114398005164e+01,5.179529844853020677e+02,1.391505845447251200e-01,1.098405195639769616e+01,3.310681304731160225e-03,1.781409052312435126e-01,-4.000000000000000327e-05,-1.000000009624798070e+00,0.000000000000000000e+00 +8.247394155482294309e+01,5.179629844304990911e+02,1.391836912972939932e-01,1.098421413780938138e+01,3.310535319329622507e-03,1.772304943795884047e-01,-4.000000000000000327e-05,-1.000000006152496956e+00,0.000000000000000000e+00 +8.247485195222365917e+01,5.179729843757008894e+02,1.392167965900168447e-01,1.098437548799079266e+01,3.310389333928084789e-03,1.763200969732684198e-01,-4.000000000000000327e-05,-1.000000010504187742e+00,0.000000000000000000e+00 +8.247576233625149200e+01,5.179829843209075761e+02,1.392499004228936743e-01,1.098453600699086330e+01,3.310243348526547072e-03,1.754097129358714036e-01,-4.000000000000000327e-05,-1.000000005611831000e+00,0.000000000000000000e+00 +8.247667270697571951e+01,5.179929842661190378e+02,1.392830027959244821e-01,1.098469569485826547e+01,3.310097363125009354e-03,1.744993422065339028e-01,-4.000000000000000327e-05,-1.000000010843079767e+00,0.000000000000000000e+00 +8.247758306446560539e+01,5.180029842113353880e+02,1.393161037091092680e-01,1.098485455164142444e+01,3.309951377723471637e-03,1.735889847067706993e-01,-4.000000000000000327e-05,-1.000000006984775425e+00,0.000000000000000000e+00 +8.247849340879041335e+01,5.180129841565565130e+02,1.393492031624480598e-01,1.098501257738850256e+01,3.309805392321933919e-03,1.726786403755976029e-01,-4.000000000000000327e-05,-1.000000009117890443e+00,0.000000000000000000e+00 +8.247940374001939290e+01,5.180229841017825265e+02,1.393823011559408298e-01,1.098516977214741530e+01,3.309659406920396202e-03,1.717683091383113703e-01,-4.000000000000000327e-05,-1.000000008744908131e+00,0.000000000000000000e+00 +8.248031405822179352e+01,5.180329840470133149e+02,1.394153976895875779e-01,1.098532613596581875e+01,3.309513421518858484e-03,1.708579909279543674e-01,-4.000000000000000327e-05,-1.000000005941699577e+00,0.000000000000000000e+00 +8.248122436346683628e+01,5.180429839922489919e+02,1.394484927633883042e-01,1.098548166889111677e+01,3.309367436117320767e-03,1.699476856775096745e-01,-4.000000000000000327e-05,-1.000000011502282682e+00,0.000000000000000000e+00 +8.248213465582372805e+01,5.180529839374894436e+02,1.394815863773430087e-01,1.098563637097046097e+01,3.309221450715783049e-03,1.690373933101443904e-01,-4.000000000000000327e-05,-1.000000006208642267e+00,0.000000000000000000e+00 +8.248304493536168991e+01,5.180629838827347839e+02,1.395146785314516913e-01,1.098579024225074185e+01,3.309075465314245332e-03,1.681271137665294735e-01,-4.000000000000000327e-05,-1.000000009429135917e+00,0.000000000000000000e+00 +8.248395520214991450e+01,5.180729838279848991e+02,1.395477692257143520e-01,1.098594328277860477e+01,3.308929479912707614e-03,1.672168469697148108e-01,-4.000000000000000327e-05,-1.000000008375580896e+00,0.000000000000000000e+00 +8.248486545625760868e+01,5.180829837732399028e+02,1.395808584601309910e-01,1.098609549260043394e+01,3.308783494511169897e-03,1.663065928544007754e-01,-4.000000000000000327e-05,-1.000000007409459712e+00,0.000000000000000000e+00 +8.248577569775393670e+01,5.180929837184996813e+02,1.396139462347016080e-01,1.098624687176236314e+01,3.308637509109632179e-03,1.653963513513271866e-01,-4.000000000000000327e-05,-1.000000008748389124e+00,0.000000000000000000e+00 +8.248668592670807698e+01,5.181029836637643484e+02,1.396470325494262033e-01,1.098639742031027211e+01,3.308491523708094462e-03,1.644861223892248869e-01,-4.000000000000000327e-05,-1.000000008177622135e+00,0.000000000000000000e+00 +8.248759614318919375e+01,5.181129836090337903e+02,1.396801174043047766e-01,1.098654713828978480e+01,3.308345538306556744e-03,1.635759059006706428e-01,-4.000000000000000327e-05,-1.000000007913812716e+00,0.000000000000000000e+00 +8.248850634726642284e+01,5.181229835543081208e+02,1.397132007993373004e-01,1.098669602574627291e+01,3.308199552905019027e-03,1.626657018162329937e-01,-4.000000000000000327e-05,-1.000000008029355625e+00,0.000000000000000000e+00 +8.248941653900892845e+01,5.181329834995872261e+02,1.397462827345238023e-01,1.098684408272485413e+01,3.308053567503481309e-03,1.617555100664239964e-01,-4.000000000000000327e-05,-1.000000008596225065e+00,0.000000000000000000e+00 +8.249032671848583220e+01,5.181429834448712199e+02,1.397793632098642824e-01,1.098699130927039214e+01,3.307907582101943592e-03,1.608453305816995582e-01,-4.000000000000000327e-05,-1.000000009686035529e+00,0.000000000000000000e+00 +8.249123688576625568e+01,5.181529833901599886e+02,1.398124422253587407e-01,1.098713770542749657e+01,3.307761596700405874e-03,1.599351632924597144e-01,-4.000000000000000327e-05,-1.000000007081072617e+00,0.000000000000000000e+00 +8.249214704091932049e+01,5.181629833354536459e+02,1.398455197810071771e-01,1.098728327124052306e+01,3.307615611298868157e-03,1.590250081329525333e-01,-4.000000000000000327e-05,-1.000000007285066328e+00,0.000000000000000000e+00 +8.249305718401411980e+01,5.181729832807520779e+02,1.398785958768095639e-01,1.098742800675357678e+01,3.307469625897330439e-03,1.581148650315158111e-01,-4.000000000000000327e-05,-1.000000010368516490e+00,0.000000000000000000e+00 +8.249396731511976100e+01,5.181829832260553985e+02,1.399116705127659288e-01,1.098757191201050709e+01,3.307323640495792721e-03,1.572047339164324153e-01,-4.000000000000000327e-05,-1.000000005678882031e+00,0.000000000000000000e+00 +8.249487743430533726e+01,5.181929831713634940e+02,1.399447436888762719e-01,1.098771498705490757e+01,3.307177655094255004e-03,1.562946147256894791e-01,-4.000000000000000327e-05,-1.000000010441750575e+00,0.000000000000000000e+00 +8.249578754163991334e+01,5.182029831166764779e+02,1.399778154051405654e-01,1.098785723193012487e+01,3.307031669692717286e-03,1.553845073816057520e-01,-4.000000000000000327e-05,-1.000000007569669336e+00,0.000000000000000000e+00 +8.249669763719256821e+01,5.182129830619942368e+02,1.400108856615588371e-01,1.098799864667924453e+01,3.306885684291179569e-03,1.544744118220605089e-01,-4.000000000000000327e-05,-1.000000007854223494e+00,0.000000000000000000e+00 +8.249760772103236661e+01,5.182229830073167705e+02,1.400439544581310869e-01,1.098813923134510517e+01,3.306739698889641851e-03,1.535643279751204293e-01,-4.000000000000000327e-05,-1.000000009219172092e+00,0.000000000000000000e+00 +8.249851779322834489e+01,5.182329829526441927e+02,1.400770217948572871e-01,1.098827898597028963e+01,3.306593713488104134e-03,1.526542557707507020e-01,-4.000000000000000327e-05,-1.000000007442745531e+00,0.000000000000000000e+00 +8.249942785384955357e+01,5.182429828979763897e+02,1.401100876717374655e-01,1.098841791059712669e+01,3.306447728086566416e-03,1.517441951427674351e-01,-4.000000000000000327e-05,-1.000000006881870629e+00,0.000000000000000000e+00 +8.250033790296502900e+01,5.182529828433134753e+02,1.401431520887715942e-01,1.098855600526769472e+01,3.306301742685028699e-03,1.508341460210303742e-01,-4.000000000000000327e-05,-1.000000009748554630e+00,0.000000000000000000e+00 +8.250124794064379330e+01,5.182629827886553358e+02,1.401762150459597012e-01,1.098869327002381802e+01,3.306155757283490981e-03,1.499241083333950064e-01,-4.000000000000000327e-05,-1.000000007529802781e+00,0.000000000000000000e+00 +8.250215796695486858e+01,5.182729827340020847e+02,1.402092765433017585e-01,1.098882970490706512e+01,3.306009771881953264e-03,1.490140820154726431e-01,-4.000000000000000327e-05,-1.000000008871479995e+00,0.000000000000000000e+00 +8.250306798196724856e+01,5.182829826793536085e+02,1.402423365807977940e-01,1.098896530995875587e+01,3.305863786480415546e-03,1.481040669950151600e-01,-4.000000000000000327e-05,-1.000000007404362012e+00,0.000000000000000000e+00 +8.250397798574994113e+01,5.182929826247100209e+02,1.402753951584477798e-01,1.098910008521995429e+01,3.305717801078877829e-03,1.471940632055791232e-01,-4.000000000000000327e-05,-1.000000009629034681e+00,0.000000000000000000e+00 +8.250488797837193999e+01,5.183029825700712081e+02,1.403084522762517161e-01,1.098923403073147398e+01,3.305571815677340111e-03,1.462840705748140180e-01,-4.000000000000000327e-05,-1.000000004884784133e+00,0.000000000000000000e+00 +8.250579795990222465e+01,5.183129825154372838e+02,1.403415079342096305e-01,1.098936714653387270e+01,3.305425830275802394e-03,1.453740890400789521e-01,-4.000000000000000327e-05,-1.000000010397586125e+00,0.000000000000000000e+00 +8.250670793040977458e+01,5.183229824608081344e+02,1.403745621323214954e-01,1.098949943266746132e+01,3.305279844874264676e-03,1.444641185230660652e-01,-4.000000000000000327e-05,-1.000000009070060480e+00,0.000000000000000000e+00 +8.250761788996355506e+01,5.183329824061837598e+02,1.404076148705873106e-01,1.098963088917228959e+01,3.305133859472726959e-03,1.435541589610341007e-01,-4.000000000000000327e-05,-1.000000007401297797e+00,0.000000000000000000e+00 +8.250852783863251716e+01,5.183429823515642738e+02,1.404406661490071040e-01,1.098976151608816032e+01,3.304987874071189241e-03,1.426442102853360261e-01,-4.000000000000000327e-05,-1.000000005454723118e+00,0.000000000000000000e+00 +8.250943777648561195e+01,5.183529822969495626e+02,1.404737159675808478e-01,1.098989131345462411e+01,3.304841888669651524e-03,1.417342724272753207e-01,-4.000000000000000327e-05,-1.000000011874984107e+00,0.000000000000000000e+00 +8.251034770359179049e+01,5.183629822423397400e+02,1.405067643263085420e-01,1.099002028131097930e+01,3.304695903268113806e-03,1.408243453102976384e-01,-4.000000000000000327e-05,-1.000000005270254233e+00,0.000000000000000000e+00 +8.251125762001997543e+01,5.183729821877346922e+02,1.405398112251901865e-01,1.099014841969626488e+01,3.304549917866576089e-03,1.399144288773218059e-01,-4.000000000000000327e-05,-1.000000009302658643e+00,0.000000000000000000e+00 +8.251216752583908942e+01,5.183829821331345329e+02,1.405728566642258093e-01,1.099027572864927826e+01,3.304403932465038371e-03,1.390045230497440054e-01,-4.000000000000000327e-05,-1.000000009015567848e+00,0.000000000000000000e+00 +8.251307742111805510e+01,5.183929820785391485e+02,1.406059006434153824e-01,1.099040220820855573e+01,3.304257947063500653e-03,1.380946277625777485e-01,-4.000000000000000327e-05,-1.000000006615502590e+00,0.000000000000000000e+00 +8.251398730592578090e+01,5.184029820239485389e+02,1.406389431627589059e-01,1.099052785841238489e+01,3.304111961661962936e-03,1.371847429488367021e-01,-4.000000000000000327e-05,-1.000000006454587753e+00,0.000000000000000000e+00 +8.251489718033116105e+01,5.184129819693628178e+02,1.406719842222563799e-01,1.099065267929880285e+01,3.303965976260425218e-03,1.362748685375824997e-01,-4.000000000000000327e-05,-1.000000010739292344e+00,0.000000000000000000e+00 +8.251580704440308978e+01,5.184229819147818716e+02,1.407050238219078042e-01,1.099077667090559274e+01,3.303819990858887501e-03,1.353650044558771248e-01,-4.000000000000000327e-05,-1.000000006655171525e+00,0.000000000000000000e+00 +8.251671689821046130e+01,5.184329818602058140e+02,1.407380619617131789e-01,1.099089983327028186e+01,3.303674005457349783e-03,1.344551506424497833e-01,-4.000000000000000327e-05,-1.000000009282205893e+00,0.000000000000000000e+00 +8.251762674182215562e+01,5.184429818056345312e+02,1.407710986416725041e-01,1.099102216643015240e+01,3.303528020055812066e-03,1.335453070223167615e-01,-4.000000000000000327e-05,-1.000000005804738912e+00,0.000000000000000000e+00 +8.251853657530702435e+01,5.184529817510681369e+02,1.408041338617857796e-01,1.099114367042222895e+01,3.303382034654274348e-03,1.326354735321623735e-01,-4.000000000000000327e-05,-1.000000009156852832e+00,0.000000000000000000e+00 +8.251944639873394749e+01,5.184629816965065174e+02,1.408371676220530055e-01,1.099126434528328922e+01,3.303236049252736631e-03,1.317256500969106736e-01,-4.000000000000000327e-05,-1.000000008667585760e+00,0.000000000000000000e+00 +8.252035621217177663e+01,5.184729816419496728e+02,1.408701999224741819e-01,1.099138419104985331e+01,3.303090063851198913e-03,1.308158366512021109e-01,-4.000000000000000327e-05,-1.000000006540593844e+00,0.000000000000000000e+00 +8.252126601568934916e+01,5.184829815873977168e+02,1.409032307630493086e-01,1.099150320775819267e+01,3.302944078449661196e-03,1.299060331276796765e-01,-4.000000000000000327e-05,-1.000000009271802215e+00,0.000000000000000000e+00 +8.252217580935550245e+01,5.184929815328505356e+02,1.409362601437783857e-01,1.099162139544432826e+01,3.302798093048123478e-03,1.289962394530838607e-01,-4.000000000000000327e-05,-1.000000008334120061e+00,0.000000000000000000e+00 +8.252308559323908810e+01,5.185029814783082429e+02,1.409692880646614133e-01,1.099173875414402524e+01,3.302652107646585761e-03,1.280864555619205536e-01,-4.000000000000000327e-05,-1.000000005930377966e+00,0.000000000000000000e+00 +8.252399536740891506e+01,5.185129814237707251e+02,1.410023145256983912e-01,1.099185528389280009e+01,3.302506122245048043e-03,1.271766813866988532e-01,-4.000000000000000327e-05,-1.000000008555475217e+00,0.000000000000000000e+00 +8.252490513193380650e+01,5.185229813692380958e+02,1.410353395268893195e-01,1.099197098472591883e+01,3.302360136843510326e-03,1.262669168540263287e-01,-4.000000000000000327e-05,-1.000000007680750480e+00,0.000000000000000000e+00 +8.252581488688257139e+01,5.185329813147102413e+02,1.410683630682341982e-01,1.099208585667839166e+01,3.302214151441972608e-03,1.253571618982769753e-01,-4.000000000000000327e-05,-1.000000009800525724e+00,0.000000000000000000e+00 +8.252672463232400446e+01,5.185429812601871618e+02,1.411013851497329996e-01,1.099219989978498013e+01,3.302068166040434891e-03,1.244474164479237449e-01,-4.000000000000000327e-05,-1.000000006384697882e+00,0.000000000000000000e+00 +8.252763436832691468e+01,5.185529812056689707e+02,1.411344057713857514e-01,1.099231311408019174e+01,3.301922180638897173e-03,1.235376804392070010e-01,-4.000000000000000327e-05,-1.000000006073316516e+00,0.000000000000000000e+00 +8.252854409496008259e+01,5.185629811511555545e+02,1.411674249331924536e-01,1.099242549959828708e+01,3.301776195237359456e-03,1.226279538005140002e-01,-4.000000000000000327e-05,-1.000000011067433858e+00,0.000000000000000000e+00 +8.252945381229228872e+01,5.185729810966470268e+02,1.412004426351531061e-01,1.099253705637327272e+01,3.301630209835821738e-03,1.217182364582368309e-01,-4.000000000000000327e-05,-1.000000006395983521e+00,0.000000000000000000e+00 +8.253036352039231360e+01,5.185829810421432740e+02,1.412334588772676813e-01,1.099264778443889945e+01,3.301484224434284021e-03,1.208085283523940567e-01,-4.000000000000000327e-05,-1.000000007137570535e+00,0.000000000000000000e+00 +8.253127321932892357e+01,5.185929809876442960e+02,1.412664736595362069e-01,1.099275768382867469e+01,3.301338239032746303e-03,1.198988294092939583e-01,-4.000000000000000327e-05,-1.000000009052620209e+00,0.000000000000000000e+00 +8.253218290917087074e+01,5.186029809331502065e+02,1.412994869819586830e-01,1.099286675457585005e+01,3.301192253631208585e-03,1.189891395591085865e-01,-4.000000000000000327e-05,-1.000000005754108301e+00,0.000000000000000000e+00 +8.253309258998692144e+01,5.186129808786608919e+02,1.413324988445350816e-01,1.099297499671342493e+01,3.301046268229670868e-03,1.180794587378270477e-01,-4.000000000000000327e-05,-1.000000010174028509e+00,0.000000000000000000e+00 +8.253400226184581356e+01,5.186229808241764658e+02,1.413655092472654307e-01,1.099308241027415178e+01,3.300900282828133150e-03,1.171697868696812556e-01,-4.000000000000000327e-05,-1.000000005191211017e+00,0.000000000000000000e+00 +8.253491192481628502e+01,5.186329807696968146e+02,1.413985181901497024e-01,1.099318899529052551e+01,3.300754297426595433e-03,1.162601238944845905e-01,-4.000000000000000327e-05,-1.000000010177302334e+00,0.000000000000000000e+00 +8.253582157896707372e+01,5.186429807152219382e+02,1.414315256731879245e-01,1.099329475179479765e+01,3.300608312025057715e-03,1.153504697344353985e-01,-4.000000000000000327e-05,-1.000000005863079799e+00,0.000000000000000000e+00 +8.253673122436690335e+01,5.186529806607519504e+02,1.414645316963800692e-01,1.099339967981896038e+01,3.300462326623519998e-03,1.144408243292671101e-01,-4.000000000000000327e-05,-1.000000007326369289e+00,0.000000000000000000e+00 +8.253764086108449760e+01,5.186629806062867374e+02,1.414975362597261643e-01,1.099350377939476253e+01,3.300316341221982280e-03,1.135311876050041774e-01,-4.000000000000000327e-05,-1.000000010324283650e+00,0.000000000000000000e+00 +8.253855048918858017e+01,5.186729805518262992e+02,1.415305393632261821e-01,1.099360705055369714e+01,3.300170355820444563e-03,1.126215594915372098e-01,-4.000000000000000327e-05,-1.000000006319154311e+00,0.000000000000000000e+00 +8.253946010874784633e+01,5.186829804973707496e+02,1.415635410068801503e-01,1.099370949332700498e+01,3.300024370418906845e-03,1.117119399265293911e-01,-4.000000000000000327e-05,-1.000000006094804661e+00,0.000000000000000000e+00 +8.254036971983099136e+01,5.186929804429199748e+02,1.415965411906880411e-01,1.099381110774568171e+01,3.299878385017369128e-03,1.108023288378410937e-01,-4.000000000000000327e-05,-1.000000009700670489e+00,0.000000000000000000e+00 +8.254127932250671051e+01,5.187029803884740886e+02,1.416295399146498823e-01,1.099391189384046896e+01,3.299732399615831410e-03,1.098927261532942207e-01,-4.000000000000000327e-05,-1.000000006450549428e+00,0.000000000000000000e+00 +8.254218891684369908e+01,5.187129803340329772e+02,1.416625371787656462e-01,1.099401185164185435e+01,3.299586414214293693e-03,1.089831318104372282e-01,-4.000000000000000327e-05,-1.000000007127697099e+00,0.000000000000000000e+00 +8.254309850291063810e+01,5.187229802795966407e+02,1.416955329830353327e-01,1.099411098118008034e+01,3.299440428812755975e-03,1.080735457370163993e-01,-4.000000000000000327e-05,-1.000000009633168263e+00,0.000000000000000000e+00 +8.254400808077619445e+01,5.187329802251651927e+02,1.417285273274589696e-01,1.099420928248513540e+01,3.299294443411218258e-03,1.071639678626935127e-01,-4.000000000000000327e-05,-1.000000005426032734e+00,0.000000000000000000e+00 +8.254491765050904917e+01,5.187429801707385195e+02,1.417615202120365292e-01,1.099430675558675574e+01,3.299148458009680540e-03,1.062543981249051556e-01,-4.000000000000000327e-05,-1.000000009583254634e+00,0.000000000000000000e+00 +8.254582721217785490e+01,5.187529801163166212e+02,1.417945116367680114e-01,1.099440340051443243e+01,3.299002472608142823e-03,1.053448364473804633e-01,-4.000000000000000327e-05,-1.000000004974356704e+00,0.000000000000000000e+00 +8.254673676585127851e+01,5.187629800618996114e+02,1.418275016016534162e-01,1.099449921729739899e+01,3.298856487206605105e-03,1.044352827694359498e-01,-4.000000000000000327e-05,-1.000000008823131781e+00,0.000000000000000000e+00 +8.254764631159795840e+01,5.187729800074873765e+02,1.418604901066927437e-01,1.099459420596464554e+01,3.298710501805067388e-03,1.035257370147281281e-01,-4.000000000000000327e-05,-1.000000008292293296e+00,0.000000000000000000e+00 +8.254855584948654723e+01,5.187829799530799164e+02,1.418934771518860216e-01,1.099468836654490467e+01,3.298564516403529670e-03,1.026161991185956940e-01,-4.000000000000000327e-05,-1.000000005574398054e+00,0.000000000000000000e+00 +8.254946537958568342e+01,5.187929798986773449e+02,1.419264627372332221e-01,1.099478169906666203e+01,3.298418531001991953e-03,1.017066690143889757e-01,-4.000000000000000327e-05,-1.000000009303888771e+00,0.000000000000000000e+00 +8.255037490196400540e+01,5.188029798442795482e+02,1.419594468627343453e-01,1.099487420355815459e+01,3.298272545600454235e-03,1.007971466276109118e-01,-4.000000000000000327e-05,-1.000000006641442951e+00,0.000000000000000000e+00 +8.255128441669012318e+01,5.188129797898866400e+02,1.419924295283893911e-01,1.099496588004736353e+01,3.298126560198916517e-03,9.988763189544797028e-02,-4.000000000000000327e-05,-1.000000006220772342e+00,0.000000000000000000e+00 +8.255219392383267518e+01,5.188229797354985067e+02,1.420254107341983596e-01,1.099505672856202487e+01,3.297980574797378800e-03,9.897812474723982623e-02,-4.000000000000000327e-05,-1.000000008085900394e+00,0.000000000000000000e+00 +8.255310342346027142e+01,5.188329796811151482e+02,1.420583904801612507e-01,1.099514674912962242e+01,3.297834589395841082e-03,9.806862511229189061e-02,-4.000000000000000327e-05,-1.000000007985478501e+00,0.000000000000000000e+00 +8.255401291564152189e+01,5.188429796267366783e+02,1.420913687662780645e-01,1.099523594177738772e+01,3.297688603994303365e-03,9.715913292378186572e-02,-4.000000000000000327e-05,-1.000000008109987570e+00,0.000000000000000000e+00 +8.255492240044502239e+01,5.188529795723629832e+02,1.421243455925488008e-01,1.099532430653230364e+01,3.297542618592765647e-03,9.624964811290082078e-02,-4.000000000000000327e-05,-1.000000006354659909e+00,0.000000000000000000e+00 +8.255583187793938293e+01,5.188629795179940629e+02,1.421573209589734599e-01,1.099541184342110256e+01,3.297396633191227930e-03,9.534017061275963656e-02,-4.000000000000000327e-05,-1.000000007056778495e+00,0.000000000000000000e+00 +8.255674134819319931e+01,5.188729794636300312e+02,1.421902948655520416e-01,1.099549855247026819e+01,3.297250647789690212e-03,9.443070035253003924e-02,-4.000000000000000327e-05,-1.000000005963244343e+00,0.000000000000000000e+00 +8.255765081127505312e+01,5.188829794092707743e+02,1.422232673122845459e-01,1.099558443370603200e+01,3.297104662388152495e-03,9.352123726525730929e-02,-4.000000000000000327e-05,-1.000000009558390968e+00,0.000000000000000000e+00 +8.255856026725352592e+01,5.188929793549162923e+02,1.422562382991709728e-01,1.099566948715437675e+01,3.296958676986614777e-03,9.261178127809488458e-02,-4.000000000000000327e-05,-1.000000004997370739e+00,0.000000000000000000e+00 +8.255946971619719932e+01,5.189029793005666988e+02,1.422892078262113225e-01,1.099575371284103120e+01,3.296812691585077060e-03,9.170233232988339589e-02,-4.000000000000000327e-05,-1.000000009502375775e+00,0.000000000000000000e+00 +8.256037915817464068e+01,5.189129792462218802e+02,1.423221758934055947e-01,1.099583711079148074e+01,3.296666706183539342e-03,9.079289034380602641e-02,-4.000000000000000327e-05,-1.000000005931983349e+00,0.000000000000000000e+00 +8.256128859325441738e+01,5.189229791918818364e+02,1.423551425007537896e-01,1.099591968103095319e+01,3.296520720782001625e-03,8.988345525864041563e-02,-4.000000000000000327e-05,-1.000000007212477282e+00,0.000000000000000000e+00 +8.256219802150508258e+01,5.189329791375466812e+02,1.423881076482558794e-01,1.099600142358443300e+01,3.296374735380463907e-03,8.897402700141371357e-02,-4.000000000000000327e-05,-1.000000006940181319e+00,0.000000000000000000e+00 +8.256310744299520366e+01,5.189429790832163008e+02,1.424210713359118918e-01,1.099608233847665062e+01,3.296228749978926190e-03,8.806460550498196316e-02,-4.000000000000000327e-05,-1.000000007301891314e+00,0.000000000000000000e+00 +8.256401685779333377e+01,5.189529790288906952e+02,1.424540335637218269e-01,1.099616242573208780e+01,3.296082764577388472e-03,8.715519070021757186e-02,-4.000000000000000327e-05,-1.000000006188516366e+00,0.000000000000000000e+00 +8.256492626596801188e+01,5.189629789745699782e+02,1.424869943316856846e-01,1.099624168537497582e+01,3.295936779175850755e-03,8.624578251991603384e-02,-4.000000000000000327e-05,-1.000000007934117807e+00,0.000000000000000000e+00 +8.256583566758777692e+01,5.189729789202540360e+02,1.425199536398034372e-01,1.099632011742929727e+01,3.295790793774313037e-03,8.533638089293640872e-02,-4.000000000000000327e-05,-1.000000006132833574e+00,0.000000000000000000e+00 +8.256674506272116787e+01,5.189829788659428687e+02,1.425529114880751125e-01,1.099639772191878251e+01,3.295644808372775320e-03,8.442698575396821725e-02,-4.000000000000000327e-05,-1.000000009413990476e+00,0.000000000000000000e+00 +8.256765445143672366e+01,5.189929788116365899e+02,1.425858678765007104e-01,1.099647449886691497e+01,3.295498822971237602e-03,8.351759702985839251e-02,-4.000000000000000327e-05,-1.000000004926771879e+00,0.000000000000000000e+00 +8.256856383380295483e+01,5.190029787573350859e+02,1.426188228050802032e-01,1.099655044829692407e+01,3.295352837569699885e-03,8.260821465914511275e-02,-4.000000000000000327e-05,-1.000000005595845565e+00,0.000000000000000000e+00 +8.256947320988840033e+01,5.190129787030383568e+02,1.426517762738136186e-01,1.099662557023179588e+01,3.295206852168162167e-03,8.169883856861781535e-02,-4.000000000000000327e-05,-1.000000009309691684e+00,0.000000000000000000e+00 +8.257038257976155649e+01,5.190229786487465162e+02,1.426847282827009289e-01,1.099669986469426242e+01,3.295060866766624449e-03,8.078946868699092565e-02,-4.000000000000000327e-05,-1.000000005363761435e+00,0.000000000000000000e+00 +8.257129194349094803e+01,5.190329785944594505e+02,1.427176788317421618e-01,1.099677333170680349e+01,3.294914881365086732e-03,7.988010495271793965e-02,-4.000000000000000327e-05,-1.000000008830193465e+00,0.000000000000000000e+00 +8.257220130114508549e+01,5.190429785401771596e+02,1.427506279209372897e-01,1.099684597129165553e+01,3.294768895963549014e-03,7.897074729055088282e-02,-4.000000000000000327e-05,-1.000000004707283452e+00,0.000000000000000000e+00 +8.257311065279246520e+01,5.190529784858996436e+02,1.427835755502863402e-01,1.099691778347079918e+01,3.294622910562011297e-03,7.806139563888832289e-02,-4.000000000000000327e-05,-1.000000005918530555e+00,0.000000000000000000e+00 +8.257401999850158347e+01,5.190629784316270161e+02,1.428165217197892856e-01,1.099698876826597171e+01,3.294476925160473579e-03,7.715204992438129405e-02,-4.000000000000000327e-05,-1.000000008202079682e+00,0.000000000000000000e+00 +8.257492933834095084e+01,5.190729783773591635e+02,1.428494664294461536e-01,1.099705892569865640e+01,3.294330939758935862e-03,7.624271007756087959e-02,-4.000000000000000327e-05,-1.000000007295327453e+00,0.000000000000000000e+00 +8.257583867237903519e+01,5.190829783230960857e+02,1.428824096792569165e-01,1.099712825579008602e+01,3.294184954357398144e-03,7.533337603283873918e-02,-4.000000000000000327e-05,-1.000000005379998447e+00,0.000000000000000000e+00 +8.257674800068433285e+01,5.190929782688378964e+02,1.429153514692216020e-01,1.099719675856124645e+01,3.294038968955860427e-03,7.442404772264694934e-02,-4.000000000000000327e-05,-1.000000006785683127e+00,0.000000000000000000e+00 +8.257765732332532593e+01,5.191029782145844820e+02,1.429482917993401825e-01,1.099726443403287490e+01,3.293892983554322709e-03,7.351472507548489910e-02,-4.000000000000000327e-05,-1.000000007248608158e+00,0.000000000000000000e+00 +8.257856664037048233e+01,5.191129781603358424e+02,1.429812306696126578e-01,1.099733128222545631e+01,3.293746998152784992e-03,7.260540802373342817e-02,-4.000000000000000327e-05,-1.000000006801083030e+00,0.000000000000000000e+00 +8.257947595188828416e+01,5.191229781060920914e+02,1.430141680800390558e-01,1.099739730315922692e+01,3.293601012751247274e-03,7.169609649974820198e-02,-4.000000000000000327e-05,-1.000000005474949383e+00,0.000000000000000000e+00 +8.258038525794719931e+01,5.191329780518531152e+02,1.430471040306193486e-01,1.099746249685417432e+01,3.293455027349709557e-03,7.078679043586008635e-02,-4.000000000000000327e-05,-1.000000005450080387e+00,0.000000000000000000e+00 +8.258129455861568147e+01,5.191429779976189138e+02,1.430800385213535364e-01,1.099752686333003737e+01,3.293309041948171839e-03,6.987748976242189047e-02,-4.000000000000000327e-05,-1.000000008906114735e+00,0.000000000000000000e+00 +8.258220385396219854e+01,5.191529779433894873e+02,1.431129715522416468e-01,1.099759040260630449e+01,3.293163056546634122e-03,6.896819440780857513e-02,-4.000000000000000327e-05,-1.000000005131616021e+00,0.000000000000000000e+00 +8.258311314405520420e+01,5.191629778891649494e+02,1.431459031232836521e-01,1.099765311470221185e+01,3.293017071145096404e-03,6.805890431013897346e-02,-4.000000000000000327e-05,-1.000000004899017858e+00,0.000000000000000000e+00 +8.258402242896315215e+01,5.191729778349451863e+02,1.431788332344795522e-01,1.099771499963675225e+01,3.292871085743558687e-03,6.714961939774055644e-02,-4.000000000000000327e-05,-1.000000008238369098e+00,0.000000000000000000e+00 +8.258493170875448186e+01,5.191829777807301980e+02,1.432117618858293473e-01,1.099777605742866626e+01,3.292725100342020969e-03,6.624033959891743872e-02,-4.000000000000000327e-05,-1.000000004436736090e+00,0.000000000000000000e+00 +8.258584098349764702e+01,5.191929777265200983e+02,1.432446890773330372e-01,1.099783628809644220e+01,3.292579114940483252e-03,6.533106485171864819e-02,-4.000000000000000327e-05,-1.000000008562797138e+00,0.000000000000000000e+00 +8.258675025326108710e+01,5.192029776723147734e+02,1.432776148089906221e-01,1.099789569165832503e+01,3.292433129538945534e-03,6.442179508049541981e-02,-4.000000000000000327e-05,-1.000000003456974484e+00,0.000000000000000000e+00 +8.258765951811322736e+01,5.192129776181142233e+02,1.433105390808021296e-01,1.099795426813230392e+01,3.292287144137407816e-03,6.351253022520546299e-02,-4.000000000000000327e-05,-1.000000006336086322e+00,0.000000000000000000e+00 +8.258856877812252151e+01,5.192229775639184481e+02,1.433434618927675319e-01,1.099801201753612645e+01,3.292141158735870099e-03,6.260327021015549276e-02,-4.000000000000000327e-05,-1.000000008633844084e+00,0.000000000000000000e+00 +8.258947803335738058e+01,5.192329775097275615e+02,1.433763832448868292e-01,1.099806893988728440e+01,3.291995173334332381e-03,6.169401496744493507e-02,-4.000000000000000327e-05,-1.000000003931843295e+00,0.000000000000000000e+00 +8.259038728388624406e+01,5.192429774555414497e+02,1.434093031371600213e-01,1.099812503520302087e+01,3.291849187932794664e-03,6.078476443501274612e-02,-4.000000000000000327e-05,-1.000000005148935278e+00,0.000000000000000000e+00 +8.259129652977752301e+01,5.192529774013601127e+02,1.434422215695871083e-01,1.099818030350033560e+01,3.291703202531256946e-03,5.987551853905492133e-02,-4.000000000000000327e-05,-1.000000005866065411e+00,0.000000000000000000e+00 +8.259220577109964267e+01,5.192629773471836643e+02,1.434751385421680903e-01,1.099823474479597429e+01,3.291557217129719229e-03,5.896627721160750679e-02,-4.000000000000000327e-05,-1.000000008258240314e+00,0.000000000000000000e+00 +8.259311500792101413e+01,5.192729772930119907e+02,1.435080540549029671e-01,1.099828835910643399e+01,3.291411231728181511e-03,5.805704038273239165e-02,-4.000000000000000327e-05,-1.000000003756540190e+00,0.000000000000000000e+00 +8.259402424031004841e+01,5.192829772388450920e+02,1.435409681077917110e-01,1.099834114644796124e+01,3.291265246326643794e-03,5.714780799028602171e-02,-4.000000000000000327e-05,-1.000000005278775639e+00,0.000000000000000000e+00 +8.259493346833515659e+01,5.192929771846829681e+02,1.435738807008343498e-01,1.099839310683655924e+01,3.291119260925106076e-03,5.623857996038286039e-02,-4.000000000000000327e-05,-1.000000006404009989e+00,0.000000000000000000e+00 +8.259584269206473550e+01,5.193029771305257327e+02,1.436067918340308835e-01,1.099844424028797718e+01,3.290973275523568359e-03,5.532935622497880956e-02,-4.000000000000000327e-05,-1.000000005008196968e+00,0.000000000000000000e+00 +8.259675191156719620e+01,5.193129770763732722e+02,1.436397015073813122e-01,1.099849454681771554e+01,3.290827290122030641e-03,5.442013671796423063e-02,-4.000000000000000327e-05,-1.000000005413212989e+00,0.000000000000000000e+00 +8.259766112691093554e+01,5.193229770222255866e+02,1.436726097208856356e-01,1.099854402644102791e+01,3.290681304720492924e-03,5.351092136930312576e-02,-4.000000000000000327e-05,-1.000000005494253275e+00,0.000000000000000000e+00 +8.259857033816435035e+01,5.193329769680826757e+02,1.437055164745438540e-01,1.099859267917291739e+01,3.290535319318955206e-03,5.260171011089455340e-02,-4.000000000000000327e-05,-1.000000005274893855e+00,0.000000000000000000e+00 +8.259947954539582327e+01,5.193429769139446535e+02,1.437384217683559395e-01,1.099864050502813839e+01,3.290389333917417489e-03,5.169250287461921861e-02,-4.000000000000000327e-05,-1.000000004778249574e+00,0.000000000000000000e+00 +8.260038874867375114e+01,5.193529768598114060e+02,1.437713256023219199e-01,1.099868750402119666e+01,3.290243348515879771e-03,5.078329959233984087e-02,-4.000000000000000327e-05,-1.000000006176019252e+00,0.000000000000000000e+00 +8.260129794806653081e+01,5.193629768056829334e+02,1.438042279764417952e-01,1.099873367616634923e+01,3.290097363114342054e-03,4.987410019394761251e-02,-4.000000000000000327e-05,-1.000000003043891139e+00,0.000000000000000000e+00 +8.260220714364253070e+01,5.193729767515592357e+02,1.438371288907155654e-01,1.099877902147760267e+01,3.289951377712804336e-03,4.896490461517763459e-02,-4.000000000000000327e-05,-1.000000006148303644e+00,0.000000000000000000e+00 +8.260311633547013344e+01,5.193829766974404265e+02,1.438700283451432027e-01,1.099882353996871842e+01,3.289805392311266619e-03,4.805571278197907914e-02,-4.000000000000000327e-05,-1.000000004766371076e+00,0.000000000000000000e+00 +8.260402552361772166e+01,5.193929766433263921e+02,1.439029263397247349e-01,1.099886723165320390e+01,3.289659406909728901e-03,4.714652463005313682e-02,-4.000000000000000327e-05,-1.000000005365967448e+00,0.000000000000000000e+00 +8.260493470815367800e+01,5.194029765892171326e+02,1.439358228744601342e-01,1.099891009654432139e+01,3.289513421508191184e-03,4.623734008922323474e-02,-4.000000000000000327e-05,-1.000000003670012294e+00,0.000000000000000000e+00 +8.260584388914635667e+01,5.194129765351126480e+02,1.439687179493494285e-01,1.099895213465508270e+01,3.289367436106653466e-03,4.532815909320418724e-02,-4.000000000000000327e-05,-1.000000006145802756e+00,0.000000000000000000e+00 +8.260675306666414031e+01,5.194229764810130519e+02,1.440016115643926176e-01,1.099899334599825274e+01,3.289221450705115748e-03,4.441898156983353774e-02,-4.000000000000000327e-05,-1.000000002068413441e+00,0.000000000000000000e+00 +8.260766224077539732e+01,5.194329764269182306e+02,1.440345037195896738e-01,1.099903373058634415e+01,3.289075465303578031e-03,4.350980745670231936e-02,-4.000000000000000327e-05,-1.000000006500421978e+00,0.000000000000000000e+00 +8.260857141154848193e+01,5.194429763728281841e+02,1.440673944149406249e-01,1.099907328843162624e+01,3.288929479902040313e-03,4.260063667770961487e-02,-4.000000000000000327e-05,-1.000000002268957910e+00,0.000000000000000000e+00 +8.260948057905176256e+01,5.194529763187429126e+02,1.441002836504454432e-01,1.099911201954611251e+01,3.288783494500502596e-03,4.169146917237012695e-02,-4.000000000000000327e-05,-1.000000004435947165e+00,0.000000000000000000e+00 +8.261038974335359342e+01,5.194629762646625295e+02,1.441331714261041563e-01,1.099914992394157487e+01,3.288637509098964878e-03,4.078230486650717690e-02,-4.000000000000000327e-05,-1.000000004423720945e+00,0.000000000000000000e+00 +8.261129890452232871e+01,5.194729762105869213e+02,1.441660577419167366e-01,1.099918700162953122e+01,3.288491523697427161e-03,3.987314369374504730e-02,-4.000000000000000327e-05,-1.000000004399310027e+00,0.000000000000000000e+00 +8.261220806262633687e+01,5.194829761565160879e+02,1.441989425978831840e-01,1.099922325262125256e+01,3.288345538295889443e-03,3.896398558574019205e-02,-4.000000000000000327e-05,-1.000000002231238083e+00,0.000000000000000000e+00 +8.261311721773395789e+01,5.194929761024500294e+02,1.442318259940035263e-01,1.099925867692776116e+01,3.288199552894351726e-03,3.805483047608922142e-02,-4.000000000000000327e-05,-1.000000004383985841e+00,0.000000000000000000e+00 +8.261402636991354598e+01,5.195029760483887458e+02,1.442647079302777358e-01,1.099929327455983241e+01,3.288053567492814008e-03,3.714567829251379238e-02,-4.000000000000000327e-05,-1.000000002277994460e+00,0.000000000000000000e+00 +8.261493551923345535e+01,5.195129759943323506e+02,1.442975884067058401e-01,1.099932704552798945e+01,3.287907582091276291e-03,3.623652897053791094e-02,-4.000000000000000327e-05,-1.000000004526157449e+00,0.000000000000000000e+00 +8.261584466576202601e+01,5.195229759402807304e+02,1.443304674232878115e-01,1.099935998984251029e+01,3.287761596689738573e-03,3.532738243785732424e-02,-4.000000000000000327e-05,-1.000000002547993150e+00,0.000000000000000000e+00 +8.261675380956759795e+01,5.195329758862338849e+02,1.443633449800236501e-01,1.099939210751342067e+01,3.287615611288200856e-03,3.441823862997081540e-02,-4.000000000000000327e-05,-1.000000002806520349e+00,0.000000000000000000e+00 +8.261766295071851118e+01,5.195429758321918143e+02,1.443962210769133558e-01,1.099942339855050122e+01,3.287469625886663138e-03,3.350909747650339388e-02,-4.000000000000000327e-05,-1.000000003167874407e+00,0.000000000000000000e+00 +8.261857208928310570e+01,5.195529757781546323e+02,1.444290957139569564e-01,1.099945386296328209e+01,3.287323640485125421e-03,3.259995890902207122e-02,-4.000000000000000327e-05,-1.000000001497712177e+00,0.000000000000000000e+00 +8.261948122532973571e+01,5.195629757241222251e+02,1.444619688911544242e-01,1.099948350076104475e+01,3.287177655083587703e-03,3.169082286103622192e-02,-4.000000000000000327e-05,-1.000000002108808017e+00,0.000000000000000000e+00 +8.262039035892671279e+01,5.195729756700945927e+02,1.444948406085057591e-01,1.099951231195282375e+01,3.287031669682049986e-03,3.078168926213621995e-02,-4.000000000000000327e-05,-1.000000002866090476e+00,0.000000000000000000e+00 +8.262129949014239116e+01,5.195829756160717352e+02,1.445277108660109611e-01,1.099954029654740317e+01,3.286885684280512268e-03,2.987255804385536770e-02,-4.000000000000000327e-05,-1.000000001633980284e+00,0.000000000000000000e+00 +8.262220861904509661e+01,5.195929755620536525e+02,1.445605796636700302e-01,1.099956745455331841e+01,3.286739698878974551e-03,2.896342913967028462e-02,-4.000000000000000327e-05,-1.000000000574940096e+00,0.000000000000000000e+00 +8.262311774570315492e+01,5.196029755080404584e+02,1.445934470014829665e-01,1.099959378597885795e+01,3.286593713477436833e-03,2.805430248109337318e-02,-4.000000000000000327e-05,-1.000000001851057085e+00,0.000000000000000000e+00 +8.262402687018489189e+01,5.196129754540320391e+02,1.446263128794497699e-01,1.099961929083206158e+01,3.286447728075899116e-03,2.714517799767312764e-02,-4.000000000000000327e-05,-1.000000001176373443e+00,0.000000000000000000e+00 +8.262493599255863330e+01,5.196229754000283947e+02,1.446591772975704682e-01,1.099964396912071862e+01,3.286301742674361398e-03,2.623605562285616366e-02,-4.000000000000000327e-05,-1.000000000712174764e+00,0.000000000000000000e+00 +8.262584511289271916e+01,5.196329753460295251e+02,1.446920402558450336e-01,1.099966782085237149e+01,3.286155757272823680e-03,2.532693528812580974e-02,-4.000000000000000327e-05,-9.999999983208738286e-01,0.000000000000000000e+00 +8.262675423125546104e+01,5.196429752920354304e+02,1.447249017542734661e-01,1.099969084603431391e+01,3.286009771871285963e-03,2.441781692691025879e-02,-4.000000000000000327e-05,-1.000000002610824668e+00,0.000000000000000000e+00 +8.262766334771518473e+01,5.196529752380462241e+02,1.447577617928557658e-01,1.099971304467359268e+01,3.285863786469748245e-03,2.350870046481318837e-02,-4.000000000000000327e-05,-9.999999985480456655e-01,0.000000000000000000e+00 +8.262857246234021602e+01,5.196629751840617928e+02,1.447906203715919327e-01,1.099973441677700059e+01,3.285717801068210528e-03,2.259958584110736621e-02,-4.000000000000000327e-05,-9.999999990386366777e-01,0.000000000000000000e+00 +8.262948157519886649e+01,5.196729751300821363e+02,1.448234774904819389e-01,1.099975496235108885e+01,3.285571815666672810e-03,2.169047298333380211e-02,-4.000000000000000327e-05,-9.999999976448761263e-01,0.000000000000000000e+00 +8.263039068635944773e+01,5.196829750761072546e+02,1.448563331495258122e-01,1.099977468140215642e+01,3.285425830265135093e-03,2.078136182488747249e-02,-4.000000000000000327e-05,-9.999999986750421899e-01,0.000000000000000000e+00 +8.263129979589028551e+01,5.196929750221371478e+02,1.448891873487235527e-01,1.099979357393625534e+01,3.285279844863597375e-03,1.987225229524793371e-02,-4.000000000000000327e-05,-9.999999978398557143e-01,0.000000000000000000e+00 +8.263220890385970563e+01,5.197029749681719295e+02,1.449220400880751602e-01,1.099981163995918720e+01,3.285133859462059658e-03,1.896314432779540662e-02,-4.000000000000000327e-05,-9.999999972975205376e-01,0.000000000000000000e+00 +8.263311801033600545e+01,5.197129749142114861e+02,1.449548913675806350e-01,1.099982887947650667e+01,3.284987874060521940e-03,1.805403785394925006e-02,-4.000000000000000327e-05,-9.999999949072219119e-01,0.000000000000000000e+00 +8.263402711538751078e+01,5.197229748602558175e+02,1.449877411872399768e-01,1.099984529249351972e+01,3.284841888658984223e-03,1.714493280707618181e-02,-4.000000000000000327e-05,-9.999999971250720376e-01,0.000000000000000000e+00 +8.263493621908251896e+01,5.197329748063049237e+02,1.450205895470531858e-01,1.099986087901528542e+01,3.284695903257446505e-03,1.623582911467471787e-02,-4.000000000000000327e-05,-9.999999932121342860e-01,0.000000000000000000e+00 +8.263584532148935580e+01,5.197429747523588048e+02,1.450534364470202342e-01,1.099987563904661059e+01,3.284549917855908788e-03,1.532672671400721505e-02,-4.000000000000000327e-05,-9.999999939224109013e-01,0.000000000000000000e+00 +8.263675442267633287e+01,5.197529746984174608e+02,1.450862818871411497e-01,1.099988957259205868e+01,3.284403932454371070e-03,1.441762553256050947e-02,-4.000000000000000327e-05,-9.999999928148305406e-01,0.000000000000000000e+00 +8.263766352271174753e+01,5.197629746444810053e+02,1.451191258674159323e-01,1.099990267965594093e+01,3.284257947052833353e-03,1.350852550367795911e-02,-4.000000000000000327e-05,-9.999999920452654623e-01,0.000000000000000000e+00 +8.263857262166391138e+01,5.197729745905493246e+02,1.451519683878445544e-01,1.099991496024232163e+01,3.284111961651295635e-03,1.259942655874389007e-02,-4.000000000000000327e-05,-9.999999916198637484e-01,0.000000000000000000e+00 +8.263948171960113598e+01,5.197829745366224188e+02,1.451848094484270435e-01,1.099992641435501639e+01,3.283965976249757918e-03,1.169032862913786490e-02,-4.000000000000000327e-05,-9.999999850962848491e-01,0.000000000000000000e+00 +8.264039081659173291e+01,5.197929744827002878e+02,1.452176490491633998e-01,1.099993704199759215e+01,3.283819990848220200e-03,1.078123165209693250e-02,-4.000000000000000327e-05,-9.999999875254167447e-01,0.000000000000000000e+00 +8.264129991270399955e+01,5.198029744287829317e+02,1.452504871900535954e-01,1.099994684317337246e+01,3.283674005446682483e-03,9.872135551176143553e-03,-4.000000000000000327e-05,-9.999999860160506682e-01,0.000000000000000000e+00 +8.264220900800623326e+01,5.198129743748703504e+02,1.452833238710976582e-01,1.099995581788542509e+01,3.283528020045144765e-03,8.963040261650579918e-03,-4.000000000000000327e-05,-9.999999784233435385e-01,0.000000000000000000e+00 +8.264311810256675983e+01,5.198229743209626577e+02,1.453161590922955604e-01,1.099996396613657268e+01,3.283382034643607048e-03,8.053945720745797968e-03,-4.000000000000000327e-05,-9.999999797970861026e-01,0.000000000000000000e+00 +8.264402719645386242e+01,5.198329742670597398e+02,1.453489928536473297e-01,1.099997128792939449e+01,3.283236049242069330e-03,7.144851852006237070e-03,-4.000000000000000327e-05,-9.999999729460447018e-01,0.000000000000000000e+00 +8.264493628973585260e+01,5.198429742131615967e+02,1.453818251551529384e-01,1.099997778326621400e+01,3.283090063840531612e-03,6.235758594605306064e-03,-4.000000000000000327e-05,-9.999999664710983449e-01,0.000000000000000000e+00 +8.264584538248104195e+01,5.198529741592682285e+02,1.454146559968124142e-01,1.099998345214911311e+01,3.282944078438993895e-03,5.326665879897868501e-03,-4.000000000000000327e-05,-9.999999582258499720e-01,0.000000000000000000e+00 +8.264675447475772785e+01,5.198629741053796351e+02,1.454474853786257293e-01,1.099998829457992500e+01,3.282798093037456177e-03,4.417573641190476741e-03,-4.000000000000000327e-05,-9.999999460634990678e-01,0.000000000000000000e+00 +8.264766356663420765e+01,5.198729740514958166e+02,1.454803133005929117e-01,1.099999231056023596e+01,3.282652107635918460e-03,3.508481813741684205e-03,-4.000000000000000327e-05,-9.999999235380686580e-01,0.000000000000000000e+00 +8.264857265817879295e+01,5.198829739976168867e+02,1.455131397627139334e-01,1.099999550009138716e+01,3.282506122234380742e-03,2.599390338670336600e-03,-4.000000000000000327e-05,-9.999998820537838728e-01,0.000000000000000000e+00 +8.264948174945978110e+01,5.198929739437427315e+02,1.455459647649888222e-01,1.099999786317447992e+01,3.282360136832843025e-03,1.690299164909878213e-03,-4.000000000000000327e-05,-9.999997528315274220e-01,0.000000000000000000e+00 +8.265039084054546947e+01,5.199029738898733513e+02,1.455787883074175504e-01,1.099999939981038288e+01,3.282214151431305307e-03,7.812083039204394119e-04,-4.000000000000000327e-05,-8.594667194226105478e-01,0.000000000000000000e+00 +8.265129993150416965e+01,5.199129738360087458e+02,1.456116103900001180e-01,1.100000010999978883e+01,3.282068166029767590e-03,-1.251200044982454915e-07,-4.000000000000000327e-05,1.376964880789466480e-04,0.000000000000000000e+00 +8.265220902240416478e+01,5.199229737821489152e+02,1.456444310127365527e-01,1.100000010988604338e+01,3.281922180628229872e-03,5.861977628579873417e-11,-4.000000000000000327e-05,-6.663114637714574404e-08,0.000000000000000000e+00 +8.265311811330417413e+01,5.199329737282938595e+02,1.456772501756268268e-01,1.100000010988609667e+01,3.281776195226692155e-03,-1.953992542859967284e-12,-4.000000000000000327e-05,2.149391818617625273e-09,0.000000000000000000e+00 +8.265402720420418348e+01,5.199429736744435786e+02,1.457100678786709402e-01,1.100000010988609489e+01,3.281630209825154437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.265493629510419282e+01,5.199529736205981862e+02,1.457428841218688931e-01,1.100000010988609489e+01,3.281484224423616720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.265584538600420217e+01,5.199629735667575687e+02,1.457756989052206853e-01,1.100000010988609489e+01,3.281338239022079002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.265675447690421151e+01,5.199729735129217261e+02,1.458085122287263447e-01,1.100000010988609489e+01,3.281192253620541285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.265766356780422086e+01,5.199829734590906583e+02,1.458413240923858434e-01,1.100000010988609489e+01,3.281046268219003567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.265857265870423021e+01,5.199929734052643653e+02,1.458741344961991815e-01,1.100000010988609489e+01,3.280900282817465850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.265948174960423955e+01,5.200029733514428472e+02,1.459069434401663590e-01,1.100000010988609489e+01,3.280754297415928132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266039084050424890e+01,5.200129732976261039e+02,1.459397509242873758e-01,1.100000010988609489e+01,3.280608312014390415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266129993140425825e+01,5.200229732438142491e+02,1.459725569485622321e-01,1.100000010988609489e+01,3.280462326612852697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266220902230426759e+01,5.200329731900071693e+02,1.460053615129909277e-01,1.100000010988609489e+01,3.280316341211314980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266311811320427694e+01,5.200429731362048642e+02,1.460381646175734627e-01,1.100000010988609489e+01,3.280170355809777262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266402720410428628e+01,5.200529730824073340e+02,1.460709662623098370e-01,1.100000010988609489e+01,3.280024370408239544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266493629500429563e+01,5.200629730286145787e+02,1.461037664472000508e-01,1.100000010988609489e+01,3.279878385006701827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266584538590430498e+01,5.200729729748265981e+02,1.461365651722441039e-01,1.100000010988609489e+01,3.279732399605164109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266675447680431432e+01,5.200829729210433925e+02,1.461693624374419964e-01,1.100000010988609489e+01,3.279586414203626392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266766356770432367e+01,5.200929728672649617e+02,1.462021582427937283e-01,1.100000010988609489e+01,3.279440428802088674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266857265860433301e+01,5.201029728134913057e+02,1.462349525882992995e-01,1.100000010988609489e+01,3.279294443400550957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.266948174950434236e+01,5.201129727597225383e+02,1.462677454739586824e-01,1.100000010988609489e+01,3.279148457999013239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267039084040435171e+01,5.201229727059585457e+02,1.463005368997719047e-01,1.100000010988609489e+01,3.279002472597475522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267129993130436105e+01,5.201329726521993280e+02,1.463333268657389663e-01,1.100000010988609489e+01,3.278856487195937804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267220902220437040e+01,5.201429725984448851e+02,1.463661153718598673e-01,1.100000010988609489e+01,3.278710501794400087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267311811310437974e+01,5.201529725446952170e+02,1.463989024181345799e-01,1.100000010988609489e+01,3.278564516392862369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267402720400438909e+01,5.201629724909503238e+02,1.464316880045631319e-01,1.100000010988609489e+01,3.278418530991324652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267493629490439844e+01,5.201729724372102055e+02,1.464644721311455233e-01,1.100000010988609489e+01,3.278272545589786934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267584538580440778e+01,5.201829723834748620e+02,1.464972547978817541e-01,1.100000010988609489e+01,3.278126560188249217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267675447670441713e+01,5.201929723297442933e+02,1.465300360047717965e-01,1.100000010988609489e+01,3.277980574786711499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267766356760442648e+01,5.202029722760186132e+02,1.465628157518156782e-01,1.100000010988609489e+01,3.277834589385173782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267857265850443582e+01,5.202129722222977080e+02,1.465955940390133716e-01,1.100000010988609489e+01,3.277688603983636064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.267948174940444517e+01,5.202229721685815775e+02,1.466283708663649044e-01,1.100000010988609489e+01,3.277542618582098347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268039084030445451e+01,5.202329721148702220e+02,1.466611462338702487e-01,1.100000010988609489e+01,3.277396633180560629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268129993120446386e+01,5.202429720611636412e+02,1.466939201415294325e-01,1.100000010988609489e+01,3.277250647779022912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268220902210447321e+01,5.202529720074618353e+02,1.467266925893424279e-01,1.100000010988609489e+01,3.277104662377485194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268311811300448255e+01,5.202629719537648043e+02,1.467594635773092626e-01,1.100000010988609489e+01,3.276958676975947476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268402720390449190e+01,5.202729719000725481e+02,1.467922331054299090e-01,1.100000010988609489e+01,3.276812691574409759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268493629480450124e+01,5.202829718463850668e+02,1.468250011737043947e-01,1.100000010988609489e+01,3.276666706172872041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268584538570451059e+01,5.202929717927023603e+02,1.468577677821326921e-01,1.100000010988609489e+01,3.276520720771334324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268675447660451994e+01,5.203029717390244286e+02,1.468905329307148011e-01,1.100000010988609489e+01,3.276374735369796606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268766356750452928e+01,5.203129716853512718e+02,1.469232966194507495e-01,1.100000010988609489e+01,3.276228749968258889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268857265840453863e+01,5.203229716316828899e+02,1.469560588483405095e-01,1.100000010988609489e+01,3.276082764566721171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.268948174930454798e+01,5.203329715780193965e+02,1.469888196173840811e-01,1.100000010988609489e+01,3.275936779165183454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269039084020455732e+01,5.203429715243606779e+02,1.470215789265814643e-01,1.100000010988609489e+01,3.275790793763645736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269129993110456667e+01,5.203529714707067342e+02,1.470543367759326869e-01,1.100000010988609489e+01,3.275644808362108019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269220902200457601e+01,5.203629714170575653e+02,1.470870931654377212e-01,1.100000010988609489e+01,3.275498822960570301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269311811290458536e+01,5.203729713634131713e+02,1.471198480950965670e-01,1.100000010988609489e+01,3.275352837559032584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269402720380459471e+01,5.203829713097735521e+02,1.471526015649092245e-01,1.100000010988609489e+01,3.275206852157494866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269493629470460405e+01,5.203929712561387078e+02,1.471853535748756936e-01,1.100000010988609489e+01,3.275060866755957149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269584538560461340e+01,5.204029712025086383e+02,1.472181041249959743e-01,1.100000010988609489e+01,3.274914881354419431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269675447650462274e+01,5.204129711488833436e+02,1.472508532152700667e-01,1.100000010988609489e+01,3.274768895952881714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269766356740463209e+01,5.204229710952628238e+02,1.472836008456979706e-01,1.100000010988609489e+01,3.274622910551343996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269857265830464144e+01,5.204329710416470789e+02,1.473163470162796862e-01,1.100000010988609489e+01,3.274476925149806279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.269948174920465078e+01,5.204429709880361088e+02,1.473490917270152134e-01,1.100000010988609489e+01,3.274330939748268561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270039084010466013e+01,5.204529709344299135e+02,1.473818349779045522e-01,1.100000010988609489e+01,3.274184954346730844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270129993100466947e+01,5.204629708808284931e+02,1.474145767689477027e-01,1.100000010988609489e+01,3.274038968945193126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270220902190467882e+01,5.204729708272318476e+02,1.474473171001446647e-01,1.100000010988609489e+01,3.273892983543655408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270311811280468817e+01,5.204829707736399769e+02,1.474800559714954384e-01,1.100000010988609489e+01,3.273746998142117691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270402720370469751e+01,5.204929707200528810e+02,1.475127933830000238e-01,1.100000010988609489e+01,3.273601012740579973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270493629460470686e+01,5.205029706664705600e+02,1.475455293346584207e-01,1.100000010988609489e+01,3.273455027339042256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270584538550471621e+01,5.205129706128930138e+02,1.475782638264706292e-01,1.100000010988609489e+01,3.273309041937504538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270675447640472555e+01,5.205229705593203562e+02,1.476109968584366217e-01,1.100000010988609489e+01,3.273163056535966821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270766356730473490e+01,5.205329705057524734e+02,1.476437284305564257e-01,1.100000010988609489e+01,3.273017071134429103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270857265820474424e+01,5.205429704521893655e+02,1.476764585428300414e-01,1.100000010988609489e+01,3.272871085732891386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.270948174910475359e+01,5.205529703986310324e+02,1.477091871952574686e-01,1.100000010988609489e+01,3.272725100331353668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271039084000476294e+01,5.205629703450774741e+02,1.477419143878386798e-01,1.100000010988609489e+01,3.272579114929815951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271129993090477228e+01,5.205729702915286907e+02,1.477746401205737026e-01,1.100000010988609489e+01,3.272433129528278233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271220902180478163e+01,5.205829702379846822e+02,1.478073643934625370e-01,1.100000010988609489e+01,3.272287144126740516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271311811270479097e+01,5.205929701844454485e+02,1.478400872065051552e-01,1.100000010988609489e+01,3.272141158725202798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271402720360480032e+01,5.206029701309109896e+02,1.478728085597015851e-01,1.100000010988609489e+01,3.271995173323665081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271493629450480967e+01,5.206129700773813056e+02,1.479055284530517989e-01,1.100000010988609489e+01,3.271849187922127363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271584538540481901e+01,5.206229700238563964e+02,1.479382468865558242e-01,1.100000010988609489e+01,3.271703202520589646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271675447630482836e+01,5.206329699703362621e+02,1.479709638602136612e-01,1.100000010988609489e+01,3.271557217119051928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271766356720483770e+01,5.206429699168209027e+02,1.480036793740252821e-01,1.100000010988609489e+01,3.271411231717514211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271857265810484705e+01,5.206529698633103180e+02,1.480363934279906868e-01,1.100000010988609489e+01,3.271265246315976493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.271948174900485640e+01,5.206629698098045083e+02,1.480691060221099031e-01,1.100000010988609489e+01,3.271119260914438776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272039083990486574e+01,5.206729697563034733e+02,1.481018171563829033e-01,1.100000010988609489e+01,3.270973275512901058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272129993080487509e+01,5.206829697028072133e+02,1.481345268308097152e-01,1.100000010988609489e+01,3.270827290111363340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272220902170488444e+01,5.206929696493157280e+02,1.481672350453903109e-01,1.100000010988609489e+01,3.270681304709825623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272311811260489378e+01,5.207029695958290176e+02,1.481999418001246904e-01,1.100000010988609489e+01,3.270535319308287905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272402720350490313e+01,5.207129695423470821e+02,1.482326470950128816e-01,1.100000010988609489e+01,3.270389333906750188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272493629440491247e+01,5.207229694888699214e+02,1.482653509300548567e-01,1.100000010988609489e+01,3.270243348505212470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272584538530492182e+01,5.207329694353975356e+02,1.482980533052506156e-01,1.100000010988609489e+01,3.270097363103674753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272675447620493117e+01,5.207429693819299246e+02,1.483307542206001861e-01,1.100000010988609489e+01,3.269951377702137035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272766356710494051e+01,5.207529693284670884e+02,1.483634536761035405e-01,1.100000010988609489e+01,3.269805392300599318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272857265800494986e+01,5.207629692750090271e+02,1.483961516717606788e-01,1.100000010988609489e+01,3.269659406899061600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.272948174890495920e+01,5.207729692215557407e+02,1.484288482075716009e-01,1.100000010988609489e+01,3.269513421497523883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273039083980496855e+01,5.207829691681072291e+02,1.484615432835363069e-01,1.100000010988609489e+01,3.269367436095986165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273129993070497790e+01,5.207929691146634923e+02,1.484942368996547968e-01,1.100000010988609489e+01,3.269221450694448448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273220902160498724e+01,5.208029690612245304e+02,1.485269290559270705e-01,1.100000010988609489e+01,3.269075465292910730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273311811250499659e+01,5.208129690077903433e+02,1.485596197523531281e-01,1.100000010988609489e+01,3.268929479891373013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273402720340500593e+01,5.208229689543609311e+02,1.485923089889329973e-01,1.100000010988609489e+01,3.268783494489835295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273493629430501528e+01,5.208329689009362937e+02,1.486249967656666504e-01,1.100000010988609489e+01,3.268637509088297578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273584538520502463e+01,5.208429688475164312e+02,1.486576830825540874e-01,1.100000010988609489e+01,3.268491523686759860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273675447610503397e+01,5.208529687941013435e+02,1.486903679395952804e-01,1.100000010988609489e+01,3.268345538285222143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273766356700504332e+01,5.208629687406910307e+02,1.487230513367902573e-01,1.100000010988609489e+01,3.268199552883684425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273857265790505267e+01,5.208729686872854927e+02,1.487557332741390181e-01,1.100000010988609489e+01,3.268053567482146708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.273948174880506201e+01,5.208829686338846159e+02,1.487884137516415628e-01,1.100000010988609489e+01,3.267907582080608990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274039083970507136e+01,5.208929685804885139e+02,1.488210927692978913e-01,1.100000010988609489e+01,3.267761596679071272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274129993060508070e+01,5.209029685270971868e+02,1.488537703271080037e-01,1.100000010988609489e+01,3.267615611277533555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274220902150509005e+01,5.209129684737106345e+02,1.488864464250719000e-01,1.100000010988609489e+01,3.267469625875995837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274311811240509940e+01,5.209229684203288571e+02,1.489191210631895801e-01,1.100000010988609489e+01,3.267323640474458120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274402720330510874e+01,5.209329683669518545e+02,1.489517942414610163e-01,1.100000010988609489e+01,3.267177655072920402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274493629420511809e+01,5.209429683135796267e+02,1.489844659598862364e-01,1.100000010988609489e+01,3.267031669671382685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274584538510512743e+01,5.209529682602121738e+02,1.490171362184652404e-01,1.100000010988609489e+01,3.266885684269844967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274675447600513678e+01,5.209629682068494958e+02,1.490498050171980005e-01,1.100000010988609489e+01,3.266739698868307250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274766356690514613e+01,5.209729681534915926e+02,1.490824723560845444e-01,1.100000010988609489e+01,3.266593713466769532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274857265780515547e+01,5.209829681001384643e+02,1.491151382351248722e-01,1.100000010988609489e+01,3.266447728065231815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.274948174870516482e+01,5.209929680467901107e+02,1.491478026543189561e-01,1.100000010988609489e+01,3.266301742663694097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275039083960517416e+01,5.210029679934465321e+02,1.491804656136668239e-01,1.100000010988609489e+01,3.266155757262156380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275129993050518351e+01,5.210129679401077283e+02,1.492131271131684478e-01,1.100000010988609489e+01,3.266009771860618662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275220902140519286e+01,5.210229678867736993e+02,1.492457871528238555e-01,1.100000010988609489e+01,3.265863786459080945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275311811230520220e+01,5.210329678334444452e+02,1.492784457326330472e-01,1.100000010988609489e+01,3.265717801057543227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275402720320521155e+01,5.210429677801199659e+02,1.493111028525959949e-01,1.100000010988609489e+01,3.265571815656005510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275493629410522090e+01,5.210529677268002615e+02,1.493437585127126987e-01,1.100000010988609489e+01,3.265425830254467792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275584538500523024e+01,5.210629676734853319e+02,1.493764127129831865e-01,1.100000010988609489e+01,3.265279844852930075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275675447590523959e+01,5.210729676201750635e+02,1.494090654534074303e-01,1.100000010988609489e+01,3.265133859451392357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275766356680524893e+01,5.210829675668695700e+02,1.494417167339854580e-01,1.100000010988609489e+01,3.264987874049854640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275857265770525828e+01,5.210929675135688512e+02,1.494743665547172418e-01,1.100000010988609489e+01,3.264841888648316922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.275948174860526763e+01,5.211029674602729074e+02,1.495070149156027817e-01,1.100000010988609489e+01,3.264695903246779204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276039083950527697e+01,5.211129674069817383e+02,1.495396618166421054e-01,1.100000010988609489e+01,3.264549917845241487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276129993040528632e+01,5.211229673536953442e+02,1.495723072578351853e-01,1.100000010988609489e+01,3.264403932443703769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276220902130529566e+01,5.211329673004137248e+02,1.496049512391820213e-01,1.100000010988609489e+01,3.264257947042166052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276311811220530501e+01,5.211429672471368804e+02,1.496375937606826134e-01,1.100000010988609489e+01,3.264111961640628334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276402720310531436e+01,5.211529671938648107e+02,1.496702348223369894e-01,1.100000010988609489e+01,3.263965976239090617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276493629400532370e+01,5.211629671405975159e+02,1.497028744241451215e-01,1.100000010988609489e+01,3.263819990837552899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276584538490533305e+01,5.211729670873349960e+02,1.497355125661070097e-01,1.100000010988609489e+01,3.263674005436015182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276675447580534239e+01,5.211829670340772509e+02,1.497681492482226540e-01,1.100000010988609489e+01,3.263528020034477464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276766356670535174e+01,5.211929669808241670e+02,1.498007844704920544e-01,1.100000010988609489e+01,3.263382034632939747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276857265760536109e+01,5.212029669275758579e+02,1.498334182329152109e-01,1.100000010988609489e+01,3.263236049231402029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.276948174850537043e+01,5.212129668743323236e+02,1.498660505354921235e-01,1.100000010988609489e+01,3.263090063829864312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277039083940537978e+01,5.212229668210935642e+02,1.498986813782227923e-01,1.100000010988609489e+01,3.262944078428326594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277129993030538913e+01,5.212329667678595797e+02,1.499313107611072171e-01,1.100000010988609489e+01,3.262798093026788877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277220902120539847e+01,5.212429667146303700e+02,1.499639386841453981e-01,1.100000010988609489e+01,3.262652107625251159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277311811210540782e+01,5.212529666614059352e+02,1.499965651473373351e-01,1.100000010988609489e+01,3.262506122223713442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277402720300541716e+01,5.212629666081862752e+02,1.500291901506830283e-01,1.100000010988609489e+01,3.262360136822175724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277493629390542651e+01,5.212729665549713900e+02,1.500618136941824776e-01,1.100000010988609489e+01,3.262214151420638007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277584538480543586e+01,5.212829665017612797e+02,1.500944357778356830e-01,1.100000010988609489e+01,3.262068166019100289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277675447570544520e+01,5.212929664485558305e+02,1.501270564016426445e-01,1.100000010988609489e+01,3.261922180617562571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277766356660545455e+01,5.213029663953551562e+02,1.501596755656033622e-01,1.100000010988609489e+01,3.261776195216024854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277857265750546389e+01,5.213129663421592568e+02,1.501922932697178359e-01,1.100000010988609489e+01,3.261630209814487136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.277948174840547324e+01,5.213229662889681322e+02,1.502249095139860380e-01,1.100000010988609489e+01,3.261484224412949419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278039083930548259e+01,5.213329662357817824e+02,1.502575242984079962e-01,1.100000010988609489e+01,3.261338239011411701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278129993020549193e+01,5.213429661826002075e+02,1.502901376229837105e-01,1.100000010988609489e+01,3.261192253609873984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278220902110550128e+01,5.213529661294234074e+02,1.503227494877131809e-01,1.100000010988609489e+01,3.261046268208336266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278311811200551062e+01,5.213629660762513822e+02,1.503553598925963797e-01,1.100000010988609489e+01,3.260900282806798549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278402720290551997e+01,5.213729660230841318e+02,1.503879688376333346e-01,1.100000010988609489e+01,3.260754297405260831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278493629380552932e+01,5.213829659699215426e+02,1.504205763228240456e-01,1.100000010988609489e+01,3.260608312003723114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278584538470553866e+01,5.213929659167637283e+02,1.504531823481684849e-01,1.100000010988609489e+01,3.260462326602185396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278675447560554801e+01,5.214029658636106888e+02,1.504857869136666804e-01,1.100000010988609489e+01,3.260316341200647679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278766356650555736e+01,5.214129658104624241e+02,1.505183900193186042e-01,1.100000010988609489e+01,3.260170355799109961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278857265740556670e+01,5.214229657573189343e+02,1.505509916651242841e-01,1.100000010988609489e+01,3.260024370397572244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.278948174830557605e+01,5.214329657041802193e+02,1.505835918510836924e-01,1.100000010988609489e+01,3.259878384996034526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279039083920558539e+01,5.214429656510462792e+02,1.506161905771968568e-01,1.100000010988609489e+01,3.259732399594496809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279129993010559474e+01,5.214529655979170002e+02,1.506487878434637495e-01,1.100000010988609489e+01,3.259586414192959091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279220902100560409e+01,5.214629655447924961e+02,1.506813836498843984e-01,1.100000010988609489e+01,3.259440428791421374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279311811190561343e+01,5.214729654916727668e+02,1.507139779964587756e-01,1.100000010988609489e+01,3.259294443389883656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279402720280562278e+01,5.214829654385578124e+02,1.507465708831869089e-01,1.100000010988609489e+01,3.259148457988345939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279493629370563212e+01,5.214929653854476328e+02,1.507791623100687706e-01,1.100000010988609489e+01,3.259002472586808221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279584538460564147e+01,5.215029653323422281e+02,1.508117522771043606e-01,1.100000010988609489e+01,3.258856487185270503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279675447550565082e+01,5.215129652792415982e+02,1.508443407842937067e-01,1.100000010988609489e+01,3.258710501783732786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279766356640566016e+01,5.215229652261456295e+02,1.508769278316367812e-01,1.100000010988609489e+01,3.258564516382195068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279857265730566951e+01,5.215329651730544356e+02,1.509095134191335841e-01,1.100000010988609489e+01,3.258418530980657351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.279948174820567885e+01,5.215429651199680166e+02,1.509420975467841153e-01,1.100000010988609489e+01,3.258272545579119633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280039083910568820e+01,5.215529650668863724e+02,1.509746802145883748e-01,1.100000010988609489e+01,3.258126560177581916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280129993000569755e+01,5.215629650138095030e+02,1.510072614225463905e-01,1.100000010988609489e+01,3.257980574776044198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280220902090570689e+01,5.215729649607374085e+02,1.510398411706581345e-01,1.100000010988609489e+01,3.257834589374506481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280311811180571624e+01,5.215829649076699752e+02,1.510724194589236069e-01,1.100000010988609489e+01,3.257688603972968763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280402720270572559e+01,5.215929648546073167e+02,1.511049962873428076e-01,1.100000010988609489e+01,3.257542618571431046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280493629360573493e+01,5.216029648015494331e+02,1.511375716559157367e-01,1.100000010988609489e+01,3.257396633169893328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280584538450574428e+01,5.216129647484963243e+02,1.511701455646423942e-01,1.100000010988609489e+01,3.257250647768355611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280675447540575362e+01,5.216229646954479904e+02,1.512027180135227800e-01,1.100000010988609489e+01,3.257104662366817893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280766356630576297e+01,5.216329646424044313e+02,1.512352890025568941e-01,1.100000010988609489e+01,3.256958676965280176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280857265720577232e+01,5.216429645893655334e+02,1.512678585317447366e-01,1.100000010988609489e+01,3.256812691563742458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.280948174810578166e+01,5.216529645363314103e+02,1.513004266010863075e-01,1.100000010988609489e+01,3.256666706162204741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281039083900579101e+01,5.216629644833020620e+02,1.513329932105816067e-01,1.100000010988609489e+01,3.256520720760667023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281129992990580035e+01,5.216729644302774886e+02,1.513655583602306343e-01,1.100000010988609489e+01,3.256374735359129306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281220902080580970e+01,5.216829643772576901e+02,1.513981220500333902e-01,1.100000010988609489e+01,3.256228749957591588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281311811170581905e+01,5.216929643242425527e+02,1.514306842799898745e-01,1.100000010988609489e+01,3.256082764556053871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281402720260582839e+01,5.217029642712321902e+02,1.514632450501000871e-01,1.100000010988609489e+01,3.255936779154516153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281493629350583774e+01,5.217129642182266025e+02,1.514958043603640003e-01,1.100000010988609489e+01,3.255790793752978435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281584538440584708e+01,5.217229641652257897e+02,1.515283622107816419e-01,1.100000010988609489e+01,3.255644808351440718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281675447530585643e+01,5.217329641122297517e+02,1.515609186013530119e-01,1.100000010988609489e+01,3.255498822949903000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281766356620586578e+01,5.217429640592384885e+02,1.515934735320781102e-01,1.100000010988609489e+01,3.255352837548365283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281857265710587512e+01,5.217529640062518865e+02,1.516260270029569091e-01,1.100000010988609489e+01,3.255206852146827565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.281948174800588447e+01,5.217629639532700594e+02,1.516585790139894363e-01,1.100000010988609489e+01,3.255060866745289848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282039083890589382e+01,5.217729639002930071e+02,1.516911295651756919e-01,1.100000010988609489e+01,3.254914881343752130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282129992980590316e+01,5.217829638473207297e+02,1.517236786565156481e-01,1.100000010988609489e+01,3.254768895942214413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282220902070591251e+01,5.217929637943532271e+02,1.517562262880093327e-01,1.100000010988609489e+01,3.254622910540676695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282311811160592185e+01,5.218029637413903856e+02,1.517887724596567456e-01,1.100000010988609489e+01,3.254476925139138978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282402720250593120e+01,5.218129636884323190e+02,1.518213171714578591e-01,1.100000010988609489e+01,3.254330939737601260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282493629340594055e+01,5.218229636354790273e+02,1.518538604234127010e-01,1.100000010988609489e+01,3.254184954336063543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282584538430594989e+01,5.218329635825305104e+02,1.518864022155212434e-01,1.100000010988609489e+01,3.254038968934525825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282675447520595924e+01,5.218429635295866547e+02,1.519189425477835143e-01,1.100000010988609489e+01,3.253892983532988108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282766356610596858e+01,5.218529634766475738e+02,1.519514814201994857e-01,1.100000010988609489e+01,3.253746998131450390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282857265700597793e+01,5.218629634237132677e+02,1.519840188327691854e-01,1.100000010988609489e+01,3.253601012729912673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.282948174790598728e+01,5.218729633707837365e+02,1.520165547854925858e-01,1.100000010988609489e+01,3.253455027328374955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283039083880599662e+01,5.218829633178589802e+02,1.520490892783696868e-01,1.100000010988609489e+01,3.253309041926837238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283129992970600597e+01,5.218929632649388850e+02,1.520816223114005161e-01,1.100000010988609489e+01,3.253163056525299520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283220902060601532e+01,5.219029632120235647e+02,1.521141538845850461e-01,1.100000010988609489e+01,3.253017071123761803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283311811150602466e+01,5.219129631591130192e+02,1.521466839979232766e-01,1.100000010988609489e+01,3.252871085722224085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283402720240603401e+01,5.219229631062072485e+02,1.521792126514152355e-01,1.100000010988609489e+01,3.252725100320686367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283493629330604335e+01,5.219329630533061390e+02,1.522117398450608949e-01,1.100000010988609489e+01,3.252579114919148650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283584538420605270e+01,5.219429630004098044e+02,1.522442655788602550e-01,1.100000010988609489e+01,3.252433129517610932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283675447510606205e+01,5.219529629475182446e+02,1.522767898528133157e-01,1.100000010988609489e+01,3.252287144116073215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283766356600607139e+01,5.219629628946314597e+02,1.523093126669200770e-01,1.100000010988609489e+01,3.252141158714535497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283857265690608074e+01,5.219729628417494496e+02,1.523418340211805666e-01,1.100000010988609489e+01,3.251995173312997780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.283948174780609008e+01,5.219829627888721006e+02,1.523743539155947568e-01,1.100000010988609489e+01,3.251849187911460062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284039083870609943e+01,5.219929627359995266e+02,1.524068723501626477e-01,1.100000010988609489e+01,3.251703202509922345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284129992960610878e+01,5.220029626831317273e+02,1.524393893248842391e-01,1.100000010988609489e+01,3.251557217108384627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284220902050611812e+01,5.220129626302687029e+02,1.524719048397595311e-01,1.100000010988609489e+01,3.251411231706846910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284311811140612747e+01,5.220229625774103397e+02,1.525044188947885238e-01,1.100000010988609489e+01,3.251265246305309192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284402720230613681e+01,5.220329625245567513e+02,1.525369314899712170e-01,1.100000010988609489e+01,3.251119260903771475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284493629320614616e+01,5.220429624717079378e+02,1.525694426253076108e-01,1.100000010988609489e+01,3.250973275502233757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284584538410615551e+01,5.220529624188638991e+02,1.526019523007977052e-01,1.100000010988609489e+01,3.250827290100696040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284675447500616485e+01,5.220629623660245215e+02,1.526344605164415003e-01,1.100000010988609489e+01,3.250681304699158322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284766356590617420e+01,5.220729623131899189e+02,1.526669672722389959e-01,1.100000010988609489e+01,3.250535319297620605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284857265680618355e+01,5.220829622603600910e+02,1.526994725681901921e-01,1.100000010988609489e+01,3.250389333896082887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.284948174770619289e+01,5.220929622075350380e+02,1.527319764042950889e-01,1.100000010988609489e+01,3.250243348494545170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285039083860620224e+01,5.221029621547146462e+02,1.527644787805536586e-01,1.100000010988609489e+01,3.250097363093007452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285129992950621158e+01,5.221129621018990292e+02,1.527969796969659289e-01,1.100000010988609489e+01,3.249951377691469735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285220902040622093e+01,5.221229620490881871e+02,1.528294791535318997e-01,1.100000010988609489e+01,3.249805392289932017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285311811130623028e+01,5.221329619962820061e+02,1.528619771502515712e-01,1.100000010988609489e+01,3.249659406888394299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285402720220623962e+01,5.221429619434806000e+02,1.528944736871249155e-01,1.100000010988609489e+01,3.249513421486856582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285493629310624897e+01,5.221529618906839687e+02,1.529269687641519604e-01,1.100000010988609489e+01,3.249367436085318864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285584538400625831e+01,5.221629618378921123e+02,1.529594623813327059e-01,1.100000010988609489e+01,3.249221450683781147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285675447490626766e+01,5.221729617851049170e+02,1.529919545386671520e-01,1.100000010988609489e+01,3.249075465282243429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285766356580627701e+01,5.221829617323224966e+02,1.530244452361552709e-01,1.100000010988609489e+01,3.248929479880705712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285857265670628635e+01,5.221929616795448510e+02,1.530569344737970905e-01,1.100000010988609489e+01,3.248783494479167994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.285948174760629570e+01,5.222029616267719803e+02,1.530894222515925829e-01,1.100000010988609489e+01,3.248637509077630277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286039083850630504e+01,5.222129615740037707e+02,1.531219085695417759e-01,1.100000010988609489e+01,3.248491523676092559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286129992940631439e+01,5.222229615212403360e+02,1.531543934276446417e-01,1.100000010988609489e+01,3.248345538274554842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286220902030632374e+01,5.222329614684816761e+02,1.531868768259012081e-01,1.100000010988609489e+01,3.248199552873017124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286311811120633308e+01,5.222429614157276774e+02,1.532193587643114474e-01,1.100000010988609489e+01,3.248053567471479407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286402720210634243e+01,5.222529613629784535e+02,1.532518392428753873e-01,1.100000010988609489e+01,3.247907582069941689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286493629300635178e+01,5.222629613102340045e+02,1.532843182615930000e-01,1.100000010988609489e+01,3.247761596668403972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286584538390636112e+01,5.222729612574943303e+02,1.533167958204643133e-01,1.100000010988609489e+01,3.247615611266866254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286675447480637047e+01,5.222829612047593173e+02,1.533492719194892995e-01,1.100000010988609489e+01,3.247469625865328537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286766356570637981e+01,5.222929611520290791e+02,1.533817465586679862e-01,1.100000010988609489e+01,3.247323640463790819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286857265660638916e+01,5.223029610993036158e+02,1.534142197380003458e-01,1.100000010988609489e+01,3.247177655062253102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.286948174750639851e+01,5.223129610465828137e+02,1.534466914574863783e-01,1.100000010988609489e+01,3.247031669660715384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287039083840640785e+01,5.223229609938667863e+02,1.534791617171260836e-01,1.100000010988609489e+01,3.246885684259177667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287129992930641720e+01,5.223329609411555339e+02,1.535116305169194895e-01,1.100000010988609489e+01,3.246739698857639949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287220902020642654e+01,5.223429608884489426e+02,1.535440978568665682e-01,1.100000010988609489e+01,3.246593713456102231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287311811110643589e+01,5.223529608357471261e+02,1.535765637369673198e-01,1.100000010988609489e+01,3.246447728054564514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287402720200644524e+01,5.223629607830500845e+02,1.536090281572217442e-01,1.100000010988609489e+01,3.246301742653026796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287493629290645458e+01,5.223729607303577041e+02,1.536414911176298415e-01,1.100000010988609489e+01,3.246155757251489079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287584538380646393e+01,5.223829606776700984e+02,1.536739526181916393e-01,1.100000010988609489e+01,3.246009771849951361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287675447470647327e+01,5.223929606249872677e+02,1.537064126589071100e-01,1.100000010988609489e+01,3.245863786448413644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287766356560648262e+01,5.224029605723092118e+02,1.537388712397762536e-01,1.100000010988609489e+01,3.245717801046875926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287857265650649197e+01,5.224129605196358170e+02,1.537713283607990700e-01,1.100000010988609489e+01,3.245571815645338209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.287948174740650131e+01,5.224229604669671971e+02,1.538037840219755592e-01,1.100000010988609489e+01,3.245425830243800491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288039083830651066e+01,5.224329604143033521e+02,1.538362382233057213e-01,1.100000010988609489e+01,3.245279844842262774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288129992920652001e+01,5.224429603616441682e+02,1.538686909647895562e-01,1.100000010988609489e+01,3.245133859440725056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288220902010652935e+01,5.224529603089897591e+02,1.539011422464270640e-01,1.100000010988609489e+01,3.244987874039187339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288311811100653870e+01,5.224629602563401249e+02,1.539335920682182446e-01,1.100000010988609489e+01,3.244841888637649621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288402720190654804e+01,5.224729602036951519e+02,1.539660404301630980e-01,1.100000010988609489e+01,3.244695903236111904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288493629280655739e+01,5.224829601510549537e+02,1.539984873322616243e-01,1.100000010988609489e+01,3.244549917834574186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288584538370656674e+01,5.224929600984195304e+02,1.540309327745137957e-01,1.100000010988609489e+01,3.244403932433036469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288675447460657608e+01,5.225029600457887682e+02,1.540633767569196400e-01,1.100000010988609489e+01,3.244257947031498751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288766356550658543e+01,5.225129599931627808e+02,1.540958192794791570e-01,1.100000010988609489e+01,3.244111961629961034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288857265640659477e+01,5.225229599405415684e+02,1.541282603421923469e-01,1.100000010988609489e+01,3.243965976228423316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.288948174730660412e+01,5.225329598879250170e+02,1.541606999450592097e-01,1.100000010988609489e+01,3.243819990826885599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289039083820661347e+01,5.225429598353132405e+02,1.541931380880797176e-01,1.100000010988609489e+01,3.243674005425347881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289129992910662281e+01,5.225529597827061252e+02,1.542255747712538982e-01,1.100000010988609489e+01,3.243528020023810163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289220902000663216e+01,5.225629597301037848e+02,1.542580099945817518e-01,1.100000010988609489e+01,3.243382034622272446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289311811090664150e+01,5.225729596775062191e+02,1.542904437580632504e-01,1.100000010988609489e+01,3.243236049220734728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289402720180665085e+01,5.225829596249133147e+02,1.543228760616984219e-01,1.100000010988609489e+01,3.243090063819197011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289493629270666020e+01,5.225929595723251850e+02,1.543553069054872662e-01,1.100000010988609489e+01,3.242944078417659293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289584538360666954e+01,5.226029595197418303e+02,1.543877362894297556e-01,1.100000010988609489e+01,3.242798093016121576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289675447450667889e+01,5.226129594671631367e+02,1.544201642135259178e-01,1.100000010988609489e+01,3.242652107614583858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289766356540668824e+01,5.226229594145892179e+02,1.544525906777757251e-01,1.100000010988609489e+01,3.242506122213046141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289857265630669758e+01,5.226329593620200740e+02,1.544850156821792053e-01,1.100000010988609489e+01,3.242360136811508423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.289948174720670693e+01,5.226429593094555912e+02,1.545174392267363306e-01,1.100000010988609489e+01,3.242214151409970706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290039083810671627e+01,5.226529592568958833e+02,1.545498613114471287e-01,1.100000010988609489e+01,3.242068166008432988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290129992900672562e+01,5.226629592043409502e+02,1.545822819363115719e-01,1.100000010988609489e+01,3.241922180606895271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290220901990673497e+01,5.226729591517906783e+02,1.546147011013296879e-01,1.100000010988609489e+01,3.241776195205357553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290311811080674431e+01,5.226829590992451813e+02,1.546471188065014490e-01,1.100000010988609489e+01,3.241630209803819836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290402720170675366e+01,5.226929590467043454e+02,1.546795350518268553e-01,1.100000010988609489e+01,3.241484224402282118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290493629260676300e+01,5.227029589941682843e+02,1.547119498373059343e-01,1.100000010988609489e+01,3.241338239000744401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290584538350677235e+01,5.227129589416369981e+02,1.547443631629386585e-01,1.100000010988609489e+01,3.241192253599206683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290675447440678170e+01,5.227229588891103731e+02,1.547767750287250277e-01,1.100000010988609489e+01,3.241046268197668966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290766356530679104e+01,5.227329588365885229e+02,1.548091854346650698e-01,1.100000010988609489e+01,3.240900282796131248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290857265620680039e+01,5.227429587840714476e+02,1.548415943807587569e-01,1.100000010988609489e+01,3.240754297394593531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.290948174710680973e+01,5.227529587315590334e+02,1.548740018670060892e-01,1.100000010988609489e+01,3.240608311993055813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291039083800681908e+01,5.227629586790513940e+02,1.549064078934070665e-01,1.100000010988609489e+01,3.240462326591518095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291129992890682843e+01,5.227729586265484159e+02,1.549388124599616889e-01,1.100000010988609489e+01,3.240316341189980378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291220901980683777e+01,5.227829585740502125e+02,1.549712155666699842e-01,1.100000010988609489e+01,3.240170355788442660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291311811070684712e+01,5.227929585215567840e+02,1.550036172135319246e-01,1.100000010988609489e+01,3.240024370386904943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291402720160685647e+01,5.228029584690680167e+02,1.550360174005475100e-01,1.100000010988609489e+01,3.239878384985367225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291493629250686581e+01,5.228129584165840242e+02,1.550684161277167405e-01,1.100000010988609489e+01,3.239732399583829508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291584538340687516e+01,5.228229583641046929e+02,1.551008133950396162e-01,1.100000010988609489e+01,3.239586414182291790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291675447430688450e+01,5.228329583116301364e+02,1.551332092025161369e-01,1.100000010988609489e+01,3.239440428780754073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291766356520689385e+01,5.228429582591603548e+02,1.551656035501463027e-01,1.100000010988609489e+01,3.239294443379216355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291857265610690320e+01,5.228529582066952344e+02,1.551979964379301136e-01,1.100000010988609489e+01,3.239148457977678638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.291948174700691254e+01,5.228629581542348888e+02,1.552303878658675695e-01,1.100000010988609489e+01,3.239002472576140920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292039083790692189e+01,5.228729581017792043e+02,1.552627778339586706e-01,1.100000010988609489e+01,3.238856487174603203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292129992880693123e+01,5.228829580493282947e+02,1.552951663422034168e-01,1.100000010988609489e+01,3.238710501773065485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292220901970694058e+01,5.228929579968821599e+02,1.553275533906017802e-01,1.100000010988609489e+01,3.238564516371527768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292311811060694993e+01,5.229029579444406863e+02,1.553599389791537888e-01,1.100000010988609489e+01,3.238418530969990050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292402720150695927e+01,5.229129578920039876e+02,1.553923231078594425e-01,1.100000010988609489e+01,3.238272545568452333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292493629240696862e+01,5.229229578395719500e+02,1.554247057767187412e-01,1.100000010988609489e+01,3.238126560166914615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292584538330697796e+01,5.229329577871446872e+02,1.554570869857316850e-01,1.100000010988609489e+01,3.237980574765376898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292675447420698731e+01,5.229429577347220857e+02,1.554894667348982462e-01,1.100000010988609489e+01,3.237834589363839180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292766356510699666e+01,5.229529576823042589e+02,1.555218450242184525e-01,1.100000010988609489e+01,3.237688603962301463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292857265600700600e+01,5.229629576298912070e+02,1.555542218536923038e-01,1.100000010988609489e+01,3.237542618560763745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.292948174690701535e+01,5.229729575774828163e+02,1.555865972233197725e-01,1.100000010988609489e+01,3.237396633159226027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293039083780702470e+01,5.229829575250792004e+02,1.556189711331008863e-01,1.100000010988609489e+01,3.237250647757688310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293129992870703404e+01,5.229929574726802457e+02,1.556513435830356451e-01,1.100000010988609489e+01,3.237104662356150592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293220901960704339e+01,5.230029574202860658e+02,1.556837145731240213e-01,1.100000010988609489e+01,3.236958676954612875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293311811050705273e+01,5.230129573678966608e+02,1.557160841033660426e-01,1.100000010988609489e+01,3.236812691553075157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293402720140706208e+01,5.230229573155119169e+02,1.557484521737616812e-01,1.100000010988609489e+01,3.236666706151537440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293493629230707143e+01,5.230329572631319479e+02,1.557808187843109649e-01,1.100000010988609489e+01,3.236520720749999722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293584538320708077e+01,5.230429572107566401e+02,1.558131839350138659e-01,1.100000010988609489e+01,3.236374735348462005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293675447410709012e+01,5.230529571583861070e+02,1.558455476258704120e-01,1.100000010988609489e+01,3.236228749946924287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293766356500709946e+01,5.230629571060202352e+02,1.558779098568805754e-01,1.100000010988609489e+01,3.236082764545386570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293857265590710881e+01,5.230729570536591382e+02,1.559102706280443840e-01,1.100000010988609489e+01,3.235936779143848852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.293948174680711816e+01,5.230829570013027023e+02,1.559426299393618098e-01,1.100000010988609489e+01,3.235790793742311135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294039083770712750e+01,5.230929569489510413e+02,1.559749877908328808e-01,1.100000010988609489e+01,3.235644808340773417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294129992860713685e+01,5.231029568966041552e+02,1.560073441824575691e-01,1.100000010988609489e+01,3.235498822939235700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294220901950714619e+01,5.231129568442619302e+02,1.560396991142358747e-01,1.100000010988609489e+01,3.235352837537697982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294311811040715554e+01,5.231229567919244801e+02,1.560720525861678254e-01,1.100000010988609489e+01,3.235206852136160265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294402720130716489e+01,5.231329567395916911e+02,1.561044045982533934e-01,1.100000010988609489e+01,3.235060866734622547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294493629220717423e+01,5.231429566872636769e+02,1.561367551504925788e-01,1.100000010988609489e+01,3.234914881333084830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294584538310718358e+01,5.231529566349403240e+02,1.561691042428853815e-01,1.100000010988609489e+01,3.234768895931547112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294675447400719293e+01,5.231629565826217458e+02,1.562014518754318015e-01,1.100000010988609489e+01,3.234622910530009395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294766356490720227e+01,5.231729565303078289e+02,1.562337980481318667e-01,1.100000010988609489e+01,3.234476925128471677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294857265580721162e+01,5.231829564779986868e+02,1.562661427609855491e-01,1.100000010988609489e+01,3.234330939726933959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.294948174670722096e+01,5.231929564256942058e+02,1.562984860139928489e-01,1.100000010988609489e+01,3.234184954325396242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295039083760723031e+01,5.232029563733944997e+02,1.563308278071537660e-01,1.100000010988609489e+01,3.234038968923858524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295129992850723966e+01,5.232129563210994547e+02,1.563631681404683005e-01,1.100000010988609489e+01,3.233892983522320807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295220901940724900e+01,5.232229562688091846e+02,1.563955070139364523e-01,1.100000010988609489e+01,3.233746998120783089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295311811030725835e+01,5.232329562165235757e+02,1.564278444275582214e-01,1.100000010988609489e+01,3.233601012719245372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295402720120726769e+01,5.232429561642427416e+02,1.564601803813336078e-01,1.100000010988609489e+01,3.233455027317707654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295493629210727704e+01,5.232529561119666823e+02,1.564925148752626116e-01,1.100000010988609489e+01,3.233309041916169937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295584538300728639e+01,5.232629560596952842e+02,1.565248479093452327e-01,1.100000010988609489e+01,3.233163056514632219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295675447390729573e+01,5.232729560074286610e+02,1.565571794835814712e-01,1.100000010988609489e+01,3.233017071113094502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295766356480730508e+01,5.232829559551666989e+02,1.565895095979713270e-01,1.100000010988609489e+01,3.232871085711556784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295857265570731442e+01,5.232929559029095117e+02,1.566218382525148001e-01,1.100000010988609489e+01,3.232725100310019067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.295948174660732377e+01,5.233029558506569856e+02,1.566541654472118905e-01,1.100000010988609489e+01,3.232579114908481349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296039083750733312e+01,5.233129557984092344e+02,1.566864911820625705e-01,1.100000010988609489e+01,3.232433129506943632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296129992840734246e+01,5.233229557461661443e+02,1.567188154570668679e-01,1.100000010988609489e+01,3.232287144105405914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296220901930735181e+01,5.233329556939278291e+02,1.567511382722247826e-01,1.100000010988609489e+01,3.232141158703868197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296311811020736116e+01,5.233429556416941750e+02,1.567834596275363146e-01,1.100000010988609489e+01,3.231995173302330479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296402720110737050e+01,5.233529555894652958e+02,1.568157795230014362e-01,1.100000010988609489e+01,3.231849187900792762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296493629200737985e+01,5.233629555372410778e+02,1.568480979586201751e-01,1.100000010988609489e+01,3.231703202499255044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296584538290738919e+01,5.233729554850216346e+02,1.568804149343925314e-01,1.100000010988609489e+01,3.231557217097717326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296675447380739854e+01,5.233829554328068525e+02,1.569127304503184772e-01,1.100000010988609489e+01,3.231411231696179609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296766356470740789e+01,5.233929553805968453e+02,1.569450445063980404e-01,1.100000010988609489e+01,3.231265246294641891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296857265560741723e+01,5.234029553283914993e+02,1.569773571026312209e-01,1.100000010988609489e+01,3.231119260893104174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.296948174650742658e+01,5.234129552761909281e+02,1.570096682390179910e-01,1.100000010988609489e+01,3.230973275491566456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297039083740743592e+01,5.234229552239950181e+02,1.570419779155583784e-01,1.100000010988609489e+01,3.230827290090028739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297129992830744527e+01,5.234329551718038829e+02,1.570742861322523554e-01,1.100000010988609489e+01,3.230681304688491021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297220901920745462e+01,5.234429551196174089e+02,1.571065928890999497e-01,1.100000010988609489e+01,3.230535319286953304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297311811010746396e+01,5.234529550674357097e+02,1.571388981861011336e-01,1.100000010988609489e+01,3.230389333885415586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297402720100747331e+01,5.234629550152586717e+02,1.571712020232559348e-01,1.100000010988609489e+01,3.230243348483877869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297493629190748266e+01,5.234729549630864085e+02,1.572035044005643256e-01,1.100000010988609489e+01,3.230097363082340151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297584538280749200e+01,5.234829549109188065e+02,1.572358053180263338e-01,1.100000010988609489e+01,3.229951377680802434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297675447370750135e+01,5.234929548587558656e+02,1.572681047756419315e-01,1.100000010988609489e+01,3.229805392279264716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297766356460751069e+01,5.235029548065976996e+02,1.573004027734111188e-01,1.100000010988609489e+01,3.229659406877726999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297857265550752004e+01,5.235129547544441948e+02,1.573326993113339234e-01,1.100000010988609489e+01,3.229513421476189281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.297948174640752939e+01,5.235229547022954648e+02,1.573649943894103176e-01,1.100000010988609489e+01,3.229367436074651564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298039083730753873e+01,5.235329546501513960e+02,1.573972880076403014e-01,1.100000010988609489e+01,3.229221450673113846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298129992820754808e+01,5.235429545980121020e+02,1.574295801660238747e-01,1.100000010988609489e+01,3.229075465271576129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298220901910755742e+01,5.235529545458774692e+02,1.574618708645610654e-01,1.100000010988609489e+01,3.228929479870038411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298311811000756677e+01,5.235629544937476112e+02,1.574941601032518457e-01,1.100000010988609489e+01,3.228783494468500694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298402720090757612e+01,5.235729544416224144e+02,1.575264478820962155e-01,1.100000010988609489e+01,3.228637509066962976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298493629180758546e+01,5.235829543895019924e+02,1.575587342010941749e-01,1.100000010988609489e+01,3.228491523665425258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298584538270759481e+01,5.235929543373862316e+02,1.575910190602457239e-01,1.100000010988609489e+01,3.228345538263887541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298675447360760415e+01,5.236029542852752456e+02,1.576233024595508625e-01,1.100000010988609489e+01,3.228199552862349823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298766356450761350e+01,5.236129542331689208e+02,1.576555843990095906e-01,1.100000010988609489e+01,3.228053567460812106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298857265540762285e+01,5.236229541810673709e+02,1.576878648786219361e-01,1.100000010988609489e+01,3.227907582059274388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.298948174630763219e+01,5.236329541289704821e+02,1.577201438983878712e-01,1.100000010988609489e+01,3.227761596657736671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299039083720764154e+01,5.236429540768782545e+02,1.577524214583073958e-01,1.100000010988609489e+01,3.227615611256198953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299129992810765089e+01,5.236529540247908017e+02,1.577846975583805100e-01,1.100000010988609489e+01,3.227469625854661236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299220901900766023e+01,5.236629539727080100e+02,1.578169721986071861e-01,1.100000010988609489e+01,3.227323640453123518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299311810990766958e+01,5.236729539206299933e+02,1.578492453789874517e-01,1.100000010988609489e+01,3.227177655051585801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299402720080767892e+01,5.236829538685566376e+02,1.578815170995213069e-01,1.100000010988609489e+01,3.227031669650048083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299493629170768827e+01,5.236929538164880569e+02,1.579137873602087516e-01,1.100000010988609489e+01,3.226885684248510366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299584538260769762e+01,5.237029537644241373e+02,1.579460561610497860e-01,1.100000010988609489e+01,3.226739698846972648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299675447350770696e+01,5.237129537123649925e+02,1.579783235020444099e-01,1.100000010988609489e+01,3.226593713445434931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299766356440771631e+01,5.237229536603105089e+02,1.580105893831926234e-01,1.100000010988609489e+01,3.226447728043897213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299857265530772565e+01,5.237329536082606865e+02,1.580428538044943987e-01,1.100000010988609489e+01,3.226301742642359496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.299948174620773500e+01,5.237429535562156389e+02,1.580751167659497636e-01,1.100000010988609489e+01,3.226155757240821778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300039083710774435e+01,5.237529535041752524e+02,1.581073782675587180e-01,1.100000010988609489e+01,3.226009771839284061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300129992800775369e+01,5.237629534521396408e+02,1.581396383093212621e-01,1.100000010988609489e+01,3.225863786437746343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300220901890776304e+01,5.237729534001086904e+02,1.581718968912373680e-01,1.100000010988609489e+01,3.225717801036208626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300311810980777238e+01,5.237829533480825148e+02,1.582041540133070634e-01,1.100000010988609489e+01,3.225571815634670908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300402720070778173e+01,5.237929532960610004e+02,1.582364096755303484e-01,1.100000010988609489e+01,3.225425830233133190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300493629160779108e+01,5.238029532440441471e+02,1.582686638779071953e-01,1.100000010988609489e+01,3.225279844831595473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300584538250780042e+01,5.238129531920320687e+02,1.583009166204376317e-01,1.100000010988609489e+01,3.225133859430057755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300675447340780977e+01,5.238229531400246515e+02,1.583331679031216299e-01,1.100000010988609489e+01,3.224987874028520038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300766356430781912e+01,5.238329530880220091e+02,1.583654177259592177e-01,1.100000010988609489e+01,3.224841888626982320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300857265520782846e+01,5.238429530360240278e+02,1.583976660889503674e-01,1.100000010988609489e+01,3.224695903225444603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.300948174610783781e+01,5.238529529840307077e+02,1.584299129920951066e-01,1.100000010988609489e+01,3.224549917823906885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301039083700784715e+01,5.238629529320421625e+02,1.584621584353934076e-01,1.100000010988609489e+01,3.224403932422369168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301129992790785650e+01,5.238729528800582784e+02,1.584944024188452982e-01,1.100000010988609489e+01,3.224257947020831450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301220901880786585e+01,5.238829528280791692e+02,1.585266449424507507e-01,1.100000010988609489e+01,3.224111961619293733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301311810970787519e+01,5.238929527761047211e+02,1.585588860062097927e-01,1.100000010988609489e+01,3.223965976217756015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301402720060788454e+01,5.239029527241349342e+02,1.585911256101223965e-01,1.100000010988609489e+01,3.223819990816218298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301493629150789388e+01,5.239129526721699222e+02,1.586233637541885622e-01,1.100000010988609489e+01,3.223674005414680580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301584538240790323e+01,5.239229526202095713e+02,1.586556004384083174e-01,1.100000010988609489e+01,3.223528020013142863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301675447330791258e+01,5.239329525682539952e+02,1.586878356627816344e-01,1.100000010988609489e+01,3.223382034611605145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301766356420792192e+01,5.239429525163030803e+02,1.587200694273085133e-01,1.100000010988609489e+01,3.223236049210067428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301857265510793127e+01,5.239529524643568266e+02,1.587523017319889540e-01,1.100000010988609489e+01,3.223090063808529710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.301948174600794061e+01,5.239629524124153477e+02,1.587845325768229843e-01,1.100000010988609489e+01,3.222944078406991993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302039083690794996e+01,5.239729523604785300e+02,1.588167619618105764e-01,1.100000010988609489e+01,3.222798093005454275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302129992780795931e+01,5.239829523085464871e+02,1.588489898869517303e-01,1.100000010988609489e+01,3.222652107603916558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302220901870796865e+01,5.239929522566191054e+02,1.588812163522464460e-01,1.100000010988609489e+01,3.222506122202378840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302311810960797800e+01,5.240029522046963848e+02,1.589134413576947236e-01,1.100000010988609489e+01,3.222360136800841122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302402720050798735e+01,5.240129521527784391e+02,1.589456649032965629e-01,1.100000010988609489e+01,3.222214151399303405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302493629140799669e+01,5.240229521008651545e+02,1.589778869890519641e-01,1.100000010988609489e+01,3.222068165997765687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302584538230800604e+01,5.240329520489565311e+02,1.590101076149609272e-01,1.100000010988609489e+01,3.221922180596227970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302675447320801538e+01,5.240429519970526826e+02,1.590423267810234520e-01,1.100000010988609489e+01,3.221776195194690252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302766356410802473e+01,5.240529519451534952e+02,1.590745444872395387e-01,1.100000010988609489e+01,3.221630209793152535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302857265500803408e+01,5.240629518932590827e+02,1.591067607336091871e-01,1.100000010988609489e+01,3.221484224391614817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.302948174590804342e+01,5.240729518413693313e+02,1.591389755201323974e-01,1.100000010988609489e+01,3.221338238990077100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303039083680805277e+01,5.240829517894842411e+02,1.591711888468091696e-01,1.100000010988609489e+01,3.221192253588539382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303129992770806211e+01,5.240929517376039257e+02,1.592034007136395035e-01,1.100000010988609489e+01,3.221046268187001665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303220901860807146e+01,5.241029516857282715e+02,1.592356111206233993e-01,1.100000010988609489e+01,3.220900282785463947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303311810950808081e+01,5.241129516338572785e+02,1.592678200677608569e-01,1.100000010988609489e+01,3.220754297383926230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303402720040809015e+01,5.241229515819910603e+02,1.593000275550518763e-01,1.100000010988609489e+01,3.220608311982388512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303493629130809950e+01,5.241329515301295032e+02,1.593322335824964298e-01,1.100000010988609489e+01,3.220462326580850795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303584538220810884e+01,5.241429514782726073e+02,1.593644381500945451e-01,1.100000010988609489e+01,3.220316341179313077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303675447310811819e+01,5.241529514264204863e+02,1.593966412578462222e-01,1.100000010988609489e+01,3.220170355777775360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303766356400812754e+01,5.241629513745730264e+02,1.594288429057514611e-01,1.100000010988609489e+01,3.220024370376237642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303857265490813688e+01,5.241729513227303414e+02,1.594610430938102341e-01,1.100000010988609489e+01,3.219878384974699925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.303948174580814623e+01,5.241829512708923176e+02,1.594932418220225689e-01,1.100000010988609489e+01,3.219732399573162207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304039083670815558e+01,5.241929512190589548e+02,1.595254390903884656e-01,1.100000010988609489e+01,3.219586414171624490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304129992760816492e+01,5.242029511672303670e+02,1.595576348989078963e-01,1.100000010988609489e+01,3.219440428770086772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304220901850817427e+01,5.242129511154064403e+02,1.595898292475808888e-01,1.100000010988609489e+01,3.219294443368549054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304311810940818361e+01,5.242229510635871748e+02,1.596220221364074154e-01,1.100000010988609489e+01,3.219148457967011337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304402720030819296e+01,5.242329510117726841e+02,1.596542135653875039e-01,1.100000010988609489e+01,3.219002472565473619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304493629120820231e+01,5.242429509599628545e+02,1.596864035345211263e-01,1.100000010988609489e+01,3.218856487163935902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304584538210821165e+01,5.242529509081576862e+02,1.597185920438083107e-01,1.100000010988609489e+01,3.218710501762398184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304675447300822100e+01,5.242629508563572927e+02,1.597507790932490290e-01,1.100000010988609489e+01,3.218564516360860467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304766356390823034e+01,5.242729508045615603e+02,1.597829646828433092e-01,1.100000010988609489e+01,3.218418530959322749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304857265480823969e+01,5.242829507527704891e+02,1.598151488125911235e-01,1.100000010988609489e+01,3.218272545557785032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.304948174570824904e+01,5.242929507009841927e+02,1.598473314824924996e-01,1.100000010988609489e+01,3.218126560156247314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305039083660825838e+01,5.243029506492025575e+02,1.598795126925474097e-01,1.100000010988609489e+01,3.217980574754709597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305129992750826773e+01,5.243129505974255835e+02,1.599116924427558539e-01,1.100000010988609489e+01,3.217834589353171879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305220901840827707e+01,5.243229505456533843e+02,1.599438707331178600e-01,1.100000010988609489e+01,3.217688603951634162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305311810930828642e+01,5.243329504938858463e+02,1.599760475636334001e-01,1.100000010988609489e+01,3.217542618550096444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305402720020829577e+01,5.243429504421229694e+02,1.600082229343024742e-01,1.100000010988609489e+01,3.217396633148558727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305493629110830511e+01,5.243529503903647537e+02,1.600403968451251102e-01,1.100000010988609489e+01,3.217250647747021009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305584538200831446e+01,5.243629503386113129e+02,1.600725692961012803e-01,1.100000010988609489e+01,3.217104662345483292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305675447290832381e+01,5.243729502868625332e+02,1.601047402872309844e-01,1.100000010988609489e+01,3.216958676943945574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305766356380833315e+01,5.243829502351184146e+02,1.601369098185142226e-01,1.100000010988609489e+01,3.216812691542407857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305857265470834250e+01,5.243929501833790709e+02,1.601690778899509948e-01,1.100000010988609489e+01,3.216666706140870139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.305948174560835184e+01,5.244029501316443884e+02,1.602012445015413011e-01,1.100000010988609489e+01,3.216520720739332422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306039083650836119e+01,5.244129500799143671e+02,1.602334096532851415e-01,1.100000010988609489e+01,3.216374735337794704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306129992740837054e+01,5.244229500281891205e+02,1.602655733451825437e-01,1.100000010988609489e+01,3.216228749936256986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306220901830837988e+01,5.244329499764685352e+02,1.602977355772334800e-01,1.100000010988609489e+01,3.216082764534719269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306311810920838923e+01,5.244429499247526110e+02,1.603298963494379503e-01,1.100000010988609489e+01,3.215936779133181551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306402720010839857e+01,5.244529498730414616e+02,1.603620556617959547e-01,1.100000010988609489e+01,3.215790793731643834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306493629100840792e+01,5.244629498213349734e+02,1.603942135143074932e-01,1.100000010988609489e+01,3.215644808330106116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306584538190841727e+01,5.244729497696331464e+02,1.604263699069725657e-01,1.100000010988609489e+01,3.215498822928568399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306675447280842661e+01,5.244829497179359805e+02,1.604585248397911446e-01,1.100000010988609489e+01,3.215352837527030681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306766356370843596e+01,5.244929496662435895e+02,1.604906783127632575e-01,1.100000010988609489e+01,3.215206852125492964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306857265460844530e+01,5.245029496145558596e+02,1.605228303258889044e-01,1.100000010988609489e+01,3.215060866723955246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.306948174550845465e+01,5.245129495628727909e+02,1.605549808791680855e-01,1.100000010988609489e+01,3.214914881322417529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307039083640846400e+01,5.245229495111944971e+02,1.605871299726008006e-01,1.100000010988609489e+01,3.214768895920879811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307129992730847334e+01,5.245329494595208644e+02,1.606192776061870497e-01,1.100000010988609489e+01,3.214622910519342094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307220901820848269e+01,5.245429494078518928e+02,1.606514237799268052e-01,1.100000010988609489e+01,3.214476925117804376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307311810910849204e+01,5.245529493561875825e+02,1.606835684938200948e-01,1.100000010988609489e+01,3.214330939716266659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307402720000850138e+01,5.245629493045280469e+02,1.607157117478669184e-01,1.100000010988609489e+01,3.214184954314728941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307493629090851073e+01,5.245729492528731726e+02,1.607478535420672761e-01,1.100000010988609489e+01,3.214038968913191224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307584538180852007e+01,5.245829492012229593e+02,1.607799938764211400e-01,1.100000010988609489e+01,3.213892983511653506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307675447270852942e+01,5.245929491495774073e+02,1.608121327509285381e-01,1.100000010988609489e+01,3.213746998110115789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307766356360853877e+01,5.246029490979366301e+02,1.608442701655894702e-01,1.100000010988609489e+01,3.213601012708578071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307857265450854811e+01,5.246129490463005141e+02,1.608764061204039086e-01,1.100000010988609489e+01,3.213455027307040354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.307948174540855746e+01,5.246229489946690592e+02,1.609085406153718811e-01,1.100000010988609489e+01,3.213309041905502636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308039083630856680e+01,5.246329489430423791e+02,1.609406736504933599e-01,1.100000010988609489e+01,3.213163056503964918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308129992720857615e+01,5.246429488914203603e+02,1.609728052257683728e-01,1.100000010988609489e+01,3.213017071102427201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308220901810858550e+01,5.246529488398030026e+02,1.610049353411968920e-01,1.100000010988609489e+01,3.212871085700889483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308311810900859484e+01,5.246629487881903060e+02,1.610370639967789452e-01,1.100000010988609489e+01,3.212725100299351766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308402719990860419e+01,5.246729487365823843e+02,1.610691911925145048e-01,1.100000010988609489e+01,3.212579114897814048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308493629080861353e+01,5.246829486849791238e+02,1.611013169284035984e-01,1.100000010988609489e+01,3.212433129496276331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308584538170862288e+01,5.246929486333805244e+02,1.611334412044461983e-01,1.100000010988609489e+01,3.212287144094738613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308675447260863223e+01,5.247029485817865861e+02,1.611655640206423323e-01,1.100000010988609489e+01,3.212141158693200896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308766356350864157e+01,5.247129485301974228e+02,1.611976853769919726e-01,1.100000010988609489e+01,3.211995173291663178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308857265440865092e+01,5.247229484786129206e+02,1.612298052734951193e-01,1.100000010988609489e+01,3.211849187890125461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.308948174530866027e+01,5.247329484270330795e+02,1.612619237101517999e-01,1.100000010988609489e+01,3.211703202488587743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309039083620866961e+01,5.247429483754578996e+02,1.612940406869619869e-01,1.100000010988609489e+01,3.211557217087050026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309129992710867896e+01,5.247529483238874946e+02,1.613261562039256802e-01,1.100000010988609489e+01,3.211411231685512308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309220901800868830e+01,5.247629482723217507e+02,1.613582702610428798e-01,1.100000010988609489e+01,3.211265246283974591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309311810890869765e+01,5.247729482207606679e+02,1.613903828583136135e-01,1.100000010988609489e+01,3.211119260882436873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309402719980870700e+01,5.247829481692042464e+02,1.614224939957378535e-01,1.100000010988609489e+01,3.210973275480899156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309493629070871634e+01,5.247929481176525996e+02,1.614546036733155998e-01,1.100000010988609489e+01,3.210827290079361438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309584538160872569e+01,5.248029480661056141e+02,1.614867118910468524e-01,1.100000010988609489e+01,3.210681304677823721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309675447250873503e+01,5.248129480145632897e+02,1.615188186489316113e-01,1.100000010988609489e+01,3.210535319276286003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309766356340874438e+01,5.248229479630256264e+02,1.615509239469698766e-01,1.100000010988609489e+01,3.210389333874748286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309857265430875373e+01,5.248329479114926244e+02,1.615830277851616481e-01,1.100000010988609489e+01,3.210243348473210568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.309948174520876307e+01,5.248429478599643971e+02,1.616151301635069260e-01,1.100000010988609489e+01,3.210097363071672850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310039083610877242e+01,5.248529478084408311e+02,1.616472310820057101e-01,1.100000010988609489e+01,3.209951377670135133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310129992700878176e+01,5.248629477569219262e+02,1.616793305406580006e-01,1.100000010988609489e+01,3.209805392268597415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310220901790879111e+01,5.248729477054076824e+02,1.617114285394637974e-01,1.100000010988609489e+01,3.209659406867059698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310311810880880046e+01,5.248829476538982135e+02,1.617435250784231004e-01,1.100000010988609489e+01,3.209513421465521980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310402719970880980e+01,5.248929476023934058e+02,1.617756201575359098e-01,1.100000010988609489e+01,3.209367436063984263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310493629060881915e+01,5.249029475508932592e+02,1.618077137768022256e-01,1.100000010988609489e+01,3.209221450662446545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310584538150882850e+01,5.249129474993977738e+02,1.618398059362220476e-01,1.100000010988609489e+01,3.209075465260908828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310675447240883784e+01,5.249229474479069495e+02,1.618718966357953759e-01,1.100000010988609489e+01,3.208929479859371110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310766356330884719e+01,5.249329473964209001e+02,1.619039858755222105e-01,1.100000010988609489e+01,3.208783494457833393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310857265420885653e+01,5.249429473449395118e+02,1.619360736554025237e-01,1.100000010988609489e+01,3.208637509056295675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.310948174510886588e+01,5.249529472934627847e+02,1.619681599754363432e-01,1.100000010988609489e+01,3.208491523654757958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311039083600887523e+01,5.249629472419907188e+02,1.620002448356236691e-01,1.100000010988609489e+01,3.208345538253220240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311129992690888457e+01,5.249729471905233140e+02,1.620323282359645012e-01,1.100000010988609489e+01,3.208199552851682523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311220901780889392e+01,5.249829471390606841e+02,1.620644101764588119e-01,1.100000010988609489e+01,3.208053567450144805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311311810870890326e+01,5.249929470876027153e+02,1.620964906571066289e-01,1.100000010988609489e+01,3.207907582048607088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311402719960891261e+01,5.250029470361494077e+02,1.621285696779079522e-01,1.100000010988609489e+01,3.207761596647069370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311493629050892196e+01,5.250129469847007613e+02,1.621606472388627540e-01,1.100000010988609489e+01,3.207615611245531653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311584538140893130e+01,5.250229469332567760e+02,1.621927233399710622e-01,1.100000010988609489e+01,3.207469625843993935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311675447230894065e+01,5.250329468818175656e+02,1.622247979812328489e-01,1.100000010988609489e+01,3.207323640442456218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311766356320894999e+01,5.250429468303830163e+02,1.622568711626481419e-01,1.100000010988609489e+01,3.207177655040918500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311857265410895934e+01,5.250529467789531282e+02,1.622889428842169135e-01,1.100000010988609489e+01,3.207031669639380782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.311948174500896869e+01,5.250629467275279012e+02,1.623210131459391914e-01,1.100000010988609489e+01,3.206885684237843065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312039083590897803e+01,5.250729466761073354e+02,1.623530819478149478e-01,1.100000010988609489e+01,3.206739698836305347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312129992680898738e+01,5.250829466246914308e+02,1.623851492898442106e-01,1.100000010988609489e+01,3.206593713434767630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312220901770899673e+01,5.250929465732803010e+02,1.624172151720269519e-01,1.100000010988609489e+01,3.206447728033229912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312311810860900607e+01,5.251029465218738324e+02,1.624492795943631995e-01,1.100000010988609489e+01,3.206301742631692195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312402719950901542e+01,5.251129464704720249e+02,1.624813425568529257e-01,1.100000010988609489e+01,3.206155757230154477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312493629040902476e+01,5.251229464190748786e+02,1.625134040594961304e-01,1.100000010988609489e+01,3.206009771828616760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312584538130903411e+01,5.251329463676823934e+02,1.625454641022928415e-01,1.100000010988609489e+01,3.205863786427079042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312675447220904346e+01,5.251429463162945694e+02,1.625775226852430311e-01,1.100000010988609489e+01,3.205717801025541325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312766356310905280e+01,5.251529462649115203e+02,1.626095798083466992e-01,1.100000010988609489e+01,3.205571815624003607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312857265400906215e+01,5.251629462135331323e+02,1.626416354716038737e-01,1.100000010988609489e+01,3.205425830222465890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.312948174490907149e+01,5.251729461621594055e+02,1.626736896750145267e-01,1.100000010988609489e+01,3.205279844820928172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313039083580908084e+01,5.251829461107903398e+02,1.627057424185786583e-01,1.100000010988609489e+01,3.205133859419390455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313129992670909019e+01,5.251929460594259353e+02,1.627377937022962684e-01,1.100000010988609489e+01,3.204987874017852737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313220901760909953e+01,5.252029460080661920e+02,1.627698435261673571e-01,1.100000010988609489e+01,3.204841888616315020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313311810850910888e+01,5.252129459567112235e+02,1.628018918901919243e-01,1.100000010988609489e+01,3.204695903214777302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313402719940911823e+01,5.252229459053609162e+02,1.628339387943699701e-01,1.100000010988609489e+01,3.204549917813239585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313493629030912757e+01,5.252329458540152700e+02,1.628659842387015222e-01,1.100000010988609489e+01,3.204403932411701867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313584538120913692e+01,5.252429458026742850e+02,1.628980282231865528e-01,1.100000010988609489e+01,3.204257947010164150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313675447210914626e+01,5.252529457513379612e+02,1.629300707478250620e-01,1.100000010988609489e+01,3.204111961608626432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313766356300915561e+01,5.252629457000062985e+02,1.629621118126170498e-01,1.100000010988609489e+01,3.203965976207088714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313857265390916496e+01,5.252729456486792969e+02,1.629941514175625161e-01,1.100000010988609489e+01,3.203819990805550997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.313948174480917430e+01,5.252829455973570703e+02,1.630261895626614610e-01,1.100000010988609489e+01,3.203674005404013279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314039083570918365e+01,5.252929455460395047e+02,1.630582262479138844e-01,1.100000010988609489e+01,3.203528020002475562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314129992660919299e+01,5.253029454947266004e+02,1.630902614733197586e-01,1.100000010988609489e+01,3.203382034600937844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314220901750920234e+01,5.253129454434183572e+02,1.631222952388791114e-01,1.100000010988609489e+01,3.203236049199400127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314311810840921169e+01,5.253229453921147751e+02,1.631543275445919428e-01,1.100000010988609489e+01,3.203090063797862409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314402719930922103e+01,5.253329453408158543e+02,1.631863583904582526e-01,1.100000010988609489e+01,3.202944078396324692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314493629020923038e+01,5.253429452895215945e+02,1.632183877764780411e-01,1.100000010988609489e+01,3.202798092994786974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314584538110923972e+01,5.253529452382321097e+02,1.632504157026513081e-01,1.100000010988609489e+01,3.202652107593249257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314675447200924907e+01,5.253629451869472859e+02,1.632824421689780259e-01,1.100000010988609489e+01,3.202506122191711539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314766356290925842e+01,5.253729451356671234e+02,1.633144671754582222e-01,1.100000010988609489e+01,3.202360136790173822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314857265380926776e+01,5.253829450843916220e+02,1.633464907220918971e-01,1.100000010988609489e+01,3.202214151388636104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.314948174470927711e+01,5.253929450331207818e+02,1.633785128088790228e-01,1.100000010988609489e+01,3.202068165987098387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315039083560928646e+01,5.254029449818546027e+02,1.634105334358196271e-01,1.100000010988609489e+01,3.201922180585560669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315129992650929580e+01,5.254129449305930848e+02,1.634425526029137099e-01,1.100000010988609489e+01,3.201776195184022952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315220901740930515e+01,5.254229448793362280e+02,1.634745703101612435e-01,1.100000010988609489e+01,3.201630209782485234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315311810830931449e+01,5.254329448280841461e+02,1.635065865575622557e-01,1.100000010988609489e+01,3.201484224380947517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315402719920932384e+01,5.254429447768367254e+02,1.635386013451167186e-01,1.100000010988609489e+01,3.201338238979409799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315493629010933319e+01,5.254529447255939658e+02,1.635706146728246602e-01,1.100000010988609489e+01,3.201192253577872081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315584538100934253e+01,5.254629446743558674e+02,1.636026265406860802e-01,1.100000010988609489e+01,3.201046268176334364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315675447190935188e+01,5.254729446231224301e+02,1.636346369487009511e-01,1.100000010988609489e+01,3.200900282774796646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315766356280936122e+01,5.254829445718936540e+02,1.636666458968692728e-01,1.100000010988609489e+01,3.200754297373258929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315857265370937057e+01,5.254929445206695391e+02,1.636986533851910730e-01,1.100000010988609489e+01,3.200608311971721211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.315948174460937992e+01,5.255029444694500853e+02,1.637306594136663240e-01,1.100000010988609489e+01,3.200462326570183494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316039083550938926e+01,5.255129444182352927e+02,1.637626639822950536e-01,1.100000010988609489e+01,3.200316341168645776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316129992640939861e+01,5.255229443670251612e+02,1.637946670910772340e-01,1.100000010988609489e+01,3.200170355767108059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316220901730940795e+01,5.255329443158198046e+02,1.638266687400128652e-01,1.100000010988609489e+01,3.200024370365570341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316311810820941730e+01,5.255429442646191092e+02,1.638586689291019749e-01,1.100000010988609489e+01,3.199878384964032624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316402719910942665e+01,5.255529442134230749e+02,1.638906676583445354e-01,1.100000010988609489e+01,3.199732399562494906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316493629000943599e+01,5.255629441622317017e+02,1.639226649277405468e-01,1.100000010988609489e+01,3.199586414160957189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316584538090944534e+01,5.255729441110449898e+02,1.639546607372900366e-01,1.100000010988609489e+01,3.199440428759419471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316675447180945469e+01,5.255829440598629390e+02,1.639866550869929773e-01,1.100000010988609489e+01,3.199294443357881754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316766356270946403e+01,5.255929440086855493e+02,1.640186479768493688e-01,1.100000010988609489e+01,3.199148457956344036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316857265360947338e+01,5.256029439575128208e+02,1.640506394068592111e-01,1.100000010988609489e+01,3.199002472554806319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.316948174450948272e+01,5.256129439063447535e+02,1.640826293770225042e-01,1.100000010988609489e+01,3.198856487153268601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317039083540949207e+01,5.256229438551813473e+02,1.641146178873392480e-01,1.100000010988609489e+01,3.198710501751730884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317129992630950142e+01,5.256329438040226023e+02,1.641466049378094427e-01,1.100000010988609489e+01,3.198564516350193166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317220901720951076e+01,5.256429437528685185e+02,1.641785905284331160e-01,1.100000010988609489e+01,3.198418530948655449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317311810810952011e+01,5.256529437017192095e+02,1.642105746592102400e-01,1.100000010988609489e+01,3.198272545547117731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317402719900952945e+01,5.256629436505745616e+02,1.642425573301408148e-01,1.100000010988609489e+01,3.198126560145580013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317493628990953880e+01,5.256729435994345749e+02,1.642745385412248404e-01,1.100000010988609489e+01,3.197980574744042296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317584538080954815e+01,5.256829435482992494e+02,1.643065182924623169e-01,1.100000010988609489e+01,3.197834589342504578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317675447170955749e+01,5.256929434971685851e+02,1.643384965838532441e-01,1.100000010988609489e+01,3.197688603940966861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317766356260956684e+01,5.257029434460425819e+02,1.643704734153975944e-01,1.100000010988609489e+01,3.197542618539429143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317857265350957618e+01,5.257129433949212398e+02,1.644024487870953954e-01,1.100000010988609489e+01,3.197396633137891426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.317948174440958553e+01,5.257229433438045589e+02,1.644344226989466473e-01,1.100000010988609489e+01,3.197250647736353708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318039083530959488e+01,5.257329432926925392e+02,1.644663951509513500e-01,1.100000010988609489e+01,3.197104662334815991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318129992620960422e+01,5.257429432415851807e+02,1.644983661431095034e-01,1.100000010988609489e+01,3.196958676933278273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318220901710961357e+01,5.257529431904824833e+02,1.645303356754211077e-01,1.100000010988609489e+01,3.196812691531740556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318311810800962292e+01,5.257629431393844470e+02,1.645623037478861350e-01,1.100000010988609489e+01,3.196666706130202838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318402719890963226e+01,5.257729430882910719e+02,1.645942703605046131e-01,1.100000010988609489e+01,3.196520720728665121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318493628980964161e+01,5.257829430372023580e+02,1.646262355132765420e-01,1.100000010988609489e+01,3.196374735327127403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318584538070965095e+01,5.257929429861183053e+02,1.646581992062019217e-01,1.100000010988609489e+01,3.196228749925589686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318675447160966030e+01,5.258029429350389137e+02,1.646901614392807245e-01,1.100000010988609489e+01,3.196082764524051968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318766356250966965e+01,5.258129428839641832e+02,1.647221222125129780e-01,1.100000010988609489e+01,3.195936779122514251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318857265340967899e+01,5.258229428328941140e+02,1.647540815258986824e-01,1.100000010988609489e+01,3.195790793720976533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.318948174430968834e+01,5.258329427818288195e+02,1.647860393794378098e-01,1.100000010988609489e+01,3.195644808319438816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319039083520969768e+01,5.258429427307681863e+02,1.648179957731303880e-01,1.100000010988609489e+01,3.195498822917901098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319129992610970703e+01,5.258529426797122142e+02,1.648499507069763892e-01,1.100000010988609489e+01,3.195352837516363381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319220901700971638e+01,5.258629426286609032e+02,1.648819041809758412e-01,1.100000010988609489e+01,3.195206852114825663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319311810790972572e+01,5.258729425776142534e+02,1.649138561951287163e-01,1.100000010988609489e+01,3.195060866713287945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319402719880973507e+01,5.258829425265722648e+02,1.649458067494350422e-01,1.100000010988609489e+01,3.194914881311750228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319493628970974441e+01,5.258929424755349373e+02,1.649777558438947911e-01,1.100000010988609489e+01,3.194768895910212510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319584538060975376e+01,5.259029424245022710e+02,1.650097034785079908e-01,1.100000010988609489e+01,3.194622910508674793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319675447150976311e+01,5.259129423734742659e+02,1.650416496532746136e-01,1.100000010988609489e+01,3.194476925107137075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319766356240977245e+01,5.259229423224509219e+02,1.650735943681946594e-01,1.100000010988609489e+01,3.194330939705599358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319857265330978180e+01,5.259329422714322391e+02,1.651055376232681560e-01,1.100000010988609489e+01,3.194184954304061640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.319948174420979115e+01,5.259429422204182174e+02,1.651374794184950756e-01,1.100000010988609489e+01,3.194038968902523923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320039083510980049e+01,5.259529421694088569e+02,1.651694197538754183e-01,1.100000010988609489e+01,3.193892983500986205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320129992600980984e+01,5.259629421184041576e+02,1.652013586294092118e-01,1.100000010988609489e+01,3.193746998099448488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320220901690981918e+01,5.259729420674041194e+02,1.652332960450964283e-01,1.100000010988609489e+01,3.193601012697910770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320311810780982853e+01,5.259829420164087423e+02,1.652652320009370679e-01,1.100000010988609489e+01,3.193455027296373053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320402719870983788e+01,5.259929419654180265e+02,1.652971664969311305e-01,1.100000010988609489e+01,3.193309041894835335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320493628960984722e+01,5.260029419144319718e+02,1.653290995330786439e-01,1.100000010988609489e+01,3.193163056493297618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320584538050985657e+01,5.260129418634505782e+02,1.653610311093795804e-01,1.100000010988609489e+01,3.193017071091759900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320675447140986591e+01,5.260229418124738459e+02,1.653929612258339399e-01,1.100000010988609489e+01,3.192871085690222183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320766356230987526e+01,5.260329417615017746e+02,1.654248898824417224e-01,1.100000010988609489e+01,3.192725100288684465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320857265320988461e+01,5.260429417105343646e+02,1.654568170792029280e-01,1.100000010988609489e+01,3.192579114887146748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.320948174410989395e+01,5.260529416595716157e+02,1.654887428161175567e-01,1.100000010988609489e+01,3.192433129485609030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321039083500990330e+01,5.260629416086135279e+02,1.655206670931856083e-01,1.100000010988609489e+01,3.192287144084071313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321129992590991264e+01,5.260729415576601014e+02,1.655525899104070831e-01,1.100000010988609489e+01,3.192141158682533595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321220901680992199e+01,5.260829415067113359e+02,1.655845112677819808e-01,1.100000010988609489e+01,3.191995173280995877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321311810770993134e+01,5.260929414557672317e+02,1.656164311653103016e-01,1.100000010988609489e+01,3.191849187879458160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321402719860994068e+01,5.261029414048277886e+02,1.656483496029920455e-01,1.100000010988609489e+01,3.191703202477920442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321493628950995003e+01,5.261129413538930066e+02,1.656802665808272124e-01,1.100000010988609489e+01,3.191557217076382725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321584538040995938e+01,5.261229413029628859e+02,1.657121820988158023e-01,1.100000010988609489e+01,3.191411231674845007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321675447130996872e+01,5.261329412520374262e+02,1.657440961569578153e-01,1.100000010988609489e+01,3.191265246273307290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321766356220997807e+01,5.261429412011166278e+02,1.657760087552532513e-01,1.100000010988609489e+01,3.191119260871769572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321857265310998741e+01,5.261529411502004905e+02,1.658079198937020826e-01,1.100000010988609489e+01,3.190973275470231855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.321948174400999676e+01,5.261629410992890143e+02,1.658398295723043370e-01,1.100000010988609489e+01,3.190827290068694137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322039083491000611e+01,5.261729410483821994e+02,1.658717377910600144e-01,1.100000010988609489e+01,3.190681304667156420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322129992581001545e+01,5.261829409974800456e+02,1.659036445499691148e-01,1.100000010988609489e+01,3.190535319265618702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322220901671002480e+01,5.261929409465825529e+02,1.659355498490316383e-01,1.100000010988609489e+01,3.190389333864080985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322311810761003414e+01,5.262029408956897214e+02,1.659674536882475571e-01,1.100000010988609489e+01,3.190243348462543267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322402719851004349e+01,5.262129408448015511e+02,1.659993560676168989e-01,1.100000010988609489e+01,3.190097363061005550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322493628941005284e+01,5.262229407939180419e+02,1.660312569871396637e-01,1.100000010988609489e+01,3.189951377659467832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322584538031006218e+01,5.262329407430390802e+02,1.660631564468158239e-01,1.100000010988609489e+01,3.189805392257930115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322675447121007153e+01,5.262429406921647796e+02,1.660950544466454071e-01,1.100000010988609489e+01,3.189659406856392397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322766356211008087e+01,5.262529406412951403e+02,1.661269509866283856e-01,1.100000010988609489e+01,3.189513421454854680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322857265301009022e+01,5.262629405904301620e+02,1.661588460667647871e-01,1.100000010988609489e+01,3.189367436053316962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.322948174391009957e+01,5.262729405395698450e+02,1.661907396870545839e-01,1.100000010988609489e+01,3.189221450651779245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323039083481010891e+01,5.262829404887141891e+02,1.662226318474978037e-01,1.100000010988609489e+01,3.189075465250241527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323129992571011826e+01,5.262929404378631943e+02,1.662545225480944189e-01,1.100000010988609489e+01,3.188929479848703809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323220901661012761e+01,5.263029403870168608e+02,1.662864117888444571e-01,1.100000010988609489e+01,3.188783494447166092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323311810751013695e+01,5.263129403361751883e+02,1.663182995697478905e-01,1.100000010988609489e+01,3.188637509045628374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323402719841014630e+01,5.263229402853381771e+02,1.663501858908047470e-01,1.100000010988609489e+01,3.188491523644090657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323493628931015564e+01,5.263329402345058270e+02,1.663820707520149988e-01,1.100000010988609489e+01,3.188345538242552939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323584538021016499e+01,5.263429401836781381e+02,1.664139541533786459e-01,1.100000010988609489e+01,3.188199552841015222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323675447111017434e+01,5.263529401328551103e+02,1.664458360948957161e-01,1.100000010988609489e+01,3.188053567439477504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323766356201018368e+01,5.263629400820367437e+02,1.664777165765661815e-01,1.100000010988609489e+01,3.187907582037939787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323857265291019303e+01,5.263729400312230382e+02,1.665095955983900422e-01,1.100000010988609489e+01,3.187761596636402069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.323948174381020237e+01,5.263829399804139939e+02,1.665414731603673260e-01,1.100000010988609489e+01,3.187615611234864352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324039083471021172e+01,5.263929399296096108e+02,1.665733492624980050e-01,1.100000010988609489e+01,3.187469625833326634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324129992561022107e+01,5.264029398788098888e+02,1.666052239047820793e-01,1.100000010988609489e+01,3.187323640431788917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324220901651023041e+01,5.264129398280148280e+02,1.666370970872195489e-01,1.100000010988609489e+01,3.187177655030251199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324311810741023976e+01,5.264229397772243146e+02,1.666689688098104138e-01,1.100000010988609489e+01,3.187031669628713482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324402719831024910e+01,5.264329397264384625e+02,1.667008390725546740e-01,1.100000010988609489e+01,3.186885684227175764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324493628921025845e+01,5.264429396756572714e+02,1.667327078754523573e-01,1.100000010988609489e+01,3.186739698825638047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324584538011026780e+01,5.264529396248807416e+02,1.667645752185034358e-01,1.100000010988609489e+01,3.186593713424100329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324675447101027714e+01,5.264629395741088729e+02,1.667964411017079096e-01,1.100000010988609489e+01,3.186447728022562612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324766356191028649e+01,5.264729395233416653e+02,1.668283055250657787e-01,1.100000010988609489e+01,3.186301742621024894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324857265281029584e+01,5.264829394725791190e+02,1.668601684885770431e-01,1.100000010988609489e+01,3.186155757219487177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.324948174371030518e+01,5.264929394218212337e+02,1.668920299922417028e-01,1.100000010988609489e+01,3.186009771817949459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325039083461031453e+01,5.265029393710680097e+02,1.669238900360597577e-01,1.100000010988609489e+01,3.185863786416411741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325129992551032387e+01,5.265129393203194468e+02,1.669557486200312080e-01,1.100000010988609489e+01,3.185717801014874024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325220901641033322e+01,5.265229392695755450e+02,1.669876057441560535e-01,1.100000010988609489e+01,3.185571815613336306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325311810731034257e+01,5.265329392188363045e+02,1.670194614084342666e-01,1.100000010988609489e+01,3.185425830211798589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325402719821035191e+01,5.265429391681016114e+02,1.670513156128658749e-01,1.100000010988609489e+01,3.185279844810260871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325493628911036126e+01,5.265529391173715794e+02,1.670831683574508786e-01,1.100000010988609489e+01,3.185133859408723154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325584538001037060e+01,5.265629390666462086e+02,1.671150196421892775e-01,1.100000010988609489e+01,3.184987874007185436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325675447091037995e+01,5.265729390159254990e+02,1.671468694670810717e-01,1.100000010988609489e+01,3.184841888605647719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325766356181038930e+01,5.265829389652094505e+02,1.671787178321262335e-01,1.100000010988609489e+01,3.184695903204110001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325857265271039864e+01,5.265929389144980632e+02,1.672105647373247905e-01,1.100000010988609489e+01,3.184549917802572284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.325948174361040799e+01,5.266029388637913371e+02,1.672424101826767429e-01,1.100000010988609489e+01,3.184403932401034566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326039083451041733e+01,5.266129388130892721e+02,1.672742541681820905e-01,1.100000010988609489e+01,3.184257946999496849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326129992541042668e+01,5.266229387623918683e+02,1.673060966938408056e-01,1.100000010988609489e+01,3.184111961597959131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326220901631043603e+01,5.266329387116990119e+02,1.673379377596529161e-01,1.100000010988609489e+01,3.183965976196421414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326311810721044537e+01,5.266429386610108168e+02,1.673697773656184218e-01,1.100000010988609489e+01,3.183819990794883696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326402719811045472e+01,5.266529386103272827e+02,1.674016155117372950e-01,1.100000010988609489e+01,3.183674005393345979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326493628901046407e+01,5.266629385596484099e+02,1.674334521980095636e-01,1.100000010988609489e+01,3.183528019991808261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326584537991047341e+01,5.266729385089741982e+02,1.674652874244351997e-01,1.100000010988609489e+01,3.183382034590270544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326675447081048276e+01,5.266829384583046476e+02,1.674971211910142310e-01,1.100000010988609489e+01,3.183236049188732826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326766356171049210e+01,5.266929384076397582e+02,1.675289534977466299e-01,1.100000010988609489e+01,3.183090063787195109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326857265261050145e+01,5.267029383569795300e+02,1.675607843446324241e-01,1.100000010988609489e+01,3.182944078385657391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.326948174351051080e+01,5.267129383063239629e+02,1.675926137316715858e-01,1.100000010988609489e+01,3.182798092984119673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327039083441052014e+01,5.267229382556729433e+02,1.676244416588641428e-01,1.100000010988609489e+01,3.182652107582581956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327129992531052949e+01,5.267329382050265849e+02,1.676562681262100674e-01,1.100000010988609489e+01,3.182506122181044238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327220901621053883e+01,5.267429381543848876e+02,1.676880931337093594e-01,1.100000010988609489e+01,3.182360136779506521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327311810711054818e+01,5.267529381037478515e+02,1.677199166813620468e-01,1.100000010988609489e+01,3.182214151377968803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327402719801055753e+01,5.267629380531154766e+02,1.677517387691681017e-01,1.100000010988609489e+01,3.182068165976431086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327493628891056687e+01,5.267729380024877628e+02,1.677835593971275241e-01,1.100000010988609489e+01,3.181922180574893368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327584537981057622e+01,5.267829379518647102e+02,1.678153785652403418e-01,1.100000010988609489e+01,3.181776195173355651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327675447071058557e+01,5.267929379012462050e+02,1.678471962735065270e-01,1.100000010988609489e+01,3.181630209771817933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327766356161059491e+01,5.268029378506323610e+02,1.678790125219260798e-01,1.100000010988609489e+01,3.181484224370280216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327857265251060426e+01,5.268129378000231782e+02,1.679108273104990001e-01,1.100000010988609489e+01,3.181338238968742498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.327948174341061360e+01,5.268229377494186565e+02,1.679426406392253157e-01,1.100000010988609489e+01,3.181192253567204781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328039083431062295e+01,5.268329376988187960e+02,1.679744525081049988e-01,1.100000010988609489e+01,3.181046268165667063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328129992521063230e+01,5.268429376482235966e+02,1.680062629171380495e-01,1.100000010988609489e+01,3.180900282764129346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328220901611064164e+01,5.268529375976330584e+02,1.680380718663244677e-01,1.100000010988609489e+01,3.180754297362591628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328311810701065099e+01,5.268629375470470677e+02,1.680698793556642534e-01,1.100000010988609489e+01,3.180608311961053911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328402719791066033e+01,5.268729374964657381e+02,1.681016853851574067e-01,1.100000010988609489e+01,3.180462326559516193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328493628881066968e+01,5.268829374458890697e+02,1.681334899548039274e-01,1.100000010988609489e+01,3.180316341157978476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328584537971067903e+01,5.268929373953170625e+02,1.681652930646038158e-01,1.100000010988609489e+01,3.180170355756440758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328675447061068837e+01,5.269029373447497164e+02,1.681970947145570716e-01,1.100000010988609489e+01,3.180024370354903041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328766356151069772e+01,5.269129372941870315e+02,1.682288949046636950e-01,1.100000010988609489e+01,3.179878384953365323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328857265241070706e+01,5.269229372436288941e+02,1.682606936349236859e-01,1.100000010988609489e+01,3.179732399551827605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.328948174331071641e+01,5.269329371930754178e+02,1.682924909053370444e-01,1.100000010988609489e+01,3.179586414150289888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329039083421072576e+01,5.269429371425266027e+02,1.683242867159037703e-01,1.100000010988609489e+01,3.179440428748752170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329129992511073510e+01,5.269529370919824487e+02,1.683560810666238639e-01,1.100000010988609489e+01,3.179294443347214453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329220901601074445e+01,5.269629370414429559e+02,1.683878739574972971e-01,1.100000010988609489e+01,3.179148457945676735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329311810691075380e+01,5.269729369909081242e+02,1.684196653885240980e-01,1.100000010988609489e+01,3.179002472544139018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329402719781076314e+01,5.269829369403778401e+02,1.684514553597042663e-01,1.100000010988609489e+01,3.178856487142601300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329493628871077249e+01,5.269929368898522171e+02,1.684832438710378022e-01,1.100000010988609489e+01,3.178710501741063583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329584537961078183e+01,5.270029368393312552e+02,1.685150309225247056e-01,1.100000010988609489e+01,3.178564516339525865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329675447051079118e+01,5.270129367888149545e+02,1.685468165141649488e-01,1.100000010988609489e+01,3.178418530937988148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329766356141080053e+01,5.270229367383033150e+02,1.685786006459585595e-01,1.100000010988609489e+01,3.178272545536450430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329857265231080987e+01,5.270329366877962229e+02,1.686103833179055378e-01,1.100000010988609489e+01,3.178126560134912713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.329948174321081922e+01,5.270429366372937920e+02,1.686421645300058558e-01,1.100000010988609489e+01,3.177980574733374995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330039083411082856e+01,5.270529365867960223e+02,1.686739442822595414e-01,1.100000010988609489e+01,3.177834589331837278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330129992501083791e+01,5.270629365363029137e+02,1.687057225746665667e-01,1.100000010988609489e+01,3.177688603930299560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330220901591084726e+01,5.270729364858144663e+02,1.687374994072269596e-01,1.100000010988609489e+01,3.177542618528761843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330311810681085660e+01,5.270829364353306801e+02,1.687692747799407200e-01,1.100000010988609489e+01,3.177396633127224125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330402719771086595e+01,5.270929363848514413e+02,1.688010486928078202e-01,1.100000010988609489e+01,3.177250647725686408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330493628861087529e+01,5.271029363343768637e+02,1.688328211458282879e-01,1.100000010988609489e+01,3.177104662324148690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330584537951088464e+01,5.271129362839069472e+02,1.688645921390020954e-01,1.100000010988609489e+01,3.176958676922610973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330675447041089399e+01,5.271229362334416919e+02,1.688963616723292704e-01,1.100000010988609489e+01,3.176812691521073255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330766356131090333e+01,5.271329361829809841e+02,1.689281297458097852e-01,1.100000010988609489e+01,3.176666706119535537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330857265221091268e+01,5.271429361325249374e+02,1.689598963594436398e-01,1.100000010988609489e+01,3.176520720717997820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.330948174311092203e+01,5.271529360820735519e+02,1.689916615132308619e-01,1.100000010988609489e+01,3.176374735316460102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331039083401093137e+01,5.271629360316268276e+02,1.690234252071714238e-01,1.100000010988609489e+01,3.176228749914922385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331129992491094072e+01,5.271729359811847644e+02,1.690551874412653255e-01,1.100000010988609489e+01,3.176082764513384667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331220901581095006e+01,5.271829359307472487e+02,1.690869482155125947e-01,1.100000010988609489e+01,3.175936779111846950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331311810671095941e+01,5.271929358803143941e+02,1.691187075299132037e-01,1.100000010988609489e+01,3.175790793710309232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331402719761096876e+01,5.272029358298862007e+02,1.691504653844671524e-01,1.100000010988609489e+01,3.175644808308771515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331493628851097810e+01,5.272129357794626685e+02,1.691822217791744409e-01,1.100000010988609489e+01,3.175498822907233797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331584537941098745e+01,5.272229357290437974e+02,1.692139767140350970e-01,1.100000010988609489e+01,3.175352837505696080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331675447031099679e+01,5.272329356786294738e+02,1.692457301890490928e-01,1.100000010988609489e+01,3.175206852104158362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331766356121100614e+01,5.272429356282198114e+02,1.692774822042164284e-01,1.100000010988609489e+01,3.175060866702620645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331857265211101549e+01,5.272529355778148101e+02,1.693092327595371038e-01,1.100000010988609489e+01,3.174914881301082927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.331948174301102483e+01,5.272629355274144700e+02,1.693409818550111190e-01,1.100000010988609489e+01,3.174768895899545210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332039083391103418e+01,5.272729354770186774e+02,1.693727294906384739e-01,1.100000010988609489e+01,3.174622910498007492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332129992481104352e+01,5.272829354266275459e+02,1.694044756664191687e-01,1.100000010988609489e+01,3.174476925096469775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332220901571105287e+01,5.272929353762410756e+02,1.694362203823532032e-01,1.100000010988609489e+01,3.174330939694932057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332311810661106222e+01,5.273029353258592664e+02,1.694679636384405774e-01,1.100000010988609489e+01,3.174184954293394340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332402719751107156e+01,5.273129352754820047e+02,1.694997054346812915e-01,1.100000010988609489e+01,3.174038968891856622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332493628841108091e+01,5.273229352251094042e+02,1.695314457710753453e-01,1.100000010988609489e+01,3.173892983490318905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332584537931109026e+01,5.273329351747414648e+02,1.695631846476227389e-01,1.100000010988609489e+01,3.173746998088781187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332675447021109960e+01,5.273429351243781866e+02,1.695949220643234723e-01,1.100000010988609489e+01,3.173601012687243469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332766356111110895e+01,5.273529350740194559e+02,1.696266580211775454e-01,1.100000010988609489e+01,3.173455027285705752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332857265201111829e+01,5.273629350236653863e+02,1.696583925181849584e-01,1.100000010988609489e+01,3.173309041884168034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.332948174291112764e+01,5.273729349733159779e+02,1.696901255553457111e-01,1.100000010988609489e+01,3.173163056482630317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333039083381113699e+01,5.273829349229712307e+02,1.697218571326598036e-01,1.100000010988609489e+01,3.173017071081092599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333129992471114633e+01,5.273929348726310309e+02,1.697535872501272081e-01,1.100000010988609489e+01,3.172871085679554882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333220901561115568e+01,5.274029348222954923e+02,1.697853159077479523e-01,1.100000010988609489e+01,3.172725100278017164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333311810651116502e+01,5.274129347719646148e+02,1.698170431055220364e-01,1.100000010988609489e+01,3.172579114876479447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333402719741117437e+01,5.274229347216383985e+02,1.698487688434494602e-01,1.100000010988609489e+01,3.172433129474941729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333493628831118372e+01,5.274329346713167297e+02,1.698804931215301961e-01,1.100000010988609489e+01,3.172287144073404012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333584537921119306e+01,5.274429346209997220e+02,1.699122159397642717e-01,1.100000010988609489e+01,3.172141158671866294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333675447011120241e+01,5.274529345706873755e+02,1.699439372981516871e-01,1.100000010988609489e+01,3.171995173270328577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333766356101121175e+01,5.274629345203796902e+02,1.699756571966924146e-01,1.100000010988609489e+01,3.171849187868790859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333857265191122110e+01,5.274729344700765523e+02,1.700073756353864818e-01,1.100000010988609489e+01,3.171703202467253142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.333948174281123045e+01,5.274829344197780756e+02,1.700390926142338610e-01,1.100000010988609489e+01,3.171557217065715424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334039083371123979e+01,5.274929343694842601e+02,1.700708081332345800e-01,1.100000010988609489e+01,3.171411231664177707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334129992461124914e+01,5.275029343191951057e+02,1.701025221923886110e-01,1.100000010988609489e+01,3.171265246262639989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334220901551125849e+01,5.275129342689104988e+02,1.701342347916959818e-01,1.100000010988609489e+01,3.171119260861102272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334311810641126783e+01,5.275229342186305530e+02,1.701659459311566647e-01,1.100000010988609489e+01,3.170973275459564554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334402719731127718e+01,5.275329341683552684e+02,1.701976556107706873e-01,1.100000010988609489e+01,3.170827290058026837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334493628821128652e+01,5.275429341180845313e+02,1.702293638305380219e-01,1.100000010988609489e+01,3.170681304656489119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334584537911129587e+01,5.275529340678184553e+02,1.702610705904586963e-01,1.100000010988609489e+01,3.170535319254951401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334675447001130522e+01,5.275629340175570405e+02,1.702927758905326827e-01,1.100000010988609489e+01,3.170389333853413684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334766356091131456e+01,5.275729339673002869e+02,1.703244797307599812e-01,1.100000010988609489e+01,3.170243348451875966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334857265181132391e+01,5.275829339170480807e+02,1.703561821111406194e-01,1.100000010988609489e+01,3.170097363050338249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.334948174271133325e+01,5.275929338668005357e+02,1.703878830316745696e-01,1.100000010988609489e+01,3.169951377648800531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335039083361134260e+01,5.276029338165576519e+02,1.704195824923618319e-01,1.100000010988609489e+01,3.169805392247262814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335129992451135195e+01,5.276129337663193155e+02,1.704512804932024339e-01,1.100000010988609489e+01,3.169659406845725096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335220901541136129e+01,5.276229337160856403e+02,1.704829770341963480e-01,1.100000010988609489e+01,3.169513421444187379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335311810631137064e+01,5.276329336658566262e+02,1.705146721153435740e-01,1.100000010988609489e+01,3.169367436042649661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335402719721137998e+01,5.276429336156322734e+02,1.705463657366441121e-01,1.100000010988609489e+01,3.169221450641111944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335493628811138933e+01,5.276529335654124679e+02,1.705780578980979623e-01,1.100000010988609489e+01,3.169075465239574226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335584537901139868e+01,5.276629335151973237e+02,1.706097485997051244e-01,1.100000010988609489e+01,3.168929479838036509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335675446991140802e+01,5.276729334649868406e+02,1.706414378414656263e-01,1.100000010988609489e+01,3.168783494436498791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335766356081141737e+01,5.276829334147809050e+02,1.706731256233794403e-01,1.100000010988609489e+01,3.168637509034961074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335857265171142672e+01,5.276929333645796305e+02,1.707048119454465662e-01,1.100000010988609489e+01,3.168491523633423356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.335948174261143606e+01,5.277029333143830172e+02,1.707364968076670042e-01,1.100000010988609489e+01,3.168345538231885639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336039083351144541e+01,5.277129332641909514e+02,1.707681802100407542e-01,1.100000010988609489e+01,3.168199552830347921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336129992441145475e+01,5.277229332140035467e+02,1.707998621525678162e-01,1.100000010988609489e+01,3.168053567428810204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336220901531146410e+01,5.277329331638208032e+02,1.708315426352481903e-01,1.100000010988609489e+01,3.167907582027272486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336311810621147345e+01,5.277429331136426072e+02,1.708632216580818763e-01,1.100000010988609489e+01,3.167761596625734768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336402719711148279e+01,5.277529330634690723e+02,1.708948992210688467e-01,1.100000010988609489e+01,3.167615611224197051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336493628801149214e+01,5.277629330133001986e+02,1.709265753242091290e-01,1.100000010988609489e+01,3.167469625822659333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336584537891150148e+01,5.277729329631358723e+02,1.709582499675027234e-01,1.100000010988609489e+01,3.167323640421121616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336675446981151083e+01,5.277829329129762073e+02,1.709899231509496298e-01,1.100000010988609489e+01,3.167177655019583898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336766356071152018e+01,5.277929328628212033e+02,1.710215948745498482e-01,1.100000010988609489e+01,3.167031669618046181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336857265161152952e+01,5.278029328126707469e+02,1.710532651383033786e-01,1.100000010988609489e+01,3.166885684216508463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.336948174251153887e+01,5.278129327625249516e+02,1.710849339422101933e-01,1.100000010988609489e+01,3.166739698814970746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337039083341154821e+01,5.278229327123838175e+02,1.711166012862703201e-01,1.100000010988609489e+01,3.166593713413433028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337129992431155756e+01,5.278329326622472308e+02,1.711482671704837588e-01,1.100000010988609489e+01,3.166447728011895311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337220901521156691e+01,5.278429326121153053e+02,1.711799315948505096e-01,1.100000010988609489e+01,3.166301742610357593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337311810611157625e+01,5.278529325619880410e+02,1.712115945593705446e-01,1.100000010988609489e+01,3.166155757208819876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337402719701158560e+01,5.278629325118653242e+02,1.712432560640438917e-01,1.100000010988609489e+01,3.166009771807282158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337493628791159495e+01,5.278729324617472685e+02,1.712749161088705507e-01,1.100000010988609489e+01,3.165863786405744441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337584537881160429e+01,5.278829324116338739e+02,1.713065746938504941e-01,1.100000010988609489e+01,3.165717801004206723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337675446971161364e+01,5.278929323615250269e+02,1.713382318189837494e-01,1.100000010988609489e+01,3.165571815602669006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337766356061162298e+01,5.279029323114208410e+02,1.713698874842702891e-01,1.100000010988609489e+01,3.165425830201131288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337857265151163233e+01,5.279129322613213162e+02,1.714015416897101407e-01,1.100000010988609489e+01,3.165279844799593571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.337948174241164168e+01,5.279229322112263389e+02,1.714331944353032766e-01,1.100000010988609489e+01,3.165133859398055853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338039083331165102e+01,5.279329321611360228e+02,1.714648457210497245e-01,1.100000010988609489e+01,3.164987873996518136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338129992421166037e+01,5.279429321110503679e+02,1.714964955469494567e-01,1.100000010988609489e+01,3.164841888594980418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338220901511166971e+01,5.279529320609692604e+02,1.715281439130025010e-01,1.100000010988609489e+01,3.164695903193442700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338311810601167906e+01,5.279629320108928141e+02,1.715597908192088294e-01,1.100000010988609489e+01,3.164549917791904983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338402719691168841e+01,5.279729319608210290e+02,1.715914362655684422e-01,1.100000010988609489e+01,3.164403932390367265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338493628781169775e+01,5.279829319107537913e+02,1.716230802520813670e-01,1.100000010988609489e+01,3.164257946988829548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338584537871170710e+01,5.279929318606912148e+02,1.716547227787475760e-01,1.100000010988609489e+01,3.164111961587291830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338675446961171644e+01,5.280029318106331857e+02,1.716863638455670693e-01,1.100000010988609489e+01,3.163965976185754113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338766356051172579e+01,5.280129317605798178e+02,1.717180034525398746e-01,1.100000010988609489e+01,3.163819990784216395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338857265141173514e+01,5.280229317105311111e+02,1.717496415996659642e-01,1.100000010988609489e+01,3.163674005382678678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.338948174231174448e+01,5.280329316604869518e+02,1.717812782869453381e-01,1.100000010988609489e+01,3.163528019981140960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339039083321175383e+01,5.280429316104474537e+02,1.718129135143779962e-01,1.100000010988609489e+01,3.163382034579603243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339129992411176318e+01,5.280529315604126168e+02,1.718445472819639663e-01,1.100000010988609489e+01,3.163236049178065525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339220901501177252e+01,5.280629315103823274e+02,1.718761795897032207e-01,1.100000010988609489e+01,3.163090063776527808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339311810591178187e+01,5.280729314603566991e+02,1.719078104375957594e-01,1.100000010988609489e+01,3.162944078374990090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339402719681179121e+01,5.280829314103356182e+02,1.719394398256415823e-01,1.100000010988609489e+01,3.162798092973452373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339493628771180056e+01,5.280929313603191986e+02,1.719710677538406896e-01,1.100000010988609489e+01,3.162652107571914655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339584537861180991e+01,5.281029313103074401e+02,1.720026942221930810e-01,1.100000010988609489e+01,3.162506122170376938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339675446951181925e+01,5.281129312603002290e+02,1.720343192306987568e-01,1.100000010988609489e+01,3.162360136768839220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339766356041182860e+01,5.281229312102976792e+02,1.720659427793577168e-01,1.100000010988609489e+01,3.162214151367301503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339857265131183794e+01,5.281329311602996768e+02,1.720975648681699610e-01,1.100000010988609489e+01,3.162068165965763785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.339948174221184729e+01,5.281429311103063355e+02,1.721291854971354895e-01,1.100000010988609489e+01,3.161922180564226068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340039083311185664e+01,5.281529310603176555e+02,1.721608046662543023e-01,1.100000010988609489e+01,3.161776195162688350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340129992401186598e+01,5.281629310103335229e+02,1.721924223755263994e-01,1.100000010988609489e+01,3.161630209761150632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340220901491187533e+01,5.281729309603540514e+02,1.722240386249517807e-01,1.100000010988609489e+01,3.161484224359612915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340311810581188467e+01,5.281829309103791275e+02,1.722556534145304463e-01,1.100000010988609489e+01,3.161338238958075197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340402719671189402e+01,5.281929308604088646e+02,1.722872667442623962e-01,1.100000010988609489e+01,3.161192253556537480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340493628761190337e+01,5.282029308104432630e+02,1.723188786141476025e-01,1.100000010988609489e+01,3.161046268154999762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340584537851191271e+01,5.282129307604822088e+02,1.723504890241860932e-01,1.100000010988609489e+01,3.160900282753462045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340675446941192206e+01,5.282229307105258158e+02,1.723820979743778681e-01,1.100000010988609489e+01,3.160754297351924327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340766356031193141e+01,5.282329306605739703e+02,1.724137054647229272e-01,1.100000010988609489e+01,3.160608311950386610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340857265121194075e+01,5.282429306106267859e+02,1.724453114952212429e-01,1.100000010988609489e+01,3.160462326548848892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.340948174211195010e+01,5.282529305606842627e+02,1.724769160658728429e-01,1.100000010988609489e+01,3.160316341147311175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341039083301195944e+01,5.282629305107462869e+02,1.725085191766777271e-01,1.100000010988609489e+01,3.160170355745773457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341129992391196879e+01,5.282729304608129723e+02,1.725401208276358678e-01,1.100000010988609489e+01,3.160024370344235740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341220901481197814e+01,5.282829304108842052e+02,1.725717210187472928e-01,1.100000010988609489e+01,3.159878384942698022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341311810571198748e+01,5.282929303609600993e+02,1.726033197500120020e-01,1.100000010988609489e+01,3.159732399541160305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341402719661199683e+01,5.283029303110405408e+02,1.726349170214299678e-01,1.100000010988609489e+01,3.159586414139622587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341493628751200617e+01,5.283129302611256435e+02,1.726665128330012178e-01,1.100000010988609489e+01,3.159440428738084870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341584537841201552e+01,5.283229302112154073e+02,1.726981071847257243e-01,1.100000010988609489e+01,3.159294443336547152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341675446931202487e+01,5.283329301613097186e+02,1.727297000766035151e-01,1.100000010988609489e+01,3.159148457935009435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341766356021203421e+01,5.283429301114086911e+02,1.727612915086345624e-01,1.100000010988609489e+01,3.159002472533471717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341857265111204356e+01,5.283529300615122111e+02,1.727928814808188940e-01,1.100000010988609489e+01,3.158856487131934000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.341948174201205291e+01,5.283629300116203922e+02,1.728244699931564821e-01,1.100000010988609489e+01,3.158710501730396282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342039083291206225e+01,5.283729299617331208e+02,1.728560570456473544e-01,1.100000010988609489e+01,3.158564516328858564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342129992381207160e+01,5.283829299118505105e+02,1.728876426382914833e-01,1.100000010988609489e+01,3.158418530927320847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342220901471208094e+01,5.283929298619725614e+02,1.729192267710888686e-01,1.100000010988609489e+01,3.158272545525783129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342311810561209029e+01,5.284029298120991598e+02,1.729508094440395383e-01,1.100000010988609489e+01,3.158126560124245412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342402719651209964e+01,5.284129297622304193e+02,1.729823906571434644e-01,1.100000010988609489e+01,3.157980574722707694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342493628741210898e+01,5.284229297123662263e+02,1.730139704104006471e-01,1.100000010988609489e+01,3.157834589321169977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342584537831211833e+01,5.284329296625066945e+02,1.730455487038110862e-01,1.100000010988609489e+01,3.157688603919632259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342675446921212767e+01,5.284429296126517102e+02,1.730771255373748096e-01,1.100000010988609489e+01,3.157542618518094542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342766356011213702e+01,5.284529295628013870e+02,1.731087009110917896e-01,1.100000010988609489e+01,3.157396633116556824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342857265101214637e+01,5.284629295129556112e+02,1.731402748249620260e-01,1.100000010988609489e+01,3.157250647715019107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.342948174191215571e+01,5.284729294631144967e+02,1.731718472789855190e-01,1.100000010988609489e+01,3.157104662313481389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343039083281216506e+01,5.284829294132780433e+02,1.732034182731622685e-01,1.100000010988609489e+01,3.156958676911943672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343129992371217440e+01,5.284929293634461374e+02,1.732349878074923022e-01,1.100000010988609489e+01,3.156812691510405954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343220901461218375e+01,5.285029293136188926e+02,1.732665558819755924e-01,1.100000010988609489e+01,3.156666706108868237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343311810551219310e+01,5.285129292637961953e+02,1.732981224966121392e-01,1.100000010988609489e+01,3.156520720707330519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343402719641220244e+01,5.285229292139781592e+02,1.733296876514019424e-01,1.100000010988609489e+01,3.156374735305792802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343493628731221179e+01,5.285329291641646705e+02,1.733612513463450022e-01,1.100000010988609489e+01,3.156228749904255084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343584537821222114e+01,5.285429291143558430e+02,1.733928135814413185e-01,1.100000010988609489e+01,3.156082764502717367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343675446911223048e+01,5.285529290645515630e+02,1.734243743566908913e-01,1.100000010988609489e+01,3.155936779101179649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343766356001223983e+01,5.285629290147519441e+02,1.734559336720937206e-01,1.100000010988609489e+01,3.155790793699641932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343857265091224917e+01,5.285729289649568727e+02,1.734874915276498064e-01,1.100000010988609489e+01,3.155644808298104214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.343948174181225852e+01,5.285829289151664625e+02,1.735190479233591210e-01,1.100000010988609489e+01,3.155498822896566496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344039083271226787e+01,5.285929288653805997e+02,1.735506028592216921e-01,1.100000010988609489e+01,3.155352837495028779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344129992361227721e+01,5.286029288155993981e+02,1.735821563352375196e-01,1.100000010988609489e+01,3.155206852093491061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344220901451228656e+01,5.286129287658227440e+02,1.736137083514066037e-01,1.100000010988609489e+01,3.155060866691953344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344311810541229590e+01,5.286229287160507511e+02,1.736452589077289443e-01,1.100000010988609489e+01,3.154914881290415626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344402719631230525e+01,5.286329286662833056e+02,1.736768080042045415e-01,1.100000010988609489e+01,3.154768895888877909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344493628721231460e+01,5.286429286165205212e+02,1.737083556408333673e-01,1.100000010988609489e+01,3.154622910487340191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344584537811232394e+01,5.286529285667622844e+02,1.737399018176154497e-01,1.100000010988609489e+01,3.154476925085802474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344675446901233329e+01,5.286629285170087087e+02,1.737714465345507886e-01,1.100000010988609489e+01,3.154330939684264756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344766355991234263e+01,5.286729284672596805e+02,1.738029897916393562e-01,1.100000010988609489e+01,3.154184954282727039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344857265081235198e+01,5.286829284175153134e+02,1.738345315888811804e-01,1.100000010988609489e+01,3.154038968881189321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.344948174171236133e+01,5.286929283677754938e+02,1.738660719262762611e-01,1.100000010988609489e+01,3.153892983479651604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345039083261237067e+01,5.287029283180403354e+02,1.738976108038245705e-01,1.100000010988609489e+01,3.153746998078113886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345129992351238002e+01,5.287129282683097244e+02,1.739291482215261364e-01,1.100000010988609489e+01,3.153601012676576169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345220901441238937e+01,5.287229282185837747e+02,1.739606841793809311e-01,1.100000010988609489e+01,3.153455027275038451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345311810531239871e+01,5.287329281688623723e+02,1.739922186773889823e-01,1.100000010988609489e+01,3.153309041873500734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345402719621240806e+01,5.287429281191456312e+02,1.740237517155502622e-01,1.100000010988609489e+01,3.153163056471963016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345493628711241740e+01,5.287529280694334375e+02,1.740552832938647987e-01,1.100000010988609489e+01,3.153017071070425299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345584537801242675e+01,5.287629280197259050e+02,1.740868134123325639e-01,1.100000010988609489e+01,3.152871085668887581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345675446891243610e+01,5.287729279700229199e+02,1.741183420709535856e-01,1.100000010988609489e+01,3.152725100267349864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345766355981244544e+01,5.287829279203245960e+02,1.741498692697278361e-01,1.100000010988609489e+01,3.152579114865812146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345857265071245479e+01,5.287929278706308196e+02,1.741813950086553431e-01,1.100000010988609489e+01,3.152433129464274428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.345948174161246413e+01,5.288029278209417043e+02,1.742129192877360788e-01,1.100000010988609489e+01,3.152287144062736711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346039083251247348e+01,5.288129277712571366e+02,1.742444421069700433e-01,1.100000010988609489e+01,3.152141158661198993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346129992341248283e+01,5.288229277215772299e+02,1.742759634663572643e-01,1.100000010988609489e+01,3.151995173259661276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346220901431249217e+01,5.288329276719018708e+02,1.743074833658977141e-01,1.100000010988609489e+01,3.151849187858123558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346311810521250152e+01,5.288429276222311728e+02,1.743390018055913926e-01,1.100000010988609489e+01,3.151703202456585841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346402719611251086e+01,5.288529275725650223e+02,1.743705187854382999e-01,1.100000010988609489e+01,3.151557217055048123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346493628701252021e+01,5.288629275229035329e+02,1.744020343054384636e-01,1.100000010988609489e+01,3.151411231653510406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346584537791252956e+01,5.288729274732465910e+02,1.744335483655918562e-01,1.100000010988609489e+01,3.151265246251972688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346675446881253890e+01,5.288829274235943103e+02,1.744650609658984775e-01,1.100000010988609489e+01,3.151119260850434971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346766355971254825e+01,5.288929273739465771e+02,1.744965721063583275e-01,1.100000010988609489e+01,3.150973275448897253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346857265061255760e+01,5.289029273243035050e+02,1.745280817869714063e-01,1.100000010988609489e+01,3.150827290047359536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.346948174151256694e+01,5.289129272746649804e+02,1.745595900077377138e-01,1.100000010988609489e+01,3.150681304645821818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347039083241257629e+01,5.289229272250310032e+02,1.745910967686572779e-01,1.100000010988609489e+01,3.150535319244284101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347129992331258563e+01,5.289329271754016872e+02,1.746226020697300707e-01,1.100000010988609489e+01,3.150389333842746383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347220901421259498e+01,5.289429271257769187e+02,1.746541059109560923e-01,1.100000010988609489e+01,3.150243348441208666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347311810511260433e+01,5.289529270761568114e+02,1.746856082923353426e-01,1.100000010988609489e+01,3.150097363039670948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347402719601261367e+01,5.289629270265412515e+02,1.747171092138678217e-01,1.100000010988609489e+01,3.149951377638133231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347493628691262302e+01,5.289729269769303528e+02,1.747486086755535295e-01,1.100000010988609489e+01,3.149805392236595513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347584537781263236e+01,5.289829269273240016e+02,1.747801066773924383e-01,1.100000010988609489e+01,3.149659406835057796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347675446871264171e+01,5.289929268777223115e+02,1.748116032193845759e-01,1.100000010988609489e+01,3.149513421433520078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347766355961265106e+01,5.290029268281251689e+02,1.748430983015299423e-01,1.100000010988609489e+01,3.149367436031982360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347857265051266040e+01,5.290129267785326874e+02,1.748745919238285373e-01,1.100000010988609489e+01,3.149221450630444643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.347948174141266975e+01,5.290229267289447534e+02,1.749060840862803612e-01,1.100000010988609489e+01,3.149075465228906925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348039083231267909e+01,5.290329266793613670e+02,1.749375747888854138e-01,1.100000010988609489e+01,3.148929479827369208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348129992321268844e+01,5.290429266297826416e+02,1.749690640316436951e-01,1.100000010988609489e+01,3.148783494425831490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348220901411269779e+01,5.290529265802084637e+02,1.750005518145551775e-01,1.100000010988609489e+01,3.148637509024293773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348311810501270713e+01,5.290629265306389470e+02,1.750320381376198886e-01,1.100000010988609489e+01,3.148491523622756055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348402719591271648e+01,5.290729264810739778e+02,1.750635230008378285e-01,1.100000010988609489e+01,3.148345538221218338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348493628681272583e+01,5.290829264315136697e+02,1.750950064042089693e-01,1.100000010988609489e+01,3.148199552819680620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348584537771273517e+01,5.290929263819579091e+02,1.751264883477333389e-01,1.100000010988609489e+01,3.148053567418142903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348675446861274452e+01,5.291029263324066960e+02,1.751579688314109373e-01,1.100000010988609489e+01,3.147907582016605185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348766355951275386e+01,5.291129262828601441e+02,1.751894478552417367e-01,1.100000010988609489e+01,3.147761596615067468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348857265041276321e+01,5.291229262333181396e+02,1.752209254192257648e-01,1.100000010988609489e+01,3.147615611213529750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.348948174131277256e+01,5.291329261837807962e+02,1.752524015233629939e-01,1.100000010988609489e+01,3.147469625811992033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349039083221278190e+01,5.291429261342480004e+02,1.752838761676534518e-01,1.100000010988609489e+01,3.147323640410454315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349129992311279125e+01,5.291529260847198657e+02,1.753153493520971384e-01,1.100000010988609489e+01,3.147177655008916598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349220901401280059e+01,5.291629260351962785e+02,1.753468210766940261e-01,1.100000010988609489e+01,3.147031669607378880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349311810491280994e+01,5.291729259856772387e+02,1.753782913414441147e-01,1.100000010988609489e+01,3.146885684205841163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349402719581281929e+01,5.291829259361628601e+02,1.754097601463474321e-01,1.100000010988609489e+01,3.146739698804303445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349493628671282863e+01,5.291929258866530290e+02,1.754412274914039505e-01,1.100000010988609489e+01,3.146593713402765728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349584537761283798e+01,5.292029258371478591e+02,1.754726933766136976e-01,1.100000010988609489e+01,3.146447728001228010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349675446851284732e+01,5.292129257876472366e+02,1.755041578019766457e-01,1.100000010988609489e+01,3.146301742599690292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349766355941285667e+01,5.292229257381511616e+02,1.755356207674927949e-01,1.100000010988609489e+01,3.146155757198152575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349857265031286602e+01,5.292329256886597477e+02,1.755670822731621727e-01,1.100000010988609489e+01,3.146009771796614857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.349948174121287536e+01,5.292429256391728813e+02,1.755985423189847516e-01,1.100000010988609489e+01,3.145863786395077140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350039083211288471e+01,5.292529255896906761e+02,1.756300009049605315e-01,1.100000010988609489e+01,3.145717800993539422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350129992301289406e+01,5.292629255402130184e+02,1.756614580310895402e-01,1.100000010988609489e+01,3.145571815592001705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350220901391290340e+01,5.292729254907399081e+02,1.756929136973717498e-01,1.100000010988609489e+01,3.145425830190463987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350311810481291275e+01,5.292829254412714590e+02,1.757243679038071604e-01,1.100000010988609489e+01,3.145279844788926270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350402719571292209e+01,5.292929253918075574e+02,1.757558206503957721e-01,1.100000010988609489e+01,3.145133859387388552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350493628661293144e+01,5.293029253423483169e+02,1.757872719371375847e-01,1.100000010988609489e+01,3.144987873985850835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350584537751294079e+01,5.293129252928936239e+02,1.758187217640326261e-01,1.100000010988609489e+01,3.144841888584313117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350675446841295013e+01,5.293229252434434784e+02,1.758501701310808685e-01,1.100000010988609489e+01,3.144695903182775400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350766355931295948e+01,5.293329251939979940e+02,1.758816170382823119e-01,1.100000010988609489e+01,3.144549917781237682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350857265021296882e+01,5.293429251445570571e+02,1.759130624856369562e-01,1.100000010988609489e+01,3.144403932379699965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.350948174111297817e+01,5.293529250951206677e+02,1.759445064731448016e-01,1.100000010988609489e+01,3.144257946978162247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351039083201298752e+01,5.293629250456889395e+02,1.759759490008058480e-01,1.100000010988609489e+01,3.144111961576624530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351129992291299686e+01,5.293729249962617587e+02,1.760073900686200954e-01,1.100000010988609489e+01,3.143965976175086812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351220901381300621e+01,5.293829249468392391e+02,1.760388296765875438e-01,1.100000010988609489e+01,3.143819990773549095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351311810471301555e+01,5.293929248974212669e+02,1.760702678247081931e-01,1.100000010988609489e+01,3.143674005372011377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351402719561302490e+01,5.294029248480078422e+02,1.761017045129820435e-01,1.100000010988609489e+01,3.143528019970473660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351493628651303425e+01,5.294129247985990787e+02,1.761331397414090671e-01,1.100000010988609489e+01,3.143382034568935942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351584537741304359e+01,5.294229247491948627e+02,1.761645735099892918e-01,1.100000010988609489e+01,3.143236049167398224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351675446831305294e+01,5.294329246997951941e+02,1.761960058187227174e-01,1.100000010988609489e+01,3.143090063765860507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351766355921306229e+01,5.294429246504001867e+02,1.762274366676093440e-01,1.100000010988609489e+01,3.142944078364322789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351857265011307163e+01,5.294529246010097268e+02,1.762588660566491716e-01,1.100000010988609489e+01,3.142798092962785072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.351948174101308098e+01,5.294629245516238143e+02,1.762902939858422002e-01,1.100000010988609489e+01,3.142652107561247354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352039083191309032e+01,5.294729245022425630e+02,1.763217204551884021e-01,1.100000010988609489e+01,3.142506122159709637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352129992281309967e+01,5.294829244528658592e+02,1.763531454646878049e-01,1.100000010988609489e+01,3.142360136758171919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352220901371310902e+01,5.294929244034938165e+02,1.763845690143404088e-01,1.100000010988609489e+01,3.142214151356634202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352311810461311836e+01,5.295029243541263213e+02,1.764159911041461859e-01,1.100000010988609489e+01,3.142068165955096484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352402719551312771e+01,5.295129243047633736e+02,1.764474117341051640e-01,1.100000010988609489e+01,3.141922180553558767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352493628641313705e+01,5.295229242554050870e+02,1.764788309042173431e-01,1.100000010988609489e+01,3.141776195152021049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352584537731314640e+01,5.295329242060513479e+02,1.765102486144826954e-01,1.100000010988609489e+01,3.141630209750483332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352675446821315575e+01,5.295429241567021563e+02,1.765416648649012488e-01,1.100000010988609489e+01,3.141484224348945614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352766355911316509e+01,5.295529241073576259e+02,1.765730796554729753e-01,1.100000010988609489e+01,3.141338238947407897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352857265001317444e+01,5.295629240580176429e+02,1.766044929861979029e-01,1.100000010988609489e+01,3.141192253545870179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.352948174091318378e+01,5.295729240086822074e+02,1.766359048570760037e-01,1.100000010988609489e+01,3.141046268144332462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353039083181319313e+01,5.295829239593514330e+02,1.766673152681073056e-01,1.100000010988609489e+01,3.140900282742794744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353129992271320248e+01,5.295929239100252062e+02,1.766987242192917806e-01,1.100000010988609489e+01,3.140754297341257027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353220901361321182e+01,5.296029238607035268e+02,1.767301317106294567e-01,1.100000010988609489e+01,3.140608311939719309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353311810451322117e+01,5.296129238113865085e+02,1.767615377421203060e-01,1.100000010988609489e+01,3.140462326538181592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353402719541323052e+01,5.296229237620740378e+02,1.767929423137643563e-01,1.100000010988609489e+01,3.140316341136643874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353493628631323986e+01,5.296329237127661145e+02,1.768243454255615799e-01,1.100000010988609489e+01,3.140170355735106156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353584537721324921e+01,5.296429236634628523e+02,1.768557470775119767e-01,1.100000010988609489e+01,3.140024370333568439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353675446811325855e+01,5.296529236141641377e+02,1.768871472696155744e-01,1.100000010988609489e+01,3.139878384932030721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353766355901326790e+01,5.296629235648699705e+02,1.769185460018723455e-01,1.100000010988609489e+01,3.139732399530493004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353857264991327725e+01,5.296729235155804645e+02,1.769499432742822898e-01,1.100000010988609489e+01,3.139586414128955286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.353948174081328659e+01,5.296829234662955059e+02,1.769813390868454073e-01,1.100000010988609489e+01,3.139440428727417569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354039083171329594e+01,5.296929234170150949e+02,1.770127334395617258e-01,1.100000010988609489e+01,3.139294443325879851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354129992261330528e+01,5.297029233677392313e+02,1.770441263324312176e-01,1.100000010988609489e+01,3.139148457924342134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354220901351331463e+01,5.297129233184680288e+02,1.770755177654538826e-01,1.100000010988609489e+01,3.139002472522804416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354311810441332398e+01,5.297229232692013738e+02,1.771069077386297208e-01,1.100000010988609489e+01,3.138856487121266699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354402719531333332e+01,5.297329232199392663e+02,1.771382962519587323e-01,1.100000010988609489e+01,3.138710501719728981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354493628621334267e+01,5.297429231706818200e+02,1.771696833054409170e-01,1.100000010988609489e+01,3.138564516318191264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354584537711335201e+01,5.297529231214289211e+02,1.772010688990762750e-01,1.100000010988609489e+01,3.138418530916653546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354675446801336136e+01,5.297629230721805698e+02,1.772324530328648062e-01,1.100000010988609489e+01,3.138272545515115829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354766355891337071e+01,5.297729230229368795e+02,1.772638357068065107e-01,1.100000010988609489e+01,3.138126560113578111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354857264981338005e+01,5.297829229736977368e+02,1.772952169209013884e-01,1.100000010988609489e+01,3.137980574712040394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.354948174071338940e+01,5.297929229244631415e+02,1.773265966751494394e-01,1.100000010988609489e+01,3.137834589310502676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355039083161339875e+01,5.298029228752332074e+02,1.773579749695506635e-01,1.100000010988609489e+01,3.137688603908964959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355129992251340809e+01,5.298129228260078207e+02,1.773893518041050610e-01,1.100000010988609489e+01,3.137542618507427241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355220901341341744e+01,5.298229227767869816e+02,1.774207271788126317e-01,1.100000010988609489e+01,3.137396633105889523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355311810431342678e+01,5.298329227275706899e+02,1.774521010936733756e-01,1.100000010988609489e+01,3.137250647704351806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355402719521343613e+01,5.298429226783590593e+02,1.774834735486872928e-01,1.100000010988609489e+01,3.137104662302814088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355493628611344548e+01,5.298529226291519763e+02,1.775148445438543832e-01,1.100000010988609489e+01,3.136958676901276371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355584537701345482e+01,5.298629225799494407e+02,1.775462140791746468e-01,1.100000010988609489e+01,3.136812691499738653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355675446791346417e+01,5.298729225307515662e+02,1.775775821546480560e-01,1.100000010988609489e+01,3.136666706098200936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355766355881347351e+01,5.298829224815582393e+02,1.776089487702746383e-01,1.100000010988609489e+01,3.136520720696663218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355857264971348286e+01,5.298929224323694598e+02,1.776403139260543940e-01,1.100000010988609489e+01,3.136374735295125501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.355948174061349221e+01,5.299029223831852278e+02,1.776716776219873228e-01,1.100000010988609489e+01,3.136228749893587783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356039083151350155e+01,5.299129223340056569e+02,1.777030398580733972e-01,1.100000010988609489e+01,3.136082764492050066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356129992241351090e+01,5.299229222848306335e+02,1.777344006343126448e-01,1.100000010988609489e+01,3.135936779090512348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356220901331352024e+01,5.299329222356601576e+02,1.777657599507050379e-01,1.100000010988609489e+01,3.135790793688974631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356311810421352959e+01,5.299429221864942292e+02,1.777971178072506042e-01,1.100000010988609489e+01,3.135644808287436913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356402719511353894e+01,5.299529221373329619e+02,1.778284742039493438e-01,1.100000010988609489e+01,3.135498822885899196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356493628601354828e+01,5.299629220881762421e+02,1.778598291408012289e-01,1.100000010988609489e+01,3.135352837484361478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356584537691355763e+01,5.299729220390240698e+02,1.778911826178062872e-01,1.100000010988609489e+01,3.135206852082823761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356675446781356698e+01,5.299829219898764450e+02,1.779225346349644910e-01,1.100000010988609489e+01,3.135060866681286043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356766355871357632e+01,5.299929219407334813e+02,1.779538851922758680e-01,1.100000010988609489e+01,3.134914881279748326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356857264961358567e+01,5.300029218915950651e+02,1.779852342897403905e-01,1.100000010988609489e+01,3.134768895878210608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.356948174051359501e+01,5.300129218424611963e+02,1.780165819273580863e-01,1.100000010988609489e+01,3.134622910476672891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357039083141360436e+01,5.300229217933319887e+02,1.780479281051289275e-01,1.100000010988609489e+01,3.134476925075135173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357129992231361371e+01,5.300329217442073286e+02,1.780792728230529420e-01,1.100000010988609489e+01,3.134330939673597455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357220901321362305e+01,5.300429216950872160e+02,1.781106160811301020e-01,1.100000010988609489e+01,3.134184954272059738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357311810411363240e+01,5.300529216459716508e+02,1.781419578793604075e-01,1.100000010988609489e+01,3.134038968870522020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357402719501364174e+01,5.300629215968606331e+02,1.781732982177438862e-01,1.100000010988609489e+01,3.133892983468984303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357493628591365109e+01,5.300729215477542766e+02,1.782046370962805104e-01,1.100000010988609489e+01,3.133746998067446585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357584537681366044e+01,5.300829214986524676e+02,1.782359745149702801e-01,1.100000010988609489e+01,3.133601012665908868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357675446771366978e+01,5.300929214495552060e+02,1.782673104738131953e-01,1.100000010988609489e+01,3.133455027264371150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357766355861367913e+01,5.301029214004624919e+02,1.782986449728092837e-01,1.100000010988609489e+01,3.133309041862833433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357857264951368848e+01,5.301129213513744389e+02,1.783299780119585176e-01,1.100000010988609489e+01,3.133163056461295715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.357948174041369782e+01,5.301229213022909335e+02,1.783613095912608970e-01,1.100000010988609489e+01,3.133017071059757998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358039083131370717e+01,5.301329212532119755e+02,1.783926397107164219e-01,1.100000010988609489e+01,3.132871085658220280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358129992221371651e+01,5.301429212041375649e+02,1.784239683703250923e-01,1.100000010988609489e+01,3.132725100256682563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358220901311372586e+01,5.301529211550678156e+02,1.784552955700869081e-01,1.100000010988609489e+01,3.132579114855144845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358311810401373521e+01,5.301629211060026137e+02,1.784866213100018695e-01,1.100000010988609489e+01,3.132433129453607128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358402719491374455e+01,5.301729210569419593e+02,1.785179455900700041e-01,1.100000010988609489e+01,3.132287144052069410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358493628581375390e+01,5.301829210078858523e+02,1.785492684102912841e-01,1.100000010988609489e+01,3.132141158650531693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358584537671376324e+01,5.301929209588344065e+02,1.785805897706657097e-01,1.100000010988609489e+01,3.131995173248993975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358675446761377259e+01,5.302029209097875082e+02,1.786119096711932808e-01,1.100000010988609489e+01,3.131849187847456258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358766355851378194e+01,5.302129208607451574e+02,1.786432281118739973e-01,1.100000010988609489e+01,3.131703202445918540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358857264941379128e+01,5.302229208117073540e+02,1.786745450927078316e-01,1.100000010988609489e+01,3.131557217044380823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.358948174031380063e+01,5.302329207626740981e+02,1.787058606136948113e-01,1.100000010988609489e+01,3.131411231642843105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359039083121380997e+01,5.302429207136455034e+02,1.787371746748349366e-01,1.100000010988609489e+01,3.131265246241305387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359129992211381932e+01,5.302529206646214561e+02,1.787684872761282073e-01,1.100000010988609489e+01,3.131119260839767670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359220901301382867e+01,5.302629206156019563e+02,1.787997984175746236e-01,1.100000010988609489e+01,3.130973275438229952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359311810391383801e+01,5.302729205665870040e+02,1.788311080991741853e-01,1.100000010988609489e+01,3.130827290036692235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359402719481384736e+01,5.302829205175765992e+02,1.788624163209268925e-01,1.100000010988609489e+01,3.130681304635154517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359493628571385671e+01,5.302929204685708555e+02,1.788937230828327174e-01,1.100000010988609489e+01,3.130535319233616800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359584537661386605e+01,5.303029204195696593e+02,1.789250283848916878e-01,1.100000010988609489e+01,3.130389333832079082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359675446751387540e+01,5.303129203705730106e+02,1.789563322271038037e-01,1.100000010988609489e+01,3.130243348430541365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359766355841388474e+01,5.303229203215809093e+02,1.789876346094690651e-01,1.100000010988609489e+01,3.130097363029003647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359857264931389409e+01,5.303329202725933555e+02,1.790189355319874442e-01,1.100000010988609489e+01,3.129951377627465930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.359948174021390344e+01,5.303429202236104629e+02,1.790502349946589689e-01,1.100000010988609489e+01,3.129805392225928212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360039083111391278e+01,5.303529201746321178e+02,1.790815329974836112e-01,1.100000010988609489e+01,3.129659406824390495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360129992201392213e+01,5.303629201256583201e+02,1.791128295404613990e-01,1.100000010988609489e+01,3.129513421422852777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360220901291393147e+01,5.303729200766890699e+02,1.791441246235923324e-01,1.100000010988609489e+01,3.129367436021315060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360311810381394082e+01,5.303829200277243672e+02,1.791754182468763834e-01,1.100000010988609489e+01,3.129221450619777342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360402719471395017e+01,5.303929199787643256e+02,1.792067104103135800e-01,1.100000010988609489e+01,3.129075465218239625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360493628561395951e+01,5.304029199298088315e+02,1.792380011139038942e-01,1.100000010988609489e+01,3.128929479816701907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360584537651396886e+01,5.304129198808578849e+02,1.792692903576473540e-01,1.100000010988609489e+01,3.128783494415164190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360675446741397820e+01,5.304229198319114857e+02,1.793005781415439315e-01,1.100000010988609489e+01,3.128637509013626472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360766355831398755e+01,5.304329197829696341e+02,1.793318644655936545e-01,1.100000010988609489e+01,3.128491523612088755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360857264921399690e+01,5.304429197340323299e+02,1.793631493297964952e-01,1.100000010988609489e+01,3.128345538210551037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.360948174011400624e+01,5.304529196850996868e+02,1.793944327341524536e-01,1.100000010988609489e+01,3.128199552809013319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361039083101401559e+01,5.304629196361715913e+02,1.794257146786615575e-01,1.100000010988609489e+01,3.128053567407475602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361129992191402494e+01,5.304729195872480432e+02,1.794569951633237792e-01,1.100000010988609489e+01,3.127907582005937884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361220901281403428e+01,5.304829195383290426e+02,1.794882741881391186e-01,1.100000010988609489e+01,3.127761596604400167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361311810371404363e+01,5.304929194894145894e+02,1.795195517531076035e-01,1.100000010988609489e+01,3.127615611202862449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361402719461405297e+01,5.305029194405046837e+02,1.795508278582292061e-01,1.100000010988609489e+01,3.127469625801324732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361493628551406232e+01,5.305129193915994392e+02,1.795821025035039264e-01,1.100000010988609489e+01,3.127323640399787014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361584537641407167e+01,5.305229193426987422e+02,1.796133756889317645e-01,1.100000010988609489e+01,3.127177654998249297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361675446731408101e+01,5.305329192938025926e+02,1.796446474145127481e-01,1.100000010988609489e+01,3.127031669596711579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361766355821409036e+01,5.305429192449109905e+02,1.796759176802468494e-01,1.100000010988609489e+01,3.126885684195173862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361857264911409970e+01,5.305529191960239359e+02,1.797071864861340684e-01,1.100000010988609489e+01,3.126739698793636144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.361948174001410905e+01,5.305629191471414288e+02,1.797384538321744052e-01,1.100000010988609489e+01,3.126593713392098427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362039083091411840e+01,5.305729190982635828e+02,1.797697197183678597e-01,1.100000010988609489e+01,3.126447727990560709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362129992181412774e+01,5.305829190493902843e+02,1.798009841447144319e-01,1.100000010988609489e+01,3.126301742589022992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362220901271413709e+01,5.305929190005215332e+02,1.798322471112141219e-01,1.100000010988609489e+01,3.126155757187485274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362311810361414643e+01,5.306029189516573297e+02,1.798635086178669296e-01,1.100000010988609489e+01,3.126009771785947557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362402719451415578e+01,5.306129189027976736e+02,1.798947686646728550e-01,1.100000010988609489e+01,3.125863786384409839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362493628541416513e+01,5.306229188539425650e+02,1.799260272516318981e-01,1.100000010988609489e+01,3.125717800982872122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362584537631417447e+01,5.306329188050920038e+02,1.799572843787440590e-01,1.100000010988609489e+01,3.125571815581334404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362675446721418382e+01,5.306429187562461038e+02,1.799885400460093376e-01,1.100000010988609489e+01,3.125425830179796687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362766355811419317e+01,5.306529187074047513e+02,1.800197942534277340e-01,1.100000010988609489e+01,3.125279844778258969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362857264901420251e+01,5.306629186585679463e+02,1.800510470009992481e-01,1.100000010988609489e+01,3.125133859376721251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.362948173991421186e+01,5.306729186097356887e+02,1.800822982887238799e-01,1.100000010988609489e+01,3.124987873975183534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363039083081422120e+01,5.306829185609079786e+02,1.801135481166016294e-01,1.100000010988609489e+01,3.124841888573645816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363129992171423055e+01,5.306929185120848160e+02,1.801447964846324690e-01,1.100000010988609489e+01,3.124695903172108099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363220901261423990e+01,5.307029184632662009e+02,1.801760433928164262e-01,1.100000010988609489e+01,3.124549917770570381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363311810351424924e+01,5.307129184144521332e+02,1.802072888411535012e-01,1.100000010988609489e+01,3.124403932369032664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363402719441425859e+01,5.307229183656427267e+02,1.802385328296436939e-01,1.100000010988609489e+01,3.124257946967494946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363493628531426793e+01,5.307329183168378677e+02,1.802697753582869766e-01,1.100000010988609489e+01,3.124111961565957229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363584537621427728e+01,5.307429182680375561e+02,1.803010164270833771e-01,1.100000010988609489e+01,3.123965976164419511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363675446711428663e+01,5.307529182192417920e+02,1.803322560360328952e-01,1.100000010988609489e+01,3.123819990762881794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363766355801429597e+01,5.307629181704505754e+02,1.803634941851355034e-01,1.100000010988609489e+01,3.123674005361344076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363857264891430532e+01,5.307729181216639063e+02,1.803947308743912292e-01,1.100000010988609489e+01,3.123528019959806359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.363948173981431466e+01,5.307829180728817846e+02,1.804259661038000728e-01,1.100000010988609489e+01,3.123382034558268641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364039083071432401e+01,5.307929180241042104e+02,1.804571998733620064e-01,1.100000010988609489e+01,3.123236049156730924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364129992161433336e+01,5.308029179753311837e+02,1.804884321830770577e-01,1.100000010988609489e+01,3.123090063755193206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364220901251434270e+01,5.308129179265628181e+02,1.805196630329451990e-01,1.100000010988609489e+01,3.122944078353655489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364311810341435205e+01,5.308229178777990001e+02,1.805508924229664580e-01,1.100000010988609489e+01,3.122798092952117771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364402719431436140e+01,5.308329178290397294e+02,1.805821203531408070e-01,1.100000010988609489e+01,3.122652107550580054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364493628521437074e+01,5.308429177802850063e+02,1.806133468234682737e-01,1.100000010988609489e+01,3.122506122149042336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364584537611438009e+01,5.308529177315348306e+02,1.806445718339488304e-01,1.100000010988609489e+01,3.122360136747504619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364675446701438943e+01,5.308629176827892024e+02,1.806757953845824771e-01,1.100000010988609489e+01,3.122214151345966901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364766355791439878e+01,5.308729176340481217e+02,1.807070174753692415e-01,1.100000010988609489e+01,3.122068165944429183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364857264881440813e+01,5.308829175853115885e+02,1.807382381063090959e-01,1.100000010988609489e+01,3.121922180542891466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.364948173971441747e+01,5.308929175365796027e+02,1.807694572774020680e-01,1.100000010988609489e+01,3.121776195141353748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365039083061442682e+01,5.309029174878521644e+02,1.808006749886481301e-01,1.100000010988609489e+01,3.121630209739816031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365129992151443616e+01,5.309129174391292736e+02,1.808318912400472822e-01,1.100000010988609489e+01,3.121484224338278313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365220901241444551e+01,5.309229173904110439e+02,1.808631060315995243e-01,1.100000010988609489e+01,3.121338238936740596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365311810331445486e+01,5.309329173416973617e+02,1.808943193633048840e-01,1.100000010988609489e+01,3.121192253535202878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365402719421446420e+01,5.309429172929882270e+02,1.809255312351633338e-01,1.100000010988609489e+01,3.121046268133665161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365493628511447355e+01,5.309529172442836398e+02,1.809567416471748735e-01,1.100000010988609489e+01,3.120900282732127443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365584537601448289e+01,5.309629171955836000e+02,1.809879505993395032e-01,1.100000010988609489e+01,3.120754297330589726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365675446691449224e+01,5.309729171468881077e+02,1.810191580916572229e-01,1.100000010988609489e+01,3.120608311929052008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365766355781450159e+01,5.309829170981971629e+02,1.810503641241280326e-01,1.100000010988609489e+01,3.120462326527514291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365857264871451093e+01,5.309929170495107655e+02,1.810815686967519600e-01,1.100000010988609489e+01,3.120316341125976573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.365948173961452028e+01,5.310029170008289157e+02,1.811127718095289774e-01,1.100000010988609489e+01,3.120170355724438856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366039083051452963e+01,5.310129169521516133e+02,1.811439734624590847e-01,1.100000010988609489e+01,3.120024370322901138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366129992141453897e+01,5.310229169034788583e+02,1.811751736555422820e-01,1.100000010988609489e+01,3.119878384921363421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366220901231454832e+01,5.310329168548106509e+02,1.812063723887785693e-01,1.100000010988609489e+01,3.119732399519825703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366311810321455766e+01,5.310429168061469909e+02,1.812375696621679466e-01,1.100000010988609489e+01,3.119586414118287986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366402719411456701e+01,5.310529167574878784e+02,1.812687654757104139e-01,1.100000010988609489e+01,3.119440428716750268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366493628501457636e+01,5.310629167088334270e+02,1.812999598294059433e-01,1.100000010988609489e+01,3.119294443315212551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366584537591458570e+01,5.310729166601835232e+02,1.813311527232545628e-01,1.100000010988609489e+01,3.119148457913674833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366675446681459505e+01,5.310829166115381668e+02,1.813623441572562722e-01,1.100000010988609489e+01,3.119002472512137115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366766355771460439e+01,5.310929165628973578e+02,1.813935341314110716e-01,1.100000010988609489e+01,3.118856487110599398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366857264861461374e+01,5.311029165142610964e+02,1.814247226457189610e-01,1.100000010988609489e+01,3.118710501709061680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.366948173951462309e+01,5.311129164656293824e+02,1.814559097001799404e-01,1.100000010988609489e+01,3.118564516307523963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367039083041463243e+01,5.311229164170022159e+02,1.814870952947940097e-01,1.100000010988609489e+01,3.118418530905986245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367129992131464178e+01,5.311329163683795969e+02,1.815182794295611413e-01,1.100000010988609489e+01,3.118272545504448528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367220901221465112e+01,5.311429163197615253e+02,1.815494621044813628e-01,1.100000010988609489e+01,3.118126560102910810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367311810311466047e+01,5.311529162711480012e+02,1.815806433195546743e-01,1.100000010988609489e+01,3.117980574701373093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367402719401466982e+01,5.311629162225390246e+02,1.816118230747810480e-01,1.100000010988609489e+01,3.117834589299835375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367493628491467916e+01,5.311729161739345955e+02,1.816430013701605117e-01,1.100000010988609489e+01,3.117688603898297658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367584537581468851e+01,5.311829161253347138e+02,1.816741782056930654e-01,1.100000010988609489e+01,3.117542618496759940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367675446671469786e+01,5.311929160767393796e+02,1.817053535813786813e-01,1.100000010988609489e+01,3.117396633095222223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367766355761470720e+01,5.312029160281485929e+02,1.817365274972173872e-01,1.100000010988609489e+01,3.117250647693684505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367857264851471655e+01,5.312129159795623536e+02,1.817676999532091553e-01,1.100000010988609489e+01,3.117104662292146788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.367948173941472589e+01,5.312229159309806619e+02,1.817988709493540134e-01,1.100000010988609489e+01,3.116958676890609070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368039083031473524e+01,5.312329158824035176e+02,1.818300404856519337e-01,1.100000010988609489e+01,3.116812691489071353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368129992121474459e+01,5.312429158338309207e+02,1.818612085621029439e-01,1.100000010988609489e+01,3.116666706087533635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368220901211475393e+01,5.312529157852628714e+02,1.818923751787070164e-01,1.100000010988609489e+01,3.116520720685995918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368311810301476328e+01,5.312629157366993695e+02,1.819235403354641789e-01,1.100000010988609489e+01,3.116374735284458200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368402719391477262e+01,5.312729156881404151e+02,1.819547040323744036e-01,1.100000010988609489e+01,3.116228749882920483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368493628481478197e+01,5.312829156395860082e+02,1.819858662694377183e-01,1.100000010988609489e+01,3.116082764481382765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368584537571479132e+01,5.312929155910361487e+02,1.820170270466540952e-01,1.100000010988609489e+01,3.115936779079845047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368675446661480066e+01,5.313029155424908367e+02,1.820481863640235343e-01,1.100000010988609489e+01,3.115790793678307330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368766355751481001e+01,5.313129154939500722e+02,1.820793442215460634e-01,1.100000010988609489e+01,3.115644808276769612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368857264841481935e+01,5.313229154454138552e+02,1.821105006192216547e-01,1.100000010988609489e+01,3.115498822875231895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.368948173931482870e+01,5.313329153968821856e+02,1.821416555570503082e-01,1.100000010988609489e+01,3.115352837473694177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369039083021483805e+01,5.313429153483550635e+02,1.821728090350320517e-01,1.100000010988609489e+01,3.115206852072156460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369129992111484739e+01,5.313529152998324889e+02,1.822039610531668574e-01,1.100000010988609489e+01,3.115060866670618742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369220901201485674e+01,5.313629152513144618e+02,1.822351116114547254e-01,1.100000010988609489e+01,3.114914881269081025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369311810291486609e+01,5.313729152028009821e+02,1.822662607098956555e-01,1.100000010988609489e+01,3.114768895867543307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369402719381487543e+01,5.313829151542920499e+02,1.822974083484896479e-01,1.100000010988609489e+01,3.114622910466005590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369493628471488478e+01,5.313929151057876652e+02,1.823285545272367025e-01,1.100000010988609489e+01,3.114476925064467872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369584537561489412e+01,5.314029150572878279e+02,1.823596992461368471e-01,1.100000010988609489e+01,3.114330939662930155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369675446651490347e+01,5.314129150087925382e+02,1.823908425051900539e-01,1.100000010988609489e+01,3.114184954261392437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369766355741491282e+01,5.314229149603017959e+02,1.824219843043963230e-01,1.100000010988609489e+01,3.114038968859854720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369857264831492216e+01,5.314329149118156010e+02,1.824531246437556542e-01,1.100000010988609489e+01,3.113892983458317002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.369948173921493151e+01,5.314429148633339537e+02,1.824842635232680477e-01,1.100000010988609489e+01,3.113746998056779285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370039083011494085e+01,5.314529148148568538e+02,1.825154009429335034e-01,1.100000010988609489e+01,3.113601012655241567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370129992101495020e+01,5.314629147663843014e+02,1.825465369027520213e-01,1.100000010988609489e+01,3.113455027253703850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370220901191495955e+01,5.314729147179162965e+02,1.825776714027236014e-01,1.100000010988609489e+01,3.113309041852166132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370311810281496889e+01,5.314829146694528390e+02,1.826088044428482438e-01,1.100000010988609489e+01,3.113163056450628415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370402719371497824e+01,5.314929146209939290e+02,1.826399360231259206e-01,1.100000010988609489e+01,3.113017071049090697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370493628461498758e+01,5.315029145725395665e+02,1.826710661435566596e-01,1.100000010988609489e+01,3.112871085647552979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370584537551499693e+01,5.315129145240897515e+02,1.827021948041404609e-01,1.100000010988609489e+01,3.112725100246015262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370675446641500628e+01,5.315229144756444839e+02,1.827333220048773244e-01,1.100000010988609489e+01,3.112579114844477544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370766355731501562e+01,5.315329144272037638e+02,1.827644477457672501e-01,1.100000010988609489e+01,3.112433129442939827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370857264821502497e+01,5.315429143787675912e+02,1.827955720268102380e-01,1.100000010988609489e+01,3.112287144041402109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.370948173911503432e+01,5.315529143303359660e+02,1.828266948480062604e-01,1.100000010988609489e+01,3.112141158639864392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371039083001504366e+01,5.315629142819088884e+02,1.828578162093553450e-01,1.100000010988609489e+01,3.111995173238326674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371129992091505301e+01,5.315729142334863582e+02,1.828889361108574918e-01,1.100000010988609489e+01,3.111849187836788957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371220901181506235e+01,5.315829141850683754e+02,1.829200545525126731e-01,1.100000010988609489e+01,3.111703202435251239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371311810271507170e+01,5.315929141366549402e+02,1.829511715343209166e-01,1.100000010988609489e+01,3.111557217033713522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371402719361508105e+01,5.316029140882460524e+02,1.829822870562822223e-01,1.100000010988609489e+01,3.111411231632175804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371493628451509039e+01,5.316129140398417121e+02,1.830134011183965626e-01,1.100000010988609489e+01,3.111265246230638087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371584537541509974e+01,5.316229139914419193e+02,1.830445137206639650e-01,1.100000010988609489e+01,3.111119260829100369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371675446631510908e+01,5.316329139430466739e+02,1.830756248630844019e-01,1.100000010988609489e+01,3.110973275427562652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371766355721511843e+01,5.316429138946559760e+02,1.831067345456579010e-01,1.100000010988609489e+01,3.110827290026024934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371857264811512778e+01,5.316529138462698256e+02,1.831378427683844345e-01,1.100000010988609489e+01,3.110681304624487217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.371948173901513712e+01,5.316629137978882227e+02,1.831689495312640303e-01,1.100000010988609489e+01,3.110535319222949499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372039082991514647e+01,5.316729137495111672e+02,1.832000548342966606e-01,1.100000010988609489e+01,3.110389333821411782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372129992081515582e+01,5.316829137011385455e+02,1.832311586774823531e-01,1.100000010988609489e+01,3.110243348419874064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372220901171516516e+01,5.316929136527704713e+02,1.832622610608210800e-01,1.100000010988609489e+01,3.110097363018336347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372311810261517451e+01,5.317029136044069446e+02,1.832933619843128692e-01,1.100000010988609489e+01,3.109951377616798629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372402719351518385e+01,5.317129135560479654e+02,1.833244614479576928e-01,1.100000010988609489e+01,3.109805392215260911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372493628441519320e+01,5.317229135076935336e+02,1.833555594517555509e-01,1.100000010988609489e+01,3.109659406813723194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372584537531520255e+01,5.317329134593436493e+02,1.833866559957064712e-01,1.100000010988609489e+01,3.109513421412185476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372675446621521189e+01,5.317429134109983124e+02,1.834177510798104260e-01,1.100000010988609489e+01,3.109367436010647759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372766355711522124e+01,5.317529133626575231e+02,1.834488447040674153e-01,1.100000010988609489e+01,3.109221450609110041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372857264801523058e+01,5.317629133143212812e+02,1.834799368684774667e-01,1.100000010988609489e+01,3.109075465207572324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.372948173891523993e+01,5.317729132659895868e+02,1.835110275730405527e-01,1.100000010988609489e+01,3.108929479806034606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373039082981524928e+01,5.317829132176624398e+02,1.835421168177566731e-01,1.100000010988609489e+01,3.108783494404496889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373129992071525862e+01,5.317929131693398404e+02,1.835732046026258280e-01,1.100000010988609489e+01,3.108637509002959171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373220901161526797e+01,5.318029131210217884e+02,1.836042909276480173e-01,1.100000010988609489e+01,3.108491523601421454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373311810251527731e+01,5.318129130727082838e+02,1.836353757928232411e-01,1.100000010988609489e+01,3.108345538199883736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373402719341528666e+01,5.318229130243992131e+02,1.836664591981515271e-01,1.100000010988609489e+01,3.108199552798346019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373493628431529601e+01,5.318329129760946898e+02,1.836975411436328476e-01,1.100000010988609489e+01,3.108053567396808301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373584537521530535e+01,5.318429129277947141e+02,1.837286216292672025e-01,1.100000010988609489e+01,3.107907581995270584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373675446611531470e+01,5.318529128794992857e+02,1.837597006550545919e-01,1.100000010988609489e+01,3.107761596593732866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373766355701532405e+01,5.318629128312084049e+02,1.837907782209950158e-01,1.100000010988609489e+01,3.107615611192195149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373857264791533339e+01,5.318729127829220715e+02,1.838218543270884742e-01,1.100000010988609489e+01,3.107469625790657431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.373948173881534274e+01,5.318829127346402856e+02,1.838529289733349670e-01,1.100000010988609489e+01,3.107323640389119714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374039082971535208e+01,5.318929126863630472e+02,1.838840021597344943e-01,1.100000010988609489e+01,3.107177654987581996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374129992061536143e+01,5.319029126380903563e+02,1.839150738862870282e-01,1.100000010988609489e+01,3.107031669586044278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374220901151537078e+01,5.319129125898222128e+02,1.839461441529925967e-01,1.100000010988609489e+01,3.106885684184506561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374311810241538012e+01,5.319229125415585031e+02,1.839772129598511996e-01,1.100000010988609489e+01,3.106739698782968843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374402719331538947e+01,5.319329124932993409e+02,1.840082803068628370e-01,1.100000010988609489e+01,3.106593713381431126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374493628421539881e+01,5.319429124450447262e+02,1.840393461940275088e-01,1.100000010988609489e+01,3.106447727979893408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374584537511540816e+01,5.319529123967946589e+02,1.840704106213452151e-01,1.100000010988609489e+01,3.106301742578355691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374675446601541751e+01,5.319629123485491391e+02,1.841014735888159282e-01,1.100000010988609489e+01,3.106155757176817973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374766355691542685e+01,5.319729123003081668e+02,1.841325350964396756e-01,1.100000010988609489e+01,3.106009771775280256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374857264781543620e+01,5.319829122520717419e+02,1.841635951442164576e-01,1.100000010988609489e+01,3.105863786373742538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.374948173871544554e+01,5.319929122038398646e+02,1.841946537321462740e-01,1.100000010988609489e+01,3.105717800972204821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375039082961545489e+01,5.320029121556125347e+02,1.842257108602290971e-01,1.100000010988609489e+01,3.105571815570667103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375129992051546424e+01,5.320129121073896385e+02,1.842567665284649547e-01,1.100000010988609489e+01,3.105425830169129386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375220901141547358e+01,5.320229120591712899e+02,1.842878207368538468e-01,1.100000010988609489e+01,3.105279844767591668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375311810231548293e+01,5.320329120109574887e+02,1.843188734853957456e-01,1.100000010988609489e+01,3.105133859366053951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375402719321549228e+01,5.320429119627482351e+02,1.843499247740906788e-01,1.100000010988609489e+01,3.104987873964516233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375493628411550162e+01,5.320529119145435288e+02,1.843809746029386187e-01,1.100000010988609489e+01,3.104841888562978516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375584537501551097e+01,5.320629118663433701e+02,1.844120229719395931e-01,1.100000010988609489e+01,3.104695903161440798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375675446591552031e+01,5.320729118181477588e+02,1.844430698810935743e-01,1.100000010988609489e+01,3.104549917759903081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375766355681552966e+01,5.320829117699566950e+02,1.844741153304005898e-01,1.100000010988609489e+01,3.104403932358365363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375857264771553901e+01,5.320929117217700650e+02,1.845051593198606121e-01,1.100000010988609489e+01,3.104257946956827646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.375948173861554835e+01,5.321029116735879825e+02,1.845362018494736689e-01,1.100000010988609489e+01,3.104111961555289928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376039082951555770e+01,5.321129116254104474e+02,1.845672429192397324e-01,1.100000010988609489e+01,3.103965976153752210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376129992041556704e+01,5.321229115772374598e+02,1.845982825291588303e-01,1.100000010988609489e+01,3.103819990752214493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376220901131557639e+01,5.321329115290690197e+02,1.846293206792309349e-01,1.100000010988609489e+01,3.103674005350676775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376311810221558574e+01,5.321429114809051271e+02,1.846603573694560463e-01,1.100000010988609489e+01,3.103528019949139058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376402719311559508e+01,5.321529114327457819e+02,1.846913925998341921e-01,1.100000010988609489e+01,3.103382034547601340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376493628401560443e+01,5.321629113845908705e+02,1.847224263703653446e-01,1.100000010988609489e+01,3.103236049146063623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376584537491561377e+01,5.321729113364405066e+02,1.847534586810495039e-01,1.100000010988609489e+01,3.103090063744525905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376675446581562312e+01,5.321829112882946902e+02,1.847844895318866698e-01,1.100000010988609489e+01,3.102944078342988188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376766355671563247e+01,5.321929112401534212e+02,1.848155189228768702e-01,1.100000010988609489e+01,3.102798092941450470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376857264761564181e+01,5.322029111920166997e+02,1.848465468540200773e-01,1.100000010988609489e+01,3.102652107539912753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.376948173851565116e+01,5.322129111438845257e+02,1.848775733253162912e-01,1.100000010988609489e+01,3.102506122138375035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377039082941566051e+01,5.322229110957568992e+02,1.849085983367655117e-01,1.100000010988609489e+01,3.102360136736837318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377129992031566985e+01,5.322329110476337064e+02,1.849396218883677390e-01,1.100000010988609489e+01,3.102214151335299600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377220901121567920e+01,5.322429109995150611e+02,1.849706439801229729e-01,1.100000010988609489e+01,3.102068165933761883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377311810211568854e+01,5.322529109514009633e+02,1.850016646120312136e-01,1.100000010988609489e+01,3.101922180532224165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377402719301569789e+01,5.322629109032914130e+02,1.850326837840924887e-01,1.100000010988609489e+01,3.101776195130686448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377493628391570724e+01,5.322729108551864101e+02,1.850637014963067706e-01,1.100000010988609489e+01,3.101630209729148730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377584537481571658e+01,5.322829108070859547e+02,1.850947177486740591e-01,1.100000010988609489e+01,3.101484224327611013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377675446571572593e+01,5.322929107589899331e+02,1.851257325411943544e-01,1.100000010988609489e+01,3.101338238926073295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377766355661573527e+01,5.323029107108984590e+02,1.851567458738676286e-01,1.100000010988609489e+01,3.101192253524535578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377857264751574462e+01,5.323129106628115323e+02,1.851877577466939095e-01,1.100000010988609489e+01,3.101046268122997860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.377948173841575397e+01,5.323229106147291532e+02,1.852187681596731972e-01,1.100000010988609489e+01,3.100900282721460142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378039082931576331e+01,5.323329105666513215e+02,1.852497771128054915e-01,1.100000010988609489e+01,3.100754297319922425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378129992021577266e+01,5.323429105185779235e+02,1.852807846060907926e-01,1.100000010988609489e+01,3.100608311918384707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378220901111578200e+01,5.323529104705090731e+02,1.853117906395291004e-01,1.100000010988609489e+01,3.100462326516846990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378311810201579135e+01,5.323629104224447701e+02,1.853427952131204148e-01,1.100000010988609489e+01,3.100316341115309272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378402719291580070e+01,5.323729103743850146e+02,1.853737983268647360e-01,1.100000010988609489e+01,3.100170355713771555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378493628381581004e+01,5.323829103263298066e+02,1.854047999807620362e-01,1.100000010988609489e+01,3.100024370312233837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378584537471581939e+01,5.323929102782791460e+02,1.854358001748123430e-01,1.100000010988609489e+01,3.099878384910696120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378675446561582874e+01,5.324029102302329193e+02,1.854667989090156566e-01,1.100000010988609489e+01,3.099732399509158402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378766355651583808e+01,5.324129101821912400e+02,1.854977961833719491e-01,1.100000010988609489e+01,3.099586414107620685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378857264741584743e+01,5.324229101341541082e+02,1.855287919978812483e-01,1.100000010988609489e+01,3.099440428706082967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.378948173831585677e+01,5.324329100861215238e+02,1.855597863525435542e-01,1.100000010988609489e+01,3.099294443304545250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379039082921586612e+01,5.324429100380934869e+02,1.855907792473588391e-01,1.100000010988609489e+01,3.099148457903007532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379129992011587547e+01,5.324529099900698839e+02,1.856217706823271307e-01,1.100000010988609489e+01,3.099002472501469815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379220901101588481e+01,5.324629099420508282e+02,1.856527606574484290e-01,1.100000010988609489e+01,3.098856487099932097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379311810191589416e+01,5.324729098940363201e+02,1.856837491727227063e-01,1.100000010988609489e+01,3.098710501698394380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379402719281590350e+01,5.324829098460263594e+02,1.857147362281499903e-01,1.100000010988609489e+01,3.098564516296856662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379493628371591285e+01,5.324929097980208326e+02,1.857457218237302532e-01,1.100000010988609489e+01,3.098418530895318945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379584537461592220e+01,5.325029097500198532e+02,1.857767059594635228e-01,1.100000010988609489e+01,3.098272545493781227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379675446551593154e+01,5.325129097020234212e+02,1.858076886353497714e-01,1.100000010988609489e+01,3.098126560092243510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379766355641594089e+01,5.325229096540315368e+02,1.858386698513890267e-01,1.100000010988609489e+01,3.097980574690705792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379857264731595023e+01,5.325329096060441998e+02,1.858696496075812610e-01,1.100000010988609489e+01,3.097834589289168074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.379948173821595958e+01,5.325429095580612966e+02,1.859006279039264742e-01,1.100000010988609489e+01,3.097688603887630357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380039082911596893e+01,5.325529095100829409e+02,1.859316047404246941e-01,1.100000010988609489e+01,3.097542618486092639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380129992001597827e+01,5.325629094621091326e+02,1.859625801170758930e-01,1.100000010988609489e+01,3.097396633084554922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380220901091598762e+01,5.325729094141398718e+02,1.859935540338800708e-01,1.100000010988609489e+01,3.097250647683017204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380311810181599697e+01,5.325829093661751585e+02,1.860245264908372553e-01,1.100000010988609489e+01,3.097104662281479487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380402719271600631e+01,5.325929093182148790e+02,1.860554974879474188e-01,1.100000010988609489e+01,3.096958676879941769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380493628361601566e+01,5.326029092702591470e+02,1.860864670252105613e-01,1.100000010988609489e+01,3.096812691478404052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380584537451602500e+01,5.326129092223079624e+02,1.861174351026266827e-01,1.100000010988609489e+01,3.096666706076866334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380675446541603435e+01,5.326229091743613253e+02,1.861484017201958108e-01,1.100000010988609489e+01,3.096520720675328617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380766355631604370e+01,5.326329091264191220e+02,1.861793668779179178e-01,1.100000010988609489e+01,3.096374735273790899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380857264721605304e+01,5.326429090784814662e+02,1.862103305757930038e-01,1.100000010988609489e+01,3.096228749872253182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.380948173811606239e+01,5.326529090305483578e+02,1.862412928138210688e-01,1.100000010988609489e+01,3.096082764470715464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381039082901607173e+01,5.326629089826197969e+02,1.862722535920021127e-01,1.100000010988609489e+01,3.095936779069177747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381129991991608108e+01,5.326729089346956698e+02,1.863032129103361356e-01,1.100000010988609489e+01,3.095790793667640029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381220901081609043e+01,5.326829088867760902e+02,1.863341707688231375e-01,1.100000010988609489e+01,3.095644808266102312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381311810171609977e+01,5.326929088388610580e+02,1.863651271674631182e-01,1.100000010988609489e+01,3.095498822864564594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381402719261610912e+01,5.327029087909505733e+02,1.863960821062560780e-01,1.100000010988609489e+01,3.095352837463026877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381493628351611846e+01,5.327129087430445225e+02,1.864270355852020167e-01,1.100000010988609489e+01,3.095206852061489159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381584537441612781e+01,5.327229086951430190e+02,1.864579876043009343e-01,1.100000010988609489e+01,3.095060866659951442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381675446531613716e+01,5.327329086472460631e+02,1.864889381635528309e-01,1.100000010988609489e+01,3.094914881258413724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381766355621614650e+01,5.327429085993536546e+02,1.865198872629577065e-01,1.100000010988609489e+01,3.094768895856876006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381857264711615585e+01,5.327529085514656799e+02,1.865508349025155610e-01,1.100000010988609489e+01,3.094622910455338289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.381948173801616520e+01,5.327629085035822527e+02,1.865817810822263945e-01,1.100000010988609489e+01,3.094476925053800571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382039082891617454e+01,5.327729084557033730e+02,1.866127258020902069e-01,1.100000010988609489e+01,3.094330939652262854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382129991981618389e+01,5.327829084078290407e+02,1.866436690621069983e-01,1.100000010988609489e+01,3.094184954250725136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382220901071619323e+01,5.327929083599591422e+02,1.866746108622767408e-01,1.100000010988609489e+01,3.094038968849187419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382311810161620258e+01,5.328029083120937912e+02,1.867055512025994624e-01,1.100000010988609489e+01,3.093892983447649701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382402719251621193e+01,5.328129082642329877e+02,1.867364900830751628e-01,1.100000010988609489e+01,3.093746998046111984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382493628341622127e+01,5.328229082163766179e+02,1.867674275037038423e-01,1.100000010988609489e+01,3.093601012644574266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382584537431623062e+01,5.328329081685247957e+02,1.867983634644854729e-01,1.100000010988609489e+01,3.093455027243036549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382675446521623996e+01,5.328429081206775209e+02,1.868292979654200825e-01,1.100000010988609489e+01,3.093309041841498831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382766355611624931e+01,5.328529080728347935e+02,1.868602310065076710e-01,1.100000010988609489e+01,3.093163056439961114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382857264701625866e+01,5.328629080249965000e+02,1.868911625877482108e-01,1.100000010988609489e+01,3.093017071038423396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.382948173791626800e+01,5.328729079771627539e+02,1.869220927091417295e-01,1.100000010988609489e+01,3.092871085636885679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383039082881627735e+01,5.328829079293335553e+02,1.869530213706881994e-01,1.100000010988609489e+01,3.092725100235347961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383129991971628669e+01,5.328929078815089042e+02,1.869839485723876482e-01,1.100000010988609489e+01,3.092579114833810244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383220901061629604e+01,5.329029078336886869e+02,1.870148743142400760e-01,1.100000010988609489e+01,3.092433129432272526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383311810151630539e+01,5.329129077858730170e+02,1.870457985962454550e-01,1.100000010988609489e+01,3.092287144030734809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383402719241631473e+01,5.329229077380618946e+02,1.870767214184038130e-01,1.100000010988609489e+01,3.092141158629197091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383493628331632408e+01,5.329329076902552060e+02,1.871076427807151221e-01,1.100000010988609489e+01,3.091995173227659374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383584537421633343e+01,5.329429076424530649e+02,1.871385626831793825e-01,1.100000010988609489e+01,3.091849187826121656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383675446511634277e+01,5.329529075946554713e+02,1.871694811257966218e-01,1.100000010988609489e+01,3.091703202424583938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383766355601635212e+01,5.329629075468623114e+02,1.872003981085668123e-01,1.100000010988609489e+01,3.091557217023046221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383857264691636146e+01,5.329729074990736990e+02,1.872313136314899817e-01,1.100000010988609489e+01,3.091411231621508503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.383948173781637081e+01,5.329829074512896341e+02,1.872622276945661024e-01,1.100000010988609489e+01,3.091265246219970786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384039082871638016e+01,5.329929074035101166e+02,1.872931402977951743e-01,1.100000010988609489e+01,3.091119260818433068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384129991961638950e+01,5.330029073557350330e+02,1.873240514411772251e-01,1.100000010988609489e+01,3.090973275416895351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384220901051639885e+01,5.330129073079644968e+02,1.873549611247122271e-01,1.100000010988609489e+01,3.090827290015357633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384311810141640819e+01,5.330229072601985081e+02,1.873858693484001803e-01,1.100000010988609489e+01,3.090681304613819916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384402719231641754e+01,5.330329072124369532e+02,1.874167761122410847e-01,1.100000010988609489e+01,3.090535319212282198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384493628321642689e+01,5.330429071646799457e+02,1.874476814162349680e-01,1.100000010988609489e+01,3.090389333810744481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384584537411643623e+01,5.330529071169274857e+02,1.874785852603818026e-01,1.100000010988609489e+01,3.090243348409206763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384675446501644558e+01,5.330629070691794595e+02,1.875094876446815884e-01,1.100000010988609489e+01,3.090097363007669046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384766355591645492e+01,5.330729070214359808e+02,1.875403885691343253e-01,1.100000010988609489e+01,3.089951377606131328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384857264681646427e+01,5.330829069736970496e+02,1.875712880337400135e-01,1.100000010988609489e+01,3.089805392204593611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.384948173771647362e+01,5.330929069259625521e+02,1.876021860384986528e-01,1.100000010988609489e+01,3.089659406803055893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385039082861648296e+01,5.331029068782326021e+02,1.876330825834102434e-01,1.100000010988609489e+01,3.089513421401518176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385129991951649231e+01,5.331129068305071996e+02,1.876639776684747851e-01,1.100000010988609489e+01,3.089367435999980458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385220901041650166e+01,5.331229067827862309e+02,1.876948712936922781e-01,1.100000010988609489e+01,3.089221450598442741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385311810131651100e+01,5.331329067350698097e+02,1.877257634590627222e-01,1.100000010988609489e+01,3.089075465196905023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385402719221652035e+01,5.331429066873579359e+02,1.877566541645861176e-01,1.100000010988609489e+01,3.088929479795367306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385493628311652969e+01,5.331529066396504959e+02,1.877875434102624641e-01,1.100000010988609489e+01,3.088783494393829588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385584537401653904e+01,5.331629065919476034e+02,1.878184311960917618e-01,1.100000010988609489e+01,3.088637508992291870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385675446491654839e+01,5.331729065442492583e+02,1.878493175220740108e-01,1.100000010988609489e+01,3.088491523590754153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385766355581655773e+01,5.331829064965553471e+02,1.878802023882092109e-01,1.100000010988609489e+01,3.088345538189216435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385857264671656708e+01,5.331929064488659833e+02,1.879110857944973623e-01,1.100000010988609489e+01,3.088199552787678718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.385948173761657642e+01,5.332029064011811670e+02,1.879419677409384648e-01,1.100000010988609489e+01,3.088053567386141000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386039082851658577e+01,5.332129063535007845e+02,1.879728482275324908e-01,1.100000010988609489e+01,3.087907581984603283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386129991941659512e+01,5.332229063058249494e+02,1.880037272542794680e-01,1.100000010988609489e+01,3.087761596583065565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386220901031660446e+01,5.332329062581536618e+02,1.880346048211793963e-01,1.100000010988609489e+01,3.087615611181527848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386311810121661381e+01,5.332429062104868080e+02,1.880654809282322759e-01,1.100000010988609489e+01,3.087469625779990130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386402719211662316e+01,5.332529061628245017e+02,1.880963555754380789e-01,1.100000010988609489e+01,3.087323640378452413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386493628301663250e+01,5.332629061151667429e+02,1.881272287627968332e-01,1.100000010988609489e+01,3.087177654976914695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386584537391664185e+01,5.332729060675134178e+02,1.881581004903085386e-01,1.100000010988609489e+01,3.087031669575376978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386675446481665119e+01,5.332829060198646403e+02,1.881889707579731674e-01,1.100000010988609489e+01,3.086885684173839260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386766355571666054e+01,5.332929059722204101e+02,1.882198395657907475e-01,1.100000010988609489e+01,3.086739698772301543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386857264661666989e+01,5.333029059245806138e+02,1.882507069137612510e-01,1.100000010988609489e+01,3.086593713370763825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.386948173751667923e+01,5.333129058769453650e+02,1.882815728018847057e-01,1.100000010988609489e+01,3.086447727969226108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387039082841668858e+01,5.333229058293145499e+02,1.883124372301611116e-01,1.100000010988609489e+01,3.086301742567688390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387129991931669792e+01,5.333329057816882823e+02,1.883433001985904409e-01,1.100000010988609489e+01,3.086155757166150673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387220901021670727e+01,5.333429057340665622e+02,1.883741617071727215e-01,1.100000010988609489e+01,3.086009771764612955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387311810111671662e+01,5.333529056864492759e+02,1.884050217559079254e-01,1.100000010988609489e+01,3.085863786363075238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387402719201672596e+01,5.333629056388365370e+02,1.884358803447960529e-01,1.100000010988609489e+01,3.085717800961537520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387493628291673531e+01,5.333729055912283457e+02,1.884667374738371315e-01,1.100000010988609489e+01,3.085571815559999802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387584537381674465e+01,5.333829055436245881e+02,1.884975931430311336e-01,1.100000010988609489e+01,3.085425830158462085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387675446471675400e+01,5.333929054960253779e+02,1.885284473523780868e-01,1.100000010988609489e+01,3.085279844756924367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387766355561676335e+01,5.334029054484306016e+02,1.885593001018779635e-01,1.100000010988609489e+01,3.085133859355386650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387857264651677269e+01,5.334129054008403727e+02,1.885901513915307637e-01,1.100000010988609489e+01,3.084987873953848932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.387948173741678204e+01,5.334229053532546914e+02,1.886210012213365150e-01,1.100000010988609489e+01,3.084841888552311215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388039082831679139e+01,5.334329053056734438e+02,1.886518495912951898e-01,1.100000010988609489e+01,3.084695903150773497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388129991921680073e+01,5.334429052580967436e+02,1.886826965014067881e-01,1.100000010988609489e+01,3.084549917749235780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388220901011681008e+01,5.334529052105245910e+02,1.887135419516713097e-01,1.100000010988609489e+01,3.084403932347698062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388311810101681942e+01,5.334629051629568721e+02,1.887443859420887826e-01,1.100000010988609489e+01,3.084257946946160345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388402719191682877e+01,5.334729051153937007e+02,1.887752284726591789e-01,1.100000010988609489e+01,3.084111961544622627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388493628281683812e+01,5.334829050678349631e+02,1.888060695433824987e-01,1.100000010988609489e+01,3.083965976143084910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388584537371684746e+01,5.334929050202807730e+02,1.888369091542587419e-01,1.100000010988609489e+01,3.083819990741547192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388675446461685681e+01,5.335029049727311303e+02,1.888677473052879086e-01,1.100000010988609489e+01,3.083674005340009475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388766355551686615e+01,5.335129049251859215e+02,1.888985839964699986e-01,1.100000010988609489e+01,3.083528019938471757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388857264641687550e+01,5.335229048776452601e+02,1.889294192278050122e-01,1.100000010988609489e+01,3.083382034536934040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.388948173731688485e+01,5.335329048301090324e+02,1.889602529992929492e-01,1.100000010988609489e+01,3.083236049135396322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389039082821689419e+01,5.335429047825773523e+02,1.889910853109338096e-01,1.100000010988609489e+01,3.083090063733858605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389129991911690354e+01,5.335529047350502196e+02,1.890219161627275934e-01,1.100000010988609489e+01,3.082944078332320887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389220901001691288e+01,5.335629046875275208e+02,1.890527455546743008e-01,1.100000010988609489e+01,3.082798092930783170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389311810091692223e+01,5.335729046400093694e+02,1.890835734867739315e-01,1.100000010988609489e+01,3.082652107529245452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389402719181693158e+01,5.335829045924956517e+02,1.891143999590264857e-01,1.100000010988609489e+01,3.082506122127707734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389493628271694092e+01,5.335929045449864816e+02,1.891452249714319633e-01,1.100000010988609489e+01,3.082360136726170017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389584537361695027e+01,5.336029044974817452e+02,1.891760485239903644e-01,1.100000010988609489e+01,3.082214151324632299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389675446451695962e+01,5.336129044499815564e+02,1.892068706167016889e-01,1.100000010988609489e+01,3.082068165923094582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389766355541696896e+01,5.336229044024859149e+02,1.892376912495659369e-01,1.100000010988609489e+01,3.081922180521556864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389857264631697831e+01,5.336329043549947073e+02,1.892685104225830806e-01,1.100000010988609489e+01,3.081776195120019147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.389948173721698765e+01,5.336429043075080472e+02,1.892993281357531477e-01,1.100000010988609489e+01,3.081630209718481429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390039082811699700e+01,5.336529042600258208e+02,1.893301443890761382e-01,1.100000010988609489e+01,3.081484224316943712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390129991901700635e+01,5.336629042125481419e+02,1.893609591825520522e-01,1.100000010988609489e+01,3.081338238915405994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390220900991701569e+01,5.336729041650748968e+02,1.893917725161808618e-01,1.100000010988609489e+01,3.081192253513868277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390311810081702504e+01,5.336829041176061992e+02,1.894225843899625950e-01,1.100000010988609489e+01,3.081046268112330559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390402719171703438e+01,5.336929040701420490e+02,1.894533948038972515e-01,1.100000010988609489e+01,3.080900282710792842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390493628261704373e+01,5.337029040226823327e+02,1.894842037579848038e-01,1.100000010988609489e+01,3.080754297309255124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390584537351705308e+01,5.337129039752271638e+02,1.895150112522252794e-01,1.100000010988609489e+01,3.080608311907717407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390675446441706242e+01,5.337229039277764286e+02,1.895458172866186786e-01,1.100000010988609489e+01,3.080462326506179689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390766355531707177e+01,5.337329038803302410e+02,1.895766218611649734e-01,1.100000010988609489e+01,3.080316341104641972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390857264621708111e+01,5.337429038328884872e+02,1.896074249758641916e-01,1.100000010988609489e+01,3.080170355703104254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.390948173711709046e+01,5.337529037854512808e+02,1.896382266307163056e-01,1.100000010988609489e+01,3.080024370301566537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391039082801709981e+01,5.337629037380186219e+02,1.896690268257213430e-01,1.100000010988609489e+01,3.079878384900028819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391129991891710915e+01,5.337729036905903968e+02,1.896998255608792761e-01,1.100000010988609489e+01,3.079732399498491102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391220900981711850e+01,5.337829036431667191e+02,1.897306228361901326e-01,1.100000010988609489e+01,3.079586414096953384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391311810071712785e+01,5.337929035957474753e+02,1.897614186516538848e-01,1.100000010988609489e+01,3.079440428695415666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391402719161713719e+01,5.338029035483327789e+02,1.897922130072705327e-01,1.100000010988609489e+01,3.079294443293877949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391493628251714654e+01,5.338129035009225163e+02,1.898230059030401040e-01,1.100000010988609489e+01,3.079148457892340231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391584537341715588e+01,5.338229034535168012e+02,1.898537973389625710e-01,1.100000010988609489e+01,3.079002472490802514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391675446431716523e+01,5.338329034061155198e+02,1.898845873150379615e-01,1.100000010988609489e+01,3.078856487089264796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391766355521717458e+01,5.338429033587187860e+02,1.899153758312662477e-01,1.100000010988609489e+01,3.078710501687727079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391857264611718392e+01,5.338529033113264859e+02,1.899461628876474295e-01,1.100000010988609489e+01,3.078564516286189361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.391948173701719327e+01,5.338629032639387333e+02,1.899769484841815070e-01,1.100000010988609489e+01,3.078418530884651644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392039082791720261e+01,5.338729032165554145e+02,1.900077326208685080e-01,1.100000010988609489e+01,3.078272545483113926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392129991881721196e+01,5.338829031691766431e+02,1.900385152977084047e-01,1.100000010988609489e+01,3.078126560081576209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392220900971722131e+01,5.338929031218024193e+02,1.900692965147011970e-01,1.100000010988609489e+01,3.077980574680038491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392311810061723065e+01,5.339029030744326292e+02,1.901000762718468851e-01,1.100000010988609489e+01,3.077834589278500774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392402719151724000e+01,5.339129030270673866e+02,1.901308545691454688e-01,1.100000010988609489e+01,3.077688603876963056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392493628241724934e+01,5.339229029797065778e+02,1.901616314065969482e-01,1.100000010988609489e+01,3.077542618475425339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392584537331725869e+01,5.339329029323503164e+02,1.901924067842013510e-01,1.100000010988609489e+01,3.077396633073887621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392675446421726804e+01,5.339429028849984888e+02,1.902231807019586496e-01,1.100000010988609489e+01,3.077250647672349904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392766355511727738e+01,5.339529028376512088e+02,1.902539531598688438e-01,1.100000010988609489e+01,3.077104662270812186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392857264601728673e+01,5.339629027903083625e+02,1.902847241579319337e-01,1.100000010988609489e+01,3.076958676869274469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.392948173691729608e+01,5.339729027429700636e+02,1.903154936961479193e-01,1.100000010988609489e+01,3.076812691467736751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393039082781730542e+01,5.339829026956361986e+02,1.903462617745168006e-01,1.100000010988609489e+01,3.076666706066199033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393129991871731477e+01,5.339929026483068810e+02,1.903770283930385776e-01,1.100000010988609489e+01,3.076520720664661316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393220900961732411e+01,5.340029026009819972e+02,1.904077935517132503e-01,1.100000010988609489e+01,3.076374735263123598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393311810051733346e+01,5.340129025536616609e+02,1.904385572505407909e-01,1.100000010988609489e+01,3.076228749861585881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393402719141734281e+01,5.340229025063457584e+02,1.904693194895212272e-01,1.100000010988609489e+01,3.076082764460048163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393493628231735215e+01,5.340329024590344034e+02,1.905000802686545591e-01,1.100000010988609489e+01,3.075936779058510446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393584537321736150e+01,5.340429024117274821e+02,1.905308395879407868e-01,1.100000010988609489e+01,3.075790793656972728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393675446411737084e+01,5.340529023644251083e+02,1.905615974473799101e-01,1.100000010988609489e+01,3.075644808255435011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393766355501738019e+01,5.340629023171271683e+02,1.905923538469719292e-01,1.100000010988609489e+01,3.075498822853897293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393857264591738954e+01,5.340729022698337758e+02,1.906231087867168161e-01,1.100000010988609489e+01,3.075352837452359576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.393948173681739888e+01,5.340829022225448171e+02,1.906538622666145988e-01,1.100000010988609489e+01,3.075206852050821858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394039082771740823e+01,5.340929021752604058e+02,1.906846142866652771e-01,1.100000010988609489e+01,3.075060866649284141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394129991861741757e+01,5.341029021279804283e+02,1.907153648468688234e-01,1.100000010988609489e+01,3.074914881247746423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394220900951742692e+01,5.341129020807049983e+02,1.907461139472252654e-01,1.100000010988609489e+01,3.074768895846208706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394311810041743627e+01,5.341229020334340021e+02,1.907768615877346030e-01,1.100000010988609489e+01,3.074622910444670988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394402719131744561e+01,5.341329019861675533e+02,1.908076077683968086e-01,1.100000010988609489e+01,3.074476925043133271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394493628221745496e+01,5.341429019389055384e+02,1.908383524892119099e-01,1.100000010988609489e+01,3.074330939641595553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394584537311746431e+01,5.341529018916480709e+02,1.908690957501799068e-01,1.100000010988609489e+01,3.074184954240057836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394675446401747365e+01,5.341629018443950372e+02,1.908998375513007717e-01,1.100000010988609489e+01,3.074038968838520118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394766355491748300e+01,5.341729017971465510e+02,1.909305778925745323e-01,1.100000010988609489e+01,3.073892983436982401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394857264581749234e+01,5.341829017499024985e+02,1.909613167740011608e-01,1.100000010988609489e+01,3.073746998035444683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.394948173671750169e+01,5.341929017026628799e+02,1.909920541955806850e-01,1.100000010988609489e+01,3.073601012633906965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395039082761751104e+01,5.342029016554278087e+02,1.910227901573130771e-01,1.100000010988609489e+01,3.073455027232369248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395129991851752038e+01,5.342129016081971713e+02,1.910535246591983649e-01,1.100000010988609489e+01,3.073309041830831530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395220900941752973e+01,5.342229015609710814e+02,1.910842577012365207e-01,1.100000010988609489e+01,3.073163056429293813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395311810031753907e+01,5.342329015137494252e+02,1.911149892834275443e-01,1.100000010988609489e+01,3.073017071027756095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395402719121754842e+01,5.342429014665323166e+02,1.911457194057714637e-01,1.100000010988609489e+01,3.072871085626218378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395493628211755777e+01,5.342529014193196417e+02,1.911764480682682510e-01,1.100000010988609489e+01,3.072725100224680660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395584537301756711e+01,5.342629013721115143e+02,1.912071752709179062e-01,1.100000010988609489e+01,3.072579114823142943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395675446391757646e+01,5.342729013249078207e+02,1.912379010137204571e-01,1.100000010988609489e+01,3.072433129421605225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395766355481758580e+01,5.342829012777086746e+02,1.912686252966758760e-01,1.100000010988609489e+01,3.072287144020067508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395857264571759515e+01,5.342929012305139622e+02,1.912993481197841628e-01,1.100000010988609489e+01,3.072141158618529790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.395948173661760450e+01,5.343029011833237973e+02,1.913300694830453175e-01,1.100000010988609489e+01,3.071995173216992073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396039082751761384e+01,5.343129011361380662e+02,1.913607893864593679e-01,1.100000010988609489e+01,3.071849187815454355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396129991841762319e+01,5.343229010889567689e+02,1.913915078300262862e-01,1.100000010988609489e+01,3.071703202413916638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396220900931763254e+01,5.343329010417800191e+02,1.914222248137460725e-01,1.100000010988609489e+01,3.071557217012378920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396311810021764188e+01,5.343429009946077031e+02,1.914529403376187267e-01,1.100000010988609489e+01,3.071411231610841203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396402719111765123e+01,5.343529009474399345e+02,1.914836544016442488e-01,1.100000010988609489e+01,3.071265246209303485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396493628201766057e+01,5.343629009002765997e+02,1.915143670058226388e-01,1.100000010988609489e+01,3.071119260807765768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396584537291766992e+01,5.343729008531178124e+02,1.915450781501538968e-01,1.100000010988609489e+01,3.070973275406228050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396675446381767927e+01,5.343829008059634589e+02,1.915757878346380227e-01,1.100000010988609489e+01,3.070827290004690333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396766355471768861e+01,5.343929007588135391e+02,1.916064960592750166e-01,1.100000010988609489e+01,3.070681304603152615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396857264561769796e+01,5.344029007116681669e+02,1.916372028240648784e-01,1.100000010988609489e+01,3.070535319201614897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.396948173651770730e+01,5.344129006645272284e+02,1.916679081290076081e-01,1.100000010988609489e+01,3.070389333800077180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397039082741771665e+01,5.344229006173908374e+02,1.916986119741032057e-01,1.100000010988609489e+01,3.070243348398539462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397129991831772600e+01,5.344329005702588802e+02,1.917293143593516713e-01,1.100000010988609489e+01,3.070097362997001745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397220900921773534e+01,5.344429005231314704e+02,1.917600152847530048e-01,1.100000010988609489e+01,3.069951377595464027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397311810011774469e+01,5.344529004760084945e+02,1.917907147503072063e-01,1.100000010988609489e+01,3.069805392193926310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397402719101775403e+01,5.344629004288899523e+02,1.918214127560142757e-01,1.100000010988609489e+01,3.069659406792388592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397493628191776338e+01,5.344729003817759576e+02,1.918521093018742130e-01,1.100000010988609489e+01,3.069513421390850875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397584537281777273e+01,5.344829003346663967e+02,1.918828043878869904e-01,1.100000010988609489e+01,3.069367435989313157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397675446371778207e+01,5.344929002875613833e+02,1.919134980140526359e-01,1.100000010988609489e+01,3.069221450587775440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397766355461779142e+01,5.345029002404608036e+02,1.919441901803711492e-01,1.100000010988609489e+01,3.069075465186237722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397857264551780077e+01,5.345129001933647714e+02,1.919748808868425305e-01,1.100000010988609489e+01,3.068929479784700005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.397948173641781011e+01,5.345229001462731730e+02,1.920055701334667519e-01,1.100000010988609489e+01,3.068783494383162287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398039082731781946e+01,5.345329000991860084e+02,1.920362579202438413e-01,1.100000010988609489e+01,3.068637508981624570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398129991821782880e+01,5.345429000521033913e+02,1.920669442471737987e-01,1.100000010988609489e+01,3.068491523580086852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398220900911783815e+01,5.345529000050252080e+02,1.920976291142565962e-01,1.100000010988609489e+01,3.068345538178549135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398311810001784750e+01,5.345628999579515721e+02,1.921283125214922616e-01,1.100000010988609489e+01,3.068199552777011417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398402719091785684e+01,5.345728999108823700e+02,1.921589944688807672e-01,1.100000010988609489e+01,3.068053567375473700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398493628181786619e+01,5.345828998638176017e+02,1.921896749564221407e-01,1.100000010988609489e+01,3.067907581973935982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398584537271787553e+01,5.345928998167573809e+02,1.922203539841163544e-01,1.100000010988609489e+01,3.067761596572398265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398675446361788488e+01,5.346028997697015939e+02,1.922510315519634361e-01,1.100000010988609489e+01,3.067615611170860547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398766355451789423e+01,5.346128997226503543e+02,1.922817076599633579e-01,1.100000010988609489e+01,3.067469625769322829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398857264541790357e+01,5.346228996756035485e+02,1.923123823081161476e-01,1.100000010988609489e+01,3.067323640367785112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.398948173631791292e+01,5.346328996285611765e+02,1.923430554964217776e-01,1.100000010988609489e+01,3.067177654966247394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399039082721792226e+01,5.346428995815233520e+02,1.923737272248802754e-01,1.100000010988609489e+01,3.067031669564709677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399129991811793161e+01,5.346528995344899613e+02,1.924043974934916135e-01,1.100000010988609489e+01,3.066885684163171959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399220900901794096e+01,5.346628994874610044e+02,1.924350663022558194e-01,1.100000010988609489e+01,3.066739698761634242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399311809991795030e+01,5.346728994404365949e+02,1.924657336511728656e-01,1.100000010988609489e+01,3.066593713360096524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399402719081795965e+01,5.346828993934166192e+02,1.924963995402427519e-01,1.100000010988609489e+01,3.066447727958558807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399493628171796900e+01,5.346928993464011910e+02,1.925270639694655062e-01,1.100000010988609489e+01,3.066301742557021089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399584537261797834e+01,5.347028992993901966e+02,1.925577269388411006e-01,1.100000010988609489e+01,3.066155757155483372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399675446351798769e+01,5.347128992523836359e+02,1.925883884483695352e-01,1.100000010988609489e+01,3.066009771753945654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399766355441799703e+01,5.347228992053816228e+02,1.926190484980508100e-01,1.100000010988609489e+01,3.065863786352407937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399857264531800638e+01,5.347328991583840434e+02,1.926497070878849527e-01,1.100000010988609489e+01,3.065717800950870219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.399948173621801573e+01,5.347428991113908978e+02,1.926803642178719356e-01,1.100000010988609489e+01,3.065571815549332502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400039082711802507e+01,5.347528990644022997e+02,1.927110198880117586e-01,1.100000010988609489e+01,3.065425830147794784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400129991801803442e+01,5.347628990174181354e+02,1.927416740983044219e-01,1.100000010988609489e+01,3.065279844746257067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400220900891804376e+01,5.347728989704385185e+02,1.927723268487499253e-01,1.100000010988609489e+01,3.065133859344719349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400311809981805311e+01,5.347828989234633354e+02,1.928029781393482689e-01,1.100000010988609489e+01,3.064987873943181632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400402719071806246e+01,5.347928988764925862e+02,1.928336279700994527e-01,1.100000010988609489e+01,3.064841888541643914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400493628161807180e+01,5.348028988295263844e+02,1.928642763410034766e-01,1.100000010988609489e+01,3.064695903140106197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400584537251808115e+01,5.348128987825646163e+02,1.928949232520603407e-01,1.100000010988609489e+01,3.064549917738568479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400675446341809049e+01,5.348228987356072821e+02,1.929255687032700450e-01,1.100000010988609489e+01,3.064403932337030761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400766355431809984e+01,5.348328986886544953e+02,1.929562126946325895e-01,1.100000010988609489e+01,3.064257946935493044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400857264521810919e+01,5.348428986417061424e+02,1.929868552261479742e-01,1.100000010988609489e+01,3.064111961533955326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.400948173611811853e+01,5.348528985947622232e+02,1.930174962978161990e-01,1.100000010988609489e+01,3.063965976132417609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401039082701812788e+01,5.348628985478228515e+02,1.930481359096372640e-01,1.100000010988609489e+01,3.063819990730879891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401129991791813723e+01,5.348728985008879135e+02,1.930787740616111692e-01,1.100000010988609489e+01,3.063674005329342174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401220900881814657e+01,5.348828984539574094e+02,1.931094107537379145e-01,1.100000010988609489e+01,3.063528019927804456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401311809971815592e+01,5.348928984070314527e+02,1.931400459860175001e-01,1.100000010988609489e+01,3.063382034526266739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401402719061816526e+01,5.349028983601099299e+02,1.931706797584498980e-01,1.100000010988609489e+01,3.063236049124729021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401493628151817461e+01,5.349128983131928408e+02,1.932013120710351362e-01,1.100000010988609489e+01,3.063090063723191304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401584537241818396e+01,5.349228982662802991e+02,1.932319429237732145e-01,1.100000010988609489e+01,3.062944078321653586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401675446331819330e+01,5.349328982193721913e+02,1.932625723166641329e-01,1.100000010988609489e+01,3.062798092920115869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401766355421820265e+01,5.349428981724685173e+02,1.932932002497078638e-01,1.100000010988609489e+01,3.062652107518578151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401857264511821199e+01,5.349528981255693907e+02,1.933238267229044349e-01,1.100000010988609489e+01,3.062506122117040434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.401948173601822134e+01,5.349628980786746979e+02,1.933544517362538462e-01,1.100000010988609489e+01,3.062360136715502716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402039082691823069e+01,5.349728980317844389e+02,1.933850752897560699e-01,1.100000010988609489e+01,3.062214151313964999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402129991781824003e+01,5.349828979848987274e+02,1.934156973834111337e-01,1.100000010988609489e+01,3.062068165912427281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402220900871824938e+01,5.349928979380174496e+02,1.934463180172190377e-01,1.100000010988609489e+01,3.061922180510889564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402311809961825873e+01,5.350028978911406057e+02,1.934769371911797542e-01,1.100000010988609489e+01,3.061776195109351846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402402719051826807e+01,5.350128978442683092e+02,1.935075549052933108e-01,1.100000010988609489e+01,3.061630209707814129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402493628141827742e+01,5.350228977974004465e+02,1.935381711595596799e-01,1.100000010988609489e+01,3.061484224306276411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402584537231828676e+01,5.350328977505370176e+02,1.935687859539788891e-01,1.100000010988609489e+01,3.061338238904738693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402675446321829611e+01,5.350428977036781362e+02,1.935993992885509107e-01,1.100000010988609489e+01,3.061192253503200976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402766355411830546e+01,5.350528976568236885e+02,1.936300111632757726e-01,1.100000010988609489e+01,3.061046268101663258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402857264501831480e+01,5.350628976099736747e+02,1.936606215781534468e-01,1.100000010988609489e+01,3.060900282700125541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.402948173591832415e+01,5.350728975631282083e+02,1.936912305331839612e-01,1.100000010988609489e+01,3.060754297298587823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403039082681833349e+01,5.350828975162871757e+02,1.937218380283672881e-01,1.100000010988609489e+01,3.060608311897050106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403129991771834284e+01,5.350928974694505769e+02,1.937524440637034273e-01,1.100000010988609489e+01,3.060462326495512388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403220900861835219e+01,5.351028974226184118e+02,1.937830486391924067e-01,1.100000010988609489e+01,3.060316341093974671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403311809951836153e+01,5.351128973757907943e+02,1.938136517548341986e-01,1.100000010988609489e+01,3.060170355692436953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403402719041837088e+01,5.351228973289676105e+02,1.938442534106288029e-01,1.100000010988609489e+01,3.060024370290899236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403493628131838022e+01,5.351328972821488605e+02,1.938748536065762196e-01,1.100000010988609489e+01,3.059878384889361518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403584537221838957e+01,5.351428972353346580e+02,1.939054523426764765e-01,1.100000010988609489e+01,3.059732399487823801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403675446311839892e+01,5.351528971885248893e+02,1.939360496189295457e-01,1.100000010988609489e+01,3.059586414086286083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403766355401840826e+01,5.351628971417195544e+02,1.939666454353354275e-01,1.100000010988609489e+01,3.059440428684748366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403857264491841761e+01,5.351728970949187669e+02,1.939972397918941216e-01,1.100000010988609489e+01,3.059294443283210648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.403948173581842696e+01,5.351828970481224133e+02,1.940278326886056282e-01,1.100000010988609489e+01,3.059148457881672931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404039082671843630e+01,5.351928970013304934e+02,1.940584241254699749e-01,1.100000010988609489e+01,3.059002472480135213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404129991761844565e+01,5.352028969545430073e+02,1.940890141024871340e-01,1.100000010988609489e+01,3.058856487078597496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404220900851845499e+01,5.352128969077600686e+02,1.941196026196571056e-01,1.100000010988609489e+01,3.058710501677059778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404311809941846434e+01,5.352228968609815638e+02,1.941501896769798896e-01,1.100000010988609489e+01,3.058564516275522061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404402719031847369e+01,5.352328968142074928e+02,1.941807752744554860e-01,1.100000010988609489e+01,3.058418530873984343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404493628121848303e+01,5.352428967674378555e+02,1.942113594120838949e-01,1.100000010988609489e+01,3.058272545472446625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404584537211849238e+01,5.352528967206727657e+02,1.942419420898651161e-01,1.100000010988609489e+01,3.058126560070908908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404675446301850172e+01,5.352628966739121097e+02,1.942725233077991498e-01,1.100000010988609489e+01,3.057980574669371190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404766355391851107e+01,5.352728966271558875e+02,1.943031030658859959e-01,1.100000010988609489e+01,3.057834589267833473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404857264481852042e+01,5.352828965804042127e+02,1.943336813641256544e-01,1.100000010988609489e+01,3.057688603866295755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.404948173571852976e+01,5.352928965336569718e+02,1.943642582025181254e-01,1.100000010988609489e+01,3.057542618464758038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405039082661853911e+01,5.353028964869141646e+02,1.943948335810633810e-01,1.100000010988609489e+01,3.057396633063220320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405129991751854845e+01,5.353128964401757912e+02,1.944254074997614490e-01,1.100000010988609489e+01,3.057250647661682603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405220900841855780e+01,5.353228963934419653e+02,1.944559799586123294e-01,1.100000010988609489e+01,3.057104662260144885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405311809931856715e+01,5.353328963467125732e+02,1.944865509576160223e-01,1.100000010988609489e+01,3.056958676858607168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405402719021857649e+01,5.353428962999876148e+02,1.945171204967725276e-01,1.100000010988609489e+01,3.056812691457069450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405493628111858584e+01,5.353528962532670903e+02,1.945476885760818175e-01,1.100000010988609489e+01,3.056666706055531733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405584537201859519e+01,5.353628962065511132e+02,1.945782551955439199e-01,1.100000010988609489e+01,3.056520720653994015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405675446291860453e+01,5.353728961598395699e+02,1.946088203551588347e-01,1.100000010988609489e+01,3.056374735252456298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405766355381861388e+01,5.353828961131324604e+02,1.946393840549265619e-01,1.100000010988609489e+01,3.056228749850918580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405857264471862322e+01,5.353928960664297847e+02,1.946699462948470738e-01,1.100000010988609489e+01,3.056082764449380863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.405948173561863257e+01,5.354028960197316565e+02,1.947005070749203981e-01,1.100000010988609489e+01,3.055936779047843145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406039082651864192e+01,5.354128959730379620e+02,1.947310663951465071e-01,1.100000010988609489e+01,3.055790793646305428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406129991741865126e+01,5.354228959263487013e+02,1.947616242555254285e-01,1.100000010988609489e+01,3.055644808244767710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406220900831866061e+01,5.354328958796638744e+02,1.947921806560571623e-01,1.100000010988609489e+01,3.055498822843229993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406311809921866995e+01,5.354428958329835950e+02,1.948227355967416807e-01,1.100000010988609489e+01,3.055352837441692275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406402719011867930e+01,5.354528957863077494e+02,1.948532890775790116e-01,1.100000010988609489e+01,3.055206852040154557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406493628101868865e+01,5.354628957396363376e+02,1.948838410985691272e-01,1.100000010988609489e+01,3.055060866638616840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406584537191869799e+01,5.354728956929693595e+02,1.949143916597120552e-01,1.100000010988609489e+01,3.054914881237079122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406675446281870734e+01,5.354828956463068153e+02,1.949449407610077678e-01,1.100000010988609489e+01,3.054768895835541405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406766355371871668e+01,5.354928955996488185e+02,1.949754884024562651e-01,1.100000010988609489e+01,3.054622910434003687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406857264461872603e+01,5.355028955529952555e+02,1.950060345840575748e-01,1.100000010988609489e+01,3.054476925032465970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.406948173551873538e+01,5.355128955063461262e+02,1.950365793058116692e-01,1.100000010988609489e+01,3.054330939630928252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407039082641874472e+01,5.355228954597014308e+02,1.950671225677185761e-01,1.100000010988609489e+01,3.054184954229390535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407129991731875407e+01,5.355328954130612829e+02,1.950976643697782675e-01,1.100000010988609489e+01,3.054038968827852817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407220900821876342e+01,5.355428953664255687e+02,1.951282047119907437e-01,1.100000010988609489e+01,3.053892983426315100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407311809911877276e+01,5.355528953197942883e+02,1.951587435943560045e-01,1.100000010988609489e+01,3.053746998024777382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407402719001878211e+01,5.355628952731674417e+02,1.951892810168740777e-01,1.100000010988609489e+01,3.053601012623239665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407493628091879145e+01,5.355728952265450289e+02,1.952198169795449356e-01,1.100000010988609489e+01,3.053455027221701947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407584537181880080e+01,5.355828951799271636e+02,1.952503514823685782e-01,1.100000010988609489e+01,3.053309041820164230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407675446271881015e+01,5.355928951333137320e+02,1.952808845253450054e-01,1.100000010988609489e+01,3.053163056418626512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407766355361881949e+01,5.356028950867047342e+02,1.953114161084742173e-01,1.100000010988609489e+01,3.053017071017088795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407857264451882884e+01,5.356128950401001703e+02,1.953419462317562416e-01,1.100000010988609489e+01,3.052871085615551077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.407948173541883818e+01,5.356228949935001538e+02,1.953724748951910506e-01,1.100000010988609489e+01,3.052725100214013360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408039082631884753e+01,5.356328949469045710e+02,1.954030020987786442e-01,1.100000010988609489e+01,3.052579114812475642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408129991721885688e+01,5.356428949003134221e+02,1.954335278425190225e-01,1.100000010988609489e+01,3.052433129410937925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408220900811886622e+01,5.356528948537267070e+02,1.954640521264121855e-01,1.100000010988609489e+01,3.052287144009400207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408311809901887557e+01,5.356628948071444256e+02,1.954945749504581332e-01,1.100000010988609489e+01,3.052141158607862489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408402718991888491e+01,5.356728947605665780e+02,1.955250963146568655e-01,1.100000010988609489e+01,3.051995173206324772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408493628081889426e+01,5.356828947139932779e+02,1.955556162190083824e-01,1.100000010988609489e+01,3.051849187804787054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408584537171890361e+01,5.356928946674244116e+02,1.955861346635126841e-01,1.100000010988609489e+01,3.051703202403249337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408675446261891295e+01,5.357028946208599791e+02,1.956166516481697704e-01,1.100000010988609489e+01,3.051557217001711619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408766355351892230e+01,5.357128945742999804e+02,1.956471671729796413e-01,1.100000010988609489e+01,3.051411231600173902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408857264441893165e+01,5.357228945277444154e+02,1.956776812379422970e-01,1.100000010988609489e+01,3.051265246198636184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.408948173531894099e+01,5.357328944811933980e+02,1.957081938430577095e-01,1.100000010988609489e+01,3.051119260797098467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409039082621895034e+01,5.357428944346468143e+02,1.957387049883259067e-01,1.100000010988609489e+01,3.050973275395560749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409129991711895968e+01,5.357528943881046644e+02,1.957692146737468886e-01,1.100000010988609489e+01,3.050827289994023032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409220900801896903e+01,5.357628943415669482e+02,1.957997228993206551e-01,1.100000010988609489e+01,3.050681304592485314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409311809891897838e+01,5.357728942950336659e+02,1.958302296650472063e-01,1.100000010988609489e+01,3.050535319190947597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409402718981898772e+01,5.357828942485048174e+02,1.958607349709265144e-01,1.100000010988609489e+01,3.050389333789409879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409493628071899707e+01,5.357928942019805163e+02,1.958912388169586072e-01,1.100000010988609489e+01,3.050243348387872162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409584537161900641e+01,5.358028941554606490e+02,1.959217412031434846e-01,1.100000010988609489e+01,3.050097362986334444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409675446251901576e+01,5.358128941089452155e+02,1.959522421294811467e-01,1.100000010988609489e+01,3.049951377584796727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409766355341902511e+01,5.358228940624342158e+02,1.959827415959715657e-01,1.100000010988609489e+01,3.049805392183259009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409857264431903445e+01,5.358328940159276499e+02,1.960132396026147694e-01,1.100000010988609489e+01,3.049659406781721292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.409948173521904380e+01,5.358428939694255178e+02,1.960437361494107300e-01,1.100000010988609489e+01,3.049513421380183574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410039082611905314e+01,5.358528939229279331e+02,1.960742312363594753e-01,1.100000010988609489e+01,3.049367435978645857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410129991701906249e+01,5.358628938764347822e+02,1.961047248634610052e-01,1.100000010988609489e+01,3.049221450577108139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410220900791907184e+01,5.358728938299460651e+02,1.961352170307152920e-01,1.100000010988609489e+01,3.049075465175570421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410311809881908118e+01,5.358828937834617818e+02,1.961657077381223635e-01,1.100000010988609489e+01,3.048929479774032704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410402718971909053e+01,5.358928937369819323e+02,1.961961969856821919e-01,1.100000010988609489e+01,3.048783494372494986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410493628061909988e+01,5.359028936905065166e+02,1.962266847733947772e-01,1.100000010988609489e+01,3.048637508970957269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410584537151910922e+01,5.359128936440356483e+02,1.962571711012601472e-01,1.100000010988609489e+01,3.048491523569419551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410675446241911857e+01,5.359228935975692139e+02,1.962876559692782741e-01,1.100000010988609489e+01,3.048345538167881834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410766355331912791e+01,5.359328935511072132e+02,1.963181393774491856e-01,1.100000010988609489e+01,3.048199552766344116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410857264421913726e+01,5.359428935046496463e+02,1.963486213257728541e-01,1.100000010988609489e+01,3.048053567364806399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.410948173511914661e+01,5.359528934581965132e+02,1.963791018142492795e-01,1.100000010988609489e+01,3.047907581963268681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411039082601915595e+01,5.359628934117478138e+02,1.964095808428784895e-01,1.100000010988609489e+01,3.047761596561730964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411129991691916530e+01,5.359728933653035483e+02,1.964400584116604564e-01,1.100000010988609489e+01,3.047615611160193246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411220900781917464e+01,5.359828933188638302e+02,1.964705345205951803e-01,1.100000010988609489e+01,3.047469625758655529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411311809871918399e+01,5.359928932724285460e+02,1.965010091696826888e-01,1.100000010988609489e+01,3.047323640357117811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411402718961919334e+01,5.360028932259976955e+02,1.965314823589229543e-01,1.100000010988609489e+01,3.047177654955580094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411493628051920268e+01,5.360128931795712788e+02,1.965619540883159766e-01,1.100000010988609489e+01,3.047031669554042376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411584537141921203e+01,5.360228931331492959e+02,1.965924243578617558e-01,1.100000010988609489e+01,3.046885684152504659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411675446231922137e+01,5.360328930867317467e+02,1.966228931675602920e-01,1.100000010988609489e+01,3.046739698750966941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411766355321923072e+01,5.360428930403186314e+02,1.966533605174115851e-01,1.100000010988609489e+01,3.046593713349429224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411857264411924007e+01,5.360528929939099498e+02,1.966838264074156628e-01,1.100000010988609489e+01,3.046447727947891506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.411948173501924941e+01,5.360628929475058158e+02,1.967142908375724975e-01,1.100000010988609489e+01,3.046301742546353788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412039082591925876e+01,5.360728929011061155e+02,1.967447538078820890e-01,1.100000010988609489e+01,3.046155757144816071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412129991681926811e+01,5.360828928547108490e+02,1.967752153183444375e-01,1.100000010988609489e+01,3.046009771743278353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412220900771927745e+01,5.360928928083200162e+02,1.968056753689595428e-01,1.100000010988609489e+01,3.045863786341740636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412311809861928680e+01,5.361028927619336173e+02,1.968361339597274051e-01,1.100000010988609489e+01,3.045717800940202918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412402718951929614e+01,5.361128927155516521e+02,1.968665910906480243e-01,1.100000010988609489e+01,3.045571815538665201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412493628041930549e+01,5.361228926691741208e+02,1.968970467617214004e-01,1.100000010988609489e+01,3.045425830137127483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412584537131931484e+01,5.361328926228010232e+02,1.969275009729475334e-01,1.100000010988609489e+01,3.045279844735589766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412675446221932418e+01,5.361428925764323594e+02,1.969579537243263956e-01,1.100000010988609489e+01,3.045133859334052048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412766355311933353e+01,5.361528925300682431e+02,1.969884050158580147e-01,1.100000010988609489e+01,3.044987873932514331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412857264401934287e+01,5.361628924837085606e+02,1.970188548475423906e-01,1.100000010988609489e+01,3.044841888530976613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.412948173491935222e+01,5.361728924373533118e+02,1.970493032193795235e-01,1.100000010988609489e+01,3.044695903129438896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413039082581936157e+01,5.361828923910024969e+02,1.970797501313694133e-01,1.100000010988609489e+01,3.044549917727901178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413129991671937091e+01,5.361928923446561157e+02,1.971101955835120600e-01,1.100000010988609489e+01,3.044403932326363461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413220900761938026e+01,5.362028922983141683e+02,1.971406395758074359e-01,1.100000010988609489e+01,3.044257946924825743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413311809851938960e+01,5.362128922519766547e+02,1.971710821082555687e-01,1.100000010988609489e+01,3.044111961523288026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413402718941939895e+01,5.362228922056435749e+02,1.972015231808564584e-01,1.100000010988609489e+01,3.043965976121750308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413493628031940830e+01,5.362328921593149289e+02,1.972319627936101050e-01,1.100000010988609489e+01,3.043819990720212591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413584537121941764e+01,5.362428921129907167e+02,1.972624009465164807e-01,1.100000010988609489e+01,3.043674005318674873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413675446211942699e+01,5.362528920666710519e+02,1.972928376395756134e-01,1.100000010988609489e+01,3.043528019917137156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413766355301943634e+01,5.362628920203558209e+02,1.973232728727874752e-01,1.100000010988609489e+01,3.043382034515599438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413857264391944568e+01,5.362728919740450237e+02,1.973537066461520939e-01,1.100000010988609489e+01,3.043236049114061720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.413948173481945503e+01,5.362828919277386603e+02,1.973841389596694695e-01,1.100000010988609489e+01,3.043090063712524003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414039082571946437e+01,5.362928918814367307e+02,1.974145698133395743e-01,1.100000010988609489e+01,3.042944078310986285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414129991661947372e+01,5.363028918351392349e+02,1.974449992071624360e-01,1.100000010988609489e+01,3.042798092909448568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414220900751948307e+01,5.363128917888461729e+02,1.974754271411380269e-01,1.100000010988609489e+01,3.042652107507910850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414311809841949241e+01,5.363228917425575446e+02,1.975058536152663746e-01,1.100000010988609489e+01,3.042506122106373133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414402718931950176e+01,5.363328916962733501e+02,1.975362786295474515e-01,1.100000010988609489e+01,3.042360136704835415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414493628021951110e+01,5.363428916499935895e+02,1.975667021839812854e-01,1.100000010988609489e+01,3.042214151303297698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414584537111952045e+01,5.363528916037182626e+02,1.975971242785678483e-01,1.100000010988609489e+01,3.042068165901759980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414675446201952980e+01,5.363628915574473695e+02,1.976275449133071405e-01,1.100000010988609489e+01,3.041922180500222263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414766355291953914e+01,5.363728915111809101e+02,1.976579640881991895e-01,1.100000010988609489e+01,3.041776195098684545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414857264381954849e+01,5.363828914649188846e+02,1.976883818032439677e-01,1.100000010988609489e+01,3.041630209697146828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.414948173471955783e+01,5.363928914186612928e+02,1.977187980584414750e-01,1.100000010988609489e+01,3.041484224295609110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415039082561956718e+01,5.364028913724082486e+02,1.977492128537917393e-01,1.100000010988609489e+01,3.041338238894071393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415129991651957653e+01,5.364128913261596381e+02,1.977796261892947327e-01,1.100000010988609489e+01,3.041192253492533675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415220900741958587e+01,5.364228912799154614e+02,1.978100380649504553e-01,1.100000010988609489e+01,3.041046268090995958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415311809831959522e+01,5.364328912336757185e+02,1.978404484807589070e-01,1.100000010988609489e+01,3.040900282689458240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415402718921960457e+01,5.364428911874404093e+02,1.978708574367201156e-01,1.100000010988609489e+01,3.040754297287920523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415493628011961391e+01,5.364528911412095340e+02,1.979012649328340534e-01,1.100000010988609489e+01,3.040608311886382805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415584537101962326e+01,5.364628910949830924e+02,1.979316709691007203e-01,1.100000010988609489e+01,3.040462326484845088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415675446191963260e+01,5.364728910487610847e+02,1.979620755455201164e-01,1.100000010988609489e+01,3.040316341083307370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415766355281964195e+01,5.364828910025435107e+02,1.979924786620922417e-01,1.100000010988609489e+01,3.040170355681769652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415857264371965130e+01,5.364928909563303705e+02,1.980228803188170961e-01,1.100000010988609489e+01,3.040024370280231935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.415948173461966064e+01,5.365028909101216641e+02,1.980532805156946796e-01,1.100000010988609489e+01,3.039878384878694217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416039082551966999e+01,5.365128908639173915e+02,1.980836792527249923e-01,1.100000010988609489e+01,3.039732399477156500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416129991641967933e+01,5.365228908177175526e+02,1.981140765299080342e-01,1.100000010988609489e+01,3.039586414075618782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416220900731968868e+01,5.365328907715221476e+02,1.981444723472438052e-01,1.100000010988609489e+01,3.039440428674081065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416311809821969803e+01,5.365428907253311763e+02,1.981748667047323054e-01,1.100000010988609489e+01,3.039294443272543347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416402718911970737e+01,5.365528906791446389e+02,1.982052596023735347e-01,1.100000010988609489e+01,3.039148457871005630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416493628001971672e+01,5.365628906329625352e+02,1.982356510401674932e-01,1.100000010988609489e+01,3.039002472469467912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416584537091972607e+01,5.365728905867848653e+02,1.982660410181141808e-01,1.100000010988609489e+01,3.038856487067930195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416675446181973541e+01,5.365828905406116291e+02,1.982964295362135976e-01,1.100000010988609489e+01,3.038710501666392477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416766355271974476e+01,5.365928904944428268e+02,1.983268165944657435e-01,1.100000010988609489e+01,3.038564516264854760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416857264361975410e+01,5.366028904482784583e+02,1.983572021928706186e-01,1.100000010988609489e+01,3.038418530863317042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.416948173451976345e+01,5.366128904021185235e+02,1.983875863314281951e-01,1.100000010988609489e+01,3.038272545461779325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417039082541977280e+01,5.366228903559630226e+02,1.984179690101385007e-01,1.100000010988609489e+01,3.038126560060241607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417129991631978214e+01,5.366328903098119554e+02,1.984483502290015355e-01,1.100000010988609489e+01,3.037980574658703890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417220900721979149e+01,5.366428902636653220e+02,1.984787299880172995e-01,1.100000010988609489e+01,3.037834589257166172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417311809811980083e+01,5.366528902175231224e+02,1.985091082871857648e-01,1.100000010988609489e+01,3.037688603855628455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417402718901981018e+01,5.366628901713853566e+02,1.985394851265069593e-01,1.100000010988609489e+01,3.037542618454090737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417493627991981953e+01,5.366728901252520245e+02,1.985698605059808830e-01,1.100000010988609489e+01,3.037396633052553020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417584537081982887e+01,5.366828900791231263e+02,1.986002344256075081e-01,1.100000010988609489e+01,3.037250647651015302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417675446171983822e+01,5.366928900329986618e+02,1.986306068853868623e-01,1.100000010988609489e+01,3.037104662249477584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417766355261984756e+01,5.367028899868786311e+02,1.986609778853189456e-01,1.100000010988609489e+01,3.036958676847939867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417857264351985691e+01,5.367128899407630342e+02,1.986913474254037304e-01,1.100000010988609489e+01,3.036812691446402149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.417948173441986626e+01,5.367228898946518711e+02,1.987217155056412443e-01,1.100000010988609489e+01,3.036666706044864432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418039082531987560e+01,5.367328898485451418e+02,1.987520821260314596e-01,1.100000010988609489e+01,3.036520720643326714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418129991621988495e+01,5.367428898024428463e+02,1.987824472865744041e-01,1.100000010988609489e+01,3.036374735241788997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418220900711989430e+01,5.367528897563449846e+02,1.988128109872700500e-01,1.100000010988609489e+01,3.036228749840251279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418311809801990364e+01,5.367628897102515566e+02,1.988431732281184250e-01,1.100000010988609489e+01,3.036082764438713562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418402718891991299e+01,5.367728896641625624e+02,1.988735340091195014e-01,1.100000010988609489e+01,3.035936779037175844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418493627981992233e+01,5.367828896180780021e+02,1.989038933302732792e-01,1.100000010988609489e+01,3.035790793635638127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418584537071993168e+01,5.367928895719978755e+02,1.989342511915797862e-01,1.100000010988609489e+01,3.035644808234100409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418675446161994103e+01,5.368028895259221827e+02,1.989646075930389946e-01,1.100000010988609489e+01,3.035498822832562692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418766355251995037e+01,5.368128894798509236e+02,1.989949625346509043e-01,1.100000010988609489e+01,3.035352837431024974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418857264341995972e+01,5.368228894337840984e+02,1.990253160164155433e-01,1.100000010988609489e+01,3.035206852029487257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.418948173431996906e+01,5.368328893877217070e+02,1.990556680383328836e-01,1.100000010988609489e+01,3.035060866627949539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419039082521997841e+01,5.368428893416637493e+02,1.990860186004029253e-01,1.100000010988609489e+01,3.034914881226411822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419129991611998776e+01,5.368528892956102254e+02,1.991163677026256962e-01,1.100000010988609489e+01,3.034768895824874104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419220900701999710e+01,5.368628892495611353e+02,1.991467153450011685e-01,1.100000010988609489e+01,3.034622910423336387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419311809792000645e+01,5.368728892035164790e+02,1.991770615275293421e-01,1.100000010988609489e+01,3.034476925021798669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419402718882001579e+01,5.368828891574762565e+02,1.992074062502102172e-01,1.100000010988609489e+01,3.034330939620260952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419493627972002514e+01,5.368928891114404678e+02,1.992377495130437937e-01,1.100000010988609489e+01,3.034184954218723234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419584537062003449e+01,5.369028890654091128e+02,1.992680913160300715e-01,1.100000010988609489e+01,3.034038968817185516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419675446152004383e+01,5.369128890193821917e+02,1.992984316591690785e-01,1.100000010988609489e+01,3.033892983415647799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419766355242005318e+01,5.369228889733597043e+02,1.993287705424607870e-01,1.100000010988609489e+01,3.033746998014110081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419857264332006253e+01,5.369328889273416507e+02,1.993591079659051968e-01,1.100000010988609489e+01,3.033601012612572364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.419948173422007187e+01,5.369428888813280309e+02,1.993894439295023080e-01,1.100000010988609489e+01,3.033455027211034646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420039082512008122e+01,5.369528888353188449e+02,1.994197784332521206e-01,1.100000010988609489e+01,3.033309041809496929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420129991602009056e+01,5.369628887893140927e+02,1.994501114771546346e-01,1.100000010988609489e+01,3.033163056407959211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420220900692009991e+01,5.369728887433137743e+02,1.994804430612098500e-01,1.100000010988609489e+01,3.033017071006421494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420311809782010926e+01,5.369828886973178896e+02,1.995107731854177668e-01,1.100000010988609489e+01,3.032871085604883776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420402718872011860e+01,5.369928886513264388e+02,1.995411018497783850e-01,1.100000010988609489e+01,3.032725100203346059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420493627962012795e+01,5.370028886053394217e+02,1.995714290542916769e-01,1.100000010988609489e+01,3.032579114801808341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420584537052013729e+01,5.370128885593567247e+02,1.996017547989576701e-01,1.100000010988609489e+01,3.032433129400270624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420675446142014664e+01,5.370228885133784615e+02,1.996320790837763648e-01,1.100000010988609489e+01,3.032287143998732906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420766355232015599e+01,5.370328884674046321e+02,1.996624019087477608e-01,1.100000010988609489e+01,3.032141158597195189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420857264322016533e+01,5.370428884214352365e+02,1.996927232738718583e-01,1.100000010988609489e+01,3.031995173195657471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.420948173412017468e+01,5.370528883754702747e+02,1.997230431791486571e-01,1.100000010988609489e+01,3.031849187794119754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421039082502018402e+01,5.370628883295097467e+02,1.997533616245781296e-01,1.100000010988609489e+01,3.031703202392582036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421129991592019337e+01,5.370728882835536524e+02,1.997836786101603035e-01,1.100000010988609489e+01,3.031557216991044319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421220900682020272e+01,5.370828882376019919e+02,1.998139941358951788e-01,1.100000010988609489e+01,3.031411231589506601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421311809772021206e+01,5.370928881916547653e+02,1.998443082017827277e-01,1.100000010988609489e+01,3.031265246187968884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421402718862022141e+01,5.371028881457119724e+02,1.998746208078229780e-01,1.100000010988609489e+01,3.031119260786431166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421493627952023076e+01,5.371128880997736132e+02,1.999049319540159297e-01,1.100000010988609489e+01,3.030973275384893448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421584537042024010e+01,5.371228880538396879e+02,1.999352416403615551e-01,1.100000010988609489e+01,3.030827289983355731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421675446132024945e+01,5.371328880079101964e+02,1.999655498668598819e-01,1.100000010988609489e+01,3.030681304581818013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421766355222025879e+01,5.371428879619851386e+02,1.999958566335108823e-01,1.100000010988609489e+01,3.030535319180280296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421857264312026814e+01,5.371528879160644010e+02,2.000261619403145841e-01,1.100000010988609489e+01,3.030389333778742578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.421948173402027749e+01,5.371628878701480971e+02,2.000564657872709595e-01,1.100000010988609489e+01,3.030243348377204861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422039082492028683e+01,5.371728878242362271e+02,2.000867681743800364e-01,1.100000010988609489e+01,3.030097362975667143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422129991582029618e+01,5.371828877783287908e+02,2.001170691016417869e-01,1.100000010988609489e+01,3.029951377574129426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422220900672030552e+01,5.371928877324257883e+02,2.001473685690562387e-01,1.100000010988609489e+01,3.029805392172591708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422311809762031487e+01,5.372028876865272196e+02,2.001776665766233643e-01,1.100000010988609489e+01,3.029659406771053991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422402718852032422e+01,5.372128876406330846e+02,2.002079631243431912e-01,1.100000010988609489e+01,3.029513421369516273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422493627942033356e+01,5.372228875947433835e+02,2.002382582122156918e-01,1.100000010988609489e+01,3.029367435967978556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422584537032034291e+01,5.372328875488581161e+02,2.002685518402408660e-01,1.100000010988609489e+01,3.029221450566440838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422675446122035225e+01,5.372428875029772826e+02,2.002988440084187416e-01,1.100000010988609489e+01,3.029075465164903121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422766355212036160e+01,5.372528874571008828e+02,2.003291347167492908e-01,1.100000010988609489e+01,3.028929479763365403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422857264302037095e+01,5.372628874112288031e+02,2.003594239652325137e-01,1.100000010988609489e+01,3.028783494361827686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.422948173392038029e+01,5.372728873653611572e+02,2.003897117538684380e-01,1.100000010988609489e+01,3.028637508960289968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423039082482038964e+01,5.372828873194979451e+02,2.004199980826570360e-01,1.100000010988609489e+01,3.028491523558752251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423129991572039899e+01,5.372928872736391668e+02,2.004502829515983076e-01,1.100000010988609489e+01,3.028345538157214533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423220900662040833e+01,5.373028872277848222e+02,2.004805663606922528e-01,1.100000010988609489e+01,3.028199552755676816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423311809752041768e+01,5.373128871819349115e+02,2.005108483099388716e-01,1.100000010988609489e+01,3.028053567354139098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423402718842042702e+01,5.373228871360894345e+02,2.005411287993381919e-01,1.100000010988609489e+01,3.027907581952601380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423493627932043637e+01,5.373328870902483914e+02,2.005714078288901858e-01,1.100000010988609489e+01,3.027761596551063663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423584537022044572e+01,5.373428870444116683e+02,2.006016853985948534e-01,1.100000010988609489e+01,3.027615611149525945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423675446112045506e+01,5.373528869985793790e+02,2.006319615084521946e-01,1.100000010988609489e+01,3.027469625747988228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423766355202046441e+01,5.373628869527515235e+02,2.006622361584622094e-01,1.100000010988609489e+01,3.027323640346450510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423857264292047375e+01,5.373728869069281018e+02,2.006925093486248979e-01,1.100000010988609489e+01,3.027177654944912793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.423948173382048310e+01,5.373828868611091139e+02,2.007227810789402600e-01,1.100000010988609489e+01,3.027031669543375075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424039082472049245e+01,5.373928868152945597e+02,2.007530513494082958e-01,1.100000010988609489e+01,3.026885684141837358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424129991562050179e+01,5.374028867694844394e+02,2.007833201600290052e-01,1.100000010988609489e+01,3.026739698740299640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424220900652051114e+01,5.374128867236787528e+02,2.008135875108023882e-01,1.100000010988609489e+01,3.026593713338761923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424311809742052048e+01,5.374228866778773863e+02,2.008438534017284449e-01,1.100000010988609489e+01,3.026447727937224205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424402718832052983e+01,5.374328866320804536e+02,2.008741178328071753e-01,1.100000010988609489e+01,3.026301742535686488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424493627922053918e+01,5.374428865862879547e+02,2.009043808040385792e-01,1.100000010988609489e+01,3.026155757134148770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424584537012054852e+01,5.374528865404998896e+02,2.009346423154226291e-01,1.100000010988609489e+01,3.026009771732611053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424675446102055787e+01,5.374628864947162583e+02,2.009649023669593526e-01,1.100000010988609489e+01,3.025863786331073335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424766355192056722e+01,5.374728864489370608e+02,2.009951609586487498e-01,1.100000010988609489e+01,3.025717800929535618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424857264282057656e+01,5.374828864031622970e+02,2.010254180904908206e-01,1.100000010988609489e+01,3.025571815527997900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.424948173372058591e+01,5.374928863573918534e+02,2.010556737624855650e-01,1.100000010988609489e+01,3.025425830126460183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425039082462059525e+01,5.375028863116258435e+02,2.010859279746329553e-01,1.100000010988609489e+01,3.025279844724922465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425129991552060460e+01,5.375128862658642674e+02,2.011161807269330193e-01,1.100000010988609489e+01,3.025133859323384748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425220900642061395e+01,5.375228862201071252e+02,2.011464320193857569e-01,1.100000010988609489e+01,3.024987873921847030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425311809732062329e+01,5.375328861743544167e+02,2.011766818519911404e-01,1.100000010988609489e+01,3.024841888520309312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425402718822063264e+01,5.375428861286061419e+02,2.012069302247491975e-01,1.100000010988609489e+01,3.024695903118771595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425493627912064198e+01,5.375528860828623010e+02,2.012371771376599283e-01,1.100000010988609489e+01,3.024549917717233877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425584537002065133e+01,5.375628860371227802e+02,2.012674225907233050e-01,1.100000010988609489e+01,3.024403932315696160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425675446092066068e+01,5.375728859913876931e+02,2.012976665839393553e-01,1.100000010988609489e+01,3.024257946914158442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425766355182067002e+01,5.375828859456570399e+02,2.013279091173080515e-01,1.100000010988609489e+01,3.024111961512620725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425857264272067937e+01,5.375928858999308204e+02,2.013581501908294213e-01,1.100000010988609489e+01,3.023965976111083007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.425948173362068871e+01,5.376028858542090347e+02,2.013883898045034371e-01,1.100000010988609489e+01,3.023819990709545290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426039082452069806e+01,5.376128858084916828e+02,2.014186279583301264e-01,1.100000010988609489e+01,3.023674005308007572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426129991542070741e+01,5.376228857627786510e+02,2.014488646523094617e-01,1.100000010988609489e+01,3.023528019906469855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426220900632071675e+01,5.376328857170700530e+02,2.014790998864414706e-01,1.100000010988609489e+01,3.023382034504932137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426311809722072610e+01,5.376428856713658888e+02,2.015093336607261254e-01,1.100000010988609489e+01,3.023236049103394420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426402718812073545e+01,5.376528856256661584e+02,2.015395659751634261e-01,1.100000010988609489e+01,3.023090063701856702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426493627902074479e+01,5.376628855799708617e+02,2.015697968297534004e-01,1.100000010988609489e+01,3.022944078300318985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426584536992075414e+01,5.376728855342798852e+02,2.016000262244960206e-01,1.100000010988609489e+01,3.022798092898781267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426675446082076348e+01,5.376828854885933424e+02,2.016302541593912867e-01,1.100000010988609489e+01,3.022652107497243550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426766355172077283e+01,5.376928854429112334e+02,2.016604806344392264e-01,1.100000010988609489e+01,3.022506122095705832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426857264262078218e+01,5.377028853972335583e+02,2.016907056496398121e-01,1.100000010988609489e+01,3.022360136694168115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.426948173352079152e+01,5.377128853515603168e+02,2.017209292049930436e-01,1.100000010988609489e+01,3.022214151292630397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427039082442080087e+01,5.377228853058915092e+02,2.017511513004989210e-01,1.100000010988609489e+01,3.022068165891092680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427129991532081021e+01,5.377328852602270217e+02,2.017813719361574720e-01,1.100000010988609489e+01,3.021922180489554962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427220900622081956e+01,5.377428852145669680e+02,2.018115911119686690e-01,1.100000010988609489e+01,3.021776195088017244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427311809712082891e+01,5.377528851689113480e+02,2.018418088279325118e-01,1.100000010988609489e+01,3.021630209686479527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427402718802083825e+01,5.377628851232601619e+02,2.018720250840490005e-01,1.100000010988609489e+01,3.021484224284941809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427493627892084760e+01,5.377728850776134095e+02,2.019022398803181351e-01,1.100000010988609489e+01,3.021338238883404092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427584536982085694e+01,5.377828850319709773e+02,2.019324532167399155e-01,1.100000010988609489e+01,3.021192253481866374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427675446072086629e+01,5.377928849863329788e+02,2.019626650933143419e-01,1.100000010988609489e+01,3.021046268080328657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427766355162087564e+01,5.378028849406994141e+02,2.019928755100414142e-01,1.100000010988609489e+01,3.020900282678790939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427857264252088498e+01,5.378128848950702832e+02,2.020230844669211323e-01,1.100000010988609489e+01,3.020754297277253222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.427948173342089433e+01,5.378228848494455860e+02,2.020532919639534963e-01,1.100000010988609489e+01,3.020608311875715504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428039082432090368e+01,5.378328848038252090e+02,2.020834980011385063e-01,1.100000010988609489e+01,3.020462326474177787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428129991522091302e+01,5.378428847582092658e+02,2.021137025784761621e-01,1.100000010988609489e+01,3.020316341072640069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428220900612092237e+01,5.378528847125977563e+02,2.021439056959664637e-01,1.100000010988609489e+01,3.020170355671102352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428311809702093171e+01,5.378628846669906807e+02,2.021741073536094113e-01,1.100000010988609489e+01,3.020024370269564634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428402718792094106e+01,5.378728846213879251e+02,2.022043075514050048e-01,1.100000010988609489e+01,3.019878384868026917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428493627882095041e+01,5.378828845757896033e+02,2.022345062893532441e-01,1.100000010988609489e+01,3.019732399466489199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428584536972095975e+01,5.378928845301957153e+02,2.022647035674541294e-01,1.100000010988609489e+01,3.019586414064951482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428675446062096910e+01,5.379028844846062611e+02,2.022948993857076327e-01,1.100000010988609489e+01,3.019440428663413764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428766355152097844e+01,5.379128844390212407e+02,2.023250937441137820e-01,1.100000010988609489e+01,3.019294443261876047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428857264242098779e+01,5.379228843934405404e+02,2.023552866426725771e-01,1.100000010988609489e+01,3.019148457860338329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.428948173332099714e+01,5.379328843478642739e+02,2.023854780813840182e-01,1.100000010988609489e+01,3.019002472458800612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429039082422100648e+01,5.379428843022924411e+02,2.024156680602480773e-01,1.100000010988609489e+01,3.018856487057262894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429129991512101583e+01,5.379528842567250422e+02,2.024458565792647824e-01,1.100000010988609489e+01,3.018710501655725176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429220900602102517e+01,5.379628842111619633e+02,2.024760436384341333e-01,1.100000010988609489e+01,3.018564516254187459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429311809692103452e+01,5.379728841656033183e+02,2.025062292377561024e-01,1.100000010988609489e+01,3.018418530852649741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429402718782104387e+01,5.379828841200491070e+02,2.025364133772307174e-01,1.100000010988609489e+01,3.018272545451112024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429493627872105321e+01,5.379928840744993295e+02,2.025665960568579782e-01,1.100000010988609489e+01,3.018126560049574306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429584536962106256e+01,5.380028840289538721e+02,2.025967772766378572e-01,1.100000010988609489e+01,3.017980574648036589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429675446052107191e+01,5.380128839834128485e+02,2.026269570365703820e-01,1.100000010988609489e+01,3.017834589246498871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429766355142108125e+01,5.380228839378762586e+02,2.026571353366555250e-01,1.100000010988609489e+01,3.017688603844961154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429857264232109060e+01,5.380328838923441026e+02,2.026873121768933139e-01,1.100000010988609489e+01,3.017542618443423436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.429948173322109994e+01,5.380428838468162667e+02,2.027174875572837209e-01,1.100000010988609489e+01,3.017396633041885719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430039082412110929e+01,5.380528838012928645e+02,2.027476614778267738e-01,1.100000010988609489e+01,3.017250647640348001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430129991502111864e+01,5.380628837557738962e+02,2.027778339385224449e-01,1.100000010988609489e+01,3.017104662238810284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430220900592112798e+01,5.380728837102593616e+02,2.028080049393707340e-01,1.100000010988609489e+01,3.016958676837272566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430311809682113733e+01,5.380828836647491471e+02,2.028381744803716691e-01,1.100000010988609489e+01,3.016812691435734849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430402718772114667e+01,5.380928836192433664e+02,2.028683425615252223e-01,1.100000010988609489e+01,3.016666706034197131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430493627862115602e+01,5.381028835737420195e+02,2.028985091828314213e-01,1.100000010988609489e+01,3.016520720632659414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430584536952116537e+01,5.381128835282451064e+02,2.029286743442902385e-01,1.100000010988609489e+01,3.016374735231121696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430675446042117471e+01,5.381228834827525134e+02,2.029588380459016739e-01,1.100000010988609489e+01,3.016228749829583979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430766355132118406e+01,5.381328834372643541e+02,2.029890002876657273e-01,1.100000010988609489e+01,3.016082764428046261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430857264222119341e+01,5.381428833917806287e+02,2.030191610695824267e-01,1.100000010988609489e+01,3.015936779026508543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.430948173312120275e+01,5.381528833463013370e+02,2.030493203916517442e-01,1.100000010988609489e+01,3.015790793624970826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431039082402121210e+01,5.381628833008263655e+02,2.030794782538736798e-01,1.100000010988609489e+01,3.015644808223433108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431129991492122144e+01,5.381728832553558277e+02,2.031096346562482335e-01,1.100000010988609489e+01,3.015498822821895391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431220900582123079e+01,5.381828832098897237e+02,2.031397895987754054e-01,1.100000010988609489e+01,3.015352837420357673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431311809672124014e+01,5.381928831644279398e+02,2.031699430814552232e-01,1.100000010988609489e+01,3.015206852018819956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431402718762124948e+01,5.382028831189705897e+02,2.032000951042876591e-01,1.100000010988609489e+01,3.015060866617282238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431493627852125883e+01,5.382128830735176734e+02,2.032302456672727131e-01,1.100000010988609489e+01,3.014914881215744521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431584536942126817e+01,5.382228830280691909e+02,2.032603947704103853e-01,1.100000010988609489e+01,3.014768895814206803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431675446032127752e+01,5.382328829826250285e+02,2.032905424137006756e-01,1.100000010988609489e+01,3.014622910412669086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431766355122128687e+01,5.382428829371852999e+02,2.033206885971435840e-01,1.100000010988609489e+01,3.014476925011131368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431857264212129621e+01,5.382528828917500050e+02,2.033508333207391106e-01,1.100000010988609489e+01,3.014330939609593651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.431948173302130556e+01,5.382628828463190303e+02,2.033809765844872552e-01,1.100000010988609489e+01,3.014184954208055933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432039082392131490e+01,5.382728828008924893e+02,2.034111183883880181e-01,1.100000010988609489e+01,3.014038968806518216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432129991482132425e+01,5.382828827554703821e+02,2.034412587324413990e-01,1.100000010988609489e+01,3.013892983404980498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432220900572133360e+01,5.382928827100527087e+02,2.034713976166473981e-01,1.100000010988609489e+01,3.013746998003442781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432311809662134294e+01,5.383028826646393554e+02,2.035015350410059876e-01,1.100000010988609489e+01,3.013601012601905063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432402718752135229e+01,5.383128826192304359e+02,2.035316710055171951e-01,1.100000010988609489e+01,3.013455027200367346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432493627842136164e+01,5.383228825738259502e+02,2.035618055101810209e-01,1.100000010988609489e+01,3.013309041798829628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432584536932137098e+01,5.383328825284257846e+02,2.035919385549974647e-01,1.100000010988609489e+01,3.013163056397291911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432675446022138033e+01,5.383428824830300528e+02,2.036220701399665267e-01,1.100000010988609489e+01,3.013017070995754193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432766355112138967e+01,5.383528824376387547e+02,2.036522002650881791e-01,1.100000010988609489e+01,3.012871085594216475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432857264202139902e+01,5.383628823922517768e+02,2.036823289303624496e-01,1.100000010988609489e+01,3.012725100192678758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.432948173292140837e+01,5.383728823468692326e+02,2.037124561357893382e-01,1.100000010988609489e+01,3.012579114791141040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433039082382141771e+01,5.383828823014911222e+02,2.037425818813688450e-01,1.100000010988609489e+01,3.012433129389603323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433129991472142706e+01,5.383928822561174456e+02,2.037727061671009421e-01,1.100000010988609489e+01,3.012287143988065605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433220900562143640e+01,5.384028822107480892e+02,2.038028289929856574e-01,1.100000010988609489e+01,3.012141158586527888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433311809652144575e+01,5.384128821653831665e+02,2.038329503590229907e-01,1.100000010988609489e+01,3.011995173184990170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433402718742145510e+01,5.384228821200226776e+02,2.038630702652129145e-01,1.100000010988609489e+01,3.011849187783452453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433493627832146444e+01,5.384328820746665087e+02,2.038931887115554564e-01,1.100000010988609489e+01,3.011703202381914735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433584536922147379e+01,5.384428820293147737e+02,2.039233056980505887e-01,1.100000010988609489e+01,3.011557216980377018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433675446012148313e+01,5.384528819839674725e+02,2.039534212246983391e-01,1.100000010988609489e+01,3.011411231578839300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433766355102149248e+01,5.384628819386244913e+02,2.039835352914986799e-01,1.100000010988609489e+01,3.011265246177301583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433857264192150183e+01,5.384728818932859440e+02,2.040136478984516388e-01,1.100000010988609489e+01,3.011119260775763865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.433948173282151117e+01,5.384828818479518304e+02,2.040437590455571881e-01,1.100000010988609489e+01,3.010973275374226148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434039082372152052e+01,5.384928818026220370e+02,2.040738687328153556e-01,1.100000010988609489e+01,3.010827289972688430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434129991462152987e+01,5.385028817572966773e+02,2.041039769602261134e-01,1.100000010988609489e+01,3.010681304571150713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434220900552153921e+01,5.385128817119757514e+02,2.041340837277894615e-01,1.100000010988609489e+01,3.010535319169612995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434311809642154856e+01,5.385228816666591456e+02,2.041641890355054278e-01,1.100000010988609489e+01,3.010389333768075278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434402718732155790e+01,5.385328816213469736e+02,2.041942928833739845e-01,1.100000010988609489e+01,3.010243348366537560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434493627822156725e+01,5.385428815760392354e+02,2.042243952713951316e-01,1.100000010988609489e+01,3.010097362964999843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434584536912157660e+01,5.385528815307358173e+02,2.042544961995688968e-01,1.100000010988609489e+01,3.009951377563462125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434675446002158594e+01,5.385628814854368329e+02,2.042845956678952524e-01,1.100000010988609489e+01,3.009805392161924407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434766355092159529e+01,5.385728814401421687e+02,2.043146936763741983e-01,1.100000010988609489e+01,3.009659406760386690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434857264182160463e+01,5.385828813948519382e+02,2.043447902250057346e-01,1.100000010988609489e+01,3.009513421358848972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.434948173272161398e+01,5.385928813495661416e+02,2.043748853137898891e-01,1.100000010988609489e+01,3.009367435957311255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435039082362162333e+01,5.386028813042846650e+02,2.044049789427266339e-01,1.100000010988609489e+01,3.009221450555773537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435129991452163267e+01,5.386128812590076222e+02,2.044350711118159691e-01,1.100000010988609489e+01,3.009075465154235820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435220900542164202e+01,5.386228812137350133e+02,2.044651618210578947e-01,1.100000010988609489e+01,3.008929479752698102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435311809632165136e+01,5.386328811684667244e+02,2.044952510704524107e-01,1.100000010988609489e+01,3.008783494351160385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435402718722166071e+01,5.386428811232028693e+02,2.045253388599995170e-01,1.100000010988609489e+01,3.008637508949622667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435493627812167006e+01,5.386528810779434480e+02,2.045554251896992137e-01,1.100000010988609489e+01,3.008491523548084950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435584536902167940e+01,5.386628810326883467e+02,2.045855100595515008e-01,1.100000010988609489e+01,3.008345538146547232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435675445992168875e+01,5.386728809874376793e+02,2.046155934695563783e-01,1.100000010988609489e+01,3.008199552745009515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435766355082169810e+01,5.386828809421914457e+02,2.046456754197138461e-01,1.100000010988609489e+01,3.008053567343471797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435857264172170744e+01,5.386928808969495321e+02,2.046757559100239043e-01,1.100000010988609489e+01,3.007907581941934080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.435948173262171679e+01,5.387028808517120524e+02,2.047058349404865529e-01,1.100000010988609489e+01,3.007761596540396362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436039082352172613e+01,5.387128808064788927e+02,2.047359125111017919e-01,1.100000010988609489e+01,3.007615611138858645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436129991442173548e+01,5.387228807612501669e+02,2.047659886218696212e-01,1.100000010988609489e+01,3.007469625737320927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436220900532174483e+01,5.387328807160258748e+02,2.047960632727900410e-01,1.100000010988609489e+01,3.007323640335783210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436311809622175417e+01,5.387428806708059028e+02,2.048261364638630511e-01,1.100000010988609489e+01,3.007177654934245492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436402718712176352e+01,5.387528806255903646e+02,2.048562081950886515e-01,1.100000010988609489e+01,3.007031669532707775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436493627802177286e+01,5.387628805803791465e+02,2.048862784664668424e-01,1.100000010988609489e+01,3.006885684131170057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436584536892178221e+01,5.387728805351723622e+02,2.049163472779975959e-01,1.100000010988609489e+01,3.006739698729632339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436675445982179156e+01,5.387828804899700117e+02,2.049464146296809397e-01,1.100000010988609489e+01,3.006593713328094622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436766355072180090e+01,5.387928804447719813e+02,2.049764805215168739e-01,1.100000010988609489e+01,3.006447727926556904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436857264162181025e+01,5.388028803995783846e+02,2.050065449535053985e-01,1.100000010988609489e+01,3.006301742525019187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.436948173252181959e+01,5.388128803543892218e+02,2.050366079256464857e-01,1.100000010988609489e+01,3.006155757123481469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437039082342182894e+01,5.388228803092043790e+02,2.050666694379401633e-01,1.100000010988609489e+01,3.006009771721943752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437129991432183829e+01,5.388328802640239701e+02,2.050967294903864313e-01,1.100000010988609489e+01,3.005863786320406034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437220900522184763e+01,5.388428802188478812e+02,2.051267880829852619e-01,1.100000010988609489e+01,3.005717800918868317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437311809612185698e+01,5.388528801736762261e+02,2.051568452157366829e-01,1.100000010988609489e+01,3.005571815517330599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437402718702186633e+01,5.388628801285090049e+02,2.051869008886406665e-01,1.100000010988609489e+01,3.005425830115792882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437493627792187567e+01,5.388728800833461037e+02,2.052169551016972404e-01,1.100000010988609489e+01,3.005279844714255164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437584536882188502e+01,5.388828800381876363e+02,2.052470078549064048e-01,1.100000010988609489e+01,3.005133859312717447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437675445972189436e+01,5.388928799930334890e+02,2.052770591482681317e-01,1.100000010988609489e+01,3.004987873911179729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437766355062190371e+01,5.389028799478837755e+02,2.053071089817824491e-01,1.100000010988609489e+01,3.004841888509642012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437857264152191306e+01,5.389128799027383820e+02,2.053371573554493290e-01,1.100000010988609489e+01,3.004695903108104294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.437948173242192240e+01,5.389228798575974224e+02,2.053672042692687716e-01,1.100000010988609489e+01,3.004549917706566577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438039082332193175e+01,5.389328798124608966e+02,2.053972497232408045e-01,1.100000010988609489e+01,3.004403932305028859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438129991422194109e+01,5.389428797673286908e+02,2.054272937173654001e-01,1.100000010988609489e+01,3.004257946903491142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438220900512195044e+01,5.389528797222009189e+02,2.054573362516425861e-01,1.100000010988609489e+01,3.004111961501953424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438311809602195979e+01,5.389628796770774670e+02,2.054873773260723346e-01,1.100000010988609489e+01,3.003965976100415707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438402718692196913e+01,5.389728796319584490e+02,2.055174169406546458e-01,1.100000010988609489e+01,3.003819990698877989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438493627782197848e+01,5.389828795868438647e+02,2.055474550953895474e-01,1.100000010988609489e+01,3.003674005297340271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438584536872198782e+01,5.389928795417336005e+02,2.055774917902770116e-01,1.100000010988609489e+01,3.003528019895802554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438675445962199717e+01,5.390028794966277701e+02,2.056075270253170384e-01,1.100000010988609489e+01,3.003382034494264836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438766355052200652e+01,5.390128794515262598e+02,2.056375608005096278e-01,1.100000010988609489e+01,3.003236049092727119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438857264142201586e+01,5.390228794064291833e+02,2.056675931158548076e-01,1.100000010988609489e+01,3.003090063691189401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.438948173232202521e+01,5.390328793613364269e+02,2.056976239713525501e-01,1.100000010988609489e+01,3.002944078289651684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439039082322203456e+01,5.390428793162481043e+02,2.057276533670028551e-01,1.100000010988609489e+01,3.002798092888113966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439129991412204390e+01,5.390528792711641017e+02,2.057576813028057228e-01,1.100000010988609489e+01,3.002652107486576249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439220900502205325e+01,5.390628792260845330e+02,2.057877077787611531e-01,1.100000010988609489e+01,3.002506122085038531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439311809592206259e+01,5.390728791810093981e+02,2.058177327948691460e-01,1.100000010988609489e+01,3.002360136683500814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439402718682207194e+01,5.390828791359385832e+02,2.058477563511297015e-01,1.100000010988609489e+01,3.002214151281963096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439493627772208129e+01,5.390928790908722021e+02,2.058777784475428196e-01,1.100000010988609489e+01,3.002068165880425379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439584536862209063e+01,5.391028790458101412e+02,2.059077990841085004e-01,1.100000010988609489e+01,3.001922180478887661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439675445952209998e+01,5.391128790007525140e+02,2.059378182608267438e-01,1.100000010988609489e+01,3.001776195077349944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439766355042210932e+01,5.391228789556992069e+02,2.059678359776975498e-01,1.100000010988609489e+01,3.001630209675812226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439857264132211867e+01,5.391328789106503336e+02,2.059978522347209184e-01,1.100000010988609489e+01,3.001484224274274509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.439948173222212802e+01,5.391428788656057804e+02,2.060278670318968497e-01,1.100000010988609489e+01,3.001338238872736791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440039082312213736e+01,5.391528788205656610e+02,2.060578803692253436e-01,1.100000010988609489e+01,3.001192253471199074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440129991402214671e+01,5.391628787755299754e+02,2.060878922467064001e-01,1.100000010988609489e+01,3.001046268069661356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440220900492215605e+01,5.391728787304986099e+02,2.061179026643400192e-01,1.100000010988609489e+01,3.000900282668123639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440311809582216540e+01,5.391828786854716782e+02,2.061479116221262009e-01,1.100000010988609489e+01,3.000754297266585921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440402718672217475e+01,5.391928786404490666e+02,2.061779191200649453e-01,1.100000010988609489e+01,3.000608311865048203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440493627762218409e+01,5.392028785954308887e+02,2.062079251581562245e-01,1.100000010988609489e+01,3.000462326463510486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440584536852219344e+01,5.392128785504170310e+02,2.062379297364000663e-01,1.100000010988609489e+01,3.000316341061972768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440675445942220279e+01,5.392228785054076070e+02,2.062679328547964708e-01,1.100000010988609489e+01,3.000170355660435051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440766355032221213e+01,5.392328784604025032e+02,2.062979345133454379e-01,1.100000010988609489e+01,3.000024370258897333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440857264122222148e+01,5.392428784154018331e+02,2.063279347120469398e-01,1.100000010988609489e+01,2.999878384857359616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.440948173212223082e+01,5.392528783704054831e+02,2.063579334509010044e-01,1.100000010988609489e+01,2.999732399455821898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441039082302224017e+01,5.392628783254135669e+02,2.063879307299076316e-01,1.100000010988609489e+01,2.999586414054284181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441129991392224952e+01,5.392728782804259708e+02,2.064179265490667936e-01,1.100000010988609489e+01,2.999440428652746463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441220900482225886e+01,5.392828782354428085e+02,2.064479209083785183e-01,1.100000010988609489e+01,2.999294443251208746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441311809572226821e+01,5.392928781904639663e+02,2.064779138078428056e-01,1.100000010988609489e+01,2.999148457849671028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441402718662227755e+01,5.393028781454895579e+02,2.065079052474596277e-01,1.100000010988609489e+01,2.999002472448133311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441493627752228690e+01,5.393128781005194696e+02,2.065378952272290125e-01,1.100000010988609489e+01,2.998856487046595593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441584536842229625e+01,5.393228780555538151e+02,2.065678837471509321e-01,1.100000010988609489e+01,2.998710501645057876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441675445932230559e+01,5.393328780105924807e+02,2.065978708072254144e-01,1.100000010988609489e+01,2.998564516243520158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441766355022231494e+01,5.393428779656355800e+02,2.066278564074524315e-01,1.100000010988609489e+01,2.998418530841982441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441857264112232428e+01,5.393528779206829995e+02,2.066578405478320113e-01,1.100000010988609489e+01,2.998272545440444723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.441948173202233363e+01,5.393628778757348528e+02,2.066878232283641259e-01,1.100000010988609489e+01,2.998126560038907006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442039082292234298e+01,5.393728778307910261e+02,2.067178044490487754e-01,1.100000010988609489e+01,2.997980574637369288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442129991382235232e+01,5.393828777858516332e+02,2.067477842098859875e-01,1.100000010988609489e+01,2.997834589235831571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442220900472236167e+01,5.393928777409165605e+02,2.067777625108757344e-01,1.100000010988609489e+01,2.997688603834293853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442311809562237102e+01,5.394028776959859215e+02,2.068077393520180440e-01,1.100000010988609489e+01,2.997542618432756135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442402718652238036e+01,5.394128776510596026e+02,2.068377147333128885e-01,1.100000010988609489e+01,2.997396633031218418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442493627742238971e+01,5.394228776061377175e+02,2.068676886547602678e-01,1.100000010988609489e+01,2.997250647629680700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442584536832239905e+01,5.394328775612201525e+02,2.068976611163601820e-01,1.100000010988609489e+01,2.997104662228142983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442675445922240840e+01,5.394428775163070213e+02,2.069276321181126588e-01,1.100000010988609489e+01,2.996958676826605265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442766355012241775e+01,5.394528774713982102e+02,2.069576016600176704e-01,1.100000010988609489e+01,2.996812691425067548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442857264102242709e+01,5.394628774264938329e+02,2.069875697420752170e-01,1.100000010988609489e+01,2.996666706023529830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.442948173192243644e+01,5.394728773815937757e+02,2.070175363642852984e-01,1.100000010988609489e+01,2.996520720621992113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443039082282244578e+01,5.394828773366981522e+02,2.070475015266479146e-01,1.100000010988609489e+01,2.996374735220454395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443129991372245513e+01,5.394928772918068489e+02,2.070774652291630658e-01,1.100000010988609489e+01,2.996228749818916678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443220900462246448e+01,5.395028772469199794e+02,2.071074274718307795e-01,1.100000010988609489e+01,2.996082764417378960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443311809552247382e+01,5.395128772020374299e+02,2.071373882546510281e-01,1.100000010988609489e+01,2.995936779015841243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443402718642248317e+01,5.395228771571593143e+02,2.071673475776238116e-01,1.100000010988609489e+01,2.995790793614303525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443493627732249251e+01,5.395328771122855187e+02,2.071973054407491299e-01,1.100000010988609489e+01,2.995644808212765808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443584536822250186e+01,5.395428770674161569e+02,2.072272618440269831e-01,1.100000010988609489e+01,2.995498822811228090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443675445912251121e+01,5.395528770225511153e+02,2.072572167874573712e-01,1.100000010988609489e+01,2.995352837409690373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443766355002252055e+01,5.395628769776905074e+02,2.072871702710402941e-01,1.100000010988609489e+01,2.995206852008152655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443857264092252990e+01,5.395728769328342196e+02,2.073171222947757519e-01,1.100000010988609489e+01,2.995060866606614938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.443948173182253925e+01,5.395828768879822519e+02,2.073470728586637446e-01,1.100000010988609489e+01,2.994914881205077220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444039082272254859e+01,5.395928768431347180e+02,2.073770219627042444e-01,1.100000010988609489e+01,2.994768895803539503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444129991362255794e+01,5.396028767982915042e+02,2.074069696068972790e-01,1.100000010988609489e+01,2.994622910402001785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444220900452256728e+01,5.396128767534527242e+02,2.074369157912428485e-01,1.100000010988609489e+01,2.994476925000464067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444311809542257663e+01,5.396228767086182643e+02,2.074668605157409529e-01,1.100000010988609489e+01,2.994330939598926350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444402718632258598e+01,5.396328766637882381e+02,2.074968037803915921e-01,1.100000010988609489e+01,2.994184954197388632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444493627722259532e+01,5.396428766189625321e+02,2.075267455851947662e-01,1.100000010988609489e+01,2.994038968795850915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444584536812260467e+01,5.396528765741412599e+02,2.075566859301504474e-01,1.100000010988609489e+01,2.993892983394313197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444675445902261401e+01,5.396628765293243077e+02,2.075866248152586635e-01,1.100000010988609489e+01,2.993746997992775480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444766354992262336e+01,5.396728764845117894e+02,2.076165622405194144e-01,1.100000010988609489e+01,2.993601012591237762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444857264082263271e+01,5.396828764397035911e+02,2.076464982059327002e-01,1.100000010988609489e+01,2.993455027189700045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.444948173172264205e+01,5.396928763948997130e+02,2.076764327114984932e-01,1.100000010988609489e+01,2.993309041788162327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445039082262265140e+01,5.397028763501002686e+02,2.077063657572168209e-01,1.100000010988609489e+01,2.993163056386624610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445129991352266075e+01,5.397128763053051443e+02,2.077362973430876558e-01,1.100000010988609489e+01,2.993017070985086892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445220900442267009e+01,5.397228762605144539e+02,2.077662274691110256e-01,1.100000010988609489e+01,2.992871085583549175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445311809532267944e+01,5.397328762157280835e+02,2.077961561352869302e-01,1.100000010988609489e+01,2.992725100182011457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445402718622268878e+01,5.397428761709461469e+02,2.078260833416153419e-01,1.100000010988609489e+01,2.992579114780473740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445493627712269813e+01,5.397528761261685304e+02,2.078560090880962885e-01,1.100000010988609489e+01,2.992433129378936022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445584536802270748e+01,5.397628760813952340e+02,2.078859333747297422e-01,1.100000010988609489e+01,2.992287143977398305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445675445892271682e+01,5.397728760366263714e+02,2.079158562015157308e-01,1.100000010988609489e+01,2.992141158575860587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445766354982272617e+01,5.397828759918618289e+02,2.079457775684542264e-01,1.100000010988609489e+01,2.991995173174322870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445857264072273551e+01,5.397928759471017202e+02,2.079756974755452570e-01,1.100000010988609489e+01,2.991849187772785152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.445948173162274486e+01,5.398028759023459315e+02,2.080056159227887946e-01,1.100000010988609489e+01,2.991703202371247435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446039082252275421e+01,5.398128758575945767e+02,2.080355329101848394e-01,1.100000010988609489e+01,2.991557216969709717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446129991342276355e+01,5.398228758128475420e+02,2.080654484377334190e-01,1.100000010988609489e+01,2.991411231568171999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446220900432277290e+01,5.398328757681048273e+02,2.080953625054345058e-01,1.100000010988609489e+01,2.991265246166634282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446311809522278224e+01,5.398428757233665465e+02,2.081252751132880996e-01,1.100000010988609489e+01,2.991119260765096564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446402718612279159e+01,5.398528756786325857e+02,2.081551862612942283e-01,1.100000010988609489e+01,2.990973275363558847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446493627702280094e+01,5.398628756339030588e+02,2.081850959494528641e-01,1.100000010988609489e+01,2.990827289962021129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446584536792281028e+01,5.398728755891778519e+02,2.082150041777640070e-01,1.100000010988609489e+01,2.990681304560483412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446675445882281963e+01,5.398828755444569651e+02,2.082449109462276848e-01,1.100000010988609489e+01,2.990535319158945694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446766354972282898e+01,5.398928754997405122e+02,2.082748162548438697e-01,1.100000010988609489e+01,2.990389333757407977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446857264062283832e+01,5.399028754550283793e+02,2.083047201036125617e-01,1.100000010988609489e+01,2.990243348355870259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.446948173152284767e+01,5.399128754103206802e+02,2.083346224925337609e-01,1.100000010988609489e+01,2.990097362954332542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447039082242285701e+01,5.399228753656173012e+02,2.083645234216074671e-01,1.100000010988609489e+01,2.989951377552794824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447129991332286636e+01,5.399328753209182423e+02,2.083944228908336804e-01,1.100000010988609489e+01,2.989805392151257107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447220900422287571e+01,5.399428752762236172e+02,2.084243209002124009e-01,1.100000010988609489e+01,2.989659406749719389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447311809512288505e+01,5.399528752315333122e+02,2.084542174497436562e-01,1.100000010988609489e+01,2.989513421348181672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447402718602289440e+01,5.399628751868474410e+02,2.084841125394274186e-01,1.100000010988609489e+01,2.989367435946643954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447493627692290374e+01,5.399728751421658899e+02,2.085140061692636881e-01,1.100000010988609489e+01,2.989221450545106237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447584536782291309e+01,5.399828750974886589e+02,2.085438983392524648e-01,1.100000010988609489e+01,2.989075465143568519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447675445872292244e+01,5.399928750528158616e+02,2.085737890493937485e-01,1.100000010988609489e+01,2.988929479742030802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447766354962293178e+01,5.400028750081473845e+02,2.086036782996875394e-01,1.100000010988609489e+01,2.988783494340493084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447857264052294113e+01,5.400128749634832275e+02,2.086335660901338096e-01,1.100000010988609489e+01,2.988637508938955367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.447948173142295047e+01,5.400228749188235042e+02,2.086634524207325869e-01,1.100000010988609489e+01,2.988491523537417649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448039082232295982e+01,5.400328748741681011e+02,2.086933372914838714e-01,1.100000010988609489e+01,2.988345538135879931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448129991322296917e+01,5.400428748295171317e+02,2.087232207023876629e-01,1.100000010988609489e+01,2.988199552734342214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448220900412297851e+01,5.400528747848704825e+02,2.087531026534439615e-01,1.100000010988609489e+01,2.988053567332804496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448311809502298786e+01,5.400628747402281533e+02,2.087829831446527673e-01,1.100000010988609489e+01,2.987907581931266779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448402718592299721e+01,5.400728746955902579e+02,2.088128621760140802e-01,1.100000010988609489e+01,2.987761596529729061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448493627682300655e+01,5.400828746509566827e+02,2.088427397475278724e-01,1.100000010988609489e+01,2.987615611128191344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448584536772301590e+01,5.400928746063274275e+02,2.088726158591941717e-01,1.100000010988609489e+01,2.987469625726653626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448675445862302524e+01,5.401028745617026061e+02,2.089024905110129782e-01,1.100000010988609489e+01,2.987323640325115909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448766354952303459e+01,5.401128745170821048e+02,2.089323637029842917e-01,1.100000010988609489e+01,2.987177654923578191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448857264042304394e+01,5.401228744724660373e+02,2.089622354351080846e-01,1.100000010988609489e+01,2.987031669522040474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.448948173132305328e+01,5.401328744278542899e+02,2.089921057073843846e-01,1.100000010988609489e+01,2.986885684120502756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449039082222306263e+01,5.401428743832468626e+02,2.090219745198131640e-01,1.100000010988609489e+01,2.986739698718965039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449129991312307197e+01,5.401528743386438691e+02,2.090518418723944505e-01,1.100000010988609489e+01,2.986593713317427321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449220900402308132e+01,5.401628742940451957e+02,2.090817077651282441e-01,1.100000010988609489e+01,2.986447727915889604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449311809492309067e+01,5.401728742494508424e+02,2.091115721980145170e-01,1.100000010988609489e+01,2.986301742514351886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449402718582310001e+01,5.401828742048609229e+02,2.091414351710532971e-01,1.100000010988609489e+01,2.986155757112814169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449493627672310936e+01,5.401928741602753234e+02,2.091712966842445565e-01,1.100000010988609489e+01,2.986009771711276451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449584536762311870e+01,5.402028741156940441e+02,2.092011567375883230e-01,1.100000010988609489e+01,2.985863786309738734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449675445852312805e+01,5.402128740711171986e+02,2.092310153310845688e-01,1.100000010988609489e+01,2.985717800908201016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449766354942313740e+01,5.402228740265446731e+02,2.092608724647333218e-01,1.100000010988609489e+01,2.985571815506663299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449857264032314674e+01,5.402328739819764678e+02,2.092907281385345541e-01,1.100000010988609489e+01,2.985425830105125581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.449948173122315609e+01,5.402428739374126963e+02,2.093205823524882936e-01,1.100000010988609489e+01,2.985279844703587863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450039082212316544e+01,5.402528738928532448e+02,2.093504351065945124e-01,1.100000010988609489e+01,2.985133859302050146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450129991302317478e+01,5.402628738482981134e+02,2.093802864008532105e-01,1.100000010988609489e+01,2.984987873900512428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450220900392318413e+01,5.402728738037474159e+02,2.094101362352644158e-01,1.100000010988609489e+01,2.984841888498974711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450311809482319347e+01,5.402828737592010384e+02,2.094399846098281004e-01,1.100000010988609489e+01,2.984695903097436993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450402718572320282e+01,5.402928737146589810e+02,2.094698315245442644e-01,1.100000010988609489e+01,2.984549917695899276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450493627662321217e+01,5.403028736701213575e+02,2.094996769794129354e-01,1.100000010988609489e+01,2.984403932294361558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450584536752322151e+01,5.403128736255880540e+02,2.095295209744340859e-01,1.100000010988609489e+01,2.984257946892823841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450675445842323086e+01,5.403228735810590706e+02,2.095593635096077156e-01,1.100000010988609489e+01,2.984111961491286123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450766354932324020e+01,5.403328735365345210e+02,2.095892045849338248e-01,1.100000010988609489e+01,2.983965976089748406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450857264022324955e+01,5.403428734920142915e+02,2.096190442004124133e-01,1.100000010988609489e+01,2.983819990688210688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.450948173112325890e+01,5.403528734474983821e+02,2.096488823560435089e-01,1.100000010988609489e+01,2.983674005286672971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451039082202326824e+01,5.403628734029869065e+02,2.096787190518270838e-01,1.100000010988609489e+01,2.983528019885135253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451129991292327759e+01,5.403728733584797510e+02,2.097085542877631381e-01,1.100000010988609489e+01,2.983382034483597536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451220900382328693e+01,5.403828733139769156e+02,2.097383880638516718e-01,1.100000010988609489e+01,2.983236049082059818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451311809472329628e+01,5.403928732694785140e+02,2.097682203800926848e-01,1.100000010988609489e+01,2.983090063680522101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451402718562330563e+01,5.404028732249844325e+02,2.097980512364861772e-01,1.100000010988609489e+01,2.982944078278984383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451493627652331497e+01,5.404128731804946710e+02,2.098278806330321489e-01,1.100000010988609489e+01,2.982798092877446666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451584536742332432e+01,5.404228731360092297e+02,2.098577085697305999e-01,1.100000010988609489e+01,2.982652107475908948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451675445832333367e+01,5.404328730915282222e+02,2.098875350465815304e-01,1.100000010988609489e+01,2.982506122074371230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451766354922334301e+01,5.404428730470515347e+02,2.099173600635849402e-01,1.100000010988609489e+01,2.982360136672833513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451857264012335236e+01,5.404528730025791674e+02,2.099471836207408293e-01,1.100000010988609489e+01,2.982214151271295795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.451948173102336170e+01,5.404628729581112339e+02,2.099770057180491978e-01,1.100000010988609489e+01,2.982068165869758078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452039082192337105e+01,5.404728729136476204e+02,2.100068263555100456e-01,1.100000010988609489e+01,2.981922180468220360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452129991282338040e+01,5.404828728691883271e+02,2.100366455331233451e-01,1.100000010988609489e+01,2.981776195066682643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452220900372338974e+01,5.404928728247334675e+02,2.100664632508891239e-01,1.100000010988609489e+01,2.981630209665144925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452311809462339909e+01,5.405028727802829280e+02,2.100962795088073820e-01,1.100000010988609489e+01,2.981484224263607208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452402718552340843e+01,5.405128727358367087e+02,2.101260943068781195e-01,1.100000010988609489e+01,2.981338238862069490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452493627642341778e+01,5.405228726913948094e+02,2.101559076451013364e-01,1.100000010988609489e+01,2.981192253460531773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452584536732342713e+01,5.405328726469573439e+02,2.101857195234770048e-01,1.100000010988609489e+01,2.981046268058994055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452675445822343647e+01,5.405428726025241986e+02,2.102155299420051526e-01,1.100000010988609489e+01,2.980900282657456338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452766354912344582e+01,5.405528725580953733e+02,2.102453389006857798e-01,1.100000010988609489e+01,2.980754297255918620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452857264002345516e+01,5.405628725136709818e+02,2.102751463995188586e-01,1.100000010988609489e+01,2.980608311854380903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.452948173092346451e+01,5.405728724692509104e+02,2.103049524385044167e-01,1.100000010988609489e+01,2.980462326452843185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453039082182347386e+01,5.405828724248351591e+02,2.103347570176424541e-01,1.100000010988609489e+01,2.980316341051305468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453129991272348320e+01,5.405928723804237279e+02,2.103645601369329432e-01,1.100000010988609489e+01,2.980170355649767750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453220900362349255e+01,5.406028723360167305e+02,2.103943617963759116e-01,1.100000010988609489e+01,2.980024370248230033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453311809452350190e+01,5.406128722916140532e+02,2.104241619959713316e-01,1.100000010988609489e+01,2.979878384846692315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453402718542351124e+01,5.406228722472156960e+02,2.104539607357192310e-01,1.100000010988609489e+01,2.979732399445154598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453493627632352059e+01,5.406328722028216589e+02,2.104837580156196097e-01,1.100000010988609489e+01,2.979586414043616880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453584536722352993e+01,5.406428721584320556e+02,2.105135538356724401e-01,1.100000010988609489e+01,2.979440428642079162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453675445812353928e+01,5.406528721140467724e+02,2.105433481958777220e-01,1.100000010988609489e+01,2.979294443240541445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453766354902354863e+01,5.406628720696658092e+02,2.105731410962354833e-01,1.100000010988609489e+01,2.979148457839003727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453857263992355797e+01,5.406728720252891662e+02,2.106029325367456961e-01,1.100000010988609489e+01,2.979002472437466010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.453948173082356732e+01,5.406828719809169570e+02,2.106327225174083884e-01,1.100000010988609489e+01,2.978856487035928292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454039082172357666e+01,5.406928719365490679e+02,2.106625110382235322e-01,1.100000010988609489e+01,2.978710501634390575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454129991262358601e+01,5.407028718921854988e+02,2.106922980991911276e-01,1.100000010988609489e+01,2.978564516232852857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454220900352359536e+01,5.407128718478262499e+02,2.107220837003112024e-01,1.100000010988609489e+01,2.978418530831315140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454311809442360470e+01,5.407228718034714348e+02,2.107518678415837288e-01,1.100000010988609489e+01,2.978272545429777422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454402718532361405e+01,5.407328717591209397e+02,2.107816505230087067e-01,1.100000010988609489e+01,2.978126560028239705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454493627622362339e+01,5.407428717147747648e+02,2.108114317445861641e-01,1.100000010988609489e+01,2.977980574626701987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454584536712363274e+01,5.407528716704329099e+02,2.108412115063160730e-01,1.100000010988609489e+01,2.977834589225164270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454675445802364209e+01,5.407628716260954889e+02,2.108709898081984335e-01,1.100000010988609489e+01,2.977688603823626552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454766354892365143e+01,5.407728715817623879e+02,2.109007666502332456e-01,1.100000010988609489e+01,2.977542618422088835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454857263982366078e+01,5.407828715374336070e+02,2.109305420324205094e-01,1.100000010988609489e+01,2.977396633020551117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.454948173072367013e+01,5.407928714931091463e+02,2.109603159547602524e-01,1.100000010988609489e+01,2.977250647619013400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455039082162367947e+01,5.408028714487891193e+02,2.109900884172524471e-01,1.100000010988609489e+01,2.977104662217475682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455129991252368882e+01,5.408128714044734124e+02,2.110198594198970934e-01,1.100000010988609489e+01,2.976958676815937965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455220900342369816e+01,5.408228713601620257e+02,2.110496289626941913e-01,1.100000010988609489e+01,2.976812691414400247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455311809432370751e+01,5.408328713158549590e+02,2.110793970456437407e-01,1.100000010988609489e+01,2.976666706012862530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455402718522371686e+01,5.408428712715522124e+02,2.111091636687457418e-01,1.100000010988609489e+01,2.976520720611324812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455493627612372620e+01,5.408528712272538996e+02,2.111389288320001945e-01,1.100000010988609489e+01,2.976374735209787094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455584536702373555e+01,5.408628711829599069e+02,2.111686925354070987e-01,1.100000010988609489e+01,2.976228749808249377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455675445792374489e+01,5.408728711386702344e+02,2.111984547789664546e-01,1.100000010988609489e+01,2.976082764406711659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455766354882375424e+01,5.408828710943848819e+02,2.112282155626782620e-01,1.100000010988609489e+01,2.975936779005173942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455857263972376359e+01,5.408928710501039632e+02,2.112579748865425211e-01,1.100000010988609489e+01,2.975790793603636224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.455948173062377293e+01,5.409028710058273646e+02,2.112877327505592318e-01,1.100000010988609489e+01,2.975644808202098507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456039082152378228e+01,5.409128709615550861e+02,2.113174891547283940e-01,1.100000010988609489e+01,2.975498822800560789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456129991242379162e+01,5.409228709172871277e+02,2.113472440990499801e-01,1.100000010988609489e+01,2.975352837399023072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456220900332380097e+01,5.409328708730234894e+02,2.113769975835240178e-01,1.100000010988609489e+01,2.975206851997485354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456311809422381032e+01,5.409428708287642849e+02,2.114067496081505071e-01,1.100000010988609489e+01,2.975060866595947637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456402718512381966e+01,5.409528707845094004e+02,2.114365001729294480e-01,1.100000010988609489e+01,2.974914881194409919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456493627602382901e+01,5.409628707402588361e+02,2.114662492778608405e-01,1.100000010988609489e+01,2.974768895792872202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456584536692383836e+01,5.409728706960125919e+02,2.114959969229446568e-01,1.100000010988609489e+01,2.974622910391334484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456675445782384770e+01,5.409828706517706678e+02,2.115257431081809247e-01,1.100000010988609489e+01,2.974476924989796767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456766354872385705e+01,5.409928706075331775e+02,2.115554878335696443e-01,1.100000010988609489e+01,2.974330939588259049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456857263962386639e+01,5.410028705633000072e+02,2.115852310991107876e-01,1.100000010988609489e+01,2.974184954186721332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.456948173052387574e+01,5.410128705190711571e+02,2.116149729048043826e-01,1.100000010988609489e+01,2.974038968785183614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457039082142388509e+01,5.410228704748466271e+02,2.116447132506504292e-01,1.100000010988609489e+01,2.973892983383645897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457129991232389443e+01,5.410328704306264171e+02,2.116744521366488996e-01,1.100000010988609489e+01,2.973746997982108179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457220900322390378e+01,5.410428703864106410e+02,2.117041895627998216e-01,1.100000010988609489e+01,2.973601012580570462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457311809412391312e+01,5.410528703421991850e+02,2.117339255291031674e-01,1.100000010988609489e+01,2.973455027179032744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457402718502392247e+01,5.410628702979920490e+02,2.117636600355589649e-01,1.100000010988609489e+01,2.973309041777495026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457493627592393182e+01,5.410728702537892332e+02,2.117933930821671862e-01,1.100000010988609489e+01,2.973163056375957309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457584536682394116e+01,5.410828702095907374e+02,2.118231246689278591e-01,1.100000010988609489e+01,2.973017070974419591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457675445772395051e+01,5.410928701653965618e+02,2.118528547958409558e-01,1.100000010988609489e+01,2.972871085572881874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457766354862395985e+01,5.411028701212068199e+02,2.118825834629065041e-01,1.100000010988609489e+01,2.972725100171344156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457857263952396920e+01,5.411128700770213982e+02,2.119123106701244763e-01,1.100000010988609489e+01,2.972579114769806439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.457948173042397855e+01,5.411228700328402965e+02,2.119420364174949001e-01,1.100000010988609489e+01,2.972433129368268721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458039082132398789e+01,5.411328699886635150e+02,2.119717607050177477e-01,1.100000010988609489e+01,2.972287143966731004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458129991222399724e+01,5.411428699444910535e+02,2.120014835326930192e-01,1.100000010988609489e+01,2.972141158565193286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458220900312400659e+01,5.411528699003230258e+02,2.120312049005207422e-01,1.100000010988609489e+01,2.971995173163655569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458311809402401593e+01,5.411628698561593183e+02,2.120609248085008891e-01,1.100000010988609489e+01,2.971849187762117851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458402718492402528e+01,5.411728698119999308e+02,2.120906432566334598e-01,1.100000010988609489e+01,2.971703202360580134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458493627582403462e+01,5.411828697678448634e+02,2.121203602449184544e-01,1.100000010988609489e+01,2.971557216959042416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458584536672404397e+01,5.411928697236941161e+02,2.121500757733559006e-01,1.100000010988609489e+01,2.971411231557504699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458675445762405332e+01,5.412028696795476890e+02,2.121797898419457706e-01,1.100000010988609489e+01,2.971265246155966981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458766354852406266e+01,5.412128696354055819e+02,2.122095024506880645e-01,1.100000010988609489e+01,2.971119260754429264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458857263942407201e+01,5.412228695912679086e+02,2.122392135995827822e-01,1.100000010988609489e+01,2.970973275352891546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.458948173032408135e+01,5.412328695471345554e+02,2.122689232886299238e-01,1.100000010988609489e+01,2.970827289951353829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459039082122409070e+01,5.412428695030055223e+02,2.122986315178295169e-01,1.100000010988609489e+01,2.970681304549816111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459129991212410005e+01,5.412528694588808094e+02,2.123283382871815339e-01,1.100000010988609489e+01,2.970535319148278394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459220900302410939e+01,5.412628694147604165e+02,2.123580435966859747e-01,1.100000010988609489e+01,2.970389333746740676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459311809392411874e+01,5.412728693706443437e+02,2.123877474463428394e-01,1.100000010988609489e+01,2.970243348345202958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459402718482412808e+01,5.412828693265327047e+02,2.124174498361521279e-01,1.100000010988609489e+01,2.970097362943665241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459493627572413743e+01,5.412928692824253858e+02,2.124471507661138403e-01,1.100000010988609489e+01,2.969951377542127523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459584536662414678e+01,5.413028692383223870e+02,2.124768502362279765e-01,1.100000010988609489e+01,2.969805392140589806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459675445752415612e+01,5.413128691942237083e+02,2.125065482464945366e-01,1.100000010988609489e+01,2.969659406739052088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459766354842416547e+01,5.413228691501293497e+02,2.125362447969135204e-01,1.100000010988609489e+01,2.969513421337514371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459857263932417482e+01,5.413328691060393112e+02,2.125659398874849282e-01,1.100000010988609489e+01,2.969367435935976653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.459948173022418416e+01,5.413428690619535928e+02,2.125956335182087320e-01,1.100000010988609489e+01,2.969221450534438936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460039082112419351e+01,5.413528690178721945e+02,2.126253256890849597e-01,1.100000010988609489e+01,2.969075465132901218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460129991202420285e+01,5.413628689737952300e+02,2.126550164001136112e-01,1.100000010988609489e+01,2.968929479731363501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460220900292421220e+01,5.413728689297225856e+02,2.126847056512946865e-01,1.100000010988609489e+01,2.968783494329825783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460311809382422155e+01,5.413828688856542612e+02,2.127143934426281857e-01,1.100000010988609489e+01,2.968637508928288066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460402718472423089e+01,5.413928688415902570e+02,2.127440797741141087e-01,1.100000010988609489e+01,2.968491523526750348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460493627562424024e+01,5.414028687975305729e+02,2.127737646457524279e-01,1.100000010988609489e+01,2.968345538125212631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460584536652424958e+01,5.414128687534752089e+02,2.128034480575431708e-01,1.100000010988609489e+01,2.968199552723674913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460675445742425893e+01,5.414228687094241650e+02,2.128331300094863376e-01,1.100000010988609489e+01,2.968053567322137196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460766354832426828e+01,5.414328686653774412e+02,2.128628105015819005e-01,1.100000010988609489e+01,2.967907581920599478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460857263922427762e+01,5.414428686213351511e+02,2.128924895338298873e-01,1.100000010988609489e+01,2.967761596519061761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.460948173012428697e+01,5.414528685772971812e+02,2.129221671062302979e-01,1.100000010988609489e+01,2.967615611117524043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461039082102429632e+01,5.414628685332635314e+02,2.129518432187831045e-01,1.100000010988609489e+01,2.967469625715986326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461129991192430566e+01,5.414728684892342017e+02,2.129815178714883350e-01,1.100000010988609489e+01,2.967323640314448608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461220900282431501e+01,5.414828684452091920e+02,2.130111910643459894e-01,1.100000010988609489e+01,2.967177654912910890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461311809372432435e+01,5.414928684011885025e+02,2.130408627973560398e-01,1.100000010988609489e+01,2.967031669511373173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461402718462433370e+01,5.415028683571721331e+02,2.130705330705185141e-01,1.100000010988609489e+01,2.966885684109835455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461493627552434305e+01,5.415128683131600837e+02,2.131002018838333845e-01,1.100000010988609489e+01,2.966739698708297738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461584536642435239e+01,5.415228682691523545e+02,2.131298692373006787e-01,1.100000010988609489e+01,2.966593713306760020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461675445732436174e+01,5.415328682251489454e+02,2.131595351309203690e-01,1.100000010988609489e+01,2.966447727905222303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461766354822437108e+01,5.415428681811499700e+02,2.131891995646924554e-01,1.100000010988609489e+01,2.966301742503684585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461857263912438043e+01,5.415528681371553148e+02,2.132188625386169656e-01,1.100000010988609489e+01,2.966155757102146868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.461948173002438978e+01,5.415628680931649797e+02,2.132485240526938719e-01,1.100000010988609489e+01,2.966009771700609150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462039082092439912e+01,5.415728680491789646e+02,2.132781841069232021e-01,1.100000010988609489e+01,2.965863786299071433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462129991182440847e+01,5.415828680051972697e+02,2.133078427013049283e-01,1.100000010988609489e+01,2.965717800897533715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462220900272441781e+01,5.415928679612198948e+02,2.133374998358390506e-01,1.100000010988609489e+01,2.965571815495995998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462311809362442716e+01,5.416028679172468401e+02,2.133671555105255968e-01,1.100000010988609489e+01,2.965425830094458280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462402718452443651e+01,5.416128678732781054e+02,2.133968097253645391e-01,1.100000010988609489e+01,2.965279844692920563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462493627542444585e+01,5.416228678293136909e+02,2.134264624803558774e-01,1.100000010988609489e+01,2.965133859291382845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462584536632445520e+01,5.416328677853535964e+02,2.134561137754996119e-01,1.100000010988609489e+01,2.964987873889845128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462675445722446455e+01,5.416428677413978221e+02,2.134857636107957701e-01,1.100000010988609489e+01,2.964841888488307410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462766354812447389e+01,5.416528676974463679e+02,2.135154119862443245e-01,1.100000010988609489e+01,2.964695903086769693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462857263902448324e+01,5.416628676534993474e+02,2.135450589018452749e-01,1.100000010988609489e+01,2.964549917685231975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.462948172992449258e+01,5.416728676095566470e+02,2.135747043575986215e-01,1.100000010988609489e+01,2.964403932283694258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463039082082450193e+01,5.416828675656182668e+02,2.136043483535043641e-01,1.100000010988609489e+01,2.964257946882156540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463129991172451128e+01,5.416928675216842066e+02,2.136339908895625028e-01,1.100000010988609489e+01,2.964111961480618822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463220900262452062e+01,5.417028674777544666e+02,2.136636319657730376e-01,1.100000010988609489e+01,2.963965976079081105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463311809352452997e+01,5.417128674338290466e+02,2.136932715821359685e-01,1.100000010988609489e+01,2.963819990677543387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463402718442453931e+01,5.417228673899079467e+02,2.137229097386512955e-01,1.100000010988609489e+01,2.963674005276005670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463493627532454866e+01,5.417328673459911670e+02,2.137525464353190185e-01,1.100000010988609489e+01,2.963528019874467952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463584536622455801e+01,5.417428673020787073e+02,2.137821816721391377e-01,1.100000010988609489e+01,2.963382034472930235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463675445712456735e+01,5.417528672581705678e+02,2.138118154491116529e-01,1.100000010988609489e+01,2.963236049071392517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463766354802457670e+01,5.417628672142667483e+02,2.138414477662365643e-01,1.100000010988609489e+01,2.963090063669854800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463857263892458604e+01,5.417728671703672489e+02,2.138710786235138717e-01,1.100000010988609489e+01,2.962944078268317082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.463948172982459539e+01,5.417828671264720697e+02,2.139007080209435752e-01,1.100000010988609489e+01,2.962798092866779365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464039082072460474e+01,5.417928670825812105e+02,2.139303359585256747e-01,1.100000010988609489e+01,2.962652107465241647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464129991162461408e+01,5.418028670386946715e+02,2.139599624362601704e-01,1.100000010988609489e+01,2.962506122063703930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464220900252462343e+01,5.418128669948124525e+02,2.139895874541470622e-01,1.100000010988609489e+01,2.962360136662166212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464311809342463278e+01,5.418228669509345536e+02,2.140192110121863223e-01,1.100000010988609489e+01,2.962214151260628495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464402718432464212e+01,5.418328669070609749e+02,2.140488331103779784e-01,1.100000010988609489e+01,2.962068165859090777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464493627522465147e+01,5.418428668631917162e+02,2.140784537487220307e-01,1.100000010988609489e+01,2.961922180457553060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464584536612466081e+01,5.418528668193267777e+02,2.141080729272184791e-01,1.100000010988609489e+01,2.961776195056015342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464675445702467016e+01,5.418628667754662729e+02,2.141376906458672957e-01,1.100000010988609489e+01,2.961630209654477625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464766354792467951e+01,5.418728667316100882e+02,2.141673069046685085e-01,1.100000010988609489e+01,2.961484224252939907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464857263882468885e+01,5.418828666877582236e+02,2.141969217036221174e-01,1.100000010988609489e+01,2.961338238851402190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.464948172972469820e+01,5.418928666439106792e+02,2.142265350427280945e-01,1.100000010988609489e+01,2.961192253449864472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465039082062470754e+01,5.419028666000674548e+02,2.142561469219864678e-01,1.100000010988609489e+01,2.961046268048326754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465129991152471689e+01,5.419128665562285505e+02,2.142857573413972372e-01,1.100000010988609489e+01,2.960900282646789037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465220900242472624e+01,5.419228665123939663e+02,2.143153663009603749e-01,1.100000010988609489e+01,2.960754297245251319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465311809332473558e+01,5.419328664685637023e+02,2.143449738006759087e-01,1.100000010988609489e+01,2.960608311843713602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465402718422474493e+01,5.419428664247377583e+02,2.143745798405438108e-01,1.100000010988609489e+01,2.960462326442175884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465493627512475427e+01,5.419528663809161344e+02,2.144041844205641090e-01,1.100000010988609489e+01,2.960316341040638167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465584536602476362e+01,5.419628663370988306e+02,2.144337875407367755e-01,1.100000010988609489e+01,2.960170355639100449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465675445692477297e+01,5.419728662932858470e+02,2.144633892010618381e-01,1.100000010988609489e+01,2.960024370237562732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465766354782478231e+01,5.419828662494771834e+02,2.144929894015392691e-01,1.100000010988609489e+01,2.959878384836025014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465857263872479166e+01,5.419928662056728399e+02,2.145225881421690961e-01,1.100000010988609489e+01,2.959732399434487297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.465948172962480101e+01,5.420028661618728165e+02,2.145521854229512915e-01,1.100000010988609489e+01,2.959586414032949579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466039082052481035e+01,5.420128661180771132e+02,2.145817812438858552e-01,1.100000010988609489e+01,2.959440428631411862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466129991142481970e+01,5.420228660742857301e+02,2.146113756049728150e-01,1.100000010988609489e+01,2.959294443229874144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466220900232482904e+01,5.420328660304986670e+02,2.146409685062121431e-01,1.100000010988609489e+01,2.959148457828336427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466311809322483839e+01,5.420428659867159240e+02,2.146705599476038395e-01,1.100000010988609489e+01,2.959002472426798709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466402718412484774e+01,5.420528659429375011e+02,2.147001499291479043e-01,1.100000010988609489e+01,2.958856487025260992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466493627502485708e+01,5.420628658991633984e+02,2.147297384508443652e-01,1.100000010988609489e+01,2.958710501623723274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466584536592486643e+01,5.420728658553936157e+02,2.147593255126931944e-01,1.100000010988609489e+01,2.958564516222185557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466675445682487577e+01,5.420828658116281531e+02,2.147889111146943919e-01,1.100000010988609489e+01,2.958418530820647839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466766354772488512e+01,5.420928657678670106e+02,2.148184952568479578e-01,1.100000010988609489e+01,2.958272545419110122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466857263862489447e+01,5.421028657241101882e+02,2.148480779391539197e-01,1.100000010988609489e+01,2.958126560017572404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.466948172952490381e+01,5.421128656803576860e+02,2.148776591616122500e-01,1.100000010988609489e+01,2.957980574616034686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467039082042491316e+01,5.421228656366095038e+02,2.149072389242229486e-01,1.100000010988609489e+01,2.957834589214496969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467129991132492250e+01,5.421328655928656417e+02,2.149368172269860155e-01,1.100000010988609489e+01,2.957688603812959251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467220900222493185e+01,5.421428655491260997e+02,2.149663940699014508e-01,1.100000010988609489e+01,2.957542618411421534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467311809312494120e+01,5.421528655053908778e+02,2.149959694529692544e-01,1.100000010988609489e+01,2.957396633009883816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467402718402495054e+01,5.421628654616599761e+02,2.150255433761894264e-01,1.100000010988609489e+01,2.957250647608346099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467493627492495989e+01,5.421728654179333944e+02,2.150551158395619666e-01,1.100000010988609489e+01,2.957104662206808381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467584536582496924e+01,5.421828653742111328e+02,2.150846868430868752e-01,1.100000010988609489e+01,2.956958676805270664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467675445672497858e+01,5.421928653304931913e+02,2.151142563867641522e-01,1.100000010988609489e+01,2.956812691403732946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467766354762498793e+01,5.422028652867795699e+02,2.151438244705937974e-01,1.100000010988609489e+01,2.956666706002195229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467857263852499727e+01,5.422128652430701550e+02,2.151733910945758110e-01,1.100000010988609489e+01,2.956520720600657511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.467948172942500662e+01,5.422228651993650601e+02,2.152029562587101930e-01,1.100000010988609489e+01,2.956374735199119794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468039082032501597e+01,5.422328651556642853e+02,2.152325199629969432e-01,1.100000010988609489e+01,2.956228749797582076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468129991122502531e+01,5.422428651119678307e+02,2.152620822074360341e-01,1.100000010988609489e+01,2.956082764396044359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468220900212503466e+01,5.422528650682756961e+02,2.152916429920274932e-01,1.100000010988609489e+01,2.955936778994506641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468311809302504400e+01,5.422628650245878816e+02,2.153212023167713207e-01,1.100000010988609489e+01,2.955790793592968924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468402718392505335e+01,5.422728649809043873e+02,2.153507601816675165e-01,1.100000010988609489e+01,2.955644808191431206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468493627482506270e+01,5.422828649372252130e+02,2.153803165867160807e-01,1.100000010988609489e+01,2.955498822789893489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468584536572507204e+01,5.422928648935503588e+02,2.154098715319169854e-01,1.100000010988609489e+01,2.955352837388355771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468675445662508139e+01,5.423028648498798248e+02,2.154394250172702585e-01,1.100000010988609489e+01,2.955206851986818054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468766354752509073e+01,5.423128648062136108e+02,2.154689770427758999e-01,1.100000010988609489e+01,2.955060866585280336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468857263842510008e+01,5.423228647625517169e+02,2.154985276084338819e-01,1.100000010988609489e+01,2.954914881183742618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.468948172932510943e+01,5.423328647188941432e+02,2.155280767142442322e-01,1.100000010988609489e+01,2.954768895782204901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469039082022511877e+01,5.423428646752408895e+02,2.155576243602069508e-01,1.100000010988609489e+01,2.954622910380667183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469129991112512812e+01,5.423528646315919559e+02,2.155871705463220100e-01,1.100000010988609489e+01,2.954476924979129466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469220900202513747e+01,5.423628645879473424e+02,2.156167152725894376e-01,1.100000010988609489e+01,2.954330939577591748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469311809292514681e+01,5.423728645443070491e+02,2.156462585390092057e-01,1.100000010988609489e+01,2.954184954176054031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469402718382515616e+01,5.423828645006710758e+02,2.156758003455813422e-01,1.100000010988609489e+01,2.954038968774516313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469493627472516550e+01,5.423928644570394226e+02,2.157053406923058192e-01,1.100000010988609489e+01,2.953892983372978596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469584536562517485e+01,5.424028644134120896e+02,2.157348795791826646e-01,1.100000010988609489e+01,2.953746997971440878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469675445652518420e+01,5.424128643697889629e+02,2.157644170062118505e-01,1.100000010988609489e+01,2.953601012569903161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469766354742519354e+01,5.424228643261701563e+02,2.157939529733934048e-01,1.100000010988609489e+01,2.953455027168365443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469857263832520289e+01,5.424328642825556699e+02,2.158234874807272996e-01,1.100000010988609489e+01,2.953309041766827726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.469948172922521223e+01,5.424428642389455035e+02,2.158530205282135350e-01,1.100000010988609489e+01,2.953163056365290008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470039082012522158e+01,5.424528641953396573e+02,2.158825521158521388e-01,1.100000010988609489e+01,2.953017070963752291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470129991102523093e+01,5.424628641517381311e+02,2.159120822436430831e-01,1.100000010988609489e+01,2.952871085562214573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470220900192524027e+01,5.424728641081409251e+02,2.159416109115863958e-01,1.100000010988609489e+01,2.952725100160676856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470311809282524962e+01,5.424828640645480391e+02,2.159711381196820490e-01,1.100000010988609489e+01,2.952579114759139138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470402718372525896e+01,5.424928640209594732e+02,2.160006638679300428e-01,1.100000010988609489e+01,2.952433129357601421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470493627462526831e+01,5.425028639773752275e+02,2.160301881563303772e-01,1.100000010988609489e+01,2.952287143956063703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470584536552527766e+01,5.425128639337953018e+02,2.160597109848830799e-01,1.100000010988609489e+01,2.952141158554525985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470675445642528700e+01,5.425228638902196963e+02,2.160892323535881232e-01,1.100000010988609489e+01,2.951995173152988268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470766354732529635e+01,5.425328638466482971e+02,2.161187522624455071e-01,1.100000010988609489e+01,2.951849187751450550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470857263822530570e+01,5.425428638030812181e+02,2.161482707114552315e-01,1.100000010988609489e+01,2.951703202349912833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.470948172912531504e+01,5.425528637595184591e+02,2.161777877006172965e-01,1.100000010988609489e+01,2.951557216948375115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471039082002532439e+01,5.425628637159600203e+02,2.162073032299317021e-01,1.100000010988609489e+01,2.951411231546837398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471129991092533373e+01,5.425728636724059015e+02,2.162368172993984483e-01,1.100000010988609489e+01,2.951265246145299680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471220900182534308e+01,5.425828636288561029e+02,2.162663299090175628e-01,1.100000010988609489e+01,2.951119260743761963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471311809272535243e+01,5.425928635853106243e+02,2.162958410587890179e-01,1.100000010988609489e+01,2.950973275342224245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471402718362536177e+01,5.426028635417694659e+02,2.163253507487128136e-01,1.100000010988609489e+01,2.950827289940686528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471493627452537112e+01,5.426128634982326275e+02,2.163548589787889498e-01,1.100000010988609489e+01,2.950681304539148810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471584536542538046e+01,5.426228634547001093e+02,2.163843657490174266e-01,1.100000010988609489e+01,2.950535319137611093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471675445632538981e+01,5.426328634111717975e+02,2.164138710593982440e-01,1.100000010988609489e+01,2.950389333736073375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471766354722539916e+01,5.426428633676478057e+02,2.164433749099314019e-01,1.100000010988609489e+01,2.950243348334535658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471857263812540850e+01,5.426528633241281341e+02,2.164728773006168727e-01,1.100000010988609489e+01,2.950097362932997940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.471948172902541785e+01,5.426628632806127825e+02,2.165023782314546841e-01,1.100000010988609489e+01,2.949951377531460223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472039081992542719e+01,5.426728632371017511e+02,2.165318777024448360e-01,1.100000010988609489e+01,2.949805392129922505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472129991082543654e+01,5.426828631935950398e+02,2.165613757135873285e-01,1.100000010988609489e+01,2.949659406728384788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472220900172544589e+01,5.426928631500926485e+02,2.165908722648821616e-01,1.100000010988609489e+01,2.949513421326847070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472311809262545523e+01,5.427028631065945774e+02,2.166203673563293353e-01,1.100000010988609489e+01,2.949367435925309353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472402718352546458e+01,5.427128630631007127e+02,2.166498609879288217e-01,1.100000010988609489e+01,2.949221450523771635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472493627442547393e+01,5.427228630196111681e+02,2.166793531596806488e-01,1.100000010988609489e+01,2.949075465122233917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472584536532548327e+01,5.427328629761259435e+02,2.167088438715848164e-01,1.100000010988609489e+01,2.948929479720696200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472675445622549262e+01,5.427428629326450391e+02,2.167383331236413246e-01,1.100000010988609489e+01,2.948783494319158482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472766354712550196e+01,5.427528628891684548e+02,2.167678209158501457e-01,1.100000010988609489e+01,2.948637508917620765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472857263802551131e+01,5.427628628456961906e+02,2.167973072482113073e-01,1.100000010988609489e+01,2.948491523516083047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.472948172892552066e+01,5.427728628022282464e+02,2.168267921207248095e-01,1.100000010988609489e+01,2.948345538114545330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473039081982553000e+01,5.427828627587646224e+02,2.168562755333906245e-01,1.100000010988609489e+01,2.948199552713007612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473129991072553935e+01,5.427928627153052048e+02,2.168857574862087800e-01,1.100000010988609489e+01,2.948053567311469895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473220900162554869e+01,5.428028626718501073e+02,2.169152379791792484e-01,1.100000010988609489e+01,2.947907581909932177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473311809252555804e+01,5.428128626283993299e+02,2.169447170123020574e-01,1.100000010988609489e+01,2.947761596508394460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473402718342556739e+01,5.428228625849528726e+02,2.169741945855771792e-01,1.100000010988609489e+01,2.947615611106856742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473493627432557673e+01,5.428328625415107354e+02,2.170036706990046416e-01,1.100000010988609489e+01,2.947469625705319025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473584536522558608e+01,5.428428624980729182e+02,2.170331453525844168e-01,1.100000010988609489e+01,2.947323640303781307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473675445612559542e+01,5.428528624546394212e+02,2.170626185463165325e-01,1.100000010988609489e+01,2.947177654902243590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473766354702560477e+01,5.428628624112101306e+02,2.170920902802009611e-01,1.100000010988609489e+01,2.947031669500705872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473857263792561412e+01,5.428728623677851601e+02,2.171215605542377303e-01,1.100000010988609489e+01,2.946885684099168155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.473948172882562346e+01,5.428828623243645097e+02,2.171510293684268122e-01,1.100000010988609489e+01,2.946739698697630437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474039081972563281e+01,5.428928622809481794e+02,2.171804967227682348e-01,1.100000010988609489e+01,2.946593713296092720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474129991062564216e+01,5.429028622375361692e+02,2.172099626172619702e-01,1.100000010988609489e+01,2.946447727894555002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474220900152565150e+01,5.429128621941284791e+02,2.172394270519080184e-01,1.100000010988609489e+01,2.946301742493017285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474311809242566085e+01,5.429228621507249954e+02,2.172688900267064072e-01,1.100000010988609489e+01,2.946155757091479567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474402718332567019e+01,5.429328621073258319e+02,2.172983515416571088e-01,1.100000010988609489e+01,2.946009771689941849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474493627422567954e+01,5.429428620639309884e+02,2.173278115967601232e-01,1.100000010988609489e+01,2.945863786288404132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474584536512568889e+01,5.429528620205404650e+02,2.173572701920154504e-01,1.100000010988609489e+01,2.945717800886866414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474675445602569823e+01,5.429628619771542617e+02,2.173867273274231182e-01,1.100000010988609489e+01,2.945571815485328697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474766354692570758e+01,5.429728619337723785e+02,2.174161830029830988e-01,1.100000010988609489e+01,2.945425830083790979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474857263782571692e+01,5.429828618903947017e+02,2.174456372186953923e-01,1.100000010988609489e+01,2.945279844682253262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.474948172872572627e+01,5.429928618470213451e+02,2.174750899745599986e-01,1.100000010988609489e+01,2.945133859280715544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475039081962573562e+01,5.430028618036523085e+02,2.175045412705769177e-01,1.100000010988609489e+01,2.944987873879177827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475129991052574496e+01,5.430128617602875920e+02,2.175339911067461496e-01,1.100000010988609489e+01,2.944841888477640109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475220900142575431e+01,5.430228617169271956e+02,2.175634394830676943e-01,1.100000010988609489e+01,2.944695903076102392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475311809232576366e+01,5.430328616735710057e+02,2.175928863995415519e-01,1.100000010988609489e+01,2.944549917674564674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475402718322577300e+01,5.430428616302191358e+02,2.176223318561677222e-01,1.100000010988609489e+01,2.944403932273026957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475493627412578235e+01,5.430528615868715860e+02,2.176517758529462054e-01,1.100000010988609489e+01,2.944257946871489239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475584536502579169e+01,5.430628615435283564e+02,2.176812183898770015e-01,1.100000010988609489e+01,2.944111961469951522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475675445592580104e+01,5.430728615001894468e+02,2.177106594669601103e-01,1.100000010988609489e+01,2.943965976068413804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475766354682581039e+01,5.430828614568547437e+02,2.177400990841955319e-01,1.100000010988609489e+01,2.943819990666876087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475857263772581973e+01,5.430928614135243606e+02,2.177695372415832664e-01,1.100000010988609489e+01,2.943674005265338369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.475948172862582908e+01,5.431028613701982977e+02,2.177989739391233137e-01,1.100000010988609489e+01,2.943528019863800652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476039081952583842e+01,5.431128613268765548e+02,2.178284091768156738e-01,1.100000010988609489e+01,2.943382034462262934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476129991042584777e+01,5.431228612835591321e+02,2.178578429546603468e-01,1.100000010988609489e+01,2.943236049060725217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476220900132585712e+01,5.431328612402459157e+02,2.178872752726573325e-01,1.100000010988609489e+01,2.943090063659187499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476311809222586646e+01,5.431428611969370195e+02,2.179167061308066033e-01,1.100000010988609489e+01,2.942944078257649781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476402718312587581e+01,5.431528611536324433e+02,2.179461355291081870e-01,1.100000010988609489e+01,2.942798092856112064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476493627402588515e+01,5.431628611103321873e+02,2.179755634675620835e-01,1.100000010988609489e+01,2.942652107454574346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476584536492589450e+01,5.431728610670362514e+02,2.180049899461682927e-01,1.100000010988609489e+01,2.942506122053036629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476675445582590385e+01,5.431828610237445218e+02,2.180344149649267871e-01,1.100000010988609489e+01,2.942360136651498911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476766354672591319e+01,5.431928609804571124e+02,2.180638385238375943e-01,1.100000010988609489e+01,2.942214151249961194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476857263762592254e+01,5.432028609371740231e+02,2.180932606229007142e-01,1.100000010988609489e+01,2.942068165848423476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.476948172852593189e+01,5.432128608938952539e+02,2.181226812621161193e-01,1.100000010988609489e+01,2.941922180446885759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477039081942594123e+01,5.432228608506208047e+02,2.181521004414838372e-01,1.100000010988609489e+01,2.941776195045348041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477129991032595058e+01,5.432328608073505620e+02,2.181815181610038679e-01,1.100000010988609489e+01,2.941630209643810324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477220900122595992e+01,5.432428607640846394e+02,2.182109344206761836e-01,1.100000010988609489e+01,2.941484224242272606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477311809212596927e+01,5.432528607208230369e+02,2.182403492205008122e-01,1.100000010988609489e+01,2.941338238840734889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477402718302597862e+01,5.432628606775657545e+02,2.182697625604777258e-01,1.100000010988609489e+01,2.941192253439197171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477493627392598796e+01,5.432728606343126785e+02,2.182991744406069523e-01,1.100000010988609489e+01,2.941046268037659454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477584536482599731e+01,5.432828605910639226e+02,2.183285848608884638e-01,1.100000010988609489e+01,2.940900282636121736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477675445572600665e+01,5.432928605478194868e+02,2.183579938213222882e-01,1.100000010988609489e+01,2.940754297234584019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477766354662601600e+01,5.433028605045793711e+02,2.183874013219083976e-01,1.100000010988609489e+01,2.940608311833046301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477857263752602535e+01,5.433128604613434618e+02,2.184168073626468198e-01,1.100000010988609489e+01,2.940462326431508584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.477948172842603469e+01,5.433228604181118726e+02,2.184462119435375271e-01,1.100000010988609489e+01,2.940316341029970866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478039081932604404e+01,5.433328603748846035e+02,2.184756150645805195e-01,1.100000010988609489e+01,2.940170355628433149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478129991022605338e+01,5.433428603316616545e+02,2.185050167257758247e-01,1.100000010988609489e+01,2.940024370226895431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478220900112606273e+01,5.433528602884430256e+02,2.185344169271234149e-01,1.100000010988609489e+01,2.939878384825357713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478311809202607208e+01,5.433628602452286032e+02,2.185638156686232902e-01,1.100000010988609489e+01,2.939732399423819996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478402718292608142e+01,5.433728602020185008e+02,2.185932129502754784e-01,1.100000010988609489e+01,2.939586414022282278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478493627382609077e+01,5.433828601588127185e+02,2.186226087720799516e-01,1.100000010988609489e+01,2.939440428620744561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478584536472610012e+01,5.433928601156111426e+02,2.186520031340367098e-01,1.100000010988609489e+01,2.939294443219206843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478675445562610946e+01,5.434028600724138869e+02,2.186813960361457532e-01,1.100000010988609489e+01,2.939148457817669126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478766354652611881e+01,5.434128600292209512e+02,2.187107874784071093e-01,1.100000010988609489e+01,2.939002472416131408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478857263742612815e+01,5.434228599860323357e+02,2.187401774608207505e-01,1.100000010988609489e+01,2.938856487014593691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.478948172832613750e+01,5.434328599428479265e+02,2.187695659833866768e-01,1.100000010988609489e+01,2.938710501613055973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479039081922614685e+01,5.434428598996678375e+02,2.187989530461048882e-01,1.100000010988609489e+01,2.938564516211518256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479129991012615619e+01,5.434528598564920685e+02,2.188283386489753846e-01,1.100000010988609489e+01,2.938418530809980538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479220900102616554e+01,5.434628598133206197e+02,2.188577227919981660e-01,1.100000010988609489e+01,2.938272545408442821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479311809192617488e+01,5.434728597701533772e+02,2.188871054751732326e-01,1.100000010988609489e+01,2.938126560006905103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479402718282618423e+01,5.434828597269904549e+02,2.189164866985005842e-01,1.100000010988609489e+01,2.937980574605367386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479493627372619358e+01,5.434928596838318526e+02,2.189458664619802208e-01,1.100000010988609489e+01,2.937834589203829668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479584536462620292e+01,5.435028596406775705e+02,2.189752447656121426e-01,1.100000010988609489e+01,2.937688603802291951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479675445552621227e+01,5.435128595975274948e+02,2.190046216093963494e-01,1.100000010988609489e+01,2.937542618400754233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479766354642622161e+01,5.435228595543817391e+02,2.190339969933328412e-01,1.100000010988609489e+01,2.937396632999216516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479857263732623096e+01,5.435328595112403036e+02,2.190633709174216182e-01,1.100000010988609489e+01,2.937250647597678798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.479948172822624031e+01,5.435428594681030745e+02,2.190927433816626801e-01,1.100000010988609489e+01,2.937104662196141081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480039081912624965e+01,5.435528594249701655e+02,2.191221143860560272e-01,1.100000010988609489e+01,2.936958676794603363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480129991002625900e+01,5.435628593818415766e+02,2.191514839306016593e-01,1.100000010988609489e+01,2.936812691393065645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480220900092626835e+01,5.435728593387173078e+02,2.191808520152995765e-01,1.100000010988609489e+01,2.936666705991527928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480311809182627769e+01,5.435828592955972454e+02,2.192102186401497788e-01,1.100000010988609489e+01,2.936520720589990210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480402718272628704e+01,5.435928592524815031e+02,2.192395838051522383e-01,1.100000010988609489e+01,2.936374735188452493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480493627362629638e+01,5.436028592093700809e+02,2.192689475103069829e-01,1.100000010988609489e+01,2.936228749786914775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480584536452630573e+01,5.436128591662628651e+02,2.192983097556140126e-01,1.100000010988609489e+01,2.936082764385377058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480675445542631508e+01,5.436228591231599694e+02,2.193276705410733274e-01,1.100000010988609489e+01,2.935936778983839340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480766354632632442e+01,5.436328590800613938e+02,2.193570298666848994e-01,1.100000010988609489e+01,2.935790793582301623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480857263722633377e+01,5.436428590369671383e+02,2.193863877324487566e-01,1.100000010988609489e+01,2.935644808180763905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.480948172812634311e+01,5.436528589938770892e+02,2.194157441383648988e-01,1.100000010988609489e+01,2.935498822779226188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481039081902635246e+01,5.436628589507913603e+02,2.194450990844332983e-01,1.100000010988609489e+01,2.935352837377688470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481129990992636181e+01,5.436728589077099514e+02,2.194744525706539828e-01,1.100000010988609489e+01,2.935206851976150753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481220900082637115e+01,5.436828588646327489e+02,2.195038045970269247e-01,1.100000010988609489e+01,2.935060866574613035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481311809172638050e+01,5.436928588215598666e+02,2.195331551635521516e-01,1.100000010988609489e+01,2.934914881173075318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481402718262638984e+01,5.437028587784913043e+02,2.195625042702296359e-01,1.100000010988609489e+01,2.934768895771537600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481493627352639919e+01,5.437128587354269484e+02,2.195918519170594052e-01,1.100000010988609489e+01,2.934622910369999883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481584536442640854e+01,5.437228586923669127e+02,2.196211981040414318e-01,1.100000010988609489e+01,2.934476924968462165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481675445532641788e+01,5.437328586493111970e+02,2.196505428311757435e-01,1.100000010988609489e+01,2.934330939566924448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481766354622642723e+01,5.437428586062596878e+02,2.196798860984623125e-01,1.100000010988609489e+01,2.934184954165386730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481857263712643658e+01,5.437528585632124987e+02,2.197092279059011666e-01,1.100000010988609489e+01,2.934038968763849013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.481948172802644592e+01,5.437628585201696296e+02,2.197385682534922779e-01,1.100000010988609489e+01,2.933892983362311295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482039081892645527e+01,5.437728584771309670e+02,2.197679071412356744e-01,1.100000010988609489e+01,2.933746997960773577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482129990982646461e+01,5.437828584340966245e+02,2.197972445691313281e-01,1.100000010988609489e+01,2.933601012559235860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482220900072647396e+01,5.437928583910666021e+02,2.198265805371792392e-01,1.100000010988609489e+01,2.933455027157698142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482311809162648331e+01,5.438028583480407860e+02,2.198559150453794353e-01,1.100000010988609489e+01,2.933309041756160425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482402718252649265e+01,5.438128583050192901e+02,2.198852480937318887e-01,1.100000010988609489e+01,2.933163056354622707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482493627342650200e+01,5.438228582620021143e+02,2.199145796822365995e-01,1.100000010988609489e+01,2.933017070953084990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482584536432651134e+01,5.438328582189891449e+02,2.199439098108935675e-01,1.100000010988609489e+01,2.932871085551547272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482675445522652069e+01,5.438428581759804956e+02,2.199732384797028206e-01,1.100000010988609489e+01,2.932725100150009555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482766354612653004e+01,5.438528581329761664e+02,2.200025656886643310e-01,1.100000010988609489e+01,2.932579114748471837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482857263702653938e+01,5.438628580899760436e+02,2.200318914377780988e-01,1.100000010988609489e+01,2.932433129346934120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.482948172792654873e+01,5.438728580469802409e+02,2.200612157270441238e-01,1.100000010988609489e+01,2.932287143945396402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483039081882655807e+01,5.438828580039887584e+02,2.200905385564624062e-01,1.100000010988609489e+01,2.932141158543858685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483129990972656742e+01,5.438928579610014822e+02,2.201198599260329458e-01,1.100000010988609489e+01,2.931995173142320967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483220900062657677e+01,5.439028579180185261e+02,2.201491798357557705e-01,1.100000010988609489e+01,2.931849187740783250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483311809152658611e+01,5.439128578750398901e+02,2.201784982856308526e-01,1.100000010988609489e+01,2.931703202339245532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483402718242659546e+01,5.439228578320654606e+02,2.202078152756581919e-01,1.100000010988609489e+01,2.931557216937707815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483493627332660481e+01,5.439328577890953511e+02,2.202371308058377886e-01,1.100000010988609489e+01,2.931411231536170097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483584536422661415e+01,5.439428577461295617e+02,2.202664448761696425e-01,1.100000010988609489e+01,2.931265246134632380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483675445512662350e+01,5.439528577031679788e+02,2.202957574866537538e-01,1.100000010988609489e+01,2.931119260733094662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483766354602663284e+01,5.439628576602107159e+02,2.203250686372901224e-01,1.100000010988609489e+01,2.930973275331556945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483857263692664219e+01,5.439728576172577732e+02,2.203543783280787483e-01,1.100000010988609489e+01,2.930827289930019227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.483948172782665154e+01,5.439828575743090369e+02,2.203836865590196037e-01,1.100000010988609489e+01,2.930681304528481509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484039081872666088e+01,5.439928575313646206e+02,2.204129933301127164e-01,1.100000010988609489e+01,2.930535319126943792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484129990962667023e+01,5.440028574884244108e+02,2.204422986413580865e-01,1.100000010988609489e+01,2.930389333725406074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484220900052667957e+01,5.440128574454885211e+02,2.204716024927557139e-01,1.100000010988609489e+01,2.930243348323868357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484311809142668892e+01,5.440228574025569515e+02,2.205009048843055985e-01,1.100000010988609489e+01,2.930097362922330639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484402718232669827e+01,5.440328573596295882e+02,2.205302058160077405e-01,1.100000010988609489e+01,2.929951377520792922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484493627322670761e+01,5.440428573167065451e+02,2.205595052878621121e-01,1.100000010988609489e+01,2.929805392119255204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484584536412671696e+01,5.440528572737878221e+02,2.205888032998687409e-01,1.100000010988609489e+01,2.929659406717717487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484675445502672630e+01,5.440628572308733055e+02,2.206180998520276271e-01,1.100000010988609489e+01,2.929513421316179769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484766354592673565e+01,5.440728571879631090e+02,2.206473949443387705e-01,1.100000010988609489e+01,2.929367435914642052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484857263682674500e+01,5.440828571450571189e+02,2.206766885768021436e-01,1.100000010988609489e+01,2.929221450513104334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.484948172772675434e+01,5.440928571021554490e+02,2.207059807494177739e-01,1.100000010988609489e+01,2.929075465111566617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485039081862676369e+01,5.441028570592580991e+02,2.207352714621856615e-01,1.100000010988609489e+01,2.928929479710028899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485129990952677304e+01,5.441128570163649556e+02,2.207645607151057787e-01,1.100000010988609489e+01,2.928783494308491182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485220900042678238e+01,5.441228569734761322e+02,2.207938485081781532e-01,1.100000010988609489e+01,2.928637508906953464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485311809132679173e+01,5.441328569305916290e+02,2.208231348414027573e-01,1.100000010988609489e+01,2.928491523505415747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485402718222680107e+01,5.441428568877113321e+02,2.208524197147796186e-01,1.100000010988609489e+01,2.928345538103878029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485493627312681042e+01,5.441528568448353553e+02,2.208817031283087373e-01,1.100000010988609489e+01,2.928199552702340312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485584536402681977e+01,5.441628568019635850e+02,2.209109850819900855e-01,1.100000010988609489e+01,2.928053567300802594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485675445492682911e+01,5.441728567590961347e+02,2.209402655758236911e-01,1.100000010988609489e+01,2.927907581899264877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485766354582683846e+01,5.441828567162330046e+02,2.209695446098095262e-01,1.100000010988609489e+01,2.927761596497727159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485857263672684780e+01,5.441928566733740809e+02,2.209988221839475908e-01,1.100000010988609489e+01,2.927615611096189441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.485948172762685715e+01,5.442028566305194772e+02,2.210280982982379128e-01,1.100000010988609489e+01,2.927469625694651724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486039081852686650e+01,5.442128565876690800e+02,2.210573729526804643e-01,1.100000010988609489e+01,2.927323640293114006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486129990942687584e+01,5.442228565448230029e+02,2.210866461472752731e-01,1.100000010988609489e+01,2.927177654891576289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486220900032688519e+01,5.442328565019811322e+02,2.211159178820223115e-01,1.100000010988609489e+01,2.927031669490038571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486311809122689453e+01,5.442428564591435816e+02,2.211451881569215794e-01,1.100000010988609489e+01,2.926885684088500854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486402718212690388e+01,5.442528564163103511e+02,2.211744569719731046e-01,1.100000010988609489e+01,2.926739698686963136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486493627302691323e+01,5.442628563734813270e+02,2.212037243271768594e-01,1.100000010988609489e+01,2.926593713285425419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486584536392692257e+01,5.442728563306566230e+02,2.212329902225328437e-01,1.100000010988609489e+01,2.926447727883887701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486675445482693192e+01,5.442828562878361254e+02,2.212622546580410576e-01,1.100000010988609489e+01,2.926301742482349984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486766354572694127e+01,5.442928562450199479e+02,2.212915176337015288e-01,1.100000010988609489e+01,2.926155757080812266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486857263662695061e+01,5.443028562022080905e+02,2.213207791495142296e-01,1.100000010988609489e+01,2.926009771679274549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.486948172752695996e+01,5.443128561594004395e+02,2.213500392054791599e-01,1.100000010988609489e+01,2.925863786277736831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487039081842696930e+01,5.443228561165971087e+02,2.213792978015963198e-01,1.100000010988609489e+01,2.925717800876199114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487129990932697865e+01,5.443328560737979842e+02,2.214085549378657092e-01,1.100000010988609489e+01,2.925571815474661396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487220900022698800e+01,5.443428560310031799e+02,2.214378106142873281e-01,1.100000010988609489e+01,2.925425830073123679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487311809112699734e+01,5.443528559882125819e+02,2.214670648308611767e-01,1.100000010988609489e+01,2.925279844671585961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487402718202700669e+01,5.443628559454263041e+02,2.214963175875872547e-01,1.100000010988609489e+01,2.925133859270048244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487493627292701603e+01,5.443728559026443463e+02,2.215255688844655624e-01,1.100000010988609489e+01,2.924987873868510526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487584536382702538e+01,5.443828558598665950e+02,2.215548187214960996e-01,1.100000010988609489e+01,2.924841888466972809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487675445472703473e+01,5.443928558170931638e+02,2.215840670986788663e-01,1.100000010988609489e+01,2.924695903065435091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487766354562704407e+01,5.444028557743239389e+02,2.216133140160138626e-01,1.100000010988609489e+01,2.924549917663897373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487857263652705342e+01,5.444128557315590342e+02,2.216425594735010884e-01,1.100000010988609489e+01,2.924403932262359656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.487948172742706276e+01,5.444228556887983359e+02,2.216718034711405438e-01,1.100000010988609489e+01,2.924257946860821938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488039081832707211e+01,5.444328556460419577e+02,2.217010460089322288e-01,1.100000010988609489e+01,2.924111961459284221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488129990922708146e+01,5.444428556032897859e+02,2.217302870868761433e-01,1.100000010988609489e+01,2.923965976057746503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488220900012709080e+01,5.444528555605419342e+02,2.217595267049722874e-01,1.100000010988609489e+01,2.923819990656208786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488311809102710015e+01,5.444628555177984026e+02,2.217887648632206610e-01,1.100000010988609489e+01,2.923674005254671068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488402718192710950e+01,5.444728554750590774e+02,2.218180015616212641e-01,1.100000010988609489e+01,2.923528019853133351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488493627282711884e+01,5.444828554323240724e+02,2.218472368001740691e-01,1.100000010988609489e+01,2.923382034451595633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488584536372712819e+01,5.444928553895932737e+02,2.218764705788791036e-01,1.100000010988609489e+01,2.923236049050057916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488675445462713753e+01,5.445028553468667951e+02,2.219057028977363677e-01,1.100000010988609489e+01,2.923090063648520198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488766354552714688e+01,5.445128553041445230e+02,2.219349337567458613e-01,1.100000010988609489e+01,2.922944078246982481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488857263642715623e+01,5.445228552614265709e+02,2.219641631559075567e-01,1.100000010988609489e+01,2.922798092845444763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.488948172732716557e+01,5.445328552187128253e+02,2.219933910952214817e-01,1.100000010988609489e+01,2.922652107443907046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489039081822717492e+01,5.445428551760033997e+02,2.220226175746876363e-01,1.100000010988609489e+01,2.922506122042369328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489129990912718426e+01,5.445528551332981806e+02,2.220518425943059926e-01,1.100000010988609489e+01,2.922360136640831611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489220900002719361e+01,5.445628550905972816e+02,2.220810661540765785e-01,1.100000010988609489e+01,2.922214151239293893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489311809092720296e+01,5.445728550479005889e+02,2.221102882539993661e-01,1.100000010988609489e+01,2.922068165837756176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489402718182721230e+01,5.445828550052082164e+02,2.221395088940743834e-01,1.100000010988609489e+01,2.921922180436218458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489493627272722165e+01,5.445928549625200503e+02,2.221687280743016302e-01,1.100000010988609489e+01,2.921776195034680740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489584536362723100e+01,5.446028549198362043e+02,2.221979457946810788e-01,1.100000010988609489e+01,2.921630209633143023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489675445452724034e+01,5.446128548771565647e+02,2.222271620552127569e-01,1.100000010988609489e+01,2.921484224231605305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489766354542724969e+01,5.446228548344812452e+02,2.222563768558966368e-01,1.100000010988609489e+01,2.921338238830067588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489857263632725903e+01,5.446328547918102458e+02,2.222855901967327186e-01,1.100000010988609489e+01,2.921192253428529870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.489948172722726838e+01,5.446428547491434529e+02,2.223148020777210299e-01,1.100000010988609489e+01,2.921046268026992153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490039081812727773e+01,5.446528547064809800e+02,2.223440124988615429e-01,1.100000010988609489e+01,2.920900282625454435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490129990902728707e+01,5.446628546638227135e+02,2.223732214601542856e-01,1.100000010988609489e+01,2.920754297223916718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490220899992729642e+01,5.446728546211687672e+02,2.224024289615992300e-01,1.100000010988609489e+01,2.920608311822379000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490311809082730576e+01,5.446828545785190272e+02,2.224316350031963763e-01,1.100000010988609489e+01,2.920462326420841283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490402718172731511e+01,5.446928545358736073e+02,2.224608395849457521e-01,1.100000010988609489e+01,2.920316341019303565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490493627262732446e+01,5.447028544932323939e+02,2.224900427068473296e-01,1.100000010988609489e+01,2.920170355617765848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490584536352733380e+01,5.447128544505955006e+02,2.225192443689011090e-01,1.100000010988609489e+01,2.920024370216228130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490675445442734315e+01,5.447228544079628136e+02,2.225484445711070902e-01,1.100000010988609489e+01,2.919878384814690413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490766354532735249e+01,5.447328543653344468e+02,2.225776433134653010e-01,1.100000010988609489e+01,2.919732399413152695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490857263622736184e+01,5.447428543227102864e+02,2.226068405959757135e-01,1.100000010988609489e+01,2.919586414011614978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.490948172712737119e+01,5.447528542800904461e+02,2.226360364186383278e-01,1.100000010988609489e+01,2.919440428610077260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491039081802738053e+01,5.447628542374748122e+02,2.226652307814531440e-01,1.100000010988609489e+01,2.919294443208539543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491129990892738988e+01,5.447728541948634984e+02,2.226944236844201619e-01,1.100000010988609489e+01,2.919148457807001825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491220899982739923e+01,5.447828541522563910e+02,2.227236151275393816e-01,1.100000010988609489e+01,2.919002472405464108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491311809072740857e+01,5.447928541096534900e+02,2.227528051108108309e-01,1.100000010988609489e+01,2.918856487003926390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491402718162741792e+01,5.448028540670549091e+02,2.227819936342344820e-01,1.100000010988609489e+01,2.918710501602388672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491493627252742726e+01,5.448128540244605347e+02,2.228111806978103349e-01,1.100000010988609489e+01,2.918564516200850955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491584536342743661e+01,5.448228539818704803e+02,2.228403663015383895e-01,1.100000010988609489e+01,2.918418530799313237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491675445432744596e+01,5.448328539392846324e+02,2.228695504454186460e-01,1.100000010988609489e+01,2.918272545397775520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491766354522745530e+01,5.448428538967031045e+02,2.228987331294511043e-01,1.100000010988609489e+01,2.918126559996237802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491857263612746465e+01,5.448528538541257831e+02,2.229279143536357644e-01,1.100000010988609489e+01,2.917980574594700085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.491948172702747399e+01,5.448628538115527817e+02,2.229570941179726262e-01,1.100000010988609489e+01,2.917834589193162367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492039081792748334e+01,5.448728537689839868e+02,2.229862724224616899e-01,1.100000010988609489e+01,2.917688603791624650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492129990882749269e+01,5.448828537264195120e+02,2.230154492671029276e-01,1.100000010988609489e+01,2.917542618390086932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492220899972750203e+01,5.448928536838592436e+02,2.230446246518963671e-01,1.100000010988609489e+01,2.917396632988549215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492311809062751138e+01,5.449028536413032953e+02,2.230737985768420084e-01,1.100000010988609489e+01,2.917250647587011497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492402718152752072e+01,5.449128535987515534e+02,2.231029710419398515e-01,1.100000010988609489e+01,2.917104662185473780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492493627242753007e+01,5.449228535562041316e+02,2.231321420471898964e-01,1.100000010988609489e+01,2.916958676783936062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492584536332753942e+01,5.449328535136609162e+02,2.231613115925921431e-01,1.100000010988609489e+01,2.916812691382398345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492675445422754876e+01,5.449428534711220209e+02,2.231904796781465639e-01,1.100000010988609489e+01,2.916666705980860627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492766354512755811e+01,5.449528534285873320e+02,2.232196463038531864e-01,1.100000010988609489e+01,2.916520720579322910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492857263602756746e+01,5.449628533860568496e+02,2.232488114697120107e-01,1.100000010988609489e+01,2.916374735177785192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.492948172692757680e+01,5.449728533435306872e+02,2.232779751757230091e-01,1.100000010988609489e+01,2.916228749776247475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493039081782758615e+01,5.449828533010087313e+02,2.233071374218862093e-01,1.100000010988609489e+01,2.916082764374709757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493129990872759549e+01,5.449928532584910954e+02,2.233362982082016113e-01,1.100000010988609489e+01,2.915936778973172040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493220899962760484e+01,5.450028532159776660e+02,2.233654575346691873e-01,1.100000010988609489e+01,2.915790793571634322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493311809052761419e+01,5.450128531734685566e+02,2.233946154012889651e-01,1.100000010988609489e+01,2.915644808170096604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493402718142762353e+01,5.450228531309636537e+02,2.234237718080609170e-01,1.100000010988609489e+01,2.915498822768558887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493493627232763288e+01,5.450328530884630709e+02,2.234529267549850706e-01,1.100000010988609489e+01,2.915352837367021169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493584536322764222e+01,5.450428530459666945e+02,2.234820802420614261e-01,1.100000010988609489e+01,2.915206851965483452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493675445412765157e+01,5.450528530034745245e+02,2.235112322692899556e-01,1.100000010988609489e+01,2.915060866563945734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493766354502766092e+01,5.450628529609866746e+02,2.235403828366706869e-01,1.100000010988609489e+01,2.914914881162408017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493857263592767026e+01,5.450728529185030311e+02,2.235695319442035922e-01,1.100000010988609489e+01,2.914768895760870299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.493948172682767961e+01,5.450828528760237077e+02,2.235986795918886716e-01,1.100000010988609489e+01,2.914622910359332582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494039081772768895e+01,5.450928528335485908e+02,2.236278257797259528e-01,1.100000010988609489e+01,2.914476924957794864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494129990862769830e+01,5.451028527910777939e+02,2.236569705077154080e-01,1.100000010988609489e+01,2.914330939556257147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494220899952770765e+01,5.451128527486112034e+02,2.236861137758570650e-01,1.100000010988609489e+01,2.914184954154719429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494311809042771699e+01,5.451228527061488194e+02,2.237152555841508961e-01,1.100000010988609489e+01,2.914038968753181712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494402718132772634e+01,5.451328526636907554e+02,2.237443959325969012e-01,1.100000010988609489e+01,2.913892983351643994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494493627222773569e+01,5.451428526212368979e+02,2.237735348211951081e-01,1.100000010988609489e+01,2.913746997950106277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494584536312774503e+01,5.451528525787873605e+02,2.238026722499454890e-01,1.100000010988609489e+01,2.913601012548568559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494675445402775438e+01,5.451628525363420295e+02,2.238318082188480440e-01,1.100000010988609489e+01,2.913455027147030842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494766354492776372e+01,5.451728524939009048e+02,2.238609427279027730e-01,1.100000010988609489e+01,2.913309041745493124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494857263582777307e+01,5.451828524514641003e+02,2.238900757771097039e-01,1.100000010988609489e+01,2.913163056343955407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.494948172672778242e+01,5.451928524090315022e+02,2.239192073664688087e-01,1.100000010988609489e+01,2.913017070942417689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495039081762779176e+01,5.452028523666032243e+02,2.239483374959800877e-01,1.100000010988609489e+01,2.912871085540879972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495129990852780111e+01,5.452128523241791527e+02,2.239774661656435406e-01,1.100000010988609489e+01,2.912725100139342254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495220899942781045e+01,5.452228522817594012e+02,2.240065933754591676e-01,1.100000010988609489e+01,2.912579114737804536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495311809032781980e+01,5.452328522393438561e+02,2.240357191254269686e-01,1.100000010988609489e+01,2.912433129336266819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495402718122782915e+01,5.452428521969325175e+02,2.240648434155469715e-01,1.100000010988609489e+01,2.912287143934729101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495493627212783849e+01,5.452528521545254989e+02,2.240939662458191484e-01,1.100000010988609489e+01,2.912141158533191384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495584536302784784e+01,5.452628521121226868e+02,2.241230876162434993e-01,1.100000010988609489e+01,2.911995173131653666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495675445392785718e+01,5.452728520697240810e+02,2.241522075268200243e-01,1.100000010988609489e+01,2.911849187730115949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495766354482786653e+01,5.452828520273297954e+02,2.241813259775487233e-01,1.100000010988609489e+01,2.911703202328578231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495857263572787588e+01,5.452928519849397162e+02,2.242104429684295963e-01,1.100000010988609489e+01,2.911557216927040514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.495948172662788522e+01,5.453028519425539571e+02,2.242395584994626434e-01,1.100000010988609489e+01,2.911411231525502796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496039081752789457e+01,5.453128519001724044e+02,2.242686725706478368e-01,1.100000010988609489e+01,2.911265246123965079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496129990842790392e+01,5.453228518577950581e+02,2.242977851819852042e-01,1.100000010988609489e+01,2.911119260722427361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496220899932791326e+01,5.453328518154220319e+02,2.243268963334747457e-01,1.100000010988609489e+01,2.910973275320889644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496311809022792261e+01,5.453428517730532121e+02,2.243560060251164612e-01,1.100000010988609489e+01,2.910827289919351926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496402718112793195e+01,5.453528517306887125e+02,2.243851142569103507e-01,1.100000010988609489e+01,2.910681304517814209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496493627202794130e+01,5.453628516883284192e+02,2.244142210288564143e-01,1.100000010988609489e+01,2.910535319116276491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496584536292795065e+01,5.453728516459723323e+02,2.244433263409546520e-01,1.100000010988609489e+01,2.910389333714738774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496675445382795999e+01,5.453828516036205656e+02,2.244724301932050359e-01,1.100000010988609489e+01,2.910243348313201056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496766354472796934e+01,5.453928515612730052e+02,2.245015325856075938e-01,1.100000010988609489e+01,2.910097362911663339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496857263562797868e+01,5.454028515189296513e+02,2.245306335181623258e-01,1.100000010988609489e+01,2.909951377510125621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.496948172652798803e+01,5.454128514765906175e+02,2.245597329908692319e-01,1.100000010988609489e+01,2.909805392108587904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497039081742799738e+01,5.454228514342557901e+02,2.245888310037282842e-01,1.100000010988609489e+01,2.909659406707050186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497129990832800672e+01,5.454328513919252828e+02,2.246179275567395106e-01,1.100000010988609489e+01,2.909513421305512468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497220899922801607e+01,5.454428513495989819e+02,2.246470226499028833e-01,1.100000010988609489e+01,2.909367435903974751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497311809012802541e+01,5.454528513072768874e+02,2.246761162832184300e-01,1.100000010988609489e+01,2.909221450502437033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497402718102803476e+01,5.454628512649591130e+02,2.247052084566861507e-01,1.100000010988609489e+01,2.909075465100899316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497493627192804411e+01,5.454728512226455450e+02,2.247342991703060178e-01,1.100000010988609489e+01,2.908929479699361598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497584536282805345e+01,5.454828511803361835e+02,2.247633884240780588e-01,1.100000010988609489e+01,2.908783494297823881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497675445372806280e+01,5.454928511380311420e+02,2.247924762180022462e-01,1.100000010988609489e+01,2.908637508896286163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497766354462807215e+01,5.455028510957303070e+02,2.248215625520786076e-01,1.100000010988609489e+01,2.908491523494748446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497857263552808149e+01,5.455128510534336783e+02,2.248506474263071153e-01,1.100000010988609489e+01,2.908345538093210728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.497948172642809084e+01,5.455228510111413698e+02,2.248797308406877971e-01,1.100000010988609489e+01,2.908199552691673011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498039081732810018e+01,5.455328509688532677e+02,2.249088127952206251e-01,1.100000010988609489e+01,2.908053567290135293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498129990822810953e+01,5.455428509265693719e+02,2.249378932899056271e-01,1.100000010988609489e+01,2.907907581888597576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498220899912811888e+01,5.455528508842897963e+02,2.249669723247427755e-01,1.100000010988609489e+01,2.907761596487059858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498311809002812822e+01,5.455628508420144271e+02,2.249960498997320701e-01,1.100000010988609489e+01,2.907615611085522141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498402718092813757e+01,5.455728507997432644e+02,2.250251260148735388e-01,1.100000010988609489e+01,2.907469625683984423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498493627182814691e+01,5.455828507574764217e+02,2.250542006701671538e-01,1.100000010988609489e+01,2.907323640282446706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498584536272815626e+01,5.455928507152137854e+02,2.250832738656129151e-01,1.100000010988609489e+01,2.907177654880908988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498675445362816561e+01,5.456028506729553555e+02,2.251123456012108504e-01,1.100000010988609489e+01,2.907031669479371271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498766354452817495e+01,5.456128506307012458e+02,2.251414158769609319e-01,1.100000010988609489e+01,2.906885684077833553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498857263542818430e+01,5.456228505884513424e+02,2.251704846928631598e-01,1.100000010988609489e+01,2.906739698676295836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.498948172632819364e+01,5.456328505462056455e+02,2.251995520489175340e-01,1.100000010988609489e+01,2.906593713274758118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499039081722820299e+01,5.456428505039642687e+02,2.252286179451240822e-01,1.100000010988609489e+01,2.906447727873220400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499129990812821234e+01,5.456528504617270983e+02,2.252576823814827767e-01,1.100000010988609489e+01,2.906301742471682683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499220899902822168e+01,5.456628504194941343e+02,2.252867453579936174e-01,1.100000010988609489e+01,2.906155757070144965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499311808992823103e+01,5.456728503772654904e+02,2.253158068746566045e-01,1.100000010988609489e+01,2.906009771668607248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499402718082824038e+01,5.456828503350410529e+02,2.253448669314717379e-01,1.100000010988609489e+01,2.905863786267069530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499493627172824972e+01,5.456928502928208218e+02,2.253739255284390175e-01,1.100000010988609489e+01,2.905717800865531813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499584536262825907e+01,5.457028502506049108e+02,2.254029826655584434e-01,1.100000010988609489e+01,2.905571815463994095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499675445352826841e+01,5.457128502083932062e+02,2.254320383428300156e-01,1.100000010988609489e+01,2.905425830062456378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499766354442827776e+01,5.457228501661857081e+02,2.254610925602537341e-01,1.100000010988609489e+01,2.905279844660918660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499857263532828711e+01,5.457328501239825300e+02,2.254901453178295989e-01,1.100000010988609489e+01,2.905133859259380943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.499948172622829645e+01,5.457428500817835584e+02,2.255191966155576100e-01,1.100000010988609489e+01,2.904987873857843225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500039081712830580e+01,5.457528500395887932e+02,2.255482464534377673e-01,1.100000010988609489e+01,2.904841888456305508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500129990802831514e+01,5.457628499973982343e+02,2.255772948314700710e-01,1.100000010988609489e+01,2.904695903054767790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500220899892832449e+01,5.457728499552119956e+02,2.256063417496545209e-01,1.100000010988609489e+01,2.904549917653230073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500311808982833384e+01,5.457828499130299633e+02,2.256353872079911171e-01,1.100000010988609489e+01,2.904403932251692355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500402718072834318e+01,5.457928498708521374e+02,2.256644312064798596e-01,1.100000010988609489e+01,2.904257946850154638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500493627162835253e+01,5.458028498286786316e+02,2.256934737451207484e-01,1.100000010988609489e+01,2.904111961448616920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500584536252836187e+01,5.458128497865093323e+02,2.257225148239137558e-01,1.100000010988609489e+01,2.903965976047079203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500675445342837122e+01,5.458228497443442393e+02,2.257515544428589094e-01,1.100000010988609489e+01,2.903819990645541485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500766354432838057e+01,5.458328497021834664e+02,2.257805926019562093e-01,1.100000010988609489e+01,2.903674005244003768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500857263522838991e+01,5.458428496600269000e+02,2.258096293012056555e-01,1.100000010988609489e+01,2.903528019842466050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.500948172612839926e+01,5.458528496178745399e+02,2.258386645406072202e-01,1.100000010988609489e+01,2.903382034440928332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501039081702840861e+01,5.458628495757263863e+02,2.258676983201609312e-01,1.100000010988609489e+01,2.903236049039390615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501129990792841795e+01,5.458728495335825528e+02,2.258967306398667885e-01,1.100000010988609489e+01,2.903090063637852897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501220899882842730e+01,5.458828494914429257e+02,2.259257614997247643e-01,1.100000010988609489e+01,2.902944078236315180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501311808972843664e+01,5.458928494493075050e+02,2.259547908997348864e-01,1.100000010988609489e+01,2.902798092834777462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501402718062844599e+01,5.459028494071764044e+02,2.259838188398971548e-01,1.100000010988609489e+01,2.902652107433239745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501493627152845534e+01,5.459128493650495102e+02,2.260128453202115417e-01,1.100000010988609489e+01,2.902506122031702027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501584536242846468e+01,5.459228493229268224e+02,2.260418703406780749e-01,1.100000010988609489e+01,2.902360136630164310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501675445332847403e+01,5.459328492808083411e+02,2.260708939012967267e-01,1.100000010988609489e+01,2.902214151228626592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501766354422848337e+01,5.459428492386941798e+02,2.260999160020675247e-01,1.100000010988609489e+01,2.902068165827088875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501857263512849272e+01,5.459528491965842250e+02,2.261289366429904413e-01,1.100000010988609489e+01,2.901922180425551157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.501948172602850207e+01,5.459628491544784765e+02,2.261579558240655041e-01,1.100000010988609489e+01,2.901776195024013440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502039081692851141e+01,5.459728491123769345e+02,2.261869735452926855e-01,1.100000010988609489e+01,2.901630209622475722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502129990782852076e+01,5.459828490702797126e+02,2.262159898066720132e-01,1.100000010988609489e+01,2.901484224220938005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502220899872853010e+01,5.459928490281866971e+02,2.262450046082034594e-01,1.100000010988609489e+01,2.901338238819400287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502311808962853945e+01,5.460028489860978880e+02,2.262740179498870519e-01,1.100000010988609489e+01,2.901192253417862570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502402718052854880e+01,5.460128489440132853e+02,2.263030298317227629e-01,1.100000010988609489e+01,2.901046268016324852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502493627142855814e+01,5.460228489019330027e+02,2.263320402537105924e-01,1.100000010988609489e+01,2.900900282614787135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502584536232856749e+01,5.460328488598569265e+02,2.263610492158505683e-01,1.100000010988609489e+01,2.900754297213249417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502675445322857684e+01,5.460428488177850568e+02,2.263900567181426626e-01,1.100000010988609489e+01,2.900608311811711700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502766354412858618e+01,5.460528487757173934e+02,2.264190627605868755e-01,1.100000010988609489e+01,2.900462326410173982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502857263502859553e+01,5.460628487336540502e+02,2.264480673431832070e-01,1.100000010988609489e+01,2.900316341008636264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.502948172592860487e+01,5.460728486915949134e+02,2.264770704659316847e-01,1.100000010988609489e+01,2.900170355607098547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503039081682861422e+01,5.460828486495399829e+02,2.265060721288322809e-01,1.100000010988609489e+01,2.900024370205560829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503129990772862357e+01,5.460928486074892589e+02,2.265350723318849957e-01,1.100000010988609489e+01,2.899878384804023112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503220899862863291e+01,5.461028485654428550e+02,2.265640710750898290e-01,1.100000010988609489e+01,2.899732399402485394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503311808952864226e+01,5.461128485234006575e+02,2.265930683584467809e-01,1.100000010988609489e+01,2.899586414000947677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503402718042865160e+01,5.461228484813626665e+02,2.266220641819558512e-01,1.100000010988609489e+01,2.899440428599409959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503493627132866095e+01,5.461328484393288818e+02,2.266510585456170679e-01,1.100000010988609489e+01,2.899294443197872242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503584536222867030e+01,5.461428483972994172e+02,2.266800514494304031e-01,1.100000010988609489e+01,2.899148457796334524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503675445312867964e+01,5.461528483552741591e+02,2.267090428933958568e-01,1.100000010988609489e+01,2.899002472394796807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503766354402868899e+01,5.461628483132531073e+02,2.267380328775134291e-01,1.100000010988609489e+01,2.898856486993259089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503857263492869833e+01,5.461728482712362620e+02,2.267670214017831198e-01,1.100000010988609489e+01,2.898710501591721372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.503948172582870768e+01,5.461828482292236231e+02,2.267960084662049292e-01,1.100000010988609489e+01,2.898564516190183654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504039081672871703e+01,5.461928481872153043e+02,2.268249940707788570e-01,1.100000010988609489e+01,2.898418530788645937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504129990762872637e+01,5.462028481452111919e+02,2.268539782155049034e-01,1.100000010988609489e+01,2.898272545387108219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504220899852873572e+01,5.462128481032112859e+02,2.268829609003830405e-01,1.100000010988609489e+01,2.898126559985570502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504311808942874507e+01,5.462228480612155863e+02,2.269119421254132962e-01,1.100000010988609489e+01,2.897980574584032784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504402718032875441e+01,5.462328480192242068e+02,2.269409218905956704e-01,1.100000010988609489e+01,2.897834589182495067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504493627122876376e+01,5.462428479772370338e+02,2.269699001959301632e-01,1.100000010988609489e+01,2.897688603780957349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504584536212877310e+01,5.462528479352540671e+02,2.269988770414167745e-01,1.100000010988609489e+01,2.897542618379419632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504675445302878245e+01,5.462628478932753069e+02,2.270278524270555043e-01,1.100000010988609489e+01,2.897396632977881914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504766354392879180e+01,5.462728478513007531e+02,2.270568263528463526e-01,1.100000010988609489e+01,2.897250647576344196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504857263482880114e+01,5.462828478093305193e+02,2.270857988187892917e-01,1.100000010988609489e+01,2.897104662174806479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.504948172572881049e+01,5.462928477673644920e+02,2.271147698248843494e-01,1.100000010988609489e+01,2.896958676773268761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505039081662881983e+01,5.463028477254026711e+02,2.271437393711315256e-01,1.100000010988609489e+01,2.896812691371731044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505129990752882918e+01,5.463128476834450566e+02,2.271727074575307925e-01,1.100000010988609489e+01,2.896666705970193326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505220899842883853e+01,5.463228476414916486e+02,2.272016740840821780e-01,1.100000010988609489e+01,2.896520720568655609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505311808932884787e+01,5.463328475995425606e+02,2.272306392507856820e-01,1.100000010988609489e+01,2.896374735167117891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505402718022885722e+01,5.463428475575976790e+02,2.272596029576412768e-01,1.100000010988609489e+01,2.896228749765580174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505493627112886657e+01,5.463528475156570039e+02,2.272885652046489902e-01,1.100000010988609489e+01,2.896082764364042456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505584536202887591e+01,5.463628474737205352e+02,2.273175259918088220e-01,1.100000010988609489e+01,2.895936778962504739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505675445292888526e+01,5.463728474317882728e+02,2.273464853191207447e-01,1.100000010988609489e+01,2.895790793560967021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505766354382889460e+01,5.463828473898603306e+02,2.273754431865847858e-01,1.100000010988609489e+01,2.895644808159429304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505857263472890395e+01,5.463928473479365948e+02,2.274043995942009178e-01,1.100000010988609489e+01,2.895498822757891586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.505948172562891330e+01,5.464028473060170654e+02,2.274333545419691682e-01,1.100000010988609489e+01,2.895352837356353869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506039081652892264e+01,5.464128472641017424e+02,2.274623080298895095e-01,1.100000010988609489e+01,2.895206851954816151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506129990742893199e+01,5.464228472221906259e+02,2.274912600579619693e-01,1.100000010988609489e+01,2.895060866553278434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506220899832894133e+01,5.464328471802837157e+02,2.275202106261865198e-01,1.100000010988609489e+01,2.894914881151740716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506311808922895068e+01,5.464428471383811257e+02,2.275491597345631889e-01,1.100000010988609489e+01,2.894768895750202999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506402718012896003e+01,5.464528470964827420e+02,2.275781073830919488e-01,1.100000010988609489e+01,2.894622910348665281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506493627102896937e+01,5.464628470545885648e+02,2.276070535717727994e-01,1.100000010988609489e+01,2.894476924947127564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506584536192897872e+01,5.464728470126985940e+02,2.276359983006057686e-01,1.100000010988609489e+01,2.894330939545589846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506675445282898806e+01,5.464828469708128296e+02,2.276649415695908285e-01,1.100000010988609489e+01,2.894184954144052128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506766354372899741e+01,5.464928469289312716e+02,2.276938833787279792e-01,1.100000010988609489e+01,2.894038968742514411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506857263462900676e+01,5.465028468870540337e+02,2.277228237280172207e-01,1.100000010988609489e+01,2.893892983340976693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.506948172552901610e+01,5.465128468451810022e+02,2.277517626174585808e-01,1.100000010988609489e+01,2.893746997939438976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507039081642902545e+01,5.465228468033121771e+02,2.277807000470520316e-01,1.100000010988609489e+01,2.893601012537901258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507129990732903480e+01,5.465328467614475585e+02,2.278096360167975731e-01,1.100000010988609489e+01,2.893455027136363541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507220899822904414e+01,5.465428467195871463e+02,2.278385705266952055e-01,1.100000010988609489e+01,2.893309041734825823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507311808912905349e+01,5.465528466777309404e+02,2.278675035767449564e-01,1.100000010988609489e+01,2.893163056333288106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507402718002906283e+01,5.465628466358790547e+02,2.278964351669467980e-01,1.100000010988609489e+01,2.893017070931750388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507493627092907218e+01,5.465728465940313754e+02,2.279253652973007305e-01,1.100000010988609489e+01,2.892871085530212671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507584536182908153e+01,5.465828465521879025e+02,2.279542939678067537e-01,1.100000010988609489e+01,2.892725100128674953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507675445272909087e+01,5.465928465103486360e+02,2.279832211784648677e-01,1.100000010988609489e+01,2.892579114727137236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507766354362910022e+01,5.466028464685135759e+02,2.280121469292750724e-01,1.100000010988609489e+01,2.892433129325599518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507857263452910956e+01,5.466128464266827223e+02,2.280410712202373680e-01,1.100000010988609489e+01,2.892287143924061801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.507948172542911891e+01,5.466228463848560750e+02,2.280699940513517543e-01,1.100000010988609489e+01,2.892141158522524083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508039081632912826e+01,5.466328463430337479e+02,2.280989154226182314e-01,1.100000010988609489e+01,2.891995173120986366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508129990722913760e+01,5.466428463012156271e+02,2.281278353340367993e-01,1.100000010988609489e+01,2.891849187719448648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508220899812914695e+01,5.466528462594017128e+02,2.281567537856074579e-01,1.100000010988609489e+01,2.891703202317910931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508311808902915629e+01,5.466628462175920049e+02,2.281856707773302073e-01,1.100000010988609489e+01,2.891557216916373213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508402717992916564e+01,5.466728461757865034e+02,2.282145863092050475e-01,1.100000010988609489e+01,2.891411231514835495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508493627082917499e+01,5.466828461339852083e+02,2.282435003812319785e-01,1.100000010988609489e+01,2.891265246113297778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508584536172918433e+01,5.466928460921881197e+02,2.282724129934109725e-01,1.100000010988609489e+01,2.891119260711760060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508675445262919368e+01,5.467028460503953511e+02,2.283013241457420572e-01,1.100000010988609489e+01,2.890973275310222343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508766354352920303e+01,5.467128460086067889e+02,2.283302338382252328e-01,1.100000010988609489e+01,2.890827289908684625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508857263442921237e+01,5.467228459668224332e+02,2.283591420708604991e-01,1.100000010988609489e+01,2.890681304507146908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.508948172532922172e+01,5.467328459250422839e+02,2.283880488436478562e-01,1.100000010988609489e+01,2.890535319105609190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509039081622923106e+01,5.467428458832663409e+02,2.284169541565872763e-01,1.100000010988609489e+01,2.890389333704071473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509129990712924041e+01,5.467528458414946044e+02,2.284458580096787872e-01,1.100000010988609489e+01,2.890243348302533755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509220899802924976e+01,5.467628457997270743e+02,2.284747604029223889e-01,1.100000010988609489e+01,2.890097362900996038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509311808892925910e+01,5.467728457579637507e+02,2.285036613363180813e-01,1.100000010988609489e+01,2.889951377499458320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509402717982926845e+01,5.467828457162046334e+02,2.285325608098658368e-01,1.100000010988609489e+01,2.889805392097920603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509493627072927779e+01,5.467928456744498362e+02,2.285614588235656830e-01,1.100000010988609489e+01,2.889659406696382885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509584536162928714e+01,5.468028456326992455e+02,2.285903553774175923e-01,1.100000010988609489e+01,2.889513421294845168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509675445252929649e+01,5.468128455909528611e+02,2.286192504714215923e-01,1.100000010988609489e+01,2.889367435893307450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509766354342930583e+01,5.468228455492106832e+02,2.286481441055776831e-01,1.100000010988609489e+01,2.889221450491769733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509857263432931518e+01,5.468328455074727117e+02,2.286770362798858369e-01,1.100000010988609489e+01,2.889075465090232015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.509948172522932452e+01,5.468428454657389466e+02,2.287059269943460815e-01,1.100000010988609489e+01,2.888929479688694298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510039081612933387e+01,5.468528454240093879e+02,2.287348162489583892e-01,1.100000010988609489e+01,2.888783494287156580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510129990702934322e+01,5.468628453822840356e+02,2.287637040437227876e-01,1.100000010988609489e+01,2.888637508885618863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510220899792935256e+01,5.468728453405628898e+02,2.287925903786392490e-01,1.100000010988609489e+01,2.888491523484081145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510311808882936191e+01,5.468828452988459503e+02,2.288214752537077734e-01,1.100000010988609489e+01,2.888345538082543427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510402717972937126e+01,5.468928452571333310e+02,2.288503586689283886e-01,1.100000010988609489e+01,2.888199552681005710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510493627062938060e+01,5.469028452154249180e+02,2.288792406243010669e-01,1.100000010988609489e+01,2.888053567279467992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510584536152938995e+01,5.469128451737207115e+02,2.289081211198258359e-01,1.100000010988609489e+01,2.887907581877930275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510675445242939929e+01,5.469228451320207114e+02,2.289370001555026679e-01,1.100000010988609489e+01,2.887761596476392557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510766354332940864e+01,5.469328450903249177e+02,2.289658777313315630e-01,1.100000010988609489e+01,2.887615611074854840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510857263422941799e+01,5.469428450486333304e+02,2.289947538473125488e-01,1.100000010988609489e+01,2.887469625673317122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.510948172512942733e+01,5.469528450069459495e+02,2.290236285034455976e-01,1.100000010988609489e+01,2.887323640271779405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511039081602943668e+01,5.469628449652627751e+02,2.290525016997307095e-01,1.100000010988609489e+01,2.887177654870241687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511129990692944602e+01,5.469728449235838070e+02,2.290813734361678844e-01,1.100000010988609489e+01,2.887031669468703970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511220899782945537e+01,5.469828448819090454e+02,2.291102437127571501e-01,1.100000010988609489e+01,2.886885684067166252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511311808872946472e+01,5.469928448402384902e+02,2.291391125294984787e-01,1.100000010988609489e+01,2.886739698665628535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511402717962947406e+01,5.470028447985721414e+02,2.291679798863918704e-01,1.100000010988609489e+01,2.886593713264090817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511493627052948341e+01,5.470128447569099990e+02,2.291968457834373252e-01,1.100000010988609489e+01,2.886447727862553100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511584536142949275e+01,5.470228447152521767e+02,2.292257102206348429e-01,1.100000010988609489e+01,2.886301742461015382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511675445232950210e+01,5.470328446735985608e+02,2.292545731979844237e-01,1.100000010988609489e+01,2.886155757059477665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511766354322951145e+01,5.470428446319491513e+02,2.292834347154860675e-01,1.100000010988609489e+01,2.886009771657939947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511857263412952079e+01,5.470528445903039483e+02,2.293122947731397743e-01,1.100000010988609489e+01,2.885863786256402230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.511948172502953014e+01,5.470628445486629516e+02,2.293411533709455441e-01,1.100000010988609489e+01,2.885717800854864512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512039081592953949e+01,5.470728445070261614e+02,2.293700105089033769e-01,1.100000010988609489e+01,2.885571815453326795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512129990682954883e+01,5.470828444653935776e+02,2.293988661870132728e-01,1.100000010988609489e+01,2.885425830051789077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512220899772955818e+01,5.470928444237652002e+02,2.294277204052752317e-01,1.100000010988609489e+01,2.885279844650251359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512311808862956752e+01,5.471028443821410292e+02,2.294565731636892536e-01,1.100000010988609489e+01,2.885133859248713642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512402717952957687e+01,5.471128443405210646e+02,2.294854244622553385e-01,1.100000010988609489e+01,2.884987873847175924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512493627042958622e+01,5.471228442989053065e+02,2.295142743009734865e-01,1.100000010988609489e+01,2.884841888445638207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512584536132959556e+01,5.471328442572937547e+02,2.295431226798436974e-01,1.100000010988609489e+01,2.884695903044100489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512675445222960491e+01,5.471428442156864094e+02,2.295719695988659714e-01,1.100000010988609489e+01,2.884549917642562772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512766354312961425e+01,5.471528441740832704e+02,2.296008150580403084e-01,1.100000010988609489e+01,2.884403932241025054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512857263402962360e+01,5.471628441324843379e+02,2.296296590573667085e-01,1.100000010988609489e+01,2.884257946839487337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.512948172492963295e+01,5.471728440908896118e+02,2.296585015968451438e-01,1.100000010988609489e+01,2.884111961437949619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513039081582964229e+01,5.471828440492990921e+02,2.296873426764756421e-01,1.100000010988609489e+01,2.883965976036411902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513129990672965164e+01,5.471928440077127789e+02,2.297161822962582034e-01,1.100000010988609489e+01,2.883819990634874184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513220899762966098e+01,5.472028439661306720e+02,2.297450204561928278e-01,1.100000010988609489e+01,2.883674005233336467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513311808852967033e+01,5.472128439245527716e+02,2.297738571562794874e-01,1.100000010988609489e+01,2.883528019831798749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513402717942967968e+01,5.472228438829790775e+02,2.298026923965182100e-01,1.100000010988609489e+01,2.883382034430261032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513493627032968902e+01,5.472328438414095899e+02,2.298315261769089957e-01,1.100000010988609489e+01,2.883236049028723314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513584536122969837e+01,5.472428437998444224e+02,2.298603584974518166e-01,1.100000010988609489e+01,2.883090063627185597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513675445212970772e+01,5.472528437582834613e+02,2.298891893581467005e-01,1.100000010988609489e+01,2.882944078225647879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513766354302971706e+01,5.472628437167267066e+02,2.299180187589936197e-01,1.100000010988609489e+01,2.882798092824110162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513857263392972641e+01,5.472728436751741583e+02,2.299468466999926020e-01,1.100000010988609489e+01,2.882652107422572444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.513948172482973575e+01,5.472828436336258164e+02,2.299756731811436472e-01,1.100000010988609489e+01,2.882506122021034727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514039081572974510e+01,5.472928435920816810e+02,2.300044982024467277e-01,1.100000010988609489e+01,2.882360136619497009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514129990662975445e+01,5.473028435505417519e+02,2.300333217639018712e-01,1.100000010988609489e+01,2.882214151217959291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514220899752976379e+01,5.473128435090060293e+02,2.300621438655090500e-01,1.100000010988609489e+01,2.882068165816421574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514311808842977314e+01,5.473228434674745131e+02,2.300909645072682919e-01,1.100000010988609489e+01,2.881922180414883856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514402717932978248e+01,5.473328434259472033e+02,2.301197836891795689e-01,1.100000010988609489e+01,2.881776195013346139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514493627022979183e+01,5.473428433844240999e+02,2.301486014112428813e-01,1.100000010988609489e+01,2.881630209611808421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514584536112980118e+01,5.473528433429052029e+02,2.301774176734582567e-01,1.100000010988609489e+01,2.881484224210270704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514675445202981052e+01,5.473628433013905124e+02,2.302062324758256673e-01,1.100000010988609489e+01,2.881338238808732986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514766354292981987e+01,5.473728432598800282e+02,2.302350458183451132e-01,1.100000010988609489e+01,2.881192253407195269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514857263382982921e+01,5.473828432183737505e+02,2.302638577010166221e-01,1.100000010988609489e+01,2.881046268005657551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.514948172472983856e+01,5.473928431768716791e+02,2.302926681238401663e-01,1.100000010988609489e+01,2.880900282604119834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515039081562984791e+01,5.474028431353738142e+02,2.303214770868157457e-01,1.100000010988609489e+01,2.880754297202582116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515129990652985725e+01,5.474128430938801557e+02,2.303502845899433882e-01,1.100000010988609489e+01,2.880608311801044399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515220899742986660e+01,5.474228430523907036e+02,2.303790906332230659e-01,1.100000010988609489e+01,2.880462326399506681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515311808832987595e+01,5.474328430109054580e+02,2.304078952166547789e-01,1.100000010988609489e+01,2.880316340997968964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515402717922988529e+01,5.474428429694244187e+02,2.304366983402385272e-01,1.100000010988609489e+01,2.880170355596431246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515493627012989464e+01,5.474528429279475858e+02,2.304655000039743107e-01,1.100000010988609489e+01,2.880024370194893529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515584536102990398e+01,5.474628428864749594e+02,2.304943002078621572e-01,1.100000010988609489e+01,2.879878384793355811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515675445192991333e+01,5.474728428450065394e+02,2.305230989519020390e-01,1.100000010988609489e+01,2.879732399391818094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515766354282992268e+01,5.474828428035423258e+02,2.305518962360939561e-01,1.100000010988609489e+01,2.879586413990280376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515857263372993202e+01,5.474928427620823186e+02,2.305806920604379084e-01,1.100000010988609489e+01,2.879440428588742659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.515948172462994137e+01,5.475028427206265178e+02,2.306094864249338960e-01,1.100000010988609489e+01,2.879294443187204941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516039081552995071e+01,5.475128426791748097e+02,2.306382793295819189e-01,1.100000010988609489e+01,2.879148457785667223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516129990642996006e+01,5.475228426377273081e+02,2.306670707743819770e-01,1.100000010988609489e+01,2.879002472384129506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516220899732996941e+01,5.475328425962840129e+02,2.306958607593340704e-01,1.100000010988609489e+01,2.878856486982591788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516311808822997875e+01,5.475428425548449241e+02,2.307246492844381991e-01,1.100000010988609489e+01,2.878710501581054071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516402717912998810e+01,5.475528425134100416e+02,2.307534363496943630e-01,1.100000010988609489e+01,2.878564516179516353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516493627002999744e+01,5.475628424719793657e+02,2.307822219551025622e-01,1.100000010988609489e+01,2.878418530777978636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516584536093000679e+01,5.475728424305528961e+02,2.308110061006627967e-01,1.100000010988609489e+01,2.878272545376440918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516675445183001614e+01,5.475828423891306329e+02,2.308397887863750664e-01,1.100000010988609489e+01,2.878126559974903201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516766354273002548e+01,5.475928423477125762e+02,2.308685700122393436e-01,1.100000010988609489e+01,2.877980574573365483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516857263363003483e+01,5.476028423062987258e+02,2.308973497782556561e-01,1.100000010988609489e+01,2.877834589171827766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.516948172453004418e+01,5.476128422648890819e+02,2.309261280844240039e-01,1.100000010988609489e+01,2.877688603770290048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517039081543005352e+01,5.476228422234836444e+02,2.309549049307443869e-01,1.100000010988609489e+01,2.877542618368752331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517129990633006287e+01,5.476328421820824133e+02,2.309836803172168052e-01,1.100000010988609489e+01,2.877396632967214613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517220899723007221e+01,5.476428421406853886e+02,2.310124542438412309e-01,1.100000010988609489e+01,2.877250647565676896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517311808813008156e+01,5.476528420992925703e+02,2.310412267106176920e-01,1.100000010988609489e+01,2.877104662164139178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517402717903009091e+01,5.476628420579039584e+02,2.310699977175461883e-01,1.100000010988609489e+01,2.876958676762601461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517493626993010025e+01,5.476728420165195530e+02,2.310987672646267199e-01,1.100000010988609489e+01,2.876812691361063743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517584536083010960e+01,5.476828419751393540e+02,2.311275353518592590e-01,1.100000010988609489e+01,2.876666705959526026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517675445173011894e+01,5.476928419337633613e+02,2.311563019792438334e-01,1.100000010988609489e+01,2.876520720557988308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517766354263012829e+01,5.477028418923915751e+02,2.311850671467804152e-01,1.100000010988609489e+01,2.876374735156450591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517857263353013764e+01,5.477128418510239953e+02,2.312138308544690324e-01,1.100000010988609489e+01,2.876228749754912873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.517948172443014698e+01,5.477228418096605083e+02,2.312425931023096848e-01,1.100000010988609489e+01,2.876082764353375155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518039081533015633e+01,5.477328417683012276e+02,2.312713538903023447e-01,1.100000010988609489e+01,2.875936778951837438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518129990623016567e+01,5.477428417269461534e+02,2.313001132184470399e-01,1.100000010988609489e+01,2.875790793550299720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518220899713017502e+01,5.477528416855952855e+02,2.313288710867437425e-01,1.100000010988609489e+01,2.875644808148762003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518311808803018437e+01,5.477628416442486241e+02,2.313576274951924805e-01,1.100000010988609489e+01,2.875498822747224285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518402717893019371e+01,5.477728416029061691e+02,2.313863824437932259e-01,1.100000010988609489e+01,2.875352837345686568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518493626983020306e+01,5.477828415615679205e+02,2.314151359325460067e-01,1.100000010988609489e+01,2.875206851944148850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518584536073021241e+01,5.477928415202338783e+02,2.314438879614507949e-01,1.100000010988609489e+01,2.875060866542611133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518675445163022175e+01,5.478028414789040426e+02,2.314726385305075906e-01,1.100000010988609489e+01,2.874914881141073415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518766354253023110e+01,5.478128414375784132e+02,2.315013876397164216e-01,1.100000010988609489e+01,2.874768895739535698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518857263343024044e+01,5.478228413962569903e+02,2.315301352890772602e-01,1.100000010988609489e+01,2.874622910337997980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.518948172433024979e+01,5.478328413549397737e+02,2.315588814785901062e-01,1.100000010988609489e+01,2.874476924936460263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519039081523025914e+01,5.478428413136267636e+02,2.315876262082549875e-01,1.100000010988609489e+01,2.874330939534922545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519129990613026848e+01,5.478528412723178462e+02,2.316163694780718763e-01,1.100000010988609489e+01,2.874184954133384828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519220899703027783e+01,5.478628412310131353e+02,2.316451112880407726e-01,1.100000010988609489e+01,2.874038968731847110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519311808793028717e+01,5.478728411897126307e+02,2.316738516381617041e-01,1.100000010988609489e+01,2.873892983330309393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519402717883029652e+01,5.478828411484163325e+02,2.317025905284346432e-01,1.100000010988609489e+01,2.873746997928771675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519493626973030587e+01,5.478928411071242408e+02,2.317313279588595898e-01,1.100000010988609489e+01,2.873601012527233958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519584536063031521e+01,5.479028410658363555e+02,2.317600639294365439e-01,1.100000010988609489e+01,2.873455027125696240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519675445153032456e+01,5.479128410245526766e+02,2.317887984401655055e-01,1.100000010988609489e+01,2.873309041724158523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519766354243033391e+01,5.479228409832732041e+02,2.318175314910464746e-01,1.100000010988609489e+01,2.873163056322620805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519857263333034325e+01,5.479328409419979380e+02,2.318462630820794790e-01,1.100000010988609489e+01,2.873017070921083087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.519948172423035260e+01,5.479428409007268783e+02,2.318749932132644909e-01,1.100000010988609489e+01,2.872871085519545370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520039081513036194e+01,5.479528408594599114e+02,2.319037218846015103e-01,1.100000010988609489e+01,2.872725100118007652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520129990603037129e+01,5.479628408181971508e+02,2.319324490960905372e-01,1.100000010988609489e+01,2.872579114716469935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520220899693038064e+01,5.479728407769385967e+02,2.319611748477315716e-01,1.100000010988609489e+01,2.872433129314932217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520311808783038998e+01,5.479828407356842490e+02,2.319898991395246135e-01,1.100000010988609489e+01,2.872287143913394500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520402717873039933e+01,5.479928406944341077e+02,2.320186219714696629e-01,1.100000010988609489e+01,2.872141158511856782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520493626963040867e+01,5.480028406531881728e+02,2.320473433435667199e-01,1.100000010988609489e+01,2.871995173110319065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520584536053041802e+01,5.480128406119464444e+02,2.320760632558157843e-01,1.100000010988609489e+01,2.871849187708781347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520675445143042737e+01,5.480228405707089223e+02,2.321047817082168563e-01,1.100000010988609489e+01,2.871703202307243630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520766354233043671e+01,5.480328405294756067e+02,2.321334987007699080e-01,1.100000010988609489e+01,2.871557216905705912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520857263323044606e+01,5.480428404882463838e+02,2.321622142334749672e-01,1.100000010988609489e+01,2.871411231504168195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.520948172413045540e+01,5.480528404470213673e+02,2.321909283063320339e-01,1.100000010988609489e+01,2.871265246102630477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521039081503046475e+01,5.480628404058005572e+02,2.322196409193411082e-01,1.100000010988609489e+01,2.871119260701092760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521129990593047410e+01,5.480728403645839535e+02,2.322483520725021899e-01,1.100000010988609489e+01,2.870973275299555042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521220899683048344e+01,5.480828403233715562e+02,2.322770617658152792e-01,1.100000010988609489e+01,2.870827289898017325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521311808773049279e+01,5.480928402821633654e+02,2.323057699992803482e-01,1.100000010988609489e+01,2.870681304496479607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521402717863050214e+01,5.481028402409593809e+02,2.323344767728974247e-01,1.100000010988609489e+01,2.870535319094941890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521493626953051148e+01,5.481128401997594892e+02,2.323631820866665088e-01,1.100000010988609489e+01,2.870389333693404172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521584536043052083e+01,5.481228401585638039e+02,2.323918859405875725e-01,1.100000010988609489e+01,2.870243348291866455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521675445133053017e+01,5.481328401173723250e+02,2.324205883346606438e-01,1.100000010988609489e+01,2.870097362890328737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521766354223053952e+01,5.481428400761850526e+02,2.324492892688857226e-01,1.100000010988609489e+01,2.869951377488791019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521857263313054887e+01,5.481528400350019865e+02,2.324779887432627812e-01,1.100000010988609489e+01,2.869805392087253302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.521948172403055821e+01,5.481628399938231269e+02,2.325066867577918472e-01,1.100000010988609489e+01,2.869659406685715584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522039081493056756e+01,5.481728399526484736e+02,2.325353833124729208e-01,1.100000010988609489e+01,2.869513421284177867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522129990583057690e+01,5.481828399114779131e+02,2.325640784073059741e-01,1.100000010988609489e+01,2.869367435882640149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522220899673058625e+01,5.481928398703115590e+02,2.325927720422910350e-01,1.100000010988609489e+01,2.869221450481102432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522311808763059560e+01,5.482028398291494113e+02,2.326214642174280756e-01,1.100000010988609489e+01,2.869075465079564714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522402717853060494e+01,5.482128397879914701e+02,2.326501549327171237e-01,1.100000010988609489e+01,2.868929479678026997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522493626943061429e+01,5.482228397468377352e+02,2.326788441881581515e-01,1.100000010988609489e+01,2.868783494276489279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522584536033062363e+01,5.482328397056882068e+02,2.327075319837511869e-01,1.100000010988609489e+01,2.868637508874951562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522675445123063298e+01,5.482428396645428847e+02,2.327362183194962020e-01,1.100000010988609489e+01,2.868491523473413844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522766354213064233e+01,5.482528396234016554e+02,2.327649031953931968e-01,1.100000010988609489e+01,2.868345538071876127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522857263303065167e+01,5.482628395822646326e+02,2.327935866114421992e-01,1.100000010988609489e+01,2.868199552670338409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.522948172393066102e+01,5.482728395411318161e+02,2.328222685676431813e-01,1.100000010988609489e+01,2.868053567268800692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523039081483067037e+01,5.482828395000032060e+02,2.328509490639961432e-01,1.100000010988609489e+01,2.867907581867262974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523129990573067971e+01,5.482928394588788024e+02,2.328796281005011126e-01,1.100000010988609489e+01,2.867761596465725257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523220899663068906e+01,5.483028394177584914e+02,2.329083056771580618e-01,1.100000010988609489e+01,2.867615611064187539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523311808753069840e+01,5.483128393766423869e+02,2.329369817939669907e-01,1.100000010988609489e+01,2.867469625662649822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523402717843070775e+01,5.483228393355304888e+02,2.329656564509279271e-01,1.100000010988609489e+01,2.867323640261112104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523493626933071710e+01,5.483328392944227971e+02,2.329943296480408432e-01,1.100000010988609489e+01,2.867177654859574387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523584536023072644e+01,5.483428392533193119e+02,2.330230013853057391e-01,1.100000010988609489e+01,2.867031669458036669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523675445113073579e+01,5.483528392122200330e+02,2.330516716627226148e-01,1.100000010988609489e+01,2.866885684056498951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523766354203074513e+01,5.483628391711248469e+02,2.330803404802914702e-01,1.100000010988609489e+01,2.866739698654961234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523857263293075448e+01,5.483728391300338671e+02,2.331090078380123054e-01,1.100000010988609489e+01,2.866593713253423516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.523948172383076383e+01,5.483828390889470938e+02,2.331376737358851481e-01,1.100000010988609489e+01,2.866447727851885799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524039081473077317e+01,5.483928390478645269e+02,2.331663381739099705e-01,1.100000010988609489e+01,2.866301742450348081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524129990563078252e+01,5.484028390067861665e+02,2.331950011520867727e-01,1.100000010988609489e+01,2.866155757048810364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524220899653079186e+01,5.484128389657118987e+02,2.332236626704155547e-01,1.100000010988609489e+01,2.866009771647272646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524311808743080121e+01,5.484228389246418374e+02,2.332523227288963164e-01,1.100000010988609489e+01,2.865863786245734929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524402717833081056e+01,5.484328388835759824e+02,2.332809813275290578e-01,1.100000010988609489e+01,2.865717800844197211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524493626923081990e+01,5.484428388425143339e+02,2.333096384663137790e-01,1.100000010988609489e+01,2.865571815442659494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524584536013082925e+01,5.484528388014568918e+02,2.333382941452504800e-01,1.100000010988609489e+01,2.865425830041121776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524675445103083860e+01,5.484628387604035424e+02,2.333669483643391607e-01,1.100000010988609489e+01,2.865279844639584059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524766354193084794e+01,5.484728387193543995e+02,2.333956011235798211e-01,1.100000010988609489e+01,2.865133859238046341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524857263283085729e+01,5.484828386783094629e+02,2.334242524229724614e-01,1.100000010988609489e+01,2.864987873836508624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.524948172373086663e+01,5.484928386372687328e+02,2.334529022625170536e-01,1.100000010988609489e+01,2.864841888434970906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525039081463087598e+01,5.485028385962322091e+02,2.334815506422136255e-01,1.100000010988609489e+01,2.864695903033433189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525129990553088533e+01,5.485128385551997781e+02,2.335101975620621773e-01,1.100000010988609489e+01,2.864549917631895471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525220899643089467e+01,5.485228385141715535e+02,2.335388430220627087e-01,1.100000010988609489e+01,2.864403932230357754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525311808733090402e+01,5.485328384731475353e+02,2.335674870222152200e-01,1.100000010988609489e+01,2.864257946828820036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525402717823091336e+01,5.485428384321277235e+02,2.335961295625196832e-01,1.100000010988609489e+01,2.864111961427282319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525493626913092271e+01,5.485528383911121182e+02,2.336247706429761262e-01,1.100000010988609489e+01,2.863965976025744601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525584536003093206e+01,5.485628383501006056e+02,2.336534102635845489e-01,1.100000010988609489e+01,2.863819990624206883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525675445093094140e+01,5.485728383090932994e+02,2.336820484243449514e-01,1.100000010988609489e+01,2.863674005222669166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525766354183095075e+01,5.485828382680901996e+02,2.337106851252573059e-01,1.100000010988609489e+01,2.863528019821131448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525857263273096009e+01,5.485928382270913062e+02,2.337393203663216401e-01,1.100000010988609489e+01,2.863382034419593731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.525948172363096944e+01,5.486028381860965055e+02,2.337679541475379541e-01,1.100000010988609489e+01,2.863236049018056013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526039081453097879e+01,5.486128381451059113e+02,2.337965864689062201e-01,1.100000010988609489e+01,2.863090063616518296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526129990543098813e+01,5.486228381041195235e+02,2.338252173304264658e-01,1.100000010988609489e+01,2.862944078214980578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526220899633099748e+01,5.486328380631373420e+02,2.338538467320986636e-01,1.100000010988609489e+01,2.862798092813442861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526311808723100683e+01,5.486428380221592533e+02,2.338824746739228411e-01,1.100000010988609489e+01,2.862652107411905143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526402717813101617e+01,5.486528379811853711e+02,2.339111011558989706e-01,1.100000010988609489e+01,2.862506122010367426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526493626903102552e+01,5.486628379402156952e+02,2.339397261780270798e-01,1.100000010988609489e+01,2.862360136608829708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526584535993103486e+01,5.486728378992502257e+02,2.339683497403071410e-01,1.100000010988609489e+01,2.862214151207291991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526675445083104421e+01,5.486828378582888490e+02,2.339969718427391820e-01,1.100000010988609489e+01,2.862068165805754273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526766354173105356e+01,5.486928378173316787e+02,2.340255924853231750e-01,1.100000010988609489e+01,2.861922180404216556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526857263263106290e+01,5.487028377763787148e+02,2.340542116680591478e-01,1.100000010988609489e+01,2.861776195002678838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.526948172353107225e+01,5.487128377354299573e+02,2.340828293909470725e-01,1.100000010988609489e+01,2.861630209601141121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527039081443108159e+01,5.487228376944852926e+02,2.341114456539869493e-01,1.100000010988609489e+01,2.861484224199603403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527129990533109094e+01,5.487328376535448342e+02,2.341400604571788058e-01,1.100000010988609489e+01,2.861338238798065686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527220899623110029e+01,5.487428376126085823e+02,2.341686738005226143e-01,1.100000010988609489e+01,2.861192253396527968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527311808713110963e+01,5.487528375716765368e+02,2.341972856840183748e-01,1.100000010988609489e+01,2.861046267994990250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527402717803111898e+01,5.487628375307485840e+02,2.342258961076661150e-01,1.100000010988609489e+01,2.860900282593452533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527493626893112832e+01,5.487728374898248376e+02,2.342545050714658073e-01,1.100000010988609489e+01,2.860754297191914815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527584535983113767e+01,5.487828374489052976e+02,2.342831125754174515e-01,1.100000010988609489e+01,2.860608311790377098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527675445073114702e+01,5.487928374079899640e+02,2.343117186195210477e-01,1.100000010988609489e+01,2.860462326388839380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527766354163115636e+01,5.488028373670787232e+02,2.343403232037766237e-01,1.100000010988609489e+01,2.860316340987301663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527857263253116571e+01,5.488128373261716888e+02,2.343689263281841517e-01,1.100000010988609489e+01,2.860170355585763945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.527948172343117506e+01,5.488228372852688608e+02,2.343975279927436317e-01,1.100000010988609489e+01,2.860024370184226228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528039081433118440e+01,5.488328372443702392e+02,2.344261281974550637e-01,1.100000010988609489e+01,2.859878384782688510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528129990523119375e+01,5.488428372034757103e+02,2.344547269423184477e-01,1.100000010988609489e+01,2.859732399381150793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528220899613120309e+01,5.488528371625853879e+02,2.344833242273337837e-01,1.100000010988609489e+01,2.859586413979613075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528311808703121244e+01,5.488628371216992718e+02,2.345119200525010716e-01,1.100000010988609489e+01,2.859440428578075358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528402717793122179e+01,5.488728370808172485e+02,2.345405144178203116e-01,1.100000010988609489e+01,2.859294443176537640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528493626883123113e+01,5.488828370399394316e+02,2.345691073232915036e-01,1.100000010988609489e+01,2.859148457774999923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528584535973124048e+01,5.488928369990658211e+02,2.345976987689146476e-01,1.100000010988609489e+01,2.859002472373462205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528675445063124982e+01,5.489028369581964171e+02,2.346262887546897435e-01,1.100000010988609489e+01,2.858856486971924488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528766354153125917e+01,5.489128369173311057e+02,2.346548772806167915e-01,1.100000010988609489e+01,2.858710501570386770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528857263243126852e+01,5.489228368764700008e+02,2.346834643466957915e-01,1.100000010988609489e+01,2.858564516168849053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.528948172333127786e+01,5.489328368356131023e+02,2.347120499529267434e-01,1.100000010988609489e+01,2.858418530767311335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529039081423128721e+01,5.489428367947602965e+02,2.347406340993096474e-01,1.100000010988609489e+01,2.858272545365773618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529129990513129655e+01,5.489528367539116971e+02,2.347692167858445034e-01,1.100000010988609489e+01,2.858126559964235900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529220899603130590e+01,5.489628367130673041e+02,2.347977980125313113e-01,1.100000010988609489e+01,2.857980574562698182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529311808693131525e+01,5.489728366722271176e+02,2.348263777793700713e-01,1.100000010988609489e+01,2.857834589161160465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529402717783132459e+01,5.489828366313910237e+02,2.348549560863607555e-01,1.100000010988609489e+01,2.857688603759622747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529493626873133394e+01,5.489928365905591363e+02,2.348835329335033917e-01,1.100000010988609489e+01,2.857542618358085030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529584535963134329e+01,5.490028365497314553e+02,2.349121083207979799e-01,1.100000010988609489e+01,2.857396632956547312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529675445053135263e+01,5.490128365089078670e+02,2.349406822482445201e-01,1.100000010988609489e+01,2.857250647555009595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529766354143136198e+01,5.490228364680884852e+02,2.349692547158429845e-01,1.100000010988609489e+01,2.857104662153471877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529857263233137132e+01,5.490328364272733097e+02,2.349978257235934009e-01,1.100000010988609489e+01,2.856958676751934160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.529948172323138067e+01,5.490428363864622270e+02,2.350263952714957694e-01,1.100000010988609489e+01,2.856812691350396442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530039081413139002e+01,5.490528363456553507e+02,2.350549633595500620e-01,1.100000010988609489e+01,2.856666705948858725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530129990503139936e+01,5.490628363048526808e+02,2.350835299877563067e-01,1.100000010988609489e+01,2.856520720547321007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530220899593140871e+01,5.490728362640541036e+02,2.351120951561145034e-01,1.100000010988609489e+01,2.856374735145783290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530311808683141805e+01,5.490828362232597328e+02,2.351406588646246243e-01,1.100000010988609489e+01,2.856228749744245572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530402717773142740e+01,5.490928361824695685e+02,2.351692211132866972e-01,1.100000010988609489e+01,2.856082764342707855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530493626863143675e+01,5.491028361416834969e+02,2.351977819021006944e-01,1.100000010988609489e+01,2.855936778941170137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530584535953144609e+01,5.491128361009016317e+02,2.352263412310666435e-01,1.100000010988609489e+01,2.855790793539632420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530675445043145544e+01,5.491228360601239729e+02,2.352548991001845169e-01,1.100000010988609489e+01,2.855644808138094702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530766354133146478e+01,5.491328360193505205e+02,2.352834555094543423e-01,1.100000010988609489e+01,2.855498822736556985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530857263223147413e+01,5.491428359785811608e+02,2.353120104588760919e-01,1.100000010988609489e+01,2.855352837335019267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.530948172313148348e+01,5.491528359378160076e+02,2.353405639484497935e-01,1.100000010988609489e+01,2.855206851933481550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531039081403149282e+01,5.491628358970550607e+02,2.353691159781754194e-01,1.100000010988609489e+01,2.855060866531943832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531129990493150217e+01,5.491728358562982066e+02,2.353976665480529695e-01,1.100000010988609489e+01,2.854914881130406114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531220899583151152e+01,5.491828358155455589e+02,2.354262156580824716e-01,1.100000010988609489e+01,2.854768895728868397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531311808673152086e+01,5.491928357747970040e+02,2.354547633082638980e-01,1.100000010988609489e+01,2.854622910327330679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531402717763153021e+01,5.492028357340526554e+02,2.354833094985972486e-01,1.100000010988609489e+01,2.854476924925792962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531493626853153955e+01,5.492128356933125133e+02,2.355118542290825512e-01,1.100000010988609489e+01,2.854330939524255244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531584535943154890e+01,5.492228356525764639e+02,2.355403974997197780e-01,1.100000010988609489e+01,2.854184954122717527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531675445033155825e+01,5.492328356118446209e+02,2.355689393105089291e-01,1.100000010988609489e+01,2.854038968721179809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531766354123156759e+01,5.492428355711169843e+02,2.355974796614500044e-01,1.100000010988609489e+01,2.853892983319642092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531857263213157694e+01,5.492528355303934404e+02,2.356260185525430317e-01,1.100000010988609489e+01,2.853746997918104374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.531948172303158628e+01,5.492628354896741030e+02,2.356545559837879833e-01,1.100000010988609489e+01,2.853601012516566657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532039081393159563e+01,5.492728354489589719e+02,2.356830919551848591e-01,1.100000010988609489e+01,2.853455027115028939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532129990483160498e+01,5.492828354082479336e+02,2.357116264667336591e-01,1.100000010988609489e+01,2.853309041713491222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532220899573161432e+01,5.492928353675411017e+02,2.357401595184343834e-01,1.100000010988609489e+01,2.853163056311953504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532311808663162367e+01,5.493028353268384762e+02,2.357686911102870320e-01,1.100000010988609489e+01,2.853017070910415787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532402717753163301e+01,5.493128352861399435e+02,2.357972212422916047e-01,1.100000010988609489e+01,2.852871085508878069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532493626843164236e+01,5.493228352454456171e+02,2.358257499144481018e-01,1.100000010988609489e+01,2.852725100107340352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532584535933165171e+01,5.493328352047554972e+02,2.358542771267565508e-01,1.100000010988609489e+01,2.852579114705802634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532675445023166105e+01,5.493428351640694700e+02,2.358828028792169240e-01,1.100000010988609489e+01,2.852433129304264917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532766354113167040e+01,5.493528351233876492e+02,2.359113271718291938e-01,1.100000010988609489e+01,2.852287143902727199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532857263203167975e+01,5.493628350827099212e+02,2.359398500045933877e-01,1.100000010988609489e+01,2.852141158501189482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.532948172293168909e+01,5.493728350420363995e+02,2.359683713775095060e-01,1.100000010988609489e+01,2.851995173099651764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533039081383169844e+01,5.493828350013670843e+02,2.359968912905775484e-01,1.100000010988609489e+01,2.851849187698114046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533129990473170778e+01,5.493928349607018617e+02,2.360254097437975151e-01,1.100000010988609489e+01,2.851703202296576329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533220899563171713e+01,5.494028349200408456e+02,2.360539267371694061e-01,1.100000010988609489e+01,2.851557216895038611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533311808653172648e+01,5.494128348793840360e+02,2.360824422706932213e-01,1.100000010988609489e+01,2.851411231493500894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533402717743173582e+01,5.494228348387313190e+02,2.361109563443689607e-01,1.100000010988609489e+01,2.851265246091963176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533493626833174517e+01,5.494328347980828084e+02,2.361394689581966244e-01,1.100000010988609489e+01,2.851119260690425459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533584535923175451e+01,5.494428347574383906e+02,2.361679801121761846e-01,1.100000010988609489e+01,2.850973275288887741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533675445013176386e+01,5.494528347167981792e+02,2.361964898063076690e-01,1.100000010988609489e+01,2.850827289887350024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533766354103177321e+01,5.494628346761621742e+02,2.362249980405910776e-01,1.100000010988609489e+01,2.850681304485812306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533857263193178255e+01,5.494728346355302619e+02,2.362535048150264105e-01,1.100000010988609489e+01,2.850535319084274589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.533948172283179190e+01,5.494828345949025561e+02,2.362820101296136399e-01,1.100000010988609489e+01,2.850389333682736871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534039081373180125e+01,5.494928345542789430e+02,2.363105139843527935e-01,1.100000010988609489e+01,2.850243348281199154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534129990463181059e+01,5.495028345136595362e+02,2.363390163792438714e-01,1.100000010988609489e+01,2.850097362879661436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534220899553181994e+01,5.495128344730443359e+02,2.363675173142868458e-01,1.100000010988609489e+01,2.849951377478123719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534311808643182928e+01,5.495228344324332284e+02,2.363960167894817443e-01,1.100000010988609489e+01,2.849805392076586001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534402717733183863e+01,5.495328343918263272e+02,2.364245148048285672e-01,1.100000010988609489e+01,2.849659406675048284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534493626823184798e+01,5.495428343512235188e+02,2.364530113603272865e-01,1.100000010988609489e+01,2.849513421273510566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534584535913185732e+01,5.495528343106249167e+02,2.364815064559779301e-01,1.100000010988609489e+01,2.849367435871972849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534675445003186667e+01,5.495628342700305211e+02,2.365100000917804701e-01,1.100000010988609489e+01,2.849221450470435131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534766354093187601e+01,5.495728342294402182e+02,2.365384922677349344e-01,1.100000010988609489e+01,2.849075465068897414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534857263183188536e+01,5.495828341888541217e+02,2.365669829838412952e-01,1.100000010988609489e+01,2.848929479667359696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.534948172273189471e+01,5.495928341482721180e+02,2.365954722400995802e-01,1.100000010988609489e+01,2.848783494265821978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535039081363190405e+01,5.496028341076943207e+02,2.366239600365097617e-01,1.100000010988609489e+01,2.848637508864284261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535129990453191340e+01,5.496128340671206161e+02,2.366524463730718397e-01,1.100000010988609489e+01,2.848491523462746543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535220899543192274e+01,5.496228340265511179e+02,2.366809312497858420e-01,1.100000010988609489e+01,2.848345538061208826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535311808633193209e+01,5.496328339859858261e+02,2.367094146666517407e-01,1.100000010988609489e+01,2.848199552659671108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535402717723194144e+01,5.496428339454246270e+02,2.367378966236695637e-01,1.100000010988609489e+01,2.848053567258133391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535493626813195078e+01,5.496528339048676344e+02,2.367663771208392831e-01,1.100000010988609489e+01,2.847907581856595673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535584535903196013e+01,5.496628338643147345e+02,2.367948561581608991e-01,1.100000010988609489e+01,2.847761596455057956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535675444993196948e+01,5.496728338237660410e+02,2.368233337356344392e-01,1.100000010988609489e+01,2.847615611053520238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535766354083197882e+01,5.496828337832214402e+02,2.368518098532598759e-01,1.100000010988609489e+01,2.847469625651982521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535857263173198817e+01,5.496928337426810458e+02,2.368802845110372091e-01,1.100000010988609489e+01,2.847323640250444803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.535948172263199751e+01,5.497028337021448579e+02,2.369087577089664387e-01,1.100000010988609489e+01,2.847177654848907086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536039081353200686e+01,5.497128336616127626e+02,2.369372294470475648e-01,1.100000010988609489e+01,2.847031669447369368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536129990443201621e+01,5.497228336210848738e+02,2.369656997252806152e-01,1.100000010988609489e+01,2.846885684045831651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536220899533202555e+01,5.497328335805610777e+02,2.369941685436655621e-01,1.100000010988609489e+01,2.846739698644293933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536311808623203490e+01,5.497428335400414880e+02,2.370226359022024054e-01,1.100000010988609489e+01,2.846593713242756216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536402717713204424e+01,5.497528334995259911e+02,2.370511018008911452e-01,1.100000010988609489e+01,2.846447727841218498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536493626803205359e+01,5.497628334590147006e+02,2.370795662397317816e-01,1.100000010988609489e+01,2.846301742439680781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536584535893206294e+01,5.497728334185076164e+02,2.371080292187243144e-01,1.100000010988609489e+01,2.846155757038143063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536675444983207228e+01,5.497828333780046250e+02,2.371364907378687437e-01,1.100000010988609489e+01,2.846009771636605346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536766354073208163e+01,5.497928333375058401e+02,2.371649507971650694e-01,1.100000010988609489e+01,2.845863786235067628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536857263163209097e+01,5.498028332970111478e+02,2.371934093966132917e-01,1.100000010988609489e+01,2.845717800833529910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.536948172253210032e+01,5.498128332565206620e+02,2.372218665362134105e-01,1.100000010988609489e+01,2.845571815431992193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537039081343210967e+01,5.498228332160342688e+02,2.372503222159654257e-01,1.100000010988609489e+01,2.845425830030454475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537129990433211901e+01,5.498328331755520821e+02,2.372787764358693374e-01,1.100000010988609489e+01,2.845279844628916758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537220899523212836e+01,5.498428331350739882e+02,2.373072291959251456e-01,1.100000010988609489e+01,2.845133859227379040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537311808613213771e+01,5.498528330946001006e+02,2.373356804961328503e-01,1.100000010988609489e+01,2.844987873825841323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537402717703214705e+01,5.498628330541303058e+02,2.373641303364924515e-01,1.100000010988609489e+01,2.844841888424303605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537493626793215640e+01,5.498728330136647173e+02,2.373925787170039492e-01,1.100000010988609489e+01,2.844695903022765888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537584535883216574e+01,5.498828329732032216e+02,2.374210256376673156e-01,1.100000010988609489e+01,2.844549917621228170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537675444973217509e+01,5.498928329327459323e+02,2.374494710984825785e-01,1.100000010988609489e+01,2.844403932219690453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537766354063218444e+01,5.499028328922927358e+02,2.374779150994497379e-01,1.100000010988609489e+01,2.844257946818152735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537857263153219378e+01,5.499128328518437456e+02,2.375063576405687937e-01,1.100000010988609489e+01,2.844111961416615018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.537948172243220313e+01,5.499228328113989619e+02,2.375347987218397461e-01,1.100000010988609489e+01,2.843965976015077300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538039081333221247e+01,5.499328327709582709e+02,2.375632383432625672e-01,1.100000010988609489e+01,2.843819990613539583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538129990423222182e+01,5.499428327305217863e+02,2.375916765048372847e-01,1.100000010988609489e+01,2.843674005212001865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538220899513223117e+01,5.499528326900893944e+02,2.376201132065638988e-01,1.100000010988609489e+01,2.843528019810464148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538311808603224051e+01,5.499628326496612090e+02,2.376485484484423816e-01,1.100000010988609489e+01,2.843382034408926430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538402717693224986e+01,5.499728326092371162e+02,2.376769822304727608e-01,1.100000010988609489e+01,2.843236049007388713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538493626783225920e+01,5.499828325688172299e+02,2.377054145526550366e-01,1.100000010988609489e+01,2.843090063605850995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538584535873226855e+01,5.499928325284014363e+02,2.377338454149891811e-01,1.100000010988609489e+01,2.842944078204313278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538675444963227790e+01,5.500028324879898491e+02,2.377622748174752221e-01,1.100000010988609489e+01,2.842798092802775560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538766354053228724e+01,5.500128324475823547e+02,2.377907027601131318e-01,1.100000010988609489e+01,2.842652107401237842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538857263143229659e+01,5.500228324071790666e+02,2.378191292429029380e-01,1.100000010988609489e+01,2.842506121999700125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.538948172233230594e+01,5.500328323667798713e+02,2.378475542658446129e-01,1.100000010988609489e+01,2.842360136598162407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539039081323231528e+01,5.500428323263848824e+02,2.378759778289381843e-01,1.100000010988609489e+01,2.842214151196624690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539129990413232463e+01,5.500528322859939863e+02,2.379043999321836245e-01,1.100000010988609489e+01,2.842068165795086972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539220899503233397e+01,5.500628322456072965e+02,2.379328205755809611e-01,1.100000010988609489e+01,2.841922180393549255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539311808593234332e+01,5.500728322052246995e+02,2.379612397591301665e-01,1.100000010988609489e+01,2.841776194992011537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539402717683235267e+01,5.500828321648463088e+02,2.379896574828312406e-01,1.100000010988609489e+01,2.841630209590473820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539493626773236201e+01,5.500928321244720109e+02,2.380180737466842111e-01,1.100000010988609489e+01,2.841484224188936102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539584535863237136e+01,5.501028320841019195e+02,2.380464885506890504e-01,1.100000010988609489e+01,2.841338238787398385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539675444953238070e+01,5.501128320437359207e+02,2.380749018948457862e-01,1.100000010988609489e+01,2.841192253385860667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539766354043239005e+01,5.501228320033741284e+02,2.381033137791543908e-01,1.100000010988609489e+01,2.841046267984322950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539857263133239940e+01,5.501328319630164287e+02,2.381317242036148640e-01,1.100000010988609489e+01,2.840900282582785232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.539948172223240874e+01,5.501428319226629355e+02,2.381601331682272060e-01,1.100000010988609489e+01,2.840754297181247515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540039081313241809e+01,5.501528318823135351e+02,2.381885406729914445e-01,1.100000010988609489e+01,2.840608311779709797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540129990403242743e+01,5.501628318419683410e+02,2.382169467179075517e-01,1.100000010988609489e+01,2.840462326378172080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540220899493243678e+01,5.501728318016272397e+02,2.382453513029755277e-01,1.100000010988609489e+01,2.840316340976634362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540311808583244613e+01,5.501828317612902310e+02,2.382737544281953723e-01,1.100000010988609489e+01,2.840170355575096645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540402717673245547e+01,5.501928317209574288e+02,2.383021560935670857e-01,1.100000010988609489e+01,2.840024370173558927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540493626763246482e+01,5.502028316806287194e+02,2.383305562990906679e-01,1.100000010988609489e+01,2.839878384772021210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540584535853247417e+01,5.502128316403042163e+02,2.383589550447661465e-01,1.100000010988609489e+01,2.839732399370483492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540675444943248351e+01,5.502228315999838060e+02,2.383873523305934938e-01,1.100000010988609489e+01,2.839586413968945774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540766354033249286e+01,5.502328315596676021e+02,2.384157481565727099e-01,1.100000010988609489e+01,2.839440428567408057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540857263123250220e+01,5.502428315193554909e+02,2.384441425227037947e-01,1.100000010988609489e+01,2.839294443165870339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.540948172213251155e+01,5.502528314790475861e+02,2.384725354289867483e-01,1.100000010988609489e+01,2.839148457764332622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541039081303252090e+01,5.502628314387437740e+02,2.385009268754215705e-01,1.100000010988609489e+01,2.839002472362794904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541129990393253024e+01,5.502728313984441684e+02,2.385293168620082616e-01,1.100000010988609489e+01,2.838856486961257187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541220899483253959e+01,5.502828313581486555e+02,2.385577053887468213e-01,1.100000010988609489e+01,2.838710501559719469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541311808573254893e+01,5.502928313178573489e+02,2.385860924556372498e-01,1.100000010988609489e+01,2.838564516158181752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541402717663255828e+01,5.503028312775701352e+02,2.386144780626795470e-01,1.100000010988609489e+01,2.838418530756644034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541493626753256763e+01,5.503128312372870141e+02,2.386428622098736851e-01,1.100000010988609489e+01,2.838272545355106317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541584535843257697e+01,5.503228311970080995e+02,2.386712448972196920e-01,1.100000010988609489e+01,2.838126559953568599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541675444933258632e+01,5.503328311567332776e+02,2.386996261247175677e-01,1.100000010988609489e+01,2.837980574552030882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541766354023259566e+01,5.503428311164626621e+02,2.387280058923673121e-01,1.100000010988609489e+01,2.837834589150493164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541857263113260501e+01,5.503528310761961393e+02,2.387563842001689252e-01,1.100000010988609489e+01,2.837688603748955447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.541948172203261436e+01,5.503628310359338229e+02,2.387847610481224070e-01,1.100000010988609489e+01,2.837542618347417729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542039081293262370e+01,5.503728309956755993e+02,2.388131364362277298e-01,1.100000010988609489e+01,2.837396632945880012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542129990383263305e+01,5.503828309554215821e+02,2.388415103644849213e-01,1.100000010988609489e+01,2.837250647544342294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542220899473264240e+01,5.503928309151716576e+02,2.388698828328939816e-01,1.100000010988609489e+01,2.837104662142804577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542311808563265174e+01,5.504028308749258258e+02,2.388982538414548829e-01,1.100000010988609489e+01,2.836958676741266859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542402717653266109e+01,5.504128308346842005e+02,2.389266233901676528e-01,1.100000010988609489e+01,2.836812691339729142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542493626743267043e+01,5.504228307944466678e+02,2.389549914790322915e-01,1.100000010988609489e+01,2.836666705938191424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542584535833267978e+01,5.504328307542133416e+02,2.389833581080487712e-01,1.100000010988609489e+01,2.836520720536653706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542675444923268913e+01,5.504428307139841081e+02,2.390117232772171196e-01,1.100000010988609489e+01,2.836374735135115989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542766354013269847e+01,5.504528306737590810e+02,2.390400869865373368e-01,1.100000010988609489e+01,2.836228749733578271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542857263103270782e+01,5.504628306335381467e+02,2.390684492360093949e-01,1.100000010988609489e+01,2.836082764332040554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.542948172193271716e+01,5.504728305933213051e+02,2.390968100256333218e-01,1.100000010988609489e+01,2.835936778930502836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543039081283272651e+01,5.504828305531086698e+02,2.391251693554090896e-01,1.100000010988609489e+01,2.835790793528965119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543129990373273586e+01,5.504928305129001274e+02,2.391535272253367261e-01,1.100000010988609489e+01,2.835644808127427401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543220899463274520e+01,5.505028304726957913e+02,2.391818836354162037e-01,1.100000010988609489e+01,2.835498822725889684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543311808553275455e+01,5.505128304324955479e+02,2.392102385856475499e-01,1.100000010988609489e+01,2.835352837324351966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543402717643276389e+01,5.505228303922993973e+02,2.392385920760307372e-01,1.100000010988609489e+01,2.835206851922814249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543493626733277324e+01,5.505328303521074531e+02,2.392669441065657931e-01,1.100000010988609489e+01,2.835060866521276531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543584535823278259e+01,5.505428303119196016e+02,2.392952946772526901e-01,1.100000010988609489e+01,2.834914881119738814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543675444913279193e+01,5.505528302717359566e+02,2.393236437880914280e-01,1.100000010988609489e+01,2.834768895718201096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543766354003280128e+01,5.505628302315564042e+02,2.393519914390820347e-01,1.100000010988609489e+01,2.834622910316663379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543857263093281063e+01,5.505728301913809446e+02,2.393803376302244823e-01,1.100000010988609489e+01,2.834476924915125661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.543948172183281997e+01,5.505828301512096914e+02,2.394086823615187709e-01,1.100000010988609489e+01,2.834330939513587944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544039081273282932e+01,5.505928301110425309e+02,2.394370256329649282e-01,1.100000010988609489e+01,2.834184954112050226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544129990363283866e+01,5.506028300708795769e+02,2.394653674445629266e-01,1.100000010988609489e+01,2.834038968710512509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544220899453284801e+01,5.506128300307207155e+02,2.394937077963127658e-01,1.100000010988609489e+01,2.833892983308974791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544311808543285736e+01,5.506228299905659469e+02,2.395220466882144461e-01,1.100000010988609489e+01,2.833746997907437074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544402717633286670e+01,5.506328299504153847e+02,2.395503841202679673e-01,1.100000010988609489e+01,2.833601012505899356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544493626723287605e+01,5.506428299102689152e+02,2.395787200924733573e-01,1.100000010988609489e+01,2.833455027104361638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544584535813288539e+01,5.506528298701266522e+02,2.396070546048305883e-01,1.100000010988609489e+01,2.833309041702823921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544675444903289474e+01,5.506628298299884818e+02,2.396353876573396602e-01,1.100000010988609489e+01,2.833163056301286203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544766353993290409e+01,5.506728297898544042e+02,2.396637192500005731e-01,1.100000010988609489e+01,2.833017070899748486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544857263083291343e+01,5.506828297497245330e+02,2.396920493828133270e-01,1.100000010988609489e+01,2.832871085498210768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.544948172173292278e+01,5.506928297095987546e+02,2.397203780557779218e-01,1.100000010988609489e+01,2.832725100096673051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545039081263293212e+01,5.507028296694770688e+02,2.397487052688943576e-01,1.100000010988609489e+01,2.832579114695135333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545129990353294147e+01,5.507128296293595895e+02,2.397770310221626344e-01,1.100000010988609489e+01,2.832433129293597616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545220899443295082e+01,5.507228295892462029e+02,2.398053553155827522e-01,1.100000010988609489e+01,2.832287143892059898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545311808533296016e+01,5.507328295491370227e+02,2.398336781491547109e-01,1.100000010988609489e+01,2.832141158490522181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545402717623296951e+01,5.507428295090319352e+02,2.398619995228785107e-01,1.100000010988609489e+01,2.831995173088984463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545493626713297886e+01,5.507528294689309405e+02,2.398903194367541514e-01,1.100000010988609489e+01,2.831849187687446746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545584535803298820e+01,5.507628294288341522e+02,2.399186378907816330e-01,1.100000010988609489e+01,2.831703202285909028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545675444893299755e+01,5.507728293887414566e+02,2.399469548849609557e-01,1.100000010988609489e+01,2.831557216884371311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545766353983300689e+01,5.507828293486528537e+02,2.399752704192921193e-01,1.100000010988609489e+01,2.831411231482833593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545857263073301624e+01,5.507928293085684572e+02,2.400035844937751239e-01,1.100000010988609489e+01,2.831265246081295876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.545948172163302559e+01,5.508028292684881535e+02,2.400318971084099418e-01,1.100000010988609489e+01,2.831119260679758158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546039081253303493e+01,5.508128292284119425e+02,2.400602082631966006e-01,1.100000010988609489e+01,2.830973275278220441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546129990343304428e+01,5.508228291883399379e+02,2.400885179581351003e-01,1.100000010988609489e+01,2.830827289876682723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546220899433305362e+01,5.508328291482720260e+02,2.401168261932254411e-01,1.100000010988609489e+01,2.830681304475145006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546311808523306297e+01,5.508428291082083206e+02,2.401451329684675950e-01,1.100000010988609489e+01,2.830535319073607288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546402717613307232e+01,5.508528290681487078e+02,2.401734382838615900e-01,1.100000010988609489e+01,2.830389333672069570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546493626703308166e+01,5.508628290280931878e+02,2.402017421394074259e-01,1.100000010988609489e+01,2.830243348270531853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546584535793309101e+01,5.508728289880418743e+02,2.402300445351051028e-01,1.100000010988609489e+01,2.830097362868994135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546675444883310035e+01,5.508828289479946534e+02,2.402583454709545929e-01,1.100000010988609489e+01,2.829951377467456418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546766353973310970e+01,5.508928289079515253e+02,2.402866449469559240e-01,1.100000010988609489e+01,2.829805392065918700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546857263063311905e+01,5.509028288679126035e+02,2.403149429631090683e-01,1.100000010988609489e+01,2.829659406664380983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.546948172153312839e+01,5.509128288278777745e+02,2.403432395194140536e-01,1.100000010988609489e+01,2.829513421262843265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547039081243313774e+01,5.509228287878470383e+02,2.403715346158708799e-01,1.100000010988609489e+01,2.829367435861305548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547129990333314709e+01,5.509328287478205084e+02,2.403998282524795194e-01,1.100000010988609489e+01,2.829221450459767830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547220899423315643e+01,5.509428287077980713e+02,2.404281204292399998e-01,1.100000010988609489e+01,2.829075465058230113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547311808513316578e+01,5.509528286677797269e+02,2.404564111461522935e-01,1.100000010988609489e+01,2.828929479656692395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547402717603317512e+01,5.509628286277655889e+02,2.404847004032164282e-01,1.100000010988609489e+01,2.828783494255154678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547493626693318447e+01,5.509728285877555436e+02,2.405129882004323760e-01,1.100000010988609489e+01,2.828637508853616960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547584535783319382e+01,5.509828285477495911e+02,2.405412745378001371e-01,1.100000010988609489e+01,2.828491523452079243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547675444873320316e+01,5.509928285077478449e+02,2.405695594153197392e-01,1.100000010988609489e+01,2.828345538050541525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547766353963321251e+01,5.510028284677501915e+02,2.405978428329911545e-01,1.100000010988609489e+01,2.828199552649003808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547857263053322185e+01,5.510128284277566308e+02,2.406261247908144107e-01,1.100000010988609489e+01,2.828053567247466090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.547948172143323120e+01,5.510228283877672766e+02,2.406544052887894802e-01,1.100000010988609489e+01,2.827907581845928373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548039081233324055e+01,5.510328283477820150e+02,2.406826843269163629e-01,1.100000010988609489e+01,2.827761596444390655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548129990323324989e+01,5.510428283078008462e+02,2.407109619051950866e-01,1.100000010988609489e+01,2.827615611042852937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548220899413325924e+01,5.510528282678237701e+02,2.407392380236256235e-01,1.100000010988609489e+01,2.827469625641315220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548311808503326858e+01,5.510628282278509005e+02,2.407675126822079736e-01,1.100000010988609489e+01,2.827323640239777502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548402717593327793e+01,5.510728281878821235e+02,2.407957858809421370e-01,1.100000010988609489e+01,2.827177654838239785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548493626683328728e+01,5.510828281479174393e+02,2.408240576198281413e-01,1.100000010988609489e+01,2.827031669436702067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548584535773329662e+01,5.510928281079569615e+02,2.408523278988659588e-01,1.100000010988609489e+01,2.826885684035164350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548675444863330597e+01,5.511028280680005764e+02,2.408805967180555896e-01,1.100000010988609489e+01,2.826739698633626632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548766353953331532e+01,5.511128280280482841e+02,2.409088640773970336e-01,1.100000010988609489e+01,2.826593713232088915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548857263043332466e+01,5.511228279881001981e+02,2.409371299768902908e-01,1.100000010988609489e+01,2.826447727830551197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.548948172133333401e+01,5.511328279481562049e+02,2.409653944165353612e-01,1.100000010988609489e+01,2.826301742429013480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549039081223334335e+01,5.511428279082163044e+02,2.409936573963322448e-01,1.100000010988609489e+01,2.826155757027475762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549129990313335270e+01,5.511528278682804967e+02,2.410219189162809417e-01,1.100000010988609489e+01,2.826009771625938045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549220899403336205e+01,5.511628278283488953e+02,2.410501789763814795e-01,1.100000010988609489e+01,2.825863786224400327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549311808493337139e+01,5.511728277884213867e+02,2.410784375766338306e-01,1.100000010988609489e+01,2.825717800822862610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549402717583338074e+01,5.511828277484979708e+02,2.411066947170379948e-01,1.100000010988609489e+01,2.825571815421324892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549493626673339008e+01,5.511928277085787613e+02,2.411349503975939723e-01,1.100000010988609489e+01,2.825425830019787175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549584535763339943e+01,5.512028276686636445e+02,2.411632046183017353e-01,1.100000010988609489e+01,2.825279844618249457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549675444853340878e+01,5.512128276287526205e+02,2.411914573791613114e-01,1.100000010988609489e+01,2.825133859216711740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549766353943341812e+01,5.512228275888456892e+02,2.412197086801727008e-01,1.100000010988609489e+01,2.824987873815174022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549857263033342747e+01,5.512328275489429643e+02,2.412479585213359035e-01,1.100000010988609489e+01,2.824841888413636305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.549948172123343682e+01,5.512428275090443321e+02,2.412762069026509193e-01,1.100000010988609489e+01,2.824695903012098587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550039081213344616e+01,5.512528274691497927e+02,2.413044538241177484e-01,1.100000010988609489e+01,2.824549917610560869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550129990303345551e+01,5.512628274292594597e+02,2.413326992857363906e-01,1.100000010988609489e+01,2.824403932209023152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550220899393346485e+01,5.512728273893732194e+02,2.413609432875068461e-01,1.100000010988609489e+01,2.824257946807485434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550311808483347420e+01,5.512828273494910718e+02,2.413891858294290871e-01,1.100000010988609489e+01,2.824111961405947717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550402717573348355e+01,5.512928273096130170e+02,2.414174269115031413e-01,1.100000010988609489e+01,2.823965976004409999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550493626663349289e+01,5.513028272697391685e+02,2.414456665337290087e-01,1.100000010988609489e+01,2.823819990602872282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550584535753350224e+01,5.513128272298694128e+02,2.414739046961066893e-01,1.100000010988609489e+01,2.823674005201334564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550675444843351158e+01,5.513228271900037498e+02,2.415021413986361554e-01,1.100000010988609489e+01,2.823528019799796847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550766353933352093e+01,5.513328271501421796e+02,2.415303766413174347e-01,1.100000010988609489e+01,2.823382034398259129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550857263023353028e+01,5.513428271102848157e+02,2.415586104241505272e-01,1.100000010988609489e+01,2.823236048996721412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.550948172113353962e+01,5.513528270704315446e+02,2.415868427471354052e-01,1.100000010988609489e+01,2.823090063595183694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551039081203354897e+01,5.513628270305823662e+02,2.416150736102720964e-01,1.100000010988609489e+01,2.822944078193645977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551129990293355831e+01,5.513728269907372805e+02,2.416433030135605731e-01,1.100000010988609489e+01,2.822798092792108259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551220899383356766e+01,5.513828269508964013e+02,2.416715309570008630e-01,1.100000010988609489e+01,2.822652107390570542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551311808473357701e+01,5.513928269110596148e+02,2.416997574405929383e-01,1.100000010988609489e+01,2.822506121989032824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551402717563358635e+01,5.514028268712269210e+02,2.417279824643368269e-01,1.100000010988609489e+01,2.822360136587495107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551493626653359570e+01,5.514128268313983199e+02,2.417562060282325009e-01,1.100000010988609489e+01,2.822214151185957389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551584535743360505e+01,5.514228267915739252e+02,2.417844281322799882e-01,1.100000010988609489e+01,2.822068165784419672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551675444833361439e+01,5.514328267517536233e+02,2.418126487764792609e-01,1.100000010988609489e+01,2.821922180382881954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551766353923362374e+01,5.514428267119374141e+02,2.418408679608303469e-01,1.100000010988609489e+01,2.821776194981344237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551857263013363308e+01,5.514528266721252976e+02,2.418690856853332183e-01,1.100000010988609489e+01,2.821630209579806519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.551948172103364243e+01,5.514628266323173875e+02,2.418973019499879029e-01,1.100000010988609489e+01,2.821484224178268801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552039081193365178e+01,5.514728265925135702e+02,2.419255167547943730e-01,1.100000010988609489e+01,2.821338238776731084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552129990283366112e+01,5.514828265527138456e+02,2.419537300997526286e-01,1.100000010988609489e+01,2.821192253375193366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552220899373367047e+01,5.514928265129182137e+02,2.419819419848626973e-01,1.100000010988609489e+01,2.821046267973655649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552311808463367981e+01,5.515028264731266745e+02,2.420101524101245516e-01,1.100000010988609489e+01,2.820900282572117931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552402717553368916e+01,5.515128264333393417e+02,2.420383613755381913e-01,1.100000010988609489e+01,2.820754297170580214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552493626643369851e+01,5.515228263935561017e+02,2.420665688811036442e-01,1.100000010988609489e+01,2.820608311769042496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552584535733370785e+01,5.515328263537769544e+02,2.420947749268208826e-01,1.100000010988609489e+01,2.820462326367504779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552675444823371720e+01,5.515428263140018998e+02,2.421229795126899065e-01,1.100000010988609489e+01,2.820316340965967061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552766353913372654e+01,5.515528262742310517e+02,2.421511826387107158e-01,1.100000010988609489e+01,2.820170355564429344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552857263003373589e+01,5.515628262344642962e+02,2.421793843048833106e-01,1.100000010988609489e+01,2.820024370162891626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.552948172093374524e+01,5.515728261947016335e+02,2.422075845112077186e-01,1.100000010988609489e+01,2.819878384761353909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553039081183375458e+01,5.515828261549430636e+02,2.422357832576839121e-01,1.100000010988609489e+01,2.819732399359816191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553129990273376393e+01,5.515928261151885863e+02,2.422639805443118910e-01,1.100000010988609489e+01,2.819586413958278474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553220899363377328e+01,5.516028260754383155e+02,2.422921763710916554e-01,1.100000010988609489e+01,2.819440428556740756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553311808453378262e+01,5.516128260356921373e+02,2.423203707380232053e-01,1.100000010988609489e+01,2.819294443155203039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553402717543379197e+01,5.516228259959500519e+02,2.423485636451065406e-01,1.100000010988609489e+01,2.819148457753665321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553493626633380131e+01,5.516328259562120593e+02,2.423767550923416614e-01,1.100000010988609489e+01,2.819002472352127604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553584535723381066e+01,5.516428259164781593e+02,2.424049450797285676e-01,1.100000010988609489e+01,2.818856486950589886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553675444813382001e+01,5.516528258767484658e+02,2.424331336072672594e-01,1.100000010988609489e+01,2.818710501549052169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553766353903382935e+01,5.516628258370228650e+02,2.424613206749577365e-01,1.100000010988609489e+01,2.818564516147514451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553857262993383870e+01,5.516728257973013569e+02,2.424895062827999992e-01,1.100000010988609489e+01,2.818418530745976733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.553948172083384804e+01,5.516828257575839416e+02,2.425176904307940473e-01,1.100000010988609489e+01,2.818272545344439016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554039081173385739e+01,5.516928257178706190e+02,2.425458731189398809e-01,1.100000010988609489e+01,2.818126559942901298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554129990263386674e+01,5.517028256781615028e+02,2.425740543472374999e-01,1.100000010988609489e+01,2.817980574541363581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554220899353387608e+01,5.517128256384564793e+02,2.426022341156868767e-01,1.100000010988609489e+01,2.817834589139825863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554311808443388543e+01,5.517228255987555485e+02,2.426304124242880389e-01,1.100000010988609489e+01,2.817688603738288146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554402717533389477e+01,5.517328255590587105e+02,2.426585892730409866e-01,1.100000010988609489e+01,2.817542618336750428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554493626623390412e+01,5.517428255193659652e+02,2.426867646619457197e-01,1.100000010988609489e+01,2.817396632935212711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554584535713391347e+01,5.517528254796774263e+02,2.427149385910022383e-01,1.100000010988609489e+01,2.817250647533674993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554675444803392281e+01,5.517628254399929801e+02,2.427431110602105147e-01,1.100000010988609489e+01,2.817104662132137276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554766353893393216e+01,5.517728254003126267e+02,2.427712820695705764e-01,1.100000010988609489e+01,2.816958676730599558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554857262983394151e+01,5.517828253606363660e+02,2.427994516190824237e-01,1.100000010988609489e+01,2.816812691329061841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.554948172073395085e+01,5.517928253209641980e+02,2.428276197087460286e-01,1.100000010988609489e+01,2.816666705927524123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555039081163396020e+01,5.518028252812961227e+02,2.428557863385614191e-01,1.100000010988609489e+01,2.816520720525986406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555129990253396954e+01,5.518128252416322539e+02,2.428839515085285949e-01,1.100000010988609489e+01,2.816374735124448688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555220899343397889e+01,5.518228252019724778e+02,2.429121152186475285e-01,1.100000010988609489e+01,2.816228749722910971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555311808433398824e+01,5.518328251623167944e+02,2.429402774689182476e-01,1.100000010988609489e+01,2.816082764321373253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555402717523399758e+01,5.518428251226652037e+02,2.429684382593407244e-01,1.100000010988609489e+01,2.815936778919835536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555493626613400693e+01,5.518528250830177058e+02,2.429965975899149866e-01,1.100000010988609489e+01,2.815790793518297818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555584535703401627e+01,5.518628250433743005e+02,2.430247554606410343e-01,1.100000010988609489e+01,2.815644808116760101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555675444793402562e+01,5.518728250037351017e+02,2.430529118715188397e-01,1.100000010988609489e+01,2.815498822715222383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555766353883403497e+01,5.518828249640999957e+02,2.430810668225484306e-01,1.100000010988609489e+01,2.815352837313684665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555857262973404431e+01,5.518928249244689823e+02,2.431092203137297791e-01,1.100000010988609489e+01,2.815206851912146948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.555948172063405366e+01,5.519028248848420617e+02,2.431373723450628854e-01,1.100000010988609489e+01,2.815060866510609230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556039081153406300e+01,5.519128248452192338e+02,2.431655229165477772e-01,1.100000010988609489e+01,2.814914881109071513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556129990243407235e+01,5.519228248056004986e+02,2.431936720281844266e-01,1.100000010988609489e+01,2.814768895707533795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556220899333408170e+01,5.519328247659858562e+02,2.432218196799728616e-01,1.100000010988609489e+01,2.814622910305996078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556311808423409104e+01,5.519428247263754201e+02,2.432499658719130542e-01,1.100000010988609489e+01,2.814476924904458360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556402717513410039e+01,5.519528246867690768e+02,2.432781106040050045e-01,1.100000010988609489e+01,2.814330939502920643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556493626603410974e+01,5.519628246471668263e+02,2.433062538762487403e-01,1.100000010988609489e+01,2.814184954101382925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556584535693411908e+01,5.519728246075686684e+02,2.433343956886442339e-01,1.100000010988609489e+01,2.814038968699845208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556675444783412843e+01,5.519828245679746033e+02,2.433625360411914851e-01,1.100000010988609489e+01,2.813892983298307490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556766353873413777e+01,5.519928245283846309e+02,2.433906749338904940e-01,1.100000010988609489e+01,2.813746997896769773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556857262963414712e+01,5.520028244887987512e+02,2.434188123667412884e-01,1.100000010988609489e+01,2.813601012495232055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.556948172053415647e+01,5.520128244492170779e+02,2.434469483397438405e-01,1.100000010988609489e+01,2.813455027093694338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557039081143416581e+01,5.520228244096394974e+02,2.434750828528981503e-01,1.100000010988609489e+01,2.813309041692156620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557129990233417516e+01,5.520328243700660096e+02,2.435032159062042179e-01,1.100000010988609489e+01,2.813163056290618903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557220899323418450e+01,5.520428243304966145e+02,2.435313474996620431e-01,1.100000010988609489e+01,2.813017070889081185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557311808413419385e+01,5.520528242909313121e+02,2.435594776332716260e-01,1.100000010988609489e+01,2.812871085487543468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557402717503420320e+01,5.520628242513701025e+02,2.435876063070329667e-01,1.100000010988609489e+01,2.812725100086005750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557493626593421254e+01,5.520728242118129856e+02,2.436157335209460928e-01,1.100000010988609489e+01,2.812579114684468033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557584535683422189e+01,5.520828241722599614e+02,2.436438592750109766e-01,1.100000010988609489e+01,2.812433129282930315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557675444773423123e+01,5.520928241327111436e+02,2.436719835692276181e-01,1.100000010988609489e+01,2.812287143881392597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557766353863424058e+01,5.521028240931664186e+02,2.437001064035960174e-01,1.100000010988609489e+01,2.812141158479854880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557857262953424993e+01,5.521128240536257863e+02,2.437282277781161743e-01,1.100000010988609489e+01,2.811995173078317162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.557948172043425927e+01,5.521228240140892467e+02,2.437563476927880890e-01,1.100000010988609489e+01,2.811849187676779445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558039081133426862e+01,5.521328239745567998e+02,2.437844661476117614e-01,1.100000010988609489e+01,2.811703202275241727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558129990223427797e+01,5.521428239350284457e+02,2.438125831425871637e-01,1.100000010988609489e+01,2.811557216873704010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558220899313428731e+01,5.521528238955041843e+02,2.438406986777143237e-01,1.100000010988609489e+01,2.811411231472166292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558311808403429666e+01,5.521628238559840156e+02,2.438688127529932415e-01,1.100000010988609489e+01,2.811265246070628575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558402717493430600e+01,5.521728238164679397e+02,2.438969253684239169e-01,1.100000010988609489e+01,2.811119260669090857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558493626583431535e+01,5.521828237769559564e+02,2.439250365240063501e-01,1.100000010988609489e+01,2.810973275267553140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558584535673432470e+01,5.521928237374481796e+02,2.439531462197405409e-01,1.100000010988609489e+01,2.810827289866015422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558675444763433404e+01,5.522028236979444955e+02,2.439812544556264895e-01,1.100000010988609489e+01,2.810681304464477705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558766353853434339e+01,5.522128236584449041e+02,2.440093612316641680e-01,1.100000010988609489e+01,2.810535319062939987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558857262943435273e+01,5.522228236189494055e+02,2.440374665478536043e-01,1.100000010988609489e+01,2.810389333661402270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.558948172033436208e+01,5.522328235794579996e+02,2.440655704041947982e-01,1.100000010988609489e+01,2.810243348259864552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559039081123437143e+01,5.522428235399706864e+02,2.440936728006877221e-01,1.100000010988609489e+01,2.810097362858326835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559129990213438077e+01,5.522528235004874659e+02,2.441217737373324037e-01,1.100000010988609489e+01,2.809951377456789117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559220899303439012e+01,5.522628234610083382e+02,2.441498732141288430e-01,1.100000010988609489e+01,2.809805392055251400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559311808393439946e+01,5.522728234215333032e+02,2.441779712310770123e-01,1.100000010988609489e+01,2.809659406653713682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559402717483440881e+01,5.522828233820623609e+02,2.442060677881769393e-01,1.100000010988609489e+01,2.809513421252175965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559493626573441816e+01,5.522928233425955113e+02,2.442341628854286240e-01,1.100000010988609489e+01,2.809367435850638247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559584535663442750e+01,5.523028233031327545e+02,2.442622565228320386e-01,1.100000010988609489e+01,2.809221450449100529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559675444753443685e+01,5.523128232636742041e+02,2.442903487003872109e-01,1.100000010988609489e+01,2.809075465047562812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559766353843444620e+01,5.523228232242197464e+02,2.443184394180941132e-01,1.100000010988609489e+01,2.808929479646025094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559857262933445554e+01,5.523328231847693814e+02,2.443465286759527733e-01,1.100000010988609489e+01,2.808783494244487377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.559948172023446489e+01,5.523428231453231092e+02,2.443746164739631632e-01,1.100000010988609489e+01,2.808637508842949659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560039081113447423e+01,5.523528231058809297e+02,2.444027028121253109e-01,1.100000010988609489e+01,2.808491523441411942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560129990203448358e+01,5.523628230664428429e+02,2.444307876904391885e-01,1.100000010988609489e+01,2.808345538039874224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560220899293449293e+01,5.523728230270088488e+02,2.444588711089048239e-01,1.100000010988609489e+01,2.808199552638336507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560311808383450227e+01,5.523828229875789475e+02,2.444869530675221891e-01,1.100000010988609489e+01,2.808053567236798789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560402717473451162e+01,5.523928229481531389e+02,2.445150335662912844e-01,1.100000010988609489e+01,2.807907581835261072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560493626563452096e+01,5.524028229087314230e+02,2.445431126052121373e-01,1.100000010988609489e+01,2.807761596433723354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560584535653453031e+01,5.524128228693137999e+02,2.445711901842847202e-01,1.100000010988609489e+01,2.807615611032185637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560675444743453966e+01,5.524228228299002694e+02,2.445992663035090331e-01,1.100000010988609489e+01,2.807469625630647919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560766353833454900e+01,5.524328227904908317e+02,2.446273409628851037e-01,1.100000010988609489e+01,2.807323640229110202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560857262923455835e+01,5.524428227510854867e+02,2.446554141624129042e-01,1.100000010988609489e+01,2.807177654827572484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.560948172013456769e+01,5.524528227116842345e+02,2.446834859020924346e-01,1.100000010988609489e+01,2.807031669426034767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561039081103457704e+01,5.524628226722870750e+02,2.447115561819236951e-01,1.100000010988609489e+01,2.806885684024497049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561129990193458639e+01,5.524728226328940082e+02,2.447396250019067132e-01,1.100000010988609489e+01,2.806739698622959332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561220899283459573e+01,5.524828225935051478e+02,2.447676923620414613e-01,1.100000010988609489e+01,2.806593713221421614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561311808373460508e+01,5.524928225541203801e+02,2.447957582623279393e-01,1.100000010988609489e+01,2.806447727819883897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561402717463461443e+01,5.525028225147397052e+02,2.448238227027661473e-01,1.100000010988609489e+01,2.806301742418346179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561493626553462377e+01,5.525128224753631230e+02,2.448518856833560853e-01,1.100000010988609489e+01,2.806155757016808461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561584535643463312e+01,5.525228224359906335e+02,2.448799472040977532e-01,1.100000010988609489e+01,2.806009771615270744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561675444733464246e+01,5.525328223966222367e+02,2.449080072649911510e-01,1.100000010988609489e+01,2.805863786213733026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561766353823465181e+01,5.525428223572579327e+02,2.449360658660363066e-01,1.100000010988609489e+01,2.805717800812195309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561857262913466116e+01,5.525528223178977214e+02,2.449641230072331921e-01,1.100000010988609489e+01,2.805571815410657591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.561948172003467050e+01,5.525628222785416028e+02,2.449921786885818076e-01,1.100000010988609489e+01,2.805425830009119874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562039081093467985e+01,5.525728222391895770e+02,2.450202329100821530e-01,1.100000010988609489e+01,2.805279844607582156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562129990183468919e+01,5.525828221998416439e+02,2.450482856717342284e-01,1.100000010988609489e+01,2.805133859206044439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562220899273469854e+01,5.525928221604978035e+02,2.450763369735380337e-01,1.100000010988609489e+01,2.804987873804506721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562311808363470789e+01,5.526028221211580558e+02,2.451043868154935412e-01,1.100000010988609489e+01,2.804841888402969004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562402717453471723e+01,5.526128220818224008e+02,2.451324351976007787e-01,1.100000010988609489e+01,2.804695903001431286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562493626543472658e+01,5.526228220424908386e+02,2.451604821198597461e-01,1.100000010988609489e+01,2.804549917599893569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562584535633473592e+01,5.526328220031633691e+02,2.451885275822704435e-01,1.100000010988609489e+01,2.804403932198355851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562675444723474527e+01,5.526428219638399923e+02,2.452165715848328709e-01,1.100000010988609489e+01,2.804257946796818134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562766353813475462e+01,5.526528219245207083e+02,2.452446141275470282e-01,1.100000010988609489e+01,2.804111961395280416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562857262903476396e+01,5.526628218852055170e+02,2.452726552104129154e-01,1.100000010988609489e+01,2.803965975993742699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.562948171993477331e+01,5.526728218458944184e+02,2.453006948334305048e-01,1.100000010988609489e+01,2.803819990592204981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563039081083478266e+01,5.526828218065874125e+02,2.453287329965998242e-01,1.100000010988609489e+01,2.803674005190667264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563129990173479200e+01,5.526928217672844994e+02,2.453567696999208736e-01,1.100000010988609489e+01,2.803528019789129546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563220899263480135e+01,5.527028217279856790e+02,2.453848049433936529e-01,1.100000010988609489e+01,2.803382034387591829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563311808353481069e+01,5.527128216886909513e+02,2.454128387270181344e-01,1.100000010988609489e+01,2.803236048986054111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563402717443482004e+01,5.527228216494003163e+02,2.454408710507943459e-01,1.100000010988609489e+01,2.803090063584516393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563493626533482939e+01,5.527328216101137741e+02,2.454689019147222873e-01,1.100000010988609489e+01,2.802944078182978676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563584535623483873e+01,5.527428215708313246e+02,2.454969313188019309e-01,1.100000010988609489e+01,2.802798092781440958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563675444713484808e+01,5.527528215315529678e+02,2.455249592630333044e-01,1.100000010988609489e+01,2.802652107379903241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563766353803485742e+01,5.527628214922787038e+02,2.455529857474163802e-01,1.100000010988609489e+01,2.802506121978365523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563857262893486677e+01,5.527728214530085324e+02,2.455810107719511859e-01,1.100000010988609489e+01,2.802360136576827806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.563948171983487612e+01,5.527828214137424538e+02,2.456090343366376938e-01,1.100000010988609489e+01,2.802214151175290088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564039081073488546e+01,5.527928213744804680e+02,2.456370564414759317e-01,1.100000010988609489e+01,2.802068165773752371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564129990163489481e+01,5.528028213352225748e+02,2.456650770864658717e-01,1.100000010988609489e+01,2.801922180372214653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564220899253490416e+01,5.528128212959687744e+02,2.456930962716075417e-01,1.100000010988609489e+01,2.801776194970676936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564311808343491350e+01,5.528228212567190667e+02,2.457211139969009139e-01,1.100000010988609489e+01,2.801630209569139218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564402717433492285e+01,5.528328212174734517e+02,2.457491302623460161e-01,1.100000010988609489e+01,2.801484224167601501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564493626523493219e+01,5.528428211782319295e+02,2.457771450679428205e-01,1.100000010988609489e+01,2.801338238766063783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564584535613494154e+01,5.528528211389945000e+02,2.458051584136913548e-01,1.100000010988609489e+01,2.801192253364526066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564675444703495089e+01,5.528628210997611632e+02,2.458331702995915913e-01,1.100000010988609489e+01,2.801046267962988348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564766353793496023e+01,5.528728210605319191e+02,2.458611807256435300e-01,1.100000010988609489e+01,2.800900282561450631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564857262883496958e+01,5.528828210213067678e+02,2.458891896918471986e-01,1.100000010988609489e+01,2.800754297159912913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.564948171973497892e+01,5.528928209820857091e+02,2.459171971982025695e-01,1.100000010988609489e+01,2.800608311758375196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565039081063498827e+01,5.529028209428687433e+02,2.459452032447096426e-01,1.100000010988609489e+01,2.800462326356837478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565129990153499762e+01,5.529128209036558701e+02,2.459732078313684456e-01,1.100000010988609489e+01,2.800316340955299761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565220899243500696e+01,5.529228208644470897e+02,2.460012109581789508e-01,1.100000010988609489e+01,2.800170355553762043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565311808333501631e+01,5.529328208252424020e+02,2.460292126251411582e-01,1.100000010988609489e+01,2.800024370152224325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565402717423502565e+01,5.529428207860416933e+02,2.460572128322550678e-01,1.100000010988609489e+01,2.799878384750686608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565493626513503500e+01,5.529528207468450773e+02,2.460852115795206796e-01,1.100000010988609489e+01,2.799732399349148890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565584535603504435e+01,5.529628207076525541e+02,2.461132088669380213e-01,1.100000010988609489e+01,2.799586413947611173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565675444693505369e+01,5.529728206684641236e+02,2.461412046945070653e-01,1.100000010988609489e+01,2.799440428546073455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565766353783506304e+01,5.529828206292797859e+02,2.461691990622278114e-01,1.100000010988609489e+01,2.799294443144535738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565857262873507239e+01,5.529928205900995408e+02,2.461971919701002598e-01,1.100000010988609489e+01,2.799148457742998020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.565948171963508173e+01,5.530028205509233885e+02,2.462251834181244103e-01,1.100000010988609489e+01,2.799002472341460303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566039081053509108e+01,5.530128205117513289e+02,2.462531734063002631e-01,1.100000010988609489e+01,2.798856486939922585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566129990143510042e+01,5.530228204725833621e+02,2.462811619346278180e-01,1.100000010988609489e+01,2.798710501538384868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566220899233510977e+01,5.530328204334194879e+02,2.463091490031070752e-01,1.100000010988609489e+01,2.798564516136847150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566311808323511912e+01,5.530428203942597065e+02,2.463371346117380345e-01,1.100000010988609489e+01,2.798418530735309433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566402717413512846e+01,5.530528203551040178e+02,2.463651187605206960e-01,1.100000010988609489e+01,2.798272545333771715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566493626503513781e+01,5.530628203159524219e+02,2.463931014494550598e-01,1.100000010988609489e+01,2.798126559932233998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566584535593514715e+01,5.530728202768049186e+02,2.464210826785411257e-01,1.100000010988609489e+01,2.797980574530696280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566675444683515650e+01,5.530828202376615081e+02,2.464490624477788938e-01,1.100000010988609489e+01,2.797834589129158563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566766353773516585e+01,5.530928201985221904e+02,2.464770407571683641e-01,1.100000010988609489e+01,2.797688603727620845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566857262863517519e+01,5.531028201593868516e+02,2.465050176067095089e-01,1.100000010988609489e+01,2.797542618326083128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.566948171953518454e+01,5.531128201202556056e+02,2.465329929964023559e-01,1.100000010988609489e+01,2.797396632924545410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567039081043519388e+01,5.531228200811284523e+02,2.465609669262469050e-01,1.100000010988609489e+01,2.797250647523007692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567129990133520323e+01,5.531328200420053918e+02,2.465889393962431564e-01,1.100000010988609489e+01,2.797104662121469975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567220899223521258e+01,5.531428200028864239e+02,2.466169104063911099e-01,1.100000010988609489e+01,2.796958676719932257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567311808313522192e+01,5.531528199637715488e+02,2.466448799566907379e-01,1.100000010988609489e+01,2.796812691318394540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567402717403523127e+01,5.531628199246607664e+02,2.466728480471420681e-01,1.100000010988609489e+01,2.796666705916856822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567493626493524062e+01,5.531728198855540768e+02,2.467008146777451005e-01,1.100000010988609489e+01,2.796520720515319105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567584535583524996e+01,5.531828198464514799e+02,2.467287798484998074e-01,1.100000010988609489e+01,2.796374735113781387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567675444673525931e+01,5.531928198073529757e+02,2.467567435594062164e-01,1.100000010988609489e+01,2.796228749712243670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567766353763526865e+01,5.532028197682585642e+02,2.467847058104643276e-01,1.100000010988609489e+01,2.796082764310705952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567857262853527800e+01,5.532128197291682454e+02,2.468126666016741133e-01,1.100000010988609489e+01,2.795936778909168235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.567948171943528735e+01,5.532228196900819057e+02,2.468406259330356012e-01,1.100000010988609489e+01,2.795790793507630517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568039081033529669e+01,5.532328196509996587e+02,2.468685838045487912e-01,1.100000010988609489e+01,2.795644808106092800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568129990123530604e+01,5.532428196119215045e+02,2.468965402162136558e-01,1.100000010988609489e+01,2.795498822704555082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568220899213531538e+01,5.532528195728474429e+02,2.469244951680302225e-01,1.100000010988609489e+01,2.795352837303017365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568311808303532473e+01,5.532628195337774741e+02,2.469524486599984636e-01,1.100000010988609489e+01,2.795206851901479647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568402717393533408e+01,5.532728194947115981e+02,2.469804006921184070e-01,1.100000010988609489e+01,2.795060866499941930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568493626483534342e+01,5.532828194556498147e+02,2.470083512643900248e-01,1.100000010988609489e+01,2.794914881098404212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568584535573535277e+01,5.532928194165921241e+02,2.470363003768133447e-01,1.100000010988609489e+01,2.794768895696866495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568675444663536211e+01,5.533028193775385262e+02,2.470642480293883392e-01,1.100000010988609489e+01,2.794622910295328777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568766353753537146e+01,5.533128193384890210e+02,2.470921942221150081e-01,1.100000010988609489e+01,2.794476924893791060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568857262843538081e+01,5.533228192994434949e+02,2.471201389549933791e-01,1.100000010988609489e+01,2.794330939492253342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.568948171933539015e+01,5.533328192604020614e+02,2.471480822280234246e-01,1.100000010988609489e+01,2.794184954090715624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569039081023539950e+01,5.533428192213647208e+02,2.471760240412051446e-01,1.100000010988609489e+01,2.794038968689177907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569129990113540885e+01,5.533528191823314728e+02,2.472039643945385667e-01,1.100000010988609489e+01,2.793892983287640189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569220899203541819e+01,5.533628191433023176e+02,2.472319032880236633e-01,1.100000010988609489e+01,2.793746997886102472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569311808293542754e+01,5.533728191042772551e+02,2.472598407216604344e-01,1.100000010988609489e+01,2.793601012484564754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569402717383543688e+01,5.533828190652562853e+02,2.472877766954489076e-01,1.100000010988609489e+01,2.793455027083027037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569493626473544623e+01,5.533928190262394082e+02,2.473157112093890553e-01,1.100000010988609489e+01,2.793309041681489319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569584535563545558e+01,5.534028189872265102e+02,2.473436442634808774e-01,1.100000010988609489e+01,2.793163056279951602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569675444653546492e+01,5.534128189482177049e+02,2.473715758577243740e-01,1.100000010988609489e+01,2.793017070878413884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569766353743547427e+01,5.534228189092129924e+02,2.473995059921195450e-01,1.100000010988609489e+01,2.792871085476876167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569857262833548361e+01,5.534328188702123725e+02,2.474274346666663904e-01,1.100000010988609489e+01,2.792725100075338449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.569948171923549296e+01,5.534428188312158454e+02,2.474553618813649380e-01,1.100000010988609489e+01,2.792579114673800732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570039081013550231e+01,5.534528187922234110e+02,2.474832876362151601e-01,1.100000010988609489e+01,2.792433129272263014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570129990103551165e+01,5.534628187532350694e+02,2.475112119312170567e-01,1.100000010988609489e+01,2.792287143870725297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570220899193552100e+01,5.534728187142507068e+02,2.475391347663706276e-01,1.100000010988609489e+01,2.792141158469187579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570311808283553034e+01,5.534828186752704369e+02,2.475670561416758730e-01,1.100000010988609489e+01,2.791995173067649862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570402717373553969e+01,5.534928186362942597e+02,2.475949760571327929e-01,1.100000010988609489e+01,2.791849187666112144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570493626463554904e+01,5.535028185973221753e+02,2.476228945127413872e-01,1.100000010988609489e+01,2.791703202264574427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570584535553555838e+01,5.535128185583541836e+02,2.476508115085016559e-01,1.100000010988609489e+01,2.791557216863036709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570675444643556773e+01,5.535228185193902846e+02,2.476787270444135991e-01,1.100000010988609489e+01,2.791411231461498992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570766353733557708e+01,5.535328184804304783e+02,2.477066411204772167e-01,1.100000010988609489e+01,2.791265246059961274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570857262823558642e+01,5.535428184414746511e+02,2.477345537366925088e-01,1.100000010988609489e+01,2.791119260658423556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.570948171913559577e+01,5.535528184025229166e+02,2.477624648930594753e-01,1.100000010988609489e+01,2.790973275256885839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571039081003560511e+01,5.535628183635752748e+02,2.477903745895780885e-01,1.100000010988609489e+01,2.790827289855348121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571129990093561446e+01,5.535728183246317258e+02,2.478182828262483761e-01,1.100000010988609489e+01,2.790681304453810404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571220899183562381e+01,5.535828182856922695e+02,2.478461896030703382e-01,1.100000010988609489e+01,2.790535319052272686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571311808273563315e+01,5.535928182467569059e+02,2.478740949200439747e-01,1.100000010988609489e+01,2.790389333650734969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571402717363564250e+01,5.536028182078255213e+02,2.479019987771692857e-01,1.100000010988609489e+01,2.790243348249197251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571493626453565184e+01,5.536128181688982295e+02,2.479299011744462433e-01,1.100000010988609489e+01,2.790097362847659534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571584535543566119e+01,5.536228181299750304e+02,2.479578021118748754e-01,1.100000010988609489e+01,2.789951377446121816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571675444633567054e+01,5.536328180910559240e+02,2.479857015894551819e-01,1.100000010988609489e+01,2.789805392044584099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571766353723567988e+01,5.536428180521409104e+02,2.480135996071871629e-01,1.100000010988609489e+01,2.789659406643046381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571857262813568923e+01,5.536528180132299894e+02,2.480414961650707906e-01,1.100000010988609489e+01,2.789513421241508664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.571948171903569857e+01,5.536628179743230476e+02,2.480693912631060927e-01,1.100000010988609489e+01,2.789367435839970946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572039080993570792e+01,5.536728179354201984e+02,2.480972849012930692e-01,1.100000010988609489e+01,2.789221450438433229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572129990083571727e+01,5.536828178965214420e+02,2.481251770796316924e-01,1.100000010988609489e+01,2.789075465036895511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572220899173572661e+01,5.536928178576267783e+02,2.481530677981219901e-01,1.100000010988609489e+01,2.788929479635357794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572311808263573596e+01,5.537028178187362073e+02,2.481809570567639345e-01,1.100000010988609489e+01,2.788783494233820076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572402717353574531e+01,5.537128177798496154e+02,2.482088448555575533e-01,1.100000010988609489e+01,2.788637508832282359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572493626443575465e+01,5.537228177409671162e+02,2.482367311945028188e-01,1.100000010988609489e+01,2.788491523430744641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572584535533576400e+01,5.537328177020887097e+02,2.482646160735997587e-01,1.100000010988609489e+01,2.788345538029206924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572675444623577334e+01,5.537428176632143959e+02,2.482924994928483453e-01,1.100000010988609489e+01,2.788199552627669206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572766353713578269e+01,5.537528176243441749e+02,2.483203814522486064e-01,1.100000010988609489e+01,2.788053567226131488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572857262803579204e+01,5.537628175854779329e+02,2.483482619518005141e-01,1.100000010988609489e+01,2.787907581824593771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.572948171893580138e+01,5.537728175466157836e+02,2.483761409915040963e-01,1.100000010988609489e+01,2.787761596423056053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573039080983581073e+01,5.537828175077577271e+02,2.484040185713593252e-01,1.100000010988609489e+01,2.787615611021518336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573129990073582007e+01,5.537928174689037633e+02,2.484318946913662007e-01,1.100000010988609489e+01,2.787469625619980618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573220899163582942e+01,5.538028174300538922e+02,2.484597693515247507e-01,1.100000010988609489e+01,2.787323640218442901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573311808253583877e+01,5.538128173912080001e+02,2.484876425518349474e-01,1.100000010988609489e+01,2.787177654816905183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573402717343584811e+01,5.538228173523662008e+02,2.485155142922967908e-01,1.100000010988609489e+01,2.787031669415367466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573493626433585746e+01,5.538328173135284942e+02,2.485433845729103086e-01,1.100000010988609489e+01,2.786885684013829748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573584535523586680e+01,5.538428172746948803e+02,2.485712533936754731e-01,1.100000010988609489e+01,2.786739698612292031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573675444613587615e+01,5.538528172358653592e+02,2.485991207545922843e-01,1.100000010988609489e+01,2.786593713210754313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573766353703588550e+01,5.538628171970398171e+02,2.486269866556607422e-01,1.100000010988609489e+01,2.786447727809216596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573857262793589484e+01,5.538728171582183677e+02,2.486548510968808745e-01,1.100000010988609489e+01,2.786301742407678878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.573948171883590419e+01,5.538828171194010110e+02,2.486827140782526535e-01,1.100000010988609489e+01,2.786155757006141161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574039080973591354e+01,5.538928170805877471e+02,2.487105755997760792e-01,1.100000010988609489e+01,2.786009771604603443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574129990063592288e+01,5.539028170417785759e+02,2.487384356614511516e-01,1.100000010988609489e+01,2.785863786203065726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574220899153593223e+01,5.539128170029733838e+02,2.487662942632778706e-01,1.100000010988609489e+01,2.785717800801528008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574311808243594157e+01,5.539228169641722843e+02,2.487941514052562364e-01,1.100000010988609489e+01,2.785571815399990291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574402717333595092e+01,5.539328169253752776e+02,2.488220070873862488e-01,1.100000010988609489e+01,2.785425829998452573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574493626423596027e+01,5.539428168865823636e+02,2.488498613096679080e-01,1.100000010988609489e+01,2.785279844596914856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574584535513596961e+01,5.539528168477934287e+02,2.488777140721012138e-01,1.100000010988609489e+01,2.785133859195377138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574675444603597896e+01,5.539628168090085865e+02,2.489055653746861663e-01,1.100000010988609489e+01,2.784987873793839420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574766353693598830e+01,5.539728167702278370e+02,2.489334152174227655e-01,1.100000010988609489e+01,2.784841888392301703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574857262783599765e+01,5.539828167314511802e+02,2.489612636003110113e-01,1.100000010988609489e+01,2.784695902990763985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.574948171873600700e+01,5.539928166926785025e+02,2.489891105233509039e-01,1.100000010988609489e+01,2.784549917589226268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575039080963601634e+01,5.540028166539099175e+02,2.490169559865424431e-01,1.100000010988609489e+01,2.784403932187688550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575129990053602569e+01,5.540128166151454252e+02,2.490447999898856291e-01,1.100000010988609489e+01,2.784257946786150833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575220899143603503e+01,5.540228165763850257e+02,2.490726425333804617e-01,1.100000010988609489e+01,2.784111961384613115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575311808233604438e+01,5.540328165376286051e+02,2.491004836170269410e-01,1.100000010988609489e+01,2.783965975983075398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575402717323605373e+01,5.540428164988762774e+02,2.491283232408250670e-01,1.100000010988609489e+01,2.783819990581537680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575493626413606307e+01,5.540528164601280423e+02,2.491561614047748396e-01,1.100000010988609489e+01,2.783674005179999963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575584535503607242e+01,5.540628164213839000e+02,2.491839981088762312e-01,1.100000010988609489e+01,2.783528019778462245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575675444593608177e+01,5.540728163826437367e+02,2.492118333531292695e-01,1.100000010988609489e+01,2.783382034376924528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575766353683609111e+01,5.540828163439076661e+02,2.492396671375339545e-01,1.100000010988609489e+01,2.783236048975386810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575857262773610046e+01,5.540928163051756883e+02,2.492674994620902862e-01,1.100000010988609489e+01,2.783090063573849093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.575948171863610980e+01,5.541028162664478032e+02,2.492953303267982368e-01,1.100000010988609489e+01,2.782944078172311375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576039080953611915e+01,5.541128162277238971e+02,2.493231597316578341e-01,1.100000010988609489e+01,2.782798092770773658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576129990043612850e+01,5.541228161890040838e+02,2.493509876766690780e-01,1.100000010988609489e+01,2.782652107369235940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576220899133613784e+01,5.541328161502883631e+02,2.493788141618319409e-01,1.100000010988609489e+01,2.782506121967698223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576311808223614719e+01,5.541428161115767352e+02,2.494066391871464505e-01,1.100000010988609489e+01,2.782360136566160505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576402717313615653e+01,5.541528160728690864e+02,2.494344627526126068e-01,1.100000010988609489e+01,2.782214151164622788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576493626403616588e+01,5.541628160341655303e+02,2.494622848582303820e-01,1.100000010988609489e+01,2.782068165763085070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576584535493617523e+01,5.541728159954660669e+02,2.494901055039998039e-01,1.100000010988609489e+01,2.781922180361547352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576675444583618457e+01,5.541828159567705825e+02,2.495179246899208447e-01,1.100000010988609489e+01,2.781776194960009635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576766353673619392e+01,5.541928159180791909e+02,2.495457424159935322e-01,1.100000010988609489e+01,2.781630209558471917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576857262763620326e+01,5.542028158793918919e+02,2.495735586822178387e-01,1.100000010988609489e+01,2.781484224156934200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.576948171853621261e+01,5.542128158407086858e+02,2.496013734885937918e-01,1.100000010988609489e+01,2.781338238755396482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577039080943622196e+01,5.542228158020294586e+02,2.496291868351213639e-01,1.100000010988609489e+01,2.781192253353858765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577129990033623130e+01,5.542328157633543242e+02,2.496569987218005826e-01,1.100000010988609489e+01,2.781046267952321047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577220899123624065e+01,5.542428157246832825e+02,2.496848091486314203e-01,1.100000010988609489e+01,2.780900282550783330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577311808213625000e+01,5.542528156860162198e+02,2.497126181156138769e-01,1.100000010988609489e+01,2.780754297149245612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577402717303625934e+01,5.542628156473532499e+02,2.497404256227479802e-01,1.100000010988609489e+01,2.780608311747707895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577493626393626869e+01,5.542728156086943727e+02,2.497682316700337024e-01,1.100000010988609489e+01,2.780462326346170177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577584535483627803e+01,5.542828155700395882e+02,2.497960362574710436e-01,1.100000010988609489e+01,2.780316340944632460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577675444573628738e+01,5.542928155313887828e+02,2.498238393850600314e-01,1.100000010988609489e+01,2.780170355543094742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577766353663629673e+01,5.543028154927420701e+02,2.498516410528006382e-01,1.100000010988609489e+01,2.780024370141557025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577857262753630607e+01,5.543128154540994501e+02,2.498794412606928639e-01,1.100000010988609489e+01,2.779878384740019307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.577948171843631542e+01,5.543228154154608092e+02,2.499072400087367363e-01,1.100000010988609489e+01,2.779732399338481590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578039080933632476e+01,5.543328153768262609e+02,2.499350372969322276e-01,1.100000010988609489e+01,2.779586413936943872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578129990023633411e+01,5.543428153381958055e+02,2.499628331252793378e-01,1.100000010988609489e+01,2.779440428535406155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578220899113634346e+01,5.543528152995693290e+02,2.499906274937780670e-01,1.100000010988609489e+01,2.779294443133868437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578311808203635280e+01,5.543628152609469453e+02,2.500184204024284429e-01,1.100000010988609489e+01,2.779148457732330720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578402717293636215e+01,5.543728152223286543e+02,2.500462118512304377e-01,1.100000010988609489e+01,2.779002472330793002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578493626383637150e+01,5.543828151837144560e+02,2.500740018401840237e-01,1.100000010988609489e+01,2.778856486929255284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578584535473638084e+01,5.543928151451042368e+02,2.501017903692892563e-01,1.100000010988609489e+01,2.778710501527717567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578675444563639019e+01,5.544028151064981103e+02,2.501295774385460802e-01,1.100000010988609489e+01,2.778564516126179849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578766353653639953e+01,5.544128150678960765e+02,2.501573630479545507e-01,1.100000010988609489e+01,2.778418530724642132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578857262743640888e+01,5.544228150292980217e+02,2.501851471975146124e-01,1.100000010988609489e+01,2.778272545323104414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.578948171833641823e+01,5.544328149907040597e+02,2.502129298872263208e-01,1.100000010988609489e+01,2.778126559921566697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579039080923642757e+01,5.544428149521141904e+02,2.502407111170896203e-01,1.100000010988609489e+01,2.777980574520028979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579129990013643692e+01,5.544528149135283002e+02,2.502684908871045666e-01,1.100000010988609489e+01,2.777834589118491262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579220899103644626e+01,5.544628148749465026e+02,2.502962691972711040e-01,1.100000010988609489e+01,2.777688603716953544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579311808193645561e+01,5.544728148363687978e+02,2.503240460475892881e-01,1.100000010988609489e+01,2.777542618315415827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579402717283646496e+01,5.544828147977950721e+02,2.503518214380590634e-01,1.100000010988609489e+01,2.777396632913878109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579493626373647430e+01,5.544928147592254390e+02,2.503795953686804854e-01,1.100000010988609489e+01,2.777250647512340392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579584535463648365e+01,5.545028147206598987e+02,2.504073678394534985e-01,1.100000010988609489e+01,2.777104662110802674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579675444553649299e+01,5.545128146820983375e+02,2.504351388503781584e-01,1.100000010988609489e+01,2.776958676709264957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579766353643650234e+01,5.545228146435408689e+02,2.504629084014544094e-01,1.100000010988609489e+01,2.776812691307727239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579857262733651169e+01,5.545328146049874931e+02,2.504906764926822516e-01,1.100000010988609489e+01,2.776666705906189522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.579948171823652103e+01,5.545428145664380963e+02,2.505184431240617404e-01,1.100000010988609489e+01,2.776520720504651804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580039080913653038e+01,5.545528145278927923e+02,2.505462082955928205e-01,1.100000010988609489e+01,2.776374735103114087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580129990003653973e+01,5.545628144893515810e+02,2.505739720072754917e-01,1.100000010988609489e+01,2.776228749701576369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580220899093654907e+01,5.545728144508143487e+02,2.506017342591098096e-01,1.100000010988609489e+01,2.776082764300038652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580311808183655842e+01,5.545828144122812091e+02,2.506294950510957187e-01,1.100000010988609489e+01,2.775936778898500934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580402717273656776e+01,5.545928143737521623e+02,2.506572543832332189e-01,1.100000010988609489e+01,2.775790793496963216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580493626363657711e+01,5.546028143352270945e+02,2.506850122555223659e-01,1.100000010988609489e+01,2.775644808095425499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580584535453658646e+01,5.546128142967061194e+02,2.507127686679631040e-01,1.100000010988609489e+01,2.775498822693887781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580675444543659580e+01,5.546228142581891234e+02,2.507405236205554333e-01,1.100000010988609489e+01,2.775352837292350064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580766353633660515e+01,5.546328142196762201e+02,2.507682771132994093e-01,1.100000010988609489e+01,2.775206851890812346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580857262723661449e+01,5.546428141811674095e+02,2.507960291461949764e-01,1.100000010988609489e+01,2.775060866489274629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.580948171813662384e+01,5.546528141426625780e+02,2.508237797192421348e-01,1.100000010988609489e+01,2.774914881087736911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581039080903663319e+01,5.546628141041618392e+02,2.508515288324409398e-01,1.100000010988609489e+01,2.774768895686199194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581129989993664253e+01,5.546728140656651931e+02,2.508792764857913360e-01,1.100000010988609489e+01,2.774622910284661476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581220899083665188e+01,5.546828140271725260e+02,2.509070226792933234e-01,1.100000010988609489e+01,2.774476924883123759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581311808173666122e+01,5.546928139886839517e+02,2.509347674129469019e-01,1.100000010988609489e+01,2.774330939481586041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581402717263667057e+01,5.547028139501994701e+02,2.509625106867520716e-01,1.100000010988609489e+01,2.774184954080048324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581493626353667992e+01,5.547128139117189676e+02,2.509902525007088880e-01,1.100000010988609489e+01,2.774038968678510606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581584535443668926e+01,5.547228138732425577e+02,2.510179928548172956e-01,1.100000010988609489e+01,2.773892983276972889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581675444533669861e+01,5.547328138347701270e+02,2.510457317490772944e-01,1.100000010988609489e+01,2.773746997875435171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581766353623670796e+01,5.547428137963017889e+02,2.510734691834888843e-01,1.100000010988609489e+01,2.773601012473897454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581857262713671730e+01,5.547528137578375436e+02,2.511012051580520654e-01,1.100000010988609489e+01,2.773455027072359736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.581948171803672665e+01,5.547628137193772773e+02,2.511289396727668377e-01,1.100000010988609489e+01,2.773309041670822019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582039080893673599e+01,5.547728136809211037e+02,2.511566727276332567e-01,1.100000010988609489e+01,2.773163056269284301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582129989983674534e+01,5.547828136424689092e+02,2.511844043226512668e-01,1.100000010988609489e+01,2.773017070867746584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582220899073675469e+01,5.547928136040208074e+02,2.512121344578208681e-01,1.100000010988609489e+01,2.772871085466208866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582311808163676403e+01,5.548028135655767983e+02,2.512398631331420606e-01,1.100000010988609489e+01,2.772725100064671148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582402717253677338e+01,5.548128135271367682e+02,2.512675903486148443e-01,1.100000010988609489e+01,2.772579114663133431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582493626343678272e+01,5.548228134887008309e+02,2.512953161042392192e-01,1.100000010988609489e+01,2.772433129261595713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582584535433679207e+01,5.548328134502688727e+02,2.513230404000151852e-01,1.100000010988609489e+01,2.772287143860057996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582675444523680142e+01,5.548428134118410071e+02,2.513507632359427424e-01,1.100000010988609489e+01,2.772141158458520278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582766353613681076e+01,5.548528133734172343e+02,2.513784846120218908e-01,1.100000010988609489e+01,2.771995173056982561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582857262703682011e+01,5.548628133349974405e+02,2.514062045282526303e-01,1.100000010988609489e+01,2.771849187655444843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.582948171793682945e+01,5.548728132965817395e+02,2.514339229846349610e-01,1.100000010988609489e+01,2.771703202253907126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583039080883683880e+01,5.548828132581700174e+02,2.514616399811688829e-01,1.100000010988609489e+01,2.771557216852369408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583129989973684815e+01,5.548928132197623881e+02,2.514893555178543960e-01,1.100000010988609489e+01,2.771411231450831691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583220899063685749e+01,5.549028131813588516e+02,2.515170695946915003e-01,1.100000010988609489e+01,2.771265246049293973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583311808153686684e+01,5.549128131429592941e+02,2.515447822116801957e-01,1.100000010988609489e+01,2.771119260647756256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583402717243687619e+01,5.549228131045638293e+02,2.515724933688204823e-01,1.100000010988609489e+01,2.770973275246218538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583493626333688553e+01,5.549328130661723435e+02,2.516002030661123601e-01,1.100000010988609489e+01,2.770827289844680821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583584535423689488e+01,5.549428130277849505e+02,2.516279113035558290e-01,1.100000010988609489e+01,2.770681304443143103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583675444513690422e+01,5.549528129894016502e+02,2.516556180811508892e-01,1.100000010988609489e+01,2.770535319041605386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583766353603691357e+01,5.549628129510223289e+02,2.516833233988975405e-01,1.100000010988609489e+01,2.770389333640067668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583857262693692292e+01,5.549728129126471003e+02,2.517110272567957829e-01,1.100000010988609489e+01,2.770243348238529951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.583948171783693226e+01,5.549828128742758508e+02,2.517387296548456166e-01,1.100000010988609489e+01,2.770097362836992233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584039080873694161e+01,5.549928128359086941e+02,2.517664305930470414e-01,1.100000010988609489e+01,2.769951377435454516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584129989963695095e+01,5.550028127975455163e+02,2.517941300714000574e-01,1.100000010988609489e+01,2.769805392033916798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584220899053696030e+01,5.550128127591864313e+02,2.518218280899046646e-01,1.100000010988609489e+01,2.769659406632379080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584311808143696965e+01,5.550228127208314390e+02,2.518495246485608630e-01,1.100000010988609489e+01,2.769513421230841363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584402717233697899e+01,5.550328126824804258e+02,2.518772197473686525e-01,1.100000010988609489e+01,2.769367435829303645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584493626323698834e+01,5.550428126441335053e+02,2.519049133863279777e-01,1.100000010988609489e+01,2.769221450427765928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584584535413699768e+01,5.550528126057905638e+02,2.519326055654388941e-01,1.100000010988609489e+01,2.769075465026228210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584675444503700703e+01,5.550628125674517150e+02,2.519602962847014016e-01,1.100000010988609489e+01,2.768929479624690493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584766353593701638e+01,5.550728125291168453e+02,2.519879855441155003e-01,1.100000010988609489e+01,2.768783494223152775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584857262683702572e+01,5.550828124907860683e+02,2.520156733436811902e-01,1.100000010988609489e+01,2.768637508821615058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.584948171773703507e+01,5.550928124524592704e+02,2.520433596833984713e-01,1.100000010988609489e+01,2.768491523420077340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585039080863704442e+01,5.551028124141365652e+02,2.520710445632672880e-01,1.100000010988609489e+01,2.768345538018539623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585129989953705376e+01,5.551128123758179527e+02,2.520987279832876959e-01,1.100000010988609489e+01,2.768199552617001905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585220899043706311e+01,5.551228123375033192e+02,2.521264099434596950e-01,1.100000010988609489e+01,2.768053567215464188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585311808133707245e+01,5.551328122991927785e+02,2.521540904437832853e-01,1.100000010988609489e+01,2.767907581813926470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585402717223708180e+01,5.551428122608862168e+02,2.521817694842584112e-01,1.100000010988609489e+01,2.767761596412388753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585493626313709115e+01,5.551528122225837478e+02,2.522094470648851283e-01,1.100000010988609489e+01,2.767615611010851035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585584535403710049e+01,5.551628121842852579e+02,2.522371231856634366e-01,1.100000010988609489e+01,2.767469625609313318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585675444493710984e+01,5.551728121459908607e+02,2.522647978465933361e-01,1.100000010988609489e+01,2.767323640207775600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585766353583711918e+01,5.551828121077004425e+02,2.522924710476747712e-01,1.100000010988609489e+01,2.767177654806237883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585857262673712853e+01,5.551928120694141171e+02,2.523201427889077975e-01,1.100000010988609489e+01,2.767031669404700165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.585948171763713788e+01,5.552028120311317707e+02,2.523478130702924149e-01,1.100000010988609489e+01,2.766885684003162447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586039080853714722e+01,5.552128119928535170e+02,2.523754818918285681e-01,1.100000010988609489e+01,2.766739698601624730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586129989943715657e+01,5.552228119545792424e+02,2.524031492535163124e-01,1.100000010988609489e+01,2.766593713200087012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586220899033716591e+01,5.552328119163090605e+02,2.524308151553556478e-01,1.100000010988609489e+01,2.766447727798549295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586311808123717526e+01,5.552428118780429713e+02,2.524584795973465190e-01,1.100000010988609489e+01,2.766301742397011577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586402717213718461e+01,5.552528118397808612e+02,2.524861425794889813e-01,1.100000010988609489e+01,2.766155756995473860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586493626303719395e+01,5.552628118015228438e+02,2.525138041017829793e-01,1.100000010988609489e+01,2.766009771593936142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586584535393720330e+01,5.552728117632688054e+02,2.525414641642285685e-01,1.100000010988609489e+01,2.765863786192398425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586675444483721265e+01,5.552828117250188598e+02,2.525691227668257488e-01,1.100000010988609489e+01,2.765717800790860707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586766353573722199e+01,5.552928116867728932e+02,2.525967799095744648e-01,1.100000010988609489e+01,2.765571815389322990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586857262663723134e+01,5.553028116485310193e+02,2.526244355924747720e-01,1.100000010988609489e+01,2.765425829987785272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.586948171753724068e+01,5.553128116102931244e+02,2.526520898155266148e-01,1.100000010988609489e+01,2.765279844586247555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587039080843725003e+01,5.553228115720593223e+02,2.526797425787300488e-01,1.100000010988609489e+01,2.765133859184709837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587129989933725938e+01,5.553328115338294992e+02,2.527073938820850740e-01,1.100000010988609489e+01,2.764987873783172120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587220899023726872e+01,5.553428114956037689e+02,2.527350437255916349e-01,1.100000010988609489e+01,2.764841888381634402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587311808113727807e+01,5.553528114573820176e+02,2.527626921092497869e-01,1.100000010988609489e+01,2.764695902980096685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587402717203728741e+01,5.553628114191643590e+02,2.527903390330594746e-01,1.100000010988609489e+01,2.764549917578558967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587493626293729676e+01,5.553728113809506794e+02,2.528179844970207535e-01,1.100000010988609489e+01,2.764403932177021250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587584535383730611e+01,5.553828113427410926e+02,2.528456285011335680e-01,1.100000010988609489e+01,2.764257946775483532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587675444473731545e+01,5.553928113045354849e+02,2.528732710453979737e-01,1.100000010988609489e+01,2.764111961373945815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587766353563732480e+01,5.554028112663339698e+02,2.529009121298139151e-01,1.100000010988609489e+01,2.763965975972408097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587857262653733414e+01,5.554128112281364338e+02,2.529285517543813921e-01,1.100000010988609489e+01,2.763819990570870379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.587948171743734349e+01,5.554228111899429905e+02,2.529561899191004604e-01,1.100000010988609489e+01,2.763674005169332662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588039080833735284e+01,5.554328111517535262e+02,2.529838266239710642e-01,1.100000010988609489e+01,2.763528019767794944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588129989923736218e+01,5.554428111135681547e+02,2.530114618689932593e-01,1.100000010988609489e+01,2.763382034366257227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588220899013737153e+01,5.554528110753867622e+02,2.530390956541669900e-01,1.100000010988609489e+01,2.763236048964719509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588311808103738088e+01,5.554628110372094625e+02,2.530667279794923119e-01,1.100000010988609489e+01,2.763090063563181792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588402717193739022e+01,5.554728109990361418e+02,2.530943588449691695e-01,1.100000010988609489e+01,2.762944078161644074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588493626283739957e+01,5.554828109608669138e+02,2.531219882505975627e-01,1.100000010988609489e+01,2.762798092760106357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588584535373740891e+01,5.554928109227016648e+02,2.531496161963775471e-01,1.100000010988609489e+01,2.762652107358568639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588675444463741826e+01,5.555028108845405086e+02,2.531772426823090671e-01,1.100000010988609489e+01,2.762506121957030922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588766353553742761e+01,5.555128108463833314e+02,2.532048677083921784e-01,1.100000010988609489e+01,2.762360136555493204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588857262643743695e+01,5.555228108082301333e+02,2.532324912746268253e-01,1.100000010988609489e+01,2.762214151153955487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.588948171733744630e+01,5.555328107700810278e+02,2.532601133810130078e-01,1.100000010988609489e+01,2.762068165752417769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589039080823745564e+01,5.555428107319359015e+02,2.532877340275507816e-01,1.100000010988609489e+01,2.761922180350880052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589129989913746499e+01,5.555528106937948678e+02,2.533153532142400910e-01,1.100000010988609489e+01,2.761776194949342334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589220899003747434e+01,5.555628106556578132e+02,2.533429709410809361e-01,1.100000010988609489e+01,2.761630209547804617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589311808093748368e+01,5.555728106175248513e+02,2.533705872080733168e-01,1.100000010988609489e+01,2.761484224146266899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589402717183749303e+01,5.555828105793958684e+02,2.533982020152172887e-01,1.100000010988609489e+01,2.761338238744729182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589493626273750237e+01,5.555928105412709783e+02,2.534258153625127963e-01,1.100000010988609489e+01,2.761192253343191464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589584535363751172e+01,5.556028105031500672e+02,2.534534272499598395e-01,1.100000010988609489e+01,2.761046267941653747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589675444453752107e+01,5.556128104650332489e+02,2.534810376775584184e-01,1.100000010988609489e+01,2.760900282540116029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589766353543753041e+01,5.556228104269204096e+02,2.535086466453085885e-01,1.100000010988609489e+01,2.760754297138578311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589857262633753976e+01,5.556328103888116630e+02,2.535362541532102942e-01,1.100000010988609489e+01,2.760608311737040594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.589948171723754911e+01,5.556428103507068954e+02,2.535638602012635356e-01,1.100000010988609489e+01,2.760462326335502876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590039080813755845e+01,5.556528103126061069e+02,2.535914647894683127e-01,1.100000010988609489e+01,2.760316340933965159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590129989903756780e+01,5.556628102745094111e+02,2.536190679178246810e-01,1.100000010988609489e+01,2.760170355532427441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590220898993757714e+01,5.556728102364166944e+02,2.536466695863325849e-01,1.100000010988609489e+01,2.760024370130889724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590311808083758649e+01,5.556828101983280703e+02,2.536742697949920244e-01,1.100000010988609489e+01,2.759878384729352006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590402717173759584e+01,5.556928101602434253e+02,2.537018685438029997e-01,1.100000010988609489e+01,2.759732399327814289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590493626263760518e+01,5.557028101221628731e+02,2.537294658327655106e-01,1.100000010988609489e+01,2.759586413926276571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590584535353761453e+01,5.557128100840862999e+02,2.537570616618795571e-01,1.100000010988609489e+01,2.759440428524738854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590675444443762387e+01,5.557228100460138194e+02,2.537846560311451394e-01,1.100000010988609489e+01,2.759294443123201136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590766353533763322e+01,5.557328100079453179e+02,2.538122489405623128e-01,1.100000010988609489e+01,2.759148457721663419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590857262623764257e+01,5.557428099698807955e+02,2.538398403901310219e-01,1.100000010988609489e+01,2.759002472320125701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.590948171713765191e+01,5.557528099318203658e+02,2.538674303798512666e-01,1.100000010988609489e+01,2.758856486918587984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591039080803766126e+01,5.557628098937639152e+02,2.538950189097230470e-01,1.100000010988609489e+01,2.758710501517050266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591129989893767060e+01,5.557728098557115572e+02,2.539226059797463630e-01,1.100000010988609489e+01,2.758564516115512549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591220898983767995e+01,5.557828098176631784e+02,2.539501915899212148e-01,1.100000010988609489e+01,2.758418530713974831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591311808073768930e+01,5.557928097796188922e+02,2.539777757402476022e-01,1.100000010988609489e+01,2.758272545312437114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591402717163769864e+01,5.558028097415785851e+02,2.540053584307255252e-01,1.100000010988609489e+01,2.758126559910899396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591493626253770799e+01,5.558128097035422570e+02,2.540329396613549839e-01,1.100000010988609489e+01,2.757980574509361679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591584535343771734e+01,5.558228096655100217e+02,2.540605194321359783e-01,1.100000010988609489e+01,2.757834589107823961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591675444433772668e+01,5.558328096274817653e+02,2.540880977430685084e-01,1.100000010988609489e+01,2.757688603706286243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591766353523773603e+01,5.558428095894576018e+02,2.541156745941525741e-01,1.100000010988609489e+01,2.757542618304748526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591857262613774537e+01,5.558528095514374172e+02,2.541432499853881755e-01,1.100000010988609489e+01,2.757396632903210808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.591948171703775472e+01,5.558628095134212117e+02,2.541708239167753125e-01,1.100000010988609489e+01,2.757250647501673091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592039080793776407e+01,5.558728094754090989e+02,2.541983963883139852e-01,1.100000010988609489e+01,2.757104662100135373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592129989883777341e+01,5.558828094374009652e+02,2.542259674000041936e-01,1.100000010988609489e+01,2.756958676698597656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592220898973778276e+01,5.558928093993969242e+02,2.542535369518459376e-01,1.100000010988609489e+01,2.756812691297059938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592311808063779210e+01,5.559028093613968622e+02,2.542811050438392173e-01,1.100000010988609489e+01,2.756666705895522221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592402717153780145e+01,5.559128093234007792e+02,2.543086716759840327e-01,1.100000010988609489e+01,2.756520720493984503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592493626243781080e+01,5.559228092854087890e+02,2.543362368482803837e-01,1.100000010988609489e+01,2.756374735092446786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592584535333782014e+01,5.559328092474207779e+02,2.543638005607282704e-01,1.100000010988609489e+01,2.756228749690909068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592675444423782949e+01,5.559428092094368594e+02,2.543913628133276927e-01,1.100000010988609489e+01,2.756082764289371351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592766353513783883e+01,5.559528091714569200e+02,2.544189236060786508e-01,1.100000010988609489e+01,2.755936778887833633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592857262603784818e+01,5.559628091334809596e+02,2.544464829389810889e-01,1.100000010988609489e+01,2.755790793486295916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.592948171693785753e+01,5.559728090955090920e+02,2.544740408120350628e-01,1.100000010988609489e+01,2.755644808084758198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593039080783786687e+01,5.559828090575412034e+02,2.545015972252405723e-01,1.100000010988609489e+01,2.755498822683220481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593129989873787622e+01,5.559928090195774075e+02,2.545291521785976174e-01,1.100000010988609489e+01,2.755352837281682763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593220898963788557e+01,5.560028089816175907e+02,2.545567056721061983e-01,1.100000010988609489e+01,2.755206851880145046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593311808053789491e+01,5.560128089436617529e+02,2.545842577057663147e-01,1.100000010988609489e+01,2.755060866478607328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593402717143790426e+01,5.560228089057100078e+02,2.546118082795779669e-01,1.100000010988609489e+01,2.754914881077069611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593493626233791360e+01,5.560328088677622418e+02,2.546393573935410992e-01,1.100000010988609489e+01,2.754768895675531893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593584535323792295e+01,5.560428088298184548e+02,2.546669050476557672e-01,1.100000010988609489e+01,2.754622910273994175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593675444413793230e+01,5.560528087918787605e+02,2.546944512419219708e-01,1.100000010988609489e+01,2.754476924872456458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593766353503794164e+01,5.560628087539430453e+02,2.547219959763397101e-01,1.100000010988609489e+01,2.754330939470918740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593857262593795099e+01,5.560728087160114228e+02,2.547495392509089296e-01,1.100000010988609489e+01,2.754184954069381023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.593948171683796033e+01,5.560828086780837793e+02,2.547770810656296847e-01,1.100000010988609489e+01,2.754038968667843305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594039080773796968e+01,5.560928086401601149e+02,2.548046214205019755e-01,1.100000010988609489e+01,2.753892983266305588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594129989863797903e+01,5.561028086022405432e+02,2.548321603155258019e-01,1.100000010988609489e+01,2.753746997864767870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594220898953798837e+01,5.561128085643249506e+02,2.548596977507011085e-01,1.100000010988609489e+01,2.753601012463230153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594311808043799772e+01,5.561228085264133369e+02,2.548872337260279508e-01,1.100000010988609489e+01,2.753455027061692435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594402717133800707e+01,5.561328084885058161e+02,2.549147682415063287e-01,1.100000010988609489e+01,2.753309041660154718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594493626223801641e+01,5.561428084506022742e+02,2.549423012971361868e-01,1.100000010988609489e+01,2.753163056258617000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594584535313802576e+01,5.561528084127027114e+02,2.549698328929175806e-01,1.100000010988609489e+01,2.753017070857079283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594675444403803510e+01,5.561628083748072413e+02,2.549973630288505100e-01,1.100000010988609489e+01,2.752871085455541565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594766353493804445e+01,5.561728083369157503e+02,2.550248917049349195e-01,1.100000010988609489e+01,2.752725100054003848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594857262583805380e+01,5.561828082990283519e+02,2.550524189211708648e-01,1.100000010988609489e+01,2.752579114652466130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.594948171673806314e+01,5.561928082611449327e+02,2.550799446775583457e-01,1.100000010988609489e+01,2.752433129250928413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595039080763807249e+01,5.562028082232654924e+02,2.551074689740973067e-01,1.100000010988609489e+01,2.752287143849390695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595129989853808183e+01,5.562128081853901449e+02,2.551349918107878034e-01,1.100000010988609489e+01,2.752141158447852978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595220898943809118e+01,5.562228081475187764e+02,2.551625131876298358e-01,1.100000010988609489e+01,2.751995173046315260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595311808033810053e+01,5.562328081096513870e+02,2.551900331046233483e-01,1.100000010988609489e+01,2.751849187644777543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595402717123810987e+01,5.562428080717880903e+02,2.552175515617683965e-01,1.100000010988609489e+01,2.751703202243239825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595493626213811922e+01,5.562528080339287726e+02,2.552450685590649249e-01,1.100000010988609489e+01,2.751557216841702107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595584535303812856e+01,5.562628079960734340e+02,2.552725840965129889e-01,1.100000010988609489e+01,2.751411231440164390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595675444393813791e+01,5.562728079582221881e+02,2.553000981741125330e-01,1.100000010988609489e+01,2.751265246038626672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595766353483814726e+01,5.562828079203749212e+02,2.553276107918636129e-01,1.100000010988609489e+01,2.751119260637088955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595857262573815660e+01,5.562928078825316334e+02,2.553551219497661728e-01,1.100000010988609489e+01,2.750973275235551237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.595948171663816595e+01,5.563028078446924383e+02,2.553826316478202685e-01,1.100000010988609489e+01,2.750827289834013520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596039080753817530e+01,5.563128078068572222e+02,2.554101398860258998e-01,1.100000010988609489e+01,2.750681304432475802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596129989843818464e+01,5.563228077690259852e+02,2.554376466643830113e-01,1.100000010988609489e+01,2.750535319030938085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596220898933819399e+01,5.563328077311988409e+02,2.554651519828916029e-01,1.100000010988609489e+01,2.750389333629400367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596311808023820333e+01,5.563428076933756756e+02,2.554926558415517301e-01,1.100000010988609489e+01,2.750243348227862650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596402717113821268e+01,5.563528076555564894e+02,2.555201582403633376e-01,1.100000010988609489e+01,2.750097362826324932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596493626203822203e+01,5.563628076177412822e+02,2.555476591793264807e-01,1.100000010988609489e+01,2.749951377424787215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596584535293823137e+01,5.563728075799301678e+02,2.555751586584411039e-01,1.100000010988609489e+01,2.749805392023249497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596675444383824072e+01,5.563828075421230324e+02,2.556026566777072628e-01,1.100000010988609489e+01,2.749659406621711780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596766353473825006e+01,5.563928075043198760e+02,2.556301532371249019e-01,1.100000010988609489e+01,2.749513421220174062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596857262563825941e+01,5.564028074665208123e+02,2.556576483366940766e-01,1.100000010988609489e+01,2.749367435818636345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.596948171653826876e+01,5.564128074287257277e+02,2.556851419764147315e-01,1.100000010988609489e+01,2.749221450417098627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597039080743827810e+01,5.564228073909346222e+02,2.557126341562868665e-01,1.100000010988609489e+01,2.749075465015560910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597129989833828745e+01,5.564328073531476093e+02,2.557401248763105372e-01,1.100000010988609489e+01,2.748929479614023192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597220898923829679e+01,5.564428073153645755e+02,2.557676141364856881e-01,1.100000010988609489e+01,2.748783494212485475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597311808013830614e+01,5.564528072775855208e+02,2.557951019368123191e-01,1.100000010988609489e+01,2.748637508810947757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597402717103831549e+01,5.564628072398105587e+02,2.558225882772904858e-01,1.100000010988609489e+01,2.748491523409410039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597493626193832483e+01,5.564728072020395757e+02,2.558500731579201326e-01,1.100000010988609489e+01,2.748345538007872322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597584535283833418e+01,5.564828071642725718e+02,2.558775565787013151e-01,1.100000010988609489e+01,2.748199552606334604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597675444373834353e+01,5.564928071265095468e+02,2.559050385396339777e-01,1.100000010988609489e+01,2.748053567204796887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597766353463835287e+01,5.565028070887506146e+02,2.559325190407181205e-01,1.100000010988609489e+01,2.747907581803259169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597857262553836222e+01,5.565128070509956615e+02,2.559599980819537435e-01,1.100000010988609489e+01,2.747761596401721452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.597948171643837156e+01,5.565228070132446874e+02,2.559874756633409021e-01,1.100000010988609489e+01,2.747615611000183734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598039080733838091e+01,5.565328069754978060e+02,2.560149517848795409e-01,1.100000010988609489e+01,2.747469625598646017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598129989823839026e+01,5.565428069377549036e+02,2.560424264465696598e-01,1.100000010988609489e+01,2.747323640197108299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598220898913839960e+01,5.565528069000159803e+02,2.560698996484113144e-01,1.100000010988609489e+01,2.747177654795570582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598311808003840895e+01,5.565628068622810360e+02,2.560973713904044491e-01,1.100000010988609489e+01,2.747031669394032864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598402717093841829e+01,5.565728068245501845e+02,2.561248416725490640e-01,1.100000010988609489e+01,2.746885683992495147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598493626183842764e+01,5.565828067868233120e+02,2.561523104948451590e-01,1.100000010988609489e+01,2.746739698590957429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598584535273843699e+01,5.565928067491004185e+02,2.561797778572927342e-01,1.100000010988609489e+01,2.746593713189419712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598675444363844633e+01,5.566028067113815041e+02,2.562072437598918451e-01,1.100000010988609489e+01,2.746447727787881994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598766353453845568e+01,5.566128066736666824e+02,2.562347082026424361e-01,1.100000010988609489e+01,2.746301742386344277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598857262543846502e+01,5.566228066359558397e+02,2.562621711855445072e-01,1.100000010988609489e+01,2.746155756984806559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.598948171633847437e+01,5.566328065982489761e+02,2.562896327085980586e-01,1.100000010988609489e+01,2.746009771583268842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599039080723848372e+01,5.566428065605462052e+02,2.563170927718030900e-01,1.100000010988609489e+01,2.745863786181731124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599129989813849306e+01,5.566528065228474134e+02,2.563445513751596017e-01,1.100000010988609489e+01,2.745717800780193407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599220898903850241e+01,5.566628064851526005e+02,2.563720085186676489e-01,1.100000010988609489e+01,2.745571815378655689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599311807993851176e+01,5.566728064474617668e+02,2.563994642023271764e-01,1.100000010988609489e+01,2.745425829977117971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599402717083852110e+01,5.566828064097750257e+02,2.564269184261381840e-01,1.100000010988609489e+01,2.745279844575580254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599493626173853045e+01,5.566928063720922637e+02,2.564543711901006717e-01,1.100000010988609489e+01,2.745133859174042536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599584535263853979e+01,5.567028063344134807e+02,2.564818224942146396e-01,1.100000010988609489e+01,2.744987873772504819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599675444353854914e+01,5.567128062967386768e+02,2.565092723384800877e-01,1.100000010988609489e+01,2.744841888370967101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599766353443855849e+01,5.567228062590679656e+02,2.565367207228970159e-01,1.100000010988609489e+01,2.744695902969429384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599857262533856783e+01,5.567328062214012334e+02,2.565641676474654242e-01,1.100000010988609489e+01,2.744549917567891666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.599948171623857718e+01,5.567428061837384803e+02,2.565916131121853128e-01,1.100000010988609489e+01,2.744403932166353949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600039080713858652e+01,5.567528061460797062e+02,2.566190571170566814e-01,1.100000010988609489e+01,2.744257946764816231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600129989803859587e+01,5.567628061084250248e+02,2.566464996620795302e-01,1.100000010988609489e+01,2.744111961363278514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600220898893860522e+01,5.567728060707743225e+02,2.566739407472538592e-01,1.100000010988609489e+01,2.743965975961740796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600311807983861456e+01,5.567828060331275992e+02,2.567013803725796683e-01,1.100000010988609489e+01,2.743819990560203079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600402717073862391e+01,5.567928059954848550e+02,2.567288185380569576e-01,1.100000010988609489e+01,2.743674005158665361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600493626163863325e+01,5.568028059578460898e+02,2.567562552436857271e-01,1.100000010988609489e+01,2.743528019757127644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600584535253864260e+01,5.568128059202114173e+02,2.567836904894659766e-01,1.100000010988609489e+01,2.743382034355589926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600675444343865195e+01,5.568228058825807238e+02,2.568111242753977064e-01,1.100000010988609489e+01,2.743236048954052209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600766353433866129e+01,5.568328058449540094e+02,2.568385566014809163e-01,1.100000010988609489e+01,2.743090063552514491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600857262523867064e+01,5.568428058073312741e+02,2.568659874677156063e-01,1.100000010988609489e+01,2.742944078150976774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.600948171613867999e+01,5.568528057697126314e+02,2.568934168741017765e-01,1.100000010988609489e+01,2.742798092749439056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601039080703868933e+01,5.568628057320979678e+02,2.569208448206394269e-01,1.100000010988609489e+01,2.742652107347901339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601129989793869868e+01,5.568728056944872833e+02,2.569482713073285574e-01,1.100000010988609489e+01,2.742506121946363621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601220898883870802e+01,5.568828056568805778e+02,2.569756963341691680e-01,1.100000010988609489e+01,2.742360136544825903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601311807973871737e+01,5.568928056192778513e+02,2.570031199011612588e-01,1.100000010988609489e+01,2.742214151143288186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601402717063872672e+01,5.569028055816792175e+02,2.570305420083048298e-01,1.100000010988609489e+01,2.742068165741750468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601493626153873606e+01,5.569128055440845628e+02,2.570579626555998809e-01,1.100000010988609489e+01,2.741922180340212751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601584535243874541e+01,5.569228055064938872e+02,2.570853818430463567e-01,1.100000010988609489e+01,2.741776194938675033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601675444333875475e+01,5.569328054689071905e+02,2.571127995706443126e-01,1.100000010988609489e+01,2.741630209537137316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601766353423876410e+01,5.569428054313245866e+02,2.571402158383937486e-01,1.100000010988609489e+01,2.741484224135599598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601857262513877345e+01,5.569528053937459617e+02,2.571676306462946648e-01,1.100000010988609489e+01,2.741338238734061881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.601948171603878279e+01,5.569628053561713159e+02,2.571950439943470612e-01,1.100000010988609489e+01,2.741192253332524163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602039080693879214e+01,5.569728053186006491e+02,2.572224558825509377e-01,1.100000010988609489e+01,2.741046267930986446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602129989783880148e+01,5.569828052810339614e+02,2.572498663109062389e-01,1.100000010988609489e+01,2.740900282529448728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602220898873881083e+01,5.569928052434713663e+02,2.572772752794130202e-01,1.100000010988609489e+01,2.740754297127911011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602311807963882018e+01,5.570028052059127504e+02,2.573046827880712817e-01,1.100000010988609489e+01,2.740608311726373293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602402717053882952e+01,5.570128051683581134e+02,2.573320888368810233e-01,1.100000010988609489e+01,2.740462326324835576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602493626143883887e+01,5.570228051308074555e+02,2.573594934258422451e-01,1.100000010988609489e+01,2.740316340923297858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602584535233884822e+01,5.570328050932607766e+02,2.573868965549548915e-01,1.100000010988609489e+01,2.740170355521760141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602675444323885756e+01,5.570428050557180768e+02,2.574142982242190181e-01,1.100000010988609489e+01,2.740024370120222423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602766353413886691e+01,5.570528050181794697e+02,2.574416984336346248e-01,1.100000010988609489e+01,2.739878384718684706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602857262503887625e+01,5.570628049806448416e+02,2.574690971832016562e-01,1.100000010988609489e+01,2.739732399317146988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.602948171593888560e+01,5.570728049431141926e+02,2.574964944729201677e-01,1.100000010988609489e+01,2.739586413915609271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603039080683889495e+01,5.570828049055875226e+02,2.575238903027901594e-01,1.100000010988609489e+01,2.739440428514071553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603129989773890429e+01,5.570928048680648317e+02,2.575512846728116312e-01,1.100000010988609489e+01,2.739294443112533835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603220898863891364e+01,5.571028048305462335e+02,2.575786775829845276e-01,1.100000010988609489e+01,2.739148457710996118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603311807953892298e+01,5.571128047930316143e+02,2.576060690333089043e-01,1.100000010988609489e+01,2.739002472309458400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603402717043893233e+01,5.571228047555209741e+02,2.576334590237847610e-01,1.100000010988609489e+01,2.738856486907920683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603493626133894168e+01,5.571328047180143130e+02,2.576608475544120425e-01,1.100000010988609489e+01,2.738710501506382965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603584535223895102e+01,5.571428046805116310e+02,2.576882346251908040e-01,1.100000010988609489e+01,2.738564516104845248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603675444313896037e+01,5.571528046430129280e+02,2.577156202361209902e-01,1.100000010988609489e+01,2.738418530703307530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603766353403896971e+01,5.571628046055183177e+02,2.577430043872026566e-01,1.100000010988609489e+01,2.738272545301769813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603857262493897906e+01,5.571728045680276864e+02,2.577703870784358031e-01,1.100000010988609489e+01,2.738126559900232095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.603948171583898841e+01,5.571828045305410342e+02,2.577977683098203743e-01,1.100000010988609489e+01,2.737980574498694378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604039080673899775e+01,5.571928044930583610e+02,2.578251480813564256e-01,1.100000010988609489e+01,2.737834589097156660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604129989763900710e+01,5.572028044555796669e+02,2.578525263930439015e-01,1.100000010988609489e+01,2.737688603695618943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604220898853901645e+01,5.572128044181049518e+02,2.578799032448828576e-01,1.100000010988609489e+01,2.737542618294081225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604311807943902579e+01,5.572228043806343294e+02,2.579072786368732939e-01,1.100000010988609489e+01,2.737396632892543508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604402717033903514e+01,5.572328043431676861e+02,2.579346525690151548e-01,1.100000010988609489e+01,2.737250647491005790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604493626123904448e+01,5.572428043057050218e+02,2.579620250413084959e-01,1.100000010988609489e+01,2.737104662089468073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604584535213905383e+01,5.572528042682463365e+02,2.579893960537532616e-01,1.100000010988609489e+01,2.736958676687930355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604675444303906318e+01,5.572628042307916303e+02,2.580167656063495074e-01,1.100000010988609489e+01,2.736812691286392638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604766353393907252e+01,5.572728041933409031e+02,2.580441336990971779e-01,1.100000010988609489e+01,2.736666705884854920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604857262483908187e+01,5.572828041558941550e+02,2.580715003319963285e-01,1.100000010988609489e+01,2.736520720483317202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.604948171573909121e+01,5.572928041184514996e+02,2.580988655050469038e-01,1.100000010988609489e+01,2.736374735081779485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605039080663910056e+01,5.573028040810128232e+02,2.581262292182489593e-01,1.100000010988609489e+01,2.736228749680241767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605129989753910991e+01,5.573128040435781259e+02,2.581535914716024394e-01,1.100000010988609489e+01,2.736082764278704050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605220898843911925e+01,5.573228040061474076e+02,2.581809522651073441e-01,1.100000010988609489e+01,2.735936778877166332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605311807933912860e+01,5.573328039687206683e+02,2.582083115987637290e-01,1.100000010988609489e+01,2.735790793475628615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605402717023913794e+01,5.573428039312979081e+02,2.582356694725715385e-01,1.100000010988609489e+01,2.735644808074090897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605493626113914729e+01,5.573528038938791269e+02,2.582630258865308281e-01,1.100000010988609489e+01,2.735498822672553180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605584535203915664e+01,5.573628038564643248e+02,2.582903808406415425e-01,1.100000010988609489e+01,2.735352837271015462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605675444293916598e+01,5.573728038190536154e+02,2.583177343349036814e-01,1.100000010988609489e+01,2.735206851869477745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605766353383917533e+01,5.573828037816468850e+02,2.583450863693173005e-01,1.100000010988609489e+01,2.735060866467940027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605857262473918468e+01,5.573928037442441337e+02,2.583724369438823443e-01,1.100000010988609489e+01,2.734914881066402310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.605948171563919402e+01,5.574028037068453614e+02,2.583997860585988682e-01,1.100000010988609489e+01,2.734768895664864592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606039080653920337e+01,5.574128036694505681e+02,2.584271337134668167e-01,1.100000010988609489e+01,2.734622910263326875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606129989743921271e+01,5.574228036320597539e+02,2.584544799084861899e-01,1.100000010988609489e+01,2.734476924861789157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606220898833922206e+01,5.574328035946729187e+02,2.584818246436570433e-01,1.100000010988609489e+01,2.734330939460251440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606311807923923141e+01,5.574428035572900626e+02,2.585091679189793212e-01,1.100000010988609489e+01,2.734184954058713722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606402717013924075e+01,5.574528035199112992e+02,2.585365097344530239e-01,1.100000010988609489e+01,2.734038968657176005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606493626103925010e+01,5.574628034825365148e+02,2.585638500900782066e-01,1.100000010988609489e+01,2.733892983255638287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606584535193925944e+01,5.574728034451657095e+02,2.585911889858548141e-01,1.100000010988609489e+01,2.733746997854100570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606675444283926879e+01,5.574828034077988832e+02,2.586185264217828461e-01,1.100000010988609489e+01,2.733601012452562852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606766353373927814e+01,5.574928033704360359e+02,2.586458623978623028e-01,1.100000010988609489e+01,2.733455027051025134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606857262463928748e+01,5.575028033330771677e+02,2.586731969140932397e-01,1.100000010988609489e+01,2.733309041649487417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.606948171553929683e+01,5.575128032957222786e+02,2.587005299704756012e-01,1.100000010988609489e+01,2.733163056247949699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607039080643930617e+01,5.575228032583713684e+02,2.587278615670093873e-01,1.100000010988609489e+01,2.733017070846411982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607129989733931552e+01,5.575328032210244373e+02,2.587551917036945981e-01,1.100000010988609489e+01,2.732871085444874264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607220898823932487e+01,5.575428031836814853e+02,2.587825203805312890e-01,1.100000010988609489e+01,2.732725100043336547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607311807913933421e+01,5.575528031463426260e+02,2.588098475975194046e-01,1.100000010988609489e+01,2.732579114641798829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607402717003934356e+01,5.575628031090077457e+02,2.588371733546589448e-01,1.100000010988609489e+01,2.732433129240261112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607493626093935291e+01,5.575728030716768444e+02,2.588644976519499097e-01,1.100000010988609489e+01,2.732287143838723394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607584535183936225e+01,5.575828030343499222e+02,2.588918204893922992e-01,1.100000010988609489e+01,2.732141158437185677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607675444273937160e+01,5.575928029970269790e+02,2.589191418669861133e-01,1.100000010988609489e+01,2.731995173035647959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607766353363938094e+01,5.576028029597080149e+02,2.589464617847314076e-01,1.100000010988609489e+01,2.731849187634110242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607857262453939029e+01,5.576128029223930298e+02,2.589737802426281266e-01,1.100000010988609489e+01,2.731703202232572524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.607948171543939964e+01,5.576228028850820237e+02,2.590010972406762702e-01,1.100000010988609489e+01,2.731557216831034807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608039080633940898e+01,5.576328028477749967e+02,2.590284127788758384e-01,1.100000010988609489e+01,2.731411231429497089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608129989723941833e+01,5.576428028104719488e+02,2.590557268572268312e-01,1.100000010988609489e+01,2.731265246027959372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608220898813942767e+01,5.576528027731728798e+02,2.590830394757292487e-01,1.100000010988609489e+01,2.731119260626421654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608311807903943702e+01,5.576628027358777899e+02,2.591103506343830909e-01,1.100000010988609489e+01,2.730973275224883937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608402716993944637e+01,5.576728026985867928e+02,2.591376603331883577e-01,1.100000010988609489e+01,2.730827289823346219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608493626083945571e+01,5.576828026612997746e+02,2.591649685721450491e-01,1.100000010988609489e+01,2.730681304421808502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608584535173946506e+01,5.576928026240167355e+02,2.591922753512531652e-01,1.100000010988609489e+01,2.730535319020270784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608675444263947441e+01,5.577028025867376755e+02,2.592195806705127059e-01,1.100000010988609489e+01,2.730389333618733066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608766353353948375e+01,5.577128025494625945e+02,2.592468845299237268e-01,1.100000010988609489e+01,2.730243348217195349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608857262443949310e+01,5.577228025121914925e+02,2.592741869294861723e-01,1.100000010988609489e+01,2.730097362815657631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.608948171533950244e+01,5.577328024749243696e+02,2.593014878692000424e-01,1.100000010988609489e+01,2.729951377414119914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609039080623951179e+01,5.577428024376612257e+02,2.593287873490653372e-01,1.100000010988609489e+01,2.729805392012582196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609129989713952114e+01,5.577528024004020608e+02,2.593560853690820567e-01,1.100000010988609489e+01,2.729659406611044479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609220898803953048e+01,5.577628023631468750e+02,2.593833819292502008e-01,1.100000010988609489e+01,2.729513421209506761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609311807893953983e+01,5.577728023258956682e+02,2.594106770295697695e-01,1.100000010988609489e+01,2.729367435807969044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609402716983954917e+01,5.577828022886484405e+02,2.594379706700407073e-01,1.100000010988609489e+01,2.729221450406431326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609493626073955852e+01,5.577928022514051918e+02,2.594652628506630698e-01,1.100000010988609489e+01,2.729075465004893609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609584535163956787e+01,5.578028022141659221e+02,2.594925535714368570e-01,1.100000010988609489e+01,2.728929479603355891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609675444253957721e+01,5.578128021769306315e+02,2.595198428323620687e-01,1.100000010988609489e+01,2.728783494201818174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609766353343958656e+01,5.578228021396993199e+02,2.595471306334387052e-01,1.100000010988609489e+01,2.728637508800280456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609857262433959590e+01,5.578328021024719874e+02,2.595744169746667662e-01,1.100000010988609489e+01,2.728491523398742739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.609948171523960525e+01,5.578428020652486339e+02,2.596017018560462519e-01,1.100000010988609489e+01,2.728345537997205021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610039080613961460e+01,5.578528020280292594e+02,2.596289852775771623e-01,1.100000010988609489e+01,2.728199552595667304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610129989703962394e+01,5.578628019908138640e+02,2.596562672392594973e-01,1.100000010988609489e+01,2.728053567194129586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610220898793963329e+01,5.578728019536025613e+02,2.596835477410932569e-01,1.100000010988609489e+01,2.727907581792591869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610311807883964264e+01,5.578828019163952376e+02,2.597108267830784412e-01,1.100000010988609489e+01,2.727761596391054151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610402716973965198e+01,5.578928018791918930e+02,2.597381043652149946e-01,1.100000010988609489e+01,2.727615610989516434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610493626063966133e+01,5.579028018419925274e+02,2.597653804875029726e-01,1.100000010988609489e+01,2.727469625587978716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610584535153967067e+01,5.579128018047971409e+02,2.597926551499423753e-01,1.100000010988609489e+01,2.727323640186440998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610675444243968002e+01,5.579228017676057334e+02,2.598199283525332026e-01,1.100000010988609489e+01,2.727177654784903281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610766353333968937e+01,5.579328017304183049e+02,2.598472000952754546e-01,1.100000010988609489e+01,2.727031669383365563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610857262423969871e+01,5.579428016932348555e+02,2.598744703781690757e-01,1.100000010988609489e+01,2.726885683981827846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.610948171513970806e+01,5.579528016560553851e+02,2.599017392012141214e-01,1.100000010988609489e+01,2.726739698580290128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611039080603971740e+01,5.579628016188798938e+02,2.599290065644105918e-01,1.100000010988609489e+01,2.726593713178752411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611129989693972675e+01,5.579728015817083815e+02,2.599562724677584868e-01,1.100000010988609489e+01,2.726447727777214693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611220898783973610e+01,5.579828015445408482e+02,2.599835369112577510e-01,1.100000010988609489e+01,2.726301742375676976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611311807873974544e+01,5.579928015073772940e+02,2.600107998949084398e-01,1.100000010988609489e+01,2.726155756974139258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611402716963975479e+01,5.580028014702177188e+02,2.600380614187105532e-01,1.100000010988609489e+01,2.726009771572601541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611493626053976413e+01,5.580128014330621227e+02,2.600653214826640913e-01,1.100000010988609489e+01,2.725863786171063823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611584535143977348e+01,5.580228013959105056e+02,2.600925800867689985e-01,1.100000010988609489e+01,2.725717800769526106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611675444233978283e+01,5.580328013587628675e+02,2.601198372310253304e-01,1.100000010988609489e+01,2.725571815367988388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611766353323979217e+01,5.580428013216192085e+02,2.601470929154330869e-01,1.100000010988609489e+01,2.725425829966450671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611857262413980152e+01,5.580528012844795285e+02,2.601743471399922125e-01,1.100000010988609489e+01,2.725279844564912953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.611948171503981087e+01,5.580628012473438275e+02,2.602015999047027628e-01,1.100000010988609489e+01,2.725133859163375236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612039080593982021e+01,5.580728012102121056e+02,2.602288512095647377e-01,1.100000010988609489e+01,2.724987873761837518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612129989683982956e+01,5.580828011730843627e+02,2.602561010545780817e-01,1.100000010988609489e+01,2.724841888360299801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612220898773983890e+01,5.580928011359605989e+02,2.602833494397428504e-01,1.100000010988609489e+01,2.724695902958762083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612311807863984825e+01,5.581028010988408141e+02,2.603105963650590438e-01,1.100000010988609489e+01,2.724549917557224366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612402716953985760e+01,5.581128010617250084e+02,2.603378418305266062e-01,1.100000010988609489e+01,2.724403932155686648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612493626043986694e+01,5.581228010246131817e+02,2.603650858361455933e-01,1.100000010988609489e+01,2.724257946754148930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612584535133987629e+01,5.581328009875053340e+02,2.603923283819160051e-01,1.100000010988609489e+01,2.724111961352611213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612675444223988563e+01,5.581428009504014653e+02,2.604195694678377859e-01,1.100000010988609489e+01,2.723965975951073495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612766353313989498e+01,5.581528009133015757e+02,2.604468090939109914e-01,1.100000010988609489e+01,2.723819990549535778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612857262403990433e+01,5.581628008762056652e+02,2.604740472601355661e-01,1.100000010988609489e+01,2.723674005147998060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.612948171493991367e+01,5.581728008391137337e+02,2.605012839665115654e-01,1.100000010988609489e+01,2.723528019746460343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613039080583992302e+01,5.581828008020257812e+02,2.605285192130389338e-01,1.100000010988609489e+01,2.723382034344922625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613129989673993236e+01,5.581928007649418078e+02,2.605557529997177268e-01,1.100000010988609489e+01,2.723236048943384908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613220898763994171e+01,5.582028007278618134e+02,2.605829853265478890e-01,1.100000010988609489e+01,2.723090063541847190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613311807853995106e+01,5.582128006907856843e+02,2.606102161935294759e-01,1.100000010988609489e+01,2.722944078140309473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613402716943996040e+01,5.582228006537135343e+02,2.606374456006624318e-01,1.100000010988609489e+01,2.722798092738771755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613493626033996975e+01,5.582328006166453633e+02,2.606646735479468124e-01,1.100000010988609489e+01,2.722652107337234038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613584535123997910e+01,5.582428005795811714e+02,2.606919000353825622e-01,1.100000010988609489e+01,2.722506121935696320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613675444213998844e+01,5.582528005425209585e+02,2.607191250629697366e-01,1.100000010988609489e+01,2.722360136534158603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613766353303999779e+01,5.582628005054647247e+02,2.607463486307082801e-01,1.100000010988609489e+01,2.722214151132620885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613857262394000713e+01,5.582728004684124699e+02,2.607735707385982482e-01,1.100000010988609489e+01,2.722068165731083168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.613948171484001648e+01,5.582828004313641941e+02,2.608007913866395855e-01,1.100000010988609489e+01,2.721922180329545450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614039080574002583e+01,5.582928003943198974e+02,2.608280105748323474e-01,1.100000010988609489e+01,2.721776194928007733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614129989664003517e+01,5.583028003572795797e+02,2.608552283031764785e-01,1.100000010988609489e+01,2.721630209526470015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614220898754004452e+01,5.583128003202432410e+02,2.608824445716719787e-01,1.100000010988609489e+01,2.721484224124932298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614311807844005386e+01,5.583228002832108814e+02,2.609096593803189035e-01,1.100000010988609489e+01,2.721338238723394580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614402716934006321e+01,5.583328002461825008e+02,2.609368727291171974e-01,1.100000010988609489e+01,2.721192253321856862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614493626024007256e+01,5.583428002091580993e+02,2.609640846180669160e-01,1.100000010988609489e+01,2.721046267920319145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614584535114008190e+01,5.583528001721376768e+02,2.609912950471680038e-01,1.100000010988609489e+01,2.720900282518781427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614675444204009125e+01,5.583628001351212333e+02,2.610185040164204606e-01,1.100000010988609489e+01,2.720754297117243710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614766353294010059e+01,5.583728000981087689e+02,2.610457115258243421e-01,1.100000010988609489e+01,2.720608311715705992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614857262384010994e+01,5.583828000611002835e+02,2.610729175753795928e-01,1.100000010988609489e+01,2.720462326314168275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.614948171474011929e+01,5.583928000240957772e+02,2.611001221650862125e-01,1.100000010988609489e+01,2.720316340912630557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615039080564012863e+01,5.584027999870952499e+02,2.611273252949442569e-01,1.100000010988609489e+01,2.720170355511092840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615129989654013798e+01,5.584127999500985879e+02,2.611545269649536705e-01,1.100000010988609489e+01,2.720024370109555122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615220898744014733e+01,5.584227999131059050e+02,2.611817271751144531e-01,1.100000010988609489e+01,2.719878384708017405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615311807834015667e+01,5.584327998761172012e+02,2.612089259254266049e-01,1.100000010988609489e+01,2.719732399306479687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615402716924016602e+01,5.584427998391324763e+02,2.612361232158901814e-01,1.100000010988609489e+01,2.719586413904941970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615493626014017536e+01,5.584527998021517305e+02,2.612633190465051269e-01,1.100000010988609489e+01,2.719440428503404252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615584535104018471e+01,5.584627997651749638e+02,2.612905134172714416e-01,1.100000010988609489e+01,2.719294443101866535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615675444194019406e+01,5.584727997282021761e+02,2.613177063281891255e-01,1.100000010988609489e+01,2.719148457700328817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615766353284020340e+01,5.584827996912333674e+02,2.613448977792582339e-01,1.100000010988609489e+01,2.719002472298791100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615857262374021275e+01,5.584927996542685378e+02,2.613720877704787116e-01,1.100000010988609489e+01,2.718856486897253382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.615948171464022209e+01,5.585027996173076872e+02,2.613992763018505583e-01,1.100000010988609489e+01,2.718710501495715665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616039080554023144e+01,5.585127995803508156e+02,2.614264633733737742e-01,1.100000010988609489e+01,2.718564516094177947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616129989644024079e+01,5.585227995433979231e+02,2.614536489850484147e-01,1.100000010988609489e+01,2.718418530692640230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616220898734025013e+01,5.585327995064488960e+02,2.614808331368744243e-01,1.100000010988609489e+01,2.718272545291102512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616311807824025948e+01,5.585427994695038478e+02,2.615080158288518031e-01,1.100000010988609489e+01,2.718126559889564794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616402716914026882e+01,5.585527994325627787e+02,2.615351970609805510e-01,1.100000010988609489e+01,2.717980574488027077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616493626004027817e+01,5.585627993956256887e+02,2.615623768332606680e-01,1.100000010988609489e+01,2.717834589086489359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616584535094028752e+01,5.585727993586925777e+02,2.615895551456921542e-01,1.100000010988609489e+01,2.717688603684951642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616675444184029686e+01,5.585827993217634457e+02,2.616167319982750095e-01,1.100000010988609489e+01,2.717542618283413924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616766353274030621e+01,5.585927992848382928e+02,2.616439073910092894e-01,1.100000010988609489e+01,2.717396632881876207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616857262364031556e+01,5.586027992479171189e+02,2.616710813238949385e-01,1.100000010988609489e+01,2.717250647480338489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.616948171454032490e+01,5.586127992109999241e+02,2.616982537969319567e-01,1.100000010988609489e+01,2.717104662078800772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617039080544033425e+01,5.586227991740867083e+02,2.617254248101203440e-01,1.100000010988609489e+01,2.716958676677263054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617129989634034359e+01,5.586327991371773578e+02,2.617525943634601004e-01,1.100000010988609489e+01,2.716812691275725337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617220898724035294e+01,5.586427991002719864e+02,2.617797624569512260e-01,1.100000010988609489e+01,2.716666705874187619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617311807814036229e+01,5.586527990633705940e+02,2.618069290905937208e-01,1.100000010988609489e+01,2.716520720472649902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617402716904037163e+01,5.586627990264731807e+02,2.618340942643875846e-01,1.100000010988609489e+01,2.716374735071112184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617493625994038098e+01,5.586727989895797464e+02,2.618612579783328176e-01,1.100000010988609489e+01,2.716228749669574467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617584535084039032e+01,5.586827989526902911e+02,2.618884202324294197e-01,1.100000010988609489e+01,2.716082764268036749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617675444174039967e+01,5.586927989158048149e+02,2.619155810266773909e-01,1.100000010988609489e+01,2.715936778866499032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617766353264040902e+01,5.587027988789233177e+02,2.619427403610767313e-01,1.100000010988609489e+01,2.715790793464961314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617857262354041836e+01,5.587127988420456859e+02,2.619698982356274408e-01,1.100000010988609489e+01,2.715644808063423597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.617948171444042771e+01,5.587227988051720331e+02,2.619970546503295195e-01,1.100000010988609489e+01,2.715498822661885879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618039080534043705e+01,5.587327987683023593e+02,2.620242096051829672e-01,1.100000010988609489e+01,2.715352837260348162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618129989624044640e+01,5.587427987314366646e+02,2.620513631001877841e-01,1.100000010988609489e+01,2.715206851858810444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618220898714045575e+01,5.587527986945749490e+02,2.620785151353439701e-01,1.100000010988609489e+01,2.715060866457272726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618311807804046509e+01,5.587627986577172123e+02,2.621056657106515253e-01,1.100000010988609489e+01,2.714914881055735009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618402716894047444e+01,5.587727986208634547e+02,2.621328148261104496e-01,1.100000010988609489e+01,2.714768895654197291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618493625984048379e+01,5.587827985840136762e+02,2.621599624817207430e-01,1.100000010988609489e+01,2.714622910252659574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618584535074049313e+01,5.587927985471677630e+02,2.621871086774824056e-01,1.100000010988609489e+01,2.714476924851121856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618675444164050248e+01,5.588027985103258288e+02,2.622142534133954372e-01,1.100000010988609489e+01,2.714330939449584139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618766353254051182e+01,5.588127984734878737e+02,2.622413966894597825e-01,1.100000010988609489e+01,2.714184954048046421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618857262344052117e+01,5.588227984366538976e+02,2.622685385056754970e-01,1.100000010988609489e+01,2.714038968646508704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.618948171434053052e+01,5.588327983998239006e+02,2.622956788620425805e-01,1.100000010988609489e+01,2.713892983244970986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619039080524053986e+01,5.588427983629978826e+02,2.623228177585610332e-01,1.100000010988609489e+01,2.713746997843433269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619129989614054921e+01,5.588527983261758436e+02,2.623499551952308551e-01,1.100000010988609489e+01,2.713601012441895551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619220898704055855e+01,5.588627982893576700e+02,2.623770911720520460e-01,1.100000010988609489e+01,2.713455027040357834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619311807794056790e+01,5.588727982525434754e+02,2.624042256890245506e-01,1.100000010988609489e+01,2.713309041638820116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619402716884057725e+01,5.588827982157332599e+02,2.624313587461484243e-01,1.100000010988609489e+01,2.713163056237282399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619493625974058659e+01,5.588927981789270234e+02,2.624584903434236671e-01,1.100000010988609489e+01,2.713017070835744681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619584535064059594e+01,5.589027981421247659e+02,2.624856204808502791e-01,1.100000010988609489e+01,2.712871085434206964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619675444154060528e+01,5.589127981053264875e+02,2.625127491584282602e-01,1.100000010988609489e+01,2.712725100032669246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619766353244061463e+01,5.589227980685320745e+02,2.625398763761575549e-01,1.100000010988609489e+01,2.712579114631131529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619857262334062398e+01,5.589327980317416404e+02,2.625670021340382188e-01,1.100000010988609489e+01,2.712433129229593811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.619948171424063332e+01,5.589427979949551855e+02,2.625941264320702517e-01,1.100000010988609489e+01,2.712287143828056094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620039080514064267e+01,5.589527979581727095e+02,2.626212492702536538e-01,1.100000010988609489e+01,2.712141158426518376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620129989604065202e+01,5.589627979213942126e+02,2.626483706485883696e-01,1.100000010988609489e+01,2.711995173024980658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620220898694066136e+01,5.589727978846196947e+02,2.626754905670744544e-01,1.100000010988609489e+01,2.711849187623442941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620311807784067071e+01,5.589827978478490422e+02,2.627026090257119084e-01,1.100000010988609489e+01,2.711703202221905223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620402716874068005e+01,5.589927978110823688e+02,2.627297260245007315e-01,1.100000010988609489e+01,2.711557216820367506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620493625964068940e+01,5.590027977743196743e+02,2.627568415634408683e-01,1.100000010988609489e+01,2.711411231418829788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620584535054069875e+01,5.590127977375609589e+02,2.627839556425323742e-01,1.100000010988609489e+01,2.711265246017292071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620675444144070809e+01,5.590227977008062226e+02,2.628110682617752492e-01,1.100000010988609489e+01,2.711119260615754353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620766353234071744e+01,5.590327976640553516e+02,2.628381794211694378e-01,1.100000010988609489e+01,2.710973275214216636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620857262324072678e+01,5.590427976273084596e+02,2.628652891207149955e-01,1.100000010988609489e+01,2.710827289812678918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.620948171414073613e+01,5.590527975905655467e+02,2.628923973604119224e-01,1.100000010988609489e+01,2.710681304411141201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621039080504074548e+01,5.590627975538266128e+02,2.629195041402601629e-01,1.100000010988609489e+01,2.710535319009603483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621129989594075482e+01,5.590727975170916579e+02,2.629466094602597726e-01,1.100000010988609489e+01,2.710389333608065766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621220898684076417e+01,5.590827974803606821e+02,2.629737133204106958e-01,1.100000010988609489e+01,2.710243348206528048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621311807774077351e+01,5.590927974436335717e+02,2.630008157207129882e-01,1.100000010988609489e+01,2.710097362804990331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621402716864078286e+01,5.591027974069104403e+02,2.630279166611666497e-01,1.100000010988609489e+01,2.709951377403452613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621493625954079221e+01,5.591127973701912879e+02,2.630550161417716248e-01,1.100000010988609489e+01,2.709805392001914896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621584535044080155e+01,5.591227973334761145e+02,2.630821141625279691e-01,1.100000010988609489e+01,2.709659406600377178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621675444134081090e+01,5.591327972967649202e+02,2.631092107234356270e-01,1.100000010988609489e+01,2.709513421198839461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621766353224082025e+01,5.591427972600575913e+02,2.631363058244946540e-01,1.100000010988609489e+01,2.709367435797301743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621857262314082959e+01,5.591527972233542414e+02,2.631633994657049946e-01,1.100000010988609489e+01,2.709221450395764026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.621948171404083894e+01,5.591627971866548705e+02,2.631904916470667044e-01,1.100000010988609489e+01,2.709075464994226308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622039080494084828e+01,5.591727971499594787e+02,2.632175823685797278e-01,1.100000010988609489e+01,2.708929479592688590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622129989584085763e+01,5.591827971132679522e+02,2.632446716302441203e-01,1.100000010988609489e+01,2.708783494191150873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622220898674086698e+01,5.591927970765804048e+02,2.632717594320598264e-01,1.100000010988609489e+01,2.708637508789613155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622311807764087632e+01,5.592027970398968364e+02,2.632988457740269017e-01,1.100000010988609489e+01,2.708491523388075438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622402716854088567e+01,5.592127970032172470e+02,2.633259306561452906e-01,1.100000010988609489e+01,2.708345537986537720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622493625944089501e+01,5.592227969665416367e+02,2.633530140784150486e-01,1.100000010988609489e+01,2.708199552585000003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622584535034090436e+01,5.592327969298698918e+02,2.633800960408361203e-01,1.100000010988609489e+01,2.708053567183462285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622675444124091371e+01,5.592427968932021258e+02,2.634071765434085610e-01,1.100000010988609489e+01,2.707907581781924568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622766353214092305e+01,5.592527968565383389e+02,2.634342555861323154e-01,1.100000010988609489e+01,2.707761596380386850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622857262304093240e+01,5.592627968198785311e+02,2.634613331690073834e-01,1.100000010988609489e+01,2.707615610978849133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.622948171394094175e+01,5.592727967832225886e+02,2.634884092920338206e-01,1.100000010988609489e+01,2.707469625577311415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623039080484095109e+01,5.592827967465706251e+02,2.635154839552115713e-01,1.100000010988609489e+01,2.707323640175773698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623129989574096044e+01,5.592927967099226407e+02,2.635425571585406912e-01,1.100000010988609489e+01,2.707177654774235980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623220898664096978e+01,5.593027966732786354e+02,2.635696289020211247e-01,1.100000010988609489e+01,2.707031669372698263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623311807754097913e+01,5.593127966366386090e+02,2.635966991856528718e-01,1.100000010988609489e+01,2.706885683971160545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623402716844098848e+01,5.593227966000024480e+02,2.636237680094359881e-01,1.100000010988609489e+01,2.706739698569622828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623493625934099782e+01,5.593327965633702661e+02,2.636508353733704180e-01,1.100000010988609489e+01,2.706593713168085110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623584535024100717e+01,5.593427965267420632e+02,2.636779012774561615e-01,1.100000010988609489e+01,2.706447727766547393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623675444114101651e+01,5.593527964901178393e+02,2.637049657216932741e-01,1.100000010988609489e+01,2.706301742365009675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623766353204102586e+01,5.593627964534974808e+02,2.637320287060817003e-01,1.100000010988609489e+01,2.706155756963471957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623857262294103521e+01,5.593727964168811013e+02,2.637590902306214402e-01,1.100000010988609489e+01,2.706009771561934240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.623948171384104455e+01,5.593827963802687009e+02,2.637861502953125492e-01,1.100000010988609489e+01,2.705863786160396522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624039080474105390e+01,5.593927963436602795e+02,2.638132089001549718e-01,1.100000010988609489e+01,2.705717800758858805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624129989564106324e+01,5.594027963070557234e+02,2.638402660451487081e-01,1.100000010988609489e+01,2.705571815357321087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624220898654107259e+01,5.594127962704551464e+02,2.638673217302937579e-01,1.100000010988609489e+01,2.705425829955783370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624311807744108194e+01,5.594227962338585485e+02,2.638943759555901769e-01,1.100000010988609489e+01,2.705279844554245652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624402716834109128e+01,5.594327961972659295e+02,2.639214287210379095e-01,1.100000010988609489e+01,2.705133859152707935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624493625924110063e+01,5.594427961606771760e+02,2.639484800266369557e-01,1.100000010988609489e+01,2.704987873751170217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624584535014110998e+01,5.594527961240924014e+02,2.639755298723873156e-01,1.100000010988609489e+01,2.704841888349632500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624675444104111932e+01,5.594627960875116059e+02,2.640025782582890446e-01,1.100000010988609489e+01,2.704695902948094782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624766353194112867e+01,5.594727960509346758e+02,2.640296251843420872e-01,1.100000010988609489e+01,2.704549917546557065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624857262284113801e+01,5.594827960143617247e+02,2.640566706505464434e-01,1.100000010988609489e+01,2.704403932145019347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.624948171374114736e+01,5.594927959777927526e+02,2.640837146569021132e-01,1.100000010988609489e+01,2.704257946743481630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625039080464115671e+01,5.595027959412277596e+02,2.641107572034090967e-01,1.100000010988609489e+01,2.704111961341943912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625129989554116605e+01,5.595127959046666319e+02,2.641377982900673937e-01,1.100000010988609489e+01,2.703965975940406195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625220898644117540e+01,5.595227958681094833e+02,2.641648379168770600e-01,1.100000010988609489e+01,2.703819990538868477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625311807734118474e+01,5.595327958315563137e+02,2.641918760838380398e-01,1.100000010988609489e+01,2.703674005137330760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625402716824119409e+01,5.595427957950071232e+02,2.642189127909503332e-01,1.100000010988609489e+01,2.703528019735793042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625493625914120344e+01,5.595527957584617980e+02,2.642459480382139403e-01,1.100000010988609489e+01,2.703382034334255325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625584535004121278e+01,5.595627957219204518e+02,2.642729818256288610e-01,1.100000010988609489e+01,2.703236048932717607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625675444094122213e+01,5.595727956853830847e+02,2.643000141531950953e-01,1.100000010988609489e+01,2.703090063531179889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625766353184123147e+01,5.595827956488495829e+02,2.643270450209126432e-01,1.100000010988609489e+01,2.702944078129642172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625857262274124082e+01,5.595927956123200602e+02,2.643540744287815047e-01,1.100000010988609489e+01,2.702798092728104454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.625948171364125017e+01,5.596027955757945165e+02,2.643811023768016799e-01,1.100000010988609489e+01,2.702652107326566737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626039080454125951e+01,5.596127955392729518e+02,2.644081288649731687e-01,1.100000010988609489e+01,2.702506121925029019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626129989544126886e+01,5.596227955027552525e+02,2.644351538932959711e-01,1.100000010988609489e+01,2.702360136523491302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626220898634127821e+01,5.596327954662415323e+02,2.644621774617701426e-01,1.100000010988609489e+01,2.702214151121953584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626311807724128755e+01,5.596427954297317910e+02,2.644891995703956278e-01,1.100000010988609489e+01,2.702068165720415867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626402716814129690e+01,5.596527953932259152e+02,2.645162202191724266e-01,1.100000010988609489e+01,2.701922180318878149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626493625904130624e+01,5.596627953567240183e+02,2.645432394081005389e-01,1.100000010988609489e+01,2.701776194917340432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626584534994131559e+01,5.596727953202261006e+02,2.645702571371799650e-01,1.100000010988609489e+01,2.701630209515802714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626675444084132494e+01,5.596827952837320481e+02,2.645972734064107046e-01,1.100000010988609489e+01,2.701484224114264997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626766353174133428e+01,5.596927952472419747e+02,2.646242882157927023e-01,1.100000010988609489e+01,2.701338238712727279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626857262264134363e+01,5.597027952107558804e+02,2.646513015653260137e-01,1.100000010988609489e+01,2.701192253311189562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.626948171354135297e+01,5.597127951742736514e+02,2.646783134550106387e-01,1.100000010988609489e+01,2.701046267909651844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627039080444136232e+01,5.597227951377954014e+02,2.647053238848465773e-01,1.100000010988609489e+01,2.700900282508114127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627129989534137167e+01,5.597327951013211305e+02,2.647323328548338295e-01,1.100000010988609489e+01,2.700754297106576409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627220898624138101e+01,5.597427950648508386e+02,2.647593403649723953e-01,1.100000010988609489e+01,2.700608311705038692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627311807714139036e+01,5.597527950283844120e+02,2.647863464152622748e-01,1.100000010988609489e+01,2.700462326303500974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627402716804139970e+01,5.597627949919219645e+02,2.648133510057034679e-01,1.100000010988609489e+01,2.700316340901963257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627493625894140905e+01,5.597727949554634961e+02,2.648403541362959746e-01,1.100000010988609489e+01,2.700170355500425539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627584534984141840e+01,5.597827949190088930e+02,2.648673558070397949e-01,1.100000010988609489e+01,2.700024370098887821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627675444074142774e+01,5.597927948825582689e+02,2.648943560179349288e-01,1.100000010988609489e+01,2.699878384697350104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627766353164143709e+01,5.598027948461116239e+02,2.649213547689813208e-01,1.100000010988609489e+01,2.699732399295812386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627857262254144644e+01,5.598127948096688442e+02,2.649483520601790265e-01,1.100000010988609489e+01,2.699586413894274669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.627948171344145578e+01,5.598227947732300436e+02,2.649753478915280458e-01,1.100000010988609489e+01,2.699440428492736951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628039080434146513e+01,5.598327947367952220e+02,2.650023422630283787e-01,1.100000010988609489e+01,2.699294443091199234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628129989524147447e+01,5.598427947003642657e+02,2.650293351746800252e-01,1.100000010988609489e+01,2.699148457689661516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628220898614148382e+01,5.598527946639372885e+02,2.650563266264829854e-01,1.100000010988609489e+01,2.699002472288123799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628311807704149317e+01,5.598627946275142904e+02,2.650833166184372036e-01,1.100000010988609489e+01,2.698856486886586081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628402716794150251e+01,5.598727945910951576e+02,2.651103051505427355e-01,1.100000010988609489e+01,2.698710501485048364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628493625884151186e+01,5.598827945546800038e+02,2.651372922227995810e-01,1.100000010988609489e+01,2.698564516083510646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628584534974152120e+01,5.598927945182688291e+02,2.651642778352077401e-01,1.100000010988609489e+01,2.698418530681972929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628675444064153055e+01,5.599027944818615197e+02,2.651912619877671573e-01,1.100000010988609489e+01,2.698272545280435211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628766353154153990e+01,5.599127944454581893e+02,2.652182446804778881e-01,1.100000010988609489e+01,2.698126559878897494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628857262244154924e+01,5.599227944090587243e+02,2.652452259133399326e-01,1.100000010988609489e+01,2.697980574477359776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.628948171334155859e+01,5.599327943726632384e+02,2.652722056863532907e-01,1.100000010988609489e+01,2.697834589075822059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629039080424156793e+01,5.599427943362717315e+02,2.652991839995179069e-01,1.100000010988609489e+01,2.697688603674284341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629129989514157728e+01,5.599527942998840899e+02,2.653261608528338367e-01,1.100000010988609489e+01,2.697542618272746624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629220898604158663e+01,5.599627942635004274e+02,2.653531362463010801e-01,1.100000010988609489e+01,2.697396632871208906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629311807694159597e+01,5.599727942271207439e+02,2.653801101799195816e-01,1.100000010988609489e+01,2.697250647469671189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629402716784160532e+01,5.599827941907449258e+02,2.654070826536893968e-01,1.100000010988609489e+01,2.697104662068133471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629493625874161467e+01,5.599927941543730867e+02,2.654340536676105256e-01,1.100000010988609489e+01,2.696958676666595753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629584534964162401e+01,5.600027941180052267e+02,2.654610232216829124e-01,1.100000010988609489e+01,2.696812691265058036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629675444054163336e+01,5.600127940816412320e+02,2.654879913159066129e-01,1.100000010988609489e+01,2.696666705863520318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629766353144164270e+01,5.600227940452812163e+02,2.655149579502816271e-01,1.100000010988609489e+01,2.696520720461982601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629857262234165205e+01,5.600327940089250660e+02,2.655419231248078993e-01,1.100000010988609489e+01,2.696374735060444883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.629948171324166140e+01,5.600427939725728947e+02,2.655688868394854851e-01,1.100000010988609489e+01,2.696228749658907166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630039080414167074e+01,5.600527939362247025e+02,2.655958490943143291e-01,1.100000010988609489e+01,2.696082764257369448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630129989504168009e+01,5.600627938998803756e+02,2.656228098892944867e-01,1.100000010988609489e+01,2.695936778855831731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630220898594168943e+01,5.600727938635400278e+02,2.656497692244259579e-01,1.100000010988609489e+01,2.695790793454294013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630311807684169878e+01,5.600827938272036590e+02,2.656767270997086872e-01,1.100000010988609489e+01,2.695644808052756296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630402716774170813e+01,5.600927937908711556e+02,2.657036835151427301e-01,1.100000010988609489e+01,2.695498822651218578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630493625864171747e+01,5.601027937545426312e+02,2.657306384707280311e-01,1.100000010988609489e+01,2.695352837249680861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630584534954172682e+01,5.601127937182179721e+02,2.657575919664646458e-01,1.100000010988609489e+01,2.695206851848143143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630675444044173616e+01,5.601227936818972921e+02,2.657845440023525185e-01,1.100000010988609489e+01,2.695060866446605426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630766353134174551e+01,5.601327936455805911e+02,2.658114945783917049e-01,1.100000010988609489e+01,2.694914881045067708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630857262224175486e+01,5.601427936092677555e+02,2.658384436945821494e-01,1.100000010988609489e+01,2.694768895643529991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.630948171314176420e+01,5.601527935729588989e+02,2.658653913509239075e-01,1.100000010988609489e+01,2.694622910241992273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631039080404177355e+01,5.601627935366539077e+02,2.658923375474169237e-01,1.100000010988609489e+01,2.694476924840454556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631129989494178290e+01,5.601727935003528955e+02,2.659192822840612536e-01,1.100000010988609489e+01,2.694330939438916838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631220898584179224e+01,5.601827934640558624e+02,2.659462255608568415e-01,1.100000010988609489e+01,2.694184954037379121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631311807674180159e+01,5.601927934277626946e+02,2.659731673778037431e-01,1.100000010988609489e+01,2.694038968635841403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631402716764181093e+01,5.602027933914735058e+02,2.660001077349019027e-01,1.100000010988609489e+01,2.693892983234303685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631493625854182028e+01,5.602127933551881824e+02,2.660270466321513760e-01,1.100000010988609489e+01,2.693746997832765968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631584534944182963e+01,5.602227933189068381e+02,2.660539840695521074e-01,1.100000010988609489e+01,2.693601012431228250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631675444034183897e+01,5.602327932826294727e+02,2.660809200471040969e-01,1.100000010988609489e+01,2.693455027029690533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631766353124184832e+01,5.602427932463559728e+02,2.661078545648074001e-01,1.100000010988609489e+01,2.693309041628152815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631857262214185766e+01,5.602527932100864518e+02,2.661347876226619613e-01,1.100000010988609489e+01,2.693163056226615098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.631948171304186701e+01,5.602627931738207963e+02,2.661617192206678362e-01,1.100000010988609489e+01,2.693017070825077380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632039080394187636e+01,5.602727931375591197e+02,2.661886493588249691e-01,1.100000010988609489e+01,2.692871085423539663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632129989484188570e+01,5.602827931013014222e+02,2.662155780371333602e-01,1.100000010988609489e+01,2.692725100022001945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632220898574189505e+01,5.602927930650475901e+02,2.662425052555930649e-01,1.100000010988609489e+01,2.692579114620464228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632311807664190439e+01,5.603027930287977370e+02,2.662694310142040277e-01,1.100000010988609489e+01,2.692433129218926510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632402716754191374e+01,5.603127929925517492e+02,2.662963553129662486e-01,1.100000010988609489e+01,2.692287143817388793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632493625844192309e+01,5.603227929563097405e+02,2.663232781518797831e-01,1.100000010988609489e+01,2.692141158415851075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632584534934193243e+01,5.603327929200715971e+02,2.663501995309445758e-01,1.100000010988609489e+01,2.691995173014313358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632675444024194178e+01,5.603427928838374328e+02,2.663771194501606265e-01,1.100000010988609489e+01,2.691849187612775640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632766353114195113e+01,5.603527928476072475e+02,2.664040379095279909e-01,1.100000010988609489e+01,2.691703202211237923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632857262204196047e+01,5.603627928113809276e+02,2.664309549090466134e-01,1.100000010988609489e+01,2.691557216809700205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.632948171294196982e+01,5.603727927751585867e+02,2.664578704487164940e-01,1.100000010988609489e+01,2.691411231408162488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633039080384197916e+01,5.603827927389401111e+02,2.664847845285376327e-01,1.100000010988609489e+01,2.691265246006624770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633129989474198851e+01,5.603927927027256146e+02,2.665116971485100850e-01,1.100000010988609489e+01,2.691119260605087053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633220898564199786e+01,5.604027926665149835e+02,2.665386083086337954e-01,1.100000010988609489e+01,2.690973275203549335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633311807654200720e+01,5.604127926303083314e+02,2.665655180089087639e-01,1.100000010988609489e+01,2.690827289802011617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633402716744201655e+01,5.604227925941055446e+02,2.665924262493349906e-01,1.100000010988609489e+01,2.690681304400473900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633493625834202589e+01,5.604327925579067369e+02,2.666193330299124753e-01,1.100000010988609489e+01,2.690535318998936182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633584534924203524e+01,5.604427925217119082e+02,2.666462383506412737e-01,1.100000010988609489e+01,2.690389333597398465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633675444014204459e+01,5.604527924855209449e+02,2.666731422115213301e-01,1.100000010988609489e+01,2.690243348195860747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633766353104205393e+01,5.604627924493339606e+02,2.667000446125526447e-01,1.100000010988609489e+01,2.690097362794323030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633857262194206328e+01,5.604727924131508416e+02,2.667269455537352174e-01,1.100000010988609489e+01,2.689951377392785312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.633948171284207262e+01,5.604827923769717017e+02,2.667538450350690482e-01,1.100000010988609489e+01,2.689805391991247595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634039080374208197e+01,5.604927923407964272e+02,2.667807430565541371e-01,1.100000010988609489e+01,2.689659406589709877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634129989464209132e+01,5.605027923046251317e+02,2.668076396181905396e-01,1.100000010988609489e+01,2.689513421188172160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634220898554210066e+01,5.605127922684577015e+02,2.668345347199782003e-01,1.100000010988609489e+01,2.689367435786634442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634311807644211001e+01,5.605227922322942504e+02,2.668614283619171190e-01,1.100000010988609489e+01,2.689221450385096725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634402716734211936e+01,5.605327921961346647e+02,2.668883205440072959e-01,1.100000010988609489e+01,2.689075464983559007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634493625824212870e+01,5.605427921599790579e+02,2.669152112662487308e-01,1.100000010988609489e+01,2.688929479582021290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634584534914213805e+01,5.605527921238273166e+02,2.669421005286414239e-01,1.100000010988609489e+01,2.688783494180483572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634675444004214739e+01,5.605627920876795542e+02,2.669689883311853751e-01,1.100000010988609489e+01,2.688637508778945855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634766353094215674e+01,5.605727920515357710e+02,2.669958746738805844e-01,1.100000010988609489e+01,2.688491523377408137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634857262184216609e+01,5.605827920153958530e+02,2.670227595567270518e-01,1.100000010988609489e+01,2.688345537975870420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.634948171274217543e+01,5.605927919792599141e+02,2.670496429797247773e-01,1.100000010988609489e+01,2.688199552574332702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635039080364218478e+01,5.606027919431278406e+02,2.670765249428737609e-01,1.100000010988609489e+01,2.688053567172794985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635129989454219412e+01,5.606127919069997461e+02,2.671034054461740026e-01,1.100000010988609489e+01,2.687907581771257267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635220898544220347e+01,5.606227918708755169e+02,2.671302844896255024e-01,1.100000010988609489e+01,2.687761596369719549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635311807634221282e+01,5.606327918347552668e+02,2.671571620732282604e-01,1.100000010988609489e+01,2.687615610968181832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635402716724222216e+01,5.606427917986388820e+02,2.671840381969822764e-01,1.100000010988609489e+01,2.687469625566644114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635493625814223151e+01,5.606527917625264763e+02,2.672109128608875506e-01,1.100000010988609489e+01,2.687323640165106397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635584534904224085e+01,5.606627917264179359e+02,2.672377860649440828e-01,1.100000010988609489e+01,2.687177654763568679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635675443994225020e+01,5.606727916903133746e+02,2.672646578091518732e-01,1.100000010988609489e+01,2.687031669362030962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635766353084225955e+01,5.606827916542126786e+02,2.672915280935109217e-01,1.100000010988609489e+01,2.686885683960493244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635857262174226889e+01,5.606927916181159617e+02,2.673183969180212283e-01,1.100000010988609489e+01,2.686739698558955527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.635948171264227824e+01,5.607027915820231101e+02,2.673452642826827930e-01,1.100000010988609489e+01,2.686593713157417809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636039080354228759e+01,5.607127915459342375e+02,2.673721301874956158e-01,1.100000010988609489e+01,2.686447727755880092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636129989444229693e+01,5.607227915098492304e+02,2.673989946324596967e-01,1.100000010988609489e+01,2.686301742354342374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636220898534230628e+01,5.607327914737682022e+02,2.674258576175750357e-01,1.100000010988609489e+01,2.686155756952804657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636311807624231562e+01,5.607427914376910394e+02,2.674527191428416328e-01,1.100000010988609489e+01,2.686009771551266939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636402716714232497e+01,5.607527914016178556e+02,2.674795792082594881e-01,1.100000010988609489e+01,2.685863786149729222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636493625804233432e+01,5.607627913655485372e+02,2.675064378138285459e-01,1.100000010988609489e+01,2.685717800748191504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636584534894234366e+01,5.607727913294831978e+02,2.675332949595488619e-01,1.100000010988609489e+01,2.685571815346653787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636675443984235301e+01,5.607827912934217238e+02,2.675601506454204359e-01,1.100000010988609489e+01,2.685425829945116069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636766353074236235e+01,5.607927912573642288e+02,2.675870048714432681e-01,1.100000010988609489e+01,2.685279844543578352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636857262164237170e+01,5.608027912213105992e+02,2.676138576376173583e-01,1.100000010988609489e+01,2.685133859142040634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.636948171254238105e+01,5.608127911852609486e+02,2.676407089439427067e-01,1.100000010988609489e+01,2.684987873740502917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637039080344239039e+01,5.608227911492151634e+02,2.676675587904192577e-01,1.100000010988609489e+01,2.684841888338965199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637129989434239974e+01,5.608327911131733572e+02,2.676944071770470668e-01,1.100000010988609489e+01,2.684695902937427481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637220898524240909e+01,5.608427910771354163e+02,2.677212541038261340e-01,1.100000010988609489e+01,2.684549917535889764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637311807614241843e+01,5.608527910411013409e+02,2.677480995707564593e-01,1.100000010988609489e+01,2.684403932134352046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637402716704242778e+01,5.608627910050712444e+02,2.677749435778379872e-01,1.100000010988609489e+01,2.684257946732814329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637493625794243712e+01,5.608727909690450133e+02,2.678017861250707732e-01,1.100000010988609489e+01,2.684111961331276611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637584534884244647e+01,5.608827909330227612e+02,2.678286272124548173e-01,1.100000010988609489e+01,2.683965975929738894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637675443974245582e+01,5.608927908970043745e+02,2.678554668399901195e-01,1.100000010988609489e+01,2.683819990528201176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637766353064246516e+01,5.609027908609899669e+02,2.678823050076766243e-01,1.100000010988609489e+01,2.683674005126663459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637857262154247451e+01,5.609127908249794245e+02,2.679091417155143873e-01,1.100000010988609489e+01,2.683528019725125741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.637948171244248385e+01,5.609227907889728613e+02,2.679359769635034083e-01,1.100000010988609489e+01,2.683382034323588024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638039080334249320e+01,5.609327907529701633e+02,2.679628107516436875e-01,1.100000010988609489e+01,2.683236048922050306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638129989424250255e+01,5.609427907169714445e+02,2.679896430799351692e-01,1.100000010988609489e+01,2.683090063520512589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638220898514251189e+01,5.609527906809765909e+02,2.680164739483779091e-01,1.100000010988609489e+01,2.682944078118974871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638311807604252124e+01,5.609627906449857164e+02,2.680433033569719070e-01,1.100000010988609489e+01,2.682798092717437154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638402716694253058e+01,5.609727906089987073e+02,2.680701313057171076e-01,1.100000010988609489e+01,2.682652107315899436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638493625784253993e+01,5.609827905730155635e+02,2.680969577946135662e-01,1.100000010988609489e+01,2.682506121914361719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638584534874254928e+01,5.609927905370363987e+02,2.681237828236612275e-01,1.100000010988609489e+01,2.682360136512824001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638675443964255862e+01,5.610027905010610993e+02,2.681506063928601469e-01,1.100000010988609489e+01,2.682214151111286284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638766353054256797e+01,5.610127904650897790e+02,2.681774285022103244e-01,1.100000010988609489e+01,2.682068165709748566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638857262144257732e+01,5.610227904291223240e+02,2.682042491517117044e-01,1.100000010988609489e+01,2.681922180308210849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.638948171234258666e+01,5.610327903931588480e+02,2.682310683413643426e-01,1.100000010988609489e+01,2.681776194906673131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639039080324259601e+01,5.610427903571992374e+02,2.682578860711681834e-01,1.100000010988609489e+01,2.681630209505135413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639129989414260535e+01,5.610527903212436058e+02,2.682847023411232823e-01,1.100000010988609489e+01,2.681484224103597696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639220898504261470e+01,5.610627902852918396e+02,2.683115171512296393e-01,1.100000010988609489e+01,2.681338238702059978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639311807594262405e+01,5.610727902493439387e+02,2.683383305014871989e-01,1.100000010988609489e+01,2.681192253300522261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639402716684263339e+01,5.610827902134000169e+02,2.683651423918960166e-01,1.100000010988609489e+01,2.681046267898984543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639493625774264274e+01,5.610927901774599604e+02,2.683919528224560369e-01,1.100000010988609489e+01,2.680900282497446826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639584534864265208e+01,5.611027901415238830e+02,2.684187617931673153e-01,1.100000010988609489e+01,2.680754297095909108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639675443954266143e+01,5.611127901055916709e+02,2.684455693040297963e-01,1.100000010988609489e+01,2.680608311694371391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639766353044267078e+01,5.611227900696634379e+02,2.684723753550435354e-01,1.100000010988609489e+01,2.680462326292833673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639857262134268012e+01,5.611327900337390702e+02,2.684991799462084772e-01,1.100000010988609489e+01,2.680316340891295956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.639948171224268947e+01,5.611427899978185678e+02,2.685259830775246770e-01,1.100000010988609489e+01,2.680170355489758238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640039080314269881e+01,5.611527899619020445e+02,2.685527847489920794e-01,1.100000010988609489e+01,2.680024370088220521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640129989404270816e+01,5.611627899259893866e+02,2.685795849606106844e-01,1.100000010988609489e+01,2.679878384686682803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640220898494271751e+01,5.611727898900807077e+02,2.686063837123805476e-01,1.100000010988609489e+01,2.679732399285145086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640311807584272685e+01,5.611827898541758941e+02,2.686331810043016133e-01,1.100000010988609489e+01,2.679586413883607368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640402716674273620e+01,5.611927898182749459e+02,2.686599768363739371e-01,1.100000010988609489e+01,2.679440428482069651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640493625764274555e+01,5.612027897823779767e+02,2.686867712085974635e-01,1.100000010988609489e+01,2.679294443080531933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640584534854275489e+01,5.612127897464848729e+02,2.687135641209722481e-01,1.100000010988609489e+01,2.679148457678994216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640675443944276424e+01,5.612227897105957481e+02,2.687403555734982352e-01,1.100000010988609489e+01,2.679002472277456498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640766353034277358e+01,5.612327896747104887e+02,2.687671455661754250e-01,1.100000010988609489e+01,2.678856486875918781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640857262124278293e+01,5.612427896388290947e+02,2.687939340990038728e-01,1.100000010988609489e+01,2.678710501474381063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.640948171214279228e+01,5.612527896029516796e+02,2.688207211719835232e-01,1.100000010988609489e+01,2.678564516072843345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641039080304280162e+01,5.612627895670781299e+02,2.688475067851143763e-01,1.100000010988609489e+01,2.678418530671305628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641129989394281097e+01,5.612727895312085593e+02,2.688742909383964874e-01,1.100000010988609489e+01,2.678272545269767910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641220898484282031e+01,5.612827894953428540e+02,2.689010736318298012e-01,1.100000010988609489e+01,2.678126559868230193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641311807574282966e+01,5.612927894594810141e+02,2.689278548654143175e-01,1.100000010988609489e+01,2.677980574466692475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641402716664283901e+01,5.613027894236231532e+02,2.689546346391500919e-01,1.100000010988609489e+01,2.677834589065154758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641493625754284835e+01,5.613127893877691577e+02,2.689814129530370690e-01,1.100000010988609489e+01,2.677688603663617040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641584534844285770e+01,5.613227893519191412e+02,2.690081898070752486e-01,1.100000010988609489e+01,2.677542618262079323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641675443934286704e+01,5.613327893160729900e+02,2.690349652012646864e-01,1.100000010988609489e+01,2.677396632860541605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641766353024287639e+01,5.613427892802307042e+02,2.690617391356053267e-01,1.100000010988609489e+01,2.677250647459003888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641857262114288574e+01,5.613527892443923974e+02,2.690885116100971697e-01,1.100000010988609489e+01,2.677104662057466170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.641948171204289508e+01,5.613627892085579560e+02,2.691152826247402152e-01,1.100000010988609489e+01,2.676958676655928453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642039080294290443e+01,5.613727891727274937e+02,2.691420521795345189e-01,1.100000010988609489e+01,2.676812691254390735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642129989384291378e+01,5.613827891369008967e+02,2.691688202744800251e-01,1.100000010988609489e+01,2.676666705852853018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642220898474292312e+01,5.613927891010781650e+02,2.691955869095767340e-01,1.100000010988609489e+01,2.676520720451315300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642311807564293247e+01,5.614027890652594124e+02,2.692223520848246454e-01,1.100000010988609489e+01,2.676374735049777583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642402716654294181e+01,5.614127890294445251e+02,2.692491158002237595e-01,1.100000010988609489e+01,2.676228749648239865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642493625744295116e+01,5.614227889936335032e+02,2.692758780557741316e-01,1.100000010988609489e+01,2.676082764246702148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642584534834296051e+01,5.614327889578264603e+02,2.693026388514757063e-01,1.100000010988609489e+01,2.675936778845164430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642675443924296985e+01,5.614427889220232828e+02,2.693293981873284837e-01,1.100000010988609489e+01,2.675790793443626713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642766353014297920e+01,5.614527888862239706e+02,2.693561560633324636e-01,1.100000010988609489e+01,2.675644808042088995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642857262104298854e+01,5.614627888504286375e+02,2.693829124794876462e-01,1.100000010988609489e+01,2.675498822640551277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.642948171194299789e+01,5.614727888146371697e+02,2.694096674357940313e-01,1.100000010988609489e+01,2.675352837239013560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643039080284300724e+01,5.614827887788496810e+02,2.694364209322516190e-01,1.100000010988609489e+01,2.675206851837475842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643129989374301658e+01,5.614927887430660576e+02,2.694631729688604649e-01,1.100000010988609489e+01,2.675060866435938125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643220898464302593e+01,5.615027887072862995e+02,2.694899235456205133e-01,1.100000010988609489e+01,2.674914881034400407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643311807554303527e+01,5.615127886715105205e+02,2.695166726625317644e-01,1.100000010988609489e+01,2.674768895632862690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643402716644304462e+01,5.615227886357386069e+02,2.695434203195942180e-01,1.100000010988609489e+01,2.674622910231324972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643493625734305397e+01,5.615327885999705586e+02,2.695701665168078742e-01,1.100000010988609489e+01,2.674476924829787255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643584534824306331e+01,5.615427885642064894e+02,2.695969112541727331e-01,1.100000010988609489e+01,2.674330939428249537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643675443914307266e+01,5.615527885284462855e+02,2.696236545316887945e-01,1.100000010988609489e+01,2.674184954026711820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643766353004308201e+01,5.615627884926899469e+02,2.696503963493560585e-01,1.100000010988609489e+01,2.674038968625174102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643857262094309135e+01,5.615727884569375874e+02,2.696771367071745251e-01,1.100000010988609489e+01,2.673892983223636385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.643948171184310070e+01,5.615827884211890932e+02,2.697038756051441943e-01,1.100000010988609489e+01,2.673746997822098667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644039080274311004e+01,5.615927883854444644e+02,2.697306130432650662e-01,1.100000010988609489e+01,2.673601012420560950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644129989364311939e+01,5.616027883497038147e+02,2.697573490215371406e-01,1.100000010988609489e+01,2.673455027019023232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644220898454312874e+01,5.616127883139670303e+02,2.697840835399604176e-01,1.100000010988609489e+01,2.673309041617485515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644311807544313808e+01,5.616227882782341112e+02,2.698108165985348972e-01,1.100000010988609489e+01,2.673163056215947797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644402716634314743e+01,5.616327882425051712e+02,2.698375481972605794e-01,1.100000010988609489e+01,2.673017070814410080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644493625724315677e+01,5.616427882067800965e+02,2.698642783361374642e-01,1.100000010988609489e+01,2.672871085412872362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644584534814316612e+01,5.616527881710588872e+02,2.698910070151655516e-01,1.100000010988609489e+01,2.672725100011334644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644675443904317547e+01,5.616627881353416569e+02,2.699177342343448416e-01,1.100000010988609489e+01,2.672579114609796927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644766352994318481e+01,5.616727880996282920e+02,2.699444599936753342e-01,1.100000010988609489e+01,2.672433129208259209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644857262084319416e+01,5.616827880639187924e+02,2.699711842931570294e-01,1.100000010988609489e+01,2.672287143806721492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.644948171174320350e+01,5.616927880282132719e+02,2.699979071327899272e-01,1.100000010988609489e+01,2.672141158405183774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645039080264321285e+01,5.617027879925116167e+02,2.700246285125740275e-01,1.100000010988609489e+01,2.671995173003646057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645129989354322220e+01,5.617127879568138269e+02,2.700513484325092750e-01,1.100000010988609489e+01,2.671849187602108339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645220898444323154e+01,5.617227879211199024e+02,2.700780668925957251e-01,1.100000010988609489e+01,2.671703202200570622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645311807534324089e+01,5.617327878854299570e+02,2.701047838928333777e-01,1.100000010988609489e+01,2.671557216799032904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645402716624325024e+01,5.617427878497438769e+02,2.701314994332222330e-01,1.100000010988609489e+01,2.671411231397495187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645493625714325958e+01,5.617527878140616622e+02,2.701582135137622909e-01,1.100000010988609489e+01,2.671265245995957469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645584534804326893e+01,5.617627877783834265e+02,2.701849261344535513e-01,1.100000010988609489e+01,2.671119260594419752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645675443894327827e+01,5.617727877427090561e+02,2.702116372952960144e-01,1.100000010988609489e+01,2.670973275192882034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645766352984328762e+01,5.617827877070385512e+02,2.702383469962896245e-01,1.100000010988609489e+01,2.670827289791344317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645857262074329697e+01,5.617927876713720252e+02,2.702650552374344373e-01,1.100000010988609489e+01,2.670681304389806599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.645948171164330631e+01,5.618027876357093646e+02,2.702917620187304526e-01,1.100000010988609489e+01,2.670535318988268882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646039080254331566e+01,5.618127876000505694e+02,2.703184673401776705e-01,1.100000010988609489e+01,2.670389333586731164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646129989344332500e+01,5.618227875643956395e+02,2.703451712017760911e-01,1.100000010988609489e+01,2.670243348185193447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646220898434333435e+01,5.618327875287446886e+02,2.703718736035256587e-01,1.100000010988609489e+01,2.670097362783655729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646311807524334370e+01,5.618427874930976031e+02,2.703985745454264289e-01,1.100000010988609489e+01,2.669951377382118012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646402716614335304e+01,5.618527874574543830e+02,2.704252740274784017e-01,1.100000010988609489e+01,2.669805391980580294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646493625704336239e+01,5.618627874218151419e+02,2.704519720496815771e-01,1.100000010988609489e+01,2.669659406579042576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646584534794337173e+01,5.618727873861797661e+02,2.704786686120358996e-01,1.100000010988609489e+01,2.669513421177504859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646675443884338108e+01,5.618827873505482557e+02,2.705053637145414247e-01,1.100000010988609489e+01,2.669367435775967141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646766352974339043e+01,5.618927873149206107e+02,2.705320573571981524e-01,1.100000010988609489e+01,2.669221450374429424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646857262064339977e+01,5.619027872792969447e+02,2.705587495400060272e-01,1.100000010988609489e+01,2.669075464972891706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.646948171154340912e+01,5.619127872436771440e+02,2.705854402629651045e-01,1.100000010988609489e+01,2.668929479571353989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647039080244341847e+01,5.619227872080612087e+02,2.706121295260753845e-01,1.100000010988609489e+01,2.668783494169816271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647129989334342781e+01,5.619327871724492525e+02,2.706388173293368116e-01,1.100000010988609489e+01,2.668637508768278554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647220898424343716e+01,5.619427871368411616e+02,2.706655036727494412e-01,1.100000010988609489e+01,2.668491523366740836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647311807514344650e+01,5.619527871012369360e+02,2.706921885563132735e-01,1.100000010988609489e+01,2.668345537965203119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647402716604345585e+01,5.619627870656365758e+02,2.707188719800282528e-01,1.100000010988609489e+01,2.668199552563665401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647493625694346520e+01,5.619727870300401946e+02,2.707455539438944347e-01,1.100000010988609489e+01,2.668053567162127684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647584534784347454e+01,5.619827869944476788e+02,2.707722344479117638e-01,1.100000010988609489e+01,2.667907581760589966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647675443874348389e+01,5.619927869588590283e+02,2.707989134920802954e-01,1.100000010988609489e+01,2.667761596359052249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647766352964349323e+01,5.620027869232742432e+02,2.708255910764000296e-01,1.100000010988609489e+01,2.667615610957514531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647857262054350258e+01,5.620127868876934372e+02,2.708522672008709109e-01,1.100000010988609489e+01,2.667469625555976814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.647948171144351193e+01,5.620227868521164964e+02,2.708789418654929948e-01,1.100000010988609489e+01,2.667323640154439096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648039080234352127e+01,5.620327868165434211e+02,2.709056150702662258e-01,1.100000010988609489e+01,2.667177654752901379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648129989324353062e+01,5.620427867809742111e+02,2.709322868151906594e-01,1.100000010988609489e+01,2.667031669351363661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648220898414353996e+01,5.620527867454089801e+02,2.709589571002662400e-01,1.100000010988609489e+01,2.666885683949825944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648311807504354931e+01,5.620627867098476145e+02,2.709856259254930233e-01,1.100000010988609489e+01,2.666739698548288226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648402716594355866e+01,5.620727866742901142e+02,2.710122932908710092e-01,1.100000010988609489e+01,2.666593713146750508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648493625684356800e+01,5.620827866387364793e+02,2.710389591964001421e-01,1.100000010988609489e+01,2.666447727745212791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648584534774357735e+01,5.620927866031868234e+02,2.710656236420804777e-01,1.100000010988609489e+01,2.666301742343675073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648675443864358670e+01,5.621027865676410329e+02,2.710922866279119603e-01,1.100000010988609489e+01,2.666155756942137356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648766352954359604e+01,5.621127865320991077e+02,2.711189481538945900e-01,1.100000010988609489e+01,2.666009771540599638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648857262044360539e+01,5.621227864965610479e+02,2.711456082200284223e-01,1.100000010988609489e+01,2.665863786139061921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.648948171134361473e+01,5.621327864610269671e+02,2.711722668263134017e-01,1.100000010988609489e+01,2.665717800737524203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649039080224362408e+01,5.621427864254967517e+02,2.711989239727495837e-01,1.100000010988609489e+01,2.665571815335986486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649129989314363343e+01,5.621527863899704016e+02,2.712255796593369128e-01,1.100000010988609489e+01,2.665425829934448768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649220898404364277e+01,5.621627863544479169e+02,2.712522338860754445e-01,1.100000010988609489e+01,2.665279844532911051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649311807494365212e+01,5.621727863189294112e+02,2.712788866529651233e-01,1.100000010988609489e+01,2.665133859131373333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649402716584366146e+01,5.621827862834147709e+02,2.713055379600060046e-01,1.100000010988609489e+01,2.664987873729835616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649493625674367081e+01,5.621927862479039959e+02,2.713321878071980331e-01,1.100000010988609489e+01,2.664841888328297898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649584534764368016e+01,5.622027862123970863e+02,2.713588361945412086e-01,1.100000010988609489e+01,2.664695902926760181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649675443854368950e+01,5.622127861768940420e+02,2.713854831220355868e-01,1.100000010988609489e+01,2.664549917525222463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649766352944369885e+01,5.622227861413949768e+02,2.714121285896811120e-01,1.100000010988609489e+01,2.664403932123684746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649857262034370819e+01,5.622327861058997769e+02,2.714387725974777843e-01,1.100000010988609489e+01,2.664257946722147028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.649948171124371754e+01,5.622427860704084424e+02,2.714654151454256592e-01,1.100000010988609489e+01,2.664111961320609311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650039080214372689e+01,5.622527860349209732e+02,2.714920562335246812e-01,1.100000010988609489e+01,2.663965975919071593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650129989304373623e+01,5.622627859994373694e+02,2.715186958617748503e-01,1.100000010988609489e+01,2.663819990517533876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650220898394374558e+01,5.622727859639577446e+02,2.715453340301762220e-01,1.100000010988609489e+01,2.663674005115996158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650311807484375493e+01,5.622827859284819851e+02,2.715719707387287407e-01,1.100000010988609489e+01,2.663528019714458440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650402716574376427e+01,5.622927858930100911e+02,2.715986059874324066e-01,1.100000010988609489e+01,2.663382034312920723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650493625664377362e+01,5.623027858575420623e+02,2.716252397762872750e-01,1.100000010988609489e+01,2.663236048911383005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650584534754378296e+01,5.623127858220778990e+02,2.716518721052932905e-01,1.100000010988609489e+01,2.663090063509845288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650675443844379231e+01,5.623227857866177146e+02,2.716785029744504532e-01,1.100000010988609489e+01,2.662944078108307570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650766352934380166e+01,5.623327857511613956e+02,2.717051323837587629e-01,1.100000010988609489e+01,2.662798092706769853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650857262024381100e+01,5.623427857157089420e+02,2.717317603332182752e-01,1.100000010988609489e+01,2.662652107305232135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.650948171114382035e+01,5.623527856802603537e+02,2.717583868228289345e-01,1.100000010988609489e+01,2.662506121903694418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651039080204382969e+01,5.623627856448156308e+02,2.717850118525907410e-01,1.100000010988609489e+01,2.662360136502156700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651129989294383904e+01,5.623727856093748869e+02,2.718116354225036946e-01,1.100000010988609489e+01,2.662214151100618983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651220898384384839e+01,5.623827855739380084e+02,2.718382575325677952e-01,1.100000010988609489e+01,2.662068165699081265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651311807474385773e+01,5.623927855385049952e+02,2.718648781827830985e-01,1.100000010988609489e+01,2.661922180297543548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651402716564386708e+01,5.624027855030758474e+02,2.718914973731495488e-01,1.100000010988609489e+01,2.661776194896005830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651493625654387642e+01,5.624127854676505649e+02,2.719181151036671462e-01,1.100000010988609489e+01,2.661630209494468113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651584534744388577e+01,5.624227854322292615e+02,2.719447313743358907e-01,1.100000010988609489e+01,2.661484224092930395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651675443834389512e+01,5.624327853968118234e+02,2.719713461851557823e-01,1.100000010988609489e+01,2.661338238691392678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651766352924390446e+01,5.624427853613982506e+02,2.719979595361268210e-01,1.100000010988609489e+01,2.661192253289854960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651857262014391381e+01,5.624527853259885433e+02,2.720245714272490622e-01,1.100000010988609489e+01,2.661046267888317243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.651948171104392316e+01,5.624627852905827012e+02,2.720511818585224506e-01,1.100000010988609489e+01,2.660900282486779525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652039080194393250e+01,5.624727852551807246e+02,2.720777908299469861e-01,1.100000010988609489e+01,2.660754297085241808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652129989284394185e+01,5.624827852197827269e+02,2.721043983415226686e-01,1.100000010988609489e+01,2.660608311683704090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652220898374395119e+01,5.624927851843885946e+02,2.721310043932494982e-01,1.100000010988609489e+01,2.660462326282166372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652311807464396054e+01,5.625027851489983277e+02,2.721576089851274749e-01,1.100000010988609489e+01,2.660316340880628655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652402716554396989e+01,5.625127851136119261e+02,2.721842121171565987e-01,1.100000010988609489e+01,2.660170355479090937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652493625644397923e+01,5.625227850782293899e+02,2.722108137893368696e-01,1.100000010988609489e+01,2.660024370077553220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652584534734398858e+01,5.625327850428507190e+02,2.722374140016682875e-01,1.100000010988609489e+01,2.659878384676015502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652675443824399792e+01,5.625427850074760272e+02,2.722640127541508526e-01,1.100000010988609489e+01,2.659732399274477785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652766352914400727e+01,5.625527849721052007e+02,2.722906100467845647e-01,1.100000010988609489e+01,2.659586413872940067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652857262004401662e+01,5.625627849367382396e+02,2.723172058795694239e-01,1.100000010988609489e+01,2.659440428471402350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.652948171094402596e+01,5.625727849013751438e+02,2.723438002525054302e-01,1.100000010988609489e+01,2.659294443069864632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653039080184403531e+01,5.625827848660159134e+02,2.723703931655925836e-01,1.100000010988609489e+01,2.659148457668326915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653129989274404466e+01,5.625927848306605483e+02,2.723969846188308841e-01,1.100000010988609489e+01,2.659002472266789197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653220898364405400e+01,5.626027847953090486e+02,2.724235746122203317e-01,1.100000010988609489e+01,2.658856486865251480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653311807454406335e+01,5.626127847599615279e+02,2.724501631457609263e-01,1.100000010988609489e+01,2.658710501463713762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653402716544407269e+01,5.626227847246178726e+02,2.724767502194526680e-01,1.100000010988609489e+01,2.658564516062176045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653493625634408204e+01,5.626327846892780826e+02,2.725033358332955569e-01,1.100000010988609489e+01,2.658418530660638327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653584534724409139e+01,5.626427846539421580e+02,2.725299199872895928e-01,1.100000010988609489e+01,2.658272545259100610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653675443814410073e+01,5.626527846186100987e+02,2.725565026814347758e-01,1.100000010988609489e+01,2.658126559857562892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653766352904411008e+01,5.626627845832819048e+02,2.725830839157311059e-01,1.100000010988609489e+01,2.657980574456025175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653857261994411942e+01,5.626727845479575763e+02,2.726096636901785830e-01,1.100000010988609489e+01,2.657834589054487457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.653948171084412877e+01,5.626827845126372267e+02,2.726362420047772073e-01,1.100000010988609489e+01,2.657688603652949740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654039080174413812e+01,5.626927844773207426e+02,2.726628188595269786e-01,1.100000010988609489e+01,2.657542618251412022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654129989264414746e+01,5.627027844420081237e+02,2.726893942544278415e-01,1.100000010988609489e+01,2.657396632849874304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654220898354415681e+01,5.627127844066993703e+02,2.727159681894798515e-01,1.100000010988609489e+01,2.657250647448336587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654311807444416615e+01,5.627227843713944822e+02,2.727425406646830086e-01,1.100000010988609489e+01,2.657104662046798869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654402716534417550e+01,5.627327843360934594e+02,2.727691116800373128e-01,1.100000010988609489e+01,2.656958676645261152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654493625624418485e+01,5.627427843007963020e+02,2.727956812355427640e-01,1.100000010988609489e+01,2.656812691243723434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654584534714419419e+01,5.627527842655030099e+02,2.728222493311993624e-01,1.100000010988609489e+01,2.656666705842185717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654675443804420354e+01,5.627627842302136969e+02,2.728488159670070523e-01,1.100000010988609489e+01,2.656520720440647999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654766352894421289e+01,5.627727841949282492e+02,2.728753811429658893e-01,1.100000010988609489e+01,2.656374735039110282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654857261984422223e+01,5.627827841596466669e+02,2.729019448590758734e-01,1.100000010988609489e+01,2.656228749637572564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.654948171074423158e+01,5.627927841243689500e+02,2.729285071153370046e-01,1.100000010988609489e+01,2.656082764236034847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655039080164424092e+01,5.628027840890950984e+02,2.729550679117492828e-01,1.100000010988609489e+01,2.655936778834497129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655129989254425027e+01,5.628127840538251121e+02,2.729816272483126527e-01,1.100000010988609489e+01,2.655790793432959412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655220898344425962e+01,5.628227840185589912e+02,2.730081851250271696e-01,1.100000010988609489e+01,2.655644808031421694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655311807434426896e+01,5.628327839832967356e+02,2.730347415418928336e-01,1.100000010988609489e+01,2.655498822629883977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655402716524427831e+01,5.628427839480383454e+02,2.730612964989096447e-01,1.100000010988609489e+01,2.655352837228346259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655493625614428765e+01,5.628527839127838206e+02,2.730878499960775474e-01,1.100000010988609489e+01,2.655206851826808542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655584534704429700e+01,5.628627838775332748e+02,2.731144020333965972e-01,1.100000010988609489e+01,2.655060866425270824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655675443794430635e+01,5.628727838422865943e+02,2.731409526108667940e-01,1.100000010988609489e+01,2.654914881023733107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655766352884431569e+01,5.628827838070437792e+02,2.731675017284880824e-01,1.100000010988609489e+01,2.654768895622195389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655857261974432504e+01,5.628927837718048295e+02,2.731940493862605179e-01,1.100000010988609489e+01,2.654622910220657672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.655948171064433438e+01,5.629027837365697451e+02,2.732205955841841005e-01,1.100000010988609489e+01,2.654476924819119954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656039080154434373e+01,5.629127837013385260e+02,2.732471403222587747e-01,1.100000010988609489e+01,2.654330939417582236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656129989244435308e+01,5.629227836661111724e+02,2.732736836004845959e-01,1.100000010988609489e+01,2.654184954016044519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656220898334436242e+01,5.629327836308876840e+02,2.733002254188615643e-01,1.100000010988609489e+01,2.654038968614506801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656311807424437177e+01,5.629427835956680610e+02,2.733267657773896242e-01,1.100000010988609489e+01,2.653892983212969084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656402716514438112e+01,5.629527835604523034e+02,2.733533046760688312e-01,1.100000010988609489e+01,2.653746997811431366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656493625604439046e+01,5.629627835252404111e+02,2.733798421148991853e-01,1.100000010988609489e+01,2.653601012409893649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656584534694439981e+01,5.629727834900323842e+02,2.734063780938806310e-01,1.100000010988609489e+01,2.653455027008355931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656675443784440915e+01,5.629827834548283363e+02,2.734329126130132237e-01,1.100000010988609489e+01,2.653309041606818214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656766352874441850e+01,5.629927834196281538e+02,2.734594456722969080e-01,1.100000010988609489e+01,2.653163056205280496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656857261964442785e+01,5.630027833844318366e+02,2.734859772717317394e-01,1.100000010988609489e+01,2.653017070803742779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.656948171054443719e+01,5.630127833492393847e+02,2.735125074113176624e-01,1.100000010988609489e+01,2.652871085402205061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657039080144444654e+01,5.630227833140507983e+02,2.735390360910547325e-01,1.100000010988609489e+01,2.652725100000667344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657129989234445588e+01,5.630327832788660771e+02,2.735655633109429496e-01,1.100000010988609489e+01,2.652579114599129626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657220898324446523e+01,5.630427832436852214e+02,2.735920890709822584e-01,1.100000010988609489e+01,2.652433129197591909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657311807414447458e+01,5.630527832085082309e+02,2.736186133711727142e-01,1.100000010988609489e+01,2.652287143796054191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657402716504448392e+01,5.630627831733351059e+02,2.736451362115142616e-01,1.100000010988609489e+01,2.652141158394516474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657493625594449327e+01,5.630727831381658461e+02,2.736716575920069561e-01,1.100000010988609489e+01,2.651995172992978756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657584534684450261e+01,5.630827831030004518e+02,2.736981775126507421e-01,1.100000010988609489e+01,2.651849187591441039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657675443774451196e+01,5.630927830678389228e+02,2.737246959734456753e-01,1.100000010988609489e+01,2.651703202189903321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657766352864452131e+01,5.631027830326812591e+02,2.737512129743917000e-01,1.100000010988609489e+01,2.651557216788365604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657857261954453065e+01,5.631127829975274608e+02,2.737777285154888163e-01,1.100000010988609489e+01,2.651411231386827886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.657948171044454000e+01,5.631227829623775278e+02,2.738042425967370797e-01,1.100000010988609489e+01,2.651265245985290168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658039080134454935e+01,5.631327829272314602e+02,2.738307552181364346e-01,1.100000010988609489e+01,2.651119260583752451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658129989224455869e+01,5.631427828920892580e+02,2.738572663796869366e-01,1.100000010988609489e+01,2.650973275182214733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658220898314456804e+01,5.631527828569510348e+02,2.738837760813885303e-01,1.100000010988609489e+01,2.650827289780677016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658311807404457738e+01,5.631627828218166769e+02,2.739102843232412710e-01,1.100000010988609489e+01,2.650681304379139298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658402716494458673e+01,5.631727827866861844e+02,2.739367911052451032e-01,1.100000010988609489e+01,2.650535318977601581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658493625584459608e+01,5.631827827515595573e+02,2.739632964274000271e-01,1.100000010988609489e+01,2.650389333576063863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658584534674460542e+01,5.631927827164367955e+02,2.739898002897060980e-01,1.100000010988609489e+01,2.650243348174526146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658675443764461477e+01,5.632027826813178990e+02,2.740163026921632605e-01,1.100000010988609489e+01,2.650097362772988428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658766352854462411e+01,5.632127826462028679e+02,2.740428036347715146e-01,1.100000010988609489e+01,2.649951377371450711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658857261944463346e+01,5.632227826110917022e+02,2.740693031175309158e-01,1.100000010988609489e+01,2.649805391969912993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.658948171034464281e+01,5.632327825759844018e+02,2.740958011404414085e-01,1.100000010988609489e+01,2.649659406568375276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659039080124465215e+01,5.632427825408809667e+02,2.741222977035029928e-01,1.100000010988609489e+01,2.649513421166837558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659129989214466150e+01,5.632527825057813970e+02,2.741487928067157243e-01,1.100000010988609489e+01,2.649367435765299841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659220898304467084e+01,5.632627824706856927e+02,2.741752864500795472e-01,1.100000010988609489e+01,2.649221450363762123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659311807394468019e+01,5.632727824355938537e+02,2.742017786335944618e-01,1.100000010988609489e+01,2.649075464962224406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659402716484468954e+01,5.632827824005058801e+02,2.742282693572605234e-01,1.100000010988609489e+01,2.648929479560686688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659493625574469888e+01,5.632927823654217718e+02,2.742547586210776767e-01,1.100000010988609489e+01,2.648783494159148971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659584534664470823e+01,5.633027823303415289e+02,2.742812464250459215e-01,1.100000010988609489e+01,2.648637508757611253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659675443754471758e+01,5.633127822952651513e+02,2.743077327691652578e-01,1.100000010988609489e+01,2.648491523356073536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659766352844472692e+01,5.633227822601926391e+02,2.743342176534357413e-01,1.100000010988609489e+01,2.648345537954535818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659857261934473627e+01,5.633327822251239922e+02,2.743607010778573163e-01,1.100000010988609489e+01,2.648199552552998100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.659948171024474561e+01,5.633427821900592107e+02,2.743871830424299829e-01,1.100000010988609489e+01,2.648053567151460383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660039080114475496e+01,5.633527821549982946e+02,2.744136635471537411e-01,1.100000010988609489e+01,2.647907581749922665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660129989204476431e+01,5.633627821199412438e+02,2.744401425920286464e-01,1.100000010988609489e+01,2.647761596348384948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660220898294477365e+01,5.633727820848880583e+02,2.744666201770546432e-01,1.100000010988609489e+01,2.647615610946847230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660311807384478300e+01,5.633827820498387382e+02,2.744930963022317316e-01,1.100000010988609489e+01,2.647469625545309513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660402716474479234e+01,5.633927820147932835e+02,2.745195709675599116e-01,1.100000010988609489e+01,2.647323640143771795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660493625564480169e+01,5.634027819797516941e+02,2.745460441730391832e-01,1.100000010988609489e+01,2.647177654742234078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660584534654481104e+01,5.634127819447139700e+02,2.745725159186695463e-01,1.100000010988609489e+01,2.647031669340696360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660675443744482038e+01,5.634227819096801113e+02,2.745989862044510565e-01,1.100000010988609489e+01,2.646885683939158643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660766352834482973e+01,5.634327818746501180e+02,2.746254550303836584e-01,1.100000010988609489e+01,2.646739698537620925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660857261924483907e+01,5.634427818396239900e+02,2.746519223964673517e-01,1.100000010988609489e+01,2.646593713136083208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.660948171014484842e+01,5.634527818046017273e+02,2.746783883027021367e-01,1.100000010988609489e+01,2.646447727734545490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661039080104485777e+01,5.634627817695833301e+02,2.747048527490880132e-01,1.100000010988609489e+01,2.646301742333007773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661129989194486711e+01,5.634727817345687981e+02,2.747313157356249813e-01,1.100000010988609489e+01,2.646155756931470055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661220898284487646e+01,5.634827816995581315e+02,2.747577772623130410e-01,1.100000010988609489e+01,2.646009771529932338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661311807374488581e+01,5.634927816645513303e+02,2.747842373291521922e-01,1.100000010988609489e+01,2.645863786128394620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661402716464489515e+01,5.635027816295483944e+02,2.748106959361424351e-01,1.100000010988609489e+01,2.645717800726856903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661493625554490450e+01,5.635127815945493239e+02,2.748371530832837695e-01,1.100000010988609489e+01,2.645571815325319185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661584534644491384e+01,5.635227815595541188e+02,2.748636087705761955e-01,1.100000010988609489e+01,2.645425829923781468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661675443734492319e+01,5.635327815245627789e+02,2.748900629980197130e-01,1.100000010988609489e+01,2.645279844522243750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661766352824493254e+01,5.635427814895753045e+02,2.749165157656143221e-01,1.100000010988609489e+01,2.645133859120706032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661857261914494188e+01,5.635527814545916954e+02,2.749429670733600228e-01,1.100000010988609489e+01,2.644987873719168315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.661948171004495123e+01,5.635627814196119516e+02,2.749694169212568151e-01,1.100000010988609489e+01,2.644841888317630597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662039080094496057e+01,5.635727813846360732e+02,2.749958653093046990e-01,1.100000010988609489e+01,2.644695902916092880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662129989184496992e+01,5.635827813496640601e+02,2.750223122375036744e-01,1.100000010988609489e+01,2.644549917514555162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662220898274497927e+01,5.635927813146959124e+02,2.750487577058537414e-01,1.100000010988609489e+01,2.644403932113017445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662311807364498861e+01,5.636027812797315164e+02,2.750752017143549000e-01,1.100000010988609489e+01,2.644257946711479727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662402716454499796e+01,5.636127812447709857e+02,2.751016442630071501e-01,1.100000010988609489e+01,2.644111961309942010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662493625544500730e+01,5.636227812098143204e+02,2.751280853518104919e-01,1.100000010988609489e+01,2.643965975908404292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662584534634501665e+01,5.636327811748615204e+02,2.751545249807649252e-01,1.100000010988609489e+01,2.643819990506866575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662675443724502600e+01,5.636427811399125858e+02,2.751809631498704500e-01,1.100000010988609489e+01,2.643674005105328857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662766352814503534e+01,5.636527811049675165e+02,2.752073998591270665e-01,1.100000010988609489e+01,2.643528019703791140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662857261904504469e+01,5.636627810700263126e+02,2.752338351085347745e-01,1.100000010988609489e+01,2.643382034302253422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.662948170994505404e+01,5.636727810350889740e+02,2.752602688980935741e-01,1.100000010988609489e+01,2.643236048900715705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663039080084506338e+01,5.636827810001555008e+02,2.752867012278034653e-01,1.100000010988609489e+01,2.643090063499177987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663129989174507273e+01,5.636927809652258929e+02,2.753131320976643925e-01,1.100000010988609489e+01,2.642944078097640270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663220898264508207e+01,5.637027809303001504e+02,2.753395615076764114e-01,1.100000010988609489e+01,2.642798092696102552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663311807354509142e+01,5.637127808953782733e+02,2.753659894578395217e-01,1.100000010988609489e+01,2.642652107294564835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663402716444510077e+01,5.637227808604602615e+02,2.753924159481537237e-01,1.100000010988609489e+01,2.642506121893027117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663493625534511011e+01,5.637327808255461150e+02,2.754188409786190173e-01,1.100000010988609489e+01,2.642360136491489399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663584534624511946e+01,5.637427807906358339e+02,2.754452645492354024e-01,1.100000010988609489e+01,2.642214151089951682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663675443714512880e+01,5.637527807557294182e+02,2.754716866600028236e-01,1.100000010988609489e+01,2.642068165688413964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663766352804513815e+01,5.637627807208268678e+02,2.754981073109213363e-01,1.100000010988609489e+01,2.641922180286876247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663857261894514750e+01,5.637727806859280690e+02,2.755245265019909406e-01,1.100000010988609489e+01,2.641776194885338529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.663948170984515684e+01,5.637827806510331357e+02,2.755509442332116365e-01,1.100000010988609489e+01,2.641630209483800812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664039080074516619e+01,5.637927806161420676e+02,2.755773605045834240e-01,1.100000010988609489e+01,2.641484224082263094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664129989164517553e+01,5.638027805812548650e+02,2.756037753161062476e-01,1.100000010988609489e+01,2.641338238680725377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664220898254518488e+01,5.638127805463715276e+02,2.756301886677801627e-01,1.100000010988609489e+01,2.641192253279187659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664311807344519423e+01,5.638227805114920557e+02,2.756566005596051694e-01,1.100000010988609489e+01,2.641046267877649942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664402716434520357e+01,5.638327804766164491e+02,2.756830109915812677e-01,1.100000010988609489e+01,2.640900282476112224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664493625524521292e+01,5.638427804417447078e+02,2.757094199637084020e-01,1.100000010988609489e+01,2.640754297074574507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664584534614522227e+01,5.638527804068768319e+02,2.757358274759866279e-01,1.100000010988609489e+01,2.640608311673036789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664675443704523161e+01,5.638627803720128213e+02,2.757622335284159454e-01,1.100000010988609489e+01,2.640462326271499072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664766352794524096e+01,5.638727803371526761e+02,2.757886381209962989e-01,1.100000010988609489e+01,2.640316340869961354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664857261884525030e+01,5.638827803022963963e+02,2.758150412537277441e-01,1.100000010988609489e+01,2.640170355468423637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.664948170974525965e+01,5.638927802674438681e+02,2.758414429266102808e-01,1.100000010988609489e+01,2.640024370066885919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665039080064526900e+01,5.639027802325952052e+02,2.758678431396438535e-01,1.100000010988609489e+01,2.639878384665348202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665129989154527834e+01,5.639127801977504078e+02,2.758942418928285178e-01,1.100000010988609489e+01,2.639732399263810484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665220898244528769e+01,5.639227801629094756e+02,2.759206391861642738e-01,1.100000010988609489e+01,2.639586413862272767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665311807334529703e+01,5.639327801280724088e+02,2.759470350196510657e-01,1.100000010988609489e+01,2.639440428460735049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665402716424530638e+01,5.639427800932392074e+02,2.759734293932889493e-01,1.100000010988609489e+01,2.639294443059197331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665493625514531573e+01,5.639527800584098713e+02,2.759998223070778689e-01,1.100000010988609489e+01,2.639148457657659614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665584534604532507e+01,5.639627800235844006e+02,2.760262137610178801e-01,1.100000010988609489e+01,2.639002472256121896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665675443694533442e+01,5.639727799887627953e+02,2.760526037551089829e-01,1.100000010988609489e+01,2.638856486854584179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665766352784534376e+01,5.639827799539449416e+02,2.760789922893511217e-01,1.100000010988609489e+01,2.638710501453046461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665857261874535311e+01,5.639927799191309532e+02,2.761053793637443521e-01,1.100000010988609489e+01,2.638564516051508744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.665948170964536246e+01,5.640027798843208302e+02,2.761317649782886186e-01,1.100000010988609489e+01,2.638418530649971026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666039080054537180e+01,5.640127798495145726e+02,2.761581491329839766e-01,1.100000010988609489e+01,2.638272545248433309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666129989144538115e+01,5.640227798147121803e+02,2.761845318278303707e-01,1.100000010988609489e+01,2.638126559846895591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666220898234539050e+01,5.640327797799136533e+02,2.762109130628278564e-01,1.100000010988609489e+01,2.637980574445357874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666311807324539984e+01,5.640427797451189917e+02,2.762372928379763781e-01,1.100000010988609489e+01,2.637834589043820156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666402716414540919e+01,5.640527797103281955e+02,2.762636711532759914e-01,1.100000010988609489e+01,2.637688603642282439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666493625504541853e+01,5.640627796755412646e+02,2.762900480087266408e-01,1.100000010988609489e+01,2.637542618240744721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666584534594542788e+01,5.640727796407580854e+02,2.763164234043283818e-01,1.100000010988609489e+01,2.637396632839207004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666675443684543723e+01,5.640827796059787715e+02,2.763427973400811588e-01,1.100000010988609489e+01,2.637250647437669286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666766352774544657e+01,5.640927795712033230e+02,2.763691698159850274e-01,1.100000010988609489e+01,2.637104662036131569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666857261864545592e+01,5.641027795364317399e+02,2.763955408320399321e-01,1.100000010988609489e+01,2.636958676634593851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.666948170954546526e+01,5.641127795016640221e+02,2.764219103882459283e-01,1.100000010988609489e+01,2.636812691233056134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667039080044547461e+01,5.641227794669001696e+02,2.764482784846029606e-01,1.100000010988609489e+01,2.636666705831518416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667129989134548396e+01,5.641327794321401825e+02,2.764746451211110845e-01,1.100000010988609489e+01,2.636520720429980699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667220898224549330e+01,5.641427793973839471e+02,2.765010102977702444e-01,1.100000010988609489e+01,2.636374735028442981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667311807314550265e+01,5.641527793626315770e+02,2.765273740145804404e-01,1.100000010988609489e+01,2.636228749626905263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667402716404551200e+01,5.641627793278830723e+02,2.765537362715417280e-01,1.100000010988609489e+01,2.636082764225367546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667493625494552134e+01,5.641727792931384329e+02,2.765800970686540516e-01,1.100000010988609489e+01,2.635936778823829828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667584534584553069e+01,5.641827792583976589e+02,2.766064564059174113e-01,1.100000010988609489e+01,2.635790793422292111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667675443674554003e+01,5.641927792236607502e+02,2.766328142833318626e-01,1.100000010988609489e+01,2.635644808020754393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667766352764554938e+01,5.642027791889277069e+02,2.766591707008973500e-01,1.100000010988609489e+01,2.635498822619216676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667857261854555873e+01,5.642127791541984152e+02,2.766855256586139289e-01,1.100000010988609489e+01,2.635352837217678958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.667948170944556807e+01,5.642227791194729889e+02,2.767118791564815439e-01,1.100000010988609489e+01,2.635206851816141241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668039080034557742e+01,5.642327790847514279e+02,2.767382311945001949e-01,1.100000010988609489e+01,2.635060866414603523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668129989124558676e+01,5.642427790500337323e+02,2.767645817726698820e-01,1.100000010988609489e+01,2.634914881013065806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668220898214559611e+01,5.642527790153199021e+02,2.767909308909906607e-01,1.100000010988609489e+01,2.634768895611528088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668311807304560546e+01,5.642627789806099372e+02,2.768172785494624755e-01,1.100000010988609489e+01,2.634622910209990371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668402716394561480e+01,5.642727789459037240e+02,2.768436247480853263e-01,1.100000010988609489e+01,2.634476924808452653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668493625484562415e+01,5.642827789112013761e+02,2.768699694868592687e-01,1.100000010988609489e+01,2.634330939406914936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668584534574563349e+01,5.642927788765028936e+02,2.768963127657842471e-01,1.100000010988609489e+01,2.634184954005377218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668675443664564284e+01,5.643027788418082764e+02,2.769226545848602616e-01,1.100000010988609489e+01,2.634038968603839501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668766352754565219e+01,5.643127788071175246e+02,2.769489949440873122e-01,1.100000010988609489e+01,2.633892983202301783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668857261844566153e+01,5.643227787724306381e+02,2.769753338434654544e-01,1.100000010988609489e+01,2.633746997800764066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.668948170934567088e+01,5.643327787377475033e+02,2.770016712829946326e-01,1.100000010988609489e+01,2.633601012399226348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669039080024568023e+01,5.643427787030682339e+02,2.770280072626748469e-01,1.100000010988609489e+01,2.633455026997688631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669129989114568957e+01,5.643527786683928298e+02,2.770543417825060972e-01,1.100000010988609489e+01,2.633309041596150913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669220898204569892e+01,5.643627786337212910e+02,2.770806748424883836e-01,1.100000010988609489e+01,2.633163056194613195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669311807294570826e+01,5.643727785990536177e+02,2.771070064426217616e-01,1.100000010988609489e+01,2.633017070793075478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669402716384571761e+01,5.643827785643896959e+02,2.771333365829061757e-01,1.100000010988609489e+01,2.632871085391537760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669493625474572696e+01,5.643927785297296396e+02,2.771596652633416258e-01,1.100000010988609489e+01,2.632725099990000043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669584534564573630e+01,5.644027784950734485e+02,2.771859924839281120e-01,1.100000010988609489e+01,2.632579114588462325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669675443654574565e+01,5.644127784604211229e+02,2.772123182446656342e-01,1.100000010988609489e+01,2.632433129186924608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669766352744575499e+01,5.644227784257726626e+02,2.772386425455541925e-01,1.100000010988609489e+01,2.632287143785386890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669857261834576434e+01,5.644327783911279539e+02,2.772649653865937869e-01,1.100000010988609489e+01,2.632141158383849173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.669948170924577369e+01,5.644427783564871106e+02,2.772912867677844728e-01,1.100000010988609489e+01,2.631995172982311455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670039080014578303e+01,5.644527783218501327e+02,2.773176066891261948e-01,1.100000010988609489e+01,2.631849187580773738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670129989104579238e+01,5.644627782872170201e+02,2.773439251506189529e-01,1.100000010988609489e+01,2.631703202179236020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670220898194580172e+01,5.644727782525877728e+02,2.773702421522627470e-01,1.100000010988609489e+01,2.631557216777698303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670311807284581107e+01,5.644827782179622773e+02,2.773965576940575772e-01,1.100000010988609489e+01,2.631411231376160585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670402716374582042e+01,5.644927781833406470e+02,2.774228717760034435e-01,1.100000010988609489e+01,2.631265245974622868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670493625464582976e+01,5.645027781487228822e+02,2.774491843981003458e-01,1.100000010988609489e+01,2.631119260573085150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670584534554583911e+01,5.645127781141089827e+02,2.774754955603482842e-01,1.100000010988609489e+01,2.630973275171547433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670675443644584846e+01,5.645227780794989485e+02,2.775018052627472587e-01,1.100000010988609489e+01,2.630827289770009715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670766352734585780e+01,5.645327780448926660e+02,2.775281135052972692e-01,1.100000010988609489e+01,2.630681304368471998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670857261824586715e+01,5.645427780102902489e+02,2.775544202879983158e-01,1.100000010988609489e+01,2.630535318966934280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.670948170914587649e+01,5.645527779756916971e+02,2.775807256108503984e-01,1.100000010988609489e+01,2.630389333565396563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671039080004588584e+01,5.645627779410970106e+02,2.776070294738535171e-01,1.100000010988609489e+01,2.630243348163858845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671129989094589519e+01,5.645727779065060759e+02,2.776333318770076719e-01,1.100000010988609489e+01,2.630097362762321127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671220898184590453e+01,5.645827778719190064e+02,2.776596328203128627e-01,1.100000010988609489e+01,2.629951377360783410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671311807274591388e+01,5.645927778373358024e+02,2.776859323037690896e-01,1.100000010988609489e+01,2.629805391959245692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671402716364592322e+01,5.646027778027564636e+02,2.777122303273763526e-01,1.100000010988609489e+01,2.629659406557707975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671493625454593257e+01,5.646127777681809903e+02,2.777385268911346516e-01,1.100000010988609489e+01,2.629513421156170257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671584534544594192e+01,5.646227777336092686e+02,2.777648219950439867e-01,1.100000010988609489e+01,2.629367435754632540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671675443634595126e+01,5.646327776990414122e+02,2.777911156391043579e-01,1.100000010988609489e+01,2.629221450353094822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671766352724596061e+01,5.646427776644774212e+02,2.778174078233157651e-01,1.100000010988609489e+01,2.629075464951557105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671857261814596995e+01,5.646527776299172956e+02,2.778436985476781529e-01,1.100000010988609489e+01,2.628929479550019387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.671948170904597930e+01,5.646627775953609216e+02,2.778699878121915767e-01,1.100000010988609489e+01,2.628783494148481670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672039079994598865e+01,5.646727775608084130e+02,2.778962756168560366e-01,1.100000010988609489e+01,2.628637508746943952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672129989084599799e+01,5.646827775262597697e+02,2.779225619616715326e-01,1.100000010988609489e+01,2.628491523345406235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672220898174600734e+01,5.646927774917149918e+02,2.779488468466380646e-01,1.100000010988609489e+01,2.628345537943868517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672311807264601669e+01,5.647027774571739656e+02,2.779751302717556327e-01,1.100000010988609489e+01,2.628199552542330800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672402716354602603e+01,5.647127774226368047e+02,2.780014122370242369e-01,1.100000010988609489e+01,2.628053567140793082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672493625444603538e+01,5.647227773881035091e+02,2.780276927424438216e-01,1.100000010988609489e+01,2.627907581739255365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672584534534604472e+01,5.647327773535740789e+02,2.780539717880144424e-01,1.100000010988609489e+01,2.627761596337717647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672675443624605407e+01,5.647427773190484004e+02,2.780802493737360992e-01,1.100000010988609489e+01,2.627615610936179930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672766352714606342e+01,5.647527772845265872e+02,2.781065254996087921e-01,1.100000010988609489e+01,2.627469625534642212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672857261804607276e+01,5.647627772500086394e+02,2.781328001656325211e-01,1.100000010988609489e+01,2.627323640133104495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.672948170894608211e+01,5.647727772154945569e+02,2.781590733718072306e-01,1.100000010988609489e+01,2.627177654731566777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673039079984609145e+01,5.647827771809842261e+02,2.781853451181329762e-01,1.100000010988609489e+01,2.627031669330029059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673129989074610080e+01,5.647927771464777607e+02,2.782116154046097578e-01,1.100000010988609489e+01,2.626885683928491342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673220898164611015e+01,5.648027771119751606e+02,2.782378842312375755e-01,1.100000010988609489e+01,2.626739698526953624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673311807254611949e+01,5.648127770774764258e+02,2.782641515980163738e-01,1.100000010988609489e+01,2.626593713125415907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673402716344612884e+01,5.648227770429814427e+02,2.782904175049462081e-01,1.100000010988609489e+01,2.626447727723878189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673493625434613818e+01,5.648327770084903250e+02,2.783166819520270785e-01,1.100000010988609489e+01,2.626301742322340472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673584534524614753e+01,5.648427769740030726e+02,2.783429449392589294e-01,1.100000010988609489e+01,2.626155756920802754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673675443614615688e+01,5.648527769395195719e+02,2.783692064666418164e-01,1.100000010988609489e+01,2.626009771519265037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673766352704616622e+01,5.648627769050399365e+02,2.783954665341757395e-01,1.100000010988609489e+01,2.625863786117727319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673857261794617557e+01,5.648727768705641665e+02,2.784217251418606986e-01,1.100000010988609489e+01,2.625717800716189602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.673948170884618492e+01,5.648827768360922619e+02,2.784479822896966383e-01,1.100000010988609489e+01,2.625571815314651884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674039079974619426e+01,5.648927768016241089e+02,2.784742379776836141e-01,1.100000010988609489e+01,2.625425829913114167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674129989064620361e+01,5.649027767671598212e+02,2.785004922058215704e-01,1.100000010988609489e+01,2.625279844511576449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674220898154621295e+01,5.649127767326993990e+02,2.785267449741105628e-01,1.100000010988609489e+01,2.625133859110038732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674311807244622230e+01,5.649227766982427283e+02,2.785529962825505912e-01,1.100000010988609489e+01,2.624987873708501014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674402716334623165e+01,5.649327766637899231e+02,2.785792461311416002e-01,1.100000010988609489e+01,2.624841888306963297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674493625424624099e+01,5.649427766293409832e+02,2.786054945198836452e-01,1.100000010988609489e+01,2.624695902905425579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674584534514625034e+01,5.649527765948959086e+02,2.786317414487767263e-01,1.100000010988609489e+01,2.624549917503887862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674675443604625968e+01,5.649627765604545857e+02,2.786579869178207880e-01,1.100000010988609489e+01,2.624403932102350144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674766352694626903e+01,5.649727765260171282e+02,2.786842309270158857e-01,1.100000010988609489e+01,2.624257946700812427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674857261784627838e+01,5.649827764915835360e+02,2.787104734763619640e-01,1.100000010988609489e+01,2.624111961299274709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.674948170874628772e+01,5.649927764571536954e+02,2.787367145658590784e-01,1.100000010988609489e+01,2.623965975897736991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675039079964629707e+01,5.650027764227277203e+02,2.787629541955071732e-01,1.100000010988609489e+01,2.623819990496199274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675129989054630641e+01,5.650127763883056105e+02,2.787891923653063042e-01,1.100000010988609489e+01,2.623674005094661556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675220898144631576e+01,5.650227763538872523e+02,2.788154290752564157e-01,1.100000010988609489e+01,2.623528019693123839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675311807234632511e+01,5.650327763194727595e+02,2.788416643253575633e-01,1.100000010988609489e+01,2.623382034291586121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675402716324633445e+01,5.650427762850621320e+02,2.788678981156096914e-01,1.100000010988609489e+01,2.623236048890048404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675493625414634380e+01,5.650527762506553699e+02,2.788941304460128556e-01,1.100000010988609489e+01,2.623090063488510686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675584534504635315e+01,5.650627762162523595e+02,2.789203613165670004e-01,1.100000010988609489e+01,2.622944078086972969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675675443594636249e+01,5.650727761818532144e+02,2.789465907272721812e-01,1.100000010988609489e+01,2.622798092685435251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675766352684637184e+01,5.650827761474579347e+02,2.789728186781283426e-01,1.100000010988609489e+01,2.622652107283897534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675857261774638118e+01,5.650927761130664067e+02,2.789990451691355400e-01,1.100000010988609489e+01,2.622506121882359816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.675948170864639053e+01,5.651027760786787439e+02,2.790252702002937180e-01,1.100000010988609489e+01,2.622360136480822099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676039079954639988e+01,5.651127760442949466e+02,2.790514937716029320e-01,1.100000010988609489e+01,2.622214151079284381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676129989044640922e+01,5.651227760099149009e+02,2.790777158830631266e-01,1.100000010988609489e+01,2.622068165677746664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676220898134641857e+01,5.651327759755387206e+02,2.791039365346743018e-01,1.100000010988609489e+01,2.621922180276208946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676311807224642791e+01,5.651427759411664056e+02,2.791301557264365130e-01,1.100000010988609489e+01,2.621776194874671229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676402716314643726e+01,5.651527759067978423e+02,2.791563734583497047e-01,1.100000010988609489e+01,2.621630209473133511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676493625404644661e+01,5.651627758724331443e+02,2.791825897304139326e-01,1.100000010988609489e+01,2.621484224071595794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676584534494645595e+01,5.651727758380723117e+02,2.792088045426291409e-01,1.100000010988609489e+01,2.621338238670058076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676675443584646530e+01,5.651827758037152307e+02,2.792350178949953299e-01,1.100000010988609489e+01,2.621192253268520359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676766352674647464e+01,5.651927757693620151e+02,2.792612297875125549e-01,1.100000010988609489e+01,2.621046267866982641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676857261764648399e+01,5.652027757350126649e+02,2.792874402201807604e-01,1.100000010988609489e+01,2.620900282465444923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.676948170854649334e+01,5.652127757006670663e+02,2.793136491929999465e-01,1.100000010988609489e+01,2.620754297063907206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677039079944650268e+01,5.652227756663253331e+02,2.793398567059701687e-01,1.100000010988609489e+01,2.620608311662369488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677129989034651203e+01,5.652327756319874652e+02,2.793660627590913714e-01,1.100000010988609489e+01,2.620462326260831771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677220898124652138e+01,5.652427755976533490e+02,2.793922673523635547e-01,1.100000010988609489e+01,2.620316340859294053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677311807214653072e+01,5.652527755633230981e+02,2.794184704857867740e-01,1.100000010988609489e+01,2.620170355457756336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677402716304654007e+01,5.652627755289965990e+02,2.794446721593609739e-01,1.100000010988609489e+01,2.620024370056218618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677493625394654941e+01,5.652727754946739651e+02,2.794708723730861544e-01,1.100000010988609489e+01,2.619878384654680901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677584534484655876e+01,5.652827754603551966e+02,2.794970711269623154e-01,1.100000010988609489e+01,2.619732399253143183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677675443574656811e+01,5.652927754260401798e+02,2.795232684209895124e-01,1.100000010988609489e+01,2.619586413851605466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677766352664657745e+01,5.653027753917290283e+02,2.795494642551676900e-01,1.100000010988609489e+01,2.619440428450067748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677857261754658680e+01,5.653127753574217422e+02,2.795756586294968482e-01,1.100000010988609489e+01,2.619294443048530031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.677948170844659614e+01,5.653227753231182078e+02,2.796018515439769869e-01,1.100000010988609489e+01,2.619148457646992313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678039079934660549e+01,5.653327752888185387e+02,2.796280429986081617e-01,1.100000010988609489e+01,2.619002472245454596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678129989024661484e+01,5.653427752545227349e+02,2.796542329933903170e-01,1.100000010988609489e+01,2.618856486843916878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678220898114662418e+01,5.653527752202306829e+02,2.796804215283234529e-01,1.100000010988609489e+01,2.618710501442379161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678311807204663353e+01,5.653627751859424961e+02,2.797066086034075694e-01,1.100000010988609489e+01,2.618564516040841443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678402716294664287e+01,5.653727751516580611e+02,2.797327942186426664e-01,1.100000010988609489e+01,2.618418530639303726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678493625384665222e+01,5.653827751173774914e+02,2.797589783740287439e-01,1.100000010988609489e+01,2.618272545237766008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678584534474666157e+01,5.653927750831007870e+02,2.797851610695658575e-01,1.100000010988609489e+01,2.618126559836228291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678675443564667091e+01,5.654027750488278343e+02,2.798113423052539517e-01,1.100000010988609489e+01,2.617980574434690573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678766352654668026e+01,5.654127750145587470e+02,2.798375220810930264e-01,1.100000010988609489e+01,2.617834589033152855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678857261744668961e+01,5.654227749802935250e+02,2.798637003970830817e-01,1.100000010988609489e+01,2.617688603631615138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.678948170834669895e+01,5.654327749460320547e+02,2.798898772532241175e-01,1.100000010988609489e+01,2.617542618230077420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679039079924670830e+01,5.654427749117744497e+02,2.799160526495161339e-01,1.100000010988609489e+01,2.617396632828539703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679129989014671764e+01,5.654527748775205964e+02,2.799422265859591308e-01,1.100000010988609489e+01,2.617250647427001985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679220898104672699e+01,5.654627748432706085e+02,2.799683990625531083e-01,1.100000010988609489e+01,2.617104662025464268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679311807194673634e+01,5.654727748090244859e+02,2.799945700792980663e-01,1.100000010988609489e+01,2.616958676623926550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679402716284674568e+01,5.654827747747821149e+02,2.800207396361940049e-01,1.100000010988609489e+01,2.616812691222388833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679493625374675503e+01,5.654927747405436094e+02,2.800469077332409795e-01,1.100000010988609489e+01,2.616666705820851115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679584534464676437e+01,5.655027747063088555e+02,2.800730743704389347e-01,1.100000010988609489e+01,2.616520720419313398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679675443554677372e+01,5.655127746720779669e+02,2.800992395477878705e-01,1.100000010988609489e+01,2.616374735017775680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679766352644678307e+01,5.655227746378509437e+02,2.801254032652877868e-01,1.100000010988609489e+01,2.616228749616237963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679857261734679241e+01,5.655327746036276721e+02,2.801515655229386836e-01,1.100000010988609489e+01,2.616082764214700245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.679948170824680176e+01,5.655427745694082660e+02,2.801777263207405611e-01,1.100000010988609489e+01,2.615936778813162528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680039079914681110e+01,5.655527745351926114e+02,2.802038856586934190e-01,1.100000010988609489e+01,2.615790793411624810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680129989004682045e+01,5.655627745009808223e+02,2.802300435367972575e-01,1.100000010988609489e+01,2.615644808010087093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680220898094682980e+01,5.655727744667728984e+02,2.802561999550520766e-01,1.100000010988609489e+01,2.615498822608549375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680311807184683914e+01,5.655827744325687263e+02,2.802823549134578762e-01,1.100000010988609489e+01,2.615352837207011658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680402716274684849e+01,5.655927743983684195e+02,2.803085084120146009e-01,1.100000010988609489e+01,2.615206851805473940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680493625364685784e+01,5.656027743641718644e+02,2.803346604507223061e-01,1.100000010988609489e+01,2.615060866403936223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680584534454686718e+01,5.656127743299791746e+02,2.803608110295809919e-01,1.100000010988609489e+01,2.614914881002398505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680675443544687653e+01,5.656227742957903502e+02,2.803869601485906582e-01,1.100000010988609489e+01,2.614768895600860787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680766352634688587e+01,5.656327742616052774e+02,2.804131078077513051e-01,1.100000010988609489e+01,2.614622910199323070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680857261724689522e+01,5.656427742274240700e+02,2.804392540070629325e-01,1.100000010988609489e+01,2.614476924797785352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.680948170814690457e+01,5.656527741932466142e+02,2.804653987465255405e-01,1.100000010988609489e+01,2.614330939396247635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681039079904691391e+01,5.656627741590730238e+02,2.804915420261391290e-01,1.100000010988609489e+01,2.614184953994709917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681129988994692326e+01,5.656727741249031851e+02,2.805176838459036981e-01,1.100000010988609489e+01,2.614038968593172200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681220898084693260e+01,5.656827740907372117e+02,2.805438242058192477e-01,1.100000010988609489e+01,2.613892983191634482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681311807174694195e+01,5.656927740565751037e+02,2.805699631058857224e-01,1.100000010988609489e+01,2.613746997790096765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681402716264695130e+01,5.657027740224167474e+02,2.805961005461031776e-01,1.100000010988609489e+01,2.613601012388559047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681493625354696064e+01,5.657127739882622564e+02,2.806222365264716134e-01,1.100000010988609489e+01,2.613455026987021330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681584534444696999e+01,5.657227739541115170e+02,2.806483710469910298e-01,1.100000010988609489e+01,2.613309041585483612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681675443534697934e+01,5.657327739199646430e+02,2.806745041076614267e-01,1.100000010988609489e+01,2.613163056183945895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681766352624698868e+01,5.657427738858215207e+02,2.807006357084827486e-01,1.100000010988609489e+01,2.613017070782408177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681857261714699803e+01,5.657527738516822637e+02,2.807267658494550511e-01,1.100000010988609489e+01,2.612871085380870460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.681948170804700737e+01,5.657627738175467584e+02,2.807528945305783341e-01,1.100000010988609489e+01,2.612725099979332742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682039079894701672e+01,5.657727737834151185e+02,2.807790217518525977e-01,1.100000010988609489e+01,2.612579114577795025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682129988984702607e+01,5.657827737492873439e+02,2.808051475132778418e-01,1.100000010988609489e+01,2.612433129176257307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682220898074703541e+01,5.657927737151633210e+02,2.808312718148540110e-01,1.100000010988609489e+01,2.612287143774719590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682311807164704476e+01,5.658027736810431634e+02,2.808573946565811608e-01,1.100000010988609489e+01,2.612141158373181872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682402716254705410e+01,5.658127736469267575e+02,2.808835160384592911e-01,1.100000010988609489e+01,2.611995172971644154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682493625344706345e+01,5.658227736128142169e+02,2.809096359604883464e-01,1.100000010988609489e+01,2.611849187570106437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682584534434707280e+01,5.658327735787054280e+02,2.809357544226683823e-01,1.100000010988609489e+01,2.611703202168568719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682675443524708214e+01,5.658427735446005045e+02,2.809618714249993987e-01,1.100000010988609489e+01,2.611557216767031002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682766352614709149e+01,5.658527735104993326e+02,2.809879869674813957e-01,1.100000010988609489e+01,2.611411231365493284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682857261704710083e+01,5.658627734764020261e+02,2.810141010501143177e-01,1.100000010988609489e+01,2.611265245963955567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.682948170794711018e+01,5.658727734423084712e+02,2.810402136728982203e-01,1.100000010988609489e+01,2.611119260562417849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683039079884711953e+01,5.658827734082187817e+02,2.810663248358331034e-01,1.100000010988609489e+01,2.610973275160880132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683129988974712887e+01,5.658927733741328439e+02,2.810924345389189116e-01,1.100000010988609489e+01,2.610827289759342414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683220898064713822e+01,5.659027733400507714e+02,2.811185427821557004e-01,1.100000010988609489e+01,2.610681304357804697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683311807154714757e+01,5.659127733059724505e+02,2.811446495655434141e-01,1.100000010988609489e+01,2.610535318956266979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683402716244715691e+01,5.659227732718979951e+02,2.811707548890821085e-01,1.100000010988609489e+01,2.610389333554729262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683493625334716626e+01,5.659327732378274050e+02,2.811968587527717833e-01,1.100000010988609489e+01,2.610243348153191544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683584534424717560e+01,5.659427732037605665e+02,2.812229611566123832e-01,1.100000010988609489e+01,2.610097362751653827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683675443514718495e+01,5.659527731696975934e+02,2.812490621006039637e-01,1.100000010988609489e+01,2.609951377350116109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683766352604719430e+01,5.659627731356383720e+02,2.812751615847464692e-01,1.100000010988609489e+01,2.609805391948578392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683857261694720364e+01,5.659727731015830159e+02,2.813012596090399553e-01,1.100000010988609489e+01,2.609659406547040674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.683948170784721299e+01,5.659827730675314115e+02,2.813273561734844219e-01,1.100000010988609489e+01,2.609513421145502957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684039079874722233e+01,5.659927730334836724e+02,2.813534512780798136e-01,1.100000010988609489e+01,2.609367435743965239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684129988964723168e+01,5.660027729994396850e+02,2.813795449228261858e-01,1.100000010988609489e+01,2.609221450342427522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684220898054724103e+01,5.660127729653995630e+02,2.814056371077234830e-01,1.100000010988609489e+01,2.609075464940889804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684311807144725037e+01,5.660227729313631926e+02,2.814317278327717609e-01,1.100000010988609489e+01,2.608929479539352086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684402716234725972e+01,5.660327728973306876e+02,2.814578170979709637e-01,1.100000010988609489e+01,2.608783494137814369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684493625324726906e+01,5.660427728633019342e+02,2.814839049033211471e-01,1.100000010988609489e+01,2.608637508736276651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684584534414727841e+01,5.660527728292770462e+02,2.815099912488222555e-01,1.100000010988609489e+01,2.608491523334738934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684675443504728776e+01,5.660627727952559098e+02,2.815360761344743445e-01,1.100000010988609489e+01,2.608345537933201216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684766352594729710e+01,5.660727727612386389e+02,2.815621595602773586e-01,1.100000010988609489e+01,2.608199552531663499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684857261684730645e+01,5.660827727272251195e+02,2.815882415262313532e-01,1.100000010988609489e+01,2.608053567130125781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.684948170774731580e+01,5.660927726932154656e+02,2.816143220323362728e-01,1.100000010988609489e+01,2.607907581728588064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685039079864732514e+01,5.661027726592095632e+02,2.816404010785921730e-01,1.100000010988609489e+01,2.607761596327050346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685129988954733449e+01,5.661127726252075263e+02,2.816664786649989982e-01,1.100000010988609489e+01,2.607615610925512629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685220898044734383e+01,5.661227725912092410e+02,2.816925547915567485e-01,1.100000010988609489e+01,2.607469625523974911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685311807134735318e+01,5.661327725572148211e+02,2.817186294582654793e-01,1.100000010988609489e+01,2.607323640122437194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685402716224736253e+01,5.661427725232241528e+02,2.817447026651251352e-01,1.100000010988609489e+01,2.607177654720899476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685493625314737187e+01,5.661527724892373499e+02,2.817707744121357716e-01,1.100000010988609489e+01,2.607031669319361759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685584534404738122e+01,5.661627724552542986e+02,2.817968446992973330e-01,1.100000010988609489e+01,2.606885683917824041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685675443494739056e+01,5.661727724212749990e+02,2.818229135266098195e-01,1.100000010988609489e+01,2.606739698516286324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685766352584739991e+01,5.661827723872995648e+02,2.818489808940732866e-01,1.100000010988609489e+01,2.606593713114748606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685857261674740926e+01,5.661927723533278822e+02,2.818750468016876787e-01,1.100000010988609489e+01,2.606447727713210889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.685948170764741860e+01,5.662027723193600650e+02,2.819011112494529958e-01,1.100000010988609489e+01,2.606301742311673171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686039079854742795e+01,5.662127722853959995e+02,2.819271742373692935e-01,1.100000010988609489e+01,2.606155756910135454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686129988944743729e+01,5.662227722514357993e+02,2.819532357654365162e-01,1.100000010988609489e+01,2.606009771508597736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686220898034744664e+01,5.662327722174793507e+02,2.819792958336546640e-01,1.100000010988609489e+01,2.605863786107060018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686311807124745599e+01,5.662427721835267675e+02,2.820053544420237923e-01,1.100000010988609489e+01,2.605717800705522301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686402716214746533e+01,5.662527721495779360e+02,2.820314115905438457e-01,1.100000010988609489e+01,2.605571815303984583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686493625304747468e+01,5.662627721156329699e+02,2.820574672792148241e-01,1.100000010988609489e+01,2.605425829902446866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686584534394748403e+01,5.662727720816917554e+02,2.820835215080367275e-01,1.100000010988609489e+01,2.605279844500909148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686675443484749337e+01,5.662827720477544062e+02,2.821095742770096115e-01,1.100000010988609489e+01,2.605133859099371431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686766352574750272e+01,5.662927720138208088e+02,2.821356255861334206e-01,1.100000010988609489e+01,2.604987873697833713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686857261664751206e+01,5.663027719798909629e+02,2.821616754354081547e-01,1.100000010988609489e+01,2.604841888296295996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.686948170754752141e+01,5.663127719459649825e+02,2.821877238248338138e-01,1.100000010988609489e+01,2.604695902894758278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687039079844753076e+01,5.663227719120427537e+02,2.822137707544104535e-01,1.100000010988609489e+01,2.604549917493220561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687129988934754010e+01,5.663327718781243902e+02,2.822398162241380182e-01,1.100000010988609489e+01,2.604403932091682843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687220898024754945e+01,5.663427718442097785e+02,2.822658602340165079e-01,1.100000010988609489e+01,2.604257946690145126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687311807114755879e+01,5.663527718102990320e+02,2.822919027840459227e-01,1.100000010988609489e+01,2.604111961288607408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687402716204756814e+01,5.663627717763920373e+02,2.823179438742262626e-01,1.100000010988609489e+01,2.603965975887069691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687493625294757749e+01,5.663727717424889079e+02,2.823439835045575830e-01,1.100000010988609489e+01,2.603819990485531973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687584534384758683e+01,5.663827717085895301e+02,2.823700216750398284e-01,1.100000010988609489e+01,2.603674005083994256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687675443474759618e+01,5.663927716746939041e+02,2.823960583856729989e-01,1.100000010988609489e+01,2.603528019682456538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687766352564760552e+01,5.664027716408021433e+02,2.824220936364570944e-01,1.100000010988609489e+01,2.603382034280918821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687857261654761487e+01,5.664127716069141343e+02,2.824481274273921150e-01,1.100000010988609489e+01,2.603236048879381103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.687948170744762422e+01,5.664227715730299906e+02,2.824741597584780606e-01,1.100000010988609489e+01,2.603090063477843386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688039079834763356e+01,5.664327715391495985e+02,2.825001906297149312e-01,1.100000010988609489e+01,2.602944078076305668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688129988924764291e+01,5.664427715052730719e+02,2.825262200411027269e-01,1.100000010988609489e+01,2.602798092674767950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688220898014765226e+01,5.664527714714002968e+02,2.825522479926414476e-01,1.100000010988609489e+01,2.602652107273230233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688311807104766160e+01,5.664627714375312735e+02,2.825782744843311489e-01,1.100000010988609489e+01,2.602506121871692515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688402716194767095e+01,5.664727714036661155e+02,2.826042995161717752e-01,1.100000010988609489e+01,2.602360136470154798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688493625284768029e+01,5.664827713698047091e+02,2.826303230881633266e-01,1.100000010988609489e+01,2.602214151068617080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688584534374768964e+01,5.664927713359471682e+02,2.826563452003058030e-01,1.100000010988609489e+01,2.602068165667079363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688675443464769899e+01,5.665027713020933788e+02,2.826823658525992045e-01,1.100000010988609489e+01,2.601922180265541645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688766352554770833e+01,5.665127712682434549e+02,2.827083850450435309e-01,1.100000010988609489e+01,2.601776194864003928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688857261644771768e+01,5.665227712343972826e+02,2.827344027776387825e-01,1.100000010988609489e+01,2.601630209462466210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.688948170734772702e+01,5.665327712005548619e+02,2.827604190503849590e-01,1.100000010988609489e+01,2.601484224060928493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689039079824773637e+01,5.665427711667163067e+02,2.827864338632820607e-01,1.100000010988609489e+01,2.601338238659390775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689129988914774572e+01,5.665527711328815030e+02,2.828124472163300873e-01,1.100000010988609489e+01,2.601192253257853058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689220898004775506e+01,5.665627710990505648e+02,2.828384591095290390e-01,1.100000010988609489e+01,2.601046267856315340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689311807094776441e+01,5.665727710652233782e+02,2.828644695428789158e-01,1.100000010988609489e+01,2.600900282454777623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689402716184777375e+01,5.665827710313999432e+02,2.828904785163797175e-01,1.100000010988609489e+01,2.600754297053239905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689493625274778310e+01,5.665927709975803737e+02,2.829164860300314444e-01,1.100000010988609489e+01,2.600608311651702188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689584534364779245e+01,5.666027709637645557e+02,2.829424920838340962e-01,1.100000010988609489e+01,2.600462326250164470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689675443454780179e+01,5.666127709299526032e+02,2.829684966777876176e-01,1.100000010988609489e+01,2.600316340848626753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689766352544781114e+01,5.666227708961444023e+02,2.829944998118920640e-01,1.100000010988609489e+01,2.600170355447089035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689857261634782049e+01,5.666327708623399531e+02,2.830205014861474355e-01,1.100000010988609489e+01,2.600024370045551318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.689948170724782983e+01,5.666427708285393692e+02,2.830465017005537320e-01,1.100000010988609489e+01,2.599878384644013600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690039079814783918e+01,5.666527707947425370e+02,2.830725004551109536e-01,1.100000010988609489e+01,2.599732399242475882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690129988904784852e+01,5.666627707609494564e+02,2.830984977498191002e-01,1.100000010988609489e+01,2.599586413840938165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690220897994785787e+01,5.666727707271602412e+02,2.831244935846781718e-01,1.100000010988609489e+01,2.599440428439400447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690311807084786722e+01,5.666827706933747777e+02,2.831504879596881685e-01,1.100000010988609489e+01,2.599294443037862730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690402716174787656e+01,5.666927706595931795e+02,2.831764808748490903e-01,1.100000010988609489e+01,2.599148457636325012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690493625264788591e+01,5.667027706258153330e+02,2.832024723301608815e-01,1.100000010988609489e+01,2.599002472234787295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690584534354789525e+01,5.667127705920412382e+02,2.832284623256235978e-01,1.100000010988609489e+01,2.598856486833249577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690675443444790460e+01,5.667227705582710087e+02,2.832544508612372391e-01,1.100000010988609489e+01,2.598710501431711860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690766352534791395e+01,5.667327705245045308e+02,2.832804379370018055e-01,1.100000010988609489e+01,2.598564516030174142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690857261624792329e+01,5.667427704907419184e+02,2.833064235529172969e-01,1.100000010988609489e+01,2.598418530628636425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.690948170714793264e+01,5.667527704569830576e+02,2.833324077089836579e-01,1.100000010988609489e+01,2.598272545227098707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691039079804794198e+01,5.667627704232279484e+02,2.833583904052009439e-01,1.100000010988609489e+01,2.598126559825560990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691129988894795133e+01,5.667727703894767046e+02,2.833843716415691549e-01,1.100000010988609489e+01,2.597980574424023272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691220897984796068e+01,5.667827703557292125e+02,2.834103514180882910e-01,1.100000010988609489e+01,2.597834589022485555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691311807074797002e+01,5.667927703219854720e+02,2.834363297347582966e-01,1.100000010988609489e+01,2.597688603620947837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691402716164797937e+01,5.668027702882455969e+02,2.834623065915792273e-01,1.100000010988609489e+01,2.597542618219410120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691493625254798872e+01,5.668127702545094735e+02,2.834882819885510830e-01,1.100000010988609489e+01,2.597396632817872402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691584534344799806e+01,5.668227702207771017e+02,2.835142559256738637e-01,1.100000010988609489e+01,2.597250647416334685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691675443434800741e+01,5.668327701870485953e+02,2.835402284029475140e-01,1.100000010988609489e+01,2.597104662014796967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691766352524801675e+01,5.668427701533238405e+02,2.835661994203720893e-01,1.100000010988609489e+01,2.596958676613259250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691857261614802610e+01,5.668527701196028374e+02,2.835921689779475896e-01,1.100000010988609489e+01,2.596812691211721532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.691948170704803545e+01,5.668627700858856997e+02,2.836181370756739595e-01,1.100000010988609489e+01,2.596666705810183814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692039079794804479e+01,5.668727700521723136e+02,2.836441037135512544e-01,1.100000010988609489e+01,2.596520720408646097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692129988884805414e+01,5.668827700184626792e+02,2.836700688915794744e-01,1.100000010988609489e+01,2.596374735007108379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692220897974806348e+01,5.668927699847569102e+02,2.836960326097585638e-01,1.100000010988609489e+01,2.596228749605570662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692311807064807283e+01,5.669027699510548928e+02,2.837219948680885784e-01,1.100000010988609489e+01,2.596082764204032944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692402716154808218e+01,5.669127699173566270e+02,2.837479556665695180e-01,1.100000010988609489e+01,2.595936778802495227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692493625244809152e+01,5.669227698836622267e+02,2.837739150052013271e-01,1.100000010988609489e+01,2.595790793400957509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692584534334810087e+01,5.669327698499715780e+02,2.837998728839840612e-01,1.100000010988609489e+01,2.595644807999419792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692675443424811021e+01,5.669427698162846809e+02,2.838258293029176649e-01,1.100000010988609489e+01,2.595498822597882074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692766352514811956e+01,5.669527697826016492e+02,2.838517842620021936e-01,1.100000010988609489e+01,2.595352837196344357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692857261604812891e+01,5.669627697489223692e+02,2.838777377612376474e-01,1.100000010988609489e+01,2.595206851794806639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.692948170694813825e+01,5.669727697152468409e+02,2.839036898006239706e-01,1.100000010988609489e+01,2.595060866393268922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693039079784814760e+01,5.669827696815751779e+02,2.839296403801612190e-01,1.100000010988609489e+01,2.594914880991731204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693129988874815695e+01,5.669927696479072665e+02,2.839555894998493368e-01,1.100000010988609489e+01,2.594768895590193487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693220897964816629e+01,5.670027696142431068e+02,2.839815371596883797e-01,1.100000010988609489e+01,2.594622910188655769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693311807054817564e+01,5.670127695805828125e+02,2.840074833596782922e-01,1.100000010988609489e+01,2.594476924787118052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693402716144818498e+01,5.670227695469262699e+02,2.840334280998191296e-01,1.100000010988609489e+01,2.594330939385580334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693493625234819433e+01,5.670327695132734789e+02,2.840593713801108366e-01,1.100000010988609489e+01,2.594184953984042617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693584534324820368e+01,5.670427694796245532e+02,2.840853132005534687e-01,1.100000010988609489e+01,2.594038968582504899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693675443414821302e+01,5.670527694459793793e+02,2.841112535611469703e-01,1.100000010988609489e+01,2.593892983180967182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693766352504822237e+01,5.670627694123379570e+02,2.841371924618913969e-01,1.100000010988609489e+01,2.593746997779429464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693857261594823171e+01,5.670727693787004000e+02,2.841631299027866930e-01,1.100000010988609489e+01,2.593601012377891746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.693948170684824106e+01,5.670827693450665947e+02,2.841890658838329142e-01,1.100000010988609489e+01,2.593455026976354029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694039079774825041e+01,5.670927693114365411e+02,2.842150004050300049e-01,1.100000010988609489e+01,2.593309041574816311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694129988864825975e+01,5.671027692778103528e+02,2.842409334663780207e-01,1.100000010988609489e+01,2.593163056173278594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694220897954826910e+01,5.671127692441879162e+02,2.842668650678769060e-01,1.100000010988609489e+01,2.593017070771740876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694311807044827844e+01,5.671227692105692313e+02,2.842927952095267163e-01,1.100000010988609489e+01,2.592871085370203159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694402716134828779e+01,5.671327691769542980e+02,2.843187238913273962e-01,1.100000010988609489e+01,2.592725099968665441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694493625224829714e+01,5.671427691433432301e+02,2.843446511132789456e-01,1.100000010988609489e+01,2.592579114567127724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694584534314830648e+01,5.671527691097359138e+02,2.843705768753814200e-01,1.100000010988609489e+01,2.592433129165590006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694675443404831583e+01,5.671627690761323493e+02,2.843965011776347640e-01,1.100000010988609489e+01,2.592287143764052289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694766352494832518e+01,5.671727690425326500e+02,2.844224240200389775e-01,1.100000010988609489e+01,2.592141158362514571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694857261584833452e+01,5.671827690089367024e+02,2.844483454025941160e-01,1.100000010988609489e+01,2.591995172960976854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.694948170674834387e+01,5.671927689753445065e+02,2.844742653253001241e-01,1.100000010988609489e+01,2.591849187559439136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695039079764835321e+01,5.672027689417560623e+02,2.845001837881570572e-01,1.100000010988609489e+01,2.591703202157901419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695129988854836256e+01,5.672127689081714834e+02,2.845261007911648599e-01,1.100000010988609489e+01,2.591557216756363701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695220897944837191e+01,5.672227688745906562e+02,2.845520163343235320e-01,1.100000010988609489e+01,2.591411231354825984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695311807034838125e+01,5.672327688410135806e+02,2.845779304176330737e-01,1.100000010988609489e+01,2.591265245953288266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695402716124839060e+01,5.672427688074403704e+02,2.846038430410935405e-01,1.100000010988609489e+01,2.591119260551750549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695493625214839994e+01,5.672527687738709119e+02,2.846297542047048768e-01,1.100000010988609489e+01,2.590973275150212831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695584534304840929e+01,5.672627687403052050e+02,2.846556639084670826e-01,1.100000010988609489e+01,2.590827289748675114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695675443394841864e+01,5.672727687067432498e+02,2.846815721523802134e-01,1.100000010988609489e+01,2.590681304347137396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695766352484842798e+01,5.672827686731851600e+02,2.847074789364442138e-01,1.100000010988609489e+01,2.590535318945599678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695857261574843733e+01,5.672927686396308218e+02,2.847333842606590837e-01,1.100000010988609489e+01,2.590389333544061961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.695948170664844667e+01,5.673027686060802353e+02,2.847592881250248231e-01,1.100000010988609489e+01,2.590243348142524243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696039079754845602e+01,5.673127685725334004e+02,2.847851905295414876e-01,1.100000010988609489e+01,2.590097362740986526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696129988844846537e+01,5.673227685389904309e+02,2.848110914742090216e-01,1.100000010988609489e+01,2.589951377339448808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696220897934847471e+01,5.673327685054512131e+02,2.848369909590274252e-01,1.100000010988609489e+01,2.589805391937911091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696311807024848406e+01,5.673427684719157469e+02,2.848628889839966982e-01,1.100000010988609489e+01,2.589659406536373373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696402716114849341e+01,5.673527684383840324e+02,2.848887855491168408e-01,1.100000010988609489e+01,2.589513421134835656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696493625204850275e+01,5.673627684048561832e+02,2.849146806543879085e-01,1.100000010988609489e+01,2.589367435733297938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696584534294851210e+01,5.673727683713320857e+02,2.849405742998098456e-01,1.100000010988609489e+01,2.589221450331760221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696675443384852144e+01,5.673827683378117399e+02,2.849664664853826523e-01,1.100000010988609489e+01,2.589075464930222503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696766352474853079e+01,5.673927683042951458e+02,2.849923572111063286e-01,1.100000010988609489e+01,2.588929479528684786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696857261564854014e+01,5.674027682707824169e+02,2.850182464769808743e-01,1.100000010988609489e+01,2.588783494127147068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.696948170654854948e+01,5.674127682372734398e+02,2.850441342830062896e-01,1.100000010988609489e+01,2.588637508725609351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697039079744855883e+01,5.674227682037682143e+02,2.850700206291825745e-01,1.100000010988609489e+01,2.588491523324071633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697129988834856817e+01,5.674327681702667405e+02,2.850959055155097843e-01,1.100000010988609489e+01,2.588345537922533916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697220897924857752e+01,5.674427681367691321e+02,2.851217889419878637e-01,1.100000010988609489e+01,2.588199552520996198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697311807014858687e+01,5.674527681032752753e+02,2.851476709086168126e-01,1.100000010988609489e+01,2.588053567119458481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697402716104859621e+01,5.674627680697851702e+02,2.851735514153966311e-01,1.100000010988609489e+01,2.587907581717920763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697493625194860556e+01,5.674727680362988167e+02,2.851994304623273191e-01,1.100000010988609489e+01,2.587761596316383046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697584534284861491e+01,5.674827680028163286e+02,2.852253080494088766e-01,1.100000010988609489e+01,2.587615610914845328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697675443374862425e+01,5.674927679693375921e+02,2.852511841766413037e-01,1.100000010988609489e+01,2.587469625513307610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697766352464863360e+01,5.675027679358626074e+02,2.852770588440246002e-01,1.100000010988609489e+01,2.587323640111769893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697857261554864294e+01,5.675127679023913743e+02,2.853029320515587663e-01,1.100000010988609489e+01,2.587177654710232175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.697948170644865229e+01,5.675227678689240065e+02,2.853288037992438020e-01,1.100000010988609489e+01,2.587031669308694458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698039079734866164e+01,5.675327678354603904e+02,2.853546740870797072e-01,1.100000010988609489e+01,2.586885683907156740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698129988824867098e+01,5.675427678020005260e+02,2.853805429150664819e-01,1.100000010988609489e+01,2.586739698505619023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698220897914868033e+01,5.675527677685444132e+02,2.854064102832041261e-01,1.100000010988609489e+01,2.586593713104081305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698311807004868967e+01,5.675627677350920521e+02,2.854322761914926398e-01,1.100000010988609489e+01,2.586447727702543588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698402716094869902e+01,5.675727677016435564e+02,2.854581406399320231e-01,1.100000010988609489e+01,2.586301742301005870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698493625184870837e+01,5.675827676681988123e+02,2.854840036285222760e-01,1.100000010988609489e+01,2.586155756899468153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698584534274871771e+01,5.675927676347578199e+02,2.855098651572633983e-01,1.100000010988609489e+01,2.586009771497930435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698675443364872706e+01,5.676027676013205792e+02,2.855357252261553902e-01,1.100000010988609489e+01,2.585863786096392718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698766352454873640e+01,5.676127675678870901e+02,2.855615838351982516e-01,1.100000010988609489e+01,2.585717800694855000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698857261544874575e+01,5.676227675344574664e+02,2.855874409843919826e-01,1.100000010988609489e+01,2.585571815293317283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.698948170634875510e+01,5.676327675010315943e+02,2.856132966737365830e-01,1.100000010988609489e+01,2.585425829891779565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699039079724876444e+01,5.676427674676094739e+02,2.856391509032320530e-01,1.100000010988609489e+01,2.585279844490241848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699129988814877379e+01,5.676527674341911052e+02,2.856650036728783371e-01,1.100000010988609489e+01,2.585133859088704130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699220897904878314e+01,5.676627674007764881e+02,2.856908549826754906e-01,1.100000010988609489e+01,2.584987873687166413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699311806994879248e+01,5.676727673673657364e+02,2.857167048326235137e-01,1.100000010988609489e+01,2.584841888285628695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699402716084880183e+01,5.676827673339587363e+02,2.857425532227224063e-01,1.100000010988609489e+01,2.584695902884090978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699493625174881117e+01,5.676927673005554880e+02,2.857684001529721685e-01,1.100000010988609489e+01,2.584549917482553260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699584534264882052e+01,5.677027672671559912e+02,2.857942456233728001e-01,1.100000010988609489e+01,2.584403932081015542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699675443354882987e+01,5.677127672337602462e+02,2.858200896339243013e-01,1.100000010988609489e+01,2.584257946679477825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699766352444883921e+01,5.677227672003683665e+02,2.858459321846266166e-01,1.100000010988609489e+01,2.584111961277940107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699857261534884856e+01,5.677327671669802385e+02,2.858717732754798013e-01,1.100000010988609489e+01,2.583965975876402390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.699948170624885790e+01,5.677427671335958621e+02,2.858976129064838556e-01,1.100000010988609489e+01,2.583819990474864672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700039079714886725e+01,5.677527671002152374e+02,2.859234510776387794e-01,1.100000010988609489e+01,2.583674005073326955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700129988804887660e+01,5.677627670668383644e+02,2.859492877889445728e-01,1.100000010988609489e+01,2.583528019671789237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700220897894888594e+01,5.677727670334652430e+02,2.859751230404011801e-01,1.100000010988609489e+01,2.583382034270251520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700311806984889529e+01,5.677827670000959870e+02,2.860009568320086570e-01,1.100000010988609489e+01,2.583236048868713802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700402716074890463e+01,5.677927669667304826e+02,2.860267891637670035e-01,1.100000010988609489e+01,2.583090063467176085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700493625164891398e+01,5.678027669333687300e+02,2.860526200356762194e-01,1.100000010988609489e+01,2.582944078065638367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700584534254892333e+01,5.678127669000107289e+02,2.860784494477362494e-01,1.100000010988609489e+01,2.582798092664100650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700675443344893267e+01,5.678227668666564796e+02,2.861042773999471489e-01,1.100000010988609489e+01,2.582652107262562932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700766352434894202e+01,5.678327668333059819e+02,2.861301038923089179e-01,1.100000010988609489e+01,2.582506121861025215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700857261524895137e+01,5.678427667999593496e+02,2.861559289248215010e-01,1.100000010988609489e+01,2.582360136459487497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.700948170614896071e+01,5.678527667666164689e+02,2.861817524974849536e-01,1.100000010988609489e+01,2.582214151057949780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701039079704897006e+01,5.678627667332773399e+02,2.862075746102992757e-01,1.100000010988609489e+01,2.582068165656412062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701129988794897940e+01,5.678727666999419625e+02,2.862333952632644674e-01,1.100000010988609489e+01,2.581922180254874345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701220897884898875e+01,5.678827666666103369e+02,2.862592144563804730e-01,1.100000010988609489e+01,2.581776194853336627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701311806974899810e+01,5.678927666332824629e+02,2.862850321896473482e-01,1.100000010988609489e+01,2.581630209451798909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701402716064900744e+01,5.679027665999584542e+02,2.863108484630650374e-01,1.100000010988609489e+01,2.581484224050261192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701493625154901679e+01,5.679127665666381972e+02,2.863366632766335962e-01,1.100000010988609489e+01,2.581338238648723474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701584534244902613e+01,5.679227665333216919e+02,2.863624766303530245e-01,1.100000010988609489e+01,2.581192253247185757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701675443334903548e+01,5.679327665000089382e+02,2.863882885242232668e-01,1.100000010988609489e+01,2.581046267845648039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701766352424904483e+01,5.679427664666999362e+02,2.864140989582443786e-01,1.100000010988609489e+01,2.580900282444110322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701857261514905417e+01,5.679527664333946859e+02,2.864399079324163599e-01,1.100000010988609489e+01,2.580754297042572604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.701948170604906352e+01,5.679627664000931873e+02,2.864657154467391553e-01,1.100000010988609489e+01,2.580608311641034887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702039079694907286e+01,5.679727663667955539e+02,2.864915215012128202e-01,1.100000010988609489e+01,2.580462326239497169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702129988784908221e+01,5.679827663335016723e+02,2.865173260958372992e-01,1.100000010988609489e+01,2.580316340837959452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702220897874909156e+01,5.679927663002115423e+02,2.865431292306126476e-01,1.100000010988609489e+01,2.580170355436421734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702311806964910090e+01,5.680027662669251640e+02,2.865689309055388101e-01,1.100000010988609489e+01,2.580024370034884017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702402716054911025e+01,5.680127662336425374e+02,2.865947311206158421e-01,1.100000010988609489e+01,2.579878384633346299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702493625144911960e+01,5.680227662003636624e+02,2.866205298758436881e-01,1.100000010988609489e+01,2.579732399231808582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702584534234912894e+01,5.680327661670885391e+02,2.866463271712224037e-01,1.100000010988609489e+01,2.579586413830270864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702675443324913829e+01,5.680427661338172811e+02,2.866721230067519333e-01,1.100000010988609489e+01,2.579440428428733147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702766352414914763e+01,5.680527661005497748e+02,2.866979173824323324e-01,1.100000010988609489e+01,2.579294443027195429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702857261504915698e+01,5.680627660672860202e+02,2.867237102982635455e-01,1.100000010988609489e+01,2.579148457625657712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.702948170594916633e+01,5.680727660340260172e+02,2.867495017542456281e-01,1.100000010988609489e+01,2.579002472224119994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703039079684917567e+01,5.680827660007697659e+02,2.867752917503785248e-01,1.100000010988609489e+01,2.578856486822582277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703129988774918502e+01,5.680927659675172663e+02,2.868010802866622910e-01,1.100000010988609489e+01,2.578710501421044559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703220897864919436e+01,5.681027659342685183e+02,2.868268673630968713e-01,1.100000010988609489e+01,2.578564516019506841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703311806954920371e+01,5.681127659010235220e+02,2.868526529796823210e-01,1.100000010988609489e+01,2.578418530617969124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703402716044921306e+01,5.681227658677822774e+02,2.868784371364185848e-01,1.100000010988609489e+01,2.578272545216431406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703493625134922240e+01,5.681327658345448981e+02,2.869042198333057181e-01,1.100000010988609489e+01,2.578126559814893689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703584534224923175e+01,5.681427658013112705e+02,2.869300010703436654e-01,1.100000010988609489e+01,2.577980574413355971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703675443314924109e+01,5.681527657680813945e+02,2.869557808475324268e-01,1.100000010988609489e+01,2.577834589011818254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703766352404925044e+01,5.681627657348552702e+02,2.869815591648720576e-01,1.100000010988609489e+01,2.577688603610280536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703857261494925979e+01,5.681727657016328976e+02,2.870073360223625025e-01,1.100000010988609489e+01,2.577542618208742819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.703948170584926913e+01,5.681827656684142767e+02,2.870331114200037614e-01,1.100000010988609489e+01,2.577396632807205101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704039079674927848e+01,5.681927656351994074e+02,2.870588853577958899e-01,1.100000010988609489e+01,2.577250647405667384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704129988764928783e+01,5.682027656019882897e+02,2.870846578357388323e-01,1.100000010988609489e+01,2.577104662004129666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704220897854929717e+01,5.682127655687809238e+02,2.871104288538326443e-01,1.100000010988609489e+01,2.576958676602591949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704311806944930652e+01,5.682227655355773095e+02,2.871361984120772703e-01,1.100000010988609489e+01,2.576812691201054231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704402716034931586e+01,5.682327655023775606e+02,2.871619665104727104e-01,1.100000010988609489e+01,2.576666705799516514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704493625124932521e+01,5.682427654691815633e+02,2.871877331490189644e-01,1.100000010988609489e+01,2.576520720397978796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704584534214933456e+01,5.682527654359893177e+02,2.872134983277160880e-01,1.100000010988609489e+01,2.576374734996441079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704675443304934390e+01,5.682627654028008237e+02,2.872392620465640256e-01,1.100000010988609489e+01,2.576228749594903361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704766352394935325e+01,5.682727653696160814e+02,2.872650243055627772e-01,1.100000010988609489e+01,2.576082764193365644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704857261484936259e+01,5.682827653364350908e+02,2.872907851047123984e-01,1.100000010988609489e+01,2.575936778791827926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.704948170574937194e+01,5.682927653032578519e+02,2.873165444440128335e-01,1.100000010988609489e+01,2.575790793390290209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705039079664938129e+01,5.683027652700843646e+02,2.873423023234640827e-01,1.100000010988609489e+01,2.575644807988752491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705129988754939063e+01,5.683127652369146290e+02,2.873680587430661459e-01,1.100000010988609489e+01,2.575498822587214773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705220897844939998e+01,5.683227652037486450e+02,2.873938137028190787e-01,1.100000010988609489e+01,2.575352837185677056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705311806934940932e+01,5.683327651705864128e+02,2.874195672027228254e-01,1.100000010988609489e+01,2.575206851784139338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705402716024941867e+01,5.683427651374279321e+02,2.874453192427773862e-01,1.100000010988609489e+01,2.575060866382601621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705493625114942802e+01,5.683527651042732032e+02,2.874710698229827610e-01,1.100000010988609489e+01,2.574914880981063903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705584534204943736e+01,5.683627650711223396e+02,2.874968189433389498e-01,1.100000010988609489e+01,2.574768895579526186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705675443294944671e+01,5.683727650379752276e+02,2.875225666038460082e-01,1.100000010988609489e+01,2.574622910177988468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705766352384945606e+01,5.683827650048318674e+02,2.875483128045038805e-01,1.100000010988609489e+01,2.574476924776450751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705857261474946540e+01,5.683927649716922588e+02,2.875740575453125669e-01,1.100000010988609489e+01,2.574330939374913033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.705948170564947475e+01,5.684027649385564018e+02,2.875998008262720673e-01,1.100000010988609489e+01,2.574184953973375316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706039079654948409e+01,5.684127649054242966e+02,2.876255426473823817e-01,1.100000010988609489e+01,2.574038968571837598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706129988744949344e+01,5.684227648722959430e+02,2.876512830086435102e-01,1.100000010988609489e+01,2.573892983170299881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706220897834950279e+01,5.684327648391713410e+02,2.876770219100554526e-01,1.100000010988609489e+01,2.573746997768762163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706311806924951213e+01,5.684427648060504907e+02,2.877027593516182646e-01,1.100000010988609489e+01,2.573601012367224446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706402716014952148e+01,5.684527647729333921e+02,2.877284953333318906e-01,1.100000010988609489e+01,2.573455026965686728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706493625104953082e+01,5.684627647398200452e+02,2.877542298551963307e-01,1.100000010988609489e+01,2.573309041564149011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706584534194954017e+01,5.684727647067104499e+02,2.877799629172115847e-01,1.100000010988609489e+01,2.573163056162611293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706675443284954952e+01,5.684827646736046063e+02,2.878056945193776528e-01,1.100000010988609489e+01,2.573017070761073576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706766352374955886e+01,5.684927646405025143e+02,2.878314246616945349e-01,1.100000010988609489e+01,2.572871085359535858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706857261464956821e+01,5.685027646074041741e+02,2.878571533441622310e-01,1.100000010988609489e+01,2.572725099957998141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.706948170554957755e+01,5.685127645743095854e+02,2.878828805667807411e-01,1.100000010988609489e+01,2.572579114556460423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707039079644958690e+01,5.685227645412187485e+02,2.879086063295500653e-01,1.100000010988609489e+01,2.572433129154922705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707129988734959625e+01,5.685327645081316632e+02,2.879343306324702034e-01,1.100000010988609489e+01,2.572287143753384988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707220897824960559e+01,5.685427644750483296e+02,2.879600534755411556e-01,1.100000010988609489e+01,2.572141158351847270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707311806914961494e+01,5.685527644419687476e+02,2.879857748587629218e-01,1.100000010988609489e+01,2.571995172950309553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707402716004962429e+01,5.685627644088929173e+02,2.880114947821355020e-01,1.100000010988609489e+01,2.571849187548771835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707493625094963363e+01,5.685727643758208387e+02,2.880372132456588963e-01,1.100000010988609489e+01,2.571703202147234118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707584534184964298e+01,5.685827643427526255e+02,2.880629302493331045e-01,1.100000010988609489e+01,2.571557216745696400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707675443274965232e+01,5.685927643096881638e+02,2.880886457931581268e-01,1.100000010988609489e+01,2.571411231344158683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707766352364966167e+01,5.686027642766274539e+02,2.881143598771339631e-01,1.100000010988609489e+01,2.571265245942620965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707857261454967102e+01,5.686127642435704956e+02,2.881400725012606134e-01,1.100000010988609489e+01,2.571119260541083248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.707948170544968036e+01,5.686227642105172890e+02,2.881657836655380778e-01,1.100000010988609489e+01,2.570973275139545530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708039079634968971e+01,5.686327641774678341e+02,2.881914933699663561e-01,1.100000010988609489e+01,2.570827289738007813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708129988724969905e+01,5.686427641444221308e+02,2.882172016145454485e-01,1.100000010988609489e+01,2.570681304336470095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708220897814970840e+01,5.686527641113801792e+02,2.882429083992753549e-01,1.100000010988609489e+01,2.570535318934932378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708311806904971775e+01,5.686627640783419793e+02,2.882686137241560198e-01,1.100000010988609489e+01,2.570389333533394660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708402715994972709e+01,5.686727640453075310e+02,2.882943175891874987e-01,1.100000010988609489e+01,2.570243348131856943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708493625084973644e+01,5.686827640122768344e+02,2.883200199943697917e-01,1.100000010988609489e+01,2.570097362730319225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708584534174974578e+01,5.686927639792498894e+02,2.883457209397028986e-01,1.100000010988609489e+01,2.569951377328781508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708675443264975513e+01,5.687027639462266961e+02,2.883714204251868196e-01,1.100000010988609489e+01,2.569805391927243790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708766352354976448e+01,5.687127639132072545e+02,2.883971184508215546e-01,1.100000010988609489e+01,2.569659406525706073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708857261444977382e+01,5.687227638801915646e+02,2.884228150166071036e-01,1.100000010988609489e+01,2.569513421124168355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.708948170534978317e+01,5.687327638471796263e+02,2.884485101225434112e-01,1.100000010988609489e+01,2.569367435722630637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709039079624979252e+01,5.687427638141714397e+02,2.884742037686305327e-01,1.100000010988609489e+01,2.569221450321092920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709129988714980186e+01,5.687527637811670047e+02,2.884998959548684683e-01,1.100000010988609489e+01,2.569075464919555202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709220897804981121e+01,5.687627637481663214e+02,2.885255866812572179e-01,1.100000010988609489e+01,2.568929479518017485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709311806894982055e+01,5.687727637151693898e+02,2.885512759477967815e-01,1.100000010988609489e+01,2.568783494116479767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709402715984982990e+01,5.687827636821762098e+02,2.885769637544871036e-01,1.100000010988609489e+01,2.568637508714942050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709493625074983925e+01,5.687927636491867815e+02,2.886026501013282397e-01,1.100000010988609489e+01,2.568491523313404332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709584534164984859e+01,5.688027636162011049e+02,2.886283349883201899e-01,1.100000010988609489e+01,2.568345537911866615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709675443254985794e+01,5.688127635832191800e+02,2.886540184154629540e-01,1.100000010988609489e+01,2.568199552510328897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709766352344986728e+01,5.688227635502410067e+02,2.886797003827564767e-01,1.100000010988609489e+01,2.568053567108791180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709857261434987663e+01,5.688327635172665850e+02,2.887053808902008134e-01,1.100000010988609489e+01,2.567907581707253462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.709948170524988598e+01,5.688427634842958014e+02,2.887310599377959641e-01,1.100000010988609489e+01,2.567761596305715745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710039079614989532e+01,5.688527634513287694e+02,2.887567375255418733e-01,1.100000010988609489e+01,2.567615610904178027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710129988704990467e+01,5.688627634183654891e+02,2.887824136534385966e-01,1.100000010988609489e+01,2.567469625502640310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710220897794991401e+01,5.688727633854059604e+02,2.888080883214861339e-01,1.100000010988609489e+01,2.567323640101102592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710311806884992336e+01,5.688827633524501834e+02,2.888337615296844851e-01,1.100000010988609489e+01,2.567177654699564875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710402715974993271e+01,5.688927633194981581e+02,2.888594332780335949e-01,1.100000010988609489e+01,2.567031669298027157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710493625064994205e+01,5.689027632865498845e+02,2.888851035665335187e-01,1.100000010988609489e+01,2.566885683896489440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710584534154995140e+01,5.689127632536053625e+02,2.889107723951842011e-01,1.100000010988609489e+01,2.566739698494951722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710675443244996075e+01,5.689227632206645922e+02,2.889364397639856974e-01,1.100000010988609489e+01,2.566593713093414005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710766352334997009e+01,5.689327631877275735e+02,2.889621056729380077e-01,1.100000010988609489e+01,2.566447727691876287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710857261424997944e+01,5.689427631547943065e+02,2.889877701220410766e-01,1.100000010988609489e+01,2.566301742290338569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.710948170514998878e+01,5.689527631218647912e+02,2.890134331112949595e-01,1.100000010988609489e+01,2.566155756888800852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711039079604999813e+01,5.689627630889390275e+02,2.890390946406996564e-01,1.100000010988609489e+01,2.566009771487263134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711129988695000748e+01,5.689727630560170155e+02,2.890647547102551118e-01,1.100000010988609489e+01,2.565863786085725417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711220897785001682e+01,5.689827630230987552e+02,2.890904133199613812e-01,1.100000010988609489e+01,2.565717800684187699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711311806875002617e+01,5.689927629901842465e+02,2.891160704698184092e-01,1.100000010988609489e+01,2.565571815282649982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711402715965003551e+01,5.690027629572734895e+02,2.891417261598262511e-01,1.100000010988609489e+01,2.565425829881112264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711493625055004486e+01,5.690127629243664842e+02,2.891673803899848516e-01,1.100000010988609489e+01,2.565279844479574547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711584534145005421e+01,5.690227628914632305e+02,2.891930331602942661e-01,1.100000010988609489e+01,2.565133859078036829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711675443235006355e+01,5.690327628585637285e+02,2.892186844707544391e-01,1.100000010988609489e+01,2.564987873676499112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711766352325007290e+01,5.690427628256679782e+02,2.892443343213654261e-01,1.100000010988609489e+01,2.564841888274961394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711857261415008225e+01,5.690527627927759795e+02,2.892699827121271716e-01,1.100000010988609489e+01,2.564695902873423677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.711948170505009159e+01,5.690627627598876188e+02,2.892956296430397312e-01,1.100000010988609489e+01,2.564549917471885959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712039079595010094e+01,5.690727627270030098e+02,2.893212751141030492e-01,1.100000010988609489e+01,2.564403932070348242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712129988685011028e+01,5.690827626941221524e+02,2.893469191253171813e-01,1.100000010988609489e+01,2.564257946668810524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712220897775011963e+01,5.690927626612450467e+02,2.893725616766820719e-01,1.100000010988609489e+01,2.564111961267272807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712311806865012898e+01,5.691027626283716927e+02,2.893982027681977764e-01,1.100000010988609489e+01,2.563965975865735089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712402715955013832e+01,5.691127625955020903e+02,2.894238423998642395e-01,1.100000010988609489e+01,2.563819990464197372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712493625045014767e+01,5.691227625626362396e+02,2.894494805716815167e-01,1.100000010988609489e+01,2.563674005062659654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712584534135015701e+01,5.691327625297741406e+02,2.894751172836495523e-01,1.100000010988609489e+01,2.563528019661121937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712675443225016636e+01,5.691427624969157932e+02,2.895007525357684020e-01,1.100000010988609489e+01,2.563382034259584219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712766352315017571e+01,5.691527624640611975e+02,2.895263863280380101e-01,1.100000010988609489e+01,2.563236048858046501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712857261405018505e+01,5.691627624312103535e+02,2.895520186604583768e-01,1.100000010988609489e+01,2.563090063456508784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.712948170495019440e+01,5.691727623983632611e+02,2.895776495330295575e-01,1.100000010988609489e+01,2.562944078054971066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713039079585020374e+01,5.691827623655199204e+02,2.896032789457514967e-01,1.100000010988609489e+01,2.562798092653433349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713129988675021309e+01,5.691927623326802177e+02,2.896289068986242499e-01,1.100000010988609489e+01,2.562652107251895631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713220897765022244e+01,5.692027622998442666e+02,2.896545333916477616e-01,1.100000010988609489e+01,2.562506121850357914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713311806855023178e+01,5.692127622670120672e+02,2.896801584248220318e-01,1.100000010988609489e+01,2.562360136448820196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713402715945024113e+01,5.692227622341836195e+02,2.897057819981471161e-01,1.100000010988609489e+01,2.562214151047282479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713493625035025048e+01,5.692327622013589234e+02,2.897314041116229588e-01,1.100000010988609489e+01,2.562068165645744761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713584534125025982e+01,5.692427621685379791e+02,2.897570247652495601e-01,1.100000010988609489e+01,2.561922180244207044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713675443215026917e+01,5.692527621357207863e+02,2.897826439590269754e-01,1.100000010988609489e+01,2.561776194842669326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713766352305027851e+01,5.692627621029073453e+02,2.898082616929551492e-01,1.100000010988609489e+01,2.561630209441131609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713857261395028786e+01,5.692727620700976559e+02,2.898338779670340815e-01,1.100000010988609489e+01,2.561484224039593891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.713948170485029721e+01,5.692827620372917181e+02,2.898594927812637723e-01,1.100000010988609489e+01,2.561338238638056174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714039079575030655e+01,5.692927620044894184e+02,2.898851061356442771e-01,1.100000010988609489e+01,2.561192253236518456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714129988665031590e+01,5.693027619716908703e+02,2.899107180301755404e-01,1.100000010988609489e+01,2.561046267834980739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714220897755032524e+01,5.693127619388960738e+02,2.899363284648575623e-01,1.100000010988609489e+01,2.560900282433443021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714311806845033459e+01,5.693227619061050291e+02,2.899619374396903426e-01,1.100000010988609489e+01,2.560754297031905304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714402715935034394e+01,5.693327618733177360e+02,2.899875449546739370e-01,1.100000010988609489e+01,2.560608311630367586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714493625025035328e+01,5.693427618405341946e+02,2.900131510098082899e-01,1.100000010988609489e+01,2.560462326228829869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714584534115036263e+01,5.693527618077544048e+02,2.900387556050934013e-01,1.100000010988609489e+01,2.560316340827292151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714675443205037197e+01,5.693627617749783667e+02,2.900643587405292712e-01,1.100000010988609489e+01,2.560170355425754433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714766352295038132e+01,5.693727617422059666e+02,2.900899604161159551e-01,1.100000010988609489e+01,2.560024370024216716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714857261385039067e+01,5.693827617094373181e+02,2.901155606318533975e-01,1.100000010988609489e+01,2.559878384622678998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.714948170475040001e+01,5.693927616766724213e+02,2.901411593877415984e-01,1.100000010988609489e+01,2.559732399221141281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715039079565040936e+01,5.694027616439112762e+02,2.901667566837805579e-01,1.100000010988609489e+01,2.559586413819603563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715129988655041871e+01,5.694127616111538828e+02,2.901923525199702758e-01,1.100000010988609489e+01,2.559440428418065846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715220897745042805e+01,5.694227615784002410e+02,2.902179468963107523e-01,1.100000010988609489e+01,2.559294443016528128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715311806835043740e+01,5.694327615456503509e+02,2.902435398128019872e-01,1.100000010988609489e+01,2.559148457614990411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715402715925044674e+01,5.694427615129042124e+02,2.902691312694440362e-01,1.100000010988609489e+01,2.559002472213452693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715493625015045609e+01,5.694527614801617119e+02,2.902947212662368437e-01,1.100000010988609489e+01,2.558856486811914976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715584534105046544e+01,5.694627614474229631e+02,2.903203098031804097e-01,1.100000010988609489e+01,2.558710501410377258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715675443195047478e+01,5.694727614146879660e+02,2.903458968802747342e-01,1.100000010988609489e+01,2.558564516008839541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715766352285048413e+01,5.694827613819567205e+02,2.903714824975198172e-01,1.100000010988609489e+01,2.558418530607301823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715857261375049347e+01,5.694927613492292267e+02,2.903970666549156587e-01,1.100000010988609489e+01,2.558272545205764106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.715948170465050282e+01,5.695027613165054845e+02,2.904226493524622588e-01,1.100000010988609489e+01,2.558126559804226388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716039079555051217e+01,5.695127612837854940e+02,2.904482305901596173e-01,1.100000010988609489e+01,2.557980574402688671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716129988645052151e+01,5.695227612510691415e+02,2.904738103680077344e-01,1.100000010988609489e+01,2.557834589001150953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716220897735053086e+01,5.695327612183565407e+02,2.904993886860066099e-01,1.100000010988609489e+01,2.557688603599613236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716311806825054020e+01,5.695427611856476915e+02,2.905249655441562440e-01,1.100000010988609489e+01,2.557542618198075518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716402715915054955e+01,5.695527611529425940e+02,2.905505409424566365e-01,1.100000010988609489e+01,2.557396632796537801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716493625005055890e+01,5.695627611202412481e+02,2.905761148809077876e-01,1.100000010988609489e+01,2.557250647395000083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716584534095056824e+01,5.695727610875436540e+02,2.906016873595096972e-01,1.100000010988609489e+01,2.557104661993462365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716675443185057759e+01,5.695827610548496978e+02,2.906272583782623653e-01,1.100000010988609489e+01,2.556958676591924648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716766352275058694e+01,5.695927610221594932e+02,2.906528279371657919e-01,1.100000010988609489e+01,2.556812691190386930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716857261365059628e+01,5.696027609894730404e+02,2.906783960362199770e-01,1.100000010988609489e+01,2.556666705788849213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.716948170455060563e+01,5.696127609567903392e+02,2.907039626754249206e-01,1.100000010988609489e+01,2.556520720387311495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717039079545061497e+01,5.696227609241113896e+02,2.907295278547806228e-01,1.100000010988609489e+01,2.556374734985773778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717129988635062432e+01,5.696327608914361917e+02,2.907550915742870834e-01,1.100000010988609489e+01,2.556228749584236060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717220897725063367e+01,5.696427608587646318e+02,2.907806538339443025e-01,1.100000010988609489e+01,2.556082764182698343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717311806815064301e+01,5.696527608260968236e+02,2.908062146337522802e-01,1.100000010988609489e+01,2.555936778781160625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717402715905065236e+01,5.696627607934327671e+02,2.908317739737110164e-01,1.100000010988609489e+01,2.555790793379622908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717493624995066170e+01,5.696727607607724622e+02,2.908573318538205110e-01,1.100000010988609489e+01,2.555644807978085190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717584534085067105e+01,5.696827607281159089e+02,2.908828882740807642e-01,1.100000010988609489e+01,2.555498822576547473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717675443175068040e+01,5.696927606954631074e+02,2.909084432344917204e-01,1.100000010988609489e+01,2.555352837175009755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717766352265068974e+01,5.697027606628139438e+02,2.909339967350534351e-01,1.100000010988609489e+01,2.555206851773472038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717857261355069909e+01,5.697127606301685319e+02,2.909595487757659082e-01,1.100000010988609489e+01,2.555060866371934320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.717948170445070843e+01,5.697227605975268716e+02,2.909850993566291399e-01,1.100000010988609489e+01,2.554914880970396603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718039079535071778e+01,5.697327605648889630e+02,2.910106484776431301e-01,1.100000010988609489e+01,2.554768895568858885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718129988625072713e+01,5.697427605322548061e+02,2.910361961388078789e-01,1.100000010988609489e+01,2.554622910167321168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718220897715073647e+01,5.697527604996242871e+02,2.910617423401233861e-01,1.100000010988609489e+01,2.554476924765783450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718311806805074582e+01,5.697627604669975199e+02,2.910872870815895963e-01,1.100000010988609489e+01,2.554330939364245733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718402715895075517e+01,5.697727604343745043e+02,2.911128303632065650e-01,1.100000010988609489e+01,2.554184953962708015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718493624985076451e+01,5.697827604017552403e+02,2.911383721849742923e-01,1.100000010988609489e+01,2.554038968561170297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718584534075077386e+01,5.697927603691397280e+02,2.911639125468927780e-01,1.100000010988609489e+01,2.553892983159632580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718675443165078320e+01,5.698027603365278537e+02,2.911894514489619668e-01,1.100000010988609489e+01,2.553746997758094862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718766352255079255e+01,5.698127603039197311e+02,2.912149888911819140e-01,1.100000010988609489e+01,2.553601012356557145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718857261345080190e+01,5.698227602713153601e+02,2.912405248735526198e-01,1.100000010988609489e+01,2.553455026955019427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.718948170435081124e+01,5.698327602387147408e+02,2.912660593960740840e-01,1.100000010988609489e+01,2.553309041553481710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719039079525082059e+01,5.698427602061178732e+02,2.912915924587462513e-01,1.100000010988609489e+01,2.553163056151943992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719129988615082993e+01,5.698527601735246435e+02,2.913171240615691771e-01,1.100000010988609489e+01,2.553017070750406275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719220897705083928e+01,5.698627601409351655e+02,2.913426542045428613e-01,1.100000010988609489e+01,2.552871085348868557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719311806795084863e+01,5.698727601083494392e+02,2.913681828876673041e-01,1.100000010988609489e+01,2.552725099947330840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719402715885085797e+01,5.698827600757674645e+02,2.913937101109424499e-01,1.100000010988609489e+01,2.552579114545793122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719493624975086732e+01,5.698927600431891278e+02,2.914192358743683542e-01,1.100000010988609489e+01,2.552433129144255405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719584534065087666e+01,5.699027600106145428e+02,2.914447601779450170e-01,1.100000010988609489e+01,2.552287143742717687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719675443155088601e+01,5.699127599780437095e+02,2.914702830216723828e-01,1.100000010988609489e+01,2.552141158341179970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719766352245089536e+01,5.699227599454766278e+02,2.914958044055505071e-01,1.100000010988609489e+01,2.551995172939642252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719857261335090470e+01,5.699327599129132977e+02,2.915213243295793899e-01,1.100000010988609489e+01,2.551849187538104535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.719948170425091405e+01,5.699427598803536057e+02,2.915468427937589757e-01,1.100000010988609489e+01,2.551703202136566817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720039079515092340e+01,5.699527598477976653e+02,2.915723597980893200e-01,1.100000010988609489e+01,2.551557216735029100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720129988605093274e+01,5.699627598152454766e+02,2.915978753425703673e-01,1.100000010988609489e+01,2.551411231333491382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720220897695094209e+01,5.699727597826970396e+02,2.916233894272021732e-01,1.100000010988609489e+01,2.551265245931953664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720311806785095143e+01,5.699827597501522405e+02,2.916489020519847375e-01,1.100000010988609489e+01,2.551119260530415947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720402715875096078e+01,5.699927597176111931e+02,2.916744132169180048e-01,1.100000010988609489e+01,2.550973275128878229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720493624965097013e+01,5.700027596850738973e+02,2.916999229220020307e-01,1.100000010988609489e+01,2.550827289727340512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720584534055097947e+01,5.700127596525403533e+02,2.917254311672367595e-01,1.100000010988609489e+01,2.550681304325802794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720675443145098882e+01,5.700227596200104472e+02,2.917509379526222468e-01,1.100000010988609489e+01,2.550535318924265077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720766352235099816e+01,5.700327595874842928e+02,2.917764432781584927e-01,1.100000010988609489e+01,2.550389333522727359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720857261325100751e+01,5.700427595549618900e+02,2.918019471438454415e-01,1.100000010988609489e+01,2.550243348121189642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.720948170415101686e+01,5.700527595224432389e+02,2.918274495496831489e-01,1.100000010988609489e+01,2.550097362719651924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721039079505102620e+01,5.700627594899282258e+02,2.918529504956715592e-01,1.100000010988609489e+01,2.549951377318114207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721129988595103555e+01,5.700727594574169643e+02,2.918784499818107281e-01,1.100000010988609489e+01,2.549805391916576489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721220897685104489e+01,5.700827594249094545e+02,2.919039480081005999e-01,1.100000010988609489e+01,2.549659406515038772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721311806775105424e+01,5.700927593924056964e+02,2.919294445745412303e-01,1.100000010988609489e+01,2.549513421113501054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721402715865106359e+01,5.701027593599055763e+02,2.919549396811325637e-01,1.100000010988609489e+01,2.549367435711963337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721493624955107293e+01,5.701127593274092078e+02,2.919804333278746555e-01,1.100000010988609489e+01,2.549221450310425619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721584534045108228e+01,5.701227592949165910e+02,2.920059255147674504e-01,1.100000010988609489e+01,2.549075464908887902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721675443135109163e+01,5.701327592624277258e+02,2.920314162418109483e-01,1.100000010988609489e+01,2.548929479507350184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721766352225110097e+01,5.701427592299424987e+02,2.920569055090052046e-01,1.100000010988609489e+01,2.548783494105812467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721857261315111032e+01,5.701527591974610232e+02,2.920823933163501640e-01,1.100000010988609489e+01,2.548637508704274749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.721948170405111966e+01,5.701627591649832993e+02,2.921078796638458819e-01,1.100000010988609489e+01,2.548491523302737032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722039079495112901e+01,5.701727591325093272e+02,2.921333645514923028e-01,1.100000010988609489e+01,2.548345537901199314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722129988585113836e+01,5.701827591000389930e+02,2.921588479792894821e-01,1.100000010988609489e+01,2.548199552499661596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722220897675114770e+01,5.701927590675724105e+02,2.921843299472373645e-01,1.100000010988609489e+01,2.548053567098123879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722311806765115705e+01,5.702027590351095796e+02,2.922098104553359499e-01,1.100000010988609489e+01,2.547907581696586161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722402715855116639e+01,5.702127590026503867e+02,2.922352895035852938e-01,1.100000010988609489e+01,2.547761596295048444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722493624945117574e+01,5.702227589701949455e+02,2.922607670919853406e-01,1.100000010988609489e+01,2.547615610893510726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722584534035118509e+01,5.702327589377432560e+02,2.922862432205360905e-01,1.100000010988609489e+01,2.547469625491973009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722675443125119443e+01,5.702427589052953181e+02,2.923117178892375989e-01,1.100000010988609489e+01,2.547323640090435291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722766352215120378e+01,5.702527588728510182e+02,2.923371910980898103e-01,1.100000010988609489e+01,2.547177654688897574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722857261305121312e+01,5.702627588404104699e+02,2.923626628470927247e-01,1.100000010988609489e+01,2.547031669287359856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.722948170395122247e+01,5.702727588079736734e+02,2.923881331362463976e-01,1.100000010988609489e+01,2.546885683885822139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723039079485123182e+01,5.702827587755405148e+02,2.924136019655507734e-01,1.100000010988609489e+01,2.546739698484284421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723129988575124116e+01,5.702927587431111078e+02,2.924390693350058523e-01,1.100000010988609489e+01,2.546593713082746704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723220897665125051e+01,5.703027587106854526e+02,2.924645352446116897e-01,1.100000010988609489e+01,2.546447727681208986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723311806755125986e+01,5.703127586782634353e+02,2.924899996943682301e-01,1.100000010988609489e+01,2.546301742279671269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723402715845126920e+01,5.703227586458451697e+02,2.925154626842754735e-01,1.100000010988609489e+01,2.546155756878133551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723493624935127855e+01,5.703327586134306557e+02,2.925409242143334199e-01,1.100000010988609489e+01,2.546009771476595834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723584534025128789e+01,5.703427585810198934e+02,2.925663842845421247e-01,1.100000010988609489e+01,2.545863786075058116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723675443115129724e+01,5.703527585486127691e+02,2.925918428949015326e-01,1.100000010988609489e+01,2.545717800673520399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723766352205130659e+01,5.703627585162093965e+02,2.926173000454116435e-01,1.100000010988609489e+01,2.545571815271982681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723857261295131593e+01,5.703727584838097755e+02,2.926427557360724574e-01,1.100000010988609489e+01,2.545425829870444964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.723948170385132528e+01,5.703827584514137925e+02,2.926682099668839743e-01,1.100000010988609489e+01,2.545279844468907246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724039079475133462e+01,5.703927584190215612e+02,2.926936627378462497e-01,1.100000010988609489e+01,2.545133859067369528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724129988565134397e+01,5.704027583866330815e+02,2.927191140489592280e-01,1.100000010988609489e+01,2.544987873665831811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724220897655135332e+01,5.704127583542482398e+02,2.927445639002229094e-01,1.100000010988609489e+01,2.544841888264294093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724311806745136266e+01,5.704227583218671498e+02,2.927700122916372938e-01,1.100000010988609489e+01,2.544695902862756376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724402715835137201e+01,5.704327582894898114e+02,2.927954592232023812e-01,1.100000010988609489e+01,2.544549917461218658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724493624925138135e+01,5.704427582571161111e+02,2.928209046949181715e-01,1.100000010988609489e+01,2.544403932059680941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724584534015139070e+01,5.704527582247461623e+02,2.928463487067847204e-01,1.100000010988609489e+01,2.544257946658143223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724675443105140005e+01,5.704627581923799653e+02,2.928717912588019723e-01,1.100000010988609489e+01,2.544111961256605506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724766352195140939e+01,5.704727581600174062e+02,2.928972323509699272e-01,1.100000010988609489e+01,2.543965975855067788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724857261285141874e+01,5.704827581276585988e+02,2.929226719832885850e-01,1.100000010988609489e+01,2.543819990453530071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.724948170375142809e+01,5.704927580953035431e+02,2.929481101557579459e-01,1.100000010988609489e+01,2.543674005051992353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725039079465143743e+01,5.705027580629521253e+02,2.929735468683780097e-01,1.100000010988609489e+01,2.543528019650454636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725129988555144678e+01,5.705127580306044592e+02,2.929989821211487766e-01,1.100000010988609489e+01,2.543382034248916918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725220897645145612e+01,5.705227579982605448e+02,2.930244159140702465e-01,1.100000010988609489e+01,2.543236048847379201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725311806735146547e+01,5.705327579659202684e+02,2.930498482471424193e-01,1.100000010988609489e+01,2.543090063445841483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725402715825147482e+01,5.705427579335837436e+02,2.930752791203652952e-01,1.100000010988609489e+01,2.542944078044303766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725493624915148416e+01,5.705527579012509705e+02,2.931007085337388740e-01,1.100000010988609489e+01,2.542798092642766048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725584534005149351e+01,5.705627578689218353e+02,2.931261364872631558e-01,1.100000010988609489e+01,2.542652107241228331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725675443095150285e+01,5.705727578365964519e+02,2.931515629809381407e-01,1.100000010988609489e+01,2.542506121839690613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725766352185151220e+01,5.705827578042748200e+02,2.931769880147638285e-01,1.100000010988609489e+01,2.542360136438152896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725857261275152155e+01,5.705927577719568262e+02,2.932024115887402194e-01,1.100000010988609489e+01,2.542214151036615178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.725948170365153089e+01,5.706027577396425841e+02,2.932278337028673132e-01,1.100000010988609489e+01,2.542068165635077460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726039079455154024e+01,5.706127577073320936e+02,2.932532543571451100e-01,1.100000010988609489e+01,2.541922180233539743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726129988545154959e+01,5.706227576750252410e+02,2.932786735515736098e-01,1.100000010988609489e+01,2.541776194832002025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726220897635155893e+01,5.706327576427221402e+02,2.933040912861528127e-01,1.100000010988609489e+01,2.541630209430464308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726311806725156828e+01,5.706427576104227910e+02,2.933295075608827185e-01,1.100000010988609489e+01,2.541484224028926590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726402715815157762e+01,5.706527575781270798e+02,2.933549223757633273e-01,1.100000010988609489e+01,2.541338238627388873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726493624905158697e+01,5.706627575458351203e+02,2.933803357307946391e-01,1.100000010988609489e+01,2.541192253225851155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726584533995159632e+01,5.706727575135467987e+02,2.934057476259766539e-01,1.100000010988609489e+01,2.541046267824313438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726675443085160566e+01,5.706827574812622288e+02,2.934311580613093717e-01,1.100000010988609489e+01,2.540900282422775720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726766352175161501e+01,5.706927574489814106e+02,2.934565670367927925e-01,1.100000010988609489e+01,2.540754297021238003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726857261265162435e+01,5.707027574167042303e+02,2.934819745524269163e-01,1.100000010988609489e+01,2.540608311619700285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.726948170355163370e+01,5.707127573844308017e+02,2.935073806082117431e-01,1.100000010988609489e+01,2.540462326218162568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727039079445164305e+01,5.707227573521611248e+02,2.935327852041472174e-01,1.100000010988609489e+01,2.540316340816624850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727129988535165239e+01,5.707327573198950859e+02,2.935581883402333947e-01,1.100000010988609489e+01,2.540170355415087133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727220897625166174e+01,5.707427572876327986e+02,2.935835900164702750e-01,1.100000010988609489e+01,2.540024370013549415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727311806715167108e+01,5.707527572553741493e+02,2.936089902328578582e-01,1.100000010988609489e+01,2.539878384612011698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727402715805168043e+01,5.707627572231192516e+02,2.936343889893961445e-01,1.100000010988609489e+01,2.539732399210473980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727493624895168978e+01,5.707727571908681057e+02,2.936597862860851338e-01,1.100000010988609489e+01,2.539586413808936263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727584533985169912e+01,5.707827571586205977e+02,2.936851821229247705e-01,1.100000010988609489e+01,2.539440428407398545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727675443075170847e+01,5.707927571263768414e+02,2.937105764999151103e-01,1.100000010988609489e+01,2.539294443005860828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727766352165171782e+01,5.708027570941367230e+02,2.937359694170561530e-01,1.100000010988609489e+01,2.539148457604323110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727857261255172716e+01,5.708127570619003563e+02,2.937613608743478988e-01,1.100000010988609489e+01,2.539002472202785392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.727948170345173651e+01,5.708227570296677413e+02,2.937867508717903475e-01,1.100000010988609489e+01,2.538856486801247675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728039079435174585e+01,5.708327569974387643e+02,2.938121394093834438e-01,1.100000010988609489e+01,2.538710501399709957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728129988525175520e+01,5.708427569652135389e+02,2.938375264871272430e-01,1.100000010988609489e+01,2.538564515998172240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728220897615176455e+01,5.708527569329919515e+02,2.938629121050217452e-01,1.100000010988609489e+01,2.538418530596634522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728311806705177389e+01,5.708627569007741158e+02,2.938882962630669504e-01,1.100000010988609489e+01,2.538272545195096805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728402715795178324e+01,5.708727568685600318e+02,2.939136789612628031e-01,1.100000010988609489e+01,2.538126559793559087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728493624885179258e+01,5.708827568363495857e+02,2.939390601996093588e-01,1.100000010988609489e+01,2.537980574392021370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728584533975180193e+01,5.708927568041428913e+02,2.939644399781066175e-01,1.100000010988609489e+01,2.537834588990483652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728675443065181128e+01,5.709027567719398348e+02,2.939898182967545237e-01,1.100000010988609489e+01,2.537688603588945935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728766352155182062e+01,5.709127567397405301e+02,2.940151951555531329e-01,1.100000010988609489e+01,2.537542618187408217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728857261245182997e+01,5.709227567075449770e+02,2.940405705545024451e-01,1.100000010988609489e+01,2.537396632785870500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.728948170335183931e+01,5.709327566753530618e+02,2.940659444936024602e-01,1.100000010988609489e+01,2.537250647384332782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729039079425184866e+01,5.709427566431648984e+02,2.940913169728531229e-01,1.100000010988609489e+01,2.537104661982795065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729129988515185801e+01,5.709527566109803729e+02,2.941166879922544886e-01,1.100000010988609489e+01,2.536958676581257347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729220897605186735e+01,5.709627565787995991e+02,2.941420575518065017e-01,1.100000010988609489e+01,2.536812691179719630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729311806695187670e+01,5.709727565466225769e+02,2.941674256515092178e-01,1.100000010988609489e+01,2.536666705778181912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729402715785188605e+01,5.709827565144491928e+02,2.941927922913626370e-01,1.100000010988609489e+01,2.536520720376644195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729493624875189539e+01,5.709927564822795603e+02,2.942181574713667036e-01,1.100000010988609489e+01,2.536374734975106477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729584533965190474e+01,5.710027564501135657e+02,2.942435211915214732e-01,1.100000010988609489e+01,2.536228749573568760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729675443055191408e+01,5.710127564179513229e+02,2.942688834518268903e-01,1.100000010988609489e+01,2.536082764172031042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729766352145192343e+01,5.710227563857927180e+02,2.942942442522830104e-01,1.100000010988609489e+01,2.535936778770493324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729857261235193278e+01,5.710327563536378648e+02,2.943196035928898335e-01,1.100000010988609489e+01,2.535790793368955607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.729948170325194212e+01,5.710427563214867632e+02,2.943449614736473041e-01,1.100000010988609489e+01,2.535644807967417889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730039079415195147e+01,5.710527562893392997e+02,2.943703178945554777e-01,1.100000010988609489e+01,2.535498822565880172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730129988505196081e+01,5.710627562571955878e+02,2.943956728556142988e-01,1.100000010988609489e+01,2.535352837164342454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730220897595197016e+01,5.710727562250555138e+02,2.944210263568238228e-01,1.100000010988609489e+01,2.535206851762804737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730311806685197951e+01,5.710827561929191916e+02,2.944463783981839944e-01,1.100000010988609489e+01,2.535060866361267019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730402715775198885e+01,5.710927561607865073e+02,2.944717289796948689e-01,1.100000010988609489e+01,2.534914880959729302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730493624865199820e+01,5.711027561286575747e+02,2.944970781013563910e-01,1.100000010988609489e+01,2.534768895558191584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730584533955200754e+01,5.711127560965322800e+02,2.945224257631686160e-01,1.100000010988609489e+01,2.534622910156653867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730675443045201689e+01,5.711227560644107371e+02,2.945477719651314885e-01,1.100000010988609489e+01,2.534476924755116149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730766352135202624e+01,5.711327560322928321e+02,2.945731167072450640e-01,1.100000010988609489e+01,2.534330939353578432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730857261225203558e+01,5.711427560001786787e+02,2.945984599895092870e-01,1.100000010988609489e+01,2.534184953952040714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.730948170315204493e+01,5.711527559680682771e+02,2.946238018119242130e-01,1.100000010988609489e+01,2.534038968550502997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731039079405205428e+01,5.711627559359615134e+02,2.946491421744897865e-01,1.100000010988609489e+01,2.533892983148965279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731129988495206362e+01,5.711727559038585014e+02,2.946744810772060630e-01,1.100000010988609489e+01,2.533746997747427562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731220897585207297e+01,5.711827558717591273e+02,2.946998185200729869e-01,1.100000010988609489e+01,2.533601012345889844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731311806675208231e+01,5.711927558396635050e+02,2.947251545030905584e-01,1.100000010988609489e+01,2.533455026944352127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731402715765209166e+01,5.712027558075715206e+02,2.947504890262588328e-01,1.100000010988609489e+01,2.533309041542814409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731493624855210101e+01,5.712127557754832878e+02,2.947758220895777548e-01,1.100000010988609489e+01,2.533163056141276692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731584533945211035e+01,5.712227557433986931e+02,2.948011536930473797e-01,1.100000010988609489e+01,2.533017070739738974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731675443035211970e+01,5.712327557113178500e+02,2.948264838366676521e-01,1.100000010988609489e+01,2.532871085338201256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731766352125212904e+01,5.712427556792406449e+02,2.948518125204385720e-01,1.100000010988609489e+01,2.532725099936663539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731857261215213839e+01,5.712527556471671915e+02,2.948771397443601949e-01,1.100000010988609489e+01,2.532579114535125821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.731948170305214774e+01,5.712627556150973760e+02,2.949024655084324653e-01,1.100000010988609489e+01,2.532433129133588104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732039079395215708e+01,5.712727555830313122e+02,2.949277898126553832e-01,1.100000010988609489e+01,2.532287143732050386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732129988485216643e+01,5.712827555509688864e+02,2.949531126570290041e-01,1.100000010988609489e+01,2.532141158330512669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732220897575217577e+01,5.712927555189102122e+02,2.949784340415532724e-01,1.100000010988609489e+01,2.531995172928974951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732311806665218512e+01,5.713027554868551761e+02,2.950037539662281882e-01,1.100000010988609489e+01,2.531849187527437234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732402715755219447e+01,5.713127554548038916e+02,2.950290724310538071e-01,1.100000010988609489e+01,2.531703202125899516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732493624845220381e+01,5.713227554227563587e+02,2.950543894360300734e-01,1.100000010988609489e+01,2.531557216724361799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732584533935221316e+01,5.713327553907124638e+02,2.950797049811569872e-01,1.100000010988609489e+01,2.531411231322824081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732675443025222251e+01,5.713427553586723207e+02,2.951050190664345485e-01,1.100000010988609489e+01,2.531265245921286364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732766352115223185e+01,5.713527553266358154e+02,2.951303316918628128e-01,1.100000010988609489e+01,2.531119260519748646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732857261205224120e+01,5.713627552946030619e+02,2.951556428574417246e-01,1.100000010988609489e+01,2.530973275118210929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.732948170295225054e+01,5.713727552625739463e+02,2.951809525631712838e-01,1.100000010988609489e+01,2.530827289716673211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733039079385225989e+01,5.713827552305485824e+02,2.952062608090514906e-01,1.100000010988609489e+01,2.530681304315135494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733129988475226924e+01,5.713927551985268565e+02,2.952315675950824003e-01,1.100000010988609489e+01,2.530535318913597776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733220897565227858e+01,5.714027551665088822e+02,2.952568729212639576e-01,1.100000010988609489e+01,2.530389333512060059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733311806655228793e+01,5.714127551344945459e+02,2.952821767875961623e-01,1.100000010988609489e+01,2.530243348110522341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733402715745229727e+01,5.714227551024839613e+02,2.953074791940790145e-01,1.100000010988609489e+01,2.530097362708984624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733493624835230662e+01,5.714327550704770147e+02,2.953327801407125142e-01,1.100000010988609489e+01,2.529951377307446906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733584533925231597e+01,5.714427550384737060e+02,2.953580796274967168e-01,1.100000010988609489e+01,2.529805391905909188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733675443015232531e+01,5.714527550064741490e+02,2.953833776544315670e-01,1.100000010988609489e+01,2.529659406504371471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733766352105233466e+01,5.714627549744782300e+02,2.954086742215170647e-01,1.100000010988609489e+01,2.529513421102833753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733857261195234400e+01,5.714727549424860626e+02,2.954339693287532098e-01,1.100000010988609489e+01,2.529367435701296036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.733948170285235335e+01,5.714827549104975333e+02,2.954592629761400024e-01,1.100000010988609489e+01,2.529221450299758318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734039079375236270e+01,5.714927548785127556e+02,2.954845551636774426e-01,1.100000010988609489e+01,2.529075464898220601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734129988465237204e+01,5.715027548465316158e+02,2.955098458913655302e-01,1.100000010988609489e+01,2.528929479496682883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734220897555238139e+01,5.715127548145542278e+02,2.955351351592042652e-01,1.100000010988609489e+01,2.528783494095145166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734311806645239074e+01,5.715227547825804777e+02,2.955604229671937033e-01,1.100000010988609489e+01,2.528637508693607448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734402715735240008e+01,5.715327547506104793e+02,2.955857093153337889e-01,1.100000010988609489e+01,2.528491523292069731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734493624825240943e+01,5.715427547186441188e+02,2.956109942036245219e-01,1.100000010988609489e+01,2.528345537890532013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734584533915241877e+01,5.715527546866815101e+02,2.956362776320659025e-01,1.100000010988609489e+01,2.528199552488994296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734675443005242812e+01,5.715627546547225393e+02,2.956615596006579305e-01,1.100000010988609489e+01,2.528053567087456578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734766352095243747e+01,5.715727546227673201e+02,2.956868401094006060e-01,1.100000010988609489e+01,2.527907581685918861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734857261185244681e+01,5.715827545908157390e+02,2.957121191582939290e-01,1.100000010988609489e+01,2.527761596284381143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.734948170275245616e+01,5.715927545588679095e+02,2.957373967473378995e-01,1.100000010988609489e+01,2.527615610882843426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735039079365246550e+01,5.716027545269237180e+02,2.957626728765325175e-01,1.100000010988609489e+01,2.527469625481305708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735129988455247485e+01,5.716127544949832782e+02,2.957879475458777829e-01,1.100000010988609489e+01,2.527323640079767991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735220897545248420e+01,5.716227544630464763e+02,2.958132207553736959e-01,1.100000010988609489e+01,2.527177654678230273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735311806635249354e+01,5.716327544311133124e+02,2.958384925050202563e-01,1.100000010988609489e+01,2.527031669276692556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735402715725250289e+01,5.716427543991839002e+02,2.958637627948174642e-01,1.100000010988609489e+01,2.526885683875154838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735493624815251223e+01,5.716527543672581260e+02,2.958890316247653196e-01,1.100000010988609489e+01,2.526739698473617120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735584533905252158e+01,5.716627543353361034e+02,2.959142989948638225e-01,1.100000010988609489e+01,2.526593713072079403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735675442995253093e+01,5.716727543034177188e+02,2.959395649051129729e-01,1.100000010988609489e+01,2.526447727670541685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735766352085254027e+01,5.716827542715030859e+02,2.959648293555127707e-01,1.100000010988609489e+01,2.526301742269003968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735857261175254962e+01,5.716927542395920909e+02,2.959900923460632161e-01,1.100000010988609489e+01,2.526155756867466250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.735948170265255897e+01,5.717027542076848476e+02,2.960153538767643089e-01,1.100000010988609489e+01,2.526009771465928533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736039079355256831e+01,5.717127541757812423e+02,2.960406139476159937e-01,1.100000010988609489e+01,2.525863786064390815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736129988445257766e+01,5.717227541438812750e+02,2.960658725586183260e-01,1.100000010988609489e+01,2.525717800662853098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736220897535258700e+01,5.717327541119850594e+02,2.960911297097713057e-01,1.100000010988609489e+01,2.525571815261315380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736311806625259635e+01,5.717427540800924817e+02,2.961163854010749330e-01,1.100000010988609489e+01,2.525425829859777663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736402715715260570e+01,5.717527540482036557e+02,2.961416396325292077e-01,1.100000010988609489e+01,2.525279844458239945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736493624805261504e+01,5.717627540163184676e+02,2.961668924041341300e-01,1.100000010988609489e+01,2.525133859056702228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736584533895262439e+01,5.717727539844370312e+02,2.961921437158896997e-01,1.100000010988609489e+01,2.524987873655164510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736675442985263373e+01,5.717827539525592329e+02,2.962173935677959169e-01,1.100000010988609489e+01,2.524841888253626793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736766352075264308e+01,5.717927539206850724e+02,2.962426419598527261e-01,1.100000010988609489e+01,2.524695902852089075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736857261165265243e+01,5.718027538888146637e+02,2.962678888920601827e-01,1.100000010988609489e+01,2.524549917450551358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.736948170255266177e+01,5.718127538569478929e+02,2.962931343644182869e-01,1.100000010988609489e+01,2.524403932049013640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737039079345267112e+01,5.718227538250848738e+02,2.963183783769270385e-01,1.100000010988609489e+01,2.524257946647475923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737129988435268046e+01,5.718327537932254927e+02,2.963436209295864376e-01,1.100000010988609489e+01,2.524111961245938205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737220897525268981e+01,5.718427537613697496e+02,2.963688620223964287e-01,1.100000010988609489e+01,2.523965975844400488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737311806615269916e+01,5.718527537295177581e+02,2.963941016553570673e-01,1.100000010988609489e+01,2.523819990442862770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737402715705270850e+01,5.718627536976694046e+02,2.964193398284683534e-01,1.100000010988609489e+01,2.523674005041325052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737493624795271785e+01,5.718727536658248027e+02,2.964445765417302869e-01,1.100000010988609489e+01,2.523528019639787335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737584533885272720e+01,5.718827536339838389e+02,2.964698117951428125e-01,1.100000010988609489e+01,2.523382034238249617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737675442975273654e+01,5.718927536021466267e+02,2.964950455887059855e-01,1.100000010988609489e+01,2.523236048836711900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737766352065274589e+01,5.719027535703130525e+02,2.965202779224198060e-01,1.100000010988609489e+01,2.523090063435174182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737857261155275523e+01,5.719127535384831162e+02,2.965455087962842740e-01,1.100000010988609489e+01,2.522944078033636465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.737948170245276458e+01,5.719227535066569317e+02,2.965707382102993339e-01,1.100000010988609489e+01,2.522798092632098747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738039079335277393e+01,5.719327534748343851e+02,2.965959661644650414e-01,1.100000010988609489e+01,2.522652107230561030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738129988425278327e+01,5.719427534430155902e+02,2.966211926587813963e-01,1.100000010988609489e+01,2.522506121829023312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738220897515279262e+01,5.719527534112004332e+02,2.966464176932483432e-01,1.100000010988609489e+01,2.522360136427485595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738311806605280196e+01,5.719627533793889143e+02,2.966716412678659376e-01,1.100000010988609489e+01,2.522214151025947877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738402715695281131e+01,5.719727533475811470e+02,2.966968633826341795e-01,1.100000010988609489e+01,2.522068165624410160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738493624785282066e+01,5.719827533157770176e+02,2.967220840375530133e-01,1.100000010988609489e+01,2.521922180222872442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738584533875283000e+01,5.719927532839765263e+02,2.967473032326224947e-01,1.100000010988609489e+01,2.521776194821334725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738675442965283935e+01,5.720027532521797866e+02,2.967725209678426235e-01,1.100000010988609489e+01,2.521630209419797007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738766352055284869e+01,5.720127532203866849e+02,2.967977372432133443e-01,1.100000010988609489e+01,2.521484224018259290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738857261145285804e+01,5.720227531885973349e+02,2.968229520587347126e-01,1.100000010988609489e+01,2.521338238616721572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.738948170235286739e+01,5.720327531568116228e+02,2.968481654144066728e-01,1.100000010988609489e+01,2.521192253215183855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739039079325287673e+01,5.720427531250295488e+02,2.968733773102292806e-01,1.100000010988609489e+01,2.521046267813646137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739129988415288608e+01,5.720527530932512263e+02,2.968985877462025358e-01,1.100000010988609489e+01,2.520900282412108419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739220897505289543e+01,5.720627530614765419e+02,2.969237967223263830e-01,1.100000010988609489e+01,2.520754297010570702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739311806595290477e+01,5.720727530297054955e+02,2.969490042386008777e-01,1.100000010988609489e+01,2.520608311609032984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739402715685291412e+01,5.720827529979382007e+02,2.969742102950259643e-01,1.100000010988609489e+01,2.520462326207495267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739493624775292346e+01,5.720927529661745439e+02,2.969994148916016985e-01,1.100000010988609489e+01,2.520316340805957549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739584533865293281e+01,5.721027529344146387e+02,2.970246180283280246e-01,1.100000010988609489e+01,2.520170355404419832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739675442955294216e+01,5.721127529026583716e+02,2.970498197052049982e-01,1.100000010988609489e+01,2.520024370002882114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739766352045295150e+01,5.721227528709057424e+02,2.970750199222325638e-01,1.100000010988609489e+01,2.519878384601344397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739857261135296085e+01,5.721327528391568649e+02,2.971002186794107769e-01,1.100000010988609489e+01,2.519732399199806679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.739948170225297019e+01,5.721427528074116253e+02,2.971254159767395819e-01,1.100000010988609489e+01,2.519586413798268962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740039079315297954e+01,5.721527527756700238e+02,2.971506118142190345e-01,1.100000010988609489e+01,2.519440428396731244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740129988405298889e+01,5.721627527439321739e+02,2.971758061918490790e-01,1.100000010988609489e+01,2.519294442995193527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740220897495299823e+01,5.721727527121979620e+02,2.972009991096297710e-01,1.100000010988609489e+01,2.519148457593655809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740311806585300758e+01,5.721827526804673880e+02,2.972261905675610549e-01,1.100000010988609489e+01,2.519002472192118092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740402715675301692e+01,5.721927526487405657e+02,2.972513805656429864e-01,1.100000010988609489e+01,2.518856486790580374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740493624765302627e+01,5.722027526170173815e+02,2.972765691038755098e-01,1.100000010988609489e+01,2.518710501389042657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740584533855303562e+01,5.722127525852978351e+02,2.973017561822586252e-01,1.100000010988609489e+01,2.518564515987504939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740675442945304496e+01,5.722227525535820405e+02,2.973269418007923881e-01,1.100000010988609489e+01,2.518418530585967222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740766352035305431e+01,5.722327525218698838e+02,2.973521259594767430e-01,1.100000010988609489e+01,2.518272545184429504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740857261125306366e+01,5.722427524901613651e+02,2.973773086583117453e-01,1.100000010988609489e+01,2.518126559782891787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.740948170215307300e+01,5.722527524584565981e+02,2.974024898972973396e-01,1.100000010988609489e+01,2.517980574381354069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741039079305308235e+01,5.722627524267554691e+02,2.974276696764335259e-01,1.100000010988609489e+01,2.517834588979816351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741129988395309169e+01,5.722727523950579780e+02,2.974528479957203597e-01,1.100000010988609489e+01,2.517688603578278634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741220897485310104e+01,5.722827523633642386e+02,2.974780248551577855e-01,1.100000010988609489e+01,2.517542618176740916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741311806575311039e+01,5.722927523316741372e+02,2.975032002547458587e-01,1.100000010988609489e+01,2.517396632775203199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741402715665311973e+01,5.723027522999876737e+02,2.975283741944845239e-01,1.100000010988609489e+01,2.517250647373665481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741493624755312908e+01,5.723127522683049619e+02,2.975535466743737811e-01,1.100000010988609489e+01,2.517104661972127764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741584533845313842e+01,5.723227522366258881e+02,2.975787176944136303e-01,1.100000010988609489e+01,2.516958676570590046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741675442935314777e+01,5.723327522049504523e+02,2.976038872546041270e-01,1.100000010988609489e+01,2.516812691169052329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741766352025315712e+01,5.723427521732787682e+02,2.976290553549452156e-01,1.100000010988609489e+01,2.516666705767514611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741857261115316646e+01,5.723527521416107220e+02,2.976542219954368962e-01,1.100000010988609489e+01,2.516520720365976894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.741948170205317581e+01,5.723627521099463138e+02,2.976793871760792243e-01,1.100000010988609489e+01,2.516374734964439176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742039079295318516e+01,5.723727520782856573e+02,2.977045508968721443e-01,1.100000010988609489e+01,2.516228749562901459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742129988385319450e+01,5.723827520466286387e+02,2.977297131578156564e-01,1.100000010988609489e+01,2.516082764161363741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742220897475320385e+01,5.723927520149752581e+02,2.977548739589097604e-01,1.100000010988609489e+01,2.515936778759826024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742311806565321319e+01,5.724027519833256292e+02,2.977800333001545119e-01,1.100000010988609489e+01,2.515790793358288306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742402715655322254e+01,5.724127519516796383e+02,2.978051911815498554e-01,1.100000010988609489e+01,2.515644807956750589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742493624745323189e+01,5.724227519200372853e+02,2.978303476030957908e-01,1.100000010988609489e+01,2.515498822555212871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742584533835324123e+01,5.724327518883986841e+02,2.978555025647923182e-01,1.100000010988609489e+01,2.515352837153675154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742675442925325058e+01,5.724427518567637208e+02,2.978806560666394931e-01,1.100000010988609489e+01,2.515206851752137436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742766352015325992e+01,5.724527518251323954e+02,2.979058081086372600e-01,1.100000010988609489e+01,2.515060866350599719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742857261105326927e+01,5.724627517935047081e+02,2.979309586907856189e-01,1.100000010988609489e+01,2.514914880949062001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.742948170195327862e+01,5.724727517618807724e+02,2.979561078130845697e-01,1.100000010988609489e+01,2.514768895547524283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743039079285328796e+01,5.724827517302604747e+02,2.979812554755341125e-01,1.100000010988609489e+01,2.514622910145986566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743129988375329731e+01,5.724927516986438150e+02,2.980064016781342473e-01,1.100000010988609489e+01,2.514476924744448848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743220897465330665e+01,5.725027516670309069e+02,2.980315464208850296e-01,1.100000010988609489e+01,2.514330939342911131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743311806555331600e+01,5.725127516354216368e+02,2.980566897037864038e-01,1.100000010988609489e+01,2.514184953941373413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743402715645332535e+01,5.725227516038160047e+02,2.980818315268383700e-01,1.100000010988609489e+01,2.514038968539835696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743493624735333469e+01,5.725327515722140106e+02,2.981069718900409282e-01,1.100000010988609489e+01,2.513892983138297978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743584533825334404e+01,5.725427515406157681e+02,2.981321107933940784e-01,1.100000010988609489e+01,2.513746997736760261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743675442915335339e+01,5.725527515090211637e+02,2.981572482368978205e-01,1.100000010988609489e+01,2.513601012335222543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743766352005336273e+01,5.725627514774301972e+02,2.981823842205521546e-01,1.100000010988609489e+01,2.513455026933684826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743857261095337208e+01,5.725727514458429823e+02,2.982075187443570807e-01,1.100000010988609489e+01,2.513309041532147108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.743948170185338142e+01,5.725827514142594055e+02,2.982326518083125988e-01,1.100000010988609489e+01,2.513163056130609391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744039079275339077e+01,5.725927513826794666e+02,2.982577834124187088e-01,1.100000010988609489e+01,2.513017070729071673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744129988365340012e+01,5.726027513511031657e+02,2.982829135566754108e-01,1.100000010988609489e+01,2.512871085327533956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744220897455340946e+01,5.726127513195306165e+02,2.983080422410827048e-01,1.100000010988609489e+01,2.512725099925996238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744311806545341881e+01,5.726227512879617052e+02,2.983331694656406463e-01,1.100000010988609489e+01,2.512579114524458521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744402715635342815e+01,5.726327512563964319e+02,2.983582952303491798e-01,1.100000010988609489e+01,2.512433129122920803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744493624725343750e+01,5.726427512248347966e+02,2.983834195352083052e-01,1.100000010988609489e+01,2.512287143721383086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744584533815344685e+01,5.726527511932769130e+02,2.984085423802180226e-01,1.100000010988609489e+01,2.512141158319845368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744675442905345619e+01,5.726627511617226673e+02,2.984336637653783320e-01,1.100000010988609489e+01,2.511995172918307651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744766351995346554e+01,5.726727511301720597e+02,2.984587836906892333e-01,1.100000010988609489e+01,2.511849187516769933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744857261085347488e+01,5.726827510986250900e+02,2.984839021561506711e-01,1.100000010988609489e+01,2.511703202115232215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.744948170175348423e+01,5.726927510670818720e+02,2.985090191617627009e-01,1.100000010988609489e+01,2.511557216713694498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745039079265349358e+01,5.727027510355422919e+02,2.985341347075253227e-01,1.100000010988609489e+01,2.511411231312156780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745129988355350292e+01,5.727127510040063498e+02,2.985592487934385364e-01,1.100000010988609489e+01,2.511265245910619063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745220897445351227e+01,5.727227509724740457e+02,2.985843614195023421e-01,1.100000010988609489e+01,2.511119260509081345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745311806535352162e+01,5.727327509409454933e+02,2.986094725857167398e-01,1.100000010988609489e+01,2.510973275107543628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745402715625353096e+01,5.727427509094205789e+02,2.986345822920817294e-01,1.100000010988609489e+01,2.510827289706005910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745493624715354031e+01,5.727527508778993024e+02,2.986596905385973111e-01,1.100000010988609489e+01,2.510681304304468193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745584533805354965e+01,5.727627508463816639e+02,2.986847973252634847e-01,1.100000010988609489e+01,2.510535318902930475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745675442895355900e+01,5.727727508148677771e+02,2.987099026520802503e-01,1.100000010988609489e+01,2.510389333501392758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745766351985356835e+01,5.727827507833575282e+02,2.987350065190476078e-01,1.100000010988609489e+01,2.510243348099855040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745857261075357769e+01,5.727927507518509174e+02,2.987601089261655574e-01,1.100000010988609489e+01,2.510097362698317323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.745948170165358704e+01,5.728027507203479445e+02,2.987852098734340434e-01,1.100000010988609489e+01,2.509951377296779605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746039079255359638e+01,5.728127506888487233e+02,2.988103093608531213e-01,1.100000010988609489e+01,2.509805391895241888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746129988345360573e+01,5.728227506573531400e+02,2.988354073884227913e-01,1.100000010988609489e+01,2.509659406493704170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746220897435361508e+01,5.728327506258611947e+02,2.988605039561430532e-01,1.100000010988609489e+01,2.509513421092166453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746311806525362442e+01,5.728427505943728875e+02,2.988855990640139071e-01,1.100000010988609489e+01,2.509367435690628735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746402715615363377e+01,5.728527505628883318e+02,2.989106927120352974e-01,1.100000010988609489e+01,2.509221450289091018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746493624705364311e+01,5.728627505314074142e+02,2.989357849002072798e-01,1.100000010988609489e+01,2.509075464887553300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746584533795365246e+01,5.728727504999301345e+02,2.989608756285298541e-01,1.100000010988609489e+01,2.508929479486015583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746675442885366181e+01,5.728827504684564929e+02,2.989859648970030204e-01,1.100000010988609489e+01,2.508783494084477865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746766351975367115e+01,5.728927504369864891e+02,2.990110527056267786e-01,1.100000010988609489e+01,2.508637508682940147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746857261065368050e+01,5.729027504055202371e+02,2.990361390544010733e-01,1.100000010988609489e+01,2.508491523281402430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.746948170155368985e+01,5.729127503740576230e+02,2.990612239433259600e-01,1.100000010988609489e+01,2.508345537879864712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747039079245369919e+01,5.729227503425986470e+02,2.990863073724014387e-01,1.100000010988609489e+01,2.508199552478326995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747129988335370854e+01,5.729327503111433089e+02,2.991113893416275094e-01,1.100000010988609489e+01,2.508053567076789277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747220897425371788e+01,5.729427502796916087e+02,2.991364698510041165e-01,1.100000010988609489e+01,2.507907581675251560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747311806515372723e+01,5.729527502482436603e+02,2.991615489005313155e-01,1.100000010988609489e+01,2.507761596273713842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747402715605373658e+01,5.729627502167993498e+02,2.991866264902091066e-01,1.100000010988609489e+01,2.507615610872176125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747493624695374592e+01,5.729727501853586773e+02,2.992117026200374341e-01,1.100000010988609489e+01,2.507469625470638407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747584533785375527e+01,5.729827501539216428e+02,2.992367772900163536e-01,1.100000010988609489e+01,2.507323640069100690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747675442875376461e+01,5.729927501224882462e+02,2.992618505001458651e-01,1.100000010988609489e+01,2.507177654667562972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747766351965377396e+01,5.730027500910586014e+02,2.992869222504259130e-01,1.100000010988609489e+01,2.507031669266025255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747857261055378331e+01,5.730127500596325945e+02,2.993119925408565529e-01,1.100000010988609489e+01,2.506885683864487537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.747948170145379265e+01,5.730227500282102255e+02,2.993370613714377848e-01,1.100000010988609489e+01,2.506739698462949820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748039079235380200e+01,5.730327499967914946e+02,2.993621287421695532e-01,1.100000010988609489e+01,2.506593713061412102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748129988325381134e+01,5.730427499653764016e+02,2.993871946530519135e-01,1.100000010988609489e+01,2.506447727659874385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748220897415382069e+01,5.730527499339650603e+02,2.994122591040848658e-01,1.100000010988609489e+01,2.506301742258336667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748311806505383004e+01,5.730627499025573570e+02,2.994373220952683545e-01,1.100000010988609489e+01,2.506155756856798950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748402715595383938e+01,5.730727498711532917e+02,2.994623836266024353e-01,1.100000010988609489e+01,2.506009771455261232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748493624685384873e+01,5.730827498397528643e+02,2.994874436980870525e-01,1.100000010988609489e+01,2.505863786053723515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748584533775385808e+01,5.730927498083560749e+02,2.995125023097222616e-01,1.100000010988609489e+01,2.505717800652185797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748675442865386742e+01,5.731027497769630372e+02,2.995375594615080073e-01,1.100000010988609489e+01,2.505571815250648079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748766351955387677e+01,5.731127497455736375e+02,2.995626151534443449e-01,1.100000010988609489e+01,2.505425829849110362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748857261045388611e+01,5.731227497141878757e+02,2.995876693855312745e-01,1.100000010988609489e+01,2.505279844447572644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.748948170135389546e+01,5.731327496828057519e+02,2.996127221577687405e-01,1.100000010988609489e+01,2.505133859046034927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749039079225390481e+01,5.731427496514272661e+02,2.996377734701567985e-01,1.100000010988609489e+01,2.504987873644497209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749129988315391415e+01,5.731527496200524183e+02,2.996628233226953930e-01,1.100000010988609489e+01,2.504841888242959492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749220897405392350e+01,5.731627495886813222e+02,2.996878717153845795e-01,1.100000010988609489e+01,2.504695902841421774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749311806495393284e+01,5.731727495573138640e+02,2.997129186482243024e-01,1.100000010988609489e+01,2.504549917439884057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749402715585394219e+01,5.731827495259500438e+02,2.997379641212146173e-01,1.100000010988609489e+01,2.504403932038346339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749493624675395154e+01,5.731927494945898616e+02,2.997630081343554687e-01,1.100000010988609489e+01,2.504257946636808622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749584533765396088e+01,5.732027494632333173e+02,2.997880506876469120e-01,1.100000010988609489e+01,2.504111961235270904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749675442855397023e+01,5.732127494318804111e+02,2.998130917810888918e-01,1.100000010988609489e+01,2.503965975833733187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749766351945397957e+01,5.732227494005311428e+02,2.998381314146814636e-01,1.100000010988609489e+01,2.503819990432195469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749857261035398892e+01,5.732327493691856262e+02,2.998631695884245718e-01,1.100000010988609489e+01,2.503674005030657752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.749948170125399827e+01,5.732427493378437475e+02,2.998882063023182165e-01,1.100000010988609489e+01,2.503528019629120034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750039079215400761e+01,5.732527493065055069e+02,2.999132415563624532e-01,1.100000010988609489e+01,2.503382034227582317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750129988305401696e+01,5.732627492751709042e+02,2.999382753505572263e-01,1.100000010988609489e+01,2.503236048826044599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750220897395402631e+01,5.732727492438399395e+02,2.999633076849025914e-01,1.100000010988609489e+01,2.503090063424506882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750311806485403565e+01,5.732827492125126128e+02,2.999883385593984930e-01,1.100000010988609489e+01,2.502944078022969164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750402715575404500e+01,5.732927491811890377e+02,3.000133679740449311e-01,1.100000010988609489e+01,2.502798092621431447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750493624665405434e+01,5.733027491498691006e+02,3.000383959288419611e-01,1.100000010988609489e+01,2.502652107219893729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750584533755406369e+01,5.733127491185528015e+02,3.000634224237895276e-01,1.100000010988609489e+01,2.502506121818356011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750675442845407304e+01,5.733227490872401404e+02,3.000884474588876305e-01,1.100000010988609489e+01,2.502360136416818294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750766351935408238e+01,5.733327490559311173e+02,3.001134710341363254e-01,1.100000010988609489e+01,2.502214151015280576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750857261025409173e+01,5.733427490246257321e+02,3.001384931495355568e-01,1.100000010988609489e+01,2.502068165613742859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.750948170115410107e+01,5.733527489933239849e+02,3.001635138050853246e-01,1.100000010988609489e+01,2.501922180212205141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751039079205411042e+01,5.733627489620258757e+02,3.001885330007856845e-01,1.100000010988609489e+01,2.501776194810667424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751129988295411977e+01,5.733727489307315182e+02,3.002135507366365808e-01,1.100000010988609489e+01,2.501630209409129706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751220897385412911e+01,5.733827488994407986e+02,3.002385670126380135e-01,1.100000010988609489e+01,2.501484224007591989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751311806475413846e+01,5.733927488681537170e+02,3.002635818287900382e-01,1.100000010988609489e+01,2.501338238606054271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751402715565414780e+01,5.734027488368702734e+02,3.002885951850925994e-01,1.100000010988609489e+01,2.501192253204516554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751493624655415715e+01,5.734127488055904678e+02,3.003136070815456971e-01,1.100000010988609489e+01,2.501046267802978836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751584533745416650e+01,5.734227487743143001e+02,3.003386175181493312e-01,1.100000010988609489e+01,2.500900282401441119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751675442835417584e+01,5.734327487430417705e+02,3.003636264949035573e-01,1.100000010988609489e+01,2.500754296999903401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751766351925418519e+01,5.734427487117728788e+02,3.003886340118083198e-01,1.100000010988609489e+01,2.500608311598365684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751857261015419454e+01,5.734527486805077388e+02,3.004136400688636188e-01,1.100000010988609489e+01,2.500462326196827966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.751948170105420388e+01,5.734627486492462367e+02,3.004386446660694543e-01,1.100000010988609489e+01,2.500316340795290249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752039079195421323e+01,5.734727486179883726e+02,3.004636478034258817e-01,1.100000010988609489e+01,2.500170355393752531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752129988285422257e+01,5.734827485867341466e+02,3.004886494809328457e-01,1.100000010988609489e+01,2.500024369992214814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752220897375423192e+01,5.734927485554835584e+02,3.005136496985903460e-01,1.100000010988609489e+01,2.499878384590677096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752311806465424127e+01,5.735027485242366083e+02,3.005386484563983829e-01,1.100000010988609489e+01,2.499732399189139379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752402715555425061e+01,5.735127484929932962e+02,3.005636457543569562e-01,1.100000010988609489e+01,2.499586413787601661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752493624645425996e+01,5.735227484617536220e+02,3.005886415924661215e-01,1.100000010988609489e+01,2.499440428386063943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752584533735426930e+01,5.735327484305175858e+02,3.006136359707258232e-01,1.100000010988609489e+01,2.499294442984526226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752675442825427865e+01,5.735427483992851876e+02,3.006386288891360614e-01,1.100000010988609489e+01,2.499148457582988508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752766351915428800e+01,5.735527483680565410e+02,3.006636203476968361e-01,1.100000010988609489e+01,2.499002472181450791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752857261005429734e+01,5.735627483368315325e+02,3.006886103464081472e-01,1.100000010988609489e+01,2.498856486779913073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.752948170095430669e+01,5.735727483056101619e+02,3.007135988852699948e-01,1.100000010988609489e+01,2.498710501378375356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753039079185431603e+01,5.735827482743924293e+02,3.007385859642823789e-01,1.100000010988609489e+01,2.498564515976837638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753129988275432538e+01,5.735927482431783346e+02,3.007635715834452994e-01,1.100000010988609489e+01,2.498418530575299921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753220897365433473e+01,5.736027482119678780e+02,3.007885557427587564e-01,1.100000010988609489e+01,2.498272545173762203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753311806455434407e+01,5.736127481807610593e+02,3.008135384422228054e-01,1.100000010988609489e+01,2.498126559772224486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753402715545435342e+01,5.736227481495578786e+02,3.008385196818373908e-01,1.100000010988609489e+01,2.497980574370686768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753493624635436277e+01,5.736327481183583359e+02,3.008634994616025127e-01,1.100000010988609489e+01,2.497834588969149051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753584533725437211e+01,5.736427480871624311e+02,3.008884777815181710e-01,1.100000010988609489e+01,2.497688603567611333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753675442815438146e+01,5.736527480559701644e+02,3.009134546415843658e-01,1.100000010988609489e+01,2.497542618166073616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753766351905439080e+01,5.736627480247815356e+02,3.009384300418010971e-01,1.100000010988609489e+01,2.497396632764535898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753857260995440015e+01,5.736727479935966585e+02,3.009634039821683649e-01,1.100000010988609489e+01,2.497250647362998181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.753948170085440950e+01,5.736827479624154194e+02,3.009883764626861691e-01,1.100000010988609489e+01,2.497104661961460463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754039079175441884e+01,5.736927479312378182e+02,3.010133474833545097e-01,1.100000010988609489e+01,2.496958676559922746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754129988265442819e+01,5.737027479000638550e+02,3.010383170441733869e-01,1.100000010988609489e+01,2.496812691158385028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754220897355443753e+01,5.737127478688935298e+02,3.010632851451428005e-01,1.100000010988609489e+01,2.496666705756847311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754311806445444688e+01,5.737227478377268426e+02,3.010882517862627505e-01,1.100000010988609489e+01,2.496520720355309593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754402715535445623e+01,5.737327478065637933e+02,3.011132169675332371e-01,1.100000010988609489e+01,2.496374734953771875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754493624625446557e+01,5.737427477754043821e+02,3.011381806889542601e-01,1.100000010988609489e+01,2.496228749552234158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754584533715447492e+01,5.737527477442486088e+02,3.011631429505258195e-01,1.100000010988609489e+01,2.496082764150696440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754675442805448426e+01,5.737627477130964735e+02,3.011881037522479154e-01,1.100000010988609489e+01,2.495936778749158723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754766351895449361e+01,5.737727476819479762e+02,3.012130630941204923e-01,1.100000010988609489e+01,2.495790793347621005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754857260985450296e+01,5.737827476508031168e+02,3.012380209761436056e-01,1.100000010988609489e+01,2.495644807946083288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.754948170075451230e+01,5.737927476196618954e+02,3.012629773983172554e-01,1.100000010988609489e+01,2.495498822544545570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755039079165452165e+01,5.738027475885243121e+02,3.012879323606414417e-01,1.100000010988609489e+01,2.495352837143007853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755129988255453100e+01,5.738127475573903666e+02,3.013128858631161644e-01,1.100000010988609489e+01,2.495206851741470135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755220897345454034e+01,5.738227475262600592e+02,3.013378379057414236e-01,1.100000010988609489e+01,2.495060866339932418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755311806435454969e+01,5.738327474951333897e+02,3.013627884885172192e-01,1.100000010988609489e+01,2.494914880938394700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755402715525455903e+01,5.738427474640103583e+02,3.013877376114435513e-01,1.100000010988609489e+01,2.494768895536856983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755493624615456838e+01,5.738527474328909648e+02,3.014126852745203644e-01,1.100000010988609489e+01,2.494622910135319265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755584533705457773e+01,5.738627474017752093e+02,3.014376314777477139e-01,1.100000010988609489e+01,2.494476924733781548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755675442795458707e+01,5.738727473706632054e+02,3.014625762211255999e-01,1.100000010988609489e+01,2.494330939332243830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755766351885459642e+01,5.738827473395548395e+02,3.014875195046540224e-01,1.100000010988609489e+01,2.494184953930706113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755857260975460576e+01,5.738927473084501116e+02,3.015124613283329813e-01,1.100000010988609489e+01,2.494038968529168395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.755948170065461511e+01,5.739027472773490217e+02,3.015374016921624767e-01,1.100000010988609489e+01,2.493892983127630678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756039079155462446e+01,5.739127472462515698e+02,3.015623405961424530e-01,1.100000010988609489e+01,2.493746997726092960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756129988245463380e+01,5.739227472151577558e+02,3.015872780402729658e-01,1.100000010988609489e+01,2.493601012324555243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756220897335464315e+01,5.739327471840675798e+02,3.016122140245540151e-01,1.100000010988609489e+01,2.493455026923017525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756311806425465250e+01,5.739427471529810418e+02,3.016371485489856008e-01,1.100000010988609489e+01,2.493309041521479807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756402715515466184e+01,5.739527471218981418e+02,3.016620816135676675e-01,1.100000010988609489e+01,2.493163056119942090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756493624605467119e+01,5.739627470908188798e+02,3.016870132183002706e-01,1.100000010988609489e+01,2.493017070718404372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756584533695468053e+01,5.739727470597432557e+02,3.017119433631834102e-01,1.100000010988609489e+01,2.492871085316866655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756675442785468988e+01,5.739827470286712696e+02,3.017368720482170863e-01,1.100000010988609489e+01,2.492725099915328937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756766351875469923e+01,5.739927469976029215e+02,3.017617992734012433e-01,1.100000010988609489e+01,2.492579114513791220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756857260965470857e+01,5.740027469665382114e+02,3.017867250387359368e-01,1.100000010988609489e+01,2.492433129112253502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.756948170055471792e+01,5.740127469354771392e+02,3.018116493442211667e-01,1.100000010988609489e+01,2.492287143710715785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757039079145472726e+01,5.740227469044197051e+02,3.018365721898568776e-01,1.100000010988609489e+01,2.492141158309178067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757129988235473661e+01,5.740327468733659089e+02,3.018614935756431250e-01,1.100000010988609489e+01,2.491995172907640350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757220897325474596e+01,5.740427468423157507e+02,3.018864135015799088e-01,1.100000010988609489e+01,2.491849187506102632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757311806415475530e+01,5.740527468112692304e+02,3.019113319676671736e-01,1.100000010988609489e+01,2.491703202104564915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757402715505476465e+01,5.740627467802263482e+02,3.019362489739049749e-01,1.100000010988609489e+01,2.491557216703027197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757493624595477399e+01,5.740727467491871039e+02,3.019611645202933126e-01,1.100000010988609489e+01,2.491411231301489480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757584533685478334e+01,5.740827467181514976e+02,3.019860786068321312e-01,1.100000010988609489e+01,2.491265245899951762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757675442775479269e+01,5.740927466871195293e+02,3.020109912335214863e-01,1.100000010988609489e+01,2.491119260498414045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757766351865480203e+01,5.741027466560911989e+02,3.020359024003613779e-01,1.100000010988609489e+01,2.490973275096876327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757857260955481138e+01,5.741127466250665066e+02,3.020608121073517505e-01,1.100000010988609489e+01,2.490827289695338610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.757948170045482073e+01,5.741227465940454522e+02,3.020857203544926595e-01,1.100000010988609489e+01,2.490681304293800892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758039079135483007e+01,5.741327465630280358e+02,3.021106271417840494e-01,1.100000010988609489e+01,2.490535318892263175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758129988225483942e+01,5.741427465320142574e+02,3.021355324692259758e-01,1.100000010988609489e+01,2.490389333490725457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758220897315484876e+01,5.741527465010041169e+02,3.021604363368183832e-01,1.100000010988609489e+01,2.490243348089187739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758311806405485811e+01,5.741627464699976144e+02,3.021853387445613270e-01,1.100000010988609489e+01,2.490097362687650022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758402715495486746e+01,5.741727464389947500e+02,3.022102396924547518e-01,1.100000010988609489e+01,2.489951377286112304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758493624585487680e+01,5.741827464079955234e+02,3.022351391804987131e-01,1.100000010988609489e+01,2.489805391884574587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758584533675488615e+01,5.741927463769999349e+02,3.022600372086932108e-01,1.100000010988609489e+01,2.489659406483036869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758675442765489549e+01,5.742027463460079844e+02,3.022849337770381895e-01,1.100000010988609489e+01,2.489513421081499152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758766351855490484e+01,5.742127463150196718e+02,3.023098288855337046e-01,1.100000010988609489e+01,2.489367435679961434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758857260945491419e+01,5.742227462840348835e+02,3.023347225341797007e-01,1.100000010988609489e+01,2.489221450278423717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.758948170035492353e+01,5.742327462530537332e+02,3.023596147229762332e-01,1.100000010988609489e+01,2.489075464876885999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759039079125493288e+01,5.742427462220762209e+02,3.023845054519232467e-01,1.100000010988609489e+01,2.488929479475348282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759129988215494222e+01,5.742527461911023465e+02,3.024093947210207411e-01,1.100000010988609489e+01,2.488783494073810564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759220897305495157e+01,5.742627461601321102e+02,3.024342825302687721e-01,1.100000010988609489e+01,2.488637508672272847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759311806395496092e+01,5.742727461291655118e+02,3.024591688796672839e-01,1.100000010988609489e+01,2.488491523270735129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759402715485497026e+01,5.742827460982025514e+02,3.024840537692163323e-01,1.100000010988609489e+01,2.488345537869197412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759493624575497961e+01,5.742927460672432289e+02,3.025089371989158615e-01,1.100000010988609489e+01,2.488199552467659694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759584533665498896e+01,5.743027460362875445e+02,3.025338191687659273e-01,1.100000010988609489e+01,2.488053567066121977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759675442755499830e+01,5.743127460053354980e+02,3.025586996787664740e-01,1.100000010988609489e+01,2.487907581664584259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759766351845500765e+01,5.743227459743870895e+02,3.025835787289175016e-01,1.100000010988609489e+01,2.487761596263046542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759857260935501699e+01,5.743327459434423190e+02,3.026084563192190657e-01,1.100000010988609489e+01,2.487615610861508824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.759948170025502634e+01,5.743427459125011865e+02,3.026333324496711108e-01,1.100000010988609489e+01,2.487469625459971106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760039079115503569e+01,5.743527458815636919e+02,3.026582071202736923e-01,1.100000010988609489e+01,2.487323640058433389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760129988205504503e+01,5.743627458506298353e+02,3.026830803310267548e-01,1.100000010988609489e+01,2.487177654656895671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760220897295505438e+01,5.743727458196996167e+02,3.027079520819302982e-01,1.100000010988609489e+01,2.487031669255357954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760311806385506372e+01,5.743827457887730361e+02,3.027328223729843781e-01,1.100000010988609489e+01,2.486885683853820236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760402715475507307e+01,5.743927457578500935e+02,3.027576912041889390e-01,1.100000010988609489e+01,2.486739698452282519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760493624565508242e+01,5.744027457269307888e+02,3.027825585755439808e-01,1.100000010988609489e+01,2.486593713050744801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760584533655509176e+01,5.744127456960150084e+02,3.028074244870495590e-01,1.100000010988609489e+01,2.486447727649207084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760675442745510111e+01,5.744227456651028660e+02,3.028322889387056183e-01,1.100000010988609489e+01,2.486301742247669366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760766351835511045e+01,5.744327456341943616e+02,3.028571519305121584e-01,1.100000010988609489e+01,2.486155756846131649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760857260925511980e+01,5.744427456032894952e+02,3.028820134624691796e-01,1.100000010988609489e+01,2.486009771444593931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.760948170015512915e+01,5.744527455723882667e+02,3.029068735345767371e-01,1.100000010988609489e+01,2.485863786043056214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761039079105513849e+01,5.744627455414906763e+02,3.029317321468347757e-01,1.100000010988609489e+01,2.485717800641518496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761129988195514784e+01,5.744727455105967238e+02,3.029565892992432952e-01,1.100000010988609489e+01,2.485571815239980779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761220897285515719e+01,5.744827454797064092e+02,3.029814449918022956e-01,1.100000010988609489e+01,2.485425829838443061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761311806375516653e+01,5.744927454488197327e+02,3.030062992245118325e-01,1.100000010988609489e+01,2.485279844436905344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761402715465517588e+01,5.745027454179366941e+02,3.030311519973718504e-01,1.100000010988609489e+01,2.485133859035367626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761493624555518522e+01,5.745127453870572936e+02,3.030560033103823492e-01,1.100000010988609489e+01,2.484987873633829909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761584533645519457e+01,5.745227453561815310e+02,3.030808531635433289e-01,1.100000010988609489e+01,2.484841888232292191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761675442735520392e+01,5.745327453253094063e+02,3.031057015568548452e-01,1.100000010988609489e+01,2.484695902830754474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761766351825521326e+01,5.745427452944408060e+02,3.031305484903168423e-01,1.100000010988609489e+01,2.484549917429216756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761857260915522261e+01,5.745527452635758436e+02,3.031553939639293205e-01,1.100000010988609489e+01,2.484403932027679038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.761948170005523195e+01,5.745627452327145193e+02,3.031802379776922796e-01,1.100000010988609489e+01,2.484257946626141321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762039079095524130e+01,5.745727452018568329e+02,3.032050805316057196e-01,1.100000010988609489e+01,2.484111961224603603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762129988185525065e+01,5.745827451710027844e+02,3.032299216256696406e-01,1.100000010988609489e+01,2.483965975823065886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762220897275525999e+01,5.745927451401523740e+02,3.032547612598840425e-01,1.100000010988609489e+01,2.483819990421528168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762311806365526934e+01,5.746027451093056015e+02,3.032795994342489809e-01,1.100000010988609489e+01,2.483674005019990451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762402715455527868e+01,5.746127450784624671e+02,3.033044361487644003e-01,1.100000010988609489e+01,2.483528019618452733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762493624545528803e+01,5.746227450476229706e+02,3.033292714034303006e-01,1.100000010988609489e+01,2.483382034216915016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762584533635529738e+01,5.746327450167869983e+02,3.033541051982466819e-01,1.100000010988609489e+01,2.483236048815377298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762675442725530672e+01,5.746427449859546641e+02,3.033789375332135441e-01,1.100000010988609489e+01,2.483090063413839581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762766351815531607e+01,5.746527449551259679e+02,3.034037684083308872e-01,1.100000010988609489e+01,2.482944078012301863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762857260905532542e+01,5.746627449243009096e+02,3.034285978235987113e-01,1.100000010988609489e+01,2.482798092610764146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.762948169995533476e+01,5.746727448934794893e+02,3.034534257790170164e-01,1.100000010988609489e+01,2.482652107209226428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763039079085534411e+01,5.746827448626617070e+02,3.034782522745858024e-01,1.100000010988609489e+01,2.482506121807688711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763129988175535345e+01,5.746927448318475626e+02,3.035030773103050694e-01,1.100000010988609489e+01,2.482360136406150993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763220897265536280e+01,5.747027448010370563e+02,3.035279008861748173e-01,1.100000010988609489e+01,2.482214151004613276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763311806355537215e+01,5.747127447702301879e+02,3.035527230021950462e-01,1.100000010988609489e+01,2.482068165603075558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763402715445538149e+01,5.747227447394268438e+02,3.035775436583657561e-01,1.100000010988609489e+01,2.481922180201537841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763493624535539084e+01,5.747327447086271377e+02,3.036023628546869468e-01,1.100000010988609489e+01,2.481776194800000123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763584533625540018e+01,5.747427446778310696e+02,3.036271805911586186e-01,1.100000010988609489e+01,2.481630209398462406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763675442715540953e+01,5.747527446470386394e+02,3.036519968677807713e-01,1.100000010988609489e+01,2.481484223996924688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763766351805541888e+01,5.747627446162498472e+02,3.036768116845534049e-01,1.100000010988609489e+01,2.481338238595386970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763857260895542822e+01,5.747727445854646930e+02,3.037016250414765195e-01,1.100000010988609489e+01,2.481192253193849253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.763948169985543757e+01,5.747827445546831768e+02,3.037264369385501150e-01,1.100000010988609489e+01,2.481046267792311535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764039079075544691e+01,5.747927445239051849e+02,3.037512473757741915e-01,1.100000010988609489e+01,2.480900282390773818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764129988165545626e+01,5.748027444931308310e+02,3.037760563531487490e-01,1.100000010988609489e+01,2.480754296989236100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764220897255546561e+01,5.748127444623601150e+02,3.038008638706737874e-01,1.100000010988609489e+01,2.480608311587698383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764311806345547495e+01,5.748227444315930370e+02,3.038256699283493067e-01,1.100000010988609489e+01,2.480462326186160665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764402715435548430e+01,5.748327444008295970e+02,3.038504745261753071e-01,1.100000010988609489e+01,2.480316340784622948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764493624525549365e+01,5.748427443700697950e+02,3.038752776641517883e-01,1.100000010988609489e+01,2.480170355383085230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764584533615550299e+01,5.748527443393136309e+02,3.039000793422787505e-01,1.100000010988609489e+01,2.480024369981547513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764675442705551234e+01,5.748627443085609912e+02,3.039248795605561937e-01,1.100000010988609489e+01,2.479878384580009795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764766351795552168e+01,5.748727442778119894e+02,3.039496783189840623e-01,1.100000010988609489e+01,2.479732399178472078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764857260885553103e+01,5.748827442470666256e+02,3.039744756175624119e-01,1.100000010988609489e+01,2.479586413776934360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.764948169975554038e+01,5.748927442163248998e+02,3.039992714562912424e-01,1.100000010988609489e+01,2.479440428375396643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765039079065554972e+01,5.749027441855868119e+02,3.040240658351705538e-01,1.100000010988609489e+01,2.479294442973858925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765129988155555907e+01,5.749127441548523620e+02,3.040488587542003462e-01,1.100000010988609489e+01,2.479148457572321208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765220897245556841e+01,5.749227441241214365e+02,3.040736502133806196e-01,1.100000010988609489e+01,2.479002472170783490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765311806335557776e+01,5.749327440933941489e+02,3.040984402127113184e-01,1.100000010988609489e+01,2.478856486769245773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765402715425558711e+01,5.749427440626704993e+02,3.041232287521924982e-01,1.100000010988609489e+01,2.478710501367708055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765493624515559645e+01,5.749527440319504876e+02,3.041480158318241589e-01,1.100000010988609489e+01,2.478564515966170338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765584533605560580e+01,5.749627440012341140e+02,3.041728014516063006e-01,1.100000010988609489e+01,2.478418530564632620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765675442695561514e+01,5.749727439705213783e+02,3.041975856115389232e-01,1.100000010988609489e+01,2.478272545163094902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765766351785562449e+01,5.749827439398121669e+02,3.042223683116219712e-01,1.100000010988609489e+01,2.478126559761557185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765857260875563384e+01,5.749927439091065935e+02,3.042471495518555002e-01,1.100000010988609489e+01,2.477980574360019467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.765948169965564318e+01,5.750027438784046581e+02,3.042719293322395102e-01,1.100000010988609489e+01,2.477834588958481750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766039079055565253e+01,5.750127438477063606e+02,3.042967076527740011e-01,1.100000010988609489e+01,2.477688603556944032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766129988145566188e+01,5.750227438170117011e+02,3.043214845134589175e-01,1.100000010988609489e+01,2.477542618155406315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766220897235567122e+01,5.750327437863206796e+02,3.043462599142943148e-01,1.100000010988609489e+01,2.477396632753868597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766311806325568057e+01,5.750427437556331824e+02,3.043710338552801931e-01,1.100000010988609489e+01,2.477250647352330880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766402715415568991e+01,5.750527437249493232e+02,3.043958063364165523e-01,1.100000010988609489e+01,2.477104661950793162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766493624505569926e+01,5.750627436942691020e+02,3.044205773577033369e-01,1.100000010988609489e+01,2.476958676549255445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766584533595570861e+01,5.750727436635925187e+02,3.044453469191406025e-01,1.100000010988609489e+01,2.476812691147717727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766675442685571795e+01,5.750827436329195734e+02,3.044701150207283491e-01,1.100000010988609489e+01,2.476666705746180010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766766351775572730e+01,5.750927436022501524e+02,3.044948816624665211e-01,1.100000010988609489e+01,2.476520720344642292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766857260865573664e+01,5.751027435715843694e+02,3.045196468443551741e-01,1.100000010988609489e+01,2.476374734943104575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.766948169955574599e+01,5.751127435409222244e+02,3.045444105663943080e-01,1.100000010988609489e+01,2.476228749541566857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767039079045575534e+01,5.751227435102637173e+02,3.045691728285838673e-01,1.100000010988609489e+01,2.476082764140029140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767129988135576468e+01,5.751327434796088482e+02,3.045939336309239076e-01,1.100000010988609489e+01,2.475936778738491422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767220897225577403e+01,5.751427434489575035e+02,3.046186929734143733e-01,1.100000010988609489e+01,2.475790793336953705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767311806315578337e+01,5.751527434183097967e+02,3.046434508560553200e-01,1.100000010988609489e+01,2.475644807935415987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767402715405579272e+01,5.751627433876657278e+02,3.046682072788467477e-01,1.100000010988609489e+01,2.475498822533878270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767493624495580207e+01,5.751727433570252970e+02,3.046929622417886008e-01,1.100000010988609489e+01,2.475352837132340552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767584533585581141e+01,5.751827433263885041e+02,3.047177157448809348e-01,1.100000010988609489e+01,2.475206851730802834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767675442675582076e+01,5.751927432957552355e+02,3.047424677881236943e-01,1.100000010988609489e+01,2.475060866329265117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767766351765583011e+01,5.752027432651256049e+02,3.047672183715169347e-01,1.100000010988609489e+01,2.474914880927727399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767857260855583945e+01,5.752127432344996123e+02,3.047919674950606006e-01,1.100000010988609489e+01,2.474768895526189682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.767948169945584880e+01,5.752227432038772577e+02,3.048167151587547474e-01,1.100000010988609489e+01,2.474622910124651964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768039079035585814e+01,5.752327431732584273e+02,3.048414613625993197e-01,1.100000010988609489e+01,2.474476924723114247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768129988125586749e+01,5.752427431426432349e+02,3.048662061065943729e-01,1.100000010988609489e+01,2.474330939321576529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768220897215587684e+01,5.752527431120316805e+02,3.048909493907399071e-01,1.100000010988609489e+01,2.474184953920038812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768311806305588618e+01,5.752627430814237641e+02,3.049156912150358667e-01,1.100000010988609489e+01,2.474038968518501094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768402715395589553e+01,5.752727430508194857e+02,3.049404315794822518e-01,1.100000010988609489e+01,2.473892983116963377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768493624485590487e+01,5.752827430202187315e+02,3.049651704840791178e-01,1.100000010988609489e+01,2.473746997715425659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768584533575591422e+01,5.752927429896216154e+02,3.049899079288264092e-01,1.100000010988609489e+01,2.473601012313887942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768675442665592357e+01,5.753027429590281372e+02,3.050146439137241816e-01,1.100000010988609489e+01,2.473455026912350224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768766351755593291e+01,5.753127429284382970e+02,3.050393784387723795e-01,1.100000010988609489e+01,2.473309041510812507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768857260845594226e+01,5.753227428978519811e+02,3.050641115039710582e-01,1.100000010988609489e+01,2.473163056109274789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.768948169935595160e+01,5.753327428672693031e+02,3.050888431093201625e-01,1.100000010988609489e+01,2.473017070707737072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769039079025596095e+01,5.753427428366902632e+02,3.051135732548197477e-01,1.100000010988609489e+01,2.472871085306199354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769129988115597030e+01,5.753527428061148612e+02,3.051383019404697583e-01,1.100000010988609489e+01,2.472725099904661637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769220897205597964e+01,5.753627427755429835e+02,3.051630291662701944e-01,1.100000010988609489e+01,2.472579114503123919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769311806295598899e+01,5.753727427449747438e+02,3.051877549322211114e-01,1.100000010988609489e+01,2.472433129101586202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769402715385599834e+01,5.753827427144101421e+02,3.052124792383224539e-01,1.100000010988609489e+01,2.472287143700048484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769493624475600768e+01,5.753927426838491783e+02,3.052372020845742773e-01,1.100000010988609489e+01,2.472141158298510766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769584533565601703e+01,5.754027426532917389e+02,3.052619234709765261e-01,1.100000010988609489e+01,2.471995172896973049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769675442655602637e+01,5.754127426227379374e+02,3.052866433975292004e-01,1.100000010988609489e+01,2.471849187495435331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769766351745603572e+01,5.754227425921877739e+02,3.053113618642323557e-01,1.100000010988609489e+01,2.471703202093897614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769857260835604507e+01,5.754327425616412484e+02,3.053360788710859364e-01,1.100000010988609489e+01,2.471557216692359896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.769948169925605441e+01,5.754427425310982471e+02,3.053607944180899425e-01,1.100000010988609489e+01,2.471411231290822179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770039079015606376e+01,5.754527425005588839e+02,3.053855085052444296e-01,1.100000010988609489e+01,2.471265245889284461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770129988105607310e+01,5.754627424700231586e+02,3.054102211325493421e-01,1.100000010988609489e+01,2.471119260487746744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770220897195608245e+01,5.754727424394910713e+02,3.054349323000046801e-01,1.100000010988609489e+01,2.470973275086209026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770311806285609180e+01,5.754827424089625083e+02,3.054596420076104990e-01,1.100000010988609489e+01,2.470827289684671309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770402715375610114e+01,5.754927423784375833e+02,3.054843502553667434e-01,1.100000010988609489e+01,2.470681304283133591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770493624465611049e+01,5.755027423479162962e+02,3.055090570432734132e-01,1.100000010988609489e+01,2.470535318881595874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770584533555611984e+01,5.755127423173985335e+02,3.055337623713305084e-01,1.100000010988609489e+01,2.470389333480058156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770675442645612918e+01,5.755227422868844087e+02,3.055584662395380846e-01,1.100000010988609489e+01,2.470243348078520439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770766351735613853e+01,5.755327422563739219e+02,3.055831686478960862e-01,1.100000010988609489e+01,2.470097362676982721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770857260825614787e+01,5.755427422258670731e+02,3.056078695964045133e-01,1.100000010988609489e+01,2.469951377275445004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.770948169915615722e+01,5.755527421953637486e+02,3.056325690850633658e-01,1.100000010988609489e+01,2.469805391873907286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771039079005616657e+01,5.755627421648640620e+02,3.056572671138726993e-01,1.100000010988609489e+01,2.469659406472369569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771129988095617591e+01,5.755727421343680135e+02,3.056819636828324582e-01,1.100000010988609489e+01,2.469513421070831851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771220897185618526e+01,5.755827421038756029e+02,3.057066587919426426e-01,1.100000010988609489e+01,2.469367435669294134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771311806275619460e+01,5.755927420733867166e+02,3.057313524412032524e-01,1.100000010988609489e+01,2.469221450267756416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771402715365620395e+01,5.756027420429014683e+02,3.057560446306142876e-01,1.100000010988609489e+01,2.469075464866218698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771493624455621330e+01,5.756127420124198579e+02,3.057807353601758038e-01,1.100000010988609489e+01,2.468929479464680981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771584533545622264e+01,5.756227419819417719e+02,3.058054246298877454e-01,1.100000010988609489e+01,2.468783494063143263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771675442635623199e+01,5.756327419514673238e+02,3.058301124397501125e-01,1.100000010988609489e+01,2.468637508661605546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771766351725624133e+01,5.756427419209965137e+02,3.058547987897629050e-01,1.100000010988609489e+01,2.468491523260067828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771857260815625068e+01,5.756527418905292279e+02,3.058794836799261230e-01,1.100000010988609489e+01,2.468345537858530111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.771948169905626003e+01,5.756627418600655801e+02,3.059041671102397664e-01,1.100000010988609489e+01,2.468199552456992393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772039078995626937e+01,5.756727418296055703e+02,3.059288490807038352e-01,1.100000010988609489e+01,2.468053567055454676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772129988085627872e+01,5.756827417991491984e+02,3.059535295913183295e-01,1.100000010988609489e+01,2.467907581653916958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772220897175628807e+01,5.756927417686963508e+02,3.059782086420833047e-01,1.100000010988609489e+01,2.467761596252379241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772311806265629741e+01,5.757027417382471413e+02,3.060028862329987054e-01,1.100000010988609489e+01,2.467615610850841523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772402715355630676e+01,5.757127417078015696e+02,3.060275623640645315e-01,1.100000010988609489e+01,2.467469625449303806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772493624445631610e+01,5.757227416773595223e+02,3.060522370352807831e-01,1.100000010988609489e+01,2.467323640047766088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772584533535632545e+01,5.757327416469211130e+02,3.060769102466474600e-01,1.100000010988609489e+01,2.467177654646228371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772675442625633480e+01,5.757427416164863416e+02,3.061015819981645625e-01,1.100000010988609489e+01,2.467031669244690653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772766351715634414e+01,5.757527415860550946e+02,3.061262522898320904e-01,1.100000010988609489e+01,2.466885683843152936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772857260805635349e+01,5.757627415556274855e+02,3.061509211216500437e-01,1.100000010988609489e+01,2.466739698441615218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.772948169895636283e+01,5.757727415252035144e+02,3.061755884936184224e-01,1.100000010988609489e+01,2.466593713040077501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773039078985637218e+01,5.757827414947830675e+02,3.062002544057372266e-01,1.100000010988609489e+01,2.466447727638539783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773129988075638153e+01,5.757927414643662587e+02,3.062249188580064563e-01,1.100000010988609489e+01,2.466301742237002066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773220897165639087e+01,5.758027414339530878e+02,3.062495818504261114e-01,1.100000010988609489e+01,2.466155756835464348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773311806255640022e+01,5.758127414035434413e+02,3.062742433829961919e-01,1.100000010988609489e+01,2.466009771433926630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773402715345640956e+01,5.758227413731374327e+02,3.062989034557166979e-01,1.100000010988609489e+01,2.465863786032388913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773493624435641891e+01,5.758327413427350621e+02,3.063235620685876293e-01,1.100000010988609489e+01,2.465717800630851195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773584533525642826e+01,5.758427413123362157e+02,3.063482192216089861e-01,1.100000010988609489e+01,2.465571815229313478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773675442615643760e+01,5.758527412819410074e+02,3.063728749147807684e-01,1.100000010988609489e+01,2.465425829827775760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773766351705644695e+01,5.758627412515494370e+02,3.063975291481029761e-01,1.100000010988609489e+01,2.465279844426238043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773857260795645630e+01,5.758727412211613910e+02,3.064221819215756093e-01,1.100000010988609489e+01,2.465133859024700325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.773948169885646564e+01,5.758827411907769829e+02,3.064468332351986124e-01,1.100000010988609489e+01,2.464987873623162608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774039078975647499e+01,5.758927411603962128e+02,3.064714830889720409e-01,1.100000010988609489e+01,2.464841888221624890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774129988065648433e+01,5.759027411300189669e+02,3.064961314828958949e-01,1.100000010988609489e+01,2.464695902820087173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774220897155649368e+01,5.759127410996453591e+02,3.065207784169701744e-01,1.100000010988609489e+01,2.464549917418549455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774311806245650303e+01,5.759227410692753892e+02,3.065454238911948792e-01,1.100000010988609489e+01,2.464403932017011738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774402715335651237e+01,5.759327410389089437e+02,3.065700679055700095e-01,1.100000010988609489e+01,2.464257946615474020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774493624425652172e+01,5.759427410085461361e+02,3.065947104600955653e-01,1.100000010988609489e+01,2.464111961213936303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774584533515653106e+01,5.759527409781869665e+02,3.066193515547715465e-01,1.100000010988609489e+01,2.463965975812398585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774675442605654041e+01,5.759627409478313211e+02,3.066439911895978976e-01,1.100000010988609489e+01,2.463819990410860868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774766351695654976e+01,5.759727409174793138e+02,3.066686293645746741e-01,1.100000010988609489e+01,2.463674005009323150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774857260785655910e+01,5.759827408871308307e+02,3.066932660797018761e-01,1.100000010988609489e+01,2.463528019607785433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.774948169875656845e+01,5.759927408567859857e+02,3.067179013349795036e-01,1.100000010988609489e+01,2.463382034206247715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775039078965657779e+01,5.760027408264447786e+02,3.067425351304075565e-01,1.100000010988609489e+01,2.463236048804709998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775129988055658714e+01,5.760127407961070958e+02,3.067671674659859793e-01,1.100000010988609489e+01,2.463090063403172280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775220897145659649e+01,5.760227407657730510e+02,3.067917983417148275e-01,1.100000010988609489e+01,2.462944078001634562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775311806235660583e+01,5.760327407354426441e+02,3.068164277575941012e-01,1.100000010988609489e+01,2.462798092600096845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775402715325661518e+01,5.760427407051157616e+02,3.068410557136238004e-01,1.100000010988609489e+01,2.462652107198559127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775493624415662453e+01,5.760527406747925170e+02,3.068656822098039250e-01,1.100000010988609489e+01,2.462506121797021410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775584533505663387e+01,5.760627406444727967e+02,3.068903072461344195e-01,1.100000010988609489e+01,2.462360136395483692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775675442595664322e+01,5.760727406141567144e+02,3.069149308226153394e-01,1.100000010988609489e+01,2.462214150993945975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775766351685665256e+01,5.760827405838442701e+02,3.069395529392466848e-01,1.100000010988609489e+01,2.462068165592408257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775857260775666191e+01,5.760927405535353500e+02,3.069641735960284001e-01,1.100000010988609489e+01,2.461922180190870540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.775948169865667126e+01,5.761027405232300680e+02,3.069887927929605409e-01,1.100000010988609489e+01,2.461776194789332822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776039078955668060e+01,5.761127404929284239e+02,3.070134105300431071e-01,1.100000010988609489e+01,2.461630209387795105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776129988045668995e+01,5.761227404626303041e+02,3.070380268072760988e-01,1.100000010988609489e+01,2.461484223986257387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776220897135669929e+01,5.761327404323358223e+02,3.070626416246594603e-01,1.100000010988609489e+01,2.461338238584719670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776311806225670864e+01,5.761427404020448648e+02,3.070872549821932473e-01,1.100000010988609489e+01,2.461192253183181952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776402715315671799e+01,5.761527403717575453e+02,3.071118668798774598e-01,1.100000010988609489e+01,2.461046267781644235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776493624405672733e+01,5.761627403414738637e+02,3.071364773177120422e-01,1.100000010988609489e+01,2.460900282380106517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776584533495673668e+01,5.761727403111937065e+02,3.071610862956970500e-01,1.100000010988609489e+01,2.460754296978568800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776675442585674602e+01,5.761827402809171872e+02,3.071856938138324278e-01,1.100000010988609489e+01,2.460608311577031082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776766351675675537e+01,5.761927402506441922e+02,3.072102998721182310e-01,1.100000010988609489e+01,2.460462326175493365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776857260765676472e+01,5.762027402203748352e+02,3.072349044705544596e-01,1.100000010988609489e+01,2.460316340773955647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.776948169855677406e+01,5.762127401901091162e+02,3.072595076091410582e-01,1.100000010988609489e+01,2.460170355372417930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777039078945678341e+01,5.762227401598469214e+02,3.072841092878780822e-01,1.100000010988609489e+01,2.460024369970880212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777129988035679276e+01,5.762327401295883647e+02,3.073087095067654761e-01,1.100000010988609489e+01,2.459878384569342494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777220897125680210e+01,5.762427400993333322e+02,3.073333082658032955e-01,1.100000010988609489e+01,2.459732399167804777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777311806215681145e+01,5.762527400690819377e+02,3.073579055649915404e-01,1.100000010988609489e+01,2.459586413766267059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777402715305682079e+01,5.762627400388341812e+02,3.073825014043301551e-01,1.100000010988609489e+01,2.459440428364729342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777493624395683014e+01,5.762727400085899490e+02,3.074070957838191953e-01,1.100000010988609489e+01,2.459294442963191624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777584533485683949e+01,5.762827399783493547e+02,3.074316887034586054e-01,1.100000010988609489e+01,2.459148457561653907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777675442575684883e+01,5.762927399481122848e+02,3.074562801632484410e-01,1.100000010988609489e+01,2.459002472160116189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777766351665685818e+01,5.763027399178788528e+02,3.074808701631886465e-01,1.100000010988609489e+01,2.458856486758578472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777857260755686752e+01,5.763127398876489451e+02,3.075054587032792774e-01,1.100000010988609489e+01,2.458710501357040754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.777948169845687687e+01,5.763227398574226754e+02,3.075300457835202783e-01,1.100000010988609489e+01,2.458564515955503037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778039078935688622e+01,5.763327398272000437e+02,3.075546314039117046e-01,1.100000010988609489e+01,2.458418530553965319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778129988025689556e+01,5.763427397969809363e+02,3.075792155644535009e-01,1.100000010988609489e+01,2.458272545152427602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778220897115690491e+01,5.763527397667654668e+02,3.076037982651457225e-01,1.100000010988609489e+01,2.458126559750889884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778311806205691425e+01,5.763627397365535217e+02,3.076283795059883142e-01,1.100000010988609489e+01,2.457980574349352167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778402715295692360e+01,5.763727397063452145e+02,3.076529592869813312e-01,1.100000010988609489e+01,2.457834588947814449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778493624385693295e+01,5.763827396761404316e+02,3.076775376081247182e-01,1.100000010988609489e+01,2.457688603546276732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778584533475694229e+01,5.763927396459392867e+02,3.077021144694184751e-01,1.100000010988609489e+01,2.457542618144739014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778675442565695164e+01,5.764027396157417797e+02,3.077266898708626575e-01,1.100000010988609489e+01,2.457396632743201297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778766351655696099e+01,5.764127395855477971e+02,3.077512638124572097e-01,1.100000010988609489e+01,2.457250647341663579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778857260745697033e+01,5.764227395553574524e+02,3.077758362942021875e-01,1.100000010988609489e+01,2.457104661940125861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.778948169835697968e+01,5.764327395251706321e+02,3.078004073160975351e-01,1.100000010988609489e+01,2.456958676538588144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779039078925698902e+01,5.764427394949874497e+02,3.078249768781432527e-01,1.100000010988609489e+01,2.456812691137050426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779129988015699837e+01,5.764527394648077916e+02,3.078495449803393957e-01,1.100000010988609489e+01,2.456666705735512709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779220897105700772e+01,5.764627394346317715e+02,3.078741116226859087e-01,1.100000010988609489e+01,2.456520720333974991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779311806195701706e+01,5.764727394044592756e+02,3.078986768051828471e-01,1.100000010988609489e+01,2.456374734932437274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779402715285702641e+01,5.764827393742904178e+02,3.079232405278301554e-01,1.100000010988609489e+01,2.456228749530899556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779493624375703575e+01,5.764927393441250842e+02,3.079478027906278337e-01,1.100000010988609489e+01,2.456082764129361839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779584533465704510e+01,5.765027393139633887e+02,3.079723635935759374e-01,1.100000010988609489e+01,2.455936778727824121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779675442555705445e+01,5.765127392838053311e+02,3.079969229366744110e-01,1.100000010988609489e+01,2.455790793326286404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779766351645706379e+01,5.765227392536507978e+02,3.080214808199232546e-01,1.100000010988609489e+01,2.455644807924748686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779857260735707314e+01,5.765327392234999024e+02,3.080460372433224681e-01,1.100000010988609489e+01,2.455498822523210969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.779948169825708248e+01,5.765427391933525314e+02,3.080705922068721070e-01,1.100000010988609489e+01,2.455352837121673251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780039078915709183e+01,5.765527391632087983e+02,3.080951457105721158e-01,1.100000010988609489e+01,2.455206851720135534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780129988005710118e+01,5.765627391330685896e+02,3.081196977544224946e-01,1.100000010988609489e+01,2.455060866318597816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780220897095711052e+01,5.765727391029320188e+02,3.081442483384232989e-01,1.100000010988609489e+01,2.454914880917060099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780311806185711987e+01,5.765827390727989723e+02,3.081687974625744730e-01,1.100000010988609489e+01,2.454768895515522381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780402715275712922e+01,5.765927390426695638e+02,3.081933451268760171e-01,1.100000010988609489e+01,2.454622910113984664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780493624365713856e+01,5.766027390125436796e+02,3.082178913313279311e-01,1.100000010988609489e+01,2.454476924712446946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780584533455714791e+01,5.766127389824214333e+02,3.082424360759302706e-01,1.100000010988609489e+01,2.454330939310909229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780675442545715725e+01,5.766227389523027114e+02,3.082669793606829800e-01,1.100000010988609489e+01,2.454184953909371511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780766351635716660e+01,5.766327389221876274e+02,3.082915211855860593e-01,1.100000010988609489e+01,2.454038968507833793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780857260725717595e+01,5.766427388920760677e+02,3.083160615506395086e-01,1.100000010988609489e+01,2.453892983106296076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.780948169815718529e+01,5.766527388619681460e+02,3.083406004558433278e-01,1.100000010988609489e+01,2.453746997704758358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781039078905719464e+01,5.766627388318637486e+02,3.083651379011975724e-01,1.100000010988609489e+01,2.453601012303220641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781129987995720398e+01,5.766727388017629892e+02,3.083896738867021869e-01,1.100000010988609489e+01,2.453455026901682923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781220897085721333e+01,5.766827387716657540e+02,3.084142084123571714e-01,1.100000010988609489e+01,2.453309041500145206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781311806175722268e+01,5.766927387415721569e+02,3.084387414781625258e-01,1.100000010988609489e+01,2.453163056098607488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781402715265723202e+01,5.767027387114820840e+02,3.084632730841182502e-01,1.100000010988609489e+01,2.453017070697069771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781493624355724137e+01,5.767127386813956491e+02,3.084878032302243445e-01,1.100000010988609489e+01,2.452871085295532053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781584533445725071e+01,5.767227386513127385e+02,3.085123319164808087e-01,1.100000010988609489e+01,2.452725099893994336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781675442535726006e+01,5.767327386212334659e+02,3.085368591428876428e-01,1.100000010988609489e+01,2.452579114492456618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781766351625726941e+01,5.767427385911577176e+02,3.085613849094449024e-01,1.100000010988609489e+01,2.452433129090918901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781857260715727875e+01,5.767527385610856072e+02,3.085859092161525319e-01,1.100000010988609489e+01,2.452287143689381183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.781948169805728810e+01,5.767627385310170212e+02,3.086104320630105313e-01,1.100000010988609489e+01,2.452141158287843466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782039078895729745e+01,5.767727385009520731e+02,3.086349534500189007e-01,1.100000010988609489e+01,2.451995172886305748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782129987985730679e+01,5.767827384708906493e+02,3.086594733771776400e-01,1.100000010988609489e+01,2.451849187484768031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782220897075731614e+01,5.767927384408328635e+02,3.086839918444867492e-01,1.100000010988609489e+01,2.451703202083230313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782311806165732548e+01,5.768027384107786020e+02,3.087085088519462284e-01,1.100000010988609489e+01,2.451557216681692596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782402715255733483e+01,5.768127383807279784e+02,3.087330243995560775e-01,1.100000010988609489e+01,2.451411231280154878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782493624345734418e+01,5.768227383506808792e+02,3.087575384873162965e-01,1.100000010988609489e+01,2.451265245878617161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782584533435735352e+01,5.768327383206374179e+02,3.087820511152268854e-01,1.100000010988609489e+01,2.451119260477079443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782675442525736287e+01,5.768427382905974810e+02,3.088065622832878443e-01,1.100000010988609489e+01,2.450973275075541725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782766351615737221e+01,5.768527382605611820e+02,3.088310719914991731e-01,1.100000010988609489e+01,2.450827289674004008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782857260705738156e+01,5.768627382305284073e+02,3.088555802398608718e-01,1.100000010988609489e+01,2.450681304272466290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.782948169795739091e+01,5.768727382004992705e+02,3.088800870283729405e-01,1.100000010988609489e+01,2.450535318870928573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783039078885740025e+01,5.768827381704736581e+02,3.089045923570353791e-01,1.100000010988609489e+01,2.450389333469390855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783129987975740960e+01,5.768927381404516836e+02,3.089290962258481876e-01,1.100000010988609489e+01,2.450243348067853138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783220897065741894e+01,5.769027381104332335e+02,3.089535986348113661e-01,1.100000010988609489e+01,2.450097362666315420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783311806155742829e+01,5.769127380804183076e+02,3.089780995839249145e-01,1.100000010988609489e+01,2.449951377264777703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783402715245743764e+01,5.769227380504070197e+02,3.090025990731888328e-01,1.100000010988609489e+01,2.449805391863239985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783493624335744698e+01,5.769327380203992561e+02,3.090270971026031210e-01,1.100000010988609489e+01,2.449659406461702268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783584533425745633e+01,5.769427379903951305e+02,3.090515936721677792e-01,1.100000010988609489e+01,2.449513421060164550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783675442515746568e+01,5.769527379603945292e+02,3.090760887818828073e-01,1.100000010988609489e+01,2.449367435658626833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783766351605747502e+01,5.769627379303975658e+02,3.091005824317481498e-01,1.100000010988609489e+01,2.449221450257089115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783857260695748437e+01,5.769727379004041268e+02,3.091250746217638623e-01,1.100000010988609489e+01,2.449075464855551398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.783948169785749371e+01,5.769827378704143257e+02,3.091495653519299447e-01,1.100000010988609489e+01,2.448929479454013680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784039078875750306e+01,5.769927378404280489e+02,3.091740546222463970e-01,1.100000010988609489e+01,2.448783494052475963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784129987965751241e+01,5.770027378104454101e+02,3.091985424327132193e-01,1.100000010988609489e+01,2.448637508650938245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784220897055752175e+01,5.770127377804662956e+02,3.092230287833304114e-01,1.100000010988609489e+01,2.448491523249400528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784311806145753110e+01,5.770227377504907054e+02,3.092475136740979735e-01,1.100000010988609489e+01,2.448345537847862810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784402715235754044e+01,5.770327377205187531e+02,3.092719971050158501e-01,1.100000010988609489e+01,2.448199552446325093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784493624325754979e+01,5.770427376905503252e+02,3.092964790760840965e-01,1.100000010988609489e+01,2.448053567044787375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784584533415755914e+01,5.770527376605855352e+02,3.093209595873027129e-01,1.100000010988609489e+01,2.447907581643249657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784675442505756848e+01,5.770627376306242695e+02,3.093454386386716992e-01,1.100000010988609489e+01,2.447761596241711940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784766351595757783e+01,5.770727376006666418e+02,3.093699162301910555e-01,1.100000010988609489e+01,2.447615610840174222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784857260685758717e+01,5.770827375707125384e+02,3.093943923618607261e-01,1.100000010988609489e+01,2.447469625438636505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.784948169775759652e+01,5.770927375407619593e+02,3.094188670336807667e-01,1.100000010988609489e+01,2.447323640037098787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785039078865760587e+01,5.771027375108150181e+02,3.094433402456511772e-01,1.100000010988609489e+01,2.447177654635561070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785129987955761521e+01,5.771127374808716013e+02,3.094678119977719577e-01,1.100000010988609489e+01,2.447031669234023352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785220897045762456e+01,5.771227374509318224e+02,3.094922822900430526e-01,1.100000010988609489e+01,2.446885683832485635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785311806135763391e+01,5.771327374209955678e+02,3.095167511224645174e-01,1.100000010988609489e+01,2.446739698430947917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785402715225764325e+01,5.771427373910629512e+02,3.095412184950363521e-01,1.100000010988609489e+01,2.446593713029410200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785493624315765260e+01,5.771527373611338589e+02,3.095656844077585568e-01,1.100000010988609489e+01,2.446447727627872482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785584533405766194e+01,5.771627373312082909e+02,3.095901488606310759e-01,1.100000010988609489e+01,2.446301742226334765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785675442495767129e+01,5.771727373012863609e+02,3.096146118536539649e-01,1.100000010988609489e+01,2.446155756824797047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785766351585768064e+01,5.771827372713679551e+02,3.096390733868272238e-01,1.100000010988609489e+01,2.446009771423259330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785857260675768998e+01,5.771927372414531874e+02,3.096635334601507972e-01,1.100000010988609489e+01,2.445863786021721612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.785948169765769933e+01,5.772027372115419439e+02,3.096879920736247405e-01,1.100000010988609489e+01,2.445717800620183895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786039078855770867e+01,5.772127371816342247e+02,3.097124492272490537e-01,1.100000010988609489e+01,2.445571815218646177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786129987945771802e+01,5.772227371517301435e+02,3.097369049210236813e-01,1.100000010988609489e+01,2.445425829817108460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786220897035772737e+01,5.772327371218295866e+02,3.097613591549486789e-01,1.100000010988609489e+01,2.445279844415570742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786311806125773671e+01,5.772427370919326677e+02,3.097858119290240464e-01,1.100000010988609489e+01,2.445133859014033025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786402715215774606e+01,5.772527370620392730e+02,3.098102632432497283e-01,1.100000010988609489e+01,2.444987873612495307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786493624305775541e+01,5.772627370321494027e+02,3.098347130976257802e-01,1.100000010988609489e+01,2.444841888210957589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786584533395776475e+01,5.772727370022631703e+02,3.098591614921521464e-01,1.100000010988609489e+01,2.444695902809419872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786675442485777410e+01,5.772827369723804622e+02,3.098836084268288826e-01,1.100000010988609489e+01,2.444549917407882154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786766351575778344e+01,5.772927369425013922e+02,3.099080539016559888e-01,1.100000010988609489e+01,2.444403932006344437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786857260665779279e+01,5.773027369126258463e+02,3.099324979166334093e-01,1.100000010988609489e+01,2.444257946604806719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.786948169755780214e+01,5.773127368827538248e+02,3.099569404717611998e-01,1.100000010988609489e+01,2.444111961203269002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787039078845781148e+01,5.773227368528854413e+02,3.099813815670393047e-01,1.100000010988609489e+01,2.443965975801731284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787129987935782083e+01,5.773327368230205821e+02,3.100058212024677795e-01,1.100000010988609489e+01,2.443819990400193567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787220897025783017e+01,5.773427367931593608e+02,3.100302593780465688e-01,1.100000010988609489e+01,2.443674004998655849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787311806115783952e+01,5.773527367633016638e+02,3.100546960937757279e-01,1.100000010988609489e+01,2.443528019597118132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787402715205784887e+01,5.773627367334474911e+02,3.100791313496552015e-01,1.100000010988609489e+01,2.443382034195580414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787493624295785821e+01,5.773727367035969564e+02,3.101035651456850450e-01,1.100000010988609489e+01,2.443236048794042697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787584533385786756e+01,5.773827366737499460e+02,3.101279974818652030e-01,1.100000010988609489e+01,2.443090063392504979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787675442475787690e+01,5.773927366439064599e+02,3.101524283581957309e-01,1.100000010988609489e+01,2.442944077990967262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787766351565788625e+01,5.774027366140666118e+02,3.101768577746765732e-01,1.100000010988609489e+01,2.442798092589429544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787857260655789560e+01,5.774127365842302879e+02,3.102012857313077854e-01,1.100000010988609489e+01,2.442652107187891827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.787948169745790494e+01,5.774227365543976020e+02,3.102257122280893120e-01,1.100000010988609489e+01,2.442506121786354109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788039078835791429e+01,5.774327365245684405e+02,3.102501372650212086e-01,1.100000010988609489e+01,2.442360136384816392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788129987925792364e+01,5.774427364947428032e+02,3.102745608421034196e-01,1.100000010988609489e+01,2.442214150983278674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788220897015793298e+01,5.774527364649208039e+02,3.102989829593360005e-01,1.100000010988609489e+01,2.442068165581740957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788311806105794233e+01,5.774627364351023289e+02,3.103234036167188958e-01,1.100000010988609489e+01,2.441922180180203239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788402715195795167e+01,5.774727364052873781e+02,3.103478228142521611e-01,1.100000010988609489e+01,2.441776194778665521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788493624285796102e+01,5.774827363754760654e+02,3.103722405519357408e-01,1.100000010988609489e+01,2.441630209377127804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788584533375797037e+01,5.774927363456682770e+02,3.103966568297696349e-01,1.100000010988609489e+01,2.441484223975590086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788675442465797971e+01,5.775027363158640128e+02,3.104210716477538989e-01,1.100000010988609489e+01,2.441338238574052369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788766351555798906e+01,5.775127362860633866e+02,3.104454850058884774e-01,1.100000010988609489e+01,2.441192253172514651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788857260645799840e+01,5.775227362562662847e+02,3.104698969041733703e-01,1.100000010988609489e+01,2.441046267770976934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.788948169735800775e+01,5.775327362264728208e+02,3.104943073426086331e-01,1.100000010988609489e+01,2.440900282369439216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789039078825801710e+01,5.775427361966828812e+02,3.105187163211942103e-01,1.100000010988609489e+01,2.440754296967901499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789129987915802644e+01,5.775527361668964659e+02,3.105431238399301019e-01,1.100000010988609489e+01,2.440608311566363781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789220897005803579e+01,5.775627361371136885e+02,3.105675298988163635e-01,1.100000010988609489e+01,2.440462326164826064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789311806095804513e+01,5.775727361073344355e+02,3.105919344978529395e-01,1.100000010988609489e+01,2.440316340763288346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789402715185805448e+01,5.775827360775587067e+02,3.106163376370398299e-01,1.100000010988609489e+01,2.440170355361750629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789493624275806383e+01,5.775927360477866159e+02,3.106407393163770903e-01,1.100000010988609489e+01,2.440024369960212911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789584533365807317e+01,5.776027360180180494e+02,3.106651395358646650e-01,1.100000010988609489e+01,2.439878384558675194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789675442455808252e+01,5.776127359882530072e+02,3.106895382955025542e-01,1.100000010988609489e+01,2.439732399157137476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789766351545809187e+01,5.776227359584916030e+02,3.107139355952908133e-01,1.100000010988609489e+01,2.439586413755599759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789857260635810121e+01,5.776327359287337231e+02,3.107383314352293868e-01,1.100000010988609489e+01,2.439440428354062041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.789948169725811056e+01,5.776427358989793674e+02,3.107627258153182748e-01,1.100000010988609489e+01,2.439294442952524324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790039078815811990e+01,5.776527358692286498e+02,3.107871187355574771e-01,1.100000010988609489e+01,2.439148457550986606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790129987905812925e+01,5.776627358394814564e+02,3.108115101959470494e-01,1.100000010988609489e+01,2.439002472149448889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790220896995813860e+01,5.776727358097377873e+02,3.108359001964869361e-01,1.100000010988609489e+01,2.438856486747911171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790311806085814794e+01,5.776827357799976426e+02,3.108602887371771373e-01,1.100000010988609489e+01,2.438710501346373453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790402715175815729e+01,5.776927357502611358e+02,3.108846758180176528e-01,1.100000010988609489e+01,2.438564515944835736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790493624265816663e+01,5.777027357205281533e+02,3.109090614390084828e-01,1.100000010988609489e+01,2.438418530543298018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790584533355817598e+01,5.777127356907986950e+02,3.109334456001496827e-01,1.100000010988609489e+01,2.438272545141760301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790675442445818533e+01,5.777227356610728748e+02,3.109578283014411970e-01,1.100000010988609489e+01,2.438126559740222583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790766351535819467e+01,5.777327356313505788e+02,3.109822095428830258e-01,1.100000010988609489e+01,2.437980574338684866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790857260625820402e+01,5.777427356016318072e+02,3.110065893244751689e-01,1.100000010988609489e+01,2.437834588937147148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.790948169715821336e+01,5.777527355719166735e+02,3.110309676462176265e-01,1.100000010988609489e+01,2.437688603535609431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791039078805822271e+01,5.777627355422050641e+02,3.110553445081103985e-01,1.100000010988609489e+01,2.437542618134071713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791129987895823206e+01,5.777727355124969790e+02,3.110797199101535404e-01,1.100000010988609489e+01,2.437396632732533996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791220896985824140e+01,5.777827354827925319e+02,3.111040938523469968e-01,1.100000010988609489e+01,2.437250647330996278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791311806075825075e+01,5.777927354530916091e+02,3.111284663346907675e-01,1.100000010988609489e+01,2.437104661929458561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791402715165826010e+01,5.778027354233942106e+02,3.111528373571848527e-01,1.100000010988609489e+01,2.436958676527920843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791493624255826944e+01,5.778127353937003363e+02,3.111772069198292523e-01,1.100000010988609489e+01,2.436812691126383126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791584533345827879e+01,5.778227353640101001e+02,3.112015750226239663e-01,1.100000010988609489e+01,2.436666705724845408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791675442435828813e+01,5.778327353343233881e+02,3.112259416655689948e-01,1.100000010988609489e+01,2.436520720323307691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791766351525829748e+01,5.778427353046402004e+02,3.112503068486643376e-01,1.100000010988609489e+01,2.436374734921769973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791857260615830683e+01,5.778527352749606507e+02,3.112746705719099949e-01,1.100000010988609489e+01,2.436228749520232256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.791948169705831617e+01,5.778627352452846253e+02,3.112990328353059666e-01,1.100000010988609489e+01,2.436082764118694538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792039078795832552e+01,5.778727352156121242e+02,3.113233936388522527e-01,1.100000010988609489e+01,2.435936778717156821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792129987885833486e+01,5.778827351859431474e+02,3.113477529825488532e-01,1.100000010988609489e+01,2.435790793315619103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792220896975834421e+01,5.778927351562778085e+02,3.113721108663957682e-01,1.100000010988609489e+01,2.435644807914081385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792311806065835356e+01,5.779027351266159940e+02,3.113964672903929976e-01,1.100000010988609489e+01,2.435498822512543668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792402715155836290e+01,5.779127350969577037e+02,3.114208222545405413e-01,1.100000010988609489e+01,2.435352837111005950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792493624245837225e+01,5.779227350673030514e+02,3.114451757588383995e-01,1.100000010988609489e+01,2.435206851709468233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792584533335838159e+01,5.779327350376519234e+02,3.114695278032865722e-01,1.100000010988609489e+01,2.435060866307930515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792675442425839094e+01,5.779427350080043198e+02,3.114938783878850592e-01,1.100000010988609489e+01,2.434914880906392798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792766351515840029e+01,5.779527349783602403e+02,3.115182275126338607e-01,1.100000010988609489e+01,2.434768895504855080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792857260605840963e+01,5.779627349487197989e+02,3.115425751775329766e-01,1.100000010988609489e+01,2.434622910103317363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.792948169695841898e+01,5.779727349190828818e+02,3.115669213825824069e-01,1.100000010988609489e+01,2.434476924701779645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793039078785842833e+01,5.779827348894494889e+02,3.115912661277821516e-01,1.100000010988609489e+01,2.434330939300241928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793129987875843767e+01,5.779927348598196204e+02,3.116156094131322107e-01,1.100000010988609489e+01,2.434184953898704210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793220896965844702e+01,5.780027348301933898e+02,3.116399512386325843e-01,1.100000010988609489e+01,2.434038968497166493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793311806055845636e+01,5.780127348005706835e+02,3.116642916042832723e-01,1.100000010988609489e+01,2.433892983095628775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793402715145846571e+01,5.780227347709515016e+02,3.116886305100842747e-01,1.100000010988609489e+01,2.433746997694091058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793493624235847506e+01,5.780327347413358439e+02,3.117129679560355915e-01,1.100000010988609489e+01,2.433601012292553340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793584533325848440e+01,5.780427347117238241e+02,3.117373039421372227e-01,1.100000010988609489e+01,2.433455026891015623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793675442415849375e+01,5.780527346821153287e+02,3.117616384683891684e-01,1.100000010988609489e+01,2.433309041489477905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793766351505850309e+01,5.780627346525103576e+02,3.117859715347913729e-01,1.100000010988609489e+01,2.433163056087940188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793857260595851244e+01,5.780727346229089108e+02,3.118103031413438919e-01,1.100000010988609489e+01,2.433017070686402470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.793948169685852179e+01,5.780827345933111019e+02,3.118346332880467253e-01,1.100000010988609489e+01,2.432871085284864753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794039078775853113e+01,5.780927345637168173e+02,3.118589619748998731e-01,1.100000010988609489e+01,2.432725099883327035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794129987865854048e+01,5.781027345341260570e+02,3.118832892019033354e-01,1.100000010988609489e+01,2.432579114481789317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794220896955854982e+01,5.781127345045388211e+02,3.119076149690571120e-01,1.100000010988609489e+01,2.432433129080251600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794311806045855917e+01,5.781227344749552230e+02,3.119319392763611476e-01,1.100000010988609489e+01,2.432287143678713882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794402715135856852e+01,5.781327344453751493e+02,3.119562621238154976e-01,1.100000010988609489e+01,2.432141158277176165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794493624225857786e+01,5.781427344157985999e+02,3.119805835114201620e-01,1.100000010988609489e+01,2.431995172875638447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794584533315858721e+01,5.781527343862255748e+02,3.120049034391751408e-01,1.100000010988609489e+01,2.431849187474100730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794675442405859656e+01,5.781627343566561876e+02,3.120292219070803785e-01,1.100000010988609489e+01,2.431703202072563012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794766351495860590e+01,5.781727343270903248e+02,3.120535389151359307e-01,1.100000010988609489e+01,2.431557216671025295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794857260585861525e+01,5.781827342975279862e+02,3.120778544633417972e-01,1.100000010988609489e+01,2.431411231269487577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.794948169675862459e+01,5.781927342679691719e+02,3.121021685516979782e-01,1.100000010988609489e+01,2.431265245867949860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795039078765863394e+01,5.782027342384138819e+02,3.121264811802044181e-01,1.100000010988609489e+01,2.431119260466412142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795129987855864329e+01,5.782127342088622299e+02,3.121507923488611724e-01,1.100000010988609489e+01,2.430973275064874425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795220896945865263e+01,5.782227341793141022e+02,3.121751020576682412e-01,1.100000010988609489e+01,2.430827289663336707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795311806035866198e+01,5.782327341497694988e+02,3.121994103066256243e-01,1.100000010988609489e+01,2.430681304261798990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795402715125867132e+01,5.782427341202284197e+02,3.122237170957332664e-01,1.100000010988609489e+01,2.430535318860261272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795493624215868067e+01,5.782527340906909785e+02,3.122480224249912228e-01,1.100000010988609489e+01,2.430389333458723555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795584533305869002e+01,5.782627340611570617e+02,3.122723262943994937e-01,1.100000010988609489e+01,2.430243348057185837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795675442395869936e+01,5.782727340316266691e+02,3.122966287039580235e-01,1.100000010988609489e+01,2.430097362655648120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795766351485870871e+01,5.782827340020998008e+02,3.123209296536668678e-01,1.100000010988609489e+01,2.429951377254110402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795857260575871805e+01,5.782927339725764568e+02,3.123452291435260264e-01,1.100000010988609489e+01,2.429805391852572685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.795948169665872740e+01,5.783027339430567508e+02,3.123695271735354440e-01,1.100000010988609489e+01,2.429659406451034967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796039078755873675e+01,5.783127339135405691e+02,3.123938237436951759e-01,1.100000010988609489e+01,2.429513421049497249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796129987845874609e+01,5.783227338840279117e+02,3.124181188540052223e-01,1.100000010988609489e+01,2.429367435647959532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796220896935875544e+01,5.783327338545187786e+02,3.124424125044655276e-01,1.100000010988609489e+01,2.429221450246421814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796311806025876479e+01,5.783427338250131697e+02,3.124667046950761473e-01,1.100000010988609489e+01,2.429075464844884097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796402715115877413e+01,5.783527337955111989e+02,3.124909954258370259e-01,1.100000010988609489e+01,2.428929479443346379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796493624205878348e+01,5.783627337660127523e+02,3.125152846967482190e-01,1.100000010988609489e+01,2.428783494041808662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796584533295879282e+01,5.783727337365178300e+02,3.125395725078096709e-01,1.100000010988609489e+01,2.428637508640270944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796675442385880217e+01,5.783827337070264321e+02,3.125638588590214373e-01,1.100000010988609489e+01,2.428491523238733227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796766351475881152e+01,5.783927336775385584e+02,3.125881437503835181e-01,1.100000010988609489e+01,2.428345537837195509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796857260565882086e+01,5.784027336480542090e+02,3.126124271818958578e-01,1.100000010988609489e+01,2.428199552435657792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.796948169655883021e+01,5.784127336185734976e+02,3.126367091535585119e-01,1.100000010988609489e+01,2.428053567034120074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797039078745883955e+01,5.784227335890963104e+02,3.126609896653714249e-01,1.100000010988609489e+01,2.427907581632582357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797129987835884890e+01,5.784327335596226476e+02,3.126852687173346523e-01,1.100000010988609489e+01,2.427761596231044639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797220896925885825e+01,5.784427335301525090e+02,3.127095463094481387e-01,1.100000010988609489e+01,2.427615610829506922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797311806015886759e+01,5.784527335006858948e+02,3.127338224417119394e-01,1.100000010988609489e+01,2.427469625427969204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797402715105887694e+01,5.784627334712229185e+02,3.127580971141259991e-01,1.100000010988609489e+01,2.427323640026431487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797493624195888628e+01,5.784727334417634665e+02,3.127823703266903732e-01,1.100000010988609489e+01,2.427177654624893769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797584533285889563e+01,5.784827334123075389e+02,3.128066420794050062e-01,1.100000010988609489e+01,2.427031669223356052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797675442375890498e+01,5.784927333828551355e+02,3.128309123722699536e-01,1.100000010988609489e+01,2.426885683821818334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797766351465891432e+01,5.785027333534062564e+02,3.128551812052851600e-01,1.100000010988609489e+01,2.426739698420280616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797857260555892367e+01,5.785127333239609015e+02,3.128794485784506807e-01,1.100000010988609489e+01,2.426593713018742899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.797948169645893302e+01,5.785227332945191847e+02,3.129037144917664603e-01,1.100000010988609489e+01,2.426447727617205181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798039078735894236e+01,5.785327332650809922e+02,3.129279789452324989e-01,1.100000010988609489e+01,2.426301742215667464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798129987825895171e+01,5.785427332356463239e+02,3.129522419388488519e-01,1.100000010988609489e+01,2.426155756814129746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798220896915896105e+01,5.785527332062151800e+02,3.129765034726154638e-01,1.100000010988609489e+01,2.426009771412592029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798311806005897040e+01,5.785627331767875603e+02,3.130007635465323901e-01,1.100000010988609489e+01,2.425863786011054311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798402715095897975e+01,5.785727331473634649e+02,3.130250221605995753e-01,1.100000010988609489e+01,2.425717800609516594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798493624185898909e+01,5.785827331179428938e+02,3.130492793148170194e-01,1.100000010988609489e+01,2.425571815207978876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798584533275899844e+01,5.785927330885259607e+02,3.130735350091847780e-01,1.100000010988609489e+01,2.425425829806441159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798675442365900778e+01,5.786027330591125519e+02,3.130977892437027954e-01,1.100000010988609489e+01,2.425279844404903441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798766351455901713e+01,5.786127330297026674e+02,3.131220420183710718e-01,1.100000010988609489e+01,2.425133859003365724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798857260545902648e+01,5.786227330002963072e+02,3.131462933331896625e-01,1.100000010988609489e+01,2.424987873601828006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.798948169635903582e+01,5.786327329708934712e+02,3.131705431881585122e-01,1.100000010988609489e+01,2.424841888200290289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799039078725904517e+01,5.786427329414941596e+02,3.131947915832776208e-01,1.100000010988609489e+01,2.424695902798752571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799129987815905451e+01,5.786527329120983723e+02,3.132190385185470438e-01,1.100000010988609489e+01,2.424549917397214854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799220896905906386e+01,5.786627328827062229e+02,3.132432839939667257e-01,1.100000010988609489e+01,2.424403931995677136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799311805995907321e+01,5.786727328533175978e+02,3.132675280095366666e-01,1.100000010988609489e+01,2.424257946594139419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799402715085908255e+01,5.786827328239324970e+02,3.132917705652569218e-01,1.100000010988609489e+01,2.424111961192601701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799493624175909190e+01,5.786927327945509205e+02,3.133160116611274359e-01,1.100000010988609489e+01,2.423965975791063984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799584533265910125e+01,5.787027327651728683e+02,3.133402512971482090e-01,1.100000010988609489e+01,2.423819990389526266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799675442355911059e+01,5.787127327357983404e+02,3.133644894733192410e-01,1.100000010988609489e+01,2.423674004987988548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799766351445911994e+01,5.787227327064273368e+02,3.133887261896405874e-01,1.100000010988609489e+01,2.423528019586450831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799857260535912928e+01,5.787327326770598575e+02,3.134129614461121927e-01,1.100000010988609489e+01,2.423382034184913113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.799948169625913863e+01,5.787427326476960161e+02,3.134371952427340569e-01,1.100000010988609489e+01,2.423236048783375396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800039078715914798e+01,5.787527326183356990e+02,3.134614275795061800e-01,1.100000010988609489e+01,2.423090063381837678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800129987805915732e+01,5.787627325889789063e+02,3.134856584564286175e-01,1.100000010988609489e+01,2.422944077980299961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800220896895916667e+01,5.787727325596256378e+02,3.135098878735013139e-01,1.100000010988609489e+01,2.422798092578762243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800311805985917601e+01,5.787827325302758936e+02,3.135341158307242693e-01,1.100000010988609489e+01,2.422652107177224526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800402715075918536e+01,5.787927325009296737e+02,3.135583423280974835e-01,1.100000010988609489e+01,2.422506121775686808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800493624165919471e+01,5.788027324715869781e+02,3.135825673656209567e-01,1.100000010988609489e+01,2.422360136374149091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800584533255920405e+01,5.788127324422478068e+02,3.136067909432946887e-01,1.100000010988609489e+01,2.422214150972611373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800675442345921340e+01,5.788227324129121598e+02,3.136310130611187352e-01,1.100000010988609489e+01,2.422068165571073656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800766351435922275e+01,5.788327323835801508e+02,3.136552337190930406e-01,1.100000010988609489e+01,2.421922180169535938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800857260525923209e+01,5.788427323542516660e+02,3.136794529172176049e-01,1.100000010988609489e+01,2.421776194767998221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.800948169615924144e+01,5.788527323249267056e+02,3.137036706554924281e-01,1.100000010988609489e+01,2.421630209366460503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801039078705925078e+01,5.788627322956052694e+02,3.137278869339175102e-01,1.100000010988609489e+01,2.421484223964922786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801129987795926013e+01,5.788727322662873576e+02,3.137521017524928513e-01,1.100000010988609489e+01,2.421338238563385068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801220896885926948e+01,5.788827322369729700e+02,3.137763151112184512e-01,1.100000010988609489e+01,2.421192253161847351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801311805975927882e+01,5.788927322076621067e+02,3.138005270100943100e-01,1.100000010988609489e+01,2.421046267760309633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801402715065928817e+01,5.789027321783547677e+02,3.138247374491204833e-01,1.100000010988609489e+01,2.420900282358771916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801493624155929751e+01,5.789127321490509530e+02,3.138489464282969155e-01,1.100000010988609489e+01,2.420754296957234198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801584533245930686e+01,5.789227321197506626e+02,3.138731539476236065e-01,1.100000010988609489e+01,2.420608311555696480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801675442335931621e+01,5.789327320904540102e+02,3.138973600071005565e-01,1.100000010988609489e+01,2.420462326154158763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801766351425932555e+01,5.789427320611608820e+02,3.139215646067277654e-01,1.100000010988609489e+01,2.420316340752621045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801857260515933490e+01,5.789527320318712782e+02,3.139457677465052332e-01,1.100000010988609489e+01,2.420170355351083328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.801948169605934424e+01,5.789627320025851986e+02,3.139699694264329599e-01,1.100000010988609489e+01,2.420024369949545610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802039078695935359e+01,5.789727319733026434e+02,3.139941696465109455e-01,1.100000010988609489e+01,2.419878384548007893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802129987785936294e+01,5.789827319440236124e+02,3.140183684067391900e-01,1.100000010988609489e+01,2.419732399146470175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802220896875937228e+01,5.789927319147481057e+02,3.140425657071176935e-01,1.100000010988609489e+01,2.419586413744932458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802311805965938163e+01,5.790027318854761234e+02,3.140667615476464558e-01,1.100000010988609489e+01,2.419440428343394740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802402715055939098e+01,5.790127318562076653e+02,3.140909559283254771e-01,1.100000010988609489e+01,2.419294442941857023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802493624145940032e+01,5.790227318269427315e+02,3.141151488491547572e-01,1.100000010988609489e+01,2.419148457540319305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802584533235940967e+01,5.790327317976813220e+02,3.141393403101342963e-01,1.100000010988609489e+01,2.419002472138781588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802675442325941901e+01,5.790427317684234367e+02,3.141635303112640942e-01,1.100000010988609489e+01,2.418856486737243870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802766351415942836e+01,5.790527317391690758e+02,3.141877188525441511e-01,1.100000010988609489e+01,2.418710501335706153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802857260505943771e+01,5.790627317099182392e+02,3.142119059339744669e-01,1.100000010988609489e+01,2.418564515934168435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.802948169595944705e+01,5.790727316806709268e+02,3.142360915555549861e-01,1.100000010988609489e+01,2.418418530532630718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803039078685945640e+01,5.790827316514272525e+02,3.142602757172857642e-01,1.100000010988609489e+01,2.418272545131093000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803129987775946574e+01,5.790927316221871024e+02,3.142844584191668011e-01,1.100000010988609489e+01,2.418126559729555283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803220896865947509e+01,5.791027315929504766e+02,3.143086396611980970e-01,1.100000010988609489e+01,2.417980574328017565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803311805955948444e+01,5.791127315637173751e+02,3.143328194433796519e-01,1.100000010988609489e+01,2.417834588926479848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803402715045949378e+01,5.791227315344877979e+02,3.143569977657114656e-01,1.100000010988609489e+01,2.417688603524942130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803493624135950313e+01,5.791327315052617450e+02,3.143811746281935382e-01,1.100000010988609489e+01,2.417542618123404412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803584533225951247e+01,5.791427314760392164e+02,3.144053500308258697e-01,1.100000010988609489e+01,2.417396632721866695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803675442315952182e+01,5.791527314468202121e+02,3.144295239736084047e-01,1.100000010988609489e+01,2.417250647320328977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803766351405953117e+01,5.791627314176047321e+02,3.144536964565411985e-01,1.100000010988609489e+01,2.417104661918791260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803857260495954051e+01,5.791727313883927764e+02,3.144778674796242512e-01,1.100000010988609489e+01,2.416958676517253542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.803948169585954986e+01,5.791827313591843449e+02,3.145020370428575629e-01,1.100000010988609489e+01,2.416812691115715825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804039078675955921e+01,5.791927313299794378e+02,3.145262051462411335e-01,1.100000010988609489e+01,2.416666705714178107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804129987765956855e+01,5.792027313007780549e+02,3.145503717897749629e-01,1.100000010988609489e+01,2.416520720312640390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804220896855957790e+01,5.792127312715801963e+02,3.145745369734589958e-01,1.100000010988609489e+01,2.416374734911102672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804311805945958724e+01,5.792227312423858621e+02,3.145987006972932876e-01,1.100000010988609489e+01,2.416228749509564955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804402715035959659e+01,5.792327312131950521e+02,3.146228629612778382e-01,1.100000010988609489e+01,2.416082764108027237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804493624125960594e+01,5.792427311840077664e+02,3.146470237654126478e-01,1.100000010988609489e+01,2.415936778706489520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804584533215961528e+01,5.792527311548240050e+02,3.146711831096976608e-01,1.100000010988609489e+01,2.415790793304951802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804675442305962463e+01,5.792627311256437679e+02,3.146953409941329327e-01,1.100000010988609489e+01,2.415644807903414085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804766351395963397e+01,5.792727310964670551e+02,3.147194974187184635e-01,1.100000010988609489e+01,2.415498822501876367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804857260485964332e+01,5.792827310672938665e+02,3.147436523834542532e-01,1.100000010988609489e+01,2.415352837100338650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.804948169575965267e+01,5.792927310381242023e+02,3.147678058883402463e-01,1.100000010988609489e+01,2.415206851698800932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805039078665966201e+01,5.793027310089580624e+02,3.147919579333764983e-01,1.100000010988609489e+01,2.415060866297263215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805129987755967136e+01,5.793127309797954467e+02,3.148161085185630093e-01,1.100000010988609489e+01,2.414914880895725497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805220896845968070e+01,5.793227309506363554e+02,3.148402576438997236e-01,1.100000010988609489e+01,2.414768895494187780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805311805935969005e+01,5.793327309214807883e+02,3.148644053093866968e-01,1.100000010988609489e+01,2.414622910092650062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805402715025969940e+01,5.793427308923287455e+02,3.148885515150239289e-01,1.100000010988609489e+01,2.414476924691112344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805493624115970874e+01,5.793527308631802271e+02,3.149126962608113645e-01,1.100000010988609489e+01,2.414330939289574627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805584533205971809e+01,5.793627308340352329e+02,3.149368395467490589e-01,1.100000010988609489e+01,2.414184953888036909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805675442295972744e+01,5.793727308048937630e+02,3.149609813728370122e-01,1.100000010988609489e+01,2.414038968486499192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805766351385973678e+01,5.793827307757558174e+02,3.149851217390751690e-01,1.100000010988609489e+01,2.413892983084961474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805857260475974613e+01,5.793927307466213961e+02,3.150092606454635846e-01,1.100000010988609489e+01,2.413746997683423757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.805948169565975547e+01,5.794027307174904990e+02,3.150333980920022592e-01,1.100000010988609489e+01,2.413601012281886039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806039078655976482e+01,5.794127306883631263e+02,3.150575340786911371e-01,1.100000010988609489e+01,2.413455026880348322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806129987745977417e+01,5.794227306592392779e+02,3.150816686055302740e-01,1.100000010988609489e+01,2.413309041478810604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806220896835978351e+01,5.794327306301189537e+02,3.151058016725196143e-01,1.100000010988609489e+01,2.413163056077272887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806311805925979286e+01,5.794427306010021539e+02,3.151299332796592134e-01,1.100000010988609489e+01,2.413017070675735169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806402715015980220e+01,5.794527305718888783e+02,3.151540634269490715e-01,1.100000010988609489e+01,2.412871085274197452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806493624105981155e+01,5.794627305427791271e+02,3.151781921143891330e-01,1.100000010988609489e+01,2.412725099872659734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806584533195982090e+01,5.794727305136729001e+02,3.152023193419794533e-01,1.100000010988609489e+01,2.412579114471122017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806675442285983024e+01,5.794827304845701974e+02,3.152264451097199771e-01,1.100000010988609489e+01,2.412433129069584299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806766351375983959e+01,5.794927304554710190e+02,3.152505694176107598e-01,1.100000010988609489e+01,2.412287143668046582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806857260465984893e+01,5.795027304263753649e+02,3.152746922656517459e-01,1.100000010988609489e+01,2.412141158266508864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.806948169555985828e+01,5.795127303972832351e+02,3.152988136538429909e-01,1.100000010988609489e+01,2.411995172864971147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807039078645986763e+01,5.795227303681946296e+02,3.153229335821844392e-01,1.100000010988609489e+01,2.411849187463433429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807129987735987697e+01,5.795327303391095484e+02,3.153470520506761465e-01,1.100000010988609489e+01,2.411703202061895712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807220896825988632e+01,5.795427303100279914e+02,3.153711690593180572e-01,1.100000010988609489e+01,2.411557216660357994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807311805915989567e+01,5.795527302809499588e+02,3.153952846081102268e-01,1.100000010988609489e+01,2.411411231258820276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807402715005990501e+01,5.795627302518754504e+02,3.154193986970525998e-01,1.100000010988609489e+01,2.411265245857282559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807493624095991436e+01,5.795727302228044664e+02,3.154435113261452317e-01,1.100000010988609489e+01,2.411119260455744841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807584533185992370e+01,5.795827301937370066e+02,3.154676224953880670e-01,1.100000010988609489e+01,2.410973275054207124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807675442275993305e+01,5.795927301646730712e+02,3.154917322047811612e-01,1.100000010988609489e+01,2.410827289652669406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807766351365994240e+01,5.796027301356126600e+02,3.155158404543244588e-01,1.100000010988609489e+01,2.410681304251131689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807857260455995174e+01,5.796127301065557731e+02,3.155399472440179598e-01,1.100000010988609489e+01,2.410535318849593971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.807948169545996109e+01,5.796227300775024105e+02,3.155640525738617197e-01,1.100000010988609489e+01,2.410389333448056254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808039078635997043e+01,5.796327300484525722e+02,3.155881564438556830e-01,1.100000010988609489e+01,2.410243348046518536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808129987725997978e+01,5.796427300194062582e+02,3.156122588539999052e-01,1.100000010988609489e+01,2.410097362644980819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808220896815998913e+01,5.796527299903634685e+02,3.156363598042943308e-01,1.100000010988609489e+01,2.409951377243443101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808311805905999847e+01,5.796627299613242030e+02,3.156604592947389598e-01,1.100000010988609489e+01,2.409805391841905384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808402714996000782e+01,5.796727299322884619e+02,3.156845573253338477e-01,1.100000010988609489e+01,2.409659406440367666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808493624086001716e+01,5.796827299032561314e+02,3.157086538960789390e-01,1.100000010988609489e+01,2.409513421038829949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808584533176002651e+01,5.796927298742273251e+02,3.157327490069742337e-01,1.100000010988609489e+01,2.409367435637292231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808675442266003586e+01,5.797027298452020432e+02,3.157568426580197873e-01,1.100000010988609489e+01,2.409221450235754514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808766351356004520e+01,5.797127298161802855e+02,3.157809348492155443e-01,1.100000010988609489e+01,2.409075464834216796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808857260446005455e+01,5.797227297871620522e+02,3.158050255805615047e-01,1.100000010988609489e+01,2.408929479432679079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.808948169536006390e+01,5.797327297581473431e+02,3.158291148520577241e-01,1.100000010988609489e+01,2.408783494031141361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809039078626007324e+01,5.797427297291361583e+02,3.158532026637041468e-01,1.100000010988609489e+01,2.408637508629603644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809129987716008259e+01,5.797527297001284978e+02,3.158772890155007729e-01,1.100000010988609489e+01,2.408491523228065926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809220896806009193e+01,5.797627296711243616e+02,3.159013739074476579e-01,1.100000010988609489e+01,2.408345537826528208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809311805896010128e+01,5.797727296421237497e+02,3.159254573395447463e-01,1.100000010988609489e+01,2.408199552424990491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809402714986011063e+01,5.797827296131266621e+02,3.159495393117920381e-01,1.100000010988609489e+01,2.408053567023452773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809493624076011997e+01,5.797927295841330988e+02,3.159736198241895333e-01,1.100000010988609489e+01,2.407907581621915056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809584533166012932e+01,5.798027295551430598e+02,3.159976988767372874e-01,1.100000010988609489e+01,2.407761596220377338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809675442256013866e+01,5.798127295261565450e+02,3.160217764694352449e-01,1.100000010988609489e+01,2.407615610818839621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809766351346014801e+01,5.798227294971734409e+02,3.160458526022834058e-01,1.100000010988609489e+01,2.407469625417301903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809857260436015736e+01,5.798327294681938611e+02,3.160699272752817701e-01,1.100000010988609489e+01,2.407323640015764186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.809948169526016670e+01,5.798427294392178055e+02,3.160940004884303933e-01,1.100000010988609489e+01,2.407177654614226468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810039078616017605e+01,5.798527294102452743e+02,3.161180722417292199e-01,1.100000010988609489e+01,2.407031669212688751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810129987706018539e+01,5.798627293812762673e+02,3.161421425351782499e-01,1.100000010988609489e+01,2.406885683811151033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810220896796019474e+01,5.798727293523107846e+02,3.161662113687774833e-01,1.100000010988609489e+01,2.406739698409613316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810311805886020409e+01,5.798827293233488263e+02,3.161902787425269201e-01,1.100000010988609489e+01,2.406593713008075598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810402714976021343e+01,5.798927292943903922e+02,3.162143446564265603e-01,1.100000010988609489e+01,2.406447727606537881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810493624066022278e+01,5.799027292654354824e+02,3.162384091104764594e-01,1.100000010988609489e+01,2.406301742205000163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810584533156023213e+01,5.799127292364840969e+02,3.162624721046765619e-01,1.100000010988609489e+01,2.406155756803462446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810675442246024147e+01,5.799227292075362357e+02,3.162865336390268678e-01,1.100000010988609489e+01,2.406009771401924728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810766351336025082e+01,5.799327291785917851e+02,3.163105937135273771e-01,1.100000010988609489e+01,2.405863786000387011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810857260426026016e+01,5.799427291496508587e+02,3.163346523281780898e-01,1.100000010988609489e+01,2.405717800598849293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.810948169516026951e+01,5.799527291207134567e+02,3.163587094829790058e-01,1.100000010988609489e+01,2.405571815197311576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811039078606027886e+01,5.799627290917795790e+02,3.163827651779301253e-01,1.100000010988609489e+01,2.405425829795773858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811129987696028820e+01,5.799727290628492256e+02,3.164068194130314482e-01,1.100000010988609489e+01,2.405279844394236140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811220896786029755e+01,5.799827290339223964e+02,3.164308721882830300e-01,1.100000010988609489e+01,2.405133858992698423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811311805876030689e+01,5.799927290049990916e+02,3.164549235036848152e-01,1.100000010988609489e+01,2.404987873591160705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811402714966031624e+01,5.800027289760793110e+02,3.164789733592368037e-01,1.100000010988609489e+01,2.404841888189622988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811493624056032559e+01,5.800127289471630547e+02,3.165030217549389957e-01,1.100000010988609489e+01,2.404695902788085270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811584533146033493e+01,5.800227289182502091e+02,3.165270686907913911e-01,1.100000010988609489e+01,2.404549917386547553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811675442236034428e+01,5.800327288893408877e+02,3.165511141667939898e-01,1.100000010988609489e+01,2.404403931985009835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811766351326035362e+01,5.800427288604350906e+02,3.165751581829467920e-01,1.100000010988609489e+01,2.404257946583472118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811857260416036297e+01,5.800527288315328178e+02,3.165992007392497976e-01,1.100000010988609489e+01,2.404111961181934400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.811948169506037232e+01,5.800627288026340693e+02,3.166232418357030065e-01,1.100000010988609489e+01,2.403965975780396683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812039078596038166e+01,5.800727287737388451e+02,3.166472814723064189e-01,1.100000010988609489e+01,2.403819990378858965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812129987686039101e+01,5.800827287448471452e+02,3.166713196490600346e-01,1.100000010988609489e+01,2.403674004977321248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812220896776040036e+01,5.800927287159589696e+02,3.166953563659638538e-01,1.100000010988609489e+01,2.403528019575783530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812311805866040970e+01,5.801027286870742046e+02,3.167193916230178763e-01,1.100000010988609489e+01,2.403382034174245813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812402714956041905e+01,5.801127286581929638e+02,3.167434254202221022e-01,1.100000010988609489e+01,2.403236048772708095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812493624046042839e+01,5.801227286293152474e+02,3.167674577575765316e-01,1.100000010988609489e+01,2.403090063371170378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812584533136043774e+01,5.801327286004410553e+02,3.167914886350811643e-01,1.100000010988609489e+01,2.402944077969632660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812675442226044709e+01,5.801427285715703874e+02,3.168155180527360004e-01,1.100000010988609489e+01,2.402798092568094943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812766351316045643e+01,5.801527285427032439e+02,3.168395460105409844e-01,1.100000010988609489e+01,2.402652107166557225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812857260406046578e+01,5.801627285138396246e+02,3.168635725084961718e-01,1.100000010988609489e+01,2.402506121765019508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.812948169496047512e+01,5.801727284849794160e+02,3.168875975466015626e-01,1.100000010988609489e+01,2.402360136363481790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813039078586048447e+01,5.801827284561227316e+02,3.169116211248571569e-01,1.100000010988609489e+01,2.402214150961944072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813129987676049382e+01,5.801927284272695715e+02,3.169356432432629544e-01,1.100000010988609489e+01,2.402068165560406355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813220896766050316e+01,5.802027283984199357e+02,3.169596639018189554e-01,1.100000010988609489e+01,2.401922180158868637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813311805856051251e+01,5.802127283695738242e+02,3.169836831005251598e-01,1.100000010988609489e+01,2.401776194757330920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813402714946052185e+01,5.802227283407312370e+02,3.170077008393815676e-01,1.100000010988609489e+01,2.401630209355793202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813493624036053120e+01,5.802327283118920604e+02,3.170317171183881233e-01,1.100000010988609489e+01,2.401484223954255485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813584533126054055e+01,5.802427282830564081e+02,3.170557319375448824e-01,1.100000010988609489e+01,2.401338238552717767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813675442216054989e+01,5.802527282542242801e+02,3.170797452968518448e-01,1.100000010988609489e+01,2.401192253151180050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813766351306055924e+01,5.802627282253956764e+02,3.171037571963090107e-01,1.100000010988609489e+01,2.401046267749642332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813857260396056859e+01,5.802727281965705970e+02,3.171277676359163800e-01,1.100000010988609489e+01,2.400900282348104615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.813948169486057793e+01,5.802827281677490419e+02,3.171517766156739526e-01,1.100000010988609489e+01,2.400754296946566897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814039078576058728e+01,5.802927281389308973e+02,3.171757841355816732e-01,1.100000010988609489e+01,2.400608311545029180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814129987666059662e+01,5.803027281101162771e+02,3.171997901956395971e-01,1.100000010988609489e+01,2.400462326143491462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814220896756060597e+01,5.803127280813051811e+02,3.172237947958477244e-01,1.100000010988609489e+01,2.400316340741953745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814311805846061532e+01,5.803227280524976095e+02,3.172477979362060552e-01,1.100000010988609489e+01,2.400170355340416027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814402714936062466e+01,5.803327280236935621e+02,3.172717996167145338e-01,1.100000010988609489e+01,2.400024369938878310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814493624026063401e+01,5.803427279948930391e+02,3.172957998373732158e-01,1.100000010988609489e+01,2.399878384537340592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814584533116064335e+01,5.803527279660959266e+02,3.173197985981821012e-01,1.100000010988609489e+01,2.399732399135802875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814675442206065270e+01,5.803627279373023384e+02,3.173437958991411900e-01,1.100000010988609489e+01,2.399586413734265157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814766351296066205e+01,5.803727279085122746e+02,3.173677917402504267e-01,1.100000010988609489e+01,2.399440428332727440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814857260386067139e+01,5.803827278797257350e+02,3.173917861215098668e-01,1.100000010988609489e+01,2.399294442931189722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.814948169476068074e+01,5.803927278509427197e+02,3.174157790429195103e-01,1.100000010988609489e+01,2.399148457529652004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815039078566069009e+01,5.804027278221631150e+02,3.174397705044793017e-01,1.100000010988609489e+01,2.399002472128114287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815129987656069943e+01,5.804127277933870346e+02,3.174637605061892964e-01,1.100000010988609489e+01,2.398856486726576569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815220896746070878e+01,5.804227277646144785e+02,3.174877490480494946e-01,1.100000010988609489e+01,2.398710501325038852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815311805836071812e+01,5.804327277358454467e+02,3.175117361300598962e-01,1.100000010988609489e+01,2.398564515923501134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815402714926072747e+01,5.804427277070799391e+02,3.175357217522204456e-01,1.100000010988609489e+01,2.398418530521963417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815493624016073682e+01,5.804527276783178422e+02,3.175597059145311984e-01,1.100000010988609489e+01,2.398272545120425699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815584533106074616e+01,5.804627276495592696e+02,3.175836886169920992e-01,1.100000010988609489e+01,2.398126559718887982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815675442196075551e+01,5.804727276208042213e+02,3.176076698596032033e-01,1.100000010988609489e+01,2.397980574317350264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815766351286076485e+01,5.804827275920526972e+02,3.176316496423645108e-01,1.100000010988609489e+01,2.397834588915812547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815857260376077420e+01,5.804927275633046975e+02,3.176556279652759662e-01,1.100000010988609489e+01,2.397688603514274829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.815948169466078355e+01,5.805027275345601083e+02,3.176796048283376250e-01,1.100000010988609489e+01,2.397542618112737112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816039078556079289e+01,5.805127275058190435e+02,3.177035802315494317e-01,1.100000010988609489e+01,2.397396632711199394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816129987646080224e+01,5.805227274770815029e+02,3.177275541749114418e-01,1.100000010988609489e+01,2.397250647309661677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816220896736081158e+01,5.805327274483474866e+02,3.177515266584236553e-01,1.100000010988609489e+01,2.397104661908123959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816311805826082093e+01,5.805427274196169947e+02,3.177754976820860167e-01,1.100000010988609489e+01,2.396958676506586242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816402714916083028e+01,5.805527273908899133e+02,3.177994672458985814e-01,1.100000010988609489e+01,2.396812691105048524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816493624006083962e+01,5.805627273621663562e+02,3.178234353498612941e-01,1.100000010988609489e+01,2.396666705703510807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816584533096084897e+01,5.805727273334463234e+02,3.178474019939742101e-01,1.100000010988609489e+01,2.396520720301973089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816675442186085832e+01,5.805827273047298149e+02,3.178713671782372741e-01,1.100000010988609489e+01,2.396374734900435371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816766351276086766e+01,5.805927272760167170e+02,3.178953309026505414e-01,1.100000010988609489e+01,2.396228749498897654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816857260366087701e+01,5.806027272473071434e+02,3.179192931672139566e-01,1.100000010988609489e+01,2.396082764097359936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.816948169456088635e+01,5.806127272186010941e+02,3.179432539719275752e-01,1.100000010988609489e+01,2.395936778695822219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817039078546089570e+01,5.806227271898985691e+02,3.179672133167913417e-01,1.100000010988609489e+01,2.395790793294284501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817129987636090505e+01,5.806327271611995684e+02,3.179911712018053116e-01,1.100000010988609489e+01,2.395644807892746784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817220896726091439e+01,5.806427271325039783e+02,3.180151276269694294e-01,1.100000010988609489e+01,2.395498822491209066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817311805816092374e+01,5.806527271038119125e+02,3.180390825922837506e-01,1.100000010988609489e+01,2.395352837089671349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817402714906093308e+01,5.806627270751233709e+02,3.180630360977482196e-01,1.100000010988609489e+01,2.395206851688133631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817493623996094243e+01,5.806727270464383537e+02,3.180869881433628921e-01,1.100000010988609489e+01,2.395060866286595914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817584533086095178e+01,5.806827270177567470e+02,3.181109387291277124e-01,1.100000010988609489e+01,2.394914880885058196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817675442176096112e+01,5.806927269890786647e+02,3.181348878550427361e-01,1.100000010988609489e+01,2.394768895483520479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817766351266097047e+01,5.807027269604041066e+02,3.181588355211079078e-01,1.100000010988609489e+01,2.394622910081982761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817857260356097981e+01,5.807127269317330729e+02,3.181827817273232273e-01,1.100000010988609489e+01,2.394476924680445044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.817948169446098916e+01,5.807227269030654497e+02,3.182067264736887502e-01,1.100000010988609489e+01,2.394330939278907326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818039078536099851e+01,5.807327268744013509e+02,3.182306697602044210e-01,1.100000010988609489e+01,2.394184953877369609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818129987626100785e+01,5.807427268457407763e+02,3.182546115868702952e-01,1.100000010988609489e+01,2.394038968475831891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818220896716101720e+01,5.807527268170837260e+02,3.182785519536863172e-01,1.100000010988609489e+01,2.393892983074294174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818311805806102655e+01,5.807627267884300863e+02,3.183024908606524872e-01,1.100000010988609489e+01,2.393746997672756456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818402714896103589e+01,5.807727267597799710e+02,3.183264283077688606e-01,1.100000010988609489e+01,2.393601012271218739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818493623986104524e+01,5.807827267311333799e+02,3.183503642950353818e-01,1.100000010988609489e+01,2.393455026869681021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818584533076105458e+01,5.807927267024903131e+02,3.183742988224520509e-01,1.100000010988609489e+01,2.393309041468143303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818675442166106393e+01,5.808027266738506569e+02,3.183982318900189235e-01,1.100000010988609489e+01,2.393163056066605586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818766351256107328e+01,5.808127266452145250e+02,3.184221634977359439e-01,1.100000010988609489e+01,2.393017070665067868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818857260346108262e+01,5.808227266165819174e+02,3.184460936456031122e-01,1.100000010988609489e+01,2.392871085263530151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.818948169436109197e+01,5.808327265879527204e+02,3.184700223336204838e-01,1.100000010988609489e+01,2.392725099861992433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819039078526110131e+01,5.808427265593270477e+02,3.184939495617880034e-01,1.100000010988609489e+01,2.392579114460454716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819129987616111066e+01,5.808527265307048992e+02,3.185178753301056709e-01,1.100000010988609489e+01,2.392433129058916998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819220896706112001e+01,5.808627265020862751e+02,3.185417996385734862e-01,1.100000010988609489e+01,2.392287143657379281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819311805796112935e+01,5.808727264734710616e+02,3.185657224871915050e-01,1.100000010988609489e+01,2.392141158255841563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819402714886113870e+01,5.808827264448593724e+02,3.185896438759596716e-01,1.100000010988609489e+01,2.391995172854303846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819493623976114804e+01,5.808927264162512074e+02,3.186135638048779861e-01,1.100000010988609489e+01,2.391849187452766128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819584533066115739e+01,5.809027263876464531e+02,3.186374822739464485e-01,1.100000010988609489e+01,2.391703202051228411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819675442156116674e+01,5.809127263590452230e+02,3.186613992831651143e-01,1.100000010988609489e+01,2.391557216649690693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819766351246117608e+01,5.809227263304475173e+02,3.186853148325339280e-01,1.100000010988609489e+01,2.391411231248152976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819857260336118543e+01,5.809327263018533358e+02,3.187092289220528896e-01,1.100000010988609489e+01,2.391265245846615258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.819948169426119478e+01,5.809427262732625650e+02,3.187331415517219990e-01,1.100000010988609489e+01,2.391119260445077541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820039078516120412e+01,5.809527262446753184e+02,3.187570527215412564e-01,1.100000010988609489e+01,2.390973275043539823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820129987606121347e+01,5.809627262160915961e+02,3.187809624315107171e-01,1.100000010988609489e+01,2.390827289642002106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820220896696122281e+01,5.809727261875112845e+02,3.188048706816303257e-01,1.100000010988609489e+01,2.390681304240464388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820311805786123216e+01,5.809827261589344971e+02,3.188287774719000822e-01,1.100000010988609489e+01,2.390535318838926671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820402714876124151e+01,5.809927261303612340e+02,3.188526828023199866e-01,1.100000010988609489e+01,2.390389333437388953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820493623966125085e+01,5.810027261017914952e+02,3.188765866728900389e-01,1.100000010988609489e+01,2.390243348035851235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820584533056126020e+01,5.810127260732251671e+02,3.189004890836102390e-01,1.100000010988609489e+01,2.390097362634313518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820675442146126954e+01,5.810227260446623632e+02,3.189243900344805871e-01,1.100000010988609489e+01,2.389951377232775800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820766351236127889e+01,5.810327260161030836e+02,3.189482895255011385e-01,1.100000010988609489e+01,2.389805391831238083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820857260326128824e+01,5.810427259875472146e+02,3.189721875566718379e-01,1.100000010988609489e+01,2.389659406429700365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.820948169416129758e+01,5.810527259589948699e+02,3.189960841279926851e-01,1.100000010988609489e+01,2.389513421028162648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821039078506130693e+01,5.810627259304460495e+02,3.190199792394636802e-01,1.100000010988609489e+01,2.389367435626624930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821129987596131627e+01,5.810727259019006397e+02,3.190438728910848232e-01,1.100000010988609489e+01,2.389221450225087213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821220896686132562e+01,5.810827258733587541e+02,3.190677650828561140e-01,1.100000010988609489e+01,2.389075464823549495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821311805776133497e+01,5.810927258448203929e+02,3.190916558147775528e-01,1.100000010988609489e+01,2.388929479422011778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821402714866134431e+01,5.811027258162854423e+02,3.191155450868491394e-01,1.100000010988609489e+01,2.388783494020474060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821493623956135366e+01,5.811127257877540160e+02,3.191394328990708740e-01,1.100000010988609489e+01,2.388637508618936343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821584533046136301e+01,5.811227257592261140e+02,3.191633192514427564e-01,1.100000010988609489e+01,2.388491523217398625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821675442136137235e+01,5.811327257307016225e+02,3.191872041439647867e-01,1.100000010988609489e+01,2.388345537815860908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821766351226138170e+01,5.811427257021806554e+02,3.192110875766369649e-01,1.100000010988609489e+01,2.388199552414323190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821857260316139104e+01,5.811527256736632125e+02,3.192349695494592909e-01,1.100000010988609489e+01,2.388053567012785473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.821948169406140039e+01,5.811627256451491803e+02,3.192588500624317649e-01,1.100000010988609489e+01,2.387907581611247755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822039078496140974e+01,5.811727256166386724e+02,3.192827291155543867e-01,1.100000010988609489e+01,2.387761596209710038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822129987586141908e+01,5.811827255881316887e+02,3.193066067088271565e-01,1.100000010988609489e+01,2.387615610808172320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822220896676142843e+01,5.811927255596281157e+02,3.193304828422500741e-01,1.100000010988609489e+01,2.387469625406634603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822311805766143777e+01,5.812027255311280669e+02,3.193543575158231396e-01,1.100000010988609489e+01,2.387323640005096885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822402714856144712e+01,5.812127255026315424e+02,3.193782307295463530e-01,1.100000010988609489e+01,2.387177654603559167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822493623946145647e+01,5.812227254741384286e+02,3.194021024834197142e-01,1.100000010988609489e+01,2.387031669202021450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822584533036146581e+01,5.812327254456488390e+02,3.194259727774432234e-01,1.100000010988609489e+01,2.386885683800483732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822675442126147516e+01,5.812427254171627737e+02,3.194498416116168804e-01,1.100000010988609489e+01,2.386739698398946015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822766351216148450e+01,5.812527253886801191e+02,3.194737089859406853e-01,1.100000010988609489e+01,2.386593712997408297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822857260306149385e+01,5.812627253602009887e+02,3.194975749004146381e-01,1.100000010988609489e+01,2.386447727595870580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.822948169396150320e+01,5.812727253317253826e+02,3.195214393550386833e-01,1.100000010988609489e+01,2.386301742194332862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823039078486151254e+01,5.812827253032531871e+02,3.195453023498128764e-01,1.100000010988609489e+01,2.386155756792795145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823129987576152189e+01,5.812927252747845159e+02,3.195691638847372174e-01,1.100000010988609489e+01,2.386009771391257427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823220896666153124e+01,5.813027252463193690e+02,3.195930239598117062e-01,1.100000010988609489e+01,2.385863785989719710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823311805756154058e+01,5.813127252178576327e+02,3.196168825750363429e-01,1.100000010988609489e+01,2.385717800588181992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823402714846154993e+01,5.813227251893994207e+02,3.196407397304111275e-01,1.100000010988609489e+01,2.385571815186644275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823493623936155927e+01,5.813327251609446193e+02,3.196645954259360600e-01,1.100000010988609489e+01,2.385425829785106557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823584533026156862e+01,5.813427251324933422e+02,3.196884496616110849e-01,1.100000010988609489e+01,2.385279844383568840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823675442116157797e+01,5.813527251040455894e+02,3.197123024374362577e-01,1.100000010988609489e+01,2.385133858982031122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823766351206158731e+01,5.813627250756012472e+02,3.197361537534115783e-01,1.100000010988609489e+01,2.384987873580493405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823857260296159666e+01,5.813727250471604293e+02,3.197600036095370468e-01,1.100000010988609489e+01,2.384841888178955687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.823948169386160600e+01,5.813827250187231357e+02,3.197838520058126632e-01,1.100000010988609489e+01,2.384695902777417970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824039078476161535e+01,5.813927249902892527e+02,3.198076989422383720e-01,1.100000010988609489e+01,2.384549917375880252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824129987566162470e+01,5.814027249618588939e+02,3.198315444188142287e-01,1.100000010988609489e+01,2.384403931974342535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824220896656163404e+01,5.814127249334319458e+02,3.198553884355402332e-01,1.100000010988609489e+01,2.384257946572804817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824311805746164339e+01,5.814227249050085220e+02,3.198792309924163857e-01,1.100000010988609489e+01,2.384111961171267099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824402714836165273e+01,5.814327248765886225e+02,3.199030720894426305e-01,1.100000010988609489e+01,2.383965975769729382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824493623926166208e+01,5.814427248481721335e+02,3.199269117266190232e-01,1.100000010988609489e+01,2.383819990368191664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824584533016167143e+01,5.814527248197591689e+02,3.199507499039455638e-01,1.100000010988609489e+01,2.383674004966653947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824675442106168077e+01,5.814627247913497285e+02,3.199745866214222523e-01,1.100000010988609489e+01,2.383528019565116229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824766351196169012e+01,5.814727247629436988e+02,3.199984218790490331e-01,1.100000010988609489e+01,2.383382034163578512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824857260286169947e+01,5.814827247345411934e+02,3.200222556768259619e-01,1.100000010988609489e+01,2.383236048762040794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.824948169376170881e+01,5.814927247061420985e+02,3.200460880147530385e-01,1.100000010988609489e+01,2.383090063360503077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825039078466171816e+01,5.815027246777465280e+02,3.200699188928302075e-01,1.100000010988609489e+01,2.382944077958965359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825129987556172750e+01,5.815127246493544817e+02,3.200937483110575243e-01,1.100000010988609489e+01,2.382798092557427642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825220896646173685e+01,5.815227246209658460e+02,3.201175762694349891e-01,1.100000010988609489e+01,2.382652107155889924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825311805736174620e+01,5.815327245925807347e+02,3.201414027679625462e-01,1.100000010988609489e+01,2.382506121754352207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825402714826175554e+01,5.815427245641990339e+02,3.201652278066402513e-01,1.100000010988609489e+01,2.382360136352814489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825493623916176489e+01,5.815527245358208575e+02,3.201890513854681042e-01,1.100000010988609489e+01,2.382214150951276772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825584533006177423e+01,5.815627245074462053e+02,3.202128735044460495e-01,1.100000010988609489e+01,2.382068165549739054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825675442096178358e+01,5.815727244790749637e+02,3.202366941635741426e-01,1.100000010988609489e+01,2.381922180148201337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825766351186179293e+01,5.815827244507072464e+02,3.202605133628523837e-01,1.100000010988609489e+01,2.381776194746663619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825857260276180227e+01,5.815927244223429398e+02,3.202843311022807171e-01,1.100000010988609489e+01,2.381630209345125902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.825948169366181162e+01,5.816027243939821574e+02,3.203081473818591984e-01,1.100000010988609489e+01,2.381484223943588184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826039078456182096e+01,5.816127243656247856e+02,3.203319622015877721e-01,1.100000010988609489e+01,2.381338238542050467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826129987546183031e+01,5.816227243372709381e+02,3.203557755614664937e-01,1.100000010988609489e+01,2.381192253140512749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826220896636183966e+01,5.816327243089206149e+02,3.203795874614953076e-01,1.100000010988609489e+01,2.381046267738975031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826311805726184900e+01,5.816427242805737023e+02,3.204033979016742695e-01,1.100000010988609489e+01,2.380900282337437314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826402714816185835e+01,5.816527242522303141e+02,3.204272068820033792e-01,1.100000010988609489e+01,2.380754296935899596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826493623906186770e+01,5.816627242238903364e+02,3.204510144024825813e-01,1.100000010988609489e+01,2.380608311534361879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826584532996187704e+01,5.816727241955538830e+02,3.204748204631119313e-01,1.100000010988609489e+01,2.380462326132824161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826675442086188639e+01,5.816827241672208402e+02,3.204986250638913736e-01,1.100000010988609489e+01,2.380316340731286444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826766351176189573e+01,5.816927241388913217e+02,3.205224282048209639e-01,1.100000010988609489e+01,2.380170355329748726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826857260266190508e+01,5.817027241105653275e+02,3.205462298859006465e-01,1.100000010988609489e+01,2.380024369928211009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.826948169356191443e+01,5.817127240822427439e+02,3.205700301071304770e-01,1.100000010988609489e+01,2.379878384526673291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827039078446192377e+01,5.817227240539236846e+02,3.205938288685103998e-01,1.100000010988609489e+01,2.379732399125135574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827129987536193312e+01,5.817327240256080358e+02,3.206176261700404706e-01,1.100000010988609489e+01,2.379586413723597856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827220896626194246e+01,5.817427239972959114e+02,3.206414220117206337e-01,1.100000010988609489e+01,2.379440428322060139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827311805716195181e+01,5.817527239689871976e+02,3.206652163935509448e-01,1.100000010988609489e+01,2.379294442920522421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827402714806196116e+01,5.817627239406820081e+02,3.206890093155313481e-01,1.100000010988609489e+01,2.379148457518984704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827493623896197050e+01,5.817727239123802292e+02,3.207128007776618439e-01,1.100000010988609489e+01,2.379002472117446986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827584532986197985e+01,5.817827238840819746e+02,3.207365907799424876e-01,1.100000010988609489e+01,2.378856486715909269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827675442076198919e+01,5.817927238557872442e+02,3.207603793223732236e-01,1.100000010988609489e+01,2.378710501314371551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827766351166199854e+01,5.818027238274959245e+02,3.207841664049541075e-01,1.100000010988609489e+01,2.378564515912833834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827857260256200789e+01,5.818127237992081291e+02,3.208079520276850838e-01,1.100000010988609489e+01,2.378418530511296116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.827948169346201723e+01,5.818227237709237443e+02,3.208317361905661524e-01,1.100000010988609489e+01,2.378272545109758399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828039078436202658e+01,5.818327237426428837e+02,3.208555188935973690e-01,1.100000010988609489e+01,2.378126559708220681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828129987526203593e+01,5.818427237143654338e+02,3.208793001367786779e-01,1.100000010988609489e+01,2.377980574306682963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828220896616204527e+01,5.818527236860915082e+02,3.209030799201101347e-01,1.100000010988609489e+01,2.377834588905145246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828311805706205462e+01,5.818627236578209931e+02,3.209268582435916839e-01,1.100000010988609489e+01,2.377688603503607528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828402714796206396e+01,5.818727236295540024e+02,3.209506351072233254e-01,1.100000010988609489e+01,2.377542618102069811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828493623886207331e+01,5.818827236012904223e+02,3.209744105110051149e-01,1.100000010988609489e+01,2.377396632700532093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828584532976208266e+01,5.818927235730303664e+02,3.209981844549369967e-01,1.100000010988609489e+01,2.377250647298994376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828675442066209200e+01,5.819027235447737212e+02,3.210219569390189709e-01,1.100000010988609489e+01,2.377104661897456658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828766351156210135e+01,5.819127235165206002e+02,3.210457279632510930e-01,1.100000010988609489e+01,2.376958676495918941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828857260246211069e+01,5.819227234882710036e+02,3.210694975276333074e-01,1.100000010988609489e+01,2.376812691094381223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.828948169336212004e+01,5.819327234600248175e+02,3.210932656321656142e-01,1.100000010988609489e+01,2.376666705692843506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829039078426212939e+01,5.819427234317821558e+02,3.211170322768480134e-01,1.100000010988609489e+01,2.376520720291305788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829129987516213873e+01,5.819527234035429046e+02,3.211407974616805605e-01,1.100000010988609489e+01,2.376374734889768071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829220896606214808e+01,5.819627233753071778e+02,3.211645611866632000e-01,1.100000010988609489e+01,2.376228749488230353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829311805696215743e+01,5.819727233470748615e+02,3.211883234517959318e-01,1.100000010988609489e+01,2.376082764086692636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829402714786216677e+01,5.819827233188460696e+02,3.212120842570787560e-01,1.100000010988609489e+01,2.375936778685154918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829493623876217612e+01,5.819927232906206882e+02,3.212358436025117281e-01,1.100000010988609489e+01,2.375790793283617201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829584532966218546e+01,5.820027232623988311e+02,3.212596014880947926e-01,1.100000010988609489e+01,2.375644807882079483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829675442056219481e+01,5.820127232341803847e+02,3.212833579138279494e-01,1.100000010988609489e+01,2.375498822480541766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829766351146220416e+01,5.820227232059654625e+02,3.213071128797111986e-01,1.100000010988609489e+01,2.375352837079004048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829857260236221350e+01,5.820327231777539509e+02,3.213308663857445957e-01,1.100000010988609489e+01,2.375206851677466331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.829948169326222285e+01,5.820427231495459637e+02,3.213546184319280852e-01,1.100000010988609489e+01,2.375060866275928613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830039078416223219e+01,5.820527231213413870e+02,3.213783690182616670e-01,1.100000010988609489e+01,2.374914880874390895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830129987506224154e+01,5.820627230931403346e+02,3.214021181447453412e-01,1.100000010988609489e+01,2.374768895472853178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830220896596225089e+01,5.820727230649426929e+02,3.214258658113791078e-01,1.100000010988609489e+01,2.374622910071315460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830311805686226023e+01,5.820827230367485754e+02,3.214496120181629668e-01,1.100000010988609489e+01,2.374476924669777743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830402714776226958e+01,5.820927230085578685e+02,3.214733567650969737e-01,1.100000010988609489e+01,2.374330939268240025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830493623866227892e+01,5.821027229803706859e+02,3.214971000521810729e-01,1.100000010988609489e+01,2.374184953866702308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830584532956228827e+01,5.821127229521869140e+02,3.215208418794152645e-01,1.100000010988609489e+01,2.374038968465164590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830675442046229762e+01,5.821227229240066663e+02,3.215445822467995485e-01,1.100000010988609489e+01,2.373892983063626873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830766351136230696e+01,5.821327228958298292e+02,3.215683211543339248e-01,1.100000010988609489e+01,2.373746997662089155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830857260226231631e+01,5.821427228676565164e+02,3.215920586020183936e-01,1.100000010988609489e+01,2.373601012260551438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.830948169316232566e+01,5.821527228394866142e+02,3.216157945898529547e-01,1.100000010988609489e+01,2.373455026859013720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831039078406233500e+01,5.821627228113202364e+02,3.216395291178376081e-01,1.100000010988609489e+01,2.373309041457476003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831129987496234435e+01,5.821727227831572691e+02,3.216632621859723540e-01,1.100000010988609489e+01,2.373163056055938285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831220896586235369e+01,5.821827227549977124e+02,3.216869937942571922e-01,1.100000010988609489e+01,2.373017070654400568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831311805676236304e+01,5.821927227268416800e+02,3.217107239426921228e-01,1.100000010988609489e+01,2.372871085252862850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831402714766237239e+01,5.822027226986890582e+02,3.217344526312771458e-01,1.100000010988609489e+01,2.372725099851325133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831493623856238173e+01,5.822127226705399607e+02,3.217581798600123166e-01,1.100000010988609489e+01,2.372579114449787415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831584532946239108e+01,5.822227226423942739e+02,3.217819056288975799e-01,1.100000010988609489e+01,2.372433129048249698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831675442036240042e+01,5.822327226142521113e+02,3.218056299379329355e-01,1.100000010988609489e+01,2.372287143646711980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831766351126240977e+01,5.822427225861133593e+02,3.218293527871183834e-01,1.100000010988609489e+01,2.372141158245174263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831857260216241912e+01,5.822527225579781316e+02,3.218530741764539238e-01,1.100000010988609489e+01,2.371995172843636545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.831948169306242846e+01,5.822627225298463145e+02,3.218767941059395565e-01,1.100000010988609489e+01,2.371849187442098827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832039078396243781e+01,5.822727225017180217e+02,3.219005125755752816e-01,1.100000010988609489e+01,2.371703202040561110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832129987486244715e+01,5.822827224735931395e+02,3.219242295853610436e-01,1.100000010988609489e+01,2.371557216639023392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832220896576245650e+01,5.822927224454717816e+02,3.219479451352968979e-01,1.100000010988609489e+01,2.371411231237485675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832311805666246585e+01,5.823027224173538343e+02,3.219716592253828447e-01,1.100000010988609489e+01,2.371265245835947957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832402714756247519e+01,5.823127223892392976e+02,3.219953718556188837e-01,1.100000010988609489e+01,2.371119260434410240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832493623846248454e+01,5.823227223611282852e+02,3.220190830260050152e-01,1.100000010988609489e+01,2.370973275032872522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832584532936249389e+01,5.823327223330206834e+02,3.220427927365412391e-01,1.100000010988609489e+01,2.370827289631334805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832675442026250323e+01,5.823427223049166059e+02,3.220665009872275553e-01,1.100000010988609489e+01,2.370681304229797087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832766351116251258e+01,5.823527222768159390e+02,3.220902077780639639e-01,1.100000010988609489e+01,2.370535318828259370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832857260206252192e+01,5.823627222487187964e+02,3.221139131090504648e-01,1.100000010988609489e+01,2.370389333426721652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.832948169296253127e+01,5.823727222206250644e+02,3.221376169801870581e-01,1.100000010988609489e+01,2.370243348025183935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833039078386254062e+01,5.823827221925348567e+02,3.221613193914737439e-01,1.100000010988609489e+01,2.370097362623646217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833129987476254996e+01,5.823927221644480596e+02,3.221850203429105219e-01,1.100000010988609489e+01,2.369951377222108500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833220896566255931e+01,5.824027221363646731e+02,3.222087198344973369e-01,1.100000010988609489e+01,2.369805391820570782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833311805656256865e+01,5.824127221082848109e+02,3.222324178662342442e-01,1.100000010988609489e+01,2.369659406419033065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833402714746257800e+01,5.824227220802083593e+02,3.222561144381212439e-01,1.100000010988609489e+01,2.369513421017495347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833493623836258735e+01,5.824327220521354320e+02,3.222798095501583360e-01,1.100000010988609489e+01,2.369367435615957630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833584532926259669e+01,5.824427220240659153e+02,3.223035032023455204e-01,1.100000010988609489e+01,2.369221450214419912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833675442016260604e+01,5.824527219959999229e+02,3.223271953946827972e-01,1.100000010988609489e+01,2.369075464812882195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833766351106261538e+01,5.824627219679373411e+02,3.223508861271701109e-01,1.100000010988609489e+01,2.368929479411344477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833857260196262473e+01,5.824727219398781699e+02,3.223745753998075170e-01,1.100000010988609489e+01,2.368783494009806759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.833948169286263408e+01,5.824827219118225230e+02,3.223982632125950154e-01,1.100000010988609489e+01,2.368637508608269042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834039078376264342e+01,5.824927218837702867e+02,3.224219495655326062e-01,1.100000010988609489e+01,2.368491523206731324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834129987466265277e+01,5.825027218557215747e+02,3.224456344586202894e-01,1.100000010988609489e+01,2.368345537805193607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834220896556266212e+01,5.825127218276762733e+02,3.224693178918580094e-01,1.100000010988609489e+01,2.368199552403655889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834311805646267146e+01,5.825227217996344962e+02,3.224929998652458218e-01,1.100000010988609489e+01,2.368053567002118172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834402714736268081e+01,5.825327217715961297e+02,3.225166803787837266e-01,1.100000010988609489e+01,2.367907581600580454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834493623826269015e+01,5.825427217435611738e+02,3.225403594324717238e-01,1.100000010988609489e+01,2.367761596199042737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834584532916269950e+01,5.825527217155297421e+02,3.225640370263097578e-01,1.100000010988609489e+01,2.367615610797505019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834675442006270885e+01,5.825627216875017211e+02,3.225877131602978842e-01,1.100000010988609489e+01,2.367469625395967302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834766351096271819e+01,5.825727216594772244e+02,3.226113878344361030e-01,1.100000010988609489e+01,2.367323639994429584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834857260186272754e+01,5.825827216314561383e+02,3.226350610487243586e-01,1.100000010988609489e+01,2.367177654592891867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.834948169276273688e+01,5.825927216034384628e+02,3.226587328031627067e-01,1.100000010988609489e+01,2.367031669191354149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835039078366274623e+01,5.826027215754243116e+02,3.226824030977511470e-01,1.100000010988609489e+01,2.366885683789816432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835129987456275558e+01,5.826127215474135710e+02,3.227060719324896243e-01,1.100000010988609489e+01,2.366739698388278714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835220896546276492e+01,5.826227215194063547e+02,3.227297393073781939e-01,1.100000010988609489e+01,2.366593712986740997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835311805636277427e+01,5.826327214914025490e+02,3.227534052224168559e-01,1.100000010988609489e+01,2.366447727585203279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835402714726278361e+01,5.826427214634021539e+02,3.227770696776055548e-01,1.100000010988609489e+01,2.366301742183665562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835493623816279296e+01,5.826527214354052830e+02,3.228007326729443460e-01,1.100000010988609489e+01,2.366155756782127844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835584532906280231e+01,5.826627214074118228e+02,3.228243942084332296e-01,1.100000010988609489e+01,2.366009771380590126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835675441996281165e+01,5.826727213794217732e+02,3.228480542840721501e-01,1.100000010988609489e+01,2.365863785979052409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835766351086282100e+01,5.826827213514352479e+02,3.228717128998611630e-01,1.100000010988609489e+01,2.365717800577514691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835857260176283035e+01,5.826927213234521332e+02,3.228953700558002127e-01,1.100000010988609489e+01,2.365571815175976974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.835948169266283969e+01,5.827027212954725428e+02,3.229190257518893548e-01,1.100000010988609489e+01,2.365425829774439256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836039078356284904e+01,5.827127212674963630e+02,3.229426799881285892e-01,1.100000010988609489e+01,2.365279844372901539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836129987446285838e+01,5.827227212395235938e+02,3.229663327645178605e-01,1.100000010988609489e+01,2.365133858971363821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836220896536286773e+01,5.827327212115543489e+02,3.229899840810572242e-01,1.100000010988609489e+01,2.364987873569826104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836311805626287708e+01,5.827427211835885146e+02,3.230136339377466248e-01,1.100000010988609489e+01,2.364841888168288386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836402714716288642e+01,5.827527211556260909e+02,3.230372823345861177e-01,1.100000010988609489e+01,2.364695902766750669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836493623806289577e+01,5.827627211276671915e+02,3.230609292715756475e-01,1.100000010988609489e+01,2.364549917365212951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836584532896290511e+01,5.827727210997117027e+02,3.230845747487152697e-01,1.100000010988609489e+01,2.364403931963675234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836675441986291446e+01,5.827827210717597382e+02,3.231082187660049287e-01,1.100000010988609489e+01,2.364257946562137516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836766351076292381e+01,5.827927210438111842e+02,3.231318613234446802e-01,1.100000010988609489e+01,2.364111961160599799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836857260166293315e+01,5.828027210158660409e+02,3.231555024210344684e-01,1.100000010988609489e+01,2.363965975759062081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.836948169256294250e+01,5.828127209879244219e+02,3.231791420587743491e-01,1.100000010988609489e+01,2.363819990357524364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837039078346295184e+01,5.828227209599862135e+02,3.232027802366642666e-01,1.100000010988609489e+01,2.363674004955986646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837129987436296119e+01,5.828327209320514157e+02,3.232264169547042765e-01,1.100000010988609489e+01,2.363528019554448929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837220896526297054e+01,5.828427209041201422e+02,3.232500522128943232e-01,1.100000010988609489e+01,2.363382034152911211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837311805616297988e+01,5.828527208761922793e+02,3.232736860112344623e-01,1.100000010988609489e+01,2.363236048751373494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837402714706298923e+01,5.828627208482678270e+02,3.232973183497246383e-01,1.100000010988609489e+01,2.363090063349835776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837493623796299858e+01,5.828727208203468990e+02,3.233209492283649067e-01,1.100000010988609489e+01,2.362944077948298058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837584532886300792e+01,5.828827207924293816e+02,3.233445786471552119e-01,1.100000010988609489e+01,2.362798092546760341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837675441976301727e+01,5.828927207645152748e+02,3.233682066060955540e-01,1.100000010988609489e+01,2.362652107145222623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837766351066302661e+01,5.829027207366046923e+02,3.233918331051859885e-01,1.100000010988609489e+01,2.362506121743684906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837857260156303596e+01,5.829127207086975204e+02,3.234154581444264598e-01,1.100000010988609489e+01,2.362360136342147188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.837948169246304531e+01,5.829227206807937591e+02,3.234390817238170235e-01,1.100000010988609489e+01,2.362214150940609471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838039078336305465e+01,5.829327206528935221e+02,3.234627038433576240e-01,1.100000010988609489e+01,2.362068165539071753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838129987426306400e+01,5.829427206249966957e+02,3.234863245030482615e-01,1.100000010988609489e+01,2.361922180137534036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838220896516307334e+01,5.829527205971032799e+02,3.235099437028889913e-01,1.100000010988609489e+01,2.361776194735996318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838311805606308269e+01,5.829627205692133884e+02,3.235335614428797579e-01,1.100000010988609489e+01,2.361630209334458601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838402714696309204e+01,5.829727205413269076e+02,3.235571777230205615e-01,1.100000010988609489e+01,2.361484223932920883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838493623786310138e+01,5.829827205134438373e+02,3.235807925433114574e-01,1.100000010988609489e+01,2.361338238531383166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838584532876311073e+01,5.829927204855642913e+02,3.236044059037523901e-01,1.100000010988609489e+01,2.361192253129845448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838675441966312007e+01,5.830027204576881559e+02,3.236280178043433597e-01,1.100000010988609489e+01,2.361046267728307731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838766351056312942e+01,5.830127204298154311e+02,3.236516282450844217e-01,1.100000010988609489e+01,2.360900282326770013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838857260146313877e+01,5.830227204019462306e+02,3.236752372259755206e-01,1.100000010988609489e+01,2.360754296925232296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.838948169236314811e+01,5.830327203740804407e+02,3.236988447470166563e-01,1.100000010988609489e+01,2.360608311523694578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839039078326315746e+01,5.830427203462180614e+02,3.237224508082078844e-01,1.100000010988609489e+01,2.360462326122156861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839129987416316681e+01,5.830527203183592064e+02,3.237460554095491494e-01,1.100000010988609489e+01,2.360316340720619143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839220896506317615e+01,5.830627202905037620e+02,3.237696585510404512e-01,1.100000010988609489e+01,2.360170355319081426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839311805596318550e+01,5.830727202626517283e+02,3.237932602326817899e-01,1.100000010988609489e+01,2.360024369917543708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839402714686319484e+01,5.830827202348032188e+02,3.238168604544732210e-01,1.100000010988609489e+01,2.359878384516005990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839493623776320419e+01,5.830927202069581199e+02,3.238404592164146889e-01,1.100000010988609489e+01,2.359732399114468273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839584532866321354e+01,5.831027201791164316e+02,3.238640565185061937e-01,1.100000010988609489e+01,2.359586413712930555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839675441956322288e+01,5.831127201512781539e+02,3.238876523607477353e-01,1.100000010988609489e+01,2.359440428311392838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839766351046323223e+01,5.831227201234434006e+02,3.239112467431393139e-01,1.100000010988609489e+01,2.359294442909855120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839857260136324157e+01,5.831327200956120578e+02,3.239348396656809848e-01,1.100000010988609489e+01,2.359148457508317403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.839948169226325092e+01,5.831427200677841256e+02,3.239584311283726925e-01,1.100000010988609489e+01,2.359002472106779685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840039078316326027e+01,5.831527200399597177e+02,3.239820211312144371e-01,1.100000010988609489e+01,2.358856486705241968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840129987406326961e+01,5.831627200121387204e+02,3.240056096742062186e-01,1.100000010988609489e+01,2.358710501303704250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840220896496327896e+01,5.831727199843211338e+02,3.240291967573480370e-01,1.100000010988609489e+01,2.358564515902166533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840311805586328830e+01,5.831827199565069577e+02,3.240527823806399477e-01,1.100000010988609489e+01,2.358418530500628815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840402714676329765e+01,5.831927199286963059e+02,3.240763665440818952e-01,1.100000010988609489e+01,2.358272545099091098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840493623766330700e+01,5.832027199008890648e+02,3.240999492476738797e-01,1.100000010988609489e+01,2.358126559697553380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840584532856331634e+01,5.832127198730852342e+02,3.241235304914159010e-01,1.100000010988609489e+01,2.357980574296015663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840675441946332569e+01,5.832227198452849279e+02,3.241471102753079592e-01,1.100000010988609489e+01,2.357834588894477945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840766351036333504e+01,5.832327198174880323e+02,3.241706885993500542e-01,1.100000010988609489e+01,2.357688603492940228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840857260126334438e+01,5.832427197896945472e+02,3.241942654635421861e-01,1.100000010988609489e+01,2.357542618091402510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.840948169216335373e+01,5.832527197619044728e+02,3.242178408678843549e-01,1.100000010988609489e+01,2.357396632689864793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841039078306336307e+01,5.832627197341179226e+02,3.242414148123765605e-01,1.100000010988609489e+01,2.357250647288327075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841129987396337242e+01,5.832727197063347830e+02,3.242649872970188585e-01,1.100000010988609489e+01,2.357104661886789358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841220896486338177e+01,5.832827196785550541e+02,3.242885583218111933e-01,1.100000010988609489e+01,2.356958676485251640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841311805576339111e+01,5.832927196507788494e+02,3.243121278867535651e-01,1.100000010988609489e+01,2.356812691083713922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841402714666340046e+01,5.833027196230060554e+02,3.243356959918459737e-01,1.100000010988609489e+01,2.356666705682176205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841493623756340980e+01,5.833127195952366719e+02,3.243592626370884191e-01,1.100000010988609489e+01,2.356520720280638487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841584532846341915e+01,5.833227195674706991e+02,3.243828278224809014e-01,1.100000010988609489e+01,2.356374734879100770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841675441936342850e+01,5.833327195397082505e+02,3.244063915480234206e-01,1.100000010988609489e+01,2.356228749477563052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841766351026343784e+01,5.833427195119492126e+02,3.244299538137159766e-01,1.100000010988609489e+01,2.356082764076025335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841857260116344719e+01,5.833527194841935852e+02,3.244535146195585695e-01,1.100000010988609489e+01,2.355936778674487617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.841948169206345653e+01,5.833627194564413685e+02,3.244770739655511993e-01,1.100000010988609489e+01,2.355790793272949900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842039078296346588e+01,5.833727194286926760e+02,3.245006318516938659e-01,1.100000010988609489e+01,2.355644807871412182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842129987386347523e+01,5.833827194009473942e+02,3.245241882779865694e-01,1.100000010988609489e+01,2.355498822469874465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842220896476348457e+01,5.833927193732055230e+02,3.245477432444293098e-01,1.100000010988609489e+01,2.355352837068336747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842311805566349392e+01,5.834027193454670623e+02,3.245712967510220870e-01,1.100000010988609489e+01,2.355206851666799030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842402714656350327e+01,5.834127193177321260e+02,3.245948487977649011e-01,1.100000010988609489e+01,2.355060866265261312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842493623746351261e+01,5.834227192900006003e+02,3.246183993846576965e-01,1.100000010988609489e+01,2.354914880863723595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842584532836352196e+01,5.834327192622724851e+02,3.246419485117005288e-01,1.100000010988609489e+01,2.354768895462185877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842675441926353130e+01,5.834427192345477806e+02,3.246654961788933980e-01,1.100000010988609489e+01,2.354622910060648160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842766351016354065e+01,5.834527192068266004e+02,3.246890423862363040e-01,1.100000010988609489e+01,2.354476924659110442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842857260106355000e+01,5.834627191791088308e+02,3.247125871337292469e-01,1.100000010988609489e+01,2.354330939257572725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.842948169196355934e+01,5.834727191513944717e+02,3.247361304213722266e-01,1.100000010988609489e+01,2.354184953856035007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843039078286356869e+01,5.834827191236835233e+02,3.247596722491652432e-01,1.100000010988609489e+01,2.354038968454497290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843129987376357803e+01,5.834927190959759855e+02,3.247832126171082967e-01,1.100000010988609489e+01,2.353892983052959572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843220896466358738e+01,5.835027190682719720e+02,3.248067515252013870e-01,1.100000010988609489e+01,2.353746997651421854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843311805556359673e+01,5.835127190405713691e+02,3.248302889734445142e-01,1.100000010988609489e+01,2.353601012249884137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843402714646360607e+01,5.835227190128741768e+02,3.248538249618376228e-01,1.100000010988609489e+01,2.353455026848346419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843493623736361542e+01,5.835327189851803951e+02,3.248773594903807682e-01,1.100000010988609489e+01,2.353309041446808702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843584532826362476e+01,5.835427189574901377e+02,3.249008925590739505e-01,1.100000010988609489e+01,2.353163056045270984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843675441916363411e+01,5.835527189298032908e+02,3.249244241679171696e-01,1.100000010988609489e+01,2.353017070643733267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843766351006364346e+01,5.835627189021198546e+02,3.249479543169104256e-01,1.100000010988609489e+01,2.352871085242195549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843857260096365280e+01,5.835727188744398291e+02,3.249714830060536630e-01,1.100000010988609489e+01,2.352725099840657832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.843948169186366215e+01,5.835827188467632141e+02,3.249950102353469372e-01,1.100000010988609489e+01,2.352579114439120114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844039078276367150e+01,5.835927188190901234e+02,3.250185360047902483e-01,1.100000010988609489e+01,2.352433129037582397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844129987366368084e+01,5.836027187914204433e+02,3.250420603143835963e-01,1.100000010988609489e+01,2.352287143636044679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844220896456369019e+01,5.836127187637541738e+02,3.250655831641269811e-01,1.100000010988609489e+01,2.352141158234506962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844311805546369953e+01,5.836227187360913149e+02,3.250891045540203472e-01,1.100000010988609489e+01,2.351995172832969244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844402714636370888e+01,5.836327187084318666e+02,3.251126244840637503e-01,1.100000010988609489e+01,2.351849187431431527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844493623726371823e+01,5.836427186807759426e+02,3.251361429542571901e-01,1.100000010988609489e+01,2.351703202029893809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844584532816372757e+01,5.836527186531234292e+02,3.251596599646006669e-01,1.100000010988609489e+01,2.351557216628356092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844675441906373692e+01,5.836627186254743265e+02,3.251831755150941250e-01,1.100000010988609489e+01,2.351411231226818374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844766350996374626e+01,5.836727185978286343e+02,3.252066896057376200e-01,1.100000010988609489e+01,2.351265245825280657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844857260086375561e+01,5.836827185701863527e+02,3.252302022365311518e-01,1.100000010988609489e+01,2.351119260423742939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.844948169176376496e+01,5.836927185425475955e+02,3.252537134074746650e-01,1.100000010988609489e+01,2.350973275022205222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845039078266377430e+01,5.837027185149122488e+02,3.252772231185682150e-01,1.100000010988609489e+01,2.350827289620667504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845129987356378365e+01,5.837127184872803127e+02,3.253007313698118019e-01,1.100000010988609489e+01,2.350681304219129786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845220896446379300e+01,5.837227184596517873e+02,3.253242381612053702e-01,1.100000010988609489e+01,2.350535318817592069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845311805536380234e+01,5.837327184320266724e+02,3.253477434927489753e-01,1.100000010988609489e+01,2.350389333416054351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845402714626381169e+01,5.837427184044050819e+02,3.253712473644426173e-01,1.100000010988609489e+01,2.350243348014516634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845493623716382103e+01,5.837527183767869019e+02,3.253947497762862406e-01,1.100000010988609489e+01,2.350097362612978916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845584532806383038e+01,5.837627183491721325e+02,3.254182507282799008e-01,1.100000010988609489e+01,2.349951377211441199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845675441896383973e+01,5.837727183215607738e+02,3.254417502204235979e-01,1.100000010988609489e+01,2.349805391809903481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845766350986384907e+01,5.837827182939528257e+02,3.254652482527172763e-01,1.100000010988609489e+01,2.349659406408365764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845857260076385842e+01,5.837927182663482881e+02,3.254887448251609916e-01,1.100000010988609489e+01,2.349513421006828046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.845948169166386776e+01,5.838027182387472749e+02,3.255122399377546882e-01,1.100000010988609489e+01,2.349367435605290329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846039078256387711e+01,5.838127182111496722e+02,3.255357335904984217e-01,1.100000010988609489e+01,2.349221450203752611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846129987346388646e+01,5.838227181835554802e+02,3.255592257833921366e-01,1.100000010988609489e+01,2.349075464802214894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846220896436389580e+01,5.838327181559646988e+02,3.255827165164358883e-01,1.100000010988609489e+01,2.348929479400677176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846311805526390515e+01,5.838427181283773280e+02,3.256062057896296769e-01,1.100000010988609489e+01,2.348783493999139459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846402714616391449e+01,5.838527181007933677e+02,3.256296936029734468e-01,1.100000010988609489e+01,2.348637508597601741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846493623706392384e+01,5.838627180732129318e+02,3.256531799564672536e-01,1.100000010988609489e+01,2.348491523196064024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846584532796393319e+01,5.838727180456359065e+02,3.256766648501110417e-01,1.100000010988609489e+01,2.348345537794526306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846675441886394253e+01,5.838827180180622918e+02,3.257001482839048667e-01,1.100000010988609489e+01,2.348199552392988589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846766350976395188e+01,5.838927179904920877e+02,3.257236302578486731e-01,1.100000010988609489e+01,2.348053566991450871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846857260066396123e+01,5.839027179629252942e+02,3.257471107719425163e-01,1.100000010988609489e+01,2.347907581589913154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.846948169156397057e+01,5.839127179353619113e+02,3.257705898261863409e-01,1.100000010988609489e+01,2.347761596188375436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847039078246397992e+01,5.839227179078020527e+02,3.257940674205802023e-01,1.100000010988609489e+01,2.347615610786837718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847129987336398926e+01,5.839327178802456046e+02,3.258175435551240451e-01,1.100000010988609489e+01,2.347469625385300001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847220896426399861e+01,5.839427178526925672e+02,3.258410182298179247e-01,1.100000010988609489e+01,2.347323639983762283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847311805516400796e+01,5.839527178251429405e+02,3.258644914446617857e-01,1.100000010988609489e+01,2.347177654582224566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847402714606401730e+01,5.839627177975967243e+02,3.258879631996556836e-01,1.100000010988609489e+01,2.347031669180686848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847493623696402665e+01,5.839727177700539187e+02,3.259114334947995628e-01,1.100000010988609489e+01,2.346885683779149131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847584532786403599e+01,5.839827177425145237e+02,3.259349023300934234e-01,1.100000010988609489e+01,2.346739698377611413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847675441876404534e+01,5.839927177149786530e+02,3.259583697055373208e-01,1.100000010988609489e+01,2.346593712976073696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847766350966405469e+01,5.840027176874461929e+02,3.259818356211311996e-01,1.100000010988609489e+01,2.346447727574535978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847857260056406403e+01,5.840127176599171435e+02,3.260053000768751152e-01,1.100000010988609489e+01,2.346301742172998261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.847948169146407338e+01,5.840227176323915046e+02,3.260287630727690122e-01,1.100000010988609489e+01,2.346155756771460543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848039078236408272e+01,5.840327176048692763e+02,3.260522246088128906e-01,1.100000010988609489e+01,2.346009771369922826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848129987326409207e+01,5.840427175773504587e+02,3.260756846850068058e-01,1.100000010988609489e+01,2.345863785968385108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848220896416410142e+01,5.840527175498350516e+02,3.260991433013507024e-01,1.100000010988609489e+01,2.345717800566847391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848311805506411076e+01,5.840627175223230552e+02,3.261226004578446358e-01,1.100000010988609489e+01,2.345571815165309673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848402714596412011e+01,5.840727174948145830e+02,3.261460561544885506e-01,1.100000010988609489e+01,2.345425829763771956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848493623686412946e+01,5.840827174673095215e+02,3.261695103912824467e-01,1.100000010988609489e+01,2.345279844362234238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848584532776413880e+01,5.840927174398078705e+02,3.261929631682263797e-01,1.100000010988609489e+01,2.345133858960696521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848675441866414815e+01,5.841027174123096302e+02,3.262164144853202941e-01,1.100000010988609489e+01,2.344987873559158803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848766350956415749e+01,5.841127173848148004e+02,3.262398643425641898e-01,1.100000010988609489e+01,2.344841888157621086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848857260046416684e+01,5.841227173573233813e+02,3.262633127399581223e-01,1.100000010988609489e+01,2.344695902756083368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.848948169136417619e+01,5.841327173298353728e+02,3.262867596775020362e-01,1.100000010988609489e+01,2.344549917354545650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849039078226418553e+01,5.841427173023507748e+02,3.263102051551959315e-01,1.100000010988609489e+01,2.344403931953007933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849129987316419488e+01,5.841527172748695875e+02,3.263336491730398081e-01,1.100000010988609489e+01,2.344257946551470215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849220896406420422e+01,5.841627172473919245e+02,3.263570917310337216e-01,1.100000010988609489e+01,2.344111961149932498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849311805496421357e+01,5.841727172199176721e+02,3.263805328291776164e-01,1.100000010988609489e+01,2.343965975748394780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849402714586422292e+01,5.841827171924468303e+02,3.264039724674714926e-01,1.100000010988609489e+01,2.343819990346857063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849493623676423226e+01,5.841927171649793991e+02,3.264274106459153502e-01,1.100000010988609489e+01,2.343674004945319345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849584532766424161e+01,5.842027171375153785e+02,3.264508473645092446e-01,1.100000010988609489e+01,2.343528019543781628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849675441856425095e+01,5.842127171100547685e+02,3.264742826232531203e-01,1.100000010988609489e+01,2.343382034142243910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849766350946426030e+01,5.842227170825975691e+02,3.264977164221469774e-01,1.100000010988609489e+01,2.343236048740706193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849857260036426965e+01,5.842327170551437803e+02,3.265211487611908159e-01,1.100000010988609489e+01,2.343090063339168475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.849948169126427899e+01,5.842427170276934021e+02,3.265445796403846357e-01,1.100000010988609489e+01,2.342944077937630758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850039078216428834e+01,5.842527170002464345e+02,3.265680090597284924e-01,1.100000010988609489e+01,2.342798092536093040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850129987306429769e+01,5.842627169728028775e+02,3.265914370192223304e-01,1.100000010988609489e+01,2.342652107134555323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850220896396430703e+01,5.842727169453628449e+02,3.266148635188661498e-01,1.100000010988609489e+01,2.342506121733017605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850311805486431638e+01,5.842827169179262228e+02,3.266382885586599505e-01,1.100000010988609489e+01,2.342360136331479888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850402714576432572e+01,5.842927168904930113e+02,3.266617121386037326e-01,1.100000010988609489e+01,2.342214150929942170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850493623666433507e+01,5.843027168630632104e+02,3.266851342586974960e-01,1.100000010988609489e+01,2.342068165528404453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850584532756434442e+01,5.843127168356368202e+02,3.267085549189412963e-01,1.100000010988609489e+01,2.341922180126866735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850675441846435376e+01,5.843227168082138405e+02,3.267319741193350779e-01,1.100000010988609489e+01,2.341776194725329018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850766350936436311e+01,5.843327167807942715e+02,3.267553918598788409e-01,1.100000010988609489e+01,2.341630209323791300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850857260026437245e+01,5.843427167533781130e+02,3.267788081405725853e-01,1.100000010988609489e+01,2.341484223922253582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.850948169116438180e+01,5.843527167259653652e+02,3.268022229614163110e-01,1.100000010988609489e+01,2.341338238520715865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851039078206439115e+01,5.843627166985560279e+02,3.268256363224100181e-01,1.100000010988609489e+01,2.341192253119178147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851129987296440049e+01,5.843727166711501013e+02,3.268490482235537065e-01,1.100000010988609489e+01,2.341046267717640430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851220896386440984e+01,5.843827166437475853e+02,3.268724586648473762e-01,1.100000010988609489e+01,2.340900282316102712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851311805476441918e+01,5.843927166163484799e+02,3.268958676462910273e-01,1.100000010988609489e+01,2.340754296914564995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851402714566442853e+01,5.844027165889527851e+02,3.269192751678846598e-01,1.100000010988609489e+01,2.340608311513027277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851493623656443788e+01,5.844127165615606145e+02,3.269426812296282736e-01,1.100000010988609489e+01,2.340462326111489560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851584532746444722e+01,5.844227165341718546e+02,3.269660858315218688e-01,1.100000010988609489e+01,2.340316340709951842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851675441836445657e+01,5.844327165067865053e+02,3.269894889735654453e-01,1.100000010988609489e+01,2.340170355308414125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851766350926446592e+01,5.844427164794045666e+02,3.270128906557590587e-01,1.100000010988609489e+01,2.340024369906876407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851857260016447526e+01,5.844527164520260385e+02,3.270362908781026534e-01,1.100000010988609489e+01,2.339878384505338690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.851948169106448461e+01,5.844627164246509210e+02,3.270596896405962295e-01,1.100000010988609489e+01,2.339732399103800972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852039078196449395e+01,5.844727163972792141e+02,3.270830869432397314e-01,1.100000010988609489e+01,2.339586413702263255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852129987286450330e+01,5.844827163699109178e+02,3.271064827860332147e-01,1.100000010988609489e+01,2.339440428300725537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852220896376451265e+01,5.844927163425460321e+02,3.271298771689766793e-01,1.100000010988609489e+01,2.339294442899187820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852311805466452199e+01,5.845027163151845571e+02,3.271532700920701253e-01,1.100000010988609489e+01,2.339148457497650102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852402714556453134e+01,5.845127162878264926e+02,3.271766615553135527e-01,1.100000010988609489e+01,2.339002472096112385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852493623646454068e+01,5.845227162604718387e+02,3.272000515587069613e-01,1.100000010988609489e+01,2.338856486694574667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852584532736455003e+01,5.845327162331205955e+02,3.272234401022503514e-01,1.100000010988609489e+01,2.338710501293036950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852675441826455938e+01,5.845427162057727628e+02,3.272468271859437228e-01,1.100000010988609489e+01,2.338564515891499232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852766350916456872e+01,5.845527161784283408e+02,3.272702128097870755e-01,1.100000010988609489e+01,2.338418530489961514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852857260006457807e+01,5.845627161510873293e+02,3.272935969737804096e-01,1.100000010988609489e+01,2.338272545088423797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.852948169096458741e+01,5.845727161237497285e+02,3.273169796779237251e-01,1.100000010988609489e+01,2.338126559686886079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853039078186459676e+01,5.845827160964155382e+02,3.273403609222170219e-01,1.100000010988609489e+01,2.337980574285348362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853129987276460611e+01,5.845927160690847586e+02,3.273637407066603000e-01,1.100000010988609489e+01,2.337834588883810644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853220896366461545e+01,5.846027160417573896e+02,3.273871190312535595e-01,1.100000010988609489e+01,2.337688603482272927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853311805456462480e+01,5.846127160144334312e+02,3.274104958959967449e-01,1.100000010988609489e+01,2.337542618080735209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853402714546463415e+01,5.846227159871128833e+02,3.274338713008899115e-01,1.100000010988609489e+01,2.337396632679197492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853493623636464349e+01,5.846327159597957461e+02,3.274572452459330596e-01,1.100000010988609489e+01,2.337250647277659774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853584532726465284e+01,5.846427159324820195e+02,3.274806177311261890e-01,1.100000010988609489e+01,2.337104661876122057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853675441816466218e+01,5.846527159051717035e+02,3.275039887564692997e-01,1.100000010988609489e+01,2.336958676474584339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853766350906467153e+01,5.846627158778647981e+02,3.275273583219623919e-01,1.100000010988609489e+01,2.336812691073046622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853857259996468088e+01,5.846727158505613033e+02,3.275507264276054098e-01,1.100000010988609489e+01,2.336666705671508904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.853948169086469022e+01,5.846827158232612192e+02,3.275740930733984091e-01,1.100000010988609489e+01,2.336520720269971187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854039078176469957e+01,5.846927157959645456e+02,3.275974582593413897e-01,1.100000010988609489e+01,2.336374734868433469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854129987266470891e+01,5.847027157686712826e+02,3.276208219854343517e-01,1.100000010988609489e+01,2.336228749466895752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854220896356471826e+01,5.847127157413814302e+02,3.276441842516772951e-01,1.100000010988609489e+01,2.336082764065358034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854311805446472761e+01,5.847227157140949885e+02,3.276675450580701643e-01,1.100000010988609489e+01,2.335936778663820317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854402714536473695e+01,5.847327156868119573e+02,3.276909044046130148e-01,1.100000010988609489e+01,2.335790793262282599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854493623626474630e+01,5.847427156595323368e+02,3.277142622913058467e-01,1.100000010988609489e+01,2.335644807860744882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854584532716475564e+01,5.847527156322561268e+02,3.277376187181486600e-01,1.100000010988609489e+01,2.335498822459207164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854675441806476499e+01,5.847627156049833275e+02,3.277609736851413991e-01,1.100000010988609489e+01,2.335352837057669446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854766350896477434e+01,5.847727155777139387e+02,3.277843271922841195e-01,1.100000010988609489e+01,2.335206851656131729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854857259986478368e+01,5.847827155504479606e+02,3.278076792395768213e-01,1.100000010988609489e+01,2.335060866254594011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.854948169076479303e+01,5.847927155231853931e+02,3.278310298270194489e-01,1.100000010988609489e+01,2.334914880853056294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855039078166480238e+01,5.848027154959262361e+02,3.278543789546120579e-01,1.100000010988609489e+01,2.334768895451518576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855129987256481172e+01,5.848127154686704898e+02,3.278777266223546483e-01,1.100000010988609489e+01,2.334622910049980859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855220896346482107e+01,5.848227154414181541e+02,3.279010728302471644e-01,1.100000010988609489e+01,2.334476924648443141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855311805436483041e+01,5.848327154141692290e+02,3.279244175782896620e-01,1.100000010988609489e+01,2.334330939246905424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855402714526483976e+01,5.848427153869237145e+02,3.279477608664821409e-01,1.100000010988609489e+01,2.334184953845367706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855493623616484911e+01,5.848527153596816106e+02,3.279711026948245456e-01,1.100000010988609489e+01,2.334038968443829989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855584532706485845e+01,5.848627153324429173e+02,3.279944430633169317e-01,1.100000010988609489e+01,2.333892983042292271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855675441796486780e+01,5.848727153052076346e+02,3.280177819719592991e-01,1.100000010988609489e+01,2.333746997640754554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855766350886487714e+01,5.848827152779757625e+02,3.280411194207515924e-01,1.100000010988609489e+01,2.333601012239216836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855857259976488649e+01,5.848927152507473011e+02,3.280644554096938670e-01,1.100000010988609489e+01,2.333455026837679119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.855948169066489584e+01,5.849027152235222502e+02,3.280877899387861230e-01,1.100000010988609489e+01,2.333309041436141401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856039078156490518e+01,5.849127151963006099e+02,3.281111230080283048e-01,1.100000010988609489e+01,2.333163056034603684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856129987246491453e+01,5.849227151690823803e+02,3.281344546174204679e-01,1.100000010988609489e+01,2.333017070633065966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856220896336492387e+01,5.849327151418675612e+02,3.281577847669625569e-01,1.100000010988609489e+01,2.332871085231528249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856311805426493322e+01,5.849427151146561528e+02,3.281811134566546273e-01,1.100000010988609489e+01,2.332725099829990531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856402714516494257e+01,5.849527150874481549e+02,3.282044406864966235e-01,1.100000010988609489e+01,2.332579114428452813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856493623606495191e+01,5.849627150602435677e+02,3.282277664564886011e-01,1.100000010988609489e+01,2.332433129026915096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856584532696496126e+01,5.849727150330423910e+02,3.282510907666305600e-01,1.100000010988609489e+01,2.332287143625377378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856675441786497061e+01,5.849827150058446250e+02,3.282744136169224447e-01,1.100000010988609489e+01,2.332141158223839661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856766350876497995e+01,5.849927149786502696e+02,3.282977350073643108e-01,1.100000010988609489e+01,2.331995172822301943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856857259966498930e+01,5.850027149514593248e+02,3.283210549379561027e-01,1.100000010988609489e+01,2.331849187420764226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.856948169056499864e+01,5.850127149242717906e+02,3.283443734086978760e-01,1.100000010988609489e+01,2.331703202019226508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857039078146500799e+01,5.850227148970875533e+02,3.283676904195895752e-01,1.100000010988609489e+01,2.331557216617688791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857129987236501734e+01,5.850327148699067266e+02,3.283910059706312556e-01,1.100000010988609489e+01,2.331411231216151073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857220896326502668e+01,5.850427148427293105e+02,3.284143200618228620e-01,1.100000010988609489e+01,2.331265245814613356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857311805416503603e+01,5.850527148155553050e+02,3.284376326931644496e-01,1.100000010988609489e+01,2.331119260413075638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857402714506504537e+01,5.850627147883847101e+02,3.284609438646559632e-01,1.100000010988609489e+01,2.330973275011537921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857493623596505472e+01,5.850727147612175258e+02,3.284842535762974025e-01,1.100000010988609489e+01,2.330827289610000203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857584532686506407e+01,5.850827147340537522e+02,3.285075618280888232e-01,1.100000010988609489e+01,2.330681304208462486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857675441776507341e+01,5.850927147068933891e+02,3.285308686200301698e-01,1.100000010988609489e+01,2.330535318806924768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857766350866508276e+01,5.851027146797364367e+02,3.285541739521214977e-01,1.100000010988609489e+01,2.330389333405387051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857857259956509210e+01,5.851127146525828948e+02,3.285774778243627514e-01,1.100000010988609489e+01,2.330243348003849333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.857948169046510145e+01,5.851227146254327636e+02,3.286007802367539865e-01,1.100000010988609489e+01,2.330097362602311616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858039078136511080e+01,5.851327145982860429e+02,3.286240811892951474e-01,1.100000010988609489e+01,2.329951377200773898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858129987226512014e+01,5.851427145711427329e+02,3.286473806819862342e-01,1.100000010988609489e+01,2.329805391799236181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858220896316512949e+01,5.851527145440028335e+02,3.286706787148273023e-01,1.100000010988609489e+01,2.329659406397698463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858311805406513884e+01,5.851627145168662310e+02,3.286939752878182963e-01,1.100000010988609489e+01,2.329513420996160745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858402714496514818e+01,5.851727144897330390e+02,3.287172704009592161e-01,1.100000010988609489e+01,2.329367435594623028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858493623586515753e+01,5.851827144626032577e+02,3.287405640542501173e-01,1.100000010988609489e+01,2.329221450193085310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858584532676516687e+01,5.851927144354768870e+02,3.287638562476909443e-01,1.100000010988609489e+01,2.329075464791547593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858675441766517622e+01,5.852027144083539270e+02,3.287871469812816971e-01,1.100000010988609489e+01,2.328929479390009875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858766350856518557e+01,5.852127143812343775e+02,3.288104362550224313e-01,1.100000010988609489e+01,2.328783493988472158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858857259946519491e+01,5.852227143541182386e+02,3.288337240689130914e-01,1.100000010988609489e+01,2.328637508586934440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.858948169036520426e+01,5.852327143270055103e+02,3.288570104229536772e-01,1.100000010988609489e+01,2.328491523185396723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859039078126521360e+01,5.852427142998961926e+02,3.288802953171442445e-01,1.100000010988609489e+01,2.328345537783859005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859129987216522295e+01,5.852527142727902856e+02,3.289035787514847375e-01,1.100000010988609489e+01,2.328199552382321288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859220896306523230e+01,5.852627142456876754e+02,3.289268607259751565e-01,1.100000010988609489e+01,2.328053566980783570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859311805396524164e+01,5.852727142185884759e+02,3.289501412406155567e-01,1.100000010988609489e+01,2.327907581579245853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859402714486525099e+01,5.852827141914926870e+02,3.289734202954058828e-01,1.100000010988609489e+01,2.327761596177708135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859493623576526034e+01,5.852927141644003086e+02,3.289966978903461348e-01,1.100000010988609489e+01,2.327615610776170418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859584532666526968e+01,5.853027141373113409e+02,3.290199740254363125e-01,1.100000010988609489e+01,2.327469625374632700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859675441756527903e+01,5.853127141102257838e+02,3.290432487006764717e-01,1.100000010988609489e+01,2.327323639973094983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859766350846528837e+01,5.853227140831436373e+02,3.290665219160665567e-01,1.100000010988609489e+01,2.327177654571557265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859857259936529772e+01,5.853327140560649013e+02,3.290897936716065675e-01,1.100000010988609489e+01,2.327031669170019548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.859948169026530707e+01,5.853427140289895760e+02,3.291130639672965041e-01,1.100000010988609489e+01,2.326885683768481830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860039078116531641e+01,5.853527140019175476e+02,3.291363328031363666e-01,1.100000010988609489e+01,2.326739698366944113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860129987206532576e+01,5.853627139748489299e+02,3.291596001791262105e-01,1.100000010988609489e+01,2.326593712965406395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860220896296533510e+01,5.853727139477837227e+02,3.291828660952659802e-01,1.100000010988609489e+01,2.326447727563868677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860311805386534445e+01,5.853827139207219261e+02,3.292061305515556757e-01,1.100000010988609489e+01,2.326301742162330960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860402714476535380e+01,5.853927138936635401e+02,3.292293935479952971e-01,1.100000010988609489e+01,2.326155756760793242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860493623566536314e+01,5.854027138666085648e+02,3.292526550845848443e-01,1.100000010988609489e+01,2.326009771359255525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860584532656537249e+01,5.854127138395570000e+02,3.292759151613243174e-01,1.100000010988609489e+01,2.325863785957717807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860675441746538183e+01,5.854227138125088459e+02,3.292991737782137718e-01,1.100000010988609489e+01,2.325717800556180090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860766350836539118e+01,5.854327137854639886e+02,3.293224309352531520e-01,1.100000010988609489e+01,2.325571815154642372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860857259926540053e+01,5.854427137584225420e+02,3.293456866324424581e-01,1.100000010988609489e+01,2.325425829753104655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.860948169016540987e+01,5.854527137313845060e+02,3.293689408697816901e-01,1.100000010988609489e+01,2.325279844351566937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861039078106541922e+01,5.854627137043498806e+02,3.293921936472708478e-01,1.100000010988609489e+01,2.325133858950029220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861129987196542857e+01,5.854727136773186658e+02,3.294154449649099314e-01,1.100000010988609489e+01,2.324987873548491502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861220896286543791e+01,5.854827136502908616e+02,3.294386948226989409e-01,1.100000010988609489e+01,2.324841888146953785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861311805376544726e+01,5.854927136232664679e+02,3.294619432206378762e-01,1.100000010988609489e+01,2.324695902745416067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861402714466545660e+01,5.855027135962453713e+02,3.294851901587267373e-01,1.100000010988609489e+01,2.324549917343878350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861493623556546595e+01,5.855127135692276852e+02,3.295084356369655243e-01,1.100000010988609489e+01,2.324403931942340632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861584532646547530e+01,5.855227135422134097e+02,3.295316796553542371e-01,1.100000010988609489e+01,2.324257946540802915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861675441736548464e+01,5.855327135152025448e+02,3.295549222138929313e-01,1.100000010988609489e+01,2.324111961139265197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861766350826549399e+01,5.855427134881950906e+02,3.295781633125815513e-01,1.100000010988609489e+01,2.323965975737727480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861857259916550333e+01,5.855527134611910469e+02,3.296014029514200971e-01,1.100000010988609489e+01,2.323819990336189762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.861948169006551268e+01,5.855627134341904139e+02,3.296246411304085688e-01,1.100000010988609489e+01,2.323674004934652045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862039078096552203e+01,5.855727134071930777e+02,3.296478778495469664e-01,1.100000010988609489e+01,2.323528019533114327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862129987186553137e+01,5.855827133801991522e+02,3.296711131088352897e-01,1.100000010988609489e+01,2.323382034131576609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862220896276554072e+01,5.855927133532086373e+02,3.296943469082735390e-01,1.100000010988609489e+01,2.323236048730038892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862311805366555006e+01,5.856027133262215330e+02,3.297175792478617140e-01,1.100000010988609489e+01,2.323090063328501174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862402714456555941e+01,5.856127132992378392e+02,3.297408101275998149e-01,1.100000010988609489e+01,2.322944077926963457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862493623546556876e+01,5.856227132722575561e+02,3.297640395474877861e-01,1.100000010988609489e+01,2.322798092525425739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862584532636557810e+01,5.856327132452805699e+02,3.297872675075256832e-01,1.100000010988609489e+01,2.322652107123888022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862675441726558745e+01,5.856427132183069943e+02,3.298104940077135061e-01,1.100000010988609489e+01,2.322506121722350304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862766350816559680e+01,5.856527131913368294e+02,3.298337190480512549e-01,1.100000010988609489e+01,2.322360136320812587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862857259906560614e+01,5.856627131643700750e+02,3.298569426285389294e-01,1.100000010988609489e+01,2.322214150919274869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.862948168996561549e+01,5.856727131374067312e+02,3.298801647491765299e-01,1.100000010988609489e+01,2.322068165517737152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863039078086562483e+01,5.856827131104466844e+02,3.299033854099640561e-01,1.100000010988609489e+01,2.321922180116199434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863129987176563418e+01,5.856927130834900481e+02,3.299266046109015083e-01,1.100000010988609489e+01,2.321776194714661717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863220896266564353e+01,5.857027130565368225e+02,3.299498223519888862e-01,1.100000010988609489e+01,2.321630209313123999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863311805356565287e+01,5.857127130295870074e+02,3.299730386332261900e-01,1.100000010988609489e+01,2.321484223911586282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863402714446566222e+01,5.857227130026406030e+02,3.299962534546134196e-01,1.100000010988609489e+01,2.321338238510048564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863493623536567156e+01,5.857327129756976092e+02,3.300194668161505196e-01,1.100000010988609489e+01,2.321192253108510847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863584532626568091e+01,5.857427129487579123e+02,3.300426787178375454e-01,1.100000010988609489e+01,2.321046267706973129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863675441716569026e+01,5.857527129218216260e+02,3.300658891596744970e-01,1.100000010988609489e+01,2.320900282305435412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863766350806569960e+01,5.857627128948887503e+02,3.300890981416613745e-01,1.100000010988609489e+01,2.320754296903897694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863857259896570895e+01,5.857727128679592852e+02,3.301123056637981779e-01,1.100000010988609489e+01,2.320608311502359977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.863948168986571829e+01,5.857827128410332307e+02,3.301355117260849070e-01,1.100000010988609489e+01,2.320462326100822259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864039078076572764e+01,5.857927128141104731e+02,3.301587163285215065e-01,1.100000010988609489e+01,2.320316340699284541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864129987166573699e+01,5.858027127871911262e+02,3.301819194711080319e-01,1.100000010988609489e+01,2.320170355297746824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864220896256574633e+01,5.858127127602751898e+02,3.302051211538444830e-01,1.100000010988609489e+01,2.320024369896209106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864311805346575568e+01,5.858227127333626640e+02,3.302283213767308601e-01,1.100000010988609489e+01,2.319878384494671389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864402714436576503e+01,5.858327127064535489e+02,3.302515201397671629e-01,1.100000010988609489e+01,2.319732399093133671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864493623526577437e+01,5.858427126795477307e+02,3.302747174429533361e-01,1.100000010988609489e+01,2.319586413691595954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864584532616578372e+01,5.858527126526453230e+02,3.302979132862894351e-01,1.100000010988609489e+01,2.319440428290058236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864675441706579306e+01,5.858627126257463260e+02,3.303211076697754600e-01,1.100000010988609489e+01,2.319294442888520519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864766350796580241e+01,5.858727125988507396e+02,3.303443005934114107e-01,1.100000010988609489e+01,2.319148457486982801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864857259886581176e+01,5.858827125719584501e+02,3.303674920571972318e-01,1.100000010988609489e+01,2.319002472085445084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.864948168976582110e+01,5.858927125450695712e+02,3.303906820611329787e-01,1.100000010988609489e+01,2.318856486683907366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865039078066583045e+01,5.859027125181841029e+02,3.304138706052186514e-01,1.100000010988609489e+01,2.318710501282369649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865129987156583979e+01,5.859127124913020452e+02,3.304370576894541944e-01,1.100000010988609489e+01,2.318564515880831931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865220896246584914e+01,5.859227124644233982e+02,3.304602433138396633e-01,1.100000010988609489e+01,2.318418530479294214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865311805336585849e+01,5.859327124375480480e+02,3.304834274783750581e-01,1.100000010988609489e+01,2.318272545077756496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865402714426586783e+01,5.859427124106761084e+02,3.305066101830603231e-01,1.100000010988609489e+01,2.318126559676218779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865493623516587718e+01,5.859527123838075795e+02,3.305297914278955140e-01,1.100000010988609489e+01,2.317980574274681061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865584532606588652e+01,5.859627123569424612e+02,3.305529712128806308e-01,1.100000010988609489e+01,2.317834588873143344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865675441696589587e+01,5.859727123300806397e+02,3.305761495380156179e-01,1.100000010988609489e+01,2.317688603471605626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865766350786590522e+01,5.859827123032222289e+02,3.305993264033005308e-01,1.100000010988609489e+01,2.317542618070067909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865857259876591456e+01,5.859927122763672287e+02,3.306225018087353695e-01,1.100000010988609489e+01,2.317396632668530191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.865948168966592391e+01,5.860027122495156391e+02,3.306456757543200786e-01,1.100000010988609489e+01,2.317250647266992473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866039078056593326e+01,5.860127122226673464e+02,3.306688482400547135e-01,1.100000010988609489e+01,2.317104661865454756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866129987146594260e+01,5.860227121958224643e+02,3.306920192659392743e-01,1.100000010988609489e+01,2.316958676463917038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866220896236595195e+01,5.860327121689809928e+02,3.307151888319737054e-01,1.100000010988609489e+01,2.316812691062379321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866311805326596129e+01,5.860427121421429320e+02,3.307383569381580624e-01,1.100000010988609489e+01,2.316666705660841603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866402714416597064e+01,5.860527121153081680e+02,3.307615235844922896e-01,1.100000010988609489e+01,2.316520720259303886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866493623506597999e+01,5.860627120884768146e+02,3.307846887709764427e-01,1.100000010988609489e+01,2.316374734857766168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866584532596598933e+01,5.860727120616488719e+02,3.308078524976104662e-01,1.100000010988609489e+01,2.316228749456228451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866675441686599868e+01,5.860827120348243398e+02,3.308310147643944155e-01,1.100000010988609489e+01,2.316082764054690733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866766350776600802e+01,5.860927120080031045e+02,3.308541755713282906e-01,1.100000010988609489e+01,2.315936778653153016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866857259866601737e+01,5.861027119811852799e+02,3.308773349184120360e-01,1.100000010988609489e+01,2.315790793251615298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.866948168956602672e+01,5.861127119543708659e+02,3.309004928056457073e-01,1.100000010988609489e+01,2.315644807850077581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867039078046603606e+01,5.861227119275598625e+02,3.309236492330292490e-01,1.100000010988609489e+01,2.315498822448539863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867129987136604541e+01,5.861327119007521560e+02,3.309468042005627164e-01,1.100000010988609489e+01,2.315352837047002146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867220896226605475e+01,5.861427118739478601e+02,3.309699577082460542e-01,1.100000010988609489e+01,2.315206851645464428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867311805316606410e+01,5.861527118471469748e+02,3.309931097560793178e-01,1.100000010988609489e+01,2.315060866243926711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867402714406607345e+01,5.861627118203495002e+02,3.310162603440624518e-01,1.100000010988609489e+01,2.314914880842388993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867493623496608279e+01,5.861727117935553224e+02,3.310394094721955116e-01,1.100000010988609489e+01,2.314768895440851276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867584532586609214e+01,5.861827117667645553e+02,3.310625571404784417e-01,1.100000010988609489e+01,2.314622910039313558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867675441676610149e+01,5.861927117399771987e+02,3.310857033489112422e-01,1.100000010988609489e+01,2.314476924637775841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867766350766611083e+01,5.862027117131931391e+02,3.311088480974939685e-01,1.100000010988609489e+01,2.314330939236238123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867857259856612018e+01,5.862127116864124901e+02,3.311319913862265651e-01,1.100000010988609489e+01,2.314184953834700405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.867948168946612952e+01,5.862227116596352516e+02,3.311551332151090876e-01,1.100000010988609489e+01,2.314038968433162688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868039078036613887e+01,5.862327116328614238e+02,3.311782735841414804e-01,1.100000010988609489e+01,2.313892983031624970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868129987126614822e+01,5.862427116060908929e+02,3.312014124933237991e-01,1.100000010988609489e+01,2.313746997630087253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868220896216615756e+01,5.862527115793237726e+02,3.312245499426559880e-01,1.100000010988609489e+01,2.313601012228549535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868311805306616691e+01,5.862627115525600630e+02,3.312476859321380473e-01,1.100000010988609489e+01,2.313455026827011818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868402714396617625e+01,5.862727115257996502e+02,3.312708204617700325e-01,1.100000010988609489e+01,2.313309041425474100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868493623486618560e+01,5.862827114990426480e+02,3.312939535315518880e-01,1.100000010988609489e+01,2.313163056023936383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868584532576619495e+01,5.862927114722890565e+02,3.313170851414836138e-01,1.100000010988609489e+01,2.313017070622398665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868675441666620429e+01,5.863027114455388755e+02,3.313402152915652654e-01,1.100000010988609489e+01,2.312871085220860948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868766350756621364e+01,5.863127114187919915e+02,3.313633439817967874e-01,1.100000010988609489e+01,2.312725099819323230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868857259846622298e+01,5.863227113920485181e+02,3.313864712121782352e-01,1.100000010988609489e+01,2.312579114417785513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.868948168936623233e+01,5.863327113653084552e+02,3.314095969827095534e-01,1.100000010988609489e+01,2.312433129016247795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869039078026624168e+01,5.863427113385716893e+02,3.314327212933907418e-01,1.100000010988609489e+01,2.312287143614710078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869129987116625102e+01,5.863527113118383340e+02,3.314558441442218006e-01,1.100000010988609489e+01,2.312141158213172360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869220896206626037e+01,5.863627112851083893e+02,3.314789655352027853e-01,1.100000010988609489e+01,2.311995172811634643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869311805296626972e+01,5.863727112583817416e+02,3.315020854663336403e-01,1.100000010988609489e+01,2.311849187410096925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869402714386627906e+01,5.863827112316585044e+02,3.315252039376143656e-01,1.100000010988609489e+01,2.311703202008559208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869493623476628841e+01,5.863927112049386778e+02,3.315483209490450167e-01,1.100000010988609489e+01,2.311557216607021490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869584532566629775e+01,5.864027111782222619e+02,3.315714365006255382e-01,1.100000010988609489e+01,2.311411231205483773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869675441656630710e+01,5.864127111515091428e+02,3.315945505923559300e-01,1.100000010988609489e+01,2.311265245803946055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869766350746631645e+01,5.864227111247994344e+02,3.316176632242361921e-01,1.100000010988609489e+01,2.311119260402408337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869857259836632579e+01,5.864327110980931366e+02,3.316407743962663801e-01,1.100000010988609489e+01,2.310973275000870620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.869948168926633514e+01,5.864427110713901357e+02,3.316638841084464384e-01,1.100000010988609489e+01,2.310827289599332902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870039078016634448e+01,5.864527110446905454e+02,3.316869923607763671e-01,1.100000010988609489e+01,2.310681304197795185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870129987106635383e+01,5.864627110179943656e+02,3.317100991532561660e-01,1.100000010988609489e+01,2.310535318796257467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870220896196636318e+01,5.864727109913014829e+02,3.317332044858858908e-01,1.100000010988609489e+01,2.310389333394719750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870311805286637252e+01,5.864827109646120107e+02,3.317563083586654860e-01,1.100000010988609489e+01,2.310243347993182032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870402714376638187e+01,5.864927109379259491e+02,3.317794107715949514e-01,1.100000010988609489e+01,2.310097362591644315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870493623466639121e+01,5.865027109112431845e+02,3.318025117246742872e-01,1.100000010988609489e+01,2.309951377190106597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870584532556640056e+01,5.865127108845638304e+02,3.318256112179034933e-01,1.100000010988609489e+01,2.309805391788568880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870675441646640991e+01,5.865227108578878870e+02,3.318487092512825698e-01,1.100000010988609489e+01,2.309659406387031162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870766350736641925e+01,5.865327108312152404e+02,3.318718058248115721e-01,1.100000010988609489e+01,2.309513420985493445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870857259826642860e+01,5.865427108045460045e+02,3.318949009384904447e-01,1.100000010988609489e+01,2.309367435583955727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.870948168916643795e+01,5.865527107778801792e+02,3.319179945923191877e-01,1.100000010988609489e+01,2.309221450182418010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871039078006644729e+01,5.865627107512176508e+02,3.319410867862978010e-01,1.100000010988609489e+01,2.309075464780880292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871129987096645664e+01,5.865727107245585330e+02,3.319641775204262846e-01,1.100000010988609489e+01,2.308929479379342575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871220896186646598e+01,5.865827106979027121e+02,3.319872667947046385e-01,1.100000010988609489e+01,2.308783493977804857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871311805276647533e+01,5.865927106712503019e+02,3.320103546091328628e-01,1.100000010988609489e+01,2.308637508576267140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871402714366648468e+01,5.866027106446013022e+02,3.320334409637109574e-01,1.100000010988609489e+01,2.308491523174729422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871493623456649402e+01,5.866127106179555994e+02,3.320565258584389223e-01,1.100000010988609489e+01,2.308345537773191705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871584532546650337e+01,5.866227105913133073e+02,3.320796092933167576e-01,1.100000010988609489e+01,2.308199552371653987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871675441636651271e+01,5.866327105646744258e+02,3.321026912683445187e-01,1.100000010988609489e+01,2.308053566970116269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871766350726652206e+01,5.866427105380388412e+02,3.321257717835221501e-01,1.100000010988609489e+01,2.307907581568578552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871857259816653141e+01,5.866527105114066671e+02,3.321488508388496519e-01,1.100000010988609489e+01,2.307761596167040834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.871948168906654075e+01,5.866627104847779037e+02,3.321719284343270240e-01,1.100000010988609489e+01,2.307615610765503117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872039077996655010e+01,5.866727104581524372e+02,3.321950045699542664e-01,1.100000010988609489e+01,2.307469625363965399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872129987086655944e+01,5.866827104315303814e+02,3.322180792457313792e-01,1.100000010988609489e+01,2.307323639962427682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872220896176656879e+01,5.866927104049117361e+02,3.322411524616583622e-01,1.100000010988609489e+01,2.307177654560889964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872311805266657814e+01,5.867027103782963877e+02,3.322642242177352156e-01,1.100000010988609489e+01,2.307031669159352247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872402714356658748e+01,5.867127103516844500e+02,3.322872945139619394e-01,1.100000010988609489e+01,2.306885683757814529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872493623446659683e+01,5.867227103250758091e+02,3.323103633503385335e-01,1.100000010988609489e+01,2.306739698356276812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872584532536660618e+01,5.867327102984705789e+02,3.323334307268649979e-01,1.100000010988609489e+01,2.306593712954739094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872675441626661552e+01,5.867427102718687593e+02,3.323564966435413326e-01,1.100000010988609489e+01,2.306447727553201377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872766350716662487e+01,5.867527102452702366e+02,3.323795611003675377e-01,1.100000010988609489e+01,2.306301742151663659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872857259806663421e+01,5.867627102186751245e+02,3.324026240973436130e-01,1.100000010988609489e+01,2.306155756750125942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.872948168896664356e+01,5.867727101920833093e+02,3.324256856344695032e-01,1.100000010988609489e+01,2.306009771348588224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873039077986665291e+01,5.867827101654949047e+02,3.324487457117452638e-01,1.100000010988609489e+01,2.305863785947050507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873129987076666225e+01,5.867927101389099107e+02,3.324718043291708947e-01,1.100000010988609489e+01,2.305717800545512789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873220896166667160e+01,5.868027101123282137e+02,3.324948614867463959e-01,1.100000010988609489e+01,2.305571815143975072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873311805256668094e+01,5.868127100857499272e+02,3.325179171844717674e-01,1.100000010988609489e+01,2.305425829742437354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873402714346669029e+01,5.868227100591750514e+02,3.325409714223470092e-01,1.100000010988609489e+01,2.305279844340899637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873493623436669964e+01,5.868327100326034724e+02,3.325640242003721214e-01,1.100000010988609489e+01,2.305133858939361919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873584532526670898e+01,5.868427100060353041e+02,3.325870755185471039e-01,1.100000010988609489e+01,2.304987873537824201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873675441616671833e+01,5.868527099794704327e+02,3.326101253768719568e-01,1.100000010988609489e+01,2.304841888136286484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873766350706672768e+01,5.868627099529089719e+02,3.326331737753466800e-01,1.100000010988609489e+01,2.304695902734748766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873857259796673702e+01,5.868727099263509217e+02,3.326562207139712180e-01,1.100000010988609489e+01,2.304549917333211049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.873948168886674637e+01,5.868827098997961684e+02,3.326792661927456263e-01,1.100000010988609489e+01,2.304403931931673331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874039077976675571e+01,5.868927098732448258e+02,3.327023102116699049e-01,1.100000010988609489e+01,2.304257946530135614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874129987066676506e+01,5.869027098466967800e+02,3.327253527707440539e-01,1.100000010988609489e+01,2.304111961128597896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874220896156677441e+01,5.869127098201521449e+02,3.327483938699680732e-01,1.100000010988609489e+01,2.303965975727060179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874311805246678375e+01,5.869227097936108066e+02,3.327714335093419074e-01,1.100000010988609489e+01,2.303819990325522461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874402714336679310e+01,5.869327097670728790e+02,3.327944716888656118e-01,1.100000010988609489e+01,2.303674004923984744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874493623426680244e+01,5.869427097405383620e+02,3.328175084085391866e-01,1.100000010988609489e+01,2.303528019522447026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874584532516681179e+01,5.869527097140071419e+02,3.328405436683626317e-01,1.100000010988609489e+01,2.303382034120909309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874675441606682114e+01,5.869627096874793324e+02,3.328635774683359472e-01,1.100000010988609489e+01,2.303236048719371591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874766350696683048e+01,5.869727096609548198e+02,3.328866098084590774e-01,1.100000010988609489e+01,2.303090063317833874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874857259786683983e+01,5.869827096344337178e+02,3.329096406887320780e-01,1.100000010988609489e+01,2.302944077916296156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.874948168876684917e+01,5.869927096079160265e+02,3.329326701091549490e-01,1.100000010988609489e+01,2.302798092514758439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875039077966685852e+01,5.870027095814016320e+02,3.329556980697276902e-01,1.100000010988609489e+01,2.302652107113220721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875129987056686787e+01,5.870127095548906482e+02,3.329787245704502463e-01,1.100000010988609489e+01,2.302506121711683004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875220896146687721e+01,5.870227095283829613e+02,3.330017496113226727e-01,1.100000010988609489e+01,2.302360136310145286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875311805236688656e+01,5.870327095018786849e+02,3.330247731923449694e-01,1.100000010988609489e+01,2.302214150908607568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875402714326689591e+01,5.870427094753777055e+02,3.330477953135170810e-01,1.100000010988609489e+01,2.302068165507069851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875493623416690525e+01,5.870527094488801367e+02,3.330708159748390629e-01,1.100000010988609489e+01,2.301922180105532133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875584532506691460e+01,5.870627094223858649e+02,3.330938351763109151e-01,1.100000010988609489e+01,2.301776194703994416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875675441596692394e+01,5.870727093958950036e+02,3.331168529179326376e-01,1.100000010988609489e+01,2.301630209302456698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875766350686693329e+01,5.870827093694075529e+02,3.331398691997041750e-01,1.100000010988609489e+01,2.301484223900918981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875857259776694264e+01,5.870927093429233992e+02,3.331628840216255827e-01,1.100000010988609489e+01,2.301338238499381263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.875948168866695198e+01,5.871027093164426560e+02,3.331858973836968052e-01,1.100000010988609489e+01,2.301192253097843546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876039077956696133e+01,5.871127092899652098e+02,3.332089092859178980e-01,1.100000010988609489e+01,2.301046267696305828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876129987046697067e+01,5.871227092634911742e+02,3.332319197282888612e-01,1.100000010988609489e+01,2.300900282294768111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876220896136698002e+01,5.871327092370204355e+02,3.332549287108096392e-01,1.100000010988609489e+01,2.300754296893230393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876311805226698937e+01,5.871427092105531074e+02,3.332779362334802875e-01,1.100000010988609489e+01,2.300608311491692676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876402714316699871e+01,5.871527091840890762e+02,3.333009422963008062e-01,1.100000010988609489e+01,2.300462326090154958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876493623406700806e+01,5.871627091576284556e+02,3.333239468992711396e-01,1.100000010988609489e+01,2.300316340688617241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876584532496701740e+01,5.871727091311712456e+02,3.333469500423913434e-01,1.100000010988609489e+01,2.300170355287079523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876675441586702675e+01,5.871827091047173326e+02,3.333699517256613620e-01,1.100000010988609489e+01,2.300024369885541806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876766350676703610e+01,5.871927090782668301e+02,3.333929519490812510e-01,1.100000010988609489e+01,2.299878384484004088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876857259766704544e+01,5.872027090518196246e+02,3.334159507126509547e-01,1.100000010988609489e+01,2.299732399082466371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.876948168856705479e+01,5.872127090253758297e+02,3.334389480163705288e-01,1.100000010988609489e+01,2.299586413680928653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877039077946706414e+01,5.872227089989353317e+02,3.334619438602399732e-01,1.100000010988609489e+01,2.299440428279390936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877129987036707348e+01,5.872327089724982443e+02,3.334849382442592325e-01,1.100000010988609489e+01,2.299294442877853218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877220896126708283e+01,5.872427089460644538e+02,3.335079311684283621e-01,1.100000010988609489e+01,2.299148457476315500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877311805216709217e+01,5.872527089196340739e+02,3.335309226327473064e-01,1.100000010988609489e+01,2.299002472074777783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877402714306710152e+01,5.872627088932069910e+02,3.335539126372161212e-01,1.100000010988609489e+01,2.298856486673240065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877493623396711087e+01,5.872727088667833186e+02,3.335769011818347507e-01,1.100000010988609489e+01,2.298710501271702348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877584532486712021e+01,5.872827088403629432e+02,3.335998882666032506e-01,1.100000010988609489e+01,2.298564515870164630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877675441576712956e+01,5.872927088139459784e+02,3.336228738915215652e-01,1.100000010988609489e+01,2.298418530468626913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877766350666713890e+01,5.873027087875323105e+02,3.336458580565897503e-01,1.100000010988609489e+01,2.298272545067089195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877857259756714825e+01,5.873127087611220531e+02,3.336688407618077501e-01,1.100000010988609489e+01,2.298126559665551478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.877948168846715760e+01,5.873227087347150928e+02,3.336918220071755647e-01,1.100000010988609489e+01,2.297980574264013760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878039077936716694e+01,5.873327087083115430e+02,3.337148017926932497e-01,1.100000010988609489e+01,2.297834588862476043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878129987026717629e+01,5.873427086819112901e+02,3.337377801183607495e-01,1.100000010988609489e+01,2.297688603460938325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878220896116718563e+01,5.873527086555144479e+02,3.337607569841781197e-01,1.100000010988609489e+01,2.297542618059400608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878311805206719498e+01,5.873627086291209025e+02,3.337837323901453046e-01,1.100000010988609489e+01,2.297396632657862890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878402714296720433e+01,5.873727086027307678e+02,3.338067063362623599e-01,1.100000010988609489e+01,2.297250647256325173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878493623386721367e+01,5.873827085763439300e+02,3.338296788225292300e-01,1.100000010988609489e+01,2.297104661854787455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878584532476722302e+01,5.873927085499605028e+02,3.338526498489459149e-01,1.100000010988609489e+01,2.296958676453249738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878675441566723237e+01,5.874027085235803725e+02,3.338756194155124701e-01,1.100000010988609489e+01,2.296812691051712020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878766350656724171e+01,5.874127084972036528e+02,3.338985875222288402e-01,1.100000010988609489e+01,2.296666705650174303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878857259746725106e+01,5.874227084708302300e+02,3.339215541690950251e-01,1.100000010988609489e+01,2.296520720248636585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.878948168836726040e+01,5.874327084444602178e+02,3.339445193561110803e-01,1.100000010988609489e+01,2.296374734847098868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879039077926726975e+01,5.874427084180935026e+02,3.339674830832769503e-01,1.100000010988609489e+01,2.296228749445561150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879129987016727910e+01,5.874527083917301979e+02,3.339904453505926907e-01,1.100000010988609489e+01,2.296082764044023432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879220896106728844e+01,5.874627083653701902e+02,3.340134061580582459e-01,1.100000010988609489e+01,2.295936778642485715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879311805196729779e+01,5.874727083390135931e+02,3.340363655056736158e-01,1.100000010988609489e+01,2.295790793240947997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879402714286730713e+01,5.874827083126602929e+02,3.340593233934388007e-01,1.100000010988609489e+01,2.295644807839410280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879493623376731648e+01,5.874927082863104033e+02,3.340822798213538558e-01,1.100000010988609489e+01,2.295498822437872562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879584532466732583e+01,5.875027082599638106e+02,3.341052347894187258e-01,1.100000010988609489e+01,2.295352837036334845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879675441556733517e+01,5.875127082336206286e+02,3.341281882976334106e-01,1.100000010988609489e+01,2.295206851634797127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879766350646734452e+01,5.875227082072807434e+02,3.341511403459979657e-01,1.100000010988609489e+01,2.295060866233259410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879857259736735386e+01,5.875327081809442689e+02,3.341740909345123356e-01,1.100000010988609489e+01,2.294914880831721692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.879948168826736321e+01,5.875427081546110912e+02,3.341970400631765203e-01,1.100000010988609489e+01,2.294768895430183975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880039077916737256e+01,5.875527081282813242e+02,3.342199877319905199e-01,1.100000010988609489e+01,2.294622910028646257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880129987006738190e+01,5.875627081019548541e+02,3.342429339409543898e-01,1.100000010988609489e+01,2.294476924627108540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880220896096739125e+01,5.875727080756317946e+02,3.342658786900680745e-01,1.100000010988609489e+01,2.294330939225570822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880311805186740060e+01,5.875827080493120320e+02,3.342888219793315741e-01,1.100000010988609489e+01,2.294184953824033105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880402714276740994e+01,5.875927080229955664e+02,3.343117638087448884e-01,1.100000010988609489e+01,2.294038968422495387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880493623366741929e+01,5.876027079966825113e+02,3.343347041783080731e-01,1.100000010988609489e+01,2.293892983020957670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880584532456742863e+01,5.876127079703727532e+02,3.343576430880210726e-01,1.100000010988609489e+01,2.293746997619419952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880675441546743798e+01,5.876227079440664056e+02,3.343805805378838869e-01,1.100000010988609489e+01,2.293601012217882235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880766350636744733e+01,5.876327079177633550e+02,3.344035165278965160e-01,1.100000010988609489e+01,2.293455026816344517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880857259726745667e+01,5.876427078914637150e+02,3.344264510580589600e-01,1.100000010988609489e+01,2.293309041414806800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.880948168816746602e+01,5.876527078651673719e+02,3.344493841283712188e-01,1.100000010988609489e+01,2.293163056013269082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881039077906747536e+01,5.876627078388744394e+02,3.344723157388333479e-01,1.100000010988609489e+01,2.293017070611731364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881129986996748471e+01,5.876727078125848038e+02,3.344952458894452918e-01,1.100000010988609489e+01,2.292871085210193647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881220896086749406e+01,5.876827077862985789e+02,3.345181745802070505e-01,1.100000010988609489e+01,2.292725099808655929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881311805176750340e+01,5.876927077600156508e+02,3.345411018111186241e-01,1.100000010988609489e+01,2.292579114407118212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881402714266751275e+01,5.877027077337360197e+02,3.345640275821800125e-01,1.100000010988609489e+01,2.292433129005580494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881493623356752209e+01,5.877127077074597992e+02,3.345869518933912157e-01,1.100000010988609489e+01,2.292287143604042777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881584532446753144e+01,5.877227076811868756e+02,3.346098747447522337e-01,1.100000010988609489e+01,2.292141158202505059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881675441536754079e+01,5.877327076549173626e+02,3.346327961362630665e-01,1.100000010988609489e+01,2.291995172800967342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881766350626755013e+01,5.877427076286511465e+02,3.346557160679237142e-01,1.100000010988609489e+01,2.291849187399429624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881857259716755948e+01,5.877527076023883410e+02,3.346786345397342322e-01,1.100000010988609489e+01,2.291703201997891907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.881948168806756883e+01,5.877627075761288324e+02,3.347015515516945650e-01,1.100000010988609489e+01,2.291557216596354189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882039077896757817e+01,5.877727075498726208e+02,3.347244671038047126e-01,1.100000010988609489e+01,2.291411231194816472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882129986986758752e+01,5.877827075236198198e+02,3.347473811960646750e-01,1.100000010988609489e+01,2.291265245793278754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882220896076759686e+01,5.877927074973703157e+02,3.347702938284744523e-01,1.100000010988609489e+01,2.291119260391741037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882311805166760621e+01,5.878027074711242221e+02,3.347932050010340443e-01,1.100000010988609489e+01,2.290973274990203319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882402714256761556e+01,5.878127074448814255e+02,3.348161147137434512e-01,1.100000010988609489e+01,2.290827289588665602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882493623346762490e+01,5.878227074186420396e+02,3.348390229666026729e-01,1.100000010988609489e+01,2.290681304187127884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882584532436763425e+01,5.878327073924059505e+02,3.348619297596117095e-01,1.100000010988609489e+01,2.290535318785590167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882675441526764359e+01,5.878427073661731583e+02,3.348848350927705608e-01,1.100000010988609489e+01,2.290389333384052449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882766350616765294e+01,5.878527073399437768e+02,3.349077389660792270e-01,1.100000010988609489e+01,2.290243347982514732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882857259706766229e+01,5.878627073137176922e+02,3.349306413795377080e-01,1.100000010988609489e+01,2.290097362580977014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.882948168796767163e+01,5.878727072874950181e+02,3.349535423331460038e-01,1.100000010988609489e+01,2.289951377179439296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883039077886768098e+01,5.878827072612756410e+02,3.349764418269041144e-01,1.100000010988609489e+01,2.289805391777901579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883129986976769032e+01,5.878927072350595608e+02,3.349993398608120398e-01,1.100000010988609489e+01,2.289659406376363861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883220896066769967e+01,5.879027072088468913e+02,3.350222364348697801e-01,1.100000010988609489e+01,2.289513420974826144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883311805156770902e+01,5.879127071826375186e+02,3.350451315490773352e-01,1.100000010988609489e+01,2.289367435573288426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883402714246771836e+01,5.879227071564315565e+02,3.350680252034346496e-01,1.100000010988609489e+01,2.289221450171750709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883493623336772771e+01,5.879327071302288914e+02,3.350909173979417788e-01,1.100000010988609489e+01,2.289075464770212991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883584532426773706e+01,5.879427071040295232e+02,3.351138081325987228e-01,1.100000010988609489e+01,2.288929479368675274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883675441516774640e+01,5.879527070778335656e+02,3.351366974074054816e-01,1.100000010988609489e+01,2.288783493967137556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883766350606775575e+01,5.879627070516409049e+02,3.351595852223620553e-01,1.100000010988609489e+01,2.288637508565599839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883857259696776509e+01,5.879727070254516548e+02,3.351824715774684438e-01,1.100000010988609489e+01,2.288491523164062121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.883948168786777444e+01,5.879827069992657016e+02,3.352053564727246471e-01,1.100000010988609489e+01,2.288345537762524404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884039077876778379e+01,5.879927069730830453e+02,3.352282399081306652e-01,1.100000010988609489e+01,2.288199552360986686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884129986966779313e+01,5.880027069469037997e+02,3.352511218836864426e-01,1.100000010988609489e+01,2.288053566959448969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884220896056780248e+01,5.880127069207278510e+02,3.352740023993920349e-01,1.100000010988609489e+01,2.287907581557911251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884311805146781182e+01,5.880227068945553128e+02,3.352968814552474419e-01,1.100000010988609489e+01,2.287761596156373534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884402714236782117e+01,5.880327068683860716e+02,3.353197590512526638e-01,1.100000010988609489e+01,2.287615610754835816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884493623326783052e+01,5.880427068422201273e+02,3.353426351874077005e-01,1.100000010988609489e+01,2.287469625353298099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884584532416783986e+01,5.880527068160575936e+02,3.353655098637125520e-01,1.100000010988609489e+01,2.287323639951760381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884675441506784921e+01,5.880627067898983569e+02,3.353883830801671628e-01,1.100000010988609489e+01,2.287177654550222664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884766350596785855e+01,5.880727067637424170e+02,3.354112548367715885e-01,1.100000010988609489e+01,2.287031669148684946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884857259686786790e+01,5.880827067375898878e+02,3.354341251335258289e-01,1.100000010988609489e+01,2.286885683747147228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.884948168776787725e+01,5.880927067114406555e+02,3.354569939704298842e-01,1.100000010988609489e+01,2.286739698345609511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885039077866788659e+01,5.881027066852947200e+02,3.354798613474837543e-01,1.100000010988609489e+01,2.286593712944071793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885129986956789594e+01,5.881127066591521952e+02,3.355027272646873837e-01,1.100000010988609489e+01,2.286447727542534076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885220896046790529e+01,5.881227066330129674e+02,3.355255917220408279e-01,1.100000010988609489e+01,2.286301742140996358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885311805136791463e+01,5.881327066068771501e+02,3.355484547195440870e-01,1.100000010988609489e+01,2.286155756739458641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885402714226792398e+01,5.881427065807446297e+02,3.355713162571971608e-01,1.100000010988609489e+01,2.286009771337920923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885493623316793332e+01,5.881527065546154063e+02,3.355941763349999940e-01,1.100000010988609489e+01,2.285863785936383206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885584532406794267e+01,5.881627065284895934e+02,3.356170349529526420e-01,1.100000010988609489e+01,2.285717800534845488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885675441496795202e+01,5.881727065023670775e+02,3.356398921110551048e-01,1.100000010988609489e+01,2.285571815133307771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885766350586796136e+01,5.881827064762478585e+02,3.356627478093073269e-01,1.100000010988609489e+01,2.285425829731770053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885857259676797071e+01,5.881927064501320501e+02,3.356856020477093638e-01,1.100000010988609489e+01,2.285279844330232336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.885948168766798005e+01,5.882027064240195386e+02,3.357084548262612156e-01,1.100000010988609489e+01,2.285133858928694618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886039077856798940e+01,5.882127063979103241e+02,3.357313061449628266e-01,1.100000010988609489e+01,2.284987873527156901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886129986946799875e+01,5.882227063718045201e+02,3.357541560038142525e-01,1.100000010988609489e+01,2.284841888125619183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886220896036800809e+01,5.882327063457020131e+02,3.357770044028154932e-01,1.100000010988609489e+01,2.284695902724081466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886311805126801744e+01,5.882427063196028030e+02,3.357998513419664932e-01,1.100000010988609489e+01,2.284549917322543748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886402714216802678e+01,5.882527062935070035e+02,3.358226968212673080e-01,1.100000010988609489e+01,2.284403931921006031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886493623306803613e+01,5.882627062674145009e+02,3.358455408407179377e-01,1.100000010988609489e+01,2.284257946519468313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886584532396804548e+01,5.882727062413252952e+02,3.358683834003183266e-01,1.100000010988609489e+01,2.284111961117930596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886675441486805482e+01,5.882827062152395001e+02,3.358912245000685304e-01,1.100000010988609489e+01,2.283965975716392878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886766350576806417e+01,5.882927061891570020e+02,3.359140641399684934e-01,1.100000010988609489e+01,2.283819990314855160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886857259666807352e+01,5.883027061630778007e+02,3.359369023200182713e-01,1.100000010988609489e+01,2.283674004913317443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.886948168756808286e+01,5.883127061370020101e+02,3.359597390402178640e-01,1.100000010988609489e+01,2.283528019511779725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887039077846809221e+01,5.883227061109295164e+02,3.359825743005672161e-01,1.100000010988609489e+01,2.283382034110242008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887129986936810155e+01,5.883327060848603196e+02,3.360054081010663829e-01,1.100000010988609489e+01,2.283236048708704290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887220896026811090e+01,5.883427060587945334e+02,3.360282404417153090e-01,1.100000010988609489e+01,2.283090063307166573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887311805116812025e+01,5.883527060327320442e+02,3.360510713225140500e-01,1.100000010988609489e+01,2.282944077905628855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887402714206812959e+01,5.883627060066728518e+02,3.360739007434625503e-01,1.100000010988609489e+01,2.282798092504091138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887493623296813894e+01,5.883727059806170701e+02,3.360967287045608654e-01,1.100000010988609489e+01,2.282652107102553420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887584532386814828e+01,5.883827059545645852e+02,3.361195552058089397e-01,1.100000010988609489e+01,2.282506121701015703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887675441476815763e+01,5.883927059285153973e+02,3.361423802472068290e-01,1.100000010988609489e+01,2.282360136299477985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887766350566816698e+01,5.884027059024696200e+02,3.361652038287544775e-01,1.100000010988609489e+01,2.282214150897940268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887857259656817632e+01,5.884127058764271396e+02,3.361880259504519408e-01,1.100000010988609489e+01,2.282068165496402550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.887948168746818567e+01,5.884227058503879562e+02,3.362108466122991635e-01,1.100000010988609489e+01,2.281922180094864833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888039077836819501e+01,5.884327058243520696e+02,3.362336658142962009e-01,1.100000010988609489e+01,2.281776194693327115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888129986926820436e+01,5.884427057983195937e+02,3.362564835564429977e-01,1.100000010988609489e+01,2.281630209291789398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888220896016821371e+01,5.884527057722904146e+02,3.362792998387396093e-01,1.100000010988609489e+01,2.281484223890251680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888311805106822305e+01,5.884627057462645325e+02,3.363021146611859802e-01,1.100000010988609489e+01,2.281338238488713963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888402714196823240e+01,5.884727057202420610e+02,3.363249280237821659e-01,1.100000010988609489e+01,2.281192253087176245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888493623286824175e+01,5.884827056942228865e+02,3.363477399265281109e-01,1.100000010988609489e+01,2.281046267685638528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888584532376825109e+01,5.884927056682070088e+02,3.363705503694238708e-01,1.100000010988609489e+01,2.280900282284100810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888675441466826044e+01,5.885027056421945417e+02,3.363933593524693899e-01,1.100000010988609489e+01,2.280754296882563092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888766350556826978e+01,5.885127056161853716e+02,3.364161668756646684e-01,1.100000010988609489e+01,2.280608311481025375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888857259646827913e+01,5.885227055901794984e+02,3.364389729390097616e-01,1.100000010988609489e+01,2.280462326079487657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.888948168736828848e+01,5.885327055641769221e+02,3.364617775425046142e-01,1.100000010988609489e+01,2.280316340677949940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889039077826829782e+01,5.885427055381777564e+02,3.364845806861492816e-01,1.100000010988609489e+01,2.280170355276412222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889129986916830717e+01,5.885527055121818876e+02,3.365073823699437083e-01,1.100000010988609489e+01,2.280024369874874505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889220896006831651e+01,5.885627054861893157e+02,3.365301825938878943e-01,1.100000010988609489e+01,2.279878384473336787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889311805096832586e+01,5.885727054602001544e+02,3.365529813579818952e-01,1.100000010988609489e+01,2.279732399071799070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889402714186833521e+01,5.885827054342142901e+02,3.365757786622256553e-01,1.100000010988609489e+01,2.279586413670261352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889493623276834455e+01,5.885927054082317227e+02,3.365985745066191748e-01,1.100000010988609489e+01,2.279440428268723635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889584532366835390e+01,5.886027053822524522e+02,3.366213688911625090e-01,1.100000010988609489e+01,2.279294442867185917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889675441456836325e+01,5.886127053562765923e+02,3.366441618158556026e-01,1.100000010988609489e+01,2.279148457465648200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889766350546837259e+01,5.886227053303040293e+02,3.366669532806984555e-01,1.100000010988609489e+01,2.279002472064110482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889857259636838194e+01,5.886327053043347632e+02,3.366897432856911232e-01,1.100000010988609489e+01,2.278856486662572765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.889948168726839128e+01,5.886427052783687941e+02,3.367125318308335502e-01,1.100000010988609489e+01,2.278710501261035047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890039077816840063e+01,5.886527052524062356e+02,3.367353189161257365e-01,1.100000010988609489e+01,2.278564515859497330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890129986906840998e+01,5.886627052264469739e+02,3.367581045415676821e-01,1.100000010988609489e+01,2.278418530457959612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890220895996841932e+01,5.886727052004910092e+02,3.367808887071594426e-01,1.100000010988609489e+01,2.278272545056421895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890311805086842867e+01,5.886827051745383415e+02,3.368036714129009623e-01,1.100000010988609489e+01,2.278126559654884177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890402714176843801e+01,5.886927051485890843e+02,3.368264526587922414e-01,1.100000010988609489e+01,2.277980574253346460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890493623266844736e+01,5.887027051226431240e+02,3.368492324448332798e-01,1.100000010988609489e+01,2.277834588851808742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890584532356845671e+01,5.887127050967004607e+02,3.368720107710241329e-01,1.100000010988609489e+01,2.277688603450271024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890675441446846605e+01,5.887227050707610942e+02,3.368947876373647454e-01,1.100000010988609489e+01,2.277542618048733307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890766350536847540e+01,5.887327050448251384e+02,3.369175630438551172e-01,1.100000010988609489e+01,2.277396632647195589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890857259626848474e+01,5.887427050188924795e+02,3.369403369904952483e-01,1.100000010988609489e+01,2.277250647245657872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.890948168716849409e+01,5.887527049929631175e+02,3.369631094772851387e-01,1.100000010988609489e+01,2.277104661844120154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891039077806850344e+01,5.887627049670370525e+02,3.369858805042248440e-01,1.100000010988609489e+01,2.276958676442582437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891129986896851278e+01,5.887727049411143980e+02,3.370086500713143085e-01,1.100000010988609489e+01,2.276812691041044719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891220895986852213e+01,5.887827049151950405e+02,3.370314181785535323e-01,1.100000010988609489e+01,2.276666705639507002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891311805076853148e+01,5.887927048892789799e+02,3.370541848259425155e-01,1.100000010988609489e+01,2.276520720237969284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891402714166854082e+01,5.888027048633662162e+02,3.370769500134812580e-01,1.100000010988609489e+01,2.276374734836431567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891493623256855017e+01,5.888127048374568631e+02,3.370997137411697597e-01,1.100000010988609489e+01,2.276228749434893849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891584532346855951e+01,5.888227048115508069e+02,3.371224760090080763e-01,1.100000010988609489e+01,2.276082764033356132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891675441436856886e+01,5.888327047856480476e+02,3.371452368169961522e-01,1.100000010988609489e+01,2.275936778631818414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891766350526857821e+01,5.888427047597485853e+02,3.371679961651339874e-01,1.100000010988609489e+01,2.275790793230280697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891857259616858755e+01,5.888527047338525335e+02,3.371907540534215819e-01,1.100000010988609489e+01,2.275644807828742979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.891948168706859690e+01,5.888627047079597787e+02,3.372135104818589357e-01,1.100000010988609489e+01,2.275498822427205262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892039077796860624e+01,5.888727046820703208e+02,3.372362654504460489e-01,1.100000010988609489e+01,2.275352837025667544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892129986886861559e+01,5.888827046561841598e+02,3.372590189591829213e-01,1.100000010988609489e+01,2.275206851624129827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892220895976862494e+01,5.888927046303012958e+02,3.372817710080695530e-01,1.100000010988609489e+01,2.275060866222592109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892311805066863428e+01,5.889027046044218423e+02,3.373045215971059441e-01,1.100000010988609489e+01,2.274914880821054392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892402714156864363e+01,5.889127045785456858e+02,3.373272707262920944e-01,1.100000010988609489e+01,2.274768895419516674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892493623246865297e+01,5.889227045526728261e+02,3.373500183956280041e-01,1.100000010988609489e+01,2.274622910017978956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892584532336866232e+01,5.889327045268032634e+02,3.373727646051137286e-01,1.100000010988609489e+01,2.274476924616441239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892675441426867167e+01,5.889427045009369976e+02,3.373955093547492123e-01,1.100000010988609489e+01,2.274330939214903521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892766350516868101e+01,5.889527044750741425e+02,3.374182526445344554e-01,1.100000010988609489e+01,2.274184953813365804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892857259606869036e+01,5.889627044492145842e+02,3.374409944744694578e-01,1.100000010988609489e+01,2.274038968411828086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.892948168696869971e+01,5.889727044233583229e+02,3.374637348445542195e-01,1.100000010988609489e+01,2.273892983010290369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893039077786870905e+01,5.889827043975053584e+02,3.374864737547887406e-01,1.100000010988609489e+01,2.273746997608752651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893129986876871840e+01,5.889927043716556909e+02,3.375092112051730209e-01,1.100000010988609489e+01,2.273601012207214934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893220895966872774e+01,5.890027043458094340e+02,3.375319471957070605e-01,1.100000010988609489e+01,2.273455026805677216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893311805056873709e+01,5.890127043199664740e+02,3.375546817263908039e-01,1.100000010988609489e+01,2.273309041404139499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893402714146874644e+01,5.890227042941268110e+02,3.375774147972243067e-01,1.100000010988609489e+01,2.273163056002601781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893493623236875578e+01,5.890327042682904448e+02,3.376001464082075687e-01,1.100000010988609489e+01,2.273017070601064064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893584532326876513e+01,5.890427042424573756e+02,3.376228765593405901e-01,1.100000010988609489e+01,2.272871085199526346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893675441416877447e+01,5.890527042166277170e+02,3.376456052506233707e-01,1.100000010988609489e+01,2.272725099797988629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893766350506878382e+01,5.890627041908013553e+02,3.376683324820559107e-01,1.100000010988609489e+01,2.272579114396450911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893857259596879317e+01,5.890727041649782905e+02,3.376910582536382099e-01,1.100000010988609489e+01,2.272433128994913194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.893948168686880251e+01,5.890827041391585226e+02,3.377137825653702685e-01,1.100000010988609489e+01,2.272287143593375476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894039077776881186e+01,5.890927041133420516e+02,3.377365054172520864e-01,1.100000010988609489e+01,2.272141158191837759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894129986866882120e+01,5.891027040875289913e+02,3.377592268092836636e-01,1.100000010988609489e+01,2.271995172790300041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894220895956883055e+01,5.891127040617192279e+02,3.377819467414650001e-01,1.100000010988609489e+01,2.271849187388762323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894311805046883990e+01,5.891227040359127614e+02,3.378046652137960959e-01,1.100000010988609489e+01,2.271703201987224606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894402714136884924e+01,5.891327040101095918e+02,3.378273822262768955e-01,1.100000010988609489e+01,2.271557216585686888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894493623226885859e+01,5.891427039843097191e+02,3.378500977789074544e-01,1.100000010988609489e+01,2.271411231184149171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894584532316886794e+01,5.891527039585131433e+02,3.378728118716877726e-01,1.100000010988609489e+01,2.271265245782611453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894675441406887728e+01,5.891627039327199782e+02,3.378955245046178502e-01,1.100000010988609489e+01,2.271119260381073736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894766350496888663e+01,5.891727039069301100e+02,3.379182356776976870e-01,1.100000010988609489e+01,2.270973274979536018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894857259586889597e+01,5.891827038811435386e+02,3.379409453909272831e-01,1.100000010988609489e+01,2.270827289577998301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.894948168676890532e+01,5.891927038553602642e+02,3.379636536443065831e-01,1.100000010988609489e+01,2.270681304176460583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895039077766891467e+01,5.892027038295802868e+02,3.379863604378356423e-01,1.100000010988609489e+01,2.270535318774922866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895129986856892401e+01,5.892127038038036062e+02,3.380090657715144609e-01,1.100000010988609489e+01,2.270389333373385148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895220895946893336e+01,5.892227037780302226e+02,3.380317696453430387e-01,1.100000010988609489e+01,2.270243347971847431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895311805036894270e+01,5.892327037522602495e+02,3.380544720593213759e-01,1.100000010988609489e+01,2.270097362570309713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895402714126895205e+01,5.892427037264935734e+02,3.380771730134494168e-01,1.100000010988609489e+01,2.269951377168771996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895493623216896140e+01,5.892527037007301942e+02,3.380998725077272171e-01,1.100000010988609489e+01,2.269805391767234278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895584532306897074e+01,5.892627036749701119e+02,3.381225705421547767e-01,1.100000010988609489e+01,2.269659406365696561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895675441396898009e+01,5.892727036492133266e+02,3.381452671167320956e-01,1.100000010988609489e+01,2.269513420964158843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895766350486898943e+01,5.892827036234598381e+02,3.381679622314591183e-01,1.100000010988609489e+01,2.269367435562621126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895857259576899878e+01,5.892927035977097603e+02,3.381906558863359002e-01,1.100000010988609489e+01,2.269221450161083408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.895948168666900813e+01,5.893027035719629794e+02,3.382133480813624415e-01,1.100000010988609489e+01,2.269075464759545691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896039077756901747e+01,5.893127035462194954e+02,3.382360388165386866e-01,1.100000010988609489e+01,2.268929479358007973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896129986846902682e+01,5.893227035204793083e+02,3.382587280918646910e-01,1.100000010988609489e+01,2.268783493956470255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896220895936903617e+01,5.893327034947424181e+02,3.382814159073404547e-01,1.100000010988609489e+01,2.268637508554932538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896311805026904551e+01,5.893427034690088249e+02,3.383041022629659778e-01,1.100000010988609489e+01,2.268491523153394820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896402714116905486e+01,5.893527034432785285e+02,3.383267871587412046e-01,1.100000010988609489e+01,2.268345537751857103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896493623206906420e+01,5.893627034175515291e+02,3.383494705946661907e-01,1.100000010988609489e+01,2.268199552350319385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896584532296907355e+01,5.893727033918279403e+02,3.383721525707409361e-01,1.100000010988609489e+01,2.268053566948781668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896675441386908290e+01,5.893827033661076484e+02,3.383948330869653853e-01,1.100000010988609489e+01,2.267907581547243950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896766350476909224e+01,5.893927033403906535e+02,3.384175121433395939e-01,1.100000010988609489e+01,2.267761596145706233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896857259566910159e+01,5.894027033146769554e+02,3.384401897398635062e-01,1.100000010988609489e+01,2.267615610744168515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.896948168656911093e+01,5.894127032889665543e+02,3.384628658765371778e-01,1.100000010988609489e+01,2.267469625342630798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897039077746912028e+01,5.894227032632594501e+02,3.384855405533606088e-01,1.100000010988609489e+01,2.267323639941093080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897129986836912963e+01,5.894327032375556428e+02,3.385082137703337435e-01,1.100000010988609489e+01,2.267177654539555363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897220895926913897e+01,5.894427032118551324e+02,3.385308855274566375e-01,1.100000010988609489e+01,2.267031669138017645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897311805016914832e+01,5.894527031861580326e+02,3.385535558247292354e-01,1.100000010988609489e+01,2.266885683736479928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897402714106915766e+01,5.894627031604642298e+02,3.385762246621515925e-01,1.100000010988609489e+01,2.266739698334942210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897493623196916701e+01,5.894727031347737238e+02,3.385988920397237090e-01,1.100000010988609489e+01,2.266593712933404493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897584532286917636e+01,5.894827031090865148e+02,3.386215579574455292e-01,1.100000010988609489e+01,2.266447727531866775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897675441376918570e+01,5.894927030834026027e+02,3.386442224153171088e-01,1.100000010988609489e+01,2.266301742130329058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897766350466919505e+01,5.895027030577219875e+02,3.386668854133383921e-01,1.100000010988609489e+01,2.266155756728791340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897857259556920440e+01,5.895127030320446693e+02,3.386895469515094348e-01,1.100000010988609489e+01,2.266009771327253623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.897948168646921374e+01,5.895227030063706479e+02,3.387122070298301812e-01,1.100000010988609489e+01,2.265863785925715905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898039077736922309e+01,5.895327029806999235e+02,3.387348656483006870e-01,1.100000010988609489e+01,2.265717800524178187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898129986826923243e+01,5.895427029550324960e+02,3.387575228069208966e-01,1.100000010988609489e+01,2.265571815122640470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898220895916924178e+01,5.895527029293684791e+02,3.387801785056908654e-01,1.100000010988609489e+01,2.265425829721102752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898311805006925113e+01,5.895627029037077591e+02,3.388028327446105381e-01,1.100000010988609489e+01,2.265279844319565035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898402714096926047e+01,5.895727028780503360e+02,3.388254855236799701e-01,1.100000010988609489e+01,2.265133858918027317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898493623186926982e+01,5.895827028523962099e+02,3.388481368428991058e-01,1.100000010988609489e+01,2.264987873516489600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898584532276927916e+01,5.895927028267453807e+02,3.388707867022680009e-01,1.100000010988609489e+01,2.264841888114951882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898675441366928851e+01,5.896027028010978484e+02,3.388934351017865998e-01,1.100000010988609489e+01,2.264695902713414165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898766350456929786e+01,5.896127027754536130e+02,3.389160820414549580e-01,1.100000010988609489e+01,2.264549917311876447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898857259546930720e+01,5.896227027498126745e+02,3.389387275212730199e-01,1.100000010988609489e+01,2.264403931910338730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.898948168636931655e+01,5.896327027241750329e+02,3.389613715412408412e-01,1.100000010988609489e+01,2.264257946508801012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899039077726932589e+01,5.896427026985406883e+02,3.389840141013583663e-01,1.100000010988609489e+01,2.264111961107263295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899129986816933524e+01,5.896527026729096406e+02,3.390066552016255952e-01,1.100000010988609489e+01,2.263965975705725577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899220895906934459e+01,5.896627026472818898e+02,3.390292948420425834e-01,1.100000010988609489e+01,2.263819990304187860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899311804996935393e+01,5.896727026216575496e+02,3.390519330226092753e-01,1.100000010988609489e+01,2.263674004902650142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899402714086936328e+01,5.896827025960365063e+02,3.390745697433257266e-01,1.100000010988609489e+01,2.263528019501112425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899493623176937263e+01,5.896927025704187599e+02,3.390972050041918817e-01,1.100000010988609489e+01,2.263382034099574707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899584532266938197e+01,5.897027025448043105e+02,3.391198388052077406e-01,1.100000010988609489e+01,2.263236048698036990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899675441356939132e+01,5.897127025191931580e+02,3.391424711463733588e-01,1.100000010988609489e+01,2.263090063296499272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899766350446940066e+01,5.897227024935853024e+02,3.391651020276886808e-01,1.100000010988609489e+01,2.262944077894961555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899857259536941001e+01,5.897327024679807437e+02,3.391877314491537065e-01,1.100000010988609489e+01,2.262798092493423837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.899948168626941936e+01,5.897427024423794819e+02,3.392103594107684916e-01,1.100000010988609489e+01,2.262652107091886119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900039077716942870e+01,5.897527024167815171e+02,3.392329859125329805e-01,1.100000010988609489e+01,2.262506121690348402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900129986806943805e+01,5.897627023911868491e+02,3.392556109544471732e-01,1.100000010988609489e+01,2.262360136288810684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900220895896944739e+01,5.897727023655954781e+02,3.392782345365111252e-01,1.100000010988609489e+01,2.262214150887272967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900311804986945674e+01,5.897827023400074040e+02,3.393008566587247810e-01,1.100000010988609489e+01,2.262068165485735249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900402714076946609e+01,5.897927023144226268e+02,3.393234773210881405e-01,1.100000010988609489e+01,2.261922180084197532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900493623166947543e+01,5.898027022888411466e+02,3.393460965236012039e-01,1.100000010988609489e+01,2.261776194682659814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900584532256948478e+01,5.898127022632629632e+02,3.393687142662640266e-01,1.100000010988609489e+01,2.261630209281122097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900675441346949412e+01,5.898227022376880768e+02,3.393913305490765531e-01,1.100000010988609489e+01,2.261484223879584379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900766350436950347e+01,5.898327022121164873e+02,3.394139453720387833e-01,1.100000010988609489e+01,2.261338238478046662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900857259526951282e+01,5.898427021865481947e+02,3.394365587351507729e-01,1.100000010988609489e+01,2.261192253076508944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.900948168616952216e+01,5.898527021609831991e+02,3.394591706384124663e-01,1.100000010988609489e+01,2.261046267674971227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901039077706953151e+01,5.898627021354216140e+02,3.394817810818238635e-01,1.100000010988609489e+01,2.260900282273433509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901129986796954086e+01,5.898727021098633259e+02,3.395043900653849644e-01,1.100000010988609489e+01,2.260754296871895792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901220895886955020e+01,5.898827020843083346e+02,3.395269975890957692e-01,1.100000010988609489e+01,2.260608311470358074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901311804976955955e+01,5.898927020587566403e+02,3.395496036529563333e-01,1.100000010988609489e+01,2.260462326068820357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901402714066956889e+01,5.899027020332082429e+02,3.395722082569666012e-01,1.100000010988609489e+01,2.260316340667282639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901493623156957824e+01,5.899127020076631425e+02,3.395948114011265728e-01,1.100000010988609489e+01,2.260170355265744922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901584532246958759e+01,5.899227019821213389e+02,3.396174130854362483e-01,1.100000010988609489e+01,2.260024369864207204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901675441336959693e+01,5.899327019565828323e+02,3.396400133098956275e-01,1.100000010988609489e+01,2.259878384462669487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901766350426960628e+01,5.899427019310476226e+02,3.396626120745047106e-01,1.100000010988609489e+01,2.259732399061131769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901857259516961562e+01,5.899527019055157098e+02,3.396852093792635530e-01,1.100000010988609489e+01,2.259586413659594051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.901948168606962497e+01,5.899627018799870939e+02,3.397078052241720991e-01,1.100000010988609489e+01,2.259440428258056334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902039077696963432e+01,5.899727018544617749e+02,3.397303996092303491e-01,1.100000010988609489e+01,2.259294442856518616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902129986786964366e+01,5.899827018289397529e+02,3.397529925344383028e-01,1.100000010988609489e+01,2.259148457454980899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902220895876965301e+01,5.899927018034210278e+02,3.397755839997959604e-01,1.100000010988609489e+01,2.259002472053443181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902311804966966235e+01,5.900027017779055996e+02,3.397981740053033217e-01,1.100000010988609489e+01,2.258856486651905464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902402714056967170e+01,5.900127017523934683e+02,3.398207625509603869e-01,1.100000010988609489e+01,2.258710501250367746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902493623146968105e+01,5.900227017268846339e+02,3.398433496367671558e-01,1.100000010988609489e+01,2.258564515848830029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902584532236969039e+01,5.900327017013790964e+02,3.398659352627236840e-01,1.100000010988609489e+01,2.258418530447292311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902675441326969974e+01,5.900427016758768559e+02,3.398885194288299161e-01,1.100000010988609489e+01,2.258272545045754594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902766350416970909e+01,5.900527016503779123e+02,3.399111021350858519e-01,1.100000010988609489e+01,2.258126559644216876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902857259506971843e+01,5.900627016248822656e+02,3.399336833814914915e-01,1.100000010988609489e+01,2.257980574242679159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.902948168596972778e+01,5.900727015993899158e+02,3.399562631680468350e-01,1.100000010988609489e+01,2.257834588841141441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903039077686973712e+01,5.900827015739008630e+02,3.399788414947518822e-01,1.100000010988609489e+01,2.257688603439603724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903129986776974647e+01,5.900927015484151070e+02,3.400014183616066332e-01,1.100000010988609489e+01,2.257542618038066006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903220895866975582e+01,5.901027015229326480e+02,3.400239937686110880e-01,1.100000010988609489e+01,2.257396632636528289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903311804956976516e+01,5.901127014974534859e+02,3.400465677157652467e-01,1.100000010988609489e+01,2.257250647234990571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903402714046977451e+01,5.901227014719776207e+02,3.400691402030691091e-01,1.100000010988609489e+01,2.257104661833452854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903493623136978385e+01,5.901327014465050524e+02,3.400917112305226753e-01,1.100000010988609489e+01,2.256958676431915136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903584532226979320e+01,5.901427014210357811e+02,3.401142807981259453e-01,1.100000010988609489e+01,2.256812691030377419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903675441316980255e+01,5.901527013955698067e+02,3.401368489058789191e-01,1.100000010988609489e+01,2.256666705628839701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903766350406981189e+01,5.901627013701071292e+02,3.401594155537815967e-01,1.100000010988609489e+01,2.256520720227301983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903857259496982124e+01,5.901727013446477486e+02,3.401819807418339781e-01,1.100000010988609489e+01,2.256374734825764266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.903948168586983059e+01,5.901827013191916649e+02,3.402045444700360632e-01,1.100000010988609489e+01,2.256228749424226548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904039077676983993e+01,5.901927012937388781e+02,3.402271067383878522e-01,1.100000010988609489e+01,2.256082764022688831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904129986766984928e+01,5.902027012682893883e+02,3.402496675468893450e-01,1.100000010988609489e+01,2.255936778621151113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904220895856985862e+01,5.902127012428431954e+02,3.402722268955405416e-01,1.100000010988609489e+01,2.255790793219613396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904311804946986797e+01,5.902227012174002994e+02,3.402947847843413864e-01,1.100000010988609489e+01,2.255644807818075678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904402714036987732e+01,5.902327011919605866e+02,3.403173412132919351e-01,1.100000010988609489e+01,2.255498822416537961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904493623126988666e+01,5.902427011665241707e+02,3.403398961823921876e-01,1.100000010988609489e+01,2.255352837015000243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904584532216989601e+01,5.902527011410910518e+02,3.403624496916421438e-01,1.100000010988609489e+01,2.255206851613462526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904675441306990535e+01,5.902627011156612298e+02,3.403850017410418038e-01,1.100000010988609489e+01,2.255060866211924808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904766350396991470e+01,5.902727010902347047e+02,3.404075523305911677e-01,1.100000010988609489e+01,2.254914880810387091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904857259486992405e+01,5.902827010648114765e+02,3.404301014602902353e-01,1.100000010988609489e+01,2.254768895408849373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.904948168576993339e+01,5.902927010393915452e+02,3.404526491301390068e-01,1.100000010988609489e+01,2.254622910007311656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905039077666994274e+01,5.903027010139749109e+02,3.404751953401374265e-01,1.100000010988609489e+01,2.254476924605773938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905129986756995208e+01,5.903127009885615735e+02,3.404977400902855500e-01,1.100000010988609489e+01,2.254330939204236221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905220895846996143e+01,5.903227009631515330e+02,3.405202833805833773e-01,1.100000010988609489e+01,2.254184953802698503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905311804936997078e+01,5.903327009377447894e+02,3.405428252110309084e-01,1.100000010988609489e+01,2.254038968401160786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905402714026998012e+01,5.903427009123413427e+02,3.405653655816281433e-01,1.100000010988609489e+01,2.253892982999623068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905493623116998947e+01,5.903527008869411929e+02,3.405879044923750820e-01,1.100000010988609489e+01,2.253746997598085351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905584532206999882e+01,5.903627008615443401e+02,3.406104419432716690e-01,1.100000010988609489e+01,2.253601012196547633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905675441297000816e+01,5.903727008361507842e+02,3.406329779343179598e-01,1.100000010988609489e+01,2.253455026795009915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905766350387001751e+01,5.903827008107605252e+02,3.406555124655139544e-01,1.100000010988609489e+01,2.253309041393472198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905857259477002685e+01,5.903927007853735631e+02,3.406780455368596527e-01,1.100000010988609489e+01,2.253163055991934480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.905948168567003620e+01,5.904027007599898980e+02,3.407005771483549994e-01,1.100000010988609489e+01,2.253017070590396763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906039077657004555e+01,5.904127007346095297e+02,3.407231073000000499e-01,1.100000010988609489e+01,2.252871085188859045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906129986747005489e+01,5.904227007092323447e+02,3.407456359917948041e-01,1.100000010988609489e+01,2.252725099787321328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906220895837006424e+01,5.904327006838584566e+02,3.407681632237392622e-01,1.100000010988609489e+01,2.252579114385783610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906311804927007358e+01,5.904427006584878654e+02,3.407906889958333685e-01,1.100000010988609489e+01,2.252433128984245893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906402714017008293e+01,5.904527006331205712e+02,3.408132133080771786e-01,1.100000010988609489e+01,2.252287143582708175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906493623107009228e+01,5.904627006077565738e+02,3.408357361604706925e-01,1.100000010988609489e+01,2.252141158181170458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906584532197010162e+01,5.904727005823958734e+02,3.408582575530139103e-01,1.100000010988609489e+01,2.251995172779632740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906675441287011097e+01,5.904827005570384699e+02,3.408807774857067763e-01,1.100000010988609489e+01,2.251849187378095023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906766350377012031e+01,5.904927005316843633e+02,3.409032959585493461e-01,1.100000010988609489e+01,2.251703201976557305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906857259467012966e+01,5.905027005063335537e+02,3.409258129715416197e-01,1.100000010988609489e+01,2.251557216575019588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.906948168557013901e+01,5.905127004809860409e+02,3.409483285246835416e-01,1.100000010988609489e+01,2.251411231173481870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907039077647014835e+01,5.905227004556418251e+02,3.409708426179751672e-01,1.100000010988609489e+01,2.251265245771944153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907129986737015770e+01,5.905327004303009062e+02,3.409933552514164967e-01,1.100000010988609489e+01,2.251119260370406435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907220895827016705e+01,5.905427004049631705e+02,3.410158664250074745e-01,1.100000010988609489e+01,2.250973274968868718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907311804917017639e+01,5.905527003796287318e+02,3.410383761387481560e-01,1.100000010988609489e+01,2.250827289567331000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907402714007018574e+01,5.905627003542975899e+02,3.410608843926384859e-01,1.100000010988609489e+01,2.250681304165793283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907493623097019508e+01,5.905727003289697450e+02,3.410833911866785195e-01,1.100000010988609489e+01,2.250535318764255565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907584532187020443e+01,5.905827003036451970e+02,3.411058965208682570e-01,1.100000010988609489e+01,2.250389333362717847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907675441277021378e+01,5.905927002783239459e+02,3.411284003952076427e-01,1.100000010988609489e+01,2.250243347961180130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907766350367022312e+01,5.906027002530059917e+02,3.411509028096967322e-01,1.100000010988609489e+01,2.250097362559642412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907857259457023247e+01,5.906127002276913345e+02,3.411734037643354700e-01,1.100000010988609489e+01,2.249951377158104695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.907948168547024181e+01,5.906227002023799741e+02,3.411959032591239116e-01,1.100000010988609489e+01,2.249805391756566977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908039077637025116e+01,5.906327001770719107e+02,3.412184012940620570e-01,1.100000010988609489e+01,2.249659406355029260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908129986727026051e+01,5.906427001517670305e+02,3.412408978691498507e-01,1.100000010988609489e+01,2.249513420953491542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908220895817026985e+01,5.906527001264654473e+02,3.412633929843873482e-01,1.100000010988609489e+01,2.249367435551953825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908311804907027920e+01,5.906627001011671609e+02,3.412858866397744939e-01,1.100000010988609489e+01,2.249221450150416107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908402713997028854e+01,5.906727000758721715e+02,3.413083788353113435e-01,1.100000010988609489e+01,2.249075464748878390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908493623087029789e+01,5.906827000505804790e+02,3.413308695709978413e-01,1.100000010988609489e+01,2.248929479347340672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908584532177030724e+01,5.906927000252920834e+02,3.413533588468340430e-01,1.100000010988609489e+01,2.248783493945802955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908675441267031658e+01,5.907027000000069847e+02,3.413758466628198929e-01,1.100000010988609489e+01,2.248637508544265237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908766350357032593e+01,5.907126999747251830e+02,3.413983330189554466e-01,1.100000010988609489e+01,2.248491523142727520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908857259447033528e+01,5.907226999494466781e+02,3.414208179152406486e-01,1.100000010988609489e+01,2.248345537741189802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.908948168537034462e+01,5.907326999241713565e+02,3.414433013516755544e-01,1.100000010988609489e+01,2.248199552339652085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909039077627035397e+01,5.907426998988993319e+02,3.414657833282601085e-01,1.100000010988609489e+01,2.248053566938114367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909129986717036331e+01,5.907526998736306041e+02,3.414882638449943664e-01,1.100000010988609489e+01,2.247907581536576650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909220895807037266e+01,5.907626998483651732e+02,3.415107429018782725e-01,1.100000010988609489e+01,2.247761596135038932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909311804897038201e+01,5.907726998231030393e+02,3.415332204989118825e-01,1.100000010988609489e+01,2.247615610733501215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909402713987039135e+01,5.907826997978442023e+02,3.415556966360951408e-01,1.100000010988609489e+01,2.247469625331963497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909493623077040070e+01,5.907926997725886622e+02,3.415781713134280473e-01,1.100000010988609489e+01,2.247323639930425779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909584532167041004e+01,5.908026997473363053e+02,3.416006445309106576e-01,1.100000010988609489e+01,2.247177654528888062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909675441257041939e+01,5.908126997220872454e+02,3.416231162885429162e-01,1.100000010988609489e+01,2.247031669127350344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909766350347042874e+01,5.908226996968414824e+02,3.416455865863248786e-01,1.100000010988609489e+01,2.246885683725812627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909857259437043808e+01,5.908326996715990163e+02,3.416680554242564893e-01,1.100000010988609489e+01,2.246739698324274909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.909948168527044743e+01,5.908426996463598471e+02,3.416905228023377483e-01,1.100000010988609489e+01,2.246593712922737192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910039077617045677e+01,5.908526996211239748e+02,3.417129887205687111e-01,1.100000010988609489e+01,2.246447727521199474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910129986707046612e+01,5.908626995958913994e+02,3.417354531789493222e-01,1.100000010988609489e+01,2.246301742119661757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910220895797047547e+01,5.908726995706620073e+02,3.417579161774795815e-01,1.100000010988609489e+01,2.246155756718124039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910311804887048481e+01,5.908826995454359121e+02,3.417803777161595447e-01,1.100000010988609489e+01,2.246009771316586322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910402713977049416e+01,5.908926995202131138e+02,3.418028377949891561e-01,1.100000010988609489e+01,2.245863785915048604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910493623067050351e+01,5.909026994949936125e+02,3.418252964139684158e-01,1.100000010988609489e+01,2.245717800513510887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910584532157051285e+01,5.909126994697774080e+02,3.418477535730973793e-01,1.100000010988609489e+01,2.245571815111973169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910675441247052220e+01,5.909226994445645005e+02,3.418702092723759911e-01,1.100000010988609489e+01,2.245425829710435452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910766350337053154e+01,5.909326994193547762e+02,3.418926635118042512e-01,1.100000010988609489e+01,2.245279844308897734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910857259427054089e+01,5.909426993941483488e+02,3.419151162913822151e-01,1.100000010988609489e+01,2.245133858907360017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.910948168517055024e+01,5.909526993689452183e+02,3.419375676111098272e-01,1.100000010988609489e+01,2.244987873505822299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911039077607055958e+01,5.909626993437453848e+02,3.419600174709870877e-01,1.100000010988609489e+01,2.244841888104284582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911129986697056893e+01,5.909726993185488482e+02,3.419824658710140519e-01,1.100000010988609489e+01,2.244695902702746864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911220895787057827e+01,5.909826992933556085e+02,3.420049128111906644e-01,1.100000010988609489e+01,2.244549917301209147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911311804877058762e+01,5.909926992681655520e+02,3.420273582915169253e-01,1.100000010988609489e+01,2.244403931899671429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911402713967059697e+01,5.910026992429787924e+02,3.420498023119928344e-01,1.100000010988609489e+01,2.244257946498133711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911493623057060631e+01,5.910126992177953298e+02,3.420722448726184473e-01,1.100000010988609489e+01,2.244111961096595994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911584532147061566e+01,5.910226991926151641e+02,3.420946859733937084e-01,1.100000010988609489e+01,2.243965975695058276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911675441237062500e+01,5.910326991674382953e+02,3.421171256143186179e-01,1.100000010988609489e+01,2.243819990293520559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911766350327063435e+01,5.910426991422646097e+02,3.421395637953931756e-01,1.100000010988609489e+01,2.243674004891982841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911857259417064370e+01,5.910526991170942210e+02,3.421620005166173817e-01,1.100000010988609489e+01,2.243528019490445124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.911948168507065304e+01,5.910626990919271293e+02,3.421844357779912915e-01,1.100000010988609489e+01,2.243382034088907406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912039077597066239e+01,5.910726990667633345e+02,3.422068695795148496e-01,1.100000010988609489e+01,2.243236048687369689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912129986687067174e+01,5.910826990416028366e+02,3.422293019211880560e-01,1.100000010988609489e+01,2.243090063285831971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912220895777068108e+01,5.910926990164456356e+02,3.422517328030109107e-01,1.100000010988609489e+01,2.242944077884294254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912311804867069043e+01,5.911026989912916179e+02,3.422741622249834137e-01,1.100000010988609489e+01,2.242798092482756536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912402713957069977e+01,5.911126989661408970e+02,3.422965901871055650e-01,1.100000010988609489e+01,2.242652107081218819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912493623047070912e+01,5.911226989409934731e+02,3.423190166893774200e-01,1.100000010988609489e+01,2.242506121679681101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912584532137071847e+01,5.911326989158493461e+02,3.423414417317989233e-01,1.100000010988609489e+01,2.242360136278143384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912675441227072781e+01,5.911426988907085160e+02,3.423638653143700750e-01,1.100000010988609489e+01,2.242214150876605666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912766350317073716e+01,5.911526988655708692e+02,3.423862874370908749e-01,1.100000010988609489e+01,2.242068165475067949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912857259407074650e+01,5.911626988404365193e+02,3.424087080999613231e-01,1.100000010988609489e+01,2.241922180073530231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.912948168497075585e+01,5.911726988153054663e+02,3.424311273029814195e-01,1.100000010988609489e+01,2.241776194671992514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913039077587076520e+01,5.911826987901777102e+02,3.424535450461511643e-01,1.100000010988609489e+01,2.241630209270454796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913129986677077454e+01,5.911926987650531373e+02,3.424759613294705574e-01,1.100000010988609489e+01,2.241484223868917078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913220895767078389e+01,5.912026987399318614e+02,3.424983761529395987e-01,1.100000010988609489e+01,2.241338238467379361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913311804857079323e+01,5.912126987148138824e+02,3.425207895165582883e-01,1.100000010988609489e+01,2.241192253065841643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913402713947080258e+01,5.912226986896992003e+02,3.425432014203266262e-01,1.100000010988609489e+01,2.241046267664303926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913493623037081193e+01,5.912326986645878151e+02,3.425656118642446124e-01,1.100000010988609489e+01,2.240900282262766208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913584532127082127e+01,5.912426986394796131e+02,3.425880208483123024e-01,1.100000010988609489e+01,2.240754296861228491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913675441217083062e+01,5.912526986143747081e+02,3.426104283725296407e-01,1.100000010988609489e+01,2.240608311459690773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913766350307083997e+01,5.912626985892731000e+02,3.426328344368966272e-01,1.100000010988609489e+01,2.240462326058153056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913857259397084931e+01,5.912726985641747888e+02,3.426552390414132621e-01,1.100000010988609489e+01,2.240316340656615338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.913948168487085866e+01,5.912826985390796608e+02,3.426776421860795452e-01,1.100000010988609489e+01,2.240170355255077621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914039077577086800e+01,5.912926985139878298e+02,3.427000438708954766e-01,1.100000010988609489e+01,2.240024369853539903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914129986667087735e+01,5.913026984888992956e+02,3.427224440958610563e-01,1.100000010988609489e+01,2.239878384452002186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914220895757088670e+01,5.913126984638140584e+02,3.427448428609762843e-01,1.100000010988609489e+01,2.239732399050464468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914311804847089604e+01,5.913226984387321181e+02,3.427672401662411605e-01,1.100000010988609489e+01,2.239586413648926751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914402713937090539e+01,5.913326984136533611e+02,3.427896360116556296e-01,1.100000010988609489e+01,2.239440428247389033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914493623027091473e+01,5.913426983885779009e+02,3.428120303972197469e-01,1.100000010988609489e+01,2.239294442845851316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914584532117092408e+01,5.913526983635057377e+02,3.428344233229335125e-01,1.100000010988609489e+01,2.239148457444313598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914675441207093343e+01,5.913626983384368714e+02,3.428568147887969264e-01,1.100000010988609489e+01,2.239002472042775881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914766350297094277e+01,5.913726983133711883e+02,3.428792047948099886e-01,1.100000010988609489e+01,2.238856486641238163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914857259387095212e+01,5.913826982883088021e+02,3.429015933409726991e-01,1.100000010988609489e+01,2.238710501239700446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.914948168477096146e+01,5.913926982632497129e+02,3.429239804272850578e-01,1.100000010988609489e+01,2.238564515838162728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915039077567097081e+01,5.914026982381939206e+02,3.429463660537470648e-01,1.100000010988609489e+01,2.238418530436625010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915129986657098016e+01,5.914126982131413115e+02,3.429687502203587202e-01,1.100000010988609489e+01,2.238272545035087293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915220895747098950e+01,5.914226981880919993e+02,3.429911329271200238e-01,1.100000010988609489e+01,2.238126559633549575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915311804837099885e+01,5.914326981630459841e+02,3.430135141740309757e-01,1.100000010988609489e+01,2.237980574232011858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915402713927100820e+01,5.914426981380032657e+02,3.430358939610915203e-01,1.100000010988609489e+01,2.237834588830474140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915493623017101754e+01,5.914526981129637306e+02,3.430582722883017133e-01,1.100000010988609489e+01,2.237688603428936423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915584532107102689e+01,5.914626980879274925e+02,3.430806491556615545e-01,1.100000010988609489e+01,2.237542618027398705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915675441197103623e+01,5.914726980628945512e+02,3.431030245631710440e-01,1.100000010988609489e+01,2.237396632625860988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915766350287104558e+01,5.914826980378647932e+02,3.431253985108301818e-01,1.100000010988609489e+01,2.237250647224323270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915857259377105493e+01,5.914926980128383320e+02,3.431477709986389679e-01,1.100000010988609489e+01,2.237104661822785553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.915948168467106427e+01,5.915026979878151678e+02,3.431701420265973468e-01,1.100000010988609489e+01,2.236958676421247835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916039077557107362e+01,5.915126979627953006e+02,3.431925115947053739e-01,1.100000010988609489e+01,2.236812691019710118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916129986647108296e+01,5.915226979377786165e+02,3.432148797029630494e-01,1.100000010988609489e+01,2.236666705618172400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916220895737109231e+01,5.915326979127652294e+02,3.432372463513703731e-01,1.100000010988609489e+01,2.236520720216634683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916311804827110166e+01,5.915426978877551392e+02,3.432596115399273451e-01,1.100000010988609489e+01,2.236374734815096965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916402713917111100e+01,5.915526978627483459e+02,3.432819752686339099e-01,1.100000010988609489e+01,2.236228749413559248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916493623007112035e+01,5.915626978377447358e+02,3.433043375374901229e-01,1.100000010988609489e+01,2.236082764012021530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916584532097112969e+01,5.915726978127444227e+02,3.433266983464959843e-01,1.100000010988609489e+01,2.235936778610483813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916675441187113904e+01,5.915826977877474064e+02,3.433490576956514939e-01,1.100000010988609489e+01,2.235790793208946095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916766350277114839e+01,5.915926977627535734e+02,3.433714155849565963e-01,1.100000010988609489e+01,2.235644807807408378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916857259367115773e+01,5.916026977377630374e+02,3.433937720144113470e-01,1.100000010988609489e+01,2.235498822405870660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.916948168457116708e+01,5.916126977127757982e+02,3.434161269840157460e-01,1.100000010988609489e+01,2.235352837004332942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917039077547117643e+01,5.916226976877917423e+02,3.434384804937697933e-01,1.100000010988609489e+01,2.235206851602795225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917129986637118577e+01,5.916326976628109833e+02,3.434608325436734333e-01,1.100000010988609489e+01,2.235060866201257507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917220895727119512e+01,5.916426976378335212e+02,3.434831831337267216e-01,1.100000010988609489e+01,2.234914880799719790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917311804817120446e+01,5.916526976128593560e+02,3.435055322639296582e-01,1.100000010988609489e+01,2.234768895398182072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917402713907121381e+01,5.916626975878883741e+02,3.435278799342821876e-01,1.100000010988609489e+01,2.234622909996644355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917493622997122316e+01,5.916726975629206891e+02,3.435502261447843653e-01,1.100000010988609489e+01,2.234476924595106637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917584532087123250e+01,5.916826975379563009e+02,3.435725708954361912e-01,1.100000010988609489e+01,2.234330939193568920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917675441177124185e+01,5.916926975129950961e+02,3.435949141862376099e-01,1.100000010988609489e+01,2.234184953792031202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917766350267125119e+01,5.917026974880371881e+02,3.436172560171886770e-01,1.100000010988609489e+01,2.234038968390493485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917857259357126054e+01,5.917126974630825771e+02,3.436395963882893922e-01,1.100000010988609489e+01,2.233892982988955767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.917948168447126989e+01,5.917226974381311493e+02,3.436619352995397003e-01,1.100000010988609489e+01,2.233746997587418050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918039077537127923e+01,5.917326974131830184e+02,3.436842727509396567e-01,1.100000010988609489e+01,2.233601012185880332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918129986627128858e+01,5.917426973882381844e+02,3.437066087424892058e-01,1.100000010988609489e+01,2.233455026784342615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918220895717129793e+01,5.917526973632965337e+02,3.437289432741884032e-01,1.100000010988609489e+01,2.233309041382804897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918311804807130727e+01,5.917626973383581799e+02,3.437512763460372489e-01,1.100000010988609489e+01,2.233163055981267180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918402713897131662e+01,5.917726973134231230e+02,3.437736079580356874e-01,1.100000010988609489e+01,2.233017070579729462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918493622987132596e+01,5.917826972884913630e+02,3.437959381101837741e-01,1.100000010988609489e+01,2.232871085178191745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918584532077133531e+01,5.917926972635627862e+02,3.438182668024814537e-01,1.100000010988609489e+01,2.232725099776654027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918675441167134466e+01,5.918026972386375064e+02,3.438405940349287815e-01,1.100000010988609489e+01,2.232579114375116310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918766350257135400e+01,5.918126972137155235e+02,3.438629198075257021e-01,1.100000010988609489e+01,2.232433128973578592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918857259347136335e+01,5.918226971887967238e+02,3.438852441202722710e-01,1.100000010988609489e+01,2.232287143572040874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.918948168437137269e+01,5.918326971638812211e+02,3.439075669731684326e-01,1.100000010988609489e+01,2.232141158170503157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919039077527138204e+01,5.918426971389690152e+02,3.439298883662142425e-01,1.100000010988609489e+01,2.231995172768965439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919129986617139139e+01,5.918526971140599926e+02,3.439522082994096452e-01,1.100000010988609489e+01,2.231849187367427722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919220895707140073e+01,5.918626970891542669e+02,3.439745267727546962e-01,1.100000010988609489e+01,2.231703201965890004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919311804797141008e+01,5.918726970642518381e+02,3.439968437862493400e-01,1.100000010988609489e+01,2.231557216564352287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919402713887141942e+01,5.918826970393525926e+02,3.440191593398936321e-01,1.100000010988609489e+01,2.231411231162814569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919493622977142877e+01,5.918926970144566440e+02,3.440414734336875169e-01,1.100000010988609489e+01,2.231265245761276852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919584532067143812e+01,5.919026969895638786e+02,3.440637860676310500e-01,1.100000010988609489e+01,2.231119260359739134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919675441157144746e+01,5.919126969646744101e+02,3.440860972417241759e-01,1.100000010988609489e+01,2.230973274958201417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919766350247145681e+01,5.919226969397882385e+02,3.441084069559669500e-01,1.100000010988609489e+01,2.230827289556663699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919857259337146616e+01,5.919326969149052502e+02,3.441307152103593170e-01,1.100000010988609489e+01,2.230681304155125982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.919948168427147550e+01,5.919426968900255588e+02,3.441530220049013322e-01,1.100000010988609489e+01,2.230535318753588264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920039077517148485e+01,5.919526968651491643e+02,3.441753273395929402e-01,1.100000010988609489e+01,2.230389333352050547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920129986607149419e+01,5.919626968402759530e+02,3.441976312144341965e-01,1.100000010988609489e+01,2.230243347950512829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920220895697150354e+01,5.919726968154060387e+02,3.442199336294250456e-01,1.100000010988609489e+01,2.230097362548975112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920311804787151289e+01,5.919826967905394213e+02,3.442422345845654874e-01,1.100000010988609489e+01,2.229951377147437394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920402713877152223e+01,5.919926967656759871e+02,3.442645340798555775e-01,1.100000010988609489e+01,2.229805391745899677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920493622967153158e+01,5.920026967408158498e+02,3.442868321152952604e-01,1.100000010988609489e+01,2.229659406344361959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920584532057154092e+01,5.920126967159590095e+02,3.443091286908845916e-01,1.100000010988609489e+01,2.229513420942824242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920675441147155027e+01,5.920226966911053523e+02,3.443314238066235156e-01,1.100000010988609489e+01,2.229367435541286524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920766350237155962e+01,5.920326966662549921e+02,3.443537174625120323e-01,1.100000010988609489e+01,2.229221450139748806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920857259327156896e+01,5.920426966414078152e+02,3.443760096585501973e-01,1.100000010988609489e+01,2.229075464738211089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.920948168417157831e+01,5.920526966165639351e+02,3.443983003947379551e-01,1.100000010988609489e+01,2.228929479336673371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921039077507158765e+01,5.920626965917233520e+02,3.444205896710753056e-01,1.100000010988609489e+01,2.228783493935135654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921129986597159700e+01,5.920726965668859521e+02,3.444428774875623045e-01,1.100000010988609489e+01,2.228637508533597936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921220895687160635e+01,5.920826965420518491e+02,3.444651638441988961e-01,1.100000010988609489e+01,2.228491523132060219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921311804777161569e+01,5.920926965172210430e+02,3.444874487409850805e-01,1.100000010988609489e+01,2.228345537730522501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921402713867162504e+01,5.921026964923934202e+02,3.445097321779209132e-01,1.100000010988609489e+01,2.228199552328984784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921493622957163439e+01,5.921126964675690942e+02,3.445320141550063386e-01,1.100000010988609489e+01,2.228053566927447066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921584532047164373e+01,5.921226964427479516e+02,3.445542946722413569e-01,1.100000010988609489e+01,2.227907581525909349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921675441137165308e+01,5.921326964179301058e+02,3.445765737296259679e-01,1.100000010988609489e+01,2.227761596124371631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921766350227166242e+01,5.921426963931155569e+02,3.445988513271602272e-01,1.100000010988609489e+01,2.227615610722833914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921857259317167177e+01,5.921526963683041913e+02,3.446211274648440792e-01,1.100000010988609489e+01,2.227469625321296196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.921948168407168112e+01,5.921626963434961226e+02,3.446434021426775240e-01,1.100000010988609489e+01,2.227323639919758479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922039077497169046e+01,5.921726963186912371e+02,3.446656753606605617e-01,1.100000010988609489e+01,2.227177654518220761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922129986587169981e+01,5.921826962938896486e+02,3.446879471187932475e-01,1.100000010988609489e+01,2.227031669116683044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922220895677170915e+01,5.921926962690913570e+02,3.447102174170755262e-01,1.100000010988609489e+01,2.226885683715145326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922311804767171850e+01,5.922026962442962486e+02,3.447324862555073977e-01,1.100000010988609489e+01,2.226739698313607609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922402713857172785e+01,5.922126962195044371e+02,3.447547536340888619e-01,1.100000010988609489e+01,2.226593712912069891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922493622947173719e+01,5.922226961947158088e+02,3.447770195528199189e-01,1.100000010988609489e+01,2.226447727510532174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922584532037174654e+01,5.922326961699304775e+02,3.447992840117006241e-01,1.100000010988609489e+01,2.226301742108994456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922675441127175588e+01,5.922426961451484431e+02,3.448215470107309222e-01,1.100000010988609489e+01,2.226155756707456738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922766350217176523e+01,5.922526961203695919e+02,3.448438085499108130e-01,1.100000010988609489e+01,2.226009771305919021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922857259307177458e+01,5.922626960955940376e+02,3.448660686292402966e-01,1.100000010988609489e+01,2.225863785904381303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.922948168397178392e+01,5.922726960708216666e+02,3.448883272487193730e-01,1.100000010988609489e+01,2.225717800502843586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923039077487179327e+01,5.922826960460525925e+02,3.449105844083480421e-01,1.100000010988609489e+01,2.225571815101305868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923129986577180262e+01,5.922926960212867016e+02,3.449328401081263595e-01,1.100000010988609489e+01,2.225425829699768151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923220895667181196e+01,5.923026959965241076e+02,3.449550943480542697e-01,1.100000010988609489e+01,2.225279844298230433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923311804757182131e+01,5.923126959717648106e+02,3.449773471281317727e-01,1.100000010988609489e+01,2.225133858896692716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923402713847183065e+01,5.923226959470086967e+02,3.449995984483588685e-01,1.100000010988609489e+01,2.224987873495154998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923493622937184000e+01,5.923326959222558799e+02,3.450218483087355570e-01,1.100000010988609489e+01,2.224841888093617281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923584532027184935e+01,5.923426958975062462e+02,3.450440967092618383e-01,1.100000010988609489e+01,2.224695902692079563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923675441117185869e+01,5.923526958727599094e+02,3.450663436499377124e-01,1.100000010988609489e+01,2.224549917290541846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923766350207186804e+01,5.923626958480167559e+02,3.450885891307631792e-01,1.100000010988609489e+01,2.224403931889004128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923857259297187738e+01,5.923726958232768993e+02,3.451108331517382388e-01,1.100000010988609489e+01,2.224257946487466411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.923948168387188673e+01,5.923826957985403396e+02,3.451330757128628912e-01,1.100000010988609489e+01,2.224111961085928693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924039077477189608e+01,5.923926957738069632e+02,3.451553168141371364e-01,1.100000010988609489e+01,2.223965975684390976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924129986567190542e+01,5.924026957490768837e+02,3.451775564555609743e-01,1.100000010988609489e+01,2.223819990282853258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924220895657191477e+01,5.924126957243499874e+02,3.451997946371344606e-01,1.100000010988609489e+01,2.223674004881315541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924311804747192411e+01,5.924226956996263880e+02,3.452220313588575396e-01,1.100000010988609489e+01,2.223528019479777823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924402713837193346e+01,5.924326956749059718e+02,3.452442666207302113e-01,1.100000010988609489e+01,2.223382034078240106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924493622927194281e+01,5.924426956501888526e+02,3.452665004227524759e-01,1.100000010988609489e+01,2.223236048676702388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924584532017195215e+01,5.924526956254749166e+02,3.452887327649243332e-01,1.100000010988609489e+01,2.223090063275164670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924675441107196150e+01,5.924626956007642775e+02,3.453109636472457833e-01,1.100000010988609489e+01,2.222944077873626953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924766350197197085e+01,5.924726955760569354e+02,3.453331930697168262e-01,1.100000010988609489e+01,2.222798092472089235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924857259287198019e+01,5.924826955513527764e+02,3.453554210323374063e-01,1.100000010988609489e+01,2.222652107070551518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.924948168377198954e+01,5.924926955266519144e+02,3.453776475351075792e-01,1.100000010988609489e+01,2.222506121669013800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925039077467199888e+01,5.925026955019542356e+02,3.453998725780273449e-01,1.100000010988609489e+01,2.222360136267476083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925129986557200823e+01,5.925126954772598538e+02,3.454220961610967033e-01,1.100000010988609489e+01,2.222214150865938365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925220895647201758e+01,5.925226954525686551e+02,3.454443182843156546e-01,1.100000010988609489e+01,2.222068165464400648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925311804737202692e+01,5.925326954278807534e+02,3.454665389476841986e-01,1.100000010988609489e+01,2.221922180062862930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925402713827203627e+01,5.925426954031960349e+02,3.454887581512023353e-01,1.100000010988609489e+01,2.221776194661325213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925493622917204561e+01,5.925526953785146134e+02,3.455109758948700649e-01,1.100000010988609489e+01,2.221630209259787495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925584532007205496e+01,5.925626953538363750e+02,3.455331921786873872e-01,1.100000010988609489e+01,2.221484223858249778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925675441097206431e+01,5.925726953291614336e+02,3.455554070026543023e-01,1.100000010988609489e+01,2.221338238456712060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925766350187207365e+01,5.925826953044896754e+02,3.455776203667708102e-01,1.100000010988609489e+01,2.221192253055174343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925857259277208300e+01,5.925926952798212142e+02,3.455998322710369108e-01,1.100000010988609489e+01,2.221046267653636625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.925948168367209234e+01,5.926026952551559361e+02,3.456220427154526043e-01,1.100000010988609489e+01,2.220900282252098908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926039077457210169e+01,5.926126952304939550e+02,3.456442517000178349e-01,1.100000010988609489e+01,2.220754296850561190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926129986547211104e+01,5.926226952058352708e+02,3.456664592247326584e-01,1.100000010988609489e+01,2.220608311449023473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926220895637212038e+01,5.926326951811797699e+02,3.456886652895970746e-01,1.100000010988609489e+01,2.220462326047485755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926311804727212973e+01,5.926426951565275658e+02,3.457108698946110836e-01,1.100000010988609489e+01,2.220316340645948038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926402713817213908e+01,5.926526951318785450e+02,3.457330730397746854e-01,1.100000010988609489e+01,2.220170355244410320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926493622907214842e+01,5.926626951072328211e+02,3.457552747250878800e-01,1.100000010988609489e+01,2.220024369842872602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926584531997215777e+01,5.926726950825902804e+02,3.457774749505506118e-01,1.100000010988609489e+01,2.219878384441334885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926675441087216711e+01,5.926826950579510367e+02,3.457996737161629364e-01,1.100000010988609489e+01,2.219732399039797167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926766350177217646e+01,5.926926950333149762e+02,3.458218710219248537e-01,1.100000010988609489e+01,2.219586413638259450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926857259267218581e+01,5.927026950086822126e+02,3.458440668678363639e-01,1.100000010988609489e+01,2.219440428236721732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.926948168357219515e+01,5.927126949840526322e+02,3.458662612538974668e-01,1.100000010988609489e+01,2.219294442835184015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927039077447220450e+01,5.927226949594263488e+02,3.458884541801081070e-01,1.100000010988609489e+01,2.219148457433646297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927129986537221384e+01,5.927326949348032485e+02,3.459106456464683399e-01,1.100000010988609489e+01,2.219002472032108580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927220895627222319e+01,5.927426949101834452e+02,3.459328356529781656e-01,1.100000010988609489e+01,2.218856486630570862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927311804717223254e+01,5.927526948855668252e+02,3.459550241996375841e-01,1.100000010988609489e+01,2.218710501229033145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927402713807224188e+01,5.927626948609535020e+02,3.459772112864465399e-01,1.100000010988609489e+01,2.218564515827495427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927493622897225123e+01,5.927726948363433621e+02,3.459993969134050884e-01,1.100000010988609489e+01,2.218418530425957710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927584531987226057e+01,5.927826948117365191e+02,3.460215810805132297e-01,1.100000010988609489e+01,2.218272545024419992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927675441077226992e+01,5.927926947871328593e+02,3.460437637877709083e-01,1.100000010988609489e+01,2.218126559622882275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927766350167227927e+01,5.928026947625324965e+02,3.460659450351781796e-01,1.100000010988609489e+01,2.217980574221344557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927857259257228861e+01,5.928126947379353169e+02,3.460881248227350437e-01,1.100000010988609489e+01,2.217834588819806840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.927948168347229796e+01,5.928226947133413205e+02,3.461103031504415006e-01,1.100000010988609489e+01,2.217688603418269122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928039077437230731e+01,5.928326946887506210e+02,3.461324800182974948e-01,1.100000010988609489e+01,2.217542618016731405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928129986527231665e+01,5.928426946641631048e+02,3.461546554263030817e-01,1.100000010988609489e+01,2.217396632615193687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928220895617232600e+01,5.928526946395788855e+02,3.461768293744582614e-01,1.100000010988609489e+01,2.217250647213655970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928311804707233534e+01,5.928626946149978494e+02,3.461990018627629784e-01,1.100000010988609489e+01,2.217104661812118252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928402713797234469e+01,5.928726945904201102e+02,3.462211728912172881e-01,1.100000010988609489e+01,2.216958676410580534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928493622887235404e+01,5.928826945658455543e+02,3.462433424598211351e-01,1.100000010988609489e+01,2.216812691009042817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928584531977236338e+01,5.928926945412742953e+02,3.462655105685745749e-01,1.100000010988609489e+01,2.216666705607505099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928675441067237273e+01,5.929026945167062195e+02,3.462876772174776074e-01,1.100000010988609489e+01,2.216520720205967382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928766350157238207e+01,5.929126944921414406e+02,3.463098424065301773e-01,1.100000010988609489e+01,2.216374734804429664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928857259247239142e+01,5.929226944675798450e+02,3.463320061357323398e-01,1.100000010988609489e+01,2.216228749402891947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.928948168337240077e+01,5.929326944430215462e+02,3.463541684050840397e-01,1.100000010988609489e+01,2.216082764001354229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929039077427241011e+01,5.929426944184664308e+02,3.463763292145853323e-01,1.100000010988609489e+01,2.215936778599816512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929129986517241946e+01,5.929526943939146122e+02,3.463984885642362177e-01,1.100000010988609489e+01,2.215790793198278794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929220895607242880e+01,5.929626943693659769e+02,3.464206464540366404e-01,1.100000010988609489e+01,2.215644807796741077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929311804697243815e+01,5.929726943448205247e+02,3.464428028839866558e-01,1.100000010988609489e+01,2.215498822395203359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929402713787244750e+01,5.929826943202783696e+02,3.464649578540862085e-01,1.100000010988609489e+01,2.215352836993665642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929493622877245684e+01,5.929926942957393976e+02,3.464871113643353540e-01,1.100000010988609489e+01,2.215206851592127924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929584531967246619e+01,5.930026942712037226e+02,3.465092634147340367e-01,1.100000010988609489e+01,2.215060866190590207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929675441057247554e+01,5.930126942466712308e+02,3.465314140052823122e-01,1.100000010988609489e+01,2.214914880789052489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929766350147248488e+01,5.930226942221420359e+02,3.465535631359801250e-01,1.100000010988609489e+01,2.214768895387514772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929857259237249423e+01,5.930326941976160242e+02,3.465757108068275305e-01,1.100000010988609489e+01,2.214622909985977054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.929948168327250357e+01,5.930426941730933095e+02,3.465978570178244733e-01,1.100000010988609489e+01,2.214476924584439337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930039077417251292e+01,5.930526941485737780e+02,3.466200017689710089e-01,1.100000010988609489e+01,2.214330939182901619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930129986507252227e+01,5.930626941240574297e+02,3.466421450602670817e-01,1.100000010988609489e+01,2.214184953781363902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930220895597253161e+01,5.930726940995443783e+02,3.466642868917127474e-01,1.100000010988609489e+01,2.214038968379826184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930311804687254096e+01,5.930826940750345102e+02,3.466864272633079502e-01,1.100000010988609489e+01,2.213892982978288466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930402713777255030e+01,5.930926940505279390e+02,3.467085661750527459e-01,1.100000010988609489e+01,2.213746997576750749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930493622867255965e+01,5.931026940260245510e+02,3.467307036269470788e-01,1.100000010988609489e+01,2.213601012175213031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930584531957256900e+01,5.931126940015244600e+02,3.467528396189910045e-01,1.100000010988609489e+01,2.213455026773675314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930675441047257834e+01,5.931226939770275521e+02,3.467749741511844674e-01,1.100000010988609489e+01,2.213309041372137596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930766350137258769e+01,5.931326939525338275e+02,3.467971072235275232e-01,1.100000010988609489e+01,2.213163055970599879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930857259227259703e+01,5.931426939280433999e+02,3.468192388360201162e-01,1.100000010988609489e+01,2.213017070569062161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.930948168317260638e+01,5.931526939035561554e+02,3.468413689886622464e-01,1.100000010988609489e+01,2.212871085167524444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931039077407261573e+01,5.931626938790722079e+02,3.468634976814539694e-01,1.100000010988609489e+01,2.212725099765986726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931129986497262507e+01,5.931726938545914436e+02,3.468856249143952297e-01,1.100000010988609489e+01,2.212579114364449009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931220895587263442e+01,5.931826938301139762e+02,3.469077506874860273e-01,1.100000010988609489e+01,2.212433128962911291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931311804677264377e+01,5.931926938056396921e+02,3.469298750007264176e-01,1.100000010988609489e+01,2.212287143561373574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931402713767265311e+01,5.932026937811685912e+02,3.469519978541163452e-01,1.100000010988609489e+01,2.212141158159835856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931493622857266246e+01,5.932126937567007872e+02,3.469741192476558655e-01,1.100000010988609489e+01,2.211995172758298139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931584531947267180e+01,5.932226937322361664e+02,3.469962391813449232e-01,1.100000010988609489e+01,2.211849187356760421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931675441037268115e+01,5.932326937077748426e+02,3.470183576551835181e-01,1.100000010988609489e+01,2.211703201955222704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931766350127269050e+01,5.932426936833167019e+02,3.470404746691717057e-01,1.100000010988609489e+01,2.211557216553684986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931857259217269984e+01,5.932526936588617446e+02,3.470625902233094306e-01,1.100000010988609489e+01,2.211411231152147269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.931948168307270919e+01,5.932626936344100841e+02,3.470847043175966928e-01,1.100000010988609489e+01,2.211265245750609551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932039077397271853e+01,5.932726936099616069e+02,3.471068169520334923e-01,1.100000010988609489e+01,2.211119260349071833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932129986487272788e+01,5.932826935855164265e+02,3.471289281266198845e-01,1.100000010988609489e+01,2.210973274947534116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932220895577273723e+01,5.932926935610744295e+02,3.471510378413558140e-01,1.100000010988609489e+01,2.210827289545996398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932311804667274657e+01,5.933026935366356156e+02,3.471731460962412807e-01,1.100000010988609489e+01,2.210681304144458681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932402713757275592e+01,5.933126935122000987e+02,3.471952528912763403e-01,1.100000010988609489e+01,2.210535318742920963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932493622847276526e+01,5.933226934877677650e+02,3.472173582264609371e-01,1.100000010988609489e+01,2.210389333341383246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932584531937277461e+01,5.933326934633386145e+02,3.472394621017950711e-01,1.100000010988609489e+01,2.210243347939845528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932675441027278396e+01,5.933426934389127609e+02,3.472615645172787424e-01,1.100000010988609489e+01,2.210097362538307811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932766350117279330e+01,5.933526934144900906e+02,3.472836654729120065e-01,1.100000010988609489e+01,2.209951377136770093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932857259207280265e+01,5.933626933900707172e+02,3.473057649686948078e-01,1.100000010988609489e+01,2.209805391735232376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.932948168297281200e+01,5.933726933656545270e+02,3.473278630046271465e-01,1.100000010988609489e+01,2.209659406333694658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933039077387282134e+01,5.933826933412415201e+02,3.473499595807090223e-01,1.100000010988609489e+01,2.209513420932156941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933129986477283069e+01,5.933926933168318101e+02,3.473720546969404355e-01,1.100000010988609489e+01,2.209367435530619223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933220895567284003e+01,5.934026932924252833e+02,3.473941483533214414e-01,1.100000010988609489e+01,2.209221450129081506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933311804657284938e+01,5.934126932680219397e+02,3.474162405498519846e-01,1.100000010988609489e+01,2.209075464727543788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933402713747285873e+01,5.934226932436218931e+02,3.474383312865320650e-01,1.100000010988609489e+01,2.208929479326006071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933493622837286807e+01,5.934326932192250297e+02,3.474604205633616827e-01,1.100000010988609489e+01,2.208783493924468353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933584531927287742e+01,5.934426931948314632e+02,3.474825083803408377e-01,1.100000010988609489e+01,2.208637508522930636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933675441017288676e+01,5.934526931704410799e+02,3.475045947374695299e-01,1.100000010988609489e+01,2.208491523121392918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933766350107289611e+01,5.934626931460538799e+02,3.475266796347478149e-01,1.100000010988609489e+01,2.208345537719855201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933857259197290546e+01,5.934726931216699768e+02,3.475487630721756371e-01,1.100000010988609489e+01,2.208199552318317483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.933948168287291480e+01,5.934826930972892569e+02,3.475708450497529967e-01,1.100000010988609489e+01,2.208053566916779765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934039077377292415e+01,5.934926930729117203e+02,3.475929255674798934e-01,1.100000010988609489e+01,2.207907581515242048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934129986467293350e+01,5.935026930485374805e+02,3.476150046253563275e-01,1.100000010988609489e+01,2.207761596113704330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934220895557294284e+01,5.935126930241664240e+02,3.476370822233822988e-01,1.100000010988609489e+01,2.207615610712166613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934311804647295219e+01,5.935226929997985508e+02,3.476591583615578074e-01,1.100000010988609489e+01,2.207469625310628895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934402713737296153e+01,5.935326929754339744e+02,3.476812330398828532e-01,1.100000010988609489e+01,2.207323639909091178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934493622827297088e+01,5.935426929510725813e+02,3.477033062583574363e-01,1.100000010988609489e+01,2.207177654507553460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934584531917298023e+01,5.935526929267143714e+02,3.477253780169815567e-01,1.100000010988609489e+01,2.207031669106015743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934675441007298957e+01,5.935626929023594585e+02,3.477474483157552698e-01,1.100000010988609489e+01,2.206885683704478025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934766350097299892e+01,5.935726928780077287e+02,3.477695171546785202e-01,1.100000010988609489e+01,2.206739698302940308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934857259187300826e+01,5.935826928536591822e+02,3.477915845337513079e-01,1.100000010988609489e+01,2.206593712901402590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.934948168277301761e+01,5.935926928293139326e+02,3.478136504529736328e-01,1.100000010988609489e+01,2.206447727499864873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935039077367302696e+01,5.936026928049718663e+02,3.478357149123454950e-01,1.100000010988609489e+01,2.206301742098327155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935129986457303630e+01,5.936126927806329832e+02,3.478577779118668944e-01,1.100000010988609489e+01,2.206155756696789438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935220895547304565e+01,5.936226927562973970e+02,3.478798394515378312e-01,1.100000010988609489e+01,2.206009771295251720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935311804637305499e+01,5.936326927319649940e+02,3.479018995313583051e-01,1.100000010988609489e+01,2.205863785893714003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935402713727306434e+01,5.936426927076357742e+02,3.479239581513283164e-01,1.100000010988609489e+01,2.205717800492176285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935493622817307369e+01,5.936526926833098514e+02,3.479460153114478649e-01,1.100000010988609489e+01,2.205571815090638568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935584531907308303e+01,5.936626926589871118e+02,3.479680710117169506e-01,1.100000010988609489e+01,2.205425829689100850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935675440997309238e+01,5.936726926346675555e+02,3.479901252521355737e-01,1.100000010988609489e+01,2.205279844287563133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935766350087310173e+01,5.936826926103512960e+02,3.480121780327037340e-01,1.100000010988609489e+01,2.205133858886025415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935857259177311107e+01,5.936926925860382198e+02,3.480342293534213760e-01,1.100000010988609489e+01,2.204987873484487697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.935948168267312042e+01,5.937026925617283268e+02,3.480562792142885553e-01,1.100000010988609489e+01,2.204841888082949980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936039077357312976e+01,5.937126925374217308e+02,3.480783276153052719e-01,1.100000010988609489e+01,2.204695902681412262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936129986447313911e+01,5.937226925131183179e+02,3.481003745564715257e-01,1.100000010988609489e+01,2.204549917279874545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936220895537314846e+01,5.937326924888180883e+02,3.481224200377873168e-01,1.100000010988609489e+01,2.204403931878336827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936311804627315780e+01,5.937426924645211557e+02,3.481444640592526452e-01,1.100000010988609489e+01,2.204257946476799110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936402713717316715e+01,5.937526924402274062e+02,3.481665066208675108e-01,1.100000010988609489e+01,2.204111961075261392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936493622807317649e+01,5.937626924159368400e+02,3.481885477226319137e-01,1.100000010988609489e+01,2.203965975673723675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936584531897318584e+01,5.937726923916495707e+02,3.482105873645458538e-01,1.100000010988609489e+01,2.203819990272185957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936675440987319519e+01,5.937826923673654846e+02,3.482326255466093312e-01,1.100000010988609489e+01,2.203674004870648240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936766350077320453e+01,5.937926923430845818e+02,3.482546622688222904e-01,1.100000010988609489e+01,2.203528019469110522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936857259167321388e+01,5.938026923188068622e+02,3.482766975311847868e-01,1.100000010988609489e+01,2.203382034067572805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.936948168257322322e+01,5.938126922945324395e+02,3.482987313336968205e-01,1.100000010988609489e+01,2.203236048666035087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937039077347323257e+01,5.938226922702612001e+02,3.483207636763583914e-01,1.100000010988609489e+01,2.203090063264497370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937129986437324192e+01,5.938326922459931438e+02,3.483427945591694996e-01,1.100000010988609489e+01,2.202944077862959652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937220895527325126e+01,5.938426922217283845e+02,3.483648239821301451e-01,1.100000010988609489e+01,2.202798092461421935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937311804617326061e+01,5.938526921974668085e+02,3.483868519452402723e-01,1.100000010988609489e+01,2.202652107059884217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937402713707326996e+01,5.938626921732084156e+02,3.484088784484999368e-01,1.100000010988609489e+01,2.202506121658346500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937493622797327930e+01,5.938726921489532060e+02,3.484309034919091386e-01,1.100000010988609489e+01,2.202360136256808782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937584531887328865e+01,5.938826921247012933e+02,3.484529270754678776e-01,1.100000010988609489e+01,2.202214150855271065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937675440977329799e+01,5.938926921004525639e+02,3.484749491991761539e-01,1.100000010988609489e+01,2.202068165453733347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937766350067330734e+01,5.939026920762070176e+02,3.484969698630339119e-01,1.100000010988609489e+01,2.201922180052195629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937857259157331669e+01,5.939126920519647683e+02,3.485189890670412072e-01,1.100000010988609489e+01,2.201776194650657912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.937948168247332603e+01,5.939226920277257022e+02,3.485410068111980397e-01,1.100000010988609489e+01,2.201630209249120194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938039077337333538e+01,5.939326920034898194e+02,3.485630230955044095e-01,1.100000010988609489e+01,2.201484223847582477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938129986427334472e+01,5.939426919792571198e+02,3.485850379199602611e-01,1.100000010988609489e+01,2.201338238446044759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938220895517335407e+01,5.939526919550277171e+02,3.486070512845656499e-01,1.100000010988609489e+01,2.201192253044507042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938311804607336342e+01,5.939626919308014976e+02,3.486290631893205760e-01,1.100000010988609489e+01,2.201046267642969324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938402713697337276e+01,5.939726919065784614e+02,3.486510736342250394e-01,1.100000010988609489e+01,2.200900282241431607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938493622787338211e+01,5.939826918823586084e+02,3.486730826192789845e-01,1.100000010988609489e+01,2.200754296839893889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938584531877339145e+01,5.939926918581420523e+02,3.486950901444824669e-01,1.100000010988609489e+01,2.200608311438356172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938675440967340080e+01,5.940026918339286794e+02,3.487170962098354865e-01,1.100000010988609489e+01,2.200462326036818454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938766350057341015e+01,5.940126918097184898e+02,3.487391008153379879e-01,1.100000010988609489e+01,2.200316340635280737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938857259147341949e+01,5.940226917855114834e+02,3.487611039609900265e-01,1.100000010988609489e+01,2.200170355233743019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.938948168237342884e+01,5.940326917613077740e+02,3.487831056467916024e-01,1.100000010988609489e+01,2.200024369832205302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939039077327343819e+01,5.940426917371072477e+02,3.488051058727426601e-01,1.100000010988609489e+01,2.199878384430667584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939129986417344753e+01,5.940526917129099047e+02,3.488271046388432550e-01,1.100000010988609489e+01,2.199732399029129867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939220895507345688e+01,5.940626916887157449e+02,3.488491019450933317e-01,1.100000010988609489e+01,2.199586413627592149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939311804597346622e+01,5.940726916645248821e+02,3.488710977914929456e-01,1.100000010988609489e+01,2.199440428226054432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939402713687347557e+01,5.940826916403372024e+02,3.488930921780420968e-01,1.100000010988609489e+01,2.199294442824516714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939493622777348492e+01,5.940926916161527060e+02,3.489150851047407298e-01,1.100000010988609489e+01,2.199148457422978997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939584531867349426e+01,5.941026915919713929e+02,3.489370765715889000e-01,1.100000010988609489e+01,2.199002472021441279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939675440957350361e+01,5.941126915677933766e+02,3.489590665785866075e-01,1.100000010988609489e+01,2.198856486619903561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939766350047351295e+01,5.941226915436185436e+02,3.489810551257337967e-01,1.100000010988609489e+01,2.198710501218365844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939857259137352230e+01,5.941326915194468938e+02,3.490030422130305232e-01,1.100000010988609489e+01,2.198564515816828126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.939948168227353165e+01,5.941426914952784273e+02,3.490250278404767315e-01,1.100000010988609489e+01,2.198418530415290409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940039077317354099e+01,5.941526914711132576e+02,3.490470120080724770e-01,1.100000010988609489e+01,2.198272545013752691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940129986407355034e+01,5.941626914469512712e+02,3.490689947158177042e-01,1.100000010988609489e+01,2.198126559612214974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940220895497355968e+01,5.941726914227924681e+02,3.490909759637124687e-01,1.100000010988609489e+01,2.197980574210677256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940311804587356903e+01,5.941826913986368481e+02,3.491129557517567150e-01,1.100000010988609489e+01,2.197834588809139539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940402713677357838e+01,5.941926913744845251e+02,3.491349340799504986e-01,1.100000010988609489e+01,2.197688603407601821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940493622767358772e+01,5.942026913503353853e+02,3.491569109482937638e-01,1.100000010988609489e+01,2.197542618006064104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940584531857359707e+01,5.942126913261894288e+02,3.491788863567865664e-01,1.100000010988609489e+01,2.197396632604526386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940675440947360642e+01,5.942226913020466554e+02,3.492008603054288507e-01,1.100000010988609489e+01,2.197250647202988669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940766350037361576e+01,5.942326912779070653e+02,3.492228327942206723e-01,1.100000010988609489e+01,2.197104661801450951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940857259127362511e+01,5.942426912537707722e+02,3.492448038231619756e-01,1.100000010988609489e+01,2.196958676399913234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.940948168217363445e+01,5.942526912296376622e+02,3.492667733922528162e-01,1.100000010988609489e+01,2.196812690998375516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941039077307364380e+01,5.942626912055077355e+02,3.492887415014931385e-01,1.100000010988609489e+01,2.196666705596837799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941129986397365315e+01,5.942726911813809920e+02,3.493107081508829981e-01,1.100000010988609489e+01,2.196520720195300081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941220895487366249e+01,5.942826911572574318e+02,3.493326733404223394e-01,1.100000010988609489e+01,2.196374734793762364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941311804577367184e+01,5.942926911331371684e+02,3.493546370701112180e-01,1.100000010988609489e+01,2.196228749392224646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941402713667368118e+01,5.943026911090200883e+02,3.493765993399495784e-01,1.100000010988609489e+01,2.196082763990686929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941493622757369053e+01,5.943126910849061915e+02,3.493985601499374760e-01,1.100000010988609489e+01,2.195936778589149211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941584531847369988e+01,5.943226910607954778e+02,3.494205195000748554e-01,1.100000010988609489e+01,2.195790793187611493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941675440937370922e+01,5.943326910366879474e+02,3.494424773903617165e-01,1.100000010988609489e+01,2.195644807786073776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941766350027371857e+01,5.943426910125837139e+02,3.494644338207981149e-01,1.100000010988609489e+01,2.195498822384536058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941857259117372791e+01,5.943526909884826637e+02,3.494863887913839950e-01,1.100000010988609489e+01,2.195352836982998341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.941948168207373726e+01,5.943626909643847966e+02,3.495083423021194124e-01,1.100000010988609489e+01,2.195206851581460623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942039077297374661e+01,5.943726909402901128e+02,3.495302943530043116e-01,1.100000010988609489e+01,2.195060866179922906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942129986387375595e+01,5.943826909161986123e+02,3.495522449440386925e-01,1.100000010988609489e+01,2.194914880778385188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942220895477376530e+01,5.943926908921104086e+02,3.495741940752226107e-01,1.100000010988609489e+01,2.194768895376847471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942311804567377465e+01,5.944026908680253882e+02,3.495961417465560106e-01,1.100000010988609489e+01,2.194622909975309753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942402713657378399e+01,5.944126908439435510e+02,3.496180879580388923e-01,1.100000010988609489e+01,2.194476924573772036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942493622747379334e+01,5.944226908198648971e+02,3.496400327096713112e-01,1.100000010988609489e+01,2.194330939172234318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942584531837380268e+01,5.944326907957894264e+02,3.496619760014532119e-01,1.100000010988609489e+01,2.194184953770696601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942675440927381203e+01,5.944426907717172526e+02,3.496839178333845943e-01,1.100000010988609489e+01,2.194038968369158883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942766350017382138e+01,5.944526907476482620e+02,3.497058582054655140e-01,1.100000010988609489e+01,2.193892982967621166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942857259107383072e+01,5.944626907235824547e+02,3.497277971176959155e-01,1.100000010988609489e+01,2.193746997566083448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.942948168197384007e+01,5.944726906995198306e+02,3.497497345700757987e-01,1.100000010988609489e+01,2.193601012164545731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943039077287384941e+01,5.944826906754603897e+02,3.497716705626051636e-01,1.100000010988609489e+01,2.193455026763008013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943129986377385876e+01,5.944926906514041320e+02,3.497936050952840659e-01,1.100000010988609489e+01,2.193309041361470296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943220895467386811e+01,5.945026906273511713e+02,3.498155381681124498e-01,1.100000010988609489e+01,2.193163055959932578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943311804557387745e+01,5.945126906033013938e+02,3.498374697810903156e-01,1.100000010988609489e+01,2.193017070558394861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943402713647388680e+01,5.945226905792547996e+02,3.498593999342176630e-01,1.100000010988609489e+01,2.192871085156857143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943493622737389614e+01,5.945326905552113885e+02,3.498813286274945478e-01,1.100000010988609489e+01,2.192725099755319425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943584531827390549e+01,5.945426905311711607e+02,3.499032558609209143e-01,1.100000010988609489e+01,2.192579114353781708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943675440917391484e+01,5.945526905071341162e+02,3.499251816344967625e-01,1.100000010988609489e+01,2.192433128952243990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943766350007392418e+01,5.945626904831002548e+02,3.499471059482220925e-01,1.100000010988609489e+01,2.192287143550706273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943857259097393353e+01,5.945726904590696904e+02,3.499690288020969597e-01,1.100000010988609489e+01,2.192141158149168555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.943948168187394288e+01,5.945826904350423092e+02,3.499909501961213087e-01,1.100000010988609489e+01,2.191995172747630838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944039077277395222e+01,5.945926904110181113e+02,3.500128701302951395e-01,1.100000010988609489e+01,2.191849187346093120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944129986367396157e+01,5.946026903869970965e+02,3.500347886046184520e-01,1.100000010988609489e+01,2.191703201944555403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944220895457397091e+01,5.946126903629792650e+02,3.500567056190912463e-01,1.100000010988609489e+01,2.191557216543017685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944311804547398026e+01,5.946226903389646168e+02,3.500786211737135223e-01,1.100000010988609489e+01,2.191411231141479968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944402713637398961e+01,5.946326903149532654e+02,3.501005352684853356e-01,1.100000010988609489e+01,2.191265245739942250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944493622727399895e+01,5.946426902909450973e+02,3.501224479034066306e-01,1.100000010988609489e+01,2.191119260338404533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944584531817400830e+01,5.946526902669401125e+02,3.501443590784774074e-01,1.100000010988609489e+01,2.190973274936866815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944675440907401764e+01,5.946626902429383108e+02,3.501662687936976659e-01,1.100000010988609489e+01,2.190827289535329098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944766349997402699e+01,5.946726902189396924e+02,3.501881770490674062e-01,1.100000010988609489e+01,2.190681304133791380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944857259087403634e+01,5.946826901949442572e+02,3.502100838445866282e-01,1.100000010988609489e+01,2.190535318732253663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.944948168177404568e+01,5.946926901709520052e+02,3.502319891802553320e-01,1.100000010988609489e+01,2.190389333330715945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945039077267405503e+01,5.947026901469629365e+02,3.502538930560735175e-01,1.100000010988609489e+01,2.190243347929178228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945129986357406437e+01,5.947126901229771647e+02,3.502757954720411848e-01,1.100000010988609489e+01,2.190097362527640510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945220895447407372e+01,5.947226900989945761e+02,3.502976964281583894e-01,1.100000010988609489e+01,2.189951377126102793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945311804537408307e+01,5.947326900750151708e+02,3.503195959244250757e-01,1.100000010988609489e+01,2.189805391724565075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945402713627409241e+01,5.947426900510389487e+02,3.503414939608412437e-01,1.100000010988609489e+01,2.189659406323027357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945493622717410176e+01,5.947526900270659098e+02,3.503633905374068935e-01,1.100000010988609489e+01,2.189513420921489640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945584531807411111e+01,5.947626900030960542e+02,3.503852856541220251e-01,1.100000010988609489e+01,2.189367435519951922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945675440897412045e+01,5.947726899791293818e+02,3.504071793109866384e-01,1.100000010988609489e+01,2.189221450118414205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945766349987412980e+01,5.947826899551658926e+02,3.504290715080007335e-01,1.100000010988609489e+01,2.189075464716876487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945857259077413914e+01,5.947926899312057003e+02,3.504509622451643103e-01,1.100000010988609489e+01,2.188929479315338770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.945948168167414849e+01,5.948026899072486913e+02,3.504728515224773688e-01,1.100000010988609489e+01,2.188783493913801052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946039077257415784e+01,5.948126898832948655e+02,3.504947393399399092e-01,1.100000010988609489e+01,2.188637508512263335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946129986347416718e+01,5.948226898593442229e+02,3.505166256975519312e-01,1.100000010988609489e+01,2.188491523110725617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946220895437417653e+01,5.948326898353967636e+02,3.505385105953134350e-01,1.100000010988609489e+01,2.188345537709187900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946311804527418587e+01,5.948426898114524874e+02,3.505603940332244206e-01,1.100000010988609489e+01,2.188199552307650182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946402713617419522e+01,5.948526897875113946e+02,3.505822760112848879e-01,1.100000010988609489e+01,2.188053566906112465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946493622707420457e+01,5.948626897635734849e+02,3.506041565294948370e-01,1.100000010988609489e+01,2.187907581504574747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946584531797421391e+01,5.948726897396387585e+02,3.506260355878542678e-01,1.100000010988609489e+01,2.187761596103037030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946675440887422326e+01,5.948826897157072153e+02,3.506479131863631804e-01,1.100000010988609489e+01,2.187615610701499312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946766349977423260e+01,5.948926896917789691e+02,3.506697893250215747e-01,1.100000010988609489e+01,2.187469625299961595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946857259067424195e+01,5.949026896678539060e+02,3.506916640038294508e-01,1.100000010988609489e+01,2.187323639898423877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.946948168157425130e+01,5.949126896439320262e+02,3.507135372227867531e-01,1.100000010988609489e+01,2.187177654496886160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947039077247426064e+01,5.949226896200133297e+02,3.507354089818935372e-01,1.100000010988609489e+01,2.187031669095348442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947129986337426999e+01,5.949326895960978163e+02,3.507572792811498030e-01,1.100000010988609489e+01,2.186885683693810725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947220895427427934e+01,5.949426895721854862e+02,3.507791481205555506e-01,1.100000010988609489e+01,2.186739698292273007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947311804517428868e+01,5.949526895482763393e+02,3.508010155001107799e-01,1.100000010988609489e+01,2.186593712890735289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947402713607429803e+01,5.949626895243703757e+02,3.508228814198154910e-01,1.100000010988609489e+01,2.186447727489197572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947493622697430737e+01,5.949726895004675953e+02,3.508447458796696838e-01,1.100000010988609489e+01,2.186301742087659854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947584531787431672e+01,5.949826894765679981e+02,3.508666088796733584e-01,1.100000010988609489e+01,2.186155756686122137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947675440877432607e+01,5.949926894526715841e+02,3.508884704198264592e-01,1.100000010988609489e+01,2.186009771284584419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947766349967433541e+01,5.950026894287783534e+02,3.509103305001290418e-01,1.100000010988609489e+01,2.185863785883046702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947857259057434476e+01,5.950126894048883059e+02,3.509321891205811061e-01,1.100000010988609489e+01,2.185717800481508984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.947948168147435410e+01,5.950226893810015554e+02,3.509540462811826522e-01,1.100000010988609489e+01,2.185571815079971267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948039077237436345e+01,5.950326893571179880e+02,3.509759019819336801e-01,1.100000010988609489e+01,2.185425829678433549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948129986327437280e+01,5.950426893332376039e+02,3.509977562228341896e-01,1.100000010988609489e+01,2.185279844276895832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948220895417438214e+01,5.950526893093604031e+02,3.510196090038841255e-01,1.100000010988609489e+01,2.185133858875358114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948311804507439149e+01,5.950626892854863854e+02,3.510414603250835430e-01,1.100000010988609489e+01,2.184987873473820397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948402713597440084e+01,5.950726892616155510e+02,3.510633101864324424e-01,1.100000010988609489e+01,2.184841888072282679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948493622687441018e+01,5.950826892377478998e+02,3.510851585879308234e-01,1.100000010988609489e+01,2.184695902670744962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948584531777441953e+01,5.950926892138834319e+02,3.511070055295786307e-01,1.100000010988609489e+01,2.184549917269207244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948675440867442887e+01,5.951026891900221472e+02,3.511288510113759198e-01,1.100000010988609489e+01,2.184403931867669527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948766349957443822e+01,5.951126891661640457e+02,3.511506950333226906e-01,1.100000010988609489e+01,2.184257946466131809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948857259047444757e+01,5.951226891423091274e+02,3.511725375954189432e-01,1.100000010988609489e+01,2.184111961064594092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.948948168137445691e+01,5.951326891184573924e+02,3.511943786976646220e-01,1.100000010988609489e+01,2.183965975663056374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949039077227446626e+01,5.951426890946088406e+02,3.512162183400597826e-01,1.100000010988609489e+01,2.183819990261518657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949129986317447560e+01,5.951526890707634720e+02,3.512380565226044249e-01,1.100000010988609489e+01,2.183674004859980939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949220895407448495e+01,5.951626890469212867e+02,3.512598932452985490e-01,1.100000010988609489e+01,2.183528019458443221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949311804497449430e+01,5.951726890230822846e+02,3.512817285081420993e-01,1.100000010988609489e+01,2.183382034056905504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949402713587450364e+01,5.951826889992464658e+02,3.513035623111351313e-01,1.100000010988609489e+01,2.183236048655367786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949493622677451299e+01,5.951926889754138301e+02,3.513253946542776451e-01,1.100000010988609489e+01,2.183090063253830069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949584531767452233e+01,5.952026889515843777e+02,3.513472255375695852e-01,1.100000010988609489e+01,2.182944077852292351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949675440857453168e+01,5.952126889277581085e+02,3.513690549610110070e-01,1.100000010988609489e+01,2.182798092450754634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949766349947454103e+01,5.952226889039351363e+02,3.513908829246019105e-01,1.100000010988609489e+01,2.182652107049216916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949857259037455037e+01,5.952326888801153473e+02,3.514127094283422403e-01,1.100000010988609489e+01,2.182506121647679199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.949948168127455972e+01,5.952426888562987415e+02,3.514345344722320519e-01,1.100000010988609489e+01,2.182360136246141481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950039077217456907e+01,5.952526888324853189e+02,3.514563580562713452e-01,1.100000010988609489e+01,2.182214150844603764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950129986307457841e+01,5.952626888086750796e+02,3.514781801804600647e-01,1.100000010988609489e+01,2.182068165443066046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950220895397458776e+01,5.952726887848680235e+02,3.515000008447982660e-01,1.100000010988609489e+01,2.181922180041528329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950311804487459710e+01,5.952826887610641506e+02,3.515218200492858935e-01,1.100000010988609489e+01,2.181776194639990611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950402713577460645e+01,5.952926887372634610e+02,3.515436377939230028e-01,1.100000010988609489e+01,2.181630209238452894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950493622667461580e+01,5.953026887134659546e+02,3.515654540787095939e-01,1.100000010988609489e+01,2.181484223836915176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950584531757462514e+01,5.953126886896716314e+02,3.515872689036456111e-01,1.100000010988609489e+01,2.181338238435377459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950675440847463449e+01,5.953226886658804915e+02,3.516090822687311102e-01,1.100000010988609489e+01,2.181192253033839741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950766349937464383e+01,5.953326886420925348e+02,3.516308941739660354e-01,1.100000010988609489e+01,2.181046267632302024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950857259027465318e+01,5.953426886183077613e+02,3.516527046193504424e-01,1.100000010988609489e+01,2.180900282230764306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.950948168117466253e+01,5.953526885945261711e+02,3.516745136048842757e-01,1.100000010988609489e+01,2.180754296829226588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951039077207467187e+01,5.953626885707477641e+02,3.516963211305675907e-01,1.100000010988609489e+01,2.180608311427688871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951129986297468122e+01,5.953726885469725403e+02,3.517181271964003320e-01,1.100000010988609489e+01,2.180462326026151153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951220895387469056e+01,5.953826885232004997e+02,3.517399318023825550e-01,1.100000010988609489e+01,2.180316340624613436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951311804477469991e+01,5.953926884994316424e+02,3.517617349485142597e-01,1.100000010988609489e+01,2.180170355223075718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951402713567470926e+01,5.954026884756659683e+02,3.517835366347953907e-01,1.100000010988609489e+01,2.180024369821538001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951493622657471860e+01,5.954126884519034775e+02,3.518053368612260035e-01,1.100000010988609489e+01,2.179878384420000283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951584531747472795e+01,5.954226884281441698e+02,3.518271356278060424e-01,1.100000010988609489e+01,2.179732399018462566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951675440837473730e+01,5.954326884043880455e+02,3.518489329345355632e-01,1.100000010988609489e+01,2.179586413616924848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951766349927474664e+01,5.954426883806351043e+02,3.518707287814145102e-01,1.100000010988609489e+01,2.179440428215387131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951857259017475599e+01,5.954526883568853464e+02,3.518925231684428834e-01,1.100000010988609489e+01,2.179294442813849413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.951948168107476533e+01,5.954626883331387717e+02,3.519143160956207383e-01,1.100000010988609489e+01,2.179148457412311696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952039077197477468e+01,5.954726883093953802e+02,3.519361075629480196e-01,1.100000010988609489e+01,2.179002472010773978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952129986287478403e+01,5.954826882856551720e+02,3.519578975704247825e-01,1.100000010988609489e+01,2.178856486609236261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952220895377479337e+01,5.954926882619181470e+02,3.519796861180509717e-01,1.100000010988609489e+01,2.178710501207698543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952311804467480272e+01,5.955026882381843052e+02,3.520014732058266427e-01,1.100000010988609489e+01,2.178564515806160826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952402713557481206e+01,5.955126882144536467e+02,3.520232588337517399e-01,1.100000010988609489e+01,2.178418530404623108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952493622647482141e+01,5.955226881907261713e+02,3.520450430018262633e-01,1.100000010988609489e+01,2.178272545003085391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952584531737483076e+01,5.955326881670018793e+02,3.520668257100502685e-01,1.100000010988609489e+01,2.178126559601547673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952675440827484010e+01,5.955426881432806567e+02,3.520886069584236999e-01,1.100000010988609489e+01,2.177980574200009956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952766349917484945e+01,5.955526881195626174e+02,3.521103867469466131e-01,1.100000010988609489e+01,2.177834588798472238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952857259007485879e+01,5.955626880958477614e+02,3.521321650756189525e-01,1.100000010988609489e+01,2.177688603396934520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.952948168097486814e+01,5.955726880721360885e+02,3.521539419444407182e-01,1.100000010988609489e+01,2.177542617995396803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953039077187487749e+01,5.955826880484275989e+02,3.521757173534119656e-01,1.100000010988609489e+01,2.177396632593859085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953129986277488683e+01,5.955926880247222925e+02,3.521974913025326392e-01,1.100000010988609489e+01,2.177250647192321368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953220895367489618e+01,5.956026880010201694e+02,3.522192637918027391e-01,1.100000010988609489e+01,2.177104661790783650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953311804457490553e+01,5.956126879773212295e+02,3.522410348212223208e-01,1.100000010988609489e+01,2.176958676389245933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953402713547491487e+01,5.956226879536254728e+02,3.522628043907913287e-01,1.100000010988609489e+01,2.176812690987708215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953493622637492422e+01,5.956326879299328994e+02,3.522845725005097628e-01,1.100000010988609489e+01,2.176666705586170498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953584531727493356e+01,5.956426879062435091e+02,3.523063391503776787e-01,1.100000010988609489e+01,2.176520720184632780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953675440817494291e+01,5.956526878825573021e+02,3.523281043403950208e-01,1.100000010988609489e+01,2.176374734783095063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953766349907495226e+01,5.956626878588742784e+02,3.523498680705617891e-01,1.100000010988609489e+01,2.176228749381557345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953857258997496160e+01,5.956726878351944379e+02,3.523716303408780393e-01,1.100000010988609489e+01,2.176082763980019628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.953948168087497095e+01,5.956826878115177806e+02,3.523933911513437156e-01,1.100000010988609489e+01,2.175936778578481910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954039077177498029e+01,5.956926877878443065e+02,3.524151505019588182e-01,1.100000010988609489e+01,2.175790793176944193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954129986267498964e+01,5.957026877641740157e+02,3.524369083927233470e-01,1.100000010988609489e+01,2.175644807775406475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954220895357499899e+01,5.957126877405069081e+02,3.524586648236373576e-01,1.100000010988609489e+01,2.175498822373868758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954311804447500833e+01,5.957226877168429837e+02,3.524804197947007944e-01,1.100000010988609489e+01,2.175352836972331040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954402713537501768e+01,5.957326876931822426e+02,3.525021733059136575e-01,1.100000010988609489e+01,2.175206851570793323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954493622627502702e+01,5.957426876695245710e+02,3.525239253572759468e-01,1.100000010988609489e+01,2.175060866169255605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954584531717503637e+01,5.957526876458700826e+02,3.525456759487876623e-01,1.100000010988609489e+01,2.174914880767717888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954675440807504572e+01,5.957626876222187775e+02,3.525674250804488596e-01,1.100000010988609489e+01,2.174768895366180170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954766349897505506e+01,5.957726875985706556e+02,3.525891727522594832e-01,1.100000010988609489e+01,2.174622909964642452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954857258987506441e+01,5.957826875749257169e+02,3.526109189642195330e-01,1.100000010988609489e+01,2.174476924563104735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.954948168077507376e+01,5.957926875512839615e+02,3.526326637163290090e-01,1.100000010988609489e+01,2.174330939161567017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955039077167508310e+01,5.958026875276453893e+02,3.526544070085879112e-01,1.100000010988609489e+01,2.174184953760029300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955129986257509245e+01,5.958126875040100003e+02,3.526761488409962952e-01,1.100000010988609489e+01,2.174038968358491582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955220895347510179e+01,5.958226874803777946e+02,3.526978892135541055e-01,1.100000010988609489e+01,2.173892982956953865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955311804437511114e+01,5.958326874567487721e+02,3.527196281262613420e-01,1.100000010988609489e+01,2.173746997555416147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955402713527512049e+01,5.958426874331229328e+02,3.527413655791180047e-01,1.100000010988609489e+01,2.173601012153878430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955493622617512983e+01,5.958526874095002768e+02,3.527631015721240937e-01,1.100000010988609489e+01,2.173455026752340712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955584531707513918e+01,5.958626873858808040e+02,3.527848361052796089e-01,1.100000010988609489e+01,2.173309041350802995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955675440797514852e+01,5.958726873622644007e+02,3.528065691785845504e-01,1.100000010988609489e+01,2.173163055949265277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955766349887515787e+01,5.958826873386511807e+02,3.528283007920389180e-01,1.100000010988609489e+01,2.173017070547727560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955857258977516722e+01,5.958926873150411438e+02,3.528500309456427675e-01,1.100000010988609489e+01,2.172871085146189842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.955948168067517656e+01,5.959026872914342903e+02,3.528717596393960432e-01,1.100000010988609489e+01,2.172725099744652125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956039077157518591e+01,5.959126872678306199e+02,3.528934868732987451e-01,1.100000010988609489e+01,2.172579114343114407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956129986247519525e+01,5.959226872442301328e+02,3.529152126473508733e-01,1.100000010988609489e+01,2.172433128941576690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956220895337520460e+01,5.959326872206328289e+02,3.529369369615524277e-01,1.100000010988609489e+01,2.172287143540038972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956311804427521395e+01,5.959426871970387083e+02,3.529586598159034083e-01,1.100000010988609489e+01,2.172141158138501255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956402713517522329e+01,5.959526871734477709e+02,3.529803812104038152e-01,1.100000010988609489e+01,2.171995172736963537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956493622607523264e+01,5.959626871498600167e+02,3.530021011450536483e-01,1.100000010988609489e+01,2.171849187335425820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956584531697524199e+01,5.959726871262753320e+02,3.530238196198529077e-01,1.100000010988609489e+01,2.171703201933888102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956675440787525133e+01,5.959826871026938306e+02,3.530455366348015933e-01,1.100000010988609489e+01,2.171557216532350384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956766349877526068e+01,5.959926870791155125e+02,3.530672521898997052e-01,1.100000010988609489e+01,2.171411231130812667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956857258967527002e+01,5.960026870555403775e+02,3.530889662851472433e-01,1.100000010988609489e+01,2.171265245729274949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.956948168057527937e+01,5.960126870319684258e+02,3.531106789205442076e-01,1.100000010988609489e+01,2.171119260327737232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957039077147528872e+01,5.960226870083996573e+02,3.531323900960905982e-01,1.100000010988609489e+01,2.170973274926199514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957129986237529806e+01,5.960326869848340721e+02,3.531540998117864150e-01,1.100000010988609489e+01,2.170827289524661797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957220895327530741e+01,5.960426869612716700e+02,3.531758080676316580e-01,1.100000010988609489e+01,2.170681304123124079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957311804417531675e+01,5.960526869377123376e+02,3.531975148636263273e-01,1.100000010988609489e+01,2.170535318721586362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957402713507532610e+01,5.960626869141561883e+02,3.532192201997704228e-01,1.100000010988609489e+01,2.170389333320048644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957493622597533545e+01,5.960726868906032223e+02,3.532409240760639446e-01,1.100000010988609489e+01,2.170243347918510927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957584531687534479e+01,5.960826868670534395e+02,3.532626264925068926e-01,1.100000010988609489e+01,2.170097362516973209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957675440777535414e+01,5.960926868435068400e+02,3.532843274490992669e-01,1.100000010988609489e+01,2.169951377115435492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957766349867536348e+01,5.961026868199634237e+02,3.533060269458410674e-01,1.100000010988609489e+01,2.169805391713897774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957857258957537283e+01,5.961126867964231906e+02,3.533277249827322941e-01,1.100000010988609489e+01,2.169659406312360057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.957948168047538218e+01,5.961226867728861407e+02,3.533494215597728916e-01,1.100000010988609489e+01,2.169513420910822339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958039077137539152e+01,5.961326867493521604e+02,3.533711166769629153e-01,1.100000010988609489e+01,2.169367435509284622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958129986227540087e+01,5.961426867258213633e+02,3.533928103343023652e-01,1.100000010988609489e+01,2.169221450107746904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958220895317541022e+01,5.961526867022937495e+02,3.534145025317912414e-01,1.100000010988609489e+01,2.169075464706209187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958311804407541956e+01,5.961626866787693189e+02,3.534361932694295438e-01,1.100000010988609489e+01,2.168929479304671469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958402713497542891e+01,5.961726866552480715e+02,3.534578825472172725e-01,1.100000010988609489e+01,2.168783493903133752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958493622587543825e+01,5.961826866317300073e+02,3.534795703651544274e-01,1.100000010988609489e+01,2.168637508501596034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958584531677544760e+01,5.961926866082151264e+02,3.535012567232410086e-01,1.100000010988609489e+01,2.168491523100058316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958675440767545695e+01,5.962026865847033150e+02,3.535229416214769604e-01,1.100000010988609489e+01,2.168345537698520599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958766349857546629e+01,5.962126865611946869e+02,3.535446250598623386e-01,1.100000010988609489e+01,2.168199552296982881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958857258947547564e+01,5.962226865376892420e+02,3.535663070383971429e-01,1.100000010988609489e+01,2.168053566895445164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.958948168037548498e+01,5.962326865141869803e+02,3.535879875570813735e-01,1.100000010988609489e+01,2.167907581493907446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959039077127549433e+01,5.962426864906879018e+02,3.536096666159150304e-01,1.100000010988609489e+01,2.167761596092369729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959129986217550368e+01,5.962526864671920066e+02,3.536313442148980579e-01,1.100000010988609489e+01,2.167615610690832011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959220895307551302e+01,5.962626864436991809e+02,3.536530203540305117e-01,1.100000010988609489e+01,2.167469625289294294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959311804397552237e+01,5.962726864202095385e+02,3.536746950333123918e-01,1.100000010988609489e+01,2.167323639887756576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959402713487553171e+01,5.962826863967230793e+02,3.536963682527436981e-01,1.100000010988609489e+01,2.167177654486218859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959493622577554106e+01,5.962926863732398033e+02,3.537180400123244306e-01,1.100000010988609489e+01,2.167031669084681141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959584531667555041e+01,5.963026863497597105e+02,3.537397103120545339e-01,1.100000010988609489e+01,2.166885683683143424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959675440757555975e+01,5.963126863262828010e+02,3.537613791519340634e-01,1.100000010988609489e+01,2.166739698281605706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959766349847556910e+01,5.963226863028089610e+02,3.537830465319630191e-01,1.100000010988609489e+01,2.166593712880067989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959857258937557845e+01,5.963326862793383043e+02,3.538047124521414011e-01,1.100000010988609489e+01,2.166447727478530271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.959948168027558779e+01,5.963426862558708308e+02,3.538263769124691538e-01,1.100000010988609489e+01,2.166301742076992554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960039077117559714e+01,5.963526862324065405e+02,3.538480399129463327e-01,1.100000010988609489e+01,2.166155756675454836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960129986207560648e+01,5.963626862089454335e+02,3.538697014535729379e-01,1.100000010988609489e+01,2.166009771273917119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960220895297561583e+01,5.963726861854873960e+02,3.538913615343489139e-01,1.100000010988609489e+01,2.165863785872379401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960311804387562518e+01,5.963826861620325417e+02,3.539130201552743160e-01,1.100000010988609489e+01,2.165717800470841684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960402713477563452e+01,5.963926861385808706e+02,3.539346773163491444e-01,1.100000010988609489e+01,2.165571815069303966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960493622567564387e+01,5.964026861151323828e+02,3.539563330175733435e-01,1.100000010988609489e+01,2.165425829667766248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960584531657565321e+01,5.964126860916870783e+02,3.539779872589469689e-01,1.100000010988609489e+01,2.165279844266228531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960675440747566256e+01,5.964226860682449569e+02,3.539996400404700205e-01,1.100000010988609489e+01,2.165133858864690813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960766349837567191e+01,5.964326860448059051e+02,3.540212913621424429e-01,1.100000010988609489e+01,2.164987873463153096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960857258927568125e+01,5.964426860213700365e+02,3.540429412239642915e-01,1.100000010988609489e+01,2.164841888061615378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.960948168017569060e+01,5.964526859979373512e+02,3.540645896259355663e-01,1.100000010988609489e+01,2.164695902660077661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961039077107569994e+01,5.964626859745078491e+02,3.540862365680562118e-01,1.100000010988609489e+01,2.164549917258539943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961129986197570929e+01,5.964726859510815302e+02,3.541078820503262836e-01,1.100000010988609489e+01,2.164403931857002226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961220895287571864e+01,5.964826859276582809e+02,3.541295260727457261e-01,1.100000010988609489e+01,2.164257946455464508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961311804377572798e+01,5.964926859042382148e+02,3.541511686353145949e-01,1.100000010988609489e+01,2.164111961053926791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961402713467573733e+01,5.965026858808213319e+02,3.541728097380328899e-01,1.100000010988609489e+01,2.163965975652389073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961493622557574668e+01,5.965126858574076323e+02,3.541944493809005556e-01,1.100000010988609489e+01,2.163819990250851356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961584531647575602e+01,5.965226858339970022e+02,3.542160875639176476e-01,1.100000010988609489e+01,2.163674004849313638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961675440737576537e+01,5.965326858105895553e+02,3.542377242870841103e-01,1.100000010988609489e+01,2.163528019447775921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961766349827577471e+01,5.965426857871852917e+02,3.542593595503999993e-01,1.100000010988609489e+01,2.163382034046238203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961857258917578406e+01,5.965526857637842113e+02,3.542809933538652589e-01,1.100000010988609489e+01,2.163236048644700486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.961948168007579341e+01,5.965626857403863141e+02,3.543026256974799448e-01,1.100000010988609489e+01,2.163090063243162768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962039077097580275e+01,5.965726857169914865e+02,3.543242565812440570e-01,1.100000010988609489e+01,2.162944077841625051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962129986187581210e+01,5.965826856935998421e+02,3.543458860051575399e-01,1.100000010988609489e+01,2.162798092440087333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962220895277582144e+01,5.965926856702113810e+02,3.543675139692204490e-01,1.100000010988609489e+01,2.162652107038549616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962311804367583079e+01,5.966026856468261030e+02,3.543891404734327288e-01,1.100000010988609489e+01,2.162506121637011898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962402713457584014e+01,5.966126856234438947e+02,3.544107655177944349e-01,1.100000010988609489e+01,2.162360136235474180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962493622547584948e+01,5.966226856000648695e+02,3.544323891023055118e-01,1.100000010988609489e+01,2.162214150833936463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962584531637585883e+01,5.966326855766890276e+02,3.544540112269660148e-01,1.100000010988609489e+01,2.162068165432398745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962675440727586818e+01,5.966426855533163689e+02,3.544756318917758886e-01,1.100000010988609489e+01,2.161922180030861028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962766349817587752e+01,5.966526855299468934e+02,3.544972510967351331e-01,1.100000010988609489e+01,2.161776194629323310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962857258907588687e+01,5.966626855065804875e+02,3.545188688418438039e-01,1.100000010988609489e+01,2.161630209227785593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.962948167997589621e+01,5.966726854832172648e+02,3.545404851271018454e-01,1.100000010988609489e+01,2.161484223826247875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963039077087590556e+01,5.966826854598572254e+02,3.545620999525093131e-01,1.100000010988609489e+01,2.161338238424710158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963129986177591491e+01,5.966926854365003692e+02,3.545837133180661516e-01,1.100000010988609489e+01,2.161192253023172440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963220895267592425e+01,5.967026854131465825e+02,3.546053252237724163e-01,1.100000010988609489e+01,2.161046267621634723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963311804357593360e+01,5.967126853897959791e+02,3.546269356696280517e-01,1.100000010988609489e+01,2.160900282220097005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963402713447594294e+01,5.967226853664485589e+02,3.546485446556331134e-01,1.100000010988609489e+01,2.160754296818559288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963493622537595229e+01,5.967326853431043219e+02,3.546701521817875458e-01,1.100000010988609489e+01,2.160608311417021570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963584531627596164e+01,5.967426853197631544e+02,3.546917582480913489e-01,1.100000010988609489e+01,2.160462326015483853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963675440717597098e+01,5.967526852964251702e+02,3.547133628545445783e-01,1.100000010988609489e+01,2.160316340613946135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963766349807598033e+01,5.967626852730903693e+02,3.547349660011471784e-01,1.100000010988609489e+01,2.160170355212408418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963857258897598967e+01,5.967726852497587515e+02,3.547565676878991492e-01,1.100000010988609489e+01,2.160024369810870700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.963948167987599902e+01,5.967826852264302033e+02,3.547781679148005463e-01,1.100000010988609489e+01,2.159878384409332983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964039077077600837e+01,5.967926852031048384e+02,3.547997666818513141e-01,1.100000010988609489e+01,2.159732399007795265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964129986167601771e+01,5.968026851797826566e+02,3.548213639890514526e-01,1.100000010988609489e+01,2.159586413606257548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964220895257602706e+01,5.968126851564635444e+02,3.548429598364010173e-01,1.100000010988609489e+01,2.159440428204719830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964311804347603641e+01,5.968226851331476155e+02,3.548645542238999528e-01,1.100000010988609489e+01,2.159294442803182112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964402713437604575e+01,5.968326851098348698e+02,3.548861471515482591e-01,1.100000010988609489e+01,2.159148457401644395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964493622527605510e+01,5.968426850865253073e+02,3.549077386193459915e-01,1.100000010988609489e+01,2.159002472000106677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964584531617606444e+01,5.968526850632188143e+02,3.549293286272930947e-01,1.100000010988609489e+01,2.158856486598568960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964675440707607379e+01,5.968626850399155046e+02,3.549509171753895687e-01,1.100000010988609489e+01,2.158710501197031242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964766349797608314e+01,5.968726850166153781e+02,3.549725042636354688e-01,1.100000010988609489e+01,2.158564515795493525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964857258887609248e+01,5.968826849933184349e+02,3.549940898920307397e-01,1.100000010988609489e+01,2.158418530393955807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.964948167977610183e+01,5.968926849700245612e+02,3.550156740605753813e-01,1.100000010988609489e+01,2.158272544992418090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965039077067611117e+01,5.969026849467338707e+02,3.550372567692693937e-01,1.100000010988609489e+01,2.158126559590880372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965129986157612052e+01,5.969126849234463634e+02,3.550588380181128323e-01,1.100000010988609489e+01,2.157980574189342655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965220895247612987e+01,5.969226849001619257e+02,3.550804178071056416e-01,1.100000010988609489e+01,2.157834588787804937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965311804337613921e+01,5.969326848768806713e+02,3.551019961362478217e-01,1.100000010988609489e+01,2.157688603386267220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965402713427614856e+01,5.969426848536026000e+02,3.551235730055393724e-01,1.100000010988609489e+01,2.157542617984729502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965493622517615790e+01,5.969526848303277120e+02,3.551451484149803495e-01,1.100000010988609489e+01,2.157396632583191785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965584531607616725e+01,5.969626848070558935e+02,3.551667223645706972e-01,1.100000010988609489e+01,2.157250647181654067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965675440697617660e+01,5.969726847837872583e+02,3.551882948543104157e-01,1.100000010988609489e+01,2.157104661780116350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965766349787618594e+01,5.969826847605218063e+02,3.552098658841995049e-01,1.100000010988609489e+01,2.156958676378578632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965857258877619529e+01,5.969926847372594239e+02,3.552314354542379649e-01,1.100000010988609489e+01,2.156812690977040915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.965948167967620464e+01,5.970026847140002246e+02,3.552530035644257955e-01,1.100000010988609489e+01,2.156666705575503197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966039077057621398e+01,5.970126846907442086e+02,3.552745702147630524e-01,1.100000010988609489e+01,2.156520720173965480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966129986147622333e+01,5.970226846674912622e+02,3.552961354052496801e-01,1.100000010988609489e+01,2.156374734772427762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966220895237623267e+01,5.970326846442414990e+02,3.553176991358856784e-01,1.100000010988609489e+01,2.156228749370890044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966311804327624202e+01,5.970426846209949190e+02,3.553392614066710475e-01,1.100000010988609489e+01,2.156082763969352327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966402713417625137e+01,5.970526845977514085e+02,3.553608222176057874e-01,1.100000010988609489e+01,2.155936778567814609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966493622507626071e+01,5.970626845745110813e+02,3.553823815686898979e-01,1.100000010988609489e+01,2.155790793166276892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966584531597627006e+01,5.970726845512739374e+02,3.554039394599233792e-01,1.100000010988609489e+01,2.155644807764739174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966675440687627940e+01,5.970826845280399766e+02,3.554254958913062867e-01,1.100000010988609489e+01,2.155498822363201457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966766349777628875e+01,5.970926845048090854e+02,3.554470508628385650e-01,1.100000010988609489e+01,2.155352836961663739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966857258867629810e+01,5.971026844815813774e+02,3.554686043745202140e-01,1.100000010988609489e+01,2.155206851560126022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.966948167957630744e+01,5.971126844583568527e+02,3.554901564263512337e-01,1.100000010988609489e+01,2.155060866158588304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967039077047631679e+01,5.971226844351353975e+02,3.555117070183316241e-01,1.100000010988609489e+01,2.154914880757050587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967129986137632613e+01,5.971326844119171255e+02,3.555332561504613853e-01,1.100000010988609489e+01,2.154768895355512869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967220895227633548e+01,5.971426843887020368e+02,3.555548038227405172e-01,1.100000010988609489e+01,2.154622909953975152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967311804317634483e+01,5.971526843654900176e+02,3.555763500351690198e-01,1.100000010988609489e+01,2.154476924552437434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967402713407635417e+01,5.971626843422811817e+02,3.555978947877468932e-01,1.100000010988609489e+01,2.154330939150899717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967493622497636352e+01,5.971726843190755289e+02,3.556194380804741373e-01,1.100000010988609489e+01,2.154184953749361999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967584531587637287e+01,5.971826842958729458e+02,3.556409799133507521e-01,1.100000010988609489e+01,2.154038968347824282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967675440677638221e+01,5.971926842726735458e+02,3.556625202863767377e-01,1.100000010988609489e+01,2.153892982946286564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967766349767639156e+01,5.972026842494773291e+02,3.556840591995520939e-01,1.100000010988609489e+01,2.153746997544748847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967857258857640090e+01,5.972126842262841819e+02,3.557055966528768209e-01,1.100000010988609489e+01,2.153601012143211129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.967948167947641025e+01,5.972226842030942180e+02,3.557271326463509187e-01,1.100000010988609489e+01,2.153455026741673412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968039077037641960e+01,5.972326841799074373e+02,3.557486671799743871e-01,1.100000010988609489e+01,2.153309041340135694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968129986127642894e+01,5.972426841567237261e+02,3.557702002537472263e-01,1.100000010988609489e+01,2.153163055938597976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968220895217643829e+01,5.972526841335431982e+02,3.557917318676694363e-01,1.100000010988609489e+01,2.153017070537060259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968311804307644763e+01,5.972626841103657398e+02,3.558132620217410169e-01,1.100000010988609489e+01,2.152871085135522541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968402713397645698e+01,5.972726840871914646e+02,3.558347907159619683e-01,1.100000010988609489e+01,2.152725099733984824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968493622487646633e+01,5.972826840640203727e+02,3.558563179503322904e-01,1.100000010988609489e+01,2.152579114332447106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968584531577647567e+01,5.972926840408523503e+02,3.558778437248519833e-01,1.100000010988609489e+01,2.152433128930909389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968675440667648502e+01,5.973026840176875112e+02,3.558993680395210468e-01,1.100000010988609489e+01,2.152287143529371671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968766349757649436e+01,5.973126839945258553e+02,3.559208908943394811e-01,1.100000010988609489e+01,2.152141158127833954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968857258847650371e+01,5.973226839713672689e+02,3.559424122893072862e-01,1.100000010988609489e+01,2.151995172726296236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.968948167937651306e+01,5.973326839482118658e+02,3.559639322244244619e-01,1.100000010988609489e+01,2.151849187324758519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969039077027652240e+01,5.973426839250596458e+02,3.559854506996909529e-01,1.100000010988609489e+01,2.151703201923220801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969129986117653175e+01,5.973526839019104955e+02,3.560069677151068146e-01,1.100000010988609489e+01,2.151557216521683084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969220895207654110e+01,5.973626838787645283e+02,3.560284832706720470e-01,1.100000010988609489e+01,2.151411231120145366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969311804297655044e+01,5.973726838556216308e+02,3.560499973663866502e-01,1.100000010988609489e+01,2.151265245718607649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969402713387655979e+01,5.973826838324819164e+02,3.560715100022506241e-01,1.100000010988609489e+01,2.151119260317069931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969493622477656913e+01,5.973926838093453853e+02,3.560930211782639687e-01,1.100000010988609489e+01,2.150973274915532214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969584531567657848e+01,5.974026837862119237e+02,3.561145308944266841e-01,1.100000010988609489e+01,2.150827289513994496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969675440657658783e+01,5.974126837630816453e+02,3.561360391507387146e-01,1.100000010988609489e+01,2.150681304112456779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969766349747659717e+01,5.974226837399545502e+02,3.561575459472001159e-01,1.100000010988609489e+01,2.150535318710919061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969857258837660652e+01,5.974326837168305246e+02,3.561790512838108880e-01,1.100000010988609489e+01,2.150389333309381344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.969948167927661586e+01,5.974426836937096823e+02,3.562005551605710307e-01,1.100000010988609489e+01,2.150243347907843626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970039077017662521e+01,5.974526836705919095e+02,3.562220575774805442e-01,1.100000010988609489e+01,2.150097362506305908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970129986107663456e+01,5.974626836474773199e+02,3.562435585345394284e-01,1.100000010988609489e+01,2.149951377104768191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970220895197664390e+01,5.974726836243659136e+02,3.562650580317476279e-01,1.100000010988609489e+01,2.149805391703230473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970311804287665325e+01,5.974826836012575768e+02,3.562865560691051980e-01,1.100000010988609489e+01,2.149659406301692756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970402713377666259e+01,5.974926835781524233e+02,3.563080526466121389e-01,1.100000010988609489e+01,2.149513420900155038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970493622467667194e+01,5.975026835550503392e+02,3.563295477642684506e-01,1.100000010988609489e+01,2.149367435498617321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970584531557668129e+01,5.975126835319514385e+02,3.563510414220740774e-01,1.100000010988609489e+01,2.149221450097079603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970675440647669063e+01,5.975226835088557209e+02,3.563725336200290750e-01,1.100000010988609489e+01,2.149075464695541886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970766349737669998e+01,5.975326834857630729e+02,3.563940243581334433e-01,1.100000010988609489e+01,2.148929479294004168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970857258827670933e+01,5.975426834626736081e+02,3.564155136363871823e-01,1.100000010988609489e+01,2.148783493892466451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.970948167917671867e+01,5.975526834395872129e+02,3.564370014547902366e-01,1.100000010988609489e+01,2.148637508490928733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971039077007672802e+01,5.975626834165040009e+02,3.564584878133426615e-01,1.100000010988609489e+01,2.148491523089391016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971129986097673736e+01,5.975726833934239721e+02,3.564799727120444572e-01,1.100000010988609489e+01,2.148345537687853298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971220895187674671e+01,5.975826833703470129e+02,3.565014561508955682e-01,1.100000010988609489e+01,2.148199552286315581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971311804277675606e+01,5.975926833472732369e+02,3.565229381298960498e-01,1.100000010988609489e+01,2.148053566884777863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971402713367676540e+01,5.976026833242025305e+02,3.565444186490459022e-01,1.100000010988609489e+01,2.147907581483240146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971493622457677475e+01,5.976126833011350072e+02,3.565658977083450698e-01,1.100000010988609489e+01,2.147761596081702428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971584531547678409e+01,5.976226832780706673e+02,3.565873753077936081e-01,1.100000010988609489e+01,2.147615610680164711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971675440637679344e+01,5.976326832550093968e+02,3.566088514473915172e-01,1.100000010988609489e+01,2.147469625278626993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971766349727680279e+01,5.976426832319513096e+02,3.566303261271387415e-01,1.100000010988609489e+01,2.147323639877089275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971857258817681213e+01,5.976526832088962919e+02,3.566517993470353365e-01,1.100000010988609489e+01,2.147177654475551558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.971948167907682148e+01,5.976626831858444575e+02,3.566732711070813022e-01,1.100000010988609489e+01,2.147031669074013840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972039076997683082e+01,5.976726831627956926e+02,3.566947414072765832e-01,1.100000010988609489e+01,2.146885683672476123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972129986087684017e+01,5.976826831397501110e+02,3.567162102476212349e-01,1.100000010988609489e+01,2.146739698270938405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972220895177684952e+01,5.976926831167077125e+02,3.567376776281152018e-01,1.100000010988609489e+01,2.146593712869400688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972311804267685886e+01,5.977026830936683837e+02,3.567591435487585394e-01,1.100000010988609489e+01,2.146447727467862970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972402713357686821e+01,5.977126830706322380e+02,3.567806080095512478e-01,1.100000010988609489e+01,2.146301742066325253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972493622447687756e+01,5.977226830475991619e+02,3.568020710104932713e-01,1.100000010988609489e+01,2.146155756664787535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972584531537688690e+01,5.977326830245692690e+02,3.568235325515846657e-01,1.100000010988609489e+01,2.146009771263249818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972675440627689625e+01,5.977426830015424457e+02,3.568449926328253752e-01,1.100000010988609489e+01,2.145863785861712100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972766349717690559e+01,5.977526829785188056e+02,3.568664512542154554e-01,1.100000010988609489e+01,2.145717800460174383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972857258807691494e+01,5.977626829554982351e+02,3.568879084157548509e-01,1.100000010988609489e+01,2.145571815058636665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.972948167897692429e+01,5.977726829324808477e+02,3.569093641174436171e-01,1.100000010988609489e+01,2.145425829657098948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973039076987693363e+01,5.977826829094666437e+02,3.569308183592817540e-01,1.100000010988609489e+01,2.145279844255561230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973129986077694298e+01,5.977926828864555091e+02,3.569522711412692062e-01,1.100000010988609489e+01,2.145133858854023513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973220895167695232e+01,5.978026828634475578e+02,3.569737224634060291e-01,1.100000010988609489e+01,2.144987873452485795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973311804257696167e+01,5.978126828404426760e+02,3.569951723256921672e-01,1.100000010988609489e+01,2.144841888050948078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973402713347697102e+01,5.978226828174409775e+02,3.570166207281276760e-01,1.100000010988609489e+01,2.144695902649410360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973493622437698036e+01,5.978326827944423485e+02,3.570380676707125001e-01,1.100000010988609489e+01,2.144549917247872643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973584531527698971e+01,5.978426827714469027e+02,3.570595131534466948e-01,1.100000010988609489e+01,2.144403931846334925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973675440617699905e+01,5.978526827484545265e+02,3.570809571763302048e-01,1.100000010988609489e+01,2.144257946444797207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973766349707700840e+01,5.978626827254653335e+02,3.571023997393630300e-01,1.100000010988609489e+01,2.144111961043259490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973857258797701775e+01,5.978726827024792101e+02,3.571238408425452260e-01,1.100000010988609489e+01,2.143965975641721772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.973948167887702709e+01,5.978826826794962699e+02,3.571452804858767371e-01,1.100000010988609489e+01,2.143819990240184055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974039076977703644e+01,5.978926826565165129e+02,3.571667186693576190e-01,1.100000010988609489e+01,2.143674004838646337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974129986067704579e+01,5.979026826335398255e+02,3.571881553929878161e-01,1.100000010988609489e+01,2.143528019437108620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974220895157705513e+01,5.979126826105663213e+02,3.572095906567673840e-01,1.100000010988609489e+01,2.143382034035570902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974311804247706448e+01,5.979226825875958866e+02,3.572310244606962670e-01,1.100000010988609489e+01,2.143236048634033185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974402713337707382e+01,5.979326825646286352e+02,3.572524568047745208e-01,1.100000010988609489e+01,2.143090063232495467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974493622427708317e+01,5.979426825416644533e+02,3.572738876890020898e-01,1.100000010988609489e+01,2.142944077830957750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974584531517709252e+01,5.979526825187034547e+02,3.572953171133789740e-01,1.100000010988609489e+01,2.142798092429420032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974675440607710186e+01,5.979626824957455256e+02,3.573167450779052290e-01,1.100000010988609489e+01,2.142652107027882315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974766349697711121e+01,5.979726824727907797e+02,3.573381715825807992e-01,1.100000010988609489e+01,2.142506121626344597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974857258787712055e+01,5.979826824498391034e+02,3.573595966274056845e-01,1.100000010988609489e+01,2.142360136224806880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.974948167877712990e+01,5.979926824268906103e+02,3.573810202123799407e-01,1.100000010988609489e+01,2.142214150823269162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975039076967713925e+01,5.980026824039451867e+02,3.574024423375035120e-01,1.100000010988609489e+01,2.142068165421731445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975129986057714859e+01,5.980126823810029464e+02,3.574238630027763985e-01,1.100000010988609489e+01,2.141922180020193727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975220895147715794e+01,5.980226823580637756e+02,3.574452822081986558e-01,1.100000010988609489e+01,2.141776194618656010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975311804237716728e+01,5.980326823351277881e+02,3.574666999537702283e-01,1.100000010988609489e+01,2.141630209217118292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975402713327717663e+01,5.980426823121948701e+02,3.574881162394911160e-01,1.100000010988609489e+01,2.141484223815580575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975493622417718598e+01,5.980526822892651353e+02,3.575095310653613745e-01,1.100000010988609489e+01,2.141338238414042857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975584531507719532e+01,5.980626822663384701e+02,3.575309444313809482e-01,1.100000010988609489e+01,2.141192253012505139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975675440597720467e+01,5.980726822434149881e+02,3.575523563375498370e-01,1.100000010988609489e+01,2.141046267610967422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975766349687721402e+01,5.980826822204945756e+02,3.575737667838680967e-01,1.100000010988609489e+01,2.140900282209429704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975857258777722336e+01,5.980926821975773464e+02,3.575951757703356715e-01,1.100000010988609489e+01,2.140754296807891987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.975948167867723271e+01,5.981026821746631867e+02,3.576165832969525615e-01,1.100000010988609489e+01,2.140608311406354269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976039076957724205e+01,5.981126821517522103e+02,3.576379893637187668e-01,1.100000010988609489e+01,2.140462326004816552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976129986047725140e+01,5.981226821288443034e+02,3.576593939706343428e-01,1.100000010988609489e+01,2.140316340603278834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976220895137726075e+01,5.981326821059395797e+02,3.576807971176992340e-01,1.100000010988609489e+01,2.140170355201741117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976311804227727009e+01,5.981426820830379256e+02,3.577021988049134404e-01,1.100000010988609489e+01,2.140024369800203399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976402713317727944e+01,5.981526820601394547e+02,3.577235990322769621e-01,1.100000010988609489e+01,2.139878384398665682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976493622407728878e+01,5.981626820372440534e+02,3.577449977997898545e-01,1.100000010988609489e+01,2.139732398997127964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976584531497729813e+01,5.981726820143518353e+02,3.577663951074520621e-01,1.100000010988609489e+01,2.139586413595590247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976675440587730748e+01,5.981826819914626867e+02,3.577877909552635849e-01,1.100000010988609489e+01,2.139440428194052529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976766349677731682e+01,5.981926819685767214e+02,3.578091853432244229e-01,1.100000010988609489e+01,2.139294442792514812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976857258767732617e+01,5.982026819456938256e+02,3.578305782713345762e-01,1.100000010988609489e+01,2.139148457390977094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.976948167857733552e+01,5.982126819228139993e+02,3.578519697395941002e-01,1.100000010988609489e+01,2.139002471989439377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977039076947734486e+01,5.982226818999373563e+02,3.578733597480029394e-01,1.100000010988609489e+01,2.138856486587901659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977129986037735421e+01,5.982326818770637828e+02,3.578947482965610938e-01,1.100000010988609489e+01,2.138710501186363942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977220895127736355e+01,5.982426818541933926e+02,3.579161353852685634e-01,1.100000010988609489e+01,2.138564515784826224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977311804217737290e+01,5.982526818313260719e+02,3.579375210141253483e-01,1.100000010988609489e+01,2.138418530383288507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977402713307738225e+01,5.982626818084619345e+02,3.579589051831314483e-01,1.100000010988609489e+01,2.138272544981750789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977493622397739159e+01,5.982726817856008665e+02,3.579802878922868636e-01,1.100000010988609489e+01,2.138126559580213071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977584531487740094e+01,5.982826817627429818e+02,3.580016691415916497e-01,1.100000010988609489e+01,2.137980574178675354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977675440577741028e+01,5.982926817398881667e+02,3.580230489310457509e-01,1.100000010988609489e+01,2.137834588777137636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977766349667741963e+01,5.983026817170365348e+02,3.580444272606491674e-01,1.100000010988609489e+01,2.137688603375599919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977857258757742898e+01,5.983126816941879724e+02,3.580658041304018990e-01,1.100000010988609489e+01,2.137542617974062201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.977948167847743832e+01,5.983226816713425933e+02,3.580871795403039459e-01,1.100000010988609489e+01,2.137396632572524484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978039076937744767e+01,5.983326816485002837e+02,3.581085534903553080e-01,1.100000010988609489e+01,2.137250647170986766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978129986027745701e+01,5.983426816256610437e+02,3.581299259805559854e-01,1.100000010988609489e+01,2.137104661769449049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978220895117746636e+01,5.983526816028249868e+02,3.581512970109059779e-01,1.100000010988609489e+01,2.136958676367911331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978311804207747571e+01,5.983626815799919996e+02,3.581726665814052857e-01,1.100000010988609489e+01,2.136812690966373614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978402713297748505e+01,5.983726815571621955e+02,3.581940346920539087e-01,1.100000010988609489e+01,2.136666705564835896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978493622387749440e+01,5.983826815343354610e+02,3.582154013428518469e-01,1.100000010988609489e+01,2.136520720163298179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978584531477750375e+01,5.983926815115119098e+02,3.582367665337991003e-01,1.100000010988609489e+01,2.136374734761760461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978675440567751309e+01,5.984026814886914281e+02,3.582581302648956689e-01,1.100000010988609489e+01,2.136228749360222744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978766349657752244e+01,5.984126814658740159e+02,3.582794925361415528e-01,1.100000010988609489e+01,2.136082763958685026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978857258747753178e+01,5.984226814430597869e+02,3.583008533475367519e-01,1.100000010988609489e+01,2.135936778557147309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.978948167837754113e+01,5.984326814202486275e+02,3.583222126990812662e-01,1.100000010988609489e+01,2.135790793155609591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979039076927755048e+01,5.984426813974406514e+02,3.583435705907750957e-01,1.100000010988609489e+01,2.135644807754071874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979129986017755982e+01,5.984526813746357448e+02,3.583649270226182404e-01,1.100000010988609489e+01,2.135498822352534156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979220895107756917e+01,5.984626813518340214e+02,3.583862819946107003e-01,1.100000010988609489e+01,2.135352836950996439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979311804197757851e+01,5.984726813290353675e+02,3.584076355067524755e-01,1.100000010988609489e+01,2.135206851549458721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979402713287758786e+01,5.984826813062397832e+02,3.584289875590435659e-01,1.100000010988609489e+01,2.135060866147921003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979493622377759721e+01,5.984926812834473822e+02,3.584503381514839715e-01,1.100000010988609489e+01,2.134914880746383286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979584531467760655e+01,5.985026812606580506e+02,3.584716872840736923e-01,1.100000010988609489e+01,2.134768895344845568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979675440557761590e+01,5.985126812378719023e+02,3.584930349568127284e-01,1.100000010988609489e+01,2.134622909943307851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979766349647762524e+01,5.985226812150888236e+02,3.585143811697010796e-01,1.100000010988609489e+01,2.134476924541770133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979857258737763459e+01,5.985326811923089281e+02,3.585357259227387461e-01,1.100000010988609489e+01,2.134330939140232416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.979948167827764394e+01,5.985426811695321021e+02,3.585570692159257278e-01,1.100000010988609489e+01,2.134184953738694698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980039076917765328e+01,5.985526811467583457e+02,3.585784110492620247e-01,1.100000010988609489e+01,2.134038968337156981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980129986007766263e+01,5.985626811239877725e+02,3.585997514227476368e-01,1.100000010988609489e+01,2.133892982935619263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980220895097767198e+01,5.985726811012202688e+02,3.586210903363825087e-01,1.100000010988609489e+01,2.133746997534081546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980311804187768132e+01,5.985826810784559484e+02,3.586424277901666957e-01,1.100000010988609489e+01,2.133601012132543828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980402713277769067e+01,5.985926810556946975e+02,3.586637637841001980e-01,1.100000010988609489e+01,2.133455026731006111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980493622367770001e+01,5.986026810329365162e+02,3.586850983181830155e-01,1.100000010988609489e+01,2.133309041329468393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980584531457770936e+01,5.986126810101815181e+02,3.587064313924151482e-01,1.100000010988609489e+01,2.133163055927930676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980675440547771871e+01,5.986226809874295895e+02,3.587277630067965961e-01,1.100000010988609489e+01,2.133017070526392958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980766349637772805e+01,5.986326809646808442e+02,3.587490931613273037e-01,1.100000010988609489e+01,2.132871085124855241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980857258727773740e+01,5.986426809419351684e+02,3.587704218560073266e-01,1.100000010988609489e+01,2.132725099723317523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.980948167817774674e+01,5.986526809191925622e+02,3.587917490908366647e-01,1.100000010988609489e+01,2.132579114321779806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981039076907775609e+01,5.986626808964531392e+02,3.588130748658153180e-01,1.100000010988609489e+01,2.132433128920242088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981129985997776544e+01,5.986726808737167858e+02,3.588343991809432865e-01,1.100000010988609489e+01,2.132287143518704371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981220895087777478e+01,5.986826808509835018e+02,3.588557220362205702e-01,1.100000010988609489e+01,2.132141158117166653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981311804177778413e+01,5.986926808282534012e+02,3.588770434316471136e-01,1.100000010988609489e+01,2.131995172715628935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981402713267779347e+01,5.987026808055263700e+02,3.588983633672229723e-01,1.100000010988609489e+01,2.131849187314091218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981493622357780282e+01,5.987126807828025221e+02,3.589196818429481461e-01,1.100000010988609489e+01,2.131703201912553500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981584531447781217e+01,5.987226807600817438e+02,3.589409988588226352e-01,1.100000010988609489e+01,2.131557216511015783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981675440537782151e+01,5.987326807373640349e+02,3.589623144148463840e-01,1.100000010988609489e+01,2.131411231109478065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981766349627783086e+01,5.987426807146495094e+02,3.589836285110194480e-01,1.100000010988609489e+01,2.131265245707940348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981857258717784021e+01,5.987526806919380533e+02,3.590049411473418273e-01,1.100000010988609489e+01,2.131119260306402630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.981948167807784955e+01,5.987626806692296668e+02,3.590262523238135217e-01,1.100000010988609489e+01,2.130973274904864913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982039076897785890e+01,5.987726806465244636e+02,3.590475620404344759e-01,1.100000010988609489e+01,2.130827289503327195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982129985987786824e+01,5.987826806238223298e+02,3.590688702972047452e-01,1.100000010988609489e+01,2.130681304101789478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982220895077787759e+01,5.987926806011233793e+02,3.590901770941243298e-01,1.100000010988609489e+01,2.130535318700251760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982311804167788694e+01,5.988026805784274984e+02,3.591114824311931741e-01,1.100000010988609489e+01,2.130389333298714043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982402713257789628e+01,5.988126805557346870e+02,3.591327863084113337e-01,1.100000010988609489e+01,2.130243347897176325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982493622347790563e+01,5.988226805330450588e+02,3.591540887257788084e-01,1.100000010988609489e+01,2.130097362495638608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982584531437791497e+01,5.988326805103585002e+02,3.591753896832955428e-01,1.100000010988609489e+01,2.129951377094100890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982675440527792432e+01,5.988426804876750111e+02,3.591966891809615925e-01,1.100000010988609489e+01,2.129805391692563173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982766349617793367e+01,5.988526804649947053e+02,3.592179872187769574e-01,1.100000010988609489e+01,2.129659406291025455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982857258707794301e+01,5.988626804423174690e+02,3.592392837967415820e-01,1.100000010988609489e+01,2.129513420889487738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.982948167797795236e+01,5.988726804196433022e+02,3.592605789148555218e-01,1.100000010988609489e+01,2.129367435487950020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983039076887796170e+01,5.988826803969723187e+02,3.592818725731187768e-01,1.100000010988609489e+01,2.129221450086412303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983129985977797105e+01,5.988926803743044047e+02,3.593031647715312915e-01,1.100000010988609489e+01,2.129075464684874585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983220895067798040e+01,5.989026803516395603e+02,3.593244555100931215e-01,1.100000010988609489e+01,2.128929479283336867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983311804157798974e+01,5.989126803289778991e+02,3.593457447888042111e-01,1.100000010988609489e+01,2.128783493881799150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983402713247799909e+01,5.989226803063193074e+02,3.593670326076646160e-01,1.100000010988609489e+01,2.128637508480261432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983493622337800844e+01,5.989326802836637853e+02,3.593883189666743361e-01,1.100000010988609489e+01,2.128491523078723715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983584531427801778e+01,5.989426802610114464e+02,3.594096038658333159e-01,1.100000010988609489e+01,2.128345537677185997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983675440517802713e+01,5.989526802383621771e+02,3.594308873051416109e-01,1.100000010988609489e+01,2.128199552275648280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983766349607803647e+01,5.989626802157159773e+02,3.594521692845991656e-01,1.100000010988609489e+01,2.128053566874110562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983857258697804582e+01,5.989726801930729607e+02,3.594734498042060356e-01,1.100000010988609489e+01,2.127907581472572845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.983948167787805517e+01,5.989826801704330137e+02,3.594947288639621652e-01,1.100000010988609489e+01,2.127761596071035127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984039076877806451e+01,5.989926801477961362e+02,3.595160064638676101e-01,1.100000010988609489e+01,2.127615610669497410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984129985967807386e+01,5.990026801251624420e+02,3.595372826039223146e-01,1.100000010988609489e+01,2.127469625267959692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984220895057808320e+01,5.990126801025318173e+02,3.595585572841263344e-01,1.100000010988609489e+01,2.127323639866421975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984311804147809255e+01,5.990226800799042621e+02,3.595798305044796694e-01,1.100000010988609489e+01,2.127177654464884257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984402713237810190e+01,5.990326800572798902e+02,3.596011022649822642e-01,1.100000010988609489e+01,2.127031669063346540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984493622327811124e+01,5.990426800346585878e+02,3.596223725656341741e-01,1.100000010988609489e+01,2.126885683661808822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984584531417812059e+01,5.990526800120403550e+02,3.596436414064353437e-01,1.100000010988609489e+01,2.126739698260271105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984675440507812993e+01,5.990626799894253054e+02,3.596649087873857731e-01,1.100000010988609489e+01,2.126593712858733387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984766349597813928e+01,5.990726799668133253e+02,3.596861747084855176e-01,1.100000010988609489e+01,2.126447727457195670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984857258687814863e+01,5.990826799442044148e+02,3.597074391697345219e-01,1.100000010988609489e+01,2.126301742055657952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.984948167777815797e+01,5.990926799215985739e+02,3.597287021711328414e-01,1.100000010988609489e+01,2.126155756654120235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985039076867816732e+01,5.991026798989959161e+02,3.597499637126804206e-01,1.100000010988609489e+01,2.126009771252582517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985129985957817667e+01,5.991126798763963279e+02,3.597712237943773150e-01,1.100000010988609489e+01,2.125863785851044799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985220895047818601e+01,5.991226798537998093e+02,3.597924824162234692e-01,1.100000010988609489e+01,2.125717800449507082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985311804137819536e+01,5.991326798312064739e+02,3.598137395782189385e-01,1.100000010988609489e+01,2.125571815047969364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985402713227820470e+01,5.991426798086162080e+02,3.598349952803636675e-01,1.100000010988609489e+01,2.125425829646431647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985493622317821405e+01,5.991526797860290117e+02,3.598562495226576563e-01,1.100000010988609489e+01,2.125279844244893929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985584531407822340e+01,5.991626797634449986e+02,3.598775023051009603e-01,1.100000010988609489e+01,2.125133858843356212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985675440497823274e+01,5.991726797408640550e+02,3.598987536276935240e-01,1.100000010988609489e+01,2.124987873441818494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985766349587824209e+01,5.991826797182861810e+02,3.599200034904354029e-01,1.100000010988609489e+01,2.124841888040280777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985857258677825143e+01,5.991926796957113766e+02,3.599412518933265415e-01,1.100000010988609489e+01,2.124695902638743059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.985948167767826078e+01,5.992026796731397553e+02,3.599624988363669398e-01,1.100000010988609489e+01,2.124549917237205342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986039076857827013e+01,5.992126796505712036e+02,3.599837443195566533e-01,1.100000010988609489e+01,2.124403931835667624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986129985947827947e+01,5.992226796280057215e+02,3.600049883428956266e-01,1.100000010988609489e+01,2.124257946434129907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986220895037828882e+01,5.992326796054434226e+02,3.600262309063838595e-01,1.100000010988609489e+01,2.124111961032592189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986311804127829816e+01,5.992426795828841932e+02,3.600474720100214077e-01,1.100000010988609489e+01,2.123965975631054472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986402713217830751e+01,5.992526795603280334e+02,3.600687116538082155e-01,1.100000010988609489e+01,2.123819990229516754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986493622307831686e+01,5.992626795377749431e+02,3.600899498377442831e-01,1.100000010988609489e+01,2.123674004827979037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986584531397832620e+01,5.992726795152250361e+02,3.601111865618296659e-01,1.100000010988609489e+01,2.123528019426441319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986675440487833555e+01,5.992826794926781986e+02,3.601324218260643084e-01,1.100000010988609489e+01,2.123382034024903602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986766349577834490e+01,5.992926794701344306e+02,3.601536556304482106e-01,1.100000010988609489e+01,2.123236048623365884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986857258667835424e+01,5.993026794475937322e+02,3.601748879749814281e-01,1.100000010988609489e+01,2.123090063221828167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.986948167757836359e+01,5.993126794250562170e+02,3.601961188596639052e-01,1.100000010988609489e+01,2.122944077820290449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987039076847837293e+01,5.993226794025217714e+02,3.602173482844956420e-01,1.100000010988609489e+01,2.122798092418752731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987129985937838228e+01,5.993326793799903953e+02,3.602385762494766386e-01,1.100000010988609489e+01,2.122652107017215014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987220895027839163e+01,5.993426793574620888e+02,3.602598027546069503e-01,1.100000010988609489e+01,2.122506121615677296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987311804117840097e+01,5.993526793349369655e+02,3.602810277998865218e-01,1.100000010988609489e+01,2.122360136214139579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987402713207841032e+01,5.993626793124149117e+02,3.603022513853153530e-01,1.100000010988609489e+01,2.122214150812601861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987493622297841966e+01,5.993726792898959275e+02,3.603234735108934439e-01,1.100000010988609489e+01,2.122068165411064144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987584531387842901e+01,5.993826792673800128e+02,3.603446941766208500e-01,1.100000010988609489e+01,2.121922180009526426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987675440477843836e+01,5.993926792448672813e+02,3.603659133824975158e-01,1.100000010988609489e+01,2.121776194607988709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987766349567844770e+01,5.994026792223576194e+02,3.603871311285234413e-01,1.100000010988609489e+01,2.121630209206450991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987857258657845705e+01,5.994126791998510271e+02,3.604083474146986266e-01,1.100000010988609489e+01,2.121484223804913274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.987948167747846639e+01,5.994226791773475043e+02,3.604295622410230715e-01,1.100000010988609489e+01,2.121338238403375556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988039076837847574e+01,5.994326791548471647e+02,3.604507756074967761e-01,1.100000010988609489e+01,2.121192253001837839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988129985927848509e+01,5.994426791323498946e+02,3.604719875141197960e-01,1.100000010988609489e+01,2.121046267600300121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988220895017849443e+01,5.994526791098556942e+02,3.604931979608920756e-01,1.100000010988609489e+01,2.120900282198762404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988311804107850378e+01,5.994626790873645632e+02,3.605144069478136148e-01,1.100000010988609489e+01,2.120754296797224686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988402713197851313e+01,5.994726790648766155e+02,3.605356144748844138e-01,1.100000010988609489e+01,2.120608311395686969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988493622287852247e+01,5.994826790423917373e+02,3.605568205421044725e-01,1.100000010988609489e+01,2.120462325994149251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988584531377853182e+01,5.994926790199099287e+02,3.605780251494737909e-01,1.100000010988609489e+01,2.120316340592611534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988675440467854116e+01,5.995026789974311896e+02,3.605992282969924245e-01,1.100000010988609489e+01,2.120170355191073816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988766349557855051e+01,5.995126789749556337e+02,3.606204299846603178e-01,1.100000010988609489e+01,2.120024369789536099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988857258647855986e+01,5.995226789524831474e+02,3.606416302124774709e-01,1.100000010988609489e+01,2.119878384387998381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.988948167737856920e+01,5.995326789300137307e+02,3.606628289804438836e-01,1.100000010988609489e+01,2.119732398986460663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989039076827857855e+01,5.995426789075473835e+02,3.606840262885595561e-01,1.100000010988609489e+01,2.119586413584922946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989129985917858789e+01,5.995526788850841058e+02,3.607052221368244882e-01,1.100000010988609489e+01,2.119440428183385228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989220895007859724e+01,5.995626788626240113e+02,3.607264165252386801e-01,1.100000010988609489e+01,2.119294442781847511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989311804097860659e+01,5.995726788401669864e+02,3.607476094538021316e-01,1.100000010988609489e+01,2.119148457380309793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989402713187861593e+01,5.995826788177130311e+02,3.607688009225148429e-01,1.100000010988609489e+01,2.119002471978772076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989493622277862528e+01,5.995926787952621453e+02,3.607899909313768139e-01,1.100000010988609489e+01,2.118856486577234358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989584531367863462e+01,5.996026787728144427e+02,3.608111794803880445e-01,1.100000010988609489e+01,2.118710501175696641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989675440457864397e+01,5.996126787503698097e+02,3.608323665695485349e-01,1.100000010988609489e+01,2.118564515774158923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989766349547865332e+01,5.996226787279282462e+02,3.608535521988582850e-01,1.100000010988609489e+01,2.118418530372621206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989857258637866266e+01,5.996326787054897522e+02,3.608747363683172948e-01,1.100000010988609489e+01,2.118272544971083488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.989948167727867201e+01,5.996426786830543278e+02,3.608959190779255644e-01,1.100000010988609489e+01,2.118126559569545771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990039076817868136e+01,5.996526786606220867e+02,3.609171003276830936e-01,1.100000010988609489e+01,2.117980574168008053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990129985907869070e+01,5.996626786381929151e+02,3.609382801175898825e-01,1.100000010988609489e+01,2.117834588766470336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990220894997870005e+01,5.996726786157668130e+02,3.609594584476459311e-01,1.100000010988609489e+01,2.117688603364932618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990311804087870939e+01,5.996826785933437804e+02,3.609806353178512395e-01,1.100000010988609489e+01,2.117542617963394901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990402713177871874e+01,5.996926785709238175e+02,3.610018107282058075e-01,1.100000010988609489e+01,2.117396632561857183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990493622267872809e+01,5.997026785485070377e+02,3.610229846787096353e-01,1.100000010988609489e+01,2.117250647160319466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990584531357873743e+01,5.997126785260933275e+02,3.610441571693627227e-01,1.100000010988609489e+01,2.117104661758781748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990675440447874678e+01,5.997226785036826868e+02,3.610653282001650699e-01,1.100000010988609489e+01,2.116958676357244030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990766349537875612e+01,5.997326784812751157e+02,3.610864977711166768e-01,1.100000010988609489e+01,2.116812690955706313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990857258627876547e+01,5.997426784588706141e+02,3.611076658822175434e-01,1.100000010988609489e+01,2.116666705554168595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.990948167717877482e+01,5.997526784364691821e+02,3.611288325334676697e-01,1.100000010988609489e+01,2.116520720152630878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991039076807878416e+01,5.997626784140709333e+02,3.611499977248670556e-01,1.100000010988609489e+01,2.116374734751093160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991129985897879351e+01,5.997726783916757540e+02,3.611711614564157014e-01,1.100000010988609489e+01,2.116228749349555443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991220894987880285e+01,5.997826783692836443e+02,3.611923237281136068e-01,1.100000010988609489e+01,2.116082763948017725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991311804077881220e+01,5.997926783468946041e+02,3.612134845399607164e-01,1.100000010988609489e+01,2.115936778546480008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991402713167882155e+01,5.998026783245086335e+02,3.612346438919570857e-01,1.100000010988609489e+01,2.115790793144942290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991493622257883089e+01,5.998126783021257324e+02,3.612558017841027147e-01,1.100000010988609489e+01,2.115644807743404573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991584531347884024e+01,5.998226782797460146e+02,3.612769582163976034e-01,1.100000010988609489e+01,2.115498822341866855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991675440437884959e+01,5.998326782573693663e+02,3.612981131888417519e-01,1.100000010988609489e+01,2.115352836940329138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991766349527885893e+01,5.998426782349957875e+02,3.613192667014351600e-01,1.100000010988609489e+01,2.115206851538791420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991857258617886828e+01,5.998526782126252783e+02,3.613404187541778279e-01,1.100000010988609489e+01,2.115060866137253703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.991948167707887762e+01,5.998626781902578387e+02,3.613615693470696999e-01,1.100000010988609489e+01,2.114914880735715985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992039076797888697e+01,5.998726781678934685e+02,3.613827184801108316e-01,1.100000010988609489e+01,2.114768895334178268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992129985887889632e+01,5.998826781455322816e+02,3.614038661533012231e-01,1.100000010988609489e+01,2.114622909932640550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992220894977890566e+01,5.998926781231741643e+02,3.614250123666408743e-01,1.100000010988609489e+01,2.114476924531102833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992311804067891501e+01,5.999026781008191165e+02,3.614461571201297851e-01,1.100000010988609489e+01,2.114330939129565115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992402713157892435e+01,5.999126780784671382e+02,3.614673004137679002e-01,1.100000010988609489e+01,2.114184953728027398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992493622247893370e+01,5.999226780561182295e+02,3.614884422475552750e-01,1.100000010988609489e+01,2.114038968326489680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992584531337894305e+01,5.999326780337723903e+02,3.615095826214919095e-01,1.100000010988609489e+01,2.113892982924951962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992675440427895239e+01,5.999426780114297344e+02,3.615307215355778037e-01,1.100000010988609489e+01,2.113746997523414245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992766349517896174e+01,5.999526779890901480e+02,3.615518589898129576e-01,1.100000010988609489e+01,2.113601012121876527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992857258607897109e+01,5.999626779667536312e+02,3.615729949841973156e-01,1.100000010988609489e+01,2.113455026720338810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.992948167697898043e+01,5.999726779444201838e+02,3.615941295187309334e-01,1.100000010988609489e+01,2.113309041318801092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993039076787898978e+01,5.999826779220898061e+02,3.616152625934138110e-01,1.100000010988609489e+01,2.113163055917263375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993129985877899912e+01,5.999926778997624979e+02,3.616363942082458927e-01,1.100000010988609489e+01,2.113017070515725657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993220894967900847e+01,6.000026778774382592e+02,3.616575243632272341e-01,1.100000010988609489e+01,2.112871085114187940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993311804057901782e+01,6.000126778551170901e+02,3.616786530583578352e-01,1.100000010988609489e+01,2.112725099712650222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993402713147902716e+01,6.000226778327991042e+02,3.616997802936376960e-01,1.100000010988609489e+01,2.112579114311112505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993493622237903651e+01,6.000326778104841878e+02,3.617209060690667610e-01,1.100000010988609489e+01,2.112433128909574787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993584531327904585e+01,6.000426777881723410e+02,3.617420303846450857e-01,1.100000010988609489e+01,2.112287143508037070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993675440417905520e+01,6.000526777658635638e+02,3.617631532403726702e-01,1.100000010988609489e+01,2.112141158106499352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993766349507906455e+01,6.000626777435578560e+02,3.617842746362494588e-01,1.100000010988609489e+01,2.111995172704961635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993857258597907389e+01,6.000726777212552179e+02,3.618053945722755071e-01,1.100000010988609489e+01,2.111849187303423917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.993948167687908324e+01,6.000826776989556492e+02,3.618265130484508152e-01,1.100000010988609489e+01,2.111703201901886200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994039076777909258e+01,6.000926776766591502e+02,3.618476300647753274e-01,1.100000010988609489e+01,2.111557216500348482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994129985867910193e+01,6.001026776543658343e+02,3.618687456212490994e-01,1.100000010988609489e+01,2.111411231098810765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994220894957911128e+01,6.001126776320755880e+02,3.618898597178721310e-01,1.100000010988609489e+01,2.111265245697273047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994311804047912062e+01,6.001226776097884112e+02,3.619109723546443669e-01,1.100000010988609489e+01,2.111119260295735330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994402713137912997e+01,6.001326775875043040e+02,3.619320835315658624e-01,1.100000010988609489e+01,2.110973274894197612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994493622227913932e+01,6.001426775652232664e+02,3.619531932486365622e-01,1.100000010988609489e+01,2.110827289492659894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994584531317914866e+01,6.001526775429452982e+02,3.619743015058565216e-01,1.100000010988609489e+01,2.110681304091122177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994675440407915801e+01,6.001626775206703996e+02,3.619954083032257408e-01,1.100000010988609489e+01,2.110535318689584459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994766349497916735e+01,6.001726774983985706e+02,3.620165136407441642e-01,1.100000010988609489e+01,2.110389333288046742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994857258587917670e+01,6.001826774761298111e+02,3.620376175184118472e-01,1.100000010988609489e+01,2.110243347886509024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.994948167677918605e+01,6.001926774538642348e+02,3.620587199362287345e-01,1.100000010988609489e+01,2.110097362484971307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995039076767919539e+01,6.002026774316017281e+02,3.620798208941948815e-01,1.100000010988609489e+01,2.109951377083433589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995129985857920474e+01,6.002126774093422910e+02,3.621009203923102326e-01,1.100000010988609489e+01,2.109805391681895872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995220894947921408e+01,6.002226773870859233e+02,3.621220184305748435e-01,1.100000010988609489e+01,2.109659406280358154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995311804037922343e+01,6.002326773648326252e+02,3.621431150089886586e-01,1.100000010988609489e+01,2.109513420878820437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995402713127923278e+01,6.002426773425823967e+02,3.621642101275517334e-01,1.100000010988609489e+01,2.109367435477282719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995493622217924212e+01,6.002526773203352377e+02,3.621853037862640123e-01,1.100000010988609489e+01,2.109221450075745002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995584531307925147e+01,6.002626772980911483e+02,3.622063959851255510e-01,1.100000010988609489e+01,2.109075464674207284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995675440397926081e+01,6.002726772758501284e+02,3.622274867241362939e-01,1.100000010988609489e+01,2.108929479272669567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995766349487927016e+01,6.002826772536121780e+02,3.622485760032962965e-01,1.100000010988609489e+01,2.108783493871131849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995857258577927951e+01,6.002926772313772972e+02,3.622696638226055033e-01,1.100000010988609489e+01,2.108637508469594132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.995948167667928885e+01,6.003026772091455996e+02,3.622907501820639697e-01,1.100000010988609489e+01,2.108491523068056414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996039076757929820e+01,6.003126771869169716e+02,3.623118350816716404e-01,1.100000010988609489e+01,2.108345537666518697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996129985847930755e+01,6.003226771646914131e+02,3.623329185214285708e-01,1.100000010988609489e+01,2.108199552264980979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996220894937931689e+01,6.003326771424689241e+02,3.623540005013347054e-01,1.100000010988609489e+01,2.108053566863443262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996311804027932624e+01,6.003426771202495047e+02,3.623750810213900997e-01,1.100000010988609489e+01,2.107907581461905544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996402713117933558e+01,6.003526770980331548e+02,3.623961600815946982e-01,1.100000010988609489e+01,2.107761596060367826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996493622207934493e+01,6.003626770758198745e+02,3.624172376819485564e-01,1.100000010988609489e+01,2.107615610658830109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996584531297935428e+01,6.003726770536096637e+02,3.624383138224516188e-01,1.100000010988609489e+01,2.107469625257292391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996675440387936362e+01,6.003826770314025225e+02,3.624593885031038853e-01,1.100000010988609489e+01,2.107323639855754674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996766349477937297e+01,6.003926770091984508e+02,3.624804617239054116e-01,1.100000010988609489e+01,2.107177654454216956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996857258567938231e+01,6.004026769869974487e+02,3.625015334848561421e-01,1.100000010988609489e+01,2.107031669052679239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.996948167657939166e+01,6.004126769647995161e+02,3.625226037859560768e-01,1.100000010988609489e+01,2.106885683651141521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997039076747940101e+01,6.004226769426046530e+02,3.625436726272052712e-01,1.100000010988609489e+01,2.106739698249603804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997129985837941035e+01,6.004326769204128595e+02,3.625647400086036698e-01,1.100000010988609489e+01,2.106593712848066086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997220894927941970e+01,6.004426768982241356e+02,3.625858059301513281e-01,1.100000010988609489e+01,2.106447727446528369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997311804017942904e+01,6.004526768760384812e+02,3.626068703918481906e-01,1.100000010988609489e+01,2.106301742044990651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997402713107943839e+01,6.004626768538560100e+02,3.626279333936942573e-01,1.100000010988609489e+01,2.106155756643452934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997493622197944774e+01,6.004726768316766083e+02,3.626489949356895837e-01,1.100000010988609489e+01,2.106009771241915216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997584531287945708e+01,6.004826768095002762e+02,3.626700550178341143e-01,1.100000010988609489e+01,2.105863785840377499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997675440377946643e+01,6.004926767873270137e+02,3.626911136401278490e-01,1.100000010988609489e+01,2.105717800438839781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997766349467947578e+01,6.005026767651568207e+02,3.627121708025708435e-01,1.100000010988609489e+01,2.105571815037302064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997857258557948512e+01,6.005126767429896972e+02,3.627332265051630422e-01,1.100000010988609489e+01,2.105425829635764346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.997948167647949447e+01,6.005226767208256433e+02,3.627542807479044451e-01,1.100000010988609489e+01,2.105279844234226629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998039076737950381e+01,6.005326766986646589e+02,3.627753335307950522e-01,1.100000010988609489e+01,2.105133858832688911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998129985827951316e+01,6.005426766765067441e+02,3.627963848538349190e-01,1.100000010988609489e+01,2.104987873431151194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998220894917952251e+01,6.005526766543518988e+02,3.628174347170239900e-01,1.100000010988609489e+01,2.104841888029613476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998311804007953185e+01,6.005626766322001231e+02,3.628384831203622651e-01,1.100000010988609489e+01,2.104695902628075758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998402713097954120e+01,6.005726766100514169e+02,3.628595300638498000e-01,1.100000010988609489e+01,2.104549917226538041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998493622187955054e+01,6.005826765879057803e+02,3.628805755474865391e-01,1.100000010988609489e+01,2.104403931825000323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998584531277955989e+01,6.005926765657632131e+02,3.629016195712724824e-01,1.100000010988609489e+01,2.104257946423462606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998675440367956924e+01,6.006026765436237156e+02,3.629226621352076299e-01,1.100000010988609489e+01,2.104111961021924888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998766349457957858e+01,6.006126765214872876e+02,3.629437032392919815e-01,1.100000010988609489e+01,2.103965975620387171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998857258547958793e+01,6.006226764993539291e+02,3.629647428835255929e-01,1.100000010988609489e+01,2.103819990218849453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.998948167637959727e+01,6.006326764772236402e+02,3.629857810679084085e-01,1.100000010988609489e+01,2.103674004817311736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999039076727960662e+01,6.006426764550964208e+02,3.630068177924404282e-01,1.100000010988609489e+01,2.103528019415774018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999129985817961597e+01,6.006526764329722710e+02,3.630278530571216522e-01,1.100000010988609489e+01,2.103382034014236301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999220894907962531e+01,6.006626764108511907e+02,3.630488868619520804e-01,1.100000010988609489e+01,2.103236048612698583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999311803997963466e+01,6.006726763887331799e+02,3.630699192069317682e-01,1.100000010988609489e+01,2.103090063211160866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999402713087964401e+01,6.006826763666182387e+02,3.630909500920606603e-01,1.100000010988609489e+01,2.102944077809623148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999493622177965335e+01,6.006926763445063671e+02,3.631119795173387566e-01,1.100000010988609489e+01,2.102798092408085431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999584531267966270e+01,6.007026763223975649e+02,3.631330074827660570e-01,1.100000010988609489e+01,2.102652107006547713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999675440357967204e+01,6.007126763002918324e+02,3.631540339883425617e-01,1.100000010988609489e+01,2.102506121605009996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999766349447968139e+01,6.007226762781891694e+02,3.631750590340682705e-01,1.100000010988609489e+01,2.102360136203472278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999857258537969074e+01,6.007326762560895759e+02,3.631960826199431835e-01,1.100000010988609489e+01,2.102214150801934561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +8.999948167627970008e+01,6.007426762339930519e+02,3.632171047459673563e-01,1.100000010988609489e+01,2.102068165400396843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000039076717970943e+01,6.007526762118995975e+02,3.632381254121407332e-01,1.100000010988609489e+01,2.101922179998859126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000129985807971877e+01,6.007626761898092127e+02,3.632591446184633144e-01,1.100000010988609489e+01,2.101776194597321408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000220894897972812e+01,6.007726761677218974e+02,3.632801623649350997e-01,1.100000010988609489e+01,2.101630209195783690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000311803987973747e+01,6.007826761456376516e+02,3.633011786515560892e-01,1.100000010988609489e+01,2.101484223794245973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000402713077974681e+01,6.007926761235564754e+02,3.633221934783262830e-01,1.100000010988609489e+01,2.101338238392708255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000493622167975616e+01,6.008026761014783688e+02,3.633432068452456809e-01,1.100000010988609489e+01,2.101192252991170538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000584531257976550e+01,6.008126760794033316e+02,3.633642187523142830e-01,1.100000010988609489e+01,2.101046267589632820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000675440347977485e+01,6.008226760573313641e+02,3.633852291995320893e-01,1.100000010988609489e+01,2.100900282188095103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000766349437978420e+01,6.008326760352624660e+02,3.634062381868990999e-01,1.100000010988609489e+01,2.100754296786557385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000857258527979354e+01,6.008426760131966375e+02,3.634272457144153146e-01,1.100000010988609489e+01,2.100608311385019668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.000948167617980289e+01,6.008526759911338786e+02,3.634482517820807335e-01,1.100000010988609489e+01,2.100462325983481950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001039076707981224e+01,6.008626759690741892e+02,3.634692563898953566e-01,1.100000010988609489e+01,2.100316340581944233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001129985797982158e+01,6.008726759470175693e+02,3.634902595378591839e-01,1.100000010988609489e+01,2.100170355180406515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001220894887983093e+01,6.008826759249640190e+02,3.635112612259722153e-01,1.100000010988609489e+01,2.100024369778868798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001311803977984027e+01,6.008926759029135383e+02,3.635322614542344510e-01,1.100000010988609489e+01,2.099878384377331080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001402713067984962e+01,6.009026758808661270e+02,3.635532602226458909e-01,1.100000010988609489e+01,2.099732398975793363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001493622157985897e+01,6.009126758588217854e+02,3.635742575312065350e-01,1.100000010988609489e+01,2.099586413574255645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001584531247986831e+01,6.009226758367805132e+02,3.635952533799163833e-01,1.100000010988609489e+01,2.099440428172717928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001675440337987766e+01,6.009326758147423106e+02,3.636162477687754357e-01,1.100000010988609489e+01,2.099294442771180210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001766349427988700e+01,6.009426757927071776e+02,3.636372406977836924e-01,1.100000010988609489e+01,2.099148457369642493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001857258517989635e+01,6.009526757706751141e+02,3.636582321669411533e-01,1.100000010988609489e+01,2.099002471968104775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.001948167607990570e+01,6.009626757486461202e+02,3.636792221762478183e-01,1.100000010988609489e+01,2.098856486566567058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002039076697991504e+01,6.009726757266200821e+02,3.637002107257036876e-01,1.100000010988609489e+01,2.098710501165029340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002129985787992439e+01,6.009826757045971135e+02,3.637211978153087610e-01,1.100000010988609489e+01,2.098564515763491622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002220894877993373e+01,6.009926756825772145e+02,3.637421834450630387e-01,1.100000010988609489e+01,2.098418530361953905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002311803967994308e+01,6.010026756605603850e+02,3.637631676149665205e-01,1.100000010988609489e+01,2.098272544960416187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002402713057995243e+01,6.010126756385466251e+02,3.637841503250192066e-01,1.100000010988609489e+01,2.098126559558878470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002493622147996177e+01,6.010226756165359348e+02,3.638051315752210968e-01,1.100000010988609489e+01,2.097980574157340752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002584531237997112e+01,6.010326755945283139e+02,3.638261113655721357e-01,1.100000010988609489e+01,2.097834588755803035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002675440327998047e+01,6.010426755725237626e+02,3.638470896960723788e-01,1.100000010988609489e+01,2.097688603354265317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002766349417998981e+01,6.010526755505222809e+02,3.638680665667218261e-01,1.100000010988609489e+01,2.097542617952727600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002857258507999916e+01,6.010626755285238687e+02,3.638890419775204776e-01,1.100000010988609489e+01,2.097396632551189882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.002948167598000850e+01,6.010726755065285261e+02,3.639100159284683333e-01,1.100000010988609489e+01,2.097250647149652165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003039076688001785e+01,6.010826754845362530e+02,3.639309884195653932e-01,1.100000010988609489e+01,2.097104661748114447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003129985778002720e+01,6.010926754625470494e+02,3.639519594508116573e-01,1.100000010988609489e+01,2.096958676346576730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003220894868003654e+01,6.011026754405609154e+02,3.639729290222070701e-01,1.100000010988609489e+01,2.096812690945039012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003311803958004589e+01,6.011126754185778509e+02,3.639938971337516871e-01,1.100000010988609489e+01,2.096666705543501295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003402713048005523e+01,6.011226753965978560e+02,3.640148637854455083e-01,1.100000010988609489e+01,2.096520720141963577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003493622138006458e+01,6.011326753746208169e+02,3.640358289772885336e-01,1.100000010988609489e+01,2.096374734740425860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003584531228007393e+01,6.011426753526468474e+02,3.640567927092807632e-01,1.100000010988609489e+01,2.096228749338888142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003675440318008327e+01,6.011526753306759474e+02,3.640777549814221414e-01,1.100000010988609489e+01,2.096082763937350425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003766349408009262e+01,6.011626753087081170e+02,3.640987157937127239e-01,1.100000010988609489e+01,2.095936778535812707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003857258498010196e+01,6.011726752867433561e+02,3.641196751461525105e-01,1.100000010988609489e+01,2.095790793134274990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.003948167588011131e+01,6.011826752647816647e+02,3.641406330387415013e-01,1.100000010988609489e+01,2.095644807732737272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004039076678012066e+01,6.011926752428230429e+02,3.641615894714796409e-01,1.100000010988609489e+01,2.095498822331199554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004129985768013000e+01,6.012026752208674907e+02,3.641825444443669846e-01,1.100000010988609489e+01,2.095352836929661837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004220894858013935e+01,6.012126751989150080e+02,3.642034979574035325e-01,1.100000010988609489e+01,2.095206851528124119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004311803948014870e+01,6.012226751769655948e+02,3.642244500105892846e-01,1.100000010988609489e+01,2.095060866126586402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004402713038015804e+01,6.012326751550192512e+02,3.642454006039241854e-01,1.100000010988609489e+01,2.094914880725048684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004493622128016739e+01,6.012426751330758634e+02,3.642663497374082904e-01,1.100000010988609489e+01,2.094768895323510967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004584531218017673e+01,6.012526751111355452e+02,3.642872974110415996e-01,1.100000010988609489e+01,2.094622909921973249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004675440308018608e+01,6.012626750891982965e+02,3.643082436248240574e-01,1.100000010988609489e+01,2.094476924520435532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004766349398019543e+01,6.012726750672641174e+02,3.643291883787557195e-01,1.100000010988609489e+01,2.094330939118897814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004857258488020477e+01,6.012826750453330078e+02,3.643501316728365858e-01,1.100000010988609489e+01,2.094184953717360097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.004948167578021412e+01,6.012926750234049678e+02,3.643710735070666562e-01,1.100000010988609489e+01,2.094038968315822379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005039076668022346e+01,6.013026750014799973e+02,3.643920138814458753e-01,1.100000010988609489e+01,2.093892982914284662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005129985758023281e+01,6.013126749795580963e+02,3.644129527959742987e-01,1.100000010988609489e+01,2.093746997512746944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005220894848024216e+01,6.013226749576392649e+02,3.644338902506518707e-01,1.100000010988609489e+01,2.093601012111209227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005311803938025150e+01,6.013326749357235030e+02,3.644548262454786469e-01,1.100000010988609489e+01,2.093455026709671509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005402713028026085e+01,6.013426749138106970e+02,3.644757607804546273e-01,1.100000010988609489e+01,2.093309041308133792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005493622118027019e+01,6.013526748919009606e+02,3.644966938555797564e-01,1.100000010988609489e+01,2.093163055906596074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005584531208027954e+01,6.013626748699942937e+02,3.645176254708540897e-01,1.100000010988609489e+01,2.093017070505058357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005675440298028889e+01,6.013726748480906963e+02,3.645385556262776272e-01,1.100000010988609489e+01,2.092871085103520639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005766349388029823e+01,6.013826748261901685e+02,3.645594843218503134e-01,1.100000010988609489e+01,2.092725099701982922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005857258478030758e+01,6.013926748042927102e+02,3.645804115575722038e-01,1.100000010988609489e+01,2.092579114300445204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.005948167568031693e+01,6.014026747823983214e+02,3.646013373334432428e-01,1.100000010988609489e+01,2.092433128898907486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006039076658032627e+01,6.014126747605070022e+02,3.646222616494634861e-01,1.100000010988609489e+01,2.092287143497369769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006129985748033562e+01,6.014226747386186389e+02,3.646431845056329335e-01,1.100000010988609489e+01,2.092141158095832051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006220894838034496e+01,6.014326747167333451e+02,3.646641059019515296e-01,1.100000010988609489e+01,2.091995172694294334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006311803928035431e+01,6.014426746948511209e+02,3.646850258384193300e-01,1.100000010988609489e+01,2.091849187292756616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006402713018036366e+01,6.014526746729719662e+02,3.647059443150362790e-01,1.100000010988609489e+01,2.091703201891218899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006493622108037300e+01,6.014626746510958810e+02,3.647268613318024322e-01,1.100000010988609489e+01,2.091557216489681181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006584531198038235e+01,6.014726746292228654e+02,3.647477768887177341e-01,1.100000010988609489e+01,2.091411231088143464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006675440288039169e+01,6.014826746073529193e+02,3.647686909857822402e-01,1.100000010988609489e+01,2.091265245686605746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006766349378040104e+01,6.014926745854859291e+02,3.647896036229958949e-01,1.100000010988609489e+01,2.091119260285068029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006857258468041039e+01,6.015026745636220085e+02,3.648105148003587539e-01,1.100000010988609489e+01,2.090973274883530311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.006948167558041973e+01,6.015126745417611573e+02,3.648314245178707615e-01,1.100000010988609489e+01,2.090827289481992594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007039076648042908e+01,6.015226745199033758e+02,3.648523327755319734e-01,1.100000010988609489e+01,2.090681304080454876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007129985738043843e+01,6.015326744980486637e+02,3.648732395733423339e-01,1.100000010988609489e+01,2.090535318678917159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007220894828044777e+01,6.015426744761970212e+02,3.648941449113018987e-01,1.100000010988609489e+01,2.090389333277379441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007311803918045712e+01,6.015526744543483346e+02,3.649150487894106121e-01,1.100000010988609489e+01,2.090243347875841724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007402713008046646e+01,6.015626744325027175e+02,3.649359512076685297e-01,1.100000010988609489e+01,2.090097362474304006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007493622098047581e+01,6.015726744106601700e+02,3.649568521660755960e-01,1.100000010988609489e+01,2.089951377072766289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007584531188048516e+01,6.015826743888206920e+02,3.649777516646318665e-01,1.100000010988609489e+01,2.089805391671228571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007675440278049450e+01,6.015926743669842836e+02,3.649986497033372856e-01,1.100000010988609489e+01,2.089659406269690854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007766349368050385e+01,6.016026743451509446e+02,3.650195462821918535e-01,1.100000010988609489e+01,2.089513420868153136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007857258458051319e+01,6.016126743233206753e+02,3.650404414011956256e-01,1.100000010988609489e+01,2.089367435466615418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.007948167548052254e+01,6.016226743014933618e+02,3.650613350603485463e-01,1.100000010988609489e+01,2.089221450065077701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008039076638053189e+01,6.016326742796691178e+02,3.650822272596506712e-01,1.100000010988609489e+01,2.089075464663539983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008129985728054123e+01,6.016426742578479434e+02,3.651031179991019449e-01,1.100000010988609489e+01,2.088929479262002266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008220894818055058e+01,6.016526742360298385e+02,3.651240072787023672e-01,1.100000010988609489e+01,2.088783493860464548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008311803908055992e+01,6.016626742142148032e+02,3.651448950984519937e-01,1.100000010988609489e+01,2.088637508458926831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008402712998056927e+01,6.016726741924027237e+02,3.651657814583507689e-01,1.100000010988609489e+01,2.088491523057389113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008493622088057862e+01,6.016826741705937138e+02,3.651866663583986927e-01,1.100000010988609489e+01,2.088345537655851396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008584531178058796e+01,6.016926741487877734e+02,3.652075497985958208e-01,1.100000010988609489e+01,2.088199552254313678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008675440268059731e+01,6.017026741269849026e+02,3.652284317789420975e-01,1.100000010988609489e+01,2.088053566852775961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008766349358060666e+01,6.017126741051851013e+02,3.652493122994375785e-01,1.100000010988609489e+01,2.087907581451238243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008857258448061600e+01,6.017226740833883696e+02,3.652701913600822081e-01,1.100000010988609489e+01,2.087761596049700526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.008948167538062535e+01,6.017326740615945937e+02,3.652910689608759864e-01,1.100000010988609489e+01,2.087615610648162808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009039076628063469e+01,6.017426740398038874e+02,3.653119451018189134e-01,1.100000010988609489e+01,2.087469625246625091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009129985718064404e+01,6.017526740180162506e+02,3.653328197829110446e-01,1.100000010988609489e+01,2.087323639845087373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009220894808065339e+01,6.017626739962316833e+02,3.653536930041523245e-01,1.100000010988609489e+01,2.087177654443549656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009311803898066273e+01,6.017726739744501856e+02,3.653745647655427531e-01,1.100000010988609489e+01,2.087031669042011938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009402712988067208e+01,6.017826739526716437e+02,3.653954350670823858e-01,1.100000010988609489e+01,2.086885683640474221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009493622078068142e+01,6.017926739308961714e+02,3.654163039087711673e-01,1.100000010988609489e+01,2.086739698238936503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009584531168069077e+01,6.018026739091237687e+02,3.654371712906090974e-01,1.100000010988609489e+01,2.086593712837398785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009675440258070012e+01,6.018126738873544355e+02,3.654580372125961762e-01,1.100000010988609489e+01,2.086447727435861068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009766349348070946e+01,6.018226738655881718e+02,3.654789016747324593e-01,1.100000010988609489e+01,2.086301742034323350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009857258438071881e+01,6.018326738438248640e+02,3.654997646770178910e-01,1.100000010988609489e+01,2.086155756632785633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.009948167528072815e+01,6.018426738220646257e+02,3.655206262194524713e-01,1.100000010988609489e+01,2.086009771231247915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010039076618073750e+01,6.018526738003074570e+02,3.655414863020362004e-01,1.100000010988609489e+01,2.085863785829710198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010129985708074685e+01,6.018626737785533578e+02,3.655623449247691337e-01,1.100000010988609489e+01,2.085717800428172480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010220894798075619e+01,6.018726737568023282e+02,3.655832020876512156e-01,1.100000010988609489e+01,2.085571815026634763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010311803888076554e+01,6.018826737350542544e+02,3.656040577906824462e-01,1.100000010988609489e+01,2.085425829625097045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010402712978077489e+01,6.018926737133092502e+02,3.656249120338628256e-01,1.100000010988609489e+01,2.085279844223559328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010493622068078423e+01,6.019026736915673155e+02,3.656457648171923536e-01,1.100000010988609489e+01,2.085133858822021610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010584531158079358e+01,6.019126736698284503e+02,3.656666161406710858e-01,1.100000010988609489e+01,2.084987873420483893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010675440248080292e+01,6.019226736480925410e+02,3.656874660042989666e-01,1.100000010988609489e+01,2.084841888018946175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010766349338081227e+01,6.019326736263597013e+02,3.657083144080759962e-01,1.100000010988609489e+01,2.084695902617408458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010857258428082162e+01,6.019426736046299311e+02,3.657291613520021745e-01,1.100000010988609489e+01,2.084549917215870740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.010948167518083096e+01,6.019526735829032305e+02,3.657500068360775014e-01,1.100000010988609489e+01,2.084403931814333023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011039076608084031e+01,6.019626735611794857e+02,3.657708508603019770e-01,1.100000010988609489e+01,2.084257946412795305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011129985698084965e+01,6.019726735394588104e+02,3.657916934246756013e-01,1.100000010988609489e+01,2.084111961011257588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011220894788085900e+01,6.019826735177412047e+02,3.658125345291984298e-01,1.100000010988609489e+01,2.083965975609719870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011311803878086835e+01,6.019926734960266685e+02,3.658333741738704070e-01,1.100000010988609489e+01,2.083819990208182153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011402712968087769e+01,6.020026734743152019e+02,3.658542123586915329e-01,1.100000010988609489e+01,2.083674004806644435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011493622058088704e+01,6.020126734526066912e+02,3.658750490836618074e-01,1.100000010988609489e+01,2.083528019405106717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011584531148089638e+01,6.020226734309012500e+02,3.658958843487812307e-01,1.100000010988609489e+01,2.083382034003569000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011675440238090573e+01,6.020326734091988783e+02,3.659167181540498026e-01,1.100000010988609489e+01,2.083236048602031282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011766349328091508e+01,6.020426733874995762e+02,3.659375504994675232e-01,1.100000010988609489e+01,2.083090063200493565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011857258418092442e+01,6.020526733658032299e+02,3.659583813850343925e-01,1.100000010988609489e+01,2.082944077798955847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.011948167508093377e+01,6.020626733441099532e+02,3.659792108107504105e-01,1.100000010988609489e+01,2.082798092397418130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012039076598094312e+01,6.020726733224197460e+02,3.660000387766155772e-01,1.100000010988609489e+01,2.082652106995880412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012129985688095246e+01,6.020826733007326084e+02,3.660208652826298925e-01,1.100000010988609489e+01,2.082506121594342695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012220894778096181e+01,6.020926732790484266e+02,3.660416903287933565e-01,1.100000010988609489e+01,2.082360136192804977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012311803868097115e+01,6.021026732573673144e+02,3.660625139151059693e-01,1.100000010988609489e+01,2.082214150791267260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012402712958098050e+01,6.021126732356892717e+02,3.660833360415677307e-01,1.100000010988609489e+01,2.082068165389729542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012493622048098985e+01,6.021226732140141849e+02,3.661041567081786408e-01,1.100000010988609489e+01,2.081922179988191825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012584531138099919e+01,6.021326731923421676e+02,3.661249759149386995e-01,1.100000010988609489e+01,2.081776194586654107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012675440228100854e+01,6.021426731706732198e+02,3.661457936618479070e-01,1.100000010988609489e+01,2.081630209185116390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012766349318101788e+01,6.021526731490073416e+02,3.661666099489062631e-01,1.100000010988609489e+01,2.081484223783578672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012857258408102723e+01,6.021626731273444193e+02,3.661874247761137680e-01,1.100000010988609489e+01,2.081338238382040955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.012948167498103658e+01,6.021726731056845665e+02,3.662082381434704215e-01,1.100000010988609489e+01,2.081192252980503237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013039076588104592e+01,6.021826730840277833e+02,3.662290500509762237e-01,1.100000010988609489e+01,2.081046267578965520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013129985678105527e+01,6.021926730623740696e+02,3.662498604986311745e-01,1.100000010988609489e+01,2.080900282177427802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013220894768106461e+01,6.022026730407233117e+02,3.662706694864352741e-01,1.100000010988609489e+01,2.080754296775890085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013311803858107396e+01,6.022126730190756234e+02,3.662914770143885224e-01,1.100000010988609489e+01,2.080608311374352367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013402712948108331e+01,6.022226729974310047e+02,3.663122830824909193e-01,1.100000010988609489e+01,2.080462325972814649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013493622038109265e+01,6.022326729757893418e+02,3.663330876907424649e-01,1.100000010988609489e+01,2.080316340571276932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013584531128110200e+01,6.022426729541507484e+02,3.663538908391431592e-01,1.100000010988609489e+01,2.080170355169739214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013675440218111135e+01,6.022526729325152246e+02,3.663746925276930022e-01,1.100000010988609489e+01,2.080024369768201497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013766349308112069e+01,6.022626729108827703e+02,3.663954927563919939e-01,1.100000010988609489e+01,2.079878384366663779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013857258398113004e+01,6.022726728892532719e+02,3.664162915252401342e-01,1.100000010988609489e+01,2.079732398965126062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.013948167488113938e+01,6.022826728676268431e+02,3.664370888342373678e-01,1.100000010988609489e+01,2.079586413563588344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014039076578114873e+01,6.022926728460034838e+02,3.664578846833837500e-01,1.100000010988609489e+01,2.079440428162050627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014129985668115808e+01,6.023026728243830803e+02,3.664786790726792809e-01,1.100000010988609489e+01,2.079294442760512909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014220894758116742e+01,6.023126728027657464e+02,3.664994720021239605e-01,1.100000010988609489e+01,2.079148457358975192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014311803848117677e+01,6.023226727811514820e+02,3.665202634717177888e-01,1.100000010988609489e+01,2.079002471957437474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014402712938118611e+01,6.023326727595402872e+02,3.665410534814607657e-01,1.100000010988609489e+01,2.078856486555899757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014493622028119546e+01,6.023426727379320482e+02,3.665618420313528913e-01,1.100000010988609489e+01,2.078710501154362039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014584531118120481e+01,6.023526727163268788e+02,3.665826291213941102e-01,1.100000010988609489e+01,2.078564515752824322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014675440208121415e+01,6.023626726947247789e+02,3.666034147515844777e-01,1.100000010988609489e+01,2.078418530351286604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014766349298122350e+01,6.023726726731256349e+02,3.666241989219239938e-01,1.100000010988609489e+01,2.078272544949748887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014857258388123284e+01,6.023826726515295604e+02,3.666449816324126587e-01,1.100000010988609489e+01,2.078126559548211169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.014948167478124219e+01,6.023926726299365555e+02,3.666657628830504723e-01,1.100000010988609489e+01,2.077980574146673452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015039076568125154e+01,6.024026726083465064e+02,3.666865426738373790e-01,1.100000010988609489e+01,2.077834588745135734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015129985658126088e+01,6.024126725867595269e+02,3.667073210047734344e-01,1.100000010988609489e+01,2.077688603343598017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015220894748127023e+01,6.024226725651756169e+02,3.667280978758586385e-01,1.100000010988609489e+01,2.077542617942060299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015311803838127958e+01,6.024326725435946628e+02,3.667488732870929913e-01,1.100000010988609489e+01,2.077396632540522581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015402712928128892e+01,6.024426725220167782e+02,3.667696472384764372e-01,1.100000010988609489e+01,2.077250647138984864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015493622018129827e+01,6.024526725004419632e+02,3.667904197300090319e-01,1.100000010988609489e+01,2.077104661737447146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015584531108130761e+01,6.024626724788701040e+02,3.668111907616907752e-01,1.100000010988609489e+01,2.076958676335909429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015675440198131696e+01,6.024726724573013144e+02,3.668319603335216672e-01,1.100000010988609489e+01,2.076812690934371711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015766349288132631e+01,6.024826724357355943e+02,3.668527284455016524e-01,1.100000010988609489e+01,2.076666705532833994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015857258378133565e+01,6.024926724141728300e+02,3.668734950976307863e-01,1.100000010988609489e+01,2.076520720131296276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.015948167468134500e+01,6.025026723926131353e+02,3.668942602899090688e-01,1.100000010988609489e+01,2.076374734729758559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016039076558135434e+01,6.025126723710565102e+02,3.669150240223364445e-01,1.100000010988609489e+01,2.076228749328220841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016129985648136369e+01,6.025226723495028409e+02,3.669357862949129689e-01,1.100000010988609489e+01,2.076082763926683124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016220894738137304e+01,6.025326723279522412e+02,3.669565471076386420e-01,1.100000010988609489e+01,2.075936778525145406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016311803828138238e+01,6.025426723064047110e+02,3.669773064605134083e-01,1.100000010988609489e+01,2.075790793123607689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016402712918139173e+01,6.025526722848601366e+02,3.669980643535373233e-01,1.100000010988609489e+01,2.075644807722069971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016493622008140107e+01,6.025626722633186318e+02,3.670188207867103869e-01,1.100000010988609489e+01,2.075498822320532254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016584531098141042e+01,6.025726722417801966e+02,3.670395757600325437e-01,1.100000010988609489e+01,2.075352836918994536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016675440188141977e+01,6.025826722202447172e+02,3.670603292735038492e-01,1.100000010988609489e+01,2.075206851517456819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016766349278142911e+01,6.025926721987123074e+02,3.670810813271243034e-01,1.100000010988609489e+01,2.075060866115919101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016857258368143846e+01,6.026026721771829671e+02,3.671018319208938507e-01,1.100000010988609489e+01,2.074914880714381384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.016948167458144781e+01,6.026126721556565826e+02,3.671225810548125468e-01,1.100000010988609489e+01,2.074768895312843666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017039076548145715e+01,6.026226721341332677e+02,3.671433287288803915e-01,1.100000010988609489e+01,2.074622909911305949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017129985638146650e+01,6.026326721126130224e+02,3.671640749430973294e-01,1.100000010988609489e+01,2.074476924509768231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017220894728147584e+01,6.026426720910957329e+02,3.671848196974634160e-01,1.100000010988609489e+01,2.074330939108230513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017311803818148519e+01,6.026526720695815129e+02,3.672055629919785957e-01,1.100000010988609489e+01,2.074184953706692796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017402712908149454e+01,6.026626720480702488e+02,3.672263048266429242e-01,1.100000010988609489e+01,2.074038968305155078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017493621998150388e+01,6.026726720265620543e+02,3.672470452014563458e-01,1.100000010988609489e+01,2.073892982903617361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017584531088151323e+01,6.026826720050569293e+02,3.672677841164189161e-01,1.100000010988609489e+01,2.073746997502079643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017675440178152257e+01,6.026926719835547601e+02,3.672885215715306351e-01,1.100000010988609489e+01,2.073601012100541926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017766349268153192e+01,6.027026719620556605e+02,3.673092575667914472e-01,1.100000010988609489e+01,2.073455026699004208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017857258358154127e+01,6.027126719405596305e+02,3.673299921022014081e-01,1.100000010988609489e+01,2.073309041297466491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.017948167448155061e+01,6.027226719190665563e+02,3.673507251777604621e-01,1.100000010988609489e+01,2.073163055895928773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018039076538155996e+01,6.027326718975765516e+02,3.673714567934686648e-01,1.100000010988609489e+01,2.073017070494391056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018129985628156930e+01,6.027426718760896165e+02,3.673921869493259607e-01,1.100000010988609489e+01,2.072871085092853338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018220894718157865e+01,6.027526718546056372e+02,3.674129156453324052e-01,1.100000010988609489e+01,2.072725099691315621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018311803808158800e+01,6.027626718331247275e+02,3.674336428814879429e-01,1.100000010988609489e+01,2.072579114289777903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018402712898159734e+01,6.027726718116467737e+02,3.674543686577926294e-01,1.100000010988609489e+01,2.072433128888240186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018493621988160669e+01,6.027826717901718894e+02,3.674750929742464090e-01,1.100000010988609489e+01,2.072287143486702468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018584531078161604e+01,6.027926717687000746e+02,3.674958158308493372e-01,1.100000010988609489e+01,2.072141158085164751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018675440168162538e+01,6.028026717472312157e+02,3.675165372276013587e-01,1.100000010988609489e+01,2.071995172683627033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018766349258163473e+01,6.028126717257654263e+02,3.675372571645025288e-01,1.100000010988609489e+01,2.071849187282089316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018857258348164407e+01,6.028226717043025928e+02,3.675579756415527921e-01,1.100000010988609489e+01,2.071703201880551598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.018948167438165342e+01,6.028326716828428289e+02,3.675786926587521486e-01,1.100000010988609489e+01,2.071557216479013881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019039076528166277e+01,6.028426716613861345e+02,3.675994082161006538e-01,1.100000010988609489e+01,2.071411231077476163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019129985618167211e+01,6.028526716399323959e+02,3.676201223135982521e-01,1.100000010988609489e+01,2.071265245675938445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019220894708168146e+01,6.028626716184817269e+02,3.676408349512449991e-01,1.100000010988609489e+01,2.071119260274400728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019311803798169080e+01,6.028726715970340138e+02,3.676615461290408393e-01,1.100000010988609489e+01,2.070973274872863010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019402712888170015e+01,6.028826715755893701e+02,3.676822558469858282e-01,1.100000010988609489e+01,2.070827289471325293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019493621978170950e+01,6.028926715541477961e+02,3.677029641050799103e-01,1.100000010988609489e+01,2.070681304069787575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019584531068171884e+01,6.029026715327091779e+02,3.677236709033230855e-01,1.100000010988609489e+01,2.070535318668249858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019675440158172819e+01,6.029126715112736292e+02,3.677443762417154094e-01,1.100000010988609489e+01,2.070389333266712140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019766349248173753e+01,6.029226714898410364e+02,3.677650801202568265e-01,1.100000010988609489e+01,2.070243347865174423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019857258338174688e+01,6.029326714684115132e+02,3.677857825389473367e-01,1.100000010988609489e+01,2.070097362463636705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.019948167428175623e+01,6.029426714469850594e+02,3.678064834977869957e-01,1.100000010988609489e+01,2.069951377062098988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020039076518176557e+01,6.029526714255615616e+02,3.678271829967757478e-01,1.100000010988609489e+01,2.069805391660561270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020129985608177492e+01,6.029626714041411333e+02,3.678478810359135931e-01,1.100000010988609489e+01,2.069659406259023553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020220894698178427e+01,6.029726713827236608e+02,3.678685776152005871e-01,1.100000010988609489e+01,2.069513420857485835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020311803788179361e+01,6.029826713613092579e+02,3.678892727346366742e-01,1.100000010988609489e+01,2.069367435455948118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020402712878180296e+01,6.029926713398978109e+02,3.679099663942218545e-01,1.100000010988609489e+01,2.069221450054410400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020493621968181230e+01,6.030026713184894334e+02,3.679306585939561836e-01,1.100000010988609489e+01,2.069075464652872683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020584531058182165e+01,6.030126712970841254e+02,3.679513493338396057e-01,1.100000010988609489e+01,2.068929479251334965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020675440148183100e+01,6.030226712756817733e+02,3.679720386138721211e-01,1.100000010988609489e+01,2.068783493849797248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020766349238184034e+01,6.030326712542824907e+02,3.679927264340537851e-01,1.100000010988609489e+01,2.068637508448259530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020857258328184969e+01,6.030426712328861640e+02,3.680134127943845423e-01,1.100000010988609489e+01,2.068491523046721813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.020948167418185903e+01,6.030526712114929069e+02,3.680340976948643927e-01,1.100000010988609489e+01,2.068345537645184095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021039076508186838e+01,6.030626711901026056e+02,3.680547811354933363e-01,1.100000010988609489e+01,2.068199552243646377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021129985598187773e+01,6.030726711687153738e+02,3.680754631162714285e-01,1.100000010988609489e+01,2.068053566842108660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021220894688188707e+01,6.030826711473310979e+02,3.680961436371986140e-01,1.100000010988609489e+01,2.067907581440570942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021311803778189642e+01,6.030926711259498916e+02,3.681168226982748926e-01,1.100000010988609489e+01,2.067761596039033225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021402712868190577e+01,6.031026711045717548e+02,3.681375002995002643e-01,1.100000010988609489e+01,2.067615610637495507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021493621958191511e+01,6.031126710831965738e+02,3.681581764408747848e-01,1.100000010988609489e+01,2.067469625235957790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021584531048192446e+01,6.031226710618244624e+02,3.681788511223983984e-01,1.100000010988609489e+01,2.067323639834420072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021675440138193380e+01,6.031326710404553069e+02,3.681995243440711052e-01,1.100000010988609489e+01,2.067177654432882355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021766349228194315e+01,6.031426710190892209e+02,3.682201961058929052e-01,1.100000010988609489e+01,2.067031669031344637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021857258318195250e+01,6.031526709977260907e+02,3.682408664078637983e-01,1.100000010988609489e+01,2.066885683629806920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.021948167408196184e+01,6.031626709763660301e+02,3.682615352499838401e-01,1.100000010988609489e+01,2.066739698228269202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022039076498197119e+01,6.031726709550089254e+02,3.682822026322529751e-01,1.100000010988609489e+01,2.066593712826731485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022129985588198053e+01,6.031826709336548902e+02,3.683028685546712033e-01,1.100000010988609489e+01,2.066447727425193767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022220894678198988e+01,6.031926709123038108e+02,3.683235330172385247e-01,1.100000010988609489e+01,2.066301742023656050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022311803768199923e+01,6.032026708909558010e+02,3.683441960199549392e-01,1.100000010988609489e+01,2.066155756622118332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022402712858200857e+01,6.032126708696108608e+02,3.683648575628204469e-01,1.100000010988609489e+01,2.066009771220580615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022493621948201792e+01,6.032226708482688764e+02,3.683855176458350478e-01,1.100000010988609489e+01,2.065863785819042897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022584531038202726e+01,6.032326708269299615e+02,3.684061762689987973e-01,1.100000010988609489e+01,2.065717800417505180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022675440128203661e+01,6.032426708055940026e+02,3.684268334323116401e-01,1.100000010988609489e+01,2.065571815015967462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022766349218204596e+01,6.032526707842611131e+02,3.684474891357735760e-01,1.100000010988609489e+01,2.065425829614429745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022857258308205530e+01,6.032626707629311795e+02,3.684681433793846050e-01,1.100000010988609489e+01,2.065279844212892027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.022948167398206465e+01,6.032726707416043155e+02,3.684887961631447273e-01,1.100000010988609489e+01,2.065133858811354309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023039076488207400e+01,6.032826707202804073e+02,3.685094474870539427e-01,1.100000010988609489e+01,2.064987873409816592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023129985578208334e+01,6.032926706989595687e+02,3.685300973511122513e-01,1.100000010988609489e+01,2.064841888008278874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023220894668209269e+01,6.033026706776416859e+02,3.685507457553196531e-01,1.100000010988609489e+01,2.064695902606741157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023311803758210203e+01,6.033126706563268726e+02,3.685713926996761480e-01,1.100000010988609489e+01,2.064549917205203439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023402712848211138e+01,6.033226706350150153e+02,3.685920381841817361e-01,1.100000010988609489e+01,2.064403931803665722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023493621938212073e+01,6.033326706137062274e+02,3.686126822088364174e-01,1.100000010988609489e+01,2.064257946402128004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023584531028213007e+01,6.033426705924003954e+02,3.686333247736401919e-01,1.100000010988609489e+01,2.064111961000590287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023675440118213942e+01,6.033526705710976330e+02,3.686539658785930595e-01,1.100000010988609489e+01,2.063965975599052569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023766349208214876e+01,6.033626705497978264e+02,3.686746055236950204e-01,1.100000010988609489e+01,2.063819990197514852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023857258298215811e+01,6.033726705285010894e+02,3.686952437089461299e-01,1.100000010988609489e+01,2.063674004795977134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.023948167388216746e+01,6.033826705072073082e+02,3.687158804343463325e-01,1.100000010988609489e+01,2.063528019394439417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024039076478217680e+01,6.033926704859165966e+02,3.687365156998956284e-01,1.100000010988609489e+01,2.063382033992901699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024129985568218615e+01,6.034026704646288408e+02,3.687571495055939619e-01,1.100000010988609489e+01,2.063236048591363982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024220894658219549e+01,6.034126704433441546e+02,3.687777818514413886e-01,1.100000010988609489e+01,2.063090063189826264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024311803748220484e+01,6.034226704220624242e+02,3.687984127374379084e-01,1.100000010988609489e+01,2.062944077788288547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024402712838221419e+01,6.034326704007837634e+02,3.688190421635835214e-01,1.100000010988609489e+01,2.062798092386750829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024493621928222353e+01,6.034426703795080584e+02,3.688396701298782276e-01,1.100000010988609489e+01,2.062652106985213112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024584531018223288e+01,6.034526703582354230e+02,3.688602966363220270e-01,1.100000010988609489e+01,2.062506121583675394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024675440108224223e+01,6.034626703369657434e+02,3.688809216829149196e-01,1.100000010988609489e+01,2.062360136182137677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024766349198225157e+01,6.034726703156991334e+02,3.689015452696569053e-01,1.100000010988609489e+01,2.062214150780599959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024857258288226092e+01,6.034826702944354793e+02,3.689221673965479842e-01,1.100000010988609489e+01,2.062068165379062241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.024948167378227026e+01,6.034926702731748946e+02,3.689427880635881563e-01,1.100000010988609489e+01,2.061922179977524524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025039076468227961e+01,6.035026702519172659e+02,3.689634072707774215e-01,1.100000010988609489e+01,2.061776194575986806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025129985558228896e+01,6.035126702306627067e+02,3.689840250181157799e-01,1.100000010988609489e+01,2.061630209174449089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025220894648229830e+01,6.035226702094111033e+02,3.690046413056032315e-01,1.100000010988609489e+01,2.061484223772911371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025311803738230765e+01,6.035326701881625695e+02,3.690252561332397763e-01,1.100000010988609489e+01,2.061338238371373654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025402712828231699e+01,6.035426701669169915e+02,3.690458695010254142e-01,1.100000010988609489e+01,2.061192252969835936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025493621918232634e+01,6.035526701456744831e+02,3.690664814089600898e-01,1.100000010988609489e+01,2.061046267568298219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025584531008233569e+01,6.035626701244349306e+02,3.690870918570438586e-01,1.100000010988609489e+01,2.060900282166760501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025675440098234503e+01,6.035726701031983339e+02,3.691077008452767205e-01,1.100000010988609489e+01,2.060754296765222784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025766349188235438e+01,6.035826700819648067e+02,3.691283083736586756e-01,1.100000010988609489e+01,2.060608311363685066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025857258278236372e+01,6.035926700607342354e+02,3.691489144421897239e-01,1.100000010988609489e+01,2.060462325962147349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.025948167368237307e+01,6.036026700395067337e+02,3.691695190508698654e-01,1.100000010988609489e+01,2.060316340560609631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026039076458238242e+01,6.036126700182821878e+02,3.691901221996990445e-01,1.100000010988609489e+01,2.060170355159071914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026129985548239176e+01,6.036226699970607115e+02,3.692107238886773168e-01,1.100000010988609489e+01,2.060024369757534196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026220894638240111e+01,6.036326699758421910e+02,3.692313241178046823e-01,1.100000010988609489e+01,2.059878384355996479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026311803728241046e+01,6.036426699546267400e+02,3.692519228870811410e-01,1.100000010988609489e+01,2.059732398954458761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026402712818241980e+01,6.036526699334142450e+02,3.692725201965066928e-01,1.100000010988609489e+01,2.059586413552921044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026493621908242915e+01,6.036626699122048194e+02,3.692931160460812823e-01,1.100000010988609489e+01,2.059440428151383326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026584530998243849e+01,6.036726698909983497e+02,3.693137104358049649e-01,1.100000010988609489e+01,2.059294442749845609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026675440088244784e+01,6.036826698697948359e+02,3.693343033656777408e-01,1.100000010988609489e+01,2.059148457348307891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026766349178245719e+01,6.036926698485943916e+02,3.693548948356996098e-01,1.100000010988609489e+01,2.059002471946770173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026857258268246653e+01,6.037026698273969032e+02,3.693754848458705164e-01,1.100000010988609489e+01,2.058856486545232456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.026948167358247588e+01,6.037126698062024843e+02,3.693960733961905163e-01,1.100000010988609489e+01,2.058710501143694738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027039076448248522e+01,6.037226697850110213e+02,3.694166604866596093e-01,1.100000010988609489e+01,2.058564515742157021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027129985538249457e+01,6.037326697638226278e+02,3.694372461172777955e-01,1.100000010988609489e+01,2.058418530340619303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027220894628250392e+01,6.037426697426371902e+02,3.694578302880450194e-01,1.100000010988609489e+01,2.058272544939081586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027311803718251326e+01,6.037526697214548221e+02,3.694784129989613364e-01,1.100000010988609489e+01,2.058126559537543868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027402712808252261e+01,6.037626697002754099e+02,3.694989942500267466e-01,1.100000010988609489e+01,2.057980574136006151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027493621898253195e+01,6.037726696790989536e+02,3.695195740412412500e-01,1.100000010988609489e+01,2.057834588734468433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027584530988254130e+01,6.037826696579255668e+02,3.695401523726047910e-01,1.100000010988609489e+01,2.057688603332930716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027675440078255065e+01,6.037926696367551358e+02,3.695607292441174252e-01,1.100000010988609489e+01,2.057542617931392998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027766349168255999e+01,6.038026696155877744e+02,3.695813046557791526e-01,1.100000010988609489e+01,2.057396632529855281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027857258258256934e+01,6.038126695944233688e+02,3.696018786075899176e-01,1.100000010988609489e+01,2.057250647128317563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.027948167348257869e+01,6.038226695732619191e+02,3.696224510995497758e-01,1.100000010988609489e+01,2.057104661726779846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028039076438258803e+01,6.038326695521035390e+02,3.696430221316587272e-01,1.100000010988609489e+01,2.056958676325242128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028129985528259738e+01,6.038426695309481147e+02,3.696635917039167163e-01,1.100000010988609489e+01,2.056812690923704411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028220894618260672e+01,6.038526695097957600e+02,3.696841598163237985e-01,1.100000010988609489e+01,2.056666705522166693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028311803708261607e+01,6.038626694886463611e+02,3.697047264688799184e-01,1.100000010988609489e+01,2.056520720120628976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028402712798262542e+01,6.038726694675000317e+02,3.697252916615851315e-01,1.100000010988609489e+01,2.056374734719091258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028493621888263476e+01,6.038826694463566582e+02,3.697458553944394377e-01,1.100000010988609489e+01,2.056228749317553540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028584530978264411e+01,6.038926694252162406e+02,3.697664176674427816e-01,1.100000010988609489e+01,2.056082763916015823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028675440068265345e+01,6.039026694040788925e+02,3.697869784805952187e-01,1.100000010988609489e+01,2.055936778514478105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028766349158266280e+01,6.039126693829445003e+02,3.698075378338966934e-01,1.100000010988609489e+01,2.055790793112940388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028857258248267215e+01,6.039226693618131776e+02,3.698280957273472613e-01,1.100000010988609489e+01,2.055644807711402670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.028948167338268149e+01,6.039326693406848108e+02,3.698486521609469224e-01,1.100000010988609489e+01,2.055498822309864953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029039076428269084e+01,6.039426693195593998e+02,3.698692071346956212e-01,1.100000010988609489e+01,2.055352836908327235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029129985518270018e+01,6.039526692984370584e+02,3.698897606485934131e-01,1.100000010988609489e+01,2.055206851506789518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029220894608270953e+01,6.039626692773176728e+02,3.699103127026402427e-01,1.100000010988609489e+01,2.055060866105251800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029311803698271888e+01,6.039726692562013568e+02,3.699308632968361654e-01,1.100000010988609489e+01,2.054914880703714083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029402712788272822e+01,6.039826692350879966e+02,3.699514124311811258e-01,1.100000010988609489e+01,2.054768895302176365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029493621878273757e+01,6.039926692139775923e+02,3.699719601056751794e-01,1.100000010988609489e+01,2.054622909900638648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029584530968274692e+01,6.040026691928702576e+02,3.699925063203182707e-01,1.100000010988609489e+01,2.054476924499100930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029675440058275626e+01,6.040126691717658787e+02,3.700130510751104551e-01,1.100000010988609489e+01,2.054330939097563213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029766349148276561e+01,6.040226691506644556e+02,3.700335943700516772e-01,1.100000010988609489e+01,2.054184953696025495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029857258238277495e+01,6.040326691295661021e+02,3.700541362051419925e-01,1.100000010988609489e+01,2.054038968294487778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.029948167328278430e+01,6.040426691084707045e+02,3.700746765803813454e-01,1.100000010988609489e+01,2.053892982892950060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030039076418279365e+01,6.040526690873783764e+02,3.700952154957697915e-01,1.100000010988609489e+01,2.053746997491412343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030129985508280299e+01,6.040626690662890041e+02,3.701157529513072753e-01,1.100000010988609489e+01,2.053601012089874625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030220894598281234e+01,6.040726690452025878e+02,3.701362889469938522e-01,1.100000010988609489e+01,2.053455026688336908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030311803688282168e+01,6.040826690241192409e+02,3.701568234828294668e-01,1.100000010988609489e+01,2.053309041286799190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030402712778283103e+01,6.040926690030388500e+02,3.701773565588141746e-01,1.100000010988609489e+01,2.053163055885261472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030493621868284038e+01,6.041026689819614148e+02,3.701978881749479200e-01,1.100000010988609489e+01,2.053017070483723755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030584530958284972e+01,6.041126689608870493e+02,3.702184183312307031e-01,1.100000010988609489e+01,2.052871085082186037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030675440048285907e+01,6.041226689398156395e+02,3.702389470276625794e-01,1.100000010988609489e+01,2.052725099680648320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030766349138286841e+01,6.041326689187472994e+02,3.702594742642434933e-01,1.100000010988609489e+01,2.052579114279110602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030857258228287776e+01,6.041426688976819150e+02,3.702800000409735004e-01,1.100000010988609489e+01,2.052433128877572885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.030948167318288711e+01,6.041526688766194866e+02,3.703005243578525452e-01,1.100000010988609489e+01,2.052287143476035167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031039076408289645e+01,6.041626688555601277e+02,3.703210472148806276e-01,1.100000010988609489e+01,2.052141158074497450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031129985498290580e+01,6.041726688345037246e+02,3.703415686120578032e-01,1.100000010988609489e+01,2.051995172672959732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031220894588291515e+01,6.041826688134502774e+02,3.703620885493840165e-01,1.100000010988609489e+01,2.051849187271422015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031311803678292449e+01,6.041926687923998998e+02,3.703826070268593229e-01,1.100000010988609489e+01,2.051703201869884297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031402712768293384e+01,6.042026687713524780e+02,3.704031240444836670e-01,1.100000010988609489e+01,2.051557216468346580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031493621858294318e+01,6.042126687503080120e+02,3.704236396022570488e-01,1.100000010988609489e+01,2.051411231066808862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031584530948295253e+01,6.042226687292666156e+02,3.704441537001795237e-01,1.100000010988609489e+01,2.051265245665271145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031675440038296188e+01,6.042326687082281751e+02,3.704646663382510363e-01,1.100000010988609489e+01,2.051119260263733427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031766349128297122e+01,6.042426686871926904e+02,3.704851775164715866e-01,1.100000010988609489e+01,2.050973274862195710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031857258218298057e+01,6.042526686661602753e+02,3.705056872348412300e-01,1.100000010988609489e+01,2.050827289460657992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.031948167308298991e+01,6.042626686451308160e+02,3.705261954933599111e-01,1.100000010988609489e+01,2.050681304059120275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032039076398299926e+01,6.042726686241043126e+02,3.705467022920276299e-01,1.100000010988609489e+01,2.050535318657582557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032129985488300861e+01,6.042826686030808787e+02,3.705672076308444418e-01,1.100000010988609489e+01,2.050389333256044840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032220894578301795e+01,6.042926685820604007e+02,3.705877115098102914e-01,1.100000010988609489e+01,2.050243347854507122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032311803668302730e+01,6.043026685610428785e+02,3.706082139289251787e-01,1.100000010988609489e+01,2.050097362452969404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032402712758303664e+01,6.043126685400284259e+02,3.706287148881891036e-01,1.100000010988609489e+01,2.049951377051431687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032493621848304599e+01,6.043226685190169292e+02,3.706492143876021217e-01,1.100000010988609489e+01,2.049805391649893969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032584530938305534e+01,6.043326684980083883e+02,3.706697124271641774e-01,1.100000010988609489e+01,2.049659406248356252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032675440028306468e+01,6.043426684770029169e+02,3.706902090068752709e-01,1.100000010988609489e+01,2.049513420846818534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032766349118307403e+01,6.043526684560004014e+02,3.707107041267354020e-01,1.100000010988609489e+01,2.049367435445280817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032857258208308338e+01,6.043626684350008418e+02,3.707311977867446262e-01,1.100000010988609489e+01,2.049221450043743099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.032948167298309272e+01,6.043726684140043517e+02,3.707516899869028881e-01,1.100000010988609489e+01,2.049075464642205382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033039076388310207e+01,6.043826683930108175e+02,3.707721807272101877e-01,1.100000010988609489e+01,2.048929479240667664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033129985478311141e+01,6.043926683720202391e+02,3.707926700076665250e-01,1.100000010988609489e+01,2.048783493839129947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033220894568312076e+01,6.044026683510327302e+02,3.708131578282718999e-01,1.100000010988609489e+01,2.048637508437592229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033311803658313011e+01,6.044126683300481773e+02,3.708336441890263679e-01,1.100000010988609489e+01,2.048491523036054512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033402712748313945e+01,6.044226683090665802e+02,3.708541290899298737e-01,1.100000010988609489e+01,2.048345537634516794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033493621838314880e+01,6.044326682880879389e+02,3.708746125309824171e-01,1.100000010988609489e+01,2.048199552232979077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033584530928315814e+01,6.044426682671123672e+02,3.708950945121839982e-01,1.100000010988609489e+01,2.048053566831441359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033675440018316749e+01,6.044526682461397513e+02,3.709155750335346169e-01,1.100000010988609489e+01,2.047907581429903642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033766349108317684e+01,6.044626682251700913e+02,3.709360540950342733e-01,1.100000010988609489e+01,2.047761596028365924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033857258198318618e+01,6.044726682042035009e+02,3.709565316966830228e-01,1.100000010988609489e+01,2.047615610626828207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.033948167288319553e+01,6.044826681832398663e+02,3.709770078384808101e-01,1.100000010988609489e+01,2.047469625225290489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034039076378320487e+01,6.044926681622791875e+02,3.709974825204276350e-01,1.100000010988609489e+01,2.047323639823752772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034129985468321422e+01,6.045026681413215783e+02,3.710179557425234975e-01,1.100000010988609489e+01,2.047177654422215054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034220894558322357e+01,6.045126681203669250e+02,3.710384275047683977e-01,1.100000010988609489e+01,2.047031669020677336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034311803648323291e+01,6.045226680994152275e+02,3.710588978071623356e-01,1.100000010988609489e+01,2.046885683619139619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034402712738324226e+01,6.045326680784664859e+02,3.710793666497053112e-01,1.100000010988609489e+01,2.046739698217601901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034493621828325161e+01,6.045426680575208138e+02,3.710998340323973244e-01,1.100000010988609489e+01,2.046593712816064184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034584530918326095e+01,6.045526680365780976e+02,3.711202999552383752e-01,1.100000010988609489e+01,2.046447727414526466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034675440008327030e+01,6.045626680156383372e+02,3.711407644182285193e-01,1.100000010988609489e+01,2.046301742012988749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034766349098327964e+01,6.045726679947016464e+02,3.711612274213677010e-01,1.100000010988609489e+01,2.046155756611451031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034857258188328899e+01,6.045826679737679115e+02,3.711816889646559203e-01,1.100000010988609489e+01,2.046009771209913314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.034948167278329834e+01,6.045926679528371324e+02,3.712021490480931774e-01,1.100000010988609489e+01,2.045863785808375596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035039076368330768e+01,6.046026679319093091e+02,3.712226076716794720e-01,1.100000010988609489e+01,2.045717800406837879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035129985458331703e+01,6.046126679109845554e+02,3.712430648354148044e-01,1.100000010988609489e+01,2.045571815005300161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035220894548332637e+01,6.046226678900627576e+02,3.712635205392991744e-01,1.100000010988609489e+01,2.045425829603762444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035311803638333572e+01,6.046326678691439156e+02,3.712839747833325821e-01,1.100000010988609489e+01,2.045279844202224726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035402712728334507e+01,6.046426678482280295e+02,3.713044275675150274e-01,1.100000010988609489e+01,2.045133858800687009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035493621818335441e+01,6.046526678273152129e+02,3.713248788918465104e-01,1.100000010988609489e+01,2.044987873399149291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035584530908336376e+01,6.046626678064053522e+02,3.713453287563270311e-01,1.100000010988609489e+01,2.044841887997611574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035675439998337310e+01,6.046726677854984473e+02,3.713657771609565894e-01,1.100000010988609489e+01,2.044695902596073856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035766349088338245e+01,6.046826677645944983e+02,3.713862241057351854e-01,1.100000010988609489e+01,2.044549917194536139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035857258178339180e+01,6.046926677436936188e+02,3.714066695906628190e-01,1.100000010988609489e+01,2.044403931792998421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.035948167268340114e+01,6.047026677227956952e+02,3.714271136157394904e-01,1.100000010988609489e+01,2.044257946391460704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036039076358341049e+01,6.047126677019007275e+02,3.714475561809651993e-01,1.100000010988609489e+01,2.044111960989922986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036129985448341984e+01,6.047226676810087156e+02,3.714679972863399460e-01,1.100000010988609489e+01,2.043965975588385268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036220894538342918e+01,6.047326676601197732e+02,3.714884369318637303e-01,1.100000010988609489e+01,2.043819990186847551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036311803628343853e+01,6.047426676392337868e+02,3.715088751175365522e-01,1.100000010988609489e+01,2.043674004785309833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036402712718344787e+01,6.047526676183507561e+02,3.715293118433583563e-01,1.100000010988609489e+01,2.043528019383772116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036493621808345722e+01,6.047626675974706814e+02,3.715497471093291981e-01,1.100000010988609489e+01,2.043382033982234398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036584530898346657e+01,6.047726675765936761e+02,3.715701809154490776e-01,1.100000010988609489e+01,2.043236048580696681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036675439988347591e+01,6.047826675557196268e+02,3.715906132617179947e-01,1.100000010988609489e+01,2.043090063179158963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036766349078348526e+01,6.047926675348485333e+02,3.716110441481359494e-01,1.100000010988609489e+01,2.042944077777621246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036857258168349460e+01,6.048026675139803956e+02,3.716314735747029419e-01,1.100000010988609489e+01,2.042798092376083528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.036948167258350395e+01,6.048126674931153275e+02,3.716519015414189719e-01,1.100000010988609489e+01,2.042652106974545811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037039076348351330e+01,6.048226674722532152e+02,3.716723280482840397e-01,1.100000010988609489e+01,2.042506121573008093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037129985438352264e+01,6.048326674513940588e+02,3.716927530952981451e-01,1.100000010988609489e+01,2.042360136171470376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037220894528353199e+01,6.048426674305378583e+02,3.717131766824612327e-01,1.100000010988609489e+01,2.042214150769932658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037311803618354134e+01,6.048526674096847273e+02,3.717335988097733579e-01,1.100000010988609489e+01,2.042068165368394941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037402712708355068e+01,6.048626673888345522e+02,3.717540194772345208e-01,1.100000010988609489e+01,2.041922179966857223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037493621798356003e+01,6.048726673679873329e+02,3.717744386848447213e-01,1.100000010988609489e+01,2.041776194565319506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037584530888356937e+01,6.048826673471430695e+02,3.717948564326039596e-01,1.100000010988609489e+01,2.041630209163781788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037675439978357872e+01,6.048926673263017619e+02,3.718152727205122354e-01,1.100000010988609489e+01,2.041484223762244071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037766349068358807e+01,6.049026673054635239e+02,3.718356875485694935e-01,1.100000010988609489e+01,2.041338238360706353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037857258158359741e+01,6.049126672846282418e+02,3.718561009167757891e-01,1.100000010988609489e+01,2.041192252959168636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.037948167248360676e+01,6.049226672637959155e+02,3.718765128251311225e-01,1.100000010988609489e+01,2.041046267557630918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038039076338361610e+01,6.049326672429665450e+02,3.718969232736354935e-01,1.100000010988609489e+01,2.040900282156093200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038129985428362545e+01,6.049426672221401304e+02,3.719173322622889022e-01,1.100000010988609489e+01,2.040754296754555483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038220894518363480e+01,6.049526672013167854e+02,3.719377397910912930e-01,1.100000010988609489e+01,2.040608311353017765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038311803608364414e+01,6.049626671804963962e+02,3.719581458600427215e-01,1.100000010988609489e+01,2.040462325951480048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038402712698365349e+01,6.049726671596789629e+02,3.719785504691431877e-01,1.100000010988609489e+01,2.040316340549942330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038493621788366283e+01,6.049826671388644854e+02,3.719989536183926915e-01,1.100000010988609489e+01,2.040170355148404613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038584530878367218e+01,6.049926671180529638e+02,3.720193553077911774e-01,1.100000010988609489e+01,2.040024369746866895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038675439968368153e+01,6.050026670972445118e+02,3.720397555373387011e-01,1.100000010988609489e+01,2.039878384345329178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038766349058369087e+01,6.050126670764390155e+02,3.720601543070352624e-01,1.100000010988609489e+01,2.039732398943791460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038857258148370022e+01,6.050226670556364752e+02,3.720805516168808058e-01,1.100000010988609489e+01,2.039586413542253743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.038948167238370957e+01,6.050326670348368907e+02,3.721009474668753869e-01,1.100000010988609489e+01,2.039440428140716025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039039076328371891e+01,6.050426670140402621e+02,3.721213418570190057e-01,1.100000010988609489e+01,2.039294442739178308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039129985418372826e+01,6.050526669932467030e+02,3.721417347873116621e-01,1.100000010988609489e+01,2.039148457337640590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039220894508373760e+01,6.050626669724560998e+02,3.721621262577533007e-01,1.100000010988609489e+01,2.039002471936102873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039311803598374695e+01,6.050726669516684524e+02,3.721825162683439769e-01,1.100000010988609489e+01,2.038856486534565155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039402712688375630e+01,6.050826669308837609e+02,3.722029048190836908e-01,1.100000010988609489e+01,2.038710501133027438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039493621778376564e+01,6.050926669101020252e+02,3.722232919099723869e-01,1.100000010988609489e+01,2.038564515731489720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039584530868377499e+01,6.051026668893233591e+02,3.722436775410101206e-01,1.100000010988609489e+01,2.038418530329952003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039675439958378433e+01,6.051126668685476488e+02,3.722640617121968920e-01,1.100000010988609489e+01,2.038272544928414285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039766349048379368e+01,6.051226668477748944e+02,3.722844444235326455e-01,1.100000010988609489e+01,2.038126559526876568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039857258138380303e+01,6.051326668270050959e+02,3.723048256750174367e-01,1.100000010988609489e+01,2.037980574125338850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.039948167228381237e+01,6.051426668062382532e+02,3.723252054666512101e-01,1.100000010988609489e+01,2.037834588723801132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040039076318382172e+01,6.051526667854743664e+02,3.723455837984340211e-01,1.100000010988609489e+01,2.037688603322263415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040129985408383106e+01,6.051626667647135491e+02,3.723659606703658698e-01,1.100000010988609489e+01,2.037542617920725697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040220894498384041e+01,6.051726667439556877e+02,3.723863360824467006e-01,1.100000010988609489e+01,2.037396632519187980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040311803588384976e+01,6.051826667232007821e+02,3.724067100346765691e-01,1.100000010988609489e+01,2.037250647117650262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040402712678385910e+01,6.051926667024488324e+02,3.724270825270554197e-01,1.100000010988609489e+01,2.037104661716112545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040493621768386845e+01,6.052026666816998386e+02,3.724474535595833080e-01,1.100000010988609489e+01,2.036958676314574827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040584530858387780e+01,6.052126666609538006e+02,3.724678231322602340e-01,1.100000010988609489e+01,2.036812690913037110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040675439948388714e+01,6.052226666402108322e+02,3.724881912450861421e-01,1.100000010988609489e+01,2.036666705511499392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040766349038389649e+01,6.052326666194708196e+02,3.725085578980610879e-01,1.100000010988609489e+01,2.036520720109961675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040857258128390583e+01,6.052426665987337628e+02,3.725289230911850158e-01,1.100000010988609489e+01,2.036374734708423957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.040948167218391518e+01,6.052526665779996620e+02,3.725492868244579814e-01,1.100000010988609489e+01,2.036228749306886240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041039076308392453e+01,6.052626665572685170e+02,3.725696490978799291e-01,1.100000010988609489e+01,2.036082763905348522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041129985398393387e+01,6.052726665365403278e+02,3.725900099114509145e-01,1.100000010988609489e+01,2.035936778503810805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041220894488394322e+01,6.052826665158150945e+02,3.726103692651708821e-01,1.100000010988609489e+01,2.035790793102273087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041311803578395256e+01,6.052926664950929307e+02,3.726307271590398873e-01,1.100000010988609489e+01,2.035644807700735370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041402712668396191e+01,6.053026664743737228e+02,3.726510835930578747e-01,1.100000010988609489e+01,2.035498822299197652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041493621758397126e+01,6.053126664536574708e+02,3.726714385672248997e-01,1.100000010988609489e+01,2.035352836897659935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041584530848398060e+01,6.053226664329441746e+02,3.726917920815409069e-01,1.100000010988609489e+01,2.035206851496122217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041675439938398995e+01,6.053326664122338343e+02,3.727121441360059517e-01,1.100000010988609489e+01,2.035060866094584500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041766349028399929e+01,6.053426663915264498e+02,3.727324947306199787e-01,1.100000010988609489e+01,2.034914880693046782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041857258118400864e+01,6.053526663708220212e+02,3.727528438653830434e-01,1.100000010988609489e+01,2.034768895291509064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.041948167208401799e+01,6.053626663501206622e+02,3.727731915402950902e-01,1.100000010988609489e+01,2.034622909889971347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042039076298402733e+01,6.053726663294222590e+02,3.727935377553561191e-01,1.100000010988609489e+01,2.034476924488433629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042129985388403668e+01,6.053826663087268116e+02,3.728138825105661858e-01,1.100000010988609489e+01,2.034330939086895912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042220894478404603e+01,6.053926662880343201e+02,3.728342258059252345e-01,1.100000010988609489e+01,2.034184953685358194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042311803568405537e+01,6.054026662673447845e+02,3.728545676414333210e-01,1.100000010988609489e+01,2.034038968283820477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042402712658406472e+01,6.054126662466582047e+02,3.728749080170903896e-01,1.100000010988609489e+01,2.033892982882282759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042493621748407406e+01,6.054226662259745808e+02,3.728952469328964958e-01,1.100000010988609489e+01,2.033746997480745042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042584530838408341e+01,6.054326662052939128e+02,3.729155843888515842e-01,1.100000010988609489e+01,2.033601012079207324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042675439928409276e+01,6.054426661846162006e+02,3.729359203849556548e-01,1.100000010988609489e+01,2.033455026677669607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042766349018410210e+01,6.054526661639415579e+02,3.729562549212087630e-01,1.100000010988609489e+01,2.033309041276131889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042857258108411145e+01,6.054626661432698711e+02,3.729765879976108534e-01,1.100000010988609489e+01,2.033163055874594172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.042948167198412079e+01,6.054726661226011402e+02,3.729969196141619259e-01,1.100000010988609489e+01,2.033017070473056454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043039076288413014e+01,6.054826661019353651e+02,3.730172497708620361e-01,1.100000010988609489e+01,2.032871085071518737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043129985378413949e+01,6.054926660812725459e+02,3.730375784677111284e-01,1.100000010988609489e+01,2.032725099669981019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043220894468414883e+01,6.055026660606126825e+02,3.730579057047092029e-01,1.100000010988609489e+01,2.032579114268443302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043311803558415818e+01,6.055126660399557750e+02,3.730782314818563150e-01,1.100000010988609489e+01,2.032433128866905584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043402712648416752e+01,6.055226660193018233e+02,3.730985557991524093e-01,1.100000010988609489e+01,2.032287143465367867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043493621738417687e+01,6.055326659986508275e+02,3.731188786565974858e-01,1.100000010988609489e+01,2.032141158063830149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043584530828418622e+01,6.055426659780029013e+02,3.731392000541915999e-01,1.100000010988609489e+01,2.031995172662292432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043675439918419556e+01,6.055526659573579309e+02,3.731595199919346961e-01,1.100000010988609489e+01,2.031849187260754714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043766349008420491e+01,6.055626659367159164e+02,3.731798384698267745e-01,1.100000010988609489e+01,2.031703201859216996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043857258098421426e+01,6.055726659160768577e+02,3.732001554878678906e-01,1.100000010988609489e+01,2.031557216457679279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.043948167188422360e+01,6.055826658954407549e+02,3.732204710460579888e-01,1.100000010988609489e+01,2.031411231056141561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044039076278423295e+01,6.055926658748076079e+02,3.732407851443970692e-01,1.100000010988609489e+01,2.031265245654603844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044129985368424229e+01,6.056026658541774168e+02,3.732610977828851317e-01,1.100000010988609489e+01,2.031119260253066126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044220894458425164e+01,6.056126658335501816e+02,3.732814089615222319e-01,1.100000010988609489e+01,2.030973274851528409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044311803548426099e+01,6.056226658129259022e+02,3.733017186803083143e-01,1.100000010988609489e+01,2.030827289449990691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044402712638427033e+01,6.056326657923045786e+02,3.733220269392433788e-01,1.100000010988609489e+01,2.030681304048452974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044493621728427968e+01,6.056426657716862110e+02,3.733423337383274254e-01,1.100000010988609489e+01,2.030535318646915256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044584530818428902e+01,6.056526657510707992e+02,3.733626390775605097e-01,1.100000010988609489e+01,2.030389333245377539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044675439908429837e+01,6.056626657304584569e+02,3.733829429569425762e-01,1.100000010988609489e+01,2.030243347843839821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044766348998430772e+01,6.056726657098490705e+02,3.734032453764736248e-01,1.100000010988609489e+01,2.030097362442302104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044857258088431706e+01,6.056826656892426399e+02,3.734235463361536556e-01,1.100000010988609489e+01,2.029951377040764386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.044948167178432641e+01,6.056926656686391652e+02,3.734438458359826685e-01,1.100000010988609489e+01,2.029805391639226669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045039076268433575e+01,6.057026656480386464e+02,3.734641438759607190e-01,1.100000010988609489e+01,2.029659406237688951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045129985358434510e+01,6.057126656274410834e+02,3.734844404560877518e-01,1.100000010988609489e+01,2.029513420836151234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045220894448435445e+01,6.057226656068464763e+02,3.735047355763637666e-01,1.100000010988609489e+01,2.029367435434613516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045311803538436379e+01,6.057326655862548250e+02,3.735250292367887637e-01,1.100000010988609489e+01,2.029221450033075799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045402712628437314e+01,6.057426655656661296e+02,3.735453214373627429e-01,1.100000010988609489e+01,2.029075464631538081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045493621718438249e+01,6.057526655450803901e+02,3.735656121780857042e-01,1.100000010988609489e+01,2.028929479230000364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045584530808439183e+01,6.057626655244976064e+02,3.735859014589576477e-01,1.100000010988609489e+01,2.028783493828462646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045675439898440118e+01,6.057726655039177786e+02,3.736061892799786288e-01,1.100000010988609489e+01,2.028637508426924928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045766348988441052e+01,6.057826654833409066e+02,3.736264756411485921e-01,1.100000010988609489e+01,2.028491523025387211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045857258078441987e+01,6.057926654627669905e+02,3.736467605424675376e-01,1.100000010988609489e+01,2.028345537623849493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.045948167168442922e+01,6.058026654421960302e+02,3.736670439839354652e-01,1.100000010988609489e+01,2.028199552222311776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046039076258443856e+01,6.058126654216280258e+02,3.736873259655523749e-01,1.100000010988609489e+01,2.028053566820774058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046129985348444791e+01,6.058226654010629773e+02,3.737076064873182668e-01,1.100000010988609489e+01,2.027907581419236341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046220894438445725e+01,6.058326653805008846e+02,3.737278855492331409e-01,1.100000010988609489e+01,2.027761596017698623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046311803528446660e+01,6.058426653599418614e+02,3.737481631512969971e-01,1.100000010988609489e+01,2.027615610616160906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046402712618447595e+01,6.058526653393857941e+02,3.737684392935098354e-01,1.100000010988609489e+01,2.027469625214623188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046493621708448529e+01,6.058626653188326827e+02,3.737887139758716559e-01,1.100000010988609489e+01,2.027323639813085471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046584530798449464e+01,6.058726652982825271e+02,3.738089871983824586e-01,1.100000010988609489e+01,2.027177654411547753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046675439888450398e+01,6.058826652777353274e+02,3.738292589610422434e-01,1.100000010988609489e+01,2.027031669010010036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046766348978451333e+01,6.058926652571910836e+02,3.738495292638510659e-01,1.100000010988609489e+01,2.026885683608472318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046857258068452268e+01,6.059026652366497956e+02,3.738697981068088705e-01,1.100000010988609489e+01,2.026739698206934601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.046948167158453202e+01,6.059126652161114635e+02,3.738900654899156573e-01,1.100000010988609489e+01,2.026593712805396883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047039076248454137e+01,6.059226651955760872e+02,3.739103314131714262e-01,1.100000010988609489e+01,2.026447727403859166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047129985338455072e+01,6.059326651750436667e+02,3.739305958765761773e-01,1.100000010988609489e+01,2.026301742002321448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047220894428456006e+01,6.059426651545142022e+02,3.739508588801299105e-01,1.100000010988609489e+01,2.026155756600783731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047311803518456941e+01,6.059526651339876935e+02,3.739711204238326259e-01,1.100000010988609489e+01,2.026009771199246013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047402712608457875e+01,6.059626651134641406e+02,3.739913805076843234e-01,1.100000010988609489e+01,2.025863785797708295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047493621698458810e+01,6.059726650929435436e+02,3.740116391316850031e-01,1.100000010988609489e+01,2.025717800396170578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047584530788459745e+01,6.059826650724259025e+02,3.740318962958346094e-01,1.100000010988609489e+01,2.025571814994632860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047675439878460679e+01,6.059926650519112172e+02,3.740521520001331979e-01,1.100000010988609489e+01,2.025425829593095143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047766348968461614e+01,6.060026650313994878e+02,3.740724062445807685e-01,1.100000010988609489e+01,2.025279844191557425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047857258058462548e+01,6.060126650108907143e+02,3.740926590291773213e-01,1.100000010988609489e+01,2.025133858790019708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.047948167148463483e+01,6.060226649903848966e+02,3.741129103539228562e-01,1.100000010988609489e+01,2.024987873388481990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048039076238464418e+01,6.060326649698820347e+02,3.741331602188173733e-01,1.100000010988609489e+01,2.024841887986944273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048129985328465352e+01,6.060426649493821287e+02,3.741534086238608725e-01,1.100000010988609489e+01,2.024695902585406555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048220894418466287e+01,6.060526649288851786e+02,3.741736555690533539e-01,1.100000010988609489e+01,2.024549917183868838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048311803508467221e+01,6.060626649083911843e+02,3.741939010543948174e-01,1.100000010988609489e+01,2.024403931782331120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048402712598468156e+01,6.060726648879001459e+02,3.742141450798852631e-01,1.100000010988609489e+01,2.024257946380793403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048493621688469091e+01,6.060826648674120634e+02,3.742343876455246909e-01,1.100000010988609489e+01,2.024111960979255685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048584530778470025e+01,6.060926648469269367e+02,3.742546287513131009e-01,1.100000010988609489e+01,2.023965975577717968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048675439868470960e+01,6.061026648264447658e+02,3.742748683972504375e-01,1.100000010988609489e+01,2.023819990176180250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048766348958471895e+01,6.061126648059655508e+02,3.742951065833367563e-01,1.100000010988609489e+01,2.023674004774642533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048857258048472829e+01,6.061226647854892917e+02,3.743153433095720573e-01,1.100000010988609489e+01,2.023528019373104815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.048948167138473764e+01,6.061326647650159885e+02,3.743355785759563403e-01,1.100000010988609489e+01,2.023382033971567098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049039076228474698e+01,6.061426647445456410e+02,3.743558123824896056e-01,1.100000010988609489e+01,2.023236048570029380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049129985318475633e+01,6.061526647240782495e+02,3.743760447291718529e-01,1.100000010988609489e+01,2.023090063168491663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049220894408476568e+01,6.061626647036138138e+02,3.743962756160030270e-01,1.100000010988609489e+01,2.022944077766953945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049311803498477502e+01,6.061726646831523340e+02,3.744165050429831831e-01,1.100000010988609489e+01,2.022798092365416227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049402712588478437e+01,6.061826646626938100e+02,3.744367330101123215e-01,1.100000010988609489e+01,2.022652106963878510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049493621678479371e+01,6.061926646422382419e+02,3.744569595173904419e-01,1.100000010988609489e+01,2.022506121562340792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049584530768480306e+01,6.062026646217856296e+02,3.744771845648175446e-01,1.100000010988609489e+01,2.022360136160803075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049675439858481241e+01,6.062126646013359732e+02,3.744974081523935738e-01,1.100000010988609489e+01,2.022214150759265357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049766348948482175e+01,6.062226645808892727e+02,3.745176302801185853e-01,1.100000010988609489e+01,2.022068165357727640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049857258038483110e+01,6.062326645604455280e+02,3.745378509479925788e-01,1.100000010988609489e+01,2.021922179956189922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.049948167128484044e+01,6.062426645400047391e+02,3.745580701560155545e-01,1.100000010988609489e+01,2.021776194554652205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050039076218484979e+01,6.062526645195669062e+02,3.745782879041875124e-01,1.100000010988609489e+01,2.021630209153114487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050129985308485914e+01,6.062626644991319154e+02,3.745985041925083969e-01,1.100000010988609489e+01,2.021484223751576770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050220894398486848e+01,6.062726644786998804e+02,3.746187190209782636e-01,1.100000010988609489e+01,2.021338238350039052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050311803488487783e+01,6.062826644582708013e+02,3.746389323895971124e-01,1.100000010988609489e+01,2.021192252948501335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050402712578488718e+01,6.062926644378446781e+02,3.746591442983648879e-01,1.100000010988609489e+01,2.021046267546963617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050493621668489652e+01,6.063026644174215107e+02,3.746793547472816455e-01,1.100000010988609489e+01,2.020900282145425900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050584530758490587e+01,6.063126643970012992e+02,3.746995637363473852e-01,1.100000010988609489e+01,2.020754296743888182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050675439848491521e+01,6.063226643765840436e+02,3.747197712655621071e-01,1.100000010988609489e+01,2.020608311342350465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050766348938492456e+01,6.063326643561697438e+02,3.747399773349257557e-01,1.100000010988609489e+01,2.020462325940812747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050857258028493391e+01,6.063426643357583998e+02,3.747601819444383864e-01,1.100000010988609489e+01,2.020316340539275030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.050948167118494325e+01,6.063526643153500117e+02,3.747803850940999992e-01,1.100000010988609489e+01,2.020170355137737312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051039076208495260e+01,6.063626642949445795e+02,3.748005867839105387e-01,1.100000010988609489e+01,2.020024369736199595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051129985298496194e+01,6.063726642745421032e+02,3.748207870138700604e-01,1.100000010988609489e+01,2.019878384334661877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051220894388497129e+01,6.063826642541425826e+02,3.748409857839785642e-01,1.100000010988609489e+01,2.019732398933124159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051311803478498064e+01,6.063926642337460180e+02,3.748611830942359946e-01,1.100000010988609489e+01,2.019586413531586442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051402712568498998e+01,6.064026642133524092e+02,3.748813789446424072e-01,1.100000010988609489e+01,2.019440428130048724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051493621658499933e+01,6.064126641929617563e+02,3.749015733351978019e-01,1.100000010988609489e+01,2.019294442728511007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051584530748500868e+01,6.064226641725740592e+02,3.749217662659021233e-01,1.100000010988609489e+01,2.019148457326973289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051675439838501802e+01,6.064326641521893180e+02,3.749419577367554268e-01,1.100000010988609489e+01,2.019002471925435572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051766348928502737e+01,6.064426641318074189e+02,3.749621477477576570e-01,1.100000010988609489e+01,2.018856486523897854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051857258018503671e+01,6.064526641114284757e+02,3.749823362989088693e-01,1.100000010988609489e+01,2.018710501122360137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.051948167108504606e+01,6.064626640910524884e+02,3.750025233902090638e-01,1.100000010988609489e+01,2.018564515720822419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052039076198505541e+01,6.064726640706794569e+02,3.750227090216581849e-01,1.100000010988609489e+01,2.018418530319284702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052129985288506475e+01,6.064826640503093813e+02,3.750428931932562882e-01,1.100000010988609489e+01,2.018272544917746984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052220894378507410e+01,6.064926640299422615e+02,3.750630759050033181e-01,1.100000010988609489e+01,2.018126559516209267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052311803468508344e+01,6.065026640095780976e+02,3.750832571568993301e-01,1.100000010988609489e+01,2.017980574114671549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052402712558509279e+01,6.065126639892168896e+02,3.751034369489442688e-01,1.100000010988609489e+01,2.017834588713133832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052493621648510214e+01,6.065226639688586374e+02,3.751236152811381896e-01,1.100000010988609489e+01,2.017688603311596114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052584530738511148e+01,6.065326639485033411e+02,3.751437921534810926e-01,1.100000010988609489e+01,2.017542617910058397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052675439828512083e+01,6.065426639281510006e+02,3.751639675659729223e-01,1.100000010988609489e+01,2.017396632508520679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052766348918513017e+01,6.065526639078016160e+02,3.751841415186137341e-01,1.100000010988609489e+01,2.017250647106982962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052857258008513952e+01,6.065626638874550736e+02,3.752043140114034725e-01,1.100000010988609489e+01,2.017104661705445244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.052948167098514887e+01,6.065726638671114870e+02,3.752244850443421931e-01,1.100000010988609489e+01,2.016958676303907527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053039076188515821e+01,6.065826638467708563e+02,3.752446546174298403e-01,1.100000010988609489e+01,2.016812690902369809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053129985278516756e+01,6.065926638264331814e+02,3.752648227306664697e-01,1.100000010988609489e+01,2.016666705500832091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053220894368517691e+01,6.066026638060984624e+02,3.752849893840520257e-01,1.100000010988609489e+01,2.016520720099294374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053311803458518625e+01,6.066126637857666992e+02,3.753051545775865638e-01,1.100000010988609489e+01,2.016374734697756656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053402712548519560e+01,6.066226637654378919e+02,3.753253183112700286e-01,1.100000010988609489e+01,2.016228749296218939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053493621638520494e+01,6.066326637451120405e+02,3.753454805851024201e-01,1.100000010988609489e+01,2.016082763894681221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053584530728521429e+01,6.066426637247891449e+02,3.753656413990837937e-01,1.100000010988609489e+01,2.015936778493143504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053675439818522364e+01,6.066526637044690915e+02,3.753858007532140939e-01,1.100000010988609489e+01,2.015790793091605786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053766348908523298e+01,6.066626636841519939e+02,3.754059586474933763e-01,1.100000010988609489e+01,2.015644807690068069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053857257998524233e+01,6.066726636638378523e+02,3.754261150819215853e-01,1.100000010988609489e+01,2.015498822288530351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.053948167088525167e+01,6.066826636435266664e+02,3.754462700564987765e-01,1.100000010988609489e+01,2.015352836886992634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054039076178526102e+01,6.066926636232184364e+02,3.754664235712248943e-01,1.100000010988609489e+01,2.015206851485454916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054129985268527037e+01,6.067026636029131623e+02,3.754865756260999388e-01,1.100000010988609489e+01,2.015060866083917199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054220894358527971e+01,6.067126635826108441e+02,3.755067262211239654e-01,1.100000010988609489e+01,2.014914880682379481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054311803448528906e+01,6.067226635623114817e+02,3.755268753562969186e-01,1.100000010988609489e+01,2.014768895280841764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054402712538529840e+01,6.067326635420150751e+02,3.755470230316188540e-01,1.100000010988609489e+01,2.014622909879304046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054493621628530775e+01,6.067426635217215107e+02,3.755671692470897161e-01,1.100000010988609489e+01,2.014476924477766329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054584530718531710e+01,6.067526635014309022e+02,3.755873140027095047e-01,1.100000010988609489e+01,2.014330939076228611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054675439808532644e+01,6.067626634811432496e+02,3.756074572984782756e-01,1.100000010988609489e+01,2.014184953674690894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054766348898533579e+01,6.067726634608585528e+02,3.756275991343959730e-01,1.100000010988609489e+01,2.014038968273153176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054857257988534514e+01,6.067826634405768118e+02,3.756477395104625971e-01,1.100000010988609489e+01,2.013892982871615459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.054948167078535448e+01,6.067926634202980267e+02,3.756678784266782034e-01,1.100000010988609489e+01,2.013746997470077741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055039076168536383e+01,6.068026634000221975e+02,3.756880158830427363e-01,1.100000010988609489e+01,2.013601012068540023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055129985258537317e+01,6.068126633797492104e+02,3.757081518795561959e-01,1.100000010988609489e+01,2.013455026667002306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055220894348538252e+01,6.068226633594791792e+02,3.757282864162186375e-01,1.100000010988609489e+01,2.013309041265464588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055311803438539187e+01,6.068326633392121039e+02,3.757484194930300059e-01,1.100000010988609489e+01,2.013163055863926871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055402712528540121e+01,6.068426633189479844e+02,3.757685511099903009e-01,1.100000010988609489e+01,2.013017070462389153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055493621618541056e+01,6.068526632986868208e+02,3.757886812670995780e-01,1.100000010988609489e+01,2.012871085060851436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055584530708541990e+01,6.068626632784286130e+02,3.758088099643577817e-01,1.100000010988609489e+01,2.012725099659313718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055675439798542925e+01,6.068726632581733611e+02,3.758289372017649121e-01,1.100000010988609489e+01,2.012579114257776001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055766348888543860e+01,6.068826632379209514e+02,3.758490629793209692e-01,1.100000010988609489e+01,2.012433128856238283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055857257978544794e+01,6.068926632176714975e+02,3.758691872970260084e-01,1.100000010988609489e+01,2.012287143454700566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.055948167068545729e+01,6.069026631974249995e+02,3.758893101548799742e-01,1.100000010988609489e+01,2.012141158053162848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056039076158546663e+01,6.069126631771814573e+02,3.759094315528828667e-01,1.100000010988609489e+01,2.011995172651625131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056129985248547598e+01,6.069226631569408710e+02,3.759295514910346858e-01,1.100000010988609489e+01,2.011849187250087413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056220894338548533e+01,6.069326631367032405e+02,3.759496699693354871e-01,1.100000010988609489e+01,2.011703201848549696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056311803428549467e+01,6.069426631164684522e+02,3.759697869877852150e-01,1.100000010988609489e+01,2.011557216447011978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056402712518550402e+01,6.069526630962366198e+02,3.759899025463838695e-01,1.100000010988609489e+01,2.011411231045474261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056493621608551337e+01,6.069626630760077433e+02,3.760100166451314507e-01,1.100000010988609489e+01,2.011265245643936543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056584530698552271e+01,6.069726630557818225e+02,3.760301292840279586e-01,1.100000010988609489e+01,2.011119260242398826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056675439788553206e+01,6.069826630355588577e+02,3.760502404630734485e-01,1.100000010988609489e+01,2.010973274840861108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056766348878554140e+01,6.069926630153388487e+02,3.760703501822678652e-01,1.100000010988609489e+01,2.010827289439323391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056857257968555075e+01,6.070026629951216819e+02,3.760904584416112084e-01,1.100000010988609489e+01,2.010681304037785673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.056948167058556010e+01,6.070126629749074709e+02,3.761105652411034783e-01,1.100000010988609489e+01,2.010535318636247955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057039076148556944e+01,6.070226629546962158e+02,3.761306705807446749e-01,1.100000010988609489e+01,2.010389333234710238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057129985238557879e+01,6.070326629344879166e+02,3.761507744605347980e-01,1.100000010988609489e+01,2.010243347833172520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057220894328558813e+01,6.070426629142825732e+02,3.761708768804739034e-01,1.100000010988609489e+01,2.010097362431634803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057311803418559748e+01,6.070526628940800720e+02,3.761909778405619353e-01,1.100000010988609489e+01,2.009951377030097085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057402712508560683e+01,6.070626628738805266e+02,3.762110773407988940e-01,1.100000010988609489e+01,2.009805391628559368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057493621598561617e+01,6.070726628536839371e+02,3.762311753811847792e-01,1.100000010988609489e+01,2.009659406227021650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057584530688562552e+01,6.070826628334903035e+02,3.762512719617195911e-01,1.100000010988609489e+01,2.009513420825483933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057675439778563486e+01,6.070926628132996257e+02,3.762713670824033296e-01,1.100000010988609489e+01,2.009367435423946215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057766348868564421e+01,6.071026627931117901e+02,3.762914607432359948e-01,1.100000010988609489e+01,2.009221450022408498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057857257958565356e+01,6.071126627729269103e+02,3.763115529442175866e-01,1.100000010988609489e+01,2.009075464620870780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.057948167048566290e+01,6.071226627527449864e+02,3.763316436853481051e-01,1.100000010988609489e+01,2.008929479219333063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058039076138567225e+01,6.071326627325660183e+02,3.763517329666276057e-01,1.100000010988609489e+01,2.008783493817795345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058129985228568160e+01,6.071426627123900062e+02,3.763718207880560329e-01,1.100000010988609489e+01,2.008637508416257628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058220894318569094e+01,6.071526626922168361e+02,3.763919071496333868e-01,1.100000010988609489e+01,2.008491523014719910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058311803408570029e+01,6.071626626720466220e+02,3.764119920513596673e-01,1.100000010988609489e+01,2.008345537613182193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058402712498570963e+01,6.071726626518793637e+02,3.764320754932348745e-01,1.100000010988609489e+01,2.008199552211644475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058493621588571898e+01,6.071826626317150613e+02,3.764521574752590083e-01,1.100000010988609489e+01,2.008053566810106758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058584530678572833e+01,6.071926626115537147e+02,3.764722379974320687e-01,1.100000010988609489e+01,2.007907581408569040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058675439768573767e+01,6.072026625913952103e+02,3.764923170597540558e-01,1.100000010988609489e+01,2.007761596007031323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058766348858574702e+01,6.072126625712396617e+02,3.765123946622249695e-01,1.100000010988609489e+01,2.007615610605493605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058857257948575636e+01,6.072226625510870690e+02,3.765324708048448099e-01,1.100000010988609489e+01,2.007469625203955887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.058948167038576571e+01,6.072326625309374322e+02,3.765525454876135769e-01,1.100000010988609489e+01,2.007323639802418170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059039076128577506e+01,6.072426625107907512e+02,3.765726187105312706e-01,1.100000010988609489e+01,2.007177654400880452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059129985218578440e+01,6.072526624906469124e+02,3.765926904735978908e-01,1.100000010988609489e+01,2.007031668999342735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059220894308579375e+01,6.072626624705060294e+02,3.766127607768134378e-01,1.100000010988609489e+01,2.006885683597805017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059311803398580309e+01,6.072726624503681023e+02,3.766328296201779113e-01,1.100000010988609489e+01,2.006739698196267300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059402712488581244e+01,6.072826624302331311e+02,3.766528970036913115e-01,1.100000010988609489e+01,2.006593712794729582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059493621578582179e+01,6.072926624101010020e+02,3.766729629273536384e-01,1.100000010988609489e+01,2.006447727393191865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059584530668583113e+01,6.073026623899718288e+02,3.766930273911648919e-01,1.100000010988609489e+01,2.006301741991654147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059675439758584048e+01,6.073126623698456115e+02,3.767130903951250720e-01,1.100000010988609489e+01,2.006155756590116430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059766348848584983e+01,6.073226623497223500e+02,3.767331519392341233e-01,1.100000010988609489e+01,2.006009771188578712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059857257938585917e+01,6.073326623296019307e+02,3.767532120234921011e-01,1.100000010988609489e+01,2.005863785787040995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.059948167028586852e+01,6.073426623094844672e+02,3.767732706478990057e-01,1.100000010988609489e+01,2.005717800385503277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060039076118587786e+01,6.073526622893699596e+02,3.767933278124548369e-01,1.100000010988609489e+01,2.005571814983965560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060129985208588721e+01,6.073626622692584078e+02,3.768133835171595947e-01,1.100000010988609489e+01,2.005425829582427842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060220894298589656e+01,6.073726622491496983e+02,3.768334377620132791e-01,1.100000010988609489e+01,2.005279844180890125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060311803388590590e+01,6.073826622290439445e+02,3.768534905470158902e-01,1.100000010988609489e+01,2.005133858779352407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060402712478591525e+01,6.073926622089411467e+02,3.768735418721674280e-01,1.100000010988609489e+01,2.004987873377814690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060493621568592459e+01,6.074026621888413047e+02,3.768935917374678923e-01,1.100000010988609489e+01,2.004841887976276972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060584530658593394e+01,6.074126621687443048e+02,3.769136401429172278e-01,1.100000010988609489e+01,2.004695902574739255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060675439748594329e+01,6.074226621486502609e+02,3.769336870885154900e-01,1.100000010988609489e+01,2.004549917173201537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060766348838595263e+01,6.074326621285591727e+02,3.769537325742626788e-01,1.100000010988609489e+01,2.004403931771663819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060857257928596198e+01,6.074426621084710405e+02,3.769737766001587942e-01,1.100000010988609489e+01,2.004257946370126102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.060948167018597132e+01,6.074526620883857504e+02,3.769938191662038363e-01,1.100000010988609489e+01,2.004111960968588384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061039076108598067e+01,6.074626620683034162e+02,3.770138602723978050e-01,1.100000010988609489e+01,2.003965975567050667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061129985198599002e+01,6.074726620482240378e+02,3.770338999187406448e-01,1.100000010988609489e+01,2.003819990165512949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061220894288599936e+01,6.074826620281476153e+02,3.770539381052324113e-01,1.100000010988609489e+01,2.003674004763975232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061311803378600871e+01,6.074926620080740349e+02,3.770739748318731044e-01,1.100000010988609489e+01,2.003528019362437514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061402712468601806e+01,6.075026619880034104e+02,3.770940100986627241e-01,1.100000010988609489e+01,2.003382033960899797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061493621558602740e+01,6.075126619679357418e+02,3.771140439056012705e-01,1.100000010988609489e+01,2.003236048559362079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061584530648603675e+01,6.075226619478710290e+02,3.771340762526886881e-01,1.100000010988609489e+01,2.003090063157824362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061675439738604609e+01,6.075326619278091584e+02,3.771541071399250322e-01,1.100000010988609489e+01,2.002944077756286644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061766348828605544e+01,6.075426619077502437e+02,3.771741365673103030e-01,1.100000010988609489e+01,2.002798092354748927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061857257918606479e+01,6.075526618876942848e+02,3.771941645348445005e-01,1.100000010988609489e+01,2.002652106953211209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.061948167008607413e+01,6.075626618676411681e+02,3.772141910425275690e-01,1.100000010988609489e+01,2.002506121551673492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062039076098608348e+01,6.075726618475910072e+02,3.772342160903595643e-01,1.100000010988609489e+01,2.002360136150135774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062129985188609282e+01,6.075826618275438022e+02,3.772542396783404861e-01,1.100000010988609489e+01,2.002214150748598057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062220894278610217e+01,6.075926618074995531e+02,3.772742618064703346e-01,1.100000010988609489e+01,2.002068165347060339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062311803368611152e+01,6.076026617874581461e+02,3.772942824747490542e-01,1.100000010988609489e+01,2.001922179945522622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062402712458612086e+01,6.076126617674196950e+02,3.773143016831767005e-01,1.100000010988609489e+01,2.001776194543984904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062493621548613021e+01,6.076226617473841998e+02,3.773343194317532734e-01,1.100000010988609489e+01,2.001630209142447187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062584530638613955e+01,6.076326617273515467e+02,3.773543357204787174e-01,1.100000010988609489e+01,2.001484223740909469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062675439728614890e+01,6.076426617073218495e+02,3.773743505493530881e-01,1.100000010988609489e+01,2.001338238339371751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062766348818615825e+01,6.076526616872951081e+02,3.773943639183763854e-01,1.100000010988609489e+01,2.001192252937834034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062857257908616759e+01,6.076626616672712089e+02,3.774143758275485538e-01,1.100000010988609489e+01,2.001046267536296316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.062948166998617694e+01,6.076726616472502656e+02,3.774343862768696489e-01,1.100000010988609489e+01,2.000900282134758599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063039076088618629e+01,6.076826616272322781e+02,3.774543952663396706e-01,1.100000010988609489e+01,2.000754296733220881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063129985178619563e+01,6.076926616072172465e+02,3.774744027959585635e-01,1.100000010988609489e+01,2.000608311331683164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063220894268620498e+01,6.077026615872050570e+02,3.774944088657263830e-01,1.100000010988609489e+01,2.000462325930145446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063311803358621432e+01,6.077126615671958234e+02,3.775144134756431291e-01,1.100000010988609489e+01,2.000316340528607729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063402712448622367e+01,6.077226615471895457e+02,3.775344166257087464e-01,1.100000010988609489e+01,2.000170355127070011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063493621538623302e+01,6.077326615271861101e+02,3.775544183159232903e-01,1.100000010988609489e+01,2.000024369725532294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063584530628624236e+01,6.077426615071856304e+02,3.775744185462867053e-01,1.100000010988609489e+01,1.999878384323994576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063675439718625171e+01,6.077526614871881065e+02,3.775944173167990470e-01,1.100000010988609489e+01,1.999732398922456859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063766348808626105e+01,6.077626614671934249e+02,3.776144146274603153e-01,1.100000010988609489e+01,1.999586413520919141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063857257898627040e+01,6.077726614472016990e+02,3.776344104782704547e-01,1.100000010988609489e+01,1.999440428119381424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.063948166988627975e+01,6.077826614272129291e+02,3.776544048692295208e-01,1.100000010988609489e+01,1.999294442717843706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064039076078628909e+01,6.077926614072270013e+02,3.776743978003374580e-01,1.100000010988609489e+01,1.999148457316305989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064129985168629844e+01,6.078026613872440294e+02,3.776943892715943218e-01,1.100000010988609489e+01,1.999002471914768271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064220894258630778e+01,6.078126613672640133e+02,3.777143792830000568e-01,1.100000010988609489e+01,1.998856486513230554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064311803348631713e+01,6.078226613472868394e+02,3.777343678345547184e-01,1.100000010988609489e+01,1.998710501111692836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064402712438632648e+01,6.078326613273126213e+02,3.777543549262582512e-01,1.100000010988609489e+01,1.998564515710155119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064493621528633582e+01,6.078426613073413591e+02,3.777743405581107106e-01,1.100000010988609489e+01,1.998418530308617401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064584530618634517e+01,6.078526612873729391e+02,3.777943247301120966e-01,1.100000010988609489e+01,1.998272544907079683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064675439708635452e+01,6.078626612674074750e+02,3.778143074422623537e-01,1.100000010988609489e+01,1.998126559505541966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064766348798636386e+01,6.078726612474449666e+02,3.778342886945615375e-01,1.100000010988609489e+01,1.997980574104004248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064857257888637321e+01,6.078826612274853005e+02,3.778542684870095925e-01,1.100000010988609489e+01,1.997834588702466531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.064948166978638255e+01,6.078926612075285902e+02,3.778742468196065740e-01,1.100000010988609489e+01,1.997688603300928813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065039076068639190e+01,6.079026611875748358e+02,3.778942236923524267e-01,1.100000010988609489e+01,1.997542617899391096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065129985158640125e+01,6.079126611676239236e+02,3.779141991052471505e-01,1.100000010988609489e+01,1.997396632497853378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065220894248641059e+01,6.079226611476759672e+02,3.779341730582908010e-01,1.100000010988609489e+01,1.997250647096315661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065311803338641994e+01,6.079326611277309667e+02,3.779541455514833226e-01,1.100000010988609489e+01,1.997104661694777943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065402712428642928e+01,6.079426611077888083e+02,3.779741165848247708e-01,1.100000010988609489e+01,1.996958676293240226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065493621518643863e+01,6.079526610878496058e+02,3.779940861583150902e-01,1.100000010988609489e+01,1.996812690891702508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065584530608644798e+01,6.079626610679133591e+02,3.780140542719543362e-01,1.100000010988609489e+01,1.996666705490164791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065675439698645732e+01,6.079726610479799547e+02,3.780340209257424533e-01,1.100000010988609489e+01,1.996520720088627073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065766348788646667e+01,6.079826610280495061e+02,3.780539861196794971e-01,1.100000010988609489e+01,1.996374734687089356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065857257878647602e+01,6.079926610081218996e+02,3.780739498537654120e-01,1.100000010988609489e+01,1.996228749285551638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.065948166968648536e+01,6.080026609881972490e+02,3.780939121280001980e-01,1.100000010988609489e+01,1.996082763884013921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066039076058649471e+01,6.080126609682755543e+02,3.781138729423839107e-01,1.100000010988609489e+01,1.995936778482476203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066129985148650405e+01,6.080226609483567017e+02,3.781338322969164945e-01,1.100000010988609489e+01,1.995790793080938486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066220894238651340e+01,6.080326609284408050e+02,3.781537901915980049e-01,1.100000010988609489e+01,1.995644807679400768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066311803328652275e+01,6.080426609085278642e+02,3.781737466264283865e-01,1.100000010988609489e+01,1.995498822277863051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066402712418653209e+01,6.080526608886177655e+02,3.781937016014076391e-01,1.100000010988609489e+01,1.995352836876325333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066493621508654144e+01,6.080626608687106227e+02,3.782136551165358185e-01,1.100000010988609489e+01,1.995206851474787615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066584530598655078e+01,6.080726608488063221e+02,3.782336071718128689e-01,1.100000010988609489e+01,1.995060866073249898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066675439688656013e+01,6.080826608289049773e+02,3.782535577672387905e-01,1.100000010988609489e+01,1.994914880671712180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066766348778656948e+01,6.080926608090065884e+02,3.782735069028136388e-01,1.100000010988609489e+01,1.994768895270174463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066857257868657882e+01,6.081026607891110416e+02,3.782934545785373581e-01,1.100000010988609489e+01,1.994622909868636745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.066948166958658817e+01,6.081126607692184507e+02,3.783134007944099486e-01,1.100000010988609489e+01,1.994476924467099028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067039076048659751e+01,6.081226607493288157e+02,3.783333455504314657e-01,1.100000010988609489e+01,1.994330939065561310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067129985138660686e+01,6.081326607294420228e+02,3.783532888466018540e-01,1.100000010988609489e+01,1.994184953664023593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067220894228661621e+01,6.081426607095581858e+02,3.783732306829211134e-01,1.100000010988609489e+01,1.994038968262485875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067311803318662555e+01,6.081526606896771909e+02,3.783931710593892994e-01,1.100000010988609489e+01,1.993892982860948158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067402712408663490e+01,6.081626606697991519e+02,3.784131099760063566e-01,1.100000010988609489e+01,1.993746997459410440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067493621498664425e+01,6.081726606499240688e+02,3.784330474327722849e-01,1.100000010988609489e+01,1.993601012057872723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067584530588665359e+01,6.081826606300518279e+02,3.784529834296870843e-01,1.100000010988609489e+01,1.993455026656335005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067675439678666294e+01,6.081926606101825428e+02,3.784729179667508103e-01,1.100000010988609489e+01,1.993309041254797288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067766348768667228e+01,6.082026605903160998e+02,3.784928510439634075e-01,1.100000010988609489e+01,1.993163055853259570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067857257858668163e+01,6.082126605704526128e+02,3.785127826613248758e-01,1.100000010988609489e+01,1.993017070451721853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.067948166948669098e+01,6.082226605505920816e+02,3.785327128188352153e-01,1.100000010988609489e+01,1.992871085050184135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068039076038670032e+01,6.082326605307343925e+02,3.785526415164944813e-01,1.100000010988609489e+01,1.992725099648646418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068129985128670967e+01,6.082426605108796593e+02,3.785725687543026186e-01,1.100000010988609489e+01,1.992579114247108700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068220894218671901e+01,6.082526604910277683e+02,3.785924945322596269e-01,1.100000010988609489e+01,1.992433128845570982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068311803308672836e+01,6.082626604711788332e+02,3.786124188503655064e-01,1.100000010988609489e+01,1.992287143444033265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068402712398673771e+01,6.082726604513328539e+02,3.786323417086202570e-01,1.100000010988609489e+01,1.992141158042495547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068493621488674705e+01,6.082826604314897168e+02,3.786522631070239342e-01,1.100000010988609489e+01,1.991995172640957830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068584530578675640e+01,6.082926604116495355e+02,3.786721830455764826e-01,1.100000010988609489e+01,1.991849187239420112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068675439668676574e+01,6.083026603918121964e+02,3.786921015242779021e-01,1.100000010988609489e+01,1.991703201837882395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068766348758677509e+01,6.083126603719778132e+02,3.787120185431281927e-01,1.100000010988609489e+01,1.991557216436344677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068857257848678444e+01,6.083226603521462721e+02,3.787319341021273544e-01,1.100000010988609489e+01,1.991411231034806960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.068948166938679378e+01,6.083326603323176869e+02,3.787518482012753873e-01,1.100000010988609489e+01,1.991265245633269242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069039076028680313e+01,6.083426603124920575e+02,3.787717608405723468e-01,1.100000010988609489e+01,1.991119260231731525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069129985118681248e+01,6.083526602926692703e+02,3.787916720200181775e-01,1.100000010988609489e+01,1.990973274830193807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069220894208682182e+01,6.083626602728494390e+02,3.788115817396128793e-01,1.100000010988609489e+01,1.990827289428656090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069311803298683117e+01,6.083726602530324499e+02,3.788314899993564522e-01,1.100000010988609489e+01,1.990681304027118372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069402712388684051e+01,6.083826602332184166e+02,3.788513967992488962e-01,1.100000010988609489e+01,1.990535318625580655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069493621478684986e+01,6.083926602134072255e+02,3.788713021392902114e-01,1.100000010988609489e+01,1.990389333224042937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069584530568685921e+01,6.084026601935989902e+02,3.788912060194803977e-01,1.100000010988609489e+01,1.990243347822505220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069675439658686855e+01,6.084126601737935971e+02,3.789111084398194551e-01,1.100000010988609489e+01,1.990097362420967502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069766348748687790e+01,6.084226601539911599e+02,3.789310094003073837e-01,1.100000010988609489e+01,1.989951377019429785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069857257838688724e+01,6.084326601341916785e+02,3.789509089009442389e-01,1.100000010988609489e+01,1.989805391617892067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.069948166928689659e+01,6.084426601143950393e+02,3.789708069417299652e-01,1.100000010988609489e+01,1.989659406216354350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070039076018690594e+01,6.084526600946013559e+02,3.789907035226645626e-01,1.100000010988609489e+01,1.989513420814816632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070129985108691528e+01,6.084626600748105147e+02,3.790105986437480312e-01,1.100000010988609489e+01,1.989367435413278914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070220894198692463e+01,6.084726600550226294e+02,3.790304923049803709e-01,1.100000010988609489e+01,1.989221450011741197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070311803288693397e+01,6.084826600352375863e+02,3.790503845063615818e-01,1.100000010988609489e+01,1.989075464610203479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070402712378694332e+01,6.084926600154554990e+02,3.790702752478916637e-01,1.100000010988609489e+01,1.988929479208665762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070493621468695267e+01,6.085026599956762539e+02,3.790901645295706168e-01,1.100000010988609489e+01,1.988783493807128044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070584530558696201e+01,6.085126599758999646e+02,3.791100523513984411e-01,1.100000010988609489e+01,1.988637508405590327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070675439648697136e+01,6.085226599561266312e+02,3.791299387133751364e-01,1.100000010988609489e+01,1.988491523004052609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070766348738698071e+01,6.085326599363561400e+02,3.791498236155007029e-01,1.100000010988609489e+01,1.988345537602514892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070857257828699005e+01,6.085426599165886046e+02,3.791697070577751405e-01,1.100000010988609489e+01,1.988199552200977174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.070948166918699940e+01,6.085526598968239114e+02,3.791895890401984492e-01,1.100000010988609489e+01,1.988053566799439457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071039076008700874e+01,6.085626598770621740e+02,3.792094695627706291e-01,1.100000010988609489e+01,1.987907581397901739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071129985098701809e+01,6.085726598573032788e+02,3.792293486254916801e-01,1.100000010988609489e+01,1.987761595996364022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071220894188702744e+01,6.085826598375473395e+02,3.792492262283616022e-01,1.100000010988609489e+01,1.987615610594826304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071311803278703678e+01,6.085926598177942424e+02,3.792691023713803955e-01,1.100000010988609489e+01,1.987469625193288587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071402712368704613e+01,6.086026597980441011e+02,3.792889770545480599e-01,1.100000010988609489e+01,1.987323639791750869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071493621458705547e+01,6.086126597782968020e+02,3.793088502778645954e-01,1.100000010988609489e+01,1.987177654390213152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071584530548706482e+01,6.086226597585524587e+02,3.793287220413299465e-01,1.100000010988609489e+01,1.987031668988675434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071675439638707417e+01,6.086326597388109576e+02,3.793485923449441688e-01,1.100000010988609489e+01,1.986885683587137717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071766348728708351e+01,6.086426597190724124e+02,3.793684611887072622e-01,1.100000010988609489e+01,1.986739698185599999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071857257818709286e+01,6.086526596993367093e+02,3.793883285726192267e-01,1.100000010988609489e+01,1.986593712784062282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.071948166908710220e+01,6.086626596796039621e+02,3.794081944966800624e-01,1.100000010988609489e+01,1.986447727382524564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072039075998711155e+01,6.086726596598740571e+02,3.794280589608897691e-01,1.100000010988609489e+01,1.986301741980986846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072129985088712090e+01,6.086826596401471079e+02,3.794479219652483470e-01,1.100000010988609489e+01,1.986155756579449129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072220894178713024e+01,6.086926596204230009e+02,3.794677835097557961e-01,1.100000010988609489e+01,1.986009771177911411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072311803268713959e+01,6.087026596007018497e+02,3.794876435944121162e-01,1.100000010988609489e+01,1.985863785776373694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072402712358714894e+01,6.087126595809835408e+02,3.795075022192173075e-01,1.100000010988609489e+01,1.985717800374835976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072493621448715828e+01,6.087226595612681876e+02,3.795273593841713144e-01,1.100000010988609489e+01,1.985571814973298259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072584530538716763e+01,6.087326595415556767e+02,3.795472150892741925e-01,1.100000010988609489e+01,1.985425829571760541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072675439628717697e+01,6.087426595218461216e+02,3.795670693345259417e-01,1.100000010988609489e+01,1.985279844170222824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072766348718718632e+01,6.087526595021394087e+02,3.795869221199265620e-01,1.100000010988609489e+01,1.985133858768685106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072857257808719567e+01,6.087626594824356516e+02,3.796067734454760534e-01,1.100000010988609489e+01,1.984987873367147389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.072948166898720501e+01,6.087726594627347367e+02,3.796266233111744159e-01,1.100000010988609489e+01,1.984841887965609671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073039075988721436e+01,6.087826594430367777e+02,3.796464717170215941e-01,1.100000010988609489e+01,1.984695902564071954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073129985078722370e+01,6.087926594233416608e+02,3.796663186630176434e-01,1.100000010988609489e+01,1.984549917162534236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073220894168723305e+01,6.088026594036494998e+02,3.796861641491625639e-01,1.100000010988609489e+01,1.984403931760996519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073311803258724240e+01,6.088126593839601810e+02,3.797060081754563554e-01,1.100000010988609489e+01,1.984257946359458801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073402712348725174e+01,6.088226593642738180e+02,3.797258507418989626e-01,1.100000010988609489e+01,1.984111960957921084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073493621438726109e+01,6.088326593445902972e+02,3.797456918484904409e-01,1.100000010988609489e+01,1.983965975556383366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073584530528727043e+01,6.088426593249097323e+02,3.797655314952307903e-01,1.100000010988609489e+01,1.983819990154845649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073675439618727978e+01,6.088526593052320095e+02,3.797853696821200109e-01,1.100000010988609489e+01,1.983674004753307931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073766348708728913e+01,6.088626592855572426e+02,3.798052064091581026e-01,1.100000010988609489e+01,1.983528019351770214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073857257798729847e+01,6.088726592658853178e+02,3.798250416763450099e-01,1.100000010988609489e+01,1.983382033950232496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.073948166888730782e+01,6.088826592462163489e+02,3.798448754836807884e-01,1.100000010988609489e+01,1.983236048548694778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074039075978731717e+01,6.088926592265502222e+02,3.798647078311654379e-01,1.100000010988609489e+01,1.983090063147157061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074129985068732651e+01,6.089026592068870514e+02,3.798845387187989031e-01,1.100000010988609489e+01,1.982944077745619343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074220894158733586e+01,6.089126591872267227e+02,3.799043681465812394e-01,1.100000010988609489e+01,1.982798092344081626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074311803248734520e+01,6.089226591675692362e+02,3.799241961145124469e-01,1.100000010988609489e+01,1.982652106942543908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074402712338735455e+01,6.089326591479147055e+02,3.799440226225925255e-01,1.100000010988609489e+01,1.982506121541006191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074493621428736390e+01,6.089426591282630170e+02,3.799638476708214196e-01,1.100000010988609489e+01,1.982360136139468473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074584530518737324e+01,6.089526591086142844e+02,3.799836712591991850e-01,1.100000010988609489e+01,1.982214150737930756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074675439608738259e+01,6.089626590889683939e+02,3.800034933877258214e-01,1.100000010988609489e+01,1.982068165336393038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074766348698739193e+01,6.089726590693254593e+02,3.800233140564012735e-01,1.100000010988609489e+01,1.981922179934855321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074857257788740128e+01,6.089826590496853669e+02,3.800431332652255967e-01,1.100000010988609489e+01,1.981776194533317603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.074948166878741063e+01,6.089926590300482303e+02,3.800629510141987910e-01,1.100000010988609489e+01,1.981630209131779886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075039075968741997e+01,6.090026590104139359e+02,3.800827673033208010e-01,1.100000010988609489e+01,1.981484223730242168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075129985058742932e+01,6.090126589907825974e+02,3.801025821325916820e-01,1.100000010988609489e+01,1.981338238328704451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075220894148743866e+01,6.090226589711541010e+02,3.801223955020113787e-01,1.100000010988609489e+01,1.981192252927166733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075311803238744801e+01,6.090326589515284468e+02,3.801422074115799465e-01,1.100000010988609489e+01,1.981046267525629016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075402712328745736e+01,6.090426589319057484e+02,3.801620178612973855e-01,1.100000010988609489e+01,1.980900282124091298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075493621418746670e+01,6.090526589122858923e+02,3.801818268511636401e-01,1.100000010988609489e+01,1.980754296722553581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075584530508747605e+01,6.090626588926689919e+02,3.802016343811787658e-01,1.100000010988609489e+01,1.980608311321015863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075675439598748540e+01,6.090726588730549338e+02,3.802214404513427071e-01,1.100000010988609489e+01,1.980462325919478146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075766348688749474e+01,6.090826588534438315e+02,3.802412450616555195e-01,1.100000010988609489e+01,1.980316340517940428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075857257778750409e+01,6.090926588338355714e+02,3.802610482121172031e-01,1.100000010988609489e+01,1.980170355116402710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.075948166868751343e+01,6.091026588142301534e+02,3.802808499027277023e-01,1.100000010988609489e+01,1.980024369714864993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076039075958752278e+01,6.091126587946276913e+02,3.803006501334870726e-01,1.100000010988609489e+01,1.979878384313327275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076129985048753213e+01,6.091226587750280714e+02,3.803204489043952585e-01,1.100000010988609489e+01,1.979732398911789558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076220894138754147e+01,6.091326587554314074e+02,3.803402462154523156e-01,1.100000010988609489e+01,1.979586413510251840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076311803228755082e+01,6.091426587358375855e+02,3.803600420666581883e-01,1.100000010988609489e+01,1.979440428108714123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076402712318756016e+01,6.091526587162467195e+02,3.803798364580129321e-01,1.100000010988609489e+01,1.979294442707176405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076493621408756951e+01,6.091626586966586956e+02,3.803996293895164915e-01,1.100000010988609489e+01,1.979148457305638688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076584530498757886e+01,6.091726586770735139e+02,3.804194208611689221e-01,1.100000010988609489e+01,1.979002471904100970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076675439588758820e+01,6.091826586574912881e+02,3.804392108729701683e-01,1.100000010988609489e+01,1.978856486502563253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076766348678759755e+01,6.091926586379119044e+02,3.804589994249202856e-01,1.100000010988609489e+01,1.978710501101025535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076857257768760689e+01,6.092026586183354766e+02,3.804787865170192185e-01,1.100000010988609489e+01,1.978564515699487818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.076948166858761624e+01,6.092126585987618910e+02,3.804985721492670225e-01,1.100000010988609489e+01,1.978418530297950100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077039075948762559e+01,6.092226585791911475e+02,3.805183563216636422e-01,1.100000010988609489e+01,1.978272544896412383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077129985038763493e+01,6.092326585596233599e+02,3.805381390342091330e-01,1.100000010988609489e+01,1.978126559494874665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077220894128764428e+01,6.092426585400584145e+02,3.805579202869034394e-01,1.100000010988609489e+01,1.977980574093336948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077311803218765363e+01,6.092526585204964249e+02,3.805777000797466170e-01,1.100000010988609489e+01,1.977834588691799230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077402712308766297e+01,6.092626585009372775e+02,3.805974784127386101e-01,1.100000010988609489e+01,1.977688603290261513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077493621398767232e+01,6.092726584813809723e+02,3.806172552858794744e-01,1.100000010988609489e+01,1.977542617888723795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077584530488768166e+01,6.092826584618276229e+02,3.806370306991691543e-01,1.100000010988609489e+01,1.977396632487186078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077675439578769101e+01,6.092926584422771157e+02,3.806568046526076499e-01,1.100000010988609489e+01,1.977250647085648360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077766348668770036e+01,6.093026584227295643e+02,3.806765771461950165e-01,1.100000010988609489e+01,1.977104661684110642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077857257758770970e+01,6.093126584031848552e+02,3.806963481799311988e-01,1.100000010988609489e+01,1.976958676282572925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.077948166848771905e+01,6.093226583836429882e+02,3.807161177538162522e-01,1.100000010988609489e+01,1.976812690881035207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078039075938772839e+01,6.093326583641040770e+02,3.807358858678501212e-01,1.100000010988609489e+01,1.976666705479497490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078129985028773774e+01,6.093426583445680080e+02,3.807556525220328059e-01,1.100000010988609489e+01,1.976520720077959772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078220894118774709e+01,6.093526583250348949e+02,3.807754177163643616e-01,1.100000010988609489e+01,1.976374734676422055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078311803208775643e+01,6.093626583055046240e+02,3.807951814508447330e-01,1.100000010988609489e+01,1.976228749274884337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078402712298776578e+01,6.093726582859771952e+02,3.808149437254739200e-01,1.100000010988609489e+01,1.976082763873346620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078493621388777512e+01,6.093826582664527223e+02,3.808347045402519782e-01,1.100000010988609489e+01,1.975936778471808902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078584530478778447e+01,6.093926582469310915e+02,3.808544638951788519e-01,1.100000010988609489e+01,1.975790793070271185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078675439568779382e+01,6.094026582274123029e+02,3.808742217902545968e-01,1.100000010988609489e+01,1.975644807668733467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078766348658780316e+01,6.094126582078964702e+02,3.808939782254791573e-01,1.100000010988609489e+01,1.975498822267195750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078857257748781251e+01,6.094226581883834797e+02,3.809137332008525334e-01,1.100000010988609489e+01,1.975352836865658032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.078948166838782186e+01,6.094326581688734450e+02,3.809334867163747251e-01,1.100000010988609489e+01,1.975206851464120315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079039075928783120e+01,6.094426581493662525e+02,3.809532387720457880e-01,1.100000010988609489e+01,1.975060866062582597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079129985018784055e+01,6.094526581298619021e+02,3.809729893678656665e-01,1.100000010988609489e+01,1.974914880661044880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079220894108784989e+01,6.094626581103605076e+02,3.809927385038343606e-01,1.100000010988609489e+01,1.974768895259507162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079311803198785924e+01,6.094726580908619553e+02,3.810124861799519258e-01,1.100000010988609489e+01,1.974622909857969445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079402712288786859e+01,6.094826580713662452e+02,3.810322323962183066e-01,1.100000010988609489e+01,1.974476924456431727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079493621378787793e+01,6.094926580518734909e+02,3.810519771526335031e-01,1.100000010988609489e+01,1.974330939054894010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079584530468788728e+01,6.095026580323835788e+02,3.810717204491975152e-01,1.100000010988609489e+01,1.974184953653356292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079675439558789662e+01,6.095126580128965088e+02,3.810914622859103984e-01,1.100000010988609489e+01,1.974038968251818574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079766348648790597e+01,6.095226579934123947e+02,3.811112026627720972e-01,1.100000010988609489e+01,1.973892982850280857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079857257738791532e+01,6.095326579739311228e+02,3.811309415797826117e-01,1.100000010988609489e+01,1.973746997448743139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.079948166828792466e+01,6.095426579544526930e+02,3.811506790369419417e-01,1.100000010988609489e+01,1.973601012047205422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080039075918793401e+01,6.095526579349772192e+02,3.811704150342501429e-01,1.100000010988609489e+01,1.973455026645667704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080129985008794335e+01,6.095626579155045874e+02,3.811901495717071597e-01,1.100000010988609489e+01,1.973309041244129987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080220894098795270e+01,6.095726578960347979e+02,3.812098826493129922e-01,1.100000010988609489e+01,1.973163055842592269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080311803188796205e+01,6.095826578765679642e+02,3.812296142670676402e-01,1.100000010988609489e+01,1.973017070441054552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080402712278797139e+01,6.095926578571039727e+02,3.812493444249711039e-01,1.100000010988609489e+01,1.972871085039516834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080493621368798074e+01,6.096026578376428233e+02,3.812690731230234387e-01,1.100000010988609489e+01,1.972725099637979117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080584530458799009e+01,6.096126578181846298e+02,3.812888003612245891e-01,1.100000010988609489e+01,1.972579114236441399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080675439548799943e+01,6.096226577987292785e+02,3.813085261395745551e-01,1.100000010988609489e+01,1.972433128834903682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080766348638800878e+01,6.096326577792767694e+02,3.813282504580733367e-01,1.100000010988609489e+01,1.972287143433365964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080857257728801812e+01,6.096426577598272161e+02,3.813479733167209340e-01,1.100000010988609489e+01,1.972141158031828247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.080948166818802747e+01,6.096526577403805049e+02,3.813676947155173469e-01,1.100000010988609489e+01,1.971995172630290529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081039075908803682e+01,6.096626577209366360e+02,3.813874146544626309e-01,1.100000010988609489e+01,1.971849187228752812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081129984998804616e+01,6.096726577014957229e+02,3.814071331335567305e-01,1.100000010988609489e+01,1.971703201827215094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081220894088805551e+01,6.096826576820576520e+02,3.814268501527996458e-01,1.100000010988609489e+01,1.971557216425677377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081311803178806485e+01,6.096926576626224232e+02,3.814465657121913766e-01,1.100000010988609489e+01,1.971411231024139659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081402712268807420e+01,6.097026576431901503e+02,3.814662798117319231e-01,1.100000010988609489e+01,1.971265245622601942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081493621358808355e+01,6.097126576237607196e+02,3.814859924514212852e-01,1.100000010988609489e+01,1.971119260221064224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081584530448809289e+01,6.097226576043341311e+02,3.815057036312594629e-01,1.100000010988609489e+01,1.970973274819526506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081675439538810224e+01,6.097326575849104984e+02,3.815254133512464563e-01,1.100000010988609489e+01,1.970827289417988789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081766348628811159e+01,6.097426575654897078e+02,3.815451216113822652e-01,1.100000010988609489e+01,1.970681304016451071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081857257718812093e+01,6.097526575460717595e+02,3.815648284116669453e-01,1.100000010988609489e+01,1.970535318614913354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.081948166808813028e+01,6.097626575266567670e+02,3.815845337521004410e-01,1.100000010988609489e+01,1.970389333213375636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082039075898813962e+01,6.097726575072446167e+02,3.816042376326827523e-01,1.100000010988609489e+01,1.970243347811837919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082129984988814897e+01,6.097826574878353085e+02,3.816239400534138793e-01,1.100000010988609489e+01,1.970097362410300201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082220894078815832e+01,6.097926574684288425e+02,3.816436410142938218e-01,1.100000010988609489e+01,1.969951377008762484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082311803168816766e+01,6.098026574490253324e+02,3.816633405153225800e-01,1.100000010988609489e+01,1.969805391607224766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082402712258817701e+01,6.098126574296246645e+02,3.816830385565001538e-01,1.100000010988609489e+01,1.969659406205687049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082493621348818635e+01,6.098226574102268387e+02,3.817027351378265432e-01,1.100000010988609489e+01,1.969513420804149331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082584530438819570e+01,6.098326573908319688e+02,3.817224302593017482e-01,1.100000010988609489e+01,1.969367435402611614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082675439528820505e+01,6.098426573714399410e+02,3.817421239209257688e-01,1.100000010988609489e+01,1.969221450001073896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082766348618821439e+01,6.098526573520507554e+02,3.817618161226986051e-01,1.100000010988609489e+01,1.969075464599536179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082857257708822374e+01,6.098626573326645257e+02,3.817815068646202570e-01,1.100000010988609489e+01,1.968929479197998461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.082948166798823308e+01,6.098726573132811382e+02,3.818011961466907245e-01,1.100000010988609489e+01,1.968783493796460744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083039075888824243e+01,6.098826572939005928e+02,3.818208839689100076e-01,1.100000010988609489e+01,1.968637508394923026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083129984978825178e+01,6.098926572745228896e+02,3.818405703312781063e-01,1.100000010988609489e+01,1.968491522993385309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083220894068826112e+01,6.099026572551481422e+02,3.818602552337950207e-01,1.100000010988609489e+01,1.968345537591847591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083311803158827047e+01,6.099126572357762370e+02,3.818799386764607506e-01,1.100000010988609489e+01,1.968199552190309874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083402712248827982e+01,6.099226572164071740e+02,3.818996206592752962e-01,1.100000010988609489e+01,1.968053566788772156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083493621338828916e+01,6.099326571970409532e+02,3.819193011822386574e-01,1.100000010988609489e+01,1.967907581387234438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083584530428829851e+01,6.099426571776776882e+02,3.819389802453507787e-01,1.100000010988609489e+01,1.967761595985696721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083675439518830785e+01,6.099526571583172654e+02,3.819586578486117157e-01,1.100000010988609489e+01,1.967615610584159003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083766348608831720e+01,6.099626571389596847e+02,3.819783339920214682e-01,1.100000010988609489e+01,1.967469625182621286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083857257698832655e+01,6.099726571196050600e+02,3.819980086755800364e-01,1.100000010988609489e+01,1.967323639781083568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.083948166788833589e+01,6.099826571002532773e+02,3.820176818992874201e-01,1.100000010988609489e+01,1.967177654379545851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084039075878834524e+01,6.099926570809043369e+02,3.820373536631436195e-01,1.100000010988609489e+01,1.967031668978008133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084129984968835458e+01,6.100026570615582386e+02,3.820570239671486346e-01,1.100000010988609489e+01,1.966885683576470416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084220894058836393e+01,6.100126570422150962e+02,3.820766928113024652e-01,1.100000010988609489e+01,1.966739698174932698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084311803148837328e+01,6.100226570228747960e+02,3.820963601956051114e-01,1.100000010988609489e+01,1.966593712773394981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084402712238838262e+01,6.100326570035373379e+02,3.821160261200565178e-01,1.100000010988609489e+01,1.966447727371857263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084493621328839197e+01,6.100426569842027220e+02,3.821356905846567398e-01,1.100000010988609489e+01,1.966301741970319546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084584530418840131e+01,6.100526569648710620e+02,3.821553535894057774e-01,1.100000010988609489e+01,1.966155756568781828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084675439508841066e+01,6.100626569455422441e+02,3.821750151343036306e-01,1.100000010988609489e+01,1.966009771167244111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084766348598842001e+01,6.100726569262162684e+02,3.821946752193502994e-01,1.100000010988609489e+01,1.965863785765706393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084857257688842935e+01,6.100826569068931349e+02,3.822143338445457839e-01,1.100000010988609489e+01,1.965717800364168676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.084948166778843870e+01,6.100926568875729572e+02,3.822339910098900284e-01,1.100000010988609489e+01,1.965571814962630958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085039075868844805e+01,6.101026568682556217e+02,3.822536467153830886e-01,1.100000010988609489e+01,1.965425829561093241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085129984958845739e+01,6.101126568489411284e+02,3.822733009610249644e-01,1.100000010988609489e+01,1.965279844159555523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085220894048846674e+01,6.101226568296294772e+02,3.822929537468156558e-01,1.100000010988609489e+01,1.965133858758017806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085311803138847608e+01,6.101326568103207819e+02,3.823126050727551628e-01,1.100000010988609489e+01,1.964987873356480088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085402712228848543e+01,6.101426567910149288e+02,3.823322549388434299e-01,1.100000010988609489e+01,1.964841887954942370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085493621318849478e+01,6.101526567717119178e+02,3.823519033450805127e-01,1.100000010988609489e+01,1.964695902553404653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085584530408850412e+01,6.101626567524117490e+02,3.823715502914664111e-01,1.100000010988609489e+01,1.964549917151866935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085675439498851347e+01,6.101726567331144224e+02,3.823911957780011250e-01,1.100000010988609489e+01,1.964403931750329218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085766348588852281e+01,6.101826567138200517e+02,3.824108398046845991e-01,1.100000010988609489e+01,1.964257946348791500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085857257678853216e+01,6.101926566945285231e+02,3.824304823715168888e-01,1.100000010988609489e+01,1.964111960947253783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.085948166768854151e+01,6.102026566752398367e+02,3.824501234784979942e-01,1.100000010988609489e+01,1.963965975545716065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086039075858855085e+01,6.102126566559539924e+02,3.824697631256279151e-01,1.100000010988609489e+01,1.963819990144178348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086129984948856020e+01,6.102226566366711040e+02,3.824894013129065962e-01,1.100000010988609489e+01,1.963674004742640630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086220894038856954e+01,6.102326566173910578e+02,3.825090380403340928e-01,1.100000010988609489e+01,1.963528019341102913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086311803128857889e+01,6.102426565981138538e+02,3.825286733079104051e-01,1.100000010988609489e+01,1.963382033939565195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086402712218858824e+01,6.102526565788394919e+02,3.825483071156354775e-01,1.100000010988609489e+01,1.963236048538027478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086493621308859758e+01,6.102626565595679722e+02,3.825679394635093655e-01,1.100000010988609489e+01,1.963090063136489760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086584530398860693e+01,6.102726565402994083e+02,3.825875703515320692e-01,1.100000010988609489e+01,1.962944077734952043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086675439488861628e+01,6.102826565210336867e+02,3.826071997797035329e-01,1.100000010988609489e+01,1.962798092333414325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086766348578862562e+01,6.102926565017708072e+02,3.826268277480238122e-01,1.100000010988609489e+01,1.962652106931876608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086857257668863497e+01,6.103026564825107698e+02,3.826464542564929072e-01,1.100000010988609489e+01,1.962506121530338890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.086948166758864431e+01,6.103126564632535747e+02,3.826660793051107623e-01,1.100000010988609489e+01,1.962360136128801173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087039075848865366e+01,6.103226564439993354e+02,3.826857028938774330e-01,1.100000010988609489e+01,1.962214150727263455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087129984938866301e+01,6.103326564247479382e+02,3.827053250227929193e-01,1.100000010988609489e+01,1.962068165325725737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087220894028867235e+01,6.103426564054993833e+02,3.827249456918571657e-01,1.100000010988609489e+01,1.961922179924188020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087311803118868170e+01,6.103526563862536705e+02,3.827445649010702278e-01,1.100000010988609489e+01,1.961776194522650302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087402712208869104e+01,6.103626563670107998e+02,3.827641826504321054e-01,1.100000010988609489e+01,1.961630209121112585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087493621298870039e+01,6.103726563477708851e+02,3.827837989399427432e-01,1.100000010988609489e+01,1.961484223719574867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087584530388870974e+01,6.103826563285338125e+02,3.828034137696021966e-01,1.100000010988609489e+01,1.961338238318037150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087675439478871908e+01,6.103926563092995821e+02,3.828230271394104101e-01,1.100000010988609489e+01,1.961192252916499432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087766348568872843e+01,6.104026562900681938e+02,3.828426390493674392e-01,1.100000010988609489e+01,1.961046267514961715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087857257658873777e+01,6.104126562708396477e+02,3.828622494994732839e-01,1.100000010988609489e+01,1.960900282113423997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.087948166748874712e+01,6.104226562516140575e+02,3.828818584897278887e-01,1.100000010988609489e+01,1.960754296711886280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088039075838875647e+01,6.104326562323913095e+02,3.829014660201313092e-01,1.100000010988609489e+01,1.960608311310348562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088129984928876581e+01,6.104426562131714036e+02,3.829210720906834897e-01,1.100000010988609489e+01,1.960462325908810845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088220894018877516e+01,6.104526561939543399e+02,3.829406767013844859e-01,1.100000010988609489e+01,1.960316340507273127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088311803108878451e+01,6.104626561747401183e+02,3.829602798522342422e-01,1.100000010988609489e+01,1.960170355105735410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088402712198879385e+01,6.104726561555287390e+02,3.829798815432328141e-01,1.100000010988609489e+01,1.960024369704197692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088493621288880320e+01,6.104826561363203155e+02,3.829994817743801461e-01,1.100000010988609489e+01,1.959878384302659975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088584530378881254e+01,6.104926561171147341e+02,3.830190805456762937e-01,1.100000010988609489e+01,1.959732398901122257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088675439468882189e+01,6.105026560979119949e+02,3.830386778571212014e-01,1.100000010988609489e+01,1.959586413499584540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088766348558883124e+01,6.105126560787120980e+02,3.830582737087149248e-01,1.100000010988609489e+01,1.959440428098046822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088857257648884058e+01,6.105226560595150431e+02,3.830778681004574082e-01,1.100000010988609489e+01,1.959294442696509105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.088948166738884993e+01,6.105326560403208305e+02,3.830974610323487073e-01,1.100000010988609489e+01,1.959148457294971387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089039075828885927e+01,6.105426560211295737e+02,3.831170525043887665e-01,1.100000010988609489e+01,1.959002471893433669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089129984918886862e+01,6.105526560019411590e+02,3.831366425165776413e-01,1.100000010988609489e+01,1.958856486491895952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089220894008887797e+01,6.105626559827555866e+02,3.831562310689152762e-01,1.100000010988609489e+01,1.958710501090358234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089311803098888731e+01,6.105726559635728563e+02,3.831758181614017267e-01,1.100000010988609489e+01,1.958564515688820517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089402712188889666e+01,6.105826559443929682e+02,3.831954037940369373e-01,1.100000010988609489e+01,1.958418530287282799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089493621278890600e+01,6.105926559252159223e+02,3.832149879668209635e-01,1.100000010988609489e+01,1.958272544885745082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089584530368891535e+01,6.106026559060417185e+02,3.832345706797537499e-01,1.100000010988609489e+01,1.958126559484207364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089675439458892470e+01,6.106126558868704706e+02,3.832541519328352964e-01,1.100000010988609489e+01,1.957980574082669647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089766348548893404e+01,6.106226558677020648e+02,3.832737317260656584e-01,1.100000010988609489e+01,1.957834588681131929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089857257638894339e+01,6.106326558485365013e+02,3.832933100594447806e-01,1.100000010988609489e+01,1.957688603279594212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.089948166728895274e+01,6.106426558293737799e+02,3.833128869329727184e-01,1.100000010988609489e+01,1.957542617878056494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090039075818896208e+01,6.106526558102139006e+02,3.833324623466494163e-01,1.100000010988609489e+01,1.957396632476518777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090129984908897143e+01,6.106626557910568636e+02,3.833520363004748743e-01,1.100000010988609489e+01,1.957250647074981059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090220893998898077e+01,6.106726557719026687e+02,3.833716087944491480e-01,1.100000010988609489e+01,1.957104661673443342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090311803088899012e+01,6.106826557527514296e+02,3.833911798285721817e-01,1.100000010988609489e+01,1.956958676271905624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090402712178899947e+01,6.106926557336030328e+02,3.834107494028440311e-01,1.100000010988609489e+01,1.956812690870367907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090493621268900881e+01,6.107026557144574781e+02,3.834303175172646405e-01,1.100000010988609489e+01,1.956666705468830189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090584530358901816e+01,6.107126556953147656e+02,3.834498841718340101e-01,1.100000010988609489e+01,1.956520720067292472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090675439448902750e+01,6.107226556761748952e+02,3.834694493665521953e-01,1.100000010988609489e+01,1.956374734665754754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090766348538903685e+01,6.107326556570378671e+02,3.834890131014191406e-01,1.100000010988609489e+01,1.956228749264217037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090857257628904620e+01,6.107426556379036811e+02,3.835085753764348460e-01,1.100000010988609489e+01,1.956082763862679319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.090948166718905554e+01,6.107526556187723372e+02,3.835281361915993670e-01,1.100000010988609489e+01,1.955936778461141601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091039075808906489e+01,6.107626555996439492e+02,3.835476955469126481e-01,1.100000010988609489e+01,1.955790793059603884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091129984898907423e+01,6.107726555805184034e+02,3.835672534423746893e-01,1.100000010988609489e+01,1.955644807658066166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091220893988908358e+01,6.107826555613956998e+02,3.835868098779854907e-01,1.100000010988609489e+01,1.955498822256528449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091311803078909293e+01,6.107926555422758383e+02,3.836063648537451076e-01,1.100000010988609489e+01,1.955352836854990731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091402712168910227e+01,6.108026555231588191e+02,3.836259183696534847e-01,1.100000010988609489e+01,1.955206851453453014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091493621258911162e+01,6.108126555040446419e+02,3.836454704257106219e-01,1.100000010988609489e+01,1.955060866051915296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091584530348912097e+01,6.108226554849333070e+02,3.836650210219165746e-01,1.100000010988609489e+01,1.954914880650377579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091675439438913031e+01,6.108326554658248142e+02,3.836845701582712875e-01,1.100000010988609489e+01,1.954768895248839861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091766348528913966e+01,6.108426554467191636e+02,3.837041178347747605e-01,1.100000010988609489e+01,1.954622909847302144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091857257618914900e+01,6.108526554276164688e+02,3.837236640514269936e-01,1.100000010988609489e+01,1.954476924445764426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.091948166708915835e+01,6.108626554085166163e+02,3.837432088082280424e-01,1.100000010988609489e+01,1.954330939044226709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092039075798916770e+01,6.108726553894196059e+02,3.837627521051778512e-01,1.100000010988609489e+01,1.954184953642688991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092129984888917704e+01,6.108826553703254376e+02,3.837822939422764201e-01,1.100000010988609489e+01,1.954038968241151274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092220893978918639e+01,6.108926553512341115e+02,3.838018343195237492e-01,1.100000010988609489e+01,1.953892982839613556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092311803068919573e+01,6.109026553321456277e+02,3.838213732369198383e-01,1.100000010988609489e+01,1.953746997438075839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092402712158920508e+01,6.109126553130599859e+02,3.838409106944647431e-01,1.100000010988609489e+01,1.953601012036538121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092493621248921443e+01,6.109226552939771864e+02,3.838604466921584080e-01,1.100000010988609489e+01,1.953455026635000404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092584530338922377e+01,6.109326552748972290e+02,3.838799812300008329e-01,1.100000010988609489e+01,1.953309041233462686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092675439428923312e+01,6.109426552558201138e+02,3.838995143079920180e-01,1.100000010988609489e+01,1.953163055831924969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092766348518924246e+01,6.109526552367458407e+02,3.839190459261319632e-01,1.100000010988609489e+01,1.953017070430387251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092857257608925181e+01,6.109626552176745236e+02,3.839385760844206685e-01,1.100000010988609489e+01,1.952871085028849533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.092948166698926116e+01,6.109726551986060485e+02,3.839581047828581895e-01,1.100000010988609489e+01,1.952725099627311816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093039075788927050e+01,6.109826551795404157e+02,3.839776320214444705e-01,1.100000010988609489e+01,1.952579114225774098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093129984878927985e+01,6.109926551604776250e+02,3.839971578001795116e-01,1.100000010988609489e+01,1.952433128824236381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093220893968928920e+01,6.110026551414176765e+02,3.840166821190633129e-01,1.100000010988609489e+01,1.952287143422698663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093311803058929854e+01,6.110126551223605702e+02,3.840362049780958742e-01,1.100000010988609489e+01,1.952141158021160946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093402712148930789e+01,6.110226551033063060e+02,3.840557263772771956e-01,1.100000010988609489e+01,1.951995172619623228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093493621238931723e+01,6.110326550842548841e+02,3.840752463166072772e-01,1.100000010988609489e+01,1.951849187218085511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093584530328932658e+01,6.110426550652063042e+02,3.840947647960861189e-01,1.100000010988609489e+01,1.951703201816547793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093675439418933593e+01,6.110526550461605666e+02,3.841142818157137762e-01,1.100000010988609489e+01,1.951557216415010076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093766348508934527e+01,6.110626550271176711e+02,3.841337973754901935e-01,1.100000010988609489e+01,1.951411231013472358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093857257598935462e+01,6.110726550080776178e+02,3.841533114754153710e-01,1.100000010988609489e+01,1.951265245611934641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.093948166688936396e+01,6.110826549890404067e+02,3.841728241154893086e-01,1.100000010988609489e+01,1.951119260210396923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094039075778937331e+01,6.110926549700060377e+02,3.841923352957120064e-01,1.100000010988609489e+01,1.950973274808859206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094129984868938266e+01,6.111026549509745109e+02,3.842118450160834642e-01,1.100000010988609489e+01,1.950827289407321488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094220893958939200e+01,6.111126549319458263e+02,3.842313532766036821e-01,1.100000010988609489e+01,1.950681304005783771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094311803048940135e+01,6.111226549129200976e+02,3.842508600772726601e-01,1.100000010988609489e+01,1.950535318604246053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094402712138941069e+01,6.111326548938972110e+02,3.842703654180903983e-01,1.100000010988609489e+01,1.950389333202708336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094493621228942004e+01,6.111426548748771665e+02,3.842898692990568965e-01,1.100000010988609489e+01,1.950243347801170618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094584530318942939e+01,6.111526548558599643e+02,3.843093717201721549e-01,1.100000010988609489e+01,1.950097362399632901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094675439408943873e+01,6.111626548368456042e+02,3.843288726814361733e-01,1.100000010988609489e+01,1.949951376998095183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094766348498944808e+01,6.111726548178340863e+02,3.843483721828489519e-01,1.100000010988609489e+01,1.949805391596557465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094857257588945743e+01,6.111826547988254106e+02,3.843678702244104906e-01,1.100000010988609489e+01,1.949659406195019748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.094948166678946677e+01,6.111926547798195770e+02,3.843873668061207893e-01,1.100000010988609489e+01,1.949513420793482030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095039075768947612e+01,6.112026547608165856e+02,3.844068619279798482e-01,1.100000010988609489e+01,1.949367435391944313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095129984858948546e+01,6.112126547418164364e+02,3.844263555899876672e-01,1.100000010988609489e+01,1.949221449990406595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095220893948949481e+01,6.112226547228191293e+02,3.844458477921442463e-01,1.100000010988609489e+01,1.949075464588868878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095311803038950416e+01,6.112326547038246645e+02,3.844653385344495855e-01,1.100000010988609489e+01,1.948929479187331160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095402712128951350e+01,6.112426546848330418e+02,3.844848278169036848e-01,1.100000010988609489e+01,1.948783493785793443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095493621218952285e+01,6.112526546658442612e+02,3.845043156395065442e-01,1.100000010988609489e+01,1.948637508384255725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095584530308953219e+01,6.112626546468583228e+02,3.845238020022581638e-01,1.100000010988609489e+01,1.948491522982718008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095675439398954154e+01,6.112726546278752267e+02,3.845432869051585434e-01,1.100000010988609489e+01,1.948345537581180290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095766348488955089e+01,6.112826546088949726e+02,3.845627703482076831e-01,1.100000010988609489e+01,1.948199552179642573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095857257578956023e+01,6.112926545899175608e+02,3.845822523314055830e-01,1.100000010988609489e+01,1.948053566778104855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.095948166668956958e+01,6.113026545709429911e+02,3.846017328547521874e-01,1.100000010988609489e+01,1.947907581376567138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096039075758957893e+01,6.113126545519712636e+02,3.846212119182475520e-01,1.100000010988609489e+01,1.947761595975029420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096129984848958827e+01,6.113226545330023782e+02,3.846406895218916766e-01,1.100000010988609489e+01,1.947615610573491703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096220893938959762e+01,6.113326545140363351e+02,3.846601656656845614e-01,1.100000010988609489e+01,1.947469625171953985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096311803028960696e+01,6.113426544950731341e+02,3.846796403496262062e-01,1.100000010988609489e+01,1.947323639770416268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096402712118961631e+01,6.113526544761127752e+02,3.846991135737166112e-01,1.100000010988609489e+01,1.947177654368878550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096493621208962566e+01,6.113626544571552586e+02,3.847185853379557763e-01,1.100000010988609489e+01,1.947031668967340833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096584530298963500e+01,6.113726544382005841e+02,3.847380556423437015e-01,1.100000010988609489e+01,1.946885683565803115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096675439388964435e+01,6.113826544192487518e+02,3.847575244868803312e-01,1.100000010988609489e+01,1.946739698164265397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096766348478965369e+01,6.113926544002997616e+02,3.847769918715657211e-01,1.100000010988609489e+01,1.946593712762727680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096857257568966304e+01,6.114026543813536136e+02,3.847964577963998711e-01,1.100000010988609489e+01,1.946447727361189962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.096948166658967239e+01,6.114126543624103078e+02,3.848159222613827812e-01,1.100000010988609489e+01,1.946301741959652245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097039075748968173e+01,6.114226543434698442e+02,3.848353852665144514e-01,1.100000010988609489e+01,1.946155756558114527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097129984838969108e+01,6.114326543245322227e+02,3.848548468117948818e-01,1.100000010988609489e+01,1.946009771156576810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097220893928970042e+01,6.114426543055974435e+02,3.848743068972240167e-01,1.100000010988609489e+01,1.945863785755039092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097311803018970977e+01,6.114526542866655063e+02,3.848937655228019117e-01,1.100000010988609489e+01,1.945717800353501375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097402712108971912e+01,6.114626542677364114e+02,3.849132226885285668e-01,1.100000010988609489e+01,1.945571814951963657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097493621198972846e+01,6.114726542488101586e+02,3.849326783944039820e-01,1.100000010988609489e+01,1.945425829550425940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097584530288973781e+01,6.114826542298867480e+02,3.849521326404281019e-01,1.100000010988609489e+01,1.945279844148888222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097675439378974716e+01,6.114926542109661796e+02,3.849715854266009818e-01,1.100000010988609489e+01,1.945133858747350505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097766348468975650e+01,6.115026541920484533e+02,3.849910367529226218e-01,1.100000010988609489e+01,1.944987873345812787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097857257558976585e+01,6.115126541731335692e+02,3.850104866193930220e-01,1.100000010988609489e+01,1.944841887944275070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.097948166648977519e+01,6.115226541542215273e+02,3.850299350260121267e-01,1.100000010988609489e+01,1.944695902542737352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098039075738978454e+01,6.115326541353123275e+02,3.850493819727799916e-01,1.100000010988609489e+01,1.944549917141199635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098129984828979389e+01,6.115426541164059699e+02,3.850688274596966165e-01,1.100000010988609489e+01,1.944403931739661917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098220893918980323e+01,6.115526540975024545e+02,3.850882714867620016e-01,1.100000010988609489e+01,1.944257946338124200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098311803008981258e+01,6.115626540786017813e+02,3.851077140539760912e-01,1.100000010988609489e+01,1.944111960936586482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098402712098982192e+01,6.115726540597039502e+02,3.851271551613389410e-01,1.100000010988609489e+01,1.943965975535048765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098493621188983127e+01,6.115826540408089613e+02,3.851465948088505509e-01,1.100000010988609489e+01,1.943819990133511047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098584530278984062e+01,6.115926540219168146e+02,3.851660329965108653e-01,1.100000010988609489e+01,1.943674004731973329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098675439368984996e+01,6.116026540030275100e+02,3.851854697243199399e-01,1.100000010988609489e+01,1.943528019330435612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098766348458985931e+01,6.116126539841410477e+02,3.852049049922777746e-01,1.100000010988609489e+01,1.943382033928897894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098857257548986865e+01,6.116226539652574274e+02,3.852243388003843139e-01,1.100000010988609489e+01,1.943236048527360177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.098948166638987800e+01,6.116326539463766494e+02,3.852437711486396132e-01,1.100000010988609489e+01,1.943090063125822459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099039075728988735e+01,6.116426539274987135e+02,3.852632020370436727e-01,1.100000010988609489e+01,1.942944077724284742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099129984818989669e+01,6.116526539086235061e+02,3.852826314655964368e-01,1.100000010988609489e+01,1.942798092322747024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099220893908990604e+01,6.116626538897511409e+02,3.853020594342979610e-01,1.100000010988609489e+01,1.942652106921209307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099311802998991539e+01,6.116726538708816179e+02,3.853214859431482453e-01,1.100000010988609489e+01,1.942506121519671589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099402712088992473e+01,6.116826538520149370e+02,3.853409109921472342e-01,1.100000010988609489e+01,1.942360136118133872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099493621178993408e+01,6.116926538331510983e+02,3.853603345812949832e-01,1.100000010988609489e+01,1.942214150716596154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099584530268994342e+01,6.117026538142901018e+02,3.853797567105914923e-01,1.100000010988609489e+01,1.942068165315058437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099675439358995277e+01,6.117126537954319474e+02,3.853991773800367060e-01,1.100000010988609489e+01,1.941922179913520719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099766348448996212e+01,6.117226537765766352e+02,3.854185965896306798e-01,1.100000010988609489e+01,1.941776194511983002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099857257538997146e+01,6.117326537577241652e+02,3.854380143393733582e-01,1.100000010988609489e+01,1.941630209110445284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.099948166628998081e+01,6.117426537388745373e+02,3.854574306292647967e-01,1.100000010988609489e+01,1.941484223708907567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100039075718999015e+01,6.117526537200277517e+02,3.854768454593049398e-01,1.100000010988609489e+01,1.941338238307369849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100129984808999950e+01,6.117626537011838082e+02,3.854962588294938430e-01,1.100000010988609489e+01,1.941192252905832132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100220893899000885e+01,6.117726536823427068e+02,3.855156707398315064e-01,1.100000010988609489e+01,1.941046267504294414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100311802989001819e+01,6.117826536635044476e+02,3.855350811903178743e-01,1.100000010988609489e+01,1.940900282102756697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100402712079002754e+01,6.117926536446690307e+02,3.855544901809530023e-01,1.100000010988609489e+01,1.940754296701218979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100493621169003688e+01,6.118026536258364558e+02,3.855738977117368349e-01,1.100000010988609489e+01,1.940608311299681261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100584530259004623e+01,6.118126536070066095e+02,3.855933037826694276e-01,1.100000010988609489e+01,1.940462325898143544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100675439349005558e+01,6.118226535881796053e+02,3.856127083937507249e-01,1.100000010988609489e+01,1.940316340496605826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100766348439006492e+01,6.118326535693554433e+02,3.856321115449807824e-01,1.100000010988609489e+01,1.940170355095068109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100857257529007427e+01,6.118426535505341235e+02,3.856515132363595444e-01,1.100000010988609489e+01,1.940024369693530391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.100948166619008362e+01,6.118526535317156458e+02,3.856709134678870665e-01,1.100000010988609489e+01,1.939878384291992674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101039075709009296e+01,6.118626535129000104e+02,3.856903122395632932e-01,1.100000010988609489e+01,1.939732398890454956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101129984799010231e+01,6.118726534940872170e+02,3.857097095513882801e-01,1.100000010988609489e+01,1.939586413488917239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101220893889011165e+01,6.118826534752772659e+02,3.857291054033619715e-01,1.100000010988609489e+01,1.939440428087379521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101311802979012100e+01,6.118926534564701569e+02,3.857484997954844230e-01,1.100000010988609489e+01,1.939294442685841804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101402712069013035e+01,6.119026534376658901e+02,3.857678927277555792e-01,1.100000010988609489e+01,1.939148457284304086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101493621159013969e+01,6.119126534188644655e+02,3.857872842001754954e-01,1.100000010988609489e+01,1.939002471882766369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101584530249014904e+01,6.119226534000657693e+02,3.858066742127441162e-01,1.100000010988609489e+01,1.938856486481228651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101675439339015838e+01,6.119326533812699154e+02,3.858260627654614416e-01,1.100000010988609489e+01,1.938710501079690934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101766348429016773e+01,6.119426533624769036e+02,3.858454498583275272e-01,1.100000010988609489e+01,1.938564515678153216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101857257519017708e+01,6.119526533436867339e+02,3.858648354913423173e-01,1.100000010988609489e+01,1.938418530276615499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.101948166609018642e+01,6.119626533248994065e+02,3.858842196645058675e-01,1.100000010988609489e+01,1.938272544875077781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102039075699019577e+01,6.119726533061149212e+02,3.859036023778181224e-01,1.100000010988609489e+01,1.938126559473540064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102129984789020511e+01,6.119826532873332781e+02,3.859229836312790818e-01,1.100000010988609489e+01,1.937980574072002346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102220893879021446e+01,6.119926532685544771e+02,3.859423634248888013e-01,1.100000010988609489e+01,1.937834588670464629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102311802969022381e+01,6.120026532497785183e+02,3.859617417586472254e-01,1.100000010988609489e+01,1.937688603268926911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102402712059023315e+01,6.120126532310052880e+02,3.859811186325544097e-01,1.100000010988609489e+01,1.937542617867389193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102493621149024250e+01,6.120226532122348999e+02,3.860004940466102985e-01,1.100000010988609489e+01,1.937396632465851476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102584530239025185e+01,6.120326531934673540e+02,3.860198680008148919e-01,1.100000010988609489e+01,1.937250647064313758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102675439329026119e+01,6.120426531747026502e+02,3.860392404951682455e-01,1.100000010988609489e+01,1.937104661662776041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102766348419027054e+01,6.120526531559407886e+02,3.860586115296703036e-01,1.100000010988609489e+01,1.936958676261238323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102857257509027988e+01,6.120626531371817691e+02,3.860779811043210663e-01,1.100000010988609489e+01,1.936812690859700606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.102948166599028923e+01,6.120726531184255919e+02,3.860973492191205891e-01,1.100000010988609489e+01,1.936666705458162888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103039075689029858e+01,6.120826530996722568e+02,3.861167158740688166e-01,1.100000010988609489e+01,1.936520720056625171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103129984779030792e+01,6.120926530809216501e+02,3.861360810691657486e-01,1.100000010988609489e+01,1.936374734655087453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103220893869031727e+01,6.121026530621738857e+02,3.861554448044114407e-01,1.100000010988609489e+01,1.936228749253549736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103311802959032661e+01,6.121126530434289634e+02,3.861748070798058374e-01,1.100000010988609489e+01,1.936082763852012018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103402712049033596e+01,6.121226530246868833e+02,3.861941678953489387e-01,1.100000010988609489e+01,1.935936778450474301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103493621139034531e+01,6.121326530059476454e+02,3.862135272510408002e-01,1.100000010988609489e+01,1.935790793048936583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103584530229035465e+01,6.121426529872112496e+02,3.862328851468813662e-01,1.100000010988609489e+01,1.935644807647398866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103675439319036400e+01,6.121526529684776960e+02,3.862522415828706368e-01,1.100000010988609489e+01,1.935498822245861148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103766348409037334e+01,6.121626529497468709e+02,3.862715965590086120e-01,1.100000010988609489e+01,1.935352836844323431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103857257499038269e+01,6.121726529310188880e+02,3.862909500752953473e-01,1.100000010988609489e+01,1.935206851442785713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.103948166589039204e+01,6.121826529122937472e+02,3.863103021317307872e-01,1.100000010988609489e+01,1.935060866041247996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104039075679040138e+01,6.121926528935714487e+02,3.863296527283149318e-01,1.100000010988609489e+01,1.934914880639710278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104129984769041073e+01,6.122026528748519922e+02,3.863490018650477809e-01,1.100000010988609489e+01,1.934768895238172561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104220893859042008e+01,6.122126528561353780e+02,3.863683495419293901e-01,1.100000010988609489e+01,1.934622909836634843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104311802949042942e+01,6.122226528374216059e+02,3.863876957589597039e-01,1.100000010988609489e+01,1.934476924435097125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104402712039043877e+01,6.122326528187105623e+02,3.864070405161387223e-01,1.100000010988609489e+01,1.934330939033559408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104493621129044811e+01,6.122426528000023609e+02,3.864263838134664453e-01,1.100000010988609489e+01,1.934184953632021690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104584530219045746e+01,6.122526527812970016e+02,3.864457256509428729e-01,1.100000010988609489e+01,1.934038968230483973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104675439309046681e+01,6.122626527625944846e+02,3.864650660285680606e-01,1.100000010988609489e+01,1.933892982828946255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104766348399047615e+01,6.122726527438948096e+02,3.864844049463419529e-01,1.100000010988609489e+01,1.933746997427408538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104857257489048550e+01,6.122826527251979769e+02,3.865037424042645497e-01,1.100000010988609489e+01,1.933601012025870820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.104948166579049484e+01,6.122926527065038727e+02,3.865230784023358512e-01,1.100000010988609489e+01,1.933455026624333103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105039075669050419e+01,6.123026526878126106e+02,3.865424129405558573e-01,1.100000010988609489e+01,1.933309041222795385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105129984759051354e+01,6.123126526691241907e+02,3.865617460189245680e-01,1.100000010988609489e+01,1.933163055821257668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105220893849052288e+01,6.123226526504386129e+02,3.865810776374420388e-01,1.100000010988609489e+01,1.933017070419719950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105311802939053223e+01,6.123326526317558773e+02,3.866004077961082142e-01,1.100000010988609489e+01,1.932871085018182233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105402712029054157e+01,6.123426526130759839e+02,3.866197364949230941e-01,1.100000010988609489e+01,1.932725099616644515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105493621119055092e+01,6.123526525943988190e+02,3.866390637338866787e-01,1.100000010988609489e+01,1.932579114215106798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105584530209056027e+01,6.123626525757244963e+02,3.866583895129989679e-01,1.100000010988609489e+01,1.932433128813569080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105675439299056961e+01,6.123726525570530157e+02,3.866777138322599616e-01,1.100000010988609489e+01,1.932287143412031363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105766348389057896e+01,6.123826525383843773e+02,3.866970366916696600e-01,1.100000010988609489e+01,1.932141158010493645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105857257479058831e+01,6.123926525197185811e+02,3.867163580912280629e-01,1.100000010988609489e+01,1.931995172608955928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.105948166569059765e+01,6.124026525010555133e+02,3.867356780309351705e-01,1.100000010988609489e+01,1.931849187207418210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106039075659060700e+01,6.124126524823952877e+02,3.867549965107910381e-01,1.100000010988609489e+01,1.931703201805880492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106129984749061634e+01,6.124226524637379043e+02,3.867743135307956104e-01,1.100000010988609489e+01,1.931557216404342775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106220893839062569e+01,6.124326524450833631e+02,3.867936290909488872e-01,1.100000010988609489e+01,1.931411231002805057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106311802929063504e+01,6.124426524264316640e+02,3.868129431912508687e-01,1.100000010988609489e+01,1.931265245601267340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106402712019064438e+01,6.124526524077826934e+02,3.868322558317015547e-01,1.100000010988609489e+01,1.931119260199729622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106493621109065373e+01,6.124626523891365650e+02,3.868515670123009453e-01,1.100000010988609489e+01,1.930973274798191905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106584530199066307e+01,6.124726523704932788e+02,3.868708767330490406e-01,1.100000010988609489e+01,1.930827289396654187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106675439289067242e+01,6.124826523518528347e+02,3.868901849939458404e-01,1.100000010988609489e+01,1.930681303995116470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106766348379068177e+01,6.124926523332152328e+02,3.869094917949913448e-01,1.100000010988609489e+01,1.930535318593578752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106857257469069111e+01,6.125026523145803594e+02,3.869287971361855538e-01,1.100000010988609489e+01,1.930389333192041035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.106948166559070046e+01,6.125126522959483282e+02,3.869481010175284674e-01,1.100000010988609489e+01,1.930243347790503317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107039075649070980e+01,6.125226522773191391e+02,3.869674034390200856e-01,1.100000010988609489e+01,1.930097362388965600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107129984739071915e+01,6.125326522586927922e+02,3.869867044006604084e-01,1.100000010988609489e+01,1.929951376987427882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107220893829072850e+01,6.125426522400692875e+02,3.870060039024494358e-01,1.100000010988609489e+01,1.929805391585890165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107311802919073784e+01,6.125526522214485112e+02,3.870253019443871678e-01,1.100000010988609489e+01,1.929659406184352447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107402712009074719e+01,6.125626522028305772e+02,3.870445985264736044e-01,1.100000010988609489e+01,1.929513420782814730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107493621099075654e+01,6.125726521842154852e+02,3.870638936487087456e-01,1.100000010988609489e+01,1.929367435381277012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107584530189076588e+01,6.125826521656032355e+02,3.870831873110925914e-01,1.100000010988609489e+01,1.929221449979739295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107675439279077523e+01,6.125926521469937143e+02,3.871024795136251417e-01,1.100000010988609489e+01,1.929075464578201577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107766348369078457e+01,6.126026521283870352e+02,3.871217702563063967e-01,1.100000010988609489e+01,1.928929479176663860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107857257459079392e+01,6.126126521097831983e+02,3.871410595391363563e-01,1.100000010988609489e+01,1.928783493775126142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.107948166549080327e+01,6.126226520911822035e+02,3.871603473621149649e-01,1.100000010988609489e+01,1.928637508373588424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108039075639081261e+01,6.126326520725840510e+02,3.871796337252422782e-01,1.100000010988609489e+01,1.928491522972050707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108129984729082196e+01,6.126426520539886269e+02,3.871989186285182960e-01,1.100000010988609489e+01,1.928345537570512989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108220893819083130e+01,6.126526520353960450e+02,3.872182020719430184e-01,1.100000010988609489e+01,1.928199552168975272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108311802909084065e+01,6.126626520168063053e+02,3.872374840555164455e-01,1.100000010988609489e+01,1.928053566767437554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108402711999085000e+01,6.126726519982194077e+02,3.872567645792385771e-01,1.100000010988609489e+01,1.927907581365899837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108493621089085934e+01,6.126826519796352386e+02,3.872760436431094133e-01,1.100000010988609489e+01,1.927761595964362119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108584530179086869e+01,6.126926519610539117e+02,3.872953212471289541e-01,1.100000010988609489e+01,1.927615610562824402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108675439269087803e+01,6.127026519424754269e+02,3.873145973912971995e-01,1.100000010988609489e+01,1.927469625161286684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108766348359088738e+01,6.127126519238997844e+02,3.873338720756140940e-01,1.100000010988609489e+01,1.927323639759748967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108857257449089673e+01,6.127226519053268703e+02,3.873531453000796931e-01,1.100000010988609489e+01,1.927177654358211249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.108948166539090607e+01,6.127326518867567984e+02,3.873724170646939968e-01,1.100000010988609489e+01,1.927031668956673532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109039075629091542e+01,6.127426518681895686e+02,3.873916873694570051e-01,1.100000010988609489e+01,1.926885683555135814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109129984719092477e+01,6.127526518496251811e+02,3.874109562143687180e-01,1.100000010988609489e+01,1.926739698153598097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109220893809093411e+01,6.127626518310635220e+02,3.874302235994291355e-01,1.100000010988609489e+01,1.926593712752060379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109311802899094346e+01,6.127726518125047050e+02,3.874494895246382020e-01,1.100000010988609489e+01,1.926447727350522662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109402711989095280e+01,6.127826517939487303e+02,3.874687539899959732e-01,1.100000010988609489e+01,1.926301741948984944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109493621079096215e+01,6.127926517753955977e+02,3.874880169955024489e-01,1.100000010988609489e+01,1.926155756547447227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109584530169097150e+01,6.128026517568451936e+02,3.875072785411576293e-01,1.100000010988609489e+01,1.926009771145909509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109675439259098084e+01,6.128126517382976317e+02,3.875265386269615142e-01,1.100000010988609489e+01,1.925863785744371792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109766348349099019e+01,6.128226517197529120e+02,3.875457972529140482e-01,1.100000010988609489e+01,1.925717800342834074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109857257439099953e+01,6.128326517012109207e+02,3.875650544190152869e-01,1.100000010988609489e+01,1.925571814941296356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.109948166529100888e+01,6.128426516826717716e+02,3.875843101252652301e-01,1.100000010988609489e+01,1.925425829539758639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110039075619101823e+01,6.128526516641354647e+02,3.876035643716638779e-01,1.100000010988609489e+01,1.925279844138220921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110129984709102757e+01,6.128626516456019999e+02,3.876228171582111748e-01,1.100000010988609489e+01,1.925133858736683204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110220893799103692e+01,6.128726516270712636e+02,3.876420684849071763e-01,1.100000010988609489e+01,1.924987873335145486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110311802889104627e+01,6.128826516085433695e+02,3.876613183517518824e-01,1.100000010988609489e+01,1.924841887933607769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110402711979105561e+01,6.128926515900183176e+02,3.876805667587452930e-01,1.100000010988609489e+01,1.924695902532070051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110493621069106496e+01,6.129026515714961079e+02,3.876998137058873528e-01,1.100000010988609489e+01,1.924549917130532334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110584530159107430e+01,6.129126515529766266e+02,3.877190591931781172e-01,1.100000010988609489e+01,1.924403931728994616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110675439249108365e+01,6.129226515344599875e+02,3.877383032206175861e-01,1.100000010988609489e+01,1.924257946327456899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110766348339109300e+01,6.129326515159461906e+02,3.877575457882057042e-01,1.100000010988609489e+01,1.924111960925919181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110857257429110234e+01,6.129426514974351221e+02,3.877767868959425268e-01,1.100000010988609489e+01,1.923965975524381464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.110948166519111169e+01,6.129526514789268958e+02,3.877960265438280540e-01,1.100000010988609489e+01,1.923819990122843746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111039075609112103e+01,6.129626514604215117e+02,3.878152647318622304e-01,1.100000010988609489e+01,1.923674004721306029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111129984699113038e+01,6.129726514419188561e+02,3.878345014600451113e-01,1.100000010988609489e+01,1.923528019319768311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111220893789113973e+01,6.129826514234190427e+02,3.878537367283766968e-01,1.100000010988609489e+01,1.923382033918230594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111311802879114907e+01,6.129926514049220714e+02,3.878729705368569314e-01,1.100000010988609489e+01,1.923236048516692876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111402711969115842e+01,6.130026513864279423e+02,3.878922028854858706e-01,1.100000010988609489e+01,1.923090063115155159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111493621059116776e+01,6.130126513679365416e+02,3.879114337742635144e-01,1.100000010988609489e+01,1.922944077713617441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111584530149117711e+01,6.130226513494479832e+02,3.879306632031898072e-01,1.100000010988609489e+01,1.922798092312079724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111675439239118646e+01,6.130326513309622669e+02,3.879498911722648047e-01,1.100000010988609489e+01,1.922652106910542006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111766348329119580e+01,6.130426513124792791e+02,3.879691176814885067e-01,1.100000010988609489e+01,1.922506121509004288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111857257419120515e+01,6.130526512939991335e+02,3.879883427308608579e-01,1.100000010988609489e+01,1.922360136107466571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.111948166509121450e+01,6.130626512755218300e+02,3.880075663203819136e-01,1.100000010988609489e+01,1.922214150705928853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112039075599122384e+01,6.130726512570472551e+02,3.880267884500516185e-01,1.100000010988609489e+01,1.922068165304391136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112129984689123319e+01,6.130826512385755223e+02,3.880460091198700279e-01,1.100000010988609489e+01,1.921922179902853418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112220893779124253e+01,6.130926512201066316e+02,3.880652283298370864e-01,1.100000010988609489e+01,1.921776194501315701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112311802869125188e+01,6.131026512016404695e+02,3.880844460799528495e-01,1.100000010988609489e+01,1.921630209099777983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112402711959126123e+01,6.131126511831771495e+02,3.881036623702173172e-01,1.100000010988609489e+01,1.921484223698240266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112493621049127057e+01,6.131226511647166717e+02,3.881228772006304339e-01,1.100000010988609489e+01,1.921338238296702548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112584530139127992e+01,6.131326511462589224e+02,3.881420905711922553e-01,1.100000010988609489e+01,1.921192252895164831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112675439229128926e+01,6.131426511278040152e+02,3.881613024819027258e-01,1.100000010988609489e+01,1.921046267493627113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112766348319129861e+01,6.131526511093519503e+02,3.881805129327619008e-01,1.100000010988609489e+01,1.920900282092089396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112857257409130796e+01,6.131626510909026138e+02,3.881997219237697250e-01,1.100000010988609489e+01,1.920754296690551678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.112948166499131730e+01,6.131726510724561194e+02,3.882189294549262537e-01,1.100000010988609489e+01,1.920608311289013961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113039075589132665e+01,6.131826510540124673e+02,3.882381355262314315e-01,1.100000010988609489e+01,1.920462325887476243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113129984679133599e+01,6.131926510355715436e+02,3.882573401376853139e-01,1.100000010988609489e+01,1.920316340485938526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113220893769134534e+01,6.132026510171334621e+02,3.882765432892878454e-01,1.100000010988609489e+01,1.920170355084400808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113311802859135469e+01,6.132126509986982228e+02,3.882957449810390815e-01,1.100000010988609489e+01,1.920024369682863091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113402711949136403e+01,6.132226509802657120e+02,3.883149452129389667e-01,1.100000010988609489e+01,1.919878384281325373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113493621039137338e+01,6.132326509618360433e+02,3.883341439849875565e-01,1.100000010988609489e+01,1.919732398879787656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113584530129138273e+01,6.132426509434092168e+02,3.883533412971847953e-01,1.100000010988609489e+01,1.919586413478249938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113675439219139207e+01,6.132526509249851188e+02,3.883725371495307388e-01,1.100000010988609489e+01,1.919440428076712220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113766348309140142e+01,6.132626509065638629e+02,3.883917315420253313e-01,1.100000010988609489e+01,1.919294442675174503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113857257399141076e+01,6.132726508881454492e+02,3.884109244746686285e-01,1.100000010988609489e+01,1.919148457273636785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.113948166489142011e+01,6.132826508697297641e+02,3.884301159474605747e-01,1.100000010988609489e+01,1.919002471872099068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114039075579142946e+01,6.132926508513169210e+02,3.884493059604011700e-01,1.100000010988609489e+01,1.918856486470561350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114129984669143880e+01,6.133026508329069202e+02,3.884684945134904699e-01,1.100000010988609489e+01,1.918710501069023633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114220893759144815e+01,6.133126508144996478e+02,3.884876816067284189e-01,1.100000010988609489e+01,1.918564515667485915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114311802849145749e+01,6.133226507960952176e+02,3.885068672401150724e-01,1.100000010988609489e+01,1.918418530265948198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114402711939146684e+01,6.133326507776936296e+02,3.885260514136503751e-01,1.100000010988609489e+01,1.918272544864410480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114493621029147619e+01,6.133426507592947701e+02,3.885452341273343269e-01,1.100000010988609489e+01,1.918126559462872763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114584530119148553e+01,6.133526507408987527e+02,3.885644153811669832e-01,1.100000010988609489e+01,1.917980574061335045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114675439209149488e+01,6.133626507225054638e+02,3.885835951751482886e-01,1.100000010988609489e+01,1.917834588659797328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114766348299150422e+01,6.133726507041150171e+02,3.886027735092782986e-01,1.100000010988609489e+01,1.917688603258259610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114857257389151357e+01,6.133826506857274126e+02,3.886219503835569578e-01,1.100000010988609489e+01,1.917542617856721893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.114948166479152292e+01,6.133926506673425365e+02,3.886411257979842659e-01,1.100000010988609489e+01,1.917396632455184175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115039075569153226e+01,6.134026506489605026e+02,3.886602997525602787e-01,1.100000010988609489e+01,1.917250647053646458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115129984659154161e+01,6.134126506305813109e+02,3.886794722472849406e-01,1.100000010988609489e+01,1.917104661652108740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115220893749155096e+01,6.134226506122048477e+02,3.886986432821582516e-01,1.100000010988609489e+01,1.916958676250571023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115311802839156030e+01,6.134326505938312266e+02,3.887178128571802671e-01,1.100000010988609489e+01,1.916812690849033305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115402711929156965e+01,6.134426505754603340e+02,3.887369809723509317e-01,1.100000010988609489e+01,1.916666705447495588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115493621019157899e+01,6.134526505570922836e+02,3.887561476276702455e-01,1.100000010988609489e+01,1.916520720045957870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115584530109158834e+01,6.134626505387270754e+02,3.887753128231382638e-01,1.100000010988609489e+01,1.916374734644420152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115675439199159769e+01,6.134726505203645956e+02,3.887944765587549312e-01,1.100000010988609489e+01,1.916228749242882435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115766348289160703e+01,6.134826505020049581e+02,3.888136388345202477e-01,1.100000010988609489e+01,1.916082763841344717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115857257379161638e+01,6.134926504836480490e+02,3.888327996504342132e-01,1.100000010988609489e+01,1.915936778439807000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.115948166469162572e+01,6.135026504652939821e+02,3.888519590064968834e-01,1.100000010988609489e+01,1.915790793038269282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116039075559163507e+01,6.135126504469427573e+02,3.888711169027082026e-01,1.100000010988609489e+01,1.915644807636731565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116129984649164442e+01,6.135226504285942610e+02,3.888902733390681710e-01,1.100000010988609489e+01,1.915498822235193847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116220893739165376e+01,6.135326504102486069e+02,3.889094283155768439e-01,1.100000010988609489e+01,1.915352836833656130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116311802829166311e+01,6.135426503919056813e+02,3.889285818322341659e-01,1.100000010988609489e+01,1.915206851432118412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116402711919167245e+01,6.135526503735655979e+02,3.889477338890401370e-01,1.100000010988609489e+01,1.915060866030580695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116493621009168180e+01,6.135626503552283566e+02,3.889668844859947572e-01,1.100000010988609489e+01,1.914914880629042977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116584530099169115e+01,6.135726503368938438e+02,3.889860336230980264e-01,1.100000010988609489e+01,1.914768895227505260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116675439189170049e+01,6.135826503185621732e+02,3.890051813003500003e-01,1.100000010988609489e+01,1.914622909825967542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116766348279170984e+01,6.135926503002332311e+02,3.890243275177506233e-01,1.100000010988609489e+01,1.914476924424429825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116857257369171919e+01,6.136026502819071311e+02,3.890434722752998953e-01,1.100000010988609489e+01,1.914330939022892107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.116948166459172853e+01,6.136126502635838733e+02,3.890626155729978164e-01,1.100000010988609489e+01,1.914184953621354390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117039075549173788e+01,6.136226502452633440e+02,3.890817574108443866e-01,1.100000010988609489e+01,1.914038968219816672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117129984639174722e+01,6.136326502269456569e+02,3.891008977888396614e-01,1.100000010988609489e+01,1.913892982818278955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117220893729175657e+01,6.136426502086306982e+02,3.891200367069835853e-01,1.100000010988609489e+01,1.913746997416741237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117311802819176592e+01,6.136526501903185817e+02,3.891391741652761582e-01,1.100000010988609489e+01,1.913601012015203520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117402711909177526e+01,6.136626501720091937e+02,3.891583101637173803e-01,1.100000010988609489e+01,1.913455026613665802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117493620999178461e+01,6.136726501537026479e+02,3.891774447023072514e-01,1.100000010988609489e+01,1.913309041212128084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117584530089179395e+01,6.136826501353989443e+02,3.891965777810457716e-01,1.100000010988609489e+01,1.913163055810590367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117675439179180330e+01,6.136926501170979691e+02,3.892157093999329964e-01,1.100000010988609489e+01,1.913017070409052649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117766348269181265e+01,6.137026500987998361e+02,3.892348395589688703e-01,1.100000010988609489e+01,1.912871085007514932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117857257359182199e+01,6.137126500805044316e+02,3.892539682581533933e-01,1.100000010988609489e+01,1.912725099605977214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.117948166449183134e+01,6.137226500622118692e+02,3.892730954974865654e-01,1.100000010988609489e+01,1.912579114204439497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118039075539184068e+01,6.137326500439220354e+02,3.892922212769683865e-01,1.100000010988609489e+01,1.912433128802901779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118129984629185003e+01,6.137426500256350437e+02,3.893113455965988567e-01,1.100000010988609489e+01,1.912287143401364062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118220893719185938e+01,6.137526500073508942e+02,3.893304684563779761e-01,1.100000010988609489e+01,1.912141157999826344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118311802809186872e+01,6.137626499890694731e+02,3.893495898563057445e-01,1.100000010988609489e+01,1.911995172598288627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118402711899187807e+01,6.137726499707908943e+02,3.893687097963821619e-01,1.100000010988609489e+01,1.911849187196750909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118493620989188742e+01,6.137826499525150439e+02,3.893878282766072285e-01,1.100000010988609489e+01,1.911703201795213192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118584530079189676e+01,6.137926499342420357e+02,3.894069452969809442e-01,1.100000010988609489e+01,1.911557216393675474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118675439169190611e+01,6.138026499159717559e+02,3.894260608575033644e-01,1.100000010988609489e+01,1.911411230992137757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118766348259191545e+01,6.138126498977043184e+02,3.894451749581744338e-01,1.100000010988609489e+01,1.911265245590600039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118857257349192480e+01,6.138226498794396093e+02,3.894642875989941522e-01,1.100000010988609489e+01,1.911119260189062322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.118948166439193415e+01,6.138326498611777424e+02,3.894833987799625197e-01,1.100000010988609489e+01,1.910973274787524604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119039075529194349e+01,6.138426498429186040e+02,3.895025085010795363e-01,1.100000010988609489e+01,1.910827289385986887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119129984619195284e+01,6.138526498246623078e+02,3.895216167623452019e-01,1.100000010988609489e+01,1.910681303984449169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119220893709196218e+01,6.138626498064088537e+02,3.895407235637595167e-01,1.100000010988609489e+01,1.910535318582911452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119311802799197153e+01,6.138726497881581281e+02,3.895598289053224805e-01,1.100000010988609489e+01,1.910389333181373734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119402711889198088e+01,6.138826497699102447e+02,3.895789327870340935e-01,1.100000010988609489e+01,1.910243347779836016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119493620979199022e+01,6.138926497516650898e+02,3.895980352088943555e-01,1.100000010988609489e+01,1.910097362378298299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119584530069199957e+01,6.139026497334227770e+02,3.896171361709032666e-01,1.100000010988609489e+01,1.909951376976760581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119675439159200891e+01,6.139126497151831927e+02,3.896362356730608267e-01,1.100000010988609489e+01,1.909805391575222864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119766348249201826e+01,6.139226496969464506e+02,3.896553337153670360e-01,1.100000010988609489e+01,1.909659406173685146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119857257339202761e+01,6.139326496787124370e+02,3.896744302978218943e-01,1.100000010988609489e+01,1.909513420772147429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.119948166429203695e+01,6.139426496604812655e+02,3.896935254204253463e-01,1.100000010988609489e+01,1.909367435370609711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120039075519204630e+01,6.139526496422528226e+02,3.897126190831774473e-01,1.100000010988609489e+01,1.909221449969071994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120129984609205565e+01,6.139626496240272218e+02,3.897317112860781974e-01,1.100000010988609489e+01,1.909075464567534276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120220893699206499e+01,6.139726496058043494e+02,3.897508020291275965e-01,1.100000010988609489e+01,1.908929479165996559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120311802789207434e+01,6.139826495875843193e+02,3.897698913123256448e-01,1.100000010988609489e+01,1.908783493764458841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120402711879208368e+01,6.139926495693670176e+02,3.897889791356723421e-01,1.100000010988609489e+01,1.908637508362921124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120493620969209303e+01,6.140026495511525582e+02,3.898080654991676886e-01,1.100000010988609489e+01,1.908491522961383406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120584530059210238e+01,6.140126495329408272e+02,3.898271504028116841e-01,1.100000010988609489e+01,1.908345537559845689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120675439149211172e+01,6.140226495147319383e+02,3.898462338466043287e-01,1.100000010988609489e+01,1.908199552158307971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120766348239212107e+01,6.140326494965257780e+02,3.898653158305456223e-01,1.100000010988609489e+01,1.908053566756770254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120857257329213041e+01,6.140426494783224598e+02,3.898843963546355651e-01,1.100000010988609489e+01,1.907907581355232536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.120948166419213976e+01,6.140526494601218701e+02,3.899034754188741014e-01,1.100000010988609489e+01,1.907761595953694819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121039075509214911e+01,6.140626494419241226e+02,3.899225530232612869e-01,1.100000010988609489e+01,1.907615610552157101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121129984599215845e+01,6.140726494237291035e+02,3.899416291677971214e-01,1.100000010988609489e+01,1.907469625150619384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121220893689216780e+01,6.140826494055369267e+02,3.899607038524816049e-01,1.100000010988609489e+01,1.907323639749081666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121311802779217714e+01,6.140926493873474783e+02,3.899797770773147376e-01,1.100000010988609489e+01,1.907177654347543948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121402711869218649e+01,6.141026493691608721e+02,3.899988488422965194e-01,1.100000010988609489e+01,1.907031668946006231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121493620959219584e+01,6.141126493509769944e+02,3.900179191474269502e-01,1.100000010988609489e+01,1.906885683544468513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121584530049220518e+01,6.141226493327959588e+02,3.900369879927059746e-01,1.100000010988609489e+01,1.906739698142930796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121675439139221453e+01,6.141326493146176517e+02,3.900560553781336481e-01,1.100000010988609489e+01,1.906593712741393078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121766348229222388e+01,6.141426492964421868e+02,3.900751213037099707e-01,1.100000010988609489e+01,1.906447727339855361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121857257319223322e+01,6.141526492782694504e+02,3.900941857694349424e-01,1.100000010988609489e+01,1.906301741938317643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.121948166409224257e+01,6.141626492600995562e+02,3.901132487753085631e-01,1.100000010988609489e+01,1.906155756536779926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122039075499225191e+01,6.141726492419323904e+02,3.901323103213307775e-01,1.100000010988609489e+01,1.906009771135242208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122129984589226126e+01,6.141826492237680668e+02,3.901513704075016409e-01,1.100000010988609489e+01,1.905863785733704491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122220893679227061e+01,6.141926492056064717e+02,3.901704290338211534e-01,1.100000010988609489e+01,1.905717800332166773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122311802769227995e+01,6.142026491874477188e+02,3.901894862002893150e-01,1.100000010988609489e+01,1.905571814930629056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122402711859228930e+01,6.142126491692916943e+02,3.902085419069060701e-01,1.100000010988609489e+01,1.905425829529091338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122493620949229864e+01,6.142226491511385120e+02,3.902275961536714743e-01,1.100000010988609489e+01,1.905279844127553621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122584530039230799e+01,6.142326491329880582e+02,3.902466489405855277e-01,1.100000010988609489e+01,1.905133858726015903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122675439129231734e+01,6.142426491148403329e+02,3.902657002676482301e-01,1.100000010988609489e+01,1.904987873324478186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122766348219232668e+01,6.142526490966954498e+02,3.902847501348595260e-01,1.100000010988609489e+01,1.904841887922940468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122857257309233603e+01,6.142626490785532951e+02,3.903037985422194711e-01,1.100000010988609489e+01,1.904695902521402751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.122948166399234537e+01,6.142726490604139826e+02,3.903228454897280653e-01,1.100000010988609489e+01,1.904549917119865033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123039075489235472e+01,6.142826490422773986e+02,3.903418909773852530e-01,1.100000010988609489e+01,1.904403931718327316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123129984579236407e+01,6.142926490241436568e+02,3.903609350051910898e-01,1.100000010988609489e+01,1.904257946316789598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123220893669237341e+01,6.143026490060126434e+02,3.903799775731455757e-01,1.100000010988609489e+01,1.904111960915251880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123311802759238276e+01,6.143126489878844723e+02,3.903990186812486551e-01,1.100000010988609489e+01,1.903965975513714163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123402711849239211e+01,6.143226489697590296e+02,3.904180583295003837e-01,1.100000010988609489e+01,1.903819990112176445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123493620939240145e+01,6.143326489516364290e+02,3.904370965179007613e-01,1.100000010988609489e+01,1.903674004710638728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123584530029241080e+01,6.143426489335165570e+02,3.904561332464497325e-01,1.100000010988609489e+01,1.903528019309101010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123675439119242014e+01,6.143526489153994135e+02,3.904751685151473528e-01,1.100000010988609489e+01,1.903382033907563293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123766348209242949e+01,6.143626488972851121e+02,3.904942023239936222e-01,1.100000010988609489e+01,1.903236048506025575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123857257299243884e+01,6.143726488791735392e+02,3.905132346729884851e-01,1.100000010988609489e+01,1.903090063104487858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.123948166389244818e+01,6.143826488610648084e+02,3.905322655621319972e-01,1.100000010988609489e+01,1.902944077702950140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124039075479245753e+01,6.143926488429588062e+02,3.905512949914241583e-01,1.100000010988609489e+01,1.902798092301412423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124129984569246687e+01,6.144026488248556461e+02,3.905703229608649130e-01,1.100000010988609489e+01,1.902652106899874705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124220893659247622e+01,6.144126488067552145e+02,3.905893494704543167e-01,1.100000010988609489e+01,1.902506121498336988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124311802749248557e+01,6.144226487886576251e+02,3.906083745201923141e-01,1.100000010988609489e+01,1.902360136096799270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124402711839249491e+01,6.144326487705627642e+02,3.906273981100789605e-01,1.100000010988609489e+01,1.902214150695261553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124493620929250426e+01,6.144426487524706317e+02,3.906464202401142560e-01,1.100000010988609489e+01,1.902068165293723835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124584530019251360e+01,6.144526487343813415e+02,3.906654409102981451e-01,1.100000010988609489e+01,1.901922179892186118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124675439109252295e+01,6.144626487162947797e+02,3.906844601206306833e-01,1.100000010988609489e+01,1.901776194490648400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124766348199253230e+01,6.144726486982110600e+02,3.907034778711118150e-01,1.100000010988609489e+01,1.901630209089110683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124857257289254164e+01,6.144826486801300689e+02,3.907224941617415959e-01,1.100000010988609489e+01,1.901484223687572965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.124948166379255099e+01,6.144926486620518062e+02,3.907415089925199703e-01,1.100000010988609489e+01,1.901338238286035247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125039075469256034e+01,6.145026486439763858e+02,3.907605223634469938e-01,1.100000010988609489e+01,1.901192252884497530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125129984559256968e+01,6.145126486259036938e+02,3.907795342745226663e-01,1.100000010988609489e+01,1.901046267482959812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125220893649257903e+01,6.145226486078338439e+02,3.907985447257469325e-01,1.100000010988609489e+01,1.900900282081422095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125311802739258837e+01,6.145326485897667226e+02,3.908175537171198477e-01,1.100000010988609489e+01,1.900754296679884377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125402711829259772e+01,6.145426485717024434e+02,3.908365612486413565e-01,1.100000010988609489e+01,1.900608311278346660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125493620919260707e+01,6.145526485536408927e+02,3.908555673203115144e-01,1.100000010988609489e+01,1.900462325876808942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125584530009261641e+01,6.145626485355820705e+02,3.908745719321302658e-01,1.100000010988609489e+01,1.900316340475271225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125675439099262576e+01,6.145726485175260905e+02,3.908935750840976664e-01,1.100000010988609489e+01,1.900170355073733507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125766348189263510e+01,6.145826484994728389e+02,3.909125767762136605e-01,1.100000010988609489e+01,1.900024369672195790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125857257279264445e+01,6.145926484814224295e+02,3.909315770084783037e-01,1.100000010988609489e+01,1.899878384270658072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.125948166369265380e+01,6.146026484633747486e+02,3.909505757808915405e-01,1.100000010988609489e+01,1.899732398869120355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126039075459266314e+01,6.146126484453297962e+02,3.909695730934533708e-01,1.100000010988609489e+01,1.899586413467582637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126129984549267249e+01,6.146226484272876860e+02,3.909885689461638503e-01,1.100000010988609489e+01,1.899440428066044920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126220893639268184e+01,6.146326484092483042e+02,3.910075633390229233e-01,1.100000010988609489e+01,1.899294442664507202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126311802729269118e+01,6.146426483912117646e+02,3.910265562720306454e-01,1.100000010988609489e+01,1.899148457262969485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126402711819270053e+01,6.146526483731779535e+02,3.910455477451869610e-01,1.100000010988609489e+01,1.899002471861431767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126493620909270987e+01,6.146626483551468709e+02,3.910645377584919258e-01,1.100000010988609489e+01,1.898856486459894050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126584529999271922e+01,6.146726483371186305e+02,3.910835263119454841e-01,1.100000010988609489e+01,1.898710501058356332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126675439089272857e+01,6.146826483190931185e+02,3.911025134055476360e-01,1.100000010988609489e+01,1.898564515656818615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126766348179273791e+01,6.146926483010703350e+02,3.911214990392984370e-01,1.100000010988609489e+01,1.898418530255280897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126857257269274726e+01,6.147026482830503937e+02,3.911404832131978315e-01,1.100000010988609489e+01,1.898272544853743179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.126948166359275660e+01,6.147126482650331809e+02,3.911594659272458752e-01,1.100000010988609489e+01,1.898126559452205462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127039075449276595e+01,6.147226482470188103e+02,3.911784471814425124e-01,1.100000010988609489e+01,1.897980574050667744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127129984539277530e+01,6.147326482290071681e+02,3.911974269757877432e-01,1.100000010988609489e+01,1.897834588649130027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127220893629278464e+01,6.147426482109982544e+02,3.912164053102816230e-01,1.100000010988609489e+01,1.897688603247592309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127311802719279399e+01,6.147526481929921829e+02,3.912353821849240965e-01,1.100000010988609489e+01,1.897542617846054592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127402711809280333e+01,6.147626481749888399e+02,3.912543575997151635e-01,1.100000010988609489e+01,1.897396632444516874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127493620899281268e+01,6.147726481569882253e+02,3.912733315546548796e-01,1.100000010988609489e+01,1.897250647042979157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127584529989282203e+01,6.147826481389904529e+02,3.912923040497431892e-01,1.100000010988609489e+01,1.897104661641441439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127675439079283137e+01,6.147926481209954090e+02,3.913112750849801480e-01,1.100000010988609489e+01,1.896958676239903722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127766348169284072e+01,6.148026481030032073e+02,3.913302446603657003e-01,1.100000010988609489e+01,1.896812690838366004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127857257259285007e+01,6.148126480850137341e+02,3.913492127758998462e-01,1.100000010988609489e+01,1.896666705436828287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.127948166349285941e+01,6.148226480670269893e+02,3.913681794315825857e-01,1.100000010988609489e+01,1.896520720035290569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128039075439286876e+01,6.148326480490430868e+02,3.913871446274139743e-01,1.100000010988609489e+01,1.896374734633752852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128129984529287810e+01,6.148426480310619127e+02,3.914061083633939564e-01,1.100000010988609489e+01,1.896228749232215134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128220893619288745e+01,6.148526480130834670e+02,3.914250706395225321e-01,1.100000010988609489e+01,1.896082763830677417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128311802709289680e+01,6.148626479951078636e+02,3.914440314557997569e-01,1.100000010988609489e+01,1.895936778429139699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128402711799290614e+01,6.148726479771349887e+02,3.914629908122255753e-01,1.100000010988609489e+01,1.895790793027601982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128493620889291549e+01,6.148826479591648422e+02,3.914819487087999872e-01,1.100000010988609489e+01,1.895644807626064264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128584529979292483e+01,6.148926479411975379e+02,3.915009051455229927e-01,1.100000010988609489e+01,1.895498822224526547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128675439069293418e+01,6.149026479232329621e+02,3.915198601223946473e-01,1.100000010988609489e+01,1.895352836822988829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128766348159294353e+01,6.149126479052711147e+02,3.915388136394148955e-01,1.100000010988609489e+01,1.895206851421451111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128857257249295287e+01,6.149226478873121096e+02,3.915577656965837372e-01,1.100000010988609489e+01,1.895060866019913394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.128948166339296222e+01,6.149326478693558329e+02,3.915767162939011725e-01,1.100000010988609489e+01,1.894914880618375676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129039075429297156e+01,6.149426478514022847e+02,3.915956654313672569e-01,1.100000010988609489e+01,1.894768895216837959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129129984519298091e+01,6.149526478334515787e+02,3.916146131089819349e-01,1.100000010988609489e+01,1.894622909815300241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129220893609299026e+01,6.149626478155036011e+02,3.916335593267452064e-01,1.100000010988609489e+01,1.894476924413762524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129311802699299960e+01,6.149726477975583521e+02,3.916525040846570715e-01,1.100000010988609489e+01,1.894330939012224806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129402711789300895e+01,6.149826477796159452e+02,3.916714473827175302e-01,1.100000010988609489e+01,1.894184953610687089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129493620879301830e+01,6.149926477616762668e+02,3.916903892209266380e-01,1.100000010988609489e+01,1.894038968209149371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129584529969302764e+01,6.150026477437393169e+02,3.917093295992843394e-01,1.100000010988609489e+01,1.893892982807611654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129675439059303699e+01,6.150126477258052091e+02,3.917282685177906343e-01,1.100000010988609489e+01,1.893746997406073936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129766348149304633e+01,6.150226477078738299e+02,3.917472059764455228e-01,1.100000010988609489e+01,1.893601012004536219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129857257239305568e+01,6.150326476899451791e+02,3.917661419752490048e-01,1.100000010988609489e+01,1.893455026602998501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.129948166329306503e+01,6.150426476720193705e+02,3.917850765142010805e-01,1.100000010988609489e+01,1.893309041201460784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130039075419307437e+01,6.150526476540962904e+02,3.918040095933017497e-01,1.100000010988609489e+01,1.893163055799923066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130129984509308372e+01,6.150626476361759387e+02,3.918229412125510680e-01,1.100000010988609489e+01,1.893017070398385349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130220893599309306e+01,6.150726476182584292e+02,3.918418713719489799e-01,1.100000010988609489e+01,1.892871084996847631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130311802689310241e+01,6.150826476003436483e+02,3.918608000714954853e-01,1.100000010988609489e+01,1.892725099595309914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130402711779311176e+01,6.150926475824315958e+02,3.918797273111905843e-01,1.100000010988609489e+01,1.892579114193772196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130493620869312110e+01,6.151026475645222718e+02,3.918986530910342769e-01,1.100000010988609489e+01,1.892433128792234479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130584529959313045e+01,6.151126475466157899e+02,3.919175774110265631e-01,1.100000010988609489e+01,1.892287143390696761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130675439049313979e+01,6.151226475287120365e+02,3.919365002711674428e-01,1.100000010988609489e+01,1.892141157989159043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130766348139314914e+01,6.151326475108110117e+02,3.919554216714569161e-01,1.100000010988609489e+01,1.891995172587621326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130857257229315849e+01,6.151426474929128290e+02,3.919743416118949830e-01,1.100000010988609489e+01,1.891849187186083608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.130948166319316783e+01,6.151526474750173747e+02,3.919932600924816435e-01,1.100000010988609489e+01,1.891703201784545891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131039075409317718e+01,6.151626474571246490e+02,3.920121771132169530e-01,1.100000010988609489e+01,1.891557216383008173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131129984499318653e+01,6.151726474392347654e+02,3.920310926741008561e-01,1.100000010988609489e+01,1.891411230981470456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131220893589319587e+01,6.151826474213476104e+02,3.920500067751333528e-01,1.100000010988609489e+01,1.891265245579932738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131311802679320522e+01,6.151926474034631838e+02,3.920689194163144431e-01,1.100000010988609489e+01,1.891119260178395021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131402711769321456e+01,6.152026473855814857e+02,3.920878305976441269e-01,1.100000010988609489e+01,1.890973274776857303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131493620859322391e+01,6.152126473677026297e+02,3.921067403191224043e-01,1.100000010988609489e+01,1.890827289375319586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131584529949323326e+01,6.152226473498265022e+02,3.921256485807492753e-01,1.100000010988609489e+01,1.890681303973781868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131675439039324260e+01,6.152326473319531033e+02,3.921445553825247399e-01,1.100000010988609489e+01,1.890535318572244151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131766348129325195e+01,6.152426473140825465e+02,3.921634607244487980e-01,1.100000010988609489e+01,1.890389333170706433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131857257219326129e+01,6.152526472962147182e+02,3.921823646065214497e-01,1.100000010988609489e+01,1.890243347769168716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.131948166309327064e+01,6.152626472783496183e+02,3.922012670287426950e-01,1.100000010988609489e+01,1.890097362367630998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132039075399327999e+01,6.152726472604872470e+02,3.922201679911125338e-01,1.100000010988609489e+01,1.889951376966093281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132129984489328933e+01,6.152826472426277178e+02,3.922390674936309662e-01,1.100000010988609489e+01,1.889805391564555563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132220893579329868e+01,6.152926472247709171e+02,3.922579655362979922e-01,1.100000010988609489e+01,1.889659406163017846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132311802669330802e+01,6.153026472069168449e+02,3.922768621191136118e-01,1.100000010988609489e+01,1.889513420761480128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132402711759331737e+01,6.153126471890655012e+02,3.922957572420778249e-01,1.100000010988609489e+01,1.889367435359942411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132493620849332672e+01,6.153226471712169996e+02,3.923146509051906317e-01,1.100000010988609489e+01,1.889221449958404693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132584529939333606e+01,6.153326471533712265e+02,3.923335431084519764e-01,1.100000010988609489e+01,1.889075464556866975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132675439029334541e+01,6.153426471355281819e+02,3.923524338518619148e-01,1.100000010988609489e+01,1.888929479155329258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132766348119335476e+01,6.153526471176878658e+02,3.923713231354204467e-01,1.100000010988609489e+01,1.888783493753791540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132857257209336410e+01,6.153626470998503919e+02,3.923902109591275722e-01,1.100000010988609489e+01,1.888637508352253823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.132948166299337345e+01,6.153726470820156464e+02,3.924090973229832913e-01,1.100000010988609489e+01,1.888491522950716105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133039075389338279e+01,6.153826470641836295e+02,3.924279822269876039e-01,1.100000010988609489e+01,1.888345537549178388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133129984479339214e+01,6.153926470463543410e+02,3.924468656711405101e-01,1.100000010988609489e+01,1.888199552147640670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133220893569340149e+01,6.154026470285278947e+02,3.924657476554420099e-01,1.100000010988609489e+01,1.888053566746102953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133311802659341083e+01,6.154126470107041769e+02,3.924846281798921033e-01,1.100000010988609489e+01,1.887907581344565235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133402711749342018e+01,6.154226469928831875e+02,3.925035072444907902e-01,1.100000010988609489e+01,1.887761595943027518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133493620839342952e+01,6.154326469750649267e+02,3.925223848492380152e-01,1.100000010988609489e+01,1.887615610541489800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133584529929343887e+01,6.154426469572495080e+02,3.925412609941338338e-01,1.100000010988609489e+01,1.887469625139952083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133675439019344822e+01,6.154526469394368178e+02,3.925601356791782459e-01,1.100000010988609489e+01,1.887323639738414365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133766348109345756e+01,6.154626469216268561e+02,3.925790089043712516e-01,1.100000010988609489e+01,1.887177654336876648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133857257199346691e+01,6.154726469038196228e+02,3.925978806697128509e-01,1.100000010988609489e+01,1.887031668935338930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.133948166289347625e+01,6.154826468860152318e+02,3.926167509752030438e-01,1.100000010988609489e+01,1.886885683533801213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134039075379348560e+01,6.154926468682135692e+02,3.926356198208417747e-01,1.100000010988609489e+01,1.886739698132263495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134129984469349495e+01,6.155026468504146351e+02,3.926544872066290992e-01,1.100000010988609489e+01,1.886593712730725778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134220893559350429e+01,6.155126468326184295e+02,3.926733531325650173e-01,1.100000010988609489e+01,1.886447727329188060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134311802649351364e+01,6.155226468148250660e+02,3.926922175986495289e-01,1.100000010988609489e+01,1.886301741927650343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134402711739352299e+01,6.155326467970344311e+02,3.927110806048826341e-01,1.100000010988609489e+01,1.886155756526112625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134493620829353233e+01,6.155426467792465246e+02,3.927299421512642774e-01,1.100000010988609489e+01,1.886009771124574907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134584529919354168e+01,6.155526467614613466e+02,3.927488022377945143e-01,1.100000010988609489e+01,1.885863785723037190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134675439009355102e+01,6.155626467436788971e+02,3.927676608644733447e-01,1.100000010988609489e+01,1.885717800321499472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134766348099356037e+01,6.155726467258992898e+02,3.927865180313007687e-01,1.100000010988609489e+01,1.885571814919961755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134857257189356972e+01,6.155826467081224109e+02,3.928053737382767863e-01,1.100000010988609489e+01,1.885425829518424037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.134948166279357906e+01,6.155926466903482606e+02,3.928242279854013419e-01,1.100000010988609489e+01,1.885279844116886320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135039075369358841e+01,6.156026466725768387e+02,3.928430807726744911e-01,1.100000010988609489e+01,1.885133858715348602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135129984459359775e+01,6.156126466548081453e+02,3.928619321000962339e-01,1.100000010988609489e+01,1.884987873313810885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135220893549360710e+01,6.156226466370422941e+02,3.928807819676665147e-01,1.100000010988609489e+01,1.884841887912273167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135311802639361645e+01,6.156326466192791713e+02,3.928996303753853891e-01,1.100000010988609489e+01,1.884695902510735450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135402711729362579e+01,6.156426466015187771e+02,3.929184773232528571e-01,1.100000010988609489e+01,1.884549917109197732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135493620819363514e+01,6.156526465837611113e+02,3.929373228112689187e-01,1.100000010988609489e+01,1.884403931707660015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135584529909364448e+01,6.156626465660061740e+02,3.929561668394335183e-01,1.100000010988609489e+01,1.884257946306122297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135675438999365383e+01,6.156726465482540789e+02,3.929750094077467115e-01,1.100000010988609489e+01,1.884111960904584580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135766348089366318e+01,6.156826465305047122e+02,3.929938505162084983e-01,1.100000010988609489e+01,1.883965975503046862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135857257179367252e+01,6.156926465127580741e+02,3.930126901648188231e-01,1.100000010988609489e+01,1.883819990101509145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.135948166269368187e+01,6.157026464950141644e+02,3.930315283535777415e-01,1.100000010988609489e+01,1.883674004699971427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136039075359369122e+01,6.157126464772729832e+02,3.930503650824852535e-01,1.100000010988609489e+01,1.883528019298433710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136129984449370056e+01,6.157226464595346442e+02,3.930692003515413036e-01,1.100000010988609489e+01,1.883382033896895992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136220893539370991e+01,6.157326464417990337e+02,3.930880341607459472e-01,1.100000010988609489e+01,1.883236048495358275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136311802629371925e+01,6.157426464240661517e+02,3.931068665100991844e-01,1.100000010988609489e+01,1.883090063093820557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136402711719372860e+01,6.157526464063359981e+02,3.931256973996009596e-01,1.100000010988609489e+01,1.882944077692282839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136493620809373795e+01,6.157626463886085730e+02,3.931445268292513284e-01,1.100000010988609489e+01,1.882798092290745122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136584529899374729e+01,6.157726463708839901e+02,3.931633547990502353e-01,1.100000010988609489e+01,1.882652106889207404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136675438989375664e+01,6.157826463531621357e+02,3.931821813089977358e-01,1.100000010988609489e+01,1.882506121487669687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136766348079376598e+01,6.157926463354430098e+02,3.932010063590938298e-01,1.100000010988609489e+01,1.882360136086131969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136857257169377533e+01,6.158026463177266123e+02,3.932198299493384619e-01,1.100000010988609489e+01,1.882214150684594252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.136948166259378468e+01,6.158126463000129434e+02,3.932386520797316876e-01,1.100000010988609489e+01,1.882068165283056534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137039075349379402e+01,6.158226462823020029e+02,3.932574727502734513e-01,1.100000010988609489e+01,1.881922179881518817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137129984439380337e+01,6.158326462645939046e+02,3.932762919609638086e-01,1.100000010988609489e+01,1.881776194479981099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137220893529381271e+01,6.158426462468885347e+02,3.932951097118027595e-01,1.100000010988609489e+01,1.881630209078443382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137311802619382206e+01,6.158526462291858934e+02,3.933139260027902484e-01,1.100000010988609489e+01,1.881484223676905664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137402711709383141e+01,6.158626462114859805e+02,3.933327408339263309e-01,1.100000010988609489e+01,1.881338238275367947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137493620799384075e+01,6.158726461937887962e+02,3.933515542052109515e-01,1.100000010988609489e+01,1.881192252873830229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137584529889385010e+01,6.158826461760943403e+02,3.933703661166441656e-01,1.100000010988609489e+01,1.881046267472292512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137675438979385945e+01,6.158926461584027265e+02,3.933891765682259178e-01,1.100000010988609489e+01,1.880900282070754794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137766348069386879e+01,6.159026461407138413e+02,3.934079855599562636e-01,1.100000010988609489e+01,1.880754296669217077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137857257159387814e+01,6.159126461230276846e+02,3.934267930918351475e-01,1.100000010988609489e+01,1.880608311267679359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.137948166249388748e+01,6.159226461053442563e+02,3.934455991638626249e-01,1.100000010988609489e+01,1.880462325866141642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138039075339389683e+01,6.159326460876635565e+02,3.934644037760386404e-01,1.100000010988609489e+01,1.880316340464603924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138129984429390618e+01,6.159426460699855852e+02,3.934832069283632494e-01,1.100000010988609489e+01,1.880170355063066207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138220893519391552e+01,6.159526460523103424e+02,3.935020086208363965e-01,1.100000010988609489e+01,1.880024369661528489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138311802609392487e+01,6.159626460346379417e+02,3.935208088534581372e-01,1.100000010988609489e+01,1.879878384259990771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138402711699393421e+01,6.159726460169682696e+02,3.935396076262284160e-01,1.100000010988609489e+01,1.879732398858453054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138493620789394356e+01,6.159826459993013259e+02,3.935584049391472883e-01,1.100000010988609489e+01,1.879586413456915336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138584529879395291e+01,6.159926459816371107e+02,3.935772007922146987e-01,1.100000010988609489e+01,1.879440428055377619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138675438969396225e+01,6.160026459639756240e+02,3.935959951854307026e-01,1.100000010988609489e+01,1.879294442653839901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138766348059397160e+01,6.160126459463168658e+02,3.936147881187952446e-01,1.100000010988609489e+01,1.879148457252302184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138857257149398094e+01,6.160226459286608360e+02,3.936335795923083802e-01,1.100000010988609489e+01,1.879002471850764466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.138948166239399029e+01,6.160326459110075348e+02,3.936523696059700539e-01,1.100000010988609489e+01,1.878856486449226749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139039075329399964e+01,6.160426458933570757e+02,3.936711581597802656e-01,1.100000010988609489e+01,1.878710501047689031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139129984419400898e+01,6.160526458757093451e+02,3.936899452537390709e-01,1.100000010988609489e+01,1.878564515646151314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139220893509401833e+01,6.160626458580643430e+02,3.937087308878464142e-01,1.100000010988609489e+01,1.878418530244613596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139311802599402768e+01,6.160726458404220693e+02,3.937275150621023512e-01,1.100000010988609489e+01,1.878272544843075879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139402711689403702e+01,6.160826458227825242e+02,3.937462977765068262e-01,1.100000010988609489e+01,1.878126559441538161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139493620779404637e+01,6.160926458051457075e+02,3.937650790310598392e-01,1.100000010988609489e+01,1.877980574040000444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139584529869405571e+01,6.161026457875116193e+02,3.937838588257614458e-01,1.100000010988609489e+01,1.877834588638462726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139675438959406506e+01,6.161126457698802596e+02,3.938026371606115905e-01,1.100000010988609489e+01,1.877688603236925009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139766348049407441e+01,6.161226457522517421e+02,3.938214140356103288e-01,1.100000010988609489e+01,1.877542617835387291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139857257139408375e+01,6.161326457346259531e+02,3.938401894507576051e-01,1.100000010988609489e+01,1.877396632433849574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.139948166229409310e+01,6.161426457170028925e+02,3.938589634060534195e-01,1.100000010988609489e+01,1.877250647032311856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140039075319410244e+01,6.161526456993825605e+02,3.938777359014978274e-01,1.100000010988609489e+01,1.877104661630774139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140129984409411179e+01,6.161626456817649569e+02,3.938965069370907734e-01,1.100000010988609489e+01,1.876958676229236421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140220893499412114e+01,6.161726456641500818e+02,3.939152765128322575e-01,1.100000010988609489e+01,1.876812690827698703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140311802589413048e+01,6.161826456465379351e+02,3.939340446287223352e-01,1.100000010988609489e+01,1.876666705426160986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140402711679413983e+01,6.161926456289285170e+02,3.939528112847609509e-01,1.100000010988609489e+01,1.876520720024623268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140493620769414918e+01,6.162026456113218273e+02,3.939715764809481047e-01,1.100000010988609489e+01,1.876374734623085551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140584529859415852e+01,6.162126455937178662e+02,3.939903402172838520e-01,1.100000010988609489e+01,1.876228749221547833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140675438949416787e+01,6.162226455761167472e+02,3.940091024937681374e-01,1.100000010988609489e+01,1.876082763820010116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140766348039417721e+01,6.162326455585183567e+02,3.940278633104009609e-01,1.100000010988609489e+01,1.875936778418472398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140857257129418656e+01,6.162426455409226946e+02,3.940466226671823224e-01,1.100000010988609489e+01,1.875790793016934681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.140948166219419591e+01,6.162526455233297611e+02,3.940653805641122776e-01,1.100000010988609489e+01,1.875644807615396963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141039075309420525e+01,6.162626455057395560e+02,3.940841370011907707e-01,1.100000010988609489e+01,1.875498822213859246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141129984399421460e+01,6.162726454881520795e+02,3.941028919784178020e-01,1.100000010988609489e+01,1.875352836812321528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141220893489422394e+01,6.162826454705673314e+02,3.941216454957933712e-01,1.100000010988609489e+01,1.875206851410783811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141311802579423329e+01,6.162926454529853117e+02,3.941403975533175341e-01,1.100000010988609489e+01,1.875060866009246093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141402711669424264e+01,6.163026454354060206e+02,3.941591481509902350e-01,1.100000010988609489e+01,1.874914880607708376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141493620759425198e+01,6.163126454178294580e+02,3.941778972888114740e-01,1.100000010988609489e+01,1.874768895206170658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141584529849426133e+01,6.163226454002556238e+02,3.941966449667812511e-01,1.100000010988609489e+01,1.874622909804632941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141675438939427067e+01,6.163326453826845182e+02,3.942153911848996217e-01,1.100000010988609489e+01,1.874476924403095223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141766348029428002e+01,6.163426453651162547e+02,3.942341359431665304e-01,1.100000010988609489e+01,1.874330939001557506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141857257119428937e+01,6.163526453475507196e+02,3.942528792415819772e-01,1.100000010988609489e+01,1.874184953600019788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.141948166209429871e+01,6.163626453299879131e+02,3.942716210801459620e-01,1.100000010988609489e+01,1.874038968198482071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142039075299430806e+01,6.163726453124278351e+02,3.942903614588584849e-01,1.100000010988609489e+01,1.873892982796944353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142129984389431741e+01,6.163826452948704855e+02,3.943091003777196013e-01,1.100000010988609489e+01,1.873746997395406635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142220893479432675e+01,6.163926452773158644e+02,3.943278378367292558e-01,1.100000010988609489e+01,1.873601011993868918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142311802569433610e+01,6.164026452597639718e+02,3.943465738358874484e-01,1.100000010988609489e+01,1.873455026592331200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142402711659434544e+01,6.164126452422148077e+02,3.943653083751941790e-01,1.100000010988609489e+01,1.873309041190793483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142493620749435479e+01,6.164226452246683721e+02,3.943840414546494477e-01,1.100000010988609489e+01,1.873163055789255765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142584529839436414e+01,6.164326452071246649e+02,3.944027730742532545e-01,1.100000010988609489e+01,1.873017070387718048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142675438929437348e+01,6.164426451895836863e+02,3.944215032340055993e-01,1.100000010988609489e+01,1.872871084986180330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142766348019438283e+01,6.164526451720454361e+02,3.944402319339065377e-01,1.100000010988609489e+01,1.872725099584642613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142857257109439217e+01,6.164626451545099144e+02,3.944589591739560142e-01,1.100000010988609489e+01,1.872579114183104895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.142948166199440152e+01,6.164726451369771212e+02,3.944776849541540287e-01,1.100000010988609489e+01,1.872433128781567178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143039075289441087e+01,6.164826451194470565e+02,3.944964092745005813e-01,1.100000010988609489e+01,1.872287143380029460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143129984379442021e+01,6.164926451019197202e+02,3.945151321349956719e-01,1.100000010988609489e+01,1.872141157978491743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143220893469442956e+01,6.165026450843951125e+02,3.945338535356393006e-01,1.100000010988609489e+01,1.871995172576954025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143311802559443890e+01,6.165126450668732332e+02,3.945525734764314674e-01,1.100000010988609489e+01,1.871849187175416308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143402711649444825e+01,6.165226450493541961e+02,3.945712919573721722e-01,1.100000010988609489e+01,1.871703201773878590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143493620739445760e+01,6.165326450318378875e+02,3.945900089784614151e-01,1.100000010988609489e+01,1.871557216372340873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143584529829446694e+01,6.165426450143243073e+02,3.946087245396991960e-01,1.100000010988609489e+01,1.871411230970803155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143675438919447629e+01,6.165526449968134557e+02,3.946274386410855151e-01,1.100000010988609489e+01,1.871265245569265438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143766348009448564e+01,6.165626449793053325e+02,3.946461512826204276e-01,1.100000010988609489e+01,1.871119260167727720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143857257099449498e+01,6.165726449617999378e+02,3.946648624643038783e-01,1.100000010988609489e+01,1.870973274766190002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.143948166189450433e+01,6.165826449442972716e+02,3.946835721861358670e-01,1.100000010988609489e+01,1.870827289364652285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144039075279451367e+01,6.165926449267973339e+02,3.947022804481163938e-01,1.100000010988609489e+01,1.870681303963114567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144129984369452302e+01,6.166026449093001247e+02,3.947209872502454586e-01,1.100000010988609489e+01,1.870535318561576850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144220893459453237e+01,6.166126448918056440e+02,3.947396925925230615e-01,1.100000010988609489e+01,1.870389333160039132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144311802549454171e+01,6.166226448743138917e+02,3.947583964749492025e-01,1.100000010988609489e+01,1.870243347758501415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144402711639455106e+01,6.166326448568248679e+02,3.947770988975238815e-01,1.100000010988609489e+01,1.870097362356963697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144493620729456040e+01,6.166426448393385726e+02,3.947957998602470986e-01,1.100000010988609489e+01,1.869951376955425980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144584529819456975e+01,6.166526448218550058e+02,3.948144993631188537e-01,1.100000010988609489e+01,1.869805391553888262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144675438909457910e+01,6.166626448043741675e+02,3.948331974061391469e-01,1.100000010988609489e+01,1.869659406152350545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144766347999458844e+01,6.166726447868960577e+02,3.948518939893079782e-01,1.100000010988609489e+01,1.869513420750812827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144857257089459779e+01,6.166826447694206763e+02,3.948705891126253475e-01,1.100000010988609489e+01,1.869367435349275110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.144948166179460713e+01,6.166926447519480234e+02,3.948892827760911994e-01,1.100000010988609489e+01,1.869221449947737392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145039075269461648e+01,6.167026447344780991e+02,3.949079749797055894e-01,1.100000010988609489e+01,1.869075464546199675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145129984359462583e+01,6.167126447170109032e+02,3.949266657234685174e-01,1.100000010988609489e+01,1.868929479144661957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145220893449463517e+01,6.167226446995464357e+02,3.949453550073799835e-01,1.100000010988609489e+01,1.868783493743124240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145311802539464452e+01,6.167326446820846968e+02,3.949640428314399876e-01,1.100000010988609489e+01,1.868637508341586522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145402711629465387e+01,6.167426446646256863e+02,3.949827291956485298e-01,1.100000010988609489e+01,1.868491522940048805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145493620719466321e+01,6.167526446471694044e+02,3.950014141000056100e-01,1.100000010988609489e+01,1.868345537538511087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145584529809467256e+01,6.167626446297158509e+02,3.950200975445112284e-01,1.100000010988609489e+01,1.868199552136973370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145675438899468190e+01,6.167726446122650259e+02,3.950387795291653847e-01,1.100000010988609489e+01,1.868053566735435652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145766347989469125e+01,6.167826445948169294e+02,3.950574600539680792e-01,1.100000010988609489e+01,1.867907581333897934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145857257079470060e+01,6.167926445773715614e+02,3.950761391189193117e-01,1.100000010988609489e+01,1.867761595932360217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.145948166169470994e+01,6.168026445599289218e+02,3.950948167240190823e-01,1.100000010988609489e+01,1.867615610530822499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146039075259471929e+01,6.168126445424890107e+02,3.951134928692673354e-01,1.100000010988609489e+01,1.867469625129284782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146129984349472863e+01,6.168226445250518282e+02,3.951321675546641266e-01,1.100000010988609489e+01,1.867323639727747064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146220893439473798e+01,6.168326445076173741e+02,3.951508407802094558e-01,1.100000010988609489e+01,1.867177654326209347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146311802529474733e+01,6.168426444901856485e+02,3.951695125459033231e-01,1.100000010988609489e+01,1.867031668924671629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146402711619475667e+01,6.168526444727566513e+02,3.951881828517457285e-01,1.100000010988609489e+01,1.866885683523133912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146493620709476602e+01,6.168626444553303827e+02,3.952068516977366719e-01,1.100000010988609489e+01,1.866739698121596194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146584529799477536e+01,6.168726444379068425e+02,3.952255190838760979e-01,1.100000010988609489e+01,1.866593712720058477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146675438889478471e+01,6.168826444204860309e+02,3.952441850101640619e-01,1.100000010988609489e+01,1.866447727318520759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146766347979479406e+01,6.168926444030679477e+02,3.952628494766005640e-01,1.100000010988609489e+01,1.866301741916983042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146857257069480340e+01,6.169026443856525930e+02,3.952815124831856042e-01,1.100000010988609489e+01,1.866155756515445324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.146948166159481275e+01,6.169126443682399668e+02,3.953001740299191824e-01,1.100000010988609489e+01,1.866009771113907607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147039075249482210e+01,6.169226443508299553e+02,3.953188341168012432e-01,1.100000010988609489e+01,1.865863785712369889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147129984339483144e+01,6.169326443334226724e+02,3.953374927438318420e-01,1.100000010988609489e+01,1.865717800310832172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147220893429484079e+01,6.169426443160181179e+02,3.953561499110109789e-01,1.100000010988609489e+01,1.865571814909294454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147311802519485013e+01,6.169526442986162920e+02,3.953748056183386539e-01,1.100000010988609489e+01,1.865425829507756737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147402711609485948e+01,6.169626442812171945e+02,3.953934598658148669e-01,1.100000010988609489e+01,1.865279844106219019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147493620699486883e+01,6.169726442638208255e+02,3.954121126534395625e-01,1.100000010988609489e+01,1.865133858704681302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147584529789487817e+01,6.169826442464271850e+02,3.954307639812127961e-01,1.100000010988609489e+01,1.864987873303143584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147675438879488752e+01,6.169926442290362729e+02,3.954494138491345678e-01,1.100000010988609489e+01,1.864841887901605866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147766347969489686e+01,6.170026442116480894e+02,3.954680622572048776e-01,1.100000010988609489e+01,1.864695902500068149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147857257059490621e+01,6.170126441942626343e+02,3.954867092054236699e-01,1.100000010988609489e+01,1.864549917098530431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.147948166149491556e+01,6.170226441768799077e+02,3.955053546937910003e-01,1.100000010988609489e+01,1.864403931696992714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148039075239492490e+01,6.170326441594999096e+02,3.955239987223068687e-01,1.100000010988609489e+01,1.864257946295454996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148129984329493425e+01,6.170426441421226400e+02,3.955426412909712197e-01,1.100000010988609489e+01,1.864111960893917279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148220893419494359e+01,6.170526441247480989e+02,3.955612823997841088e-01,1.100000010988609489e+01,1.863965975492379561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148311802509495294e+01,6.170626441073762862e+02,3.955799220487455359e-01,1.100000010988609489e+01,1.863819990090841844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148402711599496229e+01,6.170726440900072021e+02,3.955985602378554455e-01,1.100000010988609489e+01,1.863674004689304126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148493620689497163e+01,6.170826440726408464e+02,3.956171969671138933e-01,1.100000010988609489e+01,1.863528019287766409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148584529779498098e+01,6.170926440552772192e+02,3.956358322365208791e-01,1.100000010988609489e+01,1.863382033886228691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148675438869499033e+01,6.171026440379162068e+02,3.956544660460763474e-01,1.100000010988609489e+01,1.863236048484690974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148766347959499967e+01,6.171126440205579229e+02,3.956730983957803538e-01,1.100000010988609489e+01,1.863090063083153256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148857257049500902e+01,6.171226440032023675e+02,3.956917292856328983e-01,1.100000010988609489e+01,1.862944077681615539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.148948166139501836e+01,6.171326439858495405e+02,3.957103587156339253e-01,1.100000010988609489e+01,1.862798092280077821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149039075229502771e+01,6.171426439684994421e+02,3.957289866857834904e-01,1.100000010988609489e+01,1.862652106878540104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149129984319503706e+01,6.171526439511520721e+02,3.957476131960815935e-01,1.100000010988609489e+01,1.862506121477002386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149220893409504640e+01,6.171626439338074306e+02,3.957662382465281792e-01,1.100000010988609489e+01,1.862360136075464669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149311802499505575e+01,6.171726439164655176e+02,3.957848618371233029e-01,1.100000010988609489e+01,1.862214150673926951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149402711589506509e+01,6.171826438991263331e+02,3.958034839678669647e-01,1.100000010988609489e+01,1.862068165272389234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149493620679507444e+01,6.171926438817898770e+02,3.958221046387591091e-01,1.100000010988609489e+01,1.861922179870851516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149584529769508379e+01,6.172026438644561495e+02,3.958407238497997915e-01,1.100000010988609489e+01,1.861776194469313798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149675438859509313e+01,6.172126438471251504e+02,3.958593416009889565e-01,1.100000010988609489e+01,1.861630209067776081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149766347949510248e+01,6.172226438297967661e+02,3.958779578923266596e-01,1.100000010988609489e+01,1.861484223666238363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149857257039511182e+01,6.172326438124711103e+02,3.958965727238128451e-01,1.100000010988609489e+01,1.861338238264700646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.149948166129512117e+01,6.172426437951481830e+02,3.959151860954475688e-01,1.100000010988609489e+01,1.861192252863162928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150039075219513052e+01,6.172526437778279842e+02,3.959337980072308305e-01,1.100000010988609489e+01,1.861046267461625211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150129984309513986e+01,6.172626437605105139e+02,3.959524084591625748e-01,1.100000010988609489e+01,1.860900282060087493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150220893399514921e+01,6.172726437431957720e+02,3.959710174512428571e-01,1.100000010988609489e+01,1.860754296658549776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150311802489515856e+01,6.172826437258837586e+02,3.959896249834716220e-01,1.100000010988609489e+01,1.860608311257012058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150402711579516790e+01,6.172926437085744737e+02,3.960082310558489249e-01,1.100000010988609489e+01,1.860462325855474341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150493620669517725e+01,6.173026436912679173e+02,3.960268356683747104e-01,1.100000010988609489e+01,1.860316340453936623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150584529759518659e+01,6.173126436739640894e+02,3.960454388210490340e-01,1.100000010988609489e+01,1.860170355052398906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150675438849519594e+01,6.173226436566628763e+02,3.960640405138718401e-01,1.100000010988609489e+01,1.860024369650861188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150766347939520529e+01,6.173326436393643917e+02,3.960826407468431842e-01,1.100000010988609489e+01,1.859878384249323471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150857257029521463e+01,6.173426436220686355e+02,3.961012395199630109e-01,1.100000010988609489e+01,1.859732398847785753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.150948166119522398e+01,6.173526436047756079e+02,3.961198368332313757e-01,1.100000010988609489e+01,1.859586413446248036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151039075209523332e+01,6.173626435874853087e+02,3.961384326866482231e-01,1.100000010988609489e+01,1.859440428044710318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151129984299524267e+01,6.173726435701977380e+02,3.961570270802136084e-01,1.100000010988609489e+01,1.859294442643172601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151220893389525202e+01,6.173826435529128958e+02,3.961756200139274764e-01,1.100000010988609489e+01,1.859148457241634883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151311802479526136e+01,6.173926435356307820e+02,3.961942114877898824e-01,1.100000010988609489e+01,1.859002471840097166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151402711569527071e+01,6.174026435183512831e+02,3.962128015018007710e-01,1.100000010988609489e+01,1.858856486438559448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151493620659528005e+01,6.174126435010745126e+02,3.962313900559601421e-01,1.100000010988609489e+01,1.858710501037021730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151584529749528940e+01,6.174226434838004707e+02,3.962499771502680512e-01,1.100000010988609489e+01,1.858564515635484013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151675438839529875e+01,6.174326434665291572e+02,3.962685627847244429e-01,1.100000010988609489e+01,1.858418530233946295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151766347929530809e+01,6.174426434492605722e+02,3.962871469593293727e-01,1.100000010988609489e+01,1.858272544832408578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151857257019531744e+01,6.174526434319947157e+02,3.963057296740827851e-01,1.100000010988609489e+01,1.858126559430870860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.151948166109532679e+01,6.174626434147315877e+02,3.963243109289847355e-01,1.100000010988609489e+01,1.857980574029333143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152039075199533613e+01,6.174726433974711881e+02,3.963428907240351684e-01,1.100000010988609489e+01,1.857834588627795425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152129984289534548e+01,6.174826433802134034e+02,3.963614690592340839e-01,1.100000010988609489e+01,1.857688603226257708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152220893379535482e+01,6.174926433629583471e+02,3.963800459345815375e-01,1.100000010988609489e+01,1.857542617824719990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152311802469536417e+01,6.175026433457060193e+02,3.963986213500774736e-01,1.100000010988609489e+01,1.857396632423182273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152402711559537352e+01,6.175126433284564200e+02,3.964171953057218922e-01,1.100000010988609489e+01,1.857250647021644555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152493620649538286e+01,6.175226433112095492e+02,3.964357678015148490e-01,1.100000010988609489e+01,1.857104661620106838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152584529739539221e+01,6.175326432939654069e+02,3.964543388374562882e-01,1.100000010988609489e+01,1.856958676218569120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152675438829540155e+01,6.175426432767238794e+02,3.964729084135462656e-01,1.100000010988609489e+01,1.856812690817031403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152766347919541090e+01,6.175526432594850803e+02,3.964914765297847254e-01,1.100000010988609489e+01,1.856666705415493685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152857257009542025e+01,6.175626432422490097e+02,3.965100431861716679e-01,1.100000010988609489e+01,1.856520720013955968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.152948166099542959e+01,6.175726432250156677e+02,3.965286083827071484e-01,1.100000010988609489e+01,1.856374734612418250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153039075189543894e+01,6.175826432077850541e+02,3.965471721193911114e-01,1.100000010988609489e+01,1.856228749210880533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153129984279544828e+01,6.175926431905571690e+02,3.965657343962235570e-01,1.100000010988609489e+01,1.856082763809342815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153220893369545763e+01,6.176026431733320123e+02,3.965842952132044852e-01,1.100000010988609489e+01,1.855936778407805098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153311802459546698e+01,6.176126431561094705e+02,3.966028545703339514e-01,1.100000010988609489e+01,1.855790793006267380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153402711549547632e+01,6.176226431388896572e+02,3.966214124676119002e-01,1.100000010988609489e+01,1.855644807604729662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153493620639548567e+01,6.176326431216725723e+02,3.966399689050383315e-01,1.100000010988609489e+01,1.855498822203191945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153584529729549502e+01,6.176426431044582159e+02,3.966585238826133009e-01,1.100000010988609489e+01,1.855352836801654227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153675438819550436e+01,6.176526430872465880e+02,3.966770774003367528e-01,1.100000010988609489e+01,1.855206851400116510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153766347909551371e+01,6.176626430700375749e+02,3.966956294582086873e-01,1.100000010988609489e+01,1.855060865998578792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153857256999552305e+01,6.176726430528312903e+02,3.967141800562291043e-01,1.100000010988609489e+01,1.854914880597041075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.153948166089553240e+01,6.176826430356277342e+02,3.967327291943980594e-01,1.100000010988609489e+01,1.854768895195503357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154039075179554175e+01,6.176926430184269066e+02,3.967512768727154970e-01,1.100000010988609489e+01,1.854622909793965640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154129984269555109e+01,6.177026430012288074e+02,3.967698230911814172e-01,1.100000010988609489e+01,1.854476924392427922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154220893359556044e+01,6.177126429840334367e+02,3.967883678497958200e-01,1.100000010988609489e+01,1.854330938990890205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154311802449556978e+01,6.177226429668406809e+02,3.968069111485587608e-01,1.100000010988609489e+01,1.854184953589352487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154402711539557913e+01,6.177326429496506535e+02,3.968254529874701841e-01,1.100000010988609489e+01,1.854038968187814770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154493620629558848e+01,6.177426429324633546e+02,3.968439933665300901e-01,1.100000010988609489e+01,1.853892982786277052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154584529719559782e+01,6.177526429152787841e+02,3.968625322857384785e-01,1.100000010988609489e+01,1.853746997384739335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154675438809560717e+01,6.177626428980969422e+02,3.968810697450953495e-01,1.100000010988609489e+01,1.853601011983201617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154766347899561652e+01,6.177726428809177150e+02,3.968996057446007586e-01,1.100000010988609489e+01,1.853455026581663900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154857256989562586e+01,6.177826428637412164e+02,3.969181402842546502e-01,1.100000010988609489e+01,1.853309041180126182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.154948166079563521e+01,6.177926428465674462e+02,3.969366733640570244e-01,1.100000010988609489e+01,1.853163055778588465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155039075169564455e+01,6.178026428293964045e+02,3.969552049840078811e-01,1.100000010988609489e+01,1.853017070377050747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155129984259565390e+01,6.178126428122280913e+02,3.969737351441072204e-01,1.100000010988609489e+01,1.852871084975513030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155220893349566325e+01,6.178226427950623929e+02,3.969922638443550422e-01,1.100000010988609489e+01,1.852725099573975312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155311802439567259e+01,6.178326427778994230e+02,3.970107910847513466e-01,1.100000010988609489e+01,1.852579114172437594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155402711529568194e+01,6.178426427607391815e+02,3.970293168652961890e-01,1.100000010988609489e+01,1.852433128770899877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155493620619569128e+01,6.178526427435816686e+02,3.970478411859895140e-01,1.100000010988609489e+01,1.852287143369362159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155584529709570063e+01,6.178626427264268841e+02,3.970663640468313216e-01,1.100000010988609489e+01,1.852141157967824442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155675438799570998e+01,6.178726427092747144e+02,3.970848854478216117e-01,1.100000010988609489e+01,1.851995172566286724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155766347889571932e+01,6.178826426921252732e+02,3.971034053889603843e-01,1.100000010988609489e+01,1.851849187164749007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155857256979572867e+01,6.178926426749785605e+02,3.971219238702476395e-01,1.100000010988609489e+01,1.851703201763211289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.155948166069573801e+01,6.179026426578345763e+02,3.971404408916833773e-01,1.100000010988609489e+01,1.851557216361673572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156039075159574736e+01,6.179126426406932069e+02,3.971589564532675976e-01,1.100000010988609489e+01,1.851411230960135854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156129984249575671e+01,6.179226426235545659e+02,3.971774705550003004e-01,1.100000010988609489e+01,1.851265245558598137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156220893339576605e+01,6.179326426064186535e+02,3.971959831968814858e-01,1.100000010988609489e+01,1.851119260157060419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156311802429577540e+01,6.179426425892854695e+02,3.972144943789112093e-01,1.100000010988609489e+01,1.850973274755522702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156402711519578475e+01,6.179526425721550140e+02,3.972330041010894153e-01,1.100000010988609489e+01,1.850827289353984984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156493620609579409e+01,6.179626425550271733e+02,3.972515123634161038e-01,1.100000010988609489e+01,1.850681303952447267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156584529699580344e+01,6.179726425379020611e+02,3.972700191658912749e-01,1.100000010988609489e+01,1.850535318550909549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156675438789581278e+01,6.179826425207796774e+02,3.972885245085149286e-01,1.100000010988609489e+01,1.850389333149371832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156766347879582213e+01,6.179926425036600222e+02,3.973070283912870648e-01,1.100000010988609489e+01,1.850243347747834114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156857256969583148e+01,6.180026424865429817e+02,3.973255308142076836e-01,1.100000010988609489e+01,1.850097362346296397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.156948166059584082e+01,6.180126424694286698e+02,3.973440317772767849e-01,1.100000010988609489e+01,1.849951376944758679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157039075149585017e+01,6.180226424523170863e+02,3.973625312804943688e-01,1.100000010988609489e+01,1.849805391543220962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157129984239585951e+01,6.180326424352082313e+02,3.973810293238604352e-01,1.100000010988609489e+01,1.849659406141683244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157220893329586886e+01,6.180426424181019911e+02,3.973995259073749842e-01,1.100000010988609489e+01,1.849513420740145526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157311802419587821e+01,6.180526424009984794e+02,3.974180210310380157e-01,1.100000010988609489e+01,1.849367435338607809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157402711509588755e+01,6.180626423838976962e+02,3.974365146948495298e-01,1.100000010988609489e+01,1.849221449937070091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157493620599589690e+01,6.180726423667996414e+02,3.974550068988095264e-01,1.100000010988609489e+01,1.849075464535532374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157584529689590624e+01,6.180826423497042015e+02,3.974734976429180056e-01,1.100000010988609489e+01,1.848929479133994656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157675438779591559e+01,6.180926423326114900e+02,3.974919869271749673e-01,1.100000010988609489e+01,1.848783493732456939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157766347869592494e+01,6.181026423155215070e+02,3.975104747515804116e-01,1.100000010988609489e+01,1.848637508330919221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157857256959593428e+01,6.181126422984342526e+02,3.975289611161343384e-01,1.100000010988609489e+01,1.848491522929381504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.157948166049594363e+01,6.181226422813496129e+02,3.975474460208366922e-01,1.100000010988609489e+01,1.848345537527843786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158039075139595298e+01,6.181326422642677016e+02,3.975659294656875287e-01,1.100000010988609489e+01,1.848199552126306069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158129984229596232e+01,6.181426422471885189e+02,3.975844114506868476e-01,1.100000010988609489e+01,1.848053566724768351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158220893319597167e+01,6.181526422301120647e+02,3.976028919758346492e-01,1.100000010988609489e+01,1.847907581323230634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158311802409598101e+01,6.181626422130382252e+02,3.976213710411309332e-01,1.100000010988609489e+01,1.847761595921692916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158402711499599036e+01,6.181726421959671143e+02,3.976398486465756998e-01,1.100000010988609489e+01,1.847615610520155199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158493620589599971e+01,6.181826421788987318e+02,3.976583247921689490e-01,1.100000010988609489e+01,1.847469625118617481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158584529679600905e+01,6.181926421618329641e+02,3.976767994779106807e-01,1.100000010988609489e+01,1.847323639717079764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158675438769601840e+01,6.182026421447699249e+02,3.976952727038008950e-01,1.100000010988609489e+01,1.847177654315542046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158766347859602774e+01,6.182126421277096142e+02,3.977137444698395918e-01,1.100000010988609489e+01,1.847031668914004329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158857256949603709e+01,6.182226421106520320e+02,3.977322147760267157e-01,1.100000010988609489e+01,1.846885683512466611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.158948166039604644e+01,6.182326420935970646e+02,3.977506836223623221e-01,1.100000010988609489e+01,1.846739698110928894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159039075129605578e+01,6.182426420765448256e+02,3.977691510088464111e-01,1.100000010988609489e+01,1.846593712709391176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159129984219606513e+01,6.182526420594953152e+02,3.977876169354789826e-01,1.100000010988609489e+01,1.846447727307853458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159220893309607447e+01,6.182626420424484195e+02,3.978060814022600367e-01,1.100000010988609489e+01,1.846301741906315741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159311802399608382e+01,6.182726420254042523e+02,3.978245444091895733e-01,1.100000010988609489e+01,1.846155756504778023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159402711489609317e+01,6.182826420083628136e+02,3.978430059562675369e-01,1.100000010988609489e+01,1.846009771103240306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159493620579610251e+01,6.182926419913241034e+02,3.978614660434939831e-01,1.100000010988609489e+01,1.845863785701702588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159584529669611186e+01,6.183026419742880080e+02,3.978799246708689119e-01,1.100000010988609489e+01,1.845717800300164871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159675438759612121e+01,6.183126419572546411e+02,3.978983818383923232e-01,1.100000010988609489e+01,1.845571814898627153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159766347849613055e+01,6.183226419402240026e+02,3.979168375460642171e-01,1.100000010988609489e+01,1.845425829497089436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159857256939613990e+01,6.183326419231959790e+02,3.979352917938845380e-01,1.100000010988609489e+01,1.845279844095551718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.159948166029614924e+01,6.183426419061706838e+02,3.979537445818533414e-01,1.100000010988609489e+01,1.845133858694014001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160039075119615859e+01,6.183526418891481171e+02,3.979721959099706274e-01,1.100000010988609489e+01,1.844987873292476283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160129984209616794e+01,6.183626418721281652e+02,3.979906457782363960e-01,1.100000010988609489e+01,1.844841887890938566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160220893299617728e+01,6.183726418551109418e+02,3.980090941866506471e-01,1.100000010988609489e+01,1.844695902489400848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160311802389618663e+01,6.183826418380964469e+02,3.980275411352133252e-01,1.100000010988609489e+01,1.844549917087863131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160402711479619597e+01,6.183926418210846805e+02,3.980459866239244859e-01,1.100000010988609489e+01,1.844403931686325413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160493620569620532e+01,6.184026418040755289e+02,3.980644306527841292e-01,1.100000010988609489e+01,1.844257946284787696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160584529659621467e+01,6.184126417870691057e+02,3.980828732217921995e-01,1.100000010988609489e+01,1.844111960883249978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160675438749622401e+01,6.184226417700654110e+02,3.981013143309487523e-01,1.100000010988609489e+01,1.843965975481712261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160766347839623336e+01,6.184326417530643312e+02,3.981197539802537877e-01,1.100000010988609489e+01,1.843819990080174543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160857256929624270e+01,6.184426417360659798e+02,3.981381921697073056e-01,1.100000010988609489e+01,1.843674004678636826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.160948166019625205e+01,6.184526417190703569e+02,3.981566288993092506e-01,1.100000010988609489e+01,1.843528019277099108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161039075109626140e+01,6.184626417020773488e+02,3.981750641690596781e-01,1.100000010988609489e+01,1.843382033875561390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161129984199627074e+01,6.184726416850870692e+02,3.981934979789585882e-01,1.100000010988609489e+01,1.843236048474023673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161220893289628009e+01,6.184826416680995180e+02,3.982119303290059253e-01,1.100000010988609489e+01,1.843090063072485955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161311802379628944e+01,6.184926416511145817e+02,3.982303612192017450e-01,1.100000010988609489e+01,1.842944077670948238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161402711469629878e+01,6.185026416341323738e+02,3.982487906495460472e-01,1.100000010988609489e+01,1.842798092269410520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161493620559630813e+01,6.185126416171528945e+02,3.982672186200387765e-01,1.100000010988609489e+01,1.842652106867872803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161584529649631747e+01,6.185226416001760299e+02,3.982856451306799883e-01,1.100000010988609489e+01,1.842506121466335085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161675438739632682e+01,6.185326415832018938e+02,3.983040701814696827e-01,1.100000010988609489e+01,1.842360136064797368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161766347829633617e+01,6.185426415662304862e+02,3.983224937724078041e-01,1.100000010988609489e+01,1.842214150663259650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161857256919634551e+01,6.185526415492616934e+02,3.983409159034944080e-01,1.100000010988609489e+01,1.842068165261721933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.161948166009635486e+01,6.185626415322956291e+02,3.983593365747294945e-01,1.100000010988609489e+01,1.841922179860184215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162039075099636420e+01,6.185726415153322932e+02,3.983777557861130081e-01,1.100000010988609489e+01,1.841776194458646498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162129984189637355e+01,6.185826414983715722e+02,3.983961735376450042e-01,1.100000010988609489e+01,1.841630209057108780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162220893279638290e+01,6.185926414814135796e+02,3.984145898293254273e-01,1.100000010988609489e+01,1.841484223655571063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162311802369639224e+01,6.186026414644583156e+02,3.984330046611543330e-01,1.100000010988609489e+01,1.841338238254033345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162402711459640159e+01,6.186126414475056663e+02,3.984514180331317212e-01,1.100000010988609489e+01,1.841192252852495628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162493620549641093e+01,6.186226414305557455e+02,3.984698299452575365e-01,1.100000010988609489e+01,1.841046267450957910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162584529639642028e+01,6.186326414136084395e+02,3.984882403975318343e-01,1.100000010988609489e+01,1.840900282049420193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162675438729642963e+01,6.186426413966638620e+02,3.985066493899545592e-01,1.100000010988609489e+01,1.840754296647882475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162766347819643897e+01,6.186526413797220130e+02,3.985250569225257666e-01,1.100000010988609489e+01,1.840608311246344758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162857256909644832e+01,6.186626413627827787e+02,3.985434629952454011e-01,1.100000010988609489e+01,1.840462325844807040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.162948165999645767e+01,6.186726413458462730e+02,3.985618676081135181e-01,1.100000010988609489e+01,1.840316340443269322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163039075089646701e+01,6.186826413289124957e+02,3.985802707611301177e-01,1.100000010988609489e+01,1.840170355041731605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163129984179647636e+01,6.186926413119813333e+02,3.985986724542951443e-01,1.100000010988609489e+01,1.840024369640193887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163220893269648570e+01,6.187026412950528993e+02,3.986170726876086534e-01,1.100000010988609489e+01,1.839878384238656170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163311802359649505e+01,6.187126412781271938e+02,3.986354714610705896e-01,1.100000010988609489e+01,1.839732398837118452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163402711449650440e+01,6.187226412612041031e+02,3.986538687746810083e-01,1.100000010988609489e+01,1.839586413435580735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163493620539651374e+01,6.187326412442837409e+02,3.986722646284398541e-01,1.100000010988609489e+01,1.839440428034043017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163584529629652309e+01,6.187426412273659935e+02,3.986906590223471825e-01,1.100000010988609489e+01,1.839294442632505300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163675438719653243e+01,6.187526412104509745e+02,3.987090519564029378e-01,1.100000010988609489e+01,1.839148457230967582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163766347809654178e+01,6.187626411935386841e+02,3.987274434306071758e-01,1.100000010988609489e+01,1.839002471829429865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163857256899655113e+01,6.187726411766290084e+02,3.987458334449598407e-01,1.100000010988609489e+01,1.838856486427892147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.163948165989656047e+01,6.187826411597220613e+02,3.987642219994609327e-01,1.100000010988609489e+01,1.838710501026354430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164039075079656982e+01,6.187926411428177289e+02,3.987826090941105073e-01,1.100000010988609489e+01,1.838564515624816712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164129984169657916e+01,6.188026411259161250e+02,3.988009947289085089e-01,1.100000010988609489e+01,1.838418530223278995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164220893259658851e+01,6.188126411090172496e+02,3.988193789038549930e-01,1.100000010988609489e+01,1.838272544821741277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164311802349659786e+01,6.188226410921209890e+02,3.988377616189499042e-01,1.100000010988609489e+01,1.838126559420203560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164402711439660720e+01,6.188326410752274569e+02,3.988561428741932979e-01,1.100000010988609489e+01,1.837980574018665842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164493620529661655e+01,6.188426410583366533e+02,3.988745226695851187e-01,1.100000010988609489e+01,1.837834588617128125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164584529619662590e+01,6.188526410414484644e+02,3.988929010051254220e-01,1.100000010988609489e+01,1.837688603215590407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164675438709663524e+01,6.188626410245630041e+02,3.989112778808141524e-01,1.100000010988609489e+01,1.837542617814052689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164766347799664459e+01,6.188726410076801585e+02,3.989296532966513098e-01,1.100000010988609489e+01,1.837396632412514972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164857256889665393e+01,6.188826409908000414e+02,3.989480272526369498e-01,1.100000010988609489e+01,1.837250647010977254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.164948165979666328e+01,6.188926409739226528e+02,3.989663997487710168e-01,1.100000010988609489e+01,1.837104661609439537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165039075069667263e+01,6.189026409570478791e+02,3.989847707850535663e-01,1.100000010988609489e+01,1.836958676207901819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165129984159668197e+01,6.189126409401758337e+02,3.990031403614845429e-01,1.100000010988609489e+01,1.836812690806364102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165220893249669132e+01,6.189226409233064032e+02,3.990215084780639465e-01,1.100000010988609489e+01,1.836666705404826384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165311802339670066e+01,6.189326409064397012e+02,3.990398751347918327e-01,1.100000010988609489e+01,1.836520720003288667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165402711429671001e+01,6.189426408895756140e+02,3.990582403316681459e-01,1.100000010988609489e+01,1.836374734601750949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165493620519671936e+01,6.189526408727142552e+02,3.990766040686928862e-01,1.100000010988609489e+01,1.836228749200213232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165584529609672870e+01,6.189626408558556250e+02,3.990949663458661090e-01,1.100000010988609489e+01,1.836082763798675514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165675438699673805e+01,6.189726408389996095e+02,3.991133271631877588e-01,1.100000010988609489e+01,1.835936778397137797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165766347789674739e+01,6.189826408221463225e+02,3.991316865206578357e-01,1.100000010988609489e+01,1.835790792995600079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165857256879675674e+01,6.189926408052956504e+02,3.991500444182763951e-01,1.100000010988609489e+01,1.835644807594062362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.165948165969676609e+01,6.190026407884477067e+02,3.991684008560433816e-01,1.100000010988609489e+01,1.835498822192524644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166039075059677543e+01,6.190126407716023778e+02,3.991867558339587951e-01,1.100000010988609489e+01,1.835352836790986927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166129984149678478e+01,6.190226407547597773e+02,3.992051093520226912e-01,1.100000010988609489e+01,1.835206851389449209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166220893239679413e+01,6.190326407379199054e+02,3.992234614102350143e-01,1.100000010988609489e+01,1.835060865987911492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166311802329680347e+01,6.190426407210826483e+02,3.992418120085957645e-01,1.100000010988609489e+01,1.834914880586373774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166402711419681282e+01,6.190526407042481196e+02,3.992601611471049416e-01,1.100000010988609489e+01,1.834768895184836057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166493620509682216e+01,6.190626406874162058e+02,3.992785088257626014e-01,1.100000010988609489e+01,1.834622909783298339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166584529599683151e+01,6.190726406705870204e+02,3.992968550445686882e-01,1.100000010988609489e+01,1.834476924381760621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166675438689684086e+01,6.190826406537604498e+02,3.993151998035232020e-01,1.100000010988609489e+01,1.834330938980222904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166766347779685020e+01,6.190926406369366077e+02,3.993335431026261428e-01,1.100000010988609489e+01,1.834184953578685186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166857256869685955e+01,6.191026406201154941e+02,3.993518849418775662e-01,1.100000010988609489e+01,1.834038968177147469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.166948165959686889e+01,6.191126406032969953e+02,3.993702253212774167e-01,1.100000010988609489e+01,1.833892982775609751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167039075049687824e+01,6.191226405864812250e+02,3.993885642408256942e-01,1.100000010988609489e+01,1.833746997374072034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167129984139688759e+01,6.191326405696680695e+02,3.994069017005223987e-01,1.100000010988609489e+01,1.833601011972534316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167220893229689693e+01,6.191426405528576424e+02,3.994252377003675858e-01,1.100000010988609489e+01,1.833455026570996599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167311802319690628e+01,6.191526405360498302e+02,3.994435722403611999e-01,1.100000010988609489e+01,1.833309041169458881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167402711409691562e+01,6.191626405192447464e+02,3.994619053205032411e-01,1.100000010988609489e+01,1.833163055767921164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167493620499692497e+01,6.191726405024422775e+02,3.994802369407937093e-01,1.100000010988609489e+01,1.833017070366383446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167584529589693432e+01,6.191826404856425370e+02,3.994985671012326045e-01,1.100000010988609489e+01,1.832871084964845729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167675438679694366e+01,6.191926404688454113e+02,3.995168958018199823e-01,1.100000010988609489e+01,1.832725099563308011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167766347769695301e+01,6.192026404520510141e+02,3.995352230425557871e-01,1.100000010988609489e+01,1.832579114161770294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167857256859696236e+01,6.192126404352592317e+02,3.995535488234400190e-01,1.100000010988609489e+01,1.832433128760232576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.167948165949697170e+01,6.192226404184701778e+02,3.995718731444726779e-01,1.100000010988609489e+01,1.832287143358694859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168039075039698105e+01,6.192326404016838524e+02,3.995901960056537638e-01,1.100000010988609489e+01,1.832141157957157141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168129984129699039e+01,6.192426403849001417e+02,3.996085174069832768e-01,1.100000010988609489e+01,1.831995172555619424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168220893219699974e+01,6.192526403681191596e+02,3.996268373484612724e-01,1.100000010988609489e+01,1.831849187154081706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168311802309700909e+01,6.192626403513407922e+02,3.996451558300876949e-01,1.100000010988609489e+01,1.831703201752543989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168402711399701843e+01,6.192726403345651534e+02,3.996634728518625446e-01,1.100000010988609489e+01,1.831557216351006271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168493620489702778e+01,6.192826403177921293e+02,3.996817884137858212e-01,1.100000010988609489e+01,1.831411230949468553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168584529579703712e+01,6.192926403010218337e+02,3.997001025158575249e-01,1.100000010988609489e+01,1.831265245547930836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168675438669704647e+01,6.193026402842541529e+02,3.997184151580776557e-01,1.100000010988609489e+01,1.831119260146393118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168766347759705582e+01,6.193126402674892006e+02,3.997367263404462134e-01,1.100000010988609489e+01,1.830973274744855401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168857256849706516e+01,6.193226402507268631e+02,3.997550360629631983e-01,1.100000010988609489e+01,1.830827289343317683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.168948165939707451e+01,6.193326402339672541e+02,3.997733443256286101e-01,1.100000010988609489e+01,1.830681303941779966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169039075029708386e+01,6.193426402172102598e+02,3.997916511284424490e-01,1.100000010988609489e+01,1.830535318540242248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169129984119709320e+01,6.193526402004559941e+02,3.998099564714047149e-01,1.100000010988609489e+01,1.830389333138704531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169220893209710255e+01,6.193626401837043431e+02,3.998282603545154634e-01,1.100000010988609489e+01,1.830243347737166813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169311802299711189e+01,6.193726401669554207e+02,3.998465627777746390e-01,1.100000010988609489e+01,1.830097362335629096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169402711389712124e+01,6.193826401502091130e+02,3.998648637411822415e-01,1.100000010988609489e+01,1.829951376934091378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169493620479713059e+01,6.193926401334655338e+02,3.998831632447382711e-01,1.100000010988609489e+01,1.829805391532553661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169584529569713993e+01,6.194026401167245695e+02,3.999014612884427278e-01,1.100000010988609489e+01,1.829659406131015943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169675438659714928e+01,6.194126400999863336e+02,3.999197578722956115e-01,1.100000010988609489e+01,1.829513420729478226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169766347749715862e+01,6.194226400832507125e+02,3.999380529962969222e-01,1.100000010988609489e+01,1.829367435327940508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169857256839716797e+01,6.194326400665178198e+02,3.999563466604466599e-01,1.100000010988609489e+01,1.829221449926402791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.169948165929717732e+01,6.194426400497875420e+02,3.999746388647448248e-01,1.100000010988609489e+01,1.829075464524865073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170039075019718666e+01,6.194526400330599927e+02,3.999929296091914166e-01,1.100000010988609489e+01,1.828929479123327356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170129984109719601e+01,6.194626400163350581e+02,4.000112188937864355e-01,1.100000010988609489e+01,1.828783493721789638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170220893199720535e+01,6.194726399996128521e+02,4.000295067185298814e-01,1.100000010988609489e+01,1.828637508320251921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170311802289721470e+01,6.194826399828932608e+02,4.000477930834217544e-01,1.100000010988609489e+01,1.828491522918714203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170402711379722405e+01,6.194926399661763980e+02,4.000660779884620544e-01,1.100000010988609489e+01,1.828345537517176485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170493620469723339e+01,6.195026399494621501e+02,4.000843614336507814e-01,1.100000010988609489e+01,1.828199552115638768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170584529559724274e+01,6.195126399327506306e+02,4.001026434189879355e-01,1.100000010988609489e+01,1.828053566714101050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170675438649725209e+01,6.195226399160417259e+02,4.001209239444735166e-01,1.100000010988609489e+01,1.827907581312563333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170766347739726143e+01,6.195326398993355497e+02,4.001392030101074693e-01,1.100000010988609489e+01,1.827761595911025615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170857256829727078e+01,6.195426398826319883e+02,4.001574806158898490e-01,1.100000010988609489e+01,1.827615610509487898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.170948165919728012e+01,6.195526398659311553e+02,4.001757567618206557e-01,1.100000010988609489e+01,1.827469625107950180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171039075009728947e+01,6.195626398492329372e+02,4.001940314478998895e-01,1.100000010988609489e+01,1.827323639706412463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171129984099729882e+01,6.195726398325373339e+02,4.002123046741275503e-01,1.100000010988609489e+01,1.827177654304874745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171220893189730816e+01,6.195826398158444590e+02,4.002305764405036381e-01,1.100000010988609489e+01,1.827031668903337028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171311802279731751e+01,6.195926397991541990e+02,4.002488467470281530e-01,1.100000010988609489e+01,1.826885683501799310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171402711369732685e+01,6.196026397824666674e+02,4.002671155937010949e-01,1.100000010988609489e+01,1.826739698100261593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171493620459733620e+01,6.196126397657817506e+02,4.002853829805224639e-01,1.100000010988609489e+01,1.826593712698723875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171584529549734555e+01,6.196226397490995623e+02,4.003036489074922599e-01,1.100000010988609489e+01,1.826447727297186158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171675438639735489e+01,6.196326397324199888e+02,4.003219133746104275e-01,1.100000010988609489e+01,1.826301741895648440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171766347729736424e+01,6.196426397157431438e+02,4.003401763818770220e-01,1.100000010988609489e+01,1.826155756494110723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171857256819737358e+01,6.196526396990689136e+02,4.003584379292920437e-01,1.100000010988609489e+01,1.826009771092573005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.171948165909738293e+01,6.196626396823974119e+02,4.003766980168554923e-01,1.100000010988609489e+01,1.825863785691035288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172039074999739228e+01,6.196726396657285250e+02,4.003949566445673680e-01,1.100000010988609489e+01,1.825717800289497570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172129984089740162e+01,6.196826396490622528e+02,4.004132138124276707e-01,1.100000010988609489e+01,1.825571814887959853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172220893179741097e+01,6.196926396323987092e+02,4.004314695204364005e-01,1.100000010988609489e+01,1.825425829486422135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172311802269742032e+01,6.197026396157377803e+02,4.004497237685935018e-01,1.100000010988609489e+01,1.825279844084884417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172402711359742966e+01,6.197126395990795800e+02,4.004679765568990302e-01,1.100000010988609489e+01,1.825133858683346700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172493620449743901e+01,6.197226395824239944e+02,4.004862278853529856e-01,1.100000010988609489e+01,1.824987873281808982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172584529539744835e+01,6.197326395657711373e+02,4.005044777539553680e-01,1.100000010988609489e+01,1.824841887880271265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172675438629745770e+01,6.197426395491208950e+02,4.005227261627061774e-01,1.100000010988609489e+01,1.824695902478733547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172766347719746705e+01,6.197526395324732675e+02,4.005409731116053584e-01,1.100000010988609489e+01,1.824549917077195830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172857256809747639e+01,6.197626395158283685e+02,4.005592186006529665e-01,1.100000010988609489e+01,1.824403931675658112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.172948165899748574e+01,6.197726394991860843e+02,4.005774626298490015e-01,1.100000010988609489e+01,1.824257946274120395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173039074989749508e+01,6.197826394825465286e+02,4.005957051991934637e-01,1.100000010988609489e+01,1.824111960872582677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173129984079750443e+01,6.197926394659095877e+02,4.006139463086862973e-01,1.100000010988609489e+01,1.823965975471044960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173220893169751378e+01,6.198026394492753752e+02,4.006321859583275580e-01,1.100000010988609489e+01,1.823819990069507242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173311802259752312e+01,6.198126394326437776e+02,4.006504241481172457e-01,1.100000010988609489e+01,1.823674004667969525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173402711349753247e+01,6.198226394160147947e+02,4.006686608780553605e-01,1.100000010988609489e+01,1.823528019266431807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173493620439754181e+01,6.198326393993885404e+02,4.006868961481418467e-01,1.100000010988609489e+01,1.823382033864894090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173584529529755116e+01,6.198426393827649008e+02,4.007051299583767601e-01,1.100000010988609489e+01,1.823236048463356372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173675438619756051e+01,6.198526393661439897e+02,4.007233623087601004e-01,1.100000010988609489e+01,1.823090063061818655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173766347709756985e+01,6.198626393495256934e+02,4.007415931992918678e-01,1.100000010988609489e+01,1.822944077660280937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173857256799757920e+01,6.198726393329101256e+02,4.007598226299720068e-01,1.100000010988609489e+01,1.822798092258743220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.173948165889758855e+01,6.198826393162971726e+02,4.007780506008005728e-01,1.100000010988609489e+01,1.822652106857205502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174039074979759789e+01,6.198926392996868344e+02,4.007962771117775658e-01,1.100000010988609489e+01,1.822506121455667785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174129984069760724e+01,6.199026392830792247e+02,4.008145021629029303e-01,1.100000010988609489e+01,1.822360136054130067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174220893159761658e+01,6.199126392664742298e+02,4.008327257541767219e-01,1.100000010988609489e+01,1.822214150652592349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174311802249762593e+01,6.199226392498719633e+02,4.008509478855989405e-01,1.100000010988609489e+01,1.822068165251054632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174402711339763528e+01,6.199326392332723117e+02,4.008691685571695307e-01,1.100000010988609489e+01,1.821922179849516914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174493620429764462e+01,6.199426392166752748e+02,4.008873877688885479e-01,1.100000010988609489e+01,1.821776194447979197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174584529519765397e+01,6.199526392000809665e+02,4.009056055207559921e-01,1.100000010988609489e+01,1.821630209046441479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174675438609766331e+01,6.199626391834892729e+02,4.009238218127718079e-01,1.100000010988609489e+01,1.821484223644903762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174766347699767266e+01,6.199726391669003078e+02,4.009420366449360507e-01,1.100000010988609489e+01,1.821338238243366044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174857256789768201e+01,6.199826391503139575e+02,4.009602500172486650e-01,1.100000010988609489e+01,1.821192252841828327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.174948165879769135e+01,6.199926391337302221e+02,4.009784619297097064e-01,1.100000010988609489e+01,1.821046267440290609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175039074969770070e+01,6.200026391171492151e+02,4.009966723823191748e-01,1.100000010988609489e+01,1.820900282038752892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175129984059771004e+01,6.200126391005708228e+02,4.010148813750770147e-01,1.100000010988609489e+01,1.820754296637215174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175220893149771939e+01,6.200226390839950454e+02,4.010330889079832817e-01,1.100000010988609489e+01,1.820608311235677457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175311802239772874e+01,6.200326390674219965e+02,4.010512949810379757e-01,1.100000010988609489e+01,1.820462325834139739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175402711329773808e+01,6.200426390508515624e+02,4.010694995942410412e-01,1.100000010988609489e+01,1.820316340432602022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175493620419774743e+01,6.200526390342838567e+02,4.010877027475925338e-01,1.100000010988609489e+01,1.820170355031064304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175584529509775678e+01,6.200626390177187659e+02,4.011059044410923979e-01,1.100000010988609489e+01,1.820024369629526587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175675438599776612e+01,6.200726390011562899e+02,4.011241046747406891e-01,1.100000010988609489e+01,1.819878384227988869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175766347689777547e+01,6.200826389845965423e+02,4.011423034485373518e-01,1.100000010988609489e+01,1.819732398826451152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175857256779778481e+01,6.200926389680394095e+02,4.011605007624824415e-01,1.100000010988609489e+01,1.819586413424913434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.175948165869779416e+01,6.201026389514848915e+02,4.011786966165759027e-01,1.100000010988609489e+01,1.819440428023375717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176039074959780351e+01,6.201126389349331021e+02,4.011968910108177910e-01,1.100000010988609489e+01,1.819294442621837999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176129984049781285e+01,6.201226389183839274e+02,4.012150839452081064e-01,1.100000010988609489e+01,1.819148457220300281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176220893139782220e+01,6.201326389018374812e+02,4.012332754197467932e-01,1.100000010988609489e+01,1.819002471818762564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176311802229783154e+01,6.201426388852936498e+02,4.012514654344339071e-01,1.100000010988609489e+01,1.818856486417224846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176402711319784089e+01,6.201526388687524332e+02,4.012696539892693925e-01,1.100000010988609489e+01,1.818710501015687129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176493620409785024e+01,6.201626388522139450e+02,4.012878410842533050e-01,1.100000010988609489e+01,1.818564515614149411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176584529499785958e+01,6.201726388356780717e+02,4.013060267193855890e-01,1.100000010988609489e+01,1.818418530212611694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176675438589786893e+01,6.201826388191448132e+02,4.013242108946663000e-01,1.100000010988609489e+01,1.818272544811073976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176766347679787827e+01,6.201926388026142831e+02,4.013423936100953826e-01,1.100000010988609489e+01,1.818126559409536259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176857256769788762e+01,6.202026387860863679e+02,4.013605748656728367e-01,1.100000010988609489e+01,1.817980574007998541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.176948165859789697e+01,6.202126387695610674e+02,4.013787546613987178e-01,1.100000010988609489e+01,1.817834588606460824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177039074949790631e+01,6.202226387530384955e+02,4.013969329972729705e-01,1.100000010988609489e+01,1.817688603204923106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177129984039791566e+01,6.202326387365185383e+02,4.014151098732956502e-01,1.100000010988609489e+01,1.817542617803385389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177220893129792501e+01,6.202426387200011959e+02,4.014332852894667014e-01,1.100000010988609489e+01,1.817396632401847671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177311802219793435e+01,6.202526387034865820e+02,4.014514592457861797e-01,1.100000010988609489e+01,1.817250647000309954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177402711309794370e+01,6.202626386869745829e+02,4.014696317422540295e-01,1.100000010988609489e+01,1.817104661598772236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177493620399795304e+01,6.202726386704651986e+02,4.014878027788703063e-01,1.100000010988609489e+01,1.816958676197234519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177584529489796239e+01,6.202826386539585428e+02,4.015059723556349547e-01,1.100000010988609489e+01,1.816812690795696801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177675438579797174e+01,6.202926386374545018e+02,4.015241404725479746e-01,1.100000010988609489e+01,1.816666705394159084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177766347669798108e+01,6.203026386209530756e+02,4.015423071296094215e-01,1.100000010988609489e+01,1.816520719992621366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177857256759799043e+01,6.203126386044543779e+02,4.015604723268192400e-01,1.100000010988609489e+01,1.816374734591083649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.177948165849799977e+01,6.203226385879582949e+02,4.015786360641774855e-01,1.100000010988609489e+01,1.816228749189545931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178039074939800912e+01,6.203326385714648268e+02,4.015967983416841025e-01,1.100000010988609489e+01,1.816082763788008213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178129984029801847e+01,6.203426385549740871e+02,4.016149591593390911e-01,1.100000010988609489e+01,1.815936778386470496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178220893119802781e+01,6.203526385384859623e+02,4.016331185171425067e-01,1.100000010988609489e+01,1.815790792984932778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178311802209803716e+01,6.203626385220004522e+02,4.016512764150942938e-01,1.100000010988609489e+01,1.815644807583395061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178402711299804650e+01,6.203726385055176706e+02,4.016694328531944524e-01,1.100000010988609489e+01,1.815498822181857343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178493620389805585e+01,6.203826384890375039e+02,4.016875878314430381e-01,1.100000010988609489e+01,1.815352836780319626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178584529479806520e+01,6.203926384725599519e+02,4.017057413498399954e-01,1.100000010988609489e+01,1.815206851378781908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178675438569807454e+01,6.204026384560851284e+02,4.017238934083853241e-01,1.100000010988609489e+01,1.815060865977244191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178766347659808389e+01,6.204126384396129197e+02,4.017420440070790799e-01,1.100000010988609489e+01,1.814914880575706473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178857256749809324e+01,6.204226384231433258e+02,4.017601931459212072e-01,1.100000010988609489e+01,1.814768895174168756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.178948165839810258e+01,6.204326384066763467e+02,4.017783408249117061e-01,1.100000010988609489e+01,1.814622909772631038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179039074929811193e+01,6.204426383902120961e+02,4.017964870440506320e-01,1.100000010988609489e+01,1.814476924371093321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179129984019812127e+01,6.204526383737504602e+02,4.018146318033379294e-01,1.100000010988609489e+01,1.814330938969555603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179220893109813062e+01,6.204626383572914392e+02,4.018327751027735983e-01,1.100000010988609489e+01,1.814184953568017886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179311802199813997e+01,6.204726383408351467e+02,4.018509169423576943e-01,1.100000010988609489e+01,1.814038968166480168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179402711289814931e+01,6.204826383243814689e+02,4.018690573220901618e-01,1.100000010988609489e+01,1.813892982764942451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179493620379815866e+01,6.204926383079304060e+02,4.018871962419710009e-01,1.100000010988609489e+01,1.813746997363404733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179584529469816800e+01,6.205026382914820715e+02,4.019053337020002115e-01,1.100000010988609489e+01,1.813601011961867016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179675438559817735e+01,6.205126382750363518e+02,4.019234697021778491e-01,1.100000010988609489e+01,1.813455026560329298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179766347649818670e+01,6.205226382585932470e+02,4.019416042425038582e-01,1.100000010988609489e+01,1.813309041158791581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179857256739819604e+01,6.205326382421527569e+02,4.019597373229782389e-01,1.100000010988609489e+01,1.813163055757253863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.179948165829820539e+01,6.205426382257149953e+02,4.019778689436009911e-01,1.100000010988609489e+01,1.813017070355716145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180039074919821473e+01,6.205526382092798485e+02,4.019959991043721703e-01,1.100000010988609489e+01,1.812871084954178428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180129984009822408e+01,6.205626381928473165e+02,4.020141278052917211e-01,1.100000010988609489e+01,1.812725099552640710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180220893099823343e+01,6.205726381764175130e+02,4.020322550463596434e-01,1.100000010988609489e+01,1.812579114151102993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180311802189824277e+01,6.205826381599903243e+02,4.020503808275759372e-01,1.100000010988609489e+01,1.812433128749565275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180402711279825212e+01,6.205926381435657504e+02,4.020685051489406026e-01,1.100000010988609489e+01,1.812287143348027558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180493620369826147e+01,6.206026381271437913e+02,4.020866280104536949e-01,1.100000010988609489e+01,1.812141157946489840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180584529459827081e+01,6.206126381107245606e+02,4.021047494121151589e-01,1.100000010988609489e+01,1.811995172544952123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180675438549828016e+01,6.206226380943079448e+02,4.021228693539249943e-01,1.100000010988609489e+01,1.811849187143414405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180766347639828950e+01,6.206326380778939438e+02,4.021409878358832013e-01,1.100000010988609489e+01,1.811703201741876688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180857256729829885e+01,6.206426380614825575e+02,4.021591048579897798e-01,1.100000010988609489e+01,1.811557216340338970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.180948165819830820e+01,6.206526380450738998e+02,4.021772204202447298e-01,1.100000010988609489e+01,1.811411230938801253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181039074909831754e+01,6.206626380286678568e+02,4.021953345226481069e-01,1.100000010988609489e+01,1.811265245537263535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181129983999832689e+01,6.206726380122644287e+02,4.022134471651998555e-01,1.100000010988609489e+01,1.811119260135725818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181220893089833623e+01,6.206826379958636153e+02,4.022315583478999756e-01,1.100000010988609489e+01,1.810973274734188100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181311802179834558e+01,6.206926379794655304e+02,4.022496680707484673e-01,1.100000010988609489e+01,1.810827289332650383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181402711269835493e+01,6.207026379630700603e+02,4.022677763337453305e-01,1.100000010988609489e+01,1.810681303931112665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181493620359836427e+01,6.207126379466772050e+02,4.022858831368905652e-01,1.100000010988609489e+01,1.810535318529574948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181584529449837362e+01,6.207226379302869645e+02,4.023039884801841715e-01,1.100000010988609489e+01,1.810389333128037230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181675438539838296e+01,6.207326379138994525e+02,4.023220923636261492e-01,1.100000010988609489e+01,1.810243347726499513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181766347629839231e+01,6.207426378975145553e+02,4.023401947872165541e-01,1.100000010988609489e+01,1.810097362324961795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181857256719840166e+01,6.207526378811322729e+02,4.023582957509553304e-01,1.100000010988609489e+01,1.809951376923424077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.181948165809841100e+01,6.207626378647526053e+02,4.023763952548424783e-01,1.100000010988609489e+01,1.809805391521886360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182039074899842035e+01,6.207726378483756662e+02,4.023944932988779977e-01,1.100000010988609489e+01,1.809659406120348642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182129983989842970e+01,6.207826378320013418e+02,4.024125898830618886e-01,1.100000010988609489e+01,1.809513420718810925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182220893079843904e+01,6.207926378156296323e+02,4.024306850073941511e-01,1.100000010988609489e+01,1.809367435317273207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182311802169844839e+01,6.208026377992605376e+02,4.024487786718747850e-01,1.100000010988609489e+01,1.809221449915735490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182402711259845773e+01,6.208126377828941713e+02,4.024668708765037906e-01,1.100000010988609489e+01,1.809075464514197772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182493620349846708e+01,6.208226377665304199e+02,4.024849616212811676e-01,1.100000010988609489e+01,1.808929479112660055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182584529439847643e+01,6.208326377501692832e+02,4.025030509062069162e-01,1.100000010988609489e+01,1.808783493711122337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182675438529848577e+01,6.208426377338107613e+02,4.025211387312810363e-01,1.100000010988609489e+01,1.808637508309584620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182766347619849512e+01,6.208526377174549680e+02,4.025392250965035279e-01,1.100000010988609489e+01,1.808491522908046902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182857256709850446e+01,6.208626377011017894e+02,4.025573100018743911e-01,1.100000010988609489e+01,1.808345537506509185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.182948165799851381e+01,6.208726376847512256e+02,4.025753934473936257e-01,1.100000010988609489e+01,1.808199552104971467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183039074889852316e+01,6.208826376684032766e+02,4.025934754330612320e-01,1.100000010988609489e+01,1.808053566703433750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183129983979853250e+01,6.208926376520579424e+02,4.026115559588772097e-01,1.100000010988609489e+01,1.807907581301896032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183220893069854185e+01,6.209026376357153367e+02,4.026296350248415590e-01,1.100000010988609489e+01,1.807761595900358315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183311802159855119e+01,6.209126376193753458e+02,4.026477126309542798e-01,1.100000010988609489e+01,1.807615610498820597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183402711249856054e+01,6.209226376030379697e+02,4.026657887772153721e-01,1.100000010988609489e+01,1.807469625097282880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183493620339856989e+01,6.209326375867032084e+02,4.026838634636248360e-01,1.100000010988609489e+01,1.807323639695745162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183584529429857923e+01,6.209426375703711756e+02,4.027019366901826714e-01,1.100000010988609489e+01,1.807177654294207444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183675438519858858e+01,6.209526375540417575e+02,4.027200084568888783e-01,1.100000010988609489e+01,1.807031668892669727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183766347609859793e+01,6.209626375377149543e+02,4.027380787637434567e-01,1.100000010988609489e+01,1.806885683491132009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183857256699860727e+01,6.209726375213907659e+02,4.027561476107464067e-01,1.100000010988609489e+01,1.806739698089594292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.183948165789861662e+01,6.209826375050691922e+02,4.027742149978977282e-01,1.100000010988609489e+01,1.806593712688056574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184039074879862596e+01,6.209926374887503471e+02,4.027922809251974212e-01,1.100000010988609489e+01,1.806447727286518857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184129983969863531e+01,6.210026374724341167e+02,4.028103453926454858e-01,1.100000010988609489e+01,1.806301741884981139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184220893059864466e+01,6.210126374561205012e+02,4.028284084002418663e-01,1.100000010988609489e+01,1.806155756483443422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184311802149865400e+01,6.210226374398095004e+02,4.028464699479866185e-01,1.100000010988609489e+01,1.806009771081905704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184402711239866335e+01,6.210326374235011144e+02,4.028645300358797421e-01,1.100000010988609489e+01,1.805863785680367987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184493620329867269e+01,6.210426374071953433e+02,4.028825886639212372e-01,1.100000010988609489e+01,1.805717800278830269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184584529419868204e+01,6.210526373908923006e+02,4.029006458321111039e-01,1.100000010988609489e+01,1.805571814877292552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184675438509869139e+01,6.210626373745918727e+02,4.029187015404493422e-01,1.100000010988609489e+01,1.805425829475754834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184766347599870073e+01,6.210726373582940596e+02,4.029367557889359519e-01,1.100000010988609489e+01,1.805279844074217117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184857256689871008e+01,6.210826373419988613e+02,4.029548085775709332e-01,1.100000010988609489e+01,1.805133858672679399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.184948165779871943e+01,6.210926373257062778e+02,4.029728599063542305e-01,1.100000010988609489e+01,1.804987873271141682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185039074869872877e+01,6.211026373094164228e+02,4.029909097752858993e-01,1.100000010988609489e+01,1.804841887869603964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185129983959873812e+01,6.211126372931291826e+02,4.030089581843659396e-01,1.100000010988609489e+01,1.804695902468066247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185220893049874746e+01,6.211226372768445572e+02,4.030270051335943515e-01,1.100000010988609489e+01,1.804549917066528529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185311802139875681e+01,6.211326372605625465e+02,4.030450506229711349e-01,1.100000010988609489e+01,1.804403931664990812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185402711229876616e+01,6.211426372442831507e+02,4.030630946524962899e-01,1.100000010988609489e+01,1.804257946263453094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185493620319877550e+01,6.211526372280063697e+02,4.030811372221697608e-01,1.100000010988609489e+01,1.804111960861915376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185584529409878485e+01,6.211626372117323172e+02,4.030991783319916033e-01,1.100000010988609489e+01,1.803965975460377659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185675438499879419e+01,6.211726371954608794e+02,4.031172179819618173e-01,1.100000010988609489e+01,1.803819990058839941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185766347589880354e+01,6.211826371791920565e+02,4.031352561720804029e-01,1.100000010988609489e+01,1.803674004657302224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185857256679881289e+01,6.211926371629258483e+02,4.031532929023473599e-01,1.100000010988609489e+01,1.803528019255764506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.185948165769882223e+01,6.212026371466622550e+02,4.031713281727626330e-01,1.100000010988609489e+01,1.803382033854226789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186039074859883158e+01,6.212126371304012764e+02,4.031893619833262776e-01,1.100000010988609489e+01,1.803236048452689071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186129983949884092e+01,6.212226371141430263e+02,4.032073943340382938e-01,1.100000010988609489e+01,1.803090063051151354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186220893039885027e+01,6.212326370978873911e+02,4.032254252248986814e-01,1.100000010988609489e+01,1.802944077649613636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186311802129885962e+01,6.212426370816343706e+02,4.032434546559073851e-01,1.100000010988609489e+01,1.802798092248075919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186402711219886896e+01,6.212526370653839649e+02,4.032614826270644603e-01,1.100000010988609489e+01,1.802652106846538201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186493620309887831e+01,6.212626370491361740e+02,4.032795091383699071e-01,1.100000010988609489e+01,1.802506121445000484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186584529399888766e+01,6.212726370328909979e+02,4.032975341898237254e-01,1.100000010988609489e+01,1.802360136043462766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186675438489889700e+01,6.212826370166484367e+02,4.033155577814258597e-01,1.100000010988609489e+01,1.802214150641925049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186766347579890635e+01,6.212926370004086039e+02,4.033335799131763655e-01,1.100000010988609489e+01,1.802068165240387331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186857256669891569e+01,6.213026369841713858e+02,4.033516005850752428e-01,1.100000010988609489e+01,1.801922179838849614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.186948165759892504e+01,6.213126369679367826e+02,4.033696197971224362e-01,1.100000010988609489e+01,1.801776194437311896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187039074849893439e+01,6.213226369517047942e+02,4.033876375493180011e-01,1.100000010988609489e+01,1.801630209035774179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187129983939894373e+01,6.213326369354754206e+02,4.034056538416619375e-01,1.100000010988609489e+01,1.801484223634236461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187220893029895308e+01,6.213426369192486618e+02,4.034236686741541900e-01,1.100000010988609489e+01,1.801338238232698744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187311802119896242e+01,6.213526369030245178e+02,4.034416820467948139e-01,1.100000010988609489e+01,1.801192252831161026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187402711209897177e+01,6.213626368868031022e+02,4.034596939595838094e-01,1.100000010988609489e+01,1.801046267429623308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187493620299898112e+01,6.213726368705843015e+02,4.034777044125211209e-01,1.100000010988609489e+01,1.800900282028085591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187584529389899046e+01,6.213826368543681156e+02,4.034957134056068040e-01,1.100000010988609489e+01,1.800754296626547873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187675438479899981e+01,6.213926368381545444e+02,4.035137209388408586e-01,1.100000010988609489e+01,1.800608311225010156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187766347569900915e+01,6.214026368219435881e+02,4.035317270122232292e-01,1.100000010988609489e+01,1.800462325823472438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187857256659901850e+01,6.214126368057352465e+02,4.035497316257539713e-01,1.100000010988609489e+01,1.800316340421934721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.187948165749902785e+01,6.214226367895295198e+02,4.035677347794330849e-01,1.100000010988609489e+01,1.800170355020397003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188039074839903719e+01,6.214326367733264078e+02,4.035857364732605146e-01,1.100000010988609489e+01,1.800024369618859286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188129983929904654e+01,6.214426367571260243e+02,4.036037367072363158e-01,1.100000010988609489e+01,1.799878384217321568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188220893019905589e+01,6.214526367409282557e+02,4.036217354813604330e-01,1.100000010988609489e+01,1.799732398815783851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188311802109906523e+01,6.214626367247331018e+02,4.036397327956329217e-01,1.100000010988609489e+01,1.799586413414246133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188402711199907458e+01,6.214726367085405627e+02,4.036577286500537820e-01,1.100000010988609489e+01,1.799440428012708416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188493620289908392e+01,6.214826366923506384e+02,4.036757230446229583e-01,1.100000010988609489e+01,1.799294442611170698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188584529379909327e+01,6.214926366761633290e+02,4.036937159793405061e-01,1.100000010988609489e+01,1.799148457209632981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188675438469910262e+01,6.215026366599786343e+02,4.037117074542063699e-01,1.100000010988609489e+01,1.799002471808095263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188766347559911196e+01,6.215126366437965544e+02,4.037296974692206053e-01,1.100000010988609489e+01,1.798856486406557546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188857256649912131e+01,6.215226366276170893e+02,4.037476860243832122e-01,1.100000010988609489e+01,1.798710501005019828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.188948165739913065e+01,6.215326366114403527e+02,4.037656731196941351e-01,1.100000010988609489e+01,1.798564515603482111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189039074829914000e+01,6.215426365952662309e+02,4.037836587551534295e-01,1.100000010988609489e+01,1.798418530201944393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189129983919914935e+01,6.215526365790947239e+02,4.038016429307610400e-01,1.100000010988609489e+01,1.798272544800406676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189220893009915869e+01,6.215626365629258316e+02,4.038196256465170220e-01,1.100000010988609489e+01,1.798126559398868958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189311802099916804e+01,6.215726365467595542e+02,4.038376069024213200e-01,1.100000010988609489e+01,1.797980573997331240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189402711189917738e+01,6.215826365305958916e+02,4.038555866984739895e-01,1.100000010988609489e+01,1.797834588595793523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189493620279918673e+01,6.215926365144348438e+02,4.038735650346749750e-01,1.100000010988609489e+01,1.797688603194255805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189584529369919608e+01,6.216026364982764107e+02,4.038915419110243321e-01,1.100000010988609489e+01,1.797542617792718088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189675438459920542e+01,6.216126364821205925e+02,4.039095173275220052e-01,1.100000010988609489e+01,1.797396632391180370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189766347549921477e+01,6.216226364659673891e+02,4.039274912841680498e-01,1.100000010988609489e+01,1.797250646989642653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189857256639922412e+01,6.216326364498168005e+02,4.039454637809624105e-01,1.100000010988609489e+01,1.797104661588104935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.189948165729923346e+01,6.216426364336688266e+02,4.039634348179051426e-01,1.100000010988609489e+01,1.796958676186567218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190039074819924281e+01,6.216526364175235813e+02,4.039814043949961908e-01,1.100000010988609489e+01,1.796812690785029500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190129983909925215e+01,6.216626364013809507e+02,4.039993725122356105e-01,1.100000010988609489e+01,1.796666705383491783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190220892999926150e+01,6.216726363852409349e+02,4.040173391696233463e-01,1.100000010988609489e+01,1.796520719981954065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190311802089927085e+01,6.216826363691035340e+02,4.040353043671593980e-01,1.100000010988609489e+01,1.796374734580416348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190402711179928019e+01,6.216926363529687478e+02,4.040532681048438213e-01,1.100000010988609489e+01,1.796228749178878630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190493620269928954e+01,6.217026363368365764e+02,4.040712303826765606e-01,1.100000010988609489e+01,1.796082763777340913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190584529359929888e+01,6.217126363207070199e+02,4.040891912006576714e-01,1.100000010988609489e+01,1.795936778375803195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190675438449930823e+01,6.217226363045800781e+02,4.041071505587870982e-01,1.100000010988609489e+01,1.795790792974265478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190766347539931758e+01,6.217326362884557511e+02,4.041251084570648966e-01,1.100000010988609489e+01,1.795644807572727760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190857256629932692e+01,6.217426362723340389e+02,4.041430648954910110e-01,1.100000010988609489e+01,1.795498822171190043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.190948165719933627e+01,6.217526362562149416e+02,4.041610198740654414e-01,1.100000010988609489e+01,1.795352836769652325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191039074809934561e+01,6.217626362400984590e+02,4.041789733927882433e-01,1.100000010988609489e+01,1.795206851368114608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191129983899935496e+01,6.217726362239845912e+02,4.041969254516593613e-01,1.100000010988609489e+01,1.795060865966576890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191220892989936431e+01,6.217826362078733382e+02,4.042148760506788507e-01,1.100000010988609489e+01,1.794914880565039172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191311802079937365e+01,6.217926361917647000e+02,4.042328251898466562e-01,1.100000010988609489e+01,1.794768895163501455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191402711169938300e+01,6.218026361756586766e+02,4.042507728691627777e-01,1.100000010988609489e+01,1.794622909761963737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191493620259939235e+01,6.218126361595552680e+02,4.042687190886272708e-01,1.100000010988609489e+01,1.794476924360426020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191584529349940169e+01,6.218226361434545879e+02,4.042866638482400798e-01,1.100000010988609489e+01,1.794330938958888302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191675438439941104e+01,6.218326361273565226e+02,4.043046071480012049e-01,1.100000010988609489e+01,1.794184953557350585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191766347529942038e+01,6.218426361112610721e+02,4.043225489879107015e-01,1.100000010988609489e+01,1.794038968155812867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191857256619942973e+01,6.218526360951682364e+02,4.043404893679685141e-01,1.100000010988609489e+01,1.793892982754275150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.191948165709943908e+01,6.218626360790780154e+02,4.043584282881746428e-01,1.100000010988609489e+01,1.793746997352737432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192039074799944842e+01,6.218726360629904093e+02,4.043763657485291430e-01,1.100000010988609489e+01,1.793601011951199715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192129983889945777e+01,6.218826360469054180e+02,4.043943017490319591e-01,1.100000010988609489e+01,1.793455026549661997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192220892979946711e+01,6.218926360308230414e+02,4.044122362896830913e-01,1.100000010988609489e+01,1.793309041148124280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192311802069947646e+01,6.219026360147432797e+02,4.044301693704825396e-01,1.100000010988609489e+01,1.793163055746586562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192402711159948581e+01,6.219126359986661328e+02,4.044481009914303593e-01,1.100000010988609489e+01,1.793017070345048845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192493620249949515e+01,6.219226359825916006e+02,4.044660311525264951e-01,1.100000010988609489e+01,1.792871084943511127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192584529339950450e+01,6.219326359665196833e+02,4.044839598537709469e-01,1.100000010988609489e+01,1.792725099541973410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192675438429951384e+01,6.219426359504503807e+02,4.045018870951637702e-01,1.100000010988609489e+01,1.792579114140435692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192766347519952319e+01,6.219526359343836930e+02,4.045198128767049095e-01,1.100000010988609489e+01,1.792433128738897975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192857256609953254e+01,6.219626359183196200e+02,4.045377371983943648e-01,1.100000010988609489e+01,1.792287143337360257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.192948165699954188e+01,6.219726359022581619e+02,4.045556600602321362e-01,1.100000010988609489e+01,1.792141157935822540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193039074789955123e+01,6.219826358861993185e+02,4.045735814622182791e-01,1.100000010988609489e+01,1.791995172534284822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193129983879956058e+01,6.219926358701430900e+02,4.045915014043527380e-01,1.100000010988609489e+01,1.791849187132747104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193220892969956992e+01,6.220026358540894762e+02,4.046094198866355129e-01,1.100000010988609489e+01,1.791703201731209387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193311802059957927e+01,6.220126358380384772e+02,4.046273369090666039e-01,1.100000010988609489e+01,1.791557216329671669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193402711149958861e+01,6.220226358219900931e+02,4.046452524716460109e-01,1.100000010988609489e+01,1.791411230928133952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193493620239959796e+01,6.220326358059443237e+02,4.046631665743737893e-01,1.100000010988609489e+01,1.791265245526596234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193584529329960731e+01,6.220426357899011691e+02,4.046810792172498839e-01,1.100000010988609489e+01,1.791119260125058517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193675438419961665e+01,6.220526357738606293e+02,4.046989904002742944e-01,1.100000010988609489e+01,1.790973274723520799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193766347509962600e+01,6.220626357578227044e+02,4.047169001234470209e-01,1.100000010988609489e+01,1.790827289321983082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193857256599963534e+01,6.220726357417873942e+02,4.047348083867680635e-01,1.100000010988609489e+01,1.790681303920445364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.193948165689964469e+01,6.220826357257546988e+02,4.047527151902374776e-01,1.100000010988609489e+01,1.790535318518907647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194039074779965404e+01,6.220926357097246182e+02,4.047706205338552077e-01,1.100000010988609489e+01,1.790389333117369929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194129983869966338e+01,6.221026356936971524e+02,4.047885244176212538e-01,1.100000010988609489e+01,1.790243347715832212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194220892959967273e+01,6.221126356776723014e+02,4.048064268415356159e-01,1.100000010988609489e+01,1.790097362314294494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194311802049968207e+01,6.221226356616500652e+02,4.048243278055982941e-01,1.100000010988609489e+01,1.789951376912756777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194402711139969142e+01,6.221326356456304438e+02,4.048422273098092883e-01,1.100000010988609489e+01,1.789805391511219059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194493620229970077e+01,6.221426356296134372e+02,4.048601253541685985e-01,1.100000010988609489e+01,1.789659406109681342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194584529319971011e+01,6.221526356135990454e+02,4.048780219386762802e-01,1.100000010988609489e+01,1.789513420708143624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194675438409971946e+01,6.221626355975872684e+02,4.048959170633322779e-01,1.100000010988609489e+01,1.789367435306605907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194766347499972881e+01,6.221726355815781062e+02,4.049138107281365917e-01,1.100000010988609489e+01,1.789221449905068189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194857256589973815e+01,6.221826355655715588e+02,4.049317029330892215e-01,1.100000010988609489e+01,1.789075464503530472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.194948165679974750e+01,6.221926355495676262e+02,4.049495936781901673e-01,1.100000010988609489e+01,1.788929479101992754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195039074769975684e+01,6.222026355335663084e+02,4.049674829634394291e-01,1.100000010988609489e+01,1.788783493700455036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195129983859976619e+01,6.222126355175676053e+02,4.049853707888370069e-01,1.100000010988609489e+01,1.788637508298917319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195220892949977554e+01,6.222226355015715171e+02,4.050032571543829008e-01,1.100000010988609489e+01,1.788491522897379601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195311802039978488e+01,6.222326354855780437e+02,4.050211420600771106e-01,1.100000010988609489e+01,1.788345537495841884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195402711129979423e+01,6.222426354695871851e+02,4.050390255059196365e-01,1.100000010988609489e+01,1.788199552094304166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195493620219980357e+01,6.222526354535989412e+02,4.050569074919104784e-01,1.100000010988609489e+01,1.788053566692766449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195584529309981292e+01,6.222626354376133122e+02,4.050747880180496363e-01,1.100000010988609489e+01,1.787907581291228731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195675438399982227e+01,6.222726354216302980e+02,4.050926670843371102e-01,1.100000010988609489e+01,1.787761595889691014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195766347489983161e+01,6.222826354056498985e+02,4.051105446907729002e-01,1.100000010988609489e+01,1.787615610488153296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195857256579984096e+01,6.222926353896720002e+02,4.051284208373570062e-01,1.100000010988609489e+01,1.787469625086615579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.195948165669985030e+01,6.223026353736967167e+02,4.051462955240894837e-01,1.100000010988609489e+01,1.787323639685077861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196039074759985965e+01,6.223126353577240479e+02,4.051641687509702772e-01,1.100000010988609489e+01,1.787177654283540144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196129983849986900e+01,6.223226353417539940e+02,4.051820405179993867e-01,1.100000010988609489e+01,1.787031668882002426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196220892939987834e+01,6.223326353257865549e+02,4.051999108251768122e-01,1.100000010988609489e+01,1.786885683480464709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196311802029988769e+01,6.223426353098217305e+02,4.052177796725025538e-01,1.100000010988609489e+01,1.786739698078926991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196402711119989704e+01,6.223526352938595210e+02,4.052356470599765559e-01,1.100000010988609489e+01,1.786593712677389274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196493620209990638e+01,6.223626352778999262e+02,4.052535129875988740e-01,1.100000010988609489e+01,1.786447727275851556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196584529299991573e+01,6.223726352619429463e+02,4.052713774553695081e-01,1.100000010988609489e+01,1.786301741874313839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196675438389992507e+01,6.223826352459885811e+02,4.052892404632884582e-01,1.100000010988609489e+01,1.786155756472776121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196766347479993442e+01,6.223926352300368308e+02,4.053071020113557243e-01,1.100000010988609489e+01,1.786009771071238404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196857256569994377e+01,6.224026352140876952e+02,4.053249620995713065e-01,1.100000010988609489e+01,1.785863785669700686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.196948165659995311e+01,6.224126351981411744e+02,4.053428207279352047e-01,1.100000010988609489e+01,1.785717800268162968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197039074749996246e+01,6.224226351821972685e+02,4.053606778964474189e-01,1.100000010988609489e+01,1.785571814866625251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197129983839997180e+01,6.224326351662559773e+02,4.053785336051079491e-01,1.100000010988609489e+01,1.785425829465087533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197220892929998115e+01,6.224426351503173009e+02,4.053963878539167953e-01,1.100000010988609489e+01,1.785279844063549816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197311802019999050e+01,6.224526351343812394e+02,4.054142406428739576e-01,1.100000010988609489e+01,1.785133858662012098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197402711109999984e+01,6.224626351184476789e+02,4.054320919719794358e-01,1.100000010988609489e+01,1.784987873260474381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197493620200000919e+01,6.224726351025167332e+02,4.054499418412332301e-01,1.100000010988609489e+01,1.784841887858936663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197584529290001853e+01,6.224826350865884024e+02,4.054677902506353404e-01,1.100000010988609489e+01,1.784695902457398946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197675438380002788e+01,6.224926350706626863e+02,4.054856372001857667e-01,1.100000010988609489e+01,1.784549917055861228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197766347470003723e+01,6.225026350547395850e+02,4.055034826898844535e-01,1.100000010988609489e+01,1.784403931654323511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197857256560004657e+01,6.225126350388190986e+02,4.055213267197314564e-01,1.100000010988609489e+01,1.784257946252785793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.197948165650005592e+01,6.225226350229012269e+02,4.055391692897267752e-01,1.100000010988609489e+01,1.784111960851248076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198039074740006527e+01,6.225326350069859700e+02,4.055570103998704101e-01,1.100000010988609489e+01,1.783965975449710358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198129983830007461e+01,6.225426349910733279e+02,4.055748500501623610e-01,1.100000010988609489e+01,1.783819990048172641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198220892920008396e+01,6.225526349751633006e+02,4.055926882406026279e-01,1.100000010988609489e+01,1.783674004646634923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198311802010009330e+01,6.225626349592558881e+02,4.056105249711912109e-01,1.100000010988609489e+01,1.783528019245097206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198402711100010265e+01,6.225726349433509768e+02,4.056283602419280543e-01,1.100000010988609489e+01,1.783382033843559488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198493620190011200e+01,6.225826349274486802e+02,4.056461940528132137e-01,1.100000010988609489e+01,1.783236048442021771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198584529280012134e+01,6.225926349115489984e+02,4.056640264038466892e-01,1.100000010988609489e+01,1.783090063040484053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198675438370013069e+01,6.226026348956519314e+02,4.056818572950284807e-01,1.100000010988609489e+01,1.782944077638946336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198766347460014003e+01,6.226126348797574792e+02,4.056996867263585882e-01,1.100000010988609489e+01,1.782798092237408618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198857256550014938e+01,6.226226348638656418e+02,4.057175146978369562e-01,1.100000010988609489e+01,1.782652106835870900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.198948165640015873e+01,6.226326348479764192e+02,4.057353412094636402e-01,1.100000010988609489e+01,1.782506121434333183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199039074730016807e+01,6.226426348320898114e+02,4.057531662612386403e-01,1.100000010988609489e+01,1.782360136032795465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199129983820017742e+01,6.226526348162058184e+02,4.057709898531619563e-01,1.100000010988609489e+01,1.782214150631257748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199220892910018677e+01,6.226626348003244402e+02,4.057888119852335884e-01,1.100000010988609489e+01,1.782068165229720030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199311802000019611e+01,6.226726347844455631e+02,4.058066326574534810e-01,1.100000010988609489e+01,1.781922179828182313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199402711090020546e+01,6.226826347685693008e+02,4.058244518698216896e-01,1.100000010988609489e+01,1.781776194426644595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199493620180021480e+01,6.226926347526956533e+02,4.058422696223382142e-01,1.100000010988609489e+01,1.781630209025106878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199584529270022415e+01,6.227026347368246206e+02,4.058600859150030549e-01,1.100000010988609489e+01,1.781484223623569160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199675438360023350e+01,6.227126347209562027e+02,4.058779007478161560e-01,1.100000010988609489e+01,1.781338238222031443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199766347450024284e+01,6.227226347050903996e+02,4.058957141207775732e-01,1.100000010988609489e+01,1.781192252820493725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199857256540025219e+01,6.227326346892272113e+02,4.059135260338873064e-01,1.100000010988609489e+01,1.781046267418956008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.199948165630026153e+01,6.227426346733666378e+02,4.059313364871453000e-01,1.100000010988609489e+01,1.780900282017418290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200039074720027088e+01,6.227526346575085654e+02,4.059491454805516097e-01,1.100000010988609489e+01,1.780754296615880573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200129983810028023e+01,6.227626346416531078e+02,4.059669530141062355e-01,1.100000010988609489e+01,1.780608311214342855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200220892900028957e+01,6.227726346258002650e+02,4.059847590878091772e-01,1.100000010988609489e+01,1.780462325812805138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200311801990029892e+01,6.227826346099500370e+02,4.060025637016603794e-01,1.100000010988609489e+01,1.780316340411267420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200402711080030826e+01,6.227926345941024238e+02,4.060203668556598977e-01,1.100000010988609489e+01,1.780170355009729703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200493620170031761e+01,6.228026345782574253e+02,4.060381685498077320e-01,1.100000010988609489e+01,1.780024369608191985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200584529260032696e+01,6.228126345624150417e+02,4.060559687841038268e-01,1.100000010988609489e+01,1.779878384206654268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200675438350033630e+01,6.228226345465751592e+02,4.060737675585482376e-01,1.100000010988609489e+01,1.779732398805116550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200766347440034565e+01,6.228326345307378915e+02,4.060915648731409644e-01,1.100000010988609489e+01,1.779586413403578832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200857256530035500e+01,6.228426345149032386e+02,4.061093607278819517e-01,1.100000010988609489e+01,1.779440428002041115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.200948165620036434e+01,6.228526344990712005e+02,4.061271551227712551e-01,1.100000010988609489e+01,1.779294442600503397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201039074710037369e+01,6.228626344832417772e+02,4.061449480578088744e-01,1.100000010988609489e+01,1.779148457198965680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201129983800038303e+01,6.228726344674149686e+02,4.061627395329947543e-01,1.100000010988609489e+01,1.779002471797427962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201220892890039238e+01,6.228826344515907749e+02,4.061805295483289502e-01,1.100000010988609489e+01,1.778856486395890245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201311801980040173e+01,6.228926344357690823e+02,4.061983181038114066e-01,1.100000010988609489e+01,1.778710500994352527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201402711070041107e+01,6.229026344199500045e+02,4.062161051994421790e-01,1.100000010988609489e+01,1.778564515592814810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201493620160042042e+01,6.229126344041335415e+02,4.062338908352212674e-01,1.100000010988609489e+01,1.778418530191277092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201584529250042976e+01,6.229226343883196932e+02,4.062516750111486163e-01,1.100000010988609489e+01,1.778272544789739375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201675438340043911e+01,6.229326343725084598e+02,4.062694577272242813e-01,1.100000010988609489e+01,1.778126559388201657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201766347430044846e+01,6.229426343566998412e+02,4.062872389834482068e-01,1.100000010988609489e+01,1.777980573986663940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201857256520045780e+01,6.229526343408937237e+02,4.063050187798204482e-01,1.100000010988609489e+01,1.777834588585126222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.201948165610046715e+01,6.229626343250902210e+02,4.063227971163409502e-01,1.100000010988609489e+01,1.777688603183588505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202039074700047649e+01,6.229726343092893330e+02,4.063405739930097682e-01,1.100000010988609489e+01,1.777542617782050787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202129983790048584e+01,6.229826342934910599e+02,4.063583494098269022e-01,1.100000010988609489e+01,1.777396632380513070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202220892880049519e+01,6.229926342776954016e+02,4.063761233667922967e-01,1.100000010988609489e+01,1.777250646978975352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202311801970050453e+01,6.230026342619023580e+02,4.063938958639060073e-01,1.100000010988609489e+01,1.777104661577437635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202402711060051388e+01,6.230126342461118156e+02,4.064116669011679783e-01,1.100000010988609489e+01,1.776958676175899917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202493620150052323e+01,6.230226342303238880e+02,4.064294364785782654e-01,1.100000010988609489e+01,1.776812690774362199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202584529240053257e+01,6.230326342145385752e+02,4.064472045961368130e-01,1.100000010988609489e+01,1.776666705372824482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202675438330054192e+01,6.230426341987558772e+02,4.064649712538436765e-01,1.100000010988609489e+01,1.776520719971286764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202766347420055126e+01,6.230526341829757939e+02,4.064827364516988006e-01,1.100000010988609489e+01,1.776374734569749047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202857256510056061e+01,6.230626341671982118e+02,4.065005001897022407e-01,1.100000010988609489e+01,1.776228749168211329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.202948165600056996e+01,6.230726341514232445e+02,4.065182624678539414e-01,1.100000010988609489e+01,1.776082763766673612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203039074690057930e+01,6.230826341356508919e+02,4.065360232861539580e-01,1.100000010988609489e+01,1.775936778365135894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203129983780058865e+01,6.230926341198811542e+02,4.065537826446022351e-01,1.100000010988609489e+01,1.775790792963598177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203220892870059799e+01,6.231026341041140313e+02,4.065715405431988283e-01,1.100000010988609489e+01,1.775644807562060459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203311801960060734e+01,6.231126340883494095e+02,4.065892969819436820e-01,1.100000010988609489e+01,1.775498822160522742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203402711050061669e+01,6.231226340725874024e+02,4.066070519608368516e-01,1.100000010988609489e+01,1.775352836758985024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203493620140062603e+01,6.231326340568280102e+02,4.066248054798782818e-01,1.100000010988609489e+01,1.775206851357447307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203584529230063538e+01,6.231426340410712328e+02,4.066425575390679725e-01,1.100000010988609489e+01,1.775060865955909589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203675438320064472e+01,6.231526340253170702e+02,4.066603081384059792e-01,1.100000010988609489e+01,1.774914880554371872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203766347410065407e+01,6.231626340095654086e+02,4.066780572778922465e-01,1.100000010988609489e+01,1.774768895152834154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203857256500066342e+01,6.231726339938163619e+02,4.066958049575268297e-01,1.100000010988609489e+01,1.774622909751296437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.203948165590067276e+01,6.231826339780699300e+02,4.067135511773096734e-01,1.100000010988609489e+01,1.774476924349758719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204039074680068211e+01,6.231926339623261129e+02,4.067312959372408332e-01,1.100000010988609489e+01,1.774330938948221002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204129983770069146e+01,6.232026339465849105e+02,4.067490392373202535e-01,1.100000010988609489e+01,1.774184953546683284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204220892860070080e+01,6.232126339308462093e+02,4.067667810775479342e-01,1.100000010988609489e+01,1.774038968145145567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204311801950071015e+01,6.232226339151101229e+02,4.067845214579239310e-01,1.100000010988609489e+01,1.773892982743607849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204402711040071949e+01,6.232326338993766512e+02,4.068022603784481883e-01,1.100000010988609489e+01,1.773746997342070131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204493620130072884e+01,6.232426338836457944e+02,4.068199978391207616e-01,1.100000010988609489e+01,1.773601011940532414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204584529220073819e+01,6.232526338679175524e+02,4.068377338399415954e-01,1.100000010988609489e+01,1.773455026538994696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204675438310074753e+01,6.232626338521918115e+02,4.068554683809106898e-01,1.100000010988609489e+01,1.773309041137456979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204766347400075688e+01,6.232726338364686853e+02,4.068732014620281001e-01,1.100000010988609489e+01,1.773163055735919261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204857256490076622e+01,6.232826338207481740e+02,4.068909330832937710e-01,1.100000010988609489e+01,1.773017070334381544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.204948165580077557e+01,6.232926338050302775e+02,4.069086632447077023e-01,1.100000010988609489e+01,1.772871084932843826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205039074670078492e+01,6.233026337893148821e+02,4.069263919462699497e-01,1.100000010988609489e+01,1.772725099531306109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205129983760079426e+01,6.233126337736021014e+02,4.069441191879804576e-01,1.100000010988609489e+01,1.772579114129768391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205220892850080361e+01,6.233226337578919356e+02,4.069618449698392260e-01,1.100000010988609489e+01,1.772433128728230674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205311801940081295e+01,6.233326337421843846e+02,4.069795692918463104e-01,1.100000010988609489e+01,1.772287143326692956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205402711030082230e+01,6.233426337264793347e+02,4.069972921540016553e-01,1.100000010988609489e+01,1.772141157925155239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205493620120083165e+01,6.233526337107768995e+02,4.070150135563052607e-01,1.100000010988609489e+01,1.771995172523617521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205584529210084099e+01,6.233626336950770792e+02,4.070327334987571821e-01,1.100000010988609489e+01,1.771849187122079804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205675438300085034e+01,6.233726336793798737e+02,4.070504519813573641e-01,1.100000010988609489e+01,1.771703201720542086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205766347390085969e+01,6.233826336636851693e+02,4.070681690041058065e-01,1.100000010988609489e+01,1.771557216319004369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205857256480086903e+01,6.233926336479930796e+02,4.070858845670025095e-01,1.100000010988609489e+01,1.771411230917466651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.205948165570087838e+01,6.234026336323036048e+02,4.071035986700475284e-01,1.100000010988609489e+01,1.771265245515928934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206039074660088772e+01,6.234126336166167448e+02,4.071213113132408079e-01,1.100000010988609489e+01,1.771119260114391216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206129983750089707e+01,6.234226336009323859e+02,4.071390224965823479e-01,1.100000010988609489e+01,1.770973274712853499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206220892840090642e+01,6.234326335852506418e+02,4.071567322200721484e-01,1.100000010988609489e+01,1.770827289311315781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206311801930091576e+01,6.234426335695715125e+02,4.071744404837102649e-01,1.100000010988609489e+01,1.770681303909778063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206402711020092511e+01,6.234526335538949979e+02,4.071921472874966419e-01,1.100000010988609489e+01,1.770535318508240346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206493620110093445e+01,6.234626335382209845e+02,4.072098526314312794e-01,1.100000010988609489e+01,1.770389333106702628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206584529200094380e+01,6.234726335225495859e+02,4.072275565155141774e-01,1.100000010988609489e+01,1.770243347705164911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206675438290095315e+01,6.234826335068808021e+02,4.072452589397453360e-01,1.100000010988609489e+01,1.770097362303627193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206766347380096249e+01,6.234926334912146331e+02,4.072629599041248105e-01,1.100000010988609489e+01,1.769951376902089476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206857256470097184e+01,6.235026334755509652e+02,4.072806594086525456e-01,1.100000010988609489e+01,1.769805391500551758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.206948165560098118e+01,6.235126334598899120e+02,4.072983574533285411e-01,1.100000010988609489e+01,1.769659406099014041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207039074650099053e+01,6.235226334442314737e+02,4.073160540381527972e-01,1.100000010988609489e+01,1.769513420697476323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207129983740099988e+01,6.235326334285755365e+02,4.073337491631253138e-01,1.100000010988609489e+01,1.769367435295938606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207220892830100922e+01,6.235426334129222141e+02,4.073514428282461464e-01,1.100000010988609489e+01,1.769221449894400888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207311801920101857e+01,6.235526333972715065e+02,4.073691350335152395e-01,1.100000010988609489e+01,1.769075464492863171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207402711010102792e+01,6.235626333816234137e+02,4.073868257789325931e-01,1.100000010988609489e+01,1.768929479091325453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207493620100103726e+01,6.235726333659778220e+02,4.074045150644982072e-01,1.100000010988609489e+01,1.768783493689787736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207584529190104661e+01,6.235826333503348451e+02,4.074222028902120818e-01,1.100000010988609489e+01,1.768637508288250018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207675438280105595e+01,6.235926333346944830e+02,4.074398892560742169e-01,1.100000010988609489e+01,1.768491522886712301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207766347370106530e+01,6.236026333190566220e+02,4.074575741620846125e-01,1.100000010988609489e+01,1.768345537485174583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207857256460107465e+01,6.236126333034213758e+02,4.074752576082433242e-01,1.100000010988609489e+01,1.768199552083636866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.207948165550108399e+01,6.236226332877887444e+02,4.074929395945502963e-01,1.100000010988609489e+01,1.768053566682099148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208039074640109334e+01,6.236326332721587278e+02,4.075106201210055290e-01,1.100000010988609489e+01,1.767907581280561431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208129983730110268e+01,6.236426332565312123e+02,4.075282991876090222e-01,1.100000010988609489e+01,1.767761595879023713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208220892820111203e+01,6.236526332409063116e+02,4.075459767943607758e-01,1.100000010988609489e+01,1.767615610477485995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208311801910112138e+01,6.236626332252840257e+02,4.075636529412607900e-01,1.100000010988609489e+01,1.767469625075948278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208402711000113072e+01,6.236726332096642409e+02,4.075813276283090647e-01,1.100000010988609489e+01,1.767323639674410560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208493620090114007e+01,6.236826331940470709e+02,4.075990008555055999e-01,1.100000010988609489e+01,1.767177654272872843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208584529180114941e+01,6.236926331784325157e+02,4.076166726228503956e-01,1.100000010988609489e+01,1.767031668871335125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208675438270115876e+01,6.237026331628204616e+02,4.076343429303434518e-01,1.100000010988609489e+01,1.766885683469797408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208766347360116811e+01,6.237126331472110223e+02,4.076520117779847685e-01,1.100000010988609489e+01,1.766739698068259690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208857256450117745e+01,6.237226331316041978e+02,4.076696791657744012e-01,1.100000010988609489e+01,1.766593712666721973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.208948165540118680e+01,6.237326331159999881e+02,4.076873450937122945e-01,1.100000010988609489e+01,1.766447727265184255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209039074630119615e+01,6.237426331003982796e+02,4.077050095617984482e-01,1.100000010988609489e+01,1.766301741863646538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209129983720120549e+01,6.237526330847991858e+02,4.077226725700328624e-01,1.100000010988609489e+01,1.766155756462108820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209220892810121484e+01,6.237626330692027068e+02,4.077403341184155372e-01,1.100000010988609489e+01,1.766009771060571103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209311801900122418e+01,6.237726330536087289e+02,4.077579942069464725e-01,1.100000010988609489e+01,1.765863785659033385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209402710990123353e+01,6.237826330380173658e+02,4.077756528356256682e-01,1.100000010988609489e+01,1.765717800257495668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209493620080124288e+01,6.237926330224286176e+02,4.077933100044531245e-01,1.100000010988609489e+01,1.765571814855957950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209584529170125222e+01,6.238026330068423704e+02,4.078109657134288413e-01,1.100000010988609489e+01,1.765425829454420233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209675438260126157e+01,6.238126329912587380e+02,4.078286199625528186e-01,1.100000010988609489e+01,1.765279844052882515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209766347350127091e+01,6.238226329756777204e+02,4.078462727518250563e-01,1.100000010988609489e+01,1.765133858651344798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209857256440128026e+01,6.238326329600992040e+02,4.078639240812455546e-01,1.100000010988609489e+01,1.764987873249807080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.209948165530128961e+01,6.238426329445233023e+02,4.078815739508143134e-01,1.100000010988609489e+01,1.764841887848269363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210039074620129895e+01,6.238526329289500154e+02,4.078992223605313328e-01,1.100000010988609489e+01,1.764695902446731645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210129983710130830e+01,6.238626329133792296e+02,4.079168693103965571e-01,1.100000010988609489e+01,1.764549917045193927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210220892800131764e+01,6.238726328978110587e+02,4.079345148004100419e-01,1.100000010988609489e+01,1.764403931643656210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210311801890132699e+01,6.238826328822455025e+02,4.079521588305717872e-01,1.100000010988609489e+01,1.764257946242118492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210402710980133634e+01,6.238926328666824475e+02,4.079698014008817930e-01,1.100000010988609489e+01,1.764111960840580775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210493620070134568e+01,6.239026328511220072e+02,4.079874425113400593e-01,1.100000010988609489e+01,1.763965975439043057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210584529160135503e+01,6.239126328355641817e+02,4.080050821619465862e-01,1.100000010988609489e+01,1.763819990037505340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210675438250136438e+01,6.239226328200088574e+02,4.080227203527013735e-01,1.100000010988609489e+01,1.763674004635967622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210766347340137372e+01,6.239326328044561478e+02,4.080403570836044214e-01,1.100000010988609489e+01,1.763528019234429905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210857256430138307e+01,6.239426327889060531e+02,4.080579923546557297e-01,1.100000010988609489e+01,1.763382033832892187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.210948165520139241e+01,6.239526327733584594e+02,4.080756261658552986e-01,1.100000010988609489e+01,1.763236048431354470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211039074610140176e+01,6.239626327578134806e+02,4.080932585172031279e-01,1.100000010988609489e+01,1.763090063029816752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211129983700141111e+01,6.239726327422710028e+02,4.081108894086992178e-01,1.100000010988609489e+01,1.762944077628279035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211220892790142045e+01,6.239826327267311399e+02,4.081285188403435127e-01,1.100000010988609489e+01,1.762798092226741317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211311801880142980e+01,6.239926327111938917e+02,4.081461468121360681e-01,1.100000010988609489e+01,1.762652106825203600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211402710970143914e+01,6.240026326956591447e+02,4.081637733240768839e-01,1.100000010988609489e+01,1.762506121423665882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211493620060144849e+01,6.240126326801270125e+02,4.081813983761659603e-01,1.100000010988609489e+01,1.762360136022128165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211584529150145784e+01,6.240226326645974950e+02,4.081990219684032972e-01,1.100000010988609489e+01,1.762214150620590447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211675438240146718e+01,6.240326326490704787e+02,4.082166441007888946e-01,1.100000010988609489e+01,1.762068165219052730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211766347330147653e+01,6.240426326335460772e+02,4.082342647733226970e-01,1.100000010988609489e+01,1.761922179817515012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211857256420148587e+01,6.240526326180241767e+02,4.082518839860047599e-01,1.100000010988609489e+01,1.761776194415977295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.211948165510149522e+01,6.240626326025048911e+02,4.082695017388350833e-01,1.100000010988609489e+01,1.761630209014439577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212039074600150457e+01,6.240726325869882203e+02,4.082871180318136672e-01,1.100000010988609489e+01,1.761484223612901859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212129983690151391e+01,6.240826325714740506e+02,4.083047328649405117e-01,1.100000010988609489e+01,1.761338238211364142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212220892780152326e+01,6.240926325559624956e+02,4.083223462382156166e-01,1.100000010988609489e+01,1.761192252809826424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212311801870153261e+01,6.241026325404535555e+02,4.083399581516389265e-01,1.100000010988609489e+01,1.761046267408288707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212402710960154195e+01,6.241126325249471165e+02,4.083575686052104969e-01,1.100000010988609489e+01,1.760900282006750989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212493620050155130e+01,6.241226325094432923e+02,4.083751775989303279e-01,1.100000010988609489e+01,1.760754296605213272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212584529140156064e+01,6.241326324939419692e+02,4.083927851327984193e-01,1.100000010988609489e+01,1.760608311203675554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212675438230156999e+01,6.241426324784432609e+02,4.084103912068147157e-01,1.100000010988609489e+01,1.760462325802137837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212766347320157934e+01,6.241526324629471674e+02,4.084279958209792727e-01,1.100000010988609489e+01,1.760316340400600119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212857256410158868e+01,6.241626324474535750e+02,4.084455989752920901e-01,1.100000010988609489e+01,1.760170354999062402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.212948165500159803e+01,6.241726324319625974e+02,4.084632006697531681e-01,1.100000010988609489e+01,1.760024369597524684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213039074590160737e+01,6.241826324164741209e+02,4.084808009043624510e-01,1.100000010988609489e+01,1.759878384195986967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213129983680161672e+01,6.241926324009882592e+02,4.084983996791199945e-01,1.100000010988609489e+01,1.759732398794449249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213220892770162607e+01,6.242026323855050123e+02,4.085159969940257985e-01,1.100000010988609489e+01,1.759586413392911532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213311801860163541e+01,6.242126323700242665e+02,4.085335928490798629e-01,1.100000010988609489e+01,1.759440427991373814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213402710950164476e+01,6.242226323545461355e+02,4.085511872442821324e-01,1.100000010988609489e+01,1.759294442589836097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213493620040165411e+01,6.242326323390705056e+02,4.085687801796326624e-01,1.100000010988609489e+01,1.759148457188298379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213584529130166345e+01,6.242426323235974905e+02,4.085863716551314528e-01,1.100000010988609489e+01,1.759002471786760662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213675438220167280e+01,6.242526323081270903e+02,4.086039616707784483e-01,1.100000010988609489e+01,1.758856486385222944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213766347310168214e+01,6.242626322926591911e+02,4.086215502265737043e-01,1.100000010988609489e+01,1.758710500983685227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213857256400169149e+01,6.242726322771939067e+02,4.086391373225172208e-01,1.100000010988609489e+01,1.758564515582147509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.213948165490170084e+01,6.242826322617311234e+02,4.086567229586089423e-01,1.100000010988609489e+01,1.758418530180609791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214039074580171018e+01,6.242926322462709550e+02,4.086743071348489242e-01,1.100000010988609489e+01,1.758272544779072074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214129983670171953e+01,6.243026322308134013e+02,4.086918898512371667e-01,1.100000010988609489e+01,1.758126559377534356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214220892760172887e+01,6.243126322153583487e+02,4.087094711077736142e-01,1.100000010988609489e+01,1.757980573975996639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214311801850173822e+01,6.243226321999059110e+02,4.087270509044583222e-01,1.100000010988609489e+01,1.757834588574458921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214402710940174757e+01,6.243326321844559743e+02,4.087446292412912907e-01,1.100000010988609489e+01,1.757688603172921204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214493620030175691e+01,6.243426321690086525e+02,4.087622061182724642e-01,1.100000010988609489e+01,1.757542617771383486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214584529120176626e+01,6.243526321535638317e+02,4.087797815354018982e-01,1.100000010988609489e+01,1.757396632369845769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214675438210177560e+01,6.243626321381216258e+02,4.087973554926795927e-01,1.100000010988609489e+01,1.757250646968308051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214766347300178495e+01,6.243726321226820346e+02,4.088149279901054922e-01,1.100000010988609489e+01,1.757104661566770334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214857256390179430e+01,6.243826321072449446e+02,4.088324990276796522e-01,1.100000010988609489e+01,1.756958676165232616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.214948165480180364e+01,6.243926320918104693e+02,4.088500686054020172e-01,1.100000010988609489e+01,1.756812690763694899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215039074570181299e+01,6.244026320763784952e+02,4.088676367232726427e-01,1.100000010988609489e+01,1.756666705362157181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215129983660182234e+01,6.244126320609491358e+02,4.088852033812914732e-01,1.100000010988609489e+01,1.756520719960619464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215220892750183168e+01,6.244226320455222776e+02,4.089027685794585643e-01,1.100000010988609489e+01,1.756374734559081746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215311801840184103e+01,6.244326320300980342e+02,4.089203323177739158e-01,1.100000010988609489e+01,1.756228749157544029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215402710930185037e+01,6.244426320146762919e+02,4.089378945962374723e-01,1.100000010988609489e+01,1.756082763756006311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215493620020185972e+01,6.244526319992571644e+02,4.089554554148492893e-01,1.100000010988609489e+01,1.755936778354468594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215584529110186907e+01,6.244626319838406516e+02,4.089730147736093113e-01,1.100000010988609489e+01,1.755790792952930876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215675438200187841e+01,6.244726319684266400e+02,4.089905726725175938e-01,1.100000010988609489e+01,1.755644807551393159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215766347290188776e+01,6.244826319530152432e+02,4.090081291115740814e-01,1.100000010988609489e+01,1.755498822149855441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215857256380189710e+01,6.244926319376063475e+02,4.090256840907788294e-01,1.100000010988609489e+01,1.755352836748317723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.215948165470190645e+01,6.245026319222000666e+02,4.090432376101317824e-01,1.100000010988609489e+01,1.755206851346780006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216039074560191580e+01,6.245126319067962868e+02,4.090607896696329959e-01,1.100000010988609489e+01,1.755060865945242288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216129983650192514e+01,6.245226318913951218e+02,4.090783402692824144e-01,1.100000010988609489e+01,1.754914880543704571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216220892740193449e+01,6.245326318759964579e+02,4.090958894090800935e-01,1.100000010988609489e+01,1.754768895142166853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216311801830194383e+01,6.245426318606004088e+02,4.091134370890259775e-01,1.100000010988609489e+01,1.754622909740629136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216402710920195318e+01,6.245526318452068608e+02,4.091309833091201220e-01,1.100000010988609489e+01,1.754476924339091418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216493620010196253e+01,6.245626318298159276e+02,4.091485280693624715e-01,1.100000010988609489e+01,1.754330938937553701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216584529100197187e+01,6.245726318144274956e+02,4.091660713697530816e-01,1.100000010988609489e+01,1.754184953536015983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216675438190198122e+01,6.245826317990416783e+02,4.091836132102918966e-01,1.100000010988609489e+01,1.754038968134478266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216766347280199057e+01,6.245926317836583621e+02,4.092011535909789721e-01,1.100000010988609489e+01,1.753892982732940548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216857256370199991e+01,6.246026317682776607e+02,4.092186925118142526e-01,1.100000010988609489e+01,1.753746997331402831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.216948165460200926e+01,6.246126317528995742e+02,4.092362299727977937e-01,1.100000010988609489e+01,1.753601011929865113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217039074550201860e+01,6.246226317375239887e+02,4.092537659739295397e-01,1.100000010988609489e+01,1.753455026528327396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217129983640202795e+01,6.246326317221510180e+02,4.092713005152095462e-01,1.100000010988609489e+01,1.753309041126789678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217220892730203730e+01,6.246426317067805485e+02,4.092888335966377578e-01,1.100000010988609489e+01,1.753163055725251961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217311801820204664e+01,6.246526316914126937e+02,4.093063652182141743e-01,1.100000010988609489e+01,1.753017070323714243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217402710910205599e+01,6.246626316760473401e+02,4.093238953799388513e-01,1.100000010988609489e+01,1.752871084922176526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217493620000206533e+01,6.246726316606846012e+02,4.093414240818117333e-01,1.100000010988609489e+01,1.752725099520638808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217584529090207468e+01,6.246826316453243635e+02,4.093589513238328759e-01,1.100000010988609489e+01,1.752579114119101091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217675438180208403e+01,6.246926316299667405e+02,4.093764771060022234e-01,1.100000010988609489e+01,1.752433128717563373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217766347270209337e+01,6.247026316146116187e+02,4.093940014283197759e-01,1.100000010988609489e+01,1.752287143316025655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217857256360210272e+01,6.247126315992591117e+02,4.094115242907855889e-01,1.100000010988609489e+01,1.752141157914487938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.217948165450211206e+01,6.247226315839091058e+02,4.094290456933996070e-01,1.100000010988609489e+01,1.751995172512950220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218039074540212141e+01,6.247326315685617146e+02,4.094465656361618855e-01,1.100000010988609489e+01,1.751849187111412503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218129983630213076e+01,6.247426315532168246e+02,4.094640841190723690e-01,1.100000010988609489e+01,1.751703201709874785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218220892720214010e+01,6.247526315378745494e+02,4.094816011421310575e-01,1.100000010988609489e+01,1.751557216308337068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218311801810214945e+01,6.247626315225347753e+02,4.094991167053380066e-01,1.100000010988609489e+01,1.751411230906799350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218402710900215880e+01,6.247726315071976160e+02,4.095166308086931606e-01,1.100000010988609489e+01,1.751265245505261633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218493619990216814e+01,6.247826314918629578e+02,4.095341434521965196e-01,1.100000010988609489e+01,1.751119260103723915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218584529080217749e+01,6.247926314765309144e+02,4.095516546358481391e-01,1.100000010988609489e+01,1.750973274702186198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218675438170218683e+01,6.248026314612013721e+02,4.095691643596479636e-01,1.100000010988609489e+01,1.750827289300648480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218766347260219618e+01,6.248126314458744446e+02,4.095866726235959931e-01,1.100000010988609489e+01,1.750681303899110763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218857256350220553e+01,6.248226314305500182e+02,4.096041794276922832e-01,1.100000010988609489e+01,1.750535318497573045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.218948165440221487e+01,6.248326314152282066e+02,4.096216847719367782e-01,1.100000010988609489e+01,1.750389333096035328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219039074530222422e+01,6.248426313999088961e+02,4.096391886563294782e-01,1.100000010988609489e+01,1.750243347694497610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219129983620223356e+01,6.248526313845920868e+02,4.096566910808703832e-01,1.100000010988609489e+01,1.750097362292959893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219220892710224291e+01,6.248626313692778922e+02,4.096741920455595487e-01,1.100000010988609489e+01,1.749951376891422175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219311801800225226e+01,6.248726313539661987e+02,4.096916915503969192e-01,1.100000010988609489e+01,1.749805391489884458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219402710890226160e+01,6.248826313386571201e+02,4.097091895953824947e-01,1.100000010988609489e+01,1.749659406088346740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219493619980227095e+01,6.248926313233505425e+02,4.097266861805162752e-01,1.100000010988609489e+01,1.749513420686809023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219584529070228029e+01,6.249026313080465798e+02,4.097441813057983162e-01,1.100000010988609489e+01,1.749367435285271305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219675438160228964e+01,6.249126312927451181e+02,4.097616749712285622e-01,1.100000010988609489e+01,1.749221449883733587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219766347250229899e+01,6.249226312774462713e+02,4.097791671768070132e-01,1.100000010988609489e+01,1.749075464482195870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219857256340230833e+01,6.249326312621499255e+02,4.097966579225336692e-01,1.100000010988609489e+01,1.748929479080658152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.219948165430231768e+01,6.249426312468561946e+02,4.098141472084085857e-01,1.100000010988609489e+01,1.748783493679120435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220039074520232703e+01,6.249526312315649648e+02,4.098316350344317072e-01,1.100000010988609489e+01,1.748637508277582717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220129983610233637e+01,6.249626312162763497e+02,4.098491214006030336e-01,1.100000010988609489e+01,1.748491522876045000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220220892700234572e+01,6.249726312009902358e+02,4.098666063069225651e-01,1.100000010988609489e+01,1.748345537474507282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220311801790235506e+01,6.249826311857066230e+02,4.098840897533903571e-01,1.100000010988609489e+01,1.748199552072969565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220402710880236441e+01,6.249926311704256250e+02,4.099015717400063541e-01,1.100000010988609489e+01,1.748053566671431847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220493619970237376e+01,6.250026311551471281e+02,4.099190522667705561e-01,1.100000010988609489e+01,1.747907581269894130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220584529060238310e+01,6.250126311398712460e+02,4.099365313336829630e-01,1.100000010988609489e+01,1.747761595868356412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220675438150239245e+01,6.250226311245978650e+02,4.099540089407435750e-01,1.100000010988609489e+01,1.747615610466818695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220766347240240179e+01,6.250326311093270988e+02,4.099714850879523920e-01,1.100000010988609489e+01,1.747469625065280977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220857256330241114e+01,6.250426310940588337e+02,4.099889597753094694e-01,1.100000010988609489e+01,1.747323639663743260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.220948165420242049e+01,6.250526310787931834e+02,4.100064330028147519e-01,1.100000010988609489e+01,1.747177654262205542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221039074510242983e+01,6.250626310635300342e+02,4.100239047704682394e-01,1.100000010988609489e+01,1.747031668860667825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221129983600243918e+01,6.250726310482693862e+02,4.100413750782699318e-01,1.100000010988609489e+01,1.746885683459130107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221220892690244852e+01,6.250826310330113529e+02,4.100588439262198293e-01,1.100000010988609489e+01,1.746739698057592390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221311801780245787e+01,6.250926310177558207e+02,4.100763113143179317e-01,1.100000010988609489e+01,1.746593712656054672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221402710870246722e+01,6.251026310025029034e+02,4.100937772425642391e-01,1.100000010988609489e+01,1.746447727254516954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221493619960247656e+01,6.251126309872524871e+02,4.101112417109587516e-01,1.100000010988609489e+01,1.746301741852979237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221584529050248591e+01,6.251226309720046856e+02,4.101287047195015245e-01,1.100000010988609489e+01,1.746155756451441519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221675438140249526e+01,6.251326309567593853e+02,4.101461662681925024e-01,1.100000010988609489e+01,1.746009771049903802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221766347230250460e+01,6.251426309415165861e+02,4.101636263570316854e-01,1.100000010988609489e+01,1.745863785648366084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221857256320251395e+01,6.251526309262764016e+02,4.101810849860190733e-01,1.100000010988609489e+01,1.745717800246828367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.221948165410252329e+01,6.251626309110387183e+02,4.101985421551546662e-01,1.100000010988609489e+01,1.745571814845290649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222039074500253264e+01,6.251726308958036498e+02,4.102159978644384641e-01,1.100000010988609489e+01,1.745425829443752932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222129983590254199e+01,6.251826308805710823e+02,4.102334521138704670e-01,1.100000010988609489e+01,1.745279844042215214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222220892680255133e+01,6.251926308653411297e+02,4.102509049034506750e-01,1.100000010988609489e+01,1.745133858640677497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222311801770256068e+01,6.252026308501136782e+02,4.102683562331790879e-01,1.100000010988609489e+01,1.744987873239139779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222402710860257002e+01,6.252126308348887278e+02,4.102858061030557058e-01,1.100000010988609489e+01,1.744841887837602062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222493619950257937e+01,6.252226308196663922e+02,4.103032545130805286e-01,1.100000010988609489e+01,1.744695902436064344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222584529040258872e+01,6.252326308044465577e+02,4.103207014632535565e-01,1.100000010988609489e+01,1.744549917034526627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222675438130259806e+01,6.252426307892293380e+02,4.103381469535747894e-01,1.100000010988609489e+01,1.744403931632988909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222766347220260741e+01,6.252526307740146194e+02,4.103555909840442273e-01,1.100000010988609489e+01,1.744257946231451192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222857256310261675e+01,6.252626307588024019e+02,4.103730335546618702e-01,1.100000010988609489e+01,1.744111960829913474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.222948165400262610e+01,6.252726307435927993e+02,4.103904746654277180e-01,1.100000010988609489e+01,1.743965975428375757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223039074490263545e+01,6.252826307283856977e+02,4.104079143163417709e-01,1.100000010988609489e+01,1.743819990026838039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223129983580264479e+01,6.252926307131812109e+02,4.104253525074040287e-01,1.100000010988609489e+01,1.743674004625300322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223220892670265414e+01,6.253026306979792253e+02,4.104427892386144916e-01,1.100000010988609489e+01,1.743528019223762604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223311801760266349e+01,6.253126306827797407e+02,4.104602245099731594e-01,1.100000010988609489e+01,1.743382033822224886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223402710850267283e+01,6.253226306675828710e+02,4.104776583214800323e-01,1.100000010988609489e+01,1.743236048420687169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223493619940268218e+01,6.253326306523885023e+02,4.104950906731351101e-01,1.100000010988609489e+01,1.743090063019149451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223584529030269152e+01,6.253426306371966348e+02,4.105125215649383930e-01,1.100000010988609489e+01,1.742944077617611734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223675438120270087e+01,6.253526306220073820e+02,4.105299509968898808e-01,1.100000010988609489e+01,1.742798092216074016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223766347210271022e+01,6.253626306068206304e+02,4.105473789689895736e-01,1.100000010988609489e+01,1.742652106814536299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223857256300271956e+01,6.253726305916364936e+02,4.105648054812374714e-01,1.100000010988609489e+01,1.742506121412998581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.223948165390272891e+01,6.253826305764548579e+02,4.105822305336335742e-01,1.100000010988609489e+01,1.742360136011460864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224039074480273825e+01,6.253926305612757233e+02,4.105996541261778821e-01,1.100000010988609489e+01,1.742214150609923146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224129983570274760e+01,6.254026305460992035e+02,4.106170762588703949e-01,1.100000010988609489e+01,1.742068165208385429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224220892660275695e+01,6.254126305309251848e+02,4.106344969317111127e-01,1.100000010988609489e+01,1.741922179806847711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224311801750276629e+01,6.254226305157537809e+02,4.106519161447000354e-01,1.100000010988609489e+01,1.741776194405309994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224402710840277564e+01,6.254326305005848781e+02,4.106693338978371077e-01,1.100000010988609489e+01,1.741630209003772276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224493619930278498e+01,6.254426304854184764e+02,4.106867501911223850e-01,1.100000010988609489e+01,1.741484223602234559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224584529020279433e+01,6.254526304702546895e+02,4.107041650245558673e-01,1.100000010988609489e+01,1.741338238200696841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224675438110280368e+01,6.254626304550934037e+02,4.107215783981375545e-01,1.100000010988609489e+01,1.741192252799159124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224766347200281302e+01,6.254726304399346191e+02,4.107389903118674468e-01,1.100000010988609489e+01,1.741046267397621406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224857256290282237e+01,6.254826304247784492e+02,4.107564007657455440e-01,1.100000010988609489e+01,1.740900281996083689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.224948165380283172e+01,6.254926304096247804e+02,4.107738097597718463e-01,1.100000010988609489e+01,1.740754296594545971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225039074470284106e+01,6.255026303944736128e+02,4.107912172939463535e-01,1.100000010988609489e+01,1.740608311193008254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225129983560285041e+01,6.255126303793250599e+02,4.108086233682690103e-01,1.100000010988609489e+01,1.740462325791470536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225220892650285975e+01,6.255226303641790082e+02,4.108260279827398720e-01,1.100000010988609489e+01,1.740316340389932818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225311801740286910e+01,6.255326303490354576e+02,4.108434311373589387e-01,1.100000010988609489e+01,1.740170354988395101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225402710830287845e+01,6.255426303338945218e+02,4.108608328321262104e-01,1.100000010988609489e+01,1.740024369586857383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225493619920288779e+01,6.255526303187560870e+02,4.108782330670416871e-01,1.100000010988609489e+01,1.739878384185319666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225584529010289714e+01,6.255626303036201534e+02,4.108956318421053688e-01,1.100000010988609489e+01,1.739732398783781948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225675438100290648e+01,6.255726302884868346e+02,4.109130291573172000e-01,1.100000010988609489e+01,1.739586413382244231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225766347190291583e+01,6.255826302733560169e+02,4.109304250126772362e-01,1.100000010988609489e+01,1.739440427980706513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225857256280292518e+01,6.255926302582277003e+02,4.109478194081854774e-01,1.100000010988609489e+01,1.739294442579168796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.225948165370293452e+01,6.256026302431019985e+02,4.109652123438419236e-01,1.100000010988609489e+01,1.739148457177631078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226039074460294387e+01,6.256126302279787978e+02,4.109826038196465192e-01,1.100000010988609489e+01,1.739002471776093361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226129983550295321e+01,6.256226302128580983e+02,4.109999938355993199e-01,1.100000010988609489e+01,1.738856486374555643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226220892640296256e+01,6.256326301977400135e+02,4.110173823917003255e-01,1.100000010988609489e+01,1.738710500973017926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226311801730297191e+01,6.256426301826244298e+02,4.110347694879495362e-01,1.100000010988609489e+01,1.738564515571480208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226402710820298125e+01,6.256526301675113473e+02,4.110521551243469518e-01,1.100000010988609489e+01,1.738418530169942491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226493619910299060e+01,6.256626301524008795e+02,4.110695393008925169e-01,1.100000010988609489e+01,1.738272544768404773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226584529000299995e+01,6.256726301372929129e+02,4.110869220175862870e-01,1.100000010988609489e+01,1.738126559366867056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226675438090300929e+01,6.256826301221874473e+02,4.111043032744282621e-01,1.100000010988609489e+01,1.737980573965329338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226766347180301864e+01,6.256926301070845966e+02,4.111216830714183867e-01,1.100000010988609489e+01,1.737834588563791621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226857256270302798e+01,6.257026300919842470e+02,4.111390614085567163e-01,1.100000010988609489e+01,1.737688603162253903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.226948165360303733e+01,6.257126300768863985e+02,4.111564382858432509e-01,1.100000010988609489e+01,1.737542617760716186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227039074450304668e+01,6.257226300617911647e+02,4.111738137032779905e-01,1.100000010988609489e+01,1.737396632359178468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227129983540305602e+01,6.257326300466984321e+02,4.111911876608608796e-01,1.100000010988609489e+01,1.737250646957640750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227220892630306537e+01,6.257426300316082006e+02,4.112085601585919736e-01,1.100000010988609489e+01,1.737104661556103033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227311801720307471e+01,6.257526300165205839e+02,4.112259311964712727e-01,1.100000010988609489e+01,1.736958676154565315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227402710810308406e+01,6.257626300014354683e+02,4.112433007744987212e-01,1.100000010988609489e+01,1.736812690753027598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227493619900309341e+01,6.257726299863528538e+02,4.112606688926743748e-01,1.100000010988609489e+01,1.736666705351489880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227584528990310275e+01,6.257826299712728542e+02,4.112780355509982333e-01,1.100000010988609489e+01,1.736520719949952163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227675438080311210e+01,6.257926299561953556e+02,4.112954007494702413e-01,1.100000010988609489e+01,1.736374734548414445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227766347170312144e+01,6.258026299411203581e+02,4.113127644880904543e-01,1.100000010988609489e+01,1.736228749146876728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227857256260313079e+01,6.258126299260478618e+02,4.113301267668588723e-01,1.100000010988609489e+01,1.736082763745339010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.227948165350314014e+01,6.258226299109779802e+02,4.113474875857754398e-01,1.100000010988609489e+01,1.735936778343801293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228039074440314948e+01,6.258326298959105998e+02,4.113648469448402123e-01,1.100000010988609489e+01,1.735790792942263575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228129983530315883e+01,6.258426298808457204e+02,4.113822048440531343e-01,1.100000010988609489e+01,1.735644807540725858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228220892620316818e+01,6.258526298657834559e+02,4.113995612834142612e-01,1.100000010988609489e+01,1.735498822139188140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228311801710317752e+01,6.258626298507236925e+02,4.114169162629235932e-01,1.100000010988609489e+01,1.735352836737650423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228402710800318687e+01,6.258726298356664302e+02,4.114342697825810746e-01,1.100000010988609489e+01,1.735206851336112705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228493619890319621e+01,6.258826298206116689e+02,4.114516218423867611e-01,1.100000010988609489e+01,1.735060865934574988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228584528980320556e+01,6.258926298055595225e+02,4.114689724423405970e-01,1.100000010988609489e+01,1.734914880533037270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228675438070321491e+01,6.259026297905098772e+02,4.114863215824426379e-01,1.100000010988609489e+01,1.734768895131499553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228766347160322425e+01,6.259126297754627331e+02,4.115036692626928838e-01,1.100000010988609489e+01,1.734622909729961835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228857256250323360e+01,6.259226297604182037e+02,4.115210154830912792e-01,1.100000010988609489e+01,1.734476924328424118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.228948165340324294e+01,6.259326297453761754e+02,4.115383602436378796e-01,1.100000010988609489e+01,1.734330938926886400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229039074430325229e+01,6.259426297303366482e+02,4.115557035443326295e-01,1.100000010988609489e+01,1.734184953525348682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229129983520326164e+01,6.259526297152996221e+02,4.115730453851755843e-01,1.100000010988609489e+01,1.734038968123810965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229220892610327098e+01,6.259626297002652109e+02,4.115903857661666887e-01,1.100000010988609489e+01,1.733892982722273247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229311801700328033e+01,6.259726296852333007e+02,4.116077246873059980e-01,1.100000010988609489e+01,1.733746997320735530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229402710790328968e+01,6.259826296702038917e+02,4.116250621485935124e-01,1.100000010988609489e+01,1.733601011919197812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229493619880329902e+01,6.259926296551769838e+02,4.116423981500291762e-01,1.100000010988609489e+01,1.733455026517660095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229584528970330837e+01,6.260026296401526906e+02,4.116597326916130450e-01,1.100000010988609489e+01,1.733309041116122377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229675438060331771e+01,6.260126296251308986e+02,4.116770657733450633e-01,1.100000010988609489e+01,1.733163055714584660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229766347150332706e+01,6.260226296101116077e+02,4.116943973952252867e-01,1.100000010988609489e+01,1.733017070313046942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229857256240333641e+01,6.260326295950948179e+02,4.117117275572536594e-01,1.100000010988609489e+01,1.732871084911509225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.229948165330334575e+01,6.260426295800806429e+02,4.117290562594302372e-01,1.100000010988609489e+01,1.732725099509971507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230039074420335510e+01,6.260526295650689690e+02,4.117463835017549645e-01,1.100000010988609489e+01,1.732579114108433790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230129983510336444e+01,6.260626295500597962e+02,4.117637092842278967e-01,1.100000010988609489e+01,1.732433128706896072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230220892600337379e+01,6.260726295350531245e+02,4.117810336068489785e-01,1.100000010988609489e+01,1.732287143305358355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230311801690338314e+01,6.260826295200490677e+02,4.117983564696182097e-01,1.100000010988609489e+01,1.732141157903820637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230402710780339248e+01,6.260926295050475119e+02,4.118156778725356459e-01,1.100000010988609489e+01,1.731995172502282920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230493619870340183e+01,6.261026294900484572e+02,4.118329978156012317e-01,1.100000010988609489e+01,1.731849187100745202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230584528960341117e+01,6.261126294750519037e+02,4.118503162988150224e-01,1.100000010988609489e+01,1.731703201699207485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230675438050342052e+01,6.261226294600579649e+02,4.118676333221769625e-01,1.100000010988609489e+01,1.731557216297669767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230766347140342987e+01,6.261326294450665273e+02,4.118849488856871077e-01,1.100000010988609489e+01,1.731411230896132050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230857256230343921e+01,6.261426294300775908e+02,4.119022629893454024e-01,1.100000010988609489e+01,1.731265245494594332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.230948165320344856e+01,6.261526294150911554e+02,4.119195756331518465e-01,1.100000010988609489e+01,1.731119260093056614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231039074410345791e+01,6.261626294001073347e+02,4.119368868171064957e-01,1.100000010988609489e+01,1.730973274691518897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231129983500346725e+01,6.261726293851260152e+02,4.119541965412092943e-01,1.100000010988609489e+01,1.730827289289981179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231220892590347660e+01,6.261826293701471968e+02,4.119715048054602979e-01,1.100000010988609489e+01,1.730681303888443462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231311801680348594e+01,6.261926293551708795e+02,4.119888116098594510e-01,1.100000010988609489e+01,1.730535318486905744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231402710770349529e+01,6.262026293401971770e+02,4.120061169544067536e-01,1.100000010988609489e+01,1.730389333085368027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231493619860350464e+01,6.262126293252259757e+02,4.120234208391022612e-01,1.100000010988609489e+01,1.730243347683830309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231584528950351398e+01,6.262226293102572754e+02,4.120407232639459183e-01,1.100000010988609489e+01,1.730097362282292592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231675438040352333e+01,6.262326292952910762e+02,4.120580242289377804e-01,1.100000010988609489e+01,1.729951376880754874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231766347130353267e+01,6.262426292803273782e+02,4.120753237340777919e-01,1.100000010988609489e+01,1.729805391479217157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231857256220354202e+01,6.262526292653662949e+02,4.120926217793659529e-01,1.100000010988609489e+01,1.729659406077679439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.231948165310355137e+01,6.262626292504077128e+02,4.121099183648023190e-01,1.100000010988609489e+01,1.729513420676141722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232039074400356071e+01,6.262726292354516318e+02,4.121272134903868345e-01,1.100000010988609489e+01,1.729367435274604004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232129983490357006e+01,6.262826292204980518e+02,4.121445071561194995e-01,1.100000010988609489e+01,1.729221449873066287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232220892580357940e+01,6.262926292055469730e+02,4.121617993620003695e-01,1.100000010988609489e+01,1.729075464471528569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232311801670358875e+01,6.263026291905985090e+02,4.121790901080293890e-01,1.100000010988609489e+01,1.728929479069990852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232402710760359810e+01,6.263126291756525461e+02,4.121963793942065579e-01,1.100000010988609489e+01,1.728783493668453134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232493619850360744e+01,6.263226291607090843e+02,4.122136672205319319e-01,1.100000010988609489e+01,1.728637508266915417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232584528940361679e+01,6.263326291457681236e+02,4.122309535870054553e-01,1.100000010988609489e+01,1.728491522865377699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232675438030362614e+01,6.263426291308296641e+02,4.122482384936271282e-01,1.100000010988609489e+01,1.728345537463839982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232766347120363548e+01,6.263526291158938193e+02,4.122655219403969507e-01,1.100000010988609489e+01,1.728199552062302264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232857256210364483e+01,6.263626291009604756e+02,4.122828039273149781e-01,1.100000010988609489e+01,1.728053566660764546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.232948165300365417e+01,6.263726290860296331e+02,4.123000844543811549e-01,1.100000010988609489e+01,1.727907581259226829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233039074390366352e+01,6.263826290711012916e+02,4.123173635215954813e-01,1.100000010988609489e+01,1.727761595857689111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233129983480367287e+01,6.263926290561754513e+02,4.123346411289579572e-01,1.100000010988609489e+01,1.727615610456151394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233220892570368221e+01,6.264026290412522258e+02,4.123519172764686380e-01,1.100000010988609489e+01,1.727469625054613676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233311801660369156e+01,6.264126290263315013e+02,4.123691919641274684e-01,1.100000010988609489e+01,1.727323639653075959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233402710750370090e+01,6.264226290114132780e+02,4.123864651919344482e-01,1.100000010988609489e+01,1.727177654251538241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233493619840371025e+01,6.264326289964975558e+02,4.124037369598895775e-01,1.100000010988609489e+01,1.727031668850000524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233584528930371960e+01,6.264426289815843347e+02,4.124210072679929118e-01,1.100000010988609489e+01,1.726885683448462806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233675438020372894e+01,6.264526289666736147e+02,4.124382761162443956e-01,1.100000010988609489e+01,1.726739698046925089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233766347110373829e+01,6.264626289517655096e+02,4.124555435046440288e-01,1.100000010988609489e+01,1.726593712645387371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233857256200374763e+01,6.264726289368599055e+02,4.124728094331918116e-01,1.100000010988609489e+01,1.726447727243849654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.233948165290375698e+01,6.264826289219568025e+02,4.124900739018877993e-01,1.100000010988609489e+01,1.726301741842311936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234039074380376633e+01,6.264926289070562007e+02,4.125073369107319365e-01,1.100000010988609489e+01,1.726155756440774219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234129983470377567e+01,6.265026288921580999e+02,4.125245984597242233e-01,1.100000010988609489e+01,1.726009771039236501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234220892560378502e+01,6.265126288772625003e+02,4.125418585488646595e-01,1.100000010988609489e+01,1.725863785637698784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234311801650379437e+01,6.265226288623695154e+02,4.125591171781532451e-01,1.100000010988609489e+01,1.725717800236161066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234402710740380371e+01,6.265326288474790317e+02,4.125763743475899803e-01,1.100000010988609489e+01,1.725571814834623349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234493619830381306e+01,6.265426288325910491e+02,4.125936300571749205e-01,1.100000010988609489e+01,1.725425829433085631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234584528920382240e+01,6.265526288177055676e+02,4.126108843069080101e-01,1.100000010988609489e+01,1.725279844031547914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234675438010383175e+01,6.265626288028225872e+02,4.126281370967892492e-01,1.100000010988609489e+01,1.725133858630010196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234766347100384110e+01,6.265726287879421079e+02,4.126453884268186378e-01,1.100000010988609489e+01,1.724987873228472478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234857256190385044e+01,6.265826287730642434e+02,4.126626382969961759e-01,1.100000010988609489e+01,1.724841887826934761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.234948165280385979e+01,6.265926287581888801e+02,4.126798867073218635e-01,1.100000010988609489e+01,1.724695902425397043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235039074370386913e+01,6.266026287433160178e+02,4.126971336577957006e-01,1.100000010988609489e+01,1.724549917023859326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235129983460387848e+01,6.266126287284456566e+02,4.127143791484176871e-01,1.100000010988609489e+01,1.724403931622321608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235220892550388783e+01,6.266226287135777966e+02,4.127316231791878787e-01,1.100000010988609489e+01,1.724257946220783891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235311801640389717e+01,6.266326286987124377e+02,4.127488657501062197e-01,1.100000010988609489e+01,1.724111960819246173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235402710730390652e+01,6.266426286838495798e+02,4.127661068611727102e-01,1.100000010988609489e+01,1.723965975417708456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235493619820391586e+01,6.266526286689893368e+02,4.127833465123873502e-01,1.100000010988609489e+01,1.723819990016170738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235584528910392521e+01,6.266626286541315949e+02,4.128005847037501397e-01,1.100000010988609489e+01,1.723674004614633021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235675438000393456e+01,6.266726286392763541e+02,4.128178214352610786e-01,1.100000010988609489e+01,1.723528019213095303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235766347090394390e+01,6.266826286244236144e+02,4.128350567069201671e-01,1.100000010988609489e+01,1.723382033811557586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235857256180395325e+01,6.266926286095733758e+02,4.128522905187274050e-01,1.100000010988609489e+01,1.723236048410019868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.235948165270396260e+01,6.267026285947256383e+02,4.128695228706827924e-01,1.100000010988609489e+01,1.723090063008482151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236039074360397194e+01,6.267126285798804020e+02,4.128867537627863293e-01,1.100000010988609489e+01,1.722944077606944433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236129983450398129e+01,6.267226285650377804e+02,4.129039831950380157e-01,1.100000010988609489e+01,1.722798092205406716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236220892540399063e+01,6.267326285501976599e+02,4.129212111674378516e-01,1.100000010988609489e+01,1.722652106803868998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236311801630399998e+01,6.267426285353600406e+02,4.129384376799858369e-01,1.100000010988609489e+01,1.722506121402331281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236402710720400933e+01,6.267526285205249224e+02,4.129556627326819718e-01,1.100000010988609489e+01,1.722360136000793563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236493619810401867e+01,6.267626285056923052e+02,4.129728863255262561e-01,1.100000010988609489e+01,1.722214150599255846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236584528900402802e+01,6.267726284908621892e+02,4.129901084585186899e-01,1.100000010988609489e+01,1.722068165197718128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236675437990403736e+01,6.267826284760345743e+02,4.130073291316592732e-01,1.100000010988609489e+01,1.721922179796180410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236766347080404671e+01,6.267926284612094605e+02,4.130245483449480060e-01,1.100000010988609489e+01,1.721776194394642693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236857256170405606e+01,6.268026284463868478e+02,4.130417660983848882e-01,1.100000010988609489e+01,1.721630208993104975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.236948165260406540e+01,6.268126284315668499e+02,4.130589823919699199e-01,1.100000010988609489e+01,1.721484223591567258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237039074350407475e+01,6.268226284167493532e+02,4.130761972257031012e-01,1.100000010988609489e+01,1.721338238190029540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237129983440408409e+01,6.268326284019343575e+02,4.130934105995844319e-01,1.100000010988609489e+01,1.721192252788491823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237220892530409344e+01,6.268426283871218629e+02,4.131106225136139121e-01,1.100000010988609489e+01,1.721046267386954105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237311801620410279e+01,6.268526283723118695e+02,4.131278329677915417e-01,1.100000010988609489e+01,1.720900281985416388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237402710710411213e+01,6.268626283575043772e+02,4.131450419621173209e-01,1.100000010988609489e+01,1.720754296583878670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237493619800412148e+01,6.268726283426993859e+02,4.131622494965912495e-01,1.100000010988609489e+01,1.720608311182340953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237584528890413083e+01,6.268826283278968958e+02,4.131794555712133277e-01,1.100000010988609489e+01,1.720462325780803235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237675437980414017e+01,6.268926283130969068e+02,4.131966601859835553e-01,1.100000010988609489e+01,1.720316340379265518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237766347070414952e+01,6.269026282982994189e+02,4.132138633409019324e-01,1.100000010988609489e+01,1.720170354977727800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237857256160415886e+01,6.269126282835045458e+02,4.132310650359684590e-01,1.100000010988609489e+01,1.720024369576190083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.237948165250416821e+01,6.269226282687121738e+02,4.132482652711831350e-01,1.100000010988609489e+01,1.719878384174652365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238039074340417756e+01,6.269326282539223030e+02,4.132654640465459606e-01,1.100000010988609489e+01,1.719732398773114648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238129983430418690e+01,6.269426282391349332e+02,4.132826613620568801e-01,1.100000010988609489e+01,1.719586413371576930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238220892520419625e+01,6.269526282243500646e+02,4.132998572177159491e-01,1.100000010988609489e+01,1.719440427970039213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238311801610420559e+01,6.269626282095676970e+02,4.133170516135231676e-01,1.100000010988609489e+01,1.719294442568501495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238402710700421494e+01,6.269726281947878306e+02,4.133342445494785355e-01,1.100000010988609489e+01,1.719148457166963778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238493619790422429e+01,6.269826281800104653e+02,4.133514360255820530e-01,1.100000010988609489e+01,1.719002471765426060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238584528880423363e+01,6.269926281652356010e+02,4.133686260418337199e-01,1.100000010988609489e+01,1.718856486363888342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238675437970424298e+01,6.270026281504632379e+02,4.133858145982335364e-01,1.100000010988609489e+01,1.718710500962350625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238766347060425232e+01,6.270126281356933760e+02,4.134030016947814468e-01,1.100000010988609489e+01,1.718564515560812907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238857256150426167e+01,6.270226281209260151e+02,4.134201873314775066e-01,1.100000010988609489e+01,1.718418530159275190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.238948165240427102e+01,6.270326281061611553e+02,4.134373715083217160e-01,1.100000010988609489e+01,1.718272544757737472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239039074330428036e+01,6.270426280913989103e+02,4.134545542253140749e-01,1.100000010988609489e+01,1.718126559356199755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239129983420428971e+01,6.270526280766391665e+02,4.134717354824545832e-01,1.100000010988609489e+01,1.717980573954662037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239220892510429906e+01,6.270626280618819237e+02,4.134889152797432410e-01,1.100000010988609489e+01,1.717834588553124320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239311801600430840e+01,6.270726280471271821e+02,4.135060936171799928e-01,1.100000010988609489e+01,1.717688603151586602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239402710690431775e+01,6.270826280323749415e+02,4.135232704947648941e-01,1.100000010988609489e+01,1.717542617750048885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239493619780432709e+01,6.270926280176252021e+02,4.135404459124979448e-01,1.100000010988609489e+01,1.717396632348511167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239584528870433644e+01,6.271026280028779638e+02,4.135576198703791451e-01,1.100000010988609489e+01,1.717250646946973450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239675437960434579e+01,6.271126279881332266e+02,4.135747923684084948e-01,1.100000010988609489e+01,1.717104661545435732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239766347050435513e+01,6.271226279733909905e+02,4.135919634065859385e-01,1.100000010988609489e+01,1.716958676143898015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239857256140436448e+01,6.271326279586512555e+02,4.136091329849115317e-01,1.100000010988609489e+01,1.716812690742360297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.239948165230437382e+01,6.271426279439140217e+02,4.136263011033852743e-01,1.100000010988609489e+01,1.716666705340822580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240039074320438317e+01,6.271526279291792889e+02,4.136434677620071665e-01,1.100000010988609489e+01,1.716520719939284862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240129983410439252e+01,6.271626279144470573e+02,4.136606329607771526e-01,1.100000010988609489e+01,1.716374734537747145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240220892500440186e+01,6.271726278997173267e+02,4.136777966996952882e-01,1.100000010988609489e+01,1.716228749136209427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240311801590441121e+01,6.271826278849900973e+02,4.136949589787615733e-01,1.100000010988609489e+01,1.716082763734671709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240402710680442055e+01,6.271926278702653690e+02,4.137121197979760079e-01,1.100000010988609489e+01,1.715936778333133992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240493619770442990e+01,6.272026278555431418e+02,4.137292791573385364e-01,1.100000010988609489e+01,1.715790792931596274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240584528860443925e+01,6.272126278408234157e+02,4.137464370568492145e-01,1.100000010988609489e+01,1.715644807530058557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240675437950444859e+01,6.272226278261061907e+02,4.137635934965080420e-01,1.100000010988609489e+01,1.715498822128520839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240766347040445794e+01,6.272326278113914668e+02,4.137807484763149635e-01,1.100000010988609489e+01,1.715352836726983122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240857256130446729e+01,6.272426277966792441e+02,4.137979019962700344e-01,1.100000010988609489e+01,1.715206851325445404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.240948165220447663e+01,6.272526277819695224e+02,4.138150540563732549e-01,1.100000010988609489e+01,1.715060865923907687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241039074310448598e+01,6.272626277672623019e+02,4.138322046566246248e-01,1.100000010988609489e+01,1.714914880522369969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241129983400449532e+01,6.272726277525576961e+02,4.138493537970240888e-01,1.100000010988609489e+01,1.714768895120832252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241220892490450467e+01,6.272826277378555915e+02,4.138665014775717022e-01,1.100000010988609489e+01,1.714622909719294534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241311801580451402e+01,6.272926277231559880e+02,4.138836476982674650e-01,1.100000010988609489e+01,1.714476924317756817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241402710670452336e+01,6.273026277084588855e+02,4.139007924591113219e-01,1.100000010988609489e+01,1.714330938916219099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241493619760453271e+01,6.273126276937642842e+02,4.139179357601033282e-01,1.100000010988609489e+01,1.714184953514681382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241584528850454205e+01,6.273226276790721840e+02,4.139350776012434285e-01,1.100000010988609489e+01,1.714038968113143664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241675437940455140e+01,6.273326276643825850e+02,4.139522179825316783e-01,1.100000010988609489e+01,1.713892982711605947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241766347030456075e+01,6.273426276496954870e+02,4.139693569039680776e-01,1.100000010988609489e+01,1.713746997310068229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241857256120457009e+01,6.273526276350108901e+02,4.139864943655525709e-01,1.100000010988609489e+01,1.713601011908530512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.241948165210457944e+01,6.273626276203287944e+02,4.140036303672852136e-01,1.100000010988609489e+01,1.713455026506992794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242039074300458878e+01,6.273726276056491997e+02,4.140207649091660058e-01,1.100000010988609489e+01,1.713309041105455077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242129983390459813e+01,6.273826275909721062e+02,4.140378979911948920e-01,1.100000010988609489e+01,1.713163055703917359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242220892480460748e+01,6.273926275762975138e+02,4.140550296133719277e-01,1.100000010988609489e+01,1.713017070302379641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242311801570461682e+01,6.274026275616254225e+02,4.140721597756970573e-01,1.100000010988609489e+01,1.712871084900841924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242402710660462617e+01,6.274126275469558323e+02,4.140892884781703365e-01,1.100000010988609489e+01,1.712725099499304206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242493619750463552e+01,6.274226275322887432e+02,4.141064157207917651e-01,1.100000010988609489e+01,1.712579114097766489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242584528840464486e+01,6.274326275176241552e+02,4.141235415035612877e-01,1.100000010988609489e+01,1.712433128696228771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242675437930465421e+01,6.274426275029620683e+02,4.141406658264789598e-01,1.100000010988609489e+01,1.712287143294691054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242766347020466355e+01,6.274526274883024826e+02,4.141577886895447258e-01,1.100000010988609489e+01,1.712141157893153336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242857256110467290e+01,6.274626274736453979e+02,4.141749100927586413e-01,1.100000010988609489e+01,1.711995172491615619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.242948165200468225e+01,6.274726274589908144e+02,4.141920300361206508e-01,1.100000010988609489e+01,1.711849187090077901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243039074290469159e+01,6.274826274443387319e+02,4.142091485196308098e-01,1.100000010988609489e+01,1.711703201688540184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243129983380470094e+01,6.274926274296891506e+02,4.142262655432890628e-01,1.100000010988609489e+01,1.711557216287002466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243220892470471028e+01,6.275026274150420704e+02,4.142433811070954652e-01,1.100000010988609489e+01,1.711411230885464749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243311801560471963e+01,6.275126274003973776e+02,4.142604952110499617e-01,1.100000010988609489e+01,1.711265245483927031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243402710650472898e+01,6.275226273857551860e+02,4.142776078551526076e-01,1.100000010988609489e+01,1.711119260082389314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243493619740473832e+01,6.275326273711154954e+02,4.142947190394033474e-01,1.100000010988609489e+01,1.710973274680851596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243584528830474767e+01,6.275426273564783060e+02,4.143118287638022368e-01,1.100000010988609489e+01,1.710827289279313879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243675437920475702e+01,6.275526273418436176e+02,4.143289370283492201e-01,1.100000010988609489e+01,1.710681303877776161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243766347010476636e+01,6.275626273272114304e+02,4.143460438330443529e-01,1.100000010988609489e+01,1.710535318476238444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243857256100477571e+01,6.275726273125817443e+02,4.143631491778875797e-01,1.100000010988609489e+01,1.710389333074700726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.243948165190478505e+01,6.275826272979545593e+02,4.143802530628789560e-01,1.100000010988609489e+01,1.710243347673163009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244039074280479440e+01,6.275926272833298754e+02,4.143973554880184262e-01,1.100000010988609489e+01,1.710097362271625291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244129983370480375e+01,6.276026272687076926e+02,4.144144564533060460e-01,1.100000010988609489e+01,1.709951376870087573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244220892460481309e+01,6.276126272540880109e+02,4.144315559587417597e-01,1.100000010988609489e+01,1.709805391468549856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244311801550482244e+01,6.276226272394708303e+02,4.144486540043256229e-01,1.100000010988609489e+01,1.709659406067012138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244402710640483178e+01,6.276326272248561509e+02,4.144657505900575800e-01,1.100000010988609489e+01,1.709513420665474421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244493619730484113e+01,6.276426272102439725e+02,4.144828457159376867e-01,1.100000010988609489e+01,1.709367435263936703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244584528820485048e+01,6.276526271956342953e+02,4.144999393819658873e-01,1.100000010988609489e+01,1.709221449862398986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244675437910485982e+01,6.276626271810271191e+02,4.145170315881421819e-01,1.100000010988609489e+01,1.709075464460861268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244766347000486917e+01,6.276726271664224441e+02,4.145341223344666259e-01,1.100000010988609489e+01,1.708929479059323551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244857256090487851e+01,6.276826271518202702e+02,4.145512116209391640e-01,1.100000010988609489e+01,1.708783493657785833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.244948165180488786e+01,6.276926271372205974e+02,4.145682994475598515e-01,1.100000010988609489e+01,1.708637508256248116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245039074270489721e+01,6.277026271226234257e+02,4.145853858143286330e-01,1.100000010988609489e+01,1.708491522854710398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245129983360490655e+01,6.277126271080287552e+02,4.146024707212455085e-01,1.100000010988609489e+01,1.708345537453172681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245220892450491590e+01,6.277226270934365857e+02,4.146195541683105334e-01,1.100000010988609489e+01,1.708199552051634963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245311801540492525e+01,6.277326270788469174e+02,4.146366361555236524e-01,1.100000010988609489e+01,1.708053566650097246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245402710630493459e+01,6.277426270642596364e+02,4.146537166828849208e-01,1.100000010988609489e+01,1.707907581248559528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245493619720494394e+01,6.277526270496748566e+02,4.146707957503942832e-01,1.100000010988609489e+01,1.707761595847021811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245584528810495328e+01,6.277626270350925779e+02,4.146878733580517395e-01,1.100000010988609489e+01,1.707615610445484093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245675437900496263e+01,6.277726270205128003e+02,4.147049495058573454e-01,1.100000010988609489e+01,1.707469625043946376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245766346990497198e+01,6.277826270059355238e+02,4.147220241938110452e-01,1.100000010988609489e+01,1.707323639642408658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245857256080498132e+01,6.277926269913607484e+02,4.147390974219128390e-01,1.100000010988609489e+01,1.707177654240870941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.245948165170499067e+01,6.278026269767884742e+02,4.147561691901627823e-01,1.100000010988609489e+01,1.707031668839333223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246039074260500001e+01,6.278126269622187010e+02,4.147732394985608195e-01,1.100000010988609489e+01,1.706885683437795505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246129983350500936e+01,6.278226269476514290e+02,4.147903083471069507e-01,1.100000010988609489e+01,1.706739698036257788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246220892440501871e+01,6.278326269330866580e+02,4.148073757358012315e-01,1.100000010988609489e+01,1.706593712634720070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246311801530502805e+01,6.278426269185243882e+02,4.148244416646436061e-01,1.100000010988609489e+01,1.706447727233182353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246402710620503740e+01,6.278526269039646195e+02,4.148415061336340748e-01,1.100000010988609489e+01,1.706301741831644635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246493619710504674e+01,6.278626268894072382e+02,4.148585691427726374e-01,1.100000010988609489e+01,1.706155756430106918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246584528800505609e+01,6.278726268748523580e+02,4.148756306920593495e-01,1.100000010988609489e+01,1.706009771028569200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246675437890506544e+01,6.278826268602999789e+02,4.148926907814941556e-01,1.100000010988609489e+01,1.705863785627031483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246766346980507478e+01,6.278926268457501010e+02,4.149097494110770556e-01,1.100000010988609489e+01,1.705717800225493765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246857256070508413e+01,6.279026268312027241e+02,4.149268065808081052e-01,1.100000010988609489e+01,1.705571814823956048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.246948165160509348e+01,6.279126268166578484e+02,4.149438622906872487e-01,1.100000010988609489e+01,1.705425829422418330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247039074250510282e+01,6.279226268021154738e+02,4.149609165407144862e-01,1.100000010988609489e+01,1.705279844020880613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247129983340511217e+01,6.279326267875756002e+02,4.149779693308898176e-01,1.100000010988609489e+01,1.705133858619342895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247220892430512151e+01,6.279426267730382278e+02,4.149950206612132431e-01,1.100000010988609489e+01,1.704987873217805178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247311801520513086e+01,6.279526267585033565e+02,4.150120705316848180e-01,1.100000010988609489e+01,1.704841887816267460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247402710610514021e+01,6.279626267439709864e+02,4.150291189423044869e-01,1.100000010988609489e+01,1.704695902414729743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247493619700514955e+01,6.279726267294410036e+02,4.150461658930722497e-01,1.100000010988609489e+01,1.704549917013192025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247584528790515890e+01,6.279826267149135219e+02,4.150632113839881066e-01,1.100000010988609489e+01,1.704403931611654308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247675437880516824e+01,6.279926267003885414e+02,4.150802554150521129e-01,1.100000010988609489e+01,1.704257946210116590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247766346970517759e+01,6.280026266858660620e+02,4.150972979862642132e-01,1.100000010988609489e+01,1.704111960808578873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247857256060518694e+01,6.280126266713460836e+02,4.151143390976244074e-01,1.100000010988609489e+01,1.703965975407041155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.247948165150519628e+01,6.280226266568286064e+02,4.151313787491326956e-01,1.100000010988609489e+01,1.703819990005503437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248039074240520563e+01,6.280326266423136303e+02,4.151484169407890779e-01,1.100000010988609489e+01,1.703674004603965720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248129983330521497e+01,6.280426266278011553e+02,4.151654536725935540e-01,1.100000010988609489e+01,1.703528019202428002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248220892420522432e+01,6.280526266132910678e+02,4.151824889445461797e-01,1.100000010988609489e+01,1.703382033800890285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248311801510523367e+01,6.280626265987834813e+02,4.151995227566468993e-01,1.100000010988609489e+01,1.703236048399352567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248402710600524301e+01,6.280726265842783960e+02,4.152165551088957129e-01,1.100000010988609489e+01,1.703090062997814850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248493619690525236e+01,6.280826265697758117e+02,4.152335860012926205e-01,1.100000010988609489e+01,1.702944077596277132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248584528780526171e+01,6.280926265552757286e+02,4.152506154338376221e-01,1.100000010988609489e+01,1.702798092194739415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248675437870527105e+01,6.281026265407781466e+02,4.152676434065307176e-01,1.100000010988609489e+01,1.702652106793201697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248766346960528040e+01,6.281126265262830657e+02,4.152846699193719071e-01,1.100000010988609489e+01,1.702506121391663980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248857256050528974e+01,6.281226265117904859e+02,4.153016949723612461e-01,1.100000010988609489e+01,1.702360135990126262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.248948165140529909e+01,6.281326264973002935e+02,4.153187185654986791e-01,1.100000010988609489e+01,1.702214150588588545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249039074230530844e+01,6.281426264828126023e+02,4.153357406987842060e-01,1.100000010988609489e+01,1.702068165187050827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249129983320531778e+01,6.281526264683274121e+02,4.153527613722178269e-01,1.100000010988609489e+01,1.701922179785513110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249220892410532713e+01,6.281626264538447231e+02,4.153697805857995418e-01,1.100000010988609489e+01,1.701776194383975392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249311801500533647e+01,6.281726264393645351e+02,4.153867983395293506e-01,1.100000010988609489e+01,1.701630208982437675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249402710590534582e+01,6.281826264248868483e+02,4.154038146334072534e-01,1.100000010988609489e+01,1.701484223580899957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249493619680535517e+01,6.281926264104116626e+02,4.154208294674332502e-01,1.100000010988609489e+01,1.701338238179362240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249584528770536451e+01,6.282026263959388643e+02,4.154378428416073410e-01,1.100000010988609489e+01,1.701192252777824522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249675437860537386e+01,6.282126263814685672e+02,4.154548547559295257e-01,1.100000010988609489e+01,1.701046267376286805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249766346950538320e+01,6.282226263670007711e+02,4.154718652103998044e-01,1.100000010988609489e+01,1.700900281974749087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249857256040539255e+01,6.282326263525354761e+02,4.154888742050181771e-01,1.100000010988609489e+01,1.700754296573211369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.249948165130540190e+01,6.282426263380726823e+02,4.155058817397846993e-01,1.100000010988609489e+01,1.700608311171673652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250039074220541124e+01,6.282526263236123896e+02,4.155228878146993154e-01,1.100000010988609489e+01,1.700462325770135934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250129983310542059e+01,6.282626263091544843e+02,4.155398924297620256e-01,1.100000010988609489e+01,1.700316340368598217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250220892400542994e+01,6.282726262946990801e+02,4.155568955849728296e-01,1.100000010988609489e+01,1.700170354967060499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250311801490543928e+01,6.282826262802461770e+02,4.155738972803317277e-01,1.100000010988609489e+01,1.700024369565522782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250402710580544863e+01,6.282926262657957750e+02,4.155908975158387197e-01,1.100000010988609489e+01,1.699878384163985064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250493619670545797e+01,6.283026262513478741e+02,4.156078962914938058e-01,1.100000010988609489e+01,1.699732398762447347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250584528760546732e+01,6.283126262369024744e+02,4.156248936072969857e-01,1.100000010988609489e+01,1.699586413360909629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250675437850547667e+01,6.283226262224594620e+02,4.156418894632482597e-01,1.100000010988609489e+01,1.699440427959371912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250766346940548601e+01,6.283326262080189508e+02,4.156588838593476276e-01,1.100000010988609489e+01,1.699294442557834194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250857256030549536e+01,6.283426261935809407e+02,4.156758767955950895e-01,1.100000010988609489e+01,1.699148457156296477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.250948165120550470e+01,6.283526261791454317e+02,4.156928682719906454e-01,1.100000010988609489e+01,1.699002471754758759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251039074210551405e+01,6.283626261647124238e+02,4.157098582885342397e-01,1.100000010988609489e+01,1.698856486353221042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251129983300552340e+01,6.283726261502819170e+02,4.157268468452259280e-01,1.100000010988609489e+01,1.698710500951683324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251220892390553274e+01,6.283826261358537977e+02,4.157438339420657103e-01,1.100000010988609489e+01,1.698564515550145607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251311801480554209e+01,6.283926261214281794e+02,4.157608195790535865e-01,1.100000010988609489e+01,1.698418530148607889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251402710570555143e+01,6.284026261070050623e+02,4.157778037561895568e-01,1.100000010988609489e+01,1.698272544747070172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251493619660556078e+01,6.284126260925844463e+02,4.157947864734736210e-01,1.100000010988609489e+01,1.698126559345532454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251584528750557013e+01,6.284226260781663314e+02,4.158117677309057791e-01,1.100000010988609489e+01,1.697980573943994737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251675437840557947e+01,6.284326260637506039e+02,4.158287475284860313e-01,1.100000010988609489e+01,1.697834588542457019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251766346930558882e+01,6.284426260493373775e+02,4.158457258662143774e-01,1.100000010988609489e+01,1.697688603140919301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251857256020559817e+01,6.284526260349266522e+02,4.158627027440908175e-01,1.100000010988609489e+01,1.697542617739381584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.251948165110560751e+01,6.284626260205184280e+02,4.158796781621153515e-01,1.100000010988609489e+01,1.697396632337843866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252039074200561686e+01,6.284726260061127050e+02,4.158966521202879796e-01,1.100000010988609489e+01,1.697250646936306149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252129983290562620e+01,6.284826259917093694e+02,4.159136246186087016e-01,1.100000010988609489e+01,1.697104661534768431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252220892380563555e+01,6.284926259773085349e+02,4.159305956570774621e-01,1.100000010988609489e+01,1.696958676133230714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252311801470564490e+01,6.285026259629102015e+02,4.159475652356943165e-01,1.100000010988609489e+01,1.696812690731692996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252402710560565424e+01,6.285126259485143692e+02,4.159645333544592649e-01,1.100000010988609489e+01,1.696666705330155279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252493619650566359e+01,6.285226259341210380e+02,4.159815000133723073e-01,1.100000010988609489e+01,1.696520719928617561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252584528740567293e+01,6.285326259197300942e+02,4.159984652124334437e-01,1.100000010988609489e+01,1.696374734527079844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252675437830568228e+01,6.285426259053416516e+02,4.160154289516426740e-01,1.100000010988609489e+01,1.696228749125542126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252766346920569163e+01,6.285526258909557100e+02,4.160323912309999983e-01,1.100000010988609489e+01,1.696082763724004409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252857256010570097e+01,6.285626258765722696e+02,4.160493520505053611e-01,1.100000010988609489e+01,1.695936778322466691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.252948165100571032e+01,6.285726258621912166e+02,4.160663114101588178e-01,1.100000010988609489e+01,1.695790792920928974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253039074190571966e+01,6.285826258478126647e+02,4.160832693099603685e-01,1.100000010988609489e+01,1.695644807519391256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253129983280572901e+01,6.285926258334366139e+02,4.161002257499100132e-01,1.100000010988609489e+01,1.695498822117853539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253220892370573836e+01,6.286026258190630642e+02,4.161171807300077519e-01,1.100000010988609489e+01,1.695352836716315821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253311801460574770e+01,6.286126258046920157e+02,4.161341342502535290e-01,1.100000010988609489e+01,1.695206851314778104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253402710550575705e+01,6.286226257903233545e+02,4.161510863106474001e-01,1.100000010988609489e+01,1.695060865913240386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253493619640576640e+01,6.286326257759571945e+02,4.161680369111893651e-01,1.100000010988609489e+01,1.694914880511702669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253584528730577574e+01,6.286426257615935356e+02,4.161849860518794242e-01,1.100000010988609489e+01,1.694768895110164951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253675437820578509e+01,6.286526257472323778e+02,4.162019337327175772e-01,1.100000010988609489e+01,1.694622909708627233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253766346910579443e+01,6.286626257328736074e+02,4.162188799537037687e-01,1.100000010988609489e+01,1.694476924307089516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253857256000580378e+01,6.286726257185173381e+02,4.162358247148380541e-01,1.100000010988609489e+01,1.694330938905551798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.253948165090581313e+01,6.286826257041635699e+02,4.162527680161204335e-01,1.100000010988609489e+01,1.694184953504014081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254039074180582247e+01,6.286926256898123029e+02,4.162697098575509069e-01,1.100000010988609489e+01,1.694038968102476363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254129983270583182e+01,6.287026256754634232e+02,4.162866502391294188e-01,1.100000010988609489e+01,1.693892982700938646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254220892360584116e+01,6.287126256611170447e+02,4.163035891608560246e-01,1.100000010988609489e+01,1.693746997299400928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254311801450585051e+01,6.287226256467731673e+02,4.163205266227307244e-01,1.100000010988609489e+01,1.693601011897863211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254402710540585986e+01,6.287326256324317910e+02,4.163374626247534627e-01,1.100000010988609489e+01,1.693455026496325493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254493619630586920e+01,6.287426256180928021e+02,4.163543971669242949e-01,1.100000010988609489e+01,1.693309041094787776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254584528720587855e+01,6.287526256037563144e+02,4.163713302492432211e-01,1.100000010988609489e+01,1.693163055693250058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254675437810588789e+01,6.287626255894223277e+02,4.163882618717102413e-01,1.100000010988609489e+01,1.693017070291712341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254766346900589724e+01,6.287726255750908422e+02,4.164051920343252999e-01,1.100000010988609489e+01,1.692871084890174623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254857255990590659e+01,6.287826255607617441e+02,4.164221207370884525e-01,1.100000010988609489e+01,1.692725099488636906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.254948165080591593e+01,6.287926255464351470e+02,4.164390479799996991e-01,1.100000010988609489e+01,1.692579114087099188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255039074170592528e+01,6.288026255321110511e+02,4.164559737630589842e-01,1.100000010988609489e+01,1.692433128685561471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255129983260593463e+01,6.288126255177894564e+02,4.164728980862663632e-01,1.100000010988609489e+01,1.692287143284023753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255220892350594397e+01,6.288226255034702490e+02,4.164898209496218362e-01,1.100000010988609489e+01,1.692141157882486036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255311801440595332e+01,6.288326254891535427e+02,4.165067423531253477e-01,1.100000010988609489e+01,1.691995172480948318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255402710530596266e+01,6.288426254748393376e+02,4.165236622967769531e-01,1.100000010988609489e+01,1.691849187079410601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255493619620597201e+01,6.288526254605275199e+02,4.165405807805766525e-01,1.100000010988609489e+01,1.691703201677872883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255584528710598136e+01,6.288626254462182033e+02,4.165574978045243904e-01,1.100000010988609489e+01,1.691557216276335165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255675437800599070e+01,6.288726254319113878e+02,4.165744133686202222e-01,1.100000010988609489e+01,1.691411230874797448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255766346890600005e+01,6.288826254176070734e+02,4.165913274728640925e-01,1.100000010988609489e+01,1.691265245473259730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255857255980600939e+01,6.288926254033051464e+02,4.166082401172560568e-01,1.100000010988609489e+01,1.691119260071722013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.255948165070601874e+01,6.289026253890057205e+02,4.166251513017961150e-01,1.100000010988609489e+01,1.690973274670184295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256039074160602809e+01,6.289126253747087958e+02,4.166420610264842117e-01,1.100000010988609489e+01,1.690827289268646578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256129983250603743e+01,6.289226253604142585e+02,4.166589692913204024e-01,1.100000010988609489e+01,1.690681303867108860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256220892340604678e+01,6.289326253461222223e+02,4.166758760963046870e-01,1.100000010988609489e+01,1.690535318465571143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256311801430605612e+01,6.289426253318326872e+02,4.166927814414370101e-01,1.100000010988609489e+01,1.690389333064033425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256402710520606547e+01,6.289526253175456532e+02,4.167096853267174272e-01,1.100000010988609489e+01,1.690243347662495708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256493619610607482e+01,6.289626253032610066e+02,4.167265877521458828e-01,1.100000010988609489e+01,1.690097362260957990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256584528700608416e+01,6.289726252889788611e+02,4.167434887177224323e-01,1.100000010988609489e+01,1.689951376859420273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256675437790609351e+01,6.289826252746992168e+02,4.167603882234470203e-01,1.100000010988609489e+01,1.689805391457882555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256766346880610286e+01,6.289926252604219599e+02,4.167772862693197022e-01,1.100000010988609489e+01,1.689659406056344838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256857255970611220e+01,6.290026252461472041e+02,4.167941828553404227e-01,1.100000010988609489e+01,1.689513420654807120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.256948165060612155e+01,6.290126252318749493e+02,4.168110779815092370e-01,1.100000010988609489e+01,1.689367435253269403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257039074150613089e+01,6.290226252176051958e+02,4.168279716478261454e-01,1.100000010988609489e+01,1.689221449851731685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257129983240614024e+01,6.290326252033378296e+02,4.168448638542910922e-01,1.100000010988609489e+01,1.689075464450193968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257220892330614959e+01,6.290426251890729645e+02,4.168617546009041330e-01,1.100000010988609489e+01,1.688929479048656250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257311801420615893e+01,6.290526251748106006e+02,4.168786438876652123e-01,1.100000010988609489e+01,1.688783493647118533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257402710510616828e+01,6.290626251605506241e+02,4.168955317145743855e-01,1.100000010988609489e+01,1.688637508245580815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257493619600617762e+01,6.290726251462931486e+02,4.169124180816315972e-01,1.100000010988609489e+01,1.688491522844043097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257584528690618697e+01,6.290826251320381743e+02,4.169293029888369029e-01,1.100000010988609489e+01,1.688345537442505380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257675437780619632e+01,6.290926251177855875e+02,4.169461864361902470e-01,1.100000010988609489e+01,1.688199552040967662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257766346870620566e+01,6.291026251035355017e+02,4.169630684236916851e-01,1.100000010988609489e+01,1.688053566639429945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257857255960621501e+01,6.291126250892879170e+02,4.169799489513411617e-01,1.100000010988609489e+01,1.687907581237892227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.257948165050622436e+01,6.291226250750427198e+02,4.169968280191386767e-01,1.100000010988609489e+01,1.687761595836354510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258039074140623370e+01,6.291326250608000237e+02,4.170137056270842857e-01,1.100000010988609489e+01,1.687615610434816792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258129983230624305e+01,6.291426250465598287e+02,4.170305817751779331e-01,1.100000010988609489e+01,1.687469625033279075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258220892320625239e+01,6.291526250323220211e+02,4.170474564634196746e-01,1.100000010988609489e+01,1.687323639631741357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258311801410626174e+01,6.291626250180867146e+02,4.170643296918094545e-01,1.100000010988609489e+01,1.687177654230203640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258402710500627109e+01,6.291726250038539092e+02,4.170812014603473283e-01,1.100000010988609489e+01,1.687031668828665922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258493619590628043e+01,6.291826249896234913e+02,4.170980717690332407e-01,1.100000010988609489e+01,1.686885683427128205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258584528680628978e+01,6.291926249753955744e+02,4.171149406178672470e-01,1.100000010988609489e+01,1.686739698025590487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258675437770629912e+01,6.292026249611701587e+02,4.171318080068492917e-01,1.100000010988609489e+01,1.686593712624052770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258766346860630847e+01,6.292126249469471304e+02,4.171486739359793749e-01,1.100000010988609489e+01,1.686447727222515052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258857255950631782e+01,6.292226249327266032e+02,4.171655384052575521e-01,1.100000010988609489e+01,1.686301741820977335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.258948165040632716e+01,6.292326249185085771e+02,4.171824014146837678e-01,1.100000010988609489e+01,1.686155756419439617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259039074130633651e+01,6.292426249042929385e+02,4.171992629642580774e-01,1.100000010988609489e+01,1.686009771017901900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259129983220634585e+01,6.292526248900798009e+02,4.172161230539804255e-01,1.100000010988609489e+01,1.685863785616364182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259220892310635520e+01,6.292626248758691645e+02,4.172329816838508121e-01,1.100000010988609489e+01,1.685717800214826464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259311801400636455e+01,6.292726248616609155e+02,4.172498388538692926e-01,1.100000010988609489e+01,1.685571814813288747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259402710490637389e+01,6.292826248474551676e+02,4.172666945640358116e-01,1.100000010988609489e+01,1.685425829411751029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259493619580638324e+01,6.292926248332519208e+02,4.172835488143503690e-01,1.100000010988609489e+01,1.685279844010213312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259584528670639259e+01,6.293026248190510614e+02,4.173004016048130205e-01,1.100000010988609489e+01,1.685133858608675594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259675437760640193e+01,6.293126248048527032e+02,4.173172529354237104e-01,1.100000010988609489e+01,1.684987873207137877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259766346850641128e+01,6.293226247906567323e+02,4.173341028061824387e-01,1.100000010988609489e+01,1.684841887805600159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259857255940642062e+01,6.293326247764632626e+02,4.173509512170892610e-01,1.100000010988609489e+01,1.684695902404062442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.259948165030642997e+01,6.293426247622722940e+02,4.173677981681441218e-01,1.100000010988609489e+01,1.684549917002524724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260039074120643932e+01,6.293526247480837128e+02,4.173846436593470210e-01,1.100000010988609489e+01,1.684403931600987007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260129983210644866e+01,6.293626247338976327e+02,4.174014876906980143e-01,1.100000010988609489e+01,1.684257946199449289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260220892300645801e+01,6.293726247197140538e+02,4.174183302621970459e-01,1.100000010988609489e+01,1.684111960797911572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260311801390646735e+01,6.293826247055328622e+02,4.174351713738441161e-01,1.100000010988609489e+01,1.683965975396373854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260402710480647670e+01,6.293926246913541718e+02,4.174520110256392802e-01,1.100000010988609489e+01,1.683819989994836137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260493619570648605e+01,6.294026246771779824e+02,4.174688492175824828e-01,1.100000010988609489e+01,1.683674004593298419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260584528660649539e+01,6.294126246630041805e+02,4.174856859496737238e-01,1.100000010988609489e+01,1.683528019191760702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260675437750650474e+01,6.294226246488328798e+02,4.175025212219130033e-01,1.100000010988609489e+01,1.683382033790222984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260766346840651408e+01,6.294326246346639664e+02,4.175193550343003768e-01,1.100000010988609489e+01,1.683236048388685267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260857255930652343e+01,6.294426246204975541e+02,4.175361873868357887e-01,1.100000010988609489e+01,1.683090062987147549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.260948165020653278e+01,6.294526246063336430e+02,4.175530182795192391e-01,1.100000010988609489e+01,1.682944077585609832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261039074110654212e+01,6.294626245921721193e+02,4.175698477123507835e-01,1.100000010988609489e+01,1.682798092184072114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261129983200655147e+01,6.294726245780130967e+02,4.175866756853303663e-01,1.100000010988609489e+01,1.682652106782534396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261220892290656082e+01,6.294826245638564615e+02,4.176035021984579876e-01,1.100000010988609489e+01,1.682506121380996679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261311801380657016e+01,6.294926245497023274e+02,4.176203272517336473e-01,1.100000010988609489e+01,1.682360135979458961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261402710470657951e+01,6.295026245355506944e+02,4.176371508451573455e-01,1.100000010988609489e+01,1.682214150577921244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261493619560658885e+01,6.295126245214014489e+02,4.176539729787291377e-01,1.100000010988609489e+01,1.682068165176383526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261584528650659820e+01,6.295226245072547044e+02,4.176707936524489684e-01,1.100000010988609489e+01,1.681922179774845809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261675437740660755e+01,6.295326244931103474e+02,4.176876128663168375e-01,1.100000010988609489e+01,1.681776194373308091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261766346830661689e+01,6.295426244789684915e+02,4.177044306203327451e-01,1.100000010988609489e+01,1.681630208971770374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261857255920662624e+01,6.295526244648291367e+02,4.177212469144966911e-01,1.100000010988609489e+01,1.681484223570232656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.261948165010663558e+01,6.295626244506921694e+02,4.177380617488087311e-01,1.100000010988609489e+01,1.681338238168694939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262039074100664493e+01,6.295726244365577031e+02,4.177548751232688096e-01,1.100000010988609489e+01,1.681192252767157221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262129983190665428e+01,6.295826244224256243e+02,4.177716870378769265e-01,1.100000010988609489e+01,1.681046267365619504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262220892280666362e+01,6.295926244082960466e+02,4.177884974926330819e-01,1.100000010988609489e+01,1.680900281964081786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262311801370667297e+01,6.296026243941689700e+02,4.178053064875372757e-01,1.100000010988609489e+01,1.680754296562544069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262402710460668231e+01,6.296126243800442808e+02,4.178221140225895081e-01,1.100000010988609489e+01,1.680608311161006351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262493619550669166e+01,6.296226243659220927e+02,4.178389200977898343e-01,1.100000010988609489e+01,1.680462325759468634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262584528640670101e+01,6.296326243518022920e+02,4.178557247131381991e-01,1.100000010988609489e+01,1.680316340357930916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262675437730671035e+01,6.296426243376849925e+02,4.178725278686346023e-01,1.100000010988609489e+01,1.680170354956393199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262766346820671970e+01,6.296526243235700804e+02,4.178893295642790440e-01,1.100000010988609489e+01,1.680024369554855481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262857255910672905e+01,6.296626243094576694e+02,4.179061298000715241e-01,1.100000010988609489e+01,1.679878384153317764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.262948165000673839e+01,6.296726242953477595e+02,4.179229285760120427e-01,1.100000010988609489e+01,1.679732398751780046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263039074090674774e+01,6.296826242812402370e+02,4.179397258921005998e-01,1.100000010988609489e+01,1.679586413350242328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263129983180675708e+01,6.296926242671352156e+02,4.179565217483371953e-01,1.100000010988609489e+01,1.679440427948704611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263220892270676643e+01,6.297026242530325817e+02,4.179733161447218848e-01,1.100000010988609489e+01,1.679294442547166893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263311801360677578e+01,6.297126242389324489e+02,4.179901090812546127e-01,1.100000010988609489e+01,1.679148457145629176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263402710450678512e+01,6.297226242248347035e+02,4.180069005579353791e-01,1.100000010988609489e+01,1.679002471744091458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263493619540679447e+01,6.297326242107394592e+02,4.180236905747641840e-01,1.100000010988609489e+01,1.678856486342553741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263584528630680381e+01,6.297426241966467160e+02,4.180404791317410274e-01,1.100000010988609489e+01,1.678710500941016023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263675437720681316e+01,6.297526241825563602e+02,4.180572662288659092e-01,1.100000010988609489e+01,1.678564515539478306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263766346810682251e+01,6.297626241684685056e+02,4.180740518661388294e-01,1.100000010988609489e+01,1.678418530137940588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263857255900683185e+01,6.297726241543830383e+02,4.180908360435597881e-01,1.100000010988609489e+01,1.678272544736402871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.263948164990684120e+01,6.297826241403000722e+02,4.181076187611287853e-01,1.100000010988609489e+01,1.678126559334865153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264039074080685054e+01,6.297926241262194935e+02,4.181244000188458210e-01,1.100000010988609489e+01,1.677980573933327436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264129983170685989e+01,6.298026241121414159e+02,4.181411798167108951e-01,1.100000010988609489e+01,1.677834588531789718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264220892260686924e+01,6.298126240980657258e+02,4.181579581547240076e-01,1.100000010988609489e+01,1.677688603130252001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264311801350687858e+01,6.298226240839925367e+02,4.181747350328851587e-01,1.100000010988609489e+01,1.677542617728714283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264402710440688793e+01,6.298326240699218488e+02,4.181915104511943482e-01,1.100000010988609489e+01,1.677396632327176566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264493619530689728e+01,6.298426240558535483e+02,4.182082844096515761e-01,1.100000010988609489e+01,1.677250646925638848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264584528620690662e+01,6.298526240417877489e+02,4.182250569082568425e-01,1.100000010988609489e+01,1.677104661524101131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264675437710691597e+01,6.298626240277243369e+02,4.182418279470101474e-01,1.100000010988609489e+01,1.676958676122563413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264766346800692531e+01,6.298726240136634260e+02,4.182585975259114908e-01,1.100000010988609489e+01,1.676812690721025696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264857255890693466e+01,6.298826239996049026e+02,4.182753656449608726e-01,1.100000010988609489e+01,1.676666705319487978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.264948164980694401e+01,6.298926239855488802e+02,4.182921323041582928e-01,1.100000010988609489e+01,1.676520719917950260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265039074070695335e+01,6.299026239714952453e+02,4.183088975035037516e-01,1.100000010988609489e+01,1.676374734516412543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265129983160696270e+01,6.299126239574441115e+02,4.183256612429972487e-01,1.100000010988609489e+01,1.676228749114874825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265220892250697204e+01,6.299226239433953651e+02,4.183424235226387844e-01,1.100000010988609489e+01,1.676082763713337108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265311801340698139e+01,6.299326239293491199e+02,4.183591843424283585e-01,1.100000010988609489e+01,1.675936778311799390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265402710430699074e+01,6.299426239153052620e+02,4.183759437023659711e-01,1.100000010988609489e+01,1.675790792910261673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265493619520700008e+01,6.299526239012639053e+02,4.183927016024516221e-01,1.100000010988609489e+01,1.675644807508723955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265584528610700943e+01,6.299626238872249360e+02,4.184094580426853116e-01,1.100000010988609489e+01,1.675498822107186238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265675437700701877e+01,6.299726238731884678e+02,4.184262130230670396e-01,1.100000010988609489e+01,1.675352836705648520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265766346790702812e+01,6.299826238591543870e+02,4.184429665435967505e-01,1.100000010988609489e+01,1.675206851304110803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265857255880703747e+01,6.299926238451228073e+02,4.184597186042744998e-01,1.100000010988609489e+01,1.675060865902573085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.265948164970704681e+01,6.300026238310936151e+02,4.184764692051002877e-01,1.100000010988609489e+01,1.674914880501035368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266039074060705616e+01,6.300126238170669239e+02,4.184932183460741140e-01,1.100000010988609489e+01,1.674768895099497650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266129983150706551e+01,6.300226238030426202e+02,4.185099660271959787e-01,1.100000010988609489e+01,1.674622909697959933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266220892240707485e+01,6.300326237890208176e+02,4.185267122484658819e-01,1.100000010988609489e+01,1.674476924296422215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266311801330708420e+01,6.300426237750014025e+02,4.185434570098838236e-01,1.100000010988609489e+01,1.674330938894884498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266402710420709354e+01,6.300526237609844884e+02,4.185602003114498038e-01,1.100000010988609489e+01,1.674184953493346780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266493619510710289e+01,6.300626237469699618e+02,4.185769421531638224e-01,1.100000010988609489e+01,1.674038968091809063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266584528600711224e+01,6.300726237329579362e+02,4.185936825350258239e-01,1.100000010988609489e+01,1.673892982690271345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266675437690712158e+01,6.300826237189482981e+02,4.186104214570358639e-01,1.100000010988609489e+01,1.673746997288733628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266766346780713093e+01,6.300926237049411611e+02,4.186271589191939424e-01,1.100000010988609489e+01,1.673601011887195910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266857255870714027e+01,6.301026236909364115e+02,4.186438949215000593e-01,1.100000010988609489e+01,1.673455026485658192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.266948164960714962e+01,6.301126236769341631e+02,4.186606294639542147e-01,1.100000010988609489e+01,1.673309041084120475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267039074050715897e+01,6.301226236629343020e+02,4.186773625465564086e-01,1.100000010988609489e+01,1.673163055682582757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267129983140716831e+01,6.301326236489369421e+02,4.186940941693065854e-01,1.100000010988609489e+01,1.673017070281045040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267220892230717766e+01,6.301426236349419696e+02,4.187108243322048007e-01,1.100000010988609489e+01,1.672871084879507322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267311801320718700e+01,6.301526236209494982e+02,4.187275530352510544e-01,1.100000010988609489e+01,1.672725099477969605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267402710410719635e+01,6.301626236069594142e+02,4.187442802784453466e-01,1.100000010988609489e+01,1.672579114076431887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267493619500720570e+01,6.301726235929718314e+02,4.187610060617876773e-01,1.100000010988609489e+01,1.672433128674894170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267584528590721504e+01,6.301826235789866359e+02,4.187777303852779909e-01,1.100000010988609489e+01,1.672287143273356452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267675437680722439e+01,6.301926235650039416e+02,4.187944532489163429e-01,1.100000010988609489e+01,1.672141157871818735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267766346770723374e+01,6.302026235510236347e+02,4.188111746527027335e-01,1.100000010988609489e+01,1.671995172470281017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267857255860724308e+01,6.302126235370458289e+02,4.188278945966371625e-01,1.100000010988609489e+01,1.671849187068743300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.267948164950725243e+01,6.302226235230704106e+02,4.188446130807195744e-01,1.100000010988609489e+01,1.671703201667205582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268039074040726177e+01,6.302326235090974933e+02,4.188613301049500248e-01,1.100000010988609489e+01,1.671557216265667865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268129983130727112e+01,6.302426234951269635e+02,4.188780456693285137e-01,1.100000010988609489e+01,1.671411230864130147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268220892220728047e+01,6.302526234811589347e+02,4.188947597738550410e-01,1.100000010988609489e+01,1.671265245462592430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268311801310728981e+01,6.302626234671932934e+02,4.189114724185295513e-01,1.100000010988609489e+01,1.671119260061054712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268402710400729916e+01,6.302726234532301532e+02,4.189281836033521000e-01,1.100000010988609489e+01,1.670973274659516995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268493619490730850e+01,6.302826234392694005e+02,4.189448933283226872e-01,1.100000010988609489e+01,1.670827289257979277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268584528580731785e+01,6.302926234253110351e+02,4.189616015934413129e-01,1.100000010988609489e+01,1.670681303856441560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268675437670732720e+01,6.303026234113551709e+02,4.189783083987079215e-01,1.100000010988609489e+01,1.670535318454903842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268766346760733654e+01,6.303126233974016941e+02,4.189950137441225686e-01,1.100000010988609489e+01,1.670389333053366124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268857255850734589e+01,6.303226233834507184e+02,4.190117176296852541e-01,1.100000010988609489e+01,1.670243347651828407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.268948164940735523e+01,6.303326233695021301e+02,4.190284200553959226e-01,1.100000010988609489e+01,1.670097362250290689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269039074030736458e+01,6.303426233555560430e+02,4.190451210212546296e-01,1.100000010988609489e+01,1.669951376848752972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269129983120737393e+01,6.303526233416123432e+02,4.190618205272613750e-01,1.100000010988609489e+01,1.669805391447215254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269220892210738327e+01,6.303626233276711446e+02,4.190785185734161034e-01,1.100000010988609489e+01,1.669659406045677537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269311801300739262e+01,6.303726233137323334e+02,4.190952151597188702e-01,1.100000010988609489e+01,1.669513420644139819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269402710390740197e+01,6.303826232997959096e+02,4.191119102861696755e-01,1.100000010988609489e+01,1.669367435242602102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269493619480741131e+01,6.303926232858619869e+02,4.191286039527684637e-01,1.100000010988609489e+01,1.669221449841064384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269584528570742066e+01,6.304026232719304517e+02,4.191452961595152904e-01,1.100000010988609489e+01,1.669075464439526667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269675437660743000e+01,6.304126232580014175e+02,4.191619869064101556e-01,1.100000010988609489e+01,1.668929479037988949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269766346750743935e+01,6.304226232440747708e+02,4.191786761934530037e-01,1.100000010988609489e+01,1.668783493636451232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269857255840744870e+01,6.304326232301506252e+02,4.191953640206438902e-01,1.100000010988609489e+01,1.668637508234913514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.269948164930745804e+01,6.304426232162288670e+02,4.192120503879827598e-01,1.100000010988609489e+01,1.668491522833375797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270039074020746739e+01,6.304526232023094963e+02,4.192287352954696678e-01,1.100000010988609489e+01,1.668345537431838079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270129983110747673e+01,6.304626231883926266e+02,4.192454187431046142e-01,1.100000010988609489e+01,1.668199552030300362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270220892200748608e+01,6.304726231744781444e+02,4.192621007308875436e-01,1.100000010988609489e+01,1.668053566628762644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270311801290749543e+01,6.304826231605661633e+02,4.192787812588185115e-01,1.100000010988609489e+01,1.667907581227224927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270402710380750477e+01,6.304926231466565696e+02,4.192954603268974623e-01,1.100000010988609489e+01,1.667761595825687209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270493619470751412e+01,6.305026231327494770e+02,4.193121379351244515e-01,1.100000010988609489e+01,1.667615610424149492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270584528560752346e+01,6.305126231188447719e+02,4.193288140834994793e-01,1.100000010988609489e+01,1.667469625022611774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270675437650753281e+01,6.305226231049424541e+02,4.193454887720224900e-01,1.100000010988609489e+01,1.667323639621074056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270766346740754216e+01,6.305326230910426375e+02,4.193621620006935391e-01,1.100000010988609489e+01,1.667177654219536339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270857255830755150e+01,6.305426230771452083e+02,4.193788337695125712e-01,1.100000010988609489e+01,1.667031668817998621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.270948164920756085e+01,6.305526230632502802e+02,4.193955040784796418e-01,1.100000010988609489e+01,1.666885683416460904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271039074010757020e+01,6.305626230493577395e+02,4.194121729275946953e-01,1.100000010988609489e+01,1.666739698014923186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271129983100757954e+01,6.305726230354675863e+02,4.194288403168577872e-01,1.100000010988609489e+01,1.666593712613385469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271220892190758889e+01,6.305826230215799342e+02,4.194455062462688621e-01,1.100000010988609489e+01,1.666447727211847751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271311801280759823e+01,6.305926230076946695e+02,4.194621707158279755e-01,1.100000010988609489e+01,1.666301741810310034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271402710370760758e+01,6.306026229938119059e+02,4.194788337255350719e-01,1.100000010988609489e+01,1.666155756408772316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271493619460761693e+01,6.306126229799315297e+02,4.194954952753902067e-01,1.100000010988609489e+01,1.666009771007234599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271584528550762627e+01,6.306226229660535409e+02,4.195121553653933244e-01,1.100000010988609489e+01,1.665863785605696881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271675437640763562e+01,6.306326229521780533e+02,4.195288139955444806e-01,1.100000010988609489e+01,1.665717800204159164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271766346730764496e+01,6.306426229383049531e+02,4.195454711658436198e-01,1.100000010988609489e+01,1.665571814802621446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271857255820765431e+01,6.306526229244343540e+02,4.195621268762907974e-01,1.100000010988609489e+01,1.665425829401083729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.271948164910766366e+01,6.306626229105661423e+02,4.195787811268859580e-01,1.100000010988609489e+01,1.665279843999546011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272039074000767300e+01,6.306726228967003181e+02,4.195954339176291570e-01,1.100000010988609489e+01,1.665133858598008294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272129983090768235e+01,6.306826228828369949e+02,4.196120852485203390e-01,1.100000010988609489e+01,1.664987873196470576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272220892180769169e+01,6.306926228689760592e+02,4.196287351195595594e-01,1.100000010988609489e+01,1.664841887794932859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272311801270770104e+01,6.307026228551176246e+02,4.196453835307467628e-01,1.100000010988609489e+01,1.664695902393395141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272402710360771039e+01,6.307126228412615774e+02,4.196620304820820047e-01,1.100000010988609489e+01,1.664549916991857424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272493619450771973e+01,6.307226228274079176e+02,4.196786759735652295e-01,1.100000010988609489e+01,1.664403931590319706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272584528540772908e+01,6.307326228135567590e+02,4.196953200051964927e-01,1.100000010988609489e+01,1.664257946188781988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272675437630773843e+01,6.307426227997079877e+02,4.197119625769757389e-01,1.100000010988609489e+01,1.664111960787244271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272766346720774777e+01,6.307526227858616039e+02,4.197286036889029681e-01,1.100000010988609489e+01,1.663965975385706553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272857255810775712e+01,6.307626227720177212e+02,4.197452433409782357e-01,1.100000010988609489e+01,1.663819989984168836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.272948164900776646e+01,6.307726227581762259e+02,4.197618815332014863e-01,1.100000010988609489e+01,1.663674004582631118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273039073990777581e+01,6.307826227443371181e+02,4.197785182655727754e-01,1.100000010988609489e+01,1.663528019181093401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273129983080778516e+01,6.307926227305005114e+02,4.197951535380920474e-01,1.100000010988609489e+01,1.663382033779555683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273220892170779450e+01,6.308026227166662920e+02,4.198117873507593023e-01,1.100000010988609489e+01,1.663236048378017966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273311801260780385e+01,6.308126227028345738e+02,4.198284197035745957e-01,1.100000010988609489e+01,1.663090062976480248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273402710350781319e+01,6.308226226890052430e+02,4.198450505965378721e-01,1.100000010988609489e+01,1.662944077574942531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273493619440782254e+01,6.308326226751782997e+02,4.198616800296491869e-01,1.100000010988609489e+01,1.662798092173404813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273584528530783189e+01,6.308426226613538574e+02,4.198783080029084847e-01,1.100000010988609489e+01,1.662652106771867096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273675437620784123e+01,6.308526226475318026e+02,4.198949345163157654e-01,1.100000010988609489e+01,1.662506121370329378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273766346710785058e+01,6.308626226337121352e+02,4.199115595698710846e-01,1.100000010988609489e+01,1.662360135968791661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273857255800785993e+01,6.308726226198949689e+02,4.199281831635743867e-01,1.100000010988609489e+01,1.662214150567253943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.273948164890786927e+01,6.308826226060801901e+02,4.199448052974256718e-01,1.100000010988609489e+01,1.662068165165716226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274039073980787862e+01,6.308926225922677986e+02,4.199614259714249953e-01,1.100000010988609489e+01,1.661922179764178508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274129983070788796e+01,6.309026225784579083e+02,4.199780451855723018e-01,1.100000010988609489e+01,1.661776194362640791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274220892160789731e+01,6.309126225646504054e+02,4.199946629398675912e-01,1.100000010988609489e+01,1.661630208961103073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274311801250790666e+01,6.309226225508452899e+02,4.200112792343109192e-01,1.100000010988609489e+01,1.661484223559565356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274402710340791600e+01,6.309326225370426755e+02,4.200278940689022300e-01,1.100000010988609489e+01,1.661338238158027638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274493619430792535e+01,6.309426225232424486e+02,4.200445074436415238e-01,1.100000010988609489e+01,1.661192252756489920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274584528520793469e+01,6.309526225094446090e+02,4.200611193585288006e-01,1.100000010988609489e+01,1.661046267354952203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274675437610794404e+01,6.309626224956492706e+02,4.200777298135641158e-01,1.100000010988609489e+01,1.660900281953414485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274766346700795339e+01,6.309726224818563196e+02,4.200943388087474140e-01,1.100000010988609489e+01,1.660754296551876768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274857255790796273e+01,6.309826224680657560e+02,4.201109463440786951e-01,1.100000010988609489e+01,1.660608311150339050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.274948164880797208e+01,6.309926224542776936e+02,4.201275524195580147e-01,1.100000010988609489e+01,1.660462325748801333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275039073970798142e+01,6.310026224404920185e+02,4.201441570351853172e-01,1.100000010988609489e+01,1.660316340347263615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275129983060799077e+01,6.310126224267087309e+02,4.201607601909606027e-01,1.100000010988609489e+01,1.660170354945725898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275220892150800012e+01,6.310226224129279444e+02,4.201773618868838711e-01,1.100000010988609489e+01,1.660024369544188180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275311801240800946e+01,6.310326223991495453e+02,4.201939621229551780e-01,1.100000010988609489e+01,1.659878384142650463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275402710330801881e+01,6.310426223853735337e+02,4.202105608991744679e-01,1.100000010988609489e+01,1.659732398741112745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275493619420802816e+01,6.310526223716000231e+02,4.202271582155417406e-01,1.100000010988609489e+01,1.659586413339575028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275584528510803750e+01,6.310626223578289000e+02,4.202437540720569964e-01,1.100000010988609489e+01,1.659440427938037310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275675437600804685e+01,6.310726223440601643e+02,4.202603484687202351e-01,1.100000010988609489e+01,1.659294442536499593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275766346690805619e+01,6.310826223302939297e+02,4.202769414055315123e-01,1.100000010988609489e+01,1.659148457134961875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275857255780806554e+01,6.310926223165300826e+02,4.202935328824907724e-01,1.100000010988609489e+01,1.659002471733424158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.275948164870807489e+01,6.311026223027686228e+02,4.203101228995980154e-01,1.100000010988609489e+01,1.658856486331886440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276039073960808423e+01,6.311126222890095505e+02,4.203267114568532414e-01,1.100000010988609489e+01,1.658710500930348723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276129983050809358e+01,6.311226222752529793e+02,4.203432985542564504e-01,1.100000010988609489e+01,1.658564515528811005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276220892140810292e+01,6.311326222614987955e+02,4.203598841918076978e-01,1.100000010988609489e+01,1.658418530127273288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276311801230811227e+01,6.311426222477469992e+02,4.203764683695069282e-01,1.100000010988609489e+01,1.658272544725735570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276402710320812162e+01,6.311526222339977039e+02,4.203930510873541415e-01,1.100000010988609489e+01,1.658126559324197852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276493619410813096e+01,6.311626222202507961e+02,4.204096323453493378e-01,1.100000010988609489e+01,1.657980573922660135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276584528500814031e+01,6.311726222065062757e+02,4.204262121434925170e-01,1.100000010988609489e+01,1.657834588521122417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276675437590814965e+01,6.311826221927642564e+02,4.204427904817836792e-01,1.100000010988609489e+01,1.657688603119584700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276766346680815900e+01,6.311926221790246245e+02,4.204593673602228243e-01,1.100000010988609489e+01,1.657542617718046982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276857255770816835e+01,6.312026221652873801e+02,4.204759427788100079e-01,1.100000010988609489e+01,1.657396632316509265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.276948164860817769e+01,6.312126221515525231e+02,4.204925167375451744e-01,1.100000010988609489e+01,1.657250646914971547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277039073950818704e+01,6.312226221378201672e+02,4.205090892364283239e-01,1.100000010988609489e+01,1.657104661513433830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277129983040819639e+01,6.312326221240901987e+02,4.205256602754594564e-01,1.100000010988609489e+01,1.656958676111896112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277220892130820573e+01,6.312426221103626176e+02,4.205422298546385718e-01,1.100000010988609489e+01,1.656812690710358395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277311801220821508e+01,6.312526220966374240e+02,4.205587979739656701e-01,1.100000010988609489e+01,1.656666705308820677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277402710310822442e+01,6.312626220829147314e+02,4.205753646334407514e-01,1.100000010988609489e+01,1.656520719907282960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277493619400823377e+01,6.312726220691944263e+02,4.205919298330638156e-01,1.100000010988609489e+01,1.656374734505745242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277584528490824312e+01,6.312826220554765086e+02,4.206084935728348628e-01,1.100000010988609489e+01,1.656228749104207525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277675437580825246e+01,6.312926220417610921e+02,4.206250558527539485e-01,1.100000010988609489e+01,1.656082763702669807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277766346670826181e+01,6.313026220280480629e+02,4.206416166728210171e-01,1.100000010988609489e+01,1.655936778301132090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277857255760827115e+01,6.313126220143374212e+02,4.206581760330360686e-01,1.100000010988609489e+01,1.655790792899594372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.277948164850828050e+01,6.313226220006291669e+02,4.206747339333991031e-01,1.100000010988609489e+01,1.655644807498056655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278039073940828985e+01,6.313326219869234137e+02,4.206912903739101206e-01,1.100000010988609489e+01,1.655498822096518937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278129983030829919e+01,6.313426219732200479e+02,4.207078453545691210e-01,1.100000010988609489e+01,1.655352836694981220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278220892120830854e+01,6.313526219595190696e+02,4.207243988753761044e-01,1.100000010988609489e+01,1.655206851293443502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278311801210831788e+01,6.313626219458204787e+02,4.207409509363310707e-01,1.100000010988609489e+01,1.655060865891905784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278402710300832723e+01,6.313726219321243889e+02,4.207575015374340199e-01,1.100000010988609489e+01,1.654914880490368067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278493619390833658e+01,6.313826219184306865e+02,4.207740506786849521e-01,1.100000010988609489e+01,1.654768895088830349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278584528480834592e+01,6.313926219047393715e+02,4.207905983600838673e-01,1.100000010988609489e+01,1.654622909687292632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278675437570835527e+01,6.314026218910504440e+02,4.208071445816307654e-01,1.100000010988609489e+01,1.654476924285754914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278766346660836462e+01,6.314126218773640176e+02,4.208236893433256465e-01,1.100000010988609489e+01,1.654330938884217197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278857255750837396e+01,6.314226218636799786e+02,4.208402326451685105e-01,1.100000010988609489e+01,1.654184953482679479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.278948164840838331e+01,6.314326218499983270e+02,4.208567744871593574e-01,1.100000010988609489e+01,1.654038968081141762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279039073930839265e+01,6.314426218363190628e+02,4.208733148692981874e-01,1.100000010988609489e+01,1.653892982679604044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279129983020840200e+01,6.314526218226422998e+02,4.208898537915850002e-01,1.100000010988609489e+01,1.653746997278066327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279220892110841135e+01,6.314626218089679242e+02,4.209063912540197960e-01,1.100000010988609489e+01,1.653601011876528609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279311801200842069e+01,6.314726217952959360e+02,4.209229272566025748e-01,1.100000010988609489e+01,1.653455026474990892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279402710290843004e+01,6.314826217816263352e+02,4.209394617993333365e-01,1.100000010988609489e+01,1.653309041073453174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279493619380843938e+01,6.314926217679592355e+02,4.209559948822120812e-01,1.100000010988609489e+01,1.653163055671915457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279584528470844873e+01,6.315026217542945233e+02,4.209725265052388088e-01,1.100000010988609489e+01,1.653017070270377739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279675437560845808e+01,6.315126217406321985e+02,4.209890566684135194e-01,1.100000010988609489e+01,1.652871084868840022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279766346650846742e+01,6.315226217269722611e+02,4.210055853717361574e-01,1.100000010988609489e+01,1.652725099467302304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279857255740847677e+01,6.315326217133147111e+02,4.210221126152067783e-01,1.100000010988609489e+01,1.652579114065764587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.279948164830848611e+01,6.315426216996596622e+02,4.210386383988253822e-01,1.100000010988609489e+01,1.652433128664226869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280039073920849546e+01,6.315526216860070008e+02,4.210551627225919691e-01,1.100000010988609489e+01,1.652287143262689151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280129983010850481e+01,6.315626216723567268e+02,4.210716855865065389e-01,1.100000010988609489e+01,1.652141157861151434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280220892100851415e+01,6.315726216587088402e+02,4.210882069905690916e-01,1.100000010988609489e+01,1.651995172459613716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280311801190852350e+01,6.315826216450634547e+02,4.211047269347796274e-01,1.100000010988609489e+01,1.651849187058075999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280402710280853285e+01,6.315926216314204567e+02,4.211212454191381460e-01,1.100000010988609489e+01,1.651703201656538281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280493619370854219e+01,6.316026216177798460e+02,4.211377624436446476e-01,1.100000010988609489e+01,1.651557216255000564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280584528460855154e+01,6.316126216041416228e+02,4.211542780082991322e-01,1.100000010988609489e+01,1.651411230853462846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280675437550856088e+01,6.316226215905057870e+02,4.211707921131015442e-01,1.100000010988609489e+01,1.651265245451925129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280766346640857023e+01,6.316326215768724524e+02,4.211873047580519391e-01,1.100000010988609489e+01,1.651119260050387411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280857255730857958e+01,6.316426215632415051e+02,4.212038159431503170e-01,1.100000010988609489e+01,1.650973274648849694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.280948164820858892e+01,6.316526215496129453e+02,4.212203256683966779e-01,1.100000010988609489e+01,1.650827289247311976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281039073910859827e+01,6.316626215359867729e+02,4.212368339337910217e-01,1.100000010988609489e+01,1.650681303845774259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281129983000860761e+01,6.316726215223629879e+02,4.212533407393333484e-01,1.100000010988609489e+01,1.650535318444236541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281220892090861696e+01,6.316826215087417040e+02,4.212698460850236026e-01,1.100000010988609489e+01,1.650389333042698824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281311801180862631e+01,6.316926214951228076e+02,4.212863499708618398e-01,1.100000010988609489e+01,1.650243347641161106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281402710270863565e+01,6.317026214815062986e+02,4.213028523968480599e-01,1.100000010988609489e+01,1.650097362239623389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281493619360864500e+01,6.317126214678921770e+02,4.213193533629822629e-01,1.100000010988609489e+01,1.649951376838085671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281584528450865434e+01,6.317226214542804428e+02,4.213358528692644489e-01,1.100000010988609489e+01,1.649805391436547954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281675437540866369e+01,6.317326214406712097e+02,4.213523509156945623e-01,1.100000010988609489e+01,1.649659406035010236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281766346630867304e+01,6.317426214270643641e+02,4.213688475022726587e-01,1.100000010988609489e+01,1.649513420633472519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281857255720868238e+01,6.317526214134599059e+02,4.213853426289987381e-01,1.100000010988609489e+01,1.649367435231934801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.281948164810869173e+01,6.317626213998578351e+02,4.214018362958728003e-01,1.100000010988609489e+01,1.649221449830397083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282039073900870108e+01,6.317726213862581517e+02,4.214183285028948456e-01,1.100000010988609489e+01,1.649075464428859366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282129982990871042e+01,6.317826213726608557e+02,4.214348192500648183e-01,1.100000010988609489e+01,1.648929479027321648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282220892080871977e+01,6.317926213590660609e+02,4.214513085373827739e-01,1.100000010988609489e+01,1.648783493625783931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282311801170872911e+01,6.318026213454736535e+02,4.214677963648487125e-01,1.100000010988609489e+01,1.648637508224246213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282402710260873846e+01,6.318126213318836335e+02,4.214842827324626340e-01,1.100000010988609489e+01,1.648491522822708496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282493619350874781e+01,6.318226213182960009e+02,4.215007676402244829e-01,1.100000010988609489e+01,1.648345537421170778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282584528440875715e+01,6.318326213047107558e+02,4.215172510881343149e-01,1.100000010988609489e+01,1.648199552019633061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282675437530876650e+01,6.318426212911278981e+02,4.215337330761921297e-01,1.100000010988609489e+01,1.648053566618095343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282766346620877584e+01,6.318526212775475415e+02,4.215502136043979275e-01,1.100000010988609489e+01,1.647907581216557626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282857255710878519e+01,6.318626212639695723e+02,4.215666926727516528e-01,1.100000010988609489e+01,1.647761595815019908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.282948164800879454e+01,6.318726212503939905e+02,4.215831702812533610e-01,1.100000010988609489e+01,1.647615610413482191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283039073890880388e+01,6.318826212368207962e+02,4.215996464299030522e-01,1.100000010988609489e+01,1.647469625011944473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283129982980881323e+01,6.318926212232499893e+02,4.216161211187006708e-01,1.100000010988609489e+01,1.647323639610406756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283220892070882257e+01,6.319026212096815698e+02,4.216325943476462723e-01,1.100000010988609489e+01,1.647177654208869038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283311801160883192e+01,6.319126211961156514e+02,4.216490661167398568e-01,1.100000010988609489e+01,1.647031668807331321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283402710250884127e+01,6.319226211825521204e+02,4.216655364259813688e-01,1.100000010988609489e+01,1.646885683405793603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283493619340885061e+01,6.319326211689909769e+02,4.216820052753708636e-01,1.100000010988609489e+01,1.646739698004255886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283584528430885996e+01,6.319426211554322208e+02,4.216984726649083415e-01,1.100000010988609489e+01,1.646593712602718168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283675437520886931e+01,6.319526211418758521e+02,4.217149385945937468e-01,1.100000010988609489e+01,1.646447727201180451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283766346610887865e+01,6.319626211283218709e+02,4.217314030644271350e-01,1.100000010988609489e+01,1.646301741799642733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283857255700888800e+01,6.319726211147702770e+02,4.217478660744085062e-01,1.100000010988609489e+01,1.646155756398105015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.283948164790889734e+01,6.319826211012211843e+02,4.217643276245378048e-01,1.100000010988609489e+01,1.646009770996567298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284039073880890669e+01,6.319926210876744790e+02,4.217807877148150864e-01,1.100000010988609489e+01,1.645863785595029580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284129982970891604e+01,6.320026210741301611e+02,4.217972463452403509e-01,1.100000010988609489e+01,1.645717800193491863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284220892060892538e+01,6.320126210605882306e+02,4.218137035158135428e-01,1.100000010988609489e+01,1.645571814791954145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284311801150893473e+01,6.320226210470486876e+02,4.218301592265347177e-01,1.100000010988609489e+01,1.645425829390416428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284402710240894407e+01,6.320326210335115320e+02,4.218466134774038201e-01,1.100000010988609489e+01,1.645279843988878710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284493619330895342e+01,6.320426210199767638e+02,4.218630662684209054e-01,1.100000010988609489e+01,1.645133858587340993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284584528420896277e+01,6.320526210064443831e+02,4.218795175995859736e-01,1.100000010988609489e+01,1.644987873185803275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284675437510897211e+01,6.320626209929145034e+02,4.218959674708989693e-01,1.100000010988609489e+01,1.644841887784265558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284766346600898146e+01,6.320726209793870112e+02,4.219124158823599480e-01,1.100000010988609489e+01,1.644695902382727840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284857255690899080e+01,6.320826209658619064e+02,4.219288628339688541e-01,1.100000010988609489e+01,1.644549916981190123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.284948164780900015e+01,6.320926209523391890e+02,4.219453083257257431e-01,1.100000010988609489e+01,1.644403931579652405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285039073870900950e+01,6.321026209388188590e+02,4.219617523576305596e-01,1.100000010988609489e+01,1.644257946178114688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285129982960901884e+01,6.321126209253009165e+02,4.219781949296833590e-01,1.100000010988609489e+01,1.644111960776576970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285220892050902819e+01,6.321226209117853614e+02,4.219946360418841413e-01,1.100000010988609489e+01,1.643965975375039253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285311801140903754e+01,6.321326208982721937e+02,4.220110756942328512e-01,1.100000010988609489e+01,1.643819989973501535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285402710230904688e+01,6.321426208847615271e+02,4.220275138867295439e-01,1.100000010988609489e+01,1.643674004571963818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285493619320905623e+01,6.321526208712532480e+02,4.220439506193741641e-01,1.100000010988609489e+01,1.643528019170426100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285584528410906557e+01,6.321626208577473562e+02,4.220603858921667673e-01,1.100000010988609489e+01,1.643382033768888383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285675437500907492e+01,6.321726208442438519e+02,4.220768197051072979e-01,1.100000010988609489e+01,1.643236048367350665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285766346590908427e+01,6.321826208307427351e+02,4.220932520581958114e-01,1.100000010988609489e+01,1.643090062965812947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285857255680909361e+01,6.321926208172440056e+02,4.221096829514322524e-01,1.100000010988609489e+01,1.642944077564275230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.285948164770910296e+01,6.322026208037476636e+02,4.221261123848166763e-01,1.100000010988609489e+01,1.642798092162737512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286039073860911230e+01,6.322126207902537089e+02,4.221425403583490277e-01,1.100000010988609489e+01,1.642652106761199795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286129982950912165e+01,6.322226207767621418e+02,4.221589668720293620e-01,1.100000010988609489e+01,1.642506121359662077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286220892040913100e+01,6.322326207632729620e+02,4.221753919258576238e-01,1.100000010988609489e+01,1.642360135958124360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286311801130914034e+01,6.322426207497862833e+02,4.221918155198338685e-01,1.100000010988609489e+01,1.642214150556586642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286402710220914969e+01,6.322526207363019921e+02,4.222082376539580406e-01,1.100000010988609489e+01,1.642068165155048925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286493619310915903e+01,6.322626207228200883e+02,4.222246583282301957e-01,1.100000010988609489e+01,1.641922179753511207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286584528400916838e+01,6.322726207093405719e+02,4.222410775426502783e-01,1.100000010988609489e+01,1.641776194351973490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286675437490917773e+01,6.322826206958634430e+02,4.222574952972182882e-01,1.100000010988609489e+01,1.641630208950435772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286766346580918707e+01,6.322926206823887014e+02,4.222739115919342812e-01,1.100000010988609489e+01,1.641484223548898055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286857255670919642e+01,6.323026206689163473e+02,4.222903264267982015e-01,1.100000010988609489e+01,1.641338238147360337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.286948164760920577e+01,6.323126206554463806e+02,4.223067398018101049e-01,1.100000010988609489e+01,1.641192252745822620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287039073850921511e+01,6.323226206419788014e+02,4.223231517169699356e-01,1.100000010988609489e+01,1.641046267344284902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287129982940922446e+01,6.323326206285136095e+02,4.223395621722777493e-01,1.100000010988609489e+01,1.640900281942747185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287220892030923380e+01,6.323426206150508051e+02,4.223559711677334905e-01,1.100000010988609489e+01,1.640754296541209467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287311801120924315e+01,6.323526206015903881e+02,4.223723787033371591e-01,1.100000010988609489e+01,1.640608311139671750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287402710210925250e+01,6.323626205881323585e+02,4.223887847790888106e-01,1.100000010988609489e+01,1.640462325738134032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287493619300926184e+01,6.323726205746768301e+02,4.224051893949883896e-01,1.100000010988609489e+01,1.640316340336596315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287584528390927119e+01,6.323826205612236890e+02,4.224215925510359515e-01,1.100000010988609489e+01,1.640170354935058597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287675437480928053e+01,6.323926205477729354e+02,4.224379942472314409e-01,1.100000010988609489e+01,1.640024369533520879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287766346570928988e+01,6.324026205343245692e+02,4.224543944835748577e-01,1.100000010988609489e+01,1.639878384131983162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287857255660929923e+01,6.324126205208785905e+02,4.224707932600662574e-01,1.100000010988609489e+01,1.639732398730445444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.287948164750930857e+01,6.324226205074349991e+02,4.224871905767055846e-01,1.100000010988609489e+01,1.639586413328907727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288039073840931792e+01,6.324326204939937952e+02,4.225035864334928393e-01,1.100000010988609489e+01,1.639440427927370009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288129982930932727e+01,6.324426204805549787e+02,4.225199808304280769e-01,1.100000010988609489e+01,1.639294442525832292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288220892020933661e+01,6.324526204671185496e+02,4.225363737675112419e-01,1.100000010988609489e+01,1.639148457124294574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288311801110934596e+01,6.324626204536845080e+02,4.225527652447423343e-01,1.100000010988609489e+01,1.639002471722756857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288402710200935530e+01,6.324726204402528538e+02,4.225691552621214098e-01,1.100000010988609489e+01,1.638856486321219139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288493619290936465e+01,6.324826204268235870e+02,4.225855438196484126e-01,1.100000010988609489e+01,1.638710500919681422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288584528380937400e+01,6.324926204133967076e+02,4.226019309173233429e-01,1.100000010988609489e+01,1.638564515518143704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288675437470938334e+01,6.325026203999722156e+02,4.226183165551462562e-01,1.100000010988609489e+01,1.638418530116605987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288766346560939269e+01,6.325126203865501111e+02,4.226347007331170968e-01,1.100000010988609489e+01,1.638272544715068269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288857255650940203e+01,6.325226203731303940e+02,4.226510834512358650e-01,1.100000010988609489e+01,1.638126559313530552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.288948164740941138e+01,6.325326203597130643e+02,4.226674647095026160e-01,1.100000010988609489e+01,1.637980573911992834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289039073830942073e+01,6.325426203462981221e+02,4.226838445079172946e-01,1.100000010988609489e+01,1.637834588510455117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289129982920943007e+01,6.325526203328855672e+02,4.227002228464799005e-01,1.100000010988609489e+01,1.637688603108917399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289220892010943942e+01,6.325626203194753998e+02,4.227165997251904339e-01,1.100000010988609489e+01,1.637542617707379682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289311801100944876e+01,6.325726203060676198e+02,4.227329751440489503e-01,1.100000010988609489e+01,1.637396632305841964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289402710190945811e+01,6.325826202926623409e+02,4.227493491030553940e-01,1.100000010988609489e+01,1.637250646904304247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289493619280946746e+01,6.325926202792594495e+02,4.227657216022097653e-01,1.100000010988609489e+01,1.637104661502766529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289584528370947680e+01,6.326026202658589455e+02,4.227820926415120639e-01,1.100000010988609489e+01,1.636958676101228811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289675437460948615e+01,6.326126202524608289e+02,4.227984622209623455e-01,1.100000010988609489e+01,1.636812690699691094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289766346550949550e+01,6.326226202390650997e+02,4.228148303405605546e-01,1.100000010988609489e+01,1.636666705298153376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289857255640950484e+01,6.326326202256717579e+02,4.228311970003066911e-01,1.100000010988609489e+01,1.636520719896615659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.289948164730951419e+01,6.326426202122808036e+02,4.228475622002007550e-01,1.100000010988609489e+01,1.636374734495077941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290039073820952353e+01,6.326526201988922367e+02,4.228639259402428019e-01,1.100000010988609489e+01,1.636228749093540224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290129982910953288e+01,6.326626201855060572e+02,4.228802882204327762e-01,1.100000010988609489e+01,1.636082763692002506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290220892000954223e+01,6.326726201721222651e+02,4.228966490407706780e-01,1.100000010988609489e+01,1.635936778290464789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290311801090955157e+01,6.326826201587408605e+02,4.229130084012565072e-01,1.100000010988609489e+01,1.635790792888927071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290402710180956092e+01,6.326926201453618432e+02,4.229293663018902638e-01,1.100000010988609489e+01,1.635644807487389354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290493619270957026e+01,6.327026201319852134e+02,4.229457227426720034e-01,1.100000010988609489e+01,1.635498822085851636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290584528360957961e+01,6.327126201186109711e+02,4.229620777236016704e-01,1.100000010988609489e+01,1.635352836684313919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290675437450958896e+01,6.327226201052391161e+02,4.229784312446792649e-01,1.100000010988609489e+01,1.635206851282776201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290766346540959830e+01,6.327326200918696486e+02,4.229947833059047868e-01,1.100000010988609489e+01,1.635060865881238484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290857255630960765e+01,6.327426200785025685e+02,4.230111339072782362e-01,1.100000010988609489e+01,1.634914880479700766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.290948164720961699e+01,6.327526200651378758e+02,4.230274830487996129e-01,1.100000010988609489e+01,1.634768895078163049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291039073810962634e+01,6.327626200517755706e+02,4.230438307304689727e-01,1.100000010988609489e+01,1.634622909676625331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291129982900963569e+01,6.327726200384156527e+02,4.230601769522862599e-01,1.100000010988609489e+01,1.634476924275087614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291220891990964503e+01,6.327826200250581223e+02,4.230765217142514745e-01,1.100000010988609489e+01,1.634330938873549896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291311801080965438e+01,6.327926200117029794e+02,4.230928650163646165e-01,1.100000010988609489e+01,1.634184953472012179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291402710170966373e+01,6.328026199983502238e+02,4.231092068586256860e-01,1.100000010988609489e+01,1.634038968070474461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291493619260967307e+01,6.328126199849998557e+02,4.231255472410346830e-01,1.100000010988609489e+01,1.633892982668936743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291584528350968242e+01,6.328226199716518749e+02,4.231418861635916073e-01,1.100000010988609489e+01,1.633746997267399026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291675437440969176e+01,6.328326199583062817e+02,4.231582236262964591e-01,1.100000010988609489e+01,1.633601011865861308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291766346530970111e+01,6.328426199449630758e+02,4.231745596291492384e-01,1.100000010988609489e+01,1.633455026464323591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291857255620971046e+01,6.328526199316222574e+02,4.231908941721500006e-01,1.100000010988609489e+01,1.633309041062785873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.291948164710971980e+01,6.328626199182837127e+02,4.232072272552986902e-01,1.100000010988609489e+01,1.633163055661248156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292039073800972915e+01,6.328726199049475554e+02,4.232235588785953073e-01,1.100000010988609489e+01,1.633017070259710438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292129982890973849e+01,6.328826198916137855e+02,4.232398890420398518e-01,1.100000010988609489e+01,1.632871084858172721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292220891980974784e+01,6.328926198782824031e+02,4.232562177456323238e-01,1.100000010988609489e+01,1.632725099456635003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292311801070975719e+01,6.329026198649534081e+02,4.232725449893727232e-01,1.100000010988609489e+01,1.632579114055097286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292402710160976653e+01,6.329126198516268005e+02,4.232888707732610500e-01,1.100000010988609489e+01,1.632433128653559568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292493619250977588e+01,6.329226198383025803e+02,4.233051950972973043e-01,1.100000010988609489e+01,1.632287143252021851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292584528340978522e+01,6.329326198249807476e+02,4.233215179614814860e-01,1.100000010988609489e+01,1.632141157850484133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292675437430979457e+01,6.329426198116613023e+02,4.233378393658135952e-01,1.100000010988609489e+01,1.631995172448946416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292766346520980392e+01,6.329526197983442444e+02,4.233541593102936318e-01,1.100000010988609489e+01,1.631849187047408698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292857255610981326e+01,6.329626197850295739e+02,4.233704777949215958e-01,1.100000010988609489e+01,1.631703201645870981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.292948164700982261e+01,6.329726197717172909e+02,4.233867948196974873e-01,1.100000010988609489e+01,1.631557216244333263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293039073790983196e+01,6.329826197584073952e+02,4.234031103846213062e-01,1.100000010988609489e+01,1.631411230842795546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293129982880984130e+01,6.329926197450998870e+02,4.234194244896930526e-01,1.100000010988609489e+01,1.631265245441257828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293220891970985065e+01,6.330026197317947663e+02,4.234357371349127264e-01,1.100000010988609489e+01,1.631119260039720111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293311801060985999e+01,6.330126197184920329e+02,4.234520483202803276e-01,1.100000010988609489e+01,1.630973274638182393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293402710150986934e+01,6.330226197051916870e+02,4.234683580457958563e-01,1.100000010988609489e+01,1.630827289236644675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293493619240987869e+01,6.330326196918937285e+02,4.234846663114593124e-01,1.100000010988609489e+01,1.630681303835106958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293584528330988803e+01,6.330426196785981574e+02,4.235009731172706959e-01,1.100000010988609489e+01,1.630535318433569240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293675437420989738e+01,6.330526196653049738e+02,4.235172784632300069e-01,1.100000010988609489e+01,1.630389333032031523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293766346510990672e+01,6.330626196520141775e+02,4.235335823493372454e-01,1.100000010988609489e+01,1.630243347630493805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293857255600991607e+01,6.330726196387257687e+02,4.235498847755924112e-01,1.100000010988609489e+01,1.630097362228956088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.293948164690992542e+01,6.330826196254396336e+02,4.235661857419955045e-01,1.100000010988609489e+01,1.629951376827418370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294039073780993476e+01,6.330926196121558860e+02,4.235824852485465253e-01,1.100000010988609489e+01,1.629805391425880653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294129982870994411e+01,6.331026195988745258e+02,4.235987832952454735e-01,1.100000010988609489e+01,1.629659406024342935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294220891960995345e+01,6.331126195855955530e+02,4.236150798820923491e-01,1.100000010988609489e+01,1.629513420622805218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294311801050996280e+01,6.331226195723189676e+02,4.236313750090871522e-01,1.100000010988609489e+01,1.629367435221267500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294402710140997215e+01,6.331326195590447696e+02,4.236476686762298272e-01,1.100000010988609489e+01,1.629221449819729783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294493619230998149e+01,6.331426195457729591e+02,4.236639608835204296e-01,1.100000010988609489e+01,1.629075464418192065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294584528320999084e+01,6.331526195325035360e+02,4.236802516309589595e-01,1.100000010988609489e+01,1.628929479016654348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294675437411000019e+01,6.331626195192365003e+02,4.236965409185454168e-01,1.100000010988609489e+01,1.628783493615116630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294766346501000953e+01,6.331726195059718520e+02,4.237128287462798015e-01,1.100000010988609489e+01,1.628637508213578913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294857255591001888e+01,6.331826194927095912e+02,4.237291151141621137e-01,1.100000010988609489e+01,1.628491522812041195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.294948164681002822e+01,6.331926194794497178e+02,4.237454000221923534e-01,1.100000010988609489e+01,1.628345537410503478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295039073771003757e+01,6.332026194661921181e+02,4.237616834703705204e-01,1.100000010988609489e+01,1.628199552008965760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295129982861004692e+01,6.332126194529369059e+02,4.237779654586966149e-01,1.100000010988609489e+01,1.628053566607428043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295220891951005626e+01,6.332226194396840810e+02,4.237942459871705814e-01,1.100000010988609489e+01,1.627907581205890325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295311801041006561e+01,6.332326194264336436e+02,4.238105250557924752e-01,1.100000010988609489e+01,1.627761595804352607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295402710131007495e+01,6.332426194131855937e+02,4.238268026645622966e-01,1.100000010988609489e+01,1.627615610402814890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295493619221008430e+01,6.332526193999399311e+02,4.238430788134800453e-01,1.100000010988609489e+01,1.627469625001277172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295584528311009365e+01,6.332626193866966560e+02,4.238593535025457215e-01,1.100000010988609489e+01,1.627323639599739455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295675437401010299e+01,6.332726193734557683e+02,4.238756267317593251e-01,1.100000010988609489e+01,1.627177654198201737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295766346491011234e+01,6.332826193602172680e+02,4.238918985011208007e-01,1.100000010988609489e+01,1.627031668796664020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295857255581012168e+01,6.332926193469811551e+02,4.239081688106302037e-01,1.100000010988609489e+01,1.626885683395126302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.295948164671013103e+01,6.333026193337474297e+02,4.239244376602875342e-01,1.100000010988609489e+01,1.626739697993588585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296039073761014038e+01,6.333126193205159780e+02,4.239407050500927920e-01,1.100000010988609489e+01,1.626593712592050867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296129982851014972e+01,6.333226193072869137e+02,4.239569709800459774e-01,1.100000010988609489e+01,1.626447727190513150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296220891941015907e+01,6.333326192940602368e+02,4.239732354501470346e-01,1.100000010988609489e+01,1.626301741788975432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296311801031016842e+01,6.333426192808359474e+02,4.239894984603960193e-01,1.100000010988609489e+01,1.626155756387437715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296402710121017776e+01,6.333526192676140454e+02,4.240057600107929314e-01,1.100000010988609489e+01,1.626009770985899997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296493619211018711e+01,6.333626192543945308e+02,4.240220201013377710e-01,1.100000010988609489e+01,1.625863785584362280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296584528301019645e+01,6.333726192411774036e+02,4.240382787320305380e-01,1.100000010988609489e+01,1.625717800182824562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296675437391020580e+01,6.333826192279626639e+02,4.240545359028711769e-01,1.100000010988609489e+01,1.625571814781286845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296766346481021515e+01,6.333926192147501979e+02,4.240707916138597433e-01,1.100000010988609489e+01,1.625425829379749127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296857255571022449e+01,6.334026192015401193e+02,4.240870458649962371e-01,1.100000010988609489e+01,1.625279843978211410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.296948164661023384e+01,6.334126191883324282e+02,4.241032986562806584e-01,1.100000010988609489e+01,1.625133858576673692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297039073751024318e+01,6.334226191751271244e+02,4.241195499877129516e-01,1.100000010988609489e+01,1.624987873175135975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297129982841025253e+01,6.334326191619242081e+02,4.241357998592931722e-01,1.100000010988609489e+01,1.624841887773598257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297220891931026188e+01,6.334426191487236792e+02,4.241520482710213202e-01,1.100000010988609489e+01,1.624695902372060539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297311801021027122e+01,6.334526191355255378e+02,4.241682952228973402e-01,1.100000010988609489e+01,1.624549916970522822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297402710111028057e+01,6.334626191223297837e+02,4.241845407149212877e-01,1.100000010988609489e+01,1.624403931568985104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297493619201028991e+01,6.334726191091363035e+02,4.242007847470931625e-01,1.100000010988609489e+01,1.624257946167447387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297584528291029926e+01,6.334826190959452106e+02,4.242170273194129648e-01,1.100000010988609489e+01,1.624111960765909669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297675437381030861e+01,6.334926190827565051e+02,4.242332684318806391e-01,1.100000010988609489e+01,1.623965975364371952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297766346471031795e+01,6.335026190695701871e+02,4.242495080844962407e-01,1.100000010988609489e+01,1.623819989962834234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297857255561032730e+01,6.335126190563862565e+02,4.242657462772597698e-01,1.100000010988609489e+01,1.623674004561296517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.297948164651033665e+01,6.335226190432047133e+02,4.242819830101711709e-01,1.100000010988609489e+01,1.623528019159758799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298039073741034599e+01,6.335326190300254439e+02,4.242982182832304994e-01,1.100000010988609489e+01,1.623382033758221082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298129982831035534e+01,6.335426190168485618e+02,4.243144520964377553e-01,1.100000010988609489e+01,1.623236048356683364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298220891921036468e+01,6.335526190036740672e+02,4.243306844497928831e-01,1.100000010988609489e+01,1.623090062955145647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298311801011037403e+01,6.335626189905019601e+02,4.243469153432959384e-01,1.100000010988609489e+01,1.622944077553607929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298402710101038338e+01,6.335726189773322403e+02,4.243631447769468656e-01,1.100000010988609489e+01,1.622798092152070212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298493619191039272e+01,6.335826189641649080e+02,4.243793727507457203e-01,1.100000010988609489e+01,1.622652106750532494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298584528281040207e+01,6.335926189509999631e+02,4.243955992646925024e-01,1.100000010988609489e+01,1.622506121348994777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298675437371041141e+01,6.336026189378372919e+02,4.244118243187871564e-01,1.100000010988609489e+01,1.622360135947457059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298766346461042076e+01,6.336126189246770082e+02,4.244280479130297379e-01,1.100000010988609489e+01,1.622214150545919342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298857255551043011e+01,6.336226189115191119e+02,4.244442700474202468e-01,1.100000010988609489e+01,1.622068165144381624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.298948164641043945e+01,6.336326188983636030e+02,4.244604907219586276e-01,1.100000010988609489e+01,1.621922179742843906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299039073731044880e+01,6.336426188852104815e+02,4.244767099366449359e-01,1.100000010988609489e+01,1.621776194341306189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299129982821045814e+01,6.336526188720597474e+02,4.244929276914791161e-01,1.100000010988609489e+01,1.621630208939768471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299220891911046749e+01,6.336626188589112871e+02,4.245091439864612237e-01,1.100000010988609489e+01,1.621484223538230754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299311801001047684e+01,6.336726188457652142e+02,4.245253588215912588e-01,1.100000010988609489e+01,1.621338238136693036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299402710091048618e+01,6.336826188326215288e+02,4.245415721968691658e-01,1.100000010988609489e+01,1.621192252735155319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299493619181049553e+01,6.336926188194802307e+02,4.245577841122950002e-01,1.100000010988609489e+01,1.621046267333617601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299584528271050488e+01,6.337026188063413201e+02,4.245739945678687066e-01,1.100000010988609489e+01,1.620900281932079884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299675437361051422e+01,6.337126187932046832e+02,4.245902035635903404e-01,1.100000010988609489e+01,1.620754296530542166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299766346451052357e+01,6.337226187800704338e+02,4.246064110994598462e-01,1.100000010988609489e+01,1.620608311129004449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299857255541053291e+01,6.337326187669385718e+02,4.246226171754772793e-01,1.100000010988609489e+01,1.620462325727466731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.299948164631054226e+01,6.337426187538090971e+02,4.246388217916425845e-01,1.100000010988609489e+01,1.620316340325929014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300039073721055161e+01,6.337526187406820100e+02,4.246550249479558170e-01,1.100000010988609489e+01,1.620170354924391296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300129982811056095e+01,6.337626187275571965e+02,4.246712266444169215e-01,1.100000010988609489e+01,1.620024369522853579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300220891901057030e+01,6.337726187144347705e+02,4.246874268810259534e-01,1.100000010988609489e+01,1.619878384121315861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300311800991057964e+01,6.337826187013147319e+02,4.247036256577828572e-01,1.100000010988609489e+01,1.619732398719778144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300402710081058899e+01,6.337926186881970807e+02,4.247198229746876885e-01,1.100000010988609489e+01,1.619586413318240426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300493619171059834e+01,6.338026186750818169e+02,4.247360188317403917e-01,1.100000010988609489e+01,1.619440427916702709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300584528261060768e+01,6.338126186619688269e+02,4.247522132289410224e-01,1.100000010988609489e+01,1.619294442515164991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300675437351061703e+01,6.338226186488582243e+02,4.247684061662895250e-01,1.100000010988609489e+01,1.619148457113627274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300766346441062637e+01,6.338326186357500092e+02,4.247845976437859550e-01,1.100000010988609489e+01,1.619002471712089556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300857255531063572e+01,6.338426186226441814e+02,4.248007876614302569e-01,1.100000010988609489e+01,1.618856486310551838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.300948164621064507e+01,6.338526186095407411e+02,4.248169762192224863e-01,1.100000010988609489e+01,1.618710500909014121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301039073711065441e+01,6.338626185964395745e+02,4.248331633171625876e-01,1.100000010988609489e+01,1.618564515507476403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301129982801066376e+01,6.338726185833407953e+02,4.248493489552506164e-01,1.100000010988609489e+01,1.618418530105938686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301220891891067311e+01,6.338826185702444036e+02,4.248655331334865171e-01,1.100000010988609489e+01,1.618272544704400968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301311800981068245e+01,6.338926185571503993e+02,4.248817158518703452e-01,1.100000010988609489e+01,1.618126559302863251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301402710071069180e+01,6.339026185440587824e+02,4.248978971104020452e-01,1.100000010988609489e+01,1.617980573901325533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301493619161070114e+01,6.339126185309694392e+02,4.249140769090816727e-01,1.100000010988609489e+01,1.617834588499787816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301584528251071049e+01,6.339226185178824835e+02,4.249302552479091721e-01,1.100000010988609489e+01,1.617688603098250098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301675437341071984e+01,6.339326185047979152e+02,4.249464321268845435e-01,1.100000010988609489e+01,1.617542617696712381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301766346431072918e+01,6.339426184917157343e+02,4.249626075460078423e-01,1.100000010988609489e+01,1.617396632295174663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301857255521073853e+01,6.339526184786358272e+02,4.249787815052790130e-01,1.100000010988609489e+01,1.617250646893636946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.301948164611074787e+01,6.339626184655583074e+02,4.249949540046981111e-01,1.100000010988609489e+01,1.617104661492099228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302039073701075722e+01,6.339726184524831751e+02,4.250111250442650812e-01,1.100000010988609489e+01,1.616958676090561511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302129982791076657e+01,6.339826184394104303e+02,4.250272946239799232e-01,1.100000010988609489e+01,1.616812690689023793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302220891881077591e+01,6.339926184263400728e+02,4.250434627438426927e-01,1.100000010988609489e+01,1.616666705287486076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302311800971078526e+01,6.340026184132719891e+02,4.250596294038533340e-01,1.100000010988609489e+01,1.616520719885948358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302402710061079461e+01,6.340126184002062928e+02,4.250757946040118473e-01,1.100000010988609489e+01,1.616374734484410641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302493619151080395e+01,6.340226183871429839e+02,4.250919583443182881e-01,1.100000010988609489e+01,1.616228749082872923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302584528241081330e+01,6.340326183740820625e+02,4.251081206247726008e-01,1.100000010988609489e+01,1.616082763681335206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302675437331082264e+01,6.340426183610234148e+02,4.251242814453747854e-01,1.100000010988609489e+01,1.615936778279797488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302766346421083199e+01,6.340526183479671545e+02,4.251404408061248974e-01,1.100000010988609489e+01,1.615790792878259770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302857255511084134e+01,6.340626183349132816e+02,4.251565987070228814e-01,1.100000010988609489e+01,1.615644807476722053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.302948164601085068e+01,6.340726183218617962e+02,4.251727551480687373e-01,1.100000010988609489e+01,1.615498822075184335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303039073691086003e+01,6.340826183088125845e+02,4.251889101292625206e-01,1.100000010988609489e+01,1.615352836673646618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303129982781086937e+01,6.340926182957657602e+02,4.252050636506041759e-01,1.100000010988609489e+01,1.615206851272108900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303220891871087872e+01,6.341026182827213233e+02,4.252212157120937031e-01,1.100000010988609489e+01,1.615060865870571183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303311800961088807e+01,6.341126182696792739e+02,4.252373663137311577e-01,1.100000010988609489e+01,1.614914880469033465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303402710051089741e+01,6.341226182566394982e+02,4.252535154555164842e-01,1.100000010988609489e+01,1.614768895067495748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303493619141090676e+01,6.341326182436021099e+02,4.252696631374496827e-01,1.100000010988609489e+01,1.614622909665958030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303584528231091610e+01,6.341426182305671091e+02,4.252858093595308087e-01,1.100000010988609489e+01,1.614476924264420313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303675437321092545e+01,6.341526182175343820e+02,4.253019541217598065e-01,1.100000010988609489e+01,1.614330938862882595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303766346411093480e+01,6.341626182045040423e+02,4.253180974241366763e-01,1.100000010988609489e+01,1.614184953461344878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303857255501094414e+01,6.341726181914760900e+02,4.253342392666614180e-01,1.100000010988609489e+01,1.614038968059807160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.303948164591095349e+01,6.341826181784505252e+02,4.253503796493340872e-01,1.100000010988609489e+01,1.613892982658269443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304039073681096284e+01,6.341926181654272341e+02,4.253665185721546282e-01,1.100000010988609489e+01,1.613746997256731725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304129982771097218e+01,6.342026181524063304e+02,4.253826560351230412e-01,1.100000010988609489e+01,1.613601011855194008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304220891861098153e+01,6.342126181393878142e+02,4.253987920382393262e-01,1.100000010988609489e+01,1.613455026453656290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304311800951099087e+01,6.342226181263716853e+02,4.254149265815035386e-01,1.100000010988609489e+01,1.613309041052118573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304402710041100022e+01,6.342326181133578302e+02,4.254310596649156229e-01,1.100000010988609489e+01,1.613163055650580855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304493619131100957e+01,6.342426181003463626e+02,4.254471912884755791e-01,1.100000010988609489e+01,1.613017070249043138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304584528221101891e+01,6.342526180873372823e+02,4.254633214521834073e-01,1.100000010988609489e+01,1.612871084847505420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304675437311102826e+01,6.342626180743304758e+02,4.254794501560391629e-01,1.100000010988609489e+01,1.612725099445967702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304766346401103760e+01,6.342726180613260567e+02,4.254955774000427904e-01,1.100000010988609489e+01,1.612579114044429985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304857255491104695e+01,6.342826180483240250e+02,4.255117031841942898e-01,1.100000010988609489e+01,1.612433128642892267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.304948164581105630e+01,6.342926180353243808e+02,4.255278275084936612e-01,1.100000010988609489e+01,1.612287143241354550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305039073671106564e+01,6.343026180223270103e+02,4.255439503729409045e-01,1.100000010988609489e+01,1.612141157839816832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305129982761107499e+01,6.343126180093320272e+02,4.255600717775360753e-01,1.100000010988609489e+01,1.611995172438279115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305220891851108433e+01,6.343226179963394316e+02,4.255761917222791180e-01,1.100000010988609489e+01,1.611849187036741397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305311800941109368e+01,6.343326179833491096e+02,4.255923102071700326e-01,1.100000010988609489e+01,1.611703201635203680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305402710031110303e+01,6.343426179703611751e+02,4.256084272322088191e-01,1.100000010988609489e+01,1.611557216233665962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305493619121111237e+01,6.343526179573756281e+02,4.256245427973954776e-01,1.100000010988609489e+01,1.611411230832128245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305584528211112172e+01,6.343626179443923547e+02,4.256406569027300080e-01,1.100000010988609489e+01,1.611265245430590527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305675437301113107e+01,6.343726179314114688e+02,4.256567695482124103e-01,1.100000010988609489e+01,1.611119260029052810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305766346391114041e+01,6.343826179184329703e+02,4.256728807338427401e-01,1.100000010988609489e+01,1.610973274627515092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305857255481114976e+01,6.343926179054567456e+02,4.256889904596209417e-01,1.100000010988609489e+01,1.610827289225977375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.305948164571115910e+01,6.344026178924829082e+02,4.257050987255470154e-01,1.100000010988609489e+01,1.610681303824439657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306039073661116845e+01,6.344126178795114583e+02,4.257212055316209609e-01,1.100000010988609489e+01,1.610535318422901940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306129982751117780e+01,6.344226178665423959e+02,4.257373108778427784e-01,1.100000010988609489e+01,1.610389333021364222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306220891841118714e+01,6.344326178535756071e+02,4.257534147642124678e-01,1.100000010988609489e+01,1.610243347619826505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306311800931119649e+01,6.344426178406112058e+02,4.257695171907300291e-01,1.100000010988609489e+01,1.610097362218288787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306402710021120583e+01,6.344526178276491919e+02,4.257856181573954624e-01,1.100000010988609489e+01,1.609951376816751070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306493619111121518e+01,6.344626178146894517e+02,4.258017176642087676e-01,1.100000010988609489e+01,1.609805391415213352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306584528201122453e+01,6.344726178017320990e+02,4.258178157111700002e-01,1.100000010988609489e+01,1.609659406013675634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306675437291123387e+01,6.344826177887771337e+02,4.258339122982791047e-01,1.100000010988609489e+01,1.609513420612137917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306766346381124322e+01,6.344926177758244421e+02,4.258500074255360812e-01,1.100000010988609489e+01,1.609367435210600199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306857255471125256e+01,6.345026177628741380e+02,4.258661010929409296e-01,1.100000010988609489e+01,1.609221449809062482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.306948164561126191e+01,6.345126177499262212e+02,4.258821933004936500e-01,1.100000010988609489e+01,1.609075464407524764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307039073651127126e+01,6.345226177369805782e+02,4.258982840481942422e-01,1.100000010988609489e+01,1.608929479005987047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307129982741128060e+01,6.345326177240373227e+02,4.259143733360427064e-01,1.100000010988609489e+01,1.608783493604449329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307220891831128995e+01,6.345426177110964545e+02,4.259304611640390426e-01,1.100000010988609489e+01,1.608637508202911612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307311800921129930e+01,6.345526176981578601e+02,4.259465475321832506e-01,1.100000010988609489e+01,1.608491522801373894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307402710011130864e+01,6.345626176852216531e+02,4.259626324404753306e-01,1.100000010988609489e+01,1.608345537399836177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307493619101131799e+01,6.345726176722878336e+02,4.259787158889152825e-01,1.100000010988609489e+01,1.608199551998298459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307584528191132733e+01,6.345826176593562877e+02,4.259947978775031063e-01,1.100000010988609489e+01,1.608053566596760742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307675437281133668e+01,6.345926176464271293e+02,4.260108784062388021e-01,1.100000010988609489e+01,1.607907581195223024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307766346371134603e+01,6.346026176335002447e+02,4.260269574751223698e-01,1.100000010988609489e+01,1.607761595793685307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307857255461135537e+01,6.346126176205757474e+02,4.260430350841538094e-01,1.100000010988609489e+01,1.607615610392147589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.307948164551136472e+01,6.346226176076536376e+02,4.260591112333331210e-01,1.100000010988609489e+01,1.607469624990609872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308039073641137406e+01,6.346326175947338015e+02,4.260751859226603044e-01,1.100000010988609489e+01,1.607323639589072154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308129982731138341e+01,6.346426175818163529e+02,4.260912591521353598e-01,1.100000010988609489e+01,1.607177654187534437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308220891821139276e+01,6.346526175689012916e+02,4.261073309217582872e-01,1.100000010988609489e+01,1.607031668785996719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308311800911140210e+01,6.346626175559885041e+02,4.261234012315290864e-01,1.100000010988609489e+01,1.606885683384459002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308402710001141145e+01,6.346726175430781041e+02,4.261394700814477576e-01,1.100000010988609489e+01,1.606739697982921284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308493619091142079e+01,6.346826175301700914e+02,4.261555374715143008e-01,1.100000010988609489e+01,1.606593712581383566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308584528181143014e+01,6.346926175172643525e+02,4.261716034017287158e-01,1.100000010988609489e+01,1.606447727179845849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308675437271143949e+01,6.347026175043610010e+02,4.261876678720910028e-01,1.100000010988609489e+01,1.606301741778308131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308766346361144883e+01,6.347126174914599233e+02,4.262037308826011617e-01,1.100000010988609489e+01,1.606155756376770414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308857255451145818e+01,6.347226174785612329e+02,4.262197924332591925e-01,1.100000010988609489e+01,1.606009770975232696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.308948164541146753e+01,6.347326174656649300e+02,4.262358525240650398e-01,1.100000010988609489e+01,1.605863785573694979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309039073631147687e+01,6.347426174527709009e+02,4.262519111550187589e-01,1.100000010988609489e+01,1.605717800172157261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309129982721148622e+01,6.347526174398792591e+02,4.262679683261203500e-01,1.100000010988609489e+01,1.605571814770619544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309220891811149556e+01,6.347626174269900048e+02,4.262840240373698131e-01,1.100000010988609489e+01,1.605425829369081826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309311800901150491e+01,6.347726174141030242e+02,4.263000782887671480e-01,1.100000010988609489e+01,1.605279843967544109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309402709991151426e+01,6.347826174012184310e+02,4.263161310803123549e-01,1.100000010988609489e+01,1.605133858566006391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309493619081152360e+01,6.347926173883361116e+02,4.263321824120054337e-01,1.100000010988609489e+01,1.604987873164468674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309584528171153295e+01,6.348026173754561796e+02,4.263482322838463845e-01,1.100000010988609489e+01,1.604841887762930956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309675437261154229e+01,6.348126173625786350e+02,4.263642806958352072e-01,1.100000010988609489e+01,1.604695902361393239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309766346351155164e+01,6.348226173497033642e+02,4.263803276479718463e-01,1.100000010988609489e+01,1.604549916959855521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309857255441156099e+01,6.348326173368304808e+02,4.263963731402563573e-01,1.100000010988609489e+01,1.604403931558317804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.309948164531157033e+01,6.348426173239598711e+02,4.264124171726887402e-01,1.100000010988609489e+01,1.604257946156780086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310039073621157968e+01,6.348526173110916488e+02,4.264284597452689951e-01,1.100000010988609489e+01,1.604111960755242369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310129982711158902e+01,6.348626172982258140e+02,4.264445008579971219e-01,1.100000010988609489e+01,1.603965975353704651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310220891801159837e+01,6.348726172853622529e+02,4.264605405108731206e-01,1.100000010988609489e+01,1.603819989952166934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310311800891160772e+01,6.348826172725010792e+02,4.264765787038969913e-01,1.100000010988609489e+01,1.603674004550629216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310402709981161706e+01,6.348926172596421793e+02,4.264926154370686784e-01,1.100000010988609489e+01,1.603528019149091498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310493619071162641e+01,6.349026172467856668e+02,4.265086507103882374e-01,1.100000010988609489e+01,1.603382033747553781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310584528161163576e+01,6.349126172339315417e+02,4.265246845238556683e-01,1.100000010988609489e+01,1.603236048346016063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310675437251164510e+01,6.349226172210796904e+02,4.265407168774709712e-01,1.100000010988609489e+01,1.603090062944478346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310766346341165445e+01,6.349326172082302264e+02,4.265567477712341460e-01,1.100000010988609489e+01,1.602944077542940628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310857255431166379e+01,6.349426171953830362e+02,4.265727772051451372e-01,1.100000010988609489e+01,1.602798092141402911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.310948164521167314e+01,6.349526171825382335e+02,4.265888051792040003e-01,1.100000010988609489e+01,1.602652106739865193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311039073611168249e+01,6.349626171696958181e+02,4.266048316934107354e-01,1.100000010988609489e+01,1.602506121338327476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311129982701169183e+01,6.349726171568556765e+02,4.266208567477653424e-01,1.100000010988609489e+01,1.602360135936789758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311220891791170118e+01,6.349826171440179223e+02,4.266368803422677658e-01,1.100000010988609489e+01,1.602214150535252041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311311800881171052e+01,6.349926171311824419e+02,4.266529024769180611e-01,1.100000010988609489e+01,1.602068165133714323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311402709971171987e+01,6.350026171183493489e+02,4.266689231517162284e-01,1.100000010988609489e+01,1.601922179732176606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311493619061172922e+01,6.350126171055185296e+02,4.266849423666622676e-01,1.100000010988609489e+01,1.601776194330638888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311584528151173856e+01,6.350226170926900977e+02,4.267009601217561232e-01,1.100000010988609489e+01,1.601630208929101171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311675437241174791e+01,6.350326170798640533e+02,4.267169764169978508e-01,1.100000010988609489e+01,1.601484223527563453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311766346331175725e+01,6.350426170670402826e+02,4.267329912523874502e-01,1.100000010988609489e+01,1.601338238126025736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311857255421176660e+01,6.350526170542188993e+02,4.267490046279249216e-01,1.100000010988609489e+01,1.601192252724488018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.311948164511177595e+01,6.350626170413997897e+02,4.267650165436102094e-01,1.100000010988609489e+01,1.601046267322950301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312039073601178529e+01,6.350726170285830676e+02,4.267810269994433692e-01,1.100000010988609489e+01,1.600900281921412583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312129982691179464e+01,6.350826170157686192e+02,4.267970359954244008e-01,1.100000010988609489e+01,1.600754296519874866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312220891781180399e+01,6.350926170029565583e+02,4.268130435315532489e-01,1.100000010988609489e+01,1.600608311118337148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312311800871181333e+01,6.351026169901467711e+02,4.268290496078299689e-01,1.100000010988609489e+01,1.600462325716799430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312402709961182268e+01,6.351126169773393713e+02,4.268450542242545609e-01,1.100000010988609489e+01,1.600316340315261713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312493619051183202e+01,6.351226169645343589e+02,4.268610573808270248e-01,1.100000010988609489e+01,1.600170354913723995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312584528141184137e+01,6.351326169517316202e+02,4.268770590775473051e-01,1.100000010988609489e+01,1.600024369512186278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312675437231185072e+01,6.351426169389312690e+02,4.268930593144154573e-01,1.100000010988609489e+01,1.599878384110648560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312766346321186006e+01,6.351526169261331916e+02,4.269090580914314814e-01,1.100000010988609489e+01,1.599732398709110843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312857255411186941e+01,6.351626169133375015e+02,4.269250554085953220e-01,1.100000010988609489e+01,1.599586413307573125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.312948164501187875e+01,6.351726169005440852e+02,4.269410512659070345e-01,1.100000010988609489e+01,1.599440427906035408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313039073591188810e+01,6.351826168877530563e+02,4.269570456633665634e-01,1.100000010988609489e+01,1.599294442504497690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313129982681189745e+01,6.351926168749643011e+02,4.269730386009739642e-01,1.100000010988609489e+01,1.599148457102959973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313220891771190679e+01,6.352026168621779334e+02,4.269890300787292370e-01,1.100000010988609489e+01,1.599002471701422255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313311800861191614e+01,6.352126168493938394e+02,4.270050200966323262e-01,1.100000010988609489e+01,1.598856486299884538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313402709951192548e+01,6.352226168366121328e+02,4.270210086546832873e-01,1.100000010988609489e+01,1.598710500898346820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313493619041193483e+01,6.352326168238328137e+02,4.270369957528821203e-01,1.100000010988609489e+01,1.598564515496809103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313584528131194418e+01,6.352426168110557683e+02,4.270529813912287698e-01,1.100000010988609489e+01,1.598418530095271385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313675437221195352e+01,6.352526167982811103e+02,4.270689655697232912e-01,1.100000010988609489e+01,1.598272544693733668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313766346311196287e+01,6.352626167855087260e+02,4.270849482883656290e-01,1.100000010988609489e+01,1.598126559292195950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313857255401197222e+01,6.352726167727387292e+02,4.271009295471558387e-01,1.100000010988609489e+01,1.597980573890658233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.313948164491198156e+01,6.352826167599710061e+02,4.271169093460939203e-01,1.100000010988609489e+01,1.597834588489120515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314039073581199091e+01,6.352926167472056704e+02,4.271328876851798184e-01,1.100000010988609489e+01,1.597688603087582798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314129982671200025e+01,6.353026167344426085e+02,4.271488645644135884e-01,1.100000010988609489e+01,1.597542617686045080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314220891761200960e+01,6.353126167216819340e+02,4.271648399837951748e-01,1.100000010988609489e+01,1.597396632284507362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314311800851201895e+01,6.353226167089235332e+02,4.271808139433246332e-01,1.100000010988609489e+01,1.597250646882969645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314402709941202829e+01,6.353326166961675199e+02,4.271967864430019080e-01,1.100000010988609489e+01,1.597104661481431927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314493619031203764e+01,6.353426166834137803e+02,4.272127574828270546e-01,1.100000010988609489e+01,1.596958676079894210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314584528121204698e+01,6.353526166706624281e+02,4.272287270628000178e-01,1.100000010988609489e+01,1.596812690678356492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314675437211205633e+01,6.353626166579133496e+02,4.272446951829208528e-01,1.100000010988609489e+01,1.596666705276818775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314766346301206568e+01,6.353726166451666586e+02,4.272606618431895598e-01,1.100000010988609489e+01,1.596520719875281057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314857255391207502e+01,6.353826166324222413e+02,4.272766270436060831e-01,1.100000010988609489e+01,1.596374734473743340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.314948164481208437e+01,6.353926166196802114e+02,4.272925907841704785e-01,1.100000010988609489e+01,1.596228749072205622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315039073571209371e+01,6.354026166069404553e+02,4.273085530648826902e-01,1.100000010988609489e+01,1.596082763670667905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315129982661210306e+01,6.354126165942030866e+02,4.273245138857427738e-01,1.100000010988609489e+01,1.595936778269130187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315220891751211241e+01,6.354226165814679916e+02,4.273404732467506739e-01,1.100000010988609489e+01,1.595790792867592470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315311800841212175e+01,6.354326165687352841e+02,4.273564311479064459e-01,1.100000010988609489e+01,1.595644807466054752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315402709931213110e+01,6.354426165560048503e+02,4.273723875892100343e-01,1.100000010988609489e+01,1.595498822064517035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315493619021214045e+01,6.354526165432768039e+02,4.273883425706614392e-01,1.100000010988609489e+01,1.595352836662979317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315584528111214979e+01,6.354626165305510312e+02,4.274042960922607159e-01,1.100000010988609489e+01,1.595206851261441600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315675437201215914e+01,6.354726165178276460e+02,4.274202481540078091e-01,1.100000010988609489e+01,1.595060865859903882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315766346291216848e+01,6.354826165051065345e+02,4.274361987559027742e-01,1.100000010988609489e+01,1.594914880458366165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315857255381217783e+01,6.354926164923878105e+02,4.274521478979455558e-01,1.100000010988609489e+01,1.594768895056828447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.315948164471218718e+01,6.355026164796713601e+02,4.274680955801362092e-01,1.100000010988609489e+01,1.594622909655290730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316039073561219652e+01,6.355126164669572972e+02,4.274840418024746791e-01,1.100000010988609489e+01,1.594476924253753012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316129982651220587e+01,6.355226164542455081e+02,4.274999865649610209e-01,1.100000010988609489e+01,1.594330938852215294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316220891741221521e+01,6.355326164415361063e+02,4.275159298675951791e-01,1.100000010988609489e+01,1.594184953450677577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316311800831222456e+01,6.355426164288289783e+02,4.275318717103772093e-01,1.100000010988609489e+01,1.594038968049139859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316402709921223391e+01,6.355526164161241240e+02,4.275478120933070558e-01,1.100000010988609489e+01,1.593892982647602142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316493619011224325e+01,6.355626164034216572e+02,4.275637510163847188e-01,1.100000010988609489e+01,1.593746997246064424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316584528101225260e+01,6.355726163907214641e+02,4.275796884796102537e-01,1.100000010988609489e+01,1.593601011844526707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316675437191226194e+01,6.355826163780236584e+02,4.275956244829836050e-01,1.100000010988609489e+01,1.593455026442988989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316766346281227129e+01,6.355926163653281264e+02,4.276115590265048283e-01,1.100000010988609489e+01,1.593309041041451272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316857255371228064e+01,6.356026163526349819e+02,4.276274921101738680e-01,1.100000010988609489e+01,1.593163055639913554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.316948164461228998e+01,6.356126163399441111e+02,4.276434237339907241e-01,1.100000010988609489e+01,1.593017070238375837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317039073551229933e+01,6.356226163272556278e+02,4.276593538979554521e-01,1.100000010988609489e+01,1.592871084836838119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317129982641230868e+01,6.356326163145694181e+02,4.276752826020679965e-01,1.100000010988609489e+01,1.592725099435300402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317220891731231802e+01,6.356426163018855959e+02,4.276912098463283574e-01,1.100000010988609489e+01,1.592579114033762684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317311800821232737e+01,6.356526162892040475e+02,4.277071356307365901e-01,1.100000010988609489e+01,1.592433128632224967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317402709911233671e+01,6.356626162765248864e+02,4.277230599552926393e-01,1.100000010988609489e+01,1.592287143230687249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317493619001234606e+01,6.356726162638479991e+02,4.277389828199965049e-01,1.100000010988609489e+01,1.592141157829149532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317584528091235541e+01,6.356826162511733855e+02,4.277549042248482425e-01,1.100000010988609489e+01,1.591995172427611814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317675437181236475e+01,6.356926162385011594e+02,4.277708241698477964e-01,1.100000010988609489e+01,1.591849187026074097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317766346271237410e+01,6.357026162258312070e+02,4.277867426549951668e-01,1.100000010988609489e+01,1.591703201624536379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317857255361238344e+01,6.357126162131636420e+02,4.278026596802904091e-01,1.100000010988609489e+01,1.591557216222998661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.317948164451239279e+01,6.357226162004983507e+02,4.278185752457334678e-01,1.100000010988609489e+01,1.591411230821460944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318039073541240214e+01,6.357326161878354469e+02,4.278344893513243430e-01,1.100000010988609489e+01,1.591265245419923226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318129982631241148e+01,6.357426161751748168e+02,4.278504019970630901e-01,1.100000010988609489e+01,1.591119260018385509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318220891721242083e+01,6.357526161625164605e+02,4.278663131829496535e-01,1.100000010988609489e+01,1.590973274616847791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318311800811243018e+01,6.357626161498604915e+02,4.278822229089840334e-01,1.100000010988609489e+01,1.590827289215310074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318402709901243952e+01,6.357726161372067963e+02,4.278981311751662853e-01,1.100000010988609489e+01,1.590681303813772356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318493618991244887e+01,6.357826161245554886e+02,4.279140379814963535e-01,1.100000010988609489e+01,1.590535318412234639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318584528081245821e+01,6.357926161119064545e+02,4.279299433279742382e-01,1.100000010988609489e+01,1.590389333010696921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318675437171246756e+01,6.358026160992598079e+02,4.279458472145999393e-01,1.100000010988609489e+01,1.590243347609159204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318766346261247691e+01,6.358126160866154351e+02,4.279617496413735123e-01,1.100000010988609489e+01,1.590097362207621486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318857255351248625e+01,6.358226160739733359e+02,4.279776506082949017e-01,1.100000010988609489e+01,1.589951376806083769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.318948164441249560e+01,6.358326160613336242e+02,4.279935501153641075e-01,1.100000010988609489e+01,1.589805391404546051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319039073531250494e+01,6.358426160486961862e+02,4.280094481625811298e-01,1.100000010988609489e+01,1.589659406003008334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319129982621251429e+01,6.358526160360611357e+02,4.280253447499460240e-01,1.100000010988609489e+01,1.589513420601470616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319220891711252364e+01,6.358626160234283589e+02,4.280412398774587346e-01,1.100000010988609489e+01,1.589367435199932899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319311800801253298e+01,6.358726160107979695e+02,4.280571335451192616e-01,1.100000010988609489e+01,1.589221449798395181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319402709891254233e+01,6.358826159981698538e+02,4.280730257529276050e-01,1.100000010988609489e+01,1.589075464396857464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319493618981255167e+01,6.358926159855440119e+02,4.280889165008837649e-01,1.100000010988609489e+01,1.588929478995319746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319584528071256102e+01,6.359026159729205574e+02,4.281048057889877967e-01,1.100000010988609489e+01,1.588783493593782029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319675437161257037e+01,6.359126159602993766e+02,4.281206936172396449e-01,1.100000010988609489e+01,1.588637508192244311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319766346251257971e+01,6.359226159476805833e+02,4.281365799856393095e-01,1.100000010988609489e+01,1.588491522790706593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319857255341258906e+01,6.359326159350640637e+02,4.281524648941867905e-01,1.100000010988609489e+01,1.588345537389168876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.319948164431259841e+01,6.359426159224498178e+02,4.281683483428820880e-01,1.100000010988609489e+01,1.588199551987631158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320039073521260775e+01,6.359526159098379594e+02,4.281842303317252574e-01,1.100000010988609489e+01,1.588053566586093441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320129982611261710e+01,6.359626158972283747e+02,4.282001108607162432e-01,1.100000010988609489e+01,1.587907581184555723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320220891701262644e+01,6.359726158846211774e+02,4.282159899298550454e-01,1.100000010988609489e+01,1.587761595783018006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320311800791263579e+01,6.359826158720162539e+02,4.282318675391416640e-01,1.100000010988609489e+01,1.587615610381480288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320402709881264514e+01,6.359926158594136041e+02,4.282477436885760991e-01,1.100000010988609489e+01,1.587469624979942571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320493618971265448e+01,6.360026158468133417e+02,4.282636183781583505e-01,1.100000010988609489e+01,1.587323639578404853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320584528061266383e+01,6.360126158342153531e+02,4.282794916078884184e-01,1.100000010988609489e+01,1.587177654176867136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320675437151267317e+01,6.360226158216196382e+02,4.282953633777663582e-01,1.100000010988609489e+01,1.587031668775329418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320766346241268252e+01,6.360326158090263107e+02,4.283112336877921145e-01,1.100000010988609489e+01,1.586885683373791701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320857255331269187e+01,6.360426157964352569e+02,4.283271025379656871e-01,1.100000010988609489e+01,1.586739697972253983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.320948164421270121e+01,6.360526157838465906e+02,4.283429699282870762e-01,1.100000010988609489e+01,1.586593712570716266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321039073511271056e+01,6.360626157712601980e+02,4.283588358587562817e-01,1.100000010988609489e+01,1.586447727169178548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321129982601271990e+01,6.360726157586760792e+02,4.283747003293733036e-01,1.100000010988609489e+01,1.586301741767640831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321220891691272925e+01,6.360826157460943477e+02,4.283905633401381419e-01,1.100000010988609489e+01,1.586155756366103113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321311800781273860e+01,6.360926157335148901e+02,4.284064248910507966e-01,1.100000010988609489e+01,1.586009770964565396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321402709871274794e+01,6.361026157209377061e+02,4.284222849821112677e-01,1.100000010988609489e+01,1.585863785563027678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321493618961275729e+01,6.361126157083629096e+02,4.284381436133195553e-01,1.100000010988609489e+01,1.585717800161489961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321584528051276664e+01,6.361226156957903868e+02,4.284540007846757148e-01,1.100000010988609489e+01,1.585571814759952243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321675437141277598e+01,6.361326156832202514e+02,4.284698564961796907e-01,1.100000010988609489e+01,1.585425829358414525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321766346231278533e+01,6.361426156706523898e+02,4.284857107478314830e-01,1.100000010988609489e+01,1.585279843956876808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321857255321279467e+01,6.361526156580868019e+02,4.285015635396310918e-01,1.100000010988609489e+01,1.585133858555339090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.321948164411280402e+01,6.361626156455236014e+02,4.285174148715785170e-01,1.100000010988609489e+01,1.584987873153801373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322039073501281337e+01,6.361726156329626747e+02,4.285332647436737585e-01,1.100000010988609489e+01,1.584841887752263655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322129982591282271e+01,6.361826156204040217e+02,4.285491131559168165e-01,1.100000010988609489e+01,1.584695902350725938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322220891681283206e+01,6.361926156078477561e+02,4.285649601083076909e-01,1.100000010988609489e+01,1.584549916949188220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322311800771284140e+01,6.362026155952937643e+02,4.285808056008463818e-01,1.100000010988609489e+01,1.584403931547650503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322402709861285075e+01,6.362126155827420462e+02,4.285966496335328890e-01,1.100000010988609489e+01,1.584257946146112785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322493618951286010e+01,6.362226155701927155e+02,4.286124922063672127e-01,1.100000010988609489e+01,1.584111960744575068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322584528041286944e+01,6.362326155576456586e+02,4.286283333193493528e-01,1.100000010988609489e+01,1.583965975343037350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322675437131287879e+01,6.362426155451008754e+02,4.286441729724793093e-01,1.100000010988609489e+01,1.583819989941499633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322766346221288813e+01,6.362526155325584796e+02,4.286600111657570822e-01,1.100000010988609489e+01,1.583674004539961915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322857255311289748e+01,6.362626155200183575e+02,4.286758478991826715e-01,1.100000010988609489e+01,1.583528019138424198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.322948164401290683e+01,6.362726155074805092e+02,4.286916831727560773e-01,1.100000010988609489e+01,1.583382033736886480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323039073491291617e+01,6.362826154949450483e+02,4.287075169864772994e-01,1.100000010988609489e+01,1.583236048335348763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323129982581292552e+01,6.362926154824118612e+02,4.287233493403463380e-01,1.100000010988609489e+01,1.583090062933811045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323220891671293487e+01,6.363026154698809478e+02,4.287391802343631930e-01,1.100000010988609489e+01,1.582944077532273328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323311800761294421e+01,6.363126154573524218e+02,4.287550096685278644e-01,1.100000010988609489e+01,1.582798092130735610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323402709851295356e+01,6.363226154448261696e+02,4.287708376428403523e-01,1.100000010988609489e+01,1.582652106729197893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323493618941296290e+01,6.363326154323021910e+02,4.287866641573006565e-01,1.100000010988609489e+01,1.582506121327660175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323584528031297225e+01,6.363426154197806000e+02,4.288024892119087772e-01,1.100000010988609489e+01,1.582360135926122457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323675437121298160e+01,6.363526154072612826e+02,4.288183128066646588e-01,1.100000010988609489e+01,1.582214150524584740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323766346211299094e+01,6.363626153947442390e+02,4.288341349415683568e-01,1.100000010988609489e+01,1.582068165123047022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323857255301300029e+01,6.363726153822295828e+02,4.288499556166198712e-01,1.100000010988609489e+01,1.581922179721509305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.323948164391300963e+01,6.363826153697172003e+02,4.288657748318192020e-01,1.100000010988609489e+01,1.581776194319971587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324039073481301898e+01,6.363926153572070916e+02,4.288815925871663493e-01,1.100000010988609489e+01,1.581630208918433870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324129982571302833e+01,6.364026153446993703e+02,4.288974088826613129e-01,1.100000010988609489e+01,1.581484223516896152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324220891661303767e+01,6.364126153321939228e+02,4.289132237183040930e-01,1.100000010988609489e+01,1.581338238115358435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324311800751304702e+01,6.364226153196907489e+02,4.289290370940946895e-01,1.100000010988609489e+01,1.581192252713820717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324402709841305636e+01,6.364326153071899626e+02,4.289448490100331024e-01,1.100000010988609489e+01,1.581046267312283000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324493618931306571e+01,6.364426152946914499e+02,4.289606594661193317e-01,1.100000010988609489e+01,1.580900281910745282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324584528021307506e+01,6.364526152821952110e+02,4.289764684623533220e-01,1.100000010988609489e+01,1.580754296509207565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324675437111308440e+01,6.364626152697012458e+02,4.289922759987351286e-01,1.100000010988609489e+01,1.580608311107669847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324766346201309375e+01,6.364726152572096680e+02,4.290080820752647517e-01,1.100000010988609489e+01,1.580462325706132130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324857255291310310e+01,6.364826152447203640e+02,4.290238866919421912e-01,1.100000010988609489e+01,1.580316340304594412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.324948164381311244e+01,6.364926152322333337e+02,4.290396898487674471e-01,1.100000010988609489e+01,1.580170354903056695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325039073471312179e+01,6.365026152197486908e+02,4.290554915457405194e-01,1.100000010988609489e+01,1.580024369501518977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325129982561313113e+01,6.365126152072663217e+02,4.290712917828613526e-01,1.100000010988609489e+01,1.579878384099981260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325220891651314048e+01,6.365226151947862263e+02,4.290870905601300023e-01,1.100000010988609489e+01,1.579732398698443542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325311800741314983e+01,6.365326151823084047e+02,4.291028878775464683e-01,1.100000010988609489e+01,1.579586413296905825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325402709831315917e+01,6.365426151698329704e+02,4.291186837351107508e-01,1.100000010988609489e+01,1.579440427895368107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325493618921316852e+01,6.365526151573598099e+02,4.291344781328228497e-01,1.100000010988609489e+01,1.579294442493830389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325584528011317786e+01,6.365626151448889232e+02,4.291502710706827650e-01,1.100000010988609489e+01,1.579148457092292672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325675437101318721e+01,6.365726151324204238e+02,4.291660625486904412e-01,1.100000010988609489e+01,1.579002471690754954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325766346191319656e+01,6.365826151199541982e+02,4.291818525668459339e-01,1.100000010988609489e+01,1.578856486289217237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325857255281320590e+01,6.365926151074902464e+02,4.291976411251492429e-01,1.100000010988609489e+01,1.578710500887679519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.325948164371321525e+01,6.366026150950285682e+02,4.292134282236003684e-01,1.100000010988609489e+01,1.578564515486141802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326039073461322459e+01,6.366126150825692775e+02,4.292292138621992548e-01,1.100000010988609489e+01,1.578418530084604084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326129982551323394e+01,6.366226150701122606e+02,4.292449980409459576e-01,1.100000010988609489e+01,1.578272544683066367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326220891641324329e+01,6.366326150576575174e+02,4.292607807598404768e-01,1.100000010988609489e+01,1.578126559281528649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326311800731325263e+01,6.366426150452050479e+02,4.292765620188828124e-01,1.100000010988609489e+01,1.577980573879990932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326402709821326198e+01,6.366526150327549658e+02,4.292923418180729089e-01,1.100000010988609489e+01,1.577834588478453214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326493618911327133e+01,6.366626150203071575e+02,4.293081201574108219e-01,1.100000010988609489e+01,1.577688603076915497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326584528001328067e+01,6.366726150078616229e+02,4.293238970368965512e-01,1.100000010988609489e+01,1.577542617675377779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326675437091329002e+01,6.366826149954184757e+02,4.293396724565300970e-01,1.100000010988609489e+01,1.577396632273840062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326766346181329936e+01,6.366926149829776023e+02,4.293554464163114037e-01,1.100000010988609489e+01,1.577250646872302344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326857255271330871e+01,6.367026149705390026e+02,4.293712189162405268e-01,1.100000010988609489e+01,1.577104661470764627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.326948164361331806e+01,6.367126149581026766e+02,4.293869899563174664e-01,1.100000010988609489e+01,1.576958676069226909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327039073451332740e+01,6.367226149456687381e+02,4.294027595365422223e-01,1.100000010988609489e+01,1.576812690667689192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327129982541333675e+01,6.367326149332370733e+02,4.294185276569147391e-01,1.100000010988609489e+01,1.576666705266151474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327220891631334609e+01,6.367426149208076822e+02,4.294342943174350724e-01,1.100000010988609489e+01,1.576520719864613757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327311800721335544e+01,6.367526149083805649e+02,4.294500595181032221e-01,1.100000010988609489e+01,1.576374734463076039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327402709811336479e+01,6.367626148959558350e+02,4.294658232589191327e-01,1.100000010988609489e+01,1.576228749061538321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327493618901337413e+01,6.367726148835333788e+02,4.294815855398828597e-01,1.100000010988609489e+01,1.576082763660000604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327584527991338348e+01,6.367826148711131964e+02,4.294973463609944031e-01,1.100000010988609489e+01,1.575936778258462886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327675437081339282e+01,6.367926148586952877e+02,4.295131057222537074e-01,1.100000010988609489e+01,1.575790792856925169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327766346171340217e+01,6.368026148462796527e+02,4.295288636236608282e-01,1.100000010988609489e+01,1.575644807455387451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327857255261341152e+01,6.368126148338664052e+02,4.295446200652157653e-01,1.100000010988609489e+01,1.575498822053849734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.327948164351342086e+01,6.368226148214554314e+02,4.295603750469184634e-01,1.100000010988609489e+01,1.575352836652312016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328039073441343021e+01,6.368326148090467314e+02,4.295761285687689779e-01,1.100000010988609489e+01,1.575206851250774299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328129982531343956e+01,6.368426147966403050e+02,4.295918806307672533e-01,1.100000010988609489e+01,1.575060865849236581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328220891621344890e+01,6.368526147842362661e+02,4.296076312329133451e-01,1.100000010988609489e+01,1.574914880447698864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328311800711345825e+01,6.368626147718345010e+02,4.296233803752072533e-01,1.100000010988609489e+01,1.574768895046161146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328402709801346759e+01,6.368726147594350095e+02,4.296391280576489224e-01,1.100000010988609489e+01,1.574622909644623429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328493618891347694e+01,6.368826147470377919e+02,4.296548742802384080e-01,1.100000010988609489e+01,1.574476924243085711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328584527981348629e+01,6.368926147346429616e+02,4.296706190429757100e-01,1.100000010988609489e+01,1.574330938841547994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328675437071349563e+01,6.369026147222504051e+02,4.296863623458607728e-01,1.100000010988609489e+01,1.574184953440010276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328766346161350498e+01,6.369126147098601223e+02,4.297021041888936521e-01,1.100000010988609489e+01,1.574038968038472559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328857255251351432e+01,6.369226146974721132e+02,4.297178445720742923e-01,1.100000010988609489e+01,1.573892982636934841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.328948164341352367e+01,6.369326146850863779e+02,4.297335834954027489e-01,1.100000010988609489e+01,1.573746997235397124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329039073431353302e+01,6.369426146727030300e+02,4.297493209588789664e-01,1.100000010988609489e+01,1.573601011833859406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329129982521354236e+01,6.369526146603219559e+02,4.297650569625030004e-01,1.100000010988609489e+01,1.573455026432321689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329220891611355171e+01,6.369626146479431554e+02,4.297807915062748507e-01,1.100000010988609489e+01,1.573309041030783971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329311800701356105e+01,6.369726146355666287e+02,4.297965245901944620e-01,1.100000010988609489e+01,1.573163055629246253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329402709791357040e+01,6.369826146231923758e+02,4.298122562142618897e-01,1.100000010988609489e+01,1.573017070227708536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329493618881357975e+01,6.369926146108205103e+02,4.298279863784770782e-01,1.100000010988609489e+01,1.572871084826170818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329584527971358909e+01,6.370026145984509185e+02,4.298437150828400832e-01,1.100000010988609489e+01,1.572725099424633101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329675437061359844e+01,6.370126145860836004e+02,4.298594423273508491e-01,1.100000010988609489e+01,1.572579114023095383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329766346151360779e+01,6.370226145737185561e+02,4.298751681120094315e-01,1.100000010988609489e+01,1.572433128621557666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329857255241361713e+01,6.370326145613557856e+02,4.298908924368157747e-01,1.100000010988609489e+01,1.572287143220019948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.329948164331362648e+01,6.370426145489954024e+02,4.299066153017699343e-01,1.100000010988609489e+01,1.572141157818482231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330039073421363582e+01,6.370526145366372930e+02,4.299223367068718549e-01,1.100000010988609489e+01,1.571995172416944513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330129982511364517e+01,6.370626145242814573e+02,4.299380566521215918e-01,1.100000010988609489e+01,1.571849187015406796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330220891601365452e+01,6.370726145119278954e+02,4.299537751375190897e-01,1.100000010988609489e+01,1.571703201613869078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330311800691366386e+01,6.370826144995766072e+02,4.299694921630644040e-01,1.100000010988609489e+01,1.571557216212331361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330402709781367321e+01,6.370926144872275927e+02,4.299852077287574792e-01,1.100000010988609489e+01,1.571411230810793643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330493618871368255e+01,6.371026144748809656e+02,4.300009218345983708e-01,1.100000010988609489e+01,1.571265245409255926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330584527961369190e+01,6.371126144625366123e+02,4.300166344805870233e-01,1.100000010988609489e+01,1.571119260007718208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330675437051370125e+01,6.371226144501945328e+02,4.300323456667234923e-01,1.100000010988609489e+01,1.570973274606180491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330766346141371059e+01,6.371326144378547269e+02,4.300480553930077221e-01,1.100000010988609489e+01,1.570827289204642773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330857255231371994e+01,6.371426144255171948e+02,4.300637636594397684e-01,1.100000010988609489e+01,1.570681303803105056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.330948164321372928e+01,6.371526144131820502e+02,4.300794704660195755e-01,1.100000010988609489e+01,1.570535318401567338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331039073411373863e+01,6.371626144008491792e+02,4.300951758127471436e-01,1.100000010988609489e+01,1.570389333000029621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331129982501374798e+01,6.371726143885185820e+02,4.301108796996225281e-01,1.100000010988609489e+01,1.570243347598491903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331220891591375732e+01,6.371826143761902586e+02,4.301265821266456735e-01,1.100000010988609489e+01,1.570097362196954185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331311800681376667e+01,6.371926143638642088e+02,4.301422830938166353e-01,1.100000010988609489e+01,1.569951376795416468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331402709771377602e+01,6.372026143515404328e+02,4.301579826011353580e-01,1.100000010988609489e+01,1.569805391393878750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331493618861378536e+01,6.372126143392190443e+02,4.301736806486018971e-01,1.100000010988609489e+01,1.569659405992341033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331584527951379471e+01,6.372226143268999294e+02,4.301893772362161972e-01,1.100000010988609489e+01,1.569513420590803315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331675437041380405e+01,6.372326143145830883e+02,4.302050723639782581e-01,1.100000010988609489e+01,1.569367435189265598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331766346131381340e+01,6.372426143022685210e+02,4.302207660318881355e-01,1.100000010988609489e+01,1.569221449787727880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331857255221382275e+01,6.372526142899562274e+02,4.302364582399457738e-01,1.100000010988609489e+01,1.569075464386190163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.331948164311383209e+01,6.372626142776462075e+02,4.302521489881512284e-01,1.100000010988609489e+01,1.568929478984652445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332039073401384144e+01,6.372726142653384613e+02,4.302678382765044440e-01,1.100000010988609489e+01,1.568783493583114728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332129982491385078e+01,6.372826142530331026e+02,4.302835261050054205e-01,1.100000010988609489e+01,1.568637508181577010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332220891581386013e+01,6.372926142407300176e+02,4.302992124736542134e-01,1.100000010988609489e+01,1.568491522780039293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332311800671386948e+01,6.373026142284292064e+02,4.303148973824507673e-01,1.100000010988609489e+01,1.568345537378501575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332402709761387882e+01,6.373126142161306689e+02,4.303305808313950820e-01,1.100000010988609489e+01,1.568199551976963858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332493618851388817e+01,6.373226142038344051e+02,4.303462628204872131e-01,1.100000010988609489e+01,1.568053566575426140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332584527941389752e+01,6.373326141915404150e+02,4.303619433497271052e-01,1.100000010988609489e+01,1.567907581173888423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332675437031390686e+01,6.373426141792486987e+02,4.303776224191147581e-01,1.100000010988609489e+01,1.567761595772350705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332766346121391621e+01,6.373526141669593699e+02,4.303933000286502275e-01,1.100000010988609489e+01,1.567615610370812988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332857255211392555e+01,6.373626141546723147e+02,4.304089761783334578e-01,1.100000010988609489e+01,1.567469624969275270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.332948164301393490e+01,6.373726141423875333e+02,4.304246508681644490e-01,1.100000010988609489e+01,1.567323639567737553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333039073391394425e+01,6.373826141301050257e+02,4.304403240981432566e-01,1.100000010988609489e+01,1.567177654166199835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333129982481395359e+01,6.373926141178247917e+02,4.304559958682698251e-01,1.100000010988609489e+01,1.567031668764662117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333220891571396294e+01,6.374026141055468315e+02,4.304716661785441545e-01,1.100000010988609489e+01,1.566885683363124400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333311800661397228e+01,6.374126140932711451e+02,4.304873350289662448e-01,1.100000010988609489e+01,1.566739697961586682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333402709751398163e+01,6.374226140809977323e+02,4.305030024195361515e-01,1.100000010988609489e+01,1.566593712560048965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333493618841399098e+01,6.374326140687267070e+02,4.305186683502538192e-01,1.100000010988609489e+01,1.566447727158511247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333584527931400032e+01,6.374426140564579555e+02,4.305343328211192477e-01,1.100000010988609489e+01,1.566301741756973530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333675437021400967e+01,6.374526140441914777e+02,4.305499958321324927e-01,1.100000010988609489e+01,1.566155756355435812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333766346111401901e+01,6.374626140319272736e+02,4.305656573832934986e-01,1.100000010988609489e+01,1.566009770953898095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333857255201402836e+01,6.374726140196653432e+02,4.305813174746022653e-01,1.100000010988609489e+01,1.565863785552360377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.333948164291403771e+01,6.374826140074056866e+02,4.305969761060587930e-01,1.100000010988609489e+01,1.565717800150822660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334039073381404705e+01,6.374926139951483037e+02,4.306126332776631371e-01,1.100000010988609489e+01,1.565571814749284942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334129982471405640e+01,6.375026139828931946e+02,4.306282889894152421e-01,1.100000010988609489e+01,1.565425829347747225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334220891561406575e+01,6.375126139706403592e+02,4.306439432413151081e-01,1.100000010988609489e+01,1.565279843946209507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334311800651407509e+01,6.375226139583899112e+02,4.306595960333627349e-01,1.100000010988609489e+01,1.565133858544671790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334402709741408444e+01,6.375326139461417370e+02,4.306752473655581226e-01,1.100000010988609489e+01,1.564987873143134072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334493618831409378e+01,6.375426139338958365e+02,4.306908972379013267e-01,1.100000010988609489e+01,1.564841887741596355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334584527921410313e+01,6.375526139216522097e+02,4.307065456503922918e-01,1.100000010988609489e+01,1.564695902340058637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334675437011411248e+01,6.375626139094108566e+02,4.307221926030310177e-01,1.100000010988609489e+01,1.564549916938520920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334766346101412182e+01,6.375726138971717774e+02,4.307378380958175046e-01,1.100000010988609489e+01,1.564403931536983202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334857255191413117e+01,6.375826138849349718e+02,4.307534821287517524e-01,1.100000010988609489e+01,1.564257946135445485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.334948164281414051e+01,6.375926138727004400e+02,4.307691247018338165e-01,1.100000010988609489e+01,1.564111960733907767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335039073371414986e+01,6.376026138604681819e+02,4.307847658150636416e-01,1.100000010988609489e+01,1.563965975332370049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335129982461415921e+01,6.376126138482381975e+02,4.308004054684412276e-01,1.100000010988609489e+01,1.563819989930832332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335220891551416855e+01,6.376226138360104869e+02,4.308160436619665745e-01,1.100000010988609489e+01,1.563674004529294614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335311800641417790e+01,6.376326138237851637e+02,4.308316803956396823e-01,1.100000010988609489e+01,1.563528019127756897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335402709731418724e+01,6.376426138115621143e+02,4.308473156694605510e-01,1.100000010988609489e+01,1.563382033726219179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335493618821419659e+01,6.376526137993413386e+02,4.308629494834292362e-01,1.100000010988609489e+01,1.563236048324681462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335584527911420594e+01,6.376626137871228366e+02,4.308785818375456822e-01,1.100000010988609489e+01,1.563090062923143744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335675437001421528e+01,6.376726137749066083e+02,4.308942127318098891e-01,1.100000010988609489e+01,1.562944077521606027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335766346091422463e+01,6.376826137626926538e+02,4.309098421662218570e-01,1.100000010988609489e+01,1.562798092120068309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335857255181423398e+01,6.376926137504809731e+02,4.309254701407815857e-01,1.100000010988609489e+01,1.562652106718530592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.335948164271424332e+01,6.377026137382715660e+02,4.309410966554890754e-01,1.100000010988609489e+01,1.562506121316992874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336039073361425267e+01,6.377126137260644327e+02,4.309567217103443260e-01,1.100000010988609489e+01,1.562360135915455157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336129982451426201e+01,6.377226137138595732e+02,4.309723453053473374e-01,1.100000010988609489e+01,1.562214150513917439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336220891541427136e+01,6.377326137016569874e+02,4.309879674404981098e-01,1.100000010988609489e+01,1.562068165112379722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336311800631428071e+01,6.377426136894566753e+02,4.310035881157966986e-01,1.100000010988609489e+01,1.561922179710842004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336402709721429005e+01,6.377526136772586369e+02,4.310192073312430483e-01,1.100000010988609489e+01,1.561776194309304287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336493618811429940e+01,6.377626136650628723e+02,4.310348250868371589e-01,1.100000010988609489e+01,1.561630208907766569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336584527901430874e+01,6.377726136528693814e+02,4.310504413825790304e-01,1.100000010988609489e+01,1.561484223506228852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336675436991431809e+01,6.377826136406781643e+02,4.310660562184686628e-01,1.100000010988609489e+01,1.561338238104691134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336766346081432744e+01,6.377926136284893346e+02,4.310816695945060562e-01,1.100000010988609489e+01,1.561192252703153416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336857255171433678e+01,6.378026136163027786e+02,4.310972815106912104e-01,1.100000010988609489e+01,1.561046267301615699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.336948164261434613e+01,6.378126136041184964e+02,4.311128919670241255e-01,1.100000010988609489e+01,1.560900281900077981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337039073351435547e+01,6.378226135919364879e+02,4.311285009635048016e-01,1.100000010988609489e+01,1.560754296498540264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337129982441436482e+01,6.378326135797567531e+02,4.311441085001332385e-01,1.100000010988609489e+01,1.560608311097002546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337220891531437417e+01,6.378426135675792921e+02,4.311597145769094364e-01,1.100000010988609489e+01,1.560462325695464829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337311800621438351e+01,6.378526135554041048e+02,4.311753191938333951e-01,1.100000010988609489e+01,1.560316340293927111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337402709711439286e+01,6.378626135432311912e+02,4.311909223509051148e-01,1.100000010988609489e+01,1.560170354892389394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337493618801440221e+01,6.378726135310605514e+02,4.312065240481245953e-01,1.100000010988609489e+01,1.560024369490851676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337584527891441155e+01,6.378826135188921853e+02,4.312221242854918368e-01,1.100000010988609489e+01,1.559878384089313959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337675436981442090e+01,6.378926135067260930e+02,4.312377230630068392e-01,1.100000010988609489e+01,1.559732398687776241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337766346071443024e+01,6.379026134945622744e+02,4.312533203806696025e-01,1.100000010988609489e+01,1.559586413286238524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337857255161443959e+01,6.379126134824007295e+02,4.312689162384801267e-01,1.100000010988609489e+01,1.559440427884700806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.337948164251444894e+01,6.379226134702414583e+02,4.312845106364384118e-01,1.100000010988609489e+01,1.559294442483163089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338039073341445828e+01,6.379326134580844609e+02,4.313001035745444578e-01,1.100000010988609489e+01,1.559148457081625371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338129982431446763e+01,6.379426134459297373e+02,4.313156950527982647e-01,1.100000010988609489e+01,1.559002471680087654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338220891521447697e+01,6.379526134337772874e+02,4.313312850711998325e-01,1.100000010988609489e+01,1.558856486278549936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338311800611448632e+01,6.379626134216271112e+02,4.313468736297491612e-01,1.100000010988609489e+01,1.558710500877012219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338402709701449567e+01,6.379726134094792087e+02,4.313624607284462509e-01,1.100000010988609489e+01,1.558564515475474501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338493618791450501e+01,6.379826133973335800e+02,4.313780463672911014e-01,1.100000010988609489e+01,1.558418530073936784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338584527881451436e+01,6.379926133851902250e+02,4.313936305462837129e-01,1.100000010988609489e+01,1.558272544672399066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338675436971452370e+01,6.380026133730491438e+02,4.314092132654240852e-01,1.100000010988609489e+01,1.558126559270861348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338766346061453305e+01,6.380126133609103363e+02,4.314247945247122185e-01,1.100000010988609489e+01,1.557980573869323631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338857255151454240e+01,6.380226133487738025e+02,4.314403743241481126e-01,1.100000010988609489e+01,1.557834588467785913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.338948164241455174e+01,6.380326133366395425e+02,4.314559526637317677e-01,1.100000010988609489e+01,1.557688603066248196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339039073331456109e+01,6.380426133245075562e+02,4.314715295434631281e-01,1.100000010988609489e+01,1.557542617664710478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339129982421457044e+01,6.380526133123778436e+02,4.314871049633422495e-01,1.100000010988609489e+01,1.557396632263172761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339220891511457978e+01,6.380626133002504048e+02,4.315026789233691318e-01,1.100000010988609489e+01,1.557250646861635043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339311800601458913e+01,6.380726132881252397e+02,4.315182514235437750e-01,1.100000010988609489e+01,1.557104661460097326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339402709691459847e+01,6.380826132760023484e+02,4.315338224638661790e-01,1.100000010988609489e+01,1.556958676058559608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339493618781460782e+01,6.380926132638817307e+02,4.315493920443363440e-01,1.100000010988609489e+01,1.556812690657021891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339584527871461717e+01,6.381026132517633869e+02,4.315649601649542699e-01,1.100000010988609489e+01,1.556666705255484173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339675436961462651e+01,6.381126132396473167e+02,4.315805268257199567e-01,1.100000010988609489e+01,1.556520719853946456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339766346051463586e+01,6.381226132275335203e+02,4.315960920266334044e-01,1.100000010988609489e+01,1.556374734452408738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339857255141464520e+01,6.381326132154219977e+02,4.316116557676945575e-01,1.100000010988609489e+01,1.556228749050871021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.339948164231465455e+01,6.381426132033127487e+02,4.316272180489034715e-01,1.100000010988609489e+01,1.556082763649333303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340039073321466390e+01,6.381526131912057735e+02,4.316427788702601465e-01,1.100000010988609489e+01,1.555936778247795586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340129982411467324e+01,6.381626131791010721e+02,4.316583382317645823e-01,1.100000010988609489e+01,1.555790792846257868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340220891501468259e+01,6.381726131669986444e+02,4.316738961334167790e-01,1.100000010988609489e+01,1.555644807444720151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340311800591469193e+01,6.381826131548984904e+02,4.316894525752167366e-01,1.100000010988609489e+01,1.555498822043182433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340402709681470128e+01,6.381926131428006101e+02,4.317050075571643997e-01,1.100000010988609489e+01,1.555352836641644716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340493618771471063e+01,6.382026131307050036e+02,4.317205610792598236e-01,1.100000010988609489e+01,1.555206851240106998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340584527861471997e+01,6.382126131186116709e+02,4.317361131415030084e-01,1.100000010988609489e+01,1.555060865838569280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340675436951472932e+01,6.382226131065206118e+02,4.317516637438939542e-01,1.100000010988609489e+01,1.554914880437031563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340766346041473867e+01,6.382326130944318265e+02,4.317672128864326608e-01,1.100000010988609489e+01,1.554768895035493845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340857255131474801e+01,6.382426130823453150e+02,4.317827605691190729e-01,1.100000010988609489e+01,1.554622909633956128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.340948164221475736e+01,6.382526130702610772e+02,4.317983067919532458e-01,1.100000010988609489e+01,1.554476924232418410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341039073311476670e+01,6.382626130581791131e+02,4.318138515549351797e-01,1.100000010988609489e+01,1.554330938830880693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341129982401477605e+01,6.382726130460994227e+02,4.318293948580648745e-01,1.100000010988609489e+01,1.554184953429342975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341220891491478540e+01,6.382826130340220061e+02,4.318449367013423301e-01,1.100000010988609489e+01,1.554038968027805258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341311800581479474e+01,6.382926130219468632e+02,4.318604770847674912e-01,1.100000010988609489e+01,1.553892982626267540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341402709671480409e+01,6.383026130098739941e+02,4.318760160083404132e-01,1.100000010988609489e+01,1.553746997224729823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341493618761481343e+01,6.383126129978033987e+02,4.318915534720610960e-01,1.100000010988609489e+01,1.553601011823192105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341584527851482278e+01,6.383226129857350770e+02,4.319070894759295398e-01,1.100000010988609489e+01,1.553455026421654388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341675436941483213e+01,6.383326129736689154e+02,4.319226240199456890e-01,1.100000010988609489e+01,1.553309041020116670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341766346031484147e+01,6.383426129616050275e+02,4.319381571041095991e-01,1.100000010988609489e+01,1.553163055618578953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341857255121485082e+01,6.383526129495434134e+02,4.319536887284212701e-01,1.100000010988609489e+01,1.553017070217041235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.341948164211486016e+01,6.383626129374840730e+02,4.319692188928806464e-01,1.100000010988609489e+01,1.552871084815503518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342039073301486951e+01,6.383726129254270063e+02,4.319847475974877837e-01,1.100000010988609489e+01,1.552725099413965800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342129982391487886e+01,6.383826129133722134e+02,4.320002748422426819e-01,1.100000010988609489e+01,1.552579114012428083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342220891481488820e+01,6.383926129013196942e+02,4.320158006271453410e-01,1.100000010988609489e+01,1.552433128610890365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342311800571489755e+01,6.384026128892694487e+02,4.320313249521957055e-01,1.100000010988609489e+01,1.552287143209352648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342402709661490690e+01,6.384126128772214770e+02,4.320468478173938309e-01,1.100000010988609489e+01,1.552141157807814930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342493618751491624e+01,6.384226128651757790e+02,4.320623692227397172e-01,1.100000010988609489e+01,1.551995172406277212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342584527841492559e+01,6.384326128531323548e+02,4.320778891682333089e-01,1.100000010988609489e+01,1.551849187004739495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342675436931493493e+01,6.384426128410912042e+02,4.320934076538746615e-01,1.100000010988609489e+01,1.551703201603201777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342766346021494428e+01,6.384526128290523275e+02,4.321089246796637751e-01,1.100000010988609489e+01,1.551557216201664060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342857255111495363e+01,6.384626128170157244e+02,4.321244402456005940e-01,1.100000010988609489e+01,1.551411230800126342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.342948164201496297e+01,6.384726128049813951e+02,4.321399543516851738e-01,1.100000010988609489e+01,1.551265245398588625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343039073291497232e+01,6.384826127929492259e+02,4.321554669979175145e-01,1.100000010988609489e+01,1.551119259997050907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343129982381498166e+01,6.384926127809193304e+02,4.321709781842975606e-01,1.100000010988609489e+01,1.550973274595513190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343220891471499101e+01,6.385026127688917086e+02,4.321864879108253676e-01,1.100000010988609489e+01,1.550827289193975472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343311800561500036e+01,6.385126127568663605e+02,4.322019961775008801e-01,1.100000010988609489e+01,1.550681303792437755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343402709651500970e+01,6.385226127448432862e+02,4.322175029843241534e-01,1.100000010988609489e+01,1.550535318390900037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343493618741501905e+01,6.385326127328224857e+02,4.322330083312951876e-01,1.100000010988609489e+01,1.550389332989362320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343584527831502839e+01,6.385426127208039588e+02,4.322485122184139272e-01,1.100000010988609489e+01,1.550243347587824602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343675436921503774e+01,6.385526127087877057e+02,4.322640146456804278e-01,1.100000010988609489e+01,1.550097362186286885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343766346011504709e+01,6.385626126967737264e+02,4.322795156130946892e-01,1.100000010988609489e+01,1.549951376784749167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343857255101505643e+01,6.385726126847620208e+02,4.322950151206566560e-01,1.100000010988609489e+01,1.549805391383211450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.343948164191506578e+01,6.385826126727525889e+02,4.323105131683663838e-01,1.100000010988609489e+01,1.549659405981673732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344039073281507513e+01,6.385926126607453170e+02,4.323260097562238169e-01,1.100000010988609489e+01,1.549513420580136015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344129982371508447e+01,6.386026126487403189e+02,4.323415048842290109e-01,1.100000010988609489e+01,1.549367435178598297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344220891461509382e+01,6.386126126367375946e+02,4.323569985523819104e-01,1.100000010988609489e+01,1.549221449777060580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344311800551510316e+01,6.386226126247371440e+02,4.323724907606825707e-01,1.100000010988609489e+01,1.549075464375522862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344402709641511251e+01,6.386326126127389671e+02,4.323879815091309919e-01,1.100000010988609489e+01,1.548929478973985144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344493618731512186e+01,6.386426126007430639e+02,4.324034707977271186e-01,1.100000010988609489e+01,1.548783493572447427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344584527821513120e+01,6.386526125887494345e+02,4.324189586264710061e-01,1.100000010988609489e+01,1.548637508170909709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344675436911514055e+01,6.386626125767580788e+02,4.324344449953625991e-01,1.100000010988609489e+01,1.548491522769371992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344766346001514989e+01,6.386726125647689969e+02,4.324499299044019529e-01,1.100000010988609489e+01,1.548345537367834274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344857255091515924e+01,6.386826125527820750e+02,4.324654133535890121e-01,1.100000010988609489e+01,1.548199551966296557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.344948164181516859e+01,6.386926125407974268e+02,4.324808953429238323e-01,1.100000010988609489e+01,1.548053566564758839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345039073271517793e+01,6.387026125288150524e+02,4.324963758724063578e-01,1.100000010988609489e+01,1.547907581163221122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345129982361518728e+01,6.387126125168349517e+02,4.325118549420366443e-01,1.100000010988609489e+01,1.547761595761683404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345220891451519662e+01,6.387226125048571248e+02,4.325273325518146361e-01,1.100000010988609489e+01,1.547615610360145687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345311800541520597e+01,6.387326124928815716e+02,4.325428087017403889e-01,1.100000010988609489e+01,1.547469624958607969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345402709631521532e+01,6.387426124809082921e+02,4.325582833918138470e-01,1.100000010988609489e+01,1.547323639557070252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345493618721522466e+01,6.387526124689372864e+02,4.325737566220350661e-01,1.100000010988609489e+01,1.547177654155532534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345584527811523401e+01,6.387626124569684407e+02,4.325892283924039905e-01,1.100000010988609489e+01,1.547031668753994817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345675436901524336e+01,6.387726124450018688e+02,4.326046987029206758e-01,1.100000010988609489e+01,1.546885683352457099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345766345991525270e+01,6.387826124330375706e+02,4.326201675535850666e-01,1.100000010988609489e+01,1.546739697950919382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345857255081526205e+01,6.387926124210755461e+02,4.326356349443972182e-01,1.100000010988609489e+01,1.546593712549381664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.345948164171527139e+01,6.388026124091157953e+02,4.326511008753570753e-01,1.100000010988609489e+01,1.546447727147843947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346039073261528074e+01,6.388126123971583183e+02,4.326665653464646932e-01,1.100000010988609489e+01,1.546301741746306229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346129982351529009e+01,6.388226123852031151e+02,4.326820283577200166e-01,1.100000010988609489e+01,1.546155756344768512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346220891441529943e+01,6.388326123732501856e+02,4.326974899091230453e-01,1.100000010988609489e+01,1.546009770943230794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346311800531530878e+01,6.388426123612994161e+02,4.327129500006738350e-01,1.100000010988609489e+01,1.545863785541693076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346402709621531812e+01,6.388526123493509203e+02,4.327284086323723300e-01,1.100000010988609489e+01,1.545717800140155359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346493618711532747e+01,6.388626123374046983e+02,4.327438658042185859e-01,1.100000010988609489e+01,1.545571814738617641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346584527801533682e+01,6.388726123254607501e+02,4.327593215162125473e-01,1.100000010988609489e+01,1.545425829337079924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346675436891534616e+01,6.388826123135190755e+02,4.327747757683542695e-01,1.100000010988609489e+01,1.545279843935542206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346766345981535551e+01,6.388926123015796747e+02,4.327902285606436972e-01,1.100000010988609489e+01,1.545133858534004489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346857255071536486e+01,6.389026122896424340e+02,4.328056798930808302e-01,1.100000010988609489e+01,1.544987873132466771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.346948164161537420e+01,6.389126122777074670e+02,4.328211297656657242e-01,1.100000010988609489e+01,1.544841887730929054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347039073251538355e+01,6.389226122657747737e+02,4.328365781783983235e-01,1.100000010988609489e+01,1.544695902329391336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347129982341539289e+01,6.389326122538443542e+02,4.328520251312786837e-01,1.100000010988609489e+01,1.544549916927853619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347220891431540224e+01,6.389426122419162084e+02,4.328674706243067494e-01,1.100000010988609489e+01,1.544403931526315901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347311800521541159e+01,6.389526122299903363e+02,4.328829146574825204e-01,1.100000010988609489e+01,1.544257946124778184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347402709611542093e+01,6.389626122180666243e+02,4.328983572308060523e-01,1.100000010988609489e+01,1.544111960723240466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347493618701543028e+01,6.389726122061451861e+02,4.329137983442772897e-01,1.100000010988609489e+01,1.543965975321702749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347584527791543962e+01,6.389826121942260215e+02,4.329292379978962324e-01,1.100000010988609489e+01,1.543819989920165031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347675436881544897e+01,6.389926121823091307e+02,4.329446761916629360e-01,1.100000010988609489e+01,1.543674004518627314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347766345971545832e+01,6.390026121703945137e+02,4.329601129255773451e-01,1.100000010988609489e+01,1.543528019117089596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347857255061546766e+01,6.390126121584821703e+02,4.329755481996394595e-01,1.100000010988609489e+01,1.543382033715551879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.347948164151547701e+01,6.390226121465719871e+02,4.329909820138493348e-01,1.100000010988609489e+01,1.543236048314014161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348039073241548635e+01,6.390326121346640775e+02,4.330064143682069155e-01,1.100000010988609489e+01,1.543090062912476444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348129982331549570e+01,6.390426121227584417e+02,4.330218452627122017e-01,1.100000010988609489e+01,1.542944077510938726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348220891421550505e+01,6.390526121108550797e+02,4.330372746973652487e-01,1.100000010988609489e+01,1.542798092109401008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348311800511551439e+01,6.390626120989539913e+02,4.330527026721660011e-01,1.100000010988609489e+01,1.542652106707863291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348402709601552374e+01,6.390726120870550631e+02,4.330681291871144589e-01,1.100000010988609489e+01,1.542506121306325573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348493618691553309e+01,6.390826120751584085e+02,4.330835542422106776e-01,1.100000010988609489e+01,1.542360135904787856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348584527781554243e+01,6.390926120632640277e+02,4.330989778374546018e-01,1.100000010988609489e+01,1.542214150503250138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348675436871555178e+01,6.391026120513719206e+02,4.331143999728462313e-01,1.100000010988609489e+01,1.542068165101712421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348766345961556112e+01,6.391126120394820873e+02,4.331298206483855662e-01,1.100000010988609489e+01,1.541922179700174703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348857255051557047e+01,6.391226120275944140e+02,4.331452398640726620e-01,1.100000010988609489e+01,1.541776194298636986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.348948164141557982e+01,6.391326120157090145e+02,4.331606576199074632e-01,1.100000010988609489e+01,1.541630208897099268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349039073231558916e+01,6.391426120038258887e+02,4.331760739158899698e-01,1.100000010988609489e+01,1.541484223495561551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349129982321559851e+01,6.391526119919450366e+02,4.331914887520201818e-01,1.100000010988609489e+01,1.541338238094023833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349220891411560785e+01,6.391626119800664583e+02,4.332069021282981547e-01,1.100000010988609489e+01,1.541192252692486116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349311800501561720e+01,6.391726119681900400e+02,4.332223140447238330e-01,1.100000010988609489e+01,1.541046267290948398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349402709591562655e+01,6.391826119563158954e+02,4.332377245012972167e-01,1.100000010988609489e+01,1.540900281889410681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349493618681563589e+01,6.391926119444440246e+02,4.332531334980183058e-01,1.100000010988609489e+01,1.540754296487872963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349584527771564524e+01,6.392026119325744276e+02,4.332685410348871557e-01,1.100000010988609489e+01,1.540608311086335246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349675436861565458e+01,6.392126119207071042e+02,4.332839471119037111e-01,1.100000010988609489e+01,1.540462325684797528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349766345951566393e+01,6.392226119088419409e+02,4.332993517290679719e-01,1.100000010988609489e+01,1.540316340283259811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349857255041567328e+01,6.392326118969790514e+02,4.333147548863799381e-01,1.100000010988609489e+01,1.540170354881722093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.349948164131568262e+01,6.392426118851184356e+02,4.333301565838396097e-01,1.100000010988609489e+01,1.540024369480184376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350039073221569197e+01,6.392526118732600935e+02,4.333455568214470421e-01,1.100000010988609489e+01,1.539878384078646658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350129982311570132e+01,6.392626118614040251e+02,4.333609555992021800e-01,1.100000010988609489e+01,1.539732398677108940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350220891401571066e+01,6.392726118495501169e+02,4.333763529171050233e-01,1.100000010988609489e+01,1.539586413275571223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350311800491572001e+01,6.392826118376984823e+02,4.333917487751555719e-01,1.100000010988609489e+01,1.539440427874033505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350402709581572935e+01,6.392926118258491215e+02,4.334071431733538260e-01,1.100000010988609489e+01,1.539294442472495788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350493618671573870e+01,6.393026118140020344e+02,4.334225361116997854e-01,1.100000010988609489e+01,1.539148457070958070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350584527761574805e+01,6.393126118021571074e+02,4.334379275901935058e-01,1.100000010988609489e+01,1.539002471669420353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350675436851575739e+01,6.393226117903144541e+02,4.334533176088349316e-01,1.100000010988609489e+01,1.538856486267882635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350766345941576674e+01,6.393326117784740745e+02,4.334687061676240627e-01,1.100000010988609489e+01,1.538710500866344918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350857255031577608e+01,6.393426117666359687e+02,4.334840932665608992e-01,1.100000010988609489e+01,1.538564515464807200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.350948164121578543e+01,6.393526117548000229e+02,4.334994789056454412e-01,1.100000010988609489e+01,1.538418530063269483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351039073211579478e+01,6.393626117429663509e+02,4.335148630848776885e-01,1.100000010988609489e+01,1.538272544661731765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351129982301580412e+01,6.393726117311349526e+02,4.335302458042576412e-01,1.100000010988609489e+01,1.538126559260194048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351220891391581347e+01,6.393826117193058280e+02,4.335456270637852993e-01,1.100000010988609489e+01,1.537980573858656330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351311800481582281e+01,6.393926117074788635e+02,4.335610068634607184e-01,1.100000010988609489e+01,1.537834588457118613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351402709571583216e+01,6.394026116956541728e+02,4.335763852032838428e-01,1.100000010988609489e+01,1.537688603055580895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351493618661584151e+01,6.394126116838317557e+02,4.335917620832546726e-01,1.100000010988609489e+01,1.537542617654043178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351584527751585085e+01,6.394226116720116124e+02,4.336071375033732078e-01,1.100000010988609489e+01,1.537396632252505460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351675436841586020e+01,6.394326116601936292e+02,4.336225114636394484e-01,1.100000010988609489e+01,1.537250646850967743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351766345931586955e+01,6.394426116483779197e+02,4.336378839640533944e-01,1.100000010988609489e+01,1.537104661449430025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351857255021587889e+01,6.394526116365644839e+02,4.336532550046150458e-01,1.100000010988609489e+01,1.536958676047892308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.351948164111588824e+01,6.394626116247533218e+02,4.336686245853244026e-01,1.100000010988609489e+01,1.536812690646354590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352039073201589758e+01,6.394726116129443199e+02,4.336839927061814648e-01,1.100000010988609489e+01,1.536666705244816872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352129982291590693e+01,6.394826116011375916e+02,4.336993593671862324e-01,1.100000010988609489e+01,1.536520719843279155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352220891381591628e+01,6.394926115893331371e+02,4.337147245683387053e-01,1.100000010988609489e+01,1.536374734441741437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352311800471592562e+01,6.395026115775309563e+02,4.337300883096388837e-01,1.100000010988609489e+01,1.536228749040203720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352402709561593497e+01,6.395126115657309356e+02,4.337454505910867675e-01,1.100000010988609489e+01,1.536082763638666002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352493618651594431e+01,6.395226115539331886e+02,4.337608114126823566e-01,1.100000010988609489e+01,1.535936778237128285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352584527741595366e+01,6.395326115421377153e+02,4.337761707744256512e-01,1.100000010988609489e+01,1.535790792835590567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352675436831596301e+01,6.395426115303444021e+02,4.337915286763166511e-01,1.100000010988609489e+01,1.535644807434052850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352766345921597235e+01,6.395526115185533627e+02,4.338068851183553565e-01,1.100000010988609489e+01,1.535498822032515132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352857255011598170e+01,6.395626115067645969e+02,4.338222401005417672e-01,1.100000010988609489e+01,1.535352836630977415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.352948164101599104e+01,6.395726114949781049e+02,4.338375936228758833e-01,1.100000010988609489e+01,1.535206851229439697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353039073191600039e+01,6.395826114831937730e+02,4.338529456853577049e-01,1.100000010988609489e+01,1.535060865827901980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353129982281600974e+01,6.395926114714117148e+02,4.338682962879872318e-01,1.100000010988609489e+01,1.534914880426364262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353220891371601908e+01,6.396026114596319303e+02,4.338836454307644641e-01,1.100000010988609489e+01,1.534768895024826545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353311800461602843e+01,6.396126114478543059e+02,4.338989931136894018e-01,1.100000010988609489e+01,1.534622909623288827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353402709551603778e+01,6.396226114360789552e+02,4.339143393367620449e-01,1.100000010988609489e+01,1.534476924221751110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353493618641604712e+01,6.396326114243058782e+02,4.339296840999823934e-01,1.100000010988609489e+01,1.534330938820213392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353584527731605647e+01,6.396426114125350750e+02,4.339450274033504473e-01,1.100000010988609489e+01,1.534184953418675675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353675436821606581e+01,6.396526114007664319e+02,4.339603692468662066e-01,1.100000010988609489e+01,1.534038968017137957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353766345911607516e+01,6.396626113890000624e+02,4.339757096305296713e-01,1.100000010988609489e+01,1.533892982615600240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353857255001608451e+01,6.396726113772359668e+02,4.339910485543408414e-01,1.100000010988609489e+01,1.533746997214062522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.353948164091609385e+01,6.396826113654740311e+02,4.340063860182997169e-01,1.100000010988609489e+01,1.533601011812524804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354039073181610320e+01,6.396926113537143692e+02,4.340217220224062977e-01,1.100000010988609489e+01,1.533455026410987087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354129982271611254e+01,6.397026113419569811e+02,4.340370565666605840e-01,1.100000010988609489e+01,1.533309041009449369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354220891361612189e+01,6.397126113302017529e+02,4.340523896510625756e-01,1.100000010988609489e+01,1.533163055607911652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354311800451613124e+01,6.397226113184487986e+02,4.340677212756122727e-01,1.100000010988609489e+01,1.533017070206373934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354402709541614058e+01,6.397326113066981179e+02,4.340830514403096752e-01,1.100000010988609489e+01,1.532871084804836217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354493618631614993e+01,6.397426112949495973e+02,4.340983801451547830e-01,1.100000010988609489e+01,1.532725099403298499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354584527721615927e+01,6.397526112832033505e+02,4.341137073901475962e-01,1.100000010988609489e+01,1.532579114001760782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354675436811616862e+01,6.397626112714593773e+02,4.341290331752880594e-01,1.100000010988609489e+01,1.532433128600223064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354766345901617797e+01,6.397726112597176780e+02,4.341443575005762279e-01,1.100000010988609489e+01,1.532287143198685347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354857254991618731e+01,6.397826112479781386e+02,4.341596803660121018e-01,1.100000010988609489e+01,1.532141157797147629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.354948164081619666e+01,6.397926112362408730e+02,4.341750017715956811e-01,1.100000010988609489e+01,1.531995172395609912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355039073171620601e+01,6.398026112245058812e+02,4.341903217173269658e-01,1.100000010988609489e+01,1.531849186994072194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355129982261621535e+01,6.398126112127730494e+02,4.342056402032059559e-01,1.100000010988609489e+01,1.531703201592534477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355220891351622470e+01,6.398226112010424913e+02,4.342209572292326514e-01,1.100000010988609489e+01,1.531557216190996759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355311800441623404e+01,6.398326111893142070e+02,4.342362727954069967e-01,1.100000010988609489e+01,1.531411230789459042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355402709531624339e+01,6.398426111775880827e+02,4.342515869017290475e-01,1.100000010988609489e+01,1.531265245387921324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355493618621625274e+01,6.398526111658642321e+02,4.342668995481988037e-01,1.100000010988609489e+01,1.531119259986383607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355584527711626208e+01,6.398626111541426553e+02,4.342822107348162652e-01,1.100000010988609489e+01,1.530973274584845889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355675436801627143e+01,6.398726111424232386e+02,4.342975204615814322e-01,1.100000010988609489e+01,1.530827289183308171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355766345891628077e+01,6.398826111307060955e+02,4.343128287284943045e-01,1.100000010988609489e+01,1.530681303781770454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355857254981629012e+01,6.398926111189912262e+02,4.343281355355548268e-01,1.100000010988609489e+01,1.530535318380232736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.355948164071629947e+01,6.399026111072785170e+02,4.343434408827630544e-01,1.100000010988609489e+01,1.530389332978695019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356039073161630881e+01,6.399126110955680815e+02,4.343587447701189874e-01,1.100000010988609489e+01,1.530243347577157301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356129982251631816e+01,6.399226110838598061e+02,4.343740471976226258e-01,1.100000010988609489e+01,1.530097362175619584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356220891341632750e+01,6.399326110721538043e+02,4.343893481652739696e-01,1.100000010988609489e+01,1.529951376774081866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356311800431633685e+01,6.399426110604500764e+02,4.344046476730729633e-01,1.100000010988609489e+01,1.529805391372544149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356402709521634620e+01,6.399526110487485084e+02,4.344199457210196624e-01,1.100000010988609489e+01,1.529659405971006431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356493618611635554e+01,6.399626110370492142e+02,4.344352423091140669e-01,1.100000010988609489e+01,1.529513420569468714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356584527701636489e+01,6.399726110253521938e+02,4.344505374373561768e-01,1.100000010988609489e+01,1.529367435167930996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356675436791637424e+01,6.399826110136573334e+02,4.344658311057459366e-01,1.100000010988609489e+01,1.529221449766393279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356766345881638358e+01,6.399926110019647467e+02,4.344811233142834017e-01,1.100000010988609489e+01,1.529075464364855561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356857254971639293e+01,6.400026109902744338e+02,4.344964140629685723e-01,1.100000010988609489e+01,1.528929478963317844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.356948164061640227e+01,6.400126109785862809e+02,4.345117033518014482e-01,1.100000010988609489e+01,1.528783493561780126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357039073151641162e+01,6.400226109669004018e+02,4.345269911807819740e-01,1.100000010988609489e+01,1.528637508160242409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357129982241642097e+01,6.400326109552167964e+02,4.345422775499102053e-01,1.100000010988609489e+01,1.528491522758704691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357220891331643031e+01,6.400426109435353510e+02,4.345575624591861419e-01,1.100000010988609489e+01,1.528345537357166974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357311800421643966e+01,6.400526109318561794e+02,4.345728459086097839e-01,1.100000010988609489e+01,1.528199551955629256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357402709511644900e+01,6.400626109201791678e+02,4.345881278981810758e-01,1.100000010988609489e+01,1.528053566554091539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357493618601645835e+01,6.400726109085044300e+02,4.346034084279000731e-01,1.100000010988609489e+01,1.527907581152553821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357584527691646770e+01,6.400826108968319659e+02,4.346186874977667758e-01,1.100000010988609489e+01,1.527761595751016103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357675436781647704e+01,6.400926108851616618e+02,4.346339651077811284e-01,1.100000010988609489e+01,1.527615610349478386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357766345871648639e+01,6.401026108734936315e+02,4.346492412579431863e-01,1.100000010988609489e+01,1.527469624947940668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357857254961649573e+01,6.401126108618277613e+02,4.346645159482529497e-01,1.100000010988609489e+01,1.527323639546402951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.357948164051650508e+01,6.401226108501641647e+02,4.346797891787103629e-01,1.100000010988609489e+01,1.527177654144865233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358039073141651443e+01,6.401326108385028419e+02,4.346950609493154816e-01,1.100000010988609489e+01,1.527031668743327516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358129982231652377e+01,6.401426108268436792e+02,4.347103312600683056e-01,1.100000010988609489e+01,1.526885683341789798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358220891321653312e+01,6.401526108151867902e+02,4.347256001109687795e-01,1.100000010988609489e+01,1.526739697940252081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358311800411654247e+01,6.401626108035321749e+02,4.347408675020169588e-01,1.100000010988609489e+01,1.526593712538714363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358402709501655181e+01,6.401726107918797197e+02,4.347561334332128435e-01,1.100000010988609489e+01,1.526447727137176646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358493618591656116e+01,6.401826107802295382e+02,4.347713979045563781e-01,1.100000010988609489e+01,1.526301741735638928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358584527681657050e+01,6.401926107685815168e+02,4.347866609160476181e-01,1.100000010988609489e+01,1.526155756334101211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358675436771657985e+01,6.402026107569357691e+02,4.348019224676865635e-01,1.100000010988609489e+01,1.526009770932563493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358766345861658920e+01,6.402126107452922952e+02,4.348171825594731588e-01,1.100000010988609489e+01,1.525863785531025776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358857254951659854e+01,6.402226107336509813e+02,4.348324411914074594e-01,1.100000010988609489e+01,1.525717800129488058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.358948164041660789e+01,6.402326107220119411e+02,4.348476983634894655e-01,1.100000010988609489e+01,1.525571814727950341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359039073131661723e+01,6.402426107103750610e+02,4.348629540757191214e-01,1.100000010988609489e+01,1.525425829326412623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359129982221662658e+01,6.402526106987404546e+02,4.348782083280964827e-01,1.100000010988609489e+01,1.525279843924874906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359220891311663593e+01,6.402626106871080083e+02,4.348934611206214940e-01,1.100000010988609489e+01,1.525133858523337188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359311800401664527e+01,6.402726106754778357e+02,4.349087124532942106e-01,1.100000010988609489e+01,1.524987873121799471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359402709491665462e+01,6.402826106638499368e+02,4.349239623261146326e-01,1.100000010988609489e+01,1.524841887720261753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359493618581666396e+01,6.402926106522241980e+02,4.349392107390827045e-01,1.100000010988609489e+01,1.524695902318724035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359584527671667331e+01,6.403026106406007329e+02,4.349544576921984818e-01,1.100000010988609489e+01,1.524549916917186318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359675436761668266e+01,6.403126106289794279e+02,4.349697031854619089e-01,1.100000010988609489e+01,1.524403931515648600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359766345851669200e+01,6.403226106173603966e+02,4.349849472188730415e-01,1.100000010988609489e+01,1.524257946114110883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359857254941670135e+01,6.403326106057436391e+02,4.350001897924318239e-01,1.100000010988609489e+01,1.524111960712573165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.359948164031671070e+01,6.403426105941290416e+02,4.350154309061383118e-01,1.100000010988609489e+01,1.523965975311035448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360039073121672004e+01,6.403526105825167178e+02,4.350306705599924495e-01,1.100000010988609489e+01,1.523819989909497730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360129982211672939e+01,6.403626105709065541e+02,4.350459087539942926e-01,1.100000010988609489e+01,1.523674004507960013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360220891301673873e+01,6.403726105592986642e+02,4.350611454881438411e-01,1.100000010988609489e+01,1.523528019106422295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360311800391674808e+01,6.403826105476929342e+02,4.350763807624410395e-01,1.100000010988609489e+01,1.523382033704884578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360402709481675743e+01,6.403926105360894780e+02,4.350916145768859433e-01,1.100000010988609489e+01,1.523236048303346860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360493618571676677e+01,6.404026105244882956e+02,4.351068469314784970e-01,1.100000010988609489e+01,1.523090062901809143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360584527661677612e+01,6.404126105128892732e+02,4.351220778262187561e-01,1.100000010988609489e+01,1.522944077500271425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360675436751678546e+01,6.404226105012925245e+02,4.351373072611066650e-01,1.100000010988609489e+01,1.522798092098733708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360766345841679481e+01,6.404326104896979359e+02,4.351525352361422794e-01,1.100000010988609489e+01,1.522652106697195990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360857254931680416e+01,6.404426104781056210e+02,4.351677617513255436e-01,1.100000010988609489e+01,1.522506121295658273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.360948164021681350e+01,6.404526104665154662e+02,4.351829868066565132e-01,1.100000010988609489e+01,1.522360135894120555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361039073111682285e+01,6.404626104549275851e+02,4.351982104021351327e-01,1.100000010988609489e+01,1.522214150492582838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361129982201683220e+01,6.404726104433418641e+02,4.352134325377614577e-01,1.100000010988609489e+01,1.522068165091045120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361220891291684154e+01,6.404826104317584168e+02,4.352286532135354324e-01,1.100000010988609489e+01,1.521922179689507403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361311800381685089e+01,6.404926104201771295e+02,4.352438724294570571e-01,1.100000010988609489e+01,1.521776194287969685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361402709471686023e+01,6.405026104085981160e+02,4.352590901855263872e-01,1.100000010988609489e+01,1.521630208886431967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361493618561686958e+01,6.405126103970213762e+02,4.352743064817433671e-01,1.100000010988609489e+01,1.521484223484894250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361584527651687893e+01,6.405226103854467965e+02,4.352895213181080525e-01,1.100000010988609489e+01,1.521338238083356532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361675436741688827e+01,6.405326103738744905e+02,4.353047346946203877e-01,1.100000010988609489e+01,1.521192252681818815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361766345831689762e+01,6.405426103623043446e+02,4.353199466112804283e-01,1.100000010988609489e+01,1.521046267280281097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361857254921690696e+01,6.405526103507364724e+02,4.353351570680881188e-01,1.100000010988609489e+01,1.520900281878743380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.361948164011691631e+01,6.405626103391707602e+02,4.353503660650435148e-01,1.100000010988609489e+01,1.520754296477205662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362039073101692566e+01,6.405726103276073218e+02,4.353655736021465605e-01,1.100000010988609489e+01,1.520608311075667945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362129982191693500e+01,6.405826103160460434e+02,4.353807796793972562e-01,1.100000010988609489e+01,1.520462325674130227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362220891281694435e+01,6.405926103044870388e+02,4.353959842967956573e-01,1.100000010988609489e+01,1.520316340272592510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362311800371695369e+01,6.406026102929301942e+02,4.354111874543417082e-01,1.100000010988609489e+01,1.520170354871054792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362402709461696304e+01,6.406126102813756233e+02,4.354263891520354646e-01,1.100000010988609489e+01,1.520024369469517075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362493618551697239e+01,6.406226102698232125e+02,4.354415893898768708e-01,1.100000010988609489e+01,1.519878384067979357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362584527641698173e+01,6.406326102582730755e+02,4.354567881678659269e-01,1.100000010988609489e+01,1.519732398666441640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362675436731699108e+01,6.406426102467250985e+02,4.354719854860026884e-01,1.100000010988609489e+01,1.519586413264903922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362766345821700043e+01,6.406526102351793952e+02,4.354871813442870998e-01,1.100000010988609489e+01,1.519440427863366205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362857254911700977e+01,6.406626102236358520e+02,4.355023757427191611e-01,1.100000010988609489e+01,1.519294442461828487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.362948164001701912e+01,6.406726102120945825e+02,4.355175686812989277e-01,1.100000010988609489e+01,1.519148457060290770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363039073091702846e+01,6.406826102005554731e+02,4.355327601600263443e-01,1.100000010988609489e+01,1.519002471658753052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363129982181703781e+01,6.406926101890186374e+02,4.355479501789014107e-01,1.100000010988609489e+01,1.518856486257215335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363220891271704716e+01,6.407026101774839617e+02,4.355631387379241826e-01,1.100000010988609489e+01,1.518710500855677617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363311800361705650e+01,6.407126101659515598e+02,4.355783258370946043e-01,1.100000010988609489e+01,1.518564515454139899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363402709451706585e+01,6.407226101544213179e+02,4.355935114764126759e-01,1.100000010988609489e+01,1.518418530052602182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363493618541707519e+01,6.407326101428933498e+02,4.356086956558784529e-01,1.100000010988609489e+01,1.518272544651064464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363584527631708454e+01,6.407426101313675417e+02,4.356238783754918797e-01,1.100000010988609489e+01,1.518126559249526747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363675436721709389e+01,6.407526101198440074e+02,4.356390596352529565e-01,1.100000010988609489e+01,1.517980573847989029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363766345811710323e+01,6.407626101083226331e+02,4.356542394351617387e-01,1.100000010988609489e+01,1.517834588446451312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363857254901711258e+01,6.407726100968035325e+02,4.356694177752181707e-01,1.100000010988609489e+01,1.517688603044913594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.363948163991712192e+01,6.407826100852865920e+02,4.356845946554222526e-01,1.100000010988609489e+01,1.517542617643375877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364039073081713127e+01,6.407926100737719253e+02,4.356997700757740399e-01,1.100000010988609489e+01,1.517396632241838159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364129982171714062e+01,6.408026100622594186e+02,4.357149440362734771e-01,1.100000010988609489e+01,1.517250646840300442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364220891261714996e+01,6.408126100507491856e+02,4.357301165369205642e-01,1.100000010988609489e+01,1.517104661438762724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364311800351715931e+01,6.408226100392411126e+02,4.357452875777153012e-01,1.100000010988609489e+01,1.516958676037225007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364402709441716866e+01,6.408326100277353135e+02,4.357604571586577435e-01,1.100000010988609489e+01,1.516812690635687289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364493618531717800e+01,6.408426100162316743e+02,4.357756252797478358e-01,1.100000010988609489e+01,1.516666705234149572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364584527621718735e+01,6.408526100047303089e+02,4.357907919409855779e-01,1.100000010988609489e+01,1.516520719832611854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364675436711719669e+01,6.408626099932311035e+02,4.358059571423709699e-01,1.100000010988609489e+01,1.516374734431074137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364766345801720604e+01,6.408726099817341719e+02,4.358211208839040673e-01,1.100000010988609489e+01,1.516228749029536419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364857254891721539e+01,6.408826099702394004e+02,4.358362831655848146e-01,1.100000010988609489e+01,1.516082763627998702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.364948163981722473e+01,6.408926099587469025e+02,4.358514439874132118e-01,1.100000010988609489e+01,1.515936778226460984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365039073071723408e+01,6.409026099472565647e+02,4.358666033493892589e-01,1.100000010988609489e+01,1.515790792824923267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365129982161724342e+01,6.409126099357685007e+02,4.358817612515130113e-01,1.100000010988609489e+01,1.515644807423385549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365220891251725277e+01,6.409226099242825967e+02,4.358969176937844137e-01,1.100000010988609489e+01,1.515498822021847831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365311800341726212e+01,6.409326099127989664e+02,4.359120726762034659e-01,1.100000010988609489e+01,1.515352836620310114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365402709431727146e+01,6.409426099013174962e+02,4.359272261987701680e-01,1.100000010988609489e+01,1.515206851218772396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365493618521728081e+01,6.409526098898381861e+02,4.359423782614845200e-01,1.100000010988609489e+01,1.515060865817234679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365584527611729015e+01,6.409626098783611496e+02,4.359575288643465774e-01,1.100000010988609489e+01,1.514914880415696961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365675436701729950e+01,6.409726098668862733e+02,4.359726780073562846e-01,1.100000010988609489e+01,1.514768895014159244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365766345791730885e+01,6.409826098554136706e+02,4.359878256905136418e-01,1.100000010988609489e+01,1.514622909612621526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365857254881731819e+01,6.409926098439432280e+02,4.360029719138186488e-01,1.100000010988609489e+01,1.514476924211083809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.365948163971732754e+01,6.410026098324750592e+02,4.360181166772713057e-01,1.100000010988609489e+01,1.514330938809546091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366039073061733689e+01,6.410126098210090504e+02,4.360332599808716125e-01,1.100000010988609489e+01,1.514184953408008374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366129982151734623e+01,6.410226098095453153e+02,4.360484018246196247e-01,1.100000010988609489e+01,1.514038968006470656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366220891241735558e+01,6.410326097980837403e+02,4.360635422085152868e-01,1.100000010988609489e+01,1.513892982604932939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366311800331736492e+01,6.410426097866244390e+02,4.360786811325585988e-01,1.100000010988609489e+01,1.513746997203395221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366402709421737427e+01,6.410526097751672978e+02,4.360938185967495606e-01,1.100000010988609489e+01,1.513601011801857504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366493618511738362e+01,6.410626097637123166e+02,4.361089546010881723e-01,1.100000010988609489e+01,1.513455026400319786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366584527601739296e+01,6.410726097522596092e+02,4.361240891455744340e-01,1.100000010988609489e+01,1.513309040998782069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366675436691740231e+01,6.410826097408090618e+02,4.361392222302083455e-01,1.100000010988609489e+01,1.513163055597244351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366766345781741165e+01,6.410926097293607882e+02,4.361543538549899068e-01,1.100000010988609489e+01,1.513017070195706634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366857254871742100e+01,6.411026097179146745e+02,4.361694840199191736e-01,1.100000010988609489e+01,1.512871084794168916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.366948163961743035e+01,6.411126097064708347e+02,4.361846127249960903e-01,1.100000010988609489e+01,1.512725099392631199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367039073051743969e+01,6.411226096950291549e+02,4.361997399702206568e-01,1.100000010988609489e+01,1.512579113991093481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367129982141744904e+01,6.411326096835896351e+02,4.362148657555928732e-01,1.100000010988609489e+01,1.512433128589555763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367220891231745838e+01,6.411426096721523891e+02,4.362299900811127396e-01,1.100000010988609489e+01,1.512287143188018046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367311800321746773e+01,6.411526096607173031e+02,4.362451129467802557e-01,1.100000010988609489e+01,1.512141157786480328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367402709411747708e+01,6.411626096492844908e+02,4.362602343525954218e-01,1.100000010988609489e+01,1.511995172384942611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367493618501748642e+01,6.411726096378538386e+02,4.362753542985582378e-01,1.100000010988609489e+01,1.511849186983404893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367584527591749577e+01,6.411826096264253465e+02,4.362904727846687036e-01,1.100000010988609489e+01,1.511703201581867176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367675436681750512e+01,6.411926096149991281e+02,4.363055898109268194e-01,1.100000010988609489e+01,1.511557216180329458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367766345771751446e+01,6.412026096035750697e+02,4.363207053773325850e-01,1.100000010988609489e+01,1.511411230778791741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367857254861752381e+01,6.412126095921532851e+02,4.363358194838860005e-01,1.100000010988609489e+01,1.511265245377254023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.367948163951753315e+01,6.412226095807336606e+02,4.363509321305870658e-01,1.100000010988609489e+01,1.511119259975716306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368039073041754250e+01,6.412326095693163097e+02,4.363660433174357811e-01,1.100000010988609489e+01,1.510973274574178588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368129982131755185e+01,6.412426095579011189e+02,4.363811530444321463e-01,1.100000010988609489e+01,1.510827289172640871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368220891221756119e+01,6.412526095464880882e+02,4.363962613115761613e-01,1.100000010988609489e+01,1.510681303771103153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368311800311757054e+01,6.412626095350773312e+02,4.364113681188678262e-01,1.100000010988609489e+01,1.510535318369565436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368402709401757988e+01,6.412726095236687343e+02,4.364264734663071410e-01,1.100000010988609489e+01,1.510389332968027718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368493618491758923e+01,6.412826095122624110e+02,4.364415773538941057e-01,1.100000010988609489e+01,1.510243347566490001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368584527581759858e+01,6.412926095008582479e+02,4.364566797816287202e-01,1.100000010988609489e+01,1.510097362164952283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368675436671760792e+01,6.413026094894562448e+02,4.364717807495109847e-01,1.100000010988609489e+01,1.509951376763414566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368766345761761727e+01,6.413126094780565154e+02,4.364868802575408990e-01,1.100000010988609489e+01,1.509805391361876848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368857254851762661e+01,6.413226094666589461e+02,4.365019783057184632e-01,1.100000010988609489e+01,1.509659405960339131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.368948163941763596e+01,6.413326094552635368e+02,4.365170748940436773e-01,1.100000010988609489e+01,1.509513420558801413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369039073031764531e+01,6.413426094438704013e+02,4.365321700225165413e-01,1.100000010988609489e+01,1.509367435157263695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369129982121765465e+01,6.413526094324794258e+02,4.365472636911370552e-01,1.100000010988609489e+01,1.509221449755725978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369220891211766400e+01,6.413626094210907240e+02,4.365623558999052189e-01,1.100000010988609489e+01,1.509075464354188260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369311800301767335e+01,6.413726094097041823e+02,4.365774466488210326e-01,1.100000010988609489e+01,1.508929478952650543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369402709391768269e+01,6.413826093983198007e+02,4.365925359378844961e-01,1.100000010988609489e+01,1.508783493551112825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369493618481769204e+01,6.413926093869376928e+02,4.366076237670956095e-01,1.100000010988609489e+01,1.508637508149575108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369584527571770138e+01,6.414026093755577449e+02,4.366227101364543728e-01,1.100000010988609489e+01,1.508491522748037390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369675436661771073e+01,6.414126093641799571e+02,4.366377950459607860e-01,1.100000010988609489e+01,1.508345537346499673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369766345751772008e+01,6.414226093528044430e+02,4.366528784956148490e-01,1.100000010988609489e+01,1.508199551944961955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369857254841772942e+01,6.414326093414310890e+02,4.366679604854165619e-01,1.100000010988609489e+01,1.508053566543424238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.369948163931773877e+01,6.414426093300600087e+02,4.366830410153659248e-01,1.100000010988609489e+01,1.507907581141886520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370039073021774811e+01,6.414526093186910884e+02,4.366981200854629375e-01,1.100000010988609489e+01,1.507761595740348803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370129982111775746e+01,6.414626093073243283e+02,4.367131976957075445e-01,1.100000010988609489e+01,1.507615610338811085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370220891201776681e+01,6.414726092959598418e+02,4.367282738460998015e-01,1.100000010988609489e+01,1.507469624937273368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370311800291777615e+01,6.414826092845975154e+02,4.367433485366397083e-01,1.100000010988609489e+01,1.507323639535735650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370402709381778550e+01,6.414926092732373490e+02,4.367584217673272651e-01,1.100000010988609489e+01,1.507177654134197933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370493618471779484e+01,6.415026092618794564e+02,4.367734935381624717e-01,1.100000010988609489e+01,1.507031668732660215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370584527561780419e+01,6.415126092505237239e+02,4.367885638491453282e-01,1.100000010988609489e+01,1.506885683331122498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370675436651781354e+01,6.415226092391701513e+02,4.368036327002758346e-01,1.100000010988609489e+01,1.506739697929584780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370766345741782288e+01,6.415326092278188526e+02,4.368187000915539908e-01,1.100000010988609489e+01,1.506593712528047063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370857254831783223e+01,6.415426092164697138e+02,4.368337660229797415e-01,1.100000010988609489e+01,1.506447727126509345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.370948163921784158e+01,6.415526092051228488e+02,4.368488304945531420e-01,1.100000010988609489e+01,1.506301741724971627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371039073011785092e+01,6.415626091937781439e+02,4.368638935062741924e-01,1.100000010988609489e+01,1.506155756323433910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371129982101786027e+01,6.415726091824355990e+02,4.368789550581428927e-01,1.100000010988609489e+01,1.506009770921896192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371220891191786961e+01,6.415826091710953278e+02,4.368940151501592428e-01,1.100000010988609489e+01,1.505863785520358475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371311800281787896e+01,6.415926091597572167e+02,4.369090737823232429e-01,1.100000010988609489e+01,1.505717800118820757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371402709371788831e+01,6.416026091484212657e+02,4.369241309546348373e-01,1.100000010988609489e+01,1.505571814717283040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371493618461789765e+01,6.416126091370875884e+02,4.369391866670940816e-01,1.100000010988609489e+01,1.505425829315745322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371584527551790700e+01,6.416226091257560711e+02,4.369542409197009758e-01,1.100000010988609489e+01,1.505279843914207605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371675436641791634e+01,6.416326091144267139e+02,4.369692937124555199e-01,1.100000010988609489e+01,1.505133858512669887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371766345731792569e+01,6.416426091030996304e+02,4.369843450453577138e-01,1.100000010988609489e+01,1.504987873111132170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371857254821793504e+01,6.416526090917747069e+02,4.369993949184075022e-01,1.100000010988609489e+01,1.504841887709594452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.371948163911794438e+01,6.416626090804519436e+02,4.370144433316049404e-01,1.100000010988609489e+01,1.504695902308056735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372039073001795373e+01,6.416726090691313402e+02,4.370294902849500285e-01,1.100000010988609489e+01,1.504549916906519017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372129982091796307e+01,6.416826090578130106e+02,4.370445357784427665e-01,1.100000010988609489e+01,1.504403931504981300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372220891181797242e+01,6.416926090464968411e+02,4.370595798120831543e-01,1.100000010988609489e+01,1.504257946103443582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372311800271798177e+01,6.417026090351828316e+02,4.370746223858711366e-01,1.100000010988609489e+01,1.504111960701905865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372402709361799111e+01,6.417126090238710958e+02,4.370896634998067687e-01,1.100000010988609489e+01,1.503965975300368147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372493618451800046e+01,6.417226090125615201e+02,4.371047031538900507e-01,1.100000010988609489e+01,1.503819989898830430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372584527541800981e+01,6.417326090012541044e+02,4.371197413481209826e-01,1.100000010988609489e+01,1.503674004497292712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372675436631801915e+01,6.417426089899489625e+02,4.371347780824995088e-01,1.100000010988609489e+01,1.503528019095754995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372766345721802850e+01,6.417526089786459806e+02,4.371498133570256850e-01,1.100000010988609489e+01,1.503382033694217277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372857254811803784e+01,6.417626089673451588e+02,4.371648471716995110e-01,1.100000010988609489e+01,1.503236048292679559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.372948163901804719e+01,6.417726089560466107e+02,4.371798795265209314e-01,1.100000010988609489e+01,1.503090062891141842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373039072991805654e+01,6.417826089447502227e+02,4.371949104214900017e-01,1.100000010988609489e+01,1.502944077489604124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373129982081806588e+01,6.417926089334559947e+02,4.372099398566067219e-01,1.100000010988609489e+01,1.502798092088066407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373220891171807523e+01,6.418026089221640405e+02,4.372249678318710919e-01,1.100000010988609489e+01,1.502652106686528689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373311800261808457e+01,6.418126089108742462e+02,4.372399943472830564e-01,1.100000010988609489e+01,1.502506121284990972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373402709351809392e+01,6.418226088995866121e+02,4.372550194028426707e-01,1.100000010988609489e+01,1.502360135883453254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373493618441810327e+01,6.418326088883011380e+02,4.372700429985499349e-01,1.100000010988609489e+01,1.502214150481915537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373584527531811261e+01,6.418426088770179376e+02,4.372850651344047934e-01,1.100000010988609489e+01,1.502068165080377819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373675436621812196e+01,6.418526088657368973e+02,4.373000858104073019e-01,1.100000010988609489e+01,1.501922179678840102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373766345711813130e+01,6.418626088544580170e+02,4.373151050265574602e-01,1.100000010988609489e+01,1.501776194277302384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373857254801814065e+01,6.418726088431814105e+02,4.373301227828552129e-01,1.100000010988609489e+01,1.501630208875764667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.373948163891815000e+01,6.418826088319069640e+02,4.373451390793006155e-01,1.100000010988609489e+01,1.501484223474226949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374039072981815934e+01,6.418926088206346776e+02,4.373601539158936680e-01,1.100000010988609489e+01,1.501338238072689232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374129982071816869e+01,6.419026088093645512e+02,4.373751672926343148e-01,1.100000010988609489e+01,1.501192252671151514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374220891161817804e+01,6.419126087980966986e+02,4.373901792095226115e-01,1.100000010988609489e+01,1.501046267269613797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374311800251818738e+01,6.419226087868310060e+02,4.374051896665585026e-01,1.100000010988609489e+01,1.500900281868076079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374402709341819673e+01,6.419326087755674735e+02,4.374201986637420436e-01,1.100000010988609489e+01,1.500754296466538362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374493618431820607e+01,6.419426087643062147e+02,4.374352062010732345e-01,1.100000010988609489e+01,1.500608311065000644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374584527521821542e+01,6.419526087530471159e+02,4.374502122785520197e-01,1.100000010988609489e+01,1.500462325663462927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374675436611822477e+01,6.419626087417901772e+02,4.374652168961784549e-01,1.100000010988609489e+01,1.500316340261925209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374766345701823411e+01,6.419726087305353985e+02,4.374802200539525399e-01,1.100000010988609489e+01,1.500170354860387491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374857254791824346e+01,6.419826087192828936e+02,4.374952217518742192e-01,1.100000010988609489e+01,1.500024369458849774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.374948163881825280e+01,6.419926087080325487e+02,4.375102219899435485e-01,1.100000010988609489e+01,1.499878384057312056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375039072971826215e+01,6.420026086967843639e+02,4.375252207681604721e-01,1.100000010988609489e+01,1.499732398655774339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375129982061827150e+01,6.420126086855383392e+02,4.375402180865250457e-01,1.100000010988609489e+01,1.499586413254236621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375220891151828084e+01,6.420226086742945881e+02,4.375552139450372136e-01,1.100000010988609489e+01,1.499440427852698904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375311800241829019e+01,6.420326086630529971e+02,4.375702083436970313e-01,1.100000010988609489e+01,1.499294442451161186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375402709331829953e+01,6.420426086518135662e+02,4.375852012825044990e-01,1.100000010988609489e+01,1.499148457049623469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375493618421830888e+01,6.420526086405762953e+02,4.376001927614595610e-01,1.100000010988609489e+01,1.499002471648085751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375584527511831823e+01,6.420626086293412982e+02,4.376151827805622729e-01,1.100000010988609489e+01,1.498856486246548034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375675436601832757e+01,6.420726086181084611e+02,4.376301713398125792e-01,1.100000010988609489e+01,1.498710500845010316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375766345691833692e+01,6.420826086068777840e+02,4.376451584392105354e-01,1.100000010988609489e+01,1.498564515443472599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375857254781834627e+01,6.420926085956492670e+02,4.376601440787560859e-01,1.100000010988609489e+01,1.498418530041934881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.375948163871835561e+01,6.421026085844230238e+02,4.376751282584492864e-01,1.100000010988609489e+01,1.498272544640397164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376039072961836496e+01,6.421126085731989406e+02,4.376901109782900812e-01,1.100000010988609489e+01,1.498126559238859446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376129982051837430e+01,6.421226085619770174e+02,4.377050922382785259e-01,1.100000010988609489e+01,1.497980573837321729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376220891141838365e+01,6.421326085507572543e+02,4.377200720384145649e-01,1.100000010988609489e+01,1.497834588435784011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376311800231839300e+01,6.421426085395397649e+02,4.377350503786982538e-01,1.100000010988609489e+01,1.497688603034246294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376402709321840234e+01,6.421526085283244356e+02,4.377500272591295372e-01,1.100000010988609489e+01,1.497542617632708576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376493618411841169e+01,6.421626085171112663e+02,4.377650026797084704e-01,1.100000010988609489e+01,1.497396632231170858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376584527501842103e+01,6.421726085059002571e+02,4.377799766404349979e-01,1.100000010988609489e+01,1.497250646829633141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376675436591843038e+01,6.421826084946914079e+02,4.377949491413091754e-01,1.100000010988609489e+01,1.497104661428095423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376766345681843973e+01,6.421926084834848325e+02,4.378099201823309472e-01,1.100000010988609489e+01,1.496958676026557706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376857254771844907e+01,6.422026084722804171e+02,4.378248897635003689e-01,1.100000010988609489e+01,1.496812690625019988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.376948163861845842e+01,6.422126084610781618e+02,4.378398578848173850e-01,1.100000010988609489e+01,1.496666705223482271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377039072951846777e+01,6.422226084498780665e+02,4.378548245462820510e-01,1.100000010988609489e+01,1.496520719821944553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377129982041847711e+01,6.422326084386802449e+02,4.378697897478943113e-01,1.100000010988609489e+01,1.496374734420406836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377220891131848646e+01,6.422426084274845834e+02,4.378847534896542215e-01,1.100000010988609489e+01,1.496228749018869118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377311800221849580e+01,6.422526084162910820e+02,4.378997157715617261e-01,1.100000010988609489e+01,1.496082763617331401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377402709311850515e+01,6.422626084050997406e+02,4.379146765936168806e-01,1.100000010988609489e+01,1.495936778215793683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377493618401851450e+01,6.422726083939105592e+02,4.379296359558196294e-01,1.100000010988609489e+01,1.495790792814255966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377584527491852384e+01,6.422826083827236516e+02,4.379445938581699727e-01,1.100000010988609489e+01,1.495644807412718248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377675436581853319e+01,6.422926083715389041e+02,4.379595503006679658e-01,1.100000010988609489e+01,1.495498822011180531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377766345671854253e+01,6.423026083603563166e+02,4.379745052833135532e-01,1.100000010988609489e+01,1.495352836609642813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377857254761855188e+01,6.423126083491758891e+02,4.379894588061067906e-01,1.100000010988609489e+01,1.495206851208105096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.377948163851856123e+01,6.423226083379976217e+02,4.380044108690476223e-01,1.100000010988609489e+01,1.495060865806567378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378039072941857057e+01,6.423326083268216280e+02,4.380193614721360484e-01,1.100000010988609489e+01,1.494914880405029661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378129982031857992e+01,6.423426083156477944e+02,4.380343106153721244e-01,1.100000010988609489e+01,1.494768895003491943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378220891121858926e+01,6.423526083044761208e+02,4.380492582987557948e-01,1.100000010988609489e+01,1.494622909601954226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378311800211859861e+01,6.423626082933066073e+02,4.380642045222871150e-01,1.100000010988609489e+01,1.494476924200416508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378402709301860796e+01,6.423726082821392538e+02,4.380791492859660297e-01,1.100000010988609489e+01,1.494330938798878790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378493618391861730e+01,6.423826082709741740e+02,4.380940925897925387e-01,1.100000010988609489e+01,1.494184953397341073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378584527481862665e+01,6.423926082598112544e+02,4.381090344337666975e-01,1.100000010988609489e+01,1.494038967995803355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378675436571863600e+01,6.424026082486504947e+02,4.381239748178884508e-01,1.100000010988609489e+01,1.493892982594265638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378766345661864534e+01,6.424126082374918951e+02,4.381389137421577984e-01,1.100000010988609489e+01,1.493746997192727920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378857254751865469e+01,6.424226082263354556e+02,4.381538512065747959e-01,1.100000010988609489e+01,1.493601011791190203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.378948163841866403e+01,6.424326082151812898e+02,4.381687872111393878e-01,1.100000010988609489e+01,1.493455026389652485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379039072931867338e+01,6.424426082040292840e+02,4.381837217558515740e-01,1.100000010988609489e+01,1.493309040988114768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379129982021868273e+01,6.424526081928794383e+02,4.381986548407114102e-01,1.100000010988609489e+01,1.493163055586577050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379220891111869207e+01,6.424626081817317527e+02,4.382135864657188407e-01,1.100000010988609489e+01,1.493017070185039333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379311800201870142e+01,6.424726081705862271e+02,4.382285166308738655e-01,1.100000010988609489e+01,1.492871084783501615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379402709291871076e+01,6.424826081594428615e+02,4.382434453361765403e-01,1.100000010988609489e+01,1.492725099381963898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379493618381872011e+01,6.424926081483017697e+02,4.382583725816268094e-01,1.100000010988609489e+01,1.492579113980426180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379584527471872946e+01,6.425026081371628379e+02,4.382732983672246729e-01,1.100000010988609489e+01,1.492433128578888463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379675436561873880e+01,6.425126081260260662e+02,4.382882226929701863e-01,1.100000010988609489e+01,1.492287143177350745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379766345651874815e+01,6.425226081148914545e+02,4.383031455588632941e-01,1.100000010988609489e+01,1.492141157775813028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379857254741875749e+01,6.425326081037590029e+02,4.383180669649039962e-01,1.100000010988609489e+01,1.491995172374275310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.379948163831876684e+01,6.425426080926287113e+02,4.383329869110922927e-01,1.100000010988609489e+01,1.491849186972737593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380039072921877619e+01,6.425526080815006935e+02,4.383479053974282391e-01,1.100000010988609489e+01,1.491703201571199875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380129982011878553e+01,6.425626080703748357e+02,4.383628224239117799e-01,1.100000010988609489e+01,1.491557216169662158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380220891101879488e+01,6.425726080592511380e+02,4.383777379905429150e-01,1.100000010988609489e+01,1.491411230768124440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380311800191880423e+01,6.425826080481296003e+02,4.383926520973216445e-01,1.100000010988609489e+01,1.491265245366586722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380402709281881357e+01,6.425926080370102227e+02,4.384075647442480239e-01,1.100000010988609489e+01,1.491119259965049005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380493618371882292e+01,6.426026080258930051e+02,4.384224759313219977e-01,1.100000010988609489e+01,1.490973274563511287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380584527461883226e+01,6.426126080147779476e+02,4.384373856585435658e-01,1.100000010988609489e+01,1.490827289161973570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380675436551884161e+01,6.426226080036651638e+02,4.384522939259127283e-01,1.100000010988609489e+01,1.490681303760435852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380766345641885096e+01,6.426326079925545400e+02,4.384672007334295407e-01,1.100000010988609489e+01,1.490535318358898135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380857254731886030e+01,6.426426079814460763e+02,4.384821060810939475e-01,1.100000010988609489e+01,1.490389332957360417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.380948163821886965e+01,6.426526079703397727e+02,4.384970099689059486e-01,1.100000010988609489e+01,1.490243347555822700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381039072911887899e+01,6.426626079592356291e+02,4.385119123968655441e-01,1.100000010988609489e+01,1.490097362154284982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381129982001888834e+01,6.426726079481336456e+02,4.385268133649727340e-01,1.100000010988609489e+01,1.489951376752747265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381220891091889769e+01,6.426826079370338221e+02,4.385417128732275738e-01,1.100000010988609489e+01,1.489805391351209547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381311800181890703e+01,6.426926079259362723e+02,4.385566109216300079e-01,1.100000010988609489e+01,1.489659405949671830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381402709271891638e+01,6.427026079148408826e+02,4.385715075101800364e-01,1.100000010988609489e+01,1.489513420548134112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381493618361892572e+01,6.427126079037476529e+02,4.385864026388776593e-01,1.100000010988609489e+01,1.489367435146596395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381584527451893507e+01,6.427226078926565833e+02,4.386012963077228766e-01,1.100000010988609489e+01,1.489221449745058677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381675436541894442e+01,6.427326078815676738e+02,4.386161885167157437e-01,1.100000010988609489e+01,1.489075464343520960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381766345631895376e+01,6.427426078704809242e+02,4.386310792658562052e-01,1.100000010988609489e+01,1.488929478941983242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381857254721896311e+01,6.427526078593963348e+02,4.386459685551442611e-01,1.100000010988609489e+01,1.488783493540445525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.381948163811897246e+01,6.427626078483139054e+02,4.386608563845799114e-01,1.100000010988609489e+01,1.488637508138907807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382039072901898180e+01,6.427726078372337497e+02,4.386757427541631560e-01,1.100000010988609489e+01,1.488491522737370090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382129981991899115e+01,6.427826078261557541e+02,4.386906276638939950e-01,1.100000010988609489e+01,1.488345537335832372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382220891081900049e+01,6.427926078150799185e+02,4.387055111137724284e-01,1.100000010988609489e+01,1.488199551934294654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382311800171900984e+01,6.428026078040062430e+02,4.387203931037985116e-01,1.100000010988609489e+01,1.488053566532756937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382402709261901919e+01,6.428126077929347275e+02,4.387352736339721893e-01,1.100000010988609489e+01,1.487907581131219219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382493618351902853e+01,6.428226077818653721e+02,4.387501527042934613e-01,1.100000010988609489e+01,1.487761595729681502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382584527441903788e+01,6.428326077707981767e+02,4.387650303147623276e-01,1.100000010988609489e+01,1.487615610328143784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382675436531904722e+01,6.428426077597331414e+02,4.387799064653787884e-01,1.100000010988609489e+01,1.487469624926606067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382766345621905657e+01,6.428526077486702661e+02,4.387947811561428435e-01,1.100000010988609489e+01,1.487323639525068349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382857254711906592e+01,6.428626077376096646e+02,4.388096543870544930e-01,1.100000010988609489e+01,1.487177654123530632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.382948163801907526e+01,6.428726077265512231e+02,4.388245261581137369e-01,1.100000010988609489e+01,1.487031668721992914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383039072891908461e+01,6.428826077154949417e+02,4.388393964693205751e-01,1.100000010988609489e+01,1.486885683320455197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383129981981909395e+01,6.428926077044408203e+02,4.388542653206750077e-01,1.100000010988609489e+01,1.486739697918917479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383220891071910330e+01,6.429026076933888589e+02,4.388691327121770347e-01,1.100000010988609489e+01,1.486593712517379762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383311800161911265e+01,6.429126076823390576e+02,4.388839986438267116e-01,1.100000010988609489e+01,1.486447727115842044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383402709251912199e+01,6.429226076712914164e+02,4.388988631156239828e-01,1.100000010988609489e+01,1.486301741714304327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383493618341913134e+01,6.429326076602459352e+02,4.389137261275688484e-01,1.100000010988609489e+01,1.486155756312766609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383584527431914069e+01,6.429426076492026141e+02,4.389285876796613084e-01,1.100000010988609489e+01,1.486009770911228892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383675436521915003e+01,6.429526076381614530e+02,4.389434477719013628e-01,1.100000010988609489e+01,1.485863785509691174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383766345611915938e+01,6.429626076271224520e+02,4.389583064042890115e-01,1.100000010988609489e+01,1.485717800108153457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383857254701916872e+01,6.429726076160856110e+02,4.389731635768242546e-01,1.100000010988609489e+01,1.485571814706615739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.383948163791917807e+01,6.429826076050510437e+02,4.389880192895070921e-01,1.100000010988609489e+01,1.485425829305078022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384039072881918742e+01,6.429926075940186365e+02,4.390028735423375239e-01,1.100000010988609489e+01,1.485279843903540304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384129981971919676e+01,6.430026075829883894e+02,4.390177263353155501e-01,1.100000010988609489e+01,1.485133858502002586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384220891061920611e+01,6.430126075719603023e+02,4.390325776684411707e-01,1.100000010988609489e+01,1.484987873100464869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384311800151921545e+01,6.430226075609343752e+02,4.390474275417143857e-01,1.100000010988609489e+01,1.484841887698927151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384402709241922480e+01,6.430326075499106082e+02,4.390622759551351950e-01,1.100000010988609489e+01,1.484695902297389434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384493618331923415e+01,6.430426075388890013e+02,4.390771229087035987e-01,1.100000010988609489e+01,1.484549916895851716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384584527421924349e+01,6.430526075278695544e+02,4.390919684024195968e-01,1.100000010988609489e+01,1.484403931494313999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384675436511925284e+01,6.430626075168522675e+02,4.391068124362831893e-01,1.100000010988609489e+01,1.484257946092776281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384766345601926218e+01,6.430726075058371407e+02,4.391216550102943761e-01,1.100000010988609489e+01,1.484111960691238564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384857254691927153e+01,6.430826074948241740e+02,4.391364961244531573e-01,1.100000010988609489e+01,1.483965975289700846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.384948163781928088e+01,6.430926074838133673e+02,4.391513357787595329e-01,1.100000010988609489e+01,1.483819989888163129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385039072871929022e+01,6.431026074728047206e+02,4.391661739732135028e-01,1.100000010988609489e+01,1.483674004486625411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385129981961929957e+01,6.431126074617982340e+02,4.391810107078150671e-01,1.100000010988609489e+01,1.483528019085087694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385220891051930892e+01,6.431226074507939074e+02,4.391958459825642258e-01,1.100000010988609489e+01,1.483382033683549976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385311800141931826e+01,6.431326074397918546e+02,4.392106797974609234e-01,1.100000010988609489e+01,1.483236048282012259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385402709231932761e+01,6.431426074287919619e+02,4.392255121525052153e-01,1.100000010988609489e+01,1.483090062880474541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385493618321933695e+01,6.431526074177942291e+02,4.392403430476971016e-01,1.100000010988609489e+01,1.482944077478936824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385584527411934630e+01,6.431626074067986565e+02,4.392551724830365822e-01,1.100000010988609489e+01,1.482798092077399106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385675436501935565e+01,6.431726073958052439e+02,4.392700004585236573e-01,1.100000010988609489e+01,1.482652106675861389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385766345591936499e+01,6.431826073848139913e+02,4.392848269741583267e-01,1.100000010988609489e+01,1.482506121274323671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385857254681937434e+01,6.431926073738248988e+02,4.392996520299405905e-01,1.100000010988609489e+01,1.482360135872785954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.385948163771938368e+01,6.432026073628379663e+02,4.393144756258704486e-01,1.100000010988609489e+01,1.482214150471248236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386039072861939303e+01,6.432126073518531939e+02,4.393292977619479012e-01,1.100000010988609489e+01,1.482068165069710518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386129981951940238e+01,6.432226073408705815e+02,4.393441184381729481e-01,1.100000010988609489e+01,1.481922179668172801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386220891041941172e+01,6.432326073298901292e+02,4.393589376545455893e-01,1.100000010988609489e+01,1.481776194266635083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386311800131942107e+01,6.432426073189118370e+02,4.393737554110657695e-01,1.100000010988609489e+01,1.481630208865097366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386402709221943041e+01,6.432526073079357047e+02,4.393885717077335440e-01,1.100000010988609489e+01,1.481484223463559648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386493618311943976e+01,6.432626072969617326e+02,4.394033865445489129e-01,1.100000010988609489e+01,1.481338238062021931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386584527401944911e+01,6.432726072859899205e+02,4.394181999215118761e-01,1.100000010988609489e+01,1.481192252660484213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386675436491945845e+01,6.432826072750202684e+02,4.394330118386224338e-01,1.100000010988609489e+01,1.481046267258946496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386766345581946780e+01,6.432926072640527764e+02,4.394478222958805858e-01,1.100000010988609489e+01,1.480900281857408778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386857254671947715e+01,6.433026072530874444e+02,4.394626312932863321e-01,1.100000010988609489e+01,1.480754296455871061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.386948163761948649e+01,6.433126072421242725e+02,4.394774388308396174e-01,1.100000010988609489e+01,1.480608311054333343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387039072851949584e+01,6.433226072311632606e+02,4.394922449085404970e-01,1.100000010988609489e+01,1.480462325652795626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387129981941950518e+01,6.433326072202044088e+02,4.395070495263889709e-01,1.100000010988609489e+01,1.480316340251257908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387220891031951453e+01,6.433426072092477170e+02,4.395218526843850393e-01,1.100000010988609489e+01,1.480170354849720191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387311800121952388e+01,6.433526071982931853e+02,4.395366543825287020e-01,1.100000010988609489e+01,1.480024369448182473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387402709211953322e+01,6.433626071873408137e+02,4.395514546208199036e-01,1.100000010988609489e+01,1.479878384046644756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387493618301954257e+01,6.433726071763906020e+02,4.395662533992586996e-01,1.100000010988609489e+01,1.479732398645107038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387584527391955191e+01,6.433826071654425505e+02,4.395810507178450899e-01,1.100000010988609489e+01,1.479586413243569321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387675436481956126e+01,6.433926071544966589e+02,4.395958465765790746e-01,1.100000010988609489e+01,1.479440427842031603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387766345571957061e+01,6.434026071435529275e+02,4.396106409754606537e-01,1.100000010988609489e+01,1.479294442440493886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387857254661957995e+01,6.434126071326113561e+02,4.396254339144897716e-01,1.100000010988609489e+01,1.479148457038956168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.387948163751958930e+01,6.434226071216719447e+02,4.396402253936664839e-01,1.100000010988609489e+01,1.479002471637418450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388039072841959864e+01,6.434326071107346934e+02,4.396550154129907906e-01,1.100000010988609489e+01,1.478856486235880733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388129981931960799e+01,6.434426070997996021e+02,4.396698039724626916e-01,1.100000010988609489e+01,1.478710500834343015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388220891021961734e+01,6.434526070888666709e+02,4.396845910720821315e-01,1.100000010988609489e+01,1.478564515432805298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388311800111962668e+01,6.434626070779358997e+02,4.396993767118491658e-01,1.100000010988609489e+01,1.478418530031267580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388402709201963603e+01,6.434726070670072886e+02,4.397141608917637945e-01,1.100000010988609489e+01,1.478272544629729863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388493618291964538e+01,6.434826070560808375e+02,4.397289436118260175e-01,1.100000010988609489e+01,1.478126559228192145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388584527381965472e+01,6.434926070451565465e+02,4.397437248720357794e-01,1.100000010988609489e+01,1.477980573826654428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388675436471966407e+01,6.435026070342344156e+02,4.397585046723931357e-01,1.100000010988609489e+01,1.477834588425116710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388766345561967341e+01,6.435126070233144446e+02,4.397732830128980863e-01,1.100000010988609489e+01,1.477688603023578993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388857254651968276e+01,6.435226070123966338e+02,4.397880598935506313e-01,1.100000010988609489e+01,1.477542617622041275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.388948163741969211e+01,6.435326070014809829e+02,4.398028353143507152e-01,1.100000010988609489e+01,1.477396632220503558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389039072831970145e+01,6.435426069905674922e+02,4.398176092752983934e-01,1.100000010988609489e+01,1.477250646818965840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389129981921971080e+01,6.435526069796561615e+02,4.398323817763936661e-01,1.100000010988609489e+01,1.477104661417428123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389220891011972014e+01,6.435626069687469908e+02,4.398471528176364775e-01,1.100000010988609489e+01,1.476958676015890405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389311800101972949e+01,6.435726069578399802e+02,4.398619223990268834e-01,1.100000010988609489e+01,1.476812690614352688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389402709191973884e+01,6.435826069469351296e+02,4.398766905205648836e-01,1.100000010988609489e+01,1.476666705212814970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389493618281974818e+01,6.435926069360324391e+02,4.398914571822504227e-01,1.100000010988609489e+01,1.476520719811277253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389584527371975753e+01,6.436026069251319086e+02,4.399062223840835562e-01,1.100000010988609489e+01,1.476374734409739535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389675436461976687e+01,6.436126069142335382e+02,4.399209861260642840e-01,1.100000010988609489e+01,1.476228749008201818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389766345551977622e+01,6.436226069033373278e+02,4.399357484081925507e-01,1.100000010988609489e+01,1.476082763606664100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389857254641978557e+01,6.436326068924432775e+02,4.399505092304684117e-01,1.100000010988609489e+01,1.475936778205126382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.389948163731979491e+01,6.436426068815513872e+02,4.399652685928918672e-01,1.100000010988609489e+01,1.475790792803588665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390039072821980426e+01,6.436526068706615433e+02,4.399800264954628615e-01,1.100000010988609489e+01,1.475644807402050947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390129981911981361e+01,6.436626068597738595e+02,4.399947829381814501e-01,1.100000010988609489e+01,1.475498822000513230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390220891001982295e+01,6.436726068488883357e+02,4.400095379210476332e-01,1.100000010988609489e+01,1.475352836598975512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390311800091983230e+01,6.436826068380049719e+02,4.400242914440613551e-01,1.100000010988609489e+01,1.475206851197437795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390402709181984164e+01,6.436926068271237682e+02,4.400390435072226714e-01,1.100000010988609489e+01,1.475060865795900077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390493618271985099e+01,6.437026068162447245e+02,4.400537941105315820e-01,1.100000010988609489e+01,1.474914880394362360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390584527361986034e+01,6.437126068053678409e+02,4.400685432539880315e-01,1.100000010988609489e+01,1.474768894992824642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390675436451986968e+01,6.437226067944931174e+02,4.400832909375920754e-01,1.100000010988609489e+01,1.474622909591286925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390766345541987903e+01,6.437326067836205539e+02,4.400980371613436581e-01,1.100000010988609489e+01,1.474476924189749207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390857254631988837e+01,6.437426067727501504e+02,4.401127819252428353e-01,1.100000010988609489e+01,1.474330938788211490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.390948163721989772e+01,6.437526067618819070e+02,4.401275252292896067e-01,1.100000010988609489e+01,1.474184953386673772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391039072811990707e+01,6.437626067510158236e+02,4.401422670734839171e-01,1.100000010988609489e+01,1.474038967985136055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391129981901991641e+01,6.437726067401519003e+02,4.401570074578258218e-01,1.100000010988609489e+01,1.473892982583598337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391220890991992576e+01,6.437826067292901371e+02,4.401717463823152654e-01,1.100000010988609489e+01,1.473746997182060620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391311800081993511e+01,6.437926067184305339e+02,4.401864838469523034e-01,1.100000010988609489e+01,1.473601011780522902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391402709171994445e+01,6.438026067075730907e+02,4.402012198517368802e-01,1.100000010988609489e+01,1.473455026378985185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391493618261995380e+01,6.438126066967176939e+02,4.402159543966690514e-01,1.100000010988609489e+01,1.473309040977447467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391584527351996314e+01,6.438226066858644572e+02,4.402306874817487614e-01,1.100000010988609489e+01,1.473163055575909750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391675436441997249e+01,6.438326066750133805e+02,4.402454191069760658e-01,1.100000010988609489e+01,1.473017070174372032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391766345531998184e+01,6.438426066641644638e+02,4.402601492723509646e-01,1.100000010988609489e+01,1.472871084772834314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391857254621999118e+01,6.438526066533177072e+02,4.402748779778734023e-01,1.100000010988609489e+01,1.472725099371296597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.391948163712000053e+01,6.438626066424731107e+02,4.402896052235434343e-01,1.100000010988609489e+01,1.472579113969758879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392039072802000987e+01,6.438726066316306742e+02,4.403043310093610052e-01,1.100000010988609489e+01,1.472433128568221162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392129981892001922e+01,6.438826066207903978e+02,4.403190553353261705e-01,1.100000010988609489e+01,1.472287143166683444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392220890982002857e+01,6.438926066099522814e+02,4.403337782014388746e-01,1.100000010988609489e+01,1.472141157765145727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392311800072003791e+01,6.439026065991163250e+02,4.403484996076991731e-01,1.100000010988609489e+01,1.471995172363608009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392402709162004726e+01,6.439126065882825287e+02,4.403632195541070105e-01,1.100000010988609489e+01,1.471849186962070292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392493618252005660e+01,6.439226065774507788e+02,4.403779380406624422e-01,1.100000010988609489e+01,1.471703201560532574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392584527342006595e+01,6.439326065666211889e+02,4.403926550673654128e-01,1.100000010988609489e+01,1.471557216158994857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392675436432007530e+01,6.439426065557937591e+02,4.404073706342159777e-01,1.100000010988609489e+01,1.471411230757457139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392766345522008464e+01,6.439526065449684893e+02,4.404220847412140816e-01,1.100000010988609489e+01,1.471265245355919422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392857254612009399e+01,6.439626065341453796e+02,4.404367973883597798e-01,1.100000010988609489e+01,1.471119259954381704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.392948163702010334e+01,6.439726065233244299e+02,4.404515085756530168e-01,1.100000010988609489e+01,1.470973274552843987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393039072792011268e+01,6.439826065125056402e+02,4.404662183030937928e-01,1.100000010988609489e+01,1.470827289151306269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393129981882012203e+01,6.439926065016890107e+02,4.404809265706821630e-01,1.100000010988609489e+01,1.470681303749768552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393220890972013137e+01,6.440026064908745411e+02,4.404956333784180722e-01,1.100000010988609489e+01,1.470535318348230834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393311800062014072e+01,6.440126064800621180e+02,4.405103387263015757e-01,1.100000010988609489e+01,1.470389332946693117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393402709152015007e+01,6.440226064692518548e+02,4.405250426143326181e-01,1.100000010988609489e+01,1.470243347545155399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393493618242015941e+01,6.440326064584437518e+02,4.405397450425112549e-01,1.100000010988609489e+01,1.470097362143617682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393584527332016876e+01,6.440426064476378087e+02,4.405544460108374305e-01,1.100000010988609489e+01,1.469951376742079964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393675436422017810e+01,6.440526064368340258e+02,4.405691455193111450e-01,1.100000010988609489e+01,1.469805391340542246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393766345512018745e+01,6.440626064260324029e+02,4.405838435679324538e-01,1.100000010988609489e+01,1.469659405939004529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393857254602019680e+01,6.440726064152329400e+02,4.405985401567013016e-01,1.100000010988609489e+01,1.469513420537466811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.393948163692020614e+01,6.440826064044356372e+02,4.406132352856177437e-01,1.100000010988609489e+01,1.469367435135929094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394039072782021549e+01,6.440926063936403807e+02,4.406279289546817246e-01,1.100000010988609489e+01,1.469221449734391376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394129981872022483e+01,6.441026063828472843e+02,4.406426211638932444e-01,1.100000010988609489e+01,1.469075464332853659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394220890962023418e+01,6.441126063720563479e+02,4.406573119132523586e-01,1.100000010988609489e+01,1.468929478931315941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394311800052024353e+01,6.441226063612675716e+02,4.406720012027590117e-01,1.100000010988609489e+01,1.468783493529778224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394402709142025287e+01,6.441326063504809554e+02,4.406866890324132591e-01,1.100000010988609489e+01,1.468637508128240506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394493618232026222e+01,6.441426063396964992e+02,4.407013754022150454e-01,1.100000010988609489e+01,1.468491522726702789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394584527322027157e+01,6.441526063289142030e+02,4.407160603121643705e-01,1.100000010988609489e+01,1.468345537325165071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394675436412028091e+01,6.441626063181340669e+02,4.407307437622612900e-01,1.100000010988609489e+01,1.468199551923627354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394766345502029026e+01,6.441726063073559772e+02,4.407454257525057484e-01,1.100000010988609489e+01,1.468053566522089636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394857254592029960e+01,6.441826062965800475e+02,4.407601062828977456e-01,1.100000010988609489e+01,1.467907581120551919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.394948163682030895e+01,6.441926062858062778e+02,4.407747853534373372e-01,1.100000010988609489e+01,1.467761595719014201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395039072772031830e+01,6.442026062750346682e+02,4.407894629641244677e-01,1.100000010988609489e+01,1.467615610317476484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395129981862032764e+01,6.442126062642652187e+02,4.408041391149591370e-01,1.100000010988609489e+01,1.467469624915938766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395220890952033699e+01,6.442226062534979292e+02,4.408188138059414007e-01,1.100000010988609489e+01,1.467323639514401049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395311800042034633e+01,6.442326062427326860e+02,4.408334870370712033e-01,1.100000010988609489e+01,1.467177654112863331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395402709132035568e+01,6.442426062319696030e+02,4.408481588083485447e-01,1.100000010988609489e+01,1.467031668711325613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395493618222036503e+01,6.442526062212086799e+02,4.408628291197734805e-01,1.100000010988609489e+01,1.466885683309787896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395584527312037437e+01,6.442626062104499169e+02,4.408774979713459552e-01,1.100000010988609489e+01,1.466739697908250178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395675436402038372e+01,6.442726061996933140e+02,4.408921653630659687e-01,1.100000010988609489e+01,1.466593712506712461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395766345492039306e+01,6.442826061889388711e+02,4.409068312949335766e-01,1.100000010988609489e+01,1.466447727105174743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395857254582040241e+01,6.442926061781864746e+02,4.409214957669487234e-01,1.100000010988609489e+01,1.466301741703637026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.395948163672041176e+01,6.443026061674362381e+02,4.409361587791114090e-01,1.100000010988609489e+01,1.466155756302099308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396039072762042110e+01,6.443126061566881617e+02,4.409508203314216335e-01,1.100000010988609489e+01,1.466009770900561591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396129981852043045e+01,6.443226061459422453e+02,4.409654804238794523e-01,1.100000010988609489e+01,1.465863785499023873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396220890942043980e+01,6.443326061351984890e+02,4.409801390564848100e-01,1.100000010988609489e+01,1.465717800097486156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396311800032044914e+01,6.443426061244568928e+02,4.409947962292377066e-01,1.100000010988609489e+01,1.465571814695948438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396402709122045849e+01,6.443526061137173429e+02,4.410094519421381420e-01,1.100000010988609489e+01,1.465425829294410721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396493618212046783e+01,6.443626061029799530e+02,4.410241061951861719e-01,1.100000010988609489e+01,1.465279843892873003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396584527302047718e+01,6.443726060922447232e+02,4.410387589883817405e-01,1.100000010988609489e+01,1.465133858491335286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396675436392048653e+01,6.443826060815116534e+02,4.410534103217248481e-01,1.100000010988609489e+01,1.464987873089797568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396766345482049587e+01,6.443926060707807437e+02,4.410680601952154944e-01,1.100000010988609489e+01,1.464841887688259851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396857254572050522e+01,6.444026060600518804e+02,4.410827086088537352e-01,1.100000010988609489e+01,1.464695902286722133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.396948163662051456e+01,6.444126060493251771e+02,4.410973555626395148e-01,1.100000010988609489e+01,1.464549916885184416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397039072752052391e+01,6.444226060386006338e+02,4.411120010565728333e-01,1.100000010988609489e+01,1.464403931483646698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397129981842053326e+01,6.444326060278782506e+02,4.411266450906536907e-01,1.100000010988609489e+01,1.464257946082108981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397220890932054260e+01,6.444426060171580275e+02,4.411412876648820869e-01,1.100000010988609489e+01,1.464111960680571263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397311800022055195e+01,6.444526060064399644e+02,4.411559287792580775e-01,1.100000010988609489e+01,1.463965975279033545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397402709112056129e+01,6.444626059957239477e+02,4.411705684337816069e-01,1.100000010988609489e+01,1.463819989877495828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397493618202057064e+01,6.444726059850100910e+02,4.411852066284526752e-01,1.100000010988609489e+01,1.463674004475958110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397584527292057999e+01,6.444826059742983944e+02,4.411998433632712824e-01,1.100000010988609489e+01,1.463528019074420393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397675436382058933e+01,6.444926059635888578e+02,4.412144786382374284e-01,1.100000010988609489e+01,1.463382033672882675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397766345472059868e+01,6.445026059528814812e+02,4.412291124533511133e-01,1.100000010988609489e+01,1.463236048271344958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397857254562060803e+01,6.445126059421761511e+02,4.412437448086123926e-01,1.100000010988609489e+01,1.463090062869807240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.397948163652061737e+01,6.445226059314729810e+02,4.412583757040212107e-01,1.100000010988609489e+01,1.462944077468269523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398039072742062672e+01,6.445326059207719709e+02,4.412730051395775677e-01,1.100000010988609489e+01,1.462798092066731805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398129981832063606e+01,6.445426059100731209e+02,4.412876331152814635e-01,1.100000010988609489e+01,1.462652106665194088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398220890922064541e+01,6.445526058993763172e+02,4.413022596311328982e-01,1.100000010988609489e+01,1.462506121263656370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398311800012065476e+01,6.445626058886816736e+02,4.413168846871318718e-01,1.100000010988609489e+01,1.462360135862118653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398402709102066410e+01,6.445726058779891900e+02,4.413315082832783842e-01,1.100000010988609489e+01,1.462214150460580935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398493618192067345e+01,6.445826058672988665e+02,4.413461304195724355e-01,1.100000010988609489e+01,1.462068165059043218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398584527282068279e+01,6.445926058566107031e+02,4.413607510960140812e-01,1.100000010988609489e+01,1.461922179657505500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398675436372069214e+01,6.446026058459245860e+02,4.413753703126032657e-01,1.100000010988609489e+01,1.461776194255967783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398766345462070149e+01,6.446126058352406289e+02,4.413899880693399891e-01,1.100000010988609489e+01,1.461630208854430065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398857254552071083e+01,6.446226058245588320e+02,4.414046043662242513e-01,1.100000010988609489e+01,1.461484223452892348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.398948163642072018e+01,6.446326058138791950e+02,4.414192192032560524e-01,1.100000010988609489e+01,1.461338238051354630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399039072732072952e+01,6.446426058032016044e+02,4.414338325804353924e-01,1.100000010988609489e+01,1.461192252649816913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399129981822073887e+01,6.446526057925261739e+02,4.414484444977622712e-01,1.100000010988609489e+01,1.461046267248279195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399220890912074822e+01,6.446626057818529034e+02,4.414630549552366889e-01,1.100000010988609489e+01,1.460900281846741477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399311800002075756e+01,6.446726057711817930e+02,4.414776639528586455e-01,1.100000010988609489e+01,1.460754296445203760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399402709092076691e+01,6.446826057605127289e+02,4.414922714906281409e-01,1.100000010988609489e+01,1.460608311043666042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399493618182077626e+01,6.446926057498458249e+02,4.415068775685451752e-01,1.100000010988609489e+01,1.460462325642128325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399584527272078560e+01,6.447026057391810809e+02,4.415214821866097483e-01,1.100000010988609489e+01,1.460316340240590607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399675436362079495e+01,6.447126057285184970e+02,4.415360853448219158e-01,1.100000010988609489e+01,1.460170354839052890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399766345452080429e+01,6.447226057178579595e+02,4.415506870431816222e-01,1.100000010988609489e+01,1.460024369437515172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399857254542081364e+01,6.447326057071995820e+02,4.415652872816888674e-01,1.100000010988609489e+01,1.459878384035977455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.399948163632082299e+01,6.447426056965433645e+02,4.415798860603436515e-01,1.100000010988609489e+01,1.459732398634439737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400039072722083233e+01,6.447526056858893071e+02,4.415944833791459745e-01,1.100000010988609489e+01,1.459586413232902020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400129981812084168e+01,6.447626056752372961e+02,4.416090792380958363e-01,1.100000010988609489e+01,1.459440427831364302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400220890902085102e+01,6.447726056645874451e+02,4.416236736371932370e-01,1.100000010988609489e+01,1.459294442429826585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400311799992086037e+01,6.447826056539397541e+02,4.416382665764381765e-01,1.100000010988609489e+01,1.459148457028288867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400402709082086972e+01,6.447926056432942232e+02,4.416528580558306549e-01,1.100000010988609489e+01,1.459002471626751150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400493618172087906e+01,6.448026056326507387e+02,4.416674480753706722e-01,1.100000010988609489e+01,1.458856486225213432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400584527262088841e+01,6.448126056220094142e+02,4.416820366350582283e-01,1.100000010988609489e+01,1.458710500823675715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400675436352089775e+01,6.448226056113702498e+02,4.416966237348933233e-01,1.100000010988609489e+01,1.458564515422137997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400766345442090710e+01,6.448326056007332454e+02,4.417112093748759571e-01,1.100000010988609489e+01,1.458418530020600280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400857254532091645e+01,6.448426055900982874e+02,4.417257935550061299e-01,1.100000010988609489e+01,1.458272544619062562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.400948163622092579e+01,6.448526055794654894e+02,4.417403762752838414e-01,1.100000010988609489e+01,1.458126559217524845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401039072712093514e+01,6.448626055688348515e+02,4.417549575357090919e-01,1.100000010988609489e+01,1.457980573815987127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401129981802094449e+01,6.448726055582062600e+02,4.417695373362818256e-01,1.100000010988609489e+01,1.457834588414449409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401220890892095383e+01,6.448826055475798285e+02,4.417841156770020983e-01,1.100000010988609489e+01,1.457688603012911692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401311799982096318e+01,6.448926055369555570e+02,4.417986925578699098e-01,1.100000010988609489e+01,1.457542617611373974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401402709072097252e+01,6.449026055263334456e+02,4.418132679788852601e-01,1.100000010988609489e+01,1.457396632209836257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401493618162098187e+01,6.449126055157133806e+02,4.418278419400481494e-01,1.100000010988609489e+01,1.457250646808298539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401584527252099122e+01,6.449226055050954756e+02,4.418424144413585775e-01,1.100000010988609489e+01,1.457104661406760822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401675436342100056e+01,6.449326054944797306e+02,4.418569854828165444e-01,1.100000010988609489e+01,1.456958676005223104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401766345432100991e+01,6.449426054838661457e+02,4.418715550644220502e-01,1.100000010988609489e+01,1.456812690603685387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401857254522101925e+01,6.449526054732546072e+02,4.418861231861750949e-01,1.100000010988609489e+01,1.456666705202147669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.401948163612102860e+01,6.449626054626452287e+02,4.419006898480756784e-01,1.100000010988609489e+01,1.456520719800609952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402039072702103795e+01,6.449726054520380103e+02,4.419152550501238008e-01,1.100000010988609489e+01,1.456374734399072234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402129981792104729e+01,6.449826054414328382e+02,4.419298187923194621e-01,1.100000010988609489e+01,1.456228748997534517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402220890882105664e+01,6.449926054308298262e+02,4.419443810746626622e-01,1.100000010988609489e+01,1.456082763595996799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402311799972106598e+01,6.450026054202289743e+02,4.419589418971533457e-01,1.100000010988609489e+01,1.455936778194459082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402402709062107533e+01,6.450126054096301687e+02,4.419735012597915680e-01,1.100000010988609489e+01,1.455790792792921364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402493618152108468e+01,6.450226053990335231e+02,4.419880591625773292e-01,1.100000010988609489e+01,1.455644807391383647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402584527242109402e+01,6.450326053884390376e+02,4.420026156055106292e-01,1.100000010988609489e+01,1.455498821989845929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402675436332110337e+01,6.450426053778467121e+02,4.420171705885914681e-01,1.100000010988609489e+01,1.455352836588308212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402766345422111272e+01,6.450526053672564331e+02,4.420317241118198459e-01,1.100000010988609489e+01,1.455206851186770494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402857254512112206e+01,6.450626053566683140e+02,4.420462761751957625e-01,1.100000010988609489e+01,1.455060865785232777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.402948163602113141e+01,6.450726053460823550e+02,4.420608267787191625e-01,1.100000010988609489e+01,1.454914880383695059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403039072692114075e+01,6.450826053354984424e+02,4.420753759223901014e-01,1.100000010988609489e+01,1.454768894982157341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403129981782115010e+01,6.450926053249166898e+02,4.420899236062085791e-01,1.100000010988609489e+01,1.454622909580619624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403220890872115945e+01,6.451026053143370973e+02,4.421044698301745957e-01,1.100000010988609489e+01,1.454476924179081906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403311799962116879e+01,6.451126053037595511e+02,4.421190145942881511e-01,1.100000010988609489e+01,1.454330938777544189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403402709052117814e+01,6.451226052931841650e+02,4.421335578985492454e-01,1.100000010988609489e+01,1.454184953376006471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403493618142118748e+01,6.451326052826109390e+02,4.421480997429578230e-01,1.100000010988609489e+01,1.454038967974468754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403584527232119683e+01,6.451426052720397593e+02,4.421626401275139395e-01,1.100000010988609489e+01,1.453892982572931036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403675436322120618e+01,6.451526052614707396e+02,4.421771790522175949e-01,1.100000010988609489e+01,1.453746997171393319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403766345412121552e+01,6.451626052509038800e+02,4.421917165170687891e-01,1.100000010988609489e+01,1.453601011769855601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403857254502122487e+01,6.451726052403390668e+02,4.422062525220675222e-01,1.100000010988609489e+01,1.453455026368317884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.403948163592123421e+01,6.451826052297764136e+02,4.422207870672137386e-01,1.100000010988609489e+01,1.453309040966780166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404039072682124356e+01,6.451926052192159204e+02,4.422353201525074939e-01,1.100000010988609489e+01,1.453163055565242449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404129981772125291e+01,6.452026052086574737e+02,4.422498517779487881e-01,1.100000010988609489e+01,1.453017070163704731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404220890862126225e+01,6.452126051981011869e+02,4.422643819435376211e-01,1.100000010988609489e+01,1.452871084762167014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404311799952127160e+01,6.452226051875470603e+02,4.422789106492739375e-01,1.100000010988609489e+01,1.452725099360629296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404402709042128095e+01,6.452326051769949800e+02,4.422934378951577927e-01,1.100000010988609489e+01,1.452579113959091579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404493618132129029e+01,6.452426051664450597e+02,4.423079636811891868e-01,1.100000010988609489e+01,1.452433128557553861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404584527222129964e+01,6.452526051558972995e+02,4.423224880073681198e-01,1.100000010988609489e+01,1.452287143156016144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404675436312130898e+01,6.452626051453515856e+02,4.423370108736945361e-01,1.100000010988609489e+01,1.452141157754478426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404766345402131833e+01,6.452726051348080318e+02,4.423515322801684913e-01,1.100000010988609489e+01,1.451995172352940709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404857254492132768e+01,6.452826051242666381e+02,4.423660522267899853e-01,1.100000010988609489e+01,1.451849186951402991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.404948163582133702e+01,6.452926051137272907e+02,4.423805707135590182e-01,1.100000010988609489e+01,1.451703201549865273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405039072672134637e+01,6.453026051031901034e+02,4.423950877404755344e-01,1.100000010988609489e+01,1.451557216148327556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405129981762135571e+01,6.453126050926549624e+02,4.424096033075395895e-01,1.100000010988609489e+01,1.451411230746789838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405220890852136506e+01,6.453226050821219815e+02,4.424241174147511835e-01,1.100000010988609489e+01,1.451265245345252121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405311799942137441e+01,6.453326050715911606e+02,4.424386300621102608e-01,1.100000010988609489e+01,1.451119259943714403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405402709032138375e+01,6.453426050610623861e+02,4.424531412496168770e-01,1.100000010988609489e+01,1.450973274542176686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405493618122139310e+01,6.453526050505357716e+02,4.424676509772710320e-01,1.100000010988609489e+01,1.450827289140638968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405584527212140245e+01,6.453626050400113172e+02,4.424821592450726704e-01,1.100000010988609489e+01,1.450681303739101251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405675436302141179e+01,6.453726050294889092e+02,4.424966660530218476e-01,1.100000010988609489e+01,1.450535318337563533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405766345392142114e+01,6.453826050189686612e+02,4.425111714011185637e-01,1.100000010988609489e+01,1.450389332936025816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405857254482143048e+01,6.453926050084505732e+02,4.425256752893627632e-01,1.100000010988609489e+01,1.450243347534488098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.405948163572143983e+01,6.454026049979345316e+02,4.425401777177545015e-01,1.100000010988609489e+01,1.450097362132950381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406039072662144918e+01,6.454126049874206501e+02,4.425546786862937787e-01,1.100000010988609489e+01,1.449951376731412663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406129981752145852e+01,6.454226049769088149e+02,4.425691781949805392e-01,1.100000010988609489e+01,1.449805391329874946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406220890842146787e+01,6.454326049663991398e+02,4.425836762438148386e-01,1.100000010988609489e+01,1.449659405928337228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406311799932147721e+01,6.454426049558916247e+02,4.425981728327966769e-01,1.100000010988609489e+01,1.449513420526799511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406402709022148656e+01,6.454526049453861560e+02,4.426126679619259985e-01,1.100000010988609489e+01,1.449367435125261793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406493618112149591e+01,6.454626049348828474e+02,4.426271616312028589e-01,1.100000010988609489e+01,1.449221449723724076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406584527202150525e+01,6.454726049243815851e+02,4.426416538406272583e-01,1.100000010988609489e+01,1.449075464322186358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406675436292151460e+01,6.454826049138824828e+02,4.426561445901991410e-01,1.100000010988609489e+01,1.448929478920648641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406766345382152394e+01,6.454926049033855406e+02,4.426706338799185625e-01,1.100000010988609489e+01,1.448783493519110923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406857254472153329e+01,6.455026048928906448e+02,4.426851217097854674e-01,1.100000010988609489e+01,1.448637508117573205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.406948163562154264e+01,6.455126048823979090e+02,4.426996080797999111e-01,1.100000010988609489e+01,1.448491522716035488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407039072652155198e+01,6.455226048719072196e+02,4.427140929899618937e-01,1.100000010988609489e+01,1.448345537314497770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407129981742156133e+01,6.455326048614186902e+02,4.427285764402713597e-01,1.100000010988609489e+01,1.448199551912960053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407220890832157068e+01,6.455426048509323209e+02,4.427430584307283645e-01,1.100000010988609489e+01,1.448053566511422335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407311799922158002e+01,6.455526048404479980e+02,4.427575389613328527e-01,1.100000010988609489e+01,1.447907581109884618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407402709012158937e+01,6.455626048299658351e+02,4.427720180320848797e-01,1.100000010988609489e+01,1.447761595708346900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407493618102159871e+01,6.455726048194857185e+02,4.427864956429843901e-01,1.100000010988609489e+01,1.447615610306809183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407584527192160806e+01,6.455826048090077620e+02,4.428009717940314394e-01,1.100000010988609489e+01,1.447469624905271465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407675436282161741e+01,6.455926047985319656e+02,4.428154464852260275e-01,1.100000010988609489e+01,1.447323639503733748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407766345372162675e+01,6.456026047880582155e+02,4.428299197165680989e-01,1.100000010988609489e+01,1.447177654102196030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407857254462163610e+01,6.456126047775866255e+02,4.428443914880577092e-01,1.100000010988609489e+01,1.447031668700658313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.407948163552164544e+01,6.456226047671170818e+02,4.428588617996948029e-01,1.100000010988609489e+01,1.446885683299120595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408039072642165479e+01,6.456326047566496982e+02,4.428733306514794354e-01,1.100000010988609489e+01,1.446739697897582878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408129981732166414e+01,6.456426047461844746e+02,4.428877980434115513e-01,1.100000010988609489e+01,1.446593712496045160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408220890822167348e+01,6.456526047357212974e+02,4.429022639754912061e-01,1.100000010988609489e+01,1.446447727094507443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408311799912168283e+01,6.456626047252602802e+02,4.429167284477183442e-01,1.100000010988609489e+01,1.446301741692969725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408402709002169217e+01,6.456726047148013095e+02,4.429311914600930211e-01,1.100000010988609489e+01,1.446155756291432008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408493618092170152e+01,6.456826047043444987e+02,4.429456530126151814e-01,1.100000010988609489e+01,1.446009770889894290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408584527182171087e+01,6.456926046938897343e+02,4.429601131052848806e-01,1.100000010988609489e+01,1.445863785488356573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408675436272172021e+01,6.457026046834371300e+02,4.429745717381020631e-01,1.100000010988609489e+01,1.445717800086818855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408766345362172956e+01,6.457126046729866857e+02,4.429890289110667845e-01,1.100000010988609489e+01,1.445571814685281137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408857254452173891e+01,6.457226046625382878e+02,4.430034846241789892e-01,1.100000010988609489e+01,1.445425829283743420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.408948163542174825e+01,6.457326046520920499e+02,4.430179388774387328e-01,1.100000010988609489e+01,1.445279843882205702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409039072632175760e+01,6.457426046416478584e+02,4.430323916708459597e-01,1.100000010988609489e+01,1.445133858480667985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409129981722176694e+01,6.457526046312058270e+02,4.430468430044007255e-01,1.100000010988609489e+01,1.444987873079130267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409220890812177629e+01,6.457626046207658419e+02,4.430612928781029747e-01,1.100000010988609489e+01,1.444841887677592550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409311799902178564e+01,6.457726046103280169e+02,4.430757412919527627e-01,1.100000010988609489e+01,1.444695902276054832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409402708992179498e+01,6.457826045998922382e+02,4.430901882459500341e-01,1.100000010988609489e+01,1.444549916874517115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409493618082180433e+01,6.457926045894586196e+02,4.431046337400948443e-01,1.100000010988609489e+01,1.444403931472979397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409584527172181367e+01,6.458026045790271610e+02,4.431190777743871378e-01,1.100000010988609489e+01,1.444257946071441680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409675436262182302e+01,6.458126045685977488e+02,4.431335203488269148e-01,1.100000010988609489e+01,1.444111960669903962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409766345352183237e+01,6.458226045581704966e+02,4.431479614634142306e-01,1.100000010988609489e+01,1.443965975268366245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409857254442184171e+01,6.458326045477452908e+02,4.431624011181490297e-01,1.100000010988609489e+01,1.443819989866828527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.409948163532185106e+01,6.458426045373222451e+02,4.431768393130313677e-01,1.100000010988609489e+01,1.443674004465290810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410039072622186040e+01,6.458526045269012457e+02,4.431912760480611890e-01,1.100000010988609489e+01,1.443528019063753092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410129981712186975e+01,6.458626045164824063e+02,4.432057113232384937e-01,1.100000010988609489e+01,1.443382033662215375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410220890802187910e+01,6.458726045060656134e+02,4.432201451385633373e-01,1.100000010988609489e+01,1.443236048260677657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410311799892188844e+01,6.458826044956509804e+02,4.432345774940356642e-01,1.100000010988609489e+01,1.443090062859139940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410402708982189779e+01,6.458926044852383939e+02,4.432490083896555300e-01,1.100000010988609489e+01,1.442944077457602222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410493618072190714e+01,6.459026044748279674e+02,4.432634378254228791e-01,1.100000010988609489e+01,1.442798092056064505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410584527162191648e+01,6.459126044644195872e+02,4.432778658013377115e-01,1.100000010988609489e+01,1.442652106654526787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410675436252192583e+01,6.459226044540133671e+02,4.432922923174000829e-01,1.100000010988609489e+01,1.442506121252989069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410766345342193517e+01,6.459326044436091934e+02,4.433067173736099376e-01,1.100000010988609489e+01,1.442360135851451352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410857254432194452e+01,6.459426044332071797e+02,4.433211409699672756e-01,1.100000010988609489e+01,1.442214150449913634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.410948163522195387e+01,6.459526044228073260e+02,4.433355631064721525e-01,1.100000010988609489e+01,1.442068165048375917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411039072612196321e+01,6.459626044124095188e+02,4.433499837831245127e-01,1.100000010988609489e+01,1.441922179646838199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411129981702197256e+01,6.459726044020138715e+02,4.433644029999244118e-01,1.100000010988609489e+01,1.441776194245300482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411220890792198190e+01,6.459826043916202707e+02,4.433788207568717943e-01,1.100000010988609489e+01,1.441630208843762764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411311799882199125e+01,6.459926043812288299e+02,4.433932370539666601e-01,1.100000010988609489e+01,1.441484223442225047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411402708972200060e+01,6.460026043708394354e+02,4.434076518912090648e-01,1.100000010988609489e+01,1.441338238040687329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411493618062200994e+01,6.460126043604522010e+02,4.434220652685989528e-01,1.100000010988609489e+01,1.441192252639149612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411584527152201929e+01,6.460226043500670130e+02,4.434364771861363241e-01,1.100000010988609489e+01,1.441046267237611894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411675436242202863e+01,6.460326043396839850e+02,4.434508876438211789e-01,1.100000010988609489e+01,1.440900281836074177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411766345332203798e+01,6.460426043293030034e+02,4.434652966416535724e-01,1.100000010988609489e+01,1.440754296434536459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411857254422204733e+01,6.460526043189241818e+02,4.434797041796334494e-01,1.100000010988609489e+01,1.440608311032998742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.411948163512205667e+01,6.460626043085474066e+02,4.434941102577608096e-01,1.100000010988609489e+01,1.440462325631461024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412039072602206602e+01,6.460726042981727915e+02,4.435085148760357088e-01,1.100000010988609489e+01,1.440316340229923307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412129981692207537e+01,6.460826042878002227e+02,4.435229180344580913e-01,1.100000010988609489e+01,1.440170354828385589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412220890782208471e+01,6.460926042774298139e+02,4.435373197330279571e-01,1.100000010988609489e+01,1.440024369426847872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412311799872209406e+01,6.461026042670614515e+02,4.435517199717453063e-01,1.100000010988609489e+01,1.439878384025310154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412402708962210340e+01,6.461126042566952492e+02,4.435661187506101943e-01,1.100000010988609489e+01,1.439732398623772437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412493618052211275e+01,6.461226042463310932e+02,4.435805160696225657e-01,1.100000010988609489e+01,1.439586413222234719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412584527142212210e+01,6.461326042359690973e+02,4.435949119287824205e-01,1.100000010988609489e+01,1.439440427820697001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412675436232213144e+01,6.461426042256091478e+02,4.436093063280898141e-01,1.100000010988609489e+01,1.439294442419159284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412766345322214079e+01,6.461526042152513583e+02,4.436236992675446911e-01,1.100000010988609489e+01,1.439148457017621566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412857254412215013e+01,6.461626042048956151e+02,4.436380907471470514e-01,1.100000010988609489e+01,1.439002471616083849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.412948163502215948e+01,6.461726041945420320e+02,4.436524807668968950e-01,1.100000010988609489e+01,1.438856486214546131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413039072592216883e+01,6.461826041841904953e+02,4.436668693267942221e-01,1.100000010988609489e+01,1.438710500813008414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413129981682217817e+01,6.461926041738410049e+02,4.436812564268390879e-01,1.100000010988609489e+01,1.438564515411470696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413220890772218752e+01,6.462026041634936746e+02,4.436956420670314372e-01,1.100000010988609489e+01,1.438418530009932979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413311799862219686e+01,6.462126041531483907e+02,4.437100262473712697e-01,1.100000010988609489e+01,1.438272544608395261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413402708952220621e+01,6.462226041428052667e+02,4.437244089678585857e-01,1.100000010988609489e+01,1.438126559206857544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413493618042221556e+01,6.462326041324641892e+02,4.437387902284934404e-01,1.100000010988609489e+01,1.437980573805319826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413584527132222490e+01,6.462426041221252717e+02,4.437531700292757786e-01,1.100000010988609489e+01,1.437834588403782109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413675436222223425e+01,6.462526041117884006e+02,4.437675483702056001e-01,1.100000010988609489e+01,1.437688603002244391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413766345312224360e+01,6.462626041014536895e+02,4.437819252512829049e-01,1.100000010988609489e+01,1.437542617600706674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413857254402225294e+01,6.462726040911210248e+02,4.437963006725076931e-01,1.100000010988609489e+01,1.437396632199168956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.413948163492226229e+01,6.462826040807905201e+02,4.438106746338799646e-01,1.100000010988609489e+01,1.437250646797631239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414039072582227163e+01,6.462926040704620618e+02,4.438250471353997750e-01,1.100000010988609489e+01,1.437104661396093521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414129981672228098e+01,6.463026040601357636e+02,4.438394181770670688e-01,1.100000010988609489e+01,1.436958675994555804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414220890762229033e+01,6.463126040498115117e+02,4.438537877588818459e-01,1.100000010988609489e+01,1.436812690593018086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414311799852229967e+01,6.463226040394893062e+02,4.438681558808441063e-01,1.100000010988609489e+01,1.436666705191480368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414402708942230902e+01,6.463326040291692607e+02,4.438825225429538501e-01,1.100000010988609489e+01,1.436520719789942651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414493618032231836e+01,6.463426040188512616e+02,4.438968877452110773e-01,1.100000010988609489e+01,1.436374734388404933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414584527122232771e+01,6.463526040085354225e+02,4.439112514876157878e-01,1.100000010988609489e+01,1.436228748986867216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414675436212233706e+01,6.463626039982216298e+02,4.439256137701680371e-01,1.100000010988609489e+01,1.436082763585329498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414766345302234640e+01,6.463726039879099972e+02,4.439399745928677699e-01,1.100000010988609489e+01,1.435936778183791781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414857254392235575e+01,6.463826039776004109e+02,4.439543339557149859e-01,1.100000010988609489e+01,1.435790792782254063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.414948163482236509e+01,6.463926039672929846e+02,4.439686918587096853e-01,1.100000010988609489e+01,1.435644807380716346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415039072572237444e+01,6.464026039569876048e+02,4.439830483018518681e-01,1.100000010988609489e+01,1.435498821979178628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415129981662238379e+01,6.464126039466842712e+02,4.439974032851415342e-01,1.100000010988609489e+01,1.435352836577640911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415220890752239313e+01,6.464226039363830978e+02,4.440117568085786837e-01,1.100000010988609489e+01,1.435206851176103193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415311799842240248e+01,6.464326039260839707e+02,4.440261088721633165e-01,1.100000010988609489e+01,1.435060865774565476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415402708932241183e+01,6.464426039157870036e+02,4.440404594758954326e-01,1.100000010988609489e+01,1.434914880373027758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415493618022242117e+01,6.464526039054920830e+02,4.440548086197750877e-01,1.100000010988609489e+01,1.434768894971490041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415584527112243052e+01,6.464626038951993223e+02,4.440691563038022260e-01,1.100000010988609489e+01,1.434622909569952323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415675436202243986e+01,6.464726038849086081e+02,4.440835025279768478e-01,1.100000010988609489e+01,1.434476924168414606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415766345292244921e+01,6.464826038746199401e+02,4.440978472922989528e-01,1.100000010988609489e+01,1.434330938766876888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415857254382245856e+01,6.464926038643334323e+02,4.441121905967685413e-01,1.100000010988609489e+01,1.434184953365339171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.415948163472246790e+01,6.465026038540489708e+02,4.441265324413856130e-01,1.100000010988609489e+01,1.434038967963801453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416039072562247725e+01,6.465126038437666693e+02,4.441408728261501682e-01,1.100000010988609489e+01,1.433892982562263736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416129981652248659e+01,6.465226038334864143e+02,4.441552117510622066e-01,1.100000010988609489e+01,1.433746997160726018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416220890742249594e+01,6.465326038232083192e+02,4.441695492161217285e-01,1.100000010988609489e+01,1.433601011759188300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416311799832250529e+01,6.465426038129322706e+02,4.441838852213287336e-01,1.100000010988609489e+01,1.433455026357650583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416402708922251463e+01,6.465526038026582683e+02,4.441982197666832222e-01,1.100000010988609489e+01,1.433309040956112865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416493618012252398e+01,6.465626037923864260e+02,4.442125528521851940e-01,1.100000010988609489e+01,1.433163055554575148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416584527102253332e+01,6.465726037821166301e+02,4.442268844778346493e-01,1.100000010988609489e+01,1.433017070153037430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416675436192254267e+01,6.465826037718489943e+02,4.442412146436315878e-01,1.100000010988609489e+01,1.432871084751499713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416766345282255202e+01,6.465926037615834048e+02,4.442555433495760098e-01,1.100000010988609489e+01,1.432725099349961995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416857254372256136e+01,6.466026037513198617e+02,4.442698705956679150e-01,1.100000010988609489e+01,1.432579113948424278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.416948163462257071e+01,6.466126037410584786e+02,4.442841963819073037e-01,1.100000010988609489e+01,1.432433128546886560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417039072552258006e+01,6.466226037307991419e+02,4.442985207082941757e-01,1.100000010988609489e+01,1.432287143145348843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417129981642258940e+01,6.466326037205419652e+02,4.443128435748285310e-01,1.100000010988609489e+01,1.432141157743811125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417220890732259875e+01,6.466426037102868349e+02,4.443271649815103697e-01,1.100000010988609489e+01,1.431995172342273408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417311799822260809e+01,6.466526037000337510e+02,4.443414849283396917e-01,1.100000010988609489e+01,1.431849186940735690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417402708912261744e+01,6.466626036897828271e+02,4.443558034153164971e-01,1.100000010988609489e+01,1.431703201539197973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417493618002262679e+01,6.466726036795339496e+02,4.443701204424407858e-01,1.100000010988609489e+01,1.431557216137660255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417584527092263613e+01,6.466826036692871185e+02,4.443844360097125579e-01,1.100000010988609489e+01,1.431411230736122538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417675436182264548e+01,6.466926036590424474e+02,4.443987501171318133e-01,1.100000010988609489e+01,1.431265245334584820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417766345272265482e+01,6.467026036487998226e+02,4.444130627646985521e-01,1.100000010988609489e+01,1.431119259933047103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417857254362266417e+01,6.467126036385593579e+02,4.444273739524127742e-01,1.100000010988609489e+01,1.430973274531509385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.417948163452267352e+01,6.467226036283209396e+02,4.444416836802744797e-01,1.100000010988609489e+01,1.430827289129971668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418039072542268286e+01,6.467326036180845676e+02,4.444559919482836130e-01,1.100000010988609489e+01,1.430681303728433950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418129981632269221e+01,6.467426036078503557e+02,4.444702987564402297e-01,1.100000010988609489e+01,1.430535318326896232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418220890722270155e+01,6.467526035976181902e+02,4.444846041047443297e-01,1.100000010988609489e+01,1.430389332925358515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418311799812271090e+01,6.467626035873880710e+02,4.444989079931959131e-01,1.100000010988609489e+01,1.430243347523820797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418402708902272025e+01,6.467726035771601119e+02,4.445132104217949798e-01,1.100000010988609489e+01,1.430097362122283080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418493617992272959e+01,6.467826035669341991e+02,4.445275113905415298e-01,1.100000010988609489e+01,1.429951376720745362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418584527082273894e+01,6.467926035567104464e+02,4.445418108994355633e-01,1.100000010988609489e+01,1.429805391319207645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418675436172274829e+01,6.468026035464887400e+02,4.445561089484770800e-01,1.100000010988609489e+01,1.429659405917669927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418766345262275763e+01,6.468126035362690800e+02,4.445704055376660802e-01,1.100000010988609489e+01,1.429513420516132210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418857254352276698e+01,6.468226035260515800e+02,4.445847006670025636e-01,1.100000010988609489e+01,1.429367435114594492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.418948163442277632e+01,6.468326035158361265e+02,4.445989943364864749e-01,1.100000010988609489e+01,1.429221449713056775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419039072532278567e+01,6.468426035056227192e+02,4.446132865461178696e-01,1.100000010988609489e+01,1.429075464311519057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419129981622279502e+01,6.468526034954114721e+02,4.446275772958967476e-01,1.100000010988609489e+01,1.428929478909981340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419220890712280436e+01,6.468626034852022713e+02,4.446418665858231090e-01,1.100000010988609489e+01,1.428783493508443622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419311799802281371e+01,6.468726034749951168e+02,4.446561544158969537e-01,1.100000010988609489e+01,1.428637508106905905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419402708892282305e+01,6.468826034647901224e+02,4.446704407861182817e-01,1.100000010988609489e+01,1.428491522705368187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419493617982283240e+01,6.468926034545871744e+02,4.446847256964870376e-01,1.100000010988609489e+01,1.428345537303830470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419584527072284175e+01,6.469026034443862727e+02,4.446990091470032769e-01,1.100000010988609489e+01,1.428199551902292752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419675436162285109e+01,6.469126034341875311e+02,4.447132911376669995e-01,1.100000010988609489e+01,1.428053566500755035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419766345252286044e+01,6.469226034239908358e+02,4.447275716684782054e-01,1.100000010988609489e+01,1.427907581099217317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419857254342286978e+01,6.469326034137961869e+02,4.447418507394368947e-01,1.100000010988609489e+01,1.427761595697679600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.419948163432287913e+01,6.469426034036036981e+02,4.447561283505430674e-01,1.100000010988609489e+01,1.427615610296141882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420039072522288848e+01,6.469526033934132556e+02,4.447704045017966679e-01,1.100000010988609489e+01,1.427469624894604164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420129981612289782e+01,6.469626033832248595e+02,4.447846791931977517e-01,1.100000010988609489e+01,1.427323639493066447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420220890702290717e+01,6.469726033730386234e+02,4.447989524247463189e-01,1.100000010988609489e+01,1.427177654091528729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420311799792291652e+01,6.469826033628544337e+02,4.448132241964423694e-01,1.100000010988609489e+01,1.427031668689991012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420402708882292586e+01,6.469926033526722904e+02,4.448274945082859033e-01,1.100000010988609489e+01,1.426885683288453294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420493617972293521e+01,6.470026033424923071e+02,4.448417633602768650e-01,1.100000010988609489e+01,1.426739697886915577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420584527062294455e+01,6.470126033323143702e+02,4.448560307524153101e-01,1.100000010988609489e+01,1.426593712485377859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420675436152295390e+01,6.470226033221384796e+02,4.448702966847012386e-01,1.100000010988609489e+01,1.426447727083840142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420766345242296325e+01,6.470326033119647491e+02,4.448845611571346503e-01,1.100000010988609489e+01,1.426301741682302424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420857254332297259e+01,6.470426033017930649e+02,4.448988241697154900e-01,1.100000010988609489e+01,1.426155756280764707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.420948163422298194e+01,6.470526032916234271e+02,4.449130857224438129e-01,1.100000010988609489e+01,1.426009770879226989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421039072512299128e+01,6.470626032814559494e+02,4.449273458153196192e-01,1.100000010988609489e+01,1.425863785477689272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421129981602300063e+01,6.470726032712905180e+02,4.449416044483429089e-01,1.100000010988609489e+01,1.425717800076151554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421220890692300998e+01,6.470826032611271330e+02,4.449558616215136264e-01,1.100000010988609489e+01,1.425571814674613837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421311799782301932e+01,6.470926032509659080e+02,4.449701173348318273e-01,1.100000010988609489e+01,1.425425829273076119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421402708872302867e+01,6.471026032408067294e+02,4.449843715882975115e-01,1.100000010988609489e+01,1.425279843871538402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421493617962303802e+01,6.471126032306495972e+02,4.449986243819106235e-01,1.100000010988609489e+01,1.425133858470000684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421584527052304736e+01,6.471226032204945113e+02,4.450128757156712189e-01,1.100000010988609489e+01,1.424987873068462967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421675436142305671e+01,6.471326032103415855e+02,4.450271255895792977e-01,1.100000010988609489e+01,1.424841887666925249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421766345232306605e+01,6.471426032001907060e+02,4.450413740036348598e-01,1.100000010988609489e+01,1.424695902265387532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421857254322307540e+01,6.471526031900418729e+02,4.450556209578378497e-01,1.100000010988609489e+01,1.424549916863849814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.421948163412308475e+01,6.471626031798951999e+02,4.450698664521883230e-01,1.100000010988609489e+01,1.424403931462312096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422039072502309409e+01,6.471726031697505732e+02,4.450841104866862796e-01,1.100000010988609489e+01,1.424257946060774379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422129981592310344e+01,6.471826031596079929e+02,4.450983530613316641e-01,1.100000010988609489e+01,1.424111960659236661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422220890682311278e+01,6.471926031494675726e+02,4.451125941761245319e-01,1.100000010988609489e+01,1.423965975257698944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422311799772312213e+01,6.472026031393291987e+02,4.451268338310648831e-01,1.100000010988609489e+01,1.423819989856161226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422402708862313148e+01,6.472126031291928712e+02,4.451410720261526621e-01,1.100000010988609489e+01,1.423674004454623509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422493617952314082e+01,6.472226031190585900e+02,4.451553087613879245e-01,1.100000010988609489e+01,1.423528019053085791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422584527042315017e+01,6.472326031089264688e+02,4.451695440367706702e-01,1.100000010988609489e+01,1.423382033651548074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422675436132315951e+01,6.472426030987963941e+02,4.451837778523008438e-01,1.100000010988609489e+01,1.423236048250010356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422766345222316886e+01,6.472526030886683657e+02,4.451980102079785007e-01,1.100000010988609489e+01,1.423090062848472639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422857254312317821e+01,6.472626030785424973e+02,4.452122411038036409e-01,1.100000010988609489e+01,1.422944077446934921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.422948163402318755e+01,6.472726030684186753e+02,4.452264705397762090e-01,1.100000010988609489e+01,1.422798092045397204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423039072492319690e+01,6.472826030582968997e+02,4.452406985158962605e-01,1.100000010988609489e+01,1.422652106643859486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423129981582320625e+01,6.472926030481771704e+02,4.452549250321637397e-01,1.100000010988609489e+01,1.422506121242321769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423220890672321559e+01,6.473026030380596012e+02,4.452691500885787024e-01,1.100000010988609489e+01,1.422360135840784051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423311799762322494e+01,6.473126030279440783e+02,4.452833736851411484e-01,1.100000010988609489e+01,1.422214150439246334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423402708852323428e+01,6.473226030178306019e+02,4.452975958218510222e-01,1.100000010988609489e+01,1.422068165037708616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423493617942324363e+01,6.473326030077191717e+02,4.453118164987083794e-01,1.100000010988609489e+01,1.421922179636170899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423584527032325298e+01,6.473426029976099016e+02,4.453260357157131644e-01,1.100000010988609489e+01,1.421776194234633181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423675436122326232e+01,6.473526029875026779e+02,4.453402534728654327e-01,1.100000010988609489e+01,1.421630208833095464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423766345212327167e+01,6.473626029773975006e+02,4.453544697701651844e-01,1.100000010988609489e+01,1.421484223431557746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423857254302328101e+01,6.473726029672943696e+02,4.453686846076123640e-01,1.100000010988609489e+01,1.421338238030020028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.423948163392329036e+01,6.473826029571933987e+02,4.453828979852070269e-01,1.100000010988609489e+01,1.421192252628482311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424039072482329971e+01,6.473926029470944741e+02,4.453971099029491176e-01,1.100000010988609489e+01,1.421046267226944593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424129981572330905e+01,6.474026029369975959e+02,4.454113203608386917e-01,1.100000010988609489e+01,1.420900281825406876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424220890662331840e+01,6.474126029269027640e+02,4.454255293588756937e-01,1.100000010988609489e+01,1.420754296423869158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424311799752332774e+01,6.474226029168100922e+02,4.454397368970601789e-01,1.100000010988609489e+01,1.420608311022331441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424402708842333709e+01,6.474326029067194668e+02,4.454539429753921476e-01,1.100000010988609489e+01,1.420462325620793723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424493617932334644e+01,6.474426028966308877e+02,4.454681475938715440e-01,1.100000010988609489e+01,1.420316340219256006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424584527022335578e+01,6.474526028865443550e+02,4.454823507524984239e-01,1.100000010988609489e+01,1.420170354817718288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424675436112336513e+01,6.474626028764599823e+02,4.454965524512727315e-01,1.100000010988609489e+01,1.420024369416180571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424766345202337448e+01,6.474726028663776560e+02,4.455107526901945225e-01,1.100000010988609489e+01,1.419878384014642853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424857254292338382e+01,6.474826028562973761e+02,4.455249514692637414e-01,1.100000010988609489e+01,1.419732398613105136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.424948163382339317e+01,6.474926028462191425e+02,4.455391487884804436e-01,1.100000010988609489e+01,1.419586413211567418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425039072472340251e+01,6.475026028361430690e+02,4.455533446478445736e-01,1.100000010988609489e+01,1.419440427810029701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425129981562341186e+01,6.475126028260690418e+02,4.455675390473561870e-01,1.100000010988609489e+01,1.419294442408491983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425220890652342121e+01,6.475226028159970610e+02,4.455817319870152282e-01,1.100000010988609489e+01,1.419148457006954266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425311799742343055e+01,6.475326028059271266e+02,4.455959234668217528e-01,1.100000010988609489e+01,1.419002471605416548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425402708832343990e+01,6.475426027958592385e+02,4.456101134867757052e-01,1.100000010988609489e+01,1.418856486203878831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425493617922344924e+01,6.475526027857935105e+02,4.456243020468771410e-01,1.100000010988609489e+01,1.418710500802341113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425584527012345859e+01,6.475626027757298289e+02,4.456384891471260046e-01,1.100000010988609489e+01,1.418564515400803396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425675436102346794e+01,6.475726027656681936e+02,4.456526747875223515e-01,1.100000010988609489e+01,1.418418529999265678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425766345192347728e+01,6.475826027556086046e+02,4.456668589680661263e-01,1.100000010988609489e+01,1.418272544597727960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425857254282348663e+01,6.475926027455511758e+02,4.456810416887573290e-01,1.100000010988609489e+01,1.418126559196190243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.425948163372349597e+01,6.476026027354957932e+02,4.456952229495960149e-01,1.100000010988609489e+01,1.417980573794652525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426039072462350532e+01,6.476126027254424571e+02,4.457094027505821288e-01,1.100000010988609489e+01,1.417834588393114808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426129981552351467e+01,6.476226027153911673e+02,4.457235810917157259e-01,1.100000010988609489e+01,1.417688602991577090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426220890642352401e+01,6.476326027053419239e+02,4.457377579729967509e-01,1.100000010988609489e+01,1.417542617590039373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426311799732353336e+01,6.476426026952948405e+02,4.457519333944252593e-01,1.100000010988609489e+01,1.417396632188501655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426402708822354271e+01,6.476526026852498035e+02,4.457661073560011955e-01,1.100000010988609489e+01,1.417250646786963938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426493617912355205e+01,6.476626026752068128e+02,4.457802798577245595e-01,1.100000010988609489e+01,1.417104661385426220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426584527002356140e+01,6.476726026651658685e+02,4.457944508995954069e-01,1.100000010988609489e+01,1.416958675983888503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426675436092357074e+01,6.476826026551269706e+02,4.458086204816136822e-01,1.100000010988609489e+01,1.416812690582350785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426766345182358009e+01,6.476926026450902327e+02,4.458227886037794407e-01,1.100000010988609489e+01,1.416666705180813068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426857254272358944e+01,6.477026026350555412e+02,4.458369552660926272e-01,1.100000010988609489e+01,1.416520719779275350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.426948163362359878e+01,6.477126026250228961e+02,4.458511204685532414e-01,1.100000010988609489e+01,1.416374734377737633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427039072452360813e+01,6.477226026149922973e+02,4.458652842111613390e-01,1.100000010988609489e+01,1.416228748976199915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427129981542361747e+01,6.477326026049637449e+02,4.458794464939168645e-01,1.100000010988609489e+01,1.416082763574662198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427220890632362682e+01,6.477426025949372388e+02,4.458936073168198733e-01,1.100000010988609489e+01,1.415936778173124480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427311799722363617e+01,6.477526025849128928e+02,4.459077666798703099e-01,1.100000010988609489e+01,1.415790792771586763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427402708812364551e+01,6.477626025748905931e+02,4.459219245830681744e-01,1.100000010988609489e+01,1.415644807370049045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427493617902365486e+01,6.477726025648703398e+02,4.459360810264135222e-01,1.100000010988609489e+01,1.415498821968511328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427584526992366420e+01,6.477826025548521329e+02,4.459502360099062979e-01,1.100000010988609489e+01,1.415352836566973610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427675436082367355e+01,6.477926025448359724e+02,4.459643895335465014e-01,1.100000010988609489e+01,1.415206851165435892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427766345172368290e+01,6.478026025348219719e+02,4.459785415973341882e-01,1.100000010988609489e+01,1.415060865763898175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427857254262369224e+01,6.478126025248100177e+02,4.459926922012693029e-01,1.100000010988609489e+01,1.414914880362360457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.427948163352370159e+01,6.478226025148001099e+02,4.460068413453518454e-01,1.100000010988609489e+01,1.414768894960822740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428039072442371094e+01,6.478326025047922485e+02,4.460209890295818713e-01,1.100000010988609489e+01,1.414622909559285022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428129981532372028e+01,6.478426024947864335e+02,4.460351352539593250e-01,1.100000010988609489e+01,1.414476924157747305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428220890622372963e+01,6.478526024847826648e+02,4.460492800184842066e-01,1.100000010988609489e+01,1.414330938756209587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428311799712373897e+01,6.478626024747810561e+02,4.460634233231565715e-01,1.100000010988609489e+01,1.414184953354671870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428402708802374832e+01,6.478726024647814938e+02,4.460775651679763643e-01,1.100000010988609489e+01,1.414038967953134152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428493617892375767e+01,6.478826024547839779e+02,4.460917055529435848e-01,1.100000010988609489e+01,1.413892982551596435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428584526982376701e+01,6.478926024447885084e+02,4.461058444780582888e-01,1.100000010988609489e+01,1.413746997150058717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428675436072377636e+01,6.479026024347950852e+02,4.461199819433204206e-01,1.100000010988609489e+01,1.413601011748521000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428766345162378570e+01,6.479126024248037083e+02,4.461341179487299802e-01,1.100000010988609489e+01,1.413455026346983282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428857254252379505e+01,6.479226024148143779e+02,4.461482524942869676e-01,1.100000010988609489e+01,1.413309040945445565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.428948163342380440e+01,6.479326024048272075e+02,4.461623855799914384e-01,1.100000010988609489e+01,1.413163055543907847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429039072432381374e+01,6.479426023948420834e+02,4.461765172058433371e-01,1.100000010988609489e+01,1.413017070142370130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429129981522382309e+01,6.479526023848590057e+02,4.461906473718426636e-01,1.100000010988609489e+01,1.412871084740832412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429220890612383243e+01,6.479626023748779744e+02,4.462047760779894179e-01,1.100000010988609489e+01,1.412725099339294695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429311799702384178e+01,6.479726023648989894e+02,4.462189033242836556e-01,1.100000010988609489e+01,1.412579113937756977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429402708792385113e+01,6.479826023549220508e+02,4.462330291107253211e-01,1.100000010988609489e+01,1.412433128536219260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429493617882386047e+01,6.479926023449472723e+02,4.462471534373144144e-01,1.100000010988609489e+01,1.412287143134681542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429584526972386982e+01,6.480026023349745401e+02,4.462612763040509356e-01,1.100000010988609489e+01,1.412141157733143824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429675436062387917e+01,6.480126023250038543e+02,4.462753977109349401e-01,1.100000010988609489e+01,1.411995172331606107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429766345152388851e+01,6.480226023150352148e+02,4.462895176579663725e-01,1.100000010988609489e+01,1.411849186930068389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429857254242389786e+01,6.480326023050686217e+02,4.463036361451452327e-01,1.100000010988609489e+01,1.411703201528530672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.429948163332390720e+01,6.480426022951040750e+02,4.463177531724715208e-01,1.100000010988609489e+01,1.411557216126992954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430039072422391655e+01,6.480526022851415746e+02,4.463318687399452367e-01,1.100000010988609489e+01,1.411411230725455237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430129981512392590e+01,6.480626022751811206e+02,4.463459828475664359e-01,1.100000010988609489e+01,1.411265245323917519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430220890602393524e+01,6.480726022652228266e+02,4.463600954953350630e-01,1.100000010988609489e+01,1.411119259922379802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430311799692394459e+01,6.480826022552665790e+02,4.463742066832511179e-01,1.100000010988609489e+01,1.410973274520842084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430402708782395393e+01,6.480926022453123778e+02,4.463883164113146007e-01,1.100000010988609489e+01,1.410827289119304367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430493617872396328e+01,6.481026022353602229e+02,4.464024246795255113e-01,1.100000010988609489e+01,1.410681303717766649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430584526962397263e+01,6.481126022254101144e+02,4.464165314878839053e-01,1.100000010988609489e+01,1.410535318316228932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430675436052398197e+01,6.481226022154620523e+02,4.464306368363897271e-01,1.100000010988609489e+01,1.410389332914691214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430766345142399132e+01,6.481326022055160365e+02,4.464447407250429767e-01,1.100000010988609489e+01,1.410243347513153497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430857254232400066e+01,6.481426021955720671e+02,4.464588431538436542e-01,1.100000010988609489e+01,1.410097362111615779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.430948163322401001e+01,6.481526021856301440e+02,4.464729441227917595e-01,1.100000010988609489e+01,1.409951376710078062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431039072412401936e+01,6.481626021756903810e+02,4.464870436318872926e-01,1.100000010988609489e+01,1.409805391308540344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431129981502402870e+01,6.481726021657526644e+02,4.465011416811302536e-01,1.100000010988609489e+01,1.409659405907002627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431220890592403805e+01,6.481826021558169941e+02,4.465152382705206979e-01,1.100000010988609489e+01,1.409513420505464909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431311799682404740e+01,6.481926021458833702e+02,4.465293334000585701e-01,1.100000010988609489e+01,1.409367435103927192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431402708772405674e+01,6.482026021359517927e+02,4.465434270697438701e-01,1.100000010988609489e+01,1.409221449702389474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431493617862406609e+01,6.482126021260222615e+02,4.465575192795765980e-01,1.100000010988609489e+01,1.409075464300851756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431584526952407543e+01,6.482226021160947766e+02,4.465716100295567537e-01,1.100000010988609489e+01,1.408929478899314039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431675436042408478e+01,6.482326021061693382e+02,4.465856993196843372e-01,1.100000010988609489e+01,1.408783493497776321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431766345132409413e+01,6.482426020962459461e+02,4.465997871499593486e-01,1.100000010988609489e+01,1.408637508096238604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431857254222410347e+01,6.482526020863246004e+02,4.466138735203817878e-01,1.100000010988609489e+01,1.408491522694700886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.431948163312411282e+01,6.482626020764054147e+02,4.466279584309516548e-01,1.100000010988609489e+01,1.408345537293163169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432039072402412216e+01,6.482726020664882753e+02,4.466420418816690052e-01,1.100000010988609489e+01,1.408199551891625451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432129981492413151e+01,6.482826020565731824e+02,4.466561238725337835e-01,1.100000010988609489e+01,1.408053566490087734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432220890582414086e+01,6.482926020466601358e+02,4.466702044035459895e-01,1.100000010988609489e+01,1.407907581088550016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432311799672415020e+01,6.483026020367491356e+02,4.466842834747056235e-01,1.100000010988609489e+01,1.407761595687012299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432402708762415955e+01,6.483126020268401817e+02,4.466983610860126852e-01,1.100000010988609489e+01,1.407615610285474581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432493617852416889e+01,6.483226020169332742e+02,4.467124372374671748e-01,1.100000010988609489e+01,1.407469624883936864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432584526942417824e+01,6.483326020070284130e+02,4.467265119290690922e-01,1.100000010988609489e+01,1.407323639482399146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432675436032418759e+01,6.483426019971255982e+02,4.467405851608184375e-01,1.100000010988609489e+01,1.407177654080861429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432766345122419693e+01,6.483526019872248298e+02,4.467546569327152106e-01,1.100000010988609489e+01,1.407031668679323711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432857254212420628e+01,6.483626019773261078e+02,4.467687272447594116e-01,1.100000010988609489e+01,1.406885683277785994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.432948163302421563e+01,6.483726019674294321e+02,4.467827960969510404e-01,1.100000010988609489e+01,1.406739697876248276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433039072392422497e+01,6.483826019575348028e+02,4.467968634892900970e-01,1.100000010988609489e+01,1.406593712474710559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433129981482423432e+01,6.483926019476422198e+02,4.468109294217765814e-01,1.100000010988609489e+01,1.406447727073172841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433220890572424366e+01,6.484026019377517969e+02,4.468249938944104938e-01,1.100000010988609489e+01,1.406301741671635123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433311799662425301e+01,6.484126019278634203e+02,4.468390569071918339e-01,1.100000010988609489e+01,1.406155756270097406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433402708752426236e+01,6.484226019179770901e+02,4.468531184601206019e-01,1.100000010988609489e+01,1.406009770868559688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433493617842427170e+01,6.484326019080928063e+02,4.468671785531967977e-01,1.100000010988609489e+01,1.405863785467021971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433584526932428105e+01,6.484426018982105688e+02,4.468812371864204214e-01,1.100000010988609489e+01,1.405717800065484253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433675436022429039e+01,6.484526018883303777e+02,4.468952943597914729e-01,1.100000010988609489e+01,1.405571814663946536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433766345112429974e+01,6.484626018784522330e+02,4.469093500733099522e-01,1.100000010988609489e+01,1.405425829262408818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433857254202430909e+01,6.484726018685761346e+02,4.469234043269758594e-01,1.100000010988609489e+01,1.405279843860871101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.433948163292431843e+01,6.484826018587020826e+02,4.469374571207891944e-01,1.100000010988609489e+01,1.405133858459333383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434039072382432778e+01,6.484926018488300770e+02,4.469515084547499573e-01,1.100000010988609489e+01,1.404987873057795666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434129981472433712e+01,6.485026018389601177e+02,4.469655583288581480e-01,1.100000010988609489e+01,1.404841887656257948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434220890562434647e+01,6.485126018290922048e+02,4.469796067431137665e-01,1.100000010988609489e+01,1.404695902254720231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434311799652435582e+01,6.485226018192263382e+02,4.469936536975168129e-01,1.100000010988609489e+01,1.404549916853182513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434402708742436516e+01,6.485326018093625180e+02,4.470076991920672871e-01,1.100000010988609489e+01,1.404403931451644796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434493617832437451e+01,6.485426017995007442e+02,4.470217432267651891e-01,1.100000010988609489e+01,1.404257946050107078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434584526922438386e+01,6.485526017896410167e+02,4.470357858016105190e-01,1.100000010988609489e+01,1.404111960648569361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434675436012439320e+01,6.485626017797833356e+02,4.470498269166032768e-01,1.100000010988609489e+01,1.403965975247031643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434766345102440255e+01,6.485726017699277008e+02,4.470638665717434623e-01,1.100000010988609489e+01,1.403819989845493926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434857254192441189e+01,6.485826017600741125e+02,4.470779047670310202e-01,1.100000010988609489e+01,1.403674004443956208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.434948163282442124e+01,6.485926017502225704e+02,4.470919415024660060e-01,1.100000010988609489e+01,1.403528019042418491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435039072372443059e+01,6.486026017403730748e+02,4.471059767780484195e-01,1.100000010988609489e+01,1.403382033640880773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435129981462443993e+01,6.486126017305256255e+02,4.471200105937782610e-01,1.100000010988609489e+01,1.403236048239343055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435220890552444928e+01,6.486226017206802226e+02,4.471340429496555302e-01,1.100000010988609489e+01,1.403090062837805338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435311799642445862e+01,6.486326017108368660e+02,4.471480738456802273e-01,1.100000010988609489e+01,1.402944077436267620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435402708732446797e+01,6.486426017009955558e+02,4.471621032818523522e-01,1.100000010988609489e+01,1.402798092034729903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435493617822447732e+01,6.486526016911562920e+02,4.471761312581719050e-01,1.100000010988609489e+01,1.402652106633192185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435584526912448666e+01,6.486626016813190745e+02,4.471901577746388856e-01,1.100000010988609489e+01,1.402506121231654468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435675436002449601e+01,6.486726016714839034e+02,4.472041828312532386e-01,1.100000010988609489e+01,1.402360135830116750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435766345092450536e+01,6.486826016616507786e+02,4.472182064280150193e-01,1.100000010988609489e+01,1.402214150428579033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435857254182451470e+01,6.486926016518198139e+02,4.472322285649242279e-01,1.100000010988609489e+01,1.402068165027041315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.435948163272452405e+01,6.487026016419908956e+02,4.472462492419808644e-01,1.100000010988609489e+01,1.401922179625503598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436039072362453339e+01,6.487126016321640236e+02,4.472602684591849287e-01,1.100000010988609489e+01,1.401776194223965880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436129981452454274e+01,6.487226016223391980e+02,4.472742862165364208e-01,1.100000010988609489e+01,1.401630208822428163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436220890542455209e+01,6.487326016125164188e+02,4.472883025140353408e-01,1.100000010988609489e+01,1.401484223420890445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436311799632456143e+01,6.487426016026956859e+02,4.473023173516816331e-01,1.100000010988609489e+01,1.401338238019352728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436402708722457078e+01,6.487526015928769993e+02,4.473163307294753532e-01,1.100000010988609489e+01,1.401192252617815010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436493617812458012e+01,6.487626015830602455e+02,4.473303426474165012e-01,1.100000010988609489e+01,1.401046267216277293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436584526902458947e+01,6.487726015732455380e+02,4.473443531055050770e-01,1.100000010988609489e+01,1.400900281814739575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436675435992459882e+01,6.487826015634328769e+02,4.473583621037410807e-01,1.100000010988609489e+01,1.400754296413201858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436766345082460816e+01,6.487926015536222621e+02,4.473723696421244567e-01,1.100000010988609489e+01,1.400608311011664140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436857254172461751e+01,6.488026015438136938e+02,4.473863757206552605e-01,1.100000010988609489e+01,1.400462325610126423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.436948163262462685e+01,6.488126015340071717e+02,4.474003803393334922e-01,1.100000010988609489e+01,1.400316340208588705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437039072352463620e+01,6.488226015242026961e+02,4.474143834981591517e-01,1.100000010988609489e+01,1.400170354807050987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437129981442464555e+01,6.488326015144002668e+02,4.474283851971322390e-01,1.100000010988609489e+01,1.400024369405513270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437220890532465489e+01,6.488426015045998838e+02,4.474423854362526987e-01,1.100000010988609489e+01,1.399878384003975552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437311799622466424e+01,6.488526014948015472e+02,4.474563842155205862e-01,1.100000010988609489e+01,1.399732398602437835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437402708712467359e+01,6.488626014850052570e+02,4.474703815349359015e-01,1.100000010988609489e+01,1.399586413200900117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437493617802468293e+01,6.488726014752110132e+02,4.474843773944986447e-01,1.100000010988609489e+01,1.399440427799362400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437584526892469228e+01,6.488826014654188157e+02,4.474983717942087602e-01,1.100000010988609489e+01,1.399294442397824682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437675435982470162e+01,6.488926014556286646e+02,4.475123647340663036e-01,1.100000010988609489e+01,1.399148456996286965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437766345072471097e+01,6.489026014458405598e+02,4.475263562140712748e-01,1.100000010988609489e+01,1.399002471594749247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437857254162472032e+01,6.489126014360545014e+02,4.475403462342236738e-01,1.100000010988609489e+01,1.398856486193211530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.437948163252472966e+01,6.489226014262704894e+02,4.475543347945234451e-01,1.100000010988609489e+01,1.398710500791673812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438039072342473901e+01,6.489326014164885237e+02,4.475683218949706443e-01,1.100000010988609489e+01,1.398564515390136095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438129981432474835e+01,6.489426014067086044e+02,4.475823075355652714e-01,1.100000010988609489e+01,1.398418529988598377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438220890522475770e+01,6.489526013969307314e+02,4.475962917163073262e-01,1.100000010988609489e+01,1.398272544587060660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438311799612476705e+01,6.489626013871549048e+02,4.476102744371967534e-01,1.100000010988609489e+01,1.398126559185522942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438402708702477639e+01,6.489726013773811246e+02,4.476242556982336085e-01,1.100000010988609489e+01,1.397980573783985225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438493617792478574e+01,6.489826013676093908e+02,4.476382354994178914e-01,1.100000010988609489e+01,1.397834588382447507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438584526882479508e+01,6.489926013578397033e+02,4.476522138407495466e-01,1.100000010988609489e+01,1.397688602980909790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438675435972480443e+01,6.490026013480720621e+02,4.476661907222286296e-01,1.100000010988609489e+01,1.397542617579372072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438766345062481378e+01,6.490126013383064674e+02,4.476801661438551405e-01,1.100000010988609489e+01,1.397396632177834355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438857254152482312e+01,6.490226013285429190e+02,4.476941401056290792e-01,1.100000010988609489e+01,1.397250646776296637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.438948163242483247e+01,6.490326013187814169e+02,4.477081126075503903e-01,1.100000010988609489e+01,1.397104661374758919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439039072332484182e+01,6.490426013090219612e+02,4.477220836496191292e-01,1.100000010988609489e+01,1.396958675973221202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439129981422485116e+01,6.490526012992645519e+02,4.477360532318352959e-01,1.100000010988609489e+01,1.396812690571683484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439220890512486051e+01,6.490626012895090753e+02,4.477500213541988350e-01,1.100000010988609489e+01,1.396666705170145767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439311799602486985e+01,6.490726012797556450e+02,4.477639880167098019e-01,1.100000010988609489e+01,1.396520719768608049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439402708692487920e+01,6.490826012700042611e+02,4.477779532193681411e-01,1.100000010988609489e+01,1.396374734367070332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439493617782488855e+01,6.490926012602549235e+02,4.477919169621739082e-01,1.100000010988609489e+01,1.396228748965532614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439584526872489789e+01,6.491026012505076324e+02,4.478058792451271031e-01,1.100000010988609489e+01,1.396082763563994897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439675435962490724e+01,6.491126012407623875e+02,4.478198400682276703e-01,1.100000010988609489e+01,1.395936778162457179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439766345052491658e+01,6.491226012310191891e+02,4.478337994314756654e-01,1.100000010988609489e+01,1.395790792760919462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439857254142492593e+01,6.491326012212780370e+02,4.478477573348710883e-01,1.100000010988609489e+01,1.395644807359381744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.439948163232493528e+01,6.491426012115389312e+02,4.478617137784138835e-01,1.100000010988609489e+01,1.395498821957844027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440039072322494462e+01,6.491526012018018719e+02,4.478756687621041066e-01,1.100000010988609489e+01,1.395352836556306309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440129981412495397e+01,6.491626011920668589e+02,4.478896222859417020e-01,1.100000010988609489e+01,1.395206851154768592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440220890502496331e+01,6.491726011823338922e+02,4.479035743499267253e-01,1.100000010988609489e+01,1.395060865753230874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440311799592497266e+01,6.491826011726029719e+02,4.479175249540591763e-01,1.100000010988609489e+01,1.394914880351693157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440402708682498201e+01,6.491926011628739843e+02,4.479314740983389997e-01,1.100000010988609489e+01,1.394768894950155439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440493617772499135e+01,6.492026011531470431e+02,4.479454217827662510e-01,1.100000010988609489e+01,1.394622909548617722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440584526862500070e+01,6.492126011434221482e+02,4.479593680073408746e-01,1.100000010988609489e+01,1.394476924147080004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440675435952501005e+01,6.492226011336992997e+02,4.479733127720629260e-01,1.100000010988609489e+01,1.394330938745542287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440766345042501939e+01,6.492326011239784975e+02,4.479872560769324052e-01,1.100000010988609489e+01,1.394184953344004569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440857254132502874e+01,6.492426011142597417e+02,4.480011979219492568e-01,1.100000010988609489e+01,1.394038967942466851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.440948163222503808e+01,6.492526011045430323e+02,4.480151383071135363e-01,1.100000010988609489e+01,1.393892982540929134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441039072312504743e+01,6.492626010948283692e+02,4.480290772324251880e-01,1.100000010988609489e+01,1.393746997139391416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441129981402505678e+01,6.492726010851157525e+02,4.480430146978842676e-01,1.100000010988609489e+01,1.393601011737853699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441220890492506612e+01,6.492826010754051822e+02,4.480569507034907195e-01,1.100000010988609489e+01,1.393455026336315981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441311799582507547e+01,6.492926010656965445e+02,4.480708852492445993e-01,1.100000010988609489e+01,1.393309040934778264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441402708672508481e+01,6.493026010559899532e+02,4.480848183351458514e-01,1.100000010988609489e+01,1.393163055533240546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441493617762509416e+01,6.493126010462854083e+02,4.480987499611945313e-01,1.100000010988609489e+01,1.393017070131702829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441584526852510351e+01,6.493226010365829097e+02,4.481126801273905835e-01,1.100000010988609489e+01,1.392871084730165111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441675435942511285e+01,6.493326010268824575e+02,4.481266088337340636e-01,1.100000010988609489e+01,1.392725099328627394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441766345032512220e+01,6.493426010171840517e+02,4.481405360802249160e-01,1.100000010988609489e+01,1.392579113927089676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441857254122513154e+01,6.493526010074876922e+02,4.481544618668631963e-01,1.100000010988609489e+01,1.392433128525551959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.441948163212514089e+01,6.493626009977933791e+02,4.481683861936488489e-01,1.100000010988609489e+01,1.392287143124014241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442039072302515024e+01,6.493726009881011123e+02,4.481823090605819293e-01,1.100000010988609489e+01,1.392141157722476524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442129981392515958e+01,6.493826009784107782e+02,4.481962304676623821e-01,1.100000010988609489e+01,1.391995172320938806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442220890482516893e+01,6.493926009687224905e+02,4.482101504148902626e-01,1.100000010988609489e+01,1.391849186919401089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442311799572517828e+01,6.494026009590362492e+02,4.482240689022655156e-01,1.100000010988609489e+01,1.391703201517863371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442402708662518762e+01,6.494126009493520542e+02,4.482379859297881963e-01,1.100000010988609489e+01,1.391557216116325654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442493617752519697e+01,6.494226009396699055e+02,4.482519014974582494e-01,1.100000010988609489e+01,1.391411230714787936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442584526842520631e+01,6.494326009299898033e+02,4.482658156052757303e-01,1.100000010988609489e+01,1.391265245313250219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442675435932521566e+01,6.494426009203117474e+02,4.482797282532405836e-01,1.100000010988609489e+01,1.391119259911712501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442766345022522501e+01,6.494526009106357378e+02,4.482936394413528647e-01,1.100000010988609489e+01,1.390973274510174783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442857254112523435e+01,6.494626009009616610e+02,4.483075491696125181e-01,1.100000010988609489e+01,1.390827289108637066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.442948163202524370e+01,6.494726008912896305e+02,4.483214574380195994e-01,1.100000010988609489e+01,1.390681303707099348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443039072292525304e+01,6.494826008816196463e+02,4.483353642465740529e-01,1.100000010988609489e+01,1.390535318305561631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443129981382526239e+01,6.494926008719517085e+02,4.483492695952758789e-01,1.100000010988609489e+01,1.390389332904023913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443220890472527174e+01,6.495026008622858171e+02,4.483631734841251326e-01,1.100000010988609489e+01,1.390243347502486196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443311799562528108e+01,6.495126008526219721e+02,4.483770759131217587e-01,1.100000010988609489e+01,1.390097362100948478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443402708652529043e+01,6.495226008429601734e+02,4.483909768822658126e-01,1.100000010988609489e+01,1.389951376699410761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443493617742529977e+01,6.495326008333003074e+02,4.484048763915572389e-01,1.100000010988609489e+01,1.389805391297873043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443584526832530912e+01,6.495426008236424877e+02,4.484187744409960930e-01,1.100000010988609489e+01,1.389659405896335326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443675435922531847e+01,6.495526008139867145e+02,4.484326710305823194e-01,1.100000010988609489e+01,1.389513420494797608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443766345012532781e+01,6.495626008043329875e+02,4.484465661603159181e-01,1.100000010988609489e+01,1.389367435093259891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443857254102533716e+01,6.495726007946813070e+02,4.484604598301969447e-01,1.100000010988609489e+01,1.389221449691722173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.443948163192534651e+01,6.495826007850316728e+02,4.484743520402253436e-01,1.100000010988609489e+01,1.389075464290184456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444039072282535585e+01,6.495926007753839713e+02,4.484882427904011148e-01,1.100000010988609489e+01,1.388929478888646738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444129981372536520e+01,6.496026007657383161e+02,4.485021320807243139e-01,1.100000010988609489e+01,1.388783493487109021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444220890462537454e+01,6.496126007560947073e+02,4.485160199111948853e-01,1.100000010988609489e+01,1.388637508085571303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444311799552538389e+01,6.496226007464531449e+02,4.485299062818128846e-01,1.100000010988609489e+01,1.388491522684033586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444402708642539324e+01,6.496326007368136288e+02,4.485437911925782561e-01,1.100000010988609489e+01,1.388345537282495868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444493617732540258e+01,6.496426007271761591e+02,4.485576746434910000e-01,1.100000010988609489e+01,1.388199551880958151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444584526822541193e+01,6.496526007175406221e+02,4.485715566345511718e-01,1.100000010988609489e+01,1.388053566479420433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444675435912542127e+01,6.496626007079071314e+02,4.485854371657587158e-01,1.100000010988609489e+01,1.387907581077882715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444766345002543062e+01,6.496726006982756871e+02,4.485993162371136322e-01,1.100000010988609489e+01,1.387761595676344998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444857254092543997e+01,6.496826006886462892e+02,4.486131938486159765e-01,1.100000010988609489e+01,1.387615610274807280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.444948163182544931e+01,6.496926006790189376e+02,4.486270700002656930e-01,1.100000010988609489e+01,1.387469624873269563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445039072272545866e+01,6.497026006693936324e+02,4.486409446920627819e-01,1.100000010988609489e+01,1.387323639471731845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445129981362546800e+01,6.497126006597702599e+02,4.486548179240072987e-01,1.100000010988609489e+01,1.387177654070194128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445220890452547735e+01,6.497226006501489337e+02,4.486686896960991877e-01,1.100000010988609489e+01,1.387031668668656410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445311799542548670e+01,6.497326006405296539e+02,4.486825600083384491e-01,1.100000010988609489e+01,1.386885683267118693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445402708632549604e+01,6.497426006309124205e+02,4.486964288607250828e-01,1.100000010988609489e+01,1.386739697865580975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445493617722550539e+01,6.497526006212972334e+02,4.487102962532591444e-01,1.100000010988609489e+01,1.386593712464043258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445584526812551474e+01,6.497626006116839790e+02,4.487241621859405782e-01,1.100000010988609489e+01,1.386447727062505540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445675435902552408e+01,6.497726006020727709e+02,4.487380266587693844e-01,1.100000010988609489e+01,1.386301741660967823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445766344992553343e+01,6.497826005924636092e+02,4.487518896717456185e-01,1.100000010988609489e+01,1.386155756259430105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445857254082554277e+01,6.497926005828564939e+02,4.487657512248692249e-01,1.100000010988609489e+01,1.386009770857892388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.445948163172555212e+01,6.498026005732514250e+02,4.487796113181402036e-01,1.100000010988609489e+01,1.385863785456354670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446039072262556147e+01,6.498126005636482887e+02,4.487934699515585546e-01,1.100000010988609489e+01,1.385717800054816953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446129981352557081e+01,6.498226005540471988e+02,4.488073271251243335e-01,1.100000010988609489e+01,1.385571814653279235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446220890442558016e+01,6.498326005444481552e+02,4.488211828388374847e-01,1.100000010988609489e+01,1.385425829251741518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446311799532558950e+01,6.498426005348511580e+02,4.488350370926980082e-01,1.100000010988609489e+01,1.385279843850203800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446402708622559885e+01,6.498526005252562072e+02,4.488488898867059040e-01,1.100000010988609489e+01,1.385133858448666083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446493617712560820e+01,6.498626005156631891e+02,4.488627412208612277e-01,1.100000010988609489e+01,1.384987873047128365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446584526802561754e+01,6.498726005060722173e+02,4.488765910951639238e-01,1.100000010988609489e+01,1.384841887645590647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446675435892562689e+01,6.498826004964832919e+02,4.488904395096139921e-01,1.100000010988609489e+01,1.384695902244052930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446766344982563623e+01,6.498926004868964128e+02,4.489042864642114328e-01,1.100000010988609489e+01,1.384549916842515212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446857254072564558e+01,6.499026004773114664e+02,4.489181319589562458e-01,1.100000010988609489e+01,1.384403931440977495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.446948163162565493e+01,6.499126004677285664e+02,4.489319759938484866e-01,1.100000010988609489e+01,1.384257946039439777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447039072252566427e+01,6.499226004581477127e+02,4.489458185688880998e-01,1.100000010988609489e+01,1.384111960637902060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447129981342567362e+01,6.499326004485689054e+02,4.489596596840750853e-01,1.100000010988609489e+01,1.383965975236364342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447220890432568297e+01,6.499426004389921445e+02,4.489734993394094431e-01,1.100000010988609489e+01,1.383819989834826625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447311799522569231e+01,6.499526004294173163e+02,4.489873375348911733e-01,1.100000010988609489e+01,1.383674004433288907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447402708612570166e+01,6.499626004198445344e+02,4.490011742705203313e-01,1.100000010988609489e+01,1.383528019031751190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447493617702571100e+01,6.499726004102737988e+02,4.490150095462968616e-01,1.100000010988609489e+01,1.383382033630213472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447584526792572035e+01,6.499826004007051097e+02,4.490288433622207642e-01,1.100000010988609489e+01,1.383236048228675755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447675435882572970e+01,6.499926003911383532e+02,4.490426757182920392e-01,1.100000010988609489e+01,1.383090062827138037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447766344972573904e+01,6.500026003815736431e+02,4.490565066145106865e-01,1.100000010988609489e+01,1.382944077425600320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447857254062574839e+01,6.500126003720109793e+02,4.490703360508767061e-01,1.100000010988609489e+01,1.382798092024062602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.447948163152575773e+01,6.500226003624503619e+02,4.490841640273901536e-01,1.100000010988609489e+01,1.382652106622524885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448039072242576708e+01,6.500326003528916772e+02,4.490979905440509734e-01,1.100000010988609489e+01,1.382506121220987167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448129981332577643e+01,6.500426003433350388e+02,4.491118156008591655e-01,1.100000010988609489e+01,1.382360135819449450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448220890422578577e+01,6.500526003337804468e+02,4.491256391978147300e-01,1.100000010988609489e+01,1.382214150417911732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448311799512579512e+01,6.500626003242279012e+02,4.491394613349176668e-01,1.100000010988609489e+01,1.382068165016374015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448402708602580446e+01,6.500726003146772882e+02,4.491532820121679759e-01,1.100000010988609489e+01,1.381922179614836297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448493617692581381e+01,6.500826003051287216e+02,4.491671012295656573e-01,1.100000010988609489e+01,1.381776194213298579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448584526782582316e+01,6.500926002955822014e+02,4.491809189871107111e-01,1.100000010988609489e+01,1.381630208811760862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448675435872583250e+01,6.501026002860377275e+02,4.491947352848031927e-01,1.100000010988609489e+01,1.381484223410223144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448766344962584185e+01,6.501126002764951863e+02,4.492085501226430466e-01,1.100000010988609489e+01,1.381338238008685427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448857254052585120e+01,6.501226002669546915e+02,4.492223635006302729e-01,1.100000010988609489e+01,1.381192252607147709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.448948163142586054e+01,6.501326002574162430e+02,4.492361754187648715e-01,1.100000010988609489e+01,1.381046267205609992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449039072232586989e+01,6.501426002478798409e+02,4.492499858770468424e-01,1.100000010988609489e+01,1.380900281804072274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449129981322587923e+01,6.501526002383453715e+02,4.492637948754761856e-01,1.100000010988609489e+01,1.380754296402534557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449220890412588858e+01,6.501626002288129484e+02,4.492776024140529012e-01,1.100000010988609489e+01,1.380608311000996839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449311799502589793e+01,6.501726002192825717e+02,4.492914084927769891e-01,1.100000010988609489e+01,1.380462325599459122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449402708592590727e+01,6.501826002097542414e+02,4.493052131116484493e-01,1.100000010988609489e+01,1.380316340197921404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449493617682591662e+01,6.501926002002278437e+02,4.493190162706672819e-01,1.100000010988609489e+01,1.380170354796383687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449584526772592596e+01,6.502026001907034924e+02,4.493328179698334868e-01,1.100000010988609489e+01,1.380024369394845969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449675435862593531e+01,6.502126001811811875e+02,4.493466182091470640e-01,1.100000010988609489e+01,1.379878383993308252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449766344952594466e+01,6.502226001716608152e+02,4.493604169886080135e-01,1.100000010988609489e+01,1.379732398591770534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449857254042595400e+01,6.502326001621424894e+02,4.493742143082163354e-01,1.100000010988609489e+01,1.379586413190232817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.449948163132596335e+01,6.502426001526262098e+02,4.493880101679720296e-01,1.100000010988609489e+01,1.379440427788695099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450039072222597270e+01,6.502526001431119766e+02,4.494018045678750961e-01,1.100000010988609489e+01,1.379294442387157382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450129981312598204e+01,6.502626001335996762e+02,4.494155975079255905e-01,1.100000010988609489e+01,1.379148456985619664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450220890402599139e+01,6.502726001240894220e+02,4.494293889881234572e-01,1.100000010988609489e+01,1.379002471584081947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450311799492600073e+01,6.502826001145812143e+02,4.494431790084686962e-01,1.100000010988609489e+01,1.378856486182544229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450402708582601008e+01,6.502926001050749392e+02,4.494569675689613075e-01,1.100000010988609489e+01,1.378710500781006511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450493617672601943e+01,6.503026000955707104e+02,4.494707546696012912e-01,1.100000010988609489e+01,1.378564515379468794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450584526762602877e+01,6.503126000860685281e+02,4.494845403103886472e-01,1.100000010988609489e+01,1.378418529977931076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450675435852603812e+01,6.503226000765683921e+02,4.494983244913233755e-01,1.100000010988609489e+01,1.378272544576393359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450766344942604746e+01,6.503326000670701887e+02,4.495121072124054207e-01,1.100000010988609489e+01,1.378126559174855641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450857254032605681e+01,6.503426000575740318e+02,4.495258884736348381e-01,1.100000010988609489e+01,1.377980573773317924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.450948163122606616e+01,6.503526000480799212e+02,4.495396682750116280e-01,1.100000010988609489e+01,1.377834588371780206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451039072212607550e+01,6.503626000385877433e+02,4.495534466165357901e-01,1.100000010988609489e+01,1.377688602970242489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451129981302608485e+01,6.503726000290976117e+02,4.495672234982073245e-01,1.100000010988609489e+01,1.377542617568704771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451220890392609419e+01,6.503826000196095265e+02,4.495809989200262313e-01,1.100000010988609489e+01,1.377396632167167054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451311799482610354e+01,6.503926000101233740e+02,4.495947728819925104e-01,1.100000010988609489e+01,1.377250646765629336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451402708572611289e+01,6.504026000006392678e+02,4.496085453841061619e-01,1.100000010988609489e+01,1.377104661364091619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451493617662612223e+01,6.504125999911572080e+02,4.496223164263671856e-01,1.100000010988609489e+01,1.376958675962553901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451584526752613158e+01,6.504225999816770809e+02,4.496360860087755817e-01,1.100000010988609489e+01,1.376812690561016184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451675435842614093e+01,6.504325999721990001e+02,4.496498541313313502e-01,1.100000010988609489e+01,1.376666705159478466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451766344932615027e+01,6.504425999627229658e+02,4.496636207940344909e-01,1.100000010988609489e+01,1.376520719757940749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451857254022615962e+01,6.504525999532488640e+02,4.496773859968850040e-01,1.100000010988609489e+01,1.376374734356403031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.451948163112616896e+01,6.504625999437768087e+02,4.496911497398828894e-01,1.100000010988609489e+01,1.376228748954865314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452039072202617831e+01,6.504725999343067997e+02,4.497049120230281471e-01,1.100000010988609489e+01,1.376082763553327596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452129981292618766e+01,6.504825999248388371e+02,4.497186728463207772e-01,1.100000010988609489e+01,1.375936778151789878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452220890382619700e+01,6.504925999153728071e+02,4.497324322097607241e-01,1.100000010988609489e+01,1.375790792750252161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452311799472620635e+01,6.505025999059088235e+02,4.497461901133480433e-01,1.100000010988609489e+01,1.375644807348714443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452402708562621569e+01,6.505125998964468863e+02,4.497599465570827348e-01,1.100000010988609489e+01,1.375498821947176726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452493617652622504e+01,6.505225998869868818e+02,4.497737015409647987e-01,1.100000010988609489e+01,1.375352836545639008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452584526742623439e+01,6.505325998775289236e+02,4.497874550649942349e-01,1.100000010988609489e+01,1.375206851144101291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452675435832624373e+01,6.505425998680730117e+02,4.498012071291710434e-01,1.100000010988609489e+01,1.375060865742563573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452766344922625308e+01,6.505525998586190326e+02,4.498149577334952243e-01,1.100000010988609489e+01,1.374914880341025856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452857254012626242e+01,6.505625998491670998e+02,4.498287068779667774e-01,1.100000010988609489e+01,1.374768894939488138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.452948163102627177e+01,6.505725998397170997e+02,4.498424545625856474e-01,1.100000010988609489e+01,1.374622909537950421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453039072192628112e+01,6.505825998302691460e+02,4.498562007873518898e-01,1.100000010988609489e+01,1.374476924136412703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453129981282629046e+01,6.505925998208232386e+02,4.498699455522655044e-01,1.100000010988609489e+01,1.374330938734874986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453220890372629981e+01,6.506025998113792639e+02,4.498836888573264914e-01,1.100000010988609489e+01,1.374184953333337268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453311799462630916e+01,6.506125998019373355e+02,4.498974307025348507e-01,1.100000010988609489e+01,1.374038967931799551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453402708552631850e+01,6.506225997924974536e+02,4.499111710878905823e-01,1.100000010988609489e+01,1.373892982530261833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453493617642632785e+01,6.506325997830595043e+02,4.499249100133936863e-01,1.100000010988609489e+01,1.373746997128724116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453584526732633719e+01,6.506425997736236013e+02,4.499386474790441071e-01,1.100000010988609489e+01,1.373601011727186398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453675435822634654e+01,6.506525997641897447e+02,4.499523834848419002e-01,1.100000010988609489e+01,1.373455026325648681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453766344912635589e+01,6.506625997547578208e+02,4.499661180307870656e-01,1.100000010988609489e+01,1.373309040924110963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453857254002636523e+01,6.506725997453279433e+02,4.499798511168796034e-01,1.100000010988609489e+01,1.373163055522573246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.453948163092637458e+01,6.506825997359001121e+02,4.499935827431195134e-01,1.100000010988609489e+01,1.373017070121035528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454039072182638392e+01,6.506925997264742136e+02,4.500073129095067404e-01,1.100000010988609489e+01,1.372871084719497810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454129981272639327e+01,6.507025997170503615e+02,4.500210416160413396e-01,1.100000010988609489e+01,1.372725099317960093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454220890362640262e+01,6.507125997076284420e+02,4.500347688627233111e-01,1.100000010988609489e+01,1.372579113916422375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454311799452641196e+01,6.507225996982085690e+02,4.500484946495526550e-01,1.100000010988609489e+01,1.372433128514884658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454402708542642131e+01,6.507325996887907422e+02,4.500622189765293157e-01,1.100000010988609489e+01,1.372287143113346940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454493617632643065e+01,6.507425996793748482e+02,4.500759418436533488e-01,1.100000010988609489e+01,1.372141157711809223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454584526722644000e+01,6.507525996699610005e+02,4.500896632509247541e-01,1.100000010988609489e+01,1.371995172310271505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454675435812644935e+01,6.507625996605491991e+02,4.501033831983435318e-01,1.100000010988609489e+01,1.371849186908733788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454766344902645869e+01,6.507725996511393305e+02,4.501171016859096818e-01,1.100000010988609489e+01,1.371703201507196070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454857253992646804e+01,6.507825996417315082e+02,4.501308187136231487e-01,1.100000010988609489e+01,1.371557216105658353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.454948163082647739e+01,6.507925996323256186e+02,4.501445342814839878e-01,1.100000010988609489e+01,1.371411230704120635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455039072172648673e+01,6.508025996229217753e+02,4.501582483894921993e-01,1.100000010988609489e+01,1.371265245302582918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455129981262649608e+01,6.508125996135199784e+02,4.501719610376477276e-01,1.100000010988609489e+01,1.371119259901045200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455220890352650542e+01,6.508225996041201142e+02,4.501856722259506283e-01,1.100000010988609489e+01,1.370973274499507483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455311799442651477e+01,6.508325995947222964e+02,4.501993819544009012e-01,1.100000010988609489e+01,1.370827289097969765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455402708532652412e+01,6.508425995853264112e+02,4.502130902229985465e-01,1.100000010988609489e+01,1.370681303696432048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455493617622653346e+01,6.508525995759325724e+02,4.502267970317435086e-01,1.100000010988609489e+01,1.370535318294894330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455584526712654281e+01,6.508625995665407800e+02,4.502405023806358431e-01,1.100000010988609489e+01,1.370389332893356613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455675435802655215e+01,6.508725995571509202e+02,4.502542062696755498e-01,1.100000010988609489e+01,1.370243347491818895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455766344892656150e+01,6.508825995477631068e+02,4.502679086988625734e-01,1.100000010988609489e+01,1.370097362090281178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455857253982657085e+01,6.508925995383772261e+02,4.502816096681969693e-01,1.100000010988609489e+01,1.369951376688743460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.455948163072658019e+01,6.509025995289933917e+02,4.502953091776787375e-01,1.100000010988609489e+01,1.369805391287205742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456039072162658954e+01,6.509125995196116037e+02,4.503090072273078226e-01,1.100000010988609489e+01,1.369659405885668025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456129981252659888e+01,6.509225995102317484e+02,4.503227038170842800e-01,1.100000010988609489e+01,1.369513420484130307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456220890342660823e+01,6.509325995008539394e+02,4.503363989470081097e-01,1.100000010988609489e+01,1.369367435082592590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456311799432661758e+01,6.509425994914780631e+02,4.503500926170792562e-01,1.100000010988609489e+01,1.369221449681054872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456402708522662692e+01,6.509525994821042332e+02,4.503637848272977751e-01,1.100000010988609489e+01,1.369075464279517155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456493617612663627e+01,6.509625994727324496e+02,4.503774755776636662e-01,1.100000010988609489e+01,1.368929478877979437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456584526702664562e+01,6.509725994633625987e+02,4.503911648681768742e-01,1.100000010988609489e+01,1.368783493476441720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456675435792665496e+01,6.509825994539947942e+02,4.504048526988374546e-01,1.100000010988609489e+01,1.368637508074904002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456766344882666431e+01,6.509925994446289224e+02,4.504185390696454072e-01,1.100000010988609489e+01,1.368491522673366285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456857253972667365e+01,6.510025994352650969e+02,4.504322239806006767e-01,1.100000010988609489e+01,1.368345537271828567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.456948163062668300e+01,6.510125994259032041e+02,4.504459074317033185e-01,1.100000010988609489e+01,1.368199551870290850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457039072152669235e+01,6.510225994165433576e+02,4.504595894229533326e-01,1.100000010988609489e+01,1.368053566468753132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457129981242670169e+01,6.510325994071855575e+02,4.504732699543506635e-01,1.100000010988609489e+01,1.367907581067215415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457220890332671104e+01,6.510425993978296901e+02,4.504869490258953668e-01,1.100000010988609489e+01,1.367761595665677697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457311799422672038e+01,6.510525993884758691e+02,4.505006266375873869e-01,1.100000010988609489e+01,1.367615610264139980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457402708512672973e+01,6.510625993791239807e+02,4.505143027894267793e-01,1.100000010988609489e+01,1.367469624862602262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457493617602673908e+01,6.510725993697741387e+02,4.505279774814135441e-01,1.100000010988609489e+01,1.367323639461064545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457584526692674842e+01,6.510825993604262294e+02,4.505416507135476256e-01,1.100000010988609489e+01,1.367177654059526827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457675435782675777e+01,6.510925993510803664e+02,4.505553224858290795e-01,1.100000010988609489e+01,1.367031668657989110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457766344872676711e+01,6.511025993417364361e+02,4.505689927982578502e-01,1.100000010988609489e+01,1.366885683256451392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457857253962677646e+01,6.511125993323945522e+02,4.505826616508339932e-01,1.100000010988609489e+01,1.366739697854913674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.457948163052678581e+01,6.511225993230547147e+02,4.505963290435574531e-01,1.100000010988609489e+01,1.366593712453375957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458039072142679515e+01,6.511325993137168098e+02,4.506099949764282853e-01,1.100000010988609489e+01,1.366447727051838239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458129981232680450e+01,6.511425993043809513e+02,4.506236594494464898e-01,1.100000010988609489e+01,1.366301741650300522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458220890322681385e+01,6.511525992950470254e+02,4.506373224626120111e-01,1.100000010988609489e+01,1.366155756248762804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458311799412682319e+01,6.511625992857151459e+02,4.506509840159249047e-01,1.100000010988609489e+01,1.366009770847225087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458402708502683254e+01,6.511725992763851991e+02,4.506646441093851152e-01,1.100000010988609489e+01,1.365863785445687369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458493617592684188e+01,6.511825992670572987e+02,4.506783027429926980e-01,1.100000010988609489e+01,1.365717800044149652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458584526682685123e+01,6.511925992577313309e+02,4.506919599167475976e-01,1.100000010988609489e+01,1.365571814642611934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458675435772686058e+01,6.512025992484074095e+02,4.507056156306498695e-01,1.100000010988609489e+01,1.365425829241074217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458766344862686992e+01,6.512125992390854208e+02,4.507192698846994583e-01,1.100000010988609489e+01,1.365279843839536499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458857253952687927e+01,6.512225992297654784e+02,4.507329226788964194e-01,1.100000010988609489e+01,1.365133858437998782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.458948163042688861e+01,6.512325992204475824e+02,4.507465740132406973e-01,1.100000010988609489e+01,1.364987873036461064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459039072132689796e+01,6.512425992111316191e+02,4.507602238877323475e-01,1.100000010988609489e+01,1.364841887634923347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459129981222690731e+01,6.512525992018177021e+02,4.507738723023713145e-01,1.100000010988609489e+01,1.364695902233385629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459220890312691665e+01,6.512625991925057178e+02,4.507875192571576539e-01,1.100000010988609489e+01,1.364549916831847912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459311799402692600e+01,6.512725991831957799e+02,4.508011647520913101e-01,1.100000010988609489e+01,1.364403931430310194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459402708492693534e+01,6.512825991738877747e+02,4.508148087871723386e-01,1.100000010988609489e+01,1.364257946028772477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459493617582694469e+01,6.512925991645818158e+02,4.508284513624006840e-01,1.100000010988609489e+01,1.364111960627234759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459584526672695404e+01,6.513025991552777896e+02,4.508420924777764016e-01,1.100000010988609489e+01,1.363965975225697042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459675435762696338e+01,6.513125991459758097e+02,4.508557321332994361e-01,1.100000010988609489e+01,1.363819989824159324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459766344852697273e+01,6.513225991366757626e+02,4.508693703289698429e-01,1.100000010988609489e+01,1.363674004422621606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459857253942698208e+01,6.513325991273777618e+02,4.508830070647875665e-01,1.100000010988609489e+01,1.363528019021083889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.459948163032699142e+01,6.513425991180816936e+02,4.508966423407526625e-01,1.100000010988609489e+01,1.363382033619546171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460039072122700077e+01,6.513525991087876719e+02,4.509102761568650752e-01,1.100000010988609489e+01,1.363236048218008454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460129981212701011e+01,6.513625990994955828e+02,4.509239085131248048e-01,1.100000010988609489e+01,1.363090062816470736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460220890302701946e+01,6.513725990902055401e+02,4.509375394095319067e-01,1.100000010988609489e+01,1.362944077414933019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460311799392702881e+01,6.513825990809174300e+02,4.509511688460863255e-01,1.100000010988609489e+01,1.362798092013395301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460402708482703815e+01,6.513925990716313663e+02,4.509647968227881165e-01,1.100000010988609489e+01,1.362652106611857584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460493617572704750e+01,6.514025990623472353e+02,4.509784233396372244e-01,1.100000010988609489e+01,1.362506121210319866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460584526662705684e+01,6.514125990530651507e+02,4.509920483966337046e-01,1.100000010988609489e+01,1.362360135808782149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460675435752706619e+01,6.514225990437849987e+02,4.510056719937775016e-01,1.100000010988609489e+01,1.362214150407244431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460766344842707554e+01,6.514325990345068931e+02,4.510192941310686154e-01,1.100000010988609489e+01,1.362068165005706714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460857253932708488e+01,6.514425990252307201e+02,4.510329148085071016e-01,1.100000010988609489e+01,1.361922179604168996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.460948163022709423e+01,6.514525990159565936e+02,4.510465340260929046e-01,1.100000010988609489e+01,1.361776194202631279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461039072112710357e+01,6.514625990066843997e+02,4.510601517838260799e-01,1.100000010988609489e+01,1.361630208801093561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461129981202711292e+01,6.514725989974142522e+02,4.510737680817065720e-01,1.100000010988609489e+01,1.361484223399555844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461220890292712227e+01,6.514825989881460373e+02,4.510873829197343809e-01,1.100000010988609489e+01,1.361338237998018126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461311799382713161e+01,6.514925989788798688e+02,4.511009962979095622e-01,1.100000010988609489e+01,1.361192252596480409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461402708472714096e+01,6.515025989696156330e+02,4.511146082162320603e-01,1.100000010988609489e+01,1.361046267194942691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461493617562715031e+01,6.515125989603534435e+02,4.511282186747018752e-01,1.100000010988609489e+01,1.360900281793404974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461584526652715965e+01,6.515225989510931868e+02,4.511418276733190624e-01,1.100000010988609489e+01,1.360754296391867256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461675435742716900e+01,6.515325989418349764e+02,4.511554352120835665e-01,1.100000010988609489e+01,1.360608310990329538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461766344832717834e+01,6.515425989325786986e+02,4.511690412909954428e-01,1.100000010988609489e+01,1.360462325588791821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461857253922718769e+01,6.515525989233244673e+02,4.511826459100546360e-01,1.100000010988609489e+01,1.360316340187254103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.461948163012719704e+01,6.515625989140721686e+02,4.511962490692611460e-01,1.100000010988609489e+01,1.360170354785716386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462039072102720638e+01,6.515725989048218025e+02,4.512098507686150284e-01,1.100000010988609489e+01,1.360024369384178668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462129981192721573e+01,6.515825988955734829e+02,4.512234510081162275e-01,1.100000010988609489e+01,1.359878383982640951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462220890282722507e+01,6.515925988863270959e+02,4.512370497877647435e-01,1.100000010988609489e+01,1.359732398581103233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462311799372723442e+01,6.516025988770827553e+02,4.512506471075605763e-01,1.100000010988609489e+01,1.359586413179565516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462402708462724377e+01,6.516125988678403473e+02,4.512642429675037814e-01,1.100000010988609489e+01,1.359440427778027798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462493617552725311e+01,6.516225988585999858e+02,4.512778373675943033e-01,1.100000010988609489e+01,1.359294442376490081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462584526642726246e+01,6.516325988493615569e+02,4.512914303078321421e-01,1.100000010988609489e+01,1.359148456974952363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462675435732727180e+01,6.516425988401251743e+02,4.513050217882173532e-01,1.100000010988609489e+01,1.359002471573414646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462766344822728115e+01,6.516525988308907245e+02,4.513186118087498810e-01,1.100000010988609489e+01,1.358856486171876928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462857253912729050e+01,6.516625988216583210e+02,4.513322003694297258e-01,1.100000010988609489e+01,1.358710500770339211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.462948163002729984e+01,6.516725988124278501e+02,4.513457874702569428e-01,1.100000010988609489e+01,1.358564515368801493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463039072092730919e+01,6.516825988031993120e+02,4.513593731112314766e-01,1.100000010988609489e+01,1.358418529967263776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463129981182731854e+01,6.516925987939728202e+02,4.513729572923533273e-01,1.100000010988609489e+01,1.358272544565726058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463220890272732788e+01,6.517025987847482611e+02,4.513865400136224948e-01,1.100000010988609489e+01,1.358126559164188341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463311799362733723e+01,6.517125987755257484e+02,4.514001212750390346e-01,1.100000010988609489e+01,1.357980573762650623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463402708452734657e+01,6.517225987663051683e+02,4.514137010766028912e-01,1.100000010988609489e+01,1.357834588361112906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463493617542735592e+01,6.517325987570866346e+02,4.514272794183140647e-01,1.100000010988609489e+01,1.357688602959575188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463584526632736527e+01,6.517425987478700335e+02,4.514408563001725549e-01,1.100000010988609489e+01,1.357542617558037470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463675435722737461e+01,6.517525987386554789e+02,4.514544317221784175e-01,1.100000010988609489e+01,1.357396632156499753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463766344812738396e+01,6.517625987294428569e+02,4.514680056843315969e-01,1.100000010988609489e+01,1.357250646754962035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463857253902739330e+01,6.517725987202321676e+02,4.514815781866320932e-01,1.100000010988609489e+01,1.357104661353424318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.463948162992740265e+01,6.517825987110235246e+02,4.514951492290799062e-01,1.100000010988609489e+01,1.356958675951886600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464039072082741200e+01,6.517925987018168144e+02,4.515087188116750361e-01,1.100000010988609489e+01,1.356812690550348883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464129981172742134e+01,6.518025986926121504e+02,4.515222869344175383e-01,1.100000010988609489e+01,1.356666705148811165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464220890262743069e+01,6.518125986834094192e+02,4.515358535973073573e-01,1.100000010988609489e+01,1.356520719747273448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464311799352744003e+01,6.518225986742087343e+02,4.515494188003444931e-01,1.100000010988609489e+01,1.356374734345735730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464402708442744938e+01,6.518325986650099821e+02,4.515629825435289457e-01,1.100000010988609489e+01,1.356228748944198013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464493617532745873e+01,6.518425986558131626e+02,4.515765448268607152e-01,1.100000010988609489e+01,1.356082763542660295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464584526622746807e+01,6.518525986466183895e+02,4.515901056503398570e-01,1.100000010988609489e+01,1.355936778141122578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464675435712747742e+01,6.518625986374255490e+02,4.516036650139663156e-01,1.100000010988609489e+01,1.355790792739584860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464766344802748677e+01,6.518725986282347549e+02,4.516172229177400910e-01,1.100000010988609489e+01,1.355644807338047143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464857253892749611e+01,6.518825986190458934e+02,4.516307793616611832e-01,1.100000010988609489e+01,1.355498821936509425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.464948162982750546e+01,6.518925986098589647e+02,4.516443343457295923e-01,1.100000010988609489e+01,1.355352836534971708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465039072072751480e+01,6.519025986006740823e+02,4.516578878699453736e-01,1.100000010988609489e+01,1.355206851133433990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465129981162752415e+01,6.519125985914911325e+02,4.516714399343084718e-01,1.100000010988609489e+01,1.355060865731896273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465220890252753350e+01,6.519225985823102292e+02,4.516849905388188868e-01,1.100000010988609489e+01,1.354914880330358555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465311799342754284e+01,6.519325985731312585e+02,4.516985396834766187e-01,1.100000010988609489e+01,1.354768894928820838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465402708432755219e+01,6.519425985639542205e+02,4.517120873682816673e-01,1.100000010988609489e+01,1.354622909527283120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465493617522756153e+01,6.519525985547792288e+02,4.517256335932340328e-01,1.100000010988609489e+01,1.354476924125745402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465584526612757088e+01,6.519625985456061699e+02,4.517391783583337150e-01,1.100000010988609489e+01,1.354330938724207685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465675435702758023e+01,6.519725985364351573e+02,4.517527216635807141e-01,1.100000010988609489e+01,1.354184953322669967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465766344792758957e+01,6.519825985272660773e+02,4.517662635089750855e-01,1.100000010988609489e+01,1.354038967921132250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465857253882759892e+01,6.519925985180989301e+02,4.517798038945167738e-01,1.100000010988609489e+01,1.353892982519594532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.465948162972760827e+01,6.520025985089338292e+02,4.517933428202057788e-01,1.100000010988609489e+01,1.353746997118056815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466039072062761761e+01,6.520125984997706610e+02,4.518068802860421007e-01,1.100000010988609489e+01,1.353601011716519097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466129981152762696e+01,6.520225984906095391e+02,4.518204162920257394e-01,1.100000010988609489e+01,1.353455026314981380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466220890242763630e+01,6.520325984814503499e+02,4.518339508381566949e-01,1.100000010988609489e+01,1.353309040913443662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466311799332764565e+01,6.520425984722930934e+02,4.518474839244349672e-01,1.100000010988609489e+01,1.353163055511905945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466402708422765500e+01,6.520525984631378833e+02,4.518610155508605564e-01,1.100000010988609489e+01,1.353017070110368227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466493617512766434e+01,6.520625984539846058e+02,4.518745457174334623e-01,1.100000010988609489e+01,1.352871084708830510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466584526602767369e+01,6.520725984448332611e+02,4.518880744241536851e-01,1.100000010988609489e+01,1.352725099307292792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466675435692768303e+01,6.520825984356839626e+02,4.519016016710212247e-01,1.100000010988609489e+01,1.352579113905755075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466766344782769238e+01,6.520925984265365969e+02,4.519151274580361366e-01,1.100000010988609489e+01,1.352433128504217357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466857253872770173e+01,6.521025984173912775e+02,4.519286517851983653e-01,1.100000010988609489e+01,1.352287143102679640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.466948162962771107e+01,6.521125984082478908e+02,4.519421746525079109e-01,1.100000010988609489e+01,1.352141157701141922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467039072052772042e+01,6.521225983991064368e+02,4.519556960599647732e-01,1.100000010988609489e+01,1.351995172299604205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467129981142772976e+01,6.521325983899670291e+02,4.519692160075689524e-01,1.100000010988609489e+01,1.351849186898066487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467220890232773911e+01,6.521425983808295541e+02,4.519827344953204484e-01,1.100000010988609489e+01,1.351703201496528770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467311799322774846e+01,6.521525983716940118e+02,4.519962515232192612e-01,1.100000010988609489e+01,1.351557216094991052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467402708412775780e+01,6.521625983625605159e+02,4.520097670912653909e-01,1.100000010988609489e+01,1.351411230693453334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467493617502776715e+01,6.521725983534289526e+02,4.520232811994588373e-01,1.100000010988609489e+01,1.351265245291915617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467584526592777650e+01,6.521825983442993220e+02,4.520367938477996006e-01,1.100000010988609489e+01,1.351119259890377899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467675435682778584e+01,6.521925983351717377e+02,4.520503050362876807e-01,1.100000010988609489e+01,1.350973274488840182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467766344772779519e+01,6.522025983260460862e+02,4.520638147649230776e-01,1.100000010988609489e+01,1.350827289087302464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467857253862780453e+01,6.522125983169223673e+02,4.520773230337057913e-01,1.100000010988609489e+01,1.350681303685764747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.467948162952781388e+01,6.522225983078006948e+02,4.520908298426358218e-01,1.100000010988609489e+01,1.350535318284227029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468039072042782323e+01,6.522325982986809549e+02,4.521043351917131692e-01,1.100000010988609489e+01,1.350389332882689312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468129981132783257e+01,6.522425982895631478e+02,4.521178390809378334e-01,1.100000010988609489e+01,1.350243347481151594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468220890222784192e+01,6.522525982804473870e+02,4.521313415103098143e-01,1.100000010988609489e+01,1.350097362079613877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468311799312785126e+01,6.522625982713335588e+02,4.521448424798291121e-01,1.100000010988609489e+01,1.349951376678076159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468402708402786061e+01,6.522725982622216634e+02,4.521583419894957268e-01,1.100000010988609489e+01,1.349805391276538442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468493617492786996e+01,6.522825982531118143e+02,4.521718400393096582e-01,1.100000010988609489e+01,1.349659405875000724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468584526582787930e+01,6.522925982440038979e+02,4.521853366292709064e-01,1.100000010988609489e+01,1.349513420473463007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468675435672788865e+01,6.523025982348979142e+02,4.521988317593794715e-01,1.100000010988609489e+01,1.349367435071925289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468766344762789799e+01,6.523125982257939768e+02,4.522123254296353534e-01,1.100000010988609489e+01,1.349221449670387572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468857253852790734e+01,6.523225982166919721e+02,4.522258176400384966e-01,1.100000010988609489e+01,1.349075464268849854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.468948162942791669e+01,6.523325982075919001e+02,4.522393083905889566e-01,1.100000010988609489e+01,1.348929478867312137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469039072032792603e+01,6.523425981984938744e+02,4.522527976812867334e-01,1.100000010988609489e+01,1.348783493465774419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469129981122793538e+01,6.523525981893977814e+02,4.522662855121318271e-01,1.100000010988609489e+01,1.348637508064236702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469220890212794473e+01,6.523625981803036211e+02,4.522797718831242375e-01,1.100000010988609489e+01,1.348491522662698984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469311799302795407e+01,6.523725981712115072e+02,4.522932567942639648e-01,1.100000010988609489e+01,1.348345537261161266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469402708392796342e+01,6.523825981621213259e+02,4.523067402455510089e-01,1.100000010988609489e+01,1.348199551859623549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469493617482797276e+01,6.523925981530330773e+02,4.523202222369853698e-01,1.100000010988609489e+01,1.348053566458085831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469584526572798211e+01,6.524025981439468751e+02,4.523337027685670475e-01,1.100000010988609489e+01,1.347907581056548114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469675435662799146e+01,6.524125981348626055e+02,4.523471818402960420e-01,1.100000010988609489e+01,1.347761595655010396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469766344752800080e+01,6.524225981257802687e+02,4.523606594521723534e-01,1.100000010988609489e+01,1.347615610253472679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469857253842801015e+01,6.524325981166999782e+02,4.523741356041959261e-01,1.100000010988609489e+01,1.347469624851934961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.469948162932801949e+01,6.524425981076216203e+02,4.523876102963668155e-01,1.100000010988609489e+01,1.347323639450397244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470039072022802884e+01,6.524525980985451952e+02,4.524010835286850218e-01,1.100000010988609489e+01,1.347177654048859526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470129981112803819e+01,6.524625980894707027e+02,4.524145553011505450e-01,1.100000010988609489e+01,1.347031668647321809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470220890202804753e+01,6.524725980803982566e+02,4.524280256137633849e-01,1.100000010988609489e+01,1.346885683245784091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470311799292805688e+01,6.524825980713277431e+02,4.524414944665235416e-01,1.100000010988609489e+01,1.346739697844246374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470402708382806622e+01,6.524925980622591624e+02,4.524549618594310152e-01,1.100000010988609489e+01,1.346593712442708656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470493617472807557e+01,6.525025980531926280e+02,4.524684277924858056e-01,1.100000010988609489e+01,1.346447727041170939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470584526562808492e+01,6.525125980441280262e+02,4.524818922656878573e-01,1.100000010988609489e+01,1.346301741639633221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470675435652809426e+01,6.525225980350653572e+02,4.524953552790372258e-01,1.100000010988609489e+01,1.346155756238095504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470766344742810361e+01,6.525325980260047345e+02,4.525088168325339111e-01,1.100000010988609489e+01,1.346009770836557786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470857253832811296e+01,6.525425980169460445e+02,4.525222769261779132e-01,1.100000010988609489e+01,1.345863785435020069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.470948162922812230e+01,6.525525980078892871e+02,4.525357355599692322e-01,1.100000010988609489e+01,1.345717800033482351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471039072012813165e+01,6.525625979988344625e+02,4.525491927339078679e-01,1.100000010988609489e+01,1.345571814631944634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471129981102814099e+01,6.525725979897816842e+02,4.525626484479937650e-01,1.100000010988609489e+01,1.345425829230406916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471220890192815034e+01,6.525825979807308386e+02,4.525761027022269789e-01,1.100000010988609489e+01,1.345279843828869198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471311799282815969e+01,6.525925979716819256e+02,4.525895554966075096e-01,1.100000010988609489e+01,1.345133858427331481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471402708372816903e+01,6.526025979626349454e+02,4.526030068311353571e-01,1.100000010988609489e+01,1.344987873025793763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471493617462817838e+01,6.526125979535900115e+02,4.526164567058105215e-01,1.100000010988609489e+01,1.344841887624256046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471584526552818772e+01,6.526225979445470102e+02,4.526299051206329471e-01,1.100000010988609489e+01,1.344695902222718328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471675435642819707e+01,6.526325979355059417e+02,4.526433520756026896e-01,1.100000010988609489e+01,1.344549916821180611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471766344732820642e+01,6.526425979264669195e+02,4.526567975707197489e-01,1.100000010988609489e+01,1.344403931419642893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471857253822821576e+01,6.526525979174298300e+02,4.526702416059841250e-01,1.100000010988609489e+01,1.344257946018105176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.471948162912822511e+01,6.526625979083946731e+02,4.526836841813957624e-01,1.100000010988609489e+01,1.344111960616567458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472039072002823445e+01,6.526725978993614490e+02,4.526971252969547166e-01,1.100000010988609489e+01,1.343965975215029741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472129981092824380e+01,6.526825978903302712e+02,4.527105649526609876e-01,1.100000010988609489e+01,1.343819989813492023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472220890182825315e+01,6.526925978813010261e+02,4.527240031485145755e-01,1.100000010988609489e+01,1.343674004411954306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472311799272826249e+01,6.527025978722737136e+02,4.527374398845154246e-01,1.100000010988609489e+01,1.343528019010416588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472402708362827184e+01,6.527125978632483339e+02,4.527508751606635906e-01,1.100000010988609489e+01,1.343382033608878871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472493617452828119e+01,6.527225978542250004e+02,4.527643089769590734e-01,1.100000010988609489e+01,1.343236048207341153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472584526542829053e+01,6.527325978452035997e+02,4.527777413334018730e-01,1.100000010988609489e+01,1.343090062805803436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472675435632829988e+01,6.527425978361841317e+02,4.527911722299919339e-01,1.100000010988609489e+01,1.342944077404265718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472766344722830922e+01,6.527525978271665963e+02,4.528046016667293117e-01,1.100000010988609489e+01,1.342798092002728001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472857253812831857e+01,6.527625978181511073e+02,4.528180296436140062e-01,1.100000010988609489e+01,1.342652106601190283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.472948162902832792e+01,6.527725978091375509e+02,4.528314561606459621e-01,1.100000010988609489e+01,1.342506121199652565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473039071992833726e+01,6.527825978001259273e+02,4.528448812178252347e-01,1.100000010988609489e+01,1.342360135798114848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473129981082834661e+01,6.527925977911162363e+02,4.528583048151518242e-01,1.100000010988609489e+01,1.342214150396577130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473220890172835595e+01,6.528025977821085917e+02,4.528717269526257305e-01,1.100000010988609489e+01,1.342068164995039413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473311799262836530e+01,6.528125977731028797e+02,4.528851476302468981e-01,1.100000010988609489e+01,1.341922179593501695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473402708352837465e+01,6.528225977640991005e+02,4.528985668480153826e-01,1.100000010988609489e+01,1.341776194191963978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473493617442838399e+01,6.528325977550972539e+02,4.529119846059311838e-01,1.100000010988609489e+01,1.341630208790426260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473584526532839334e+01,6.528425977460974536e+02,4.529254009039942463e-01,1.100000010988609489e+01,1.341484223388888543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473675435622840268e+01,6.528525977370995861e+02,4.529388157422046257e-01,1.100000010988609489e+01,1.341338237987350825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473766344712841203e+01,6.528625977281036512e+02,4.529522291205623219e-01,1.100000010988609489e+01,1.341192252585813108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473857253802842138e+01,6.528725977191096490e+02,4.529656410390672794e-01,1.100000010988609489e+01,1.341046267184275390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.473948162892843072e+01,6.528825977101175795e+02,4.529790514977195537e-01,1.100000010988609489e+01,1.340900281782737673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474039071982844007e+01,6.528925977011275563e+02,4.529924604965191448e-01,1.100000010988609489e+01,1.340754296381199955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474129981072844942e+01,6.529025976921394658e+02,4.530058680354659972e-01,1.100000010988609489e+01,1.340608310979662238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474220890162845876e+01,6.529125976831533080e+02,4.530192741145601665e-01,1.100000010988609489e+01,1.340462325578124520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474311799252846811e+01,6.529225976741690829e+02,4.530326787338015970e-01,1.100000010988609489e+01,1.340316340176586803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474402708342847745e+01,6.529325976651867904e+02,4.530460818931903444e-01,1.100000010988609489e+01,1.340170354775049085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474493617432848680e+01,6.529425976562065443e+02,4.530594835927264086e-01,1.100000010988609489e+01,1.340024369373511368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474584526522849615e+01,6.529525976472282309e+02,4.530728838324097341e-01,1.100000010988609489e+01,1.339878383971973650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474675435612850549e+01,6.529625976382518502e+02,4.530862826122403764e-01,1.100000010988609489e+01,1.339732398570435933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474766344702851484e+01,6.529725976292774021e+02,4.530996799322183355e-01,1.100000010988609489e+01,1.339586413168898215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474857253792852418e+01,6.529825976203050004e+02,4.531130757923435559e-01,1.100000010988609489e+01,1.339440427767360497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.474948162882853353e+01,6.529925976113345314e+02,4.531264701926160932e-01,1.100000010988609489e+01,1.339294442365822780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475039071972854288e+01,6.530025976023659950e+02,4.531398631330358917e-01,1.100000010988609489e+01,1.339148456964285062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475129981062855222e+01,6.530125975933993914e+02,4.531532546136030071e-01,1.100000010988609489e+01,1.339002471562747345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475220890152856157e+01,6.530225975844347204e+02,4.531666446343173837e-01,1.100000010988609489e+01,1.338856486161209627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475311799242857091e+01,6.530325975754719821e+02,4.531800331951790772e-01,1.100000010988609489e+01,1.338710500759671910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475402708332858026e+01,6.530425975665112901e+02,4.531934202961880875e-01,1.100000010988609489e+01,1.338564515358134192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475493617422858961e+01,6.530525975575525308e+02,4.532068059373443591e-01,1.100000010988609489e+01,1.338418529956596475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475584526512859895e+01,6.530625975485957042e+02,4.532201901186479476e-01,1.100000010988609489e+01,1.338272544555058757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475675435602860830e+01,6.530725975396408103e+02,4.532335728400987973e-01,1.100000010988609489e+01,1.338126559153521040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475766344692861765e+01,6.530825975306878490e+02,4.532469541016969639e-01,1.100000010988609489e+01,1.337980573751983322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475857253782862699e+01,6.530925975217369341e+02,4.532603339034423917e-01,1.100000010988609489e+01,1.337834588350445605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.475948162872863634e+01,6.531025975127879519e+02,4.532737122453351364e-01,1.100000010988609489e+01,1.337688602948907887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476039071962864568e+01,6.531125975038409024e+02,4.532870891273751424e-01,1.100000010988609489e+01,1.337542617547370170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476129981052865503e+01,6.531225974948957855e+02,4.533004645495624652e-01,1.100000010988609489e+01,1.337396632145832452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476220890142866438e+01,6.531325974859526013e+02,4.533138385118971048e-01,1.100000010988609489e+01,1.337250646744294735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476311799232867372e+01,6.531425974770113498e+02,4.533272110143790057e-01,1.100000010988609489e+01,1.337104661342757017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476402708322868307e+01,6.531525974680721447e+02,4.533405820570082234e-01,1.100000010988609489e+01,1.336958675941219300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476493617412869241e+01,6.531625974591348722e+02,4.533539516397847025e-01,1.100000010988609489e+01,1.336812690539681582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476584526502870176e+01,6.531725974501995324e+02,4.533673197627084983e-01,1.100000010988609489e+01,1.336666705138143865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476675435592871111e+01,6.531825974412661253e+02,4.533806864257795555e-01,1.100000010988609489e+01,1.336520719736606147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476766344682872045e+01,6.531925974323346509e+02,4.533940516289979294e-01,1.100000010988609489e+01,1.336374734335068429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476857253772872980e+01,6.532025974234051091e+02,4.534074153723635647e-01,1.100000010988609489e+01,1.336228748933530712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.476948162862873914e+01,6.532125974144776137e+02,4.534207776558765168e-01,1.100000010988609489e+01,1.336082763531992994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477039071952874849e+01,6.532225974055520510e+02,4.534341384795367302e-01,1.100000010988609489e+01,1.335936778130455277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477129981042875784e+01,6.532325973966284209e+02,4.534474978433442049e-01,1.100000010988609489e+01,1.335790792728917559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477220890132876718e+01,6.532425973877067236e+02,4.534608557472989965e-01,1.100000010988609489e+01,1.335644807327379842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477311799222877653e+01,6.532525973787869589e+02,4.534742121914010493e-01,1.100000010988609489e+01,1.335498821925842124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477402708312878588e+01,6.532625973698691269e+02,4.534875671756504190e-01,1.100000010988609489e+01,1.335352836524304407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477493617402879522e+01,6.532725973609533412e+02,4.535009207000470499e-01,1.100000010988609489e+01,1.335206851122766689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477584526492880457e+01,6.532825973520394882e+02,4.535142727645909977e-01,1.100000010988609489e+01,1.335060865721228972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477675435582881391e+01,6.532925973431275679e+02,4.535276233692822068e-01,1.100000010988609489e+01,1.334914880319691254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477766344672882326e+01,6.533025973342175803e+02,4.535409725141207327e-01,1.100000010988609489e+01,1.334768894918153537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477857253762883261e+01,6.533125973253095253e+02,4.535543201991065199e-01,1.100000010988609489e+01,1.334622909516615819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.477948162852884195e+01,6.533225973164034031e+02,4.535676664242395684e-01,1.100000010988609489e+01,1.334476924115078102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478039071942885130e+01,6.533325973074992135e+02,4.535810111895199337e-01,1.100000010988609489e+01,1.334330938713540384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478129981032886064e+01,6.533425972985970702e+02,4.535943544949475603e-01,1.100000010988609489e+01,1.334184953312002667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478220890122886999e+01,6.533525972896968597e+02,4.536076963405225038e-01,1.100000010988609489e+01,1.334038967910464949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478311799212887934e+01,6.533625972807985818e+02,4.536210367262447085e-01,1.100000010988609489e+01,1.333892982508927232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478402708302888868e+01,6.533725972719022366e+02,4.536343756521142301e-01,1.100000010988609489e+01,1.333746997107389514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478493617392889803e+01,6.533825972630078240e+02,4.536477131181310130e-01,1.100000010988609489e+01,1.333601011705851797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478584526482890737e+01,6.533925972541153442e+02,4.536610491242950571e-01,1.100000010988609489e+01,1.333455026304314079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478675435572891672e+01,6.534025972452247970e+02,4.536743836706064181e-01,1.100000010988609489e+01,1.333309040902776361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478766344662892607e+01,6.534125972363361825e+02,4.536877167570650404e-01,1.100000010988609489e+01,1.333163055501238644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478857253752893541e+01,6.534225972274496144e+02,4.537010483836709240e-01,1.100000010988609489e+01,1.333017070099700926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.478948162842894476e+01,6.534325972185649789e+02,4.537143785504241245e-01,1.100000010988609489e+01,1.332871084698163209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479039071932895411e+01,6.534425972096822761e+02,4.537277072573245862e-01,1.100000010988609489e+01,1.332725099296625491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479129981022896345e+01,6.534525972008015060e+02,4.537410345043723647e-01,1.100000010988609489e+01,1.332579113895087774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479220890112897280e+01,6.534625971919226686e+02,4.537543602915674046e-01,1.100000010988609489e+01,1.332433128493550056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479311799202898214e+01,6.534725971830457638e+02,4.537676846189097057e-01,1.100000010988609489e+01,1.332287143092012339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479402708292899149e+01,6.534825971741707917e+02,4.537810074863993237e-01,1.100000010988609489e+01,1.332141157690474621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479493617382900084e+01,6.534925971652977523e+02,4.537943288940362030e-01,1.100000010988609489e+01,1.331995172288936904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479584526472901018e+01,6.535025971564266456e+02,4.538076488418203436e-01,1.100000010988609489e+01,1.331849186887399186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479675435562901953e+01,6.535125971475575852e+02,4.538209673297518010e-01,1.100000010988609489e+01,1.331703201485861469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479766344652902887e+01,6.535225971386904575e+02,4.538342843578305197e-01,1.100000010988609489e+01,1.331557216084323751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479857253742903822e+01,6.535325971298252625e+02,4.538475999260564997e-01,1.100000010988609489e+01,1.331411230682786034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.479948162832904757e+01,6.535425971209620002e+02,4.538609140344297965e-01,1.100000010988609489e+01,1.331265245281248316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480039071922905691e+01,6.535525971121006705e+02,4.538742266829503547e-01,1.100000010988609489e+01,1.331119259879710599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480129981012906626e+01,6.535625971032412735e+02,4.538875378716181741e-01,1.100000010988609489e+01,1.330973274478172881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480220890102907561e+01,6.535725970943838092e+02,4.539008476004332548e-01,1.100000010988609489e+01,1.330827289076635164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480311799192908495e+01,6.535825970855282776e+02,4.539141558693956524e-01,1.100000010988609489e+01,1.330681303675097446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480402708282909430e+01,6.535925970766746786e+02,4.539274626785053113e-01,1.100000010988609489e+01,1.330535318273559729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480493617372910364e+01,6.536025970678230124e+02,4.539407680277622315e-01,1.100000010988609489e+01,1.330389332872022011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480584526462911299e+01,6.536125970589732788e+02,4.539540719171664684e-01,1.100000010988609489e+01,1.330243347470484293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480675435552912234e+01,6.536225970501255915e+02,4.539673743467179667e-01,1.100000010988609489e+01,1.330097362068946576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480766344642913168e+01,6.536325970412798370e+02,4.539806753164167263e-01,1.100000010988609489e+01,1.329951376667408858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480857253732914103e+01,6.536425970324360151e+02,4.539939748262627472e-01,1.100000010988609489e+01,1.329805391265871141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.480948162822915037e+01,6.536525970235941259e+02,4.540072728762560850e-01,1.100000010988609489e+01,1.329659405864333423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481039071912915972e+01,6.536625970147541693e+02,4.540205694663966840e-01,1.100000010988609489e+01,1.329513420462795706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481129981002916907e+01,6.536725970059161455e+02,4.540338645966845443e-01,1.100000010988609489e+01,1.329367435061257988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481220890092917841e+01,6.536825969970800543e+02,4.540471582671196660e-01,1.100000010988609489e+01,1.329221449659720271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481311799182918776e+01,6.536925969882458958e+02,4.540604504777021044e-01,1.100000010988609489e+01,1.329075464258182553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481402708272919710e+01,6.537025969794136699e+02,4.540737412284318042e-01,1.100000010988609489e+01,1.328929478856644836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481493617362920645e+01,6.537125969705833768e+02,4.540870305193087653e-01,1.100000010988609489e+01,1.328783493455107118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481584526452921580e+01,6.537225969617550163e+02,4.541003183503329876e-01,1.100000010988609489e+01,1.328637508053569401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481675435542922514e+01,6.537325969529285885e+02,4.541136047215045268e-01,1.100000010988609489e+01,1.328491522652031683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481766344632923449e+01,6.537425969441040934e+02,4.541268896328233273e-01,1.100000010988609489e+01,1.328345537250493966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481857253722924384e+01,6.537525969352815309e+02,4.541401730842893891e-01,1.100000010988609489e+01,1.328199551848956248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.481948162812925318e+01,6.537625969264610148e+02,4.541534550759027122e-01,1.100000010988609489e+01,1.328053566447418531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482039071902926253e+01,6.537725969176424314e+02,4.541667356076632966e-01,1.100000010988609489e+01,1.327907581045880813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482129980992927187e+01,6.537825969088257807e+02,4.541800146795711979e-01,1.100000010988609489e+01,1.327761595644343096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482220890082928122e+01,6.537925969000110626e+02,4.541932922916263604e-01,1.100000010988609489e+01,1.327615610242805378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482311799172929057e+01,6.538025968911982773e+02,4.542065684438287843e-01,1.100000010988609489e+01,1.327469624841267661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482402708262929991e+01,6.538125968823874246e+02,4.542198431361784694e-01,1.100000010988609489e+01,1.327323639439729943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482493617352930926e+01,6.538225968735785045e+02,4.542331163686754159e-01,1.100000010988609489e+01,1.327177654038192225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482584526442931860e+01,6.538325968647715172e+02,4.542463881413196236e-01,1.100000010988609489e+01,1.327031668636654508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482675435532932795e+01,6.538425968559664625e+02,4.542596584541111482e-01,1.100000010988609489e+01,1.326885683235116790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482766344622933730e+01,6.538525968471633405e+02,4.542729273070499341e-01,1.100000010988609489e+01,1.326739697833579073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482857253712934664e+01,6.538625968383621512e+02,4.542861947001359813e-01,1.100000010988609489e+01,1.326593712432041355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.482948162802935599e+01,6.538725968295628945e+02,4.542994606333692897e-01,1.100000010988609489e+01,1.326447727030503638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483039071892936533e+01,6.538825968207655706e+02,4.543127251067498595e-01,1.100000010988609489e+01,1.326301741628965920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483129980982937468e+01,6.538925968119701793e+02,4.543259881202776906e-01,1.100000010988609489e+01,1.326155756227428203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483220890072938403e+01,6.539025968031767206e+02,4.543392496739527830e-01,1.100000010988609489e+01,1.326009770825890485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483311799162939337e+01,6.539125967943851947e+02,4.543525097677751923e-01,1.100000010988609489e+01,1.325863785424352768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483402708252940272e+01,6.539225967855956014e+02,4.543657684017448628e-01,1.100000010988609489e+01,1.325717800022815050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483493617342941207e+01,6.539325967768079408e+02,4.543790255758617946e-01,1.100000010988609489e+01,1.325571814621277333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483584526432942141e+01,6.539425967680222129e+02,4.543922812901259878e-01,1.100000010988609489e+01,1.325425829219739615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483675435522943076e+01,6.539525967592384177e+02,4.544055355445374422e-01,1.100000010988609489e+01,1.325279843818201898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483766344612944010e+01,6.539625967504565551e+02,4.544187883390961580e-01,1.100000010988609489e+01,1.325133858416664180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483857253702944945e+01,6.539725967416766252e+02,4.544320396738021350e-01,1.100000010988609489e+01,1.324987873015126463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.483948162792945880e+01,6.539825967328986280e+02,4.544452895486553734e-01,1.100000010988609489e+01,1.324841887613588745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484039071882946814e+01,6.539925967241225635e+02,4.544585379636558731e-01,1.100000010988609489e+01,1.324695902212051028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484129980972947749e+01,6.540025967153484316e+02,4.544717849188036340e-01,1.100000010988609489e+01,1.324549916810513310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484220890062948683e+01,6.540125967065762325e+02,4.544850304140986563e-01,1.100000010988609489e+01,1.324403931408975593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484311799152949618e+01,6.540225966978059660e+02,4.544982744495409954e-01,1.100000010988609489e+01,1.324257946007437875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484402708242950553e+01,6.540325966890376321e+02,4.545115170251305958e-01,1.100000010988609489e+01,1.324111960605900157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484493617332951487e+01,6.540425966802712310e+02,4.545247581408674575e-01,1.100000010988609489e+01,1.323965975204362440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484584526422952422e+01,6.540525966715067625e+02,4.545379977967515805e-01,1.100000010988609489e+01,1.323819989802824722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484675435512953356e+01,6.540625966627442267e+02,4.545512359927829649e-01,1.100000010988609489e+01,1.323674004401287005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484766344602954291e+01,6.540725966539836236e+02,4.545644727289616105e-01,1.100000010988609489e+01,1.323528018999749287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484857253692955226e+01,6.540825966452249531e+02,4.545777080052875174e-01,1.100000010988609489e+01,1.323382033598211570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.484948162782956160e+01,6.540925966364682154e+02,4.545909418217606857e-01,1.100000010988609489e+01,1.323236048196673852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485039071872957095e+01,6.541025966277134103e+02,4.546041741783811152e-01,1.100000010988609489e+01,1.323090062795136135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485129980962958030e+01,6.541125966189605379e+02,4.546174050751488060e-01,1.100000010988609489e+01,1.322944077393598417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485220890052958964e+01,6.541225966102095981e+02,4.546306345120637582e-01,1.100000010988609489e+01,1.322798091992060700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485311799142959899e+01,6.541325966014605910e+02,4.546438624891259717e-01,1.100000010988609489e+01,1.322652106590522982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485402708232960833e+01,6.541425965927135167e+02,4.546570890063354464e-01,1.100000010988609489e+01,1.322506121188985265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485493617322961768e+01,6.541525965839683749e+02,4.546703140636921825e-01,1.100000010988609489e+01,1.322360135787447547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485584526412962703e+01,6.541625965752251659e+02,4.546835376611961799e-01,1.100000010988609489e+01,1.322214150385909830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485675435502963637e+01,6.541725965664838895e+02,4.546967597988474385e-01,1.100000010988609489e+01,1.322068164984372112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485766344592964572e+01,6.541825965577445459e+02,4.547099804766459585e-01,1.100000010988609489e+01,1.321922179582834395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485857253682965506e+01,6.541925965490071349e+02,4.547231996945917398e-01,1.100000010988609489e+01,1.321776194181296677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.485948162772966441e+01,6.542025965402716565e+02,4.547364174526847824e-01,1.100000010988609489e+01,1.321630208779758960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486039071862967376e+01,6.542125965315381109e+02,4.547496337509250863e-01,1.100000010988609489e+01,1.321484223378221242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486129980952968310e+01,6.542225965228064979e+02,4.547628485893126515e-01,1.100000010988609489e+01,1.321338237976683525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486220890042969245e+01,6.542325965140768176e+02,4.547760619678474781e-01,1.100000010988609489e+01,1.321192252575145807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486311799132970179e+01,6.542425965053490700e+02,4.547892738865295659e-01,1.100000010988609489e+01,1.321046267173608089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486402708222971114e+01,6.542525964966232550e+02,4.548024843453589150e-01,1.100000010988609489e+01,1.320900281772070372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486493617312972049e+01,6.542625964878993727e+02,4.548156933443355254e-01,1.100000010988609489e+01,1.320754296370532654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486584526402972983e+01,6.542725964791774231e+02,4.548289008834593972e-01,1.100000010988609489e+01,1.320608310968994937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486675435492973918e+01,6.542825964704574062e+02,4.548421069627305302e-01,1.100000010988609489e+01,1.320462325567457219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486766344582974853e+01,6.542925964617393220e+02,4.548553115821488690e-01,1.100000010988609489e+01,1.320316340165919502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486857253672975787e+01,6.543025964530231704e+02,4.548685147417144692e-01,1.100000010988609489e+01,1.320170354764381784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.486948162762976722e+01,6.543125964443089515e+02,4.548817164414273306e-01,1.100000010988609489e+01,1.320024369362844067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487039071852977656e+01,6.543225964355966653e+02,4.548949166812874534e-01,1.100000010988609489e+01,1.319878383961306349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487129980942978591e+01,6.543325964268863117e+02,4.549081154612948374e-01,1.100000010988609489e+01,1.319732398559768632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487220890032979526e+01,6.543425964181778909e+02,4.549213127814494828e-01,1.100000010988609489e+01,1.319586413158230914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487311799122980460e+01,6.543525964094714027e+02,4.549345086417513895e-01,1.100000010988609489e+01,1.319440427756693197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487402708212981395e+01,6.543625964007667335e+02,4.549477030422005575e-01,1.100000010988609489e+01,1.319294442355155479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487493617302982329e+01,6.543725963920639970e+02,4.549608959827969867e-01,1.100000010988609489e+01,1.319148456953617762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487584526392983264e+01,6.543825963833631931e+02,4.549740874635406773e-01,1.100000010988609489e+01,1.319002471552080044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487675435482984199e+01,6.543925963746643220e+02,4.549872774844316292e-01,1.100000010988609489e+01,1.318856486150542327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487766344572985133e+01,6.544025963659673835e+02,4.550004660454697869e-01,1.100000010988609489e+01,1.318710500749004609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487857253662986068e+01,6.544125963572723776e+02,4.550136531466552059e-01,1.100000010988609489e+01,1.318564515347466892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.487948162752987002e+01,6.544225963485793045e+02,4.550268387879878862e-01,1.100000010988609489e+01,1.318418529945929174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488039071842987937e+01,6.544325963398881640e+02,4.550400229694678278e-01,1.100000010988609489e+01,1.318272544544391457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488129980932988872e+01,6.544425963311989562e+02,4.550532056910950307e-01,1.100000010988609489e+01,1.318126559142853739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488220890022989806e+01,6.544525963225116811e+02,4.550663869528694949e-01,1.100000010988609489e+01,1.317980573741316021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488311799112990741e+01,6.544625963138263387e+02,4.550795667547912204e-01,1.100000010988609489e+01,1.317834588339778304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488402708202991676e+01,6.544725963051429289e+02,4.550927450968601518e-01,1.100000010988609489e+01,1.317688602938240586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488493617292992610e+01,6.544825962964614519e+02,4.551059219790763444e-01,1.100000010988609489e+01,1.317542617536702869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488584526382993545e+01,6.544925962877819074e+02,4.551190974014397983e-01,1.100000010988609489e+01,1.317396632135165151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488675435472994479e+01,6.545025962791042957e+02,4.551322713639505135e-01,1.100000010988609489e+01,1.317250646733627434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488766344562995414e+01,6.545125962704285030e+02,4.551454438666084901e-01,1.100000010988609489e+01,1.317104661332089716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488857253652996349e+01,6.545225962617546429e+02,4.551586149094137279e-01,1.100000010988609489e+01,1.316958675930551999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.488948162742997283e+01,6.545325962530827155e+02,4.551717844923661715e-01,1.100000010988609489e+01,1.316812690529014281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489039071832998218e+01,6.545425962444127208e+02,4.551849526154658765e-01,1.100000010988609489e+01,1.316666705127476564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489129980922999152e+01,6.545525962357446588e+02,4.551981192787128427e-01,1.100000010988609489e+01,1.316520719725938846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489220890013000087e+01,6.545625962270785294e+02,4.552112844821070703e-01,1.100000010988609489e+01,1.316374734324401129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489311799103001022e+01,6.545725962184143327e+02,4.552244482256485036e-01,1.100000010988609489e+01,1.316228748922863411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489402708193001956e+01,6.545825962097520687e+02,4.552376105093371983e-01,1.100000010988609489e+01,1.316082763521325694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489493617283002891e+01,6.545925962010917374e+02,4.552507713331731543e-01,1.100000010988609489e+01,1.315936778119787976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489584526373003825e+01,6.546025961924333387e+02,4.552639306971563715e-01,1.100000010988609489e+01,1.315790792718250259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489675435463004760e+01,6.546125961837767591e+02,4.552770886012868501e-01,1.100000010988609489e+01,1.315644807316712541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489766344553005695e+01,6.546225961751221121e+02,4.552902450455645345e-01,1.100000010988609489e+01,1.315498821915174824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489857253643006629e+01,6.546325961664693978e+02,4.553034000299894801e-01,1.100000010988609489e+01,1.315352836513637106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.489948162733007564e+01,6.546425961578186161e+02,4.553165535545616871e-01,1.100000010988609489e+01,1.315206851112099389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490039071823008499e+01,6.546525961491697672e+02,4.553297056192811554e-01,1.100000010988609489e+01,1.315060865710561671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490129980913009433e+01,6.546625961405228509e+02,4.553428562241478295e-01,1.100000010988609489e+01,1.314914880309023953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490220890003010368e+01,6.546725961318778673e+02,4.553560053691617648e-01,1.100000010988609489e+01,1.314768894907486236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490311799093011302e+01,6.546825961232348163e+02,4.553691530543229615e-01,1.100000010988609489e+01,1.314622909505948518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490402708183012237e+01,6.546925961145936981e+02,4.553822992796314195e-01,1.100000010988609489e+01,1.314476924104410801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490493617273013172e+01,6.547025961059543988e+02,4.553954440450870833e-01,1.100000010988609489e+01,1.314330938702873083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490584526363014106e+01,6.547125960973170322e+02,4.554085873506900084e-01,1.100000010988609489e+01,1.314184953301335366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490675435453015041e+01,6.547225960886815983e+02,4.554217291964401948e-01,1.100000010988609489e+01,1.314038967899797648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490766344543015975e+01,6.547325960800480971e+02,4.554348695823375870e-01,1.100000010988609489e+01,1.313892982498259931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490857253633016910e+01,6.547425960714165285e+02,4.554480085083822405e-01,1.100000010988609489e+01,1.313746997096722213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.490948162723017845e+01,6.547525960627868926e+02,4.554611459745741553e-01,1.100000010988609489e+01,1.313601011695184496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491039071813018779e+01,6.547625960541591894e+02,4.554742819809133314e-01,1.100000010988609489e+01,1.313455026293646778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491129980903019714e+01,6.547725960455334189e+02,4.554874165273997133e-01,1.100000010988609489e+01,1.313309040892109061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491220889993020648e+01,6.547825960369094673e+02,4.555005496140333565e-01,1.100000010988609489e+01,1.313163055490571343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491311799083021583e+01,6.547925960282874485e+02,4.555136812408142610e-01,1.100000010988609489e+01,1.313017070089033626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491402708173022518e+01,6.548025960196673623e+02,4.555268114077423713e-01,1.100000010988609489e+01,1.312871084687495908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491493617263023452e+01,6.548125960110492088e+02,4.555399401148177430e-01,1.100000010988609489e+01,1.312725099285958191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491584526353024387e+01,6.548225960024329879e+02,4.555530673620403759e-01,1.100000010988609489e+01,1.312579113884420473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491675435443025322e+01,6.548325959938186998e+02,4.555661931494102146e-01,1.100000010988609489e+01,1.312433128482882756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491766344533026256e+01,6.548425959852063443e+02,4.555793174769273146e-01,1.100000010988609489e+01,1.312287143081345038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491857253623027191e+01,6.548525959765958078e+02,4.555924403445916759e-01,1.100000010988609489e+01,1.312141157679807320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.491948162713028125e+01,6.548625959679872039e+02,4.556055617524032431e-01,1.100000010988609489e+01,1.311995172278269603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492039071803029060e+01,6.548725959593805328e+02,4.556186817003620715e-01,1.100000010988609489e+01,1.311849186876731885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492129980893029995e+01,6.548825959507757943e+02,4.556318001884681057e-01,1.100000010988609489e+01,1.311703201475194168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492220889983030929e+01,6.548925959421729885e+02,4.556449172167214012e-01,1.100000010988609489e+01,1.311557216073656450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492311799073031864e+01,6.549025959335721154e+02,4.556580327851219581e-01,1.100000010988609489e+01,1.311411230672118733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492402708163032798e+01,6.549125959249731750e+02,4.556711468936697207e-01,1.100000010988609489e+01,1.311265245270581015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492493617253033733e+01,6.549225959163760535e+02,4.556842595423647446e-01,1.100000010988609489e+01,1.311119259869043298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492584526343034668e+01,6.549325959077808648e+02,4.556973707312070299e-01,1.100000010988609489e+01,1.310973274467505580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492675435433035602e+01,6.549425958991876087e+02,4.557104804601965209e-01,1.100000010988609489e+01,1.310827289065967863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492766344523036537e+01,6.549525958905962852e+02,4.557235887293332732e-01,1.100000010988609489e+01,1.310681303664430145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492857253613037471e+01,6.549625958820068945e+02,4.557366955386172314e-01,1.100000010988609489e+01,1.310535318262892428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.492948162703038406e+01,6.549725958734194364e+02,4.557498008880484508e-01,1.100000010988609489e+01,1.310389332861354710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493039071793039341e+01,6.549825958648337974e+02,4.557629047776269315e-01,1.100000010988609489e+01,1.310243347459816993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493129980883040275e+01,6.549925958562500909e+02,4.557760072073526181e-01,1.100000010988609489e+01,1.310097362058279275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493220889973041210e+01,6.550025958476683172e+02,4.557891081772255659e-01,1.100000010988609489e+01,1.309951376656741558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493311799063042145e+01,6.550125958390884762e+02,4.558022076872457196e-01,1.100000010988609489e+01,1.309805391255203840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493402708153043079e+01,6.550225958305105678e+02,4.558153057374131345e-01,1.100000010988609489e+01,1.309659405853666123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493493617243044014e+01,6.550325958219344784e+02,4.558284023277277552e-01,1.100000010988609489e+01,1.309513420452128405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493584526333044948e+01,6.550425958133603217e+02,4.558414974581896373e-01,1.100000010988609489e+01,1.309367435050590688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493675435423045883e+01,6.550525958047880977e+02,4.558545911287987251e-01,1.100000010988609489e+01,1.309221449649052970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493766344513046818e+01,6.550625957962178063e+02,4.558676833395550743e-01,1.100000010988609489e+01,1.309075464247515252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493857253603047752e+01,6.550725957876494476e+02,4.558807740904586847e-01,1.100000010988609489e+01,1.308929478845977535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.493948162693048687e+01,6.550825957790830216e+02,4.558938633815095010e-01,1.100000010988609489e+01,1.308783493444439817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494039071783049621e+01,6.550925957705184146e+02,4.559069512127075785e-01,1.100000010988609489e+01,1.308637508042902100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494129980873050556e+01,6.551025957619557403e+02,4.559200375840528618e-01,1.100000010988609489e+01,1.308491522641364382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494220889963051491e+01,6.551125957533949986e+02,4.559331224955454065e-01,1.100000010988609489e+01,1.308345537239826665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494311799053052425e+01,6.551225957448361896e+02,4.559462059471851569e-01,1.100000010988609489e+01,1.308199551838288947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494402708143053360e+01,6.551325957362793133e+02,4.559592879389721687e-01,1.100000010988609489e+01,1.308053566436751230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494493617233054295e+01,6.551425957277242560e+02,4.559723684709063862e-01,1.100000010988609489e+01,1.307907581035213512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494584526323055229e+01,6.551525957191711313e+02,4.559854475429878651e-01,1.100000010988609489e+01,1.307761595633675795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494675435413056164e+01,6.551625957106199394e+02,4.559985251552165497e-01,1.100000010988609489e+01,1.307615610232138077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494766344503057098e+01,6.551725957020706801e+02,4.560116013075924957e-01,1.100000010988609489e+01,1.307469624830600360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494857253593058033e+01,6.551825956935233535e+02,4.560246760001156474e-01,1.100000010988609489e+01,1.307323639429062642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.494948162683058968e+01,6.551925956849778458e+02,4.560377492327860605e-01,1.100000010988609489e+01,1.307177654027524925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495039071773059902e+01,6.552025956764342709e+02,4.560508210056036793e-01,1.100000010988609489e+01,1.307031668625987207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495129980863060837e+01,6.552125956678926286e+02,4.560638913185685595e-01,1.100000010988609489e+01,1.306885683224449490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495220889953061771e+01,6.552225956593529190e+02,4.560769601716806454e-01,1.100000010988609489e+01,1.306739697822911772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495311799043062706e+01,6.552325956508150284e+02,4.560900275649399371e-01,1.100000010988609489e+01,1.306593712421374055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495402708133063641e+01,6.552425956422790705e+02,4.561030934983464902e-01,1.100000010988609489e+01,1.306447727019836337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495493617223064575e+01,6.552525956337450452e+02,4.561161579719002490e-01,1.100000010988609489e+01,1.306301741618298620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495584526313065510e+01,6.552625956252129527e+02,4.561292209856012692e-01,1.100000010988609489e+01,1.306155756216760902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495675435403066444e+01,6.552725956166827928e+02,4.561422825394494951e-01,1.100000010988609489e+01,1.306009770815223184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495766344493067379e+01,6.552825956081544518e+02,4.561553426334449823e-01,1.100000010988609489e+01,1.305863785413685467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495857253583068314e+01,6.552925955996280436e+02,4.561684012675876754e-01,1.100000010988609489e+01,1.305717800012147749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.495948162673069248e+01,6.553025955911035680e+02,4.561814584418776297e-01,1.100000010988609489e+01,1.305571814610610032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496039071763070183e+01,6.553125955825810252e+02,4.561945141563147899e-01,1.100000010988609489e+01,1.305425829209072314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496129980853071118e+01,6.553225955740603013e+02,4.562075684108991558e-01,1.100000010988609489e+01,1.305279843807534597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496220889943072052e+01,6.553325955655415100e+02,4.562206212056307830e-01,1.100000010988609489e+01,1.305133858405996879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496311799033072987e+01,6.553425955570246515e+02,4.562336725405096161e-01,1.100000010988609489e+01,1.304987873004459162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496402708123073921e+01,6.553525955485097256e+02,4.562467224155357104e-01,1.100000010988609489e+01,1.304841887602921444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496493617213074856e+01,6.553625955399966188e+02,4.562597708307090105e-01,1.100000010988609489e+01,1.304695902201383727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496584526303075791e+01,6.553725955314854446e+02,4.562728177860295165e-01,1.100000010988609489e+01,1.304549916799846009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496675435393076725e+01,6.553825955229762030e+02,4.562858632814972837e-01,1.100000010988609489e+01,1.304403931398308292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496766344483077660e+01,6.553925955144688942e+02,4.562989073171122567e-01,1.100000010988609489e+01,1.304257945996770574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496857253573078594e+01,6.554025955059634043e+02,4.563119498928744355e-01,1.100000010988609489e+01,1.304111960595232857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.496948162663079529e+01,6.554125954974598471e+02,4.563249910087838757e-01,1.100000010988609489e+01,1.303965975193695139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497039071753080464e+01,6.554225954889582226e+02,4.563380306648405216e-01,1.100000010988609489e+01,1.303819989792157422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497129980843081398e+01,6.554325954804585308e+02,4.563510688610444288e-01,1.100000010988609489e+01,1.303674004390619704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497220889933082333e+01,6.554425954719606580e+02,4.563641055973955418e-01,1.100000010988609489e+01,1.303528018989081987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497311799023083267e+01,6.554525954634647178e+02,4.563771408738938606e-01,1.100000010988609489e+01,1.303382033587544269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497402708113084202e+01,6.554625954549707103e+02,4.563901746905394408e-01,1.100000010988609489e+01,1.303236048186006552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497493617203085137e+01,6.554725954464786355e+02,4.564032070473322267e-01,1.100000010988609489e+01,1.303090062784468834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497584526293086071e+01,6.554825954379883797e+02,4.564162379442722184e-01,1.100000010988609489e+01,1.302944077382931116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497675435383087006e+01,6.554925954295000565e+02,4.564292673813594714e-01,1.100000010988609489e+01,1.302798091981393399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497766344473087941e+01,6.555025954210136661e+02,4.564422953585939302e-01,1.100000010988609489e+01,1.302652106579855681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497857253563088875e+01,6.555125954125292083e+02,4.564553218759755948e-01,1.100000010988609489e+01,1.302506121178317964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.497948162653089810e+01,6.555225954040465695e+02,4.564683469335045207e-01,1.100000010988609489e+01,1.302360135776780246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498039071743090744e+01,6.555325953955658633e+02,4.564813705311806524e-01,1.100000010988609489e+01,1.302214150375242529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498129980833091679e+01,6.555425953870870899e+02,4.564943926690039899e-01,1.100000010988609489e+01,1.302068164973704811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498220889923092614e+01,6.555525953786101354e+02,4.565074133469745332e-01,1.100000010988609489e+01,1.301922179572167094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498311799013093548e+01,6.555625953701351136e+02,4.565204325650923378e-01,1.100000010988609489e+01,1.301776194170629376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498402708103094483e+01,6.555725953616620245e+02,4.565334503233573482e-01,1.100000010988609489e+01,1.301630208769091659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498493617193095417e+01,6.555825953531908681e+02,4.565464666217695644e-01,1.100000010988609489e+01,1.301484223367553941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498584526283096352e+01,6.555925953447215306e+02,4.565594814603290419e-01,1.100000010988609489e+01,1.301338237966016224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498675435373097287e+01,6.556025953362541259e+02,4.565724948390357252e-01,1.100000010988609489e+01,1.301192252564478506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498766344463098221e+01,6.556125953277886538e+02,4.565855067578896143e-01,1.100000010988609489e+01,1.301046267162940789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498857253553099156e+01,6.556225953193250007e+02,4.565985172168907091e-01,1.100000010988609489e+01,1.300900281761403071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.498948162643100090e+01,6.556325953108632802e+02,4.566115262160390653e-01,1.100000010988609489e+01,1.300754296359865354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499039071733101025e+01,6.556425953024034925e+02,4.566245337553346273e-01,1.100000010988609489e+01,1.300608310958327636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499129980823101960e+01,6.556525952939456374e+02,4.566375398347773951e-01,1.100000010988609489e+01,1.300462325556789919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499220889913102894e+01,6.556625952854896013e+02,4.566505444543673686e-01,1.100000010988609489e+01,1.300316340155252201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499311799003103829e+01,6.556725952770354979e+02,4.566635476141046035e-01,1.100000010988609489e+01,1.300170354753714484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499402708093104764e+01,6.556825952685833272e+02,4.566765493139890442e-01,1.100000010988609489e+01,1.300024369352176766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499493617183105698e+01,6.556925952601329755e+02,4.566895495540206906e-01,1.100000010988609489e+01,1.299878383950639048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499584526273106633e+01,6.557025952516845564e+02,4.567025483341995429e-01,1.100000010988609489e+01,1.299732398549101331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499675435363107567e+01,6.557125952432380700e+02,4.567155456545256009e-01,1.100000010988609489e+01,1.299586413147563613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499766344453108502e+01,6.557225952347934026e+02,4.567285415149989203e-01,1.100000010988609489e+01,1.299440427746025896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499857253543109437e+01,6.557325952263506679e+02,4.567415359156194454e-01,1.100000010988609489e+01,1.299294442344488178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.499948162633110371e+01,6.557425952179098658e+02,4.567545288563871764e-01,1.100000010988609489e+01,1.299148456942950461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500039071723111306e+01,6.557525952094708828e+02,4.567675203373021131e-01,1.100000010988609489e+01,1.299002471541412743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500129980813112240e+01,6.557625952010338324e+02,4.567805103583643112e-01,1.100000010988609489e+01,1.298856486139875026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500220889903113175e+01,6.557725951925987147e+02,4.567934989195737150e-01,1.100000010988609489e+01,1.298710500738337308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500311798993114110e+01,6.557825951841654160e+02,4.568064860209303246e-01,1.100000010988609489e+01,1.298564515336799591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500402708083115044e+01,6.557925951757340499e+02,4.568194716624341400e-01,1.100000010988609489e+01,1.298418529935261873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500493617173115979e+01,6.558025951673046166e+02,4.568324558440851613e-01,1.100000010988609489e+01,1.298272544533724156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500584526263116913e+01,6.558125951588771159e+02,4.568454385658833883e-01,1.100000010988609489e+01,1.298126559132186438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500675435353117848e+01,6.558225951504514342e+02,4.568584198278288766e-01,1.100000010988609489e+01,1.297980573730648721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500766344443118783e+01,6.558325951420276851e+02,4.568713996299215707e-01,1.100000010988609489e+01,1.297834588329111003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500857253533119717e+01,6.558425951336058688e+02,4.568843779721614706e-01,1.100000010988609489e+01,1.297688602927573286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.500948162623120652e+01,6.558525951251858714e+02,4.568973548545485763e-01,1.100000010988609489e+01,1.297542617526035568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501039071713121587e+01,6.558625951167678068e+02,4.569103302770828878e-01,1.100000010988609489e+01,1.297396632124497851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501129980803122521e+01,6.558725951083515611e+02,4.569233042397644051e-01,1.100000010988609489e+01,1.297250646722960133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501220889893123456e+01,6.558825950999372481e+02,4.569362767425931282e-01,1.100000010988609489e+01,1.297104661321422416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501311798983124390e+01,6.558925950915248677e+02,4.569492477855691126e-01,1.100000010988609489e+01,1.296958675919884698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501402708073125325e+01,6.559025950831143064e+02,4.569622173686923028e-01,1.100000010988609489e+01,1.296812690518346980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501493617163126260e+01,6.559125950747056777e+02,4.569751854919626988e-01,1.100000010988609489e+01,1.296666705116809263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501584526253127194e+01,6.559225950662989817e+02,4.569881521553803005e-01,1.100000010988609489e+01,1.296520719715271545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501675435343128129e+01,6.559325950578941047e+02,4.570011173589451081e-01,1.100000010988609489e+01,1.296374734313733828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501766344433129063e+01,6.559425950494911604e+02,4.570140811026571215e-01,1.100000010988609489e+01,1.296228748912196110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501857253523129998e+01,6.559525950410901487e+02,4.570270433865163406e-01,1.100000010988609489e+01,1.296082763510658393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.501948162613130933e+01,6.559625950326909560e+02,4.570400042105227656e-01,1.100000010988609489e+01,1.295936778109120675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502039071703131867e+01,6.559725950242936960e+02,4.570529635746763963e-01,1.100000010988609489e+01,1.295790792707582958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502129980793132802e+01,6.559825950158983687e+02,4.570659214789772329e-01,1.100000010988609489e+01,1.295644807306045240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502220889883133736e+01,6.559925950075048604e+02,4.570788779234253307e-01,1.100000010988609489e+01,1.295498821904507523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502311798973134671e+01,6.560025949991132848e+02,4.570918329080206344e-01,1.100000010988609489e+01,1.295352836502969805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502402708063135606e+01,6.560125949907236418e+02,4.571047864327631438e-01,1.100000010988609489e+01,1.295206851101432088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502493617153136540e+01,6.560225949823358178e+02,4.571177384976528590e-01,1.100000010988609489e+01,1.295060865699894370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502584526243137475e+01,6.560325949739499265e+02,4.571306891026897801e-01,1.100000010988609489e+01,1.294914880298356653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502675435333138410e+01,6.560425949655658542e+02,4.571436382478739069e-01,1.100000010988609489e+01,1.294768894896818935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502766344423139344e+01,6.560525949571837145e+02,4.571565859332052395e-01,1.100000010988609489e+01,1.294622909495281218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502857253513140279e+01,6.560625949488035076e+02,4.571695321586837779e-01,1.100000010988609489e+01,1.294476924093743500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.502948162603141213e+01,6.560725949404251196e+02,4.571824769243095221e-01,1.100000010988609489e+01,1.294330938692205783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503039071693142148e+01,6.560825949320486643e+02,4.571954202300824721e-01,1.100000010988609489e+01,1.294184953290668065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503129980783143083e+01,6.560925949236741417e+02,4.572083620760026279e-01,1.100000010988609489e+01,1.294038967889130348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503220889873144017e+01,6.561025949153014380e+02,4.572213024620699895e-01,1.100000010988609489e+01,1.293892982487592630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503311798963144952e+01,6.561125949069306671e+02,4.572342413882845569e-01,1.100000010988609489e+01,1.293746997086054912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503402708053145886e+01,6.561225948985617151e+02,4.572471788546463300e-01,1.100000010988609489e+01,1.293601011684517195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503493617143146821e+01,6.561325948901946958e+02,4.572601148611553090e-01,1.100000010988609489e+01,1.293455026282979477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503584526233147756e+01,6.561425948818296092e+02,4.572730494078114938e-01,1.100000010988609489e+01,1.293309040881441760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503675435323148690e+01,6.561525948734663416e+02,4.572859824946148843e-01,1.100000010988609489e+01,1.293163055479904042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503766344413149625e+01,6.561625948651050066e+02,4.572989141215654807e-01,1.100000010988609489e+01,1.293017070078366325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503857253503150559e+01,6.561725948567454907e+02,4.573118442886632828e-01,1.100000010988609489e+01,1.292871084676828607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.503948162593151494e+01,6.561825948483879074e+02,4.573247729959082908e-01,1.100000010988609489e+01,1.292725099275290890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504039071683152429e+01,6.561925948400322568e+02,4.573377002433005045e-01,1.100000010988609489e+01,1.292579113873753172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504129980773153363e+01,6.562025948316784252e+02,4.573506260308399241e-01,1.100000010988609489e+01,1.292433128472215455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504220889863154298e+01,6.562125948233265262e+02,4.573635503585265494e-01,1.100000010988609489e+01,1.292287143070677737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504311798953155233e+01,6.562225948149764463e+02,4.573764732263603805e-01,1.100000010988609489e+01,1.292141157669140020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504402708043156167e+01,6.562325948066282990e+02,4.573893946343414174e-01,1.100000010988609489e+01,1.291995172267602302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504493617133157102e+01,6.562425947982820844e+02,4.574023145824696601e-01,1.100000010988609489e+01,1.291849186866064585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504584526223158036e+01,6.562525947899376888e+02,4.574152330707451086e-01,1.100000010988609489e+01,1.291703201464526867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504675435313158971e+01,6.562625947815952259e+02,4.574281500991677629e-01,1.100000010988609489e+01,1.291557216062989150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504766344403159906e+01,6.562725947732545819e+02,4.574410656677376230e-01,1.100000010988609489e+01,1.291411230661451432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504857253493160840e+01,6.562825947649158707e+02,4.574539797764546889e-01,1.100000010988609489e+01,1.291265245259913715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.504948162583161775e+01,6.562925947565790921e+02,4.574668924253189606e-01,1.100000010988609489e+01,1.291119259858375997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505039071673162709e+01,6.563025947482441325e+02,4.574798036143303825e-01,1.100000010988609489e+01,1.290973274456838280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505129980763163644e+01,6.563125947399111055e+02,4.574927133434890103e-01,1.100000010988609489e+01,1.290827289055300562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505220889853164579e+01,6.563225947315798976e+02,4.575056216127948439e-01,1.100000010988609489e+01,1.290681303653762844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505311798943165513e+01,6.563325947232506223e+02,4.575185284222478832e-01,1.100000010988609489e+01,1.290535318252225127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505402708033166448e+01,6.563425947149231661e+02,4.575314337718481283e-01,1.100000010988609489e+01,1.290389332850687409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505493617123167382e+01,6.563525947065976425e+02,4.575443376615955793e-01,1.100000010988609489e+01,1.290243347449149692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505584526213168317e+01,6.563625946982740516e+02,4.575572400914902360e-01,1.100000010988609489e+01,1.290097362047611974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505675435303169252e+01,6.563725946899522796e+02,4.575701410615320985e-01,1.100000010988609489e+01,1.289951376646074257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505766344393170186e+01,6.563825946816324404e+02,4.575830405717211669e-01,1.100000010988609489e+01,1.289805391244536539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505857253483171121e+01,6.563925946733144201e+02,4.575959386220574410e-01,1.100000010988609489e+01,1.289659405842998822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.505948162573172056e+01,6.564025946649983325e+02,4.576088352125408654e-01,1.100000010988609489e+01,1.289513420441461104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506039071663172990e+01,6.564125946566840639e+02,4.576217303431714956e-01,1.100000010988609489e+01,1.289367435039923387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506129980753173925e+01,6.564225946483717280e+02,4.576346240139493315e-01,1.100000010988609489e+01,1.289221449638385669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506220889843174859e+01,6.564325946400613248e+02,4.576475162248743733e-01,1.100000010988609489e+01,1.289075464236847952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506311798933175794e+01,6.564425946317527405e+02,4.576604069759466209e-01,1.100000010988609489e+01,1.288929478835310234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506402708023176729e+01,6.564525946234460889e+02,4.576732962671660743e-01,1.100000010988609489e+01,1.288783493433772517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506493617113177663e+01,6.564625946151412563e+02,4.576861840985327334e-01,1.100000010988609489e+01,1.288637508032234799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506584526203178598e+01,6.564725946068383564e+02,4.576990704700465429e-01,1.100000010988609489e+01,1.288491522630697082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506675435293179532e+01,6.564825945985372755e+02,4.577119553817075581e-01,1.100000010988609489e+01,1.288345537229159364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506766344383180467e+01,6.564925945902381272e+02,4.577248388335157792e-01,1.100000010988609489e+01,1.288199551827621647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506857253473181402e+01,6.565025945819407980e+02,4.577377208254712060e-01,1.100000010988609489e+01,1.288053566426083929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.506948162563182336e+01,6.565125945736454014e+02,4.577506013575738386e-01,1.100000010988609489e+01,1.287907581024546212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507039071653183271e+01,6.565225945653518238e+02,4.577634804298236770e-01,1.100000010988609489e+01,1.287761595623008494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507129980743184205e+01,6.565325945570601789e+02,4.577763580422206657e-01,1.100000010988609489e+01,1.287615610221470776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507220889833185140e+01,6.565425945487704666e+02,4.577892341947648602e-01,1.100000010988609489e+01,1.287469624819933059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507311798923186075e+01,6.565525945404825734e+02,4.578021088874562605e-01,1.100000010988609489e+01,1.287323639418395341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507402708013187009e+01,6.565625945321966128e+02,4.578149821202948666e-01,1.100000010988609489e+01,1.287177654016857624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507493617103187944e+01,6.565725945239124712e+02,4.578278538932806785e-01,1.100000010988609489e+01,1.287031668615319906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507584526193188879e+01,6.565825945156302623e+02,4.578407242064136407e-01,1.100000010988609489e+01,1.286885683213782189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507675435283189813e+01,6.565925945073498724e+02,4.578535930596938086e-01,1.100000010988609489e+01,1.286739697812244471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507766344373190748e+01,6.566025944990714152e+02,4.578664604531211824e-01,1.100000010988609489e+01,1.286593712410706754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507857253463191682e+01,6.566125944907947769e+02,4.578793263866957619e-01,1.100000010988609489e+01,1.286447727009169036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.507948162553192617e+01,6.566225944825200713e+02,4.578921908604174917e-01,1.100000010988609489e+01,1.286301741607631319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508039071643193552e+01,6.566325944742471847e+02,4.579050538742864274e-01,1.100000010988609489e+01,1.286155756206093601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508129980733194486e+01,6.566425944659762308e+02,4.579179154283025688e-01,1.100000010988609489e+01,1.286009770804555884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508220889823195421e+01,6.566525944577070959e+02,4.579307755224659160e-01,1.100000010988609489e+01,1.285863785403018166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508311798913196355e+01,6.566625944494398937e+02,4.579436341567764135e-01,1.100000010988609489e+01,1.285717800001480449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508402708003197290e+01,6.566725944411745104e+02,4.579564913312341168e-01,1.100000010988609489e+01,1.285571814599942731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508493617093198225e+01,6.566825944329110598e+02,4.579693470458390259e-01,1.100000010988609489e+01,1.285425829198405014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508584526183199159e+01,6.566925944246494282e+02,4.579822013005911407e-01,1.100000010988609489e+01,1.285279843796867296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508675435273200094e+01,6.567025944163897293e+02,4.579950540954904059e-01,1.100000010988609489e+01,1.285133858395329579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508766344363201029e+01,6.567125944081318494e+02,4.580079054305368769e-01,1.100000010988609489e+01,1.284987872993791861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508857253453201963e+01,6.567225943998759021e+02,4.580207553057305536e-01,1.100000010988609489e+01,1.284841887592254144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.508948162543202898e+01,6.567325943916217739e+02,4.580336037210713807e-01,1.100000010988609489e+01,1.284695902190716426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509039071633203832e+01,6.567425943833695783e+02,4.580464506765594135e-01,1.100000010988609489e+01,1.284549916789178708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509129980723204767e+01,6.567525943751192017e+02,4.580592961721946521e-01,1.100000010988609489e+01,1.284403931387640991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509220889813205702e+01,6.567625943668707578e+02,4.580721402079770965e-01,1.100000010988609489e+01,1.284257945986103273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509311798903206636e+01,6.567725943586241328e+02,4.580849827839066912e-01,1.100000010988609489e+01,1.284111960584565556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509402707993207571e+01,6.567825943503794406e+02,4.580978238999834917e-01,1.100000010988609489e+01,1.283965975183027838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509493617083208505e+01,6.567925943421365673e+02,4.581106635562074980e-01,1.100000010988609489e+01,1.283819989781490121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509584526173209440e+01,6.568025943338956267e+02,4.581235017525786546e-01,1.100000010988609489e+01,1.283674004379952403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509675435263210375e+01,6.568125943256565051e+02,4.581363384890970170e-01,1.100000010988609489e+01,1.283528018978414686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509766344353211309e+01,6.568225943174193162e+02,4.581491737657625851e-01,1.100000010988609489e+01,1.283382033576876968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509857253443212244e+01,6.568325943091839463e+02,4.581620075825753036e-01,1.100000010988609489e+01,1.283236048175339251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.509948162533213178e+01,6.568425943009505090e+02,4.581748399395352278e-01,1.100000010988609489e+01,1.283090062773801533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510039071623214113e+01,6.568525942927188908e+02,4.581876708366423578e-01,1.100000010988609489e+01,1.282944077372263816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510129980713215048e+01,6.568625942844892052e+02,4.582005002738966382e-01,1.100000010988609489e+01,1.282798091970726098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510220889803215982e+01,6.568725942762613386e+02,4.582133282512981243e-01,1.100000010988609489e+01,1.282652106569188381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510311798893216917e+01,6.568825942680354046e+02,4.582261547688468162e-01,1.100000010988609489e+01,1.282506121167650663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510402707983217852e+01,6.568925942598112897e+02,4.582389798265426584e-01,1.100000010988609489e+01,1.282360135766112946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510493617073218786e+01,6.569025942515891074e+02,4.582518034243857064e-01,1.100000010988609489e+01,1.282214150364575228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510584526163219721e+01,6.569125942433687442e+02,4.582646255623759046e-01,1.100000010988609489e+01,1.282068164963037511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510675435253220655e+01,6.569225942351501999e+02,4.582774462405133087e-01,1.100000010988609489e+01,1.281922179561499793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510766344343221590e+01,6.569325942269335883e+02,4.582902654587979185e-01,1.100000010988609489e+01,1.281776194159962075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510857253433222525e+01,6.569425942187187957e+02,4.583030832172296787e-01,1.100000010988609489e+01,1.281630208758424358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.510948162523223459e+01,6.569525942105059357e+02,4.583158995158086446e-01,1.100000010988609489e+01,1.281484223356886640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511039071613224394e+01,6.569625942022948948e+02,4.583287143545347608e-01,1.100000010988609489e+01,1.281338237955348923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511129980703225328e+01,6.569725941940857865e+02,4.583415277334080828e-01,1.100000010988609489e+01,1.281192252553811205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511220889793226263e+01,6.569825941858784972e+02,4.583543396524286107e-01,1.100000010988609489e+01,1.281046267152273488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511311798883227198e+01,6.569925941776731406e+02,4.583671501115962887e-01,1.100000010988609489e+01,1.280900281750735770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511402707973228132e+01,6.570025941694696030e+02,4.583799591109111726e-01,1.100000010988609489e+01,1.280754296349198053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511493617063229067e+01,6.570125941612679981e+02,4.583927666503732068e-01,1.100000010988609489e+01,1.280608310947660335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511584526153230001e+01,6.570225941530682121e+02,4.584055727299824468e-01,1.100000010988609489e+01,1.280462325546122618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511675435243230936e+01,6.570325941448702451e+02,4.584183773497388925e-01,1.100000010988609489e+01,1.280316340144584900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511766344333231871e+01,6.570425941366742109e+02,4.584311805096424886e-01,1.100000010988609489e+01,1.280170354743047183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511857253423232805e+01,6.570525941284799956e+02,4.584439822096932904e-01,1.100000010988609489e+01,1.280024369341509465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.511948162513233740e+01,6.570625941202877129e+02,4.584567824498912425e-01,1.100000010988609489e+01,1.279878383939971748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512039071603234675e+01,6.570725941120972493e+02,4.584695812302364004e-01,1.100000010988609489e+01,1.279732398538434030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512129980693235609e+01,6.570825941039087184e+02,4.584823785507287086e-01,1.100000010988609489e+01,1.279586413136896313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512220889783236544e+01,6.570925940957220064e+02,4.584951744113682226e-01,1.100000010988609489e+01,1.279440427735358595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512311798873237478e+01,6.571025940875371134e+02,4.585079688121548869e-01,1.100000010988609489e+01,1.279294442333820878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512402707963238413e+01,6.571125940793541531e+02,4.585207617530887569e-01,1.100000010988609489e+01,1.279148456932283160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512493617053239348e+01,6.571225940711730118e+02,4.585335532341697773e-01,1.100000010988609489e+01,1.279002471530745443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512584526143240282e+01,6.571325940629938032e+02,4.585463432553980034e-01,1.100000010988609489e+01,1.278856486129207725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512675435233241217e+01,6.571425940548164135e+02,4.585591318167733799e-01,1.100000010988609489e+01,1.278710500727670007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512766344323242151e+01,6.571525940466409565e+02,4.585719189182959621e-01,1.100000010988609489e+01,1.278564515326132290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512857253413243086e+01,6.571625940384673186e+02,4.585847045599656946e-01,1.100000010988609489e+01,1.278418529924594572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.512948162503244021e+01,6.571725940302954996e+02,4.585974887417826329e-01,1.100000010988609489e+01,1.278272544523056855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513039071593244955e+01,6.571825940221256133e+02,4.586102714637467215e-01,1.100000010988609489e+01,1.278126559121519137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513129980683245890e+01,6.571925940139575459e+02,4.586230527258580159e-01,1.100000010988609489e+01,1.277980573719981420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513220889773246824e+01,6.572025940057914113e+02,4.586358325281164605e-01,1.100000010988609489e+01,1.277834588318443702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513311798863247759e+01,6.572125939976270956e+02,4.586486108705221110e-01,1.100000010988609489e+01,1.277688602916905985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513402707953248694e+01,6.572225939894647126e+02,4.586613877530749117e-01,1.100000010988609489e+01,1.277542617515368267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513493617043249628e+01,6.572325939813041487e+02,4.586741631757749182e-01,1.100000010988609489e+01,1.277396632113830550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513584526133250563e+01,6.572425939731454037e+02,4.586869371386220751e-01,1.100000010988609489e+01,1.277250646712292832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513675435223251498e+01,6.572525939649885913e+02,4.586997096416164377e-01,1.100000010988609489e+01,1.277104661310755115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513766344313252432e+01,6.572625939568335980e+02,4.587124806847579506e-01,1.100000010988609489e+01,1.276958675909217397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513857253403253367e+01,6.572725939486805373e+02,4.587252502680466693e-01,1.100000010988609489e+01,1.276812690507679680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.513948162493254301e+01,6.572825939405292957e+02,4.587380183914825382e-01,1.100000010988609489e+01,1.276666705106141962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514039071583255236e+01,6.572925939323798730e+02,4.587507850550655575e-01,1.100000010988609489e+01,1.276520719704604245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514129980673256171e+01,6.573025939242323830e+02,4.587635502587957825e-01,1.100000010988609489e+01,1.276374734303066527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514220889763257105e+01,6.573125939160867119e+02,4.587763140026731579e-01,1.100000010988609489e+01,1.276228748901528810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514311798853258040e+01,6.573225939079428599e+02,4.587890762866977390e-01,1.100000010988609489e+01,1.276082763499991092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514402707943258974e+01,6.573325938998009406e+02,4.588018371108694704e-01,1.100000010988609489e+01,1.275936778098453375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514493617033259909e+01,6.573425938916608402e+02,4.588145964751884076e-01,1.100000010988609489e+01,1.275790792696915657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514584526123260844e+01,6.573525938835226725e+02,4.588273543796544951e-01,1.100000010988609489e+01,1.275644807295377939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514675435213261778e+01,6.573625938753863238e+02,4.588401108242677329e-01,1.100000010988609489e+01,1.275498821893840222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514766344303262713e+01,6.573725938672517941e+02,4.588528658090281764e-01,1.100000010988609489e+01,1.275352836492302504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514857253393263647e+01,6.573825938591191971e+02,4.588656193339357703e-01,1.100000010988609489e+01,1.275206851090764787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.514948162483264582e+01,6.573925938509884190e+02,4.588783713989905699e-01,1.100000010988609489e+01,1.275060865689227069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515039071573265517e+01,6.574025938428595737e+02,4.588911220041925199e-01,1.100000010988609489e+01,1.274914880287689352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515129980663266451e+01,6.574125938347325473e+02,4.589038711495416201e-01,1.100000010988609489e+01,1.274768894886151634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515220889753267386e+01,6.574225938266073399e+02,4.589166188350379261e-01,1.100000010988609489e+01,1.274622909484613917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515311798843268321e+01,6.574325938184840652e+02,4.589293650606813824e-01,1.100000010988609489e+01,1.274476924083076199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515402707933269255e+01,6.574425938103626095e+02,4.589421098264719889e-01,1.100000010988609489e+01,1.274330938681538482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515493617023270190e+01,6.574525938022429727e+02,4.589548531324098013e-01,1.100000010988609489e+01,1.274184953280000764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515584526113271124e+01,6.574625937941252687e+02,4.589675949784947639e-01,1.100000010988609489e+01,1.274038967878463047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515675435203272059e+01,6.574725937860093836e+02,4.589803353647268769e-01,1.100000010988609489e+01,1.273892982476925329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515766344293272994e+01,6.574825937778953175e+02,4.589930742911061956e-01,1.100000010988609489e+01,1.273746997075387612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515857253383273928e+01,6.574925937697831841e+02,4.590058117576326646e-01,1.100000010988609489e+01,1.273601011673849894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.515948162473274863e+01,6.575025937616728697e+02,4.590185477643062839e-01,1.100000010988609489e+01,1.273455026272312177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516039071563275797e+01,6.575125937535644880e+02,4.590312823111271090e-01,1.100000010988609489e+01,1.273309040870774459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516129980653276732e+01,6.575225937454579253e+02,4.590440153980950844e-01,1.100000010988609489e+01,1.273163055469236742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516220889743277667e+01,6.575325937373531815e+02,4.590567470252102100e-01,1.100000010988609489e+01,1.273017070067699024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516311798833278601e+01,6.575425937292503704e+02,4.590694771924725415e-01,1.100000010988609489e+01,1.272871084666161307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516402707923279536e+01,6.575525937211493783e+02,4.590822058998820232e-01,1.100000010988609489e+01,1.272725099264623589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516493617013280470e+01,6.575625937130502052e+02,4.590949331474386552e-01,1.100000010988609489e+01,1.272579113863085871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516584526103281405e+01,6.575725937049529648e+02,4.591076589351424930e-01,1.100000010988609489e+01,1.272433128461548154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516675435193282340e+01,6.575825936968575434e+02,4.591203832629934811e-01,1.100000010988609489e+01,1.272287143060010436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516766344283283274e+01,6.575925936887639409e+02,4.591331061309916195e-01,1.100000010988609489e+01,1.272141157658472719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516857253373284209e+01,6.576025936806722711e+02,4.591458275391369637e-01,1.100000010988609489e+01,1.271995172256935001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.516948162463285144e+01,6.576125936725824204e+02,4.591585474874294581e-01,1.100000010988609489e+01,1.271849186855397284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517039071553286078e+01,6.576225936644943886e+02,4.591712659758691029e-01,1.100000010988609489e+01,1.271703201453859566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517129980643287013e+01,6.576325936564082895e+02,4.591839830044558979e-01,1.100000010988609489e+01,1.271557216052321849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517220889733287947e+01,6.576425936483240093e+02,4.591966985731898987e-01,1.100000010988609489e+01,1.271411230650784131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517311798823288882e+01,6.576525936402415482e+02,4.592094126820710498e-01,1.100000010988609489e+01,1.271265245249246414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517402707913289817e+01,6.576625936321610197e+02,4.592221253310993512e-01,1.100000010988609489e+01,1.271119259847708696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517493617003290751e+01,6.576725936240823103e+02,4.592348365202748028e-01,1.100000010988609489e+01,1.270973274446170979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517584526093291686e+01,6.576825936160054198e+02,4.592475462495974603e-01,1.100000010988609489e+01,1.270827289044633261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517675435183292620e+01,6.576925936079304620e+02,4.592602545190672680e-01,1.100000010988609489e+01,1.270681303643095544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517766344273293555e+01,6.577025935998573232e+02,4.592729613286842261e-01,1.100000010988609489e+01,1.270535318241557826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517857253363294490e+01,6.577125935917860033e+02,4.592856666784483344e-01,1.100000010988609489e+01,1.270389332840020109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.517948162453295424e+01,6.577225935837165025e+02,4.592983705683596485e-01,1.100000010988609489e+01,1.270243347438482391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518039071543296359e+01,6.577325935756489343e+02,4.593110729984181129e-01,1.100000010988609489e+01,1.270097362036944674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518129980633297293e+01,6.577425935675831852e+02,4.593237739686237275e-01,1.100000010988609489e+01,1.269951376635406956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518220889723298228e+01,6.577525935595192550e+02,4.593364734789764925e-01,1.100000010988609489e+01,1.269805391233869239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518311798813299163e+01,6.577625935514572575e+02,4.593491715294764077e-01,1.100000010988609489e+01,1.269659405832331521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518402707903300097e+01,6.577725935433970790e+02,4.593618681201235288e-01,1.100000010988609489e+01,1.269513420430793803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518493616993301032e+01,6.577825935353387194e+02,4.593745632509178001e-01,1.100000010988609489e+01,1.269367435029256086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518584526083301967e+01,6.577925935272822926e+02,4.593872569218592217e-01,1.100000010988609489e+01,1.269221449627718368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518675435173302901e+01,6.578025935192276847e+02,4.593999491329477936e-01,1.100000010988609489e+01,1.269075464226180651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518766344263303836e+01,6.578125935111748959e+02,4.594126398841835157e-01,1.100000010988609489e+01,1.268929478824642933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518857253353304770e+01,6.578225935031240397e+02,4.594253291755664437e-01,1.100000010988609489e+01,1.268783493423105216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.518948162443305705e+01,6.578325934950750025e+02,4.594380170070965219e-01,1.100000010988609489e+01,1.268637508021567498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519039071533306640e+01,6.578425934870277842e+02,4.594507033787737504e-01,1.100000010988609489e+01,1.268491522620029781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519129980623307574e+01,6.578525934789823850e+02,4.594633882905981292e-01,1.100000010988609489e+01,1.268345537218492063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519220889713308509e+01,6.578625934709389185e+02,4.594760717425696583e-01,1.100000010988609489e+01,1.268199551816954346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519311798803309443e+01,6.578725934628972709e+02,4.594887537346883377e-01,1.100000010988609489e+01,1.268053566415416628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519402707893310378e+01,6.578825934548574423e+02,4.595014342669541674e-01,1.100000010988609489e+01,1.267907581013878911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519493616983311313e+01,6.578925934468195464e+02,4.595141133393672028e-01,1.100000010988609489e+01,1.267761595612341193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519584526073312247e+01,6.579025934387834695e+02,4.595267909519273886e-01,1.100000010988609489e+01,1.267615610210803476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519675435163313182e+01,6.579125934307492116e+02,4.595394671046347246e-01,1.100000010988609489e+01,1.267469624809265758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519766344253314116e+01,6.579225934227167727e+02,4.595521417974892109e-01,1.100000010988609489e+01,1.267323639407728041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519857253343315051e+01,6.579325934146862664e+02,4.595648150304908475e-01,1.100000010988609489e+01,1.267177654006190323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.519948162433315986e+01,6.579425934066575792e+02,4.595774868036396343e-01,1.100000010988609489e+01,1.267031668604652606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520039071523316920e+01,6.579525933986307109e+02,4.595901571169355715e-01,1.100000010988609489e+01,1.266885683203114888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520129980613317855e+01,6.579625933906056616e+02,4.596028259703786589e-01,1.100000010988609489e+01,1.266739697801577171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520220889703318790e+01,6.579725933825825450e+02,4.596154933639689522e-01,1.100000010988609489e+01,1.266593712400039453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520311798793319724e+01,6.579825933745612474e+02,4.596281592977063957e-01,1.100000010988609489e+01,1.266447726998501735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520402707883320659e+01,6.579925933665417688e+02,4.596408237715909895e-01,1.100000010988609489e+01,1.266301741596964018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520493616973321593e+01,6.580025933585242228e+02,4.596534867856227335e-01,1.100000010988609489e+01,1.266155756195426300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520584526063322528e+01,6.580125933505084959e+02,4.596661483398016279e-01,1.100000010988609489e+01,1.266009770793888583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520675435153323463e+01,6.580225933424945879e+02,4.596788084341276726e-01,1.100000010988609489e+01,1.265863785392350865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520766344243324397e+01,6.580325933344824989e+02,4.596914670686008675e-01,1.100000010988609489e+01,1.265717799990813148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520857253333325332e+01,6.580425933264723426e+02,4.597041242432212127e-01,1.100000010988609489e+01,1.265571814589275430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.520948162423326266e+01,6.580525933184640053e+02,4.597167799579887082e-01,1.100000010988609489e+01,1.265425829187737713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521039071513327201e+01,6.580625933104574870e+02,4.597294342129033540e-01,1.100000010988609489e+01,1.265279843786199995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521129980603328136e+01,6.580725933024527876e+02,4.597420870079651500e-01,1.100000010988609489e+01,1.265133858384662278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521220889693329070e+01,6.580825932944500209e+02,4.597547383431740964e-01,1.100000010988609489e+01,1.264987872983124560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521311798783330005e+01,6.580925932864490733e+02,4.597673882185301930e-01,1.100000010988609489e+01,1.264841887581586843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521402707873330939e+01,6.581025932784499446e+02,4.597800366340334399e-01,1.100000010988609489e+01,1.264695902180049125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521493616963331874e+01,6.581125932704526349e+02,4.597926835896838926e-01,1.100000010988609489e+01,1.264549916778511408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521584526053332809e+01,6.581225932624572579e+02,4.598053290854814956e-01,1.100000010988609489e+01,1.264403931376973690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521675435143333743e+01,6.581325932544636999e+02,4.598179731214262489e-01,1.100000010988609489e+01,1.264257945975435973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521766344233334678e+01,6.581425932464719608e+02,4.598306156975181525e-01,1.100000010988609489e+01,1.264111960573898255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521857253323335613e+01,6.581525932384820408e+02,4.598432568137572063e-01,1.100000010988609489e+01,1.263965975172360538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.521948162413336547e+01,6.581625932304939397e+02,4.598558964701434104e-01,1.100000010988609489e+01,1.263819989770822820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522039071503337482e+01,6.581725932225077713e+02,4.598685346666767648e-01,1.100000010988609489e+01,1.263674004369285103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522129980593338416e+01,6.581825932145234219e+02,4.598811714033572695e-01,1.100000010988609489e+01,1.263528018967747385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522220889683339351e+01,6.581925932065408915e+02,4.598938066801849245e-01,1.100000010988609489e+01,1.263382033566209667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522311798773340286e+01,6.582025931985601801e+02,4.599064404971597297e-01,1.100000010988609489e+01,1.263236048164671950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522402707863341220e+01,6.582125931905814014e+02,4.599190728542816853e-01,1.100000010988609489e+01,1.263090062763134232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522493616953342155e+01,6.582225931826044416e+02,4.599317037515507911e-01,1.100000010988609489e+01,1.262944077361596515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522584526043343089e+01,6.582325931746293008e+02,4.599443331889670472e-01,1.100000010988609489e+01,1.262798091960058797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522675435133344024e+01,6.582425931666559791e+02,4.599569611665304536e-01,1.100000010988609489e+01,1.262652106558521080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522766344223344959e+01,6.582525931586844763e+02,4.599695876842409548e-01,1.100000010988609489e+01,1.262506121156983362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522857253313345893e+01,6.582625931507149062e+02,4.599822127420986062e-01,1.100000010988609489e+01,1.262360135755445645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.522948162403346828e+01,6.582725931427471551e+02,4.599948363401034079e-01,1.100000010988609489e+01,1.262214150353907927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523039071493347762e+01,6.582825931347812229e+02,4.600074584782553599e-01,1.100000010988609489e+01,1.262068164952370210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523129980583348697e+01,6.582925931268171098e+02,4.600200791565544622e-01,1.100000010988609489e+01,1.261922179550832492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523220889673349632e+01,6.583025931188549293e+02,4.600326983750007148e-01,1.100000010988609489e+01,1.261776194149294775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523311798763350566e+01,6.583125931108945679e+02,4.600453161335941177e-01,1.100000010988609489e+01,1.261630208747757057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523402707853351501e+01,6.583225931029360254e+02,4.600579324323346708e-01,1.100000010988609489e+01,1.261484223346219340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523493616943352436e+01,6.583325930949793019e+02,4.600705472712223743e-01,1.100000010988609489e+01,1.261338237944681622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523584526033353370e+01,6.583425930870243974e+02,4.600831606502572280e-01,1.100000010988609489e+01,1.261192252543143905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523675435123354305e+01,6.583525930790714256e+02,4.600957725694392320e-01,1.100000010988609489e+01,1.261046267141606187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523766344213355239e+01,6.583625930711202727e+02,4.601083830287683862e-01,1.100000010988609489e+01,1.260900281740068470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523857253303356174e+01,6.583725930631709389e+02,4.601209920282446908e-01,1.100000010988609489e+01,1.260754296338530752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.523948162393357109e+01,6.583825930552234240e+02,4.601335995678681456e-01,1.100000010988609489e+01,1.260608310936993035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524039071483358043e+01,6.583925930472777281e+02,4.601462056476387508e-01,1.100000010988609489e+01,1.260462325535455317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524129980573358978e+01,6.584025930393338513e+02,4.601588102675564507e-01,1.100000010988609489e+01,1.260316340133917599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524220889663359912e+01,6.584125930313919071e+02,4.601714134276213009e-01,1.100000010988609489e+01,1.260170354732379882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524311798753360847e+01,6.584225930234517818e+02,4.601840151278333013e-01,1.100000010988609489e+01,1.260024369330842164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524402707843361782e+01,6.584325930155134756e+02,4.601966153681924521e-01,1.100000010988609489e+01,1.259878383929304447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524493616933362716e+01,6.584425930075769884e+02,4.602092141486987531e-01,1.100000010988609489e+01,1.259732398527766729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524584526023363651e+01,6.584525929996423201e+02,4.602218114693522044e-01,1.100000010988609489e+01,1.259586413126229012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524675435113364586e+01,6.584625929917095846e+02,4.602344073301528060e-01,1.100000010988609489e+01,1.259440427724691294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524766344203365520e+01,6.584725929837786680e+02,4.602470017311005579e-01,1.100000010988609489e+01,1.259294442323153577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524857253293366455e+01,6.584825929758495704e+02,4.602595946721954046e-01,1.100000010988609489e+01,1.259148456921615859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.524948162383367389e+01,6.584925929679222918e+02,4.602721861534374015e-01,1.100000010988609489e+01,1.259002471520078142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525039071473368324e+01,6.585025929599968322e+02,4.602847761748265487e-01,1.100000010988609489e+01,1.258856486118540424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525129980563369259e+01,6.585125929520731916e+02,4.602973647363628462e-01,1.100000010988609489e+01,1.258710500717002707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525220889653370193e+01,6.585225929441514836e+02,4.603099518380462940e-01,1.100000010988609489e+01,1.258564515315464989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525311798743371128e+01,6.585325929362315946e+02,4.603225374798768921e-01,1.100000010988609489e+01,1.258418529913927272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525402707833372062e+01,6.585425929283135247e+02,4.603351216618545849e-01,1.100000010988609489e+01,1.258272544512389554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525493616923372997e+01,6.585525929203972737e+02,4.603477043839794280e-01,1.100000010988609489e+01,1.258126559110851837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525584526013373932e+01,6.585625929124828417e+02,4.603602856462514215e-01,1.100000010988609489e+01,1.257980573709314119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525675435103374866e+01,6.585725929045702287e+02,4.603728654486705651e-01,1.100000010988609489e+01,1.257834588307776402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525766344193375801e+01,6.585825928966594347e+02,4.603854437912368591e-01,1.100000010988609489e+01,1.257688602906238684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525857253283376735e+01,6.585925928887505734e+02,4.603980206739503034e-01,1.100000010988609489e+01,1.257542617504700967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.525948162373377670e+01,6.586025928808435310e+02,4.604105960968108424e-01,1.100000010988609489e+01,1.257396632103163249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526039071463378605e+01,6.586125928729383077e+02,4.604231700598185317e-01,1.100000010988609489e+01,1.257250646701625531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526129980553379539e+01,6.586225928650349033e+02,4.604357425629733713e-01,1.100000010988609489e+01,1.257104661300087814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526220889643380474e+01,6.586325928571333179e+02,4.604483136062753612e-01,1.100000010988609489e+01,1.256958675898550096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526311798733381409e+01,6.586425928492335515e+02,4.604608831897244459e-01,1.100000010988609489e+01,1.256812690497012379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526402707823382343e+01,6.586525928413357178e+02,4.604734513133206808e-01,1.100000010988609489e+01,1.256666705095474661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526493616913383278e+01,6.586625928334397031e+02,4.604860179770640660e-01,1.100000010988609489e+01,1.256520719693936944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526584526003384212e+01,6.586725928255455074e+02,4.604985831809546015e-01,1.100000010988609489e+01,1.256374734292399226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526675435093385147e+01,6.586825928176531306e+02,4.605111469249922873e-01,1.100000010988609489e+01,1.256228748890861509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526766344183386082e+01,6.586925928097625729e+02,4.605237092091770679e-01,1.100000010988609489e+01,1.256082763489323791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526857253273387016e+01,6.587025928018738341e+02,4.605362700335089987e-01,1.100000010988609489e+01,1.255936778087786074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.526948162363387951e+01,6.587125927939869143e+02,4.605488293979880798e-01,1.100000010988609489e+01,1.255790792686248356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527039071453388885e+01,6.587225927861018135e+02,4.605613873026143112e-01,1.100000010988609489e+01,1.255644807284710639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527129980543389820e+01,6.587325927782186454e+02,4.605739437473876374e-01,1.100000010988609489e+01,1.255498821883172921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527220889633390755e+01,6.587425927703372963e+02,4.605864987323081139e-01,1.100000010988609489e+01,1.255352836481635204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527311798723391689e+01,6.587525927624577662e+02,4.605990522573757406e-01,1.100000010988609489e+01,1.255206851080097486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527402707813392624e+01,6.587625927545800550e+02,4.606116043225904622e-01,1.100000010988609489e+01,1.255060865678559769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527493616903393558e+01,6.587725927467041629e+02,4.606241549279523340e-01,1.100000010988609489e+01,1.254914880277022051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527584525993394493e+01,6.587825927388300897e+02,4.606367040734613560e-01,1.100000010988609489e+01,1.254768894875484334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527675435083395428e+01,6.587925927309578356e+02,4.606492517591175284e-01,1.100000010988609489e+01,1.254622909473946616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527766344173396362e+01,6.588025927230874004e+02,4.606617979849207956e-01,1.100000010988609489e+01,1.254476924072408899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527857253263397297e+01,6.588125927152187842e+02,4.606743427508712130e-01,1.100000010988609489e+01,1.254330938670871181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.527948162353398232e+01,6.588225927073521007e+02,4.606868860569687807e-01,1.100000010988609489e+01,1.254184953269333463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528039071443399166e+01,6.588325926994872361e+02,4.606994279032134432e-01,1.100000010988609489e+01,1.254038967867795746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528129980533400101e+01,6.588425926916241906e+02,4.607119682896052559e-01,1.100000010988609489e+01,1.253892982466258028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528220889623401035e+01,6.588525926837629640e+02,4.607245072161442190e-01,1.100000010988609489e+01,1.253746997064720311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528311798713401970e+01,6.588625926759035565e+02,4.607370446828302768e-01,1.100000010988609489e+01,1.253601011663182593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528402707803402905e+01,6.588725926680459679e+02,4.607495806896634849e-01,1.100000010988609489e+01,1.253455026261644876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528493616893403839e+01,6.588825926601901983e+02,4.607621152366438433e-01,1.100000010988609489e+01,1.253309040860107158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528584525983404774e+01,6.588925926523362477e+02,4.607746483237712964e-01,1.100000010988609489e+01,1.253163055458569441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528675435073405708e+01,6.589025926444841161e+02,4.607871799510458999e-01,1.100000010988609489e+01,1.253017070057031723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528766344163406643e+01,6.589125926366338035e+02,4.607997101184676536e-01,1.100000010988609489e+01,1.252871084655494006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528857253253407578e+01,6.589225926287854236e+02,4.608122388260365021e-01,1.100000010988609489e+01,1.252725099253956288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.528948162343408512e+01,6.589325926209388626e+02,4.608247660737525009e-01,1.100000010988609489e+01,1.252579113852418571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529039071433409447e+01,6.589425926130941207e+02,4.608372918616156499e-01,1.100000010988609489e+01,1.252433128450880853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529129980523410381e+01,6.589525926052511977e+02,4.608498161896258938e-01,1.100000010988609489e+01,1.252287143049343136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529220889613411316e+01,6.589625925974100937e+02,4.608623390577832879e-01,1.100000010988609489e+01,1.252141157647805418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529311798703412251e+01,6.589725925895708087e+02,4.608748604660877768e-01,1.100000010988609489e+01,1.251995172246267701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529402707793413185e+01,6.589825925817333427e+02,4.608873804145394160e-01,1.100000010988609489e+01,1.251849186844729983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529493616883414120e+01,6.589925925738976957e+02,4.608998989031382054e-01,1.100000010988609489e+01,1.251703201443192266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529584525973415055e+01,6.590025925660638677e+02,4.609124159318840896e-01,1.100000010988609489e+01,1.251557216041654548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529675435063415989e+01,6.590125925582318587e+02,4.609249315007771242e-01,1.100000010988609489e+01,1.251411230640116830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529766344153416924e+01,6.590225925504016686e+02,4.609374456098172534e-01,1.100000010988609489e+01,1.251265245238579113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529857253243417858e+01,6.590325925425732976e+02,4.609499582590045330e-01,1.100000010988609489e+01,1.251119259837041395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.529948162333418793e+01,6.590425925347467455e+02,4.609624694483389629e-01,1.100000010988609489e+01,1.250973274435503678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530039071423419728e+01,6.590525925269221261e+02,4.609749791778204875e-01,1.100000010988609489e+01,1.250827289033965960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530129980513420662e+01,6.590625925190993257e+02,4.609874874474491624e-01,1.100000010988609489e+01,1.250681303632428243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530220889603421597e+01,6.590725925112783443e+02,4.609999942572249321e-01,1.100000010988609489e+01,1.250535318230890525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530311798693422531e+01,6.590825925034591819e+02,4.610124996071478520e-01,1.100000010988609489e+01,1.250389332829352808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530402707783423466e+01,6.590925924956418385e+02,4.610250034972179223e-01,1.100000010988609489e+01,1.250243347427815090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530493616873424401e+01,6.591025924878263140e+02,4.610375059274350873e-01,1.100000010988609489e+01,1.250097362026277373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530584525963425335e+01,6.591125924800126086e+02,4.610500068977994026e-01,1.100000010988609489e+01,1.249951376624739655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530675435053426270e+01,6.591225924722007221e+02,4.610625064083108127e-01,1.100000010988609489e+01,1.249805391223201938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530766344143427204e+01,6.591325924643906546e+02,4.610750044589693730e-01,1.100000010988609489e+01,1.249659405821664220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530857253233428139e+01,6.591425924565824062e+02,4.610875010497750282e-01,1.100000010988609489e+01,1.249513420420126503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.530948162323429074e+01,6.591525924487759767e+02,4.610999961807278336e-01,1.100000010988609489e+01,1.249367435018588785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531039071413430008e+01,6.591625924409713662e+02,4.611124898518277337e-01,1.100000010988609489e+01,1.249221449617051068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531129980503430943e+01,6.591725924331685746e+02,4.611249820630747842e-01,1.100000010988609489e+01,1.249075464215513350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531220889593431878e+01,6.591825924253676021e+02,4.611374728144689294e-01,1.100000010988609489e+01,1.248929478813975633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531311798683432812e+01,6.591925924175684486e+02,4.611499621060102250e-01,1.100000010988609489e+01,1.248783493412437915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531402707773433747e+01,6.592025924097711140e+02,4.611624499376986153e-01,1.100000010988609489e+01,1.248637508010900198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531493616863434681e+01,6.592125924019755985e+02,4.611749363095341558e-01,1.100000010988609489e+01,1.248491522609362480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531584525953435616e+01,6.592225923941819019e+02,4.611874212215167912e-01,1.100000010988609489e+01,1.248345537207824762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531675435043436551e+01,6.592325923863900243e+02,4.611999046736465768e-01,1.100000010988609489e+01,1.248199551806287045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531766344133437485e+01,6.592425923785999657e+02,4.612123866659234572e-01,1.100000010988609489e+01,1.248053566404749327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531857253223438420e+01,6.592525923708117261e+02,4.612248671983474879e-01,1.100000010988609489e+01,1.247907581003211610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.531948162313439354e+01,6.592625923630253055e+02,4.612373462709186134e-01,1.100000010988609489e+01,1.247761595601673892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532039071403440289e+01,6.592725923552408176e+02,4.612498238836368891e-01,1.100000010988609489e+01,1.247615610200136175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532129980493441224e+01,6.592825923474581487e+02,4.612623000365022596e-01,1.100000010988609489e+01,1.247469624798598457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532220889583442158e+01,6.592925923396772987e+02,4.612747747295147804e-01,1.100000010988609489e+01,1.247323639397060740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532311798673443093e+01,6.593025923318982677e+02,4.612872479626743960e-01,1.100000010988609489e+01,1.247177653995523022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532402707763444027e+01,6.593125923241210558e+02,4.612997197359811619e-01,1.100000010988609489e+01,1.247031668593985305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532493616853444962e+01,6.593225923163456628e+02,4.613121900494350225e-01,1.100000010988609489e+01,1.246885683192447587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532584525943445897e+01,6.593325923085720888e+02,4.613246589030360334e-01,1.100000010988609489e+01,1.246739697790909870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532675435033446831e+01,6.593425923008003338e+02,4.613371262967841391e-01,1.100000010988609489e+01,1.246593712389372152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532766344123447766e+01,6.593525922930303977e+02,4.613495922306793395e-01,1.100000010988609489e+01,1.246447726987834435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532857253213448701e+01,6.593625922852622807e+02,4.613620567047216903e-01,1.100000010988609489e+01,1.246301741586296717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.532948162303449635e+01,6.593725922774959827e+02,4.613745197189111358e-01,1.100000010988609489e+01,1.246155756184759000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533039071393450570e+01,6.593825922697315036e+02,4.613869812732477316e-01,1.100000010988609489e+01,1.246009770783221282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533129980483451504e+01,6.593925922619688436e+02,4.613994413677314221e-01,1.100000010988609489e+01,1.245863785381683565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533220889573452439e+01,6.594025922542080025e+02,4.614119000023622630e-01,1.100000010988609489e+01,1.245717799980145847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533311798663453374e+01,6.594125922464489804e+02,4.614243571771401986e-01,1.100000010988609489e+01,1.245571814578608130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533402707753454308e+01,6.594225922386917773e+02,4.614368128920652290e-01,1.100000010988609489e+01,1.245425829177070412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533493616843455243e+01,6.594325922309363932e+02,4.614492671471374097e-01,1.100000010988609489e+01,1.245279843775532694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533584525933456177e+01,6.594425922231828281e+02,4.614617199423566851e-01,1.100000010988609489e+01,1.245133858373994977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533675435023457112e+01,6.594525922154310820e+02,4.614741712777231109e-01,1.100000010988609489e+01,1.244987872972457259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533766344113458047e+01,6.594625922076811548e+02,4.614866211532366314e-01,1.100000010988609489e+01,1.244841887570919542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533857253203458981e+01,6.594725921999330467e+02,4.614990695688972466e-01,1.100000010988609489e+01,1.244695902169381824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.533948162293459916e+01,6.594825921921867575e+02,4.615115165247050122e-01,1.100000010988609489e+01,1.244549916767844107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534039071383460850e+01,6.594925921844422874e+02,4.615239620206598725e-01,1.100000010988609489e+01,1.244403931366306389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534129980473461785e+01,6.595025921766996362e+02,4.615364060567618276e-01,1.100000010988609489e+01,1.244257945964768672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534220889563462720e+01,6.595125921689588040e+02,4.615488486330109330e-01,1.100000010988609489e+01,1.244111960563230954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534311798653463654e+01,6.595225921612196771e+02,4.615612897494071332e-01,1.100000010988609489e+01,1.243965975161693237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534402707743464589e+01,6.595325921534823692e+02,4.615737294059504281e-01,1.100000010988609489e+01,1.243819989760155519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534493616833465524e+01,6.595425921457468803e+02,4.615861676026408733e-01,1.100000010988609489e+01,1.243674004358617802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534584525923466458e+01,6.595525921380132104e+02,4.615986043394784133e-01,1.100000010988609489e+01,1.243528018957080084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534675435013467393e+01,6.595625921302813595e+02,4.616110396164631036e-01,1.100000010988609489e+01,1.243382033555542367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534766344103468327e+01,6.595725921225513275e+02,4.616234734335948886e-01,1.100000010988609489e+01,1.243236048154004649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534857253193469262e+01,6.595825921148231146e+02,4.616359057908737684e-01,1.100000010988609489e+01,1.243090062752466932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.534948162283470197e+01,6.595925921070967206e+02,4.616483366882997985e-01,1.100000010988609489e+01,1.242944077350929214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535039071373471131e+01,6.596025920993721456e+02,4.616607661258729234e-01,1.100000010988609489e+01,1.242798091949391497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535129980463472066e+01,6.596125920916493897e+02,4.616731941035931430e-01,1.100000010988609489e+01,1.242652106547853779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535220889553473000e+01,6.596225920839284527e+02,4.616856206214604574e-01,1.100000010988609489e+01,1.242506121146316062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535311798643473935e+01,6.596325920762093347e+02,4.616980456794749221e-01,1.100000010988609489e+01,1.242360135744778344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535402707733474870e+01,6.596425920684920357e+02,4.617104692776364816e-01,1.100000010988609489e+01,1.242214150343240626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535493616823475804e+01,6.596525920607765556e+02,4.617228914159451358e-01,1.100000010988609489e+01,1.242068164941702909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535584525913476739e+01,6.596625920530628946e+02,4.617353120944009404e-01,1.100000010988609489e+01,1.241922179540165191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535675435003477673e+01,6.596725920453510525e+02,4.617477313130038397e-01,1.100000010988609489e+01,1.241776194138627474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535766344093478608e+01,6.596825920376410295e+02,4.617601490717538337e-01,1.100000010988609489e+01,1.241630208737089756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535857253183479543e+01,6.596925920299328254e+02,4.617725653706509226e-01,1.100000010988609489e+01,1.241484223335552039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.535948162273480477e+01,6.597025920222264403e+02,4.617849802096951617e-01,1.100000010988609489e+01,1.241338237934014321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536039071363481412e+01,6.597125920145218743e+02,4.617973935888864956e-01,1.100000010988609489e+01,1.241192252532476604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536129980453482347e+01,6.597225920068191272e+02,4.618098055082249243e-01,1.100000010988609489e+01,1.241046267130938886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536220889543483281e+01,6.597325919991181991e+02,4.618222159677105032e-01,1.100000010988609489e+01,1.240900281729401169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536311798633484216e+01,6.597425919914189762e+02,4.618346249673431769e-01,1.100000010988609489e+01,1.240754296327863451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536402707723485150e+01,6.597525919837215724e+02,4.618470325071229454e-01,1.100000010988609489e+01,1.240608310926325734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536493616813486085e+01,6.597625919760259876e+02,4.618594385870498087e-01,1.100000010988609489e+01,1.240462325524788016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536584525903487020e+01,6.597725919683322218e+02,4.618718432071237667e-01,1.100000010988609489e+01,1.240316340123250299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536675434993487954e+01,6.597825919606402749e+02,4.618842463673448751e-01,1.100000010988609489e+01,1.240170354721712581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536766344083488889e+01,6.597925919529501471e+02,4.618966480677130781e-01,1.100000010988609489e+01,1.240024369320174864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536857253173489823e+01,6.598025919452618382e+02,4.619090483082283760e-01,1.100000010988609489e+01,1.239878383918637146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.536948162263490758e+01,6.598125919375753483e+02,4.619214470888907687e-01,1.100000010988609489e+01,1.239732398517099429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537039071353491693e+01,6.598225919298906774e+02,4.619338444097003116e-01,1.100000010988609489e+01,1.239586413115561711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537129980443492627e+01,6.598325919222078255e+02,4.619462402706569493e-01,1.100000010988609489e+01,1.239440427714023994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537220889533493562e+01,6.598425919145267926e+02,4.619586346717606817e-01,1.100000010988609489e+01,1.239294442312486276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537311798623494496e+01,6.598525919068475787e+02,4.619710276130115090e-01,1.100000010988609489e+01,1.239148456910948558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537402707713495431e+01,6.598625918991701838e+02,4.619834190944094310e-01,1.100000010988609489e+01,1.239002471509410841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537493616803496366e+01,6.598725918914944941e+02,4.619958091159545033e-01,1.100000010988609489e+01,1.238856486107873123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537584525893497300e+01,6.598825918838206235e+02,4.620081976776466703e-01,1.100000010988609489e+01,1.238710500706335406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537675434983498235e+01,6.598925918761485718e+02,4.620205847794859322e-01,1.100000010988609489e+01,1.238564515304797688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537766344073499170e+01,6.599025918684783392e+02,4.620329704214722888e-01,1.100000010988609489e+01,1.238418529903259971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537857253163500104e+01,6.599125918608099255e+02,4.620453546036057402e-01,1.100000010988609489e+01,1.238272544501722253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.537948162253501039e+01,6.599225918531433308e+02,4.620577373258862863e-01,1.100000010988609489e+01,1.238126559100184536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538039071343501973e+01,6.599325918454785551e+02,4.620701185883139828e-01,1.100000010988609489e+01,1.237980573698646818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538129980433502908e+01,6.599425918378155984e+02,4.620824983908887740e-01,1.100000010988609489e+01,1.237834588297109101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538220889523503843e+01,6.599525918301544607e+02,4.620948767336106600e-01,1.100000010988609489e+01,1.237688602895571383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538311798613504777e+01,6.599625918224951420e+02,4.621072536164796407e-01,1.100000010988609489e+01,1.237542617494033666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538402707703505712e+01,6.599725918148375285e+02,4.621196290394957162e-01,1.100000010988609489e+01,1.237396632092495948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538493616793506646e+01,6.599825918071817341e+02,4.621320030026588865e-01,1.100000010988609489e+01,1.237250646690958231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538584525883507581e+01,6.599925917995277587e+02,4.621443755059692071e-01,1.100000010988609489e+01,1.237104661289420513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538675434973508516e+01,6.600025917918756022e+02,4.621567465494266225e-01,1.100000010988609489e+01,1.236958675887882796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538766344063509450e+01,6.600125917842252647e+02,4.621691161330311326e-01,1.100000010988609489e+01,1.236812690486345078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538857253153510385e+01,6.600225917765767463e+02,4.621814842567827375e-01,1.100000010988609489e+01,1.236666705084807361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.538948162243511320e+01,6.600325917689300468e+02,4.621938509206814372e-01,1.100000010988609489e+01,1.236520719683269643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539039071333512254e+01,6.600425917612851663e+02,4.622062161247272316e-01,1.100000010988609489e+01,1.236374734281731926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539129980423513189e+01,6.600525917536421048e+02,4.622185798689201208e-01,1.100000010988609489e+01,1.236228748880194208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539220889513514123e+01,6.600625917460007486e+02,4.622309421532601048e-01,1.100000010988609489e+01,1.236082763478656490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539311798603515058e+01,6.600725917383612114e+02,4.622433029777471836e-01,1.100000010988609489e+01,1.235936778077118773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539402707693515993e+01,6.600825917307234931e+02,4.622556623423813571e-01,1.100000010988609489e+01,1.235790792675581055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539493616783516927e+01,6.600925917230875939e+02,4.622680202471626809e-01,1.100000010988609489e+01,1.235644807274043338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539584525873517862e+01,6.601025917154535136e+02,4.622803766920910995e-01,1.100000010988609489e+01,1.235498821872505620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539675434963518796e+01,6.601125917078212524e+02,4.622927316771666129e-01,1.100000010988609489e+01,1.235352836470967903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539766344053519731e+01,6.601225917001908101e+02,4.623050852023892210e-01,1.100000010988609489e+01,1.235206851069430185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539857253143520666e+01,6.601325916925621868e+02,4.623174372677589239e-01,1.100000010988609489e+01,1.235060865667892468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.539948162233521600e+01,6.601425916849352689e+02,4.623297878732757216e-01,1.100000010988609489e+01,1.234914880266354750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540039071323522535e+01,6.601525916773101699e+02,4.623421370189396140e-01,1.100000010988609489e+01,1.234768894864817033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540129980413523469e+01,6.601625916696868899e+02,4.623544847047506012e-01,1.100000010988609489e+01,1.234622909463279315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540220889503524404e+01,6.601725916620654289e+02,4.623668309307086832e-01,1.100000010988609489e+01,1.234476924061741598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540311798593525339e+01,6.601825916544457868e+02,4.623791756968138600e-01,1.100000010988609489e+01,1.234330938660203880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540402707683526273e+01,6.601925916468279638e+02,4.623915190030661315e-01,1.100000010988609489e+01,1.234184953258666163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540493616773527208e+01,6.602025916392118461e+02,4.624038608494654978e-01,1.100000010988609489e+01,1.234038967857128445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540584525863528143e+01,6.602125916315975473e+02,4.624162012360119589e-01,1.100000010988609489e+01,1.233892982455590728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540675434953529077e+01,6.602225916239850676e+02,4.624285401627055148e-01,1.100000010988609489e+01,1.233746997054053010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540766344043530012e+01,6.602325916163744068e+02,4.624408776295461654e-01,1.100000010988609489e+01,1.233601011652515293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540857253133530946e+01,6.602425916087655651e+02,4.624532136365339108e-01,1.100000010988609489e+01,1.233455026250977575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.540948162223531881e+01,6.602525916011585423e+02,4.624655481836687509e-01,1.100000010988609489e+01,1.233309040849439858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541039071313532816e+01,6.602625915935533385e+02,4.624778812709506859e-01,1.100000010988609489e+01,1.233163055447902140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541129980403533750e+01,6.602725915859498400e+02,4.624902128983797156e-01,1.100000010988609489e+01,1.233017070046364422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541220889493534685e+01,6.602825915783481605e+02,4.625025430659558401e-01,1.100000010988609489e+01,1.232871084644826705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541311798583535619e+01,6.602925915707483000e+02,4.625148717736790593e-01,1.100000010988609489e+01,1.232725099243288987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541402707673536554e+01,6.603025915631502585e+02,4.625271990215493734e-01,1.100000010988609489e+01,1.232579113841751270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541493616763537489e+01,6.603125915555540359e+02,4.625395248095667822e-01,1.100000010988609489e+01,1.232433128440213552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541584525853538423e+01,6.603225915479596324e+02,4.625518491377312857e-01,1.100000010988609489e+01,1.232287143038675835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541675434943539358e+01,6.603325915403669342e+02,4.625641720060428841e-01,1.100000010988609489e+01,1.232141157637138117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541766344033540292e+01,6.603425915327760549e+02,4.625764934145015772e-01,1.100000010988609489e+01,1.231995172235600400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541857253123541227e+01,6.603525915251869947e+02,4.625888133631073651e-01,1.100000010988609489e+01,1.231849186834062682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.541948162213542162e+01,6.603625915175997534e+02,4.626011318518602478e-01,1.100000010988609489e+01,1.231703201432524965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542039071303543096e+01,6.603725915100143311e+02,4.626134488807602252e-01,1.100000010988609489e+01,1.231557216030987247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542129980393544031e+01,6.603825915024306141e+02,4.626257644498072974e-01,1.100000010988609489e+01,1.231411230629449530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542220889483544966e+01,6.603925914948487161e+02,4.626380785590014644e-01,1.100000010988609489e+01,1.231265245227911812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542311798573545900e+01,6.604025914872686371e+02,4.626503912083427261e-01,1.100000010988609489e+01,1.231119259826374095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542402707663546835e+01,6.604125914796903771e+02,4.626627023978310826e-01,1.100000010988609489e+01,1.230973274424836377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542493616753547769e+01,6.604225914721139361e+02,4.626750121274665339e-01,1.100000010988609489e+01,1.230827289023298660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542584525843548704e+01,6.604325914645393141e+02,4.626873203972490800e-01,1.100000010988609489e+01,1.230681303621760942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542675434933549639e+01,6.604425914569663973e+02,4.626996272071787208e-01,1.100000010988609489e+01,1.230535318220223225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542766344023550573e+01,6.604525914493952996e+02,4.627119325572554009e-01,1.100000010988609489e+01,1.230389332818685507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542857253113551508e+01,6.604625914418260209e+02,4.627242364474791758e-01,1.100000010988609489e+01,1.230243347417147790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.542948162203552442e+01,6.604725914342585611e+02,4.627365388778500455e-01,1.100000010988609489e+01,1.230097362015610072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543039071293553377e+01,6.604825914266929203e+02,4.627488398483680099e-01,1.100000010988609489e+01,1.229951376614072354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543129980383554312e+01,6.604925914191289849e+02,4.627611393590330691e-01,1.100000010988609489e+01,1.229805391212534637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543220889473555246e+01,6.605025914115668684e+02,4.627734374098452230e-01,1.100000010988609489e+01,1.229659405810996919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543311798563556181e+01,6.605125914040065709e+02,4.627857340008044718e-01,1.100000010988609489e+01,1.229513420409459202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543402707653557115e+01,6.605225913964480924e+02,4.627980291319108153e-01,1.100000010988609489e+01,1.229367435007921484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543493616743558050e+01,6.605325913888913192e+02,4.628103228031642535e-01,1.100000010988609489e+01,1.229221449606383767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543584525833558985e+01,6.605425913813363650e+02,4.628226150145647311e-01,1.100000010988609489e+01,1.229075464204846049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543675434923559919e+01,6.605525913737832298e+02,4.628349057661123034e-01,1.100000010988609489e+01,1.228929478803308332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543766344013560854e+01,6.605625913662319135e+02,4.628471950578069705e-01,1.100000010988609489e+01,1.228783493401770614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543857253103561789e+01,6.605725913586824163e+02,4.628594828896487323e-01,1.100000010988609489e+01,1.228637508000232897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.543948162193562723e+01,6.605825913511346243e+02,4.628717692616375889e-01,1.100000010988609489e+01,1.228491522598695179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544039071283563658e+01,6.605925913435886514e+02,4.628840541737735403e-01,1.100000010988609489e+01,1.228345537197157462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544129980373564592e+01,6.606025913360444974e+02,4.628963376260565865e-01,1.100000010988609489e+01,1.228199551795619744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544220889463565527e+01,6.606125913285021625e+02,4.629086196184866719e-01,1.100000010988609489e+01,1.228053566394082027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544311798553566462e+01,6.606225913209615328e+02,4.629209001510638521e-01,1.100000010988609489e+01,1.227907580992544309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544402707643567396e+01,6.606325913134227221e+02,4.629331792237881271e-01,1.100000010988609489e+01,1.227761595591006592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544493616733568331e+01,6.606425913058857304e+02,4.629454568366594969e-01,1.100000010988609489e+01,1.227615610189468874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544584525823569265e+01,6.606525912983505577e+02,4.629577329896779614e-01,1.100000010988609489e+01,1.227469624787931157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544675434913570200e+01,6.606625912908172040e+02,4.629700076828435207e-01,1.100000010988609489e+01,1.227323639386393439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544766344003571135e+01,6.606725912832855556e+02,4.629822809161561192e-01,1.100000010988609489e+01,1.227177653984855722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544857253093572069e+01,6.606825912757557262e+02,4.629945526896158126e-01,1.100000010988609489e+01,1.227031668583318004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.544948162183573004e+01,6.606925912682277158e+02,4.630068230032226007e-01,1.100000010988609489e+01,1.226885683181780286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545039071273573938e+01,6.607025912607015243e+02,4.630190918569764835e-01,1.100000010988609489e+01,1.226739697780242569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545129980363574873e+01,6.607125912531770382e+02,4.630313592508774612e-01,1.100000010988609489e+01,1.226593712378704851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545220889453575808e+01,6.607225912456543711e+02,4.630436251849254781e-01,1.100000010988609489e+01,1.226447726977167134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545311798543576742e+01,6.607325912381335229e+02,4.630558896591205897e-01,1.100000010988609489e+01,1.226301741575629416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545402707633577677e+01,6.607425912306144937e+02,4.630681526734627962e-01,1.100000010988609489e+01,1.226155756174091699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545493616723578612e+01,6.607525912230971699e+02,4.630804142279520974e-01,1.100000010988609489e+01,1.226009770772553981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545584525813579546e+01,6.607625912155816650e+02,4.630926743225884379e-01,1.100000010988609489e+01,1.225863785371016264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545675434903580481e+01,6.607725912080679791e+02,4.631049329573718731e-01,1.100000010988609489e+01,1.225717799969478546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545766343993581415e+01,6.607825912005561122e+02,4.631171901323024032e-01,1.100000010988609489e+01,1.225571814567940829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545857253083582350e+01,6.607925911930459506e+02,4.631294458473800280e-01,1.100000010988609489e+01,1.225425829166403111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.545948162173583285e+01,6.608025911855376080e+02,4.631417001026047475e-01,1.100000010988609489e+01,1.225279843764865394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546039071263584219e+01,6.608125911780310844e+02,4.631539528979765064e-01,1.100000010988609489e+01,1.225133858363327676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546129980353585154e+01,6.608225911705262661e+02,4.631662042334953600e-01,1.100000010988609489e+01,1.224987872961789959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546220889443586088e+01,6.608325911630232667e+02,4.631784541091613083e-01,1.100000010988609489e+01,1.224841887560252241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546311798533587023e+01,6.608425911555220864e+02,4.631907025249742960e-01,1.100000010988609489e+01,1.224695902158714524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546402707623587958e+01,6.608525911480227251e+02,4.632029494809343784e-01,1.100000010988609489e+01,1.224549916757176806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546493616713588892e+01,6.608625911405250690e+02,4.632151949770415555e-01,1.100000010988609489e+01,1.224403931355639089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546584525803589827e+01,6.608725911330292320e+02,4.632274390132958275e-01,1.100000010988609489e+01,1.224257945954101371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546675434893590761e+01,6.608825911255352139e+02,4.632396815896971387e-01,1.100000010988609489e+01,1.224111960552563654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546766343983591696e+01,6.608925911180430148e+02,4.632519227062455447e-01,1.100000010988609489e+01,1.223965975151025936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546857253073592631e+01,6.609025911105525211e+02,4.632641623629410454e-01,1.100000010988609489e+01,1.223819989749488218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.546948162163593565e+01,6.609125911030638463e+02,4.632764005597835855e-01,1.100000010988609489e+01,1.223674004347950501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547039071253594500e+01,6.609225910955769905e+02,4.632886372967732203e-01,1.100000010988609489e+01,1.223528018946412783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547129980343595435e+01,6.609325910880918400e+02,4.633008725739099498e-01,1.100000010988609489e+01,1.223382033544875066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547220889433596369e+01,6.609425910806085085e+02,4.633131063911937741e-01,1.100000010988609489e+01,1.223236048143337348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547311798523597304e+01,6.609525910731269960e+02,4.633253387486246377e-01,1.100000010988609489e+01,1.223090062741799631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547402707613598238e+01,6.609625910656473025e+02,4.633375696462025961e-01,1.100000010988609489e+01,1.222944077340261913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547493616703599173e+01,6.609725910581693142e+02,4.633497990839276492e-01,1.100000010988609489e+01,1.222798091938724196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547584525793600108e+01,6.609825910506931450e+02,4.633620270617997416e-01,1.100000010988609489e+01,1.222652106537186478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547675434883601042e+01,6.609925910432187948e+02,4.633742535798189288e-01,1.100000010988609489e+01,1.222506121135648761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547766343973601977e+01,6.610025910357461498e+02,4.633864786379852108e-01,1.100000010988609489e+01,1.222360135734111043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547857253063602911e+01,6.610125910282753239e+02,4.633987022362985320e-01,1.100000010988609489e+01,1.222214150332573326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.547948162153603846e+01,6.610225910208063169e+02,4.634109243747589479e-01,1.100000010988609489e+01,1.222068164931035608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548039071243604781e+01,6.610325910133390153e+02,4.634231450533664032e-01,1.100000010988609489e+01,1.221922179529497891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548129980333605715e+01,6.610425910058735326e+02,4.634353642721209532e-01,1.100000010988609489e+01,1.221776194127960173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548220889423606650e+01,6.610525909984098689e+02,4.634475820310225980e-01,1.100000010988609489e+01,1.221630208726422456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548311798513607584e+01,6.610625909909480242e+02,4.634597983300712820e-01,1.100000010988609489e+01,1.221484223324884738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548402707603608519e+01,6.610725909834878848e+02,4.634720131692670608e-01,1.100000010988609489e+01,1.221338237923347021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548493616693609454e+01,6.610825909760295644e+02,4.634842265486099344e-01,1.100000010988609489e+01,1.221192252521809303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548584525783610388e+01,6.610925909685730630e+02,4.634964384680998473e-01,1.100000010988609489e+01,1.221046267120271585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548675434873611323e+01,6.611025909611182669e+02,4.635086489277368549e-01,1.100000010988609489e+01,1.220900281718733868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548766343963612258e+01,6.611125909536652898e+02,4.635208579275209018e-01,1.100000010988609489e+01,1.220754296317196150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548857253053613192e+01,6.611225909462141317e+02,4.635330654674520434e-01,1.100000010988609489e+01,1.220608310915658433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.548948162143614127e+01,6.611325909387646789e+02,4.635452715475302798e-01,1.100000010988609489e+01,1.220462325514120715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549039071233615061e+01,6.611425909313170450e+02,4.635574761677555555e-01,1.100000010988609489e+01,1.220316340112582998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549129980323615996e+01,6.611525909238712302e+02,4.635696793281279260e-01,1.100000010988609489e+01,1.220170354711045280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549220889413616931e+01,6.611625909164271206e+02,4.635818810286473357e-01,1.100000010988609489e+01,1.220024369309507563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549311798503617865e+01,6.611725909089848301e+02,4.635940812693138402e-01,1.100000010988609489e+01,1.219878383907969845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549402707593618800e+01,6.611825909015443585e+02,4.636062800501274395e-01,1.100000010988609489e+01,1.219732398506432128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549493616683619734e+01,6.611925908941055923e+02,4.636184773710880780e-01,1.100000010988609489e+01,1.219586413104894410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549584525773620669e+01,6.612025908866686450e+02,4.636306732321958113e-01,1.100000010988609489e+01,1.219440427703356693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549675434863621604e+01,6.612125908792335167e+02,4.636428676334505838e-01,1.100000010988609489e+01,1.219294442301818975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549766343953622538e+01,6.612225908718000937e+02,4.636550605748524512e-01,1.100000010988609489e+01,1.219148456900281258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549857253043623473e+01,6.612325908643684897e+02,4.636672520564013578e-01,1.100000010988609489e+01,1.219002471498743540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.549948162133624407e+01,6.612425908569387047e+02,4.636794420780973591e-01,1.100000010988609489e+01,1.218856486097205823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550039071223625342e+01,6.612525908495106250e+02,4.636916306399403997e-01,1.100000010988609489e+01,1.218710500695668105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550129980313626277e+01,6.612625908420843643e+02,4.637038177419305351e-01,1.100000010988609489e+01,1.218564515294130388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550220889403627211e+01,6.612725908346599226e+02,4.637160033840677098e-01,1.100000010988609489e+01,1.218418529892592670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550311798493628146e+01,6.612825908272371862e+02,4.637281875663519792e-01,1.100000010988609489e+01,1.218272544491054953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550402707583629081e+01,6.612925908198162688e+02,4.637403702887832879e-01,1.100000010988609489e+01,1.218126559089517235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550493616673630015e+01,6.613025908123970567e+02,4.637525515513616914e-01,1.100000010988609489e+01,1.217980573687979517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550584525763630950e+01,6.613125908049796635e+02,4.637647313540871341e-01,1.100000010988609489e+01,1.217834588286441800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550675434853631884e+01,6.613225907975640894e+02,4.637769096969596716e-01,1.100000010988609489e+01,1.217688602884904082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550766343943632819e+01,6.613325907901502205e+02,4.637890865799793039e-01,1.100000010988609489e+01,1.217542617483366365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550857253033633754e+01,6.613425907827381707e+02,4.638012620031459754e-01,1.100000010988609489e+01,1.217396632081828647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.550948162123634688e+01,6.613525907753279398e+02,4.638134359664596862e-01,1.100000010988609489e+01,1.217250646680290930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551039071213635623e+01,6.613625907679194142e+02,4.638256084699204917e-01,1.100000010988609489e+01,1.217104661278753212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551129980303636557e+01,6.613725907605127077e+02,4.638377795135283366e-01,1.100000010988609489e+01,1.216958675877215495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551220889393637492e+01,6.613825907531078201e+02,4.638499490972832762e-01,1.100000010988609489e+01,1.216812690475677777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551311798483638427e+01,6.613925907457046378e+02,4.638621172211852550e-01,1.100000010988609489e+01,1.216666705074140060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551402707573639361e+01,6.614025907383032745e+02,4.638742838852343287e-01,1.100000010988609489e+01,1.216520719672602342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551493616663640296e+01,6.614125907309036165e+02,4.638864490894304415e-01,1.100000010988609489e+01,1.216374734271064625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551584525753641230e+01,6.614225907235057775e+02,4.638986128337736492e-01,1.100000010988609489e+01,1.216228748869526907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551675434843642165e+01,6.614325907161097575e+02,4.639107751182638961e-01,1.100000010988609489e+01,1.216082763467989190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551766343933643100e+01,6.614425907087154428e+02,4.639229359429012378e-01,1.100000010988609489e+01,1.215936778066451472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551857253023644034e+01,6.614525907013229471e+02,4.639350953076856188e-01,1.100000010988609489e+01,1.215790792664913755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.551948162113644969e+01,6.614625906939321567e+02,4.639472532126170945e-01,1.100000010988609489e+01,1.215644807263376037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552039071203645904e+01,6.614725906865431853e+02,4.639594096576956095e-01,1.100000010988609489e+01,1.215498821861838320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552129980293646838e+01,6.614825906791560328e+02,4.639715646429211637e-01,1.100000010988609489e+01,1.215352836460300602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552220889383647773e+01,6.614925906717705857e+02,4.639837181682938128e-01,1.100000010988609489e+01,1.215206851058762885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552311798473648707e+01,6.615025906643869575e+02,4.639958702338135010e-01,1.100000010988609489e+01,1.215060865657225167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552402707563649642e+01,6.615125906570051484e+02,4.640080208394802841e-01,1.100000010988609489e+01,1.214914880255687449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552493616653650577e+01,6.615225906496250445e+02,4.640201699852941064e-01,1.100000010988609489e+01,1.214768894854149732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552584525743651511e+01,6.615325906422467597e+02,4.640323176712550235e-01,1.100000010988609489e+01,1.214622909452612014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552675434833652446e+01,6.615425906348701801e+02,4.640444638973629798e-01,1.100000010988609489e+01,1.214476924051074297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552766343923653380e+01,6.615525906274954195e+02,4.640566086636179755e-01,1.100000010988609489e+01,1.214330938649536579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552857253013654315e+01,6.615625906201224780e+02,4.640687519700200658e-01,1.100000010988609489e+01,1.214184953247998862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.552948162103655250e+01,6.615725906127512417e+02,4.640808938165691955e-01,1.100000010988609489e+01,1.214038967846461144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553039071193656184e+01,6.615825906053818244e+02,4.640930342032654199e-01,1.100000010988609489e+01,1.213892982444923427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553129980283657119e+01,6.615925905980141124e+02,4.641051731301086836e-01,1.100000010988609489e+01,1.213746997043385709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553220889373658054e+01,6.616025905906482194e+02,4.641173105970989865e-01,1.100000010988609489e+01,1.213601011641847992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553311798463658988e+01,6.616125905832840317e+02,4.641294466042363842e-01,1.100000010988609489e+01,1.213455026240310274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553402707553659923e+01,6.616225905759216630e+02,4.641415811515208212e-01,1.100000010988609489e+01,1.213309040838772557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553493616643660857e+01,6.616325905685611133e+02,4.641537142389522974e-01,1.100000010988609489e+01,1.213163055437234839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553584525733661792e+01,6.616425905612022689e+02,4.641658458665308684e-01,1.100000010988609489e+01,1.213017070035697122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553675434823662727e+01,6.616525905538452434e+02,4.641779760342564787e-01,1.100000010988609489e+01,1.212871084634159404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553766343913663661e+01,6.616625905464899233e+02,4.641901047421291282e-01,1.100000010988609489e+01,1.212725099232621687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553857253003664596e+01,6.616725905391364222e+02,4.642022319901488725e-01,1.100000010988609489e+01,1.212579113831083969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.553948162093665530e+01,6.616825905317846264e+02,4.642143577783156561e-01,1.100000010988609489e+01,1.212433128429546252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554039071183666465e+01,6.616925905244346495e+02,4.642264821066294789e-01,1.100000010988609489e+01,1.212287143028008534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554129980273667400e+01,6.617025905170864917e+02,4.642386049750903965e-01,1.100000010988609489e+01,1.212141157626470817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554220889363668334e+01,6.617125905097400391e+02,4.642507263836983533e-01,1.100000010988609489e+01,1.211995172224933099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554311798453669269e+01,6.617225905023954056e+02,4.642628463324533494e-01,1.100000010988609489e+01,1.211849186823395381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554402707543670203e+01,6.617325904950524773e+02,4.642749648213554403e-01,1.100000010988609489e+01,1.211703201421857664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554493616633671138e+01,6.617425904877113680e+02,4.642870818504045705e-01,1.100000010988609489e+01,1.211557216020319946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554584525723672073e+01,6.617525904803719641e+02,4.642991974196007399e-01,1.100000010988609489e+01,1.211411230618782229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554675434813673007e+01,6.617625904730343791e+02,4.643113115289440040e-01,1.100000010988609489e+01,1.211265245217244511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554766343903673942e+01,6.617725904656986131e+02,4.643234241784343075e-01,1.100000010988609489e+01,1.211119259815706794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554857252993674877e+01,6.617825904583645524e+02,4.643355353680716502e-01,1.100000010988609489e+01,1.210973274414169076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.554948162083675811e+01,6.617925904510323107e+02,4.643476450978560321e-01,1.100000010988609489e+01,1.210827289012631359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555039071173676746e+01,6.618025904437017743e+02,4.643597533677875089e-01,1.100000010988609489e+01,1.210681303611093641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555129980263677680e+01,6.618125904363730569e+02,4.643718601778660249e-01,1.100000010988609489e+01,1.210535318209555924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555220889353678615e+01,6.618225904290460448e+02,4.643839655280915801e-01,1.100000010988609489e+01,1.210389332808018206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555311798443679550e+01,6.618325904217208517e+02,4.643960694184642302e-01,1.100000010988609489e+01,1.210243347406480489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555402707533680484e+01,6.618425904143973639e+02,4.644081718489839194e-01,1.100000010988609489e+01,1.210097362004942771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555493616623681419e+01,6.618525904070756951e+02,4.644202728196506480e-01,1.100000010988609489e+01,1.209951376603405054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555584525713682353e+01,6.618625903997557316e+02,4.644323723304644158e-01,1.100000010988609489e+01,1.209805391201867336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555675434803683288e+01,6.618725903924375871e+02,4.644444703814252784e-01,1.100000010988609489e+01,1.209659405800329619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555766343893684223e+01,6.618825903851212615e+02,4.644565669725331802e-01,1.100000010988609489e+01,1.209513420398791901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555857252983685157e+01,6.618925903778066413e+02,4.644686621037881213e-01,1.100000010988609489e+01,1.209367434997254184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.555948162073686092e+01,6.619025903704938401e+02,4.644807557751901017e-01,1.100000010988609489e+01,1.209221449595716466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556039071163687026e+01,6.619125903631827441e+02,4.644928479867391768e-01,1.100000010988609489e+01,1.209075464194178749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556129980253687961e+01,6.619225903558734672e+02,4.645049387384352912e-01,1.100000010988609489e+01,1.208929478792641031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556220889343688896e+01,6.619325903485658955e+02,4.645170280302784449e-01,1.100000010988609489e+01,1.208783493391103313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556311798433689830e+01,6.619425903412601428e+02,4.645291158622686378e-01,1.100000010988609489e+01,1.208637507989565596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556402707523690765e+01,6.619525903339560955e+02,4.645412022344058700e-01,1.100000010988609489e+01,1.208491522588027878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556493616613691700e+01,6.619625903266538671e+02,4.645532871466901970e-01,1.100000010988609489e+01,1.208345537186490161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556584525703692634e+01,6.619725903193533441e+02,4.645653705991215632e-01,1.100000010988609489e+01,1.208199551784952443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556675434793693569e+01,6.619825903120546400e+02,4.645774525916999687e-01,1.100000010988609489e+01,1.208053566383414726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556766343883694503e+01,6.619925903047576412e+02,4.645895331244254134e-01,1.100000010988609489e+01,1.207907580981877008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556857252973695438e+01,6.620025902974624614e+02,4.646016121972978974e-01,1.100000010988609489e+01,1.207761595580339291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.556948162063696373e+01,6.620125902901689869e+02,4.646136898103174762e-01,1.100000010988609489e+01,1.207615610178801573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557039071153697307e+01,6.620225902828773314e+02,4.646257659634840942e-01,1.100000010988609489e+01,1.207469624777263856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557129980243698242e+01,6.620325902755873813e+02,4.646378406567977515e-01,1.100000010988609489e+01,1.207323639375726138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557220889333699176e+01,6.620425902682992501e+02,4.646499138902584480e-01,1.100000010988609489e+01,1.207177653974188421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557311798423700111e+01,6.620525902610128242e+02,4.646619856638661838e-01,1.100000010988609489e+01,1.207031668572650703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557402707513701046e+01,6.620625902537282172e+02,4.646740559776209589e-01,1.100000010988609489e+01,1.206885683171112986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557493616603701980e+01,6.620725902464453156e+02,4.646861248315228288e-01,1.100000010988609489e+01,1.206739697769575268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557584525693702915e+01,6.620825902391642330e+02,4.646981922255717379e-01,1.100000010988609489e+01,1.206593712368037551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557675434783703849e+01,6.620925902318848557e+02,4.647102581597676862e-01,1.100000010988609489e+01,1.206447726966499833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557766343873704784e+01,6.621025902246072974e+02,4.647223226341106739e-01,1.100000010988609489e+01,1.206301741564962116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557857252963705719e+01,6.621125902173314444e+02,4.647343856486007008e-01,1.100000010988609489e+01,1.206155756163424398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.557948162053706653e+01,6.621225902100574103e+02,4.647464472032377669e-01,1.100000010988609489e+01,1.206009770761886681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558039071143707588e+01,6.621325902027850816e+02,4.647585072980218723e-01,1.100000010988609489e+01,1.205863785360348963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558129980233708523e+01,6.621425901955145719e+02,4.647705659329530725e-01,1.100000010988609489e+01,1.205717799958811245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558220889323709457e+01,6.621525901882457674e+02,4.647826231080313120e-01,1.100000010988609489e+01,1.205571814557273528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558311798413710392e+01,6.621625901809787820e+02,4.647946788232565907e-01,1.100000010988609489e+01,1.205425829155735810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558402707503711326e+01,6.621725901737135018e+02,4.648067330786289086e-01,1.100000010988609489e+01,1.205279843754198093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558493616593712261e+01,6.621825901664500407e+02,4.648187858741482659e-01,1.100000010988609489e+01,1.205133858352660375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558584525683713196e+01,6.621925901591882848e+02,4.648308372098146624e-01,1.100000010988609489e+01,1.204987872951122658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558675434773714130e+01,6.622025901519283480e+02,4.648428870856280981e-01,1.100000010988609489e+01,1.204841887549584940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558766343863715065e+01,6.622125901446701164e+02,4.648549355015885731e-01,1.100000010988609489e+01,1.204695902148047223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558857252953715999e+01,6.622225901374137038e+02,4.648669824576960874e-01,1.100000010988609489e+01,1.204549916746509505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.558948162043716934e+01,6.622325901301589965e+02,4.648790279539506964e-01,1.100000010988609489e+01,1.204403931344971788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559039071133717869e+01,6.622425901229061083e+02,4.648910719903523447e-01,1.100000010988609489e+01,1.204257945943434070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559129980223718803e+01,6.622525901156549253e+02,4.649031145669010323e-01,1.100000010988609489e+01,1.204111960541896353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559220889313719738e+01,6.622625901084054476e+02,4.649151556835967591e-01,1.100000010988609489e+01,1.203965975140358635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559311798403720672e+01,6.622725901011577889e+02,4.649271953404395252e-01,1.100000010988609489e+01,1.203819989738820918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559402707493721607e+01,6.622825900939118355e+02,4.649392335374293306e-01,1.100000010988609489e+01,1.203674004337283200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559493616583722542e+01,6.622925900866677011e+02,4.649512702745661752e-01,1.100000010988609489e+01,1.203528018935745483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559584525673723476e+01,6.623025900794252721e+02,4.649633055518500591e-01,1.100000010988609489e+01,1.203382033534207765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559675434763724411e+01,6.623125900721846619e+02,4.649753393692809822e-01,1.100000010988609489e+01,1.203236048132670048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559766343853725346e+01,6.623225900649457571e+02,4.649873717268589446e-01,1.100000010988609489e+01,1.203090062731132330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559857252943726280e+01,6.623325900577086713e+02,4.649994026245839462e-01,1.100000010988609489e+01,1.202944077329594613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.559948162033727215e+01,6.623425900504732908e+02,4.650114320624559872e-01,1.100000010988609489e+01,1.202798091928056895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560039071123728149e+01,6.623525900432397293e+02,4.650234600404750673e-01,1.100000010988609489e+01,1.202652106526519177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560129980213729084e+01,6.623625900360078731e+02,4.650354865586411868e-01,1.100000010988609489e+01,1.202506121124981460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560220889303730019e+01,6.623725900287777222e+02,4.650475116169543455e-01,1.100000010988609489e+01,1.202360135723443742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560311798393730953e+01,6.623825900215493903e+02,4.650595352154145434e-01,1.100000010988609489e+01,1.202214150321906025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560402707483731888e+01,6.623925900143227636e+02,4.650715573540217807e-01,1.100000010988609489e+01,1.202068164920368307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560493616573732822e+01,6.624025900070979560e+02,4.650835780327760571e-01,1.100000010988609489e+01,1.201922179518830590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560584525663733757e+01,6.624125899998748537e+02,4.650955972516773729e-01,1.100000010988609489e+01,1.201776194117292872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560675434753734692e+01,6.624225899926535703e+02,4.651076150107257279e-01,1.100000010988609489e+01,1.201630208715755155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560766343843735626e+01,6.624325899854339923e+02,4.651196313099211221e-01,1.100000010988609489e+01,1.201484223314217437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560857252933736561e+01,6.624425899782161196e+02,4.651316461492635557e-01,1.100000010988609489e+01,1.201338237912679720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.560948162023737495e+01,6.624525899710000658e+02,4.651436595287530285e-01,1.100000010988609489e+01,1.201192252511142002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561039071113738430e+01,6.624625899637857174e+02,4.651556714483895405e-01,1.100000010988609489e+01,1.201046267109604285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561129980203739365e+01,6.624725899565731879e+02,4.651676819081730918e-01,1.100000010988609489e+01,1.200900281708066567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561220889293740299e+01,6.624825899493623638e+02,4.651796909081036824e-01,1.100000010988609489e+01,1.200754296306528850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561311798383741234e+01,6.624925899421533586e+02,4.651916984481813122e-01,1.100000010988609489e+01,1.200608310904991132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561402707473742169e+01,6.625025899349460587e+02,4.652037045284059813e-01,1.100000010988609489e+01,1.200462325503453415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561493616563743103e+01,6.625125899277404642e+02,4.652157091487776897e-01,1.100000010988609489e+01,1.200316340101915697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561584525653744038e+01,6.625225899205366886e+02,4.652277123092964373e-01,1.100000010988609489e+01,1.200170354700377980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561675434743744972e+01,6.625325899133346184e+02,4.652397140099622241e-01,1.100000010988609489e+01,1.200024369298840262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561766343833745907e+01,6.625425899061343671e+02,4.652517142507750503e-01,1.100000010988609489e+01,1.199878383897302545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561857252923746842e+01,6.625525898989358211e+02,4.652637130317349157e-01,1.100000010988609489e+01,1.199732398495764827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.561948162013747776e+01,6.625625898917389804e+02,4.652757103528418203e-01,1.100000010988609489e+01,1.199586413094227109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562039071103748711e+01,6.625725898845439588e+02,4.652877062140957642e-01,1.100000010988609489e+01,1.199440427692689392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562129980193749645e+01,6.625825898773506424e+02,4.652997006154966919e-01,1.100000010988609489e+01,1.199294442291151674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562220889283750580e+01,6.625925898701591450e+02,4.653116935570446588e-01,1.100000010988609489e+01,1.199148456889613957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562311798373751515e+01,6.626025898629693529e+02,4.653236850387396650e-01,1.100000010988609489e+01,1.199002471488076239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562402707463752449e+01,6.626125898557812661e+02,4.653356750605817105e-01,1.100000010988609489e+01,1.198856486086538522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562493616553753384e+01,6.626225898485949983e+02,4.653476636225707952e-01,1.100000010988609489e+01,1.198710500685000804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562584525643754318e+01,6.626325898414104358e+02,4.653596507247069192e-01,1.100000010988609489e+01,1.198564515283463087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562675434733755253e+01,6.626425898342276923e+02,4.653716363669900824e-01,1.100000010988609489e+01,1.198418529881925369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562766343823756188e+01,6.626525898270466541e+02,4.653836205494202849e-01,1.100000010988609489e+01,1.198272544480387652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562857252913757122e+01,6.626625898198673212e+02,4.653956032719975267e-01,1.100000010988609489e+01,1.198126559078849934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.562948162003758057e+01,6.626725898126898073e+02,4.654075845347218077e-01,1.100000010988609489e+01,1.197980573677312217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563039071093758992e+01,6.626825898055139987e+02,4.654195643375930724e-01,1.100000010988609489e+01,1.197834588275774499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563129980183759926e+01,6.626925897983400091e+02,4.654315426806113765e-01,1.100000010988609489e+01,1.197688602874236782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563220889273760861e+01,6.627025897911677248e+02,4.654435195637767197e-01,1.100000010988609489e+01,1.197542617472699064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563311798363761795e+01,6.627125897839971458e+02,4.654554949870891023e-01,1.100000010988609489e+01,1.197396632071161347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563402707453762730e+01,6.627225897768283858e+02,4.654674689505485241e-01,1.100000010988609489e+01,1.197250646669623629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563493616543763665e+01,6.627325897696613310e+02,4.654794414541549852e-01,1.100000010988609489e+01,1.197104661268085912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563584525633764599e+01,6.627425897624959816e+02,4.654914124979084855e-01,1.100000010988609489e+01,1.196958675866548194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563675434723765534e+01,6.627525897553324512e+02,4.655033820818089696e-01,1.100000010988609489e+01,1.196812690465010477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563766343813766468e+01,6.627625897481706261e+02,4.655153502058564929e-01,1.100000010988609489e+01,1.196666705063472759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563857252903767403e+01,6.627725897410106199e+02,4.655273168700510555e-01,1.100000010988609489e+01,1.196520719661935041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.563948161993768338e+01,6.627825897338523191e+02,4.655392820743926574e-01,1.100000010988609489e+01,1.196374734260397324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564039071083769272e+01,6.627925897266957236e+02,4.655512458188812985e-01,1.100000010988609489e+01,1.196228748858859606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564129980173770207e+01,6.628025897195409470e+02,4.655632081035169789e-01,1.100000010988609489e+01,1.196082763457321889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564220889263771141e+01,6.628125897123878758e+02,4.655751689282996431e-01,1.100000010988609489e+01,1.195936778055784171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564311798353772076e+01,6.628225897052365099e+02,4.655871282932293465e-01,1.100000010988609489e+01,1.195790792654246454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564402707443773011e+01,6.628325896980869629e+02,4.655990861983060891e-01,1.100000010988609489e+01,1.195644807252708736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564493616533773945e+01,6.628425896909391213e+02,4.656110426435298710e-01,1.100000010988609489e+01,1.195498821851171019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564584525623774880e+01,6.628525896837929849e+02,4.656229976289006922e-01,1.100000010988609489e+01,1.195352836449633301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564675434713775815e+01,6.628625896766486676e+02,4.656349511544184971e-01,1.100000010988609489e+01,1.195206851048095584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564766343803776749e+01,6.628725896695060555e+02,4.656469032200833413e-01,1.100000010988609489e+01,1.195060865646557866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564857252893777684e+01,6.628825896623651488e+02,4.656588538258952248e-01,1.100000010988609489e+01,1.194914880245020149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.564948161983778618e+01,6.628925896552260610e+02,4.656708029718541475e-01,1.100000010988609489e+01,1.194768894843482431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565039071073779553e+01,6.629025896480886786e+02,4.656827506579601095e-01,1.100000010988609489e+01,1.194622909441944714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565129980163780488e+01,6.629125896409531151e+02,4.656946968842130552e-01,1.100000010988609489e+01,1.194476924040406996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565220889253781422e+01,6.629225896338192570e+02,4.657066416506130402e-01,1.100000010988609489e+01,1.194330938638869279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565311798343782357e+01,6.629325896266871041e+02,4.657185849571600644e-01,1.100000010988609489e+01,1.194184953237331561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565402707433783291e+01,6.629425896195567702e+02,4.657305268038541279e-01,1.100000010988609489e+01,1.194038967835793844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565493616523784226e+01,6.629525896124281417e+02,4.657424671906951752e-01,1.100000010988609489e+01,1.193892982434256126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565584525613785161e+01,6.629625896053012184e+02,4.657544061176832617e-01,1.100000010988609489e+01,1.193746997032718409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565675434703786095e+01,6.629725895981761141e+02,4.657663435848183875e-01,1.100000010988609489e+01,1.193601011631180691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565766343793787030e+01,6.629825895910527151e+02,4.657782795921005525e-01,1.100000010988609489e+01,1.193455026229642973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565857252883787964e+01,6.629925895839310215e+02,4.657902141395297013e-01,1.100000010988609489e+01,1.193309040828105256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.565948161973788899e+01,6.630025895768111468e+02,4.658021472271058894e-01,1.100000010988609489e+01,1.193163055426567538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566039071063789834e+01,6.630125895696929774e+02,4.658140788548291167e-01,1.100000010988609489e+01,1.193017070025029821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566129980153790768e+01,6.630225895625765133e+02,4.658260090226993277e-01,1.100000010988609489e+01,1.192871084623492103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566220889243791703e+01,6.630325895554617546e+02,4.658379377307165781e-01,1.100000010988609489e+01,1.192725099221954386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566311798333792638e+01,6.630425895483488148e+02,4.658498649788808676e-01,1.100000010988609489e+01,1.192579113820416668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566402707423793572e+01,6.630525895412375803e+02,4.658617907671921965e-01,1.100000010988609489e+01,1.192433128418878951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566493616513794507e+01,6.630625895341280511e+02,4.658737150956505091e-01,1.100000010988609489e+01,1.192287143017341233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566584525603795441e+01,6.630725895270203409e+02,4.658856379642558609e-01,1.100000010988609489e+01,1.192141157615803516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566675434693796376e+01,6.630825895199143361e+02,4.658975593730082521e-01,1.100000010988609489e+01,1.191995172214265798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566766343783797311e+01,6.630925895128100365e+02,4.659094793219076269e-01,1.100000010988609489e+01,1.191849186812728081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566857252873798245e+01,6.631025895057075559e+02,4.659213978109540411e-01,1.100000010988609489e+01,1.191703201411190363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.566948161963799180e+01,6.631125894986067806e+02,4.659333148401474944e-01,1.100000010988609489e+01,1.191557216009652646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567039071053800114e+01,6.631225894915077106e+02,4.659452304094879316e-01,1.100000010988609489e+01,1.191411230608114928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567129980143801049e+01,6.631325894844104596e+02,4.659571445189754080e-01,1.100000010988609489e+01,1.191265245206577211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567220889233801984e+01,6.631425894773149139e+02,4.659690571686099236e-01,1.100000010988609489e+01,1.191119259805039493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567311798323802918e+01,6.631525894702210735e+02,4.659809683583914230e-01,1.100000010988609489e+01,1.190973274403501776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567402707413803853e+01,6.631625894631289384e+02,4.659928780883199617e-01,1.100000010988609489e+01,1.190827289001964058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567493616503804787e+01,6.631725894560386223e+02,4.660047863583955396e-01,1.100000010988609489e+01,1.190681303600426340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567584525593805722e+01,6.631825894489500115e+02,4.660166931686181013e-01,1.100000010988609489e+01,1.190535318198888623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567675434683806657e+01,6.631925894418631060e+02,4.660285985189877023e-01,1.100000010988609489e+01,1.190389332797350905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567766343773807591e+01,6.632025894347780195e+02,4.660405024095043425e-01,1.100000010988609489e+01,1.190243347395813188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567857252863808526e+01,6.632125894276946383e+02,4.660524048401679664e-01,1.100000010988609489e+01,1.190097361994275470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.567948161953809461e+01,6.632225894206129624e+02,4.660643058109786296e-01,1.100000010988609489e+01,1.189951376592737753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568039071043810395e+01,6.632325894135329918e+02,4.660762053219362766e-01,1.100000010988609489e+01,1.189805391191200035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568129980133811330e+01,6.632425894064548402e+02,4.660881033730409628e-01,1.100000010988609489e+01,1.189659405789662318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568220889223812264e+01,6.632525893993783939e+02,4.660999999642926883e-01,1.100000010988609489e+01,1.189513420388124600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568311798313813199e+01,6.632625893923036529e+02,4.661118950956913976e-01,1.100000010988609489e+01,1.189367434986586883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568402707403814134e+01,6.632725893852307308e+02,4.661237887672371460e-01,1.100000010988609489e+01,1.189221449585049165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568493616493815068e+01,6.632825893781595141e+02,4.661356809789299338e-01,1.100000010988609489e+01,1.189075464183511448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568584525583816003e+01,6.632925893710900027e+02,4.661475717307697053e-01,1.100000010988609489e+01,1.188929478781973730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568675434673816937e+01,6.633025893640221966e+02,4.661594610227565161e-01,1.100000010988609489e+01,1.188783493380436013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568766343763817872e+01,6.633125893569562095e+02,4.661713488548903106e-01,1.100000010988609489e+01,1.188637507978898295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568857252853818807e+01,6.633225893498919277e+02,4.661832352271711444e-01,1.100000010988609489e+01,1.188491522577360578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.568948161943819741e+01,6.633325893428293512e+02,4.661951201395989619e-01,1.100000010988609489e+01,1.188345537175822860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569039071033820676e+01,6.633425893357684799e+02,4.662070035921738187e-01,1.100000010988609489e+01,1.188199551774285143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569129980123821611e+01,6.633525893287094277e+02,4.662188855848957147e-01,1.100000010988609489e+01,1.188053566372747425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569220889213822545e+01,6.633625893216520808e+02,4.662307661177645945e-01,1.100000010988609489e+01,1.187907580971209708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569311798303823480e+01,6.633725893145964392e+02,4.662426451907805136e-01,1.100000010988609489e+01,1.187761595569671990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569402707393824414e+01,6.633825893075425029e+02,4.662545228039434164e-01,1.100000010988609489e+01,1.187615610168134272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569493616483825349e+01,6.633925893004903855e+02,4.662663989572533585e-01,1.100000010988609489e+01,1.187469624766596555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569584525573826284e+01,6.634025892934399735e+02,4.662782736507102843e-01,1.100000010988609489e+01,1.187323639365058837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569675434663827218e+01,6.634125892863912668e+02,4.662901468843142494e-01,1.100000010988609489e+01,1.187177653963521120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569766343753828153e+01,6.634225892793442654e+02,4.663020186580651982e-01,1.100000010988609489e+01,1.187031668561983402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569857252843829087e+01,6.634325892722990829e+02,4.663138889719631863e-01,1.100000010988609489e+01,1.186885683160445685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.569948161933830022e+01,6.634425892652556058e+02,4.663257578260081582e-01,1.100000010988609489e+01,1.186739697758907967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570039071023830957e+01,6.634525892582138340e+02,4.663376252202001693e-01,1.100000010988609489e+01,1.186593712357370250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570129980113831891e+01,6.634625892511737675e+02,4.663494911545392196e-01,1.100000010988609489e+01,1.186447726955832532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570220889203832826e+01,6.634725892441355199e+02,4.663613556290252538e-01,1.100000010988609489e+01,1.186301741554294815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570311798293833760e+01,6.634825892370989777e+02,4.663732186436583271e-01,1.100000010988609489e+01,1.186155756152757097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570402707383834695e+01,6.634925892300641408e+02,4.663850801984383843e-01,1.100000010988609489e+01,1.186009770751219380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570493616473835630e+01,6.635025892230310092e+02,4.663969402933654806e-01,1.100000010988609489e+01,1.185863785349681662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570584525563836564e+01,6.635125892159996965e+02,4.664087989284395608e-01,1.100000010988609489e+01,1.185717799948143945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570675434653837499e+01,6.635225892089700892e+02,4.664206561036606802e-01,1.100000010988609489e+01,1.185571814546606227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570766343743838434e+01,6.635325892019421872e+02,4.664325118190287833e-01,1.100000010988609489e+01,1.185425829145068510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570857252833839368e+01,6.635425891949159904e+02,4.664443660745439257e-01,1.100000010988609489e+01,1.185279843743530792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.570948161923840303e+01,6.635525891878914990e+02,4.664562188702060519e-01,1.100000010988609489e+01,1.185133858341993075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571039071013841237e+01,6.635625891808688266e+02,4.664680702060151618e-01,1.100000010988609489e+01,1.184987872940455357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571129980103842172e+01,6.635725891738478595e+02,4.664799200819713110e-01,1.100000010988609489e+01,1.184841887538917640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571220889193843107e+01,6.635825891668285976e+02,4.664917684980744439e-01,1.100000010988609489e+01,1.184695902137379922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571311798283844041e+01,6.635925891598110411e+02,4.665036154543246161e-01,1.100000010988609489e+01,1.184549916735842204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571402707373844976e+01,6.636025891527953036e+02,4.665154609507217720e-01,1.100000010988609489e+01,1.184403931334304487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571493616463845910e+01,6.636125891457812713e+02,4.665273049872659672e-01,1.100000010988609489e+01,1.184257945932766769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571584525553846845e+01,6.636225891387689444e+02,4.665391475639571461e-01,1.100000010988609489e+01,1.184111960531229052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571675434643847780e+01,6.636325891317583228e+02,4.665509886807953643e-01,1.100000010988609489e+01,1.183965975129691334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571766343733848714e+01,6.636425891247494064e+02,4.665628283377805663e-01,1.100000010988609489e+01,1.183819989728153617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571857252823849649e+01,6.636525891177423091e+02,4.665746665349128075e-01,1.100000010988609489e+01,1.183674004326615899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.571948161913850583e+01,6.636625891107369171e+02,4.665865032721920325e-01,1.100000010988609489e+01,1.183528018925078182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572039071003851518e+01,6.636725891037332303e+02,4.665983385496182412e-01,1.100000010988609489e+01,1.183382033523540464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572129980093852453e+01,6.636825890967312489e+02,4.666101723671914892e-01,1.100000010988609489e+01,1.183236048122002747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572220889183853387e+01,6.636925890897309728e+02,4.666220047249117209e-01,1.100000010988609489e+01,1.183090062720465029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572311798273854322e+01,6.637025890827325156e+02,4.666338356227789919e-01,1.100000010988609489e+01,1.182944077318927312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572402707363855257e+01,6.637125890757357638e+02,4.666456650607932466e-01,1.100000010988609489e+01,1.182798091917389594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572493616453856191e+01,6.637225890687407173e+02,4.666574930389544851e-01,1.100000010988609489e+01,1.182652106515851877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572584525543857126e+01,6.637325890617473760e+02,4.666693195572627628e-01,1.100000010988609489e+01,1.182506121114314159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572675434633858060e+01,6.637425890547557401e+02,4.666811446157180243e-01,1.100000010988609489e+01,1.182360135712776442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572766343723858995e+01,6.637525890477658095e+02,4.666929682143203251e-01,1.100000010988609489e+01,1.182214150311238724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572857252813859930e+01,6.637625890407776978e+02,4.667047903530696096e-01,1.100000010988609489e+01,1.182068164909701007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.572948161903860864e+01,6.637725890337912915e+02,4.667166110319658778e-01,1.100000010988609489e+01,1.181922179508163289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573039070993861799e+01,6.637825890268065905e+02,4.667284302510091853e-01,1.100000010988609489e+01,1.181776194106625572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573129980083862733e+01,6.637925890198235948e+02,4.667402480101994766e-01,1.100000010988609489e+01,1.181630208705087854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573220889173863668e+01,6.638025890128423043e+02,4.667520643095367516e-01,1.100000010988609489e+01,1.181484223303550136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573311798263864603e+01,6.638125890058628329e+02,4.667638791490210659e-01,1.100000010988609489e+01,1.181338237902012419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573402707353865537e+01,6.638225889988850668e+02,4.667756925286523639e-01,1.100000010988609489e+01,1.181192252500474701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573493616443866472e+01,6.638325889919090059e+02,4.667875044484306457e-01,1.100000010988609489e+01,1.181046267098936984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573584525533867406e+01,6.638425889849346504e+02,4.667993149083559667e-01,1.100000010988609489e+01,1.180900281697399266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573675434623868341e+01,6.638525889779620002e+02,4.668111239084282715e-01,1.100000010988609489e+01,1.180754296295861549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573766343713869276e+01,6.638625889709910552e+02,4.668229314486476156e-01,1.100000010988609489e+01,1.180608310894323831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573857252803870210e+01,6.638725889640219293e+02,4.668347375290139434e-01,1.100000010988609489e+01,1.180462325492786114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.573948161893871145e+01,6.638825889570545087e+02,4.668465421495272549e-01,1.100000010988609489e+01,1.180316340091248396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574039070983872080e+01,6.638925889500887934e+02,4.668583453101876057e-01,1.100000010988609489e+01,1.180170354689710679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574129980073873014e+01,6.639025889431247833e+02,4.668701470109949403e-01,1.100000010988609489e+01,1.180024369288172961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574220889163873949e+01,6.639125889361624786e+02,4.668819472519492586e-01,1.100000010988609489e+01,1.179878383886635244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574311798253874883e+01,6.639225889292018792e+02,4.668937460330505607e-01,1.100000010988609489e+01,1.179732398485097526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574402707343875818e+01,6.639325889222429851e+02,4.669055433542989020e-01,1.100000010988609489e+01,1.179586413083559809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574493616433876753e+01,6.639425889152859099e+02,4.669173392156942271e-01,1.100000010988609489e+01,1.179440427682022091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574584525523877687e+01,6.639525889083305401e+02,4.669291336172365359e-01,1.100000010988609489e+01,1.179294442280484374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574675434613878622e+01,6.639625889013768756e+02,4.669409265589258839e-01,1.100000010988609489e+01,1.179148456878946656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574766343703879556e+01,6.639725888944249164e+02,4.669527180407622158e-01,1.100000010988609489e+01,1.179002471477408939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574857252793880491e+01,6.639825888874746624e+02,4.669645080627455314e-01,1.100000010988609489e+01,1.178856486075871221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.574948161883881426e+01,6.639925888805261138e+02,4.669762966248758307e-01,1.100000010988609489e+01,1.178710500674333504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575039070973882360e+01,6.640025888735792705e+02,4.669880837271531693e-01,1.100000010988609489e+01,1.178564515272795786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575129980063883295e+01,6.640125888666342462e+02,4.669998693695774916e-01,1.100000010988609489e+01,1.178418529871258068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575220889153884229e+01,6.640225888596909272e+02,4.670116535521487977e-01,1.100000010988609489e+01,1.178272544469720351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575311798243885164e+01,6.640325888527493134e+02,4.670234362748671431e-01,1.100000010988609489e+01,1.178126559068182633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575402707333886099e+01,6.640425888458094050e+02,4.670352175377324722e-01,1.100000010988609489e+01,1.177980573666644916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575493616423887033e+01,6.640525888388712019e+02,4.670469973407447850e-01,1.100000010988609489e+01,1.177834588265107198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575584525513887968e+01,6.640625888319347041e+02,4.670587756839040816e-01,1.100000010988609489e+01,1.177688602863569481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575675434603888903e+01,6.640725888249999116e+02,4.670705525672104175e-01,1.100000010988609489e+01,1.177542617462031763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575766343693889837e+01,6.640825888180668244e+02,4.670823279906637371e-01,1.100000010988609489e+01,1.177396632060494046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575857252783890772e+01,6.640925888111355562e+02,4.670941019542640404e-01,1.100000010988609489e+01,1.177250646658956328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.575948161873891706e+01,6.641025888042059933e+02,4.671058744580113276e-01,1.100000010988609489e+01,1.177104661257418611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576039070963892641e+01,6.641125887972781356e+02,4.671176455019055984e-01,1.100000010988609489e+01,1.176958675855880893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576129980053893576e+01,6.641225887903519833e+02,4.671294150859469085e-01,1.100000010988609489e+01,1.176812690454343176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576220889143894510e+01,6.641325887834275363e+02,4.671411832101352024e-01,1.100000010988609489e+01,1.176666705052805458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576311798233895445e+01,6.641425887765047946e+02,4.671529498744704800e-01,1.100000010988609489e+01,1.176520719651267741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576402707323896379e+01,6.641525887695837582e+02,4.671647150789527414e-01,1.100000010988609489e+01,1.176374734249730023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576493616413897314e+01,6.641625887626644271e+02,4.671764788235819865e-01,1.100000010988609489e+01,1.176228748848192306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576584525503898249e+01,6.641725887557468013e+02,4.671882411083582709e-01,1.100000010988609489e+01,1.176082763446654588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576675434593899183e+01,6.641825887488309945e+02,4.672000019332815390e-01,1.100000010988609489e+01,1.175936778045116871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576766343683900118e+01,6.641925887419168930e+02,4.672117612983517909e-01,1.100000010988609489e+01,1.175790792643579153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576857252773901052e+01,6.642025887350044968e+02,4.672235192035690265e-01,1.100000010988609489e+01,1.175644807242041436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.576948161863901987e+01,6.642125887280938059e+02,4.672352756489332459e-01,1.100000010988609489e+01,1.175498821840503718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577039070953902922e+01,6.642225887211848203e+02,4.672470306344445046e-01,1.100000010988609489e+01,1.175352836438966000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577129980043903856e+01,6.642325887142775400e+02,4.672587841601027470e-01,1.100000010988609489e+01,1.175206851037428283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577220889133904791e+01,6.642425887073719650e+02,4.672705362259079731e-01,1.100000010988609489e+01,1.175060865635890565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577311798223905726e+01,6.642525887004680953e+02,4.672822868318601830e-01,1.100000010988609489e+01,1.174914880234352848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577402707313906660e+01,6.642625886935659310e+02,4.672940359779593766e-01,1.100000010988609489e+01,1.174768894832815130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577493616403907595e+01,6.642725886866654719e+02,4.673057836642055540e-01,1.100000010988609489e+01,1.174622909431277413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577584525493908529e+01,6.642825886797668318e+02,4.673175298905987707e-01,1.100000010988609489e+01,1.174476924029739695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577675434583909464e+01,6.642925886728698970e+02,4.673292746571389711e-01,1.100000010988609489e+01,1.174330938628201978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577766343673910399e+01,6.643025886659746675e+02,4.673410179638261552e-01,1.100000010988609489e+01,1.174184953226664260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577857252763911333e+01,6.643125886590811433e+02,4.673527598106603231e-01,1.100000010988609489e+01,1.174038967825126543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.577948161853912268e+01,6.643225886521893244e+02,4.673645001976414748e-01,1.100000010988609489e+01,1.173892982423588825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578039070943913202e+01,6.643325886452992108e+02,4.673762391247696102e-01,1.100000010988609489e+01,1.173746997022051108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578129980033914137e+01,6.643425886384108026e+02,4.673879765920447293e-01,1.100000010988609489e+01,1.173601011620513390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578220889123915072e+01,6.643525886315240996e+02,4.673997125994668322e-01,1.100000010988609489e+01,1.173455026218975673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578311798213916006e+01,6.643625886246391019e+02,4.674114471470359744e-01,1.100000010988609489e+01,1.173309040817437955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578402707303916941e+01,6.643725886177558095e+02,4.674231802347521003e-01,1.100000010988609489e+01,1.173163055415900238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578493616393917875e+01,6.643825886108742225e+02,4.674349118626152100e-01,1.100000010988609489e+01,1.173017070014362520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578584525483918810e+01,6.643925886039943407e+02,4.674466420306253034e-01,1.100000010988609489e+01,1.172871084612824803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578675434573919745e+01,6.644025885971161642e+02,4.674583707387823805e-01,1.100000010988609489e+01,1.172725099211287085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578766343663920679e+01,6.644125885902396931e+02,4.674700979870864415e-01,1.100000010988609489e+01,1.172579113809749368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578857252753921614e+01,6.644225885833650409e+02,4.674818237755374861e-01,1.100000010988609489e+01,1.172433128408211650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.578948161843922549e+01,6.644325885764920940e+02,4.674935481041355145e-01,1.100000010988609489e+01,1.172287143006673932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579039070933923483e+01,6.644425885696208525e+02,4.675052709728805267e-01,1.100000010988609489e+01,1.172141157605136215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579129980023924418e+01,6.644525885627513162e+02,4.675169923817725226e-01,1.100000010988609489e+01,1.171995172203598497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579220889113925352e+01,6.644625885558834852e+02,4.675287123308115023e-01,1.100000010988609489e+01,1.171849186802060780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579311798203926287e+01,6.644725885490173596e+02,4.675404308199974657e-01,1.100000010988609489e+01,1.171703201400523062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579402707293927222e+01,6.644825885421529392e+02,4.675521478493304683e-01,1.100000010988609489e+01,1.171557215998985345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579493616383928156e+01,6.644925885352902242e+02,4.675638634188104548e-01,1.100000010988609489e+01,1.171411230597447627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579584525473929091e+01,6.645025885284292144e+02,4.675755775284374249e-01,1.100000010988609489e+01,1.171265245195909910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579675434563930025e+01,6.645125885215699100e+02,4.675872901782113789e-01,1.100000010988609489e+01,1.171119259794372192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579766343653930960e+01,6.645225885147123108e+02,4.675990013681323165e-01,1.100000010988609489e+01,1.170973274392834475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579857252743931895e+01,6.645325885078564170e+02,4.676107110982002379e-01,1.100000010988609489e+01,1.170827288991296757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.579948161833932829e+01,6.645425885010022284e+02,4.676224193684151431e-01,1.100000010988609489e+01,1.170681303589759040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580039070923933764e+01,6.645525884941497452e+02,4.676341261787770320e-01,1.100000010988609489e+01,1.170535318188221322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580129980013934698e+01,6.645625884872989673e+02,4.676458315292859047e-01,1.100000010988609489e+01,1.170389332786683605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580220889103935633e+01,6.645725884804498946e+02,4.676575354199417611e-01,1.100000010988609489e+01,1.170243347385145887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580311798193936568e+01,6.645825884736025273e+02,4.676692378507446013e-01,1.100000010988609489e+01,1.170097361983608170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580402707283937502e+01,6.645925884667568653e+02,4.676809388216944252e-01,1.100000010988609489e+01,1.169951376582070452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580493616373938437e+01,6.646025884599129085e+02,4.676926383327912329e-01,1.100000010988609489e+01,1.169805391180532735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580584525463939372e+01,6.646125884530706571e+02,4.677043363840350243e-01,1.100000010988609489e+01,1.169659405778995017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580675434553940306e+01,6.646225884462301110e+02,4.677160329754257995e-01,1.100000010988609489e+01,1.169513420377457300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580766343643941241e+01,6.646325884393912702e+02,4.677277281069635584e-01,1.100000010988609489e+01,1.169367434975919582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580857252733942175e+01,6.646425884325541347e+02,4.677394217786483011e-01,1.100000010988609489e+01,1.169221449574381864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.580948161823943110e+01,6.646525884257187045e+02,4.677511139904800275e-01,1.100000010988609489e+01,1.169075464172844147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581039070913944045e+01,6.646625884188849795e+02,4.677628047424587376e-01,1.100000010988609489e+01,1.168929478771306429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581129980003944979e+01,6.646725884120529599e+02,4.677744940345844316e-01,1.100000010988609489e+01,1.168783493369768712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581220889093945914e+01,6.646825884052226456e+02,4.677861818668571092e-01,1.100000010988609489e+01,1.168637507968230994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581311798183946848e+01,6.646925883983940366e+02,4.677978682392767706e-01,1.100000010988609489e+01,1.168491522566693277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581402707273947783e+01,6.647025883915671329e+02,4.678095531518434158e-01,1.100000010988609489e+01,1.168345537165155559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581493616363948718e+01,6.647125883847419345e+02,4.678212366045570447e-01,1.100000010988609489e+01,1.168199551763617842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581584525453949652e+01,6.647225883779184414e+02,4.678329185974176574e-01,1.100000010988609489e+01,1.168053566362080124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581675434543950587e+01,6.647325883710966536e+02,4.678445991304251983e-01,1.100000010988609489e+01,1.167907580960542407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581766343633951521e+01,6.647425883642765712e+02,4.678562782035797230e-01,1.100000010988609489e+01,1.167761595559004689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581857252723952456e+01,6.647525883574581940e+02,4.678679558168812314e-01,1.100000010988609489e+01,1.167615610157466972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.581948161813953391e+01,6.647625883506415221e+02,4.678796319703297235e-01,1.100000010988609489e+01,1.167469624755929254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582039070903954325e+01,6.647725883438265555e+02,4.678913066639251994e-01,1.100000010988609489e+01,1.167323639354391537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582129979993955260e+01,6.647825883370132942e+02,4.679029798976676591e-01,1.100000010988609489e+01,1.167177653952853819e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582220889083956195e+01,6.647925883302017382e+02,4.679146516715571025e-01,1.100000010988609489e+01,1.167031668551316102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582311798173957129e+01,6.648025883233918876e+02,4.679263219855935296e-01,1.100000010988609489e+01,1.166885683149778384e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582402707263958064e+01,6.648125883165837422e+02,4.679379908397769405e-01,1.100000010988609489e+01,1.166739697748240667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582493616353958998e+01,6.648225883097773021e+02,4.679496582341073352e-01,1.100000010988609489e+01,1.166593712346702949e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582584525443959933e+01,6.648325883029725674e+02,4.679613241685847136e-01,1.100000010988609489e+01,1.166447726945165232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582675434533960868e+01,6.648425882961695379e+02,4.679729886432090757e-01,1.100000010988609489e+01,1.166301741543627514e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582766343623961802e+01,6.648525882893682137e+02,4.679846516579803661e-01,1.100000010988609489e+01,1.166155756142089796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582857252713962737e+01,6.648625882825685949e+02,4.679963132128986403e-01,1.100000010988609489e+01,1.166009770740552079e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.582948161803963671e+01,6.648725882757706813e+02,4.680079733079638982e-01,1.100000010988609489e+01,1.165863785339014361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583039070893964606e+01,6.648825882689744731e+02,4.680196319431761398e-01,1.100000010988609489e+01,1.165717799937476644e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583129979983965541e+01,6.648925882621799701e+02,4.680312891185353652e-01,1.100000010988609489e+01,1.165571814535938926e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583220889073966475e+01,6.649025882553871725e+02,4.680429448340415743e-01,1.100000010988609489e+01,1.165425829134401209e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583311798163967410e+01,6.649125882485960801e+02,4.680545990896947672e-01,1.100000010988609489e+01,1.165279843732863491e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583402707253968345e+01,6.649225882418066931e+02,4.680662518854949439e-01,1.100000010988609489e+01,1.165133858331325774e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583493616343969279e+01,6.649325882350190113e+02,4.680779032214420488e-01,1.100000010988609489e+01,1.164987872929788056e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583584525433970214e+01,6.649425882282330349e+02,4.680895530975361374e-01,1.100000010988609489e+01,1.164841887528250339e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583675434523971148e+01,6.649525882214487638e+02,4.681012015137772098e-01,1.100000010988609489e+01,1.164695902126712621e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583766343613972083e+01,6.649625882146661979e+02,4.681128484701652659e-01,1.100000010988609489e+01,1.164549916725174904e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583857252703973018e+01,6.649725882078853374e+02,4.681244939667003058e-01,1.100000010988609489e+01,1.164403931323637186e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.583948161793973952e+01,6.649825882011061822e+02,4.681361380033823294e-01,1.100000010988609489e+01,1.164257945922099469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584039070883974887e+01,6.649925881943287322e+02,4.681477805802112813e-01,1.100000010988609489e+01,1.164111960520561751e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584129979973975821e+01,6.650025881875529876e+02,4.681594216971872169e-01,1.100000010988609489e+01,1.163965975119024034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584220889063976756e+01,6.650125881807789483e+02,4.681710613543101362e-01,1.100000010988609489e+01,1.163819989717486316e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584311798153977691e+01,6.650225881740066143e+02,4.681826995515800394e-01,1.100000010988609489e+01,1.163674004315948599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584402707243978625e+01,6.650325881672359856e+02,4.681943362889969262e-01,1.100000010988609489e+01,1.163528018914410881e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584493616333979560e+01,6.650425881604669485e+02,4.682059715665607413e-01,1.100000010988609489e+01,1.163382033512873164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584584525423980494e+01,6.650525881536996167e+02,4.682176053842715402e-01,1.100000010988609489e+01,1.163236048111335446e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584675434513981429e+01,6.650625881469339902e+02,4.682292377421293228e-01,1.100000010988609489e+01,1.163090062709797728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584766343603982364e+01,6.650725881401700690e+02,4.682408686401340892e-01,1.100000010988609489e+01,1.162944077308260011e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584857252693983298e+01,6.650825881334078531e+02,4.682524980782858393e-01,1.100000010988609489e+01,1.162798091906722293e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.584948161783984233e+01,6.650925881266473425e+02,4.682641260565845176e-01,1.100000010988609489e+01,1.162652106505184576e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585039070873985168e+01,6.651025881198885372e+02,4.682757525750301797e-01,1.100000010988609489e+01,1.162506121103646858e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585129979963986102e+01,6.651125881131314372e+02,4.682873776336228255e-01,1.100000010988609489e+01,1.162360135702109141e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585220889053987037e+01,6.651225881063760426e+02,4.682990012323624551e-01,1.100000010988609489e+01,1.162214150300571423e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585311798143987971e+01,6.651325880996223532e+02,4.683106233712490685e-01,1.100000010988609489e+01,1.162068164899033706e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585402707233988906e+01,6.651425880928703691e+02,4.683222440502826101e-01,1.100000010988609489e+01,1.161922179497495988e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585493616323989841e+01,6.651525880861200903e+02,4.683338632694631354e-01,1.100000010988609489e+01,1.161776194095958271e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585584525413990775e+01,6.651625880793715169e+02,4.683454810287906445e-01,1.100000010988609489e+01,1.161630208694420553e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585675434503991710e+01,6.651725880726246487e+02,4.683570973282651373e-01,1.100000010988609489e+01,1.161484223292882836e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585766343593992644e+01,6.651825880658793722e+02,4.683687121678865584e-01,1.100000010988609489e+01,1.161338237891345118e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585857252683993579e+01,6.651925880591358009e+02,4.683803255476549632e-01,1.100000010988609489e+01,1.161192252489807401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.585948161773994514e+01,6.652025880523939350e+02,4.683919374675703517e-01,1.100000010988609489e+01,1.161046267088269683e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586039070863995448e+01,6.652125880456537743e+02,4.684035479276326686e-01,1.100000010988609489e+01,1.160900281686731966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586129979953996383e+01,6.652225880389153190e+02,4.684151569278419691e-01,1.100000010988609489e+01,1.160754296285194248e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586220889043997317e+01,6.652325880321785689e+02,4.684267644681982534e-01,1.100000010988609489e+01,1.160608310883656531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586311798133998252e+01,6.652425880254435242e+02,4.684383705487015215e-01,1.100000010988609489e+01,1.160462325482118813e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586402707223999187e+01,6.652525880187101848e+02,4.684499751693517178e-01,1.100000010988609489e+01,1.160316340080581096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586493616314000121e+01,6.652625880119785506e+02,4.684615783301488978e-01,1.100000010988609489e+01,1.160170354679043378e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586584525404001056e+01,6.652725880052486218e+02,4.684731800310930616e-01,1.100000010988609489e+01,1.160024369277505660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586675434494001991e+01,6.652825879985202846e+02,4.684847802721841536e-01,1.100000010988609489e+01,1.159878383875967943e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586766343584002925e+01,6.652925879917936527e+02,4.684963790534222294e-01,1.100000010988609489e+01,1.159732398474430225e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586857252674003860e+01,6.653025879850687261e+02,4.685079763748072890e-01,1.100000010988609489e+01,1.159586413072892508e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.586948161764004794e+01,6.653125879783455048e+02,4.685195722363393322e-01,1.100000010988609489e+01,1.159440427671354790e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587039070854005729e+01,6.653225879716239888e+02,4.685311666380183038e-01,1.100000010988609489e+01,1.159294442269817073e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587129979944006664e+01,6.653325879649041781e+02,4.685427595798442590e-01,1.100000010988609489e+01,1.159148456868279355e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587220889034007598e+01,6.653425879581860727e+02,4.685543510618171981e-01,1.100000010988609489e+01,1.159002471466741638e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587311798124008533e+01,6.653525879514696726e+02,4.685659410839370653e-01,1.100000010988609489e+01,1.158856486065203920e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587402707214009467e+01,6.653625879447549778e+02,4.685775296462039163e-01,1.100000010988609489e+01,1.158710500663666203e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587493616304010402e+01,6.653725879380418746e+02,4.685891167486177511e-01,1.100000010988609489e+01,1.158564515262128485e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587584525394011337e+01,6.653825879313304767e+02,4.686007023911785141e-01,1.100000010988609489e+01,1.158418529860590768e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587675434484012271e+01,6.653925879246207842e+02,4.686122865738862608e-01,1.100000010988609489e+01,1.158272544459053050e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587766343574013206e+01,6.654025879179127969e+02,4.686238692967409358e-01,1.100000010988609489e+01,1.158126559057515333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587857252664014140e+01,6.654125879112065149e+02,4.686354505597425946e-01,1.100000010988609489e+01,1.157980573655977615e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.587948161754015075e+01,6.654225879045019383e+02,4.686470303628912371e-01,1.100000010988609489e+01,1.157834588254439898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588039070844016010e+01,6.654325878977990669e+02,4.686586087061868078e-01,1.100000010988609489e+01,1.157688602852902180e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588129979934016944e+01,6.654425878910979009e+02,4.686701855896293623e-01,1.100000010988609489e+01,1.157542617451364463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588220889024017879e+01,6.654525878843983264e+02,4.686817610132189005e-01,1.100000010988609489e+01,1.157396632049826745e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588311798114018814e+01,6.654625878777004573e+02,4.686933349769553669e-01,1.100000010988609489e+01,1.157250646648289027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588402707204019748e+01,6.654725878710042934e+02,4.687049074808388172e-01,1.100000010988609489e+01,1.157104661246751310e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588493616294020683e+01,6.654825878643098349e+02,4.687164785248691956e-01,1.100000010988609489e+01,1.156958675845213592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588584525384021617e+01,6.654925878576170817e+02,4.687280481090465578e-01,1.100000010988609489e+01,1.156812690443675875e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588675434474022552e+01,6.655025878509260338e+02,4.687396162333709038e-01,1.100000010988609489e+01,1.156666705042138157e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588766343564023487e+01,6.655125878442366911e+02,4.687511828978421780e-01,1.100000010988609489e+01,1.156520719640600440e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588857252654024421e+01,6.655225878375489401e+02,4.687627481024604359e-01,1.100000010988609489e+01,1.156374734239062722e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.588948161744025356e+01,6.655325878308628944e+02,4.687743118472256221e-01,1.100000010988609489e+01,1.156228748837525005e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589039070834026290e+01,6.655425878241785540e+02,4.687858741321377920e-01,1.100000010988609489e+01,1.156082763435987287e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589129979924027225e+01,6.655525878174959189e+02,4.687974349571969457e-01,1.100000010988609489e+01,1.155936778034449570e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589220889014028160e+01,6.655625878108149891e+02,4.688089943224030276e-01,1.100000010988609489e+01,1.155790792632911852e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589311798104029094e+01,6.655725878041357646e+02,4.688205522277560933e-01,1.100000010988609489e+01,1.155644807231374135e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589402707194030029e+01,6.655825877974582454e+02,4.688321086732560872e-01,1.100000010988609489e+01,1.155498821829836417e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589493616284030963e+01,6.655925877907823178e+02,4.688436636589030648e-01,1.100000010988609489e+01,1.155352836428298700e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589584525374031898e+01,6.656025877841080955e+02,4.688552171846969707e-01,1.100000010988609489e+01,1.155206851026760982e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589675434464032833e+01,6.656125877774355786e+02,4.688667692506378604e-01,1.100000010988609489e+01,1.155060865625223265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589766343554033767e+01,6.656225877707647669e+02,4.688783198567257338e-01,1.100000010988609489e+01,1.154914880223685547e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589857252644034702e+01,6.656325877640956605e+02,4.688898690029605354e-01,1.100000010988609489e+01,1.154768894822147830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.589948161734035637e+01,6.656425877574282595e+02,4.689014166893423208e-01,1.100000010988609489e+01,1.154622909420610112e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590039070824036571e+01,6.656525877507624500e+02,4.689129629158710344e-01,1.100000010988609489e+01,1.154476924019072395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590129979914037506e+01,6.656625877440983459e+02,4.689245076825467318e-01,1.100000010988609489e+01,1.154330938617534677e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590220889004038440e+01,6.656725877374359470e+02,4.689360509893693574e-01,1.100000010988609489e+01,1.154184953215996959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590311798094039375e+01,6.656825877307752535e+02,4.689475928363389667e-01,1.100000010988609489e+01,1.154038967814459242e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590402707184040310e+01,6.656925877241162652e+02,4.689591332234555043e-01,1.100000010988609489e+01,1.153892982412921524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590493616274041244e+01,6.657025877174588686e+02,4.689706721507190257e-01,1.100000010988609489e+01,1.153746997011383807e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590584525364042179e+01,6.657125877108031773e+02,4.689822096181294753e-01,1.100000010988609489e+01,1.153601011609846089e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590675434454043113e+01,6.657225877041491913e+02,4.689937456256869086e-01,1.100000010988609489e+01,1.153455026208308372e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590766343544044048e+01,6.657325876974969106e+02,4.690052801733912702e-01,1.100000010988609489e+01,1.153309040806770654e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590857252634044983e+01,6.657425876908463351e+02,4.690168132612426155e-01,1.100000010988609489e+01,1.153163055405232937e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.590948161724045917e+01,6.657525876841974650e+02,4.690283448892408891e-01,1.100000010988609489e+01,1.153017070003695219e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591039070814046852e+01,6.657625876775501865e+02,4.690398750573861464e-01,1.100000010988609489e+01,1.152871084602157502e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591129979904047786e+01,6.657725876709046133e+02,4.690514037656783319e-01,1.100000010988609489e+01,1.152725099200619784e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591220888994048721e+01,6.657825876642607454e+02,4.690629310141175012e-01,1.100000010988609489e+01,1.152579113799082067e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591311798084049656e+01,6.657925876576185829e+02,4.690744568027035988e-01,1.100000010988609489e+01,1.152433128397544349e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591402707174050590e+01,6.658025876509781256e+02,4.690859811314366801e-01,1.100000010988609489e+01,1.152287142996006632e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591493616264051525e+01,6.658125876443392599e+02,4.690975040003166896e-01,1.100000010988609489e+01,1.152141157594468914e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591584525354052460e+01,6.658225876377020995e+02,4.691090254093436829e-01,1.100000010988609489e+01,1.151995172192931197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591675434444053394e+01,6.658325876310666445e+02,4.691205453585176044e-01,1.100000010988609489e+01,1.151849186791393479e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591766343534054329e+01,6.658425876244328947e+02,4.691320638478384542e-01,1.100000010988609489e+01,1.151703201389855762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591857252624055263e+01,6.658525876178008502e+02,4.691435808773062877e-01,1.100000010988609489e+01,1.151557215988318044e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.591948161714056198e+01,6.658625876111703974e+02,4.691550964469210494e-01,1.100000010988609489e+01,1.151411230586780327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592039070804057133e+01,6.658725876045416499e+02,4.691666105566827949e-01,1.100000010988609489e+01,1.151265245185242609e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592129979894058067e+01,6.658825875979146076e+02,4.691781232065914686e-01,1.100000010988609489e+01,1.151119259783704891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592220888984059002e+01,6.658925875912892707e+02,4.691896343966471261e-01,1.100000010988609489e+01,1.150973274382167174e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592311798074059936e+01,6.659025875846655254e+02,4.692011441268497118e-01,1.100000010988609489e+01,1.150827288980629456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592402707164060871e+01,6.659125875780434853e+02,4.692126523971992258e-01,1.100000010988609489e+01,1.150681303579091739e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592493616254061806e+01,6.659225875714231506e+02,4.692241592076957235e-01,1.100000010988609489e+01,1.150535318177554021e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592584525344062740e+01,6.659325875648045212e+02,4.692356645583391495e-01,1.100000010988609489e+01,1.150389332776016304e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592675434434063675e+01,6.659425875581875971e+02,4.692471684491295592e-01,1.100000010988609489e+01,1.150243347374478586e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592766343524064609e+01,6.659525875515722646e+02,4.692586708800668971e-01,1.100000010988609489e+01,1.150097361972940869e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592857252614065544e+01,6.659625875449586374e+02,4.692701718511512188e-01,1.100000010988609489e+01,1.149951376571403151e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.592948161704066479e+01,6.659725875383467155e+02,4.692816713623824687e-01,1.100000010988609489e+01,1.149805391169865434e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593039070794067413e+01,6.659825875317364989e+02,4.692931694137606469e-01,1.100000010988609489e+01,1.149659405768327716e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593129979884068348e+01,6.659925875251278740e+02,4.693046660052858088e-01,1.100000010988609489e+01,1.149513420366789999e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593220888974069283e+01,6.660025875185209543e+02,4.693161611369578989e-01,1.100000010988609489e+01,1.149367434965252281e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593311798064070217e+01,6.660125875119157399e+02,4.693276548087769173e-01,1.100000010988609489e+01,1.149221449563714564e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593402707154071152e+01,6.660225875053122309e+02,4.693391470207429195e-01,1.100000010988609489e+01,1.149075464162176846e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593493616244072086e+01,6.660325874987103134e+02,4.693506377728558498e-01,1.100000010988609489e+01,1.148929478760639129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593584525334073021e+01,6.660425874921101013e+02,4.693621270651157640e-01,1.100000010988609489e+01,1.148783493359101411e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593675434424073956e+01,6.660525874855115944e+02,4.693736148975226063e-01,1.100000010988609489e+01,1.148637507957563694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593766343514074890e+01,6.660625874789147929e+02,4.693851012700763770e-01,1.100000010988609489e+01,1.148491522556025976e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593857252604075825e+01,6.660725874723195830e+02,4.693965861827771313e-01,1.100000010988609489e+01,1.148345537154488259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.593948161694076759e+01,6.660825874657260783e+02,4.694080696356248139e-01,1.100000010988609489e+01,1.148199551752950541e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594039070784077694e+01,6.660925874591342790e+02,4.694195516286194247e-01,1.100000010988609489e+01,1.148053566351412823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594129979874078629e+01,6.661025874525441850e+02,4.694310321617610193e-01,1.100000010988609489e+01,1.147907580949875106e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594220888964079563e+01,6.661125874459556826e+02,4.694425112350495422e-01,1.100000010988609489e+01,1.147761595548337388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594311798054080498e+01,6.661225874393688855e+02,4.694539888484849932e-01,1.100000010988609489e+01,1.147615610146799671e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594402707144081432e+01,6.661325874327837937e+02,4.694654650020674280e-01,1.100000010988609489e+01,1.147469624745261953e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594493616234082367e+01,6.661425874262004072e+02,4.694769396957967911e-01,1.100000010988609489e+01,1.147323639343724236e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594584525324083302e+01,6.661525874196186123e+02,4.694884129296730824e-01,1.100000010988609489e+01,1.147177653942186518e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594675434414084236e+01,6.661625874130385228e+02,4.694998847036963574e-01,1.100000010988609489e+01,1.147031668540648801e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594766343504085171e+01,6.661725874064601385e+02,4.695113550178665607e-01,1.100000010988609489e+01,1.146885683139111083e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594857252594086106e+01,6.661825873998834595e+02,4.695228238721836922e-01,1.100000010988609489e+01,1.146739697737573366e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.594948161684087040e+01,6.661925873933083722e+02,4.695342912666477520e-01,1.100000010988609489e+01,1.146593712336035648e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595039070774087975e+01,6.662025873867349901e+02,4.695457572012587955e-01,1.100000010988609489e+01,1.146447726934497931e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595129979864088909e+01,6.662125873801633134e+02,4.695572216760167672e-01,1.100000010988609489e+01,1.146301741532960213e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595220888954089844e+01,6.662225873735932282e+02,4.695686846909216672e-01,1.100000010988609489e+01,1.146155756131422496e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595311798044090779e+01,6.662325873670248484e+02,4.695801462459735509e-01,1.100000010988609489e+01,1.146009770729884778e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595402707134091713e+01,6.662425873604581739e+02,4.695916063411723629e-01,1.100000010988609489e+01,1.145863785328347061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595493616224092648e+01,6.662525873538932046e+02,4.696030649765181031e-01,1.100000010988609489e+01,1.145717799926809343e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595584525314093582e+01,6.662625873473298270e+02,4.696145221520107715e-01,1.100000010988609489e+01,1.145571814525271626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595675434404094517e+01,6.662725873407681547e+02,4.696259778676504237e-01,1.100000010988609489e+01,1.145425829123733908e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595766343494095452e+01,6.662825873342081877e+02,4.696374321234370042e-01,1.100000010988609489e+01,1.145279843722196191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595857252584096386e+01,6.662925873276498123e+02,4.696488849193705128e-01,1.100000010988609489e+01,1.145133858320658473e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.595948161674097321e+01,6.663025873210931422e+02,4.696603362554509498e-01,1.100000010988609489e+01,1.144987872919120755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596039070764098255e+01,6.663125873145381775e+02,4.696717861316783704e-01,1.100000010988609489e+01,1.144841887517583038e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596129979854099190e+01,6.663225873079849180e+02,4.696832345480527193e-01,1.100000010988609489e+01,1.144695902116045320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596220888944100125e+01,6.663325873014332501e+02,4.696946815045739965e-01,1.100000010988609489e+01,1.144549916714507603e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596311798034101059e+01,6.663425872948832875e+02,4.697061270012422018e-01,1.100000010988609489e+01,1.144403931312969885e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596402707124101994e+01,6.663525872883350303e+02,4.697175710380573910e-01,1.100000010988609489e+01,1.144257945911432168e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596493616214102929e+01,6.663625872817883646e+02,4.697290136150195083e-01,1.100000010988609489e+01,1.144111960509894450e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596584525304103863e+01,6.663725872752434043e+02,4.697404547321285539e-01,1.100000010988609489e+01,1.143965975108356733e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596675434394104798e+01,6.663825872687001493e+02,4.697518943893845278e-01,1.100000010988609489e+01,1.143819989706819015e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596766343484105732e+01,6.663925872621584858e+02,4.697633325867874299e-01,1.100000010988609489e+01,1.143674004305281298e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596857252574106667e+01,6.664025872556185277e+02,4.697747693243373157e-01,1.100000010988609489e+01,1.143528018903743580e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.596948161664107602e+01,6.664125872490802749e+02,4.697862046020341298e-01,1.100000010988609489e+01,1.143382033502205863e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597039070754108536e+01,6.664225872425436137e+02,4.697976384198778721e-01,1.100000010988609489e+01,1.143236048100668145e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597129979844109471e+01,6.664325872360086578e+02,4.698090707778685426e-01,1.100000010988609489e+01,1.143090062699130428e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597220888934110405e+01,6.664425872294754072e+02,4.698205016760061414e-01,1.100000010988609489e+01,1.142944077297592710e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597311798024111340e+01,6.664525872229437482e+02,4.698319311142907240e-01,1.100000010988609489e+01,1.142798091896054993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597402707114112275e+01,6.664625872164137945e+02,4.698433590927222347e-01,1.100000010988609489e+01,1.142652106494517275e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597493616204113209e+01,6.664725872098855461e+02,4.698547856113006738e-01,1.100000010988609489e+01,1.142506121092979558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597584525294114144e+01,6.664825872033588894e+02,4.698662106700260410e-01,1.100000010988609489e+01,1.142360135691441840e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597675434384115079e+01,6.664925871968339379e+02,4.698776342688983365e-01,1.100000010988609489e+01,1.142214150289904123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597766343474116013e+01,6.665025871903106918e+02,4.698890564079175602e-01,1.100000010988609489e+01,1.142068164888366405e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597857252564116948e+01,6.665125871837890372e+02,4.699004770870837677e-01,1.100000010988609489e+01,1.141922179486828687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.597948161654117882e+01,6.665225871772690880e+02,4.699118963063969034e-01,1.100000010988609489e+01,1.141776194085290970e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598039070744118817e+01,6.665325871707508441e+02,4.699233140658569674e-01,1.100000010988609489e+01,1.141630208683753252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598129979834119752e+01,6.665425871642341917e+02,4.699347303654639596e-01,1.100000010988609489e+01,1.141484223282215535e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598220888924120686e+01,6.665525871577192447e+02,4.699461452052178800e-01,1.100000010988609489e+01,1.141338237880677817e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598311798014121621e+01,6.665625871512060030e+02,4.699575585851187287e-01,1.100000010988609489e+01,1.141192252479140100e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598402707104122555e+01,6.665725871446943529e+02,4.699689705051665056e-01,1.100000010988609489e+01,1.141046267077602382e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598493616194123490e+01,6.665825871381844081e+02,4.699803809653612108e-01,1.100000010988609489e+01,1.140900281676064665e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598584525284124425e+01,6.665925871316761686e+02,4.699917899657028997e-01,1.100000010988609489e+01,1.140754296274526947e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598675434374125359e+01,6.666025871251695207e+02,4.700031975061915168e-01,1.100000010988609489e+01,1.140608310872989230e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598766343464126294e+01,6.666125871186645782e+02,4.700146035868270622e-01,1.100000010988609489e+01,1.140462325471451512e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598857252554127228e+01,6.666225871121613409e+02,4.700260082076095358e-01,1.100000010988609489e+01,1.140316340069913795e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.598948161644128163e+01,6.666325871056596952e+02,4.700374113685389377e-01,1.100000010988609489e+01,1.140170354668376077e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599039070734129098e+01,6.666425870991597549e+02,4.700488130696152678e-01,1.100000010988609489e+01,1.140024369266838360e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599129979824130032e+01,6.666525870926615198e+02,4.700602133108385261e-01,1.100000010988609489e+01,1.139878383865300642e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599220888914130967e+01,6.666625870861648764e+02,4.700716120922087127e-01,1.100000010988609489e+01,1.139732398463762925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599311798004131902e+01,6.666725870796699382e+02,4.700830094137258275e-01,1.100000010988609489e+01,1.139586413062225207e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599402707094132836e+01,6.666825870731767054e+02,4.700944052753898705e-01,1.100000010988609489e+01,1.139440427660687490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599493616184133771e+01,6.666925870666850642e+02,4.701057996772008973e-01,1.100000010988609489e+01,1.139294442259149772e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599584525274134705e+01,6.667025870601951283e+02,4.701171926191588524e-01,1.100000010988609489e+01,1.139148456857612055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599675434364135640e+01,6.667125870537067840e+02,4.701285841012637357e-01,1.100000010988609489e+01,1.139002471456074337e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599766343454136575e+01,6.667225870472201450e+02,4.701399741235155472e-01,1.100000010988609489e+01,1.138856486054536619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599857252544137509e+01,6.667325870407352113e+02,4.701513626859142869e-01,1.100000010988609489e+01,1.138710500652998902e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.599948161634138444e+01,6.667425870342518692e+02,4.701627497884599549e-01,1.100000010988609489e+01,1.138564515251461184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600039070724139378e+01,6.667525870277702325e+02,4.701741354311525511e-01,1.100000010988609489e+01,1.138418529849923467e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600129979814140313e+01,6.667625870212903010e+02,4.701855196139920756e-01,1.100000010988609489e+01,1.138272544448385749e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600220888904141248e+01,6.667725870148119611e+02,4.701969023369785283e-01,1.100000010988609489e+01,1.138126559046848032e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600311797994142182e+01,6.667825870083353266e+02,4.702082836001119093e-01,1.100000010988609489e+01,1.137980573645310314e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600402707084143117e+01,6.667925870018602836e+02,4.702196634033922185e-01,1.100000010988609489e+01,1.137834588243772597e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600493616174144051e+01,6.668025869953869460e+02,4.702310417468194559e-01,1.100000010988609489e+01,1.137688602842234879e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600584525264144986e+01,6.668125869889153137e+02,4.702424186303936215e-01,1.100000010988609489e+01,1.137542617440697162e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600675434354145921e+01,6.668225869824452730e+02,4.702537940541147155e-01,1.100000010988609489e+01,1.137396632039159444e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600766343444146855e+01,6.668325869759769375e+02,4.702651680179827376e-01,1.100000010988609489e+01,1.137250646637621727e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600857252534147790e+01,6.668425869695101937e+02,4.702765405219976880e-01,1.100000010988609489e+01,1.137104661236084009e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.600948161624148725e+01,6.668525869630451552e+02,4.702879115661595666e-01,1.100000010988609489e+01,1.136958675834546292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601039070714149659e+01,6.668625869565818221e+02,4.702992811504683734e-01,1.100000010988609489e+01,1.136812690433008574e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601129979804150594e+01,6.668725869501200805e+02,4.703106492749241085e-01,1.100000010988609489e+01,1.136666705031470857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601220888894151528e+01,6.668825869436600442e+02,4.703220159395267719e-01,1.100000010988609489e+01,1.136520719629933139e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601311797984152463e+01,6.668925869372015995e+02,4.703333811442763635e-01,1.100000010988609489e+01,1.136374734228395422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601402707074153398e+01,6.669025869307448602e+02,4.703447448891728833e-01,1.100000010988609489e+01,1.136228748826857704e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601493616164154332e+01,6.669125869242898261e+02,4.703561071742163313e-01,1.100000010988609489e+01,1.136082763425319987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601584525254155267e+01,6.669225869178363837e+02,4.703674679994067076e-01,1.100000010988609489e+01,1.135936778023782269e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601675434344156201e+01,6.669325869113846466e+02,4.703788273647440121e-01,1.100000010988609489e+01,1.135790792622244551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601766343434157136e+01,6.669425869049345010e+02,4.703901852702282449e-01,1.100000010988609489e+01,1.135644807220706834e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601857252524158071e+01,6.669525868984860608e+02,4.704015417158594059e-01,1.100000010988609489e+01,1.135498821819169116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.601948161614159005e+01,6.669625868920393259e+02,4.704128967016374951e-01,1.100000010988609489e+01,1.135352836417631399e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602039070704159940e+01,6.669725868855941826e+02,4.704242502275625126e-01,1.100000010988609489e+01,1.135206851016093681e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602129979794160874e+01,6.669825868791507446e+02,4.704356022936344583e-01,1.100000010988609489e+01,1.135060865614555964e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602220888884161809e+01,6.669925868727088982e+02,4.704469528998533323e-01,1.100000010988609489e+01,1.134914880213018246e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602311797974162744e+01,6.670025868662687571e+02,4.704583020462191345e-01,1.100000010988609489e+01,1.134768894811480529e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602402707064163678e+01,6.670125868598302077e+02,4.704696497327318649e-01,1.100000010988609489e+01,1.134622909409942811e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602493616154164613e+01,6.670225868533933635e+02,4.704809959593915236e-01,1.100000010988609489e+01,1.134476924008405094e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602584525244165548e+01,6.670325868469582247e+02,4.704923407261981105e-01,1.100000010988609489e+01,1.134330938606867376e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602675434334166482e+01,6.670425868405246774e+02,4.705036840331515702e-01,1.100000010988609489e+01,1.134184953205329659e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602766343424167417e+01,6.670525868340928355e+02,4.705150258802519581e-01,1.100000010988609489e+01,1.134038967803791941e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602857252514168351e+01,6.670625868276625852e+02,4.705263662674992742e-01,1.100000010988609489e+01,1.133892982402254224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.602948161604169286e+01,6.670725868212340401e+02,4.705377051948935185e-01,1.100000010988609489e+01,1.133746997000716506e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603039070694170221e+01,6.670825868148070867e+02,4.705490426624346911e-01,1.100000010988609489e+01,1.133601011599178789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603129979784171155e+01,6.670925868083818386e+02,4.705603786701227920e-01,1.100000010988609489e+01,1.133455026197641071e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603220888874172090e+01,6.671025868019581821e+02,4.705717132179578210e-01,1.100000010988609489e+01,1.133309040796103354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603311797964173024e+01,6.671125867955362310e+02,4.705830463059397784e-01,1.100000010988609489e+01,1.133163055394565636e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603402707054173959e+01,6.671225867891159851e+02,4.705943779340686639e-01,1.100000010988609489e+01,1.133017069993027919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603493616144174894e+01,6.671325867826973308e+02,4.706057081023444777e-01,1.100000010988609489e+01,1.132871084591490201e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603584525234175828e+01,6.671425867762803819e+02,4.706170368107671642e-01,1.100000010988609489e+01,1.132725099189952483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603675434324176763e+01,6.671525867698650245e+02,4.706283640593367790e-01,1.100000010988609489e+01,1.132579113788414766e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603766343414177697e+01,6.671625867634513725e+02,4.706396898480533220e-01,1.100000010988609489e+01,1.132433128386877048e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603857252504178632e+01,6.671725867570393120e+02,4.706510141769167932e-01,1.100000010988609489e+01,1.132287142985339331e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.603948161594179567e+01,6.671825867506289569e+02,4.706623370459271927e-01,1.100000010988609489e+01,1.132141157583801613e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604039070684180501e+01,6.671925867442201934e+02,4.706736584550845204e-01,1.100000010988609489e+01,1.131995172182263896e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604129979774181436e+01,6.672025867378131352e+02,4.706849784043887763e-01,1.100000010988609489e+01,1.131849186780726178e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604220888864182371e+01,6.672125867314076686e+02,4.706962968938399050e-01,1.100000010988609489e+01,1.131703201379188461e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604311797954183305e+01,6.672225867250039073e+02,4.707076139234379619e-01,1.100000010988609489e+01,1.131557215977650743e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604402707044184240e+01,6.672325867186018513e+02,4.707189294931829471e-01,1.100000010988609489e+01,1.131411230576113026e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604493616134185174e+01,6.672425867122013869e+02,4.707302436030748605e-01,1.100000010988609489e+01,1.131265245174575308e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604584525224186109e+01,6.672525867058026279e+02,4.707415562531137021e-01,1.100000010988609489e+01,1.131119259773037591e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604675434314187044e+01,6.672625866994054604e+02,4.707528674432994720e-01,1.100000010988609489e+01,1.130973274371499873e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604766343404187978e+01,6.672725866930099983e+02,4.707641771736321146e-01,1.100000010988609489e+01,1.130827288969962156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604857252494188913e+01,6.672825866866161277e+02,4.707754854441116854e-01,1.100000010988609489e+01,1.130681303568424438e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.604948161584189847e+01,6.672925866802239625e+02,4.707867922547381845e-01,1.100000010988609489e+01,1.130535318166886721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605039070674190782e+01,6.673025866738333889e+02,4.707980976055116118e-01,1.100000010988609489e+01,1.130389332765349003e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605129979764191717e+01,6.673125866674445206e+02,4.708094014964319673e-01,1.100000010988609489e+01,1.130243347363811286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605220888854192651e+01,6.673225866610572439e+02,4.708207039274991956e-01,1.100000010988609489e+01,1.130097361962273568e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605311797944193586e+01,6.673325866546716725e+02,4.708320048987133521e-01,1.100000010988609489e+01,1.129951376560735851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605402707034194520e+01,6.673425866482876927e+02,4.708433044100744369e-01,1.100000010988609489e+01,1.129805391159198133e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605493616124195455e+01,6.673525866419054182e+02,4.708546024615824499e-01,1.100000010988609489e+01,1.129659405757660415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605584525214196390e+01,6.673625866355247354e+02,4.708658990532373911e-01,1.100000010988609489e+01,1.129513420356122698e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605675434304197324e+01,6.673725866291457578e+02,4.708771941850392051e-01,1.100000010988609489e+01,1.129367434954584980e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605766343394198259e+01,6.673825866227683719e+02,4.708884878569879473e-01,1.100000010988609489e+01,1.129221449553047263e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605857252484199194e+01,6.673925866163926912e+02,4.708997800690836177e-01,1.100000010988609489e+01,1.129075464151509545e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.605948161574200128e+01,6.674025866100186022e+02,4.709110708213262164e-01,1.100000010988609489e+01,1.128929478749971828e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606039070664201063e+01,6.674125866036462185e+02,4.709223601137157433e-01,1.100000010988609489e+01,1.128783493348434110e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606129979754201997e+01,6.674225865972754264e+02,4.709336479462521430e-01,1.100000010988609489e+01,1.128637507946896393e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606220888844202932e+01,6.674325865909063396e+02,4.709449343189354709e-01,1.100000010988609489e+01,1.128491522545358675e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606311797934203867e+01,6.674425865845388444e+02,4.709562192317657270e-01,1.100000010988609489e+01,1.128345537143820958e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606402707024204801e+01,6.674525865781730545e+02,4.709675026847429113e-01,1.100000010988609489e+01,1.128199551742283240e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606493616114205736e+01,6.674625865718088562e+02,4.709787846778669684e-01,1.100000010988609489e+01,1.128053566340745523e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606584525204206670e+01,6.674725865654463632e+02,4.709900652111379538e-01,1.100000010988609489e+01,1.127907580939207805e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606675434294207605e+01,6.674825865590854619e+02,4.710013442845558673e-01,1.100000010988609489e+01,1.127761595537670088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606766343384208540e+01,6.674925865527262658e+02,4.710126218981206536e-01,1.100000010988609489e+01,1.127615610136132370e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606857252474209474e+01,6.675025865463686614e+02,4.710238980518323682e-01,1.100000010988609489e+01,1.127469624734594653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.606948161564210409e+01,6.675125865400127623e+02,4.710351727456910109e-01,1.100000010988609489e+01,1.127323639333056935e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607039070654211343e+01,6.675225865336584548e+02,4.710464459796965819e-01,1.100000010988609489e+01,1.127177653931519218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607129979744212278e+01,6.675325865273058525e+02,4.710577177538490257e-01,1.100000010988609489e+01,1.127031668529981500e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607220888834213213e+01,6.675425865209548419e+02,4.710689880681483976e-01,1.100000010988609489e+01,1.126885683128443782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607311797924214147e+01,6.675525865146055366e+02,4.710802569225946979e-01,1.100000010988609489e+01,1.126739697726906065e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607402707014215082e+01,6.675625865082578230e+02,4.710915243171878708e-01,1.100000010988609489e+01,1.126593712325368347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607493616104216017e+01,6.675725865019117009e+02,4.711027902519279720e-01,1.100000010988609489e+01,1.126447726923830630e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607584525194216951e+01,6.675825864955672841e+02,4.711140547268150014e-01,1.100000010988609489e+01,1.126301741522292912e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607675434284217886e+01,6.675925864892244590e+02,4.711253177418489035e-01,1.100000010988609489e+01,1.126155756120755195e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607766343374218820e+01,6.676025864828833392e+02,4.711365792970297339e-01,1.100000010988609489e+01,1.126009770719217477e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607857252464219755e+01,6.676125864765438109e+02,4.711478393923574925e-01,1.100000010988609489e+01,1.125863785317679760e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.607948161554220690e+01,6.676225864702059880e+02,4.711590980278321794e-01,1.100000010988609489e+01,1.125717799916142042e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608039070644221624e+01,6.676325864638697567e+02,4.711703552034537390e-01,1.100000010988609489e+01,1.125571814514604325e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608129979734222559e+01,6.676425864575352307e+02,4.711816109192222268e-01,1.100000010988609489e+01,1.125425829113066607e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608220888824223493e+01,6.676525864512022963e+02,4.711928651751375874e-01,1.100000010988609489e+01,1.125279843711528890e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608311797914224428e+01,6.676625864448710672e+02,4.712041179711998762e-01,1.100000010988609489e+01,1.125133858309991172e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608402707004225363e+01,6.676725864385414297e+02,4.712153693074090932e-01,1.100000010988609489e+01,1.124987872908453455e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608493616094226297e+01,6.676825864322134976e+02,4.712266191837651830e-01,1.100000010988609489e+01,1.124841887506915737e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608584525184227232e+01,6.676925864258871570e+02,4.712378676002682010e-01,1.100000010988609489e+01,1.124695902105378020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608675434274228166e+01,6.677025864195624081e+02,4.712491145569181472e-01,1.100000010988609489e+01,1.124549916703840302e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608766343364229101e+01,6.677125864132393644e+02,4.712603600537149662e-01,1.100000010988609489e+01,1.124403931302302585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608857252454230036e+01,6.677225864069179124e+02,4.712716040906587134e-01,1.100000010988609489e+01,1.124257945900764867e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.608948161544230970e+01,6.677325864005981657e+02,4.712828466677493888e-01,1.100000010988609489e+01,1.124111960499227150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609039070634231905e+01,6.677425863942800106e+02,4.712940877849869370e-01,1.100000010988609489e+01,1.123965975097689432e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609129979724232840e+01,6.677525863879635608e+02,4.713053274423714134e-01,1.100000010988609489e+01,1.123819989696151714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609220888814233774e+01,6.677625863816487026e+02,4.713165656399027625e-01,1.100000010988609489e+01,1.123674004294613997e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609311797904234709e+01,6.677725863753354361e+02,4.713278023775810399e-01,1.100000010988609489e+01,1.123528018893076279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609402706994235643e+01,6.677825863690238748e+02,4.713390376554062455e-01,1.100000010988609489e+01,1.123382033491538562e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609493616084236578e+01,6.677925863627139051e+02,4.713502714733783239e-01,1.100000010988609489e+01,1.123236048090000844e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609584525174237513e+01,6.678025863564056408e+02,4.713615038314973305e-01,1.100000010988609489e+01,1.123090062688463127e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609675434264238447e+01,6.678125863500989681e+02,4.713727347297632098e-01,1.100000010988609489e+01,1.122944077286925409e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609766343354239382e+01,6.678225863437940006e+02,4.713839641681760173e-01,1.100000010988609489e+01,1.122798091885387692e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609857252444240316e+01,6.678325863374906248e+02,4.713951921467357531e-01,1.100000010988609489e+01,1.122652106483849974e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.609948161534241251e+01,6.678425863311888406e+02,4.714064186654423616e-01,1.100000010988609489e+01,1.122506121082312257e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610039070624242186e+01,6.678525863248887617e+02,4.714176437242958984e-01,1.100000010988609489e+01,1.122360135680774539e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610129979714243120e+01,6.678625863185902745e+02,4.714288673232963078e-01,1.100000010988609489e+01,1.122214150279236822e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610220888804244055e+01,6.678725863122934925e+02,4.714400894624436456e-01,1.100000010988609489e+01,1.122068164877699104e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610311797894244989e+01,6.678825863059983021e+02,4.714513101417378560e-01,1.100000010988609489e+01,1.121922179476161387e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610402706984245924e+01,6.678925862997047034e+02,4.714625293611789947e-01,1.100000010988609489e+01,1.121776194074623669e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610493616074246859e+01,6.679025862934128099e+02,4.714737471207670616e-01,1.100000010988609489e+01,1.121630208673085952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610584525164247793e+01,6.679125862871225081e+02,4.714849634205020013e-01,1.100000010988609489e+01,1.121484223271548234e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610675434254248728e+01,6.679225862808339116e+02,4.714961782603838691e-01,1.100000010988609489e+01,1.121338237870010517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610766343344249663e+01,6.679325862745469067e+02,4.715073916404126098e-01,1.100000010988609489e+01,1.121192252468472799e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610857252434250597e+01,6.679425862682614934e+02,4.715186035605882786e-01,1.100000010988609489e+01,1.121046267066935082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.610948161524251532e+01,6.679525862619777854e+02,4.715298140209108202e-01,1.100000010988609489e+01,1.120900281665397364e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611039070614252466e+01,6.679625862556956690e+02,4.715410230213802900e-01,1.100000010988609489e+01,1.120754296263859646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611129979704253401e+01,6.679725862494152580e+02,4.715522305619966326e-01,1.100000010988609489e+01,1.120608310862321929e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611220888794254336e+01,6.679825862431364385e+02,4.715634366427599033e-01,1.100000010988609489e+01,1.120462325460784211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611311797884255270e+01,6.679925862368592107e+02,4.715746412636700469e-01,1.100000010988609489e+01,1.120316340059246494e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611402706974256205e+01,6.680025862305836881e+02,4.715858444247271186e-01,1.100000010988609489e+01,1.120170354657708776e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611493616064257139e+01,6.680125862243097572e+02,4.715970461259310631e-01,1.100000010988609489e+01,1.120024369256171059e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611584525154258074e+01,6.680225862180375316e+02,4.716082463672819358e-01,1.100000010988609489e+01,1.119878383854633341e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611675434244259009e+01,6.680325862117668976e+02,4.716194451487796813e-01,1.100000010988609489e+01,1.119732398453095624e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611766343334259943e+01,6.680425862054978552e+02,4.716306424704243550e-01,1.100000010988609489e+01,1.119586413051557906e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611857252424260878e+01,6.680525861992305181e+02,4.716418383322159014e-01,1.100000010988609489e+01,1.119440427650020189e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.611948161514261812e+01,6.680625861929647726e+02,4.716530327341543760e-01,1.100000010988609489e+01,1.119294442248482471e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612039070604262747e+01,6.680725861867006188e+02,4.716642256762397234e-01,1.100000010988609489e+01,1.119148456846944754e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612129979694263682e+01,6.680825861804381702e+02,4.716754171584719990e-01,1.100000010988609489e+01,1.119002471445407036e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612220888784264616e+01,6.680925861741773133e+02,4.716866071808511474e-01,1.100000010988609489e+01,1.118856486043869319e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612311797874265551e+01,6.681025861679181617e+02,4.716977957433772239e-01,1.100000010988609489e+01,1.118710500642331601e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612402706964266486e+01,6.681125861616606016e+02,4.717089828460501733e-01,1.100000010988609489e+01,1.118564515240793884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612493616054267420e+01,6.681225861554046332e+02,4.717201684888700508e-01,1.100000010988609489e+01,1.118418529839256166e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612584525144268355e+01,6.681325861491503701e+02,4.717313526718368011e-01,1.100000010988609489e+01,1.118272544437718449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612675434234269289e+01,6.681425861428976987e+02,4.717425353949504241e-01,1.100000010988609489e+01,1.118126559036180731e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612766343324270224e+01,6.681525861366466188e+02,4.717537166582109753e-01,1.100000010988609489e+01,1.117980573634643014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612857252414271159e+01,6.681625861303972442e+02,4.717648964616183993e-01,1.100000010988609489e+01,1.117834588233105296e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.612948161504272093e+01,6.681725861241494613e+02,4.717760748051727515e-01,1.100000010988609489e+01,1.117688602831567578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613039070594273028e+01,6.681825861179032700e+02,4.717872516888739765e-01,1.100000010988609489e+01,1.117542617430029861e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613129979684273962e+01,6.681925861116587839e+02,4.717984271127221296e-01,1.100000010988609489e+01,1.117396632028492143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613220888774274897e+01,6.682025861054158895e+02,4.718096010767171555e-01,1.100000010988609489e+01,1.117250646626954426e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613311797864275832e+01,6.682125860991747004e+02,4.718207735808590542e-01,1.100000010988609489e+01,1.117104661225416708e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613402706954276766e+01,6.682225860929351029e+02,4.718319446251478810e-01,1.100000010988609489e+01,1.116958675823878991e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613493616044277701e+01,6.682325860866970970e+02,4.718431142095835806e-01,1.100000010988609489e+01,1.116812690422341273e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613584525134278636e+01,6.682425860804607964e+02,4.718542823341662085e-01,1.100000010988609489e+01,1.116666705020803556e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613675434224279570e+01,6.682525860742260875e+02,4.718654489988957090e-01,1.100000010988609489e+01,1.116520719619265838e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613766343314280505e+01,6.682625860679929701e+02,4.718766142037720823e-01,1.100000010988609489e+01,1.116374734217728121e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613857252404281439e+01,6.682725860617615581e+02,4.718877779487953839e-01,1.100000010988609489e+01,1.116228748816190403e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.613948161494282374e+01,6.682825860555317377e+02,4.718989402339655581e-01,1.100000010988609489e+01,1.116082763414652686e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614039070584283309e+01,6.682925860493035088e+02,4.719101010592826606e-01,1.100000010988609489e+01,1.115936778013114968e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614129979674284243e+01,6.683025860430769853e+02,4.719212604247466358e-01,1.100000010988609489e+01,1.115790792611577251e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614220888764285178e+01,6.683125860368520534e+02,4.719324183303574838e-01,1.100000010988609489e+01,1.115644807210039533e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614311797854286112e+01,6.683225860306287132e+02,4.719435747761152600e-01,1.100000010988609489e+01,1.115498821808501816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614402706944287047e+01,6.683325860244070782e+02,4.719547297620199089e-01,1.100000010988609489e+01,1.115352836406964098e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614493616034287982e+01,6.683425860181870348e+02,4.719658832880714305e-01,1.100000010988609489e+01,1.115206851005426381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614584525124288916e+01,6.683525860119685831e+02,4.719770353542698804e-01,1.100000010988609489e+01,1.115060865603888663e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614675434214289851e+01,6.683625860057518366e+02,4.719881859606152030e-01,1.100000010988609489e+01,1.114914880202350946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614766343304290785e+01,6.683725859995366818e+02,4.719993351071074539e-01,1.100000010988609489e+01,1.114768894800813228e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614857252394291720e+01,6.683825859933231186e+02,4.720104827937465775e-01,1.100000010988609489e+01,1.114622909399275510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.614948161484292655e+01,6.683925859871111470e+02,4.720216290205325738e-01,1.100000010988609489e+01,1.114476923997737793e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615039070574293589e+01,6.684025859809008807e+02,4.720327737874654983e-01,1.100000010988609489e+01,1.114330938596200075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615129979664294524e+01,6.684125859746922060e+02,4.720439170945452956e-01,1.100000010988609489e+01,1.114184953194662358e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615220888754295459e+01,6.684225859684851230e+02,4.720550589417719656e-01,1.100000010988609489e+01,1.114038967793124640e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615311797844296393e+01,6.684325859622797452e+02,4.720661993291455638e-01,1.100000010988609489e+01,1.113892982391586923e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615402706934297328e+01,6.684425859560759591e+02,4.720773382566660348e-01,1.100000010988609489e+01,1.113746996990049205e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615493616024298262e+01,6.684525859498737645e+02,4.720884757243333785e-01,1.100000010988609489e+01,1.113601011588511488e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615584525114299197e+01,6.684625859436732753e+02,4.720996117321476504e-01,1.100000010988609489e+01,1.113455026186973770e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615675434204300132e+01,6.684725859374743777e+02,4.721107462801087951e-01,1.100000010988609489e+01,1.113309040785436053e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615766343294301066e+01,6.684825859312770717e+02,4.721218793682168124e-01,1.100000010988609489e+01,1.113163055383898335e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615857252384302001e+01,6.684925859250813573e+02,4.721330109964717026e-01,1.100000010988609489e+01,1.113017069982360618e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.615948161474302935e+01,6.685025859188873483e+02,4.721441411648735209e-01,1.100000010988609489e+01,1.112871084580822900e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616039070564303870e+01,6.685125859126949308e+02,4.721552698734222120e-01,1.100000010988609489e+01,1.112725099179285183e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616129979654304805e+01,6.685225859065041050e+02,4.721663971221177758e-01,1.100000010988609489e+01,1.112579113777747465e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616220888744305739e+01,6.685325859003149844e+02,4.721775229109602678e-01,1.100000010988609489e+01,1.112433128376209748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616311797834306674e+01,6.685425858941274555e+02,4.721886472399496326e-01,1.100000010988609489e+01,1.112287142974672030e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616402706924307608e+01,6.685525858879415182e+02,4.721997701090858701e-01,1.100000010988609489e+01,1.112141157573134313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616493616014308543e+01,6.685625858817571725e+02,4.722108915183689803e-01,1.100000010988609489e+01,1.111995172171596595e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616584525104309478e+01,6.685725858755745321e+02,4.722220114677990188e-01,1.100000010988609489e+01,1.111849186770058878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616675434194310412e+01,6.685825858693934833e+02,4.722331299573759300e-01,1.100000010988609489e+01,1.111703201368521160e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616766343284311347e+01,6.685925858632140262e+02,4.722442469870997139e-01,1.100000010988609489e+01,1.111557215966983442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616857252374312282e+01,6.686025858570362743e+02,4.722553625569703706e-01,1.100000010988609489e+01,1.111411230565445725e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.616948161464313216e+01,6.686125858508601141e+02,4.722664766669879555e-01,1.100000010988609489e+01,1.111265245163908007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617039070554314151e+01,6.686225858446855455e+02,4.722775893171524131e-01,1.100000010988609489e+01,1.111119259762370290e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617129979644315085e+01,6.686325858385125684e+02,4.722887005074637434e-01,1.100000010988609489e+01,1.110973274360832572e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617220888734316020e+01,6.686425858323412967e+02,4.722998102379219465e-01,1.100000010988609489e+01,1.110827288959294855e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617311797824316955e+01,6.686525858261716166e+02,4.723109185085270778e-01,1.100000010988609489e+01,1.110681303557757137e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617402706914317889e+01,6.686625858200035282e+02,4.723220253192790818e-01,1.100000010988609489e+01,1.110535318156219420e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617493616004318824e+01,6.686725858138370313e+02,4.723331306701779586e-01,1.100000010988609489e+01,1.110389332754681702e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617584525094319758e+01,6.686825858076722398e+02,4.723442345612237081e-01,1.100000010988609489e+01,1.110243347353143985e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617675434184320693e+01,6.686925858015090398e+02,4.723553369924163303e-01,1.100000010988609489e+01,1.110097361951606267e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617766343274321628e+01,6.687025857953474315e+02,4.723664379637558808e-01,1.100000010988609489e+01,1.109951376550068550e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617857252364322562e+01,6.687125857891875285e+02,4.723775374752423040e-01,1.100000010988609489e+01,1.109805391148530832e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.617948161454323497e+01,6.687225857830292171e+02,4.723886355268755999e-01,1.100000010988609489e+01,1.109659405746993115e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618039070544324431e+01,6.687325857768724973e+02,4.723997321186557685e-01,1.100000010988609489e+01,1.109513420345455397e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618129979634325366e+01,6.687425857707173691e+02,4.724108272505828099e-01,1.100000010988609489e+01,1.109367434943917680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618220888724326301e+01,6.687525857645638325e+02,4.724219209226567795e-01,1.100000010988609489e+01,1.109221449542379962e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618311797814327235e+01,6.687625857584120013e+02,4.724330131348776218e-01,1.100000010988609489e+01,1.109075464140842245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618402706904328170e+01,6.687725857522617616e+02,4.724441038872453369e-01,1.100000010988609489e+01,1.108929478739304527e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618493615994329105e+01,6.687825857461131136e+02,4.724551931797599247e-01,1.100000010988609489e+01,1.108783493337766810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618584525084330039e+01,6.687925857399660572e+02,4.724662810124213852e-01,1.100000010988609489e+01,1.108637507936229092e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618675434174330974e+01,6.688025857338207061e+02,4.724773673852297184e-01,1.100000010988609489e+01,1.108491522534691374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618766343264331908e+01,6.688125857276769466e+02,4.724884522981849799e-01,1.100000010988609489e+01,1.108345537133153657e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618857252354332843e+01,6.688225857215347787e+02,4.724995357512871141e-01,1.100000010988609489e+01,1.108199551731615939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.618948161444333778e+01,6.688325857153942025e+02,4.725106177445361211e-01,1.100000010988609489e+01,1.108053566330078222e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619039070534334712e+01,6.688425857092553315e+02,4.725216982779320007e-01,1.100000010988609489e+01,1.107907580928540504e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619129979624335647e+01,6.688525857031180522e+02,4.725327773514747531e-01,1.100000010988609489e+01,1.107761595527002787e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619220888714336581e+01,6.688625856969823644e+02,4.725438549651643783e-01,1.100000010988609489e+01,1.107615610125465069e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619311797804337516e+01,6.688725856908482683e+02,4.725549311190009316e-01,1.100000010988609489e+01,1.107469624723927352e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619402706894338451e+01,6.688825856847158775e+02,4.725660058129843577e-01,1.100000010988609489e+01,1.107323639322389634e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619493615984339385e+01,6.688925856785850783e+02,4.725770790471146565e-01,1.100000010988609489e+01,1.107177653920851917e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619584525074340320e+01,6.689025856724558707e+02,4.725881508213918281e-01,1.100000010988609489e+01,1.107031668519314199e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619675434164341254e+01,6.689125856663282548e+02,4.725992211358158723e-01,1.100000010988609489e+01,1.106885683117776482e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619766343254342189e+01,6.689225856602022304e+02,4.726102899903867893e-01,1.100000010988609489e+01,1.106739697716238764e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619857252344343124e+01,6.689325856540779114e+02,4.726213573851045791e-01,1.100000010988609489e+01,1.106593712314701047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.619948161434344058e+01,6.689425856479551840e+02,4.726324233199692415e-01,1.100000010988609489e+01,1.106447726913163329e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620039070524344993e+01,6.689525856418340481e+02,4.726434877949807767e-01,1.100000010988609489e+01,1.106301741511625612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620129979614345928e+01,6.689625856357145040e+02,4.726545508101392401e-01,1.100000010988609489e+01,1.106155756110087894e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620220888704346862e+01,6.689725856295965514e+02,4.726656123654445762e-01,1.100000010988609489e+01,1.106009770708550177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620311797794347797e+01,6.689825856234803041e+02,4.726766724608967851e-01,1.100000010988609489e+01,1.105863785307012459e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620402706884348731e+01,6.689925856173656484e+02,4.726877310964958667e-01,1.100000010988609489e+01,1.105717799905474742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620493615974349666e+01,6.690025856112525844e+02,4.726987882722418211e-01,1.100000010988609489e+01,1.105571814503937024e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620584525064350601e+01,6.690125856051411120e+02,4.727098439881346481e-01,1.100000010988609489e+01,1.105425829102399306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620675434154351535e+01,6.690225855990312311e+02,4.727208982441743479e-01,1.100000010988609489e+01,1.105279843700861589e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620766343244352470e+01,6.690325855929230556e+02,4.727319510403609204e-01,1.100000010988609489e+01,1.105133858299323871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620857252334353404e+01,6.690425855868164717e+02,4.727430023766943656e-01,1.100000010988609489e+01,1.104987872897786154e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.620948161424354339e+01,6.690525855807114795e+02,4.727540522531746836e-01,1.100000010988609489e+01,1.104841887496248436e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621039070514355274e+01,6.690625855746080788e+02,4.727651006698018743e-01,1.100000010988609489e+01,1.104695902094710719e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621129979604356208e+01,6.690725855685062697e+02,4.727761476265759377e-01,1.100000010988609489e+01,1.104549916693173001e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621220888694357143e+01,6.690825855624061660e+02,4.727871931234968739e-01,1.100000010988609489e+01,1.104403931291635284e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621311797784358077e+01,6.690925855563076539e+02,4.727982371605646827e-01,1.100000010988609489e+01,1.104257945890097566e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621402706874359012e+01,6.691025855502107333e+02,4.728092797377793643e-01,1.100000010988609489e+01,1.104111960488559849e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621493615964359947e+01,6.691125855441154044e+02,4.728203208551409187e-01,1.100000010988609489e+01,1.103965975087022131e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621584525054360881e+01,6.691225855380216672e+02,4.728313605126494013e-01,1.100000010988609489e+01,1.103819989685484414e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621675434144361816e+01,6.691325855319295215e+02,4.728423987103047565e-01,1.100000010988609489e+01,1.103674004283946696e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621766343234362751e+01,6.691425855258390811e+02,4.728534354481069846e-01,1.100000010988609489e+01,1.103528018882408979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621857252324363685e+01,6.691525855197502324e+02,4.728644707260560853e-01,1.100000010988609489e+01,1.103382033480871261e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.621948161414364620e+01,6.691625855136629752e+02,4.728755045441520588e-01,1.100000010988609489e+01,1.103236048079333544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622039070504365554e+01,6.691725855075773097e+02,4.728865369023949050e-01,1.100000010988609489e+01,1.103090062677795826e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622129979594366489e+01,6.691825855014932358e+02,4.728975678007846239e-01,1.100000010988609489e+01,1.102944077276258109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622220888684367424e+01,6.691925854954107535e+02,4.729085972393212156e-01,1.100000010988609489e+01,1.102798091874720391e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622311797774368358e+01,6.692025854893299766e+02,4.729196252180046800e-01,1.100000010988609489e+01,1.102652106473182674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622402706864369293e+01,6.692125854832507912e+02,4.729306517368350171e-01,1.100000010988609489e+01,1.102506121071644956e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622493615954370227e+01,6.692225854771731974e+02,4.729416767958122270e-01,1.100000010988609489e+01,1.102360135670107238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622584525044371162e+01,6.692325854710971953e+02,4.729527003949363095e-01,1.100000010988609489e+01,1.102214150268569521e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622675434134372097e+01,6.692425854650227848e+02,4.729637225342072648e-01,1.100000010988609489e+01,1.102068164867031803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622766343224373031e+01,6.692525854589499659e+02,4.729747432136250929e-01,1.100000010988609489e+01,1.101922179465494086e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622857252314373966e+01,6.692625854528788523e+02,4.729857624331897381e-01,1.100000010988609489e+01,1.101776194063956368e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.622948161404374900e+01,6.692725854468093303e+02,4.729967801929012561e-01,1.100000010988609489e+01,1.101630208662418651e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623039070494375835e+01,6.692825854407413999e+02,4.730077964927596468e-01,1.100000010988609489e+01,1.101484223260880933e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623129979584376770e+01,6.692925854346750612e+02,4.730188113327649102e-01,1.100000010988609489e+01,1.101338237859343216e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623220888674377704e+01,6.693025854286103140e+02,4.730298247129170464e-01,1.100000010988609489e+01,1.101192252457805498e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623311797764378639e+01,6.693125854225471585e+02,4.730408366332160552e-01,1.100000010988609489e+01,1.101046267056267781e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623402706854379574e+01,6.693225854164855946e+02,4.730518470936619368e-01,1.100000010988609489e+01,1.100900281654730063e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623493615944380508e+01,6.693325854104257360e+02,4.730628560942546912e-01,1.100000010988609489e+01,1.100754296253192346e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623584525034381443e+01,6.693425854043674690e+02,4.730738636349943183e-01,1.100000010988609489e+01,1.100608310851654628e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623675434124382377e+01,6.693525853983107936e+02,4.730848697158808180e-01,1.100000010988609489e+01,1.100462325450116911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623766343214383312e+01,6.693625853922557098e+02,4.730958743369141906e-01,1.100000010988609489e+01,1.100316340048579193e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623857252304384247e+01,6.693725853862022177e+02,4.731068774980944358e-01,1.100000010988609489e+01,1.100170354647041476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.623948161394385181e+01,6.693825853801503172e+02,4.731178791994215538e-01,1.100000010988609489e+01,1.100024369245503758e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624039070484386116e+01,6.693925853741000083e+02,4.731288794408955445e-01,1.100000010988609489e+01,1.099878383843966041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624129979574387050e+01,6.694025853680512910e+02,4.731398782225164079e-01,1.100000010988609489e+01,1.099732398442428323e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624220888664387985e+01,6.694125853620042790e+02,4.731508755442841441e-01,1.100000010988609489e+01,1.099586413040890606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624311797754388920e+01,6.694225853559588586e+02,4.731618714061986974e-01,1.100000010988609489e+01,1.099440427639352888e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624402706844389854e+01,6.694325853499150298e+02,4.731728658082601235e-01,1.100000010988609489e+01,1.099294442237815170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624493615934390789e+01,6.694425853438727927e+02,4.731838587504684224e-01,1.100000010988609489e+01,1.099148456836277453e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624584525024391723e+01,6.694525853378321472e+02,4.731948502328235939e-01,1.100000010988609489e+01,1.099002471434739735e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624675434114392658e+01,6.694625853317930932e+02,4.732058402553256382e-01,1.100000010988609489e+01,1.098856486033202018e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624766343204393593e+01,6.694725853257556309e+02,4.732168288179745552e-01,1.100000010988609489e+01,1.098710500631664300e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624857252294394527e+01,6.694825853197197603e+02,4.732278159207703450e-01,1.100000010988609489e+01,1.098564515230126583e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.624948161384395462e+01,6.694925853136855949e+02,4.732388015637130074e-01,1.100000010988609489e+01,1.098418529828588865e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625039070474396397e+01,6.695025853076530211e+02,4.732497857468024871e-01,1.100000010988609489e+01,1.098272544427051148e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625129979564397331e+01,6.695125853016220390e+02,4.732607684700388395e-01,1.100000010988609489e+01,1.098126559025513430e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625220888654398266e+01,6.695225852955926484e+02,4.732717497334220647e-01,1.100000010988609489e+01,1.097980573623975713e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625311797744399200e+01,6.695325852895648495e+02,4.732827295369521625e-01,1.100000010988609489e+01,1.097834588222437995e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625402706834400135e+01,6.695425852835386422e+02,4.732937078806291331e-01,1.100000010988609489e+01,1.097688602820900278e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625493615924401070e+01,6.695525852775140265e+02,4.733046847644529764e-01,1.100000010988609489e+01,1.097542617419362560e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625584525014402004e+01,6.695625852714910025e+02,4.733156601884236925e-01,1.100000010988609489e+01,1.097396632017824843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625675434104402939e+01,6.695725852654695700e+02,4.733266341525412257e-01,1.100000010988609489e+01,1.097250646616287125e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625766343194403873e+01,6.695825852594497292e+02,4.733376066568056317e-01,1.100000010988609489e+01,1.097104661214749408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625857252284404808e+01,6.695925852534314799e+02,4.733485777012169105e-01,1.100000010988609489e+01,1.096958675813211690e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.625948161374405743e+01,6.696025852474149360e+02,4.733595472857750619e-01,1.100000010988609489e+01,1.096812690411673973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626039070464406677e+01,6.696125852413999837e+02,4.733705154104800861e-01,1.100000010988609489e+01,1.096666705010136255e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626129979554407612e+01,6.696225852353866230e+02,4.733814820753319830e-01,1.100000010988609489e+01,1.096520719608598537e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626220888644408546e+01,6.696325852293748540e+02,4.733924472803306971e-01,1.100000010988609489e+01,1.096374734207060820e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626311797734409481e+01,6.696425852233646765e+02,4.734034110254762839e-01,1.100000010988609489e+01,1.096228748805523102e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626402706824410416e+01,6.696525852173560907e+02,4.734143733107687435e-01,1.100000010988609489e+01,1.096082763403985385e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626493615914411350e+01,6.696625852113490964e+02,4.734253341362080758e-01,1.100000010988609489e+01,1.095936778002447667e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626584525004412285e+01,6.696725852053436938e+02,4.734362935017942808e-01,1.100000010988609489e+01,1.095790792600909950e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626675434094413220e+01,6.696825851993398828e+02,4.734472514075273031e-01,1.100000010988609489e+01,1.095644807199372232e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626766343184414154e+01,6.696925851933376634e+02,4.734582078534071981e-01,1.100000010988609489e+01,1.095498821797834515e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626857252274415089e+01,6.697025851873370357e+02,4.734691628394339658e-01,1.100000010988609489e+01,1.095352836396296797e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.626948161364416023e+01,6.697125851813379995e+02,4.734801163656076062e-01,1.100000010988609489e+01,1.095206850994759080e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627039070454416958e+01,6.697225851753405550e+02,4.734910684319281193e-01,1.100000010988609489e+01,1.095060865593221362e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627129979544417893e+01,6.697325851693448158e+02,4.735020190383954497e-01,1.100000010988609489e+01,1.094914880191683645e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627220888634418827e+01,6.697425851633506682e+02,4.735129681850096528e-01,1.100000010988609489e+01,1.094768894790145927e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627311797724419762e+01,6.697525851573581122e+02,4.735239158717707286e-01,1.100000010988609489e+01,1.094622909388608210e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627402706814420696e+01,6.697625851513671478e+02,4.735348620986786772e-01,1.100000010988609489e+01,1.094476923987070492e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627493615904421631e+01,6.697725851453777750e+02,4.735458068657334429e-01,1.100000010988609489e+01,1.094330938585532775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627584524994422566e+01,6.697825851393899939e+02,4.735567501729350814e-01,1.100000010988609489e+01,1.094184953183995057e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627675434084423500e+01,6.697925851334038043e+02,4.735676920202835927e-01,1.100000010988609489e+01,1.094038967782457340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627766343174424435e+01,6.698025851274192064e+02,4.735786324077789766e-01,1.100000010988609489e+01,1.093892982380919622e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627857252264425370e+01,6.698125851214362001e+02,4.735895713354211778e-01,1.100000010988609489e+01,1.093746996979381905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.627948161354426304e+01,6.698225851154547854e+02,4.736005088032102517e-01,1.100000010988609489e+01,1.093601011577844187e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628039070444427239e+01,6.698325851094749623e+02,4.736114448111461983e-01,1.100000010988609489e+01,1.093455026176306469e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628129979534428173e+01,6.698425851034967309e+02,4.736223793592290177e-01,1.100000010988609489e+01,1.093309040774768752e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628220888624429108e+01,6.698525850975200910e+02,4.736333124474586542e-01,1.100000010988609489e+01,1.093163055373231034e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628311797714430043e+01,6.698625850915450428e+02,4.736442440758351635e-01,1.100000010988609489e+01,1.093017069971693317e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628402706804430977e+01,6.698725850855715862e+02,4.736551742443585455e-01,1.100000010988609489e+01,1.092871084570155599e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628493615894431912e+01,6.698825850795997212e+02,4.736661029530287448e-01,1.100000010988609489e+01,1.092725099168617882e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628584524984432846e+01,6.698925850736294478e+02,4.736770302018458167e-01,1.100000010988609489e+01,1.092579113767080164e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628675434074433781e+01,6.699025850676607661e+02,4.736879559908097614e-01,1.100000010988609489e+01,1.092433128365542447e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628766343164434716e+01,6.699125850616936759e+02,4.736988803199205234e-01,1.100000010988609489e+01,1.092287142964004729e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628857252254435650e+01,6.699225850557281774e+02,4.737098031891781580e-01,1.100000010988609489e+01,1.092141157562467012e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.628948161344436585e+01,6.699325850497642705e+02,4.737207245985826654e-01,1.100000010988609489e+01,1.091995172160929294e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629039070434437519e+01,6.699425850438019552e+02,4.737316445481340454e-01,1.100000010988609489e+01,1.091849186759391577e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629129979524438454e+01,6.699525850378412315e+02,4.737425630378322428e-01,1.100000010988609489e+01,1.091703201357853859e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629220888614439389e+01,6.699625850318820994e+02,4.737534800676773128e-01,1.100000010988609489e+01,1.091557215956316142e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629311797704440323e+01,6.699725850259245590e+02,4.737643956376692556e-01,1.100000010988609489e+01,1.091411230554778424e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629402706794441258e+01,6.699825850199687238e+02,4.737753097478080155e-01,1.100000010988609489e+01,1.091265245153240707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629493615884442193e+01,6.699925850140144803e+02,4.737862223980936482e-01,1.100000010988609489e+01,1.091119259751702989e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629584524974443127e+01,6.700025850080618284e+02,4.737971335885261537e-01,1.100000010988609489e+01,1.090973274350165272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629675434064444062e+01,6.700125850021107681e+02,4.738080433191054763e-01,1.100000010988609489e+01,1.090827288948627554e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629766343154444996e+01,6.700225849961612994e+02,4.738189515898316717e-01,1.100000010988609489e+01,1.090681303547089837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629857252244445931e+01,6.700325849902134223e+02,4.738298584007046843e-01,1.100000010988609489e+01,1.090535318145552119e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.629948161334446866e+01,6.700425849842671369e+02,4.738407637517245696e-01,1.100000010988609489e+01,1.090389332744014401e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630039070424447800e+01,6.700525849783224430e+02,4.738516676428913277e-01,1.100000010988609489e+01,1.090243347342476684e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630129979514448735e+01,6.700625849723793408e+02,4.738625700742049029e-01,1.100000010988609489e+01,1.090097361940938966e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630220888604449669e+01,6.700725849664378302e+02,4.738734710456653509e-01,1.100000010988609489e+01,1.089951376539401249e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630311797694450604e+01,6.700825849604979112e+02,4.738843705572726717e-01,1.100000010988609489e+01,1.089805391137863531e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630402706784451539e+01,6.700925849545595838e+02,4.738952686090268096e-01,1.100000010988609489e+01,1.089659405736325814e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630493615874452473e+01,6.701025849486228481e+02,4.739061652009278203e-01,1.100000010988609489e+01,1.089513420334788096e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630584524964453408e+01,6.701125849426877039e+02,4.739170603329756482e-01,1.100000010988609489e+01,1.089367434933250379e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630675434054454342e+01,6.701225849367541514e+02,4.739279540051703488e-01,1.100000010988609489e+01,1.089221449531712661e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630766343144455277e+01,6.701325849308221905e+02,4.739388462175119221e-01,1.100000010988609489e+01,1.089075464130174944e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630857252234456212e+01,6.701425849248917075e+02,4.739497369700003127e-01,1.100000010988609489e+01,1.088929478728637226e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.630948161324457146e+01,6.701525849189628161e+02,4.739606262626355759e-01,1.100000010988609489e+01,1.088783493327099509e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631039070414458081e+01,6.701625849130355164e+02,4.739715140954176564e-01,1.100000010988609489e+01,1.088637507925561791e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631129979504459016e+01,6.701725849071098082e+02,4.739824004683466097e-01,1.100000010988609489e+01,1.088491522524024074e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631220888594459950e+01,6.701825849011856917e+02,4.739932853814224356e-01,1.100000010988609489e+01,1.088345537122486356e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631311797684460885e+01,6.701925848952631668e+02,4.740041688346450788e-01,1.100000010988609489e+01,1.088199551720948639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631402706774461819e+01,6.702025848893422335e+02,4.740150508280145947e-01,1.100000010988609489e+01,1.088053566319410921e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631493615864462754e+01,6.702125848834228918e+02,4.740259313615309278e-01,1.100000010988609489e+01,1.087907580917873204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631584524954463689e+01,6.702225848775051418e+02,4.740368104351941336e-01,1.100000010988609489e+01,1.087761595516335486e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631675434044464623e+01,6.702325848715889833e+02,4.740476880490042122e-01,1.100000010988609489e+01,1.087615610114797769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631766343134465558e+01,6.702425848656744165e+02,4.740585642029611080e-01,1.100000010988609489e+01,1.087469624713260051e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631857252224466492e+01,6.702525848597614413e+02,4.740694388970648765e-01,1.100000010988609489e+01,1.087323639311722333e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.631948161314467427e+01,6.702625848538500577e+02,4.740803121313154622e-01,1.100000010988609489e+01,1.087177653910184616e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632039070404468362e+01,6.702725848479402657e+02,4.740911839057129207e-01,1.100000010988609489e+01,1.087031668508646898e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632129979494469296e+01,6.702825848420320654e+02,4.741020542202571963e-01,1.100000010988609489e+01,1.086885683107109181e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632220888584470231e+01,6.702925848361254566e+02,4.741129230749483447e-01,1.100000010988609489e+01,1.086739697705571463e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632311797674471165e+01,6.703025848302204395e+02,4.741237904697863104e-01,1.100000010988609489e+01,1.086593712304033746e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632402706764472100e+01,6.703125848243170140e+02,4.741346564047711487e-01,1.100000010988609489e+01,1.086447726902496028e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632493615854473035e+01,6.703225848184151801e+02,4.741455208799028043e-01,1.100000010988609489e+01,1.086301741500958311e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632584524944473969e+01,6.703325848125149378e+02,4.741563838951813326e-01,1.100000010988609489e+01,1.086155756099420593e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632675434034474904e+01,6.703425848066162871e+02,4.741672454506066781e-01,1.100000010988609489e+01,1.086009770697882876e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632766343124475839e+01,6.703525848007192280e+02,4.741781055461788963e-01,1.100000010988609489e+01,1.085863785296345158e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632857252214476773e+01,6.703625847948237606e+02,4.741889641818979317e-01,1.100000010988609489e+01,1.085717799894807441e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.632948161304477708e+01,6.703725847889298848e+02,4.741998213577638399e-01,1.100000010988609489e+01,1.085571814493269723e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633039070394478642e+01,6.703825847830376006e+02,4.742106770737765653e-01,1.100000010988609489e+01,1.085425829091732006e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633129979484479577e+01,6.703925847771469080e+02,4.742215313299361634e-01,1.100000010988609489e+01,1.085279843690194288e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633220888574480512e+01,6.704025847712576933e+02,4.742323841262425788e-01,1.100000010988609489e+01,1.085133858288656571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633311797664481446e+01,6.704125847653700703e+02,4.742432354626958668e-01,1.100000010988609489e+01,1.084987872887118853e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633402706754482381e+01,6.704225847594840388e+02,4.742540853392959721e-01,1.100000010988609489e+01,1.084841887485581136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633493615844483315e+01,6.704325847535995990e+02,4.742649337560429501e-01,1.100000010988609489e+01,1.084695902084043418e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633584524934484250e+01,6.704425847477167508e+02,4.742757807129367453e-01,1.100000010988609489e+01,1.084549916682505701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633675434024485185e+01,6.704525847418354942e+02,4.742866262099774133e-01,1.100000010988609489e+01,1.084403931280967983e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633766343114486119e+01,6.704625847359558293e+02,4.742974702471648984e-01,1.100000010988609489e+01,1.084257945879430265e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633857252204487054e+01,6.704725847300777559e+02,4.743083128244992563e-01,1.100000010988609489e+01,1.084111960477892548e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.633948161294487988e+01,6.704825847242012742e+02,4.743191539419804315e-01,1.100000010988609489e+01,1.083965975076354830e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634039070384488923e+01,6.704925847183263841e+02,4.743299935996084793e-01,1.100000010988609489e+01,1.083819989674817113e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634129979474489858e+01,6.705025847124530856e+02,4.743408317973833443e-01,1.100000010988609489e+01,1.083674004273279395e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634220888564490792e+01,6.705125847065813787e+02,4.743516685353050821e-01,1.100000010988609489e+01,1.083528018871741678e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634311797654491727e+01,6.705225847007112634e+02,4.743625038133736371e-01,1.100000010988609489e+01,1.083382033470203960e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634402706744492662e+01,6.705325846948426260e+02,4.743733376315890093e-01,1.100000010988609489e+01,1.083236048068666243e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634493615834493596e+01,6.705425846889755803e+02,4.743841699899512543e-01,1.100000010988609489e+01,1.083090062667128525e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634584524924494531e+01,6.705525846831101262e+02,4.743950008884603164e-01,1.100000010988609489e+01,1.082944077265590808e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634675434014495465e+01,6.705625846772462637e+02,4.744058303271162513e-01,1.100000010988609489e+01,1.082798091864053090e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634766343104496400e+01,6.705725846713839928e+02,4.744166583059190034e-01,1.100000010988609489e+01,1.082652106462515373e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634857252194497335e+01,6.705825846655233136e+02,4.744274848248686283e-01,1.100000010988609489e+01,1.082506121060977655e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.634948161284498269e+01,6.705925846596642259e+02,4.744383098839650703e-01,1.100000010988609489e+01,1.082360135659439938e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635039070374499204e+01,6.706025846538067299e+02,4.744491334832083296e-01,1.100000010988609489e+01,1.082214150257902220e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635129979464500138e+01,6.706125846479508255e+02,4.744599556225984616e-01,1.100000010988609489e+01,1.082068164856364503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635220888554501073e+01,6.706225846420965127e+02,4.744707763021354108e-01,1.100000010988609489e+01,1.081922179454826785e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635311797644502008e+01,6.706325846362437915e+02,4.744815955218192327e-01,1.100000010988609489e+01,1.081776194053289068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635402706734502942e+01,6.706425846303925482e+02,4.744924132816498719e-01,1.100000010988609489e+01,1.081630208651751350e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635493615824503877e+01,6.706525846245428966e+02,4.745032295816273282e-01,1.100000010988609489e+01,1.081484223250213633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635584524914504811e+01,6.706625846186948365e+02,4.745140444217516573e-01,1.100000010988609489e+01,1.081338237848675915e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635675434004505746e+01,6.706725846128483681e+02,4.745248578020228036e-01,1.100000010988609489e+01,1.081192252447138197e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635766343094506681e+01,6.706825846070034913e+02,4.745356697224407672e-01,1.100000010988609489e+01,1.081046267045600480e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635857252184507615e+01,6.706925846011602061e+02,4.745464801830056034e-01,1.100000010988609489e+01,1.080900281644062762e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.635948161274508550e+01,6.707025845953185126e+02,4.745572891837172569e-01,1.100000010988609489e+01,1.080754296242525045e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636039070364509485e+01,6.707125845894784106e+02,4.745680967245757831e-01,1.100000010988609489e+01,1.080608310840987327e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636129979454510419e+01,6.707225845836397866e+02,4.745789028055811265e-01,1.100000010988609489e+01,1.080462325439449610e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636220888544511354e+01,6.707325845778027542e+02,4.745897074267332871e-01,1.100000010988609489e+01,1.080316340037911892e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636311797634512288e+01,6.707425845719673134e+02,4.746005105880323205e-01,1.100000010988609489e+01,1.080170354636374175e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636402706724513223e+01,6.707525845661334643e+02,4.746113122894781711e-01,1.100000010988609489e+01,1.080024369234836457e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636493615814514158e+01,6.707625845603012067e+02,4.746221125310708389e-01,1.100000010988609489e+01,1.079878383833298740e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636584524904515092e+01,6.707725845544705408e+02,4.746329113128103794e-01,1.100000010988609489e+01,1.079732398431761022e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636675433994516027e+01,6.707825845486414664e+02,4.746437086346967371e-01,1.100000010988609489e+01,1.079586413030223305e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636766343084516961e+01,6.707925845428139837e+02,4.746545044967299121e-01,1.100000010988609489e+01,1.079440427628685587e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636857252174517896e+01,6.708025845369879789e+02,4.746652988989099597e-01,1.100000010988609489e+01,1.079294442227147870e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.636948161264518831e+01,6.708125845311635658e+02,4.746760918412368246e-01,1.100000010988609489e+01,1.079148456825610152e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637039070354519765e+01,6.708225845253407442e+02,4.746868833237105068e-01,1.100000010988609489e+01,1.079002471424072435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637129979444520700e+01,6.708325845195195143e+02,4.746976733463310616e-01,1.100000010988609489e+01,1.078856486022534717e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637220888534521634e+01,6.708425845136998760e+02,4.747084619090984337e-01,1.100000010988609489e+01,1.078710500620997000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637311797624522569e+01,6.708525845078818293e+02,4.747192490120126229e-01,1.100000010988609489e+01,1.078564515219459282e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637402706714523504e+01,6.708625845020653742e+02,4.747300346550736849e-01,1.100000010988609489e+01,1.078418529817921565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637493615804524438e+01,6.708725844962503970e+02,4.747408188382815641e-01,1.100000010988609489e+01,1.078272544416383847e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637584524894525373e+01,6.708825844904370115e+02,4.747516015616362606e-01,1.100000010988609489e+01,1.078126559014846129e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637675433984526308e+01,6.708925844846252176e+02,4.747623828251377742e-01,1.100000010988609489e+01,1.077980573613308412e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637766343074527242e+01,6.709025844788150152e+02,4.747731626287861606e-01,1.100000010988609489e+01,1.077834588211770694e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637857252164528177e+01,6.709125844730064046e+02,4.747839409725813642e-01,1.100000010988609489e+01,1.077688602810232977e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.637948161254529111e+01,6.709225844671993855e+02,4.747947178565233850e-01,1.100000010988609489e+01,1.077542617408695259e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638039070344530046e+01,6.709325844613938443e+02,4.748054932806122785e-01,1.100000010988609489e+01,1.077396632007157542e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638129979434530981e+01,6.709425844555898948e+02,4.748162672448479893e-01,1.100000010988609489e+01,1.077250646605619824e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638220888524531915e+01,6.709525844497875369e+02,4.748270397492305173e-01,1.100000010988609489e+01,1.077104661204082107e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638311797614532850e+01,6.709625844439867706e+02,4.748378107937598624e-01,1.100000010988609489e+01,1.076958675802544389e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638402706704533784e+01,6.709725844381875959e+02,4.748485803784360804e-01,1.100000010988609489e+01,1.076812690401006672e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638493615794534719e+01,6.709825844323900128e+02,4.748593485032591155e-01,1.100000010988609489e+01,1.076666704999468954e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638584524884535654e+01,6.709925844265939077e+02,4.748701151682289678e-01,1.100000010988609489e+01,1.076520719597931237e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638675433974536588e+01,6.710025844207993941e+02,4.748808803733456374e-01,1.100000010988609489e+01,1.076374734196393519e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638766343064537523e+01,6.710125844150064722e+02,4.748916441186091797e-01,1.100000010988609489e+01,1.076228748794855802e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638857252154538457e+01,6.710225844092151419e+02,4.749024064040195392e-01,1.100000010988609489e+01,1.076082763393318084e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.638948161244539392e+01,6.710325844034254033e+02,4.749131672295767159e-01,1.100000010988609489e+01,1.075936777991780367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639039070334540327e+01,6.710425843976372562e+02,4.749239265952807099e-01,1.100000010988609489e+01,1.075790792590242649e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639129979424541261e+01,6.710525843918505871e+02,4.749346845011315210e-01,1.100000010988609489e+01,1.075644807188704932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639220888514542196e+01,6.710625843860655095e+02,4.749454409471292049e-01,1.100000010988609489e+01,1.075498821787167214e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639311797604543131e+01,6.710725843802820236e+02,4.749561959332737060e-01,1.100000010988609489e+01,1.075352836385629497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639402706694544065e+01,6.710825843745001293e+02,4.749669494595650243e-01,1.100000010988609489e+01,1.075206850984091779e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639493615784545000e+01,6.710925843687198267e+02,4.749777015260031598e-01,1.100000010988609489e+01,1.075060865582554061e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639584524874545934e+01,6.711025843629410019e+02,4.749884521325881126e-01,1.100000010988609489e+01,1.074914880181016344e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639675433964546869e+01,6.711125843571637688e+02,4.749992012793199381e-01,1.100000010988609489e+01,1.074768894779478626e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639766343054547804e+01,6.711225843513881273e+02,4.750099489661985808e-01,1.100000010988609489e+01,1.074622909377940909e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639857252144548738e+01,6.711325843456140774e+02,4.750206951932240407e-01,1.100000010988609489e+01,1.074476923976403191e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.639948161234549673e+01,6.711425843398416191e+02,4.750314399603963178e-01,1.100000010988609489e+01,1.074330938574865474e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640039070324550607e+01,6.711525843340706388e+02,4.750421832677154121e-01,1.100000010988609489e+01,1.074184953173327756e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640129979414551542e+01,6.711625843283012500e+02,4.750529251151813792e-01,1.100000010988609489e+01,1.074038967771790039e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640220888504552477e+01,6.711725843225334529e+02,4.750636655027941635e-01,1.100000010988609489e+01,1.073892982370252321e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640311797594553411e+01,6.711825843167672474e+02,4.750744044305537650e-01,1.100000010988609489e+01,1.073746996968714604e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640402706684554346e+01,6.711925843110026335e+02,4.750851418984601837e-01,1.100000010988609489e+01,1.073601011567176886e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640493615774555280e+01,6.712025843052394976e+02,4.750958779065134197e-01,1.100000010988609489e+01,1.073455026165639169e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640584524864556215e+01,6.712125842994779532e+02,4.751066124547134728e-01,1.100000010988609489e+01,1.073309040764101451e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640675433954557150e+01,6.712225842937180005e+02,4.751173455430603987e-01,1.100000010988609489e+01,1.073163055362563734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640766343044558084e+01,6.712325842879596394e+02,4.751280771715541418e-01,1.100000010988609489e+01,1.073017069961026016e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640857252134559019e+01,6.712425842822027562e+02,4.751388073401947021e-01,1.100000010988609489e+01,1.072871084559488299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.640948161224559954e+01,6.712525842764474646e+02,4.751495360489820796e-01,1.100000010988609489e+01,1.072725099157950581e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641039070314560888e+01,6.712625842706937647e+02,4.751602632979162744e-01,1.100000010988609489e+01,1.072579113756412864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641129979404561823e+01,6.712725842649416563e+02,4.751709890869972863e-01,1.100000010988609489e+01,1.072433128354875146e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641220888494562757e+01,6.712825842591911396e+02,4.751817134162251155e-01,1.100000010988609489e+01,1.072287142953337429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641311797584563692e+01,6.712925842534421008e+02,4.751924362855998174e-01,1.100000010988609489e+01,1.072141157551799711e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641402706674564627e+01,6.713025842476946536e+02,4.752031576951213365e-01,1.100000010988609489e+01,1.071995172150261993e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641493615764565561e+01,6.713125842419487981e+02,4.752138776447896729e-01,1.100000010988609489e+01,1.071849186748724276e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641584524854566496e+01,6.713225842362045341e+02,4.752245961346048264e-01,1.100000010988609489e+01,1.071703201347186558e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641675433944567430e+01,6.713325842304617481e+02,4.752353131645667972e-01,1.100000010988609489e+01,1.071557215945648841e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641766343034568365e+01,6.713425842247205537e+02,4.752460287346755852e-01,1.100000010988609489e+01,1.071411230544111123e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641857252124569300e+01,6.713525842189809509e+02,4.752567428449311904e-01,1.100000010988609489e+01,1.071265245142573406e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.641948161214570234e+01,6.713625842132429398e+02,4.752674554953336128e-01,1.100000010988609489e+01,1.071119259741035688e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642039070304571169e+01,6.713725842075064065e+02,4.752781666858828524e-01,1.100000010988609489e+01,1.070973274339497971e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642129979394572104e+01,6.713825842017714649e+02,4.752888764165789093e-01,1.100000010988609489e+01,1.070827288937960253e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642220888484573038e+01,6.713925841960381149e+02,4.752995846874218389e-01,1.100000010988609489e+01,1.070681303536422536e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642311797574573973e+01,6.714025841903063565e+02,4.753102914984115857e-01,1.100000010988609489e+01,1.070535318134884818e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642402706664574907e+01,6.714125841845760760e+02,4.753209968495481497e-01,1.100000010988609489e+01,1.070389332733347101e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642493615754575842e+01,6.714225841788473872e+02,4.753317007408315309e-01,1.100000010988609489e+01,1.070243347331809383e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642584524844576777e+01,6.714325841731202900e+02,4.753424031722617293e-01,1.100000010988609489e+01,1.070097361930271666e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642675433934577711e+01,6.714425841673947843e+02,4.753531041438387450e-01,1.100000010988609489e+01,1.069951376528733948e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642766343024578646e+01,6.714525841616707567e+02,4.753638036555625779e-01,1.100000010988609489e+01,1.069805391127196231e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642857252114579580e+01,6.714625841559483206e+02,4.753745017074332280e-01,1.100000010988609489e+01,1.069659405725658513e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.642948161204580515e+01,6.714725841502274761e+02,4.753851982994506953e-01,1.100000010988609489e+01,1.069513420324120796e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643039070294581450e+01,6.714825841445082233e+02,4.753958934316149798e-01,1.100000010988609489e+01,1.069367434922583078e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643129979384582384e+01,6.714925841387904484e+02,4.754065871039260816e-01,1.100000010988609489e+01,1.069221449521045361e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643220888474583319e+01,6.715025841330742651e+02,4.754172793163840005e-01,1.100000010988609489e+01,1.069075464119507643e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643311797564584253e+01,6.715125841273596734e+02,4.754279700689887367e-01,1.100000010988609489e+01,1.068929478717969925e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643402706654585188e+01,6.715225841216466733e+02,4.754386593617402901e-01,1.100000010988609489e+01,1.068783493316432208e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643493615744586123e+01,6.715325841159351512e+02,4.754493471946386607e-01,1.100000010988609489e+01,1.068637507914894490e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643584524834587057e+01,6.715425841102252207e+02,4.754600335676838485e-01,1.100000010988609489e+01,1.068491522513356773e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643675433924587992e+01,6.715525841045168818e+02,4.754707184808758536e-01,1.100000010988609489e+01,1.068345537111819055e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643766343014588927e+01,6.715625840988100208e+02,4.754814019342146758e-01,1.100000010988609489e+01,1.068199551710281338e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643857252104589861e+01,6.715725840931047514e+02,4.754920839277003153e-01,1.100000010988609489e+01,1.068053566308743620e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.643948161194590796e+01,6.715825840874010737e+02,4.755027644613327720e-01,1.100000010988609489e+01,1.067907580907205903e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644039070284591730e+01,6.715925840816989876e+02,4.755134435351120459e-01,1.100000010988609489e+01,1.067761595505668185e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644129979374592665e+01,6.716025840759983794e+02,4.755241211490381370e-01,1.100000010988609489e+01,1.067615610104130468e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644220888464593600e+01,6.716125840702993628e+02,4.755347973031110453e-01,1.100000010988609489e+01,1.067469624702592750e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644311797554594534e+01,6.716225840646019378e+02,4.755454719973307709e-01,1.100000010988609489e+01,1.067323639301055033e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644402706644595469e+01,6.716325840589059908e+02,4.755561452316973137e-01,1.100000010988609489e+01,1.067177653899517315e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644493615734596403e+01,6.716425840532116354e+02,4.755668170062106737e-01,1.100000010988609489e+01,1.067031668497979598e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644584524824597338e+01,6.716525840475188716e+02,4.755774873208708509e-01,1.100000010988609489e+01,1.066885683096441880e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644675433914598273e+01,6.716625840418276994e+02,4.755881561756778453e-01,1.100000010988609489e+01,1.066739697694904163e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644766343004599207e+01,6.716725840361380051e+02,4.755988235706316569e-01,1.100000010988609489e+01,1.066593712293366445e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644857252094600142e+01,6.716825840304499025e+02,4.756094895057322858e-01,1.100000010988609489e+01,1.066447726891828728e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.644948161184601076e+01,6.716925840247633914e+02,4.756201539809797318e-01,1.100000010988609489e+01,1.066301741490291010e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645039070274602011e+01,6.717025840190783583e+02,4.756308169963739951e-01,1.100000010988609489e+01,1.066155756088753292e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645129979364602946e+01,6.717125840133949168e+02,4.756414785519150756e-01,1.100000010988609489e+01,1.066009770687215575e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645220888454603880e+01,6.717225840077130670e+02,4.756521386476029734e-01,1.100000010988609489e+01,1.065863785285677857e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645311797544604815e+01,6.717325840020326950e+02,4.756627972834376883e-01,1.100000010988609489e+01,1.065717799884140140e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645402706634605750e+01,6.717425839963539147e+02,4.756734544594192204e-01,1.100000010988609489e+01,1.065571814482602422e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645493615724606684e+01,6.717525839906767260e+02,4.756841101755475698e-01,1.100000010988609489e+01,1.065425829081064705e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645584524814607619e+01,6.717625839850010152e+02,4.756947644318227364e-01,1.100000010988609489e+01,1.065279843679526987e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645675433904608553e+01,6.717725839793268960e+02,4.757054172282447202e-01,1.100000010988609489e+01,1.065133858277989270e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645766342994609488e+01,6.717825839736543685e+02,4.757160685648134657e-01,1.100000010988609489e+01,1.064987872876451552e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645857252084610423e+01,6.717925839679833189e+02,4.757267184415290284e-01,1.100000010988609489e+01,1.064841887474913835e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.645948161174611357e+01,6.718025839623138609e+02,4.757373668583914084e-01,1.100000010988609489e+01,1.064695902073376117e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646039070264612292e+01,6.718125839566459945e+02,4.757480138154006055e-01,1.100000010988609489e+01,1.064549916671838400e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646129979354613226e+01,6.718225839509796060e+02,4.757586593125566199e-01,1.100000010988609489e+01,1.064403931270300682e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646220888444614161e+01,6.718325839453148092e+02,4.757693033498594515e-01,1.100000010988609489e+01,1.064257945868762965e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646311797534615096e+01,6.718425839396516039e+02,4.757799459273091003e-01,1.100000010988609489e+01,1.064111960467225247e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646402706624616030e+01,6.718525839339898766e+02,4.757905870449055663e-01,1.100000010988609489e+01,1.063965975065687530e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646493615714616965e+01,6.718625839283297410e+02,4.758012267026488495e-01,1.100000010988609489e+01,1.063819989664149812e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646584524804617899e+01,6.718725839226711969e+02,4.758118649005389500e-01,1.100000010988609489e+01,1.063674004262612095e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646675433894618834e+01,6.718825839170141307e+02,4.758225016385758122e-01,1.100000010988609489e+01,1.063528018861074377e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646766342984619769e+01,6.718925839113586562e+02,4.758331369167594915e-01,1.100000010988609489e+01,1.063382033459536660e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646857252074620703e+01,6.719025839057047733e+02,4.758437707350899881e-01,1.100000010988609489e+01,1.063236048057998942e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.646948161164621638e+01,6.719125839000523683e+02,4.758544030935673019e-01,1.100000010988609489e+01,1.063090062656461224e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647039070254622573e+01,6.719225838944015550e+02,4.758650339921914330e-01,1.100000010988609489e+01,1.062944077254923507e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647129979344623507e+01,6.719325838887523332e+02,4.758756634309623812e-01,1.100000010988609489e+01,1.062798091853385789e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647220888434624442e+01,6.719425838831045894e+02,4.758862914098801467e-01,1.100000010988609489e+01,1.062652106451848072e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647311797524625376e+01,6.719525838774584372e+02,4.758969179289447293e-01,1.100000010988609489e+01,1.062506121050310354e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647402706614626311e+01,6.719625838718138766e+02,4.759075429881560737e-01,1.100000010988609489e+01,1.062360135648772637e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647493615704627246e+01,6.719725838661707940e+02,4.759181665875142353e-01,1.100000010988609489e+01,1.062214150247234919e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647584524794628180e+01,6.719825838605293029e+02,4.759287887270192141e-01,1.100000010988609489e+01,1.062068164845697202e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647675433884629115e+01,6.719925838548894035e+02,4.759394094066710101e-01,1.100000010988609489e+01,1.061922179444159484e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647766342974630049e+01,6.720025838492509820e+02,4.759500286264696234e-01,1.100000010988609489e+01,1.061776194042621767e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647857252064630984e+01,6.720125838436141521e+02,4.759606463864150538e-01,1.100000010988609489e+01,1.061630208641084049e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.647948161154631919e+01,6.720225838379789138e+02,4.759712626865072460e-01,1.100000010988609489e+01,1.061484223239546332e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648039070244632853e+01,6.720325838323451535e+02,4.759818775267462554e-01,1.100000010988609489e+01,1.061338237838008614e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648129979334633788e+01,6.720425838267129848e+02,4.759924909071320820e-01,1.100000010988609489e+01,1.061192252436470897e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648220888424634722e+01,6.720525838210822940e+02,4.760031028276647258e-01,1.100000010988609489e+01,1.061046267034933179e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648311797514635657e+01,6.720625838154531948e+02,4.760137132883441868e-01,1.100000010988609489e+01,1.060900281633395462e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648402706604636592e+01,6.720725838098256872e+02,4.760243222891704096e-01,1.100000010988609489e+01,1.060754296231857744e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648493615694637526e+01,6.720825838041996576e+02,4.760349298301434495e-01,1.100000010988609489e+01,1.060608310830320027e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648584524784638461e+01,6.720925837985752196e+02,4.760455359112633067e-01,1.100000010988609489e+01,1.060462325428782309e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648675433874639396e+01,6.721025837929523732e+02,4.760561405325299811e-01,1.100000010988609489e+01,1.060316340027244592e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648766342964640330e+01,6.721125837873310047e+02,4.760667436939434727e-01,1.100000010988609489e+01,1.060170354625706874e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648857252054641265e+01,6.721225837817112279e+02,4.760773453955037260e-01,1.100000010988609489e+01,1.060024369224169156e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.648948161144642199e+01,6.721325837760929289e+02,4.760879456372107965e-01,1.100000010988609489e+01,1.059878383822631439e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649039070234643134e+01,6.721425837704762216e+02,4.760985444190646843e-01,1.100000010988609489e+01,1.059732398421093721e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649129979324644069e+01,6.721525837648611059e+02,4.761091417410653892e-01,1.100000010988609489e+01,1.059586413019556004e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649220888414645003e+01,6.721625837592474682e+02,4.761197376032128559e-01,1.100000010988609489e+01,1.059440427618018286e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649311797504645938e+01,6.721725837536354220e+02,4.761303320055071397e-01,1.100000010988609489e+01,1.059294442216480569e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649402706594646872e+01,6.721825837480248538e+02,4.761409249479482408e-01,1.100000010988609489e+01,1.059148456814942851e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649493615684647807e+01,6.721925837424158772e+02,4.761515164305361592e-01,1.100000010988609489e+01,1.059002471413405134e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649584524774648742e+01,6.722025837368084922e+02,4.761621064532708392e-01,1.100000010988609489e+01,1.058856486011867416e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649675433864649676e+01,6.722125837312025851e+02,4.761726950161523364e-01,1.100000010988609489e+01,1.058710500610329699e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649766342954650611e+01,6.722225837255982697e+02,4.761832821191806508e-01,1.100000010988609489e+01,1.058564515208791981e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649857252044651545e+01,6.722325837199954321e+02,4.761938677623557825e-01,1.100000010988609489e+01,1.058418529807254264e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.649948161134652480e+01,6.722425837143941862e+02,4.762044519456776759e-01,1.100000010988609489e+01,1.058272544405716546e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650039070224653415e+01,6.722525837087945320e+02,4.762150346691463865e-01,1.100000010988609489e+01,1.058126559004178829e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650129979314654349e+01,6.722625837031963556e+02,4.762256159327619143e-01,1.100000010988609489e+01,1.057980573602641111e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650220888404655284e+01,6.722725836975997709e+02,4.762361957365242593e-01,1.100000010988609489e+01,1.057834588201103394e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650311797494656219e+01,6.722825836920046640e+02,4.762467740804333660e-01,1.100000010988609489e+01,1.057688602799565676e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650402706584657153e+01,6.722925836864111488e+02,4.762573509644892900e-01,1.100000010988609489e+01,1.057542617398027959e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650493615674658088e+01,6.723025836808191116e+02,4.762679263886920311e-01,1.100000010988609489e+01,1.057396631996490241e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650584524764659022e+01,6.723125836752286659e+02,4.762785003530415340e-01,1.100000010988609489e+01,1.057250646594952524e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650675433854659957e+01,6.723225836696398119e+02,4.762890728575378541e-01,1.100000010988609489e+01,1.057104661193414806e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650766342944660892e+01,6.723325836640524358e+02,4.762996439021809914e-01,1.100000010988609489e+01,1.056958675791877088e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650857252034661826e+01,6.723425836584666513e+02,4.763102134869709459e-01,1.100000010988609489e+01,1.056812690390339371e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.650948161124662761e+01,6.723525836528823447e+02,4.763207816119076621e-01,1.100000010988609489e+01,1.056666704988801653e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651039070214663695e+01,6.723625836472996298e+02,4.763313482769911955e-01,1.100000010988609489e+01,1.056520719587263936e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651129979304664630e+01,6.723725836417185064e+02,4.763419134822215462e-01,1.100000010988609489e+01,1.056374734185726218e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651220888394665565e+01,6.723825836361388610e+02,4.763524772275986585e-01,1.100000010988609489e+01,1.056228748784188501e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651311797484666499e+01,6.723925836305608073e+02,4.763630395131225881e-01,1.100000010988609489e+01,1.056082763382650783e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651402706574667434e+01,6.724025836249842314e+02,4.763736003387933349e-01,1.100000010988609489e+01,1.055936777981113066e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651493615664668368e+01,6.724125836194092471e+02,4.763841597046108434e-01,1.100000010988609489e+01,1.055790792579575348e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651584524754669303e+01,6.724225836138357408e+02,4.763947176105751691e-01,1.100000010988609489e+01,1.055644807178037631e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651675433844670238e+01,6.724325836082638261e+02,4.764052740566863120e-01,1.100000010988609489e+01,1.055498821776499913e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651766342934671172e+01,6.724425836026933894e+02,4.764158290429442166e-01,1.100000010988609489e+01,1.055352836374962196e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651857252024672107e+01,6.724525835971245442e+02,4.764263825693489385e-01,1.100000010988609489e+01,1.055206850973424478e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.651948161114673042e+01,6.724625835915572907e+02,4.764369346359004775e-01,1.100000010988609489e+01,1.055060865571886761e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652039070204673976e+01,6.724725835859915151e+02,4.764474852425987783e-01,1.100000010988609489e+01,1.054914880170349043e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652129979294674911e+01,6.724825835804273311e+02,4.764580343894438963e-01,1.100000010988609489e+01,1.054768894768811326e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652220888384675845e+01,6.724925835748646250e+02,4.764685820764357760e-01,1.100000010988609489e+01,1.054622909367273608e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652311797474676780e+01,6.725025835693035106e+02,4.764791283035744729e-01,1.100000010988609489e+01,1.054476923965735891e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652402706564677715e+01,6.725125835637438740e+02,4.764896730708599870e-01,1.100000010988609489e+01,1.054330938564198173e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652493615654678649e+01,6.725225835581858291e+02,4.765002163782922628e-01,1.100000010988609489e+01,1.054184953162660456e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652584524744679584e+01,6.725325835526292622e+02,4.765107582258713559e-01,1.100000010988609489e+01,1.054038967761122738e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652675433834680518e+01,6.725425835470742868e+02,4.765212986135972661e-01,1.100000010988609489e+01,1.053892982359585020e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652766342924681453e+01,6.725525835415207894e+02,4.765318375414699381e-01,1.100000010988609489e+01,1.053746996958047303e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652857252014682388e+01,6.725625835359688836e+02,4.765423750094894273e-01,1.100000010988609489e+01,1.053601011556509585e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.652948161104683322e+01,6.725725835304184557e+02,4.765529110176556782e-01,1.100000010988609489e+01,1.053455026154971868e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653039070194684257e+01,6.725825835248696194e+02,4.765634455659687463e-01,1.100000010988609489e+01,1.053309040753434150e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653129979284685191e+01,6.725925835193223747e+02,4.765739786544286316e-01,1.100000010988609489e+01,1.053163055351896433e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653220888374686126e+01,6.726025835137766080e+02,4.765845102830352786e-01,1.100000010988609489e+01,1.053017069950358715e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653311797464687061e+01,6.726125835082324329e+02,4.765950404517887429e-01,1.100000010988609489e+01,1.052871084548820998e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653402706554687995e+01,6.726225835026897357e+02,4.766055691606889688e-01,1.100000010988609489e+01,1.052725099147283280e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653493615644688930e+01,6.726325834971486302e+02,4.766160964097360120e-01,1.100000010988609489e+01,1.052579113745745563e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653584524734689865e+01,6.726425834916090025e+02,4.766266221989298169e-01,1.100000010988609489e+01,1.052433128344207845e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653675433824690799e+01,6.726525834860709665e+02,4.766371465282704389e-01,1.100000010988609489e+01,1.052287142942670128e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653766342914691734e+01,6.726625834805344084e+02,4.766476693977578782e-01,1.100000010988609489e+01,1.052141157541132410e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653857252004692668e+01,6.726725834749994419e+02,4.766581908073920792e-01,1.100000010988609489e+01,1.051995172139594693e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.653948161094693603e+01,6.726825834694659534e+02,4.766687107571730975e-01,1.100000010988609489e+01,1.051849186738056975e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654039070184694538e+01,6.726925834639340565e+02,4.766792292471008774e-01,1.100000010988609489e+01,1.051703201336519258e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654129979274695472e+01,6.727025834584036375e+02,4.766897462771754745e-01,1.100000010988609489e+01,1.051557215934981540e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654220888364696407e+01,6.727125834528748101e+02,4.767002618473968334e-01,1.100000010988609489e+01,1.051411230533443823e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654311797454697341e+01,6.727225834473474606e+02,4.767107759577650095e-01,1.100000010988609489e+01,1.051265245131906105e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654402706544698276e+01,6.727325834418217028e+02,4.767212886082799472e-01,1.100000010988609489e+01,1.051119259730368388e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654493615634699211e+01,6.727425834362974228e+02,4.767317997989417022e-01,1.100000010988609489e+01,1.050973274328830670e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654584524724700145e+01,6.727525834307747346e+02,4.767423095297502189e-01,1.100000010988609489e+01,1.050827288927292952e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654675433814701080e+01,6.727625834252535242e+02,4.767528178007055528e-01,1.100000010988609489e+01,1.050681303525755235e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654766342904702014e+01,6.727725834197339054e+02,4.767633246118077039e-01,1.100000010988609489e+01,1.050535318124217517e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654857251994702949e+01,6.727825834142157646e+02,4.767738299630566168e-01,1.100000010988609489e+01,1.050389332722679800e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.654948161084703884e+01,6.727925834086992154e+02,4.767843338544523468e-01,1.100000010988609489e+01,1.050243347321142082e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655039070174704818e+01,6.728025834031841441e+02,4.767948362859948386e-01,1.100000010988609489e+01,1.050097361919604365e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655129979264705753e+01,6.728125833976706645e+02,4.768053372576841475e-01,1.100000010988609489e+01,1.049951376518066647e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655220888354706688e+01,6.728225833921586627e+02,4.768158367695202182e-01,1.100000010988609489e+01,1.049805391116528930e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655311797444707622e+01,6.728325833866482526e+02,4.768263348215031061e-01,1.100000010988609489e+01,1.049659405714991212e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655402706534708557e+01,6.728425833811393204e+02,4.768368314136327557e-01,1.100000010988609489e+01,1.049513420313453495e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655493615624709491e+01,6.728525833756319798e+02,4.768473265459092225e-01,1.100000010988609489e+01,1.049367434911915777e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655584524714710426e+01,6.728625833701261172e+02,4.768578202183324510e-01,1.100000010988609489e+01,1.049221449510378060e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655675433804711361e+01,6.728725833646218462e+02,4.768683124309024413e-01,1.100000010988609489e+01,1.049075464108840342e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655766342894712295e+01,6.728825833591190531e+02,4.768788031836192487e-01,1.100000010988609489e+01,1.048929478707302625e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655857251984713230e+01,6.728925833536177379e+02,4.768892924764828178e-01,1.100000010988609489e+01,1.048783493305764907e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.655948161074714164e+01,6.729025833481180143e+02,4.768997803094932042e-01,1.100000010988609489e+01,1.048637507904227190e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656039070164715099e+01,6.729125833426197687e+02,4.769102666826503523e-01,1.100000010988609489e+01,1.048491522502689472e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656129979254716034e+01,6.729225833371231147e+02,4.769207515959543175e-01,1.100000010988609489e+01,1.048345537101151755e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656220888344716968e+01,6.729325833316279386e+02,4.769312350494050445e-01,1.100000010988609489e+01,1.048199551699614037e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656311797434717903e+01,6.729425833261343541e+02,4.769417170430025887e-01,1.100000010988609489e+01,1.048053566298076320e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656402706524718837e+01,6.729525833206422476e+02,4.769521975767468946e-01,1.100000010988609489e+01,1.047907580896538602e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656493615614719772e+01,6.729625833151517327e+02,4.769626766506380178e-01,1.100000010988609489e+01,1.047761595495000884e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656584524704720707e+01,6.729725833096626957e+02,4.769731542646759026e-01,1.100000010988609489e+01,1.047615610093463167e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656675433794721641e+01,6.729825833041752503e+02,4.769836304188605491e-01,1.100000010988609489e+01,1.047469624691925449e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656766342884722576e+01,6.729925832986892829e+02,4.769941051131920129e-01,1.100000010988609489e+01,1.047323639290387732e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656857251974723511e+01,6.730025832932047933e+02,4.770045783476702383e-01,1.100000010988609489e+01,1.047177653888850014e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.656948161064724445e+01,6.730125832877218954e+02,4.770150501222952810e-01,1.100000010988609489e+01,1.047031668487312297e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657039070154725380e+01,6.730225832822404755e+02,4.770255204370670854e-01,1.100000010988609489e+01,1.046885683085774579e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657129979244726314e+01,6.730325832767606471e+02,4.770359892919857070e-01,1.100000010988609489e+01,1.046739697684236862e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657220888334727249e+01,6.730425832712822967e+02,4.770464566870510903e-01,1.100000010988609489e+01,1.046593712282699144e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657311797424728184e+01,6.730525832658055378e+02,4.770569226222632353e-01,1.100000010988609489e+01,1.046447726881161427e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657402706514729118e+01,6.730625832603302570e+02,4.770673870976221975e-01,1.100000010988609489e+01,1.046301741479623709e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657493615604730053e+01,6.730725832548565677e+02,4.770778501131279214e-01,1.100000010988609489e+01,1.046155756078085992e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657584524694730987e+01,6.730825832493843563e+02,4.770883116687804626e-01,1.100000010988609489e+01,1.046009770676548274e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657675433784731922e+01,6.730925832439136229e+02,4.770987717645797654e-01,1.100000010988609489e+01,1.045863785275010557e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657766342874732857e+01,6.731025832384444811e+02,4.771092304005258300e-01,1.100000010988609489e+01,1.045717799873472839e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657857251964733791e+01,6.731125832329768173e+02,4.771196875766187118e-01,1.100000010988609489e+01,1.045571814471935122e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.657948161054734726e+01,6.731225832275107450e+02,4.771301432928583552e-01,1.100000010988609489e+01,1.045425829070397404e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658039070144735661e+01,6.731325832220461507e+02,4.771405975492448159e-01,1.100000010988609489e+01,1.045279843668859687e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658129979234736595e+01,6.731425832165831480e+02,4.771510503457780383e-01,1.100000010988609489e+01,1.045133858267321969e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658220888324737530e+01,6.731525832111216232e+02,4.771615016824580224e-01,1.100000010988609489e+01,1.044987872865784252e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658311797414738464e+01,6.731625832056615764e+02,4.771719515592848238e-01,1.100000010988609489e+01,1.044841887464246534e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658402706504739399e+01,6.731725832002031211e+02,4.771823999762583868e-01,1.100000010988609489e+01,1.044695902062708816e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658493615594740334e+01,6.731825831947461438e+02,4.771928469333787115e-01,1.100000010988609489e+01,1.044549916661171099e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658584524684741268e+01,6.731925831892907581e+02,4.772032924306458535e-01,1.100000010988609489e+01,1.044403931259633381e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658675433774742203e+01,6.732025831838368504e+02,4.772137364680597571e-01,1.100000010988609489e+01,1.044257945858095664e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658766342864743137e+01,6.732125831783845342e+02,4.772241790456204225e-01,1.100000010988609489e+01,1.044111960456557946e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658857251954744072e+01,6.732225831729336960e+02,4.772346201633279050e-01,1.100000010988609489e+01,1.043965975055020229e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.658948161044745007e+01,6.732325831674843357e+02,4.772450598211821493e-01,1.100000010988609489e+01,1.043819989653482511e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659039070134745941e+01,6.732425831620365670e+02,4.772554980191831553e-01,1.100000010988609489e+01,1.043674004251944794e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659129979224746876e+01,6.732525831565902763e+02,4.772659347573309785e-01,1.100000010988609489e+01,1.043528018850407076e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659220888314747810e+01,6.732625831511455772e+02,4.772763700356255634e-01,1.100000010988609489e+01,1.043382033448869359e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659311797404748745e+01,6.732725831457023560e+02,4.772868038540669100e-01,1.100000010988609489e+01,1.043236048047331641e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659402706494749680e+01,6.732825831402606127e+02,4.772972362126550738e-01,1.100000010988609489e+01,1.043090062645793924e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659493615584750614e+01,6.732925831348204611e+02,4.773076671113899994e-01,1.100000010988609489e+01,1.042944077244256206e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659584524674751549e+01,6.733025831293817873e+02,4.773180965502716866e-01,1.100000010988609489e+01,1.042798091842718489e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659675433764752484e+01,6.733125831239447052e+02,4.773285245293001910e-01,1.100000010988609489e+01,1.042652106441180771e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659766342854753418e+01,6.733225831185091010e+02,4.773389510484754572e-01,1.100000010988609489e+01,1.042506121039643054e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659857251944754353e+01,6.733325831130749748e+02,4.773493761077974851e-01,1.100000010988609489e+01,1.042360135638105336e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.659948161034755287e+01,6.733425831076424402e+02,4.773597997072662746e-01,1.100000010988609489e+01,1.042214150236567619e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660039070124756222e+01,6.733525831022113834e+02,4.773702218468818814e-01,1.100000010988609489e+01,1.042068164835029901e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660129979214757157e+01,6.733625830967818047e+02,4.773806425266442499e-01,1.100000010988609489e+01,1.041922179433492184e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660220888304758091e+01,6.733725830913538175e+02,4.773910617465533801e-01,1.100000010988609489e+01,1.041776194031954466e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660311797394759026e+01,6.733825830859273083e+02,4.774014795066093275e-01,1.100000010988609489e+01,1.041630208630416748e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660402706484759960e+01,6.733925830805023907e+02,4.774118958068120366e-01,1.100000010988609489e+01,1.041484223228879031e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660493615574760895e+01,6.734025830750789510e+02,4.774223106471615075e-01,1.100000010988609489e+01,1.041338237827341313e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660584524664761830e+01,6.734125830696569892e+02,4.774327240276577400e-01,1.100000010988609489e+01,1.041192252425803596e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660675433754762764e+01,6.734225830642366191e+02,4.774431359483007897e-01,1.100000010988609489e+01,1.041046267024265878e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660766342844763699e+01,6.734325830588177269e+02,4.774535464090906012e-01,1.100000010988609489e+01,1.040900281622728161e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660857251934764633e+01,6.734425830534003126e+02,4.774639554100271743e-01,1.100000010988609489e+01,1.040754296221190443e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.660948161024765568e+01,6.734525830479844899e+02,4.774743629511105092e-01,1.100000010988609489e+01,1.040608310819652726e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661039070114766503e+01,6.734625830425701452e+02,4.774847690323406613e-01,1.100000010988609489e+01,1.040462325418115008e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661129979204767437e+01,6.734725830371573920e+02,4.774951736537175750e-01,1.100000010988609489e+01,1.040316340016577291e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661220888294768372e+01,6.734825830317461168e+02,4.775055768152412505e-01,1.100000010988609489e+01,1.040170354615039573e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661311797384769307e+01,6.734925830263363196e+02,4.775159785169116877e-01,1.100000010988609489e+01,1.040024369213501856e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661402706474770241e+01,6.735025830209281139e+02,4.775263787587289421e-01,1.100000010988609489e+01,1.039878383811964138e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661493615564771176e+01,6.735125830155213862e+02,4.775367775406929582e-01,1.100000010988609489e+01,1.039732398410426421e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661584524654772110e+01,6.735225830101161364e+02,4.775471748628037361e-01,1.100000010988609489e+01,1.039586413008888703e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661675433744773045e+01,6.735325830047124782e+02,4.775575707250612756e-01,1.100000010988609489e+01,1.039440427607350986e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661766342834773980e+01,6.735425829993102980e+02,4.775679651274655768e-01,1.100000010988609489e+01,1.039294442205813268e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661857251924774914e+01,6.735525829939095956e+02,4.775783580700166953e-01,1.100000010988609489e+01,1.039148456804275551e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.661948161014775849e+01,6.735625829885104849e+02,4.775887495527145754e-01,1.100000010988609489e+01,1.039002471402737833e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662039070104776783e+01,6.735725829831128522e+02,4.775991395755592173e-01,1.100000010988609489e+01,1.038856486001200116e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662129979194777718e+01,6.735825829777166973e+02,4.776095281385506208e-01,1.100000010988609489e+01,1.038710500599662398e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662220888284778653e+01,6.735925829723221341e+02,4.776199152416887861e-01,1.100000010988609489e+01,1.038564515198124680e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662311797374779587e+01,6.736025829669290488e+02,4.776303008849737686e-01,1.100000010988609489e+01,1.038418529796586963e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662402706464780522e+01,6.736125829615374414e+02,4.776406850684055128e-01,1.100000010988609489e+01,1.038272544395049245e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662493615554781456e+01,6.736225829561474256e+02,4.776510677919840187e-01,1.100000010988609489e+01,1.038126558993511528e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662584524644782391e+01,6.736325829507588878e+02,4.776614490557092862e-01,1.100000010988609489e+01,1.037980573591973810e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662675433734783326e+01,6.736425829453718279e+02,4.776718288595813156e-01,1.100000010988609489e+01,1.037834588190436093e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662766342824784260e+01,6.736525829399863596e+02,4.776822072036001066e-01,1.100000010988609489e+01,1.037688602788898375e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662857251914785195e+01,6.736625829346023693e+02,4.776925840877657148e-01,1.100000010988609489e+01,1.037542617387360658e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.662948161004786130e+01,6.736725829292198569e+02,4.777029595120780847e-01,1.100000010988609489e+01,1.037396631985822940e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663039070094787064e+01,6.736825829238389360e+02,4.777133334765372163e-01,1.100000010988609489e+01,1.037250646584285223e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663129979184787999e+01,6.736925829184594932e+02,4.777237059811431097e-01,1.100000010988609489e+01,1.037104661182747505e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663220888274788933e+01,6.737025829130815282e+02,4.777340770258957647e-01,1.100000010988609489e+01,1.036958675781209788e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663311797364789868e+01,6.737125829077051549e+02,4.777444466107951815e-01,1.100000010988609489e+01,1.036812690379672070e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663402706454790803e+01,6.737225829023302595e+02,4.777548147358414155e-01,1.100000010988609489e+01,1.036666704978134353e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663493615544791737e+01,6.737325828969568420e+02,4.777651814010344111e-01,1.100000010988609489e+01,1.036520719576596635e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663584524634792672e+01,6.737425828915850161e+02,4.777755466063741685e-01,1.100000010988609489e+01,1.036374734175058918e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663675433724793606e+01,6.737525828862146682e+02,4.777859103518606876e-01,1.100000010988609489e+01,1.036228748773521200e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663766342814794541e+01,6.737625828808457982e+02,4.777962726374939684e-01,1.100000010988609489e+01,1.036082763371983483e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663857251904795476e+01,6.737725828754784061e+02,4.778066334632740109e-01,1.100000010988609489e+01,1.035936777970445765e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.663948160994796410e+01,6.737825828701126056e+02,4.778169928292008151e-01,1.100000010988609489e+01,1.035790792568908047e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664039070084797345e+01,6.737925828647482831e+02,4.778273507352743810e-01,1.100000010988609489e+01,1.035644807167370330e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664129979174798279e+01,6.738025828593854385e+02,4.778377071814947086e-01,1.100000010988609489e+01,1.035498821765832612e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664220888264799214e+01,6.738125828540241855e+02,4.778480621678618534e-01,1.100000010988609489e+01,1.035352836364294895e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664311797354800149e+01,6.738225828486644104e+02,4.778584156943757599e-01,1.100000010988609489e+01,1.035206850962757177e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664402706444801083e+01,6.738325828433061133e+02,4.778687677610364282e-01,1.100000010988609489e+01,1.035060865561219460e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664493615534802018e+01,6.738425828379494078e+02,4.778791183678438581e-01,1.100000010988609489e+01,1.034914880159681742e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664584524624802953e+01,6.738525828325941802e+02,4.778894675147980498e-01,1.100000010988609489e+01,1.034768894758144025e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664675433714803887e+01,6.738625828272404306e+02,4.778998152018990031e-01,1.100000010988609489e+01,1.034622909356606307e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664766342804804822e+01,6.738725828218881588e+02,4.779101614291467182e-01,1.100000010988609489e+01,1.034476923955068590e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664857251894805756e+01,6.738825828165374787e+02,4.779205061965411949e-01,1.100000010988609489e+01,1.034330938553530872e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.664948160984806691e+01,6.738925828111882765e+02,4.779308495040824334e-01,1.100000010988609489e+01,1.034184953151993155e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665039070074807626e+01,6.739025828058405523e+02,4.779411913517704336e-01,1.100000010988609489e+01,1.034038967750455437e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665129979164808560e+01,6.739125828004944196e+02,4.779515317396051954e-01,1.100000010988609489e+01,1.033892982348917720e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665220888254809495e+01,6.739225827951497649e+02,4.779618706675867190e-01,1.100000010988609489e+01,1.033746996947380002e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665311797344810429e+01,6.739325827898065882e+02,4.779722081357150598e-01,1.100000010988609489e+01,1.033601011545842285e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665402706434811364e+01,6.739425827844648893e+02,4.779825441439901623e-01,1.100000010988609489e+01,1.033455026144304567e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665493615524812299e+01,6.739525827791247821e+02,4.779928786924120265e-01,1.100000010988609489e+01,1.033309040742766850e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665584524614813233e+01,6.739625827737861528e+02,4.780032117809806524e-01,1.100000010988609489e+01,1.033163055341229132e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665675433704814168e+01,6.739725827684490014e+02,4.780135434096960401e-01,1.100000010988609489e+01,1.033017069939691415e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665766342794815102e+01,6.739825827631133279e+02,4.780238735785581894e-01,1.100000010988609489e+01,1.032871084538153697e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665857251884816037e+01,6.739925827577792461e+02,4.780342022875671004e-01,1.100000010988609489e+01,1.032725099136615979e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.665948160974816972e+01,6.740025827524466422e+02,4.780445295367227732e-01,1.100000010988609489e+01,1.032579113735078262e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666039070064817906e+01,6.740125827471155162e+02,4.780548553260252076e-01,1.100000010988609489e+01,1.032433128333540544e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666129979154818841e+01,6.740225827417859819e+02,4.780651796554744037e-01,1.100000010988609489e+01,1.032287142932002827e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666220888244819776e+01,6.740325827364579254e+02,4.780755025250703616e-01,1.100000010988609489e+01,1.032141157530465109e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666311797334820710e+01,6.740425827311313469e+02,4.780858239348130811e-01,1.100000010988609489e+01,1.031995172128927392e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666402706424821645e+01,6.740525827258062463e+02,4.780961438847025624e-01,1.100000010988609489e+01,1.031849186727389674e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666493615514822579e+01,6.740625827204827374e+02,4.781064623747388054e-01,1.100000010988609489e+01,1.031703201325851957e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666584524604823514e+01,6.740725827151607064e+02,4.781167794049218100e-01,1.100000010988609489e+01,1.031557215924314239e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666675433694824449e+01,6.740825827098401533e+02,4.781270949752515764e-01,1.100000010988609489e+01,1.031411230522776522e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666766342784825383e+01,6.740925827045210781e+02,4.781374090857281045e-01,1.100000010988609489e+01,1.031265245121238804e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666857251874826318e+01,6.741025826992035945e+02,4.781477217363513943e-01,1.100000010988609489e+01,1.031119259719701087e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.666948160964827252e+01,6.741125826938875889e+02,4.781580329271214458e-01,1.100000010988609489e+01,1.030973274318163369e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667039070054828187e+01,6.741225826885730612e+02,4.781683426580382590e-01,1.100000010988609489e+01,1.030827288916625652e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667129979144829122e+01,6.741325826832600114e+02,4.781786509291018339e-01,1.100000010988609489e+01,1.030681303515087934e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667220888234830056e+01,6.741425826779484396e+02,4.781889577403121705e-01,1.100000010988609489e+01,1.030535318113550217e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667311797324830991e+01,6.741525826726384594e+02,4.781992630916692688e-01,1.100000010988609489e+01,1.030389332712012499e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667402706414831925e+01,6.741625826673299571e+02,4.782095669831731288e-01,1.100000010988609489e+01,1.030243347310474782e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667493615504832860e+01,6.741725826620229327e+02,4.782198694148237506e-01,1.100000010988609489e+01,1.030097361908937064e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667584524594833795e+01,6.741825826567173863e+02,4.782301703866211340e-01,1.100000010988609489e+01,1.029951376507399347e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667675433684834729e+01,6.741925826514134314e+02,4.782404698985652791e-01,1.100000010988609489e+01,1.029805391105861629e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667766342774835664e+01,6.742025826461109546e+02,4.782507679506561860e-01,1.100000010988609489e+01,1.029659405704323911e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667857251864836599e+01,6.742125826408099556e+02,4.782610645428937990e-01,1.100000010988609489e+01,1.029513420302786194e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.667948160954837533e+01,6.742225826355104346e+02,4.782713596752781737e-01,1.100000010988609489e+01,1.029367434901248476e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668039070044838468e+01,6.742325826302125051e+02,4.782816533478093102e-01,1.100000010988609489e+01,1.029221449499710759e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668129979134839402e+01,6.742425826249160536e+02,4.782919455604872083e-01,1.100000010988609489e+01,1.029075464098173041e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668220888224840337e+01,6.742525826196210801e+02,4.783022363133118682e-01,1.100000010988609489e+01,1.028929478696635324e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668311797314841272e+01,6.742625826143275845e+02,4.783125256062832897e-01,1.100000010988609489e+01,1.028783493295097606e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668402706404842206e+01,6.742725826090355667e+02,4.783228134394014730e-01,1.100000010988609489e+01,1.028637507893559889e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668493615494843141e+01,6.742825826037451407e+02,4.783330998126664180e-01,1.100000010988609489e+01,1.028491522492022171e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668584524584844075e+01,6.742925825984561925e+02,4.783433847260781246e-01,1.100000010988609489e+01,1.028345537090484454e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668675433674845010e+01,6.743025825931687223e+02,4.783536681796365930e-01,1.100000010988609489e+01,1.028199551688946736e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668766342764845945e+01,6.743125825878827300e+02,4.783639501733418231e-01,1.100000010988609489e+01,1.028053566287409019e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668857251854846879e+01,6.743225825825982156e+02,4.783742307071938149e-01,1.100000010988609489e+01,1.027907580885871301e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.668948160944847814e+01,6.743325825773152928e+02,4.783845097811925129e-01,1.100000010988609489e+01,1.027761595484333584e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669039070034848748e+01,6.743425825720338480e+02,4.783947873953379726e-01,1.100000010988609489e+01,1.027615610082795866e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669129979124849683e+01,6.743525825667538811e+02,4.784050635496301940e-01,1.100000010988609489e+01,1.027469624681258149e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669220888214850618e+01,6.743625825614753921e+02,4.784153382440691771e-01,1.100000010988609489e+01,1.027323639279720431e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669311797304851552e+01,6.743725825561983811e+02,4.784256114786549219e-01,1.100000010988609489e+01,1.027177653878182714e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669402706394852487e+01,6.743825825509229617e+02,4.784358832533874284e-01,1.100000010988609489e+01,1.027031668476644996e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669493615484853422e+01,6.743925825456490202e+02,4.784461535682666966e-01,1.100000010988609489e+01,1.026885683075107279e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669584524574854356e+01,6.744025825403765566e+02,4.784564224232927265e-01,1.100000010988609489e+01,1.026739697673569561e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669675433664855291e+01,6.744125825351055710e+02,4.784666898184654626e-01,1.100000010988609489e+01,1.026593712272031843e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669766342754856225e+01,6.744225825298360633e+02,4.784769557537849605e-01,1.100000010988609489e+01,1.026447726870494126e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669857251844857160e+01,6.744325825245680335e+02,4.784872202292512200e-01,1.100000010988609489e+01,1.026301741468956408e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.669948160934858095e+01,6.744425825193015953e+02,4.784974832448642412e-01,1.100000010988609489e+01,1.026155756067418691e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670039070024859029e+01,6.744525825140366351e+02,4.785077448006240242e-01,1.100000010988609489e+01,1.026009770665880973e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670129979114859964e+01,6.744625825087731528e+02,4.785180048965305688e-01,1.100000010988609489e+01,1.025863785264343256e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670220888204860898e+01,6.744725825035111484e+02,4.785282635325838752e-01,1.100000010988609489e+01,1.025717799862805538e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670311797294861833e+01,6.744825824982506219e+02,4.785385207087838877e-01,1.100000010988609489e+01,1.025571814461267821e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670402706384862768e+01,6.744925824929916871e+02,4.785487764251306619e-01,1.100000010988609489e+01,1.025425829059730103e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670493615474863702e+01,6.745025824877342302e+02,4.785590306816241979e-01,1.100000010988609489e+01,1.025279843658192386e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670584524564864637e+01,6.745125824824782512e+02,4.785692834782644955e-01,1.100000010988609489e+01,1.025133858256654668e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670675433654865571e+01,6.745225824772237502e+02,4.785795348150515549e-01,1.100000010988609489e+01,1.024987872855116951e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670766342744866506e+01,6.745325824719707271e+02,4.785897846919853760e-01,1.100000010988609489e+01,1.024841887453579233e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670857251834867441e+01,6.745425824667191819e+02,4.786000331090659032e-01,1.100000010988609489e+01,1.024695902052041516e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.670948160924868375e+01,6.745525824614692283e+02,4.786102800662931922e-01,1.100000010988609489e+01,1.024549916650503798e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671039070014869310e+01,6.745625824562207526e+02,4.786205255636672429e-01,1.100000010988609489e+01,1.024403931248966081e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671129979104870245e+01,6.745725824509737549e+02,4.786307696011880553e-01,1.100000010988609489e+01,1.024257945847428363e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671220888194871179e+01,6.745825824457282351e+02,4.786410121788556293e-01,1.100000010988609489e+01,1.024111960445890646e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671311797284872114e+01,6.745925824404841933e+02,4.786512532966699096e-01,1.100000010988609489e+01,1.023965975044352928e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671402706374873048e+01,6.746025824352416294e+02,4.786614929546309516e-01,1.100000010988609489e+01,1.023819989642815211e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671493615464873983e+01,6.746125824300005434e+02,4.786717311527387553e-01,1.100000010988609489e+01,1.023674004241277493e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671584524554874918e+01,6.746225824247610490e+02,4.786819678909933207e-01,1.100000010988609489e+01,1.023528018839739775e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671675433644875852e+01,6.746325824195230325e+02,4.786922031693946478e-01,1.100000010988609489e+01,1.023382033438202058e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671766342734876787e+01,6.746425824142864940e+02,4.787024369879426811e-01,1.100000010988609489e+01,1.023236048036664340e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671857251824877721e+01,6.746525824090514334e+02,4.787126693466374761e-01,1.100000010988609489e+01,1.023090062635126623e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.671948160914878656e+01,6.746625824038178507e+02,4.787229002454790328e-01,1.100000010988609489e+01,1.022944077233588905e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672039070004879591e+01,6.746725823985857460e+02,4.787331296844673512e-01,1.100000010988609489e+01,1.022798091832051188e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672129979094880525e+01,6.746825823933551192e+02,4.787433576636023758e-01,1.100000010988609489e+01,1.022652106430513470e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672220888184881460e+01,6.746925823881260840e+02,4.787535841828841621e-01,1.100000010988609489e+01,1.022506121028975753e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672311797274882395e+01,6.747025823828985267e+02,4.787638092423127101e-01,1.100000010988609489e+01,1.022360135627438035e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672402706364883329e+01,6.747125823776724474e+02,4.787740328418880198e-01,1.100000010988609489e+01,1.022214150225900318e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672493615454884264e+01,6.747225823724478460e+02,4.787842549816100357e-01,1.100000010988609489e+01,1.022068164824362600e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672584524544885198e+01,6.747325823672247225e+02,4.787944756614788133e-01,1.100000010988609489e+01,1.021922179422824883e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672675433634886133e+01,6.747425823620030769e+02,4.788046948814943526e-01,1.100000010988609489e+01,1.021776194021287165e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672766342724887068e+01,6.747525823567829093e+02,4.788149126416566537e-01,1.100000010988609489e+01,1.021630208619749448e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672857251814888002e+01,6.747625823515642196e+02,4.788251289419656609e-01,1.100000010988609489e+01,1.021484223218211730e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.672948160904888937e+01,6.747725823463471215e+02,4.788353437824214298e-01,1.100000010988609489e+01,1.021338237816674013e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673039069994889871e+01,6.747825823411315014e+02,4.788455571630239604e-01,1.100000010988609489e+01,1.021192252415136295e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673129979084890806e+01,6.747925823359173592e+02,4.788557690837731973e-01,1.100000010988609489e+01,1.021046267013598578e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673220888174891741e+01,6.748025823307046949e+02,4.788659795446691958e-01,1.100000010988609489e+01,1.020900281612060860e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673311797264892675e+01,6.748125823254935085e+02,4.788761885457119560e-01,1.100000010988609489e+01,1.020754296210523143e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673402706354893610e+01,6.748225823202838001e+02,4.788863960869014780e-01,1.100000010988609489e+01,1.020608310808985425e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673493615444894544e+01,6.748325823150755696e+02,4.788966021682377061e-01,1.100000010988609489e+01,1.020462325407447707e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673584524534895479e+01,6.748425823098688170e+02,4.789068067897206959e-01,1.100000010988609489e+01,1.020316340005909990e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673675433624896414e+01,6.748525823046635423e+02,4.789170099513504475e-01,1.100000010988609489e+01,1.020170354604372272e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673766342714897348e+01,6.748625822994598593e+02,4.789272116531269052e-01,1.100000010988609489e+01,1.020024369202834555e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673857251804898283e+01,6.748725822942576542e+02,4.789374118950501247e-01,1.100000010988609489e+01,1.019878383801296837e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.673948160894899218e+01,6.748825822890569270e+02,4.789476106771201058e-01,1.100000010988609489e+01,1.019732398399759120e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674039069984900152e+01,6.748925822838576778e+02,4.789578079993367932e-01,1.100000010988609489e+01,1.019586412998221402e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674129979074901087e+01,6.749025822786599065e+02,4.789680038617002422e-01,1.100000010988609489e+01,1.019440427596683685e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674220888164902021e+01,6.749125822734636131e+02,4.789781982642104530e-01,1.100000010988609489e+01,1.019294442195145967e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674311797254902956e+01,6.749225822682687976e+02,4.789883912068673699e-01,1.100000010988609489e+01,1.019148456793608250e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674402706344903891e+01,6.749325822630754601e+02,4.789985826896710486e-01,1.100000010988609489e+01,1.019002471392070532e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674493615434904825e+01,6.749425822578836005e+02,4.790087727126214889e-01,1.100000010988609489e+01,1.018856485990532815e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674584524524905760e+01,6.749525822526932188e+02,4.790189612757186355e-01,1.100000010988609489e+01,1.018710500588995097e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674675433614906694e+01,6.749625822475043151e+02,4.790291483789625437e-01,1.100000010988609489e+01,1.018564515187457380e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674766342704907629e+01,6.749725822423170030e+02,4.790393340223532137e-01,1.100000010988609489e+01,1.018418529785919662e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674857251794908564e+01,6.749825822371311688e+02,4.790495182058905899e-01,1.100000010988609489e+01,1.018272544384381945e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.674948160884909498e+01,6.749925822319468125e+02,4.790597009295747277e-01,1.100000010988609489e+01,1.018126558982844227e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675039069974910433e+01,6.750025822267639342e+02,4.790698821934056273e-01,1.100000010988609489e+01,1.017980573581306510e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675129979064911367e+01,6.750125822215825337e+02,4.790800619973832331e-01,1.100000010988609489e+01,1.017834588179768792e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675220888154912302e+01,6.750225822164026113e+02,4.790902403415076005e-01,1.100000010988609489e+01,1.017688602778231075e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675311797244913237e+01,6.750325822112241667e+02,4.791004172257786742e-01,1.100000010988609489e+01,1.017542617376693357e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675402706334914171e+01,6.750425822060472001e+02,4.791105926501965095e-01,1.100000010988609489e+01,1.017396631975155639e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675493615424915106e+01,6.750525822008717114e+02,4.791207666147611066e-01,1.100000010988609489e+01,1.017250646573617922e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675584524514916041e+01,6.750625821956977006e+02,4.791309391194724099e-01,1.100000010988609489e+01,1.017104661172080204e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675675433604916975e+01,6.750725821905251678e+02,4.791411101643304749e-01,1.100000010988609489e+01,1.016958675770542487e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675766342694917910e+01,6.750825821853541129e+02,4.791512797493353015e-01,1.100000010988609489e+01,1.016812690369004769e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675857251784918844e+01,6.750925821801845359e+02,4.791614478744868344e-01,1.100000010988609489e+01,1.016666704967467052e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.675948160874919779e+01,6.751025821750164368e+02,4.791716145397851290e-01,1.100000010988609489e+01,1.016520719565929334e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676039069964920714e+01,6.751125821698498157e+02,4.791817797452301297e-01,1.100000010988609489e+01,1.016374734164391617e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676129979054921648e+01,6.751225821646846725e+02,4.791919434908218922e-01,1.100000010988609489e+01,1.016228748762853899e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676220888144922583e+01,6.751325821595211210e+02,4.792021057765603609e-01,1.100000010988609489e+01,1.016082763361316182e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676311797234923517e+01,6.751425821543590473e+02,4.792122666024455913e-01,1.100000010988609489e+01,1.015936777959778464e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676402706324924452e+01,6.751525821491984516e+02,4.792224259684775833e-01,1.100000010988609489e+01,1.015790792558240747e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676493615414925387e+01,6.751625821440393338e+02,4.792325838746562816e-01,1.100000010988609489e+01,1.015644807156703029e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676584524504926321e+01,6.751725821388816939e+02,4.792427403209817416e-01,1.100000010988609489e+01,1.015498821755165312e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676675433594927256e+01,6.751825821337255320e+02,4.792528953074539078e-01,1.100000010988609489e+01,1.015352836353627594e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676766342684928190e+01,6.751925821285708480e+02,4.792630488340728356e-01,1.100000010988609489e+01,1.015206850952089877e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676857251774929125e+01,6.752025821234176419e+02,4.792732009008384697e-01,1.100000010988609489e+01,1.015060865550552159e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.676948160864930060e+01,6.752125821182659138e+02,4.792833515077508655e-01,1.100000010988609489e+01,1.014914880149014442e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677039069954930994e+01,6.752225821131156636e+02,4.792935006548100230e-01,1.100000010988609489e+01,1.014768894747476724e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677129979044931929e+01,6.752325821079668913e+02,4.793036483420158866e-01,1.100000010988609489e+01,1.014622909345939007e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677220888134932864e+01,6.752425821028195969e+02,4.793137945693685120e-01,1.100000010988609489e+01,1.014476923944401289e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677311797224933798e+01,6.752525820976737805e+02,4.793239393368678436e-01,1.100000010988609489e+01,1.014330938542863571e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677402706314934733e+01,6.752625820925294420e+02,4.793340826445139369e-01,1.100000010988609489e+01,1.014184953141325854e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677493615404935667e+01,6.752725820873865814e+02,4.793442244923067364e-01,1.100000010988609489e+01,1.014038967739788136e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677584524494936602e+01,6.752825820822451988e+02,4.793543648802462975e-01,1.100000010988609489e+01,1.013892982338250419e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677675433584937537e+01,6.752925820771052940e+02,4.793645038083325649e-01,1.100000010988609489e+01,1.013746996936712701e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677766342674938471e+01,6.753025820719668673e+02,4.793746412765655940e-01,1.100000010988609489e+01,1.013601011535174984e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677857251764939406e+01,6.753125820668299184e+02,4.793847772849453293e-01,1.100000010988609489e+01,1.013455026133637266e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.677948160854940340e+01,6.753225820616944475e+02,4.793949118334718262e-01,1.100000010988609489e+01,1.013309040732099549e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678039069944941275e+01,6.753325820565604545e+02,4.794050449221450294e-01,1.100000010988609489e+01,1.013163055330561831e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678129979034942210e+01,6.753425820514279394e+02,4.794151765509649943e-01,1.100000010988609489e+01,1.013017069929024114e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678220888124943144e+01,6.753525820462969023e+02,4.794253067199316654e-01,1.100000010988609489e+01,1.012871084527486396e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678311797214944079e+01,6.753625820411673430e+02,4.794354354290450981e-01,1.100000010988609489e+01,1.012725099125948679e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678402706304945013e+01,6.753725820360392618e+02,4.794455626783052371e-01,1.100000010988609489e+01,1.012579113724410961e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678493615394945948e+01,6.753825820309126584e+02,4.794556884677121378e-01,1.100000010988609489e+01,1.012433128322873244e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678584524484946883e+01,6.753925820257875330e+02,4.794658127972657446e-01,1.100000010988609489e+01,1.012287142921335526e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678675433574947817e+01,6.754025820206638855e+02,4.794759356669661132e-01,1.100000010988609489e+01,1.012141157519797809e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678766342664948752e+01,6.754125820155417159e+02,4.794860570768131880e-01,1.100000010988609489e+01,1.011995172118260091e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678857251754949687e+01,6.754225820104210243e+02,4.794961770268070245e-01,1.100000010988609489e+01,1.011849186716722374e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.678948160844950621e+01,6.754325820053018106e+02,4.795062955169475671e-01,1.100000010988609489e+01,1.011703201315184656e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679039069934951556e+01,6.754425820001840748e+02,4.795164125472348715e-01,1.100000010988609489e+01,1.011557215913646939e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679129979024952490e+01,6.754525819950678169e+02,4.795265281176688821e-01,1.100000010988609489e+01,1.011411230512109221e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679220888114953425e+01,6.754625819899530370e+02,4.795366422282496544e-01,1.100000010988609489e+01,1.011265245110571503e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679311797204954360e+01,6.754725819848397350e+02,4.795467548789771328e-01,1.100000010988609489e+01,1.011119259709033786e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679402706294955294e+01,6.754825819797279109e+02,4.795568660698513175e-01,1.100000010988609489e+01,1.010973274307496068e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679493615384956229e+01,6.754925819746175648e+02,4.795669758008722638e-01,1.100000010988609489e+01,1.010827288905958351e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679584524474957163e+01,6.755025819695086966e+02,4.795770840720399164e-01,1.100000010988609489e+01,1.010681303504420633e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679675433564958098e+01,6.755125819644013063e+02,4.795871908833543307e-01,1.100000010988609489e+01,1.010535318102882916e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679766342654959033e+01,6.755225819592953940e+02,4.795972962348154511e-01,1.100000010988609489e+01,1.010389332701345198e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679857251744959967e+01,6.755325819541909596e+02,4.796074001264233333e-01,1.100000010988609489e+01,1.010243347299807481e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.679948160834960902e+01,6.755425819490880031e+02,4.796175025581779217e-01,1.100000010988609489e+01,1.010097361898269763e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680039069924961836e+01,6.755525819439865245e+02,4.796276035300792162e-01,1.100000010988609489e+01,1.009951376496732046e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680129979014962771e+01,6.755625819388865239e+02,4.796377030421272725e-01,1.100000010988609489e+01,1.009805391095194328e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680220888104963706e+01,6.755725819337880012e+02,4.796478010943220349e-01,1.100000010988609489e+01,1.009659405693656611e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680311797194964640e+01,6.755825819286909564e+02,4.796578976866635591e-01,1.100000010988609489e+01,1.009513420292118893e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680402706284965575e+01,6.755925819235953895e+02,4.796679928191517894e-01,1.100000010988609489e+01,1.009367434890581176e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680493615374966510e+01,6.756025819185013006e+02,4.796780864917867260e-01,1.100000010988609489e+01,1.009221449489043458e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680584524464967444e+01,6.756125819134086896e+02,4.796881787045684242e-01,1.100000010988609489e+01,1.009075464087505741e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680675433554968379e+01,6.756225819083175566e+02,4.796982694574968287e-01,1.100000010988609489e+01,1.008929478685968023e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680766342644969313e+01,6.756325819032279014e+02,4.797083587505719948e-01,1.100000010988609489e+01,1.008783493284430306e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680857251734970248e+01,6.756425818981397242e+02,4.797184465837938672e-01,1.100000010988609489e+01,1.008637507882892588e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.680948160824971183e+01,6.756525818930530249e+02,4.797285329571624457e-01,1.100000010988609489e+01,1.008491522481354871e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681039069914972117e+01,6.756625818879678036e+02,4.797386178706777859e-01,1.100000010988609489e+01,1.008345537079817153e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681129979004973052e+01,6.756725818828839465e+02,4.797487013243398324e-01,1.100000010988609489e+01,1.008199551678279435e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681220888094973986e+01,6.756825818778015673e+02,4.797587833181486405e-01,1.100000010988609489e+01,1.008053566276741718e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681311797184974921e+01,6.756925818727206661e+02,4.797688638521041549e-01,1.100000010988609489e+01,1.007907580875204000e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681402706274975856e+01,6.757025818676412428e+02,4.797789429262063754e-01,1.100000010988609489e+01,1.007761595473666283e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681493615364976790e+01,6.757125818625632974e+02,4.797890205404553576e-01,1.100000010988609489e+01,1.007615610072128565e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681584524454977725e+01,6.757225818574868299e+02,4.797990966948510461e-01,1.100000010988609489e+01,1.007469624670590848e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681675433544978659e+01,6.757325818524118404e+02,4.798091713893934407e-01,1.100000010988609489e+01,1.007323639269053130e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681766342634979594e+01,6.757425818473383288e+02,4.798192446240825970e-01,1.100000010988609489e+01,1.007177653867515413e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681857251724980529e+01,6.757525818422662951e+02,4.798293163989184595e-01,1.100000010988609489e+01,1.007031668465977695e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.681948160814981463e+01,6.757625818371957394e+02,4.798393867139010283e-01,1.100000010988609489e+01,1.006885683064439978e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682039069904982398e+01,6.757725818321266615e+02,4.798494555690303587e-01,1.100000010988609489e+01,1.006739697662902260e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682129978994983333e+01,6.757825818270590617e+02,4.798595229643063953e-01,1.100000010988609489e+01,1.006593712261364543e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682220888084984267e+01,6.757925818219929397e+02,4.798695888997291381e-01,1.100000010988609489e+01,1.006447726859826825e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682311797174985202e+01,6.758025818169282957e+02,4.798796533752986426e-01,1.100000010988609489e+01,1.006301741458289108e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682402706264986136e+01,6.758125818118651296e+02,4.798897163910148533e-01,1.100000010988609489e+01,1.006155756056751390e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682493615354987071e+01,6.758225818068033277e+02,4.798997779468777702e-01,1.100000010988609489e+01,1.006009770655213673e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682584524444988006e+01,6.758325818017430038e+02,4.799098380428874489e-01,1.100000010988609489e+01,1.005863785253675955e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682675433534988940e+01,6.758425817966841578e+02,4.799198966790438337e-01,1.100000010988609489e+01,1.005717799852138238e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682766342624989875e+01,6.758525817916267897e+02,4.799299538553469247e-01,1.100000010988609489e+01,1.005571814450600520e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682857251714990809e+01,6.758625817865708996e+02,4.799400095717967218e-01,1.100000010988609489e+01,1.005425829049062803e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.682948160804991744e+01,6.758725817815164874e+02,4.799500638283932807e-01,1.100000010988609489e+01,1.005279843647525085e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683039069894992679e+01,6.758825817764635531e+02,4.799601166251365458e-01,1.100000010988609489e+01,1.005133858245987367e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683129978984993613e+01,6.758925817714120967e+02,4.799701679620265171e-01,1.100000010988609489e+01,1.004987872844449650e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683220888074994548e+01,6.759025817663621183e+02,4.799802178390632501e-01,1.100000010988609489e+01,1.004841887442911932e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683311797164995482e+01,6.759125817613136178e+02,4.799902662562466893e-01,1.100000010988609489e+01,1.004695902041374215e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683402706254996417e+01,6.759225817562665952e+02,4.800003132135768347e-01,1.100000010988609489e+01,1.004549916639836497e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683493615344997352e+01,6.759325817512209369e+02,4.800103587110536862e-01,1.100000010988609489e+01,1.004403931238298780e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683584524434998286e+01,6.759425817461767565e+02,4.800204027486772995e-01,1.100000010988609489e+01,1.004257945836761062e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683675433524999221e+01,6.759525817411340540e+02,4.800304453264476190e-01,1.100000010988609489e+01,1.004111960435223345e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683766342615000156e+01,6.759625817360928295e+02,4.800404864443646447e-01,1.100000010988609489e+01,1.003965975033685627e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683857251705001090e+01,6.759725817310530829e+02,4.800505261024284320e-01,1.100000010988609489e+01,1.003819989632147910e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.683948160795002025e+01,6.759825817260148142e+02,4.800605643006389256e-01,1.100000010988609489e+01,1.003674004230610192e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684039069885002959e+01,6.759925817209780234e+02,4.800706010389961254e-01,1.100000010988609489e+01,1.003528018829072475e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684129978975003894e+01,6.760025817159427106e+02,4.800806363175000313e-01,1.100000010988609489e+01,1.003382033427534757e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684220888065004829e+01,6.760125817109088757e+02,4.800906701361506990e-01,1.100000010988609489e+01,1.003236048025997040e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684311797155005763e+01,6.760225817058765188e+02,4.801007024949480728e-01,1.100000010988609489e+01,1.003090062624459322e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684402706245006698e+01,6.760325817008455260e+02,4.801107333938921529e-01,1.100000010988609489e+01,1.002944077222921605e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684493615335007632e+01,6.760425816958160112e+02,4.801207628329829391e-01,1.100000010988609489e+01,1.002798091821383887e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684584524425008567e+01,6.760525816907879744e+02,4.801307908122204315e-01,1.100000010988609489e+01,1.002652106419846170e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684675433515009502e+01,6.760625816857614154e+02,4.801408173316046857e-01,1.100000010988609489e+01,1.002506121018308452e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684766342605010436e+01,6.760725816807363344e+02,4.801508423911356460e-01,1.100000010988609489e+01,1.002360135616770734e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684857251695011371e+01,6.760825816757127313e+02,4.801608659908133125e-01,1.100000010988609489e+01,1.002214150215233017e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.684948160785012305e+01,6.760925816706906062e+02,4.801708881306376853e-01,1.100000010988609489e+01,1.002068164813695299e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685039069875013240e+01,6.761025816656699590e+02,4.801809088106088197e-01,1.100000010988609489e+01,1.001922179412157582e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685129978965014175e+01,6.761125816606506760e+02,4.801909280307266603e-01,1.100000010988609489e+01,1.001776194010619864e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685220888055015109e+01,6.761225816556328709e+02,4.802009457909912071e-01,1.100000010988609489e+01,1.001630208609082147e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685311797145016044e+01,6.761325816506165438e+02,4.802109620914024601e-01,1.100000010988609489e+01,1.001484223207544429e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685402706235016979e+01,6.761425816456016946e+02,4.802209769319604193e-01,1.100000010988609489e+01,1.001338237806006712e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685493615325017913e+01,6.761525816405883234e+02,4.802309903126651403e-01,1.100000010988609489e+01,1.001192252404468994e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685584524415018848e+01,6.761625816355764300e+02,4.802410022335165674e-01,1.100000010988609489e+01,1.001046267002931277e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685675433505019782e+01,6.761725816305660146e+02,4.802510126945147007e-01,1.100000010988609489e+01,1.000900281601393559e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685766342595020717e+01,6.761825816255569634e+02,4.802610216956595401e-01,1.100000010988609489e+01,1.000754296199855842e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685857251685021652e+01,6.761925816205493902e+02,4.802710292369510858e-01,1.100000010988609489e+01,1.000608310798318124e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.685948160775022586e+01,6.762025816155432949e+02,4.802810353183893377e-01,1.100000010988609489e+01,1.000462325396780407e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686039069865023521e+01,6.762125816105386775e+02,4.802910399399743513e-01,1.100000010988609489e+01,1.000316339995242689e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686129978955024455e+01,6.762225816055355381e+02,4.803010431017060711e-01,1.100000010988609489e+01,1.000170354593704972e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686220888045025390e+01,6.762325816005338766e+02,4.803110448035844970e-01,1.100000010988609489e+01,1.000024369192167254e-03,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686311797135026325e+01,6.762425815955335793e+02,4.803210450456096292e-01,1.100000010988609489e+01,9.998783837906295366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686402706225027259e+01,6.762525815905347599e+02,4.803310438277814676e-01,1.100000010988609489e+01,9.997323983890918191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686493615315028194e+01,6.762625815855374185e+02,4.803410411501000121e-01,1.100000010988609489e+01,9.995864129875541015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686584524405029129e+01,6.762725815805415550e+02,4.803510370125652629e-01,1.100000010988609489e+01,9.994404275860163840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686675433495030063e+01,6.762825815755471695e+02,4.803610314151772753e-01,1.100000010988609489e+01,9.992944421844786665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686766342585030998e+01,6.762925815705542618e+02,4.803710243579359940e-01,1.100000010988609489e+01,9.991484567829409490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686857251675031932e+01,6.763025815655627184e+02,4.803810158408414188e-01,1.100000010988609489e+01,9.990024713814032314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.686948160765032867e+01,6.763125815605726530e+02,4.803910058638935499e-01,1.100000010988609489e+01,9.988564859798655139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687039069855033802e+01,6.763225815555840654e+02,4.804009944270923871e-01,1.100000010988609489e+01,9.987105005783277964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687129978945034736e+01,6.763325815505969558e+02,4.804109815304379305e-01,1.100000010988609489e+01,9.985645151767900789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687220888035035671e+01,6.763425815456113241e+02,4.804209671739301801e-01,1.100000010988609489e+01,9.984185297752523613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687311797125036605e+01,6.763525815406271704e+02,4.804309513575691359e-01,1.100000010988609489e+01,9.982725443737146438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687402706215037540e+01,6.763625815356443809e+02,4.804409340813548535e-01,1.100000010988609489e+01,9.981265589721769263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687493615305038475e+01,6.763725815306630693e+02,4.804509153452872772e-01,1.100000010988609489e+01,9.979805735706392088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687584524395039409e+01,6.763825815256832357e+02,4.804608951493664071e-01,1.100000010988609489e+01,9.978345881691014913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687675433485040344e+01,6.763925815207048799e+02,4.804708734935922432e-01,1.100000010988609489e+01,9.976886027675637737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687766342575041278e+01,6.764025815157280022e+02,4.804808503779647855e-01,1.100000010988609489e+01,9.975426173660260562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687857251665042213e+01,6.764125815107526023e+02,4.804908258024840340e-01,1.100000010988609489e+01,9.973966319644883387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.687948160755043148e+01,6.764225815057785667e+02,4.805007997671499886e-01,1.100000010988609489e+01,9.972506465629506212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688039069845044082e+01,6.764325815008060090e+02,4.805107722719626495e-01,1.100000010988609489e+01,9.971046611614129036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688129978935045017e+01,6.764425814958349292e+02,4.805207433169220166e-01,1.100000010988609489e+01,9.969586757598751861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688220888025045952e+01,6.764525814908653274e+02,4.805307129020280899e-01,1.100000010988609489e+01,9.968126903583374686e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688311797115046886e+01,6.764625814858972035e+02,4.805406810272808693e-01,1.100000010988609489e+01,9.966667049567997511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688402706205047821e+01,6.764725814809304438e+02,4.805506476926803550e-01,1.100000010988609489e+01,9.965207195552620335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688493615295048755e+01,6.764825814759651621e+02,4.805606128982266023e-01,1.100000010988609489e+01,9.963747341537243160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688584524385049690e+01,6.764925814710013583e+02,4.805705766439195559e-01,1.100000010988609489e+01,9.962287487521865985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688675433475050625e+01,6.765025814660390324e+02,4.805805389297592156e-01,1.100000010988609489e+01,9.960827633506488810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688766342565051559e+01,6.765125814610781845e+02,4.805904997557455816e-01,1.100000010988609489e+01,9.959367779491111634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688857251655052494e+01,6.765225814561187008e+02,4.806004591218786537e-01,1.100000010988609489e+01,9.957907925475734459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.688948160745053428e+01,6.765325814511606950e+02,4.806104170281584320e-01,1.100000010988609489e+01,9.956448071460357284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689039069835054363e+01,6.765425814462041672e+02,4.806203734745849165e-01,1.100000010988609489e+01,9.954988217444980109e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689129978925055298e+01,6.765525814412491172e+02,4.806303284611581073e-01,1.100000010988609489e+01,9.953528363429602933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689220888015056232e+01,6.765625814362954316e+02,4.806402819878780042e-01,1.100000010988609489e+01,9.952068509414225758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689311797105057167e+01,6.765725814313432238e+02,4.806502340547446073e-01,1.100000010988609489e+01,9.950608655398848583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689402706195058101e+01,6.765825814263924940e+02,4.806601846617579166e-01,1.100000010988609489e+01,9.949148801383471408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689493615285059036e+01,6.765925814214432421e+02,4.806701338089179321e-01,1.100000010988609489e+01,9.947688947368094232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689584524375059971e+01,6.766025814164954681e+02,4.806800814962246537e-01,1.100000010988609489e+01,9.946229093352717057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689675433465060905e+01,6.766125814115490584e+02,4.806900277236780816e-01,1.100000010988609489e+01,9.944769239337339882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689766342555061840e+01,6.766225814066041266e+02,4.806999724912782157e-01,1.100000010988609489e+01,9.943309385321962707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689857251645062775e+01,6.766325814016606728e+02,4.807099157990250560e-01,1.100000010988609489e+01,9.941849531306585531e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.689948160735063709e+01,6.766425813967186969e+02,4.807198576469186024e-01,1.100000010988609489e+01,9.940389677291208356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690039069825064644e+01,6.766525813917780852e+02,4.807297980349588551e-01,1.100000010988609489e+01,9.938929823275831181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690129978915065578e+01,6.766625813868389514e+02,4.807397369631458139e-01,1.100000010988609489e+01,9.937469969260454006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690220888005066513e+01,6.766725813819012956e+02,4.807496744314794790e-01,1.100000010988609489e+01,9.936010115245076831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690311797095067448e+01,6.766825813769651177e+02,4.807596104399598502e-01,1.100000010988609489e+01,9.934550261229699655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690402706185068382e+01,6.766925813720303040e+02,4.807695449885869277e-01,1.100000010988609489e+01,9.933090407214322480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690493615275069317e+01,6.767025813670969683e+02,4.807794780773607113e-01,1.100000010988609489e+01,9.931630553198945305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690584524365070251e+01,6.767125813621651105e+02,4.807894097062812011e-01,1.100000010988609489e+01,9.930170699183568130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690675433455071186e+01,6.767225813572347306e+02,4.807993398753483971e-01,1.100000010988609489e+01,9.928710845168190954e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690766342545072121e+01,6.767325813523057150e+02,4.808092685845622993e-01,1.100000010988609489e+01,9.927250991152813779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690857251635073055e+01,6.767425813473781773e+02,4.808191958339229077e-01,1.100000010988609489e+01,9.925791137137436604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.690948160725073990e+01,6.767525813424521175e+02,4.808291216234302223e-01,1.100000010988609489e+01,9.924331283122059429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691039069815074924e+01,6.767625813375275357e+02,4.808390459530842431e-01,1.100000010988609489e+01,9.922871429106682253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691129978905075859e+01,6.767725813326043180e+02,4.808489688228849701e-01,1.100000010988609489e+01,9.921411575091305078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691220887995076794e+01,6.767825813276825784e+02,4.808588902328324033e-01,1.100000010988609489e+01,9.919951721075927903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691311797085077728e+01,6.767925813227623166e+02,4.808688101829265427e-01,1.100000010988609489e+01,9.918491867060550728e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691402706175078663e+01,6.768025813178435328e+02,4.808787286731673327e-01,1.100000010988609489e+01,9.917032013045173552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691493615265079598e+01,6.768125813129261132e+02,4.808886457035548290e-01,1.100000010988609489e+01,9.915572159029796377e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691584524355080532e+01,6.768225813080101716e+02,4.808985612740890314e-01,1.100000010988609489e+01,9.914112305014419202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691675433445081467e+01,6.768325813030957079e+02,4.809084753847699401e-01,1.100000010988609489e+01,9.912652450999042027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691766342535082401e+01,6.768425812981827221e+02,4.809183880355975549e-01,1.100000010988609489e+01,9.911192596983664851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691857251625083336e+01,6.768525812932711005e+02,4.809282992265718759e-01,1.100000010988609489e+01,9.909732742968287676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.691948160715084271e+01,6.768625812883609569e+02,4.809382089576929031e-01,1.100000010988609489e+01,9.908272888952910501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692039069805085205e+01,6.768725812834522912e+02,4.809481172289606365e-01,1.100000010988609489e+01,9.906813034937533326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692129978895086140e+01,6.768825812785449898e+02,4.809580240403750762e-01,1.100000010988609489e+01,9.905353180922156150e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692220887985087074e+01,6.768925812736391663e+02,4.809679293919362220e-01,1.100000010988609489e+01,9.903893326906778975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692311797075088009e+01,6.769025812687348207e+02,4.809778332836440740e-01,1.100000010988609489e+01,9.902433472891401800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692402706165088944e+01,6.769125812638319530e+02,4.809877357154986321e-01,1.100000010988609489e+01,9.900973618876024625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692493615255089878e+01,6.769225812589304496e+02,4.809976366874998410e-01,1.100000010988609489e+01,9.899513764860647450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692584524345090813e+01,6.769325812540304241e+02,4.810075361996477561e-01,1.100000010988609489e+01,9.898053910845270274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692675433435091747e+01,6.769425812491318766e+02,4.810174342519423774e-01,1.100000010988609489e+01,9.896594056829893099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692766342525092682e+01,6.769525812442346933e+02,4.810273308443837048e-01,1.100000010988609489e+01,9.895134202814515924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692857251615093617e+01,6.769625812393389879e+02,4.810372259769717385e-01,1.100000010988609489e+01,9.893674348799138749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.692948160705094551e+01,6.769725812344447604e+02,4.810471196497064783e-01,1.100000010988609489e+01,9.892214494783761573e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693039069795095486e+01,6.769825812295520109e+02,4.810570118625879243e-01,1.100000010988609489e+01,9.890754640768384398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693129978885096421e+01,6.769925812246606256e+02,4.810669026156160766e-01,1.100000010988609489e+01,9.889294786753007223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693220887975097355e+01,6.770025812197707182e+02,4.810767919087908795e-01,1.100000010988609489e+01,9.887834932737630048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693311797065098290e+01,6.770125812148822888e+02,4.810866797421123886e-01,1.100000010988609489e+01,9.886375078722252872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693402706155099224e+01,6.770225812099952236e+02,4.810965661155806039e-01,1.100000010988609489e+01,9.884915224706875697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693493615245100159e+01,6.770325812051096364e+02,4.811064510291955254e-01,1.100000010988609489e+01,9.883455370691498522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693584524335101094e+01,6.770425812002255270e+02,4.811163344829571531e-01,1.100000010988609489e+01,9.881995516676121347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693675433425102028e+01,6.770525811953427819e+02,4.811262164768654870e-01,1.100000010988609489e+01,9.880535662660744171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693766342515102963e+01,6.770625811904615148e+02,4.811360970109205271e-01,1.100000010988609489e+01,9.879075808645366996e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693857251605103897e+01,6.770725811855817255e+02,4.811459760851222178e-01,1.100000010988609489e+01,9.877615954629989821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.693948160695104832e+01,6.770825811807034142e+02,4.811558536994706148e-01,1.100000010988609489e+01,9.876156100614612646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694039069785105767e+01,6.770925811758264672e+02,4.811657298539657179e-01,1.100000010988609489e+01,9.874696246599235470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694129978875106701e+01,6.771025811709509981e+02,4.811756045486075273e-01,1.100000010988609489e+01,9.873236392583858295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694220887965107636e+01,6.771125811660770069e+02,4.811854777833960428e-01,1.100000010988609489e+01,9.871776538568481120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694311797055108570e+01,6.771225811612043799e+02,4.811953495583312646e-01,1.100000010988609489e+01,9.870316684553103945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694402706145109505e+01,6.771325811563332309e+02,4.812052198734131370e-01,1.100000010988609489e+01,9.868856830537726769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694493615235110440e+01,6.771425811514635598e+02,4.812150887286417156e-01,1.100000010988609489e+01,9.867396976522349594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694584524325111374e+01,6.771525811465952529e+02,4.812249561240170004e-01,1.100000010988609489e+01,9.865937122506972419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694675433415112309e+01,6.771625811417284240e+02,4.812348220595389914e-01,1.100000010988609489e+01,9.864477268491595244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694766342505113244e+01,6.771725811368630730e+02,4.812446865352076886e-01,1.100000010988609489e+01,9.863017414476218069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694857251595114178e+01,6.771825811319990862e+02,4.812545495510230364e-01,1.100000010988609489e+01,9.861557560460840893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.694948160685115113e+01,6.771925811271365774e+02,4.812644111069850905e-01,1.100000010988609489e+01,9.860097706445463718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695039069775116047e+01,6.772025811222755465e+02,4.812742712030938508e-01,1.100000010988609489e+01,9.858637852430086543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695129978865116982e+01,6.772125811174158798e+02,4.812841298393493172e-01,1.100000010988609489e+01,9.857177998414709368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695220887955117917e+01,6.772225811125576911e+02,4.812939870157514344e-01,1.100000010988609489e+01,9.855718144399332192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695311797045118851e+01,6.772325811077009803e+02,4.813038427323002577e-01,1.100000010988609489e+01,9.854258290383955017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695402706135119786e+01,6.772425811028456337e+02,4.813136969889957872e-01,1.100000010988609489e+01,9.852798436368577842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695493615225120720e+01,6.772525810979917651e+02,4.813235497858380230e-01,1.100000010988609489e+01,9.851338582353200667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695584524315121655e+01,6.772625810931393744e+02,4.813334011228269649e-01,1.100000010988609489e+01,9.849878728337823491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695675433405122590e+01,6.772725810882883479e+02,4.813432509999625575e-01,1.100000010988609489e+01,9.848418874322446316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695766342495123524e+01,6.772825810834387994e+02,4.813530994172448563e-01,1.100000010988609489e+01,9.846959020307069141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695857251585124459e+01,6.772925810785906151e+02,4.813629463746738613e-01,1.100000010988609489e+01,9.845499166291691966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.695948160675125393e+01,6.773025810737439087e+02,4.813727918722495724e-01,1.100000010988609489e+01,9.844039312276314790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696039069765126328e+01,6.773125810688986803e+02,4.813826359099719343e-01,1.100000010988609489e+01,9.842579458260937615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696129978855127263e+01,6.773225810640548161e+02,4.813924784878410024e-01,1.100000010988609489e+01,9.841119604245560440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696220887945128197e+01,6.773325810592124299e+02,4.814023196058567766e-01,1.100000010988609489e+01,9.839659750230183265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696311797035129132e+01,6.773425810543715215e+02,4.814121592640192571e-01,1.100000010988609489e+01,9.838199896214806089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696402706125130067e+01,6.773525810495319774e+02,4.814219974623283882e-01,1.100000010988609489e+01,9.836740042199428914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696493615215131001e+01,6.773625810446939113e+02,4.814318342007842255e-01,1.100000010988609489e+01,9.835280188184051739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696584524305131936e+01,6.773725810398573230e+02,4.814416694793867690e-01,1.100000010988609489e+01,9.833820334168674564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696675433395132870e+01,6.773825810350220991e+02,4.814515032981359632e-01,1.100000010988609489e+01,9.832360480153297388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696766342485133805e+01,6.773925810301883530e+02,4.814613356570318636e-01,1.100000010988609489e+01,9.830900626137920213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696857251575134740e+01,6.774025810253559712e+02,4.814711665560744702e-01,1.100000010988609489e+01,9.829440772122543038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.696948160665135674e+01,6.774125810205250673e+02,4.814809959952637830e-01,1.100000010988609489e+01,9.827980918107165863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697039069755136609e+01,6.774225810156956413e+02,4.814908239745997465e-01,1.100000010988609489e+01,9.826521064091788688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697129978845137543e+01,6.774325810108675796e+02,4.815006504940824161e-01,1.100000010988609489e+01,9.825061210076411512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697220887935138478e+01,6.774425810060409958e+02,4.815104755537117920e-01,1.100000010988609489e+01,9.823601356061034337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697311797025139413e+01,6.774525810012158900e+02,4.815202991534878185e-01,1.100000010988609489e+01,9.822141502045657162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697402706115140347e+01,6.774625809963921483e+02,4.815301212934105513e-01,1.100000010988609489e+01,9.820681648030279987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697493615205141282e+01,6.774725809915698846e+02,4.815399419734799902e-01,1.100000010988609489e+01,9.819221794014902811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697584524295142216e+01,6.774825809867489852e+02,4.815497611936960798e-01,1.100000010988609489e+01,9.817761939999525636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697675433385143151e+01,6.774925809819295637e+02,4.815595789540588756e-01,1.100000010988609489e+01,9.816302085984148461e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697766342475144086e+01,6.775025809771116201e+02,4.815693952545683776e-01,1.100000010988609489e+01,9.814842231968771286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697857251565145020e+01,6.775125809722950407e+02,4.815792100952245303e-01,1.100000010988609489e+01,9.813382377953394110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.697948160655145955e+01,6.775225809674799393e+02,4.815890234760273891e-01,1.100000010988609489e+01,9.811922523938016935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698039069745146890e+01,6.775325809626662021e+02,4.815988353969769542e-01,1.100000010988609489e+01,9.810462669922639760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698129978835147824e+01,6.775425809578539429e+02,4.816086458580731700e-01,1.100000010988609489e+01,9.809002815907262585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698220887925148759e+01,6.775525809530431616e+02,4.816184548593160919e-01,1.100000010988609489e+01,9.807542961891885409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698311797015149693e+01,6.775625809482337445e+02,4.816282624007057200e-01,1.100000010988609489e+01,9.806083107876508234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698402706105150628e+01,6.775725809434258053e+02,4.816380684822419989e-01,1.100000010988609489e+01,9.804623253861131059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698493615195151563e+01,6.775825809386192304e+02,4.816478731039249839e-01,1.100000010988609489e+01,9.803163399845753884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698584524285152497e+01,6.775925809338141335e+02,4.816576762657546751e-01,1.100000010988609489e+01,9.801703545830376708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698675433375153432e+01,6.776025809290105144e+02,4.816674779677310170e-01,1.100000010988609489e+01,9.800243691814999533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698766342465154366e+01,6.776125809242082596e+02,4.816772782098540651e-01,1.100000010988609489e+01,9.798783837799622358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698857251555155301e+01,6.776225809194074827e+02,4.816870769921238193e-01,1.100000010988609489e+01,9.797323983784245183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.698948160645156236e+01,6.776325809146080701e+02,4.816968743145402243e-01,1.100000010988609489e+01,9.795864129768868007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699039069735157170e+01,6.776425809098101354e+02,4.817066701771033355e-01,1.100000010988609489e+01,9.794404275753490832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699129978825158105e+01,6.776525809050135649e+02,4.817164645798130973e-01,1.100000010988609489e+01,9.792944421738113657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699220887915159039e+01,6.776625809002184724e+02,4.817262575226695653e-01,1.100000010988609489e+01,9.791484567722736482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699311797005159974e+01,6.776725808954248578e+02,4.817360490056727396e-01,1.100000010988609489e+01,9.790024713707359307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699402706095160909e+01,6.776825808906326074e+02,4.817458390288225645e-01,1.100000010988609489e+01,9.788564859691982131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699493615185161843e+01,6.776925808858418350e+02,4.817556275921190956e-01,1.100000010988609489e+01,9.787105005676604956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699584524275162778e+01,6.777025808810524268e+02,4.817654146955622774e-01,1.100000010988609489e+01,9.785645151661227781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699675433365163713e+01,6.777125808762644965e+02,4.817752003391521654e-01,1.100000010988609489e+01,9.784185297645850606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699766342455164647e+01,6.777225808714779305e+02,4.817849845228887595e-01,1.100000010988609489e+01,9.782725443630473430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699857251545165582e+01,6.777325808666928424e+02,4.817947672467720044e-01,1.100000010988609489e+01,9.781265589615096255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.699948160635166516e+01,6.777425808619092322e+02,4.818045485108019554e-01,1.100000010988609489e+01,9.779805735599719080e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700039069725167451e+01,6.777525808571269863e+02,4.818143283149785572e-01,1.100000010988609489e+01,9.778345881584341905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700129978815168386e+01,6.777625808523462183e+02,4.818241066593018651e-01,1.100000010988609489e+01,9.776886027568964729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700220887905169320e+01,6.777725808475668146e+02,4.818338835437718792e-01,1.100000010988609489e+01,9.775426173553587554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700311796995170255e+01,6.777825808427888887e+02,4.818436589683885440e-01,1.100000010988609489e+01,9.773966319538210379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700402706085171189e+01,6.777925808380123271e+02,4.818534329331519150e-01,1.100000010988609489e+01,9.772506465522833204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700493615175172124e+01,6.778025808332372435e+02,4.818632054380619367e-01,1.100000010988609489e+01,9.771046611507456028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700584524265173059e+01,6.778125808284635241e+02,4.818729764831186646e-01,1.100000010988609489e+01,9.769586757492078853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700675433355173993e+01,6.778225808236912826e+02,4.818827460683220432e-01,1.100000010988609489e+01,9.768126903476701678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700766342445174928e+01,6.778325808189205191e+02,4.818925141936721279e-01,1.100000010988609489e+01,9.766667049461324503e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700857251535175863e+01,6.778425808141511197e+02,4.819022808591688634e-01,1.100000010988609489e+01,9.765207195445947327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.700948160625176797e+01,6.778525808093831984e+02,4.819120460648123050e-01,1.100000010988609489e+01,9.763747341430570152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701039069715177732e+01,6.778625808046166412e+02,4.819218098106024528e-01,1.100000010988609489e+01,9.762287487415192977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701129978805178666e+01,6.778725807998515620e+02,4.819315720965392513e-01,1.100000010988609489e+01,9.760827633399815802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701220887895179601e+01,6.778825807950878470e+02,4.819413329226227560e-01,1.100000010988609489e+01,9.759367779384438626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701311796985180536e+01,6.778925807903256100e+02,4.819510922888529114e-01,1.100000010988609489e+01,9.757907925369061451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701402706075181470e+01,6.779025807855647372e+02,4.819608501952297730e-01,1.100000010988609489e+01,9.756448071353684276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701493615165182405e+01,6.779125807808053423e+02,4.819706066417532853e-01,1.100000010988609489e+01,9.754988217338307101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701584524255183339e+01,6.779225807760473117e+02,4.819803616284235037e-01,1.100000010988609489e+01,9.753528363322929925e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701675433345184274e+01,6.779325807712907590e+02,4.819901151552403729e-01,1.100000010988609489e+01,9.752068509307552750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701766342435185209e+01,6.779425807665355705e+02,4.819998672222039482e-01,1.100000010988609489e+01,9.750608655292175575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701857251525186143e+01,6.779525807617818600e+02,4.820096178293141742e-01,1.100000010988609489e+01,9.749148801276798400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.701948160615187078e+01,6.779625807570295137e+02,4.820193669765711064e-01,1.100000010988609489e+01,9.747688947261421225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702039069705188012e+01,6.779725807522786454e+02,4.820291146639746893e-01,1.100000010988609489e+01,9.746229093246044049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702129978795188947e+01,6.779825807475291413e+02,4.820388608915249784e-01,1.100000010988609489e+01,9.744769239230666874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702220887885189882e+01,6.779925807427811151e+02,4.820486056592219182e-01,1.100000010988609489e+01,9.743309385215289699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702311796975190816e+01,6.780025807380345668e+02,4.820583489670655641e-01,1.100000010988609489e+01,9.741849531199912524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702402706065191751e+01,6.780125807332893828e+02,4.820680908150558608e-01,1.100000010988609489e+01,9.740389677184535348e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702493615155192686e+01,6.780225807285456767e+02,4.820778312031928636e-01,1.100000010988609489e+01,9.738929823169158173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702584524245193620e+01,6.780325807238033349e+02,4.820875701314765172e-01,1.100000010988609489e+01,9.737469969153780998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702675433335194555e+01,6.780425807190624710e+02,4.820973075999068769e-01,1.100000010988609489e+01,9.736010115138403823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702766342425195489e+01,6.780525807143229713e+02,4.821070436084838873e-01,1.100000010988609489e+01,9.734550261123026647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702857251515196424e+01,6.780625807095849495e+02,4.821167781572076039e-01,1.100000010988609489e+01,9.733090407107649472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.702948160605197359e+01,6.780725807048482920e+02,4.821265112460779712e-01,1.100000010988609489e+01,9.731630553092272297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703039069695198293e+01,6.780825807001131125e+02,4.821362428750949891e-01,1.100000010988609489e+01,9.730170699076895122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703129978785199228e+01,6.780925806953792971e+02,4.821459730442587133e-01,1.100000010988609489e+01,9.728710845061517946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703220887875200162e+01,6.781025806906469597e+02,4.821557017535690881e-01,1.100000010988609489e+01,9.727250991046140771e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703311796965201097e+01,6.781125806859159866e+02,4.821654290030261691e-01,1.100000010988609489e+01,9.725791137030763596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703402706055202032e+01,6.781225806811864913e+02,4.821751547926299009e-01,1.100000010988609489e+01,9.724331283015386421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703493615145202966e+01,6.781325806764583604e+02,4.821848791223803388e-01,1.100000010988609489e+01,9.722871429000009245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703584524235203901e+01,6.781425806717315936e+02,4.821946019922774274e-01,1.100000010988609489e+01,9.721411574984632070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703675433325204835e+01,6.781525806670063048e+02,4.822043234023212221e-01,1.100000010988609489e+01,9.719951720969254895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703766342415205770e+01,6.781625806622823802e+02,4.822140433525116676e-01,1.100000010988609489e+01,9.718491866953877720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703857251505206705e+01,6.781725806575599336e+02,4.822237618428487638e-01,1.100000010988609489e+01,9.717032012938500544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.703948160595207639e+01,6.781825806528388512e+02,4.822334788733325661e-01,1.100000010988609489e+01,9.715572158923123369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704039069685208574e+01,6.781925806481192467e+02,4.822431944439630191e-01,1.100000010988609489e+01,9.714112304907746194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704129978775209509e+01,6.782025806434010065e+02,4.822529085547401784e-01,1.100000010988609489e+01,9.712652450892369019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704220887865210443e+01,6.782125806386842441e+02,4.822626212056639883e-01,1.100000010988609489e+01,9.711192596876991844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704311796955211378e+01,6.782225806339688461e+02,4.822723323967344489e-01,1.100000010988609489e+01,9.709732742861614668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704402706045212312e+01,6.782325806292549260e+02,4.822820421279516157e-01,1.100000010988609489e+01,9.708272888846237493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704493615135213247e+01,6.782425806245423701e+02,4.822917503993154331e-01,1.100000010988609489e+01,9.706813034830860318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704584524225214182e+01,6.782525806198312921e+02,4.823014572108259568e-01,1.100000010988609489e+01,9.705353180815483143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704675433315215116e+01,6.782625806151215784e+02,4.823111625624831311e-01,1.100000010988609489e+01,9.703893326800105967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704766342405216051e+01,6.782725806104133426e+02,4.823208664542869561e-01,1.100000010988609489e+01,9.702433472784728792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704857251495216985e+01,6.782825806057064710e+02,4.823305688862374874e-01,1.100000010988609489e+01,9.700973618769351617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.704948160585217920e+01,6.782925806010010774e+02,4.823402698583346693e-01,1.100000010988609489e+01,9.699513764753974442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705039069675218855e+01,6.783025805962970480e+02,4.823499693705785574e-01,1.100000010988609489e+01,9.698053910738597266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705129978765219789e+01,6.783125805915943829e+02,4.823596674229690962e-01,1.100000010988609489e+01,9.696594056723220091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705220887855220724e+01,6.783225805868931957e+02,4.823693640155062856e-01,1.100000010988609489e+01,9.695134202707842916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705311796945221658e+01,6.783325805821933727e+02,4.823790591481901813e-01,1.100000010988609489e+01,9.693674348692465741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705402706035222593e+01,6.783425805774950277e+02,4.823887528210207276e-01,1.100000010988609489e+01,9.692214494677088565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705493615125223528e+01,6.783525805727980469e+02,4.823984450339979246e-01,1.100000010988609489e+01,9.690754640661711390e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705584524215224462e+01,6.783625805681025440e+02,4.824081357871218279e-01,1.100000010988609489e+01,9.689294786646334215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705675433305225397e+01,6.783725805634084054e+02,4.824178250803923818e-01,1.100000010988609489e+01,9.687834932630957040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705766342395226332e+01,6.783825805587157447e+02,4.824275129138095863e-01,1.100000010988609489e+01,9.686375078615579864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705857251485227266e+01,6.783925805540244482e+02,4.824371992873734971e-01,1.100000010988609489e+01,9.684915224600202689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.705948160575228201e+01,6.784025805493345160e+02,4.824468842010840586e-01,1.100000010988609489e+01,9.683455370584825514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706039069665229135e+01,6.784125805446460618e+02,4.824565676549412707e-01,1.100000010988609489e+01,9.681995516569448339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706129978755230070e+01,6.784225805399589717e+02,4.824662496489451891e-01,1.100000010988609489e+01,9.680535662554071163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706220887845231005e+01,6.784325805352733596e+02,4.824759301830957581e-01,1.100000010988609489e+01,9.679075808538693988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706311796935231939e+01,6.784425805305891117e+02,4.824856092573929778e-01,1.100000010988609489e+01,9.677615954523316813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706402706025232874e+01,6.784525805259063418e+02,4.824952868718369037e-01,1.100000010988609489e+01,9.676156100507939638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706493615115233808e+01,6.784625805212249361e+02,4.825049630264274803e-01,1.100000010988609489e+01,9.674696246492562463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706584524205234743e+01,6.784725805165448946e+02,4.825146377211647075e-01,1.100000010988609489e+01,9.673236392477185287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706675433295235678e+01,6.784825805118663311e+02,4.825243109560486410e-01,1.100000010988609489e+01,9.671776538461808112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706766342385236612e+01,6.784925805071891318e+02,4.825339827310792251e-01,1.100000010988609489e+01,9.670316684446430937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706857251475237547e+01,6.785025805025134105e+02,4.825436530462564599e-01,1.100000010988609489e+01,9.668856830431053762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.706948160565238481e+01,6.785125804978390534e+02,4.825533219015804010e-01,1.100000010988609489e+01,9.667396976415676586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707039069655239416e+01,6.785225804931661742e+02,4.825629892970509927e-01,1.100000010988609489e+01,9.665937122400299411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707129978745240351e+01,6.785325804884946592e+02,4.825726552326682350e-01,1.100000010988609489e+01,9.664477268384922236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707220887835241285e+01,6.785425804838245085e+02,4.825823197084321281e-01,1.100000010988609489e+01,9.663017414369545061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707311796925242220e+01,6.785525804791558357e+02,4.825919827243427274e-01,1.100000010988609489e+01,9.661557560354167885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707402706015243155e+01,6.785625804744885272e+02,4.826016442803999773e-01,1.100000010988609489e+01,9.660097706338790710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707493615105244089e+01,6.785725804698226966e+02,4.826113043766038779e-01,1.100000010988609489e+01,9.658637852323413535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707584524195245024e+01,6.785825804651582303e+02,4.826209630129544292e-01,1.100000010988609489e+01,9.657177998308036360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707675433285245958e+01,6.785925804604951281e+02,4.826306201894516867e-01,1.100000010988609489e+01,9.655718144292659184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707766342375246893e+01,6.786025804558335039e+02,4.826402759060955949e-01,1.100000010988609489e+01,9.654258290277282009e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707857251465247828e+01,6.786125804511732440e+02,4.826499301628861538e-01,1.100000010988609489e+01,9.652798436261904834e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.707948160555248762e+01,6.786225804465144620e+02,4.826595829598234189e-01,1.100000010988609489e+01,9.651338582246527659e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708039069645249697e+01,6.786325804418570442e+02,4.826692342969073346e-01,1.100000010988609489e+01,9.649878728231150483e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708129978735250631e+01,6.786425804372009907e+02,4.826788841741379010e-01,1.100000010988609489e+01,9.648418874215773308e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708220887825251566e+01,6.786525804325464151e+02,4.826885325915151181e-01,1.100000010988609489e+01,9.646959020200396133e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708311796915252501e+01,6.786625804278932037e+02,4.826981795490390414e-01,1.100000010988609489e+01,9.645499166185018958e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708402706005253435e+01,6.786725804232414703e+02,4.827078250467096154e-01,1.100000010988609489e+01,9.644039312169641782e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708493615095254370e+01,6.786825804185911011e+02,4.827174690845268401e-01,1.100000010988609489e+01,9.642579458154264607e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708584524185255304e+01,6.786925804139420961e+02,4.827271116624907155e-01,1.100000010988609489e+01,9.641119604138887432e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708675433275256239e+01,6.787025804092945691e+02,4.827367527806012415e-01,1.100000010988609489e+01,9.639659750123510257e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708766342365257174e+01,6.787125804046484063e+02,4.827463924388584737e-01,1.100000010988609489e+01,9.638199896108133082e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708857251455258108e+01,6.787225804000036078e+02,4.827560306372623566e-01,1.100000010988609489e+01,9.636740042092755906e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.708948160545259043e+01,6.787325803953602872e+02,4.827656673758128902e-01,1.100000010988609489e+01,9.635280188077378731e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709039069635259978e+01,6.787425803907183308e+02,4.827753026545100745e-01,1.100000010988609489e+01,9.633820334062001556e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709129978725260912e+01,6.787525803860778524e+02,4.827849364733539095e-01,1.100000010988609489e+01,9.632360480046624381e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709220887815261847e+01,6.787625803814387382e+02,4.827945688323444506e-01,1.100000010988609489e+01,9.630900626031247205e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709311796905262781e+01,6.787725803768009882e+02,4.828041997314816425e-01,1.100000010988609489e+01,9.629440772015870030e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709402705995263716e+01,6.787825803721647162e+02,4.828138291707654850e-01,1.100000010988609489e+01,9.627980918000492855e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709493615085264651e+01,6.787925803675298084e+02,4.828234571501959782e-01,1.100000010988609489e+01,9.626521063985115680e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709584524175265585e+01,6.788025803628962649e+02,4.828330836697731221e-01,1.100000010988609489e+01,9.625061209969738504e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709675433265266520e+01,6.788125803582641993e+02,4.828427087294969722e-01,1.100000010988609489e+01,9.623601355954361329e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709766342355267454e+01,6.788225803536334979e+02,4.828523323293674729e-01,1.100000010988609489e+01,9.622141501938984154e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709857251445268389e+01,6.788325803490042745e+02,4.828619544693846244e-01,1.100000010988609489e+01,9.620681647923606979e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.709948160535269324e+01,6.788425803443764153e+02,4.828715751495484265e-01,1.100000010988609489e+01,9.619221793908229803e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710039069625270258e+01,6.788525803397499203e+02,4.828811943698588793e-01,1.100000010988609489e+01,9.617761939892852628e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710129978715271193e+01,6.788625803351249033e+02,4.828908121303160383e-01,1.100000010988609489e+01,9.616302085877475453e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710220887805272127e+01,6.788725803305012505e+02,4.829004284309198480e-01,1.100000010988609489e+01,9.614842231862098278e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710311796895273062e+01,6.788825803258789620e+02,4.829100432716703084e-01,1.100000010988609489e+01,9.613382377846721102e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710402705985273997e+01,6.788925803212581513e+02,4.829196566525674195e-01,1.100000010988609489e+01,9.611922523831343927e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710493615075274931e+01,6.789025803166387050e+02,4.829292685736111812e-01,1.100000010988609489e+01,9.610462669815966752e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710584524165275866e+01,6.789125803120206228e+02,4.829388790348015936e-01,1.100000010988609489e+01,9.609002815800589577e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710675433255276801e+01,6.789225803074040186e+02,4.829484880361386567e-01,1.100000010988609489e+01,9.607542961785212401e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710766342345277735e+01,6.789325803027887787e+02,4.829580955776224260e-01,1.100000010988609489e+01,9.606083107769835226e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710857251435278670e+01,6.789425802981749030e+02,4.829677016592528460e-01,1.100000010988609489e+01,9.604623253754458051e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.710948160525279604e+01,6.789525802935625052e+02,4.829773062810299167e-01,1.100000010988609489e+01,9.603163399739080876e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711039069615280539e+01,6.789625802889514716e+02,4.829869094429536380e-01,1.100000010988609489e+01,9.601703545723703700e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711129978705281474e+01,6.789725802843418023e+02,4.829965111450240101e-01,1.100000010988609489e+01,9.600243691708326525e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711220887795282408e+01,6.789825802797336110e+02,4.830061113872410328e-01,1.100000010988609489e+01,9.598783837692949350e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711311796885283343e+01,6.789925802751267838e+02,4.830157101696047062e-01,1.100000010988609489e+01,9.597323983677572175e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711402705975284277e+01,6.790025802705213209e+02,4.830253074921150303e-01,1.100000010988609489e+01,9.595864129662195000e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711493615065285212e+01,6.790125802659173360e+02,4.830349033547720605e-01,1.100000010988609489e+01,9.594404275646817824e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711584524155286147e+01,6.790225802613147152e+02,4.830444977575757415e-01,1.100000010988609489e+01,9.592944421631440649e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711675433245287081e+01,6.790325802567134588e+02,4.830540907005260731e-01,1.100000010988609489e+01,9.591484567616063474e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711766342335288016e+01,6.790425802521136802e+02,4.830636821836230554e-01,1.100000010988609489e+01,9.590024713600686299e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711857251425288950e+01,6.790525802475152659e+02,4.830732722068666884e-01,1.100000010988609489e+01,9.588564859585309123e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.711948160515289885e+01,6.790625802429182158e+02,4.830828607702569721e-01,1.100000010988609489e+01,9.587105005569931948e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712039069605290820e+01,6.790725802383226437e+02,4.830924478737939065e-01,1.100000010988609489e+01,9.585645151554554773e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712129978695291754e+01,6.790825802337284358e+02,4.831020335174774916e-01,1.100000010988609489e+01,9.584185297539177598e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712220887785292689e+01,6.790925802291355922e+02,4.831116177013077273e-01,1.100000010988609489e+01,9.582725443523800422e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712311796875293624e+01,6.791025802245441128e+02,4.831212004252846137e-01,1.100000010988609489e+01,9.581265589508423247e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712402705965294558e+01,6.791125802199541113e+02,4.831307816894081508e-01,1.100000010988609489e+01,9.579805735493046072e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712493615055295493e+01,6.791225802153654740e+02,4.831403614936783941e-01,1.100000010988609489e+01,9.578345881477668897e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712584524145296427e+01,6.791325802107782010e+02,4.831499398380952881e-01,1.100000010988609489e+01,9.576886027462291721e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712675433235297362e+01,6.791425802061924060e+02,4.831595167226588328e-01,1.100000010988609489e+01,9.575426173446914546e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712766342325298297e+01,6.791525802016079751e+02,4.831690921473690281e-01,1.100000010988609489e+01,9.573966319431537371e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712857251415299231e+01,6.791625801970249086e+02,4.831786661122258741e-01,1.100000010988609489e+01,9.572506465416160196e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.712948160505300166e+01,6.791725801924433199e+02,4.831882386172293709e-01,1.100000010988609489e+01,9.571046611400783020e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713039069595301100e+01,6.791825801878630955e+02,4.831978096623795182e-01,1.100000010988609489e+01,9.569586757385405845e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713129978685302035e+01,6.791925801832842353e+02,4.832073792476763163e-01,1.100000010988609489e+01,9.568126903370028670e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713220887775302970e+01,6.792025801787067394e+02,4.832169473731197651e-01,1.100000010988609489e+01,9.566667049354651495e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713311796865303904e+01,6.792125801741307214e+02,4.832265140387098645e-01,1.100000010988609489e+01,9.565207195339274319e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713402705955304839e+01,6.792225801695560676e+02,4.832360792444466147e-01,1.100000010988609489e+01,9.563747341323897144e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713493615045305773e+01,6.792325801649827781e+02,4.832456429903300155e-01,1.100000010988609489e+01,9.562287487308519969e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713584524135306708e+01,6.792425801604109665e+02,4.832552052763600670e-01,1.100000010988609489e+01,9.560827633293142794e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713675433225307643e+01,6.792525801558405192e+02,4.832647661025367691e-01,1.100000010988609489e+01,9.559367779277765619e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713766342315308577e+01,6.792625801512714361e+02,4.832743254688601220e-01,1.100000010988609489e+01,9.557907925262388443e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713857251405309512e+01,6.792725801467037172e+02,4.832838833753301255e-01,1.100000010988609489e+01,9.556448071247011268e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.713948160495310447e+01,6.792825801421374763e+02,4.832934398219467798e-01,1.100000010988609489e+01,9.554988217231634093e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714039069585311381e+01,6.792925801375725996e+02,4.833029948087100847e-01,1.100000010988609489e+01,9.553528363216256918e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714129978675312316e+01,6.793025801330090871e+02,4.833125483356200403e-01,1.100000010988609489e+01,9.552068509200879742e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714220887765313250e+01,6.793125801284469389e+02,4.833221004026766465e-01,1.100000010988609489e+01,9.550608655185502567e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714311796855314185e+01,6.793225801238862687e+02,4.833316510098799035e-01,1.100000010988609489e+01,9.549148801170125392e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714402705945315120e+01,6.793325801193269626e+02,4.833412001572298111e-01,1.100000010988609489e+01,9.547688947154748217e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714493615035316054e+01,6.793425801147690208e+02,4.833507478447263694e-01,1.100000010988609489e+01,9.546229093139371041e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714584524125316989e+01,6.793525801102124433e+02,4.833602940723695784e-01,1.100000010988609489e+01,9.544769239123993866e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714675433215317923e+01,6.793625801056573437e+02,4.833698388401594381e-01,1.100000010988609489e+01,9.543309385108616691e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714766342305318858e+01,6.793725801011036083e+02,4.833793821480959485e-01,1.100000010988609489e+01,9.541849531093239516e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714857251395319793e+01,6.793825800965512371e+02,4.833889239961791096e-01,1.100000010988609489e+01,9.540389677077862340e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.714948160485320727e+01,6.793925800920002303e+02,4.833984643844089213e-01,1.100000010988609489e+01,9.538929823062485165e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715039069575321662e+01,6.794025800874507013e+02,4.834080033127853837e-01,1.100000010988609489e+01,9.537469969047107990e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715129978665322596e+01,6.794125800829025366e+02,4.834175407813084968e-01,1.100000010988609489e+01,9.536010115031730815e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715220887755323531e+01,6.794225800783557361e+02,4.834270767899782606e-01,1.100000010988609489e+01,9.534550261016353639e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715311796845324466e+01,6.794325800738102998e+02,4.834366113387946751e-01,1.100000010988609489e+01,9.533090407000976464e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715402705935325400e+01,6.794425800692663415e+02,4.834461444277577402e-01,1.100000010988609489e+01,9.531630552985599289e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715493615025326335e+01,6.794525800647237475e+02,4.834556760568674560e-01,1.100000010988609489e+01,9.530170698970222114e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715584524115327270e+01,6.794625800601825176e+02,4.834652062261238226e-01,1.100000010988609489e+01,9.528710844954844938e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715675433205328204e+01,6.794725800556426520e+02,4.834747349355268398e-01,1.100000010988609489e+01,9.527250990939467763e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715766342295329139e+01,6.794825800511042644e+02,4.834842621850765076e-01,1.100000010988609489e+01,9.525791136924090588e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715857251385330073e+01,6.794925800465672410e+02,4.834937879747728262e-01,1.100000010988609489e+01,9.524331282908713413e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.715948160475331008e+01,6.795025800420315818e+02,4.835033123046157955e-01,1.100000010988609489e+01,9.522871428893336238e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716039069565331943e+01,6.795125800374972869e+02,4.835128351746053599e-01,1.100000010988609489e+01,9.521411574877959062e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716129978655332877e+01,6.795225800329644699e+02,4.835223565847415750e-01,1.100000010988609489e+01,9.519951720862581887e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716220887745333812e+01,6.795325800284330171e+02,4.835318765350244408e-01,1.100000010988609489e+01,9.518491866847204712e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716311796835334746e+01,6.795425800239029286e+02,4.835413950254539572e-01,1.100000010988609489e+01,9.517032012831827537e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716402705925335681e+01,6.795525800193742043e+02,4.835509120560301244e-01,1.100000010988609489e+01,9.515572158816450361e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716493615015336616e+01,6.795625800148468443e+02,4.835604276267529422e-01,1.100000010988609489e+01,9.514112304801073186e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716584524105337550e+01,6.795725800103209622e+02,4.835699417376224107e-01,1.100000010988609489e+01,9.512652450785696011e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716675433195338485e+01,6.795825800057964443e+02,4.835794543886385299e-01,1.100000010988609489e+01,9.511192596770318836e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716766342285339420e+01,6.795925800012732907e+02,4.835889655798012998e-01,1.100000010988609489e+01,9.509732742754941660e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716857251375340354e+01,6.796025799967515013e+02,4.835984753111107204e-01,1.100000010988609489e+01,9.508272888739564485e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.716948160465341289e+01,6.796125799922311899e+02,4.836079835825667916e-01,1.100000010988609489e+01,9.506813034724187310e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717039069555342223e+01,6.796225799877122427e+02,4.836174903941694581e-01,1.100000010988609489e+01,9.505353180708810135e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717129978645343158e+01,6.796325799831946597e+02,4.836269957459187752e-01,1.100000010988609489e+01,9.503893326693432959e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717220887735344093e+01,6.796425799786784410e+02,4.836364996378147429e-01,1.100000010988609489e+01,9.502433472678055784e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717311796825345027e+01,6.796525799741635865e+02,4.836460020698573614e-01,1.100000010988609489e+01,9.500973618662678609e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717402705915345962e+01,6.796625799696502099e+02,4.836555030420466306e-01,1.100000010988609489e+01,9.499513764647301434e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717493615005346896e+01,6.796725799651381976e+02,4.836650025543825504e-01,1.100000010988609489e+01,9.498053910631924258e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717584524095347831e+01,6.796825799606275496e+02,4.836745006068651209e-01,1.100000010988609489e+01,9.496594056616547083e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717675433185348766e+01,6.796925799561182657e+02,4.836839971994943421e-01,1.100000010988609489e+01,9.495134202601169908e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717766342275349700e+01,6.797025799516103461e+02,4.836934923322701585e-01,1.100000010988609489e+01,9.493674348585792733e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717857251365350635e+01,6.797125799471039045e+02,4.837029860051926256e-01,1.100000010988609489e+01,9.492214494570415557e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.717948160455351569e+01,6.797225799425988271e+02,4.837124782182617433e-01,1.100000010988609489e+01,9.490754640555038382e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718039069545352504e+01,6.797325799380951139e+02,4.837219689714775117e-01,1.100000010988609489e+01,9.489294786539661207e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718129978635353439e+01,6.797425799335927650e+02,4.837314582648399308e-01,1.100000010988609489e+01,9.487834932524284032e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718220887725354373e+01,6.797525799290917803e+02,4.837409460983490006e-01,1.100000010988609489e+01,9.486375078508906857e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718311796815355308e+01,6.797625799245921598e+02,4.837504324720046656e-01,1.100000010988609489e+01,9.484915224493529681e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718402705905356243e+01,6.797725799200940173e+02,4.837599173858069812e-01,1.100000010988609489e+01,9.483455370478152506e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718493614995357177e+01,6.797825799155972391e+02,4.837694008397559475e-01,1.100000010988609489e+01,9.481995516462775331e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718584524085358112e+01,6.797925799111018250e+02,4.837788828338515645e-01,1.100000010988609489e+01,9.480535662447398156e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718675433175359046e+01,6.798025799066077752e+02,4.837883633680938322e-01,1.100000010988609489e+01,9.479075808432020980e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718766342265359981e+01,6.798125799021150897e+02,4.837978424424827506e-01,1.100000010988609489e+01,9.477615954416643805e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718857251355360916e+01,6.798225798976238821e+02,4.838073200570182641e-01,1.100000010988609489e+01,9.476156100401266630e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.718948160445361850e+01,6.798325798931340387e+02,4.838167962117004284e-01,1.100000010988609489e+01,9.474696246385889455e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719039069535362785e+01,6.798425798886455595e+02,4.838262709065292433e-01,1.100000010988609489e+01,9.473236392370512279e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719129978625363719e+01,6.798525798841584447e+02,4.838357441415047089e-01,1.100000010988609489e+01,9.471776538355135104e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719220887715364654e+01,6.798625798796726940e+02,4.838452159166268252e-01,1.100000010988609489e+01,9.470316684339757929e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719311796805365589e+01,6.798725798751883076e+02,4.838546862318955366e-01,1.100000010988609489e+01,9.468856830324380754e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719402705895366523e+01,6.798825798707053991e+02,4.838641550873108987e-01,1.100000010988609489e+01,9.467396976309003578e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719493614985367458e+01,6.798925798662238549e+02,4.838736224828729116e-01,1.100000010988609489e+01,9.465937122293626403e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719584524075368392e+01,6.799025798617436749e+02,4.838830884185815751e-01,1.100000010988609489e+01,9.464477268278249228e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719675433165369327e+01,6.799125798572648591e+02,4.838925528944368892e-01,1.100000010988609489e+01,9.463017414262872053e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719766342255370262e+01,6.799225798527874076e+02,4.839020159104387986e-01,1.100000010988609489e+01,9.461557560247494877e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719857251345371196e+01,6.799325798483113203e+02,4.839114774665873586e-01,1.100000010988609489e+01,9.460097706232117702e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.719948160435372131e+01,6.799425798438365973e+02,4.839209375628825693e-01,1.100000010988609489e+01,9.458637852216740527e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720039069525373066e+01,6.799525798393633522e+02,4.839303961993244307e-01,1.100000010988609489e+01,9.457177998201363352e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720129978615374000e+01,6.799625798348914714e+02,4.839398533759128873e-01,1.100000010988609489e+01,9.455718144185986176e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720220887705374935e+01,6.799725798304209547e+02,4.839493090926479946e-01,1.100000010988609489e+01,9.454258290170609001e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720311796795375869e+01,6.799825798259518024e+02,4.839587633495297525e-01,1.100000010988609489e+01,9.452798436155231826e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720402705885376804e+01,6.799925798214840142e+02,4.839682161465581611e-01,1.100000010988609489e+01,9.451338582139854651e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720493614975377739e+01,6.800025798170175904e+02,4.839776674837331649e-01,1.100000010988609489e+01,9.449878728124477476e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720584524065378673e+01,6.800125798125525307e+02,4.839871173610548194e-01,1.100000010988609489e+01,9.448418874109100300e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720675433155379608e+01,6.800225798080889490e+02,4.839965657785231246e-01,1.100000010988609489e+01,9.446959020093723125e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720766342245380542e+01,6.800325798036267315e+02,4.840060127361380804e-01,1.100000010988609489e+01,9.445499166078345950e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720857251335381477e+01,6.800425797991658783e+02,4.840154582338996314e-01,1.100000010988609489e+01,9.444039312062968775e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.720948160425382412e+01,6.800525797947063893e+02,4.840249022718078331e-01,1.100000010988609489e+01,9.442579458047591599e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721039069515383346e+01,6.800625797902482645e+02,4.840343448498626855e-01,1.100000010988609489e+01,9.441119604032214424e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721129978605384281e+01,6.800725797857915040e+02,4.840437859680641886e-01,1.100000010988609489e+01,9.439659750016837249e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721220887695385215e+01,6.800825797813361078e+02,4.840532256264122868e-01,1.100000010988609489e+01,9.438199896001460074e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721311796785386150e+01,6.800925797768820757e+02,4.840626638249070357e-01,1.100000010988609489e+01,9.436740041986082898e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721402705875387085e+01,6.801025797724295217e+02,4.840721005635484353e-01,1.100000010988609489e+01,9.435280187970705723e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721493614965388019e+01,6.801125797679783318e+02,4.840815358423364301e-01,1.100000010988609489e+01,9.433820333955328548e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721584524055388954e+01,6.801225797635285062e+02,4.840909696612710755e-01,1.100000010988609489e+01,9.432360479939951373e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721675433145389889e+01,6.801325797590800448e+02,4.841004020203523717e-01,1.100000010988609489e+01,9.430900625924574197e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721766342235390823e+01,6.801425797546329477e+02,4.841098329195803185e-01,1.100000010988609489e+01,9.429440771909197022e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721857251325391758e+01,6.801525797501872148e+02,4.841192623589548605e-01,1.100000010988609489e+01,9.427980917893819847e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.721948160415392692e+01,6.801625797457428462e+02,4.841286903384760532e-01,1.100000010988609489e+01,9.426521063878442672e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722039069505393627e+01,6.801725797412998418e+02,4.841381168581438965e-01,1.100000010988609489e+01,9.425061209863065496e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722129978595394562e+01,6.801825797368582016e+02,4.841475419179583350e-01,1.100000010988609489e+01,9.423601355847688321e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722220887685395496e+01,6.801925797324180394e+02,4.841569655179194243e-01,1.100000010988609489e+01,9.422141501832311146e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722311796775396431e+01,6.802025797279792414e+02,4.841663876580271642e-01,1.100000010988609489e+01,9.420681647816933971e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722402705865397365e+01,6.802125797235418077e+02,4.841758083382814992e-01,1.100000010988609489e+01,9.419221793801556795e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722493614955398300e+01,6.802225797191057381e+02,4.841852275586824850e-01,1.100000010988609489e+01,9.417761939786179620e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722584524045399235e+01,6.802325797146710329e+02,4.841946453192301214e-01,1.100000010988609489e+01,9.416302085770802445e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722675433135400169e+01,6.802425797102376919e+02,4.842040616199243530e-01,1.100000010988609489e+01,9.414842231755425270e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722766342225401104e+01,6.802525797058057151e+02,4.842134764607652353e-01,1.100000010988609489e+01,9.413382377740048094e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722857251315402038e+01,6.802625797013751026e+02,4.842228898417527683e-01,1.100000010988609489e+01,9.411922523724670919e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.722948160405402973e+01,6.802725796969458543e+02,4.842323017628868964e-01,1.100000010988609489e+01,9.410462669709293744e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723039069495403908e+01,6.802825796925179702e+02,4.842417122241676752e-01,1.100000010988609489e+01,9.409002815693916569e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723129978585404842e+01,6.802925796880914504e+02,4.842511212255951047e-01,1.100000010988609489e+01,9.407542961678539394e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723220887675405777e+01,6.803025796836664085e+02,4.842605287671691294e-01,1.100000010988609489e+01,9.406083107663162218e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723311796765406712e+01,6.803125796792427309e+02,4.842699348488898048e-01,1.100000010988609489e+01,9.404623253647785043e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723402705855407646e+01,6.803225796748204175e+02,4.842793394707570753e-01,1.100000010988609489e+01,9.403163399632407868e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723493614945408581e+01,6.803325796703994683e+02,4.842887426327709965e-01,1.100000010988609489e+01,9.401703545617030693e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723584524035409515e+01,6.803425796659798834e+02,4.842981443349315684e-01,1.100000010988609489e+01,9.400243691601653517e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723675433125410450e+01,6.803525796615616628e+02,4.843075445772387355e-01,1.100000010988609489e+01,9.398783837586276342e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723766342215411385e+01,6.803625796571448063e+02,4.843169433596925533e-01,1.100000010988609489e+01,9.397323983570899167e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723857251305412319e+01,6.803725796527293141e+02,4.843263406822930217e-01,1.100000010988609489e+01,9.395864129555521992e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.723948160395413254e+01,6.803825796483151862e+02,4.843357365450400853e-01,1.100000010988609489e+01,9.394404275540144816e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724039069485414188e+01,6.803925796439024225e+02,4.843451309479337996e-01,1.100000010988609489e+01,9.392944421524767641e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724129978575415123e+01,6.804025796394910230e+02,4.843545238909741091e-01,1.100000010988609489e+01,9.391484567509390466e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724220887665416058e+01,6.804125796350809878e+02,4.843639153741610692e-01,1.100000010988609489e+01,9.390024713494013291e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724311796755416992e+01,6.804225796306723169e+02,4.843733053974946801e-01,1.100000010988609489e+01,9.388564859478636115e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724402705845417927e+01,6.804325796262650101e+02,4.843826939609748861e-01,1.100000010988609489e+01,9.387105005463258940e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724493614935418861e+01,6.804425796218590676e+02,4.843920810646017427e-01,1.100000010988609489e+01,9.385645151447881765e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724584524025419796e+01,6.804525796174546031e+02,4.844014667083751946e-01,1.100000010988609489e+01,9.384185297432504590e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724675433115420731e+01,6.804625796130515027e+02,4.844108508922952971e-01,1.100000010988609489e+01,9.382725443417127414e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724766342205421665e+01,6.804725796086497667e+02,4.844202336163620504e-01,1.100000010988609489e+01,9.381265589401750239e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724857251295422600e+01,6.804825796042493948e+02,4.844296148805753988e-01,1.100000010988609489e+01,9.379805735386373064e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.724948160385423535e+01,6.804925795998503872e+02,4.844389946849353978e-01,1.100000010988609489e+01,9.378345881370995889e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725039069475424469e+01,6.805025795954527439e+02,4.844483730294419921e-01,1.100000010988609489e+01,9.376886027355618713e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725129978565425404e+01,6.805125795910564648e+02,4.844577499140952370e-01,1.100000010988609489e+01,9.375426173340241538e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725220887655426338e+01,6.805225795866615499e+02,4.844671253388950771e-01,1.100000010988609489e+01,9.373966319324864363e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725311796745427273e+01,6.805325795822679993e+02,4.844764993038415679e-01,1.100000010988609489e+01,9.372506465309487188e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725402705835428208e+01,6.805425795778758129e+02,4.844858718089347094e-01,1.100000010988609489e+01,9.371046611294110013e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725493614925429142e+01,6.805525795734849908e+02,4.844952428541744460e-01,1.100000010988609489e+01,9.369586757278732837e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725584524015430077e+01,6.805625795690955329e+02,4.845046124395608333e-01,1.100000010988609489e+01,9.368126903263355662e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725675433105431011e+01,6.805725795647074392e+02,4.845139805650938158e-01,1.100000010988609489e+01,9.366667049247978487e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725766342195431946e+01,6.805825795603207098e+02,4.845233472307734490e-01,1.100000010988609489e+01,9.365207195232601312e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725857251285432881e+01,6.805925795559353446e+02,4.845327124365996774e-01,1.100000010988609489e+01,9.363747341217224136e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.725948160375433815e+01,6.806025795515513437e+02,4.845420761825725564e-01,1.100000010988609489e+01,9.362287487201846961e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726039069465434750e+01,6.806125795471687070e+02,4.845514384686920306e-01,1.100000010988609489e+01,9.360827633186469786e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726129978555435684e+01,6.806225795427874345e+02,4.845607992949581555e-01,1.100000010988609489e+01,9.359367779171092611e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726220887645436619e+01,6.806325795384075263e+02,4.845701586613708756e-01,1.100000010988609489e+01,9.357907925155715435e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726311796735437554e+01,6.806425795340289824e+02,4.845795165679302463e-01,1.100000010988609489e+01,9.356448071140338260e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726402705825438488e+01,6.806525795296518027e+02,4.845888730146362122e-01,1.100000010988609489e+01,9.354988217124961085e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726493614915439423e+01,6.806625795252759872e+02,4.845982280014888288e-01,1.100000010988609489e+01,9.353528363109583910e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726584524005440358e+01,6.806725795209015359e+02,4.846075815284880406e-01,1.100000010988609489e+01,9.352068509094206734e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726675433095441292e+01,6.806825795165284489e+02,4.846169335956339030e-01,1.100000010988609489e+01,9.350608655078829559e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726766342185442227e+01,6.806925795121567262e+02,4.846262842029263607e-01,1.100000010988609489e+01,9.349148801063452384e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726857251275443161e+01,6.807025795077863677e+02,4.846356333503654690e-01,1.100000010988609489e+01,9.347688947048075209e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.726948160365444096e+01,6.807125795034173734e+02,4.846449810379511725e-01,1.100000010988609489e+01,9.346229093032698033e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727039069455445031e+01,6.807225794990497434e+02,4.846543272656835266e-01,1.100000010988609489e+01,9.344769239017320858e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727129978545445965e+01,6.807325794946834776e+02,4.846636720335624759e-01,1.100000010988609489e+01,9.343309385001943683e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727220887635446900e+01,6.807425794903185761e+02,4.846730153415880760e-01,1.100000010988609489e+01,9.341849530986566508e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727311796725447834e+01,6.807525794859550388e+02,4.846823571897602712e-01,1.100000010988609489e+01,9.340389676971189332e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727402705815448769e+01,6.807625794815928657e+02,4.846916975780791170e-01,1.100000010988609489e+01,9.338929822955812157e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727493614905449704e+01,6.807725794772320569e+02,4.847010365065445581e-01,1.100000010988609489e+01,9.337469968940434982e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727584523995450638e+01,6.807825794728726123e+02,4.847103739751566498e-01,1.100000010988609489e+01,9.336010114925057807e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727675433085451573e+01,6.807925794685145320e+02,4.847197099839153367e-01,1.100000010988609489e+01,9.334550260909680632e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727766342175452507e+01,6.808025794641578159e+02,4.847290445328206743e-01,1.100000010988609489e+01,9.333090406894303456e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727857251265453442e+01,6.808125794598024640e+02,4.847383776218726070e-01,1.100000010988609489e+01,9.331630552878926281e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.727948160355454377e+01,6.808225794554484764e+02,4.847477092510711905e-01,1.100000010988609489e+01,9.330170698863549106e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728039069445455311e+01,6.808325794510958531e+02,4.847570394204163691e-01,1.100000010988609489e+01,9.328710844848171931e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728129978535456246e+01,6.808425794467445940e+02,4.847663681299081428e-01,1.100000010988609489e+01,9.327250990832794755e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728220887625457181e+01,6.808525794423946991e+02,4.847756953795465673e-01,1.100000010988609489e+01,9.325791136817417580e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728311796715458115e+01,6.808625794380461684e+02,4.847850211693315869e-01,1.100000010988609489e+01,9.324331282802040405e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728402705805459050e+01,6.808725794336990020e+02,4.847943454992632573e-01,1.100000010988609489e+01,9.322871428786663230e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728493614895459984e+01,6.808825794293531999e+02,4.848036683693415227e-01,1.100000010988609489e+01,9.321411574771286054e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728584523985460919e+01,6.808925794250087620e+02,4.848129897795664389e-01,1.100000010988609489e+01,9.319951720755908879e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728675433075461854e+01,6.809025794206656883e+02,4.848223097299379503e-01,1.100000010988609489e+01,9.318491866740531704e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728766342165462788e+01,6.809125794163239789e+02,4.848316282204560568e-01,1.100000010988609489e+01,9.317032012725154529e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728857251255463723e+01,6.809225794119836337e+02,4.848409452511208140e-01,1.100000010988609489e+01,9.315572158709777353e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.728948160345464657e+01,6.809325794076446527e+02,4.848502608219321663e-01,1.100000010988609489e+01,9.314112304694400178e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729039069435465592e+01,6.809425794033070360e+02,4.848595749328901694e-01,1.100000010988609489e+01,9.312652450679023003e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729129978525466527e+01,6.809525793989707836e+02,4.848688875839947676e-01,1.100000010988609489e+01,9.311192596663645828e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729220887615467461e+01,6.809625793946358954e+02,4.848781987752460165e-01,1.100000010988609489e+01,9.309732742648268652e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729311796705468396e+01,6.809725793903023714e+02,4.848875085066438606e-01,1.100000010988609489e+01,9.308272888632891477e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729402705795469330e+01,6.809825793859702117e+02,4.848968167781882999e-01,1.100000010988609489e+01,9.306813034617514302e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729493614885470265e+01,6.809925793816394162e+02,4.849061235898793898e-01,1.100000010988609489e+01,9.305353180602137127e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729584523975471200e+01,6.810025793773099849e+02,4.849154289417170749e-01,1.100000010988609489e+01,9.303893326586759951e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729675433065472134e+01,6.810125793729819179e+02,4.849247328337013552e-01,1.100000010988609489e+01,9.302433472571382776e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729766342155473069e+01,6.810225793686551015e+02,4.849340352658322861e-01,1.100000010988609489e+01,9.300973618556005601e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729857251245474004e+01,6.810325793643296493e+02,4.849433362381098123e-01,1.100000010988609489e+01,9.299513764540628426e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.729948160335474938e+01,6.810425793600055613e+02,4.849526357505339891e-01,1.100000010988609489e+01,9.298053910525251251e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730039069425475873e+01,6.810525793556828376e+02,4.849619338031047611e-01,1.100000010988609489e+01,9.296594056509874075e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730129978515476807e+01,6.810625793513614781e+02,4.849712303958221282e-01,1.100000010988609489e+01,9.295134202494496900e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730220887605477742e+01,6.810725793470414828e+02,4.849805255286861461e-01,1.100000010988609489e+01,9.293674348479119725e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730311796695478677e+01,6.810825793427228518e+02,4.849898192016967591e-01,1.100000010988609489e+01,9.292214494463742550e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730402705785479611e+01,6.810925793384055851e+02,4.849991114148539673e-01,1.100000010988609489e+01,9.290754640448365374e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730493614875480546e+01,6.811025793340896826e+02,4.850084021681578261e-01,1.100000010988609489e+01,9.289294786432988199e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730584523965481480e+01,6.811125793297751443e+02,4.850176914616082802e-01,1.100000010988609489e+01,9.287834932417611024e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730675433055482415e+01,6.811225793254619703e+02,4.850269792952053294e-01,1.100000010988609489e+01,9.286375078402233849e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730766342145483350e+01,6.811325793211501605e+02,4.850362656689490293e-01,1.100000010988609489e+01,9.284915224386856673e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730857251235484284e+01,6.811425793168397149e+02,4.850455505828393243e-01,1.100000010988609489e+01,9.283455370371479498e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.730948160325485219e+01,6.811525793125306336e+02,4.850548340368762701e-01,1.100000010988609489e+01,9.281995516356102323e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731039069415486154e+01,6.811625793082229166e+02,4.850641160310598110e-01,1.100000010988609489e+01,9.280535662340725148e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731129978505487088e+01,6.811725793039164500e+02,4.850733965653899471e-01,1.100000010988609489e+01,9.279075808325347972e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731220887595488023e+01,6.811825792996113478e+02,4.850826756398666784e-01,1.100000010988609489e+01,9.277615954309970797e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731311796685488957e+01,6.811925792953076098e+02,4.850919532544900603e-01,1.100000010988609489e+01,9.276156100294593622e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731402705775489892e+01,6.812025792910052360e+02,4.851012294092600374e-01,1.100000010988609489e+01,9.274696246279216447e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731493614865490827e+01,6.812125792867042264e+02,4.851105041041766097e-01,1.100000010988609489e+01,9.273236392263839271e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731584523955491761e+01,6.812225792824045811e+02,4.851197773392398327e-01,1.100000010988609489e+01,9.271776538248462096e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731675433045492696e+01,6.812325792781063001e+02,4.851290491144496508e-01,1.100000010988609489e+01,9.270316684233084921e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731766342135493630e+01,6.812425792738093833e+02,4.851383194298060642e-01,1.100000010988609489e+01,9.268856830217707746e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731857251225494565e+01,6.812525792695138307e+02,4.851475882853091282e-01,1.100000010988609489e+01,9.267396976202330570e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.731948160315495500e+01,6.812625792652196424e+02,4.851568556809587873e-01,1.100000010988609489e+01,9.265937122186953395e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732039069405496434e+01,6.812725792609268183e+02,4.851661216167550417e-01,1.100000010988609489e+01,9.264477268171576220e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732129978495497369e+01,6.812825792566352447e+02,4.851753860926979467e-01,1.100000010988609489e+01,9.263017414156199045e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732220887585498303e+01,6.812925792523450355e+02,4.851846491087874469e-01,1.100000010988609489e+01,9.261557560140821869e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732311796675499238e+01,6.813025792480561904e+02,4.851939106650235423e-01,1.100000010988609489e+01,9.260097706125444694e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732402705765500173e+01,6.813125792437687096e+02,4.852031707614062328e-01,1.100000010988609489e+01,9.258637852110067519e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732493614855501107e+01,6.813225792394825930e+02,4.852124293979355740e-01,1.100000010988609489e+01,9.257177998094690344e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732584523945502042e+01,6.813325792351978407e+02,4.852216865746115104e-01,1.100000010988609489e+01,9.255718144079313169e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732675433035502977e+01,6.813425792309144526e+02,4.852309422914340420e-01,1.100000010988609489e+01,9.254258290063935993e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732766342125503911e+01,6.813525792266324288e+02,4.852401965484031687e-01,1.100000010988609489e+01,9.252798436048558818e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732857251215504846e+01,6.813625792223517692e+02,4.852494493455189462e-01,1.100000010988609489e+01,9.251338582033181643e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.732948160305505780e+01,6.813725792180723602e+02,4.852587006827813187e-01,1.100000010988609489e+01,9.249878728017804468e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733039069395506715e+01,6.813825792137943154e+02,4.852679505601902865e-01,1.100000010988609489e+01,9.248418874002427292e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733129978485507650e+01,6.813925792095176348e+02,4.852771989777458495e-01,1.100000010988609489e+01,9.246959019987050117e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733220887575508584e+01,6.814025792052423185e+02,4.852864459354480631e-01,1.100000010988609489e+01,9.245499165971672942e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733311796665509519e+01,6.814125792009683664e+02,4.852956914332968719e-01,1.100000010988609489e+01,9.244039311956295767e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733402705755510453e+01,6.814225791966957786e+02,4.853049354712922758e-01,1.100000010988609489e+01,9.242579457940918591e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733493614845511388e+01,6.814325791924245550e+02,4.853141780494342750e-01,1.100000010988609489e+01,9.241119603925541416e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733584523935512323e+01,6.814425791881546957e+02,4.853234191677229248e-01,1.100000010988609489e+01,9.239659749910164241e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733675433025513257e+01,6.814525791838860869e+02,4.853326588261581698e-01,1.100000010988609489e+01,9.238199895894787066e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733766342115514192e+01,6.814625791796188423e+02,4.853418970247400099e-01,1.100000010988609489e+01,9.236740041879409890e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733857251205515126e+01,6.814725791753529620e+02,4.853511337634684453e-01,1.100000010988609489e+01,9.235280187864032715e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.733948160295516061e+01,6.814825791710884459e+02,4.853603690423435313e-01,1.100000010988609489e+01,9.233820333848655540e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734039069385516996e+01,6.814925791668252941e+02,4.853696028613652125e-01,1.100000010988609489e+01,9.232360479833278365e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734129978475517930e+01,6.815025791625635065e+02,4.853788352205334888e-01,1.100000010988609489e+01,9.230900625817901189e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734220887565518865e+01,6.815125791583030832e+02,4.853880661198483604e-01,1.100000010988609489e+01,9.229440771802524014e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734311796655519800e+01,6.815225791540439104e+02,4.853972955593098271e-01,1.100000010988609489e+01,9.227980917787146839e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734402705745520734e+01,6.815325791497861019e+02,4.854065235389179445e-01,1.100000010988609489e+01,9.226521063771769664e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734493614835521669e+01,6.815425791455296576e+02,4.854157500586726570e-01,1.100000010988609489e+01,9.225061209756392488e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734584523925522603e+01,6.815525791412745775e+02,4.854249751185739647e-01,1.100000010988609489e+01,9.223601355741015313e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734675433015523538e+01,6.815625791370208617e+02,4.854341987186218677e-01,1.100000010988609489e+01,9.222141501725638138e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734766342105524473e+01,6.815725791327685101e+02,4.854434208588163657e-01,1.100000010988609489e+01,9.220681647710260963e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734857251195525407e+01,6.815825791285174091e+02,4.854526415391575145e-01,1.100000010988609489e+01,9.219221793694883788e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.734948160285526342e+01,6.815925791242676723e+02,4.854618607596452584e-01,1.100000010988609489e+01,9.217761939679506612e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735039069375527276e+01,6.816025791200192998e+02,4.854710785202795975e-01,1.100000010988609489e+01,9.216302085664129437e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735129978465528211e+01,6.816125791157722915e+02,4.854802948210605318e-01,1.100000010988609489e+01,9.214842231648752262e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735220887555529146e+01,6.816225791115266475e+02,4.854895096619880612e-01,1.100000010988609489e+01,9.213382377633375087e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735311796645530080e+01,6.816325791072823677e+02,4.854987230430621858e-01,1.100000010988609489e+01,9.211922523617997911e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735402705735531015e+01,6.816425791030393384e+02,4.855079349642829611e-01,1.100000010988609489e+01,9.210462669602620736e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735493614825531949e+01,6.816525790987976734e+02,4.855171454256503316e-01,1.100000010988609489e+01,9.209002815587243561e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735584523915532884e+01,6.816625790945573726e+02,4.855263544271642973e-01,1.100000010988609489e+01,9.207542961571866386e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735675433005533819e+01,6.816725790903184361e+02,4.855355619688248581e-01,1.100000010988609489e+01,9.206083107556489210e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735766342095534753e+01,6.816825790860808638e+02,4.855447680506320141e-01,1.100000010988609489e+01,9.204623253541112035e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735857251185535688e+01,6.816925790818446558e+02,4.855539726725857652e-01,1.100000010988609489e+01,9.203163399525734860e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.735948160275536623e+01,6.817025790776096983e+02,4.855631758346861115e-01,1.100000010988609489e+01,9.201703545510357685e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736039069365537557e+01,6.817125790733761050e+02,4.855723775369331086e-01,1.100000010988609489e+01,9.200243691494980509e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736129978455538492e+01,6.817225790691438760e+02,4.855815777793267007e-01,1.100000010988609489e+01,9.198783837479603334e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736220887545539426e+01,6.817325790649130113e+02,4.855907765618668881e-01,1.100000010988609489e+01,9.197323983464226159e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736311796635540361e+01,6.817425790606835108e+02,4.855999738845536706e-01,1.100000010988609489e+01,9.195864129448848984e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736402705725541296e+01,6.817525790564552608e+02,4.856091697473870483e-01,1.100000010988609489e+01,9.194404275433471808e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736493614815542230e+01,6.817625790522283751e+02,4.856183641503670212e-01,1.100000010988609489e+01,9.192944421418094633e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736584523905543165e+01,6.817725790480028536e+02,4.856275570934935892e-01,1.100000010988609489e+01,9.191484567402717458e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736675432995544099e+01,6.817825790437786964e+02,4.856367485767667524e-01,1.100000010988609489e+01,9.190024713387340283e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736766342085545034e+01,6.817925790395559034e+02,4.856459386001865663e-01,1.100000010988609489e+01,9.188564859371963107e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736857251175545969e+01,6.818025790353343609e+02,4.856551271637529754e-01,1.100000010988609489e+01,9.187105005356585932e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.736948160265546903e+01,6.818125790311141827e+02,4.856643142674659797e-01,1.100000010988609489e+01,9.185645151341208757e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737039069355547838e+01,6.818225790268953688e+02,4.856734999113255791e-01,1.100000010988609489e+01,9.184185297325831582e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737129978445548772e+01,6.818325790226779191e+02,4.856826840953317737e-01,1.100000010988609489e+01,9.182725443310454407e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737220887535549707e+01,6.818425790184618336e+02,4.856918668194845634e-01,1.100000010988609489e+01,9.181265589295077231e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737311796625550642e+01,6.818525790142469987e+02,4.857010480837839483e-01,1.100000010988609489e+01,9.179805735279700056e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737402705715551576e+01,6.818625790100335280e+02,4.857102278882299284e-01,1.100000010988609489e+01,9.178345881264322881e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737493614805552511e+01,6.818725790058214216e+02,4.857194062328225037e-01,1.100000010988609489e+01,9.176886027248945706e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737584523895553446e+01,6.818825790016106794e+02,4.857285831175616742e-01,1.100000010988609489e+01,9.175426173233568530e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737675432985554380e+01,6.818925789974013014e+02,4.857377585424474398e-01,1.100000010988609489e+01,9.173966319218191355e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737766342075555315e+01,6.819025789931931740e+02,4.857469325074798561e-01,1.100000010988609489e+01,9.172506465202814180e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737857251165556249e+01,6.819125789889864109e+02,4.857561050126588675e-01,1.100000010988609489e+01,9.171046611187437005e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.737948160255557184e+01,6.819225789847810120e+02,4.857652760579844742e-01,1.100000010988609489e+01,9.169586757172059829e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738039069345558119e+01,6.819325789805769773e+02,4.857744456434566760e-01,1.100000010988609489e+01,9.168126903156682654e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738129978435559053e+01,6.819425789763743069e+02,4.857836137690754730e-01,1.100000010988609489e+01,9.166667049141305479e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738220887525559988e+01,6.819525789721728870e+02,4.857927804348408651e-01,1.100000010988609489e+01,9.165207195125928304e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738311796615560922e+01,6.819625789679728314e+02,4.858019456407528525e-01,1.100000010988609489e+01,9.163747341110551128e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738402705705561857e+01,6.819725789637741400e+02,4.858111093868114350e-01,1.100000010988609489e+01,9.162287487095173953e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738493614795562792e+01,6.819825789595768128e+02,4.858202716730166126e-01,1.100000010988609489e+01,9.160827633079796778e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738584523885563726e+01,6.819925789553807363e+02,4.858294324993683855e-01,1.100000010988609489e+01,9.159367779064419603e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738675432975564661e+01,6.820025789511860239e+02,4.858385918658667535e-01,1.100000010988609489e+01,9.157907925049042427e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738766342065565595e+01,6.820125789469926758e+02,4.858477497725117167e-01,1.100000010988609489e+01,9.156448071033665252e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738857251155566530e+01,6.820225789428006919e+02,4.858569062193032750e-01,1.100000010988609489e+01,9.154988217018288077e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.738948160245567465e+01,6.820325789386099586e+02,4.858660612062414286e-01,1.100000010988609489e+01,9.153528363002910902e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739039069335568399e+01,6.820425789344205896e+02,4.858752147333261773e-01,1.100000010988609489e+01,9.152068508987533726e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739129978425569334e+01,6.820525789302325848e+02,4.858843668005575211e-01,1.100000010988609489e+01,9.150608654972156551e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739220887515570269e+01,6.820625789260459442e+02,4.858935174079354602e-01,1.100000010988609489e+01,9.149148800956779376e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739311796605571203e+01,6.820725789218605541e+02,4.859026665554599944e-01,1.100000010988609489e+01,9.147688946941402201e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739402705695572138e+01,6.820825789176765284e+02,4.859118142431311238e-01,1.100000010988609489e+01,9.146229092926025026e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739493614785573072e+01,6.820925789134938668e+02,4.859209604709488484e-01,1.100000010988609489e+01,9.144769238910647850e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739584523875574007e+01,6.821025789093125695e+02,4.859301052389131681e-01,1.100000010988609489e+01,9.143309384895270675e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739675432965574942e+01,6.821125789051325228e+02,4.859392485470240830e-01,1.100000010988609489e+01,9.141849530879893500e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739766342055575876e+01,6.821225789009538403e+02,4.859483903952815931e-01,1.100000010988609489e+01,9.140389676864516325e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739857251145576811e+01,6.821325788967765220e+02,4.859575307836856983e-01,1.100000010988609489e+01,9.138929822849139149e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.739948160235577745e+01,6.821425788926005680e+02,4.859666697122363987e-01,1.100000010988609489e+01,9.137469968833761974e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740039069325578680e+01,6.821525788884258645e+02,4.859758071809336943e-01,1.100000010988609489e+01,9.136010114818384799e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740129978415579615e+01,6.821625788842525253e+02,4.859849431897775851e-01,1.100000010988609489e+01,9.134550260803007624e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740220887505580549e+01,6.821725788800805503e+02,4.859940777387680710e-01,1.100000010988609489e+01,9.133090406787630448e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740311796595581484e+01,6.821825788759099396e+02,4.860032108279051521e-01,1.100000010988609489e+01,9.131630552772253273e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740402705685582418e+01,6.821925788717405794e+02,4.860123424571888284e-01,1.100000010988609489e+01,9.130170698756876098e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740493614775583353e+01,6.822025788675725835e+02,4.860214726266190999e-01,1.100000010988609489e+01,9.128710844741498923e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740584523865584288e+01,6.822125788634059518e+02,4.860306013361959665e-01,1.100000010988609489e+01,9.127250990726121747e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740675432955585222e+01,6.822225788592405706e+02,4.860397285859194283e-01,1.100000010988609489e+01,9.125791136710744572e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740766342045586157e+01,6.822325788550765537e+02,4.860488543757894853e-01,1.100000010988609489e+01,9.124331282695367397e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740857251135587092e+01,6.822425788509139011e+02,4.860579787058061374e-01,1.100000010988609489e+01,9.122871428679990222e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.740948160225588026e+01,6.822525788467526127e+02,4.860671015759693847e-01,1.100000010988609489e+01,9.121411574664613046e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741039069315588961e+01,6.822625788425925748e+02,4.860762229862792272e-01,1.100000010988609489e+01,9.119951720649235871e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741129978405589895e+01,6.822725788384339012e+02,4.860853429367356648e-01,1.100000010988609489e+01,9.118491866633858696e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741220887495590830e+01,6.822825788342765918e+02,4.860944614273386977e-01,1.100000010988609489e+01,9.117032012618481521e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741311796585591765e+01,6.822925788301205330e+02,4.861035784580883257e-01,1.100000010988609489e+01,9.115572158603104345e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741402705675592699e+01,6.823025788259658384e+02,4.861126940289844933e-01,1.100000010988609489e+01,9.114112304587727170e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741493614765593634e+01,6.823125788218125081e+02,4.861218081400272562e-01,1.100000010988609489e+01,9.112652450572349995e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741584523855594568e+01,6.823225788176605420e+02,4.861309207912166142e-01,1.100000010988609489e+01,9.111192596556972820e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741675432945595503e+01,6.823325788135098264e+02,4.861400319825525673e-01,1.100000010988609489e+01,9.109732742541595645e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741766342035596438e+01,6.823425788093604751e+02,4.861491417140351157e-01,1.100000010988609489e+01,9.108272888526218469e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741857251125597372e+01,6.823525788052124881e+02,4.861582499856642592e-01,1.100000010988609489e+01,9.106813034510841294e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.741948160215598307e+01,6.823625788010657516e+02,4.861673567974399979e-01,1.100000010988609489e+01,9.105353180495464119e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742039069305599241e+01,6.823725787969203793e+02,4.861764621493623317e-01,1.100000010988609489e+01,9.103893326480086944e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742129978395600176e+01,6.823825787927763713e+02,4.861855660414312608e-01,1.100000010988609489e+01,9.102433472464709768e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742220887485601111e+01,6.823925787886336138e+02,4.861946684736467850e-01,1.100000010988609489e+01,9.100973618449332593e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742311796575602045e+01,6.824025787844922206e+02,4.862037694460089043e-01,1.100000010988609489e+01,9.099513764433955418e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742402705665602980e+01,6.824125787803521916e+02,4.862128689585175634e-01,1.100000010988609489e+01,9.098053910418578243e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742493614755603915e+01,6.824225787762134132e+02,4.862219670111728176e-01,1.100000010988609489e+01,9.096594056403201067e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742584523845604849e+01,6.824325787720759990e+02,4.862310636039746670e-01,1.100000010988609489e+01,9.095134202387823892e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742675432935605784e+01,6.824425787679399491e+02,4.862401587369231115e-01,1.100000010988609489e+01,9.093674348372446717e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742766342025606718e+01,6.824525787638051497e+02,4.862492524100181512e-01,1.100000010988609489e+01,9.092214494357069542e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742857251115607653e+01,6.824625787596717146e+02,4.862583446232597861e-01,1.100000010988609489e+01,9.090754640341692366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.742948160205608588e+01,6.824725787555396437e+02,4.862674353766480162e-01,1.100000010988609489e+01,9.089294786326315191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743039069295609522e+01,6.824825787514088233e+02,4.862765246701828414e-01,1.100000010988609489e+01,9.087834932310938016e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743129978385610457e+01,6.824925787472793672e+02,4.862856125038642063e-01,1.100000010988609489e+01,9.086375078295560841e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743220887475611391e+01,6.825025787431512754e+02,4.862946988776921664e-01,1.100000010988609489e+01,9.084915224280183665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743311796565612326e+01,6.825125787390245478e+02,4.863037837916667216e-01,1.100000010988609489e+01,9.083455370264806490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743402705655613261e+01,6.825225787348990707e+02,4.863128672457878721e-01,1.100000010988609489e+01,9.081995516249429315e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743493614745614195e+01,6.825325787307749579e+02,4.863219492400556176e-01,1.100000010988609489e+01,9.080535662234052140e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743584523835615130e+01,6.825425787266520956e+02,4.863310297744699584e-01,1.100000010988609489e+01,9.079075808218674964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743675432925616064e+01,6.825525787225305976e+02,4.863401088490308943e-01,1.100000010988609489e+01,9.077615954203297789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743766342015616999e+01,6.825625787184104638e+02,4.863491864637383699e-01,1.100000010988609489e+01,9.076156100187920614e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743857251105617934e+01,6.825725787142915806e+02,4.863582626185924407e-01,1.100000010988609489e+01,9.074696246172543439e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.743948160195618868e+01,6.825825787101740616e+02,4.863673373135931066e-01,1.100000010988609489e+01,9.073236392157166263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744039069285619803e+01,6.825925787060579069e+02,4.863764105487403677e-01,1.100000010988609489e+01,9.071776538141789088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744129978375620738e+01,6.826025787019430027e+02,4.863854823240342240e-01,1.100000010988609489e+01,9.070316684126411913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744220887465621672e+01,6.826125786978294627e+02,4.863945526394746754e-01,1.100000010988609489e+01,9.068856830111034738e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744311796555622607e+01,6.826225786937172870e+02,4.864036214950616666e-01,1.100000010988609489e+01,9.067396976095657563e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744402705645623541e+01,6.826325786896063619e+02,4.864126888907952528e-01,1.100000010988609489e+01,9.065937122080280387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744493614735624476e+01,6.826425786854968010e+02,4.864217548266754343e-01,1.100000010988609489e+01,9.064477268064903212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744584523825625411e+01,6.826525786813886043e+02,4.864308193027022109e-01,1.100000010988609489e+01,9.063017414049526037e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744675432915626345e+01,6.826625786772816582e+02,4.864398823188755827e-01,1.100000010988609489e+01,9.061557560034148862e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744766342005627280e+01,6.826725786731760763e+02,4.864489438751954942e-01,1.100000010988609489e+01,9.060097706018771686e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744857251095628214e+01,6.826825786690718587e+02,4.864580039716620008e-01,1.100000010988609489e+01,9.058637852003394511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.744948160185629149e+01,6.826925786649688916e+02,4.864670626082751026e-01,1.100000010988609489e+01,9.057177997988017336e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745039069275630084e+01,6.827025786608672888e+02,4.864761197850347996e-01,1.100000010988609489e+01,9.055718143972640161e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745129978365631018e+01,6.827125786567669365e+02,4.864851755019410917e-01,1.100000010988609489e+01,9.054258289957262985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745220887455631953e+01,6.827225786526679485e+02,4.864942297589939235e-01,1.100000010988609489e+01,9.052798435941885810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745311796545632888e+01,6.827325786485703247e+02,4.865032825561933505e-01,1.100000010988609489e+01,9.051338581926508635e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745402705635633822e+01,6.827425786444739515e+02,4.865123338935393726e-01,1.100000010988609489e+01,9.049878727911131460e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745493614725634757e+01,6.827525786403789425e+02,4.865213837710319900e-01,1.100000010988609489e+01,9.048418873895754284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745584523815635691e+01,6.827625786362852978e+02,4.865304321886711469e-01,1.100000010988609489e+01,9.046959019880377109e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745675432905636626e+01,6.827725786321929036e+02,4.865394791464568991e-01,1.100000010988609489e+01,9.045499165864999934e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745766341995637561e+01,6.827825786281018736e+02,4.865485246443892464e-01,1.100000010988609489e+01,9.044039311849622759e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745857251085638495e+01,6.827925786240120942e+02,4.865575686824681889e-01,1.100000010988609489e+01,9.042579457834245583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.745948160175639430e+01,6.828025786199236791e+02,4.865666112606936711e-01,1.100000010988609489e+01,9.041119603818868408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746039069265640364e+01,6.828125786158366282e+02,4.865756523790657484e-01,1.100000010988609489e+01,9.039659749803491233e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746129978355641299e+01,6.828225786117508278e+02,4.865846920375844209e-01,1.100000010988609489e+01,9.038199895788114058e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746220887445642234e+01,6.828325786076663917e+02,4.865937302362496886e-01,1.100000010988609489e+01,9.036740041772736882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746311796535643168e+01,6.828425786035832061e+02,4.866027669750614959e-01,1.100000010988609489e+01,9.035280187757359707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746402705625644103e+01,6.828525785995013848e+02,4.866118022540198984e-01,1.100000010988609489e+01,9.033820333741982532e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746493614715645037e+01,6.828625785954209277e+02,4.866208360731248961e-01,1.100000010988609489e+01,9.032360479726605357e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746584523805645972e+01,6.828725785913417212e+02,4.866298684323764889e-01,1.100000010988609489e+01,9.030900625711228182e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746675432895646907e+01,6.828825785872638789e+02,4.866388993317746214e-01,1.100000010988609489e+01,9.029440771695851006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746766341985647841e+01,6.828925785831872872e+02,4.866479287713193491e-01,1.100000010988609489e+01,9.027980917680473831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746857251075648776e+01,6.829025785791120597e+02,4.866569567510106720e-01,1.100000010988609489e+01,9.026521063665096656e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.746948160165649711e+01,6.829125785750381965e+02,4.866659832708485900e-01,1.100000010988609489e+01,9.025061209649719481e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747039069255650645e+01,6.829225785709655838e+02,4.866750083308330477e-01,1.100000010988609489e+01,9.023601355634342305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747129978345651580e+01,6.829325785668943354e+02,4.866840319309641005e-01,1.100000010988609489e+01,9.022141501618965130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747220887435652514e+01,6.829425785628243375e+02,4.866930540712417486e-01,1.100000010988609489e+01,9.020681647603587955e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747311796525653449e+01,6.829525785587557039e+02,4.867020747516659362e-01,1.100000010988609489e+01,9.019221793588210780e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747402705615654384e+01,6.829625785546884345e+02,4.867110939722367191e-01,1.100000010988609489e+01,9.017761939572833604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747493614705655318e+01,6.829725785506224156e+02,4.867201117329540971e-01,1.100000010988609489e+01,9.016302085557456429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747584523795656253e+01,6.829825785465577610e+02,4.867291280338180148e-01,1.100000010988609489e+01,9.014842231542079254e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747675432885657187e+01,6.829925785424943570e+02,4.867381428748285277e-01,1.100000010988609489e+01,9.013382377526702079e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747766341975658122e+01,6.830025785384323171e+02,4.867471562559856357e-01,1.100000010988609489e+01,9.011922523511324903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747857251065659057e+01,6.830125785343715279e+02,4.867561681772893389e-01,1.100000010988609489e+01,9.010462669495947728e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.747948160155659991e+01,6.830225785303121029e+02,4.867651786387395818e-01,1.100000010988609489e+01,9.009002815480570553e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748039069245660926e+01,6.830325785262540421e+02,4.867741876403364198e-01,1.100000010988609489e+01,9.007542961465193378e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748129978335661860e+01,6.830425785221972319e+02,4.867831951820798531e-01,1.100000010988609489e+01,9.006083107449816202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748220887425662795e+01,6.830525785181417859e+02,4.867922012639698259e-01,1.100000010988609489e+01,9.004623253434439027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748311796515663730e+01,6.830625785140875905e+02,4.868012058860063940e-01,1.100000010988609489e+01,9.003163399419061852e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748402705605664664e+01,6.830725785100347593e+02,4.868102090481895572e-01,1.100000010988609489e+01,9.001703545403684677e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748493614695665599e+01,6.830825785059831787e+02,4.868192107505192601e-01,1.100000010988609489e+01,9.000243691388307501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748584523785666534e+01,6.830925785019329624e+02,4.868282109929955581e-01,1.100000010988609489e+01,8.998783837372930326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748675432875667468e+01,6.831025784978841102e+02,4.868372097756183958e-01,1.100000010988609489e+01,8.997323983357553151e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748766341965668403e+01,6.831125784938365086e+02,4.868462070983878287e-01,1.100000010988609489e+01,8.995864129342175976e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748857251055669337e+01,6.831225784897902713e+02,4.868552029613038568e-01,1.100000010988609489e+01,8.994404275326798801e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.748948160145670272e+01,6.831325784857452845e+02,4.868641973643664245e-01,1.100000010988609489e+01,8.992944421311421625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749039069235671207e+01,6.831425784817016620e+02,4.868731903075755874e-01,1.100000010988609489e+01,8.991484567296044450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749129978325672141e+01,6.831525784776592900e+02,4.868821817909313454e-01,1.100000010988609489e+01,8.990024713280667275e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749220887415673076e+01,6.831625784736182823e+02,4.868911718144336431e-01,1.100000010988609489e+01,8.988564859265290100e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749311796505674010e+01,6.831725784695785251e+02,4.869001603780825360e-01,1.100000010988609489e+01,8.987105005249912924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749402705595674945e+01,6.831825784655401321e+02,4.869091474818780241e-01,1.100000010988609489e+01,8.985645151234535749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749493614685675880e+01,6.831925784615029897e+02,4.869181331258200518e-01,1.100000010988609489e+01,8.984185297219158574e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749584523775676814e+01,6.832025784574672116e+02,4.869271173099086747e-01,1.100000010988609489e+01,8.982725443203781399e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749675432865677749e+01,6.832125784534327977e+02,4.869361000341438372e-01,1.100000010988609489e+01,8.981265589188404223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749766341955678683e+01,6.832225784493996343e+02,4.869450812985255950e-01,1.100000010988609489e+01,8.979805735173027048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749857251045679618e+01,6.832325784453678352e+02,4.869540611030539479e-01,1.100000010988609489e+01,8.978345881157649873e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.749948160135680553e+01,6.832425784413372867e+02,4.869630394477288404e-01,1.100000010988609489e+01,8.976886027142272698e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750039069225681487e+01,6.832525784373081024e+02,4.869720163325503282e-01,1.100000010988609489e+01,8.975426173126895522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750129978315682422e+01,6.832625784332801686e+02,4.869809917575183555e-01,1.100000010988609489e+01,8.973966319111518347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750220887405683357e+01,6.832725784292535991e+02,4.869899657226329781e-01,1.100000010988609489e+01,8.972506465096141172e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750311796495684291e+01,6.832825784252282801e+02,4.869989382278941958e-01,1.100000010988609489e+01,8.971046611080763997e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750402705585685226e+01,6.832925784212043254e+02,4.870079092733019532e-01,1.100000010988609489e+01,8.969586757065386821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750493614675686160e+01,6.833025784171816213e+02,4.870168788588563058e-01,1.100000010988609489e+01,8.968126903050009646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750584523765687095e+01,6.833125784131602813e+02,4.870258469845571980e-01,1.100000010988609489e+01,8.966667049034632471e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750675432855688030e+01,6.833225784091401920e+02,4.870348136504046854e-01,1.100000010988609489e+01,8.965207195019255296e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750766341945688964e+01,6.833325784051214669e+02,4.870437788563987680e-01,1.100000010988609489e+01,8.963747341003878120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750857251035689899e+01,6.833425784011039923e+02,4.870527426025393902e-01,1.100000010988609489e+01,8.962287486988500945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.750948160125690833e+01,6.833525783970878820e+02,4.870617048888266076e-01,1.100000010988609489e+01,8.960827632973123770e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751039069215691768e+01,6.833625783930730222e+02,4.870706657152603647e-01,1.100000010988609489e+01,8.959367778957746595e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751129978305692703e+01,6.833725783890595267e+02,4.870796250818407169e-01,1.100000010988609489e+01,8.957907924942369420e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751220887395693637e+01,6.833825783850472817e+02,4.870885829885676088e-01,1.100000010988609489e+01,8.956448070926992244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751311796485694572e+01,6.833925783810364010e+02,4.870975394354410959e-01,1.100000010988609489e+01,8.954988216911615069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751402705575695506e+01,6.834025783770267708e+02,4.871064944224611226e-01,1.100000010988609489e+01,8.953528362896237894e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751493614665696441e+01,6.834125783730185049e+02,4.871154479496277445e-01,1.100000010988609489e+01,8.952068508880860719e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751584523755697376e+01,6.834225783690114895e+02,4.871244000169409616e-01,1.100000010988609489e+01,8.950608654865483543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751675432845698310e+01,6.834325783650058384e+02,4.871333506244007183e-01,1.100000010988609489e+01,8.949148800850106368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751766341935699245e+01,6.834425783610014378e+02,4.871422997720070702e-01,1.100000010988609489e+01,8.947688946834729193e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751857251025700180e+01,6.834525783569984014e+02,4.871512474597599618e-01,1.100000010988609489e+01,8.946229092819352018e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.751948160115701114e+01,6.834625783529966156e+02,4.871601936876594485e-01,1.100000010988609489e+01,8.944769238803974842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752039069205702049e+01,6.834725783489961941e+02,4.871691384557054749e-01,1.100000010988609489e+01,8.943309384788597667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752129978295702983e+01,6.834825783449970231e+02,4.871780817638980965e-01,1.100000010988609489e+01,8.941849530773220492e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752220887385703918e+01,6.834925783409992164e+02,4.871870236122372577e-01,1.100000010988609489e+01,8.940389676757843317e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752311796475704853e+01,6.835025783370026602e+02,4.871959640007230141e-01,1.100000010988609489e+01,8.938929822742466141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752402705565705787e+01,6.835125783330074682e+02,4.872049029293553102e-01,1.100000010988609489e+01,8.937469968727088966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752493614655706722e+01,6.835225783290135269e+02,4.872138403981342014e-01,1.100000010988609489e+01,8.936010114711711791e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752584523745707656e+01,6.835325783250209497e+02,4.872227764070596323e-01,1.100000010988609489e+01,8.934550260696334616e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752675432835708591e+01,6.835425783210296231e+02,4.872317109561316584e-01,1.100000010988609489e+01,8.933090406680957440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752766341925709526e+01,6.835525783170396608e+02,4.872406440453502241e-01,1.100000010988609489e+01,8.931630552665580265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752857251015710460e+01,6.835625783130509490e+02,4.872495756747153850e-01,1.100000010988609489e+01,8.930170698650203090e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.752948160105711395e+01,6.835725783090636014e+02,4.872585058442270856e-01,1.100000010988609489e+01,8.928710844634825915e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753039069195712329e+01,6.835825783050775044e+02,4.872674345538853813e-01,1.100000010988609489e+01,8.927250990619448739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753129978285713264e+01,6.835925783010926580e+02,4.872763618036902167e-01,1.100000010988609489e+01,8.925791136604071564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753220887375714199e+01,6.836025782971091758e+02,4.872852875936416472e-01,1.100000010988609489e+01,8.924331282588694389e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753311796465715133e+01,6.836125782931269441e+02,4.872942119237396175e-01,1.100000010988609489e+01,8.922871428573317214e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753402705555716068e+01,6.836225782891460767e+02,4.873031347939841829e-01,1.100000010988609489e+01,8.921411574557940038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753493614645717003e+01,6.836325782851664599e+02,4.873120562043752879e-01,1.100000010988609489e+01,8.919951720542562863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753584523735717937e+01,6.836425782811882073e+02,4.873209761549129881e-01,1.100000010988609489e+01,8.918491866527185688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753675432825718872e+01,6.836525782772112052e+02,4.873298946455972280e-01,1.100000010988609489e+01,8.917032012511808513e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753766341915719806e+01,6.836625782732355674e+02,4.873388116764280076e-01,1.100000010988609489e+01,8.915572158496431338e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753857251005720741e+01,6.836725782692611801e+02,4.873477272474053823e-01,1.100000010988609489e+01,8.914112304481054162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.753948160095721676e+01,6.836825782652881571e+02,4.873566413585292967e-01,1.100000010988609489e+01,8.912652450465676987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754039069185722610e+01,6.836925782613163847e+02,4.873655540097998062e-01,1.100000010988609489e+01,8.911192596450299812e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754129978275723545e+01,6.837025782573458628e+02,4.873744652012168554e-01,1.100000010988609489e+01,8.909732742434922637e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754220887365724479e+01,6.837125782533767051e+02,4.873833749327804998e-01,1.100000010988609489e+01,8.908272888419545461e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754311796455725414e+01,6.837225782494087980e+02,4.873922832044906839e-01,1.100000010988609489e+01,8.906813034404168286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754402705545726349e+01,6.837325782454422551e+02,4.874011900163474631e-01,1.100000010988609489e+01,8.905353180388791111e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754493614635727283e+01,6.837425782414769628e+02,4.874100953683507820e-01,1.100000010988609489e+01,8.903893326373413936e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754584523725728218e+01,6.837525782375130348e+02,4.874189992605006405e-01,1.100000010988609489e+01,8.902433472358036760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754675432815729152e+01,6.837625782335503573e+02,4.874279016927970942e-01,1.100000010988609489e+01,8.900973618342659585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754766341905730087e+01,6.837725782295890440e+02,4.874368026652400876e-01,1.100000010988609489e+01,8.899513764327282410e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754857250995731022e+01,6.837825782256289813e+02,4.874457021778296761e-01,1.100000010988609489e+01,8.898053910311905235e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.754948160085731956e+01,6.837925782216701691e+02,4.874546002305658043e-01,1.100000010988609489e+01,8.896594056296528059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755039069175732891e+01,6.838025782177127212e+02,4.874634968234485277e-01,1.100000010988609489e+01,8.895134202281150884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755129978265733826e+01,6.838125782137565238e+02,4.874723919564777908e-01,1.100000010988609489e+01,8.893674348265773709e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755220887355734760e+01,6.838225782098016907e+02,4.874812856296535934e-01,1.100000010988609489e+01,8.892214494250396534e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755311796445735695e+01,6.838325782058481082e+02,4.874901778429759913e-01,1.100000010988609489e+01,8.890754640235019358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755402705535736629e+01,6.838425782018957761e+02,4.874990685964449288e-01,1.100000010988609489e+01,8.889294786219642183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755493614625737564e+01,6.838525781979448084e+02,4.875079578900604615e-01,1.100000010988609489e+01,8.887834932204265008e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755584523715738499e+01,6.838625781939950912e+02,4.875168457238225339e-01,1.100000010988609489e+01,8.886375078188887833e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755675432805739433e+01,6.838725781900467382e+02,4.875257320977311459e-01,1.100000010988609489e+01,8.884915224173510657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755766341895740368e+01,6.838825781860996358e+02,4.875346170117863531e-01,1.100000010988609489e+01,8.883455370158133482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755857250985741302e+01,6.838925781821538976e+02,4.875435004659881000e-01,1.100000010988609489e+01,8.881995516142756307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.755948160075742237e+01,6.839025781782094100e+02,4.875523824603363865e-01,1.100000010988609489e+01,8.880535662127379132e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756039069165743172e+01,6.839125781742661729e+02,4.875612629948312682e-01,1.100000010988609489e+01,8.879075808112001957e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756129978255744106e+01,6.839225781703243001e+02,4.875701420694726895e-01,1.100000010988609489e+01,8.877615954096624781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756220887345745041e+01,6.839325781663836779e+02,4.875790196842607060e-01,1.100000010988609489e+01,8.876156100081247606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756311796435745975e+01,6.839425781624444198e+02,4.875878958391952622e-01,1.100000010988609489e+01,8.874696246065870431e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756402705525746910e+01,6.839525781585064124e+02,4.875967705342763581e-01,1.100000010988609489e+01,8.873236392050493256e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756493614615747845e+01,6.839625781545696555e+02,4.876056437695040491e-01,1.100000010988609489e+01,8.871776538035116080e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756584523705748779e+01,6.839725781506342628e+02,4.876145155448782798e-01,1.100000010988609489e+01,8.870316684019738905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756675432795749714e+01,6.839825781467001207e+02,4.876233858603990501e-01,1.100000010988609489e+01,8.868856830004361730e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756766341885750649e+01,6.839925781427673428e+02,4.876322547160664156e-01,1.100000010988609489e+01,8.867396975988984555e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756857250975751583e+01,6.840025781388358155e+02,4.876411221118803208e-01,1.100000010988609489e+01,8.865937121973607379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.756948160065752518e+01,6.840125781349055387e+02,4.876499880478407656e-01,1.100000010988609489e+01,8.864477267958230204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757039069155753452e+01,6.840225781309766262e+02,4.876588525239478056e-01,1.100000010988609489e+01,8.863017413942853029e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757129978245754387e+01,6.840325781270489642e+02,4.876677155402013852e-01,1.100000010988609489e+01,8.861557559927475854e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757220887335755322e+01,6.840425781231225528e+02,4.876765770966015046e-01,1.100000010988609489e+01,8.860097705912098678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757311796425756256e+01,6.840525781191975057e+02,4.876854371931482190e-01,1.100000010988609489e+01,8.858637851896721503e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757402705515757191e+01,6.840625781152737090e+02,4.876942958298414732e-01,1.100000010988609489e+01,8.857177997881344328e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757493614605758125e+01,6.840725781113512767e+02,4.877031530066812670e-01,1.100000010988609489e+01,8.855718143865967153e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757584523695759060e+01,6.840825781074300949e+02,4.877120087236676560e-01,1.100000010988609489e+01,8.854258289850589977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757675432785759995e+01,6.840925781035101636e+02,4.877208629808005846e-01,1.100000010988609489e+01,8.852798435835212802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757766341875760929e+01,6.841025780995915966e+02,4.877297157780800529e-01,1.100000010988609489e+01,8.851338581819835627e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757857250965761864e+01,6.841125780956742801e+02,4.877385671155061164e-01,1.100000010988609489e+01,8.849878727804458452e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.757948160055762798e+01,6.841225780917582142e+02,4.877474169930787196e-01,1.100000010988609489e+01,8.848418873789081276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758039069145763733e+01,6.841325780878435125e+02,4.877562654107978624e-01,1.100000010988609489e+01,8.846959019773704101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758129978235764668e+01,6.841425780839300614e+02,4.877651123686635448e-01,1.100000010988609489e+01,8.845499165758326926e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758220887325765602e+01,6.841525780800179746e+02,4.877739578666758224e-01,1.100000010988609489e+01,8.844039311742949751e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758311796415766537e+01,6.841625780761071383e+02,4.877828019048346397e-01,1.100000010988609489e+01,8.842579457727572576e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758402705505767472e+01,6.841725780721975525e+02,4.877916444831399967e-01,1.100000010988609489e+01,8.841119603712195400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758493614595768406e+01,6.841825780682893310e+02,4.878004856015919488e-01,1.100000010988609489e+01,8.839659749696818225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758584523685769341e+01,6.841925780643823600e+02,4.878093252601904406e-01,1.100000010988609489e+01,8.838199895681441050e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758675432775770275e+01,6.842025780604766396e+02,4.878181634589354720e-01,1.100000010988609489e+01,8.836740041666063875e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758766341865771210e+01,6.842125780565722835e+02,4.878270001978270431e-01,1.100000010988609489e+01,8.835280187650686699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758857250955772145e+01,6.842225780526691779e+02,4.878358354768652094e-01,1.100000010988609489e+01,8.833820333635309524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.758948160045773079e+01,6.842325780487673228e+02,4.878446692960499154e-01,1.100000010988609489e+01,8.832360479619932349e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759039069135774014e+01,6.842425780448668320e+02,4.878535016553811610e-01,1.100000010988609489e+01,8.830900625604555174e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759129978225774948e+01,6.842525780409675917e+02,4.878623325548589462e-01,1.100000010988609489e+01,8.829440771589177998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759220887315775883e+01,6.842625780370696020e+02,4.878711619944833267e-01,1.100000010988609489e+01,8.827980917573800823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759311796405776818e+01,6.842725780331729766e+02,4.878799899742542467e-01,1.100000010988609489e+01,8.826521063558423648e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759402705495777752e+01,6.842825780292776017e+02,4.878888164941717065e-01,1.100000010988609489e+01,8.825061209543046473e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759493614585778687e+01,6.842925780253834773e+02,4.878976415542357059e-01,1.100000010988609489e+01,8.823601355527669297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759584523675779621e+01,6.843025780214907172e+02,4.879064651544463005e-01,1.100000010988609489e+01,8.822141501512292122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759675432765780556e+01,6.843125780175992077e+02,4.879152872948034347e-01,1.100000010988609489e+01,8.820681647496914947e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759766341855781491e+01,6.843225780137089487e+02,4.879241079753071086e-01,1.100000010988609489e+01,8.819221793481537772e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759857250945782425e+01,6.843325780098200539e+02,4.879329271959573222e-01,1.100000010988609489e+01,8.817761939466160596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.759948160035783360e+01,6.843425780059324097e+02,4.879417449567541309e-01,1.100000010988609489e+01,8.816302085450783421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760039069125784295e+01,6.843525780020460161e+02,4.879505612576974793e-01,1.100000010988609489e+01,8.814842231435406246e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760129978215785229e+01,6.843625779981609867e+02,4.879593760987873674e-01,1.100000010988609489e+01,8.813382377420029071e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760220887305786164e+01,6.843725779942772078e+02,4.879681894800237951e-01,1.100000010988609489e+01,8.811922523404651895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760311796395787098e+01,6.843825779903946795e+02,4.879770014014068180e-01,1.100000010988609489e+01,8.810462669389274720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760402705485788033e+01,6.843925779865135155e+02,4.879858118629363806e-01,1.100000010988609489e+01,8.809002815373897545e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760493614575788968e+01,6.844025779826336020e+02,4.879946208646124828e-01,1.100000010988609489e+01,8.807542961358520370e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760584523665789902e+01,6.844125779787549391e+02,4.880034284064351247e-01,1.100000010988609489e+01,8.806083107343143195e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760675432755790837e+01,6.844225779748776404e+02,4.880122344884043062e-01,1.100000010988609489e+01,8.804623253327766019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760766341845791771e+01,6.844325779710015922e+02,4.880210391105200829e-01,1.100000010988609489e+01,8.803163399312388844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760857250935792706e+01,6.844425779671267946e+02,4.880298422727823993e-01,1.100000010988609489e+01,8.801703545297011669e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.760948160025793641e+01,6.844525779632532476e+02,4.880386439751912553e-01,1.100000010988609489e+01,8.800243691281634494e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761039069115794575e+01,6.844625779593810648e+02,4.880474442177466510e-01,1.100000010988609489e+01,8.798783837266257318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761129978205795510e+01,6.844725779555101326e+02,4.880562430004485863e-01,1.100000010988609489e+01,8.797323983250880143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761220887295796445e+01,6.844825779516404509e+02,4.880650403232970613e-01,1.100000010988609489e+01,8.795864129235502968e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761311796385797379e+01,6.844925779477721335e+02,4.880738361862921315e-01,1.100000010988609489e+01,8.794404275220125793e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761402705475798314e+01,6.845025779439050666e+02,4.880826305894337414e-01,1.100000010988609489e+01,8.792944421204748617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761493614565799248e+01,6.845125779400392503e+02,4.880914235327218909e-01,1.100000010988609489e+01,8.791484567189371442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761584523655800183e+01,6.845225779361746845e+02,4.881002150161565800e-01,1.100000010988609489e+01,8.790024713173994267e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761675432745801118e+01,6.845325779323114830e+02,4.881090050397378088e-01,1.100000010988609489e+01,8.788564859158617092e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761766341835802052e+01,6.845425779284495320e+02,4.881177936034655773e-01,1.100000010988609489e+01,8.787105005143239916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761857250925802987e+01,6.845525779245888316e+02,4.881265807073399410e-01,1.100000010988609489e+01,8.785645151127862741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.761948160015803921e+01,6.845625779207294954e+02,4.881353663513608443e-01,1.100000010988609489e+01,8.784185297112485566e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762039069105804856e+01,6.845725779168714098e+02,4.881441505355282873e-01,1.100000010988609489e+01,8.782725443097108391e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762129978195805791e+01,6.845825779130145747e+02,4.881529332598422699e-01,1.100000010988609489e+01,8.781265589081731215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762220887285806725e+01,6.845925779091589902e+02,4.881617145243027922e-01,1.100000010988609489e+01,8.779805735066354040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762311796375807660e+01,6.846025779053047700e+02,4.881704943289098542e-01,1.100000010988609489e+01,8.778345881050976865e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762402705465808594e+01,6.846125779014518002e+02,4.881792726736634558e-01,1.100000010988609489e+01,8.776886027035599690e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762493614555809529e+01,6.846225778976000811e+02,4.881880495585636526e-01,1.100000010988609489e+01,8.775426173020222514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762584523645810464e+01,6.846325778937497262e+02,4.881968249836103890e-01,1.100000010988609489e+01,8.773966319004845339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762675432735811398e+01,6.846425778899006218e+02,4.882055989488036651e-01,1.100000010988609489e+01,8.772506464989468164e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762766341825812333e+01,6.846525778860527680e+02,4.882143714541434809e-01,1.100000010988609489e+01,8.771046610974090989e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762857250915813268e+01,6.846625778822061648e+02,4.882231424996298363e-01,1.100000010988609489e+01,8.769586756958713814e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.762948160005814202e+01,6.846725778783609258e+02,4.882319120852627314e-01,1.100000010988609489e+01,8.768126902943336638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763039069095815137e+01,6.846825778745169373e+02,4.882406802110421662e-01,1.100000010988609489e+01,8.766667048927959463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763129978185816071e+01,6.846925778706741994e+02,4.882494468769681406e-01,1.100000010988609489e+01,8.765207194912582288e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763220887275817006e+01,6.847025778668327121e+02,4.882582120830407102e-01,1.100000010988609489e+01,8.763747340897205113e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763311796365817941e+01,6.847125778629925890e+02,4.882669758292598194e-01,1.100000010988609489e+01,8.762287486881827937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763402705455818875e+01,6.847225778591537164e+02,4.882757381156254683e-01,1.100000010988609489e+01,8.760827632866450762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763493614545819810e+01,6.847325778553160944e+02,4.882844989421376569e-01,1.100000010988609489e+01,8.759367778851073587e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763584523635820744e+01,6.847425778514797230e+02,4.882932583087963851e-01,1.100000010988609489e+01,8.757907924835696412e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763675432725821679e+01,6.847525778476447158e+02,4.883020162156016530e-01,1.100000010988609489e+01,8.756448070820319236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763766341815822614e+01,6.847625778438109592e+02,4.883107726625534606e-01,1.100000010988609489e+01,8.754988216804942061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763857250905823548e+01,6.847725778399784531e+02,4.883195276496518078e-01,1.100000010988609489e+01,8.753528362789564886e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.763948159995824483e+01,6.847825778361471976e+02,4.883282811768966947e-01,1.100000010988609489e+01,8.752068508774187711e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764039069085825417e+01,6.847925778323173063e+02,4.883370332442881212e-01,1.100000010988609489e+01,8.750608654758810535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764129978175826352e+01,6.848025778284886655e+02,4.883457838518260874e-01,1.100000010988609489e+01,8.749148800743433360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764220887265827287e+01,6.848125778246612754e+02,4.883545329995105932e-01,1.100000010988609489e+01,8.747688946728056185e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764311796355828221e+01,6.848225778208351358e+02,4.883632806873416943e-01,1.100000010988609489e+01,8.746229092712679010e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764402705445829156e+01,6.848325778170103604e+02,4.883720269153193350e-01,1.100000010988609489e+01,8.744769238697301834e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764493614535830091e+01,6.848425778131868356e+02,4.883807716834435153e-01,1.100000010988609489e+01,8.743309384681924659e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764584523625831025e+01,6.848525778093645613e+02,4.883895149917142353e-01,1.100000010988609489e+01,8.741849530666547484e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764675432715831960e+01,6.848625778055435376e+02,4.883982568401314950e-01,1.100000010988609489e+01,8.740389676651170309e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764766341805832894e+01,6.848725778017237644e+02,4.884069972286952943e-01,1.100000010988609489e+01,8.738929822635793133e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764857250895833829e+01,6.848825777979053555e+02,4.884157361574056333e-01,1.100000010988609489e+01,8.737469968620415958e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.764948159985834764e+01,6.848925777940881972e+02,4.884244736262625119e-01,1.100000010988609489e+01,8.736010114605038783e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765039069075835698e+01,6.849025777902722893e+02,4.884332096352659303e-01,1.100000010988609489e+01,8.734550260589661608e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765129978165836633e+01,6.849125777864576321e+02,4.884419441844158882e-01,1.100000010988609489e+01,8.733090406574284432e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765220887255837567e+01,6.849225777826443391e+02,4.884506772737123859e-01,1.100000010988609489e+01,8.731630552558907257e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765311796345838502e+01,6.849325777788322966e+02,4.884594089031554232e-01,1.100000010988609489e+01,8.730170698543530082e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765402705435839437e+01,6.849425777750215047e+02,4.884681390727450001e-01,1.100000010988609489e+01,8.728710844528152907e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765493614525840371e+01,6.849525777712119634e+02,4.884768677824811167e-01,1.100000010988609489e+01,8.727250990512775732e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765584523615841306e+01,6.849625777674036726e+02,4.884855950323637730e-01,1.100000010988609489e+01,8.725791136497398556e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765675432705842240e+01,6.849725777635967461e+02,4.884943208223929689e-01,1.100000010988609489e+01,8.724331282482021381e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765766341795843175e+01,6.849825777597910701e+02,4.885030451525687045e-01,1.100000010988609489e+01,8.722871428466644206e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765857250885844110e+01,6.849925777559866447e+02,4.885117680228909798e-01,1.100000010988609489e+01,8.721411574451267031e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.765948159975845044e+01,6.850025777521834698e+02,4.885204894333597947e-01,1.100000010988609489e+01,8.719951720435889855e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766039069065845979e+01,6.850125777483815455e+02,4.885292093839751493e-01,1.100000010988609489e+01,8.718491866420512680e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766129978155846914e+01,6.850225777445809854e+02,4.885379278747370435e-01,1.100000010988609489e+01,8.717032012405135505e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766220887245847848e+01,6.850325777407816759e+02,4.885466449056454774e-01,1.100000010988609489e+01,8.715572158389758330e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766311796335848783e+01,6.850425777369836169e+02,4.885553604767004510e-01,1.100000010988609489e+01,8.714112304374381154e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766402705425849717e+01,6.850525777331868085e+02,4.885640745879019642e-01,1.100000010988609489e+01,8.712652450359003979e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766493614515850652e+01,6.850625777293912506e+02,4.885727872392500171e-01,1.100000010988609489e+01,8.711192596343626804e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766584523605851587e+01,6.850725777255970570e+02,4.885814984307446096e-01,1.100000010988609489e+01,8.709732742328249629e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766675432695852521e+01,6.850825777218041139e+02,4.885902081623857418e-01,1.100000010988609489e+01,8.708272888312872453e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766766341785853456e+01,6.850925777180124214e+02,4.885989164341734137e-01,1.100000010988609489e+01,8.706813034297495278e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766857250875854390e+01,6.851025777142219795e+02,4.886076232461076252e-01,1.100000010988609489e+01,8.705353180282118103e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.766948159965855325e+01,6.851125777104327881e+02,4.886163285981883764e-01,1.100000010988609489e+01,8.703893326266740928e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767039069055856260e+01,6.851225777066448472e+02,4.886250324904156672e-01,1.100000010988609489e+01,8.702433472251363752e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767129978145857194e+01,6.851325777028582706e+02,4.886337349227894977e-01,1.100000010988609489e+01,8.700973618235986577e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767220887235858129e+01,6.851425776990729446e+02,4.886424358953098679e-01,1.100000010988609489e+01,8.699513764220609402e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767311796325859063e+01,6.851525776952888691e+02,4.886511354079767777e-01,1.100000010988609489e+01,8.698053910205232227e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767402705415859998e+01,6.851625776915060442e+02,4.886598334607902272e-01,1.100000010988609489e+01,8.696594056189855051e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767493614505860933e+01,6.851725776877244698e+02,4.886685300537502163e-01,1.100000010988609489e+01,8.695134202174477876e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767584523595861867e+01,6.851825776839441460e+02,4.886772251868567452e-01,1.100000010988609489e+01,8.693674348159100701e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767675432685862802e+01,6.851925776801651864e+02,4.886859188601098136e-01,1.100000010988609489e+01,8.692214494143723526e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767766341775863737e+01,6.852025776763874774e+02,4.886946110735094218e-01,1.100000010988609489e+01,8.690754640128346351e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767857250865864671e+01,6.852125776726110189e+02,4.887033018270555140e-01,1.100000010988609489e+01,8.689294786112969175e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.767948159955865606e+01,6.852225776688358110e+02,4.887119911207481460e-01,1.100000010988609489e+01,8.687834932097592000e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768039069045866540e+01,6.852325776650618536e+02,4.887206789545873176e-01,1.100000010988609489e+01,8.686375078082214825e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768129978135867475e+01,6.852425776612891468e+02,4.887293653285730288e-01,1.100000010988609489e+01,8.684915224066837650e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768220887225868410e+01,6.852525776575178043e+02,4.887380502427052797e-01,1.100000010988609489e+01,8.683455370051460474e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768311796315869344e+01,6.852625776537477122e+02,4.887467336969840703e-01,1.100000010988609489e+01,8.681995516036083299e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768402705405870279e+01,6.852725776499788708e+02,4.887554156914094006e-01,1.100000010988609489e+01,8.680535662020706124e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768493614495871213e+01,6.852825776462112799e+02,4.887640962259812705e-01,1.100000010988609489e+01,8.679075808005328949e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768584523585872148e+01,6.852925776424449396e+02,4.887727753006996800e-01,1.100000010988609489e+01,8.677615953989951773e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768675432675873083e+01,6.853025776386798498e+02,4.887814529155646293e-01,1.100000010988609489e+01,8.676156099974574598e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768766341765874017e+01,6.853125776349160105e+02,4.887901290705761181e-01,1.100000010988609489e+01,8.674696245959197423e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768857250855874952e+01,6.853225776311535355e+02,4.887988037657341467e-01,1.100000010988609489e+01,8.673236391943820248e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.768948159945875886e+01,6.853325776273923111e+02,4.888074770010386594e-01,1.100000010988609489e+01,8.671776537928443072e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769039069035876821e+01,6.853425776236323372e+02,4.888161487764897117e-01,1.100000010988609489e+01,8.670316683913065897e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769129978125877756e+01,6.853525776198736139e+02,4.888248190920873038e-01,1.100000010988609489e+01,8.668856829897688722e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769220887215878690e+01,6.853625776161161411e+02,4.888334879478314354e-01,1.100000010988609489e+01,8.667396975882311547e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769311796305879625e+01,6.853725776123599189e+02,4.888421553437221068e-01,1.100000010988609489e+01,8.665937121866934371e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769402705395880560e+01,6.853825776086049473e+02,4.888508212797593178e-01,1.100000010988609489e+01,8.664477267851557196e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769493614485881494e+01,6.853925776048513399e+02,4.888594857559430684e-01,1.100000010988609489e+01,8.663017413836180021e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769584523575882429e+01,6.854025776010989830e+02,4.888681487722733587e-01,1.100000010988609489e+01,8.661557559820802846e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769675432665883363e+01,6.854125775973478767e+02,4.888768103287501332e-01,1.100000010988609489e+01,8.660097705805425670e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769766341755884298e+01,6.854225775935980209e+02,4.888854704253734473e-01,1.100000010988609489e+01,8.658637851790048495e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769857250845885233e+01,6.854325775898494157e+02,4.888941290621433011e-01,1.100000010988609489e+01,8.657177997774671320e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.769948159935886167e+01,6.854425775861020611e+02,4.889027862390596946e-01,1.100000010988609489e+01,8.655718143759294145e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770039069025887102e+01,6.854525775823559570e+02,4.889114419561226277e-01,1.100000010988609489e+01,8.654258289743916970e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770129978115888036e+01,6.854625775786111035e+02,4.889200962133321005e-01,1.100000010988609489e+01,8.652798435728539794e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770220887205888971e+01,6.854725775748676142e+02,4.889287490106881129e-01,1.100000010988609489e+01,8.651338581713162619e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770311796295889906e+01,6.854825775711253755e+02,4.889374003481906095e-01,1.100000010988609489e+01,8.649878727697785444e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770402705385890840e+01,6.854925775673843873e+02,4.889460502258396457e-01,1.100000010988609489e+01,8.648418873682408269e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770493614475891775e+01,6.855025775636446497e+02,4.889546986436352216e-01,1.100000010988609489e+01,8.646959019667031093e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770584523565892709e+01,6.855125775599061626e+02,4.889633456015773372e-01,1.100000010988609489e+01,8.645499165651653918e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770675432655893644e+01,6.855225775561689261e+02,4.889719910996659924e-01,1.100000010988609489e+01,8.644039311636276743e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770766341745894579e+01,6.855325775524329401e+02,4.889806351379011873e-01,1.100000010988609489e+01,8.642579457620899568e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770857250835895513e+01,6.855425775486982047e+02,4.889892777162828663e-01,1.100000010988609489e+01,8.641119603605522392e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.770948159925896448e+01,6.855525775449647199e+02,4.889979188348110850e-01,1.100000010988609489e+01,8.639659749590145217e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771039069015897383e+01,6.855625775412324856e+02,4.890065584934858434e-01,1.100000010988609489e+01,8.638199895574768042e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771129978105898317e+01,6.855725775375016156e+02,4.890151966923071414e-01,1.100000010988609489e+01,8.636740041559390867e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771220887195899252e+01,6.855825775337719961e+02,4.890238334312749791e-01,1.100000010988609489e+01,8.635280187544013691e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771311796285900186e+01,6.855925775300436271e+02,4.890324687103893564e-01,1.100000010988609489e+01,8.633820333528636516e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771402705375901121e+01,6.856025775263165087e+02,4.890411025296502179e-01,1.100000010988609489e+01,8.632360479513259341e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771493614465902056e+01,6.856125775225906409e+02,4.890497348890576190e-01,1.100000010988609489e+01,8.630900625497882166e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771584523555902990e+01,6.856225775188660236e+02,4.890583657886115598e-01,1.100000010988609489e+01,8.629440771482504990e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771675432645903925e+01,6.856325775151426569e+02,4.890669952283120403e-01,1.100000010988609489e+01,8.627980917467127815e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771766341735904859e+01,6.856425775114205408e+02,4.890756232081590604e-01,1.100000010988609489e+01,8.626521063451750640e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771857250825905794e+01,6.856525775076996752e+02,4.890842497281525647e-01,1.100000010988609489e+01,8.625061209436373465e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.771948159915906729e+01,6.856625775039800601e+02,4.890928747882926086e-01,1.100000010988609489e+01,8.623601355420996289e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772039069005907663e+01,6.856725775002616956e+02,4.891014983885791922e-01,1.100000010988609489e+01,8.622141501405619114e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772129978095908598e+01,6.856825774965445817e+02,4.891101205290123155e-01,1.100000010988609489e+01,8.620681647390241939e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772220887185909532e+01,6.856925774928287183e+02,4.891187412095919229e-01,1.100000010988609489e+01,8.619221793374864764e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772311796275910467e+01,6.857025774891142191e+02,4.891273604303180700e-01,1.100000010988609489e+01,8.617761939359487589e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772402705365911402e+01,6.857125774854009705e+02,4.891359781911907567e-01,1.100000010988609489e+01,8.616302085344110413e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772493614455912336e+01,6.857225774816889725e+02,4.891445944922099831e-01,1.100000010988609489e+01,8.614842231328733238e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772584523545913271e+01,6.857325774779782250e+02,4.891532093333756936e-01,1.100000010988609489e+01,8.613382377313356063e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772675432635914206e+01,6.857425774742687281e+02,4.891618227146879438e-01,1.100000010988609489e+01,8.611922523297978888e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772766341725915140e+01,6.857525774705604817e+02,4.891704346361467337e-01,1.100000010988609489e+01,8.610462669282601712e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772857250815916075e+01,6.857625774668534859e+02,4.891790450977520632e-01,1.100000010988609489e+01,8.609002815267224537e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.772948159905917009e+01,6.857725774631477407e+02,4.891876540995038769e-01,1.100000010988609489e+01,8.607542961251847362e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773039068995917944e+01,6.857825774594432460e+02,4.891962616414022302e-01,1.100000010988609489e+01,8.606083107236470187e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773129978085918879e+01,6.857925774557400018e+02,4.892048677234471232e-01,1.100000010988609489e+01,8.604623253221093011e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773220887175919813e+01,6.858025774520380082e+02,4.892134723456385559e-01,1.100000010988609489e+01,8.603163399205715836e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773311796265920748e+01,6.858125774483372652e+02,4.892220755079764727e-01,1.100000010988609489e+01,8.601703545190338661e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773402705355921682e+01,6.858225774446377727e+02,4.892306772104609291e-01,1.100000010988609489e+01,8.600243691174961486e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773493614445922617e+01,6.858325774409395308e+02,4.892392774530919253e-01,1.100000010988609489e+01,8.598783837159584310e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773584523535923552e+01,6.858425774372425394e+02,4.892478762358694611e-01,1.100000010988609489e+01,8.597323983144207135e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773675432625924486e+01,6.858525774335467986e+02,4.892564735587934810e-01,1.100000010988609489e+01,8.595864129128829960e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773766341715925421e+01,6.858625774298523083e+02,4.892650694218640406e-01,1.100000010988609489e+01,8.594404275113452785e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773857250805926355e+01,6.858725774261590686e+02,4.892736638250811398e-01,1.100000010988609489e+01,8.592944421098075609e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.773948159895927290e+01,6.858825774224670795e+02,4.892822567684447788e-01,1.100000010988609489e+01,8.591484567082698434e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774039068985928225e+01,6.858925774187764546e+02,4.892908482519549018e-01,1.100000010988609489e+01,8.590024713067321259e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774129978075929159e+01,6.859025774150870802e+02,4.892994382756115646e-01,1.100000010988609489e+01,8.588564859051944084e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774220887165930094e+01,6.859125774113989564e+02,4.893080268394147669e-01,1.100000010988609489e+01,8.587105005036566908e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774311796255931029e+01,6.859225774077120832e+02,4.893166139433644535e-01,1.100000010988609489e+01,8.585645151021189733e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774402705345931963e+01,6.859325774040264605e+02,4.893251995874606797e-01,1.100000010988609489e+01,8.584185297005812558e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774493614435932898e+01,6.859425774003420884e+02,4.893337837717034455e-01,1.100000010988609489e+01,8.582725442990435383e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774584523525933832e+01,6.859525773966589668e+02,4.893423664960926955e-01,1.100000010988609489e+01,8.581265588975058207e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774675432615934767e+01,6.859625773929770958e+02,4.893509477606284852e-01,1.100000010988609489e+01,8.579805734959681032e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774766341705935702e+01,6.859725773892964753e+02,4.893595275653108145e-01,1.100000010988609489e+01,8.578345880944303857e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774857250795936636e+01,6.859825773856171054e+02,4.893681059101396280e-01,1.100000010988609489e+01,8.576886026928926682e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.774948159885937571e+01,6.859925773819389860e+02,4.893766827951149812e-01,1.100000010988609489e+01,8.575426172913549507e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775039068975938505e+01,6.860025773782621172e+02,4.893852582202368739e-01,1.100000010988609489e+01,8.573966318898172331e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775129978065939440e+01,6.860125773745864990e+02,4.893938321855052509e-01,1.100000010988609489e+01,8.572506464882795156e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775220887155940375e+01,6.860225773709121313e+02,4.894024046909201675e-01,1.100000010988609489e+01,8.571046610867417981e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775311796245941309e+01,6.860325773672390142e+02,4.894109757364816238e-01,1.100000010988609489e+01,8.569586756852040806e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775402705335942244e+01,6.860425773635671476e+02,4.894195453221895642e-01,1.100000010988609489e+01,8.568126902836663630e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775493614425943179e+01,6.860525773598965316e+02,4.894281134480440443e-01,1.100000010988609489e+01,8.566667048821286455e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775584523515944113e+01,6.860625773562271661e+02,4.894366801140450640e-01,1.100000010988609489e+01,8.565207194805909280e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775675432605945048e+01,6.860725773525590512e+02,4.894452453201925679e-01,1.100000010988609489e+01,8.563747340790532105e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775766341695945982e+01,6.860825773488921868e+02,4.894538090664866115e-01,1.100000010988609489e+01,8.562287486775154929e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775857250785946917e+01,6.860925773452265730e+02,4.894623713529271947e-01,1.100000010988609489e+01,8.560827632759777754e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.775948159875947852e+01,6.861025773415622098e+02,4.894709321795142620e-01,1.100000010988609489e+01,8.559367778744400579e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776039068965948786e+01,6.861125773378990971e+02,4.894794915462478690e-01,1.100000010988609489e+01,8.557907924729023404e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776129978055949721e+01,6.861225773342372349e+02,4.894880494531280157e-01,1.100000010988609489e+01,8.556448070713646228e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776220887145950655e+01,6.861325773305766234e+02,4.894966059001546466e-01,1.100000010988609489e+01,8.554988216698269053e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776311796235951590e+01,6.861425773269172623e+02,4.895051608873278171e-01,1.100000010988609489e+01,8.553528362682891878e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776402705325952525e+01,6.861525773232591519e+02,4.895137144146474717e-01,1.100000010988609489e+01,8.552068508667514703e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776493614415953459e+01,6.861625773196022919e+02,4.895222664821136660e-01,1.100000010988609489e+01,8.550608654652137527e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776584523505954394e+01,6.861725773159466826e+02,4.895308170897264000e-01,1.100000010988609489e+01,8.549148800636760352e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776675432595955328e+01,6.861825773122923238e+02,4.895393662374856181e-01,1.100000010988609489e+01,8.547688946621383177e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776766341685956263e+01,6.861925773086392155e+02,4.895479139253913758e-01,1.100000010988609489e+01,8.546229092606006002e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776857250775957198e+01,6.862025773049873578e+02,4.895564601534436733e-01,1.100000010988609489e+01,8.544769238590628826e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.776948159865958132e+01,6.862125773013367507e+02,4.895650049216424549e-01,1.100000010988609489e+01,8.543309384575251651e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777039068955959067e+01,6.862225772976873941e+02,4.895735482299877761e-01,1.100000010988609489e+01,8.541849530559874476e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777129978045960002e+01,6.862325772940392881e+02,4.895820900784795815e-01,1.100000010988609489e+01,8.540389676544497301e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777220887135960936e+01,6.862425772903923189e+02,4.895906304671179265e-01,1.100000010988609489e+01,8.538929822529120126e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777311796225961871e+01,6.862525772867466003e+02,4.895991693959028113e-01,1.100000010988609489e+01,8.537469968513742950e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777402705315962805e+01,6.862625772831021322e+02,4.896077068648341801e-01,1.100000010988609489e+01,8.536010114498365775e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777493614405963740e+01,6.862725772794589147e+02,4.896162428739120887e-01,1.100000010988609489e+01,8.534550260482988600e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777584523495964675e+01,6.862825772758169478e+02,4.896247774231364813e-01,1.100000010988609489e+01,8.533090406467611425e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777675432585965609e+01,6.862925772721762314e+02,4.896333105125074137e-01,1.100000010988609489e+01,8.531630552452234249e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777766341675966544e+01,6.863025772685367656e+02,4.896418421420248301e-01,1.100000010988609489e+01,8.530170698436857074e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777857250765967478e+01,6.863125772648985503e+02,4.896503723116887863e-01,1.100000010988609489e+01,8.528710844421479899e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.777948159855968413e+01,6.863225772612615856e+02,4.896589010214992821e-01,1.100000010988609489e+01,8.527250990406102724e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778039068945969348e+01,6.863325772576258714e+02,4.896674282714562620e-01,1.100000010988609489e+01,8.525791136390725548e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778129978035970282e+01,6.863425772539914078e+02,4.896759540615597817e-01,1.100000010988609489e+01,8.524331282375348373e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778220887125971217e+01,6.863525772503581948e+02,4.896844783918097854e-01,1.100000010988609489e+01,8.522871428359971198e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778311796215972151e+01,6.863625772467262323e+02,4.896930012622063288e-01,1.100000010988609489e+01,8.521411574344594023e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778402705305973086e+01,6.863725772430955203e+02,4.897015226727493564e-01,1.100000010988609489e+01,8.519951720329216847e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778493614395974021e+01,6.863825772394660589e+02,4.897100426234389237e-01,1.100000010988609489e+01,8.518491866313839672e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778584523485974955e+01,6.863925772358378481e+02,4.897185611142749750e-01,1.100000010988609489e+01,8.517032012298462497e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778675432575975890e+01,6.864025772322108878e+02,4.897270781452575661e-01,1.100000010988609489e+01,8.515572158283085322e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778766341665976825e+01,6.864125772285851781e+02,4.897355937163866968e-01,1.100000010988609489e+01,8.514112304267708146e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778857250755977759e+01,6.864225772249607189e+02,4.897441078276623116e-01,1.100000010988609489e+01,8.512652450252330971e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.778948159845978694e+01,6.864325772213375103e+02,4.897526204790844662e-01,1.100000010988609489e+01,8.511192596236953796e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779039068935979628e+01,6.864425772177154386e+02,4.897611316706531048e-01,1.100000010988609489e+01,8.509732742221576621e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779129978025980563e+01,6.864525772140946174e+02,4.897696414023682832e-01,1.100000010988609489e+01,8.508272888206199445e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779220887115981498e+01,6.864625772104750467e+02,4.897781496742299456e-01,1.100000010988609489e+01,8.506813034190822270e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779311796205982432e+01,6.864725772068567267e+02,4.897866564862381478e-01,1.100000010988609489e+01,8.505353180175445095e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779402705295983367e+01,6.864825772032396571e+02,4.897951618383928341e-01,1.100000010988609489e+01,8.503893326160067920e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779493614385984301e+01,6.864925771996238382e+02,4.898036657306940600e-01,1.100000010988609489e+01,8.502433472144690745e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779584523475985236e+01,6.865025771960092698e+02,4.898121681631417701e-01,1.100000010988609489e+01,8.500973618129313569e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779675432565986171e+01,6.865125771923959519e+02,4.898206691357360199e-01,1.100000010988609489e+01,8.499513764113936394e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779766341655987105e+01,6.865225771887838846e+02,4.898291686484767538e-01,1.100000010988609489e+01,8.498053910098559219e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779857250745988040e+01,6.865325771851730678e+02,4.898376667013640273e-01,1.100000010988609489e+01,8.496594056083182044e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.779948159835988974e+01,6.865425771815635017e+02,4.898461632943977850e-01,1.100000010988609489e+01,8.495134202067804868e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780039068925989909e+01,6.865525771779551860e+02,4.898546584275780824e-01,1.100000010988609489e+01,8.493674348052427693e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780129978015990844e+01,6.865625771743480072e+02,4.898631521009048639e-01,1.100000010988609489e+01,8.492214494037050518e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780220887105991778e+01,6.865725771707420790e+02,4.898716443143781851e-01,1.100000010988609489e+01,8.490754640021673343e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780311796195992713e+01,6.865825771671374014e+02,4.898801350679979905e-01,1.100000010988609489e+01,8.489294786006296167e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780402705285993648e+01,6.865925771635339743e+02,4.898886243617643355e-01,1.100000010988609489e+01,8.487834931990918992e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780493614375994582e+01,6.866025771599317977e+02,4.898971121956771646e-01,1.100000010988609489e+01,8.486375077975541817e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780584523465995517e+01,6.866125771563308717e+02,4.899055985697365334e-01,1.100000010988609489e+01,8.484915223960164642e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780675432555996451e+01,6.866225771527311963e+02,4.899140834839423864e-01,1.100000010988609489e+01,8.483455369944787466e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780766341645997386e+01,6.866325771491327714e+02,4.899225669382947790e-01,1.100000010988609489e+01,8.481995515929410291e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780857250735998321e+01,6.866425771455355971e+02,4.899310489327936557e-01,1.100000010988609489e+01,8.480535661914033116e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.780948159825999255e+01,6.866525771419396733e+02,4.899395294674390167e-01,1.100000010988609489e+01,8.479075807898655941e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781039068916000190e+01,6.866625771383448864e+02,4.899480085422309172e-01,1.100000010988609489e+01,8.477615953883278765e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781129978006001124e+01,6.866725771347513501e+02,4.899564861571693020e-01,1.100000010988609489e+01,8.476156099867901590e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781220887096002059e+01,6.866825771311590643e+02,4.899649623122542264e-01,1.100000010988609489e+01,8.474696245852524415e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781311796186002994e+01,6.866925771275680290e+02,4.899734370074856349e-01,1.100000010988609489e+01,8.473236391837147240e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781402705276003928e+01,6.867025771239782443e+02,4.899819102428635831e-01,1.100000010988609489e+01,8.471776537821770064e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781493614366004863e+01,6.867125771203897102e+02,4.899903820183880154e-01,1.100000010988609489e+01,8.470316683806392889e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781584523456005797e+01,6.867225771168024266e+02,4.899988523340589874e-01,1.100000010988609489e+01,8.468856829791015714e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781675432546006732e+01,6.867325771132163936e+02,4.900073211898764436e-01,1.100000010988609489e+01,8.467396975775638539e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781766341636007667e+01,6.867425771096314975e+02,4.900157885858403839e-01,1.100000010988609489e+01,8.465937121760261364e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781857250726008601e+01,6.867525771060478519e+02,4.900242545219508639e-01,1.100000010988609489e+01,8.464477267744884188e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.781948159816009536e+01,6.867625771024654568e+02,4.900327189982078280e-01,1.100000010988609489e+01,8.463017413729507013e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782039068906010471e+01,6.867725770988843124e+02,4.900411820146113318e-01,1.100000010988609489e+01,8.461557559714129838e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782129977996011405e+01,6.867825770953044184e+02,4.900496435711613197e-01,1.100000010988609489e+01,8.460097705698752663e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782220887086012340e+01,6.867925770917257751e+02,4.900581036678578473e-01,1.100000010988609489e+01,8.458637851683375487e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782311796176013274e+01,6.868025770881483822e+02,4.900665623047008590e-01,1.100000010988609489e+01,8.457177997667998312e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782402705266014209e+01,6.868125770845722400e+02,4.900750194816903549e-01,1.100000010988609489e+01,8.455718143652621137e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782493614356015144e+01,6.868225770809972346e+02,4.900834751988263904e-01,1.100000010988609489e+01,8.454258289637243962e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782584523446016078e+01,6.868325770774234797e+02,4.900919294561089101e-01,1.100000010988609489e+01,8.452798435621866786e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782675432536017013e+01,6.868425770738509755e+02,4.901003822535379695e-01,1.100000010988609489e+01,8.451338581606489611e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782766341626017947e+01,6.868525770702797217e+02,4.901088335911135130e-01,1.100000010988609489e+01,8.449878727591112436e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782857250716018882e+01,6.868625770667097186e+02,4.901172834688355406e-01,1.100000010988609489e+01,8.448418873575735261e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.782948159806019817e+01,6.868725770631409659e+02,4.901257318867041080e-01,1.100000010988609489e+01,8.446959019560358085e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783039068896020751e+01,6.868825770595734639e+02,4.901341788447191594e-01,1.100000010988609489e+01,8.445499165544980910e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783129977986021686e+01,6.868925770560070987e+02,4.901426243428807505e-01,1.100000010988609489e+01,8.444039311529603735e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783220887076022620e+01,6.869025770524419841e+02,4.901510683811888258e-01,1.100000010988609489e+01,8.442579457514226560e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783311796166023555e+01,6.869125770488781200e+02,4.901595109596433852e-01,1.100000010988609489e+01,8.441119603498849384e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783402705256024490e+01,6.869225770453155064e+02,4.901679520782444843e-01,1.100000010988609489e+01,8.439659749483472209e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783493614346025424e+01,6.869325770417541435e+02,4.901763917369920676e-01,1.100000010988609489e+01,8.438199895468095034e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783584523436026359e+01,6.869425770381940310e+02,4.901848299358861349e-01,1.100000010988609489e+01,8.436740041452717859e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783675432526027294e+01,6.869525770346350555e+02,4.901932666749267420e-01,1.100000010988609489e+01,8.435280187437340683e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783766341616028228e+01,6.869625770310773305e+02,4.902017019541138332e-01,1.100000010988609489e+01,8.433820333421963508e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783857250706029163e+01,6.869725770275208561e+02,4.902101357734474085e-01,1.100000010988609489e+01,8.432360479406586333e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.783948159796030097e+01,6.869825770239656322e+02,4.902185681329275235e-01,1.100000010988609489e+01,8.430900625391209158e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784039068886031032e+01,6.869925770204116589e+02,4.902269990325541227e-01,1.100000010988609489e+01,8.429440771375831983e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784129977976031967e+01,6.870025770168589361e+02,4.902354284723272615e-01,1.100000010988609489e+01,8.427980917360454807e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784220887066032901e+01,6.870125770133073502e+02,4.902438564522468845e-01,1.100000010988609489e+01,8.426521063345077632e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784311796156033836e+01,6.870225770097570148e+02,4.902522829723129916e-01,1.100000010988609489e+01,8.425061209329700457e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784402705246034770e+01,6.870325770062079300e+02,4.902607080325256383e-01,1.100000010988609489e+01,8.423601355314323282e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784493614336035705e+01,6.870425770026600958e+02,4.902691316328847693e-01,1.100000010988609489e+01,8.422141501298946106e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784584523426036640e+01,6.870525769991135121e+02,4.902775537733903843e-01,1.100000010988609489e+01,8.420681647283568931e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784675432516037574e+01,6.870625769955680653e+02,4.902859744540425391e-01,1.100000010988609489e+01,8.419221793268191756e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784766341606038509e+01,6.870725769920238690e+02,4.902943936748411780e-01,1.100000010988609489e+01,8.417761939252814581e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784857250696039443e+01,6.870825769884809233e+02,4.903028114357863010e-01,1.100000010988609489e+01,8.416302085237437405e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.784948159786040378e+01,6.870925769849392282e+02,4.903112277368779082e-01,1.100000010988609489e+01,8.414842231222060230e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785039068876041313e+01,6.871025769813987836e+02,4.903196425781160550e-01,1.100000010988609489e+01,8.413382377206683055e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785129977966042247e+01,6.871125769778595895e+02,4.903280559595006860e-01,1.100000010988609489e+01,8.411922523191305880e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785220887056043182e+01,6.871225769743215324e+02,4.903364678810318011e-01,1.100000010988609489e+01,8.410462669175928704e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785311796146044117e+01,6.871325769707847257e+02,4.903448783427094559e-01,1.100000010988609489e+01,8.409002815160551529e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785402705236045051e+01,6.871425769672491697e+02,4.903532873445335949e-01,1.100000010988609489e+01,8.407542961145174354e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785493614326045986e+01,6.871525769637148642e+02,4.903616948865042180e-01,1.100000010988609489e+01,8.406083107129797179e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785584523416046920e+01,6.871625769601818092e+02,4.903701009686213808e-01,1.100000010988609489e+01,8.404623253114420003e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785675432506047855e+01,6.871725769566498911e+02,4.903785055908850277e-01,1.100000010988609489e+01,8.403163399099042828e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785766341596048790e+01,6.871825769531192236e+02,4.903869087532951587e-01,1.100000010988609489e+01,8.401703545083665653e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785857250686049724e+01,6.871925769495898066e+02,4.903953104558517739e-01,1.100000010988609489e+01,8.400243691068288478e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.785948159776050659e+01,6.872025769460616402e+02,4.904037106985549288e-01,1.100000010988609489e+01,8.398783837052911302e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786039068866051593e+01,6.872125769425346107e+02,4.904121094814045678e-01,1.100000010988609489e+01,8.397323983037534127e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786129977956052528e+01,6.872225769390088317e+02,4.904205068044006910e-01,1.100000010988609489e+01,8.395864129022156952e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786220887046053463e+01,6.872325769354843032e+02,4.904289026675433538e-01,1.100000010988609489e+01,8.394404275006779777e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786311796136054397e+01,6.872425769319610254e+02,4.904372970708325008e-01,1.100000010988609489e+01,8.392944420991402601e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786402705226055332e+01,6.872525769284389980e+02,4.904456900142681319e-01,1.100000010988609489e+01,8.391484566976025426e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786493614316056266e+01,6.872625769249181076e+02,4.904540814978502472e-01,1.100000010988609489e+01,8.390024712960648251e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786584523406057201e+01,6.872725769213984677e+02,4.904624715215789021e-01,1.100000010988609489e+01,8.388564858945271076e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786675432496058136e+01,6.872825769178800783e+02,4.904708600854540412e-01,1.100000010988609489e+01,8.387105004929893901e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786766341586059070e+01,6.872925769143629395e+02,4.904792471894756645e-01,1.100000010988609489e+01,8.385645150914516725e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786857250676060005e+01,6.873025769108469376e+02,4.904876328336437719e-01,1.100000010988609489e+01,8.384185296899139550e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.786948159766060940e+01,6.873125769073321862e+02,4.904960170179584189e-01,1.100000010988609489e+01,8.382725442883762375e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787039068856061874e+01,6.873225769038186854e+02,4.905043997424195501e-01,1.100000010988609489e+01,8.381265588868385200e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787129977946062809e+01,6.873325769003064352e+02,4.905127810070271654e-01,1.100000010988609489e+01,8.379805734853008024e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787220887036063743e+01,6.873425768967953218e+02,4.905211608117812649e-01,1.100000010988609489e+01,8.378345880837630849e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787311796126064678e+01,6.873525768932854589e+02,4.905295391566819041e-01,1.100000010988609489e+01,8.376886026822253674e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787402705216065613e+01,6.873625768897768467e+02,4.905379160417290274e-01,1.100000010988609489e+01,8.375426172806876499e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787493614306066547e+01,6.873725768862694849e+02,4.905462914669226349e-01,1.100000010988609489e+01,8.373966318791499323e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787584523396067482e+01,6.873825768827633738e+02,4.905546654322627265e-01,1.100000010988609489e+01,8.372506464776122148e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787675432486068416e+01,6.873925768792583995e+02,4.905630379377493577e-01,1.100000010988609489e+01,8.371046610760744973e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787766341576069351e+01,6.874025768757546757e+02,4.905714089833824731e-01,1.100000010988609489e+01,8.369586756745367798e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787857250666070286e+01,6.874125768722522025e+02,4.905797785691620727e-01,1.100000010988609489e+01,8.368126902729990622e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.787948159756071220e+01,6.874225768687509799e+02,4.905881466950881564e-01,1.100000010988609489e+01,8.366667048714613447e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788039068846072155e+01,6.874325768652508941e+02,4.905965133611607243e-01,1.100000010988609489e+01,8.365207194699236272e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788129977936073089e+01,6.874425768617520589e+02,4.906048785673798318e-01,1.100000010988609489e+01,8.363747340683859097e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788220887026074024e+01,6.874525768582544742e+02,4.906132423137454235e-01,1.100000010988609489e+01,8.362287486668481921e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788311796116074959e+01,6.874625768547580265e+02,4.906216046002574993e-01,1.100000010988609489e+01,8.360827632653104746e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788402705206075893e+01,6.874725768512628292e+02,4.906299654269160593e-01,1.100000010988609489e+01,8.359367778637727571e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788493614296076828e+01,6.874825768477688825e+02,4.906383247937211034e-01,1.100000010988609489e+01,8.357907924622350396e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788584523386077763e+01,6.874925768442761864e+02,4.906466827006726872e-01,1.100000010988609489e+01,8.356448070606973220e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788675432476078697e+01,6.875025768407846272e+02,4.906550391477707551e-01,1.100000010988609489e+01,8.354988216591596045e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788766341566079632e+01,6.875125768372943185e+02,4.906633941350153072e-01,1.100000010988609489e+01,8.353528362576218870e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788857250656080566e+01,6.875225768338052603e+02,4.906717476624063434e-01,1.100000010988609489e+01,8.352068508560841695e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.788948159746081501e+01,6.875325768303174527e+02,4.906800997299438638e-01,1.100000010988609489e+01,8.350608654545464520e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789039068836082436e+01,6.875425768268307820e+02,4.906884503376278683e-01,1.100000010988609489e+01,8.349148800530087344e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789129977926083370e+01,6.875525768233453618e+02,4.906967994854584125e-01,1.100000010988609489e+01,8.347688946514710169e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789220887016084305e+01,6.875625768198611922e+02,4.907051471734354409e-01,1.100000010988609489e+01,8.346229092499332994e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789311796106085239e+01,6.875725768163781595e+02,4.907134934015589534e-01,1.100000010988609489e+01,8.344769238483955819e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789402705196086174e+01,6.875825768128963773e+02,4.907218381698289500e-01,1.100000010988609489e+01,8.343309384468578643e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789493614286087109e+01,6.875925768094158457e+02,4.907301814782454308e-01,1.100000010988609489e+01,8.341849530453201468e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789584523376088043e+01,6.876025768059365646e+02,4.907385233268083957e-01,1.100000010988609489e+01,8.340389676437824293e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789675432466088978e+01,6.876125768024584204e+02,4.907468637155179003e-01,1.100000010988609489e+01,8.338929822422447118e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789766341556089913e+01,6.876225767989815267e+02,4.907552026443738891e-01,1.100000010988609489e+01,8.337469968407069942e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789857250646090847e+01,6.876325767955058836e+02,4.907635401133763620e-01,1.100000010988609489e+01,8.336010114391692767e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.789948159736091782e+01,6.876425767920313774e+02,4.907718761225253190e-01,1.100000010988609489e+01,8.334550260376315592e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790039068826092716e+01,6.876525767885581217e+02,4.907802106718207602e-01,1.100000010988609489e+01,8.333090406360938417e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790129977916093651e+01,6.876625767850861166e+02,4.907885437612626855e-01,1.100000010988609489e+01,8.331630552345561241e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790220887006094586e+01,6.876725767816153621e+02,4.907968753908510950e-01,1.100000010988609489e+01,8.330170698330184066e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790311796096095520e+01,6.876825767781457444e+02,4.908052055605860442e-01,1.100000010988609489e+01,8.328710844314806891e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790402705186096455e+01,6.876925767746773772e+02,4.908135342704674775e-01,1.100000010988609489e+01,8.327250990299429716e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790493614276097389e+01,6.877025767712102606e+02,4.908218615204953950e-01,1.100000010988609489e+01,8.325791136284052540e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790584523366098324e+01,6.877125767677442809e+02,4.908301873106697966e-01,1.100000010988609489e+01,8.324331282268675365e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790675432456099259e+01,6.877225767642795518e+02,4.908385116409906823e-01,1.100000010988609489e+01,8.322871428253298190e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790766341546100193e+01,6.877325767608160731e+02,4.908468345114580522e-01,1.100000010988609489e+01,8.321411574237921015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790857250636101128e+01,6.877425767573537314e+02,4.908551559220719063e-01,1.100000010988609489e+01,8.319951720222543839e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.790948159726102062e+01,6.877525767538926402e+02,4.908634758728322445e-01,1.100000010988609489e+01,8.318491866207166664e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791039068816102997e+01,6.877625767504327996e+02,4.908717943637390668e-01,1.100000010988609489e+01,8.317032012191789489e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791129977906103932e+01,6.877725767469740958e+02,4.908801113947924288e-01,1.100000010988609489e+01,8.315572158176412314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791220886996104866e+01,6.877825767435166426e+02,4.908884269659922750e-01,1.100000010988609489e+01,8.314112304161035139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791311796086105801e+01,6.877925767400604400e+02,4.908967410773386053e-01,1.100000010988609489e+01,8.312652450145657963e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791402705176106736e+01,6.878025767366053742e+02,4.909050537288314198e-01,1.100000010988609489e+01,8.311192596130280788e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791493614266107670e+01,6.878125767331515590e+02,4.909133649204707184e-01,1.100000010988609489e+01,8.309732742114903613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791584523356108605e+01,6.878225767296989943e+02,4.909216746522565011e-01,1.100000010988609489e+01,8.308272888099526438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791675432446109539e+01,6.878325767262476802e+02,4.909299829241887680e-01,1.100000010988609489e+01,8.306813034084149262e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791766341536110474e+01,6.878425767227975030e+02,4.909382897362675191e-01,1.100000010988609489e+01,8.305353180068772087e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791857250626111409e+01,6.878525767193485763e+02,4.909465950884927543e-01,1.100000010988609489e+01,8.303893326053394912e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.791948159716112343e+01,6.878625767159009001e+02,4.909548989808644737e-01,1.100000010988609489e+01,8.302433472038017737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792039068806113278e+01,6.878725767124543609e+02,4.909632014133826772e-01,1.100000010988609489e+01,8.300973618022640561e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792129977896114212e+01,6.878825767090090721e+02,4.909715023860473648e-01,1.100000010988609489e+01,8.299513764007263386e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792220886986115147e+01,6.878925767055649203e+02,4.909798018988585366e-01,1.100000010988609489e+01,8.298053909991886211e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792311796076116082e+01,6.879025767021220190e+02,4.909880999518162481e-01,1.100000010988609489e+01,8.296594055976509036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792402705166117016e+01,6.879125766986803683e+02,4.909963965449204437e-01,1.100000010988609489e+01,8.295134201961131860e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792493614256117951e+01,6.879225766952398544e+02,4.910046916781711235e-01,1.100000010988609489e+01,8.293674347945754685e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792584523346118885e+01,6.879325766918005911e+02,4.910129853515682874e-01,1.100000010988609489e+01,8.292214493930377510e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792675432436119820e+01,6.879425766883625784e+02,4.910212775651119355e-01,1.100000010988609489e+01,8.290754639915000335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792766341526120755e+01,6.879525766849257025e+02,4.910295683188020677e-01,1.100000010988609489e+01,8.289294785899623159e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792857250616121689e+01,6.879625766814900771e+02,4.910378576126386840e-01,1.100000010988609489e+01,8.287834931884245984e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.792948159706122624e+01,6.879725766780557024e+02,4.910461454466217845e-01,1.100000010988609489e+01,8.286375077868868809e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793039068796123559e+01,6.879825766746224645e+02,4.910544318207513692e-01,1.100000010988609489e+01,8.284915223853491634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793129977886124493e+01,6.879925766711904771e+02,4.910627167350274380e-01,1.100000010988609489e+01,8.283455369838114458e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793220886976125428e+01,6.880025766677597403e+02,4.910710001894499910e-01,1.100000010988609489e+01,8.281995515822737283e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793311796066126362e+01,6.880125766643301404e+02,4.910792821840190281e-01,1.100000010988609489e+01,8.280535661807360108e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793402705156127297e+01,6.880225766609017910e+02,4.910875627187345493e-01,1.100000010988609489e+01,8.279075807791982933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793493614246128232e+01,6.880325766574746922e+02,4.910958417935965548e-01,1.100000010988609489e+01,8.277615953776605758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793584523336129166e+01,6.880425766540487302e+02,4.911041194086050443e-01,1.100000010988609489e+01,8.276156099761228582e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793675432426130101e+01,6.880525766506240188e+02,4.911123955637600180e-01,1.100000010988609489e+01,8.274696245745851407e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793766341516131035e+01,6.880625766472004443e+02,4.911206702590614759e-01,1.100000010988609489e+01,8.273236391730474232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793857250606131970e+01,6.880725766437781203e+02,4.911289434945094179e-01,1.100000010988609489e+01,8.271776537715097057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.793948159696132905e+01,6.880825766403570469e+02,4.911372152701038440e-01,1.100000010988609489e+01,8.270316683699719881e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794039068786133839e+01,6.880925766369371104e+02,4.911454855858447544e-01,1.100000010988609489e+01,8.268856829684342706e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794129977876134774e+01,6.881025766335184244e+02,4.911537544417321488e-01,1.100000010988609489e+01,8.267396975668965531e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794220886966135708e+01,6.881125766301008753e+02,4.911620218377660274e-01,1.100000010988609489e+01,8.265937121653588356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794311796056136643e+01,6.881225766266845767e+02,4.911702877739463902e-01,1.100000010988609489e+01,8.264477267638211180e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794402705146137578e+01,6.881325766232695287e+02,4.911785522502732371e-01,1.100000010988609489e+01,8.263017413622834005e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794493614236138512e+01,6.881425766198556175e+02,4.911868152667465681e-01,1.100000010988609489e+01,8.261557559607456830e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794584523326139447e+01,6.881525766164429569e+02,4.911950768233663833e-01,1.100000010988609489e+01,8.260097705592079655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794675432416140382e+01,6.881625766130315469e+02,4.912033369201326827e-01,1.100000010988609489e+01,8.258637851576702479e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794766341506141316e+01,6.881725766096212737e+02,4.912115955570454662e-01,1.100000010988609489e+01,8.257177997561325304e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794857250596142251e+01,6.881825766062122511e+02,4.912198527341047338e-01,1.100000010988609489e+01,8.255718143545948129e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.794948159686143185e+01,6.881925766028043654e+02,4.912281084513104856e-01,1.100000010988609489e+01,8.254258289530570954e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795039068776144120e+01,6.882025765993977302e+02,4.912363627086627216e-01,1.100000010988609489e+01,8.252798435515193778e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795129977866145055e+01,6.882125765959923456e+02,4.912446155061614417e-01,1.100000010988609489e+01,8.251338581499816603e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795220886956145989e+01,6.882225765925880978e+02,4.912528668438066459e-01,1.100000010988609489e+01,8.249878727484439428e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795311796046146924e+01,6.882325765891851006e+02,4.912611167215983343e-01,1.100000010988609489e+01,8.248418873469062253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795402705136147858e+01,6.882425765857832403e+02,4.912693651395365069e-01,1.100000010988609489e+01,8.246959019453685077e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795493614226148793e+01,6.882525765823826305e+02,4.912776120976211081e-01,1.100000010988609489e+01,8.245499165438307902e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795584523316149728e+01,6.882625765789832712e+02,4.912858575958521934e-01,1.100000010988609489e+01,8.244039311422930727e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795675432406150662e+01,6.882725765755850489e+02,4.912941016342297629e-01,1.100000010988609489e+01,8.242579457407553552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795766341496151597e+01,6.882825765721880771e+02,4.913023442127538165e-01,1.100000010988609489e+01,8.241119603392176376e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795857250586152531e+01,6.882925765687922421e+02,4.913105853314243543e-01,1.100000010988609489e+01,8.239659749376799201e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.795948159676153466e+01,6.883025765653976578e+02,4.913188249902413762e-01,1.100000010988609489e+01,8.238199895361422026e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796039068766154401e+01,6.883125765620042102e+02,4.913270631892048823e-01,1.100000010988609489e+01,8.236740041346044851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796129977856155335e+01,6.883225765586120133e+02,4.913352999283148725e-01,1.100000010988609489e+01,8.235280187330667676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796220886946156270e+01,6.883325765552210669e+02,4.913435352075713469e-01,1.100000010988609489e+01,8.233820333315290500e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796311796036157205e+01,6.883425765518312573e+02,4.913517690269743055e-01,1.100000010988609489e+01,8.232360479299913325e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796402705126158139e+01,6.883525765484426984e+02,4.913600013865237481e-01,1.100000010988609489e+01,8.230900625284536150e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796493614216159074e+01,6.883625765450552763e+02,4.913682322862196750e-01,1.100000010988609489e+01,8.229440771269158975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796584523306160008e+01,6.883725765416691047e+02,4.913764617260620859e-01,1.100000010988609489e+01,8.227980917253781799e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796675432396160943e+01,6.883825765382840700e+02,4.913846897060509811e-01,1.100000010988609489e+01,8.226521063238404624e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796766341486161878e+01,6.883925765349002859e+02,4.913929162261863048e-01,1.100000010988609489e+01,8.225061209223027449e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796857250576162812e+01,6.884025765315177523e+02,4.914011412864681128e-01,1.100000010988609489e+01,8.223601355207650274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.796948159666163747e+01,6.884125765281363556e+02,4.914093648868964048e-01,1.100000010988609489e+01,8.222141501192273098e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797039068756164681e+01,6.884225765247562094e+02,4.914175870274711810e-01,1.100000010988609489e+01,8.220681647176895923e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797129977846165616e+01,6.884325765213772002e+02,4.914258077081924414e-01,1.100000010988609489e+01,8.219221793161518748e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797220886936166551e+01,6.884425765179994414e+02,4.914340269290601859e-01,1.100000010988609489e+01,8.217761939146141573e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797311796026167485e+01,6.884525765146228196e+02,4.914422446900744146e-01,1.100000010988609489e+01,8.216302085130764397e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797402705116168420e+01,6.884625765112474483e+02,4.914504609912351274e-01,1.100000010988609489e+01,8.214842231115387222e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797493614206169354e+01,6.884725765078732138e+02,4.914586758325423244e-01,1.100000010988609489e+01,8.213382377100010047e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797584523296170289e+01,6.884825765045002299e+02,4.914668892139959500e-01,1.100000010988609489e+01,8.211922523084632872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797675432386171224e+01,6.884925765011284966e+02,4.914751011355960597e-01,1.100000010988609489e+01,8.210462669069255696e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797766341476172158e+01,6.885025764977579001e+02,4.914833115973426536e-01,1.100000010988609489e+01,8.209002815053878521e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797857250566173093e+01,6.885125764943885542e+02,4.914915205992357317e-01,1.100000010988609489e+01,8.207542961038501346e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.797948159656174028e+01,6.885225764910203452e+02,4.914997281412752939e-01,1.100000010988609489e+01,8.206083107023124171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798039068746174962e+01,6.885325764876533867e+02,4.915079342234613402e-01,1.100000010988609489e+01,8.204623253007746995e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798129977836175897e+01,6.885425764842875651e+02,4.915161388457938707e-01,1.100000010988609489e+01,8.203163398992369820e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798220886926176831e+01,6.885525764809229941e+02,4.915243420082728298e-01,1.100000010988609489e+01,8.201703544976992645e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798311796016177766e+01,6.885625764775595599e+02,4.915325437108982731e-01,1.100000010988609489e+01,8.200243690961615470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798402705106178701e+01,6.885725764741973762e+02,4.915407439536702006e-01,1.100000010988609489e+01,8.198783836946238295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798493614196179635e+01,6.885825764708363295e+02,4.915489427365886121e-01,1.100000010988609489e+01,8.197323982930861119e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798584523286180570e+01,6.885925764674765333e+02,4.915571400596535079e-01,1.100000010988609489e+01,8.195864128915483944e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798675432376181504e+01,6.886025764641178739e+02,4.915653359228648878e-01,1.100000010988609489e+01,8.194404274900106769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798766341466182439e+01,6.886125764607604651e+02,4.915735303262226963e-01,1.100000010988609489e+01,8.192944420884729594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798857250556183374e+01,6.886225764574041932e+02,4.915817232697269890e-01,1.100000010988609489e+01,8.191484566869352418e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.798948159646184308e+01,6.886325764540491718e+02,4.915899147533777658e-01,1.100000010988609489e+01,8.190024712853975243e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799039068736185243e+01,6.886425764506954010e+02,4.915981047771750267e-01,1.100000010988609489e+01,8.188564858838598068e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799129977826186177e+01,6.886525764473427671e+02,4.916062933411187719e-01,1.100000010988609489e+01,8.187105004823220893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799220886916187112e+01,6.886625764439913837e+02,4.916144804452090011e-01,1.100000010988609489e+01,8.185645150807843717e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799311796006188047e+01,6.886725764406411372e+02,4.916226660894456590e-01,1.100000010988609489e+01,8.184185296792466542e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799402705096188981e+01,6.886825764372921412e+02,4.916308502738288011e-01,1.100000010988609489e+01,8.182725442777089367e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799493614186189916e+01,6.886925764339442821e+02,4.916390329983584273e-01,1.100000010988609489e+01,8.181265588761712192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799584523276190851e+01,6.887025764305976736e+02,4.916472142630345377e-01,1.100000010988609489e+01,8.179805734746335016e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799675432366191785e+01,6.887125764272522019e+02,4.916553940678571322e-01,1.100000010988609489e+01,8.178345880730957841e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799766341456192720e+01,6.887225764239079808e+02,4.916635724128261553e-01,1.100000010988609489e+01,8.176886026715580666e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799857250546193654e+01,6.887325764205648966e+02,4.916717492979416626e-01,1.100000010988609489e+01,8.175426172700203491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.799948159636194589e+01,6.887425764172230629e+02,4.916799247232036540e-01,1.100000010988609489e+01,8.173966318684826315e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800039068726195524e+01,6.887525764138823661e+02,4.916880986886121296e-01,1.100000010988609489e+01,8.172506464669449140e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800129977816196458e+01,6.887625764105429198e+02,4.916962711941670894e-01,1.100000010988609489e+01,8.171046610654071965e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800220886906197393e+01,6.887725764072046104e+02,4.917044422398684778e-01,1.100000010988609489e+01,8.169586756638694790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800311795996198327e+01,6.887825764038675516e+02,4.917126118257163503e-01,1.100000010988609489e+01,8.168126902623317614e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800402705086199262e+01,6.887925764005316296e+02,4.917207799517107070e-01,1.100000010988609489e+01,8.166667048607940439e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800493614176200197e+01,6.888025763971969582e+02,4.917289466178515478e-01,1.100000010988609489e+01,8.165207194592563264e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800584523266201131e+01,6.888125763938634236e+02,4.917371118241388173e-01,1.100000010988609489e+01,8.163747340577186089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800675432356202066e+01,6.888225763905311396e+02,4.917452755705725709e-01,1.100000010988609489e+01,8.162287486561808914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800766341446203000e+01,6.888325763871999925e+02,4.917534378571528086e-01,1.100000010988609489e+01,8.160827632546431738e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800857250536203935e+01,6.888425763838699822e+02,4.917615986838795306e-01,1.100000010988609489e+01,8.159367778531054563e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.800948159626204870e+01,6.888525763805412225e+02,4.917697580507526811e-01,1.100000010988609489e+01,8.157907924515677388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801039068716205804e+01,6.888625763772135997e+02,4.917779159577723158e-01,1.100000010988609489e+01,8.156448070500300213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801129977806206739e+01,6.888725763738872274e+02,4.917860724049384347e-01,1.100000010988609489e+01,8.154988216484923037e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801220886896207674e+01,6.888825763705619920e+02,4.917942273922510377e-01,1.100000010988609489e+01,8.153528362469545862e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801311795986208608e+01,6.888925763672380072e+02,4.918023809197100693e-01,1.100000010988609489e+01,8.152068508454168687e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801402705076209543e+01,6.889025763639151592e+02,4.918105329873155851e-01,1.100000010988609489e+01,8.150608654438791512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801493614166210477e+01,6.889125763605935617e+02,4.918186835950675850e-01,1.100000010988609489e+01,8.149148800423414336e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801584523256211412e+01,6.889225763572731012e+02,4.918268327429660691e-01,1.100000010988609489e+01,8.147688946408037161e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801675432346212347e+01,6.889325763539538912e+02,4.918349804310109818e-01,1.100000010988609489e+01,8.146229092392659986e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801766341436213281e+01,6.889425763506358180e+02,4.918431266592023787e-01,1.100000010988609489e+01,8.144769238377282811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801857250526214216e+01,6.889525763473189954e+02,4.918512714275402598e-01,1.100000010988609489e+01,8.143309384361905635e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.801948159616215150e+01,6.889625763440033097e+02,4.918594147360246249e-01,1.100000010988609489e+01,8.141849530346528460e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802039068706216085e+01,6.889725763406888746e+02,4.918675565846554187e-01,1.100000010988609489e+01,8.140389676331151285e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802129977796217020e+01,6.889825763373755763e+02,4.918756969734326967e-01,1.100000010988609489e+01,8.138929822315774110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802220886886217954e+01,6.889925763340634148e+02,4.918838359023564588e-01,1.100000010988609489e+01,8.137469968300396934e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802311795976218889e+01,6.890025763307525040e+02,4.918919733714266496e-01,1.100000010988609489e+01,8.136010114285019759e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802402705066219823e+01,6.890125763274427300e+02,4.919001093806433245e-01,1.100000010988609489e+01,8.134550260269642584e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802493614156220758e+01,6.890225763241342065e+02,4.919082439300064835e-01,1.100000010988609489e+01,8.133090406254265409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802584523246221693e+01,6.890325763208268199e+02,4.919163770195161267e-01,1.100000010988609489e+01,8.131630552238888233e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802675432336222627e+01,6.890425763175206839e+02,4.919245086491721985e-01,1.100000010988609489e+01,8.130170698223511058e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802766341426223562e+01,6.890525763142156848e+02,4.919326388189747545e-01,1.100000010988609489e+01,8.128710844208133883e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802857250516224497e+01,6.890625763109119362e+02,4.919407675289237947e-01,1.100000010988609489e+01,8.127250990192756708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.802948159606225431e+01,6.890725763076093244e+02,4.919488947790192634e-01,1.100000010988609489e+01,8.125791136177379533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803039068696226366e+01,6.890825763043078496e+02,4.919570205692612164e-01,1.100000010988609489e+01,8.124331282162002357e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803129977786227300e+01,6.890925763010076253e+02,4.919651448996496534e-01,1.100000010988609489e+01,8.122871428146625182e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803220886876228235e+01,6.891025762977085378e+02,4.919732677701845192e-01,1.100000010988609489e+01,8.121411574131248007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803311795966229170e+01,6.891125762944107009e+02,4.919813891808658690e-01,1.100000010988609489e+01,8.119951720115870832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803402705056230104e+01,6.891225762911140009e+02,4.919895091316937030e-01,1.100000010988609489e+01,8.118491866100493656e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803493614146231039e+01,6.891325762878185515e+02,4.919976276226679657e-01,1.100000010988609489e+01,8.117032012085116481e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803584523236231973e+01,6.891425762845242389e+02,4.920057446537887125e-01,1.100000010988609489e+01,8.115572158069739306e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803675432326232908e+01,6.891525762812310631e+02,4.920138602250559434e-01,1.100000010988609489e+01,8.114112304054362131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803766341416233843e+01,6.891625762779391380e+02,4.920219743364696030e-01,1.100000010988609489e+01,8.112652450038984955e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803857250506234777e+01,6.891725762746483497e+02,4.920300869880297467e-01,1.100000010988609489e+01,8.111192596023607780e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.803948159596235712e+01,6.891825762713588119e+02,4.920381981797363746e-01,1.100000010988609489e+01,8.109732742008230605e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804039068686236646e+01,6.891925762680704111e+02,4.920463079115894311e-01,1.100000010988609489e+01,8.108272887992853430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804129977776237581e+01,6.892025762647832607e+02,4.920544161835889718e-01,1.100000010988609489e+01,8.106813033977476254e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804220886866238516e+01,6.892125762614972473e+02,4.920625229957349966e-01,1.100000010988609489e+01,8.105353179962099079e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804311795956239450e+01,6.892225762582123707e+02,4.920706283480274501e-01,1.100000010988609489e+01,8.103893325946721904e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804402705046240385e+01,6.892325762549287447e+02,4.920787322404663877e-01,1.100000010988609489e+01,8.102433471931344729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804493614136241320e+01,6.892425762516462555e+02,4.920868346730518095e-01,1.100000010988609489e+01,8.100973617915967553e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804584523226242254e+01,6.892525762483650169e+02,4.920949356457836599e-01,1.100000010988609489e+01,8.099513763900590378e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804675432316243189e+01,6.892625762450849152e+02,4.921030351586619944e-01,1.100000010988609489e+01,8.098053909885213203e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804766341406244123e+01,6.892725762418059503e+02,4.921111332116867576e-01,1.100000010988609489e+01,8.096594055869836028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804857250496245058e+01,6.892825762385282360e+02,4.921192298048580049e-01,1.100000010988609489e+01,8.095134201854458852e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.804948159586245993e+01,6.892925762352516585e+02,4.921273249381757364e-01,1.100000010988609489e+01,8.093674347839081677e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805039068676246927e+01,6.893025762319763317e+02,4.921354186116398965e-01,1.100000010988609489e+01,8.092214493823704502e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805129977766247862e+01,6.893125762287021416e+02,4.921435108252505408e-01,1.100000010988609489e+01,8.090754639808327327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805220886856248796e+01,6.893225762254290885e+02,4.921516015790076692e-01,1.100000010988609489e+01,8.089294785792950152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805311795946249731e+01,6.893325762221572859e+02,4.921596908729112263e-01,1.100000010988609489e+01,8.087834931777572976e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805402705036250666e+01,6.893425762188866202e+02,4.921677787069612675e-01,1.100000010988609489e+01,8.086375077762195801e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805493614126251600e+01,6.893525762156170913e+02,4.921758650811577374e-01,1.100000010988609489e+01,8.084915223746818626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805584523216252535e+01,6.893625762123488130e+02,4.921839499955006914e-01,1.100000010988609489e+01,8.083455369731441451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805675432306253470e+01,6.893725762090816715e+02,4.921920334499901295e-01,1.100000010988609489e+01,8.081995515716064275e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805766341396254404e+01,6.893825762058157807e+02,4.922001154446259963e-01,1.100000010988609489e+01,8.080535661700687100e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805857250486255339e+01,6.893925762025510267e+02,4.922081959794083472e-01,1.100000010988609489e+01,8.079075807685309925e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.805948159576256273e+01,6.894025761992874095e+02,4.922162750543371268e-01,1.100000010988609489e+01,8.077615953669932750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806039068666257208e+01,6.894125761960250429e+02,4.922243526694123905e-01,1.100000010988609489e+01,8.076156099654555574e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806129977756258143e+01,6.894225761927638132e+02,4.922324288246340829e-01,1.100000010988609489e+01,8.074696245639178399e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806220886846259077e+01,6.894325761895038340e+02,4.922405035200022594e-01,1.100000010988609489e+01,8.073236391623801224e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806311795936260012e+01,6.894425761862449917e+02,4.922485767555169200e-01,1.100000010988609489e+01,8.071776537608424049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806402705026260946e+01,6.894525761829872863e+02,4.922566485311780093e-01,1.100000010988609489e+01,8.070316683593046873e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806493614116261881e+01,6.894625761797308314e+02,4.922647188469855828e-01,1.100000010988609489e+01,8.068856829577669698e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806584523206262816e+01,6.894725761764755134e+02,4.922727877029395849e-01,1.100000010988609489e+01,8.067396975562292523e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806675432296263750e+01,6.894825761732213323e+02,4.922808550990400711e-01,1.100000010988609489e+01,8.065937121546915348e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806766341386264685e+01,6.894925761699684017e+02,4.922889210352869860e-01,1.100000010988609489e+01,8.064477267531538172e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806857250476265619e+01,6.895025761667166080e+02,4.922969855116803850e-01,1.100000010988609489e+01,8.063017413516160997e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.806948159566266554e+01,6.895125761634659511e+02,4.923050485282202682e-01,1.100000010988609489e+01,8.061557559500783822e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807039068656267489e+01,6.895225761602165448e+02,4.923131100849065800e-01,1.100000010988609489e+01,8.060097705485406647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807129977746268423e+01,6.895325761569682754e+02,4.923211701817393759e-01,1.100000010988609489e+01,8.058637851470029471e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807220886836269358e+01,6.895425761537211429e+02,4.923292288187186005e-01,1.100000010988609489e+01,8.057177997454652296e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807311795926270293e+01,6.895525761504752609e+02,4.923372859958443093e-01,1.100000010988609489e+01,8.055718143439275121e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807402705016271227e+01,6.895625761472305157e+02,4.923453417131164467e-01,1.100000010988609489e+01,8.054258289423897946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807493614106272162e+01,6.895725761439869075e+02,4.923533959705350682e-01,1.100000010988609489e+01,8.052798435408520770e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807584523196273096e+01,6.895825761407445498e+02,4.923614487681001184e-01,1.100000010988609489e+01,8.051338581393143595e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807675432286274031e+01,6.895925761375033289e+02,4.923695001058116527e-01,1.100000010988609489e+01,8.049878727377766420e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807766341376274966e+01,6.896025761342632450e+02,4.923775499836696157e-01,1.100000010988609489e+01,8.048418873362389245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807857250466275900e+01,6.896125761310244116e+02,4.923855984016740628e-01,1.100000010988609489e+01,8.046959019347012070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.807948159556276835e+01,6.896225761277867150e+02,4.923936453598249385e-01,1.100000010988609489e+01,8.045499165331634894e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808039068646277769e+01,6.896325761245502690e+02,4.924016908581222984e-01,1.100000010988609489e+01,8.044039311316257719e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808129977736278704e+01,6.896425761213149599e+02,4.924097348965660870e-01,1.100000010988609489e+01,8.042579457300880544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808220886826279639e+01,6.896525761180807876e+02,4.924177774751563597e-01,1.100000010988609489e+01,8.041119603285503369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808311795916280573e+01,6.896625761148477523e+02,4.924258185938930610e-01,1.100000010988609489e+01,8.039659749270126193e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808402705006281508e+01,6.896725761116159674e+02,4.924338582527762465e-01,1.100000010988609489e+01,8.038199895254749018e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808493614096282442e+01,6.896825761083853195e+02,4.924418964518058606e-01,1.100000010988609489e+01,8.036740041239371843e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808584523186283377e+01,6.896925761051558084e+02,4.924499331909819588e-01,1.100000010988609489e+01,8.035280187223994668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808675432276284312e+01,6.897025761019275478e+02,4.924579684703044857e-01,1.100000010988609489e+01,8.033820333208617492e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808766341366285246e+01,6.897125760987004242e+02,4.924660022897734968e-01,1.100000010988609489e+01,8.032360479193240317e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808857250456286181e+01,6.897225760954744374e+02,4.924740346493889365e-01,1.100000010988609489e+01,8.030900625177863142e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.808948159546287116e+01,6.897325760922497011e+02,4.924820655491508603e-01,1.100000010988609489e+01,8.029440771162485967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809039068636288050e+01,6.897425760890261017e+02,4.924900949890592128e-01,1.100000010988609489e+01,8.027980917147108791e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809129977726288985e+01,6.897525760858036392e+02,4.924981229691140494e-01,1.100000010988609489e+01,8.026521063131731616e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809220886816289919e+01,6.897625760825824273e+02,4.925061494893153147e-01,1.100000010988609489e+01,8.025061209116354441e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809311795906290854e+01,6.897725760793623522e+02,4.925141745496630641e-01,1.100000010988609489e+01,8.023601355100977266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809402704996291789e+01,6.897825760761434140e+02,4.925221981501572421e-01,1.100000010988609489e+01,8.022141501085600090e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809493614086292723e+01,6.897925760729257263e+02,4.925302202907979043e-01,1.100000010988609489e+01,8.020681647070222915e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809584523176293658e+01,6.898025760697091755e+02,4.925382409715849952e-01,1.100000010988609489e+01,8.019221793054845740e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809675432266294592e+01,6.898125760664937616e+02,4.925462601925185702e-01,1.100000010988609489e+01,8.017761939039468565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809766341356295527e+01,6.898225760632794845e+02,4.925542779535985738e-01,1.100000010988609489e+01,8.016302085024091389e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809857250446296462e+01,6.898325760600664580e+02,4.925622942548250616e-01,1.100000010988609489e+01,8.014842231008714214e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.809948159536297396e+01,6.898425760568545684e+02,4.925703090961979780e-01,1.100000010988609489e+01,8.013382376993337039e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810039068626298331e+01,6.898525760536438156e+02,4.925783224777173230e-01,1.100000010988609489e+01,8.011922522977959864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810129977716299265e+01,6.898625760504343134e+02,4.925863343993831522e-01,1.100000010988609489e+01,8.010462668962582689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810220886806300200e+01,6.898725760472259481e+02,4.925943448611954101e-01,1.100000010988609489e+01,8.009002814947205513e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810311795896301135e+01,6.898825760440187196e+02,4.926023538631541521e-01,1.100000010988609489e+01,8.007542960931828338e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810402704986302069e+01,6.898925760408126280e+02,4.926103614052593227e-01,1.100000010988609489e+01,8.006083106916451163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810493614076303004e+01,6.899025760376077869e+02,4.926183674875109775e-01,1.100000010988609489e+01,8.004623252901073988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810584523166303939e+01,6.899125760344040827e+02,4.926263721099090609e-01,1.100000010988609489e+01,8.003163398885696812e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810675432256304873e+01,6.899225760312015154e+02,4.926343752724535729e-01,1.100000010988609489e+01,8.001703544870319637e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810766341346305808e+01,6.899325760280001987e+02,4.926423769751445692e-01,1.100000010988609489e+01,8.000243690854942462e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810857250436306742e+01,6.899425760248000188e+02,4.926503772179819940e-01,1.100000010988609489e+01,7.998783836839565287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.810948159526307677e+01,6.899525760216009758e+02,4.926583760009659030e-01,1.100000010988609489e+01,7.997323982824188111e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811039068616308612e+01,6.899625760184030696e+02,4.926663733240962406e-01,1.100000010988609489e+01,7.995864128808810936e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811129977706309546e+01,6.899725760152064140e+02,4.926743691873730624e-01,1.100000010988609489e+01,7.994404274793433761e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811220886796310481e+01,6.899825760120108953e+02,4.926823635907963128e-01,1.100000010988609489e+01,7.992944420778056586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811311795886311415e+01,6.899925760088165134e+02,4.926903565343659919e-01,1.100000010988609489e+01,7.991484566762679410e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811402704976312350e+01,6.900025760056232684e+02,4.926983480180821551e-01,1.100000010988609489e+01,7.990024712747302235e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811493614066313285e+01,6.900125760024312740e+02,4.927063380419447469e-01,1.100000010988609489e+01,7.988564858731925060e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811584523156314219e+01,6.900225759992404164e+02,4.927143266059538229e-01,1.100000010988609489e+01,7.987105004716547885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811675432246315154e+01,6.900325759960506957e+02,4.927223137101093275e-01,1.100000010988609489e+01,7.985645150701170709e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811766341336316088e+01,6.900425759928622256e+02,4.927302993544112608e-01,1.100000010988609489e+01,7.984185296685793534e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811857250426317023e+01,6.900525759896748923e+02,4.927382835388596782e-01,1.100000010988609489e+01,7.982725442670416359e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.811948159516317958e+01,6.900625759864886959e+02,4.927462662634545243e-01,1.100000010988609489e+01,7.981265588655039184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812039068606318892e+01,6.900725759833036363e+02,4.927542475281958545e-01,1.100000010988609489e+01,7.979805734639662008e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812129977696319827e+01,6.900825759801198274e+02,4.927622273330836133e-01,1.100000010988609489e+01,7.978345880624284833e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812220886786320762e+01,6.900925759769371552e+02,4.927702056781178008e-01,1.100000010988609489e+01,7.976886026608907658e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812311795876321696e+01,6.901025759737556200e+02,4.927781825632984725e-01,1.100000010988609489e+01,7.975426172593530483e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812402704966322631e+01,6.901125759705752216e+02,4.927861579886255727e-01,1.100000010988609489e+01,7.973966318578153308e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812493614056323565e+01,6.901225759673959601e+02,4.927941319540991016e-01,1.100000010988609489e+01,7.972506464562776132e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812584523146324500e+01,6.901325759642179491e+02,4.928021044597191147e-01,1.100000010988609489e+01,7.971046610547398957e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812675432236325435e+01,6.901425759610410751e+02,4.928100755054855564e-01,1.100000010988609489e+01,7.969586756532021782e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812766341326326369e+01,6.901525759578653378e+02,4.928180450913984267e-01,1.100000010988609489e+01,7.968126902516644607e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812857250416327304e+01,6.901625759546907375e+02,4.928260132174577812e-01,1.100000010988609489e+01,7.966667048501267431e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.812948159506328238e+01,6.901725759515173877e+02,4.928339798836635643e-01,1.100000010988609489e+01,7.965207194485890256e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813039068596329173e+01,6.901825759483451748e+02,4.928419450900157761e-01,1.100000010988609489e+01,7.963747340470513081e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813129977686330108e+01,6.901925759451740987e+02,4.928499088365144720e-01,1.100000010988609489e+01,7.962287486455135906e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813220886776331042e+01,6.902025759420041595e+02,4.928578711231595966e-01,1.100000010988609489e+01,7.960827632439758730e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813311795866331977e+01,6.902125759388354709e+02,4.928658319499511498e-01,1.100000010988609489e+01,7.959367778424381555e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813402704956332911e+01,6.902225759356679191e+02,4.928737913168891871e-01,1.100000010988609489e+01,7.957907924409004380e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813493614046333846e+01,6.902325759325015042e+02,4.928817492239736531e-01,1.100000010988609489e+01,7.956448070393627205e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813584523136334781e+01,6.902425759293362262e+02,4.928897056712045477e-01,1.100000010988609489e+01,7.954988216378250029e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813675432226335715e+01,6.902525759261720850e+02,4.928976606585819265e-01,1.100000010988609489e+01,7.953528362362872854e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813766341316336650e+01,6.902625759230091944e+02,4.929056141861057339e-01,1.100000010988609489e+01,7.952068508347495679e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813857250406337585e+01,6.902725759198474407e+02,4.929135662537759699e-01,1.100000010988609489e+01,7.950608654332118504e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.813948159496338519e+01,6.902825759166868238e+02,4.929215168615926901e-01,1.100000010988609489e+01,7.949148800316741328e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814039068586339454e+01,6.902925759135273438e+02,4.929294660095558389e-01,1.100000010988609489e+01,7.947688946301364153e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814129977676340388e+01,6.903025759103690007e+02,4.929374136976654164e-01,1.100000010988609489e+01,7.946229092285986978e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814220886766341323e+01,6.903125759072119081e+02,4.929453599259214780e-01,1.100000010988609489e+01,7.944769238270609803e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814311795856342258e+01,6.903225759040559524e+02,4.929533046943239682e-01,1.100000010988609489e+01,7.943309384255232627e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814402704946343192e+01,6.903325759009011335e+02,4.929612480028728871e-01,1.100000010988609489e+01,7.941849530239855452e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814493614036344127e+01,6.903425758977474516e+02,4.929691898515682902e-01,1.100000010988609489e+01,7.940389676224478277e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814584523126345061e+01,6.903525758945949065e+02,4.929771302404101219e-01,1.100000010988609489e+01,7.938929822209101102e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814675432216345996e+01,6.903625758914436119e+02,4.929850691693983822e-01,1.100000010988609489e+01,7.937469968193723927e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814766341306346931e+01,6.903725758882934542e+02,4.929930066385330711e-01,1.100000010988609489e+01,7.936010114178346751e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814857250396347865e+01,6.903825758851444334e+02,4.930009426478142442e-01,1.100000010988609489e+01,7.934550260162969576e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.814948159486348800e+01,6.903925758819965495e+02,4.930088771972418460e-01,1.100000010988609489e+01,7.933090406147592401e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815039068576349734e+01,6.904025758788498024e+02,4.930168102868158764e-01,1.100000010988609489e+01,7.931630552132215226e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815129977666350669e+01,6.904125758757043059e+02,4.930247419165363909e-01,1.100000010988609489e+01,7.930170698116838050e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815220886756351604e+01,6.904225758725599462e+02,4.930326720864033341e-01,1.100000010988609489e+01,7.928710844101460875e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815311795846352538e+01,6.904325758694167234e+02,4.930406007964167059e-01,1.100000010988609489e+01,7.927250990086083700e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815402704936353473e+01,6.904425758662746375e+02,4.930485280465765063e-01,1.100000010988609489e+01,7.925791136070706525e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815493614026354408e+01,6.904525758631336885e+02,4.930564538368827909e-01,1.100000010988609489e+01,7.924331282055329349e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815584523116355342e+01,6.904625758599939900e+02,4.930643781673355042e-01,1.100000010988609489e+01,7.922871428039952174e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815675432206356277e+01,6.904725758568554284e+02,4.930723010379346460e-01,1.100000010988609489e+01,7.921411574024574999e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815766341296357211e+01,6.904825758537180036e+02,4.930802224486802166e-01,1.100000010988609489e+01,7.919951720009197824e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815857250386358146e+01,6.904925758505817157e+02,4.930881423995722712e-01,1.100000010988609489e+01,7.918491865993820648e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.815948159476359081e+01,6.905025758474465647e+02,4.930960608906107545e-01,1.100000010988609489e+01,7.917032011978443473e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816039068566360015e+01,6.905125758443125505e+02,4.931039779217956665e-01,1.100000010988609489e+01,7.915572157963066298e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816129977656360950e+01,6.905225758411797869e+02,4.931118934931270070e-01,1.100000010988609489e+01,7.914112303947689123e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816220886746361884e+01,6.905325758380481602e+02,4.931198076046048318e-01,1.100000010988609489e+01,7.912652449932311947e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816311795836362819e+01,6.905425758349176704e+02,4.931277202562290851e-01,1.100000010988609489e+01,7.911192595916934772e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816402704926363754e+01,6.905525758317883174e+02,4.931356314479997671e-01,1.100000010988609489e+01,7.909732741901557597e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816493614016364688e+01,6.905625758286601013e+02,4.931435411799168778e-01,1.100000010988609489e+01,7.908272887886180422e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816584523106365623e+01,6.905725758255330220e+02,4.931514494519804725e-01,1.100000010988609489e+01,7.906813033870803246e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816675432196366557e+01,6.905825758224071933e+02,4.931593562641904960e-01,1.100000010988609489e+01,7.905353179855426071e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816766341286367492e+01,6.905925758192825015e+02,4.931672616165469480e-01,1.100000010988609489e+01,7.903893325840048896e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816857250376368427e+01,6.906025758161589465e+02,4.931751655090498287e-01,1.100000010988609489e+01,7.902433471824671721e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.816948159466369361e+01,6.906125758130365284e+02,4.931830679416991381e-01,1.100000010988609489e+01,7.900973617809294545e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817039068556370296e+01,6.906225758099152472e+02,4.931909689144949316e-01,1.100000010988609489e+01,7.899513763793917370e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817129977646371231e+01,6.906325758067951028e+02,4.931988684274371537e-01,1.100000010988609489e+01,7.898053909778540195e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817220886736372165e+01,6.906425758036760953e+02,4.932067664805258045e-01,1.100000010988609489e+01,7.896594055763163020e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817311795826373100e+01,6.906525758005583384e+02,4.932146630737608839e-01,1.100000010988609489e+01,7.895134201747785845e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817402704916374034e+01,6.906625757974417184e+02,4.932225582071423919e-01,1.100000010988609489e+01,7.893674347732408669e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817493614006374969e+01,6.906725757943262352e+02,4.932304518806703841e-01,1.100000010988609489e+01,7.892214493717031494e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817584523096375904e+01,6.906825757912118888e+02,4.932383440943448050e-01,1.100000010988609489e+01,7.890754639701654319e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817675432186376838e+01,6.906925757880986794e+02,4.932462348481656544e-01,1.100000010988609489e+01,7.889294785686277144e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817766341276377773e+01,6.907025757849866068e+02,4.932541241421329326e-01,1.100000010988609489e+01,7.887834931670899968e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817857250366378707e+01,6.907125757818756711e+02,4.932620119762466393e-01,1.100000010988609489e+01,7.886375077655522793e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.817948159456379642e+01,6.907225757787658722e+02,4.932698983505068302e-01,1.100000010988609489e+01,7.884915223640145618e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818039068546380577e+01,6.907325757756573239e+02,4.932777832649134497e-01,1.100000010988609489e+01,7.883455369624768443e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818129977636381511e+01,6.907425757725499125e+02,4.932856667194664979e-01,1.100000010988609489e+01,7.881995515609391267e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818220886726382446e+01,6.907525757694436379e+02,4.932935487141659747e-01,1.100000010988609489e+01,7.880535661594014092e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818311795816383380e+01,6.907625757663385002e+02,4.933014292490118802e-01,1.100000010988609489e+01,7.879075807578636917e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818402704906384315e+01,6.907725757632344994e+02,4.933093083240042143e-01,1.100000010988609489e+01,7.877615953563259742e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818493613996385250e+01,6.907825757601316354e+02,4.933171859391430325e-01,1.100000010988609489e+01,7.876156099547882566e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818584523086386184e+01,6.907925757570299083e+02,4.933250620944282794e-01,1.100000010988609489e+01,7.874696245532505391e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818675432176387119e+01,6.908025757539293181e+02,4.933329367898599549e-01,1.100000010988609489e+01,7.873236391517128216e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818766341266388054e+01,6.908125757508299785e+02,4.933408100254380590e-01,1.100000010988609489e+01,7.871776537501751041e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818857250356388988e+01,6.908225757477317757e+02,4.933486818011625918e-01,1.100000010988609489e+01,7.870316683486373865e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.818948159446389923e+01,6.908325757446347097e+02,4.933565521170335533e-01,1.100000010988609489e+01,7.868856829470996690e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819039068536390857e+01,6.908425757415387807e+02,4.933644209730509989e-01,1.100000010988609489e+01,7.867396975455619515e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819129977626391792e+01,6.908525757384439885e+02,4.933722883692148731e-01,1.100000010988609489e+01,7.865937121440242340e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819220886716392727e+01,6.908625757353503332e+02,4.933801543055251759e-01,1.100000010988609489e+01,7.864477267424865164e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819311795806393661e+01,6.908725757322578147e+02,4.933880187819819074e-01,1.100000010988609489e+01,7.863017413409487989e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819402704896394596e+01,6.908825757291664331e+02,4.933958817985850676e-01,1.100000010988609489e+01,7.861557559394110814e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819493613986395530e+01,6.908925757260761884e+02,4.934037433553346563e-01,1.100000010988609489e+01,7.860097705378733639e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819584523076396465e+01,6.909025757229870806e+02,4.934116034522306737e-01,1.100000010988609489e+01,7.858637851363356464e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819675432166397400e+01,6.909125757198992233e+02,4.934194620892731198e-01,1.100000010988609489e+01,7.857177997347979288e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819766341256398334e+01,6.909225757168125028e+02,4.934273192664620500e-01,1.100000010988609489e+01,7.855718143332602113e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819857250346399269e+01,6.909325757137269193e+02,4.934351749837974088e-01,1.100000010988609489e+01,7.854258289317224938e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.819948159436400204e+01,6.909425757106424726e+02,4.934430292412791963e-01,1.100000010988609489e+01,7.852798435301847763e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820039068526401138e+01,6.909525757075591628e+02,4.934508820389074124e-01,1.100000010988609489e+01,7.851338581286470587e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820129977616402073e+01,6.909625757044769898e+02,4.934587333766820572e-01,1.100000010988609489e+01,7.849878727271093412e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820220886706403007e+01,6.909725757013959537e+02,4.934665832546031305e-01,1.100000010988609489e+01,7.848418873255716237e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820311795796403942e+01,6.909825756983160545e+02,4.934744316726706326e-01,1.100000010988609489e+01,7.846959019240339062e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820402704886404877e+01,6.909925756952372922e+02,4.934822786308845632e-01,1.100000010988609489e+01,7.845499165224961886e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820493613976405811e+01,6.910025756921596667e+02,4.934901241292449225e-01,1.100000010988609489e+01,7.844039311209584711e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820584523066406746e+01,6.910125756890831781e+02,4.934979681677517660e-01,1.100000010988609489e+01,7.842579457194207536e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820675432156407680e+01,6.910225756860078263e+02,4.935058107464050381e-01,1.100000010988609489e+01,7.841119603178830361e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820766341246408615e+01,6.910325756829337251e+02,4.935136518652047388e-01,1.100000010988609489e+01,7.839659749163453185e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820857250336409550e+01,6.910425756798607608e+02,4.935214915241508682e-01,1.100000010988609489e+01,7.838199895148076010e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.820948159426410484e+01,6.910525756767889334e+02,4.935293297232434262e-01,1.100000010988609489e+01,7.836740041132698835e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821039068516411419e+01,6.910625756737182428e+02,4.935371664624824128e-01,1.100000010988609489e+01,7.835280187117321660e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821129977606412353e+01,6.910725756706486891e+02,4.935450017418678281e-01,1.100000010988609489e+01,7.833820333101944484e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821220886696413288e+01,6.910825756675802722e+02,4.935528355613996720e-01,1.100000010988609489e+01,7.832360479086567309e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821311795786414223e+01,6.910925756645129923e+02,4.935606679210779446e-01,1.100000010988609489e+01,7.830900625071190134e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821402704876415157e+01,6.911025756614468492e+02,4.935684988209026458e-01,1.100000010988609489e+01,7.829440771055812959e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821493613966416092e+01,6.911125756583818429e+02,4.935763282608737756e-01,1.100000010988609489e+01,7.827980917040435783e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821584523056417027e+01,6.911225756553179735e+02,4.935841562409913341e-01,1.100000010988609489e+01,7.826521063025058608e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821675432146417961e+01,6.911325756522552410e+02,4.935919827612553212e-01,1.100000010988609489e+01,7.825061209009681433e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821766341236418896e+01,6.911425756491936454e+02,4.935998078216657370e-01,1.100000010988609489e+01,7.823601354994304258e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821857250326419830e+01,6.911525756461331866e+02,4.936076314222226369e-01,1.100000010988609489e+01,7.822141500978927083e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.821948159416420765e+01,6.911625756430738647e+02,4.936154535629259654e-01,1.100000010988609489e+01,7.820681646963549907e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822039068506421700e+01,6.911725756400156797e+02,4.936232742437757226e-01,1.100000010988609489e+01,7.819221792948172732e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822129977596422634e+01,6.911825756369586315e+02,4.936310934647719084e-01,1.100000010988609489e+01,7.817761938932795557e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822220886686423569e+01,6.911925756339027203e+02,4.936389112259145229e-01,1.100000010988609489e+01,7.816302084917418382e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822311795776424503e+01,6.912025756308479458e+02,4.936467275272035660e-01,1.100000010988609489e+01,7.814842230902041206e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822402704866425438e+01,6.912125756277943083e+02,4.936545423686390377e-01,1.100000010988609489e+01,7.813382376886664031e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822493613956426373e+01,6.912225756247418076e+02,4.936623557502209381e-01,1.100000010988609489e+01,7.811922522871286856e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822584523046427307e+01,6.912325756216905575e+02,4.936701676719492671e-01,1.100000010988609489e+01,7.810462668855909681e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822675432136428242e+01,6.912425756186404442e+02,4.936779781338240247e-01,1.100000010988609489e+01,7.809002814840532505e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822766341226429176e+01,6.912525756155914678e+02,4.936857871358452110e-01,1.100000010988609489e+01,7.807542960825155330e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822857250316430111e+01,6.912625756125436283e+02,4.936935946780128259e-01,1.100000010988609489e+01,7.806083106809778155e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.822948159406431046e+01,6.912725756094969256e+02,4.937014007603268695e-01,1.100000010988609489e+01,7.804623252794400980e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823039068496431980e+01,6.912825756064513598e+02,4.937092053827873417e-01,1.100000010988609489e+01,7.803163398779023804e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823129977586432915e+01,6.912925756034069309e+02,4.937170085453942425e-01,1.100000010988609489e+01,7.801703544763646629e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823220886676433850e+01,6.913025756003636388e+02,4.937248102481475720e-01,1.100000010988609489e+01,7.800243690748269454e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823311795766434784e+01,6.913125755973214837e+02,4.937326104910473301e-01,1.100000010988609489e+01,7.798783836732892279e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823402704856435719e+01,6.913225755942804653e+02,4.937404092740935169e-01,1.100000010988609489e+01,7.797323982717515103e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823493613946436653e+01,6.913325755912405839e+02,4.937482065972861323e-01,1.100000010988609489e+01,7.795864128702137928e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823584523036437588e+01,6.913425755882018393e+02,4.937560024606251763e-01,1.100000010988609489e+01,7.794404274686760753e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823675432126438523e+01,6.913525755851642316e+02,4.937637968641106490e-01,1.100000010988609489e+01,7.792944420671383578e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823766341216439457e+01,6.913625755821277608e+02,4.937715898077425503e-01,1.100000010988609489e+01,7.791484566656006402e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823857250306440392e+01,6.913725755790924268e+02,4.937793812915208802e-01,1.100000010988609489e+01,7.790024712640629227e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.823948159396441326e+01,6.913825755760582297e+02,4.937871713154456388e-01,1.100000010988609489e+01,7.788564858625252052e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824039068486442261e+01,6.913925755730251694e+02,4.937949598795168260e-01,1.100000010988609489e+01,7.787105004609874877e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824129977576443196e+01,6.914025755699932461e+02,4.938027469837344419e-01,1.100000010988609489e+01,7.785645150594497702e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824220886666444130e+01,6.914125755669624596e+02,4.938105326280984864e-01,1.100000010988609489e+01,7.784185296579120526e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824311795756445065e+01,6.914225755639328099e+02,4.938183168126089595e-01,1.100000010988609489e+01,7.782725442563743351e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824402704846445999e+01,6.914325755609042972e+02,4.938260995372658613e-01,1.100000010988609489e+01,7.781265588548366176e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824493613936446934e+01,6.914425755578769213e+02,4.938338808020691917e-01,1.100000010988609489e+01,7.779805734532989001e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824584523026447869e+01,6.914525755548506822e+02,4.938416606070189507e-01,1.100000010988609489e+01,7.778345880517611825e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824675432116448803e+01,6.914625755518255801e+02,4.938494389521151384e-01,1.100000010988609489e+01,7.776886026502234650e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824766341206449738e+01,6.914725755488016148e+02,4.938572158373577548e-01,1.100000010988609489e+01,7.775426172486857475e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824857250296450673e+01,6.914825755457787864e+02,4.938649912627467997e-01,1.100000010988609489e+01,7.773966318471480300e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.824948159386451607e+01,6.914925755427570948e+02,4.938727652282822178e-01,1.100000010988609489e+01,7.772506464456103124e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825039068476452542e+01,6.915025755397365401e+02,4.938805377339640645e-01,1.100000010988609489e+01,7.771046610440725949e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825129977566453476e+01,6.915125755367171223e+02,4.938883087797923399e-01,1.100000010988609489e+01,7.769586756425348774e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825220886656454411e+01,6.915225755336988414e+02,4.938960783657670439e-01,1.100000010988609489e+01,7.768126902409971599e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825311795746455346e+01,6.915325755306816973e+02,4.939038464918881766e-01,1.100000010988609489e+01,7.766667048394594423e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825402704836456280e+01,6.915425755276656901e+02,4.939116131581557378e-01,1.100000010988609489e+01,7.765207194379217248e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825493613926457215e+01,6.915525755246508197e+02,4.939193783645697278e-01,1.100000010988609489e+01,7.763747340363840073e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825584523016458149e+01,6.915625755216370862e+02,4.939271421111301463e-01,1.100000010988609489e+01,7.762287486348462898e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825675432106459084e+01,6.915725755186243759e+02,4.939349043978369935e-01,1.100000010988609489e+01,7.760827632333085722e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825766341196460019e+01,6.915825755156128025e+02,4.939426652246902694e-01,1.100000010988609489e+01,7.759367778317708547e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825857250286460953e+01,6.915925755126023660e+02,4.939504245916899738e-01,1.100000010988609489e+01,7.757907924302331372e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.825948159376461888e+01,6.916025755095930663e+02,4.939581824988361070e-01,1.100000010988609489e+01,7.756448070286954197e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826039068466462822e+01,6.916125755065849035e+02,4.939659389461286687e-01,1.100000010988609489e+01,7.754988216271577021e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826129977556463757e+01,6.916225755035778775e+02,4.939736939335676591e-01,1.100000010988609489e+01,7.753528362256199846e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826220886646464692e+01,6.916325755005719884e+02,4.939814474611530226e-01,1.100000010988609489e+01,7.752068508240822671e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826311795736465626e+01,6.916425754975672362e+02,4.939891995288848148e-01,1.100000010988609489e+01,7.750608654225445496e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826402704826466561e+01,6.916525754945636209e+02,4.939969501367630356e-01,1.100000010988609489e+01,7.749148800210068321e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826493613916467496e+01,6.916625754915611424e+02,4.940046992847876850e-01,1.100000010988609489e+01,7.747688946194691145e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826584523006468430e+01,6.916725754885598008e+02,4.940124469729587631e-01,1.100000010988609489e+01,7.746229092179313970e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826675432096469365e+01,6.916825754855595960e+02,4.940201932012762698e-01,1.100000010988609489e+01,7.744769238163936795e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826766341186470299e+01,6.916925754825605281e+02,4.940279379697402051e-01,1.100000010988609489e+01,7.743309384148559620e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826857250276471234e+01,6.917025754795625971e+02,4.940356812783505691e-01,1.100000010988609489e+01,7.741849530133182444e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.826948159366472169e+01,6.917125754765658030e+02,4.940434231271073617e-01,1.100000010988609489e+01,7.740389676117805269e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827039068456473103e+01,6.917225754735701457e+02,4.940511635160105275e-01,1.100000010988609489e+01,7.738929822102428094e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827129977546474038e+01,6.917325754705756253e+02,4.940589024450601219e-01,1.100000010988609489e+01,7.737469968087050919e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827220886636474972e+01,6.917425754675822418e+02,4.940666399142561449e-01,1.100000010988609489e+01,7.736010114071673743e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827311795726475907e+01,6.917525754645899951e+02,4.940743759235985966e-01,1.100000010988609489e+01,7.734550260056296568e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827402704816476842e+01,6.917625754615988853e+02,4.940821104730874769e-01,1.100000010988609489e+01,7.733090406040919393e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827493613906477776e+01,6.917725754586087987e+02,4.940898435627227858e-01,1.100000010988609489e+01,7.731630552025542218e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827584522996478711e+01,6.917825754556198490e+02,4.940975751925045234e-01,1.100000010988609489e+01,7.730170698010165042e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827675432086479645e+01,6.917925754526320361e+02,4.941053053624326896e-01,1.100000010988609489e+01,7.728710843994787867e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827766341176480580e+01,6.918025754496453601e+02,4.941130340725072290e-01,1.100000010988609489e+01,7.727250989979410692e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827857250266481515e+01,6.918125754466598210e+02,4.941207613227281970e-01,1.100000010988609489e+01,7.725791135964033517e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.827948159356482449e+01,6.918225754436754187e+02,4.941284871130955936e-01,1.100000010988609489e+01,7.724331281948656341e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828039068446483384e+01,6.918325754406921533e+02,4.941362114436094188e-01,1.100000010988609489e+01,7.722871427933279166e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828129977536484319e+01,6.918425754377100247e+02,4.941439343142696727e-01,1.100000010988609489e+01,7.721411573917901991e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828220886626485253e+01,6.918525754347290331e+02,4.941516557250763553e-01,1.100000010988609489e+01,7.719951719902524816e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828311795716486188e+01,6.918625754317491783e+02,4.941593756760294665e-01,1.100000010988609489e+01,7.718491865887147640e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828402704806487122e+01,6.918725754287704603e+02,4.941670941671289508e-01,1.100000010988609489e+01,7.717032011871770465e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828493613896488057e+01,6.918825754257928793e+02,4.941748111983748637e-01,1.100000010988609489e+01,7.715572157856393290e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828584522986488992e+01,6.918925754228163214e+02,4.941825267697672053e-01,1.100000010988609489e+01,7.714112303841016115e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828675432076489926e+01,6.919025754198409004e+02,4.941902408813059755e-01,1.100000010988609489e+01,7.712652449825638939e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828766341166490861e+01,6.919125754168666163e+02,4.941979535329911744e-01,1.100000010988609489e+01,7.711192595810261764e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828857250256491795e+01,6.919225754138934690e+02,4.942056647248227463e-01,1.100000010988609489e+01,7.709732741794884589e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.828948159346492730e+01,6.919325754109214586e+02,4.942133744568007470e-01,1.100000010988609489e+01,7.708272887779507414e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829039068436493665e+01,6.919425754079505850e+02,4.942210827289251762e-01,1.100000010988609489e+01,7.706813033764130239e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829129977526494599e+01,6.919525754049808484e+02,4.942287895411960341e-01,1.100000010988609489e+01,7.705353179748753063e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829220886616495534e+01,6.919625754020122486e+02,4.942364948936133207e-01,1.100000010988609489e+01,7.703893325733375888e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829311795706496468e+01,6.919725753990447856e+02,4.942441987861770358e-01,1.100000010988609489e+01,7.702433471717998713e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829402704796497403e+01,6.919825753960784596e+02,4.942519012188871241e-01,1.100000010988609489e+01,7.700973617702621538e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829493613886498338e+01,6.919925753931131567e+02,4.942596021917436411e-01,1.100000010988609489e+01,7.699513763687244362e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829584522976499272e+01,6.920025753901489907e+02,4.942673017047465867e-01,1.100000010988609489e+01,7.698053909671867187e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829675432066500207e+01,6.920125753871859615e+02,4.942749997578959609e-01,1.100000010988609489e+01,7.696594055656490012e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829766341156501142e+01,6.920225753842240692e+02,4.942826963511917637e-01,1.100000010988609489e+01,7.695134201641112837e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829857250246502076e+01,6.920325753812633138e+02,4.942903914846339397e-01,1.100000010988609489e+01,7.693674347625735661e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.829948159336503011e+01,6.920425753783036953e+02,4.942980851582225443e-01,1.100000010988609489e+01,7.692214493610358486e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830039068426503945e+01,6.920525753753452136e+02,4.943057773719575776e-01,1.100000010988609489e+01,7.690754639594981311e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830129977516504880e+01,6.920625753723878688e+02,4.943134681258390395e-01,1.100000010988609489e+01,7.689294785579604136e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830220886606505815e+01,6.920725753694316609e+02,4.943211574198668745e-01,1.100000010988609489e+01,7.687834931564226960e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830311795696506749e+01,6.920825753664764761e+02,4.943288452540411382e-01,1.100000010988609489e+01,7.686375077548849785e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830402704786507684e+01,6.920925753635224282e+02,4.943365316283618305e-01,1.100000010988609489e+01,7.684915223533472610e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830493613876508618e+01,6.921025753605695172e+02,4.943442165428289514e-01,1.100000010988609489e+01,7.683455369518095435e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830584522966509553e+01,6.921125753576177431e+02,4.943518999974425010e-01,1.100000010988609489e+01,7.681995515502718259e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830675432056510488e+01,6.921225753546671058e+02,4.943595819922024237e-01,1.100000010988609489e+01,7.680535661487341084e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830766341146511422e+01,6.921325753517176054e+02,4.943672625271087750e-01,1.100000010988609489e+01,7.679075807471963909e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830857250236512357e+01,6.921425753487692418e+02,4.943749416021615550e-01,1.100000010988609489e+01,7.677615953456586734e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.830948159326513291e+01,6.921525753458219015e+02,4.943826192173607637e-01,1.100000010988609489e+01,7.676156099441209558e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831039068416514226e+01,6.921625753428756980e+02,4.943902953727063454e-01,1.100000010988609489e+01,7.674696245425832383e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831129977506515161e+01,6.921725753399306313e+02,4.943979700681983558e-01,1.100000010988609489e+01,7.673236391410455208e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831220886596516095e+01,6.921825753369867016e+02,4.944056433038367948e-01,1.100000010988609489e+01,7.671776537395078033e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831311795686517030e+01,6.921925753340439087e+02,4.944133150796216625e-01,1.100000010988609489e+01,7.670316683379700858e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831402704776517965e+01,6.922025753311022527e+02,4.944209853955529033e-01,1.100000010988609489e+01,7.668856829364323682e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831493613866518899e+01,6.922125753281617335e+02,4.944286542516305727e-01,1.100000010988609489e+01,7.667396975348946507e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831584522956519834e+01,6.922225753252222376e+02,4.944363216478546708e-01,1.100000010988609489e+01,7.665937121333569332e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831675432046520768e+01,6.922325753222838784e+02,4.944439875842251420e-01,1.100000010988609489e+01,7.664477267318192157e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831766341136521703e+01,6.922425753193466562e+02,4.944516520607420418e-01,1.100000010988609489e+01,7.663017413302814981e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831857250226522638e+01,6.922525753164105708e+02,4.944593150774053703e-01,1.100000010988609489e+01,7.661557559287437806e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.831948159316523572e+01,6.922625753134756224e+02,4.944669766342151274e-01,1.100000010988609489e+01,7.660097705272060631e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832039068406524507e+01,6.922725753105418107e+02,4.944746367311712576e-01,1.100000010988609489e+01,7.658637851256683456e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832129977496525441e+01,6.922825753076090223e+02,4.944822953682738165e-01,1.100000010988609489e+01,7.657177997241306280e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832220886586526376e+01,6.922925753046773707e+02,4.944899525455228040e-01,1.100000010988609489e+01,7.655718143225929105e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832311795676527311e+01,6.923025753017468560e+02,4.944976082629182201e-01,1.100000010988609489e+01,7.654258289210551930e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832402704766528245e+01,6.923125752988174781e+02,4.945052625204600094e-01,1.100000010988609489e+01,7.652798435195174755e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832493613856529180e+01,6.923225752958892372e+02,4.945129153181482273e-01,1.100000010988609489e+01,7.651338581179797579e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832584522946530114e+01,6.923325752929621331e+02,4.945205666559828739e-01,1.100000010988609489e+01,7.649878727164420404e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832675432036531049e+01,6.923425752900360521e+02,4.945282165339638936e-01,1.100000010988609489e+01,7.648418873149043229e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832766341126531984e+01,6.923525752871111081e+02,4.945358649520913419e-01,1.100000010988609489e+01,7.646959019133666054e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832857250216532918e+01,6.923625752841873009e+02,4.945435119103652188e-01,1.100000010988609489e+01,7.645499165118288878e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.832948159306533853e+01,6.923725752812646306e+02,4.945511574087854689e-01,1.100000010988609489e+01,7.644039311102911703e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833039068396534788e+01,6.923825752783430971e+02,4.945588014473521477e-01,1.100000010988609489e+01,7.642579457087534528e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833129977486535722e+01,6.923925752754227005e+02,4.945664440260652550e-01,1.100000010988609489e+01,7.641119603072157353e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833220886576536657e+01,6.924025752725033271e+02,4.945740851449247355e-01,1.100000010988609489e+01,7.639659749056780177e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833311795666537591e+01,6.924125752695850906e+02,4.945817248039306446e-01,1.100000010988609489e+01,7.638199895041403002e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833402704756538526e+01,6.924225752666679909e+02,4.945893630030829824e-01,1.100000010988609489e+01,7.636740041026025827e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833493613846539461e+01,6.924325752637520281e+02,4.945969997423816933e-01,1.100000010988609489e+01,7.635280187010648652e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833584522936540395e+01,6.924425752608372022e+02,4.946046350218268328e-01,1.100000010988609489e+01,7.633820332995271477e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833675432026541330e+01,6.924525752579233995e+02,4.946122688414184010e-01,1.100000010988609489e+01,7.632360478979894301e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833766341116542264e+01,6.924625752550107336e+02,4.946199012011563423e-01,1.100000010988609489e+01,7.630900624964517126e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833857250206543199e+01,6.924725752520992046e+02,4.946275321010407122e-01,1.100000010988609489e+01,7.629440770949139951e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.833948159296544134e+01,6.924825752491888124e+02,4.946351615410715108e-01,1.100000010988609489e+01,7.627980916933762776e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834039068386545068e+01,6.924925752462795572e+02,4.946427895212486825e-01,1.100000010988609489e+01,7.626521062918385600e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834129977476546003e+01,6.925025752433713251e+02,4.946504160415722828e-01,1.100000010988609489e+01,7.625061208903008425e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834220886566546938e+01,6.925125752404642299e+02,4.946580411020423118e-01,1.100000010988609489e+01,7.623601354887631250e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834311795656547872e+01,6.925225752375582715e+02,4.946656647026587139e-01,1.100000010988609489e+01,7.622141500872254075e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834402704746548807e+01,6.925325752346534500e+02,4.946732868434215447e-01,1.100000010988609489e+01,7.620681646856876899e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834493613836549741e+01,6.925425752317497654e+02,4.946809075243308040e-01,1.100000010988609489e+01,7.619221792841499724e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834584522926550676e+01,6.925525752288471040e+02,4.946885267453864365e-01,1.100000010988609489e+01,7.617761938826122549e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834675432016551611e+01,6.925625752259455794e+02,4.946961445065884977e-01,1.100000010988609489e+01,7.616302084810745374e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834766341106552545e+01,6.925725752230451917e+02,4.947037608079369875e-01,1.100000010988609489e+01,7.614842230795368198e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834857250196553480e+01,6.925825752201459409e+02,4.947113756494318504e-01,1.100000010988609489e+01,7.613382376779991023e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.834948159286554414e+01,6.925925752172477132e+02,4.947189890310731419e-01,1.100000010988609489e+01,7.611922522764613848e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835039068376555349e+01,6.926025752143506224e+02,4.947266009528608066e-01,1.100000010988609489e+01,7.610462668749236673e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835129977466556284e+01,6.926125752114546685e+02,4.947342114147948999e-01,1.100000010988609489e+01,7.609002814733859497e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835220886556557218e+01,6.926225752085598515e+02,4.947418204168754219e-01,1.100000010988609489e+01,7.607542960718482322e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835311795646558153e+01,6.926325752056661713e+02,4.947494279591023170e-01,1.100000010988609489e+01,7.606083106703105147e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835402704736559087e+01,6.926425752027735143e+02,4.947570340414756407e-01,1.100000010988609489e+01,7.604623252687727972e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835493613826560022e+01,6.926525751998819942e+02,4.947646386639953930e-01,1.100000010988609489e+01,7.603163398672350796e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835584522916560957e+01,6.926625751969916109e+02,4.947722418266615185e-01,1.100000010988609489e+01,7.601703544656973621e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835675432006561891e+01,6.926725751941023645e+02,4.947798435294740726e-01,1.100000010988609489e+01,7.600243690641596446e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835766341096562826e+01,6.926825751912141413e+02,4.947874437724329999e-01,1.100000010988609489e+01,7.598783836626219271e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835857250186563761e+01,6.926925751883270550e+02,4.947950425555383558e-01,1.100000010988609489e+01,7.597323982610842096e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.835948159276564695e+01,6.927025751854411055e+02,4.948026398787900848e-01,1.100000010988609489e+01,7.595864128595464920e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836039068366565630e+01,6.927125751825562929e+02,4.948102357421882425e-01,1.100000010988609489e+01,7.594404274580087745e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836129977456566564e+01,6.927225751796725035e+02,4.948178301457328288e-01,1.100000010988609489e+01,7.592944420564710570e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836220886546567499e+01,6.927325751767898510e+02,4.948254230894237882e-01,1.100000010988609489e+01,7.591484566549333395e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836311795636568434e+01,6.927425751739083353e+02,4.948330145732611762e-01,1.100000010988609489e+01,7.590024712533956219e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836402704726569368e+01,6.927525751710279565e+02,4.948406045972449374e-01,1.100000010988609489e+01,7.588564858518579044e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836493613816570303e+01,6.927625751681486008e+02,4.948481931613751272e-01,1.100000010988609489e+01,7.587105004503201869e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836584522906571237e+01,6.927725751652703821e+02,4.948557802656517457e-01,1.100000010988609489e+01,7.585645150487824694e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836675431996572172e+01,6.927825751623933002e+02,4.948633659100747373e-01,1.100000010988609489e+01,7.584185296472447518e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836766341086573107e+01,6.927925751595173551e+02,4.948709500946441575e-01,1.100000010988609489e+01,7.582725442457070343e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836857250176574041e+01,6.928025751566424333e+02,4.948785328193599509e-01,1.100000010988609489e+01,7.581265588441693168e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.836948159266574976e+01,6.928125751537686483e+02,4.948861140842221729e-01,1.100000010988609489e+01,7.579805734426315993e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837039068356575910e+01,6.928225751508960002e+02,4.948936938892307680e-01,1.100000010988609489e+01,7.578345880410938817e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837129977446576845e+01,6.928325751480244890e+02,4.949012722343857917e-01,1.100000010988609489e+01,7.576886026395561642e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837220886536577780e+01,6.928425751451540009e+02,4.949088491196871886e-01,1.100000010988609489e+01,7.575426172380184467e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837311795626578714e+01,6.928525751422846497e+02,4.949164245451350141e-01,1.100000010988609489e+01,7.573966318364807292e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837402704716579649e+01,6.928625751394164354e+02,4.949239985107292683e-01,1.100000010988609489e+01,7.572506464349430116e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837493613806580584e+01,6.928725751365492442e+02,4.949315710164698956e-01,1.100000010988609489e+01,7.571046610334052941e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837584522896581518e+01,6.928825751336831900e+02,4.949391420623569515e-01,1.100000010988609489e+01,7.569586756318675766e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837675431986582453e+01,6.928925751308182726e+02,4.949467116483903806e-01,1.100000010988609489e+01,7.568126902303298591e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837766341076583387e+01,6.929025751279544920e+02,4.949542797745702383e-01,1.100000010988609489e+01,7.566667048287921415e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837857250166584322e+01,6.929125751250917347e+02,4.949618464408964691e-01,1.100000010988609489e+01,7.565207194272544240e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.837948159256585257e+01,6.929225751222301142e+02,4.949694116473691285e-01,1.100000010988609489e+01,7.563747340257167065e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838039068346586191e+01,6.929325751193696306e+02,4.949769753939881611e-01,1.100000010988609489e+01,7.562287486241789890e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838129977436587126e+01,6.929425751165101701e+02,4.949845376807536224e-01,1.100000010988609489e+01,7.560827632226412715e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838220886526588060e+01,6.929525751136518466e+02,4.949920985076654567e-01,1.100000010988609489e+01,7.559367778211035539e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838311795616588995e+01,6.929625751107946598e+02,4.949996578747237197e-01,1.100000010988609489e+01,7.557907924195658364e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838402704706589930e+01,6.929725751079386100e+02,4.950072157819283558e-01,1.100000010988609489e+01,7.556448070180281189e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838493613796590864e+01,6.929825751050835834e+02,4.950147722292794206e-01,1.100000010988609489e+01,7.554988216164904014e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838584522886591799e+01,6.929925751022296936e+02,4.950223272167768584e-01,1.100000010988609489e+01,7.553528362149526838e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838675431976592733e+01,6.930025750993769407e+02,4.950298807444207250e-01,1.100000010988609489e+01,7.552068508134149663e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838766341066593668e+01,6.930125750965252109e+02,4.950374328122109646e-01,1.100000010988609489e+01,7.550608654118772488e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838857250156594603e+01,6.930225750936746181e+02,4.950449834201476329e-01,1.100000010988609489e+01,7.549148800103395313e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.838948159246595537e+01,6.930325750908251621e+02,4.950525325682306743e-01,1.100000010988609489e+01,7.547688946088018137e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839039068336596472e+01,6.930425750879767293e+02,4.950600802564601444e-01,1.100000010988609489e+01,7.546229092072640962e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839129977426597407e+01,6.930525750851294333e+02,4.950676264848359875e-01,1.100000010988609489e+01,7.544769238057263787e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839220886516598341e+01,6.930625750822832742e+02,4.950751712533582594e-01,1.100000010988609489e+01,7.543309384041886612e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839311795606599276e+01,6.930725750794382520e+02,4.950827145620269043e-01,1.100000010988609489e+01,7.541849530026509436e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839402704696600210e+01,6.930825750765942530e+02,4.950902564108419779e-01,1.100000010988609489e+01,7.540389676011132261e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839493613786601145e+01,6.930925750737513908e+02,4.950977967998034246e-01,1.100000010988609489e+01,7.538929821995755086e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839584522876602080e+01,6.931025750709096656e+02,4.951053357289112999e-01,1.100000010988609489e+01,7.537469967980377911e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839675431966603014e+01,6.931125750680689634e+02,4.951128731981655484e-01,1.100000010988609489e+01,7.536010113965000735e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839766341056603949e+01,6.931225750652293982e+02,4.951204092075662255e-01,1.100000010988609489e+01,7.534550259949623560e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839857250146604883e+01,6.931325750623909698e+02,4.951279437571132758e-01,1.100000010988609489e+01,7.533090405934246385e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.839948159236605818e+01,6.931425750595535646e+02,4.951354768468067546e-01,1.100000010988609489e+01,7.531630551918869210e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840039068326606753e+01,6.931525750567172963e+02,4.951430084766466067e-01,1.100000010988609489e+01,7.530170697903492034e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840129977416607687e+01,6.931625750538821649e+02,4.951505386466328873e-01,1.100000010988609489e+01,7.528710843888114859e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840220886506608622e+01,6.931725750510480566e+02,4.951580673567655411e-01,1.100000010988609489e+01,7.527250989872737684e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840311795596609556e+01,6.931825750482150852e+02,4.951655946070446235e-01,1.100000010988609489e+01,7.525791135857360509e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840402704686610491e+01,6.931925750453832507e+02,4.951731203974700790e-01,1.100000010988609489e+01,7.524331281841983333e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840493613776611426e+01,6.932025750425524393e+02,4.951806447280419077e-01,1.100000010988609489e+01,7.522871427826606158e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840584522866612360e+01,6.932125750397227648e+02,4.951881675987601650e-01,1.100000010988609489e+01,7.521411573811228983e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840675431956613295e+01,6.932225750368942272e+02,4.951956890096247954e-01,1.100000010988609489e+01,7.519951719795851808e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840766341046614230e+01,6.932325750340667128e+02,4.952032089606358545e-01,1.100000010988609489e+01,7.518491865780474633e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840857250136615164e+01,6.932425750312403352e+02,4.952107274517932867e-01,1.100000010988609489e+01,7.517032011765097457e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.840948159226616099e+01,6.932525750284150945e+02,4.952182444830971475e-01,1.100000010988609489e+01,7.515572157749720282e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841039068316617033e+01,6.932625750255908770e+02,4.952257600545473815e-01,1.100000010988609489e+01,7.514112303734343107e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841129977406617968e+01,6.932725750227677963e+02,4.952332741661439885e-01,1.100000010988609489e+01,7.512652449718965932e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841220886496618903e+01,6.932825750199458525e+02,4.952407868178870243e-01,1.100000010988609489e+01,7.511192595703588756e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841311795586619837e+01,6.932925750171249319e+02,4.952482980097764331e-01,1.100000010988609489e+01,7.509732741688211581e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841402704676620772e+01,6.933025750143051482e+02,4.952558077418122706e-01,1.100000010988609489e+01,7.508272887672834406e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841493613766621706e+01,6.933125750114863877e+02,4.952633160139944812e-01,1.100000010988609489e+01,7.506813033657457231e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841584522856622641e+01,6.933225750086687640e+02,4.952708228263231205e-01,1.100000010988609489e+01,7.505353179642080055e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841675431946623576e+01,6.933325750058522772e+02,4.952783281787981329e-01,1.100000010988609489e+01,7.503893325626702880e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841766341036624510e+01,6.933425750030368135e+02,4.952858320714195184e-01,1.100000010988609489e+01,7.502433471611325705e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841857250126625445e+01,6.933525750002224868e+02,4.952933345041873325e-01,1.100000010988609489e+01,7.500973617595948530e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.841948159216626379e+01,6.933625749974092969e+02,4.953008354771015198e-01,1.100000010988609489e+01,7.499513763580571354e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842039068306627314e+01,6.933725749945971302e+02,4.953083349901621357e-01,1.100000010988609489e+01,7.498053909565194179e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842129977396628249e+01,6.933825749917861003e+02,4.953158330433691248e-01,1.100000010988609489e+01,7.496594055549817004e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842220886486629183e+01,6.933925749889762074e+02,4.953233296367224869e-01,1.100000010988609489e+01,7.495134201534439829e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842311795576630118e+01,6.934025749861673376e+02,4.953308247702222777e-01,1.100000010988609489e+01,7.493674347519062653e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842402704666631053e+01,6.934125749833596046e+02,4.953383184438684417e-01,1.100000010988609489e+01,7.492214493503685478e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842493613756631987e+01,6.934225749805528949e+02,4.953458106576610342e-01,1.100000010988609489e+01,7.490754639488308303e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842584522846632922e+01,6.934325749777473220e+02,4.953533014115999999e-01,1.100000010988609489e+01,7.489294785472931128e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842675431936633856e+01,6.934425749749428860e+02,4.953607907056853388e-01,1.100000010988609489e+01,7.487834931457553952e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842766341026634791e+01,6.934525749721394732e+02,4.953682785399171062e-01,1.100000010988609489e+01,7.486375077442176777e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842857250116635726e+01,6.934625749693371972e+02,4.953757649142952468e-01,1.100000010988609489e+01,7.484915223426799602e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.842948159206636660e+01,6.934725749665359444e+02,4.953832498288197606e-01,1.100000010988609489e+01,7.483455369411422427e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843039068296637595e+01,6.934825749637358285e+02,4.953907332834907029e-01,1.100000010988609489e+01,7.481995515396045252e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843129977386638529e+01,6.934925749609368495e+02,4.953982152783080184e-01,1.100000010988609489e+01,7.480535661380668076e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843220886476639464e+01,6.935025749581388936e+02,4.954056958132717070e-01,1.100000010988609489e+01,7.479075807365290901e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843311795566640399e+01,6.935125749553420746e+02,4.954131748883818243e-01,1.100000010988609489e+01,7.477615953349913726e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843402704656641333e+01,6.935225749525463925e+02,4.954206525036383146e-01,1.100000010988609489e+01,7.476156099334536551e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843493613746642268e+01,6.935325749497517336e+02,4.954281286590412337e-01,1.100000010988609489e+01,7.474696245319159375e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843584522836643202e+01,6.935425749469582115e+02,4.954356033545905258e-01,1.100000010988609489e+01,7.473236391303782200e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843675431926644137e+01,6.935525749441657126e+02,4.954430765902861911e-01,1.100000010988609489e+01,7.471776537288405025e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843766341016645072e+01,6.935625749413743506e+02,4.954505483661282850e-01,1.100000010988609489e+01,7.470316683273027850e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843857250106646006e+01,6.935725749385841254e+02,4.954580186821167520e-01,1.100000010988609489e+01,7.468856829257650674e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.843948159196646941e+01,6.935825749357949235e+02,4.954654875382515922e-01,1.100000010988609489e+01,7.467396975242273499e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844039068286647876e+01,6.935925749330068584e+02,4.954729549345328610e-01,1.100000010988609489e+01,7.465937121226896324e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844129977376648810e+01,6.936025749302198165e+02,4.954804208709605029e-01,1.100000010988609489e+01,7.464477267211519149e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844220886466649745e+01,6.936125749274339114e+02,4.954878853475345180e-01,1.100000010988609489e+01,7.463017413196141973e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844311795556650679e+01,6.936225749246490295e+02,4.954953483642549616e-01,1.100000010988609489e+01,7.461557559180764798e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844402704646651614e+01,6.936325749218652845e+02,4.955028099211217785e-01,1.100000010988609489e+01,7.460097705165387623e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844493613736652549e+01,6.936425749190826764e+02,4.955102700181349684e-01,1.100000010988609489e+01,7.458637851150010448e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844584522826653483e+01,6.936525749163010914e+02,4.955177286552945870e-01,1.100000010988609489e+01,7.457177997134633272e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844675431916654418e+01,6.936625749135206433e+02,4.955251858326005787e-01,1.100000010988609489e+01,7.455718143119256097e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844766341006655352e+01,6.936725749107412184e+02,4.955326415500529436e-01,1.100000010988609489e+01,7.454258289103878922e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844857250096656287e+01,6.936825749079629304e+02,4.955400958076516815e-01,1.100000010988609489e+01,7.452798435088501747e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.844948159186657222e+01,6.936925749051856656e+02,4.955475486053968481e-01,1.100000010988609489e+01,7.451338581073124571e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845039068276658156e+01,6.937025749024095376e+02,4.955549999432883879e-01,1.100000010988609489e+01,7.449878727057747396e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845129977366659091e+01,6.937125748996345465e+02,4.955624498213263007e-01,1.100000010988609489e+01,7.448418873042370221e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845220886456660025e+01,6.937225748968605785e+02,4.955698982395106422e-01,1.100000010988609489e+01,7.446959019026993046e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845311795546660960e+01,6.937325748940877475e+02,4.955773451978413568e-01,1.100000010988609489e+01,7.445499165011615871e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845402704636661895e+01,6.937425748913159396e+02,4.955847906963184446e-01,1.100000010988609489e+01,7.444039310996238695e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845493613726662829e+01,6.937525748885452685e+02,4.955922347349419610e-01,1.100000010988609489e+01,7.442579456980861520e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845584522816663764e+01,6.937625748857756207e+02,4.955996773137118505e-01,1.100000010988609489e+01,7.441119602965484345e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845675431906664699e+01,6.937725748830071097e+02,4.956071184326281132e-01,1.100000010988609489e+01,7.439659748950107170e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845766340996665633e+01,6.937825748802397356e+02,4.956145580916907489e-01,1.100000010988609489e+01,7.438199894934729994e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845857250086666568e+01,6.937925748774733847e+02,4.956219962908998133e-01,1.100000010988609489e+01,7.436740040919352819e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.845948159176667502e+01,6.938025748747081707e+02,4.956294330302552509e-01,1.100000010988609489e+01,7.435280186903975644e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846039068266668437e+01,6.938125748719439798e+02,4.956368683097570615e-01,1.100000010988609489e+01,7.433820332888598469e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846129977356669372e+01,6.938225748691809258e+02,4.956443021294053008e-01,1.100000010988609489e+01,7.432360478873221293e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846220886446670306e+01,6.938325748664188950e+02,4.956517344891999133e-01,1.100000010988609489e+01,7.430900624857844118e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846311795536671241e+01,6.938425748636580010e+02,4.956591653891408988e-01,1.100000010988609489e+01,7.429440770842466943e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846402704626672175e+01,6.938525748608981303e+02,4.956665948292282575e-01,1.100000010988609489e+01,7.427980916827089768e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846493613716673110e+01,6.938625748581393964e+02,4.956740228094620448e-01,1.100000010988609489e+01,7.426521062811712592e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846584522806674045e+01,6.938725748553816857e+02,4.956814493298422053e-01,1.100000010988609489e+01,7.425061208796335417e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846675431896674979e+01,6.938825748526251118e+02,4.956888743903687389e-01,1.100000010988609489e+01,7.423601354780958242e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846766340986675914e+01,6.938925748498696748e+02,4.956962979910416456e-01,1.100000010988609489e+01,7.422141500765581067e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846857250076676848e+01,6.939025748471152610e+02,4.957037201318609809e-01,1.100000010988609489e+01,7.420681646750203891e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.846948159166677783e+01,6.939125748443619841e+02,4.957111408128266894e-01,1.100000010988609489e+01,7.419221792734826716e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847039068256678718e+01,6.939225748416097304e+02,4.957185600339387710e-01,1.100000010988609489e+01,7.417761938719449541e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847129977346679652e+01,6.939325748388586135e+02,4.957259777951972257e-01,1.100000010988609489e+01,7.416302084704072366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847220886436680587e+01,6.939425748361085198e+02,4.957333940966021091e-01,1.100000010988609489e+01,7.414842230688695190e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847311795526681522e+01,6.939525748333595629e+02,4.957408089381533656e-01,1.100000010988609489e+01,7.413382376673318015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847402704616682456e+01,6.939625748306116293e+02,4.957482223198509952e-01,1.100000010988609489e+01,7.411922522657940840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847493613706683391e+01,6.939725748278648325e+02,4.957556342416949979e-01,1.100000010988609489e+01,7.410462668642563665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847584522796684325e+01,6.939825748251190589e+02,4.957630447036853738e-01,1.100000010988609489e+01,7.409002814627186490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847675431886685260e+01,6.939925748223744222e+02,4.957704537058221783e-01,1.100000010988609489e+01,7.407542960611809314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847766340976686195e+01,6.940025748196308086e+02,4.957778612481053560e-01,1.100000010988609489e+01,7.406083106596432139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847857250066687129e+01,6.940125748168883320e+02,4.957852673305349067e-01,1.100000010988609489e+01,7.404623252581054964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.847948159156688064e+01,6.940225748141468785e+02,4.957926719531108306e-01,1.100000010988609489e+01,7.403163398565677789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848039068246688998e+01,6.940325748114065618e+02,4.958000751158331831e-01,1.100000010988609489e+01,7.401703544550300613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848129977336689933e+01,6.940425748086672684e+02,4.958074768187019088e-01,1.100000010988609489e+01,7.400243690534923438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848220886426690868e+01,6.940525748059291118e+02,4.958148770617170076e-01,1.100000010988609489e+01,7.398783836519546263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848311795516691802e+01,6.940625748031919784e+02,4.958222758448784795e-01,1.100000010988609489e+01,7.397323982504169088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848402704606692737e+01,6.940725748004559819e+02,4.958296731681863245e-01,1.100000010988609489e+01,7.395864128488791912e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848493613696693671e+01,6.940825747977210085e+02,4.958370690316405982e-01,1.100000010988609489e+01,7.394404274473414737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848584522786694606e+01,6.940925747949871720e+02,4.958444634352412450e-01,1.100000010988609489e+01,7.392944420458037562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848675431876695541e+01,6.941025747922543587e+02,4.958518563789882649e-01,1.100000010988609489e+01,7.391484566442660387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848766340966696475e+01,6.941125747895226823e+02,4.958592478628816580e-01,1.100000010988609489e+01,7.390024712427283211e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848857250056697410e+01,6.941225747867920290e+02,4.958666378869214242e-01,1.100000010988609489e+01,7.388564858411906036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.848948159146698345e+01,6.941325747840625127e+02,4.958740264511075635e-01,1.100000010988609489e+01,7.387105004396528861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849039068236699279e+01,6.941425747813340195e+02,4.958814135554401314e-01,1.100000010988609489e+01,7.385645150381151686e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849129977326700214e+01,6.941525747786066631e+02,4.958887991999190725e-01,1.100000010988609489e+01,7.384185296365774510e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849220886416701148e+01,6.941625747758803300e+02,4.958961833845443867e-01,1.100000010988609489e+01,7.382725442350397335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849311795506702083e+01,6.941725747731551337e+02,4.959035661093160741e-01,1.100000010988609489e+01,7.381265588335020160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849402704596703018e+01,6.941825747704309606e+02,4.959109473742341345e-01,1.100000010988609489e+01,7.379805734319642985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849493613686703952e+01,6.941925747677079244e+02,4.959183271792985681e-01,1.100000010988609489e+01,7.378345880304265809e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849584522776704887e+01,6.942025747649859113e+02,4.959257055245094303e-01,1.100000010988609489e+01,7.376886026288888634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849675431866705821e+01,6.942125747622650351e+02,4.959330824098666657e-01,1.100000010988609489e+01,7.375426172273511459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849766340956706756e+01,6.942225747595451821e+02,4.959404578353702742e-01,1.100000010988609489e+01,7.373966318258134284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849857250046707691e+01,6.942325747568264660e+02,4.959478318010202558e-01,1.100000010988609489e+01,7.372506464242757108e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.849948159136708625e+01,6.942425747541087730e+02,4.959552043068166105e-01,1.100000010988609489e+01,7.371046610227379933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850039068226709560e+01,6.942525747513921033e+02,4.959625753527593384e-01,1.100000010988609489e+01,7.369586756212002758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850129977316710495e+01,6.942625747486765704e+02,4.959699449388484949e-01,1.100000010988609489e+01,7.368126902196625583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850220886406711429e+01,6.942725747459620607e+02,4.959773130650840245e-01,1.100000010988609489e+01,7.366667048181248408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850311795496712364e+01,6.942825747432486878e+02,4.959846797314659272e-01,1.100000010988609489e+01,7.365207194165871232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850402704586713298e+01,6.942925747405363381e+02,4.959920449379942031e-01,1.100000010988609489e+01,7.363747340150494057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850493613676714233e+01,6.943025747378251253e+02,4.959994086846688521e-01,1.100000010988609489e+01,7.362287486135116882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850584522766715168e+01,6.943125747351149357e+02,4.960067709714898743e-01,1.100000010988609489e+01,7.360827632119739707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850675431856716102e+01,6.943225747324058830e+02,4.960141317984572695e-01,1.100000010988609489e+01,7.359367778104362531e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850766340946717037e+01,6.943325747296978534e+02,4.960214911655710379e-01,1.100000010988609489e+01,7.357907924088985356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850857250036717971e+01,6.943425747269909607e+02,4.960288490728312349e-01,1.100000010988609489e+01,7.356448070073608181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.850948159126718906e+01,6.943525747242850912e+02,4.960362055202378051e-01,1.100000010988609489e+01,7.354988216058231006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851039068216719841e+01,6.943625747215802448e+02,4.960435605077907484e-01,1.100000010988609489e+01,7.353528362042853830e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851129977306720775e+01,6.943725747188765354e+02,4.960509140354900648e-01,1.100000010988609489e+01,7.352068508027476655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851220886396721710e+01,6.943825747161738491e+02,4.960582661033357543e-01,1.100000010988609489e+01,7.350608654012099480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851311795486722644e+01,6.943925747134722997e+02,4.960656167113278170e-01,1.100000010988609489e+01,7.349148799996722305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851402704576723579e+01,6.944025747107717734e+02,4.960729658594662528e-01,1.100000010988609489e+01,7.347688945981345129e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851493613666724514e+01,6.944125747080723841e+02,4.960803135477510617e-01,1.100000010988609489e+01,7.346229091965967954e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851584522756725448e+01,6.944225747053740179e+02,4.960876597761822437e-01,1.100000010988609489e+01,7.344769237950590779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851675431846726383e+01,6.944325747026767885e+02,4.960950045447598544e-01,1.100000010988609489e+01,7.343309383935213604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851766340936727318e+01,6.944425746999805824e+02,4.961023478534838382e-01,1.100000010988609489e+01,7.341849529919836428e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851857250026728252e+01,6.944525746972853995e+02,4.961096897023541952e-01,1.100000010988609489e+01,7.340389675904459253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.851948159116729187e+01,6.944625746945913534e+02,4.961170300913709252e-01,1.100000010988609489e+01,7.338929821889082078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852039068206730121e+01,6.944725746918983305e+02,4.961243690205340284e-01,1.100000010988609489e+01,7.337469967873704903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852129977296731056e+01,6.944825746892064444e+02,4.961317064898435047e-01,1.100000010988609489e+01,7.336010113858327727e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852220886386731991e+01,6.944925746865155816e+02,4.961390424992993542e-01,1.100000010988609489e+01,7.334550259842950552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852311795476732925e+01,6.945025746838258556e+02,4.961463770489015768e-01,1.100000010988609489e+01,7.333090405827573377e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852402704566733860e+01,6.945125746811371528e+02,4.961537101386501725e-01,1.100000010988609489e+01,7.331630551812196202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852493613656734794e+01,6.945225746784494731e+02,4.961610417685451413e-01,1.100000010988609489e+01,7.330170697796819027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852584522746735729e+01,6.945325746757629304e+02,4.961683719385864832e-01,1.100000010988609489e+01,7.328710843781441851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852675431836736664e+01,6.945425746730774108e+02,4.961757006487741983e-01,1.100000010988609489e+01,7.327250989766064676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852766340926737598e+01,6.945525746703930281e+02,4.961830278991083421e-01,1.100000010988609489e+01,7.325791135750687501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852857250016738533e+01,6.945625746677096686e+02,4.961903536895888589e-01,1.100000010988609489e+01,7.324331281735310326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.852948159106739467e+01,6.945725746650273322e+02,4.961976780202157489e-01,1.100000010988609489e+01,7.322871427719933150e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853039068196740402e+01,6.945825746623461328e+02,4.962050008909890120e-01,1.100000010988609489e+01,7.321411573704555975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853129977286741337e+01,6.945925746596659565e+02,4.962123223019086482e-01,1.100000010988609489e+01,7.319951719689178800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853220886376742271e+01,6.946025746569869170e+02,4.962196422529746576e-01,1.100000010988609489e+01,7.318491865673801625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853311795466743206e+01,6.946125746543089008e+02,4.962269607441870400e-01,1.100000010988609489e+01,7.317032011658424449e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853402704556744141e+01,6.946225746516319077e+02,4.962342777755457957e-01,1.100000010988609489e+01,7.315572157643047274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853493613646745075e+01,6.946325746489560515e+02,4.962415933470509244e-01,1.100000010988609489e+01,7.314112303627670099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853584522736746010e+01,6.946425746462812185e+02,4.962489074587024263e-01,1.100000010988609489e+01,7.312652449612292924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853675431826746944e+01,6.946525746436075224e+02,4.962562201105003012e-01,1.100000010988609489e+01,7.311192595596915748e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853766340916747879e+01,6.946625746409348494e+02,4.962635313024445494e-01,1.100000010988609489e+01,7.309732741581538573e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853857250006748814e+01,6.946725746382631996e+02,4.962708410345351706e-01,1.100000010988609489e+01,7.308272887566161398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.853948159096749748e+01,6.946825746355926867e+02,4.962781493067721650e-01,1.100000010988609489e+01,7.306813033550784223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854039068186750683e+01,6.946925746329231970e+02,4.962854561191555325e-01,1.100000010988609489e+01,7.305353179535407047e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854129977276751617e+01,6.947025746302548441e+02,4.962927614716852731e-01,1.100000010988609489e+01,7.303893325520029872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854220886366752552e+01,6.947125746275875144e+02,4.963000653643613869e-01,1.100000010988609489e+01,7.302433471504652697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854311795456753487e+01,6.947225746249212079e+02,4.963073677971838737e-01,1.100000010988609489e+01,7.300973617489275522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854402704546754421e+01,6.947325746222560383e+02,4.963146687701527338e-01,1.100000010988609489e+01,7.299513763473898346e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854493613636755356e+01,6.947425746195918919e+02,4.963219682832679669e-01,1.100000010988609489e+01,7.298053909458521171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854584522726756290e+01,6.947525746169287686e+02,4.963292663365295732e-01,1.100000010988609489e+01,7.296594055443143996e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854675431816757225e+01,6.947625746142667822e+02,4.963365629299375525e-01,1.100000010988609489e+01,7.295134201427766821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854766340906758160e+01,6.947725746116058190e+02,4.963438580634919051e-01,1.100000010988609489e+01,7.293674347412389646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854857249996759094e+01,6.947825746089458789e+02,4.963511517371926307e-01,1.100000010988609489e+01,7.292214493397012470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.854948159086760029e+01,6.947925746062870758e+02,4.963584439510397295e-01,1.100000010988609489e+01,7.290754639381635295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855039068176760964e+01,6.948025746036292958e+02,4.963657347050332014e-01,1.100000010988609489e+01,7.289294785366258120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855129977266761898e+01,6.948125746009726527e+02,4.963730239991730464e-01,1.100000010988609489e+01,7.287834931350880945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855220886356762833e+01,6.948225745983170327e+02,4.963803118334592646e-01,1.100000010988609489e+01,7.286375077335503769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855311795446763767e+01,6.948325745956624360e+02,4.963875982078918558e-01,1.100000010988609489e+01,7.284915223320126594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855402704536764702e+01,6.948425745930089761e+02,4.963948831224708202e-01,1.100000010988609489e+01,7.283455369304749419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855493613626765637e+01,6.948525745903565394e+02,4.964021665771961578e-01,1.100000010988609489e+01,7.281995515289372244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855584522716766571e+01,6.948625745877051259e+02,4.964094485720678684e-01,1.100000010988609489e+01,7.280535661273995068e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855675431806767506e+01,6.948725745850548492e+02,4.964167291070859522e-01,1.100000010988609489e+01,7.279075807258617893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855766340896768440e+01,6.948825745824055957e+02,4.964240081822504091e-01,1.100000010988609489e+01,7.277615953243240718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855857249986769375e+01,6.948925745797573654e+02,4.964312857975612392e-01,1.100000010988609489e+01,7.276156099227863543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.855948159076770310e+01,6.949025745771102720e+02,4.964385619530184424e-01,1.100000010988609489e+01,7.274696245212486367e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856039068166771244e+01,6.949125745744642018e+02,4.964458366486220187e-01,1.100000010988609489e+01,7.273236391197109192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856129977256772179e+01,6.949225745718191547e+02,4.964531098843719681e-01,1.100000010988609489e+01,7.271776537181732017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856220886346773113e+01,6.949325745691752445e+02,4.964603816602682906e-01,1.100000010988609489e+01,7.270316683166354842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856311795436774048e+01,6.949425745665323575e+02,4.964676519763109863e-01,1.100000010988609489e+01,7.268856829150977666e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856402704526774983e+01,6.949525745638904937e+02,4.964749208325000551e-01,1.100000010988609489e+01,7.267396975135600491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856493613616775917e+01,6.949625745612497667e+02,4.964821882288354971e-01,1.100000010988609489e+01,7.265937121120223316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856584522706776852e+01,6.949725745586100629e+02,4.964894541653173121e-01,1.100000010988609489e+01,7.264477267104846141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856675431796777787e+01,6.949825745559713823e+02,4.964967186419455003e-01,1.100000010988609489e+01,7.263017413089468965e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856766340886778721e+01,6.949925745533338386e+02,4.965039816587200061e-01,1.100000010988609489e+01,7.261557559074091790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856857249976779656e+01,6.950025745506973180e+02,4.965112432156408850e-01,1.100000010988609489e+01,7.260097705058714615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.856948159066780590e+01,6.950125745480618207e+02,4.965185033127081371e-01,1.100000010988609489e+01,7.258637851043337440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857039068156781525e+01,6.950225745454274602e+02,4.965257619499217623e-01,1.100000010988609489e+01,7.257177997027960265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857129977246782460e+01,6.950325745427941229e+02,4.965330191272817606e-01,1.100000010988609489e+01,7.255718143012583089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857220886336783394e+01,6.950425745401618087e+02,4.965402748447881320e-01,1.100000010988609489e+01,7.254258288997205914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857311795426784329e+01,6.950525745375306315e+02,4.965475291024408766e-01,1.100000010988609489e+01,7.252798434981828739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857402704516785263e+01,6.950625745349004774e+02,4.965547819002399943e-01,1.100000010988609489e+01,7.251338580966451564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857493613606786198e+01,6.950725745322713465e+02,4.965620332381854851e-01,1.100000010988609489e+01,7.249878726951074388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857584522696787133e+01,6.950825745296433524e+02,4.965692831162773491e-01,1.100000010988609489e+01,7.248418872935697213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857675431786788067e+01,6.950925745270163816e+02,4.965765315345155861e-01,1.100000010988609489e+01,7.246959018920320038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857766340876789002e+01,6.951025745243904339e+02,4.965837784929001963e-01,1.100000010988609489e+01,7.245499164904942863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857857249966789936e+01,6.951125745217656231e+02,4.965910239914311797e-01,1.100000010988609489e+01,7.244039310889565687e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.857948159056790871e+01,6.951225745191418355e+02,4.965982680301084806e-01,1.100000010988609489e+01,7.242579456874188512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858039068146791806e+01,6.951325745165190710e+02,4.966055106089321547e-01,1.100000010988609489e+01,7.241119602858811337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858129977236792740e+01,6.951425745138973298e+02,4.966127517279022019e-01,1.100000010988609489e+01,7.239659748843434162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858220886326793675e+01,6.951525745112767254e+02,4.966199913870186222e-01,1.100000010988609489e+01,7.238199894828056986e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858311795416794610e+01,6.951625745086571442e+02,4.966272295862814157e-01,1.100000010988609489e+01,7.236740040812679811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858402704506795544e+01,6.951725745060385862e+02,4.966344663256905823e-01,1.100000010988609489e+01,7.235280186797302636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858493613596796479e+01,6.951825745034211650e+02,4.966417016052461220e-01,1.100000010988609489e+01,7.233820332781925461e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858584522686797413e+01,6.951925745008047670e+02,4.966489354249480348e-01,1.100000010988609489e+01,7.232360478766548285e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858675431776798348e+01,6.952025744981893922e+02,4.966561677847963208e-01,1.100000010988609489e+01,7.230900624751171110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858766340866799283e+01,6.952125744955750406e+02,4.966633986847909243e-01,1.100000010988609489e+01,7.229440770735793935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858857249956800217e+01,6.952225744929618259e+02,4.966706281249319010e-01,1.100000010988609489e+01,7.227980916720416760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.858948159046801152e+01,6.952325744903496343e+02,4.966778561052192509e-01,1.100000010988609489e+01,7.226521062705039584e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859039068136802086e+01,6.952425744877384659e+02,4.966850826256529738e-01,1.100000010988609489e+01,7.225061208689662409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859129977226803021e+01,6.952525744851284344e+02,4.966923076862330699e-01,1.100000010988609489e+01,7.223601354674285234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859220886316803956e+01,6.952625744825194261e+02,4.966995312869595391e-01,1.100000010988609489e+01,7.222141500658908059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859311795406804890e+01,6.952725744799114409e+02,4.967067534278323815e-01,1.100000010988609489e+01,7.220681646643530884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859402704496805825e+01,6.952825744773044789e+02,4.967139741088515414e-01,1.100000010988609489e+01,7.219221792628153708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859493613586806759e+01,6.952925744746986538e+02,4.967211933300170745e-01,1.100000010988609489e+01,7.217761938612776533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859584522676807694e+01,6.953025744720938519e+02,4.967284110913289807e-01,1.100000010988609489e+01,7.216302084597399358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859675431766808629e+01,6.953125744694900732e+02,4.967356273927872601e-01,1.100000010988609489e+01,7.214842230582022183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859766340856809563e+01,6.953225744668874313e+02,4.967428422343919125e-01,1.100000010988609489e+01,7.213382376566645007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859857249946810498e+01,6.953325744642858126e+02,4.967500556161429381e-01,1.100000010988609489e+01,7.211922522551267832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.859948159036811433e+01,6.953425744616852171e+02,4.967572675380403369e-01,1.100000010988609489e+01,7.210462668535890657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860039068126812367e+01,6.953525744590856448e+02,4.967644780000840532e-01,1.100000010988609489e+01,7.209002814520513482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860129977216813302e+01,6.953625744564872093e+02,4.967716870022741427e-01,1.100000010988609489e+01,7.207542960505136306e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860220886306814236e+01,6.953725744538897970e+02,4.967788945446106053e-01,1.100000010988609489e+01,7.206083106489759131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860311795396815171e+01,6.953825744512934079e+02,4.967861006270934410e-01,1.100000010988609489e+01,7.204623252474381956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860402704486816106e+01,6.953925744486980420e+02,4.967933052497226498e-01,1.100000010988609489e+01,7.203163398459004781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860493613576817040e+01,6.954025744461038130e+02,4.968005084124982318e-01,1.100000010988609489e+01,7.201703544443627605e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860584522666817975e+01,6.954125744435106071e+02,4.968077101154201314e-01,1.100000010988609489e+01,7.200243690428250430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860675431756818909e+01,6.954225744409184244e+02,4.968149103584884041e-01,1.100000010988609489e+01,7.198783836412873255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860766340846819844e+01,6.954325744383272649e+02,4.968221091417030499e-01,1.100000010988609489e+01,7.197323982397496080e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860857249936820779e+01,6.954425744357372423e+02,4.968293064650640689e-01,1.100000010988609489e+01,7.195864128382118904e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.860948159026821713e+01,6.954525744331482429e+02,4.968365023285714610e-01,1.100000010988609489e+01,7.194404274366741729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861039068116822648e+01,6.954625744305602666e+02,4.968436967322251707e-01,1.100000010988609489e+01,7.192944420351364554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861129977206823582e+01,6.954725744279733135e+02,4.968508896760252536e-01,1.100000010988609489e+01,7.191484566335987379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861220886296824517e+01,6.954825744253874973e+02,4.968580811599717095e-01,1.100000010988609489e+01,7.190024712320610203e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861311795386825452e+01,6.954925744228027042e+02,4.968652711840645386e-01,1.100000010988609489e+01,7.188564858305233028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861402704476826386e+01,6.955025744202189344e+02,4.968724597483037408e-01,1.100000010988609489e+01,7.187105004289855853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861493613566827321e+01,6.955125744176361877e+02,4.968796468526892607e-01,1.100000010988609489e+01,7.185645150274478678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861584522656828256e+01,6.955225744150544642e+02,4.968868324972211536e-01,1.100000010988609489e+01,7.184185296259101502e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861675431746829190e+01,6.955325744124738776e+02,4.968940166818994197e-01,1.100000010988609489e+01,7.182725442243724327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861766340836830125e+01,6.955425744098943142e+02,4.969011994067240590e-01,1.100000010988609489e+01,7.181265588228347152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861857249926831059e+01,6.955525744073157739e+02,4.969083806716950713e-01,1.100000010988609489e+01,7.179805734212969977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.861948159016831994e+01,6.955625744047382568e+02,4.969155604768124013e-01,1.100000010988609489e+01,7.178345880197592802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862039068106832929e+01,6.955725744021618766e+02,4.969227388220761044e-01,1.100000010988609489e+01,7.176886026182215626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862129977196833863e+01,6.955825743995865196e+02,4.969299157074861806e-01,1.100000010988609489e+01,7.175426172166838451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862220886286834798e+01,6.955925743970121857e+02,4.969370911330426299e-01,1.100000010988609489e+01,7.173966318151461276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862311795376835732e+01,6.956025743944388751e+02,4.969442650987454524e-01,1.100000010988609489e+01,7.172506464136084101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862402704466836667e+01,6.956125743918665876e+02,4.969514376045945925e-01,1.100000010988609489e+01,7.171046610120706925e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862493613556837602e+01,6.956225743892954370e+02,4.969586086505901057e-01,1.100000010988609489e+01,7.169586756105329750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862584522646838536e+01,6.956325743867253095e+02,4.969657782367319920e-01,1.100000010988609489e+01,7.168126902089952575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862675431736839471e+01,6.956425743841562053e+02,4.969729463630202515e-01,1.100000010988609489e+01,7.166667048074575400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862766340826840405e+01,6.956525743815881242e+02,4.969801130294548286e-01,1.100000010988609489e+01,7.165207194059198224e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862857249916841340e+01,6.956625743790210663e+02,4.969872782360357788e-01,1.100000010988609489e+01,7.163747340043821049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.862948159006842275e+01,6.956725743764551453e+02,4.969944419827631021e-01,1.100000010988609489e+01,7.162287486028443874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863039068096843209e+01,6.956825743738902474e+02,4.970016042696367986e-01,1.100000010988609489e+01,7.160827632013066699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863129977186844144e+01,6.956925743713263728e+02,4.970087650966568127e-01,1.100000010988609489e+01,7.159367777997689523e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863220886276845079e+01,6.957025743687635213e+02,4.970159244638231999e-01,1.100000010988609489e+01,7.157907923982312348e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863311795366846013e+01,6.957125743662016930e+02,4.970230823711359602e-01,1.100000010988609489e+01,7.156448069966935173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863402704456846948e+01,6.957225743636410016e+02,4.970302388185950937e-01,1.100000010988609489e+01,7.154988215951557998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863493613546847882e+01,6.957325743610813333e+02,4.970373938062005448e-01,1.100000010988609489e+01,7.153528361936180822e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863584522636848817e+01,6.957425743585226883e+02,4.970445473339523690e-01,1.100000010988609489e+01,7.152068507920803647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863675431726849752e+01,6.957525743559650664e+02,4.970516994018505663e-01,1.100000010988609489e+01,7.150608653905426472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863766340816850686e+01,6.957625743534084677e+02,4.970588500098950813e-01,1.100000010988609489e+01,7.149148799890049297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863857249906851621e+01,6.957725743508530059e+02,4.970659991580859693e-01,1.100000010988609489e+01,7.147688945874672121e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.863948158996852555e+01,6.957825743482985672e+02,4.970731468464232305e-01,1.100000010988609489e+01,7.146229091859294946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864039068086853490e+01,6.957925743457451517e+02,4.970802930749068649e-01,1.100000010988609489e+01,7.144769237843917771e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864129977176854425e+01,6.958025743431927594e+02,4.970874378435368168e-01,1.100000010988609489e+01,7.143309383828540596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864220886266855359e+01,6.958125743406413903e+02,4.970945811523131419e-01,1.100000010988609489e+01,7.141849529813163421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864311795356856294e+01,6.958225743380910444e+02,4.971017230012358401e-01,1.100000010988609489e+01,7.140389675797786245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864402704446857229e+01,6.958325743355418354e+02,4.971088633903048559e-01,1.100000010988609489e+01,7.138929821782409070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864493613536858163e+01,6.958425743329936495e+02,4.971160023195202449e-01,1.100000010988609489e+01,7.137469967767031895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864584522626859098e+01,6.958525743304464868e+02,4.971231397888820069e-01,1.100000010988609489e+01,7.136010113751654720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864675431716860032e+01,6.958625743279003473e+02,4.971302757983901421e-01,1.100000010988609489e+01,7.134550259736277544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864766340806860967e+01,6.958725743253552309e+02,4.971374103480445950e-01,1.100000010988609489e+01,7.133090405720900369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864857249896861902e+01,6.958825743228111378e+02,4.971445434378454209e-01,1.100000010988609489e+01,7.131630551705523194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.864948158986862836e+01,6.958925743202681815e+02,4.971516750677926200e-01,1.100000010988609489e+01,7.130170697690146019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865039068076863771e+01,6.959025743177262484e+02,4.971588052378861367e-01,1.100000010988609489e+01,7.128710843674768843e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865129977166864705e+01,6.959125743151853385e+02,4.971659339481260265e-01,1.100000010988609489e+01,7.127250989659391668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865220886256865640e+01,6.959225743126454518e+02,4.971730611985122894e-01,1.100000010988609489e+01,7.125791135644014493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865311795346866575e+01,6.959325743101065882e+02,4.971801869890448700e-01,1.100000010988609489e+01,7.124331281628637318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865402704436867509e+01,6.959425743075687478e+02,4.971873113197238236e-01,1.100000010988609489e+01,7.122871427613260142e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865493613526868444e+01,6.959525743050319306e+02,4.971944341905491505e-01,1.100000010988609489e+01,7.121411573597882967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865584522616869378e+01,6.959625743024962503e+02,4.972015556015207949e-01,1.100000010988609489e+01,7.119951719582505792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865675431706870313e+01,6.959725742999615932e+02,4.972086755526388124e-01,1.100000010988609489e+01,7.118491865567128617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865766340796871248e+01,6.959825742974279592e+02,4.972157940439032031e-01,1.100000010988609489e+01,7.117032011551751441e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865857249886872182e+01,6.959925742948953484e+02,4.972229110753139114e-01,1.100000010988609489e+01,7.115572157536374266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.865948158976873117e+01,6.960025742923637608e+02,4.972300266468709928e-01,1.100000010988609489e+01,7.114112303520997091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866039068066874052e+01,6.960125742898331964e+02,4.972371407585744474e-01,1.100000010988609489e+01,7.112652449505619916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866129977156874986e+01,6.960225742873036552e+02,4.972442534104242196e-01,1.100000010988609489e+01,7.111192595490242740e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866220886246875921e+01,6.960325742847752508e+02,4.972513646024203648e-01,1.100000010988609489e+01,7.109732741474865565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866311795336876855e+01,6.960425742822478696e+02,4.972584743345628833e-01,1.100000010988609489e+01,7.108272887459488390e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866402704426877790e+01,6.960525742797215116e+02,4.972655826068517193e-01,1.100000010988609489e+01,7.106813033444111215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866493613516878725e+01,6.960625742771961768e+02,4.972726894192869285e-01,1.100000010988609489e+01,7.105353179428734040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866584522606879659e+01,6.960725742746718652e+02,4.972797947718685108e-01,1.100000010988609489e+01,7.103893325413356864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866675431696880594e+01,6.960825742721485767e+02,4.972868986645964107e-01,1.100000010988609489e+01,7.102433471397979689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866766340786881528e+01,6.960925742696263114e+02,4.972940010974706837e-01,1.100000010988609489e+01,7.100973617382602514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866857249876882463e+01,6.961025742671050693e+02,4.973011020704913299e-01,1.100000010988609489e+01,7.099513763367225339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.866948158966883398e+01,6.961125742645849641e+02,4.973082015836582936e-01,1.100000010988609489e+01,7.098053909351848163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867039068056884332e+01,6.961225742620658821e+02,4.973152996369716305e-01,1.100000010988609489e+01,7.096594055336470988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867129977146885267e+01,6.961325742595478232e+02,4.973223962304312851e-01,1.100000010988609489e+01,7.095134201321093813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867220886236886201e+01,6.961425742570307875e+02,4.973294913640373127e-01,1.100000010988609489e+01,7.093674347305716638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867311795326887136e+01,6.961525742545147750e+02,4.973365850377897135e-01,1.100000010988609489e+01,7.092214493290339462e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867402704416888071e+01,6.961625742519997857e+02,4.973436772516884319e-01,1.100000010988609489e+01,7.090754639274962287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867493613506889005e+01,6.961725742494858196e+02,4.973507680057335234e-01,1.100000010988609489e+01,7.089294785259585112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867584522596889940e+01,6.961825742469728766e+02,4.973578572999249325e-01,1.100000010988609489e+01,7.087834931244207937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867675431686890875e+01,6.961925742444609568e+02,4.973649451342627148e-01,1.100000010988609489e+01,7.086375077228830761e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867766340776891809e+01,6.962025742419501739e+02,4.973720315087468702e-01,1.100000010988609489e+01,7.084915223213453586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867857249866892744e+01,6.962125742394404142e+02,4.973791164233773432e-01,1.100000010988609489e+01,7.083455369198076411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.867948158956893678e+01,6.962225742369316777e+02,4.973861998781541893e-01,1.100000010988609489e+01,7.081995515182699236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868039068046894613e+01,6.962325742344239643e+02,4.973932818730773531e-01,1.100000010988609489e+01,7.080535661167322060e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868129977136895548e+01,6.962425742319172741e+02,4.974003624081468899e-01,1.100000010988609489e+01,7.079075807151944885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868220886226896482e+01,6.962525742294116071e+02,4.974074414833627999e-01,1.100000010988609489e+01,7.077615953136567710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868311795316897417e+01,6.962625742269069633e+02,4.974145190987250276e-01,1.100000010988609489e+01,7.076156099121190535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868402704406898351e+01,6.962725742244033427e+02,4.974215952542336283e-01,1.100000010988609489e+01,7.074696245105813359e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868493613496899286e+01,6.962825742219007452e+02,4.974286699498885467e-01,1.100000010988609489e+01,7.073236391090436184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868584522586900221e+01,6.962925742193991709e+02,4.974357431856898382e-01,1.100000010988609489e+01,7.071776537075059009e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868675431676901155e+01,6.963025742168986199e+02,4.974428149616375028e-01,1.100000010988609489e+01,7.070316683059681834e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868766340766902090e+01,6.963125742143992056e+02,4.974498852777314850e-01,1.100000010988609489e+01,7.068856829044304659e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868857249856903024e+01,6.963225742119008146e+02,4.974569541339718404e-01,1.100000010988609489e+01,7.067396975028927483e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.868948158946903959e+01,6.963325742094034467e+02,4.974640215303585133e-01,1.100000010988609489e+01,7.065937121013550308e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869039068036904894e+01,6.963425742069071021e+02,4.974710874668915594e-01,1.100000010988609489e+01,7.064477266998173133e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869129977126905828e+01,6.963525742044117806e+02,4.974781519435709232e-01,1.100000010988609489e+01,7.063017412982795958e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869220886216906763e+01,6.963625742019174822e+02,4.974852149603966600e-01,1.100000010988609489e+01,7.061557558967418782e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869311795306907698e+01,6.963725741994242071e+02,4.974922765173687700e-01,1.100000010988609489e+01,7.060097704952041607e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869402704396908632e+01,6.963825741969319552e+02,4.974993366144871976e-01,1.100000010988609489e+01,7.058637850936664432e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869493613486909567e+01,6.963925741944407264e+02,4.975063952517519983e-01,1.100000010988609489e+01,7.057177996921287257e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869584522576910501e+01,6.964025741919505208e+02,4.975134524291631166e-01,1.100000010988609489e+01,7.055718142905910081e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869675431666911436e+01,6.964125741894613384e+02,4.975205081467206081e-01,1.100000010988609489e+01,7.054258288890532906e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869766340756912371e+01,6.964225741869731792e+02,4.975275624044244172e-01,1.100000010988609489e+01,7.052798434875155731e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869857249846913305e+01,6.964325741844860431e+02,4.975346152022745994e-01,1.100000010988609489e+01,7.051338580859778556e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.869948158936914240e+01,6.964425741819999303e+02,4.975416665402710992e-01,1.100000010988609489e+01,7.049878726844401380e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870039068026915174e+01,6.964525741795148406e+02,4.975487164184139721e-01,1.100000010988609489e+01,7.048418872829024205e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870129977116916109e+01,6.964625741770307741e+02,4.975557648367031627e-01,1.100000010988609489e+01,7.046959018813647030e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870220886206917044e+01,6.964725741745478444e+02,4.975628117951387264e-01,1.100000010988609489e+01,7.045499164798269855e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870311795296917978e+01,6.964825741720659380e+02,4.975698572937206632e-01,1.100000010988609489e+01,7.044039310782892679e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870402704386918913e+01,6.964925741695850547e+02,4.975769013324489176e-01,1.100000010988609489e+01,7.042579456767515504e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870493613476919847e+01,6.965025741671051946e+02,4.975839439113235452e-01,1.100000010988609489e+01,7.041119602752138329e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870584522566920782e+01,6.965125741646263577e+02,4.975909850303444903e-01,1.100000010988609489e+01,7.039659748736761154e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870675431656921717e+01,6.965225741621485440e+02,4.975980246895118086e-01,1.100000010988609489e+01,7.038199894721383978e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870766340746922651e+01,6.965325741596717535e+02,4.976050628888254446e-01,1.100000010988609489e+01,7.036740040706006803e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870857249836923586e+01,6.965425741571959861e+02,4.976120996282854536e-01,1.100000010988609489e+01,7.035280186690629628e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.870948158926924521e+01,6.965525741547212419e+02,4.976191349078917803e-01,1.100000010988609489e+01,7.033820332675252453e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871039068016925455e+01,6.965625741522475209e+02,4.976261687276444801e-01,1.100000010988609489e+01,7.032360478659875277e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871129977106926390e+01,6.965725741497748231e+02,4.976332010875434975e-01,1.100000010988609489e+01,7.030900624644498102e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871220886196927324e+01,6.965825741473031485e+02,4.976402319875888880e-01,1.100000010988609489e+01,7.029440770629120927e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871311795286928259e+01,6.965925741448324970e+02,4.976472614277805961e-01,1.100000010988609489e+01,7.027980916613743752e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871402704376929194e+01,6.966025741423628688e+02,4.976542894081186774e-01,1.100000010988609489e+01,7.026521062598366577e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871493613466930128e+01,6.966125741398942637e+02,4.976613159286030763e-01,1.100000010988609489e+01,7.025061208582989401e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871584522556931063e+01,6.966225741374266818e+02,4.976683409892338483e-01,1.100000010988609489e+01,7.023601354567612226e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871675431646931997e+01,6.966325741349601230e+02,4.976753645900109380e-01,1.100000010988609489e+01,7.022141500552235051e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871766340736932932e+01,6.966425741324945875e+02,4.976823867309344007e-01,1.100000010988609489e+01,7.020681646536857876e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871857249826933867e+01,6.966525741300300751e+02,4.976894074120041811e-01,1.100000010988609489e+01,7.019221792521480700e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.871948158916934801e+01,6.966625741275665860e+02,4.976964266332203346e-01,1.100000010988609489e+01,7.017761938506103525e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872039068006935736e+01,6.966725741251041200e+02,4.977034443945828057e-01,1.100000010988609489e+01,7.016302084490726350e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872129977096936670e+01,6.966825741226426771e+02,4.977104606960916500e-01,1.100000010988609489e+01,7.014842230475349175e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872220886186937605e+01,6.966925741201822575e+02,4.977174755377468118e-01,1.100000010988609489e+01,7.013382376459971999e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872311795276938540e+01,6.967025741177228610e+02,4.977244889195483468e-01,1.100000010988609489e+01,7.011922522444594824e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872402704366939474e+01,6.967125741152644878e+02,4.977315008414961994e-01,1.100000010988609489e+01,7.010462668429217649e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872493613456940409e+01,6.967225741128071377e+02,4.977385113035903696e-01,1.100000010988609489e+01,7.009002814413840474e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872584522546941344e+01,6.967325741103508108e+02,4.977455203058309130e-01,1.100000010988609489e+01,7.007542960398463298e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872675431636942278e+01,6.967425741078955070e+02,4.977525278482177740e-01,1.100000010988609489e+01,7.006083106383086123e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872766340726943213e+01,6.967525741054412265e+02,4.977595339307510081e-01,1.100000010988609489e+01,7.004623252367708948e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872857249816944147e+01,6.967625741029879691e+02,4.977665385534305598e-01,1.100000010988609489e+01,7.003163398352331773e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.872948158906945082e+01,6.967725741005357349e+02,4.977735417162564846e-01,1.100000010988609489e+01,7.001703544336954597e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873039067996946017e+01,6.967825740980845239e+02,4.977805434192287271e-01,1.100000010988609489e+01,7.000243690321577422e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873129977086946951e+01,6.967925740956343361e+02,4.977875436623473426e-01,1.100000010988609489e+01,6.998783836306200247e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873220886176947886e+01,6.968025740931851715e+02,4.977945424456122758e-01,1.100000010988609489e+01,6.997323982290823072e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873311795266948820e+01,6.968125740907370300e+02,4.978015397690235821e-01,1.100000010988609489e+01,6.995864128275445896e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873402704356949755e+01,6.968225740882899117e+02,4.978085356325812061e-01,1.100000010988609489e+01,6.994404274260068721e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873493613446950690e+01,6.968325740858438166e+02,4.978155300362851476e-01,1.100000010988609489e+01,6.992944420244691546e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873584522536951624e+01,6.968425740833987447e+02,4.978225229801354623e-01,1.100000010988609489e+01,6.991484566229314371e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873675431626952559e+01,6.968525740809546960e+02,4.978295144641320946e-01,1.100000010988609489e+01,6.990024712213937196e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873766340716953493e+01,6.968625740785116705e+02,4.978365044882751000e-01,1.100000010988609489e+01,6.988564858198560020e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873857249806954428e+01,6.968725740760696681e+02,4.978434930525644231e-01,1.100000010988609489e+01,6.987105004183182845e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.873948158896955363e+01,6.968825740736286889e+02,4.978504801570001193e-01,1.100000010988609489e+01,6.985645150167805670e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874039067986956297e+01,6.968925740711887329e+02,4.978574658015821330e-01,1.100000010988609489e+01,6.984185296152428495e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874129977076957232e+01,6.969025740687498001e+02,4.978644499863104644e-01,1.100000010988609489e+01,6.982725442137051319e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874220886166958167e+01,6.969125740663118904e+02,4.978714327111851690e-01,1.100000010988609489e+01,6.981265588121674144e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874311795256959101e+01,6.969225740638750040e+02,4.978784139762061911e-01,1.100000010988609489e+01,6.979805734106296969e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874402704346960036e+01,6.969325740614391407e+02,4.978853937813735864e-01,1.100000010988609489e+01,6.978345880090919794e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874493613436960970e+01,6.969425740590043006e+02,4.978923721266872993e-01,1.100000010988609489e+01,6.976886026075542618e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874584522526961905e+01,6.969525740565704837e+02,4.978993490121473298e-01,1.100000010988609489e+01,6.975426172060165443e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874675431616962840e+01,6.969625740541376899e+02,4.979063244377537334e-01,1.100000010988609489e+01,6.973966318044788268e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874766340706963774e+01,6.969725740517059194e+02,4.979132984035064546e-01,1.100000010988609489e+01,6.972506464029411093e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874857249796964709e+01,6.969825740492751720e+02,4.979202709094055490e-01,1.100000010988609489e+01,6.971046610014033917e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.874948158886965643e+01,6.969925740468454478e+02,4.979272419554509610e-01,1.100000010988609489e+01,6.969586755998656742e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875039067976966578e+01,6.970025740444167468e+02,4.979342115416426906e-01,1.100000010988609489e+01,6.968126901983279567e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875129977066967513e+01,6.970125740419889553e+02,4.979411796679807933e-01,1.100000010988609489e+01,6.966667047967902392e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875220886156968447e+01,6.970225740395621870e+02,4.979481463344652137e-01,1.100000010988609489e+01,6.965207193952525216e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875311795246969382e+01,6.970325740371364418e+02,4.979551115410960072e-01,1.100000010988609489e+01,6.963747339937148041e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875402704336970316e+01,6.970425740347117198e+02,4.979620752878731182e-01,1.100000010988609489e+01,6.962287485921770866e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875493613426971251e+01,6.970525740322880210e+02,4.979690375747965470e-01,1.100000010988609489e+01,6.960827631906393691e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875584522516972186e+01,6.970625740298653454e+02,4.979759984018663488e-01,1.100000010988609489e+01,6.959367777891016515e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875675431606973120e+01,6.970725740274436930e+02,4.979829577690824682e-01,1.100000010988609489e+01,6.957907923875639340e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875766340696974055e+01,6.970825740250230638e+02,4.979899156764449053e-01,1.100000010988609489e+01,6.956448069860262165e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875857249786974990e+01,6.970925740226034577e+02,4.979968721239537155e-01,1.100000010988609489e+01,6.954988215844884990e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.875948158876975924e+01,6.971025740201848748e+02,4.980038271116088433e-01,1.100000010988609489e+01,6.953528361829507815e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876039067966976859e+01,6.971125740177673151e+02,4.980107806394102887e-01,1.100000010988609489e+01,6.952068507814130639e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876129977056977793e+01,6.971225740153507786e+02,4.980177327073581073e-01,1.100000010988609489e+01,6.950608653798753464e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876220886146978728e+01,6.971325740129352653e+02,4.980246833154522434e-01,1.100000010988609489e+01,6.949148799783376289e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876311795236979663e+01,6.971425740105207751e+02,4.980316324636927527e-01,1.100000010988609489e+01,6.947688945767999114e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876402704326980597e+01,6.971525740081073081e+02,4.980385801520795797e-01,1.100000010988609489e+01,6.946229091752621938e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876493613416981532e+01,6.971625740056947507e+02,4.980455263806127242e-01,1.100000010988609489e+01,6.944769237737244763e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876584522506982466e+01,6.971725740032832164e+02,4.980524711492922418e-01,1.100000010988609489e+01,6.943309383721867588e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876675431596983401e+01,6.971825740008727053e+02,4.980594144581180771e-01,1.100000010988609489e+01,6.941849529706490413e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876766340686984336e+01,6.971925739984632173e+02,4.980663563070902300e-01,1.100000010988609489e+01,6.940389675691113237e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876857249776985270e+01,6.972025739960547526e+02,4.980732966962087560e-01,1.100000010988609489e+01,6.938929821675736062e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.876948158866986205e+01,6.972125739936473110e+02,4.980802356254735996e-01,1.100000010988609489e+01,6.937469967660358887e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877039067956987139e+01,6.972225739912408926e+02,4.980871730948847609e-01,1.100000010988609489e+01,6.936010113644981712e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877129977046988074e+01,6.972325739888354974e+02,4.980941091044422953e-01,1.100000010988609489e+01,6.934550259629604536e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877220886136989009e+01,6.972425739864311254e+02,4.981010436541461472e-01,1.100000010988609489e+01,6.933090405614227361e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877311795226989943e+01,6.972525739840277765e+02,4.981079767439963168e-01,1.100000010988609489e+01,6.931630551598850186e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877402704316990878e+01,6.972625739816254509e+02,4.981149083739928596e-01,1.100000010988609489e+01,6.930170697583473011e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877493613406991813e+01,6.972725739792240347e+02,4.981218385441357199e-01,1.100000010988609489e+01,6.928710843568095835e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877584522496992747e+01,6.972825739768236417e+02,4.981287672544248979e-01,1.100000010988609489e+01,6.927250989552718660e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877675431586993682e+01,6.972925739744242719e+02,4.981356945048604490e-01,1.100000010988609489e+01,6.925791135537341485e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877766340676994616e+01,6.973025739720259253e+02,4.981426202954423177e-01,1.100000010988609489e+01,6.924331281521964310e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877857249766995551e+01,6.973125739696286018e+02,4.981495446261705040e-01,1.100000010988609489e+01,6.922871427506587134e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.877948158856996486e+01,6.973225739672323016e+02,4.981564674970450080e-01,1.100000010988609489e+01,6.921411573491209959e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878039067946997420e+01,6.973325739648370245e+02,4.981633889080658850e-01,1.100000010988609489e+01,6.919951719475832784e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878129977036998355e+01,6.973425739624427706e+02,4.981703088592330797e-01,1.100000010988609489e+01,6.918491865460455609e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878220886126999289e+01,6.973525739600495399e+02,4.981772273505465920e-01,1.100000010988609489e+01,6.917032011445078434e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878311795217000224e+01,6.973625739576572187e+02,4.981841443820064774e-01,1.100000010988609489e+01,6.915572157429701258e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878402704307001159e+01,6.973725739552659206e+02,4.981910599536126805e-01,1.100000010988609489e+01,6.914112303414324083e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878493613397002093e+01,6.973825739528756458e+02,4.981979740653652011e-01,1.100000010988609489e+01,6.912652449398946908e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878584522487003028e+01,6.973925739504863941e+02,4.982048867172640949e-01,1.100000010988609489e+01,6.911192595383569733e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878675431577003963e+01,6.974025739480981656e+02,4.982117979093093063e-01,1.100000010988609489e+01,6.909732741368192557e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878766340667004897e+01,6.974125739457109603e+02,4.982187076415008353e-01,1.100000010988609489e+01,6.908272887352815382e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878857249757005832e+01,6.974225739433247782e+02,4.982256159138386820e-01,1.100000010988609489e+01,6.906813033337438207e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.878948158847006766e+01,6.974325739409396192e+02,4.982325227263229017e-01,1.100000010988609489e+01,6.905353179322061032e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879039067937007701e+01,6.974425739385553698e+02,4.982394280789534391e-01,1.100000010988609489e+01,6.903893325306683856e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879129977027008636e+01,6.974525739361721435e+02,4.982463319717302941e-01,1.100000010988609489e+01,6.902433471291306681e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879220886117009570e+01,6.974625739337899404e+02,4.982532344046534667e-01,1.100000010988609489e+01,6.900973617275929506e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879311795207010505e+01,6.974725739314087605e+02,4.982601353777230124e-01,1.100000010988609489e+01,6.899513763260552331e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879402704297011439e+01,6.974825739290286037e+02,4.982670348909388758e-01,1.100000010988609489e+01,6.898053909245175155e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879493613387012374e+01,6.974925739266494702e+02,4.982739329443010567e-01,1.100000010988609489e+01,6.896594055229797980e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879584522477013309e+01,6.975025739242713598e+02,4.982808295378095553e-01,1.100000010988609489e+01,6.895134201214420805e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879675431567014243e+01,6.975125739218942726e+02,4.982877246714644270e-01,1.100000010988609489e+01,6.893674347199043630e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879766340657015178e+01,6.975225739195180950e+02,4.982946183452656164e-01,1.100000010988609489e+01,6.892214493183666454e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879857249747016112e+01,6.975325739171429404e+02,4.983015105592131233e-01,1.100000010988609489e+01,6.890754639168289279e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.879948158837017047e+01,6.975425739147688091e+02,4.983084013133069479e-01,1.100000010988609489e+01,6.889294785152912104e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880039067927017982e+01,6.975525739123957010e+02,4.983152906075471456e-01,1.100000010988609489e+01,6.887834931137534929e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880129977017018916e+01,6.975625739100236160e+02,4.983221784419336609e-01,1.100000010988609489e+01,6.886375077122157753e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880220886107019851e+01,6.975725739076525542e+02,4.983290648164664938e-01,1.100000010988609489e+01,6.884915223106780578e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880311795197020786e+01,6.975825739052824019e+02,4.983359497311456443e-01,1.100000010988609489e+01,6.883455369091403403e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880402704287021720e+01,6.975925739029132728e+02,4.983428331859711680e-01,1.100000010988609489e+01,6.881995515076026228e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880493613377022655e+01,6.976025739005451669e+02,4.983497151809430092e-01,1.100000010988609489e+01,6.880535661060649053e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880584522467023589e+01,6.976125738981780842e+02,4.983565957160611681e-01,1.100000010988609489e+01,6.879075807045271877e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880675431557024524e+01,6.976225738958120246e+02,4.983634747913256446e-01,1.100000010988609489e+01,6.877615953029894702e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880766340647025459e+01,6.976325738934469882e+02,4.983703524067364943e-01,1.100000010988609489e+01,6.876156099014517527e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880857249737026393e+01,6.976425738910828613e+02,4.983772285622936615e-01,1.100000010988609489e+01,6.874696244999140352e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.880948158827027328e+01,6.976525738887197576e+02,4.983841032579971464e-01,1.100000010988609489e+01,6.873236390983763176e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881039067917028262e+01,6.976625738863576771e+02,4.983909764938469489e-01,1.100000010988609489e+01,6.871776536968386001e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881129977007029197e+01,6.976725738839966198e+02,4.983978482698430690e-01,1.100000010988609489e+01,6.870316682953008826e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881220886097030132e+01,6.976825738816365856e+02,4.984047185859855622e-01,1.100000010988609489e+01,6.868856828937631651e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881311795187031066e+01,6.976925738792775746e+02,4.984115874422743730e-01,1.100000010988609489e+01,6.867396974922254475e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881402704277032001e+01,6.977025738769194732e+02,4.984184548387095015e-01,1.100000010988609489e+01,6.865937120906877300e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881493613367032935e+01,6.977125738745623948e+02,4.984253207752909476e-01,1.100000010988609489e+01,6.864477266891500125e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881584522457033870e+01,6.977225738722063397e+02,4.984321852520187113e-01,1.100000010988609489e+01,6.863017412876122950e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881675431547034805e+01,6.977325738698513078e+02,4.984390482688928481e-01,1.100000010988609489e+01,6.861557558860745774e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881766340637035739e+01,6.977425738674972990e+02,4.984459098259133025e-01,1.100000010988609489e+01,6.860097704845368599e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881857249727036674e+01,6.977525738651441998e+02,4.984527699230800746e-01,1.100000010988609489e+01,6.858637850829991424e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.881948158817037609e+01,6.977625738627921237e+02,4.984596285603931642e-01,1.100000010988609489e+01,6.857177996814614249e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882039067907038543e+01,6.977725738604410708e+02,4.984664857378525715e-01,1.100000010988609489e+01,6.855718142799237073e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882129976997039478e+01,6.977825738580910411e+02,4.984733414554583519e-01,1.100000010988609489e+01,6.854258288783859898e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882220886087040412e+01,6.977925738557420345e+02,4.984801957132104500e-01,1.100000010988609489e+01,6.852798434768482723e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882311795177041347e+01,6.978025738533939375e+02,4.984870485111088656e-01,1.100000010988609489e+01,6.851338580753105548e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882402704267042282e+01,6.978125738510468636e+02,4.984938998491535989e-01,1.100000010988609489e+01,6.849878726737728372e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882493613357043216e+01,6.978225738487008130e+02,4.985007497273446497e-01,1.100000010988609489e+01,6.848418872722351197e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882584522447044151e+01,6.978325738463557855e+02,4.985075981456820182e-01,1.100000010988609489e+01,6.846959018706974022e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882675431537045085e+01,6.978425738440117811e+02,4.985144451041657598e-01,1.100000010988609489e+01,6.845499164691596847e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882766340627046020e+01,6.978525738416686863e+02,4.985212906027958191e-01,1.100000010988609489e+01,6.844039310676219671e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882857249717046955e+01,6.978625738393266147e+02,4.985281346415721959e-01,1.100000010988609489e+01,6.842579456660842496e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.882948158807047889e+01,6.978725738369855662e+02,4.985349772204948904e-01,1.100000010988609489e+01,6.841119602645465321e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883039067897048824e+01,6.978825738346455410e+02,4.985418183395639025e-01,1.100000010988609489e+01,6.839659748630088146e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883129976987049758e+01,6.978925738323065389e+02,4.985486579987792322e-01,1.100000010988609489e+01,6.838199894614710971e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883220886077050693e+01,6.979025738299684463e+02,4.985554961981409350e-01,1.100000010988609489e+01,6.836740040599333795e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883311795167051628e+01,6.979125738276313768e+02,4.985623329376489554e-01,1.100000010988609489e+01,6.835280186583956620e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883402704257052562e+01,6.979225738252953306e+02,4.985691682173032935e-01,1.100000010988609489e+01,6.833820332568579445e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883493613347053497e+01,6.979325738229603076e+02,4.985760020371039491e-01,1.100000010988609489e+01,6.832360478553202270e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883584522437054432e+01,6.979425738206261940e+02,4.985828343970509224e-01,1.100000010988609489e+01,6.830900624537825094e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883675431527055366e+01,6.979525738182931036e+02,4.985896652971442133e-01,1.100000010988609489e+01,6.829440770522447919e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883766340617056301e+01,6.979625738159610364e+02,4.985964947373838219e-01,1.100000010988609489e+01,6.827980916507070744e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883857249707057235e+01,6.979725738136299924e+02,4.986033227177698035e-01,1.100000010988609489e+01,6.826521062491693569e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.883948158797058170e+01,6.979825738112999716e+02,4.986101492383021028e-01,1.100000010988609489e+01,6.825061208476316393e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884039067887059105e+01,6.979925738089708602e+02,4.986169742989807196e-01,1.100000010988609489e+01,6.823601354460939218e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884129976977060039e+01,6.980025738066427721e+02,4.986237978998056541e-01,1.100000010988609489e+01,6.822141500445562043e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884220886067060974e+01,6.980125738043157071e+02,4.986306200407769063e-01,1.100000010988609489e+01,6.820681646430184868e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884311795157061908e+01,6.980225738019896653e+02,4.986374407218944760e-01,1.100000010988609489e+01,6.819221792414807692e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884402704247062843e+01,6.980325737996645330e+02,4.986442599431583633e-01,1.100000010988609489e+01,6.817761938399430517e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884493613337063778e+01,6.980425737973404239e+02,4.986510777045685683e-01,1.100000010988609489e+01,6.816302084384053342e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884584522427064712e+01,6.980525737950173379e+02,4.986578940061251464e-01,1.100000010988609489e+01,6.814842230368676167e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884675431517065647e+01,6.980625737926952752e+02,4.986647088478280421e-01,1.100000010988609489e+01,6.813382376353298991e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884766340607066581e+01,6.980725737903741219e+02,4.986715222296772554e-01,1.100000010988609489e+01,6.811922522337921816e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884857249697067516e+01,6.980825737880539918e+02,4.986783341516727863e-01,1.100000010988609489e+01,6.810462668322544641e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.884948158787068451e+01,6.980925737857348850e+02,4.986851446138146349e-01,1.100000010988609489e+01,6.809002814307167466e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885039067877069385e+01,6.981025737834168012e+02,4.986919536161028010e-01,1.100000010988609489e+01,6.807542960291790290e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885129976967070320e+01,6.981125737810996270e+02,4.986987611585372848e-01,1.100000010988609489e+01,6.806083106276413115e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885220886057071255e+01,6.981225737787834760e+02,4.987055672411180862e-01,1.100000010988609489e+01,6.804623252261035940e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885311795147072189e+01,6.981325737764683481e+02,4.987123718638452052e-01,1.100000010988609489e+01,6.803163398245658765e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885402704237073124e+01,6.981425737741542434e+02,4.987191750267186419e-01,1.100000010988609489e+01,6.801703544230281590e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885493613327074058e+01,6.981525737718410483e+02,4.987259767297384516e-01,1.100000010988609489e+01,6.800243690214904414e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885584522417074993e+01,6.981625737695288763e+02,4.987327769729045790e-01,1.100000010988609489e+01,6.798783836199527239e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885675431507075928e+01,6.981725737672177274e+02,4.987395757562170240e-01,1.100000010988609489e+01,6.797323982184150064e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885766340597076862e+01,6.981825737649076018e+02,4.987463730796757866e-01,1.100000010988609489e+01,6.795864128168772889e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885857249687077797e+01,6.981925737625983857e+02,4.987531689432808668e-01,1.100000010988609489e+01,6.794404274153395713e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.885948158777078731e+01,6.982025737602901927e+02,4.987599633470322646e-01,1.100000010988609489e+01,6.792944420138018538e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886039067867079666e+01,6.982125737579830229e+02,4.987667562909299801e-01,1.100000010988609489e+01,6.791484566122641363e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886129976957080601e+01,6.982225737556767626e+02,4.987735477749740132e-01,1.100000010988609489e+01,6.790024712107264188e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886220886047081535e+01,6.982325737533715255e+02,4.987803377991643639e-01,1.100000010988609489e+01,6.788564858091887012e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886311795137082470e+01,6.982425737510673116e+02,4.987871263635010322e-01,1.100000010988609489e+01,6.787105004076509837e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886402704227083404e+01,6.982525737487641209e+02,4.987939134679840181e-01,1.100000010988609489e+01,6.785645150061132662e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886493613317084339e+01,6.982625737464618396e+02,4.988006991126133216e-01,1.100000010988609489e+01,6.784185296045755487e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886584522407085274e+01,6.982725737441605816e+02,4.988074832973889428e-01,1.100000010988609489e+01,6.782725442030378311e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886675431497086208e+01,6.982825737418603467e+02,4.988142660223108815e-01,1.100000010988609489e+01,6.781265588015001136e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886766340587087143e+01,6.982925737395610213e+02,4.988210472873791379e-01,1.100000010988609489e+01,6.779805733999623961e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886857249677088078e+01,6.983025737372627191e+02,4.988278270925937119e-01,1.100000010988609489e+01,6.778345879984246786e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.886948158767089012e+01,6.983125737349654401e+02,4.988346054379546590e-01,1.100000010988609489e+01,6.776886025968869610e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887039067857089947e+01,6.983225737326691842e+02,4.988413823234619238e-01,1.100000010988609489e+01,6.775426171953492435e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887129976947090881e+01,6.983325737303738379e+02,4.988481577491155061e-01,1.100000010988609489e+01,6.773966317938115260e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887220886037091816e+01,6.983425737280795147e+02,4.988549317149154061e-01,1.100000010988609489e+01,6.772506463922738085e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887311795127092751e+01,6.983525737257862147e+02,4.988617042208616237e-01,1.100000010988609489e+01,6.771046609907360909e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887402704217093685e+01,6.983625737234938242e+02,4.988684752669541589e-01,1.100000010988609489e+01,6.769586755891983734e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887493613307094620e+01,6.983725737212024569e+02,4.988752448531930117e-01,1.100000010988609489e+01,6.768126901876606559e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887584522397095554e+01,6.983825737189121128e+02,4.988820129795781821e-01,1.100000010988609489e+01,6.766667047861229384e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887675431487096489e+01,6.983925737166226781e+02,4.988887796461096702e-01,1.100000010988609489e+01,6.765207193845852209e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887766340577097424e+01,6.984025737143342667e+02,4.988955448527874759e-01,1.100000010988609489e+01,6.763747339830475033e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887857249667098358e+01,6.984125737120468784e+02,4.989023085996115991e-01,1.100000010988609489e+01,6.762287485815097858e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.887948158757099293e+01,6.984225737097603997e+02,4.989090708865820400e-01,1.100000010988609489e+01,6.760827631799720683e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888039067847100227e+01,6.984325737074749441e+02,4.989158317136987986e-01,1.100000010988609489e+01,6.759367777784343508e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888129976937101162e+01,6.984425737051905116e+02,4.989225910809618747e-01,1.100000010988609489e+01,6.757907923768966332e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888220886027102097e+01,6.984525737029071024e+02,4.989293489883712684e-01,1.100000010988609489e+01,6.756448069753589157e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888311795117103031e+01,6.984625737006246027e+02,4.989361054359269798e-01,1.100000010988609489e+01,6.754988215738211982e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888402704207103966e+01,6.984725736983431261e+02,4.989428604236290088e-01,1.100000010988609489e+01,6.753528361722834807e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888493613297104901e+01,6.984825736960626728e+02,4.989496139514773554e-01,1.100000010988609489e+01,6.752068507707457631e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888584522387105835e+01,6.984925736937831289e+02,4.989563660194720196e-01,1.100000010988609489e+01,6.750608653692080456e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888675431477106770e+01,6.985025736915046082e+02,4.989631166276130014e-01,1.100000010988609489e+01,6.749148799676703281e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888766340567107704e+01,6.985125736892271107e+02,4.989698657759003009e-01,1.100000010988609489e+01,6.747688945661326106e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888857249657108639e+01,6.985225736869505226e+02,4.989766134643339179e-01,1.100000010988609489e+01,6.746229091645948930e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.888948158747109574e+01,6.985325736846749578e+02,4.989833596929138526e-01,1.100000010988609489e+01,6.744769237630571755e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889039067837110508e+01,6.985425736824004161e+02,4.989901044616401049e-01,1.100000010988609489e+01,6.743309383615194580e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889129976927111443e+01,6.985525736801267840e+02,4.989968477705126748e-01,1.100000010988609489e+01,6.741849529599817405e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889220886017112377e+01,6.985625736778541750e+02,4.990035896195315623e-01,1.100000010988609489e+01,6.740389675584440229e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889311795107113312e+01,6.985725736755825892e+02,4.990103300086967675e-01,1.100000010988609489e+01,6.738929821569063054e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889402704197114247e+01,6.985825736733119129e+02,4.990170689380082902e-01,1.100000010988609489e+01,6.737469967553685879e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889493613287115181e+01,6.985925736710422598e+02,4.990238064074661306e-01,1.100000010988609489e+01,6.736010113538308704e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889584522377116116e+01,6.986025736687735161e+02,4.990305424170702886e-01,1.100000010988609489e+01,6.734550259522931528e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889675431467117050e+01,6.986125736665057957e+02,4.990372769668207642e-01,1.100000010988609489e+01,6.733090405507554353e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889766340557117985e+01,6.986225736642390984e+02,4.990440100567175574e-01,1.100000010988609489e+01,6.731630551492177178e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889857249647118920e+01,6.986325736619733107e+02,4.990507416867606683e-01,1.100000010988609489e+01,6.730170697476800003e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.889948158737119854e+01,6.986425736597085461e+02,4.990574718569500967e-01,1.100000010988609489e+01,6.728710843461422828e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890039067827120789e+01,6.986525736574448047e+02,4.990642005672857873e-01,1.100000010988609489e+01,6.727250989446045652e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890129976917121724e+01,6.986625736551819728e+02,4.990709278177677954e-01,1.100000010988609489e+01,6.725791135430668477e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890220886007122658e+01,6.986725736529201640e+02,4.990776536083961212e-01,1.100000010988609489e+01,6.724331281415291302e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890311795097123593e+01,6.986825736506593785e+02,4.990843779391707646e-01,1.100000010988609489e+01,6.722871427399914127e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890402704187124527e+01,6.986925736483995024e+02,4.990911008100917257e-01,1.100000010988609489e+01,6.721411573384536951e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890493613277125462e+01,6.987025736461406495e+02,4.990978222211590043e-01,1.100000010988609489e+01,6.719951719369159776e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890584522367126397e+01,6.987125736438827062e+02,4.991045421723726006e-01,1.100000010988609489e+01,6.718491865353782601e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890675431457127331e+01,6.987225736416257860e+02,4.991112606637325144e-01,1.100000010988609489e+01,6.717032011338405426e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890766340547128266e+01,6.987325736393698890e+02,4.991179776952387459e-01,1.100000010988609489e+01,6.715572157323028250e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890857249637129200e+01,6.987425736371149014e+02,4.991246932668912950e-01,1.100000010988609489e+01,6.714112303307651075e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.890948158727130135e+01,6.987525736348609371e+02,4.991314073786901617e-01,1.100000010988609489e+01,6.712652449292273900e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891039067817131070e+01,6.987625736326079959e+02,4.991381200306353461e-01,1.100000010988609489e+01,6.711192595276896725e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891129976907132004e+01,6.987725736303559643e+02,4.991448312227268480e-01,1.100000010988609489e+01,6.709732741261519549e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891220885997132939e+01,6.987825736281049558e+02,4.991515409549646676e-01,1.100000010988609489e+01,6.708272887246142374e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891311795087133873e+01,6.987925736258548568e+02,4.991582492273488048e-01,1.100000010988609489e+01,6.706813033230765199e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891402704177134808e+01,6.988025736236057810e+02,4.991649560398792596e-01,1.100000010988609489e+01,6.705353179215388024e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891493613267135743e+01,6.988125736213577284e+02,4.991716613925559765e-01,1.100000010988609489e+01,6.703893325200010848e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891584522357136677e+01,6.988225736191105852e+02,4.991783652853790110e-01,1.100000010988609489e+01,6.702433471184633673e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891675431447137612e+01,6.988325736168644653e+02,4.991850677183483631e-01,1.100000010988609489e+01,6.700973617169256498e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891766340537138547e+01,6.988425736146193685e+02,4.991917686914640329e-01,1.100000010988609489e+01,6.699513763153879323e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891857249627139481e+01,6.988525736123751813e+02,4.991984682047260202e-01,1.100000010988609489e+01,6.698053909138502147e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.891948158717140416e+01,6.988625736101320172e+02,4.992051662581343252e-01,1.100000010988609489e+01,6.696594055123124972e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892039067807141350e+01,6.988725736078897626e+02,4.992118628516889478e-01,1.100000010988609489e+01,6.695134201107747797e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892129976897142285e+01,6.988825736056485312e+02,4.992185579853898880e-01,1.100000010988609489e+01,6.693674347092370622e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892220885987143220e+01,6.988925736034083229e+02,4.992252516592371459e-01,1.100000010988609489e+01,6.692214493076993446e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892311795077144154e+01,6.989025736011690242e+02,4.992319438732307213e-01,1.100000010988609489e+01,6.690754639061616271e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892402704167145089e+01,6.989125735989307486e+02,4.992386346273705588e-01,1.100000010988609489e+01,6.689294785046239096e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892493613257146023e+01,6.989225735966933826e+02,4.992453239216567140e-01,1.100000010988609489e+01,6.687834931030861921e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892584522347146958e+01,6.989325735944570397e+02,4.992520117560891868e-01,1.100000010988609489e+01,6.686375077015484746e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892675431437147893e+01,6.989425735922216063e+02,4.992586981306679772e-01,1.100000010988609489e+01,6.684915223000107570e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892766340527148827e+01,6.989525735899871961e+02,4.992653830453930852e-01,1.100000010988609489e+01,6.683455368984730395e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892857249617149762e+01,6.989625735877538091e+02,4.992720665002645108e-01,1.100000010988609489e+01,6.681995514969353220e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.892948158707150697e+01,6.989725735855213316e+02,4.992787484952822541e-01,1.100000010988609489e+01,6.680535660953976045e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893039067797151631e+01,6.989825735832898772e+02,4.992854290304463150e-01,1.100000010988609489e+01,6.679075806938598869e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893129976887152566e+01,6.989925735810593324e+02,4.992921081057566379e-01,1.100000010988609489e+01,6.677615952923221694e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893220885977153500e+01,6.990025735788298107e+02,4.992987857212132785e-01,1.100000010988609489e+01,6.676156098907844519e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893311795067154435e+01,6.990125735766013122e+02,4.993054618768162367e-01,1.100000010988609489e+01,6.674696244892467344e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893402704157155370e+01,6.990225735743737232e+02,4.993121365725655125e-01,1.100000010988609489e+01,6.673236390877090168e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893493613247156304e+01,6.990325735721471574e+02,4.993188098084611060e-01,1.100000010988609489e+01,6.671776536861712993e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893584522337157239e+01,6.990425735699215011e+02,4.993254815845030170e-01,1.100000010988609489e+01,6.670316682846335818e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893675431427158173e+01,6.990525735676968679e+02,4.993321519006912457e-01,1.100000010988609489e+01,6.668856828830958643e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893766340517159108e+01,6.990625735654731443e+02,4.993388207570257364e-01,1.100000010988609489e+01,6.667396974815581467e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893857249607160043e+01,6.990725735632504438e+02,4.993454881535065448e-01,1.100000010988609489e+01,6.665937120800204292e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.893948158697160977e+01,6.990825735610286529e+02,4.993521540901336708e-01,1.100000010988609489e+01,6.664477266784827117e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894039067787161912e+01,6.990925735588078851e+02,4.993588185669071144e-01,1.100000010988609489e+01,6.663017412769449942e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894129976877162846e+01,6.991025735565881405e+02,4.993654815838268757e-01,1.100000010988609489e+01,6.661557558754072766e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894220885967163781e+01,6.991125735543693054e+02,4.993721431408929545e-01,1.100000010988609489e+01,6.660097704738695591e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894311795057164716e+01,6.991225735521514935e+02,4.993788032381053510e-01,1.100000010988609489e+01,6.658637850723318416e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894402704147165650e+01,6.991325735499345910e+02,4.993854618754640096e-01,1.100000010988609489e+01,6.657177996707941241e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894493613237166585e+01,6.991425735477187118e+02,4.993921190529689857e-01,1.100000010988609489e+01,6.655718142692564065e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894584522327167520e+01,6.991525735455037420e+02,4.993987747706202796e-01,1.100000010988609489e+01,6.654258288677186890e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894675431417168454e+01,6.991625735432897955e+02,4.994054290284178910e-01,1.100000010988609489e+01,6.652798434661809715e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894766340507169389e+01,6.991725735410767584e+02,4.994120818263618200e-01,1.100000010988609489e+01,6.651338580646432540e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894857249597170323e+01,6.991825735388647445e+02,4.994187331644520111e-01,1.100000010988609489e+01,6.649878726631055365e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.894948158687171258e+01,6.991925735366537538e+02,4.994253830426885199e-01,1.100000010988609489e+01,6.648418872615678189e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895039067777172193e+01,6.992025735344436725e+02,4.994320314610713463e-01,1.100000010988609489e+01,6.646959018600301014e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895129976867173127e+01,6.992125735322346145e+02,4.994386784196004903e-01,1.100000010988609489e+01,6.645499164584923839e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895220885957174062e+01,6.992225735300264660e+02,4.994453239182759519e-01,1.100000010988609489e+01,6.644039310569546664e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895311795047174996e+01,6.992325735278193406e+02,4.994519679570977311e-01,1.100000010988609489e+01,6.642579456554169488e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895402704137175931e+01,6.992425735256131247e+02,4.994586105360657724e-01,1.100000010988609489e+01,6.641119602538792313e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895493613227176866e+01,6.992525735234079320e+02,4.994652516551801313e-01,1.100000010988609489e+01,6.639659748523415138e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895584522317177800e+01,6.992625735212036489e+02,4.994718913144408079e-01,1.100000010988609489e+01,6.638199894508037963e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895675431407178735e+01,6.992725735190003888e+02,4.994785295138478021e-01,1.100000010988609489e+01,6.636740040492660787e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895766340497179669e+01,6.992825735167980383e+02,4.994851662534011139e-01,1.100000010988609489e+01,6.635280186477283612e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895857249587180604e+01,6.992925735145967110e+02,4.994918015331006877e-01,1.100000010988609489e+01,6.633820332461906437e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.895948158677181539e+01,6.993025735123962932e+02,4.994984353529465793e-01,1.100000010988609489e+01,6.632360478446529262e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896039067767182473e+01,6.993125735101968985e+02,4.995050677129387884e-01,1.100000010988609489e+01,6.630900624431152086e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896129976857183408e+01,6.993225735079984133e+02,4.995116986130773151e-01,1.100000010988609489e+01,6.629440770415774911e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896220885947184343e+01,6.993325735058009514e+02,4.995183280533621040e-01,1.100000010988609489e+01,6.627980916400397736e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896311795037185277e+01,6.993425735036043989e+02,4.995249560337932104e-01,1.100000010988609489e+01,6.626521062385020561e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896402704127186212e+01,6.993525735014088696e+02,4.995315825543706345e-01,1.100000010988609489e+01,6.625061208369643385e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896493613217187146e+01,6.993625734992142498e+02,4.995382076150943762e-01,1.100000010988609489e+01,6.623601354354266210e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896584522307188081e+01,6.993725734970206531e+02,4.995448312159644355e-01,1.100000010988609489e+01,6.622141500338889035e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896675431397189016e+01,6.993825734948279660e+02,4.995514533569807569e-01,1.100000010988609489e+01,6.620681646323511860e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896766340487189950e+01,6.993925734926363020e+02,4.995580740381433960e-01,1.100000010988609489e+01,6.619221792308134684e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896857249577190885e+01,6.994025734904455476e+02,4.995646932594523526e-01,1.100000010988609489e+01,6.617761938292757509e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.896948158667191819e+01,6.994125734882558163e+02,4.995713110209076269e-01,1.100000010988609489e+01,6.616302084277380334e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897039067757192754e+01,6.994225734860669945e+02,4.995779273225091632e-01,1.100000010988609489e+01,6.614842230262003159e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897129976847193689e+01,6.994325734838791959e+02,4.995845421642570172e-01,1.100000010988609489e+01,6.613382376246625984e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897220885937194623e+01,6.994425734816923068e+02,4.995911555461511888e-01,1.100000010988609489e+01,6.611922522231248808e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897311795027195558e+01,6.994525734795064409e+02,4.995977674681916780e-01,1.100000010988609489e+01,6.610462668215871633e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897402704117196492e+01,6.994625734773214845e+02,4.996043779303784294e-01,1.100000010988609489e+01,6.609002814200494458e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897493613207197427e+01,6.994725734751375512e+02,4.996109869327114983e-01,1.100000010988609489e+01,6.607542960185117283e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897584522297198362e+01,6.994825734729545275e+02,4.996175944751908848e-01,1.100000010988609489e+01,6.606083106169740107e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897675431387199296e+01,6.994925734707725269e+02,4.996242005578165890e-01,1.100000010988609489e+01,6.604623252154362932e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897766340477200231e+01,6.995025734685914358e+02,4.996308051805885553e-01,1.100000010988609489e+01,6.603163398138985757e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897857249567201166e+01,6.995125734664113679e+02,4.996374083435068392e-01,1.100000010988609489e+01,6.601703544123608582e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.897948158657202100e+01,6.995225734642322095e+02,4.996440100465714407e-01,1.100000010988609489e+01,6.600243690108231406e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898039067747203035e+01,6.995325734620540743e+02,4.996506102897823598e-01,1.100000010988609489e+01,6.598783836092854231e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898129976837203969e+01,6.995425734598768486e+02,4.996572090731395410e-01,1.100000010988609489e+01,6.597323982077477056e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898220885927204904e+01,6.995525734577006460e+02,4.996638063966430399e-01,1.100000010988609489e+01,6.595864128062099881e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898311795017205839e+01,6.995625734555253530e+02,4.996704022602928563e-01,1.100000010988609489e+01,6.594404274046722705e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898402704107206773e+01,6.995725734533510831e+02,4.996769966640889349e-01,1.100000010988609489e+01,6.592944420031345530e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898493613197207708e+01,6.995825734511777227e+02,4.996835896080313311e-01,1.100000010988609489e+01,6.591484566015968355e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898584522287208642e+01,6.995925734490053856e+02,4.996901810921200449e-01,1.100000010988609489e+01,6.590024712000591180e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898675431377209577e+01,6.996025734468339579e+02,4.996967711163550763e-01,1.100000010988609489e+01,6.588564857985214004e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898766340467210512e+01,6.996125734446635533e+02,4.997033596807363698e-01,1.100000010988609489e+01,6.587105003969836829e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898857249557211446e+01,6.996225734424940583e+02,4.997099467852639809e-01,1.100000010988609489e+01,6.585645149954459654e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.898948158647212381e+01,6.996325734403254728e+02,4.997165324299379097e-01,1.100000010988609489e+01,6.584185295939082479e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899039067737213315e+01,6.996425734381579105e+02,4.997231166147581005e-01,1.100000010988609489e+01,6.582725441923705303e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899129976827214250e+01,6.996525734359912576e+02,4.997296993397246090e-01,1.100000010988609489e+01,6.581265587908328128e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899220885917215185e+01,6.996625734338256279e+02,4.997362806048374351e-01,1.100000010988609489e+01,6.579805733892950953e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899311795007216119e+01,6.996725734316609078e+02,4.997428604100965788e-01,1.100000010988609489e+01,6.578345879877573778e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899402704097217054e+01,6.996825734294972108e+02,4.997494387555019846e-01,1.100000010988609489e+01,6.576886025862196603e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899493613187217989e+01,6.996925734273344233e+02,4.997560156410537080e-01,1.100000010988609489e+01,6.575426171846819427e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899584522277218923e+01,6.997025734251726590e+02,4.997625910667517490e-01,1.100000010988609489e+01,6.573966317831442252e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899675431367219858e+01,6.997125734230118042e+02,4.997691650325960522e-01,1.100000010988609489e+01,6.572506463816065077e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899766340457220792e+01,6.997225734208518588e+02,4.997757375385866729e-01,1.100000010988609489e+01,6.571046609800687902e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899857249547221727e+01,6.997325734186929367e+02,4.997823085847236113e-01,1.100000010988609489e+01,6.569586755785310726e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.899948158637222662e+01,6.997425734165349240e+02,4.997888781710068118e-01,1.100000010988609489e+01,6.568126901769933551e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900039067727223596e+01,6.997525734143779346e+02,4.997954462974363299e-01,1.100000010988609489e+01,6.566667047754556376e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900129976817224531e+01,6.997625734122218546e+02,4.998020129640121656e-01,1.100000010988609489e+01,6.565207193739179201e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900220885907225465e+01,6.997725734100667978e+02,4.998085781707342634e-01,1.100000010988609489e+01,6.563747339723802025e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900311794997226400e+01,6.997825734079126505e+02,4.998151419176026788e-01,1.100000010988609489e+01,6.562287485708424850e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900402704087227335e+01,6.997925734057595264e+02,4.998217042046174119e-01,1.100000010988609489e+01,6.560827631693047675e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900493613177228269e+01,6.998025734036073118e+02,4.998282650317784070e-01,1.100000010988609489e+01,6.559367777677670500e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900584522267229204e+01,6.998125734014560066e+02,4.998348243990857198e-01,1.100000010988609489e+01,6.557907923662293324e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900675431357230138e+01,6.998225733993057247e+02,4.998413823065393502e-01,1.100000010988609489e+01,6.556448069646916149e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900766340447231073e+01,6.998325733971563523e+02,4.998479387541392427e-01,1.100000010988609489e+01,6.554988215631538974e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900857249537232008e+01,6.998425733950080030e+02,4.998544937418854528e-01,1.100000010988609489e+01,6.553528361616161799e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.900948158627232942e+01,6.998525733928605632e+02,4.998610472697779805e-01,1.100000010988609489e+01,6.552068507600784623e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901039067717233877e+01,6.998625733907140329e+02,4.998675993378167703e-01,1.100000010988609489e+01,6.550608653585407448e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901129976807234812e+01,6.998725733885685258e+02,4.998741499460018778e-01,1.100000010988609489e+01,6.549148799570030273e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901220885897235746e+01,6.998825733864239282e+02,4.998806990943333028e-01,1.100000010988609489e+01,6.547688945554653098e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901311794987236681e+01,6.998925733842803538e+02,4.998872467828109900e-01,1.100000010988609489e+01,6.546229091539275922e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901402704077237615e+01,6.999025733821376889e+02,4.998937930114349948e-01,1.100000010988609489e+01,6.544769237523898747e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901493613167238550e+01,6.999125733799959335e+02,4.999003377802052617e-01,1.100000010988609489e+01,6.543309383508521572e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901584522257239485e+01,6.999225733778552012e+02,4.999068810891218462e-01,1.100000010988609489e+01,6.541849529493144397e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901675431347240419e+01,6.999325733757153785e+02,4.999134229381847483e-01,1.100000010988609489e+01,6.540389675477767222e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901766340437241354e+01,6.999425733735765789e+02,4.999199633273939125e-01,1.100000010988609489e+01,6.538929821462390046e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901857249527242288e+01,6.999525733714386888e+02,4.999265022567493943e-01,1.100000010988609489e+01,6.537469967447012871e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.901948158617243223e+01,6.999625733693017082e+02,4.999330397262511938e-01,1.100000010988609489e+01,6.536010113431635696e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902039067707244158e+01,6.999725733671657508e+02,4.999395757358992554e-01,1.100000010988609489e+01,6.534550259416258521e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902129976797245092e+01,6.999825733650307029e+02,4.999461102856936345e-01,1.100000010988609489e+01,6.533090405400881345e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902220885887246027e+01,6.999925733628966782e+02,4.999526433756342758e-01,1.100000010988609489e+01,6.531630551385504170e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902311794977246961e+01,7.000025733607635630e+02,4.999591750057212347e-01,1.100000010988609489e+01,6.530170697370126995e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902402704067247896e+01,7.000125733586313572e+02,4.999657051759545112e-01,1.100000010988609489e+01,6.528710843354749820e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902493613157248831e+01,7.000225733565001747e+02,4.999722338863340498e-01,1.100000010988609489e+01,6.527250989339372644e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902584522247249765e+01,7.000325733543699016e+02,4.999787611368599061e-01,1.100000010988609489e+01,6.525791135323995469e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902675431337250700e+01,7.000425733522406517e+02,4.999852869275320244e-01,1.100000010988609489e+01,6.524331281308618294e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902766340427251635e+01,7.000525733501123113e+02,4.999918112583504604e-01,1.100000010988609489e+01,6.522871427293241119e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902857249517252569e+01,7.000625733479848805e+02,4.999983341293152139e-01,1.100000010988609489e+01,6.521411573277863943e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.902948158607253504e+01,7.000725733458584727e+02,5.000048555404262851e-01,1.100000010988609489e+01,6.519951719262486768e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903039067697254438e+01,7.000825733437329745e+02,5.000113754916836184e-01,1.100000010988609489e+01,6.518491865247109593e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903129976787255373e+01,7.000925733416083858e+02,5.000178939830872693e-01,1.100000010988609489e+01,6.517032011231732418e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903220885877256308e+01,7.001025733394848203e+02,5.000244110146372378e-01,1.100000010988609489e+01,6.515572157216355242e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903311794967257242e+01,7.001125733373621642e+02,5.000309265863334129e-01,1.100000010988609489e+01,6.514112303200978067e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903402704057258177e+01,7.001225733352405314e+02,5.000374406981759057e-01,1.100000010988609489e+01,6.512652449185600892e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903493613147259111e+01,7.001325733331198080e+02,5.000439533501647160e-01,1.100000010988609489e+01,6.511192595170223717e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903584522237260046e+01,7.001425733309999941e+02,5.000504645422998440e-01,1.100000010988609489e+01,6.509732741154846541e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903675431327260981e+01,7.001525733288812035e+02,5.000569742745811785e-01,1.100000010988609489e+01,6.508272887139469366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903766340417261915e+01,7.001625733267633223e+02,5.000634825470088307e-01,1.100000010988609489e+01,6.506813033124092191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903857249507262850e+01,7.001725733246463506e+02,5.000699893595828005e-01,1.100000010988609489e+01,6.505353179108715016e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.903948158597263784e+01,7.001825733225304020e+02,5.000764947123030879e-01,1.100000010988609489e+01,6.503893325093337840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904039067687264719e+01,7.001925733204153630e+02,5.000829986051696929e-01,1.100000010988609489e+01,6.502433471077960665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904129976777265654e+01,7.002025733183012335e+02,5.000895010381825045e-01,1.100000010988609489e+01,6.500973617062583490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904220885867266588e+01,7.002125733161881271e+02,5.000960020113416338e-01,1.100000010988609489e+01,6.499513763047206315e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904311794957267523e+01,7.002225733140759303e+02,5.001025015246470806e-01,1.100000010988609489e+01,6.498053909031829140e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904402704047268458e+01,7.002325733119646429e+02,5.001089995780988451e-01,1.100000010988609489e+01,6.496594055016451964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904493613137269392e+01,7.002425733098543787e+02,5.001154961716969272e-01,1.100000010988609489e+01,6.495134201001074789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904584522227270327e+01,7.002525733077450241e+02,5.001219913054412158e-01,1.100000010988609489e+01,6.493674346985697614e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904675431317271261e+01,7.002625733056365789e+02,5.001284849793318221e-01,1.100000010988609489e+01,6.492214492970320439e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904766340407272196e+01,7.002725733035291569e+02,5.001349771933687460e-01,1.100000010988609489e+01,6.490754638954943263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904857249497273131e+01,7.002825733014226444e+02,5.001414679475519875e-01,1.100000010988609489e+01,6.489294784939566088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.904948158587274065e+01,7.002925732993170413e+02,5.001479572418814357e-01,1.100000010988609489e+01,6.487834930924188913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905039067677275000e+01,7.003025732972124615e+02,5.001544450763572014e-01,1.100000010988609489e+01,6.486375076908811738e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905129976767275934e+01,7.003125732951087912e+02,5.001609314509792847e-01,1.100000010988609489e+01,6.484915222893434562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905220885857276869e+01,7.003225732930060303e+02,5.001674163657476857e-01,1.100000010988609489e+01,6.483455368878057387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905311794947277804e+01,7.003325732909042927e+02,5.001738998206622933e-01,1.100000010988609489e+01,6.481995514862680212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905402704037278738e+01,7.003425732888034645e+02,5.001803818157232184e-01,1.100000010988609489e+01,6.480535660847303037e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905493613127279673e+01,7.003525732867035458e+02,5.001868623509304612e-01,1.100000010988609489e+01,6.479075806831925861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905584522217280607e+01,7.003625732846046503e+02,5.001933414262840216e-01,1.100000010988609489e+01,6.477615952816548686e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905675431307281542e+01,7.003725732825066643e+02,5.001998190417837886e-01,1.100000010988609489e+01,6.476156098801171511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905766340397282477e+01,7.003825732804095878e+02,5.002062951974298732e-01,1.100000010988609489e+01,6.474696244785794336e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905857249487283411e+01,7.003925732783135345e+02,5.002127698932222755e-01,1.100000010988609489e+01,6.473236390770417160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.905948158577284346e+01,7.004025732762183907e+02,5.002192431291609953e-01,1.100000010988609489e+01,6.471776536755039985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906039067667285281e+01,7.004125732741241563e+02,5.002257149052460328e-01,1.100000010988609489e+01,6.470316682739662810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906129976757286215e+01,7.004225732720309452e+02,5.002321852214772768e-01,1.100000010988609489e+01,6.468856828724285635e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906220885847287150e+01,7.004325732699386435e+02,5.002386540778548385e-01,1.100000010988609489e+01,6.467396974708908459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906311794937288084e+01,7.004425732678472514e+02,5.002451214743787178e-01,1.100000010988609489e+01,6.465937120693531284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906402704027289019e+01,7.004525732657568824e+02,5.002515874110489147e-01,1.100000010988609489e+01,6.464477266678154109e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906493613117289954e+01,7.004625732636674229e+02,5.002580518878653182e-01,1.100000010988609489e+01,6.463017412662776934e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906584522207290888e+01,7.004725732615788729e+02,5.002645149048280393e-01,1.100000010988609489e+01,6.461557558647399759e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906675431297291823e+01,7.004825732594912324e+02,5.002709764619370780e-01,1.100000010988609489e+01,6.460097704632022583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906766340387292757e+01,7.004925732574046151e+02,5.002774365591924344e-01,1.100000010988609489e+01,6.458637850616645408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906857249477293692e+01,7.005025732553189073e+02,5.002838951965939973e-01,1.100000010988609489e+01,6.457177996601268233e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.906948158567294627e+01,7.005125732532341090e+02,5.002903523741418779e-01,1.100000010988609489e+01,6.455718142585891058e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907039067657295561e+01,7.005225732511503338e+02,5.002968080918360760e-01,1.100000010988609489e+01,6.454258288570513882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907129976747296496e+01,7.005325732490674682e+02,5.003032623496764808e-01,1.100000010988609489e+01,6.452798434555136707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907220885837297430e+01,7.005425732469855120e+02,5.003097151476632032e-01,1.100000010988609489e+01,6.451338580539759532e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907311794927298365e+01,7.005525732449045790e+02,5.003161664857962432e-01,1.100000010988609489e+01,6.449878726524382357e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907402704017299300e+01,7.005625732428245556e+02,5.003226163640756008e-01,1.100000010988609489e+01,6.448418872509005181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907493613107300234e+01,7.005725732407454416e+02,5.003290647825011650e-01,1.100000010988609489e+01,6.446959018493628006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907584522197301169e+01,7.005825732386672371e+02,5.003355117410730468e-01,1.100000010988609489e+01,6.445499164478250831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907675431287302104e+01,7.005925732365900558e+02,5.003419572397912463e-01,1.100000010988609489e+01,6.444039310462873656e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907766340377303038e+01,7.006025732345137840e+02,5.003484012786557633e-01,1.100000010988609489e+01,6.442579456447496480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907857249467303973e+01,7.006125732324384217e+02,5.003548438576664870e-01,1.100000010988609489e+01,6.441119602432119305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.907948158557304907e+01,7.006225732303639688e+02,5.003612849768235282e-01,1.100000010988609489e+01,6.439659748416742130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908039067647305842e+01,7.006325732282905392e+02,5.003677246361268871e-01,1.100000010988609489e+01,6.438199894401364955e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908129976737306777e+01,7.006425732262180190e+02,5.003741628355765636e-01,1.100000010988609489e+01,6.436740040385987779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908220885827307711e+01,7.006525732241464084e+02,5.003805995751724467e-01,1.100000010988609489e+01,6.435280186370610604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908311794917308646e+01,7.006625732220758209e+02,5.003870348549146474e-01,1.100000010988609489e+01,6.433820332355233429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908402704007309580e+01,7.006725732200061429e+02,5.003934686748031657e-01,1.100000010988609489e+01,6.432360478339856254e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908493613097310515e+01,7.006825732179373745e+02,5.003999010348378906e-01,1.100000010988609489e+01,6.430900624324479078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908584522187311450e+01,7.006925732158695155e+02,5.004063319350189332e-01,1.100000010988609489e+01,6.429440770309101903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908675431277312384e+01,7.007025732138026797e+02,5.004127613753462933e-01,1.100000010988609489e+01,6.427980916293724728e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908766340367313319e+01,7.007125732117367534e+02,5.004191893558199711e-01,1.100000010988609489e+01,6.426521062278347553e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908857249457314254e+01,7.007225732096717365e+02,5.004256158764398554e-01,1.100000010988609489e+01,6.425061208262970378e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.908948158547315188e+01,7.007325732076076292e+02,5.004320409372060574e-01,1.100000010988609489e+01,6.423601354247593202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909039067637316123e+01,7.007425732055445451e+02,5.004384645381185770e-01,1.100000010988609489e+01,6.422141500232216027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909129976727317057e+01,7.007525732034823704e+02,5.004448866791773032e-01,1.100000010988609489e+01,6.420681646216838852e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909220885817317992e+01,7.007625732014211053e+02,5.004513073603823470e-01,1.100000010988609489e+01,6.419221792201461677e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909311794907318927e+01,7.007725731993607496e+02,5.004577265817337084e-01,1.100000010988609489e+01,6.417761938186084501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909402703997319861e+01,7.007825731973014172e+02,5.004641443432313874e-01,1.100000010988609489e+01,6.416302084170707326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909493613087320796e+01,7.007925731952429942e+02,5.004705606448752730e-01,1.100000010988609489e+01,6.414842230155330151e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909584522177321730e+01,7.008025731931854807e+02,5.004769754866654763e-01,1.100000010988609489e+01,6.413382376139952976e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909675431267322665e+01,7.008125731911288767e+02,5.004833888686019971e-01,1.100000010988609489e+01,6.411922522124575800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909766340357323600e+01,7.008225731890732959e+02,5.004898007906847246e-01,1.100000010988609489e+01,6.410462668109198625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909857249447324534e+01,7.008325731870186246e+02,5.004962112529137697e-01,1.100000010988609489e+01,6.409002814093821450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.909948158537325469e+01,7.008425731849648628e+02,5.005026202552891323e-01,1.100000010988609489e+01,6.407542960078444275e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910039067627326403e+01,7.008525731829120105e+02,5.005090277978108126e-01,1.100000010988609489e+01,6.406083106063067099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910129976717327338e+01,7.008625731808600676e+02,5.005154338804786995e-01,1.100000010988609489e+01,6.404623252047689924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910220885807328273e+01,7.008725731788091480e+02,5.005218385032929040e-01,1.100000010988609489e+01,6.403163398032312749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910311794897329207e+01,7.008825731767591378e+02,5.005282416662534262e-01,1.100000010988609489e+01,6.401703544016935574e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910402703987330142e+01,7.008925731747100372e+02,5.005346433693601549e-01,1.100000010988609489e+01,6.400243690001558398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910493613077331077e+01,7.009025731726618460e+02,5.005410436126132012e-01,1.100000010988609489e+01,6.398783835986181223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910584522167332011e+01,7.009125731706146780e+02,5.005474423960125652e-01,1.100000010988609489e+01,6.397323981970804048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910675431257332946e+01,7.009225731685684195e+02,5.005538397195581357e-01,1.100000010988609489e+01,6.395864127955426873e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910766340347333880e+01,7.009325731665230705e+02,5.005602355832500239e-01,1.100000010988609489e+01,6.394404273940049697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910857249437334815e+01,7.009425731644786310e+02,5.005666299870882296e-01,1.100000010988609489e+01,6.392944419924672522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.910948158527335750e+01,7.009525731624351010e+02,5.005730229310726420e-01,1.100000010988609489e+01,6.391484565909295347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911039067617336684e+01,7.009625731603925942e+02,5.005794144152033720e-01,1.100000010988609489e+01,6.390024711893918172e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911129976707337619e+01,7.009725731583509969e+02,5.005858044394804196e-01,1.100000010988609489e+01,6.388564857878540997e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911220885797338553e+01,7.009825731563103091e+02,5.005921930039036738e-01,1.100000010988609489e+01,6.387105003863163821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911311794887339488e+01,7.009925731542705307e+02,5.005985801084732456e-01,1.100000010988609489e+01,6.385645149847786646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911402703977340423e+01,7.010025731522316619e+02,5.006049657531891350e-01,1.100000010988609489e+01,6.384185295832409471e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911493613067341357e+01,7.010125731501938162e+02,5.006113499380513421e-01,1.100000010988609489e+01,6.382725441817032296e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911584522157342292e+01,7.010225731481568801e+02,5.006177326630597557e-01,1.100000010988609489e+01,6.381265587801655120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911675431247343226e+01,7.010325731461208534e+02,5.006241139282144870e-01,1.100000010988609489e+01,6.379805733786277945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911766340337344161e+01,7.010425731440857362e+02,5.006304937335155358e-01,1.100000010988609489e+01,6.378345879770900770e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911857249427345096e+01,7.010525731420515285e+02,5.006368720789627913e-01,1.100000010988609489e+01,6.376886025755523595e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.911948158517346030e+01,7.010625731400183440e+02,5.006432489645563644e-01,1.100000010988609489e+01,6.375426171740146419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912039067607346965e+01,7.010725731379860690e+02,5.006496243902962551e-01,1.100000010988609489e+01,6.373966317724769244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912129976697347900e+01,7.010825731359547035e+02,5.006559983561823524e-01,1.100000010988609489e+01,6.372506463709392069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912220885787348834e+01,7.010925731339242475e+02,5.006623708622147673e-01,1.100000010988609489e+01,6.371046609694014894e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912311794877349769e+01,7.011025731318947010e+02,5.006687419083934998e-01,1.100000010988609489e+01,6.369586755678637718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912402703967350703e+01,7.011125731298660639e+02,5.006751114947184389e-01,1.100000010988609489e+01,6.368126901663260543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912493613057351638e+01,7.011225731278384501e+02,5.006814796211896956e-01,1.100000010988609489e+01,6.366667047647883368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912584522147352573e+01,7.011325731258117457e+02,5.006878462878072700e-01,1.100000010988609489e+01,6.365207193632506193e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912675431237353507e+01,7.011425731237859509e+02,5.006942114945710509e-01,1.100000010988609489e+01,6.363747339617129017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912766340327354442e+01,7.011525731217610655e+02,5.007005752414811495e-01,1.100000010988609489e+01,6.362287485601751842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912857249417355376e+01,7.011625731197370897e+02,5.007069375285375656e-01,1.100000010988609489e+01,6.360827631586374667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.912948158507356311e+01,7.011725731177141370e+02,5.007132983557401884e-01,1.100000010988609489e+01,6.359367777570997492e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913039067597357246e+01,7.011825731156920938e+02,5.007196577230891288e-01,1.100000010988609489e+01,6.357907923555620316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913129976687358180e+01,7.011925731136709601e+02,5.007260156305843868e-01,1.100000010988609489e+01,6.356448069540243141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913220885777359115e+01,7.012025731116507359e+02,5.007323720782258514e-01,1.100000010988609489e+01,6.354988215524865966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913311794867360049e+01,7.012125731096314212e+02,5.007387270660136336e-01,1.100000010988609489e+01,6.353528361509488791e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913402703957360984e+01,7.012225731076130160e+02,5.007450805939477334e-01,1.100000010988609489e+01,6.352068507494111615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913493613047361919e+01,7.012325731055956339e+02,5.007514326620280398e-01,1.100000010988609489e+01,6.350608653478734440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913584522137362853e+01,7.012425731035791614e+02,5.007577832702546639e-01,1.100000010988609489e+01,6.349148799463357265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913675431227363788e+01,7.012525731015635984e+02,5.007641324186276055e-01,1.100000010988609489e+01,6.347688945447980090e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913766340317364723e+01,7.012625730995489448e+02,5.007704801071467537e-01,1.100000010988609489e+01,6.346229091432602915e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913857249407365657e+01,7.012725730975352008e+02,5.007768263358122196e-01,1.100000010988609489e+01,6.344769237417225739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.913948158497366592e+01,7.012825730955223662e+02,5.007831711046238921e-01,1.100000010988609489e+01,6.343309383401848564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914039067587367526e+01,7.012925730935104411e+02,5.007895144135818821e-01,1.100000010988609489e+01,6.341849529386471389e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914129976677368461e+01,7.013025730914995393e+02,5.007958562626861898e-01,1.100000010988609489e+01,6.340389675371094214e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914220885767369396e+01,7.013125730894895469e+02,5.008021966519367041e-01,1.100000010988609489e+01,6.338929821355717038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914311794857370330e+01,7.013225730874804640e+02,5.008085355813335360e-01,1.100000010988609489e+01,6.337469967340339863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914402703947371265e+01,7.013325730854722906e+02,5.008148730508766855e-01,1.100000010988609489e+01,6.336010113324962688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914493613037372199e+01,7.013425730834650267e+02,5.008212090605660416e-01,1.100000010988609489e+01,6.334550259309585513e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914584522127373134e+01,7.013525730814586723e+02,5.008275436104017153e-01,1.100000010988609489e+01,6.333090405294208337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914675431217374069e+01,7.013625730794532274e+02,5.008338767003837066e-01,1.100000010988609489e+01,6.331630551278831162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914766340307375003e+01,7.013725730774488056e+02,5.008402083305119046e-01,1.100000010988609489e+01,6.330170697263453987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914857249397375938e+01,7.013825730754452934e+02,5.008465385007864201e-01,1.100000010988609489e+01,6.328710843248076812e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.914948158487376872e+01,7.013925730734426907e+02,5.008528672112072533e-01,1.100000010988609489e+01,6.327250989232699636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915039067577377807e+01,7.014025730714409974e+02,5.008591944617742930e-01,1.100000010988609489e+01,6.325791135217322461e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915129976667378742e+01,7.014125730694402137e+02,5.008655202524876504e-01,1.100000010988609489e+01,6.324331281201945286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915220885757379676e+01,7.014225730674403394e+02,5.008718445833472144e-01,1.100000010988609489e+01,6.322871427186568111e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915311794847380611e+01,7.014325730654413746e+02,5.008781674543530960e-01,1.100000010988609489e+01,6.321411573171190935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915402703937381546e+01,7.014425730634433194e+02,5.008844888655052952e-01,1.100000010988609489e+01,6.319951719155813760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915493613027382480e+01,7.014525730614461736e+02,5.008908088168037009e-01,1.100000010988609489e+01,6.318491865140436585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915584522117383415e+01,7.014625730594500510e+02,5.008971273082484243e-01,1.100000010988609489e+01,6.317032011125059410e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915675431207384349e+01,7.014725730574548379e+02,5.009034443398394654e-01,1.100000010988609489e+01,6.315572157109682234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915766340297385284e+01,7.014825730554605343e+02,5.009097599115767130e-01,1.100000010988609489e+01,6.314112303094305059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915857249387386219e+01,7.014925730534671402e+02,5.009160740234602782e-01,1.100000010988609489e+01,6.312652449078927884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.915948158477387153e+01,7.015025730514746556e+02,5.009223866754900500e-01,1.100000010988609489e+01,6.311192595063550709e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916039067567388088e+01,7.015125730494830805e+02,5.009286978676661395e-01,1.100000010988609489e+01,6.309732741048173534e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916129976657389022e+01,7.015225730474924148e+02,5.009350075999885465e-01,1.100000010988609489e+01,6.308272887032796358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916220885747389957e+01,7.015325730455026587e+02,5.009413158724571602e-01,1.100000010988609489e+01,6.306813033017419183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916311794837390892e+01,7.015425730435138121e+02,5.009476226850720915e-01,1.100000010988609489e+01,6.305353179002042008e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916402703927391826e+01,7.015525730415259886e+02,5.009539280378333403e-01,1.100000010988609489e+01,6.303893324986664833e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916493613017392761e+01,7.015625730395390747e+02,5.009602319307407958e-01,1.100000010988609489e+01,6.302433470971287657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916584522107393695e+01,7.015725730375530702e+02,5.009665343637945689e-01,1.100000010988609489e+01,6.300973616955910482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916675431197394630e+01,7.015825730355679752e+02,5.009728353369945486e-01,1.100000010988609489e+01,6.299513762940533307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916766340287395565e+01,7.015925730335837898e+02,5.009791348503408459e-01,1.100000010988609489e+01,6.298053908925156132e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916857249377396499e+01,7.016025730316005138e+02,5.009854329038334608e-01,1.100000010988609489e+01,6.296594054909778956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.916948158467397434e+01,7.016125730296181473e+02,5.009917294974722823e-01,1.100000010988609489e+01,6.295134200894401781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917039067557398369e+01,7.016225730276366903e+02,5.009980246312574215e-01,1.100000010988609489e+01,6.293674346879024606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917129976647399303e+01,7.016325730256561428e+02,5.010043183051887672e-01,1.100000010988609489e+01,6.292214492863647431e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917220885737400238e+01,7.016425730236765048e+02,5.010106105192664305e-01,1.100000010988609489e+01,6.290754638848270255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917311794827401172e+01,7.016525730216977763e+02,5.010169012734904115e-01,1.100000010988609489e+01,6.289294784832893080e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917402703917402107e+01,7.016625730197200710e+02,5.010231905678605990e-01,1.100000010988609489e+01,6.287834930817515905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917493613007403042e+01,7.016725730177432752e+02,5.010294784023771042e-01,1.100000010988609489e+01,6.286375076802138730e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917584522097403976e+01,7.016825730157673888e+02,5.010357647770398160e-01,1.100000010988609489e+01,6.284915222786761554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917675431187404911e+01,7.016925730137924120e+02,5.010420496918488453e-01,1.100000010988609489e+01,6.283455368771384379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917766340277405845e+01,7.017025730118183446e+02,5.010483331468041923e-01,1.100000010988609489e+01,6.281995514756007204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917857249367406780e+01,7.017125730098451868e+02,5.010546151419057459e-01,1.100000010988609489e+01,6.280535660740630029e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.917948158457407715e+01,7.017225730078729384e+02,5.010608956771536171e-01,1.100000010988609489e+01,6.279075806725252853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918039067547408649e+01,7.017325730059015996e+02,5.010671747525476949e-01,1.100000010988609489e+01,6.277615952709875678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918129976637409584e+01,7.017425730039311702e+02,5.010734523680880903e-01,1.100000010988609489e+01,6.276156098694498503e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918220885727410518e+01,7.017525730019616503e+02,5.010797285237748033e-01,1.100000010988609489e+01,6.274696244679121328e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918311794817411453e+01,7.017625729999930400e+02,5.010860032196077229e-01,1.100000010988609489e+01,6.273236390663744153e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918402703907412388e+01,7.017725729980253391e+02,5.010922764555869602e-01,1.100000010988609489e+01,6.271776536648366977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918493612997413322e+01,7.017825729960585477e+02,5.010985482317124040e-01,1.100000010988609489e+01,6.270316682632989802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918584522087414257e+01,7.017925729940926658e+02,5.011048185479841655e-01,1.100000010988609489e+01,6.268856828617612627e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918675431177415192e+01,7.018025729921276934e+02,5.011110874044021335e-01,1.100000010988609489e+01,6.267396974602235452e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918766340267416126e+01,7.018125729901636305e+02,5.011173548009664191e-01,1.100000010988609489e+01,6.265937120586858276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918857249357417061e+01,7.018225729882004771e+02,5.011236207376770224e-01,1.100000010988609489e+01,6.264477266571481101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.918948158447417995e+01,7.018325729862383469e+02,5.011298852145338323e-01,1.100000010988609489e+01,6.263017412556103926e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919039067537418930e+01,7.018425729842771261e+02,5.011361482315369598e-01,1.100000010988609489e+01,6.261557558540726751e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919129976627419865e+01,7.018525729823168149e+02,5.011424097886862938e-01,1.100000010988609489e+01,6.260097704525349575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919220885717420799e+01,7.018625729803574131e+02,5.011486698859819455e-01,1.100000010988609489e+01,6.258637850509972400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919311794807421734e+01,7.018725729783989209e+02,5.011549285234239148e-01,1.100000010988609489e+01,6.257177996494595225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919402703897422668e+01,7.018825729764413381e+02,5.011611857010120907e-01,1.100000010988609489e+01,6.255718142479218050e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919493612987423603e+01,7.018925729744846649e+02,5.011674414187465842e-01,1.100000010988609489e+01,6.254258288463840874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919584522077424538e+01,7.019025729725289011e+02,5.011736956766272844e-01,1.100000010988609489e+01,6.252798434448463699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919675431167425472e+01,7.019125729705740468e+02,5.011799484746543021e-01,1.100000010988609489e+01,6.251338580433086524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919766340257426407e+01,7.019225729686201021e+02,5.011861998128275264e-01,1.100000010988609489e+01,6.249878726417709349e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919857249347427341e+01,7.019325729666670668e+02,5.011924496911470683e-01,1.100000010988609489e+01,6.248418872402332173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.919948158437428276e+01,7.019425729647149410e+02,5.011986981096129279e-01,1.100000010988609489e+01,6.246959018386954998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920039067527429211e+01,7.019525729627637247e+02,5.012049450682249940e-01,1.100000010988609489e+01,6.245499164371577823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920129976617430145e+01,7.019625729608134179e+02,5.012111905669833778e-01,1.100000010988609489e+01,6.244039310356200648e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920220885707431080e+01,7.019725729588640206e+02,5.012174346058879681e-01,1.100000010988609489e+01,6.242579456340823472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920311794797432015e+01,7.019825729569155328e+02,5.012236771849388761e-01,1.100000010988609489e+01,6.241119602325446297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920402703887432949e+01,7.019925729549679545e+02,5.012299183041359907e-01,1.100000010988609489e+01,6.239659748310069122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920493612977433884e+01,7.020025729530212857e+02,5.012361579634794229e-01,1.100000010988609489e+01,6.238199894294691947e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920584522067434818e+01,7.020125729510755264e+02,5.012423961629690616e-01,1.100000010988609489e+01,6.236740040279314772e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920675431157435753e+01,7.020225729491306765e+02,5.012486329026050180e-01,1.100000010988609489e+01,6.235280186263937596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920766340247436688e+01,7.020325729471867362e+02,5.012548681823872920e-01,1.100000010988609489e+01,6.233820332248560421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920857249337437622e+01,7.020425729452437054e+02,5.012611020023157726e-01,1.100000010988609489e+01,6.232360478233183246e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.920948158427438557e+01,7.020525729433015840e+02,5.012673343623905708e-01,1.100000010988609489e+01,6.230900624217806071e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921039067517439491e+01,7.020625729413603722e+02,5.012735652626115757e-01,1.100000010988609489e+01,6.229440770202428895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921129976607440426e+01,7.020725729394200698e+02,5.012797947029788981e-01,1.100000010988609489e+01,6.227980916187051720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921220885697441361e+01,7.020825729374806770e+02,5.012860226834924271e-01,1.100000010988609489e+01,6.226521062171674545e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921311794787442295e+01,7.020925729355421936e+02,5.012922492041522737e-01,1.100000010988609489e+01,6.225061208156297370e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921402703877443230e+01,7.021025729336046197e+02,5.012984742649583270e-01,1.100000010988609489e+01,6.223601354140920194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921493612967444164e+01,7.021125729316679553e+02,5.013046978659106978e-01,1.100000010988609489e+01,6.222141500125543019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921584522057445099e+01,7.021225729297322005e+02,5.013109200070093863e-01,1.100000010988609489e+01,6.220681646110165844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921675431147446034e+01,7.021325729277973551e+02,5.013171406882542813e-01,1.100000010988609489e+01,6.219221792094788669e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921766340237446968e+01,7.021425729258634192e+02,5.013233599096454940e-01,1.100000010988609489e+01,6.217761938079411493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921857249327447903e+01,7.021525729239303928e+02,5.013295776711829133e-01,1.100000010988609489e+01,6.216302084064034318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.921948158417448838e+01,7.021625729219982759e+02,5.013357939728666501e-01,1.100000010988609489e+01,6.214842230048657143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922039067507449772e+01,7.021725729200670685e+02,5.013420088146965936e-01,1.100000010988609489e+01,6.213382376033279968e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922129976597450707e+01,7.021825729181367706e+02,5.013482221966728547e-01,1.100000010988609489e+01,6.211922522017902792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922220885687451641e+01,7.021925729162073821e+02,5.013544341187953224e-01,1.100000010988609489e+01,6.210462668002525617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922311794777452576e+01,7.022025729142789032e+02,5.013606445810641077e-01,1.100000010988609489e+01,6.209002813987148442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922402703867453511e+01,7.022125729123513338e+02,5.013668535834790996e-01,1.100000010988609489e+01,6.207542959971771267e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922493612957454445e+01,7.022225729104246739e+02,5.013730611260404091e-01,1.100000010988609489e+01,6.206083105956394091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922584522047455380e+01,7.022325729084989234e+02,5.013792672087480362e-01,1.100000010988609489e+01,6.204623251941016916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922675431137456314e+01,7.022425729065740825e+02,5.013854718316018699e-01,1.100000010988609489e+01,6.203163397925639741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922766340227457249e+01,7.022525729046501510e+02,5.013916749946020213e-01,1.100000010988609489e+01,6.201703543910262566e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922857249317458184e+01,7.022625729027271291e+02,5.013978766977483792e-01,1.100000010988609489e+01,6.200243689894885391e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.922948158407459118e+01,7.022725729008050166e+02,5.014040769410410547e-01,1.100000010988609489e+01,6.198783835879508215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923039067497460053e+01,7.022825728988838137e+02,5.014102757244799369e-01,1.100000010988609489e+01,6.197323981864131040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923129976587460988e+01,7.022925728969635202e+02,5.014164730480651366e-01,1.100000010988609489e+01,6.195864127848753865e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923220885677461922e+01,7.023025728950441362e+02,5.014226689117965430e-01,1.100000010988609489e+01,6.194404273833376690e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923311794767462857e+01,7.023125728931255480e+02,5.014288633156742669e-01,1.100000010988609489e+01,6.192944419817999514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923402703857463791e+01,7.023225728912078694e+02,5.014350562596981975e-01,1.100000010988609489e+01,6.191484565802622339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923493612947464726e+01,7.023325728892911002e+02,5.014412477438684457e-01,1.100000010988609489e+01,6.190024711787245164e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923584522037465661e+01,7.023425728873752405e+02,5.014474377681849004e-01,1.100000010988609489e+01,6.188564857771867989e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923675431127466595e+01,7.023525728854602903e+02,5.014536263326476728e-01,1.100000010988609489e+01,6.187105003756490813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923766340217467530e+01,7.023625728835462496e+02,5.014598134372566518e-01,1.100000010988609489e+01,6.185645149741113638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923857249307468464e+01,7.023725728816331184e+02,5.014659990820119484e-01,1.100000010988609489e+01,6.184185295725736463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.923948158397469399e+01,7.023825728797208967e+02,5.014721832669134516e-01,1.100000010988609489e+01,6.182725441710359288e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924039067487470334e+01,7.023925728778095845e+02,5.014783659919612724e-01,1.100000010988609489e+01,6.181265587694982112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924129976577471268e+01,7.024025728758991818e+02,5.014845472571552998e-01,1.100000010988609489e+01,6.179805733679604937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924220885667472203e+01,7.024125728739896886e+02,5.014907270624956448e-01,1.100000010988609489e+01,6.178345879664227762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924311794757473137e+01,7.024225728720811048e+02,5.014969054079821964e-01,1.100000010988609489e+01,6.176886025648850587e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924402703847474072e+01,7.024325728701734306e+02,5.015030822936150656e-01,1.100000010988609489e+01,6.175426171633473411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924493612937475007e+01,7.024425728682666659e+02,5.015092577193941414e-01,1.100000010988609489e+01,6.173966317618096236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924584522027475941e+01,7.024525728663608106e+02,5.015154316853195349e-01,1.100000010988609489e+01,6.172506463602719061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924675431117476876e+01,7.024625728644558649e+02,5.015216041913911349e-01,1.100000010988609489e+01,6.171046609587341886e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924766340207477811e+01,7.024725728625518286e+02,5.015277752376090525e-01,1.100000010988609489e+01,6.169586755571964710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924857249297478745e+01,7.024825728606485882e+02,5.015339448239731768e-01,1.100000010988609489e+01,6.168126901556587535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.924948158387479680e+01,7.024925728587462572e+02,5.015401129504836186e-01,1.100000010988609489e+01,6.166667047541210360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925039067477480614e+01,7.025025728568448358e+02,5.015462796171402671e-01,1.100000010988609489e+01,6.165207193525833185e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925129976567481549e+01,7.025125728549443238e+02,5.015524448239432331e-01,1.100000010988609489e+01,6.163747339510456009e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925220885657482484e+01,7.025225728530447213e+02,5.015586085708924058e-01,1.100000010988609489e+01,6.162287485495078834e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925311794747483418e+01,7.025325728511460284e+02,5.015647708579878961e-01,1.100000010988609489e+01,6.160827631479701659e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925402703837484353e+01,7.025425728492482449e+02,5.015709316852295929e-01,1.100000010988609489e+01,6.159367777464324484e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925493612927485287e+01,7.025525728473513709e+02,5.015770910526176074e-01,1.100000010988609489e+01,6.157907923448947309e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925584522017486222e+01,7.025625728454554064e+02,5.015832489601518285e-01,1.100000010988609489e+01,6.156448069433570133e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925675431107487157e+01,7.025725728435603514e+02,5.015894054078323672e-01,1.100000010988609489e+01,6.154988215418192958e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925766340197488091e+01,7.025825728416662059e+02,5.015955603956591125e-01,1.100000010988609489e+01,6.153528361402815783e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925857249287489026e+01,7.025925728397728562e+02,5.016017139236321754e-01,1.100000010988609489e+01,6.152068507387438608e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.925948158377489960e+01,7.026025728378804160e+02,5.016078659917514448e-01,1.100000010988609489e+01,6.150608653372061432e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926039067467490895e+01,7.026125728359888853e+02,5.016140166000170320e-01,1.100000010988609489e+01,6.149148799356684257e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926129976557491830e+01,7.026225728340982641e+02,5.016201657484288257e-01,1.100000010988609489e+01,6.147688945341307082e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926220885647492764e+01,7.026325728322085524e+02,5.016263134369869370e-01,1.100000010988609489e+01,6.146229091325929907e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926311794737493699e+01,7.026425728303197502e+02,5.016324596656912549e-01,1.100000010988609489e+01,6.144769237310552731e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926402703827494634e+01,7.026525728284318575e+02,5.016386044345418904e-01,1.100000010988609489e+01,6.143309383295175556e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926493612917495568e+01,7.026625728265448743e+02,5.016447477435387325e-01,1.100000010988609489e+01,6.141849529279798381e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926584522007496503e+01,7.026725728246588005e+02,5.016508895926818923e-01,1.100000010988609489e+01,6.140389675264421206e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926675431097497437e+01,7.026825728227736363e+02,5.016570299819712586e-01,1.100000010988609489e+01,6.138929821249044030e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926766340187498372e+01,7.026925728208892679e+02,5.016631689114069426e-01,1.100000010988609489e+01,6.137469967233666855e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926857249277499307e+01,7.027025728190058089e+02,5.016693063809888331e-01,1.100000010988609489e+01,6.136010113218289680e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.926948158367500241e+01,7.027125728171232595e+02,5.016754423907170413e-01,1.100000010988609489e+01,6.134550259202912505e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927039067457501176e+01,7.027225728152416195e+02,5.016815769405914560e-01,1.100000010988609489e+01,6.133090405187535329e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927129976547502110e+01,7.027325728133608891e+02,5.016877100306121884e-01,1.100000010988609489e+01,6.131630551172158154e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927220885637503045e+01,7.027425728114810681e+02,5.016938416607791273e-01,1.100000010988609489e+01,6.130170697156780979e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927311794727503980e+01,7.027525728096021567e+02,5.016999718310923839e-01,1.100000010988609489e+01,6.128710843141403804e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927402703817504914e+01,7.027625728077241547e+02,5.017061005415518471e-01,1.100000010988609489e+01,6.127250989126026628e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927493612907505849e+01,7.027725728058469485e+02,5.017122277921576279e-01,1.100000010988609489e+01,6.125791135110649453e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927584521997506783e+01,7.027825728039706519e+02,5.017183535829096153e-01,1.100000010988609489e+01,6.124331281095272278e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927675431087507718e+01,7.027925728020952647e+02,5.017244779138078092e-01,1.100000010988609489e+01,6.122871427079895103e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927766340177508653e+01,7.028025728002207870e+02,5.017306007848523208e-01,1.100000010988609489e+01,6.121411573064517928e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927857249267509587e+01,7.028125727983472188e+02,5.017367221960430390e-01,1.100000010988609489e+01,6.119951719049140752e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.927948158357510522e+01,7.028225727964745602e+02,5.017428421473800748e-01,1.100000010988609489e+01,6.118491865033763577e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928039067447511457e+01,7.028325727946028110e+02,5.017489606388633172e-01,1.100000010988609489e+01,6.117032011018386402e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928129976537512391e+01,7.028425727927318576e+02,5.017550776704928772e-01,1.100000010988609489e+01,6.115572157003009227e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928220885627513326e+01,7.028525727908618137e+02,5.017611932422686438e-01,1.100000010988609489e+01,6.114112302987632051e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928311794717514260e+01,7.028625727889926793e+02,5.017673073541907280e-01,1.100000010988609489e+01,6.112652448972254876e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928402703807515195e+01,7.028725727871244544e+02,5.017734200062590189e-01,1.100000010988609489e+01,6.111192594956877701e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928493612897516130e+01,7.028825727852571390e+02,5.017795311984736273e-01,1.100000010988609489e+01,6.109732740941500526e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928584521987517064e+01,7.028925727833907331e+02,5.017856409308344423e-01,1.100000010988609489e+01,6.108272886926123350e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928675431077517999e+01,7.029025727815252367e+02,5.017917492033415749e-01,1.100000010988609489e+01,6.106813032910746175e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928766340167518933e+01,7.029125727796605361e+02,5.017978560159949142e-01,1.100000010988609489e+01,6.105353178895369000e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928857249257519868e+01,7.029225727777967450e+02,5.018039613687944600e-01,1.100000010988609489e+01,6.103893324879991825e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.928948158347520803e+01,7.029325727759338633e+02,5.018100652617403235e-01,1.100000010988609489e+01,6.102433470864614649e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929039067437521737e+01,7.029425727740718912e+02,5.018161676948323935e-01,1.100000010988609489e+01,6.100973616849237474e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929129976527522672e+01,7.029525727722108286e+02,5.018222686680707811e-01,1.100000010988609489e+01,6.099513762833860299e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929220885617523606e+01,7.029625727703506755e+02,5.018283681814553754e-01,1.100000010988609489e+01,6.098053908818483124e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929311794707524541e+01,7.029725727684913181e+02,5.018344662349862872e-01,1.100000010988609489e+01,6.096594054803105948e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929402703797525476e+01,7.029825727666328703e+02,5.018405628286634057e-01,1.100000010988609489e+01,6.095134200787728773e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929493612887526410e+01,7.029925727647753320e+02,5.018466579624868418e-01,1.100000010988609489e+01,6.093674346772351598e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929584521977527345e+01,7.030025727629187031e+02,5.018527516364564844e-01,1.100000010988609489e+01,6.092214492756974423e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929675431067528280e+01,7.030125727610629838e+02,5.018588438505723337e-01,1.100000010988609489e+01,6.090754638741597247e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929766340157529214e+01,7.030225727592081739e+02,5.018649346048345006e-01,1.100000010988609489e+01,6.089294784726220072e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929857249247530149e+01,7.030325727573541599e+02,5.018710238992428740e-01,1.100000010988609489e+01,6.087834930710842897e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.929948158337531083e+01,7.030425727555010553e+02,5.018771117337975651e-01,1.100000010988609489e+01,6.086375076695465722e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930039067427532018e+01,7.030525727536488603e+02,5.018831981084984628e-01,1.100000010988609489e+01,6.084915222680088547e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930129976517532953e+01,7.030625727517975747e+02,5.018892830233456781e-01,1.100000010988609489e+01,6.083455368664711371e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930220885607533887e+01,7.030725727499471986e+02,5.018953664783391000e-01,1.100000010988609489e+01,6.081995514649334196e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930311794697534822e+01,7.030825727480976184e+02,5.019014484734788395e-01,1.100000010988609489e+01,6.080535660633957021e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930402703787535756e+01,7.030925727462489476e+02,5.019075290087647856e-01,1.100000010988609489e+01,6.079075806618579846e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930493612877536691e+01,7.031025727444011864e+02,5.019136080841969383e-01,1.100000010988609489e+01,6.077615952603202670e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930584521967537626e+01,7.031125727425543346e+02,5.019196856997754086e-01,1.100000010988609489e+01,6.076156098587825495e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930675431057538560e+01,7.031225727407083923e+02,5.019257618555000855e-01,1.100000010988609489e+01,6.074696244572448320e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930766340147539495e+01,7.031325727388632458e+02,5.019318365513710800e-01,1.100000010988609489e+01,6.073236390557071145e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930857249237540429e+01,7.031425727370190089e+02,5.019379097873882811e-01,1.100000010988609489e+01,6.071776536541693969e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.930948158327541364e+01,7.031525727351756814e+02,5.019439815635517999e-01,1.100000010988609489e+01,6.070316682526316794e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931039067417542299e+01,7.031625727333332634e+02,5.019500518798615252e-01,1.100000010988609489e+01,6.068856828510939619e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931129976507543233e+01,7.031725727314917549e+02,5.019561207363174571e-01,1.100000010988609489e+01,6.067396974495562444e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931220885597544168e+01,7.031825727296510422e+02,5.019621881329197066e-01,1.100000010988609489e+01,6.065937120480185268e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931311794687545103e+01,7.031925727278112390e+02,5.019682540696681627e-01,1.100000010988609489e+01,6.064477266464808093e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931402703777546037e+01,7.032025727259723453e+02,5.019743185465629365e-01,1.100000010988609489e+01,6.063017412449430918e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931493612867546972e+01,7.032125727241343611e+02,5.019803815636039168e-01,1.100000010988609489e+01,6.061557558434053743e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931584521957547906e+01,7.032225727222972864e+02,5.019864431207911037e-01,1.100000010988609489e+01,6.060097704418676567e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931675431047548841e+01,7.032325727204610075e+02,5.019925032181246083e-01,1.100000010988609489e+01,6.058637850403299392e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931766340137549776e+01,7.032425727186256381e+02,5.019985618556043194e-01,1.100000010988609489e+01,6.057177996387922217e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931857249227550710e+01,7.032525727167911782e+02,5.020046190332303482e-01,1.100000010988609489e+01,6.055718142372545042e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.931948158317551645e+01,7.032625727149576278e+02,5.020106747510025835e-01,1.100000010988609489e+01,6.054258288357167866e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932039067407552579e+01,7.032725727131248732e+02,5.020167290089211365e-01,1.100000010988609489e+01,6.052798434341790691e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932129976497553514e+01,7.032825727112930281e+02,5.020227818069858960e-01,1.100000010988609489e+01,6.051338580326413516e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932220885587554449e+01,7.032925727094620925e+02,5.020288331451968622e-01,1.100000010988609489e+01,6.049878726311036341e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932311794677555383e+01,7.033025727076320663e+02,5.020348830235541460e-01,1.100000010988609489e+01,6.048418872295659166e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932402703767556318e+01,7.033125727058029497e+02,5.020409314420576363e-01,1.100000010988609489e+01,6.046959018280281990e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932493612857557252e+01,7.033225727039746289e+02,5.020469784007074443e-01,1.100000010988609489e+01,6.045499164264904815e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932584521947558187e+01,7.033325727021472176e+02,5.020530238995034589e-01,1.100000010988609489e+01,6.044039310249527640e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932675431037559122e+01,7.033425727003207157e+02,5.020590679384456800e-01,1.100000010988609489e+01,6.042579456234150465e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932766340127560056e+01,7.033525726984951234e+02,5.020651105175342188e-01,1.100000010988609489e+01,6.041119602218773289e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932857249217560991e+01,7.033625726966703269e+02,5.020711516367689642e-01,1.100000010988609489e+01,6.039659748203396114e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.932948158307561926e+01,7.033725726948464398e+02,5.020771912961500272e-01,1.100000010988609489e+01,6.038199894188018939e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933039067397562860e+01,7.033825726930234623e+02,5.020832294956772968e-01,1.100000010988609489e+01,6.036740040172641764e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933129976487563795e+01,7.033925726912013943e+02,5.020892662353507729e-01,1.100000010988609489e+01,6.035280186157264588e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933220885577564729e+01,7.034025726893801220e+02,5.020953015151705667e-01,1.100000010988609489e+01,6.033820332141887413e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933311794667565664e+01,7.034125726875597593e+02,5.021013353351365671e-01,1.100000010988609489e+01,6.032360478126510238e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933402703757566599e+01,7.034225726857403060e+02,5.021073676952488851e-01,1.100000010988609489e+01,6.030900624111133063e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933493612847567533e+01,7.034325726839217623e+02,5.021133985955074097e-01,1.100000010988609489e+01,6.029440770095755887e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933584521937568468e+01,7.034425726821040143e+02,5.021194280359121409e-01,1.100000010988609489e+01,6.027980916080378712e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933675431027569402e+01,7.034525726802871759e+02,5.021254560164631897e-01,1.100000010988609489e+01,6.026521062065001537e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933766340117570337e+01,7.034625726784712469e+02,5.021314825371604451e-01,1.100000010988609489e+01,6.025061208049624362e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933857249207571272e+01,7.034725726766562275e+02,5.021375075980040181e-01,1.100000010988609489e+01,6.023601354034247186e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.933948158297572206e+01,7.034825726748420038e+02,5.021435311989937977e-01,1.100000010988609489e+01,6.022141500018870011e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934039067387573141e+01,7.034925726730286897e+02,5.021495533401297839e-01,1.100000010988609489e+01,6.020681646003492836e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934129976477574075e+01,7.035025726712162850e+02,5.021555740214120878e-01,1.100000010988609489e+01,6.019221791988115661e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934220885567575010e+01,7.035125726694047898e+02,5.021615932428405982e-01,1.100000010988609489e+01,6.017761937972738485e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934311794657575945e+01,7.035225726675940905e+02,5.021676110044153152e-01,1.100000010988609489e+01,6.016302083957361310e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934402703747576879e+01,7.035325726657843006e+02,5.021736273061363498e-01,1.100000010988609489e+01,6.014842229941984135e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934493612837577814e+01,7.035425726639754203e+02,5.021796421480035910e-01,1.100000010988609489e+01,6.013382375926606960e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934584521927578749e+01,7.035525726621673357e+02,5.021856555300171499e-01,1.100000010988609489e+01,6.011922521911229784e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934675431017579683e+01,7.035625726603601606e+02,5.021916674521769153e-01,1.100000010988609489e+01,6.010462667895852609e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934766340107580618e+01,7.035725726585538951e+02,5.021976779144828873e-01,1.100000010988609489e+01,6.009002813880475434e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934857249197581552e+01,7.035825726567485390e+02,5.022036869169351769e-01,1.100000010988609489e+01,6.007542959865098259e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.934948158287582487e+01,7.035925726549439787e+02,5.022096944595336732e-01,1.100000010988609489e+01,6.006083105849721084e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935039067377583422e+01,7.036025726531403279e+02,5.022157005422783760e-01,1.100000010988609489e+01,6.004623251834343908e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935129976467584356e+01,7.036125726513375866e+02,5.022217051651693964e-01,1.100000010988609489e+01,6.003163397818966733e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935220885557585291e+01,7.036225726495356412e+02,5.022277083282066235e-01,1.100000010988609489e+01,6.001703543803589558e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935311794647586225e+01,7.036325726477346052e+02,5.022337100313901681e-01,1.100000010988609489e+01,6.000243689788212383e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935402703737587160e+01,7.036425726459344787e+02,5.022397102747199193e-01,1.100000010988609489e+01,5.998783835772835207e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935493612827588095e+01,7.036525726441352617e+02,5.022457090581958772e-01,1.100000010988609489e+01,5.997323981757458032e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935584521917589029e+01,7.036625726423368405e+02,5.022517063818181526e-01,1.100000010988609489e+01,5.995864127742080857e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935675431007589964e+01,7.036725726405393289e+02,5.022577022455866347e-01,1.100000010988609489e+01,5.994404273726703682e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935766340097590898e+01,7.036825726387427267e+02,5.022636966495013233e-01,1.100000010988609489e+01,5.992944419711326506e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935857249187591833e+01,7.036925726369469203e+02,5.022696895935623296e-01,1.100000010988609489e+01,5.991484565695949331e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.935948158277592768e+01,7.037025726351520234e+02,5.022756810777695424e-01,1.100000010988609489e+01,5.990024711680572156e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936039067367593702e+01,7.037125726333580360e+02,5.022816711021229619e-01,1.100000010988609489e+01,5.988564857665194981e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936129976457594637e+01,7.037225726315648444e+02,5.022876596666226989e-01,1.100000010988609489e+01,5.987105003649817805e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936220885547595572e+01,7.037325726297725623e+02,5.022936467712686426e-01,1.100000010988609489e+01,5.985645149634440630e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936311794637596506e+01,7.037425726279811897e+02,5.022996324160609039e-01,1.100000010988609489e+01,5.984185295619063455e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936402703727597441e+01,7.037525726261906129e+02,5.023056166009993717e-01,1.100000010988609489e+01,5.982725441603686280e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936493612817598375e+01,7.037625726244009456e+02,5.023115993260840462e-01,1.100000010988609489e+01,5.981265587588309104e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936584521907599310e+01,7.037725726226121878e+02,5.023175805913150382e-01,1.100000010988609489e+01,5.979805733572931929e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936675430997600245e+01,7.037825726208243395e+02,5.023235603966922369e-01,1.100000010988609489e+01,5.978345879557554754e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936766340087601179e+01,7.037925726190372870e+02,5.023295387422156422e-01,1.100000010988609489e+01,5.976886025542177579e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936857249177602114e+01,7.038025726172511440e+02,5.023355156278853650e-01,1.100000010988609489e+01,5.975426171526800403e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.936948158267603048e+01,7.038125726154659105e+02,5.023414910537012945e-01,1.100000010988609489e+01,5.973966317511423228e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937039067357603983e+01,7.038225726136814728e+02,5.023474650196634306e-01,1.100000010988609489e+01,5.972506463496046053e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937129976447604918e+01,7.038325726118979446e+02,5.023534375257718843e-01,1.100000010988609489e+01,5.971046609480668878e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937220885537605852e+01,7.038425726101153259e+02,5.023594085720265445e-01,1.100000010988609489e+01,5.969586755465291703e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937311794627606787e+01,7.038525726083335030e+02,5.023653781584274114e-01,1.100000010988609489e+01,5.968126901449914527e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937402703717607722e+01,7.038625726065525896e+02,5.023713462849745959e-01,1.100000010988609489e+01,5.966667047434537352e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937493612807608656e+01,7.038725726047725857e+02,5.023773129516679870e-01,1.100000010988609489e+01,5.965207193419160177e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937584521897609591e+01,7.038825726029933776e+02,5.023832781585075846e-01,1.100000010988609489e+01,5.963747339403783002e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937675430987610525e+01,7.038925726012150790e+02,5.023892419054934999e-01,1.100000010988609489e+01,5.962287485388405826e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937766340077611460e+01,7.039025725994376899e+02,5.023952041926256218e-01,1.100000010988609489e+01,5.960827631373028651e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937857249167612395e+01,7.039125725976610966e+02,5.024011650199039503e-01,1.100000010988609489e+01,5.959367777357651476e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.937948158257613329e+01,7.039225725958854127e+02,5.024071243873285963e-01,1.100000010988609489e+01,5.957907923342274301e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938039067347614264e+01,7.039325725941105247e+02,5.024130822948994490e-01,1.100000010988609489e+01,5.956448069326897125e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938129976437615198e+01,7.039425725923365462e+02,5.024190387426165083e-01,1.100000010988609489e+01,5.954988215311519950e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938220885527616133e+01,7.039525725905634772e+02,5.024249937304798852e-01,1.100000010988609489e+01,5.953528361296142775e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938311794617617068e+01,7.039625725887912040e+02,5.024309472584894687e-01,1.100000010988609489e+01,5.952068507280765600e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938402703707618002e+01,7.039725725870198403e+02,5.024368993266452588e-01,1.100000010988609489e+01,5.950608653265388424e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938493612797618937e+01,7.039825725852493861e+02,5.024428499349473665e-01,1.100000010988609489e+01,5.949148799250011249e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938584521887619871e+01,7.039925725834797277e+02,5.024487990833956808e-01,1.100000010988609489e+01,5.947688945234634074e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938675430977620806e+01,7.040025725817109787e+02,5.024547467719902016e-01,1.100000010988609489e+01,5.946229091219256899e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938766340067621741e+01,7.040125725799431393e+02,5.024606930007310401e-01,1.100000010988609489e+01,5.944769237203879723e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938857249157622675e+01,7.040225725781760957e+02,5.024666377696180852e-01,1.100000010988609489e+01,5.943309383188502548e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.938948158247623610e+01,7.040325725764099616e+02,5.024725810786513369e-01,1.100000010988609489e+01,5.941849529173125373e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939039067337624545e+01,7.040425725746447370e+02,5.024785229278309062e-01,1.100000010988609489e+01,5.940389675157748198e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939129976427625479e+01,7.040525725728803081e+02,5.024844633171566821e-01,1.100000010988609489e+01,5.938929821142371022e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939220885517626414e+01,7.040625725711167888e+02,5.024904022466286646e-01,1.100000010988609489e+01,5.937469967126993847e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939311794607627348e+01,7.040725725693540653e+02,5.024963397162469647e-01,1.100000010988609489e+01,5.936010113111616672e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939402703697628283e+01,7.040825725675922513e+02,5.025022757260114714e-01,1.100000010988609489e+01,5.934550259096239497e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939493612787629218e+01,7.040925725658313468e+02,5.025082102759221847e-01,1.100000010988609489e+01,5.933090405080862322e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939584521877630152e+01,7.041025725640712380e+02,5.025141433659792156e-01,1.100000010988609489e+01,5.931630551065485146e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939675430967631087e+01,7.041125725623120388e+02,5.025200749961824531e-01,1.100000010988609489e+01,5.930170697050107971e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939766340057632021e+01,7.041225725605537491e+02,5.025260051665318972e-01,1.100000010988609489e+01,5.928710843034730796e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939857249147632956e+01,7.041325725587962552e+02,5.025319338770276589e-01,1.100000010988609489e+01,5.927250989019353621e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.939948158237633891e+01,7.041425725570396708e+02,5.025378611276696272e-01,1.100000010988609489e+01,5.925791135003976445e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940039067327634825e+01,7.041525725552838821e+02,5.025437869184578021e-01,1.100000010988609489e+01,5.924331280988599270e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940129976417635760e+01,7.041625725535290030e+02,5.025497112493922947e-01,1.100000010988609489e+01,5.922871426973222095e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940220885507636694e+01,7.041725725517750334e+02,5.025556341204729938e-01,1.100000010988609489e+01,5.921411572957844920e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940311794597637629e+01,7.041825725500218596e+02,5.025615555316998995e-01,1.100000010988609489e+01,5.919951718942467744e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940402703687638564e+01,7.041925725482695952e+02,5.025674754830730118e-01,1.100000010988609489e+01,5.918491864927090569e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940493612777639498e+01,7.042025725465181267e+02,5.025733939745924417e-01,1.100000010988609489e+01,5.917032010911713394e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940584521867640433e+01,7.042125725447675677e+02,5.025793110062580782e-01,1.100000010988609489e+01,5.915572156896336219e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940675430957641368e+01,7.042225725430179182e+02,5.025852265780699213e-01,1.100000010988609489e+01,5.914112302880959043e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940766340047642302e+01,7.042325725412690645e+02,5.025911406900280820e-01,1.100000010988609489e+01,5.912652448865581868e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940857249137643237e+01,7.042425725395211202e+02,5.025970533421324493e-01,1.100000010988609489e+01,5.911192594850204693e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.940948158227644171e+01,7.042525725377739718e+02,5.026029645343830232e-01,1.100000010988609489e+01,5.909732740834827518e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941039067317645106e+01,7.042625725360277329e+02,5.026088742667799147e-01,1.100000010988609489e+01,5.908272886819450342e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941129976407646041e+01,7.042725725342824035e+02,5.026147825393230129e-01,1.100000010988609489e+01,5.906813032804073167e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941220885497646975e+01,7.042825725325378698e+02,5.026206893520123176e-01,1.100000010988609489e+01,5.905353178788695992e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941311794587647910e+01,7.042925725307942457e+02,5.026265947048478289e-01,1.100000010988609489e+01,5.903893324773318817e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941402703677648844e+01,7.043025725290514174e+02,5.026324985978296578e-01,1.100000010988609489e+01,5.902433470757941641e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941493612767649779e+01,7.043125725273094986e+02,5.026384010309576933e-01,1.100000010988609489e+01,5.900973616742564466e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941584521857650714e+01,7.043225725255683756e+02,5.026443020042319354e-01,1.100000010988609489e+01,5.899513762727187291e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941675430947651648e+01,7.043325725238281620e+02,5.026502015176524951e-01,1.100000010988609489e+01,5.898053908711810116e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941766340037652583e+01,7.043425725220888580e+02,5.026560995712192614e-01,1.100000010988609489e+01,5.896594054696432941e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941857249127653517e+01,7.043525725203503498e+02,5.026619961649322343e-01,1.100000010988609489e+01,5.895134200681055765e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.941948158217654452e+01,7.043625725186127511e+02,5.026678912987914138e-01,1.100000010988609489e+01,5.893674346665678590e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942039067307655387e+01,7.043725725168759482e+02,5.026737849727969110e-01,1.100000010988609489e+01,5.892214492650301415e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942129976397656321e+01,7.043825725151400547e+02,5.026796771869486147e-01,1.100000010988609489e+01,5.890754638634924240e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942220885487657256e+01,7.043925725134049571e+02,5.026855679412465250e-01,1.100000010988609489e+01,5.889294784619547064e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942311794577658191e+01,7.044025725116707690e+02,5.026914572356907529e-01,1.100000010988609489e+01,5.887834930604169889e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942402703667659125e+01,7.044125725099374904e+02,5.026973450702811874e-01,1.100000010988609489e+01,5.886375076588792714e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942493612757660060e+01,7.044225725082050076e+02,5.027032314450178285e-01,1.100000010988609489e+01,5.884915222573415539e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942584521847660994e+01,7.044325725064734343e+02,5.027091163599006762e-01,1.100000010988609489e+01,5.883455368558038363e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942675430937661929e+01,7.044425725047426567e+02,5.027149998149298415e-01,1.100000010988609489e+01,5.881995514542661188e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942766340027662864e+01,7.044525725030127887e+02,5.027208818101052135e-01,1.100000010988609489e+01,5.880535660527284013e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942857249117663798e+01,7.044625725012837165e+02,5.027267623454267920e-01,1.100000010988609489e+01,5.879075806511906838e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.942948158207664733e+01,7.044725724995555538e+02,5.027326414208946881e-01,1.100000010988609489e+01,5.877615952496529662e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943039067297665667e+01,7.044825724978281869e+02,5.027385190365087908e-01,1.100000010988609489e+01,5.876156098481152487e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943129976387666602e+01,7.044925724961017295e+02,5.027443951922691001e-01,1.100000010988609489e+01,5.874696244465775312e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943220885477667537e+01,7.045025724943761816e+02,5.027502698881756160e-01,1.100000010988609489e+01,5.873236390450398137e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943311794567668471e+01,7.045125724926514295e+02,5.027561431242284495e-01,1.100000010988609489e+01,5.871776536435020961e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943402703657669406e+01,7.045225724909275868e+02,5.027620149004274896e-01,1.100000010988609489e+01,5.870316682419643786e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943493612747670340e+01,7.045325724892045400e+02,5.027678852167727364e-01,1.100000010988609489e+01,5.868856828404266611e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943584521837671275e+01,7.045425724874824027e+02,5.027737540732641897e-01,1.100000010988609489e+01,5.867396974388889436e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943675430927672210e+01,7.045525724857610612e+02,5.027796214699019606e-01,1.100000010988609489e+01,5.865937120373512260e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943766340017673144e+01,7.045625724840406292e+02,5.027854874066859381e-01,1.100000010988609489e+01,5.864477266358135085e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943857249107674079e+01,7.045725724823209930e+02,5.027913518836161222e-01,1.100000010988609489e+01,5.863017412342757910e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.943948158197675014e+01,7.045825724806022663e+02,5.027972149006925129e-01,1.100000010988609489e+01,5.861557558327380735e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944039067287675948e+01,7.045925724788843354e+02,5.028030764579152212e-01,1.100000010988609489e+01,5.860097704312003560e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944129976377676883e+01,7.046025724771673140e+02,5.028089365552841361e-01,1.100000010988609489e+01,5.858637850296626384e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944220885467677817e+01,7.046125724754510884e+02,5.028147951927992576e-01,1.100000010988609489e+01,5.857177996281249209e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944311794557678752e+01,7.046225724737357723e+02,5.028206523704605857e-01,1.100000010988609489e+01,5.855718142265872034e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944402703647679687e+01,7.046325724720212520e+02,5.028265080882682314e-01,1.100000010988609489e+01,5.854258288250494859e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944493612737680621e+01,7.046425724703076412e+02,5.028323623462220837e-01,1.100000010988609489e+01,5.852798434235117683e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944584521827681556e+01,7.046525724685948262e+02,5.028382151443221426e-01,1.100000010988609489e+01,5.851338580219740508e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944675430917682490e+01,7.046625724668829207e+02,5.028440664825685191e-01,1.100000010988609489e+01,5.849878726204363333e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944766340007683425e+01,7.046725724651718110e+02,5.028499163609611022e-01,1.100000010988609489e+01,5.848418872188986158e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944857249097684360e+01,7.046825724634616108e+02,5.028557647794998919e-01,1.100000010988609489e+01,5.846959018173608982e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.944948158187685294e+01,7.046925724617523201e+02,5.028616117381848882e-01,1.100000010988609489e+01,5.845499164158231807e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945039067277686229e+01,7.047025724600438252e+02,5.028674572370162021e-01,1.100000010988609489e+01,5.844039310142854632e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945129976367687163e+01,7.047125724583362398e+02,5.028733012759937226e-01,1.100000010988609489e+01,5.842579456127477457e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945220885457688098e+01,7.047225724566294502e+02,5.028791438551174497e-01,1.100000010988609489e+01,5.841119602112100281e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945311794547689033e+01,7.047325724549235701e+02,5.028849849743873834e-01,1.100000010988609489e+01,5.839659748096723106e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945402703637689967e+01,7.047425724532184859e+02,5.028908246338035237e-01,1.100000010988609489e+01,5.838199894081345931e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945493612727690902e+01,7.047525724515143111e+02,5.028966628333659816e-01,1.100000010988609489e+01,5.836740040065968756e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945584521817691837e+01,7.047625724498109321e+02,5.029024995730746461e-01,1.100000010988609489e+01,5.835280186050591580e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945675430907692771e+01,7.047725724481084626e+02,5.029083348529295172e-01,1.100000010988609489e+01,5.833820332035214405e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945766339997693706e+01,7.047825724464067889e+02,5.029141686729305949e-01,1.100000010988609489e+01,5.832360478019837230e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945857249087694640e+01,7.047925724447059110e+02,5.029200010330779902e-01,1.100000010988609489e+01,5.830900624004460055e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.945948158177695575e+01,7.048025724430059427e+02,5.029258319333715921e-01,1.100000010988609489e+01,5.829440769989082879e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946039067267696510e+01,7.048125724413067701e+02,5.029316613738114006e-01,1.100000010988609489e+01,5.827980915973705704e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946129976357697444e+01,7.048225724396085070e+02,5.029374893543974157e-01,1.100000010988609489e+01,5.826521061958328529e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946220885447698379e+01,7.048325724379110397e+02,5.029433158751297483e-01,1.100000010988609489e+01,5.825061207942951354e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946311794537699313e+01,7.048425724362144820e+02,5.029491409360082876e-01,1.100000010988609489e+01,5.823601353927574178e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946402703627700248e+01,7.048525724345187200e+02,5.029549645370330335e-01,1.100000010988609489e+01,5.822141499912197003e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946493612717701183e+01,7.048625724328238675e+02,5.029607866782039860e-01,1.100000010988609489e+01,5.820681645896819828e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946584521807702117e+01,7.048725724311298109e+02,5.029666073595212561e-01,1.100000010988609489e+01,5.819221791881442653e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946675430897703052e+01,7.048825724294366637e+02,5.029724265809847328e-01,1.100000010988609489e+01,5.817761937866065478e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946766339987703986e+01,7.048925724277443123e+02,5.029782443425944161e-01,1.100000010988609489e+01,5.816302083850688302e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946857249077704921e+01,7.049025724260528705e+02,5.029840606443503059e-01,1.100000010988609489e+01,5.814842229835311127e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.946948158167705856e+01,7.049125724243622244e+02,5.029898754862524024e-01,1.100000010988609489e+01,5.813382375819933952e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947039067257706790e+01,7.049225724226724878e+02,5.029956888683008165e-01,1.100000010988609489e+01,5.811922521804556777e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947129976347707725e+01,7.049325724209835471e+02,5.030015007904954372e-01,1.100000010988609489e+01,5.810462667789179601e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947220885437708660e+01,7.049425724192955158e+02,5.030073112528362644e-01,1.100000010988609489e+01,5.809002813773802426e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947311794527709594e+01,7.049525724176082804e+02,5.030131202553232983e-01,1.100000010988609489e+01,5.807542959758425251e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947402703617710529e+01,7.049625724159219544e+02,5.030189277979566498e-01,1.100000010988609489e+01,5.806083105743048076e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947493612707711463e+01,7.049725724142364243e+02,5.030247338807362079e-01,1.100000010988609489e+01,5.804623251727670900e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947584521797712398e+01,7.049825724125516899e+02,5.030305385036619725e-01,1.100000010988609489e+01,5.803163397712293725e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947675430887713333e+01,7.049925724108678651e+02,5.030363416667339438e-01,1.100000010988609489e+01,5.801703543696916550e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947766339977714267e+01,7.050025724091848360e+02,5.030421433699521216e-01,1.100000010988609489e+01,5.800243689681539375e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947857249067715202e+01,7.050125724075027165e+02,5.030479436133166171e-01,1.100000010988609489e+01,5.798783835666162199e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.947948158157716136e+01,7.050225724058213927e+02,5.030537423968273192e-01,1.100000010988609489e+01,5.797323981650785024e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948039067247717071e+01,7.050325724041409785e+02,5.030595397204842278e-01,1.100000010988609489e+01,5.795864127635407849e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948129976337718006e+01,7.050425724024613601e+02,5.030653355842873431e-01,1.100000010988609489e+01,5.794404273620030674e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948220885427718940e+01,7.050525724007826511e+02,5.030711299882366649e-01,1.100000010988609489e+01,5.792944419604653498e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948311794517719875e+01,7.050625723991047380e+02,5.030769229323323044e-01,1.100000010988609489e+01,5.791484565589276323e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948402703607720809e+01,7.050725723974276207e+02,5.030827144165741505e-01,1.100000010988609489e+01,5.790024711573899148e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948493612697721744e+01,7.050825723957514128e+02,5.030885044409622031e-01,1.100000010988609489e+01,5.788564857558521973e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948584521787722679e+01,7.050925723940760008e+02,5.030942930054964624e-01,1.100000010988609489e+01,5.787105003543144797e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948675430877723613e+01,7.051025723924014983e+02,5.031000801101769282e-01,1.100000010988609489e+01,5.785645149527767622e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948766339967724548e+01,7.051125723907277916e+02,5.031058657550037116e-01,1.100000010988609489e+01,5.784185295512390447e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948857249057725483e+01,7.051225723890549943e+02,5.031116499399767017e-01,1.100000010988609489e+01,5.782725441497013272e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.948948158147726417e+01,7.051325723873829929e+02,5.031174326650958983e-01,1.100000010988609489e+01,5.781265587481636097e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949039067237727352e+01,7.051425723857117873e+02,5.031232139303613016e-01,1.100000010988609489e+01,5.779805733466258921e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949129976327728286e+01,7.051525723840414912e+02,5.031289937357729114e-01,1.100000010988609489e+01,5.778345879450881746e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949220885417729221e+01,7.051625723823719909e+02,5.031347720813308388e-01,1.100000010988609489e+01,5.776886025435504571e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949311794507730156e+01,7.051725723807034001e+02,5.031405489670349729e-01,1.100000010988609489e+01,5.775426171420127396e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949402703597731090e+01,7.051825723790356051e+02,5.031463243928853135e-01,1.100000010988609489e+01,5.773966317404750220e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949493612687732025e+01,7.051925723773687196e+02,5.031520983588818607e-01,1.100000010988609489e+01,5.772506463389373045e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949584521777732959e+01,7.052025723757026299e+02,5.031578708650246146e-01,1.100000010988609489e+01,5.771046609373995870e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949675430867733894e+01,7.052125723740373360e+02,5.031636419113136860e-01,1.100000010988609489e+01,5.769586755358618695e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949766339957734829e+01,7.052225723723729516e+02,5.031694114977489640e-01,1.100000010988609489e+01,5.768126901343241519e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949857249047735763e+01,7.052325723707093630e+02,5.031751796243304486e-01,1.100000010988609489e+01,5.766667047327864344e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.949948158137736698e+01,7.052425723690466839e+02,5.031809462910581399e-01,1.100000010988609489e+01,5.765207193312487169e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950039067227737632e+01,7.052525723673848006e+02,5.031867114979320377e-01,1.100000010988609489e+01,5.763747339297109994e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950129976317738567e+01,7.052625723657237131e+02,5.031924752449522531e-01,1.100000010988609489e+01,5.762287485281732818e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950220885407739502e+01,7.052725723640635351e+02,5.031982375321186751e-01,1.100000010988609489e+01,5.760827631266355643e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950311794497740436e+01,7.052825723624041530e+02,5.032039983594313037e-01,1.100000010988609489e+01,5.759367777250978468e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950402703587741371e+01,7.052925723607456803e+02,5.032097577268901389e-01,1.100000010988609489e+01,5.757907923235601293e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950493612677742306e+01,7.053025723590880034e+02,5.032155156344951807e-01,1.100000010988609489e+01,5.756448069220224117e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950584521767743240e+01,7.053125723574311223e+02,5.032212720822465402e-01,1.100000010988609489e+01,5.754988215204846942e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950675430857744175e+01,7.053225723557751508e+02,5.032270270701441062e-01,1.100000010988609489e+01,5.753528361189469767e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950766339947745109e+01,7.053325723541199750e+02,5.032327805981878788e-01,1.100000010988609489e+01,5.752068507174092592e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950857249037746044e+01,7.053425723524657087e+02,5.032385326663778580e-01,1.100000010988609489e+01,5.750608653158715416e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.950948158127746979e+01,7.053525723508122383e+02,5.032442832747140438e-01,1.100000010988609489e+01,5.749148799143338241e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951039067217747913e+01,7.053625723491595636e+02,5.032500324231964361e-01,1.100000010988609489e+01,5.747688945127961066e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951129976307748848e+01,7.053725723475077984e+02,5.032557801118251462e-01,1.100000010988609489e+01,5.746229091112583891e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951220885397749782e+01,7.053825723458568291e+02,5.032615263406000627e-01,1.100000010988609489e+01,5.744769237097206716e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951311794487750717e+01,7.053925723442066555e+02,5.032672711095211859e-01,1.100000010988609489e+01,5.743309383081829540e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951402703577751652e+01,7.054025723425573915e+02,5.032730144185885157e-01,1.100000010988609489e+01,5.741849529066452365e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951493612667752586e+01,7.054125723409089233e+02,5.032787562678020521e-01,1.100000010988609489e+01,5.740389675051075190e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951584521757753521e+01,7.054225723392613645e+02,5.032844966571617951e-01,1.100000010988609489e+01,5.738929821035698015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951675430847754455e+01,7.054325723376146016e+02,5.032902355866678556e-01,1.100000010988609489e+01,5.737469967020320839e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951766339937755390e+01,7.054425723359686344e+02,5.032959730563201228e-01,1.100000010988609489e+01,5.736010113004943664e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951857249027756325e+01,7.054525723343235768e+02,5.033017090661185966e-01,1.100000010988609489e+01,5.734550258989566489e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.951948158117757259e+01,7.054625723326793150e+02,5.033074436160632770e-01,1.100000010988609489e+01,5.733090404974189314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952039067207758194e+01,7.054725723310358489e+02,5.033131767061541639e-01,1.100000010988609489e+01,5.731630550958812138e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952129976297759129e+01,7.054825723293932924e+02,5.033189083363912575e-01,1.100000010988609489e+01,5.730170696943434963e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952220885387760063e+01,7.054925723277515317e+02,5.033246385067746687e-01,1.100000010988609489e+01,5.728710842928057788e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952311794477760998e+01,7.055025723261106805e+02,5.033303672173042864e-01,1.100000010988609489e+01,5.727250988912680613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952402703567761932e+01,7.055125723244706251e+02,5.033360944679801108e-01,1.100000010988609489e+01,5.725791134897303437e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952493612657762867e+01,7.055225723228313655e+02,5.033418202588021417e-01,1.100000010988609489e+01,5.724331280881926262e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952584521747763802e+01,7.055325723211930153e+02,5.033475445897703793e-01,1.100000010988609489e+01,5.722871426866549087e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952675430837764736e+01,7.055425723195554610e+02,5.033532674608848234e-01,1.100000010988609489e+01,5.721411572851171912e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952766339927765671e+01,7.055525723179187025e+02,5.033589888721454741e-01,1.100000010988609489e+01,5.719951718835794736e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952857249017766605e+01,7.055625723162828535e+02,5.033647088235524425e-01,1.100000010988609489e+01,5.718491864820417561e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.952948158107767540e+01,7.055725723146478003e+02,5.033704273151056174e-01,1.100000010988609489e+01,5.717032010805040386e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953039067197768475e+01,7.055825723130135430e+02,5.033761443468049990e-01,1.100000010988609489e+01,5.715572156789663211e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953129976287769409e+01,7.055925723113801951e+02,5.033818599186505871e-01,1.100000010988609489e+01,5.714112302774286035e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953220885377770344e+01,7.056025723097476430e+02,5.033875740306423818e-01,1.100000010988609489e+01,5.712652448758908860e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953311794467771279e+01,7.056125723081158867e+02,5.033932866827803831e-01,1.100000010988609489e+01,5.711192594743531685e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953402703557772213e+01,7.056225723064850399e+02,5.033989978750647021e-01,1.100000010988609489e+01,5.709732740728154510e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953493612647773148e+01,7.056325723048549889e+02,5.034047076074952276e-01,1.100000010988609489e+01,5.708272886712777335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953584521737774082e+01,7.056425723032257338e+02,5.034104158800719597e-01,1.100000010988609489e+01,5.706813032697400159e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953675430827775017e+01,7.056525723015973881e+02,5.034161226927948984e-01,1.100000010988609489e+01,5.705353178682022984e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953766339917775952e+01,7.056625722999698382e+02,5.034218280456640437e-01,1.100000010988609489e+01,5.703893324666645809e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953857249007776886e+01,7.056725722983430842e+02,5.034275319386793957e-01,1.100000010988609489e+01,5.702433470651268634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.953948158097777821e+01,7.056825722967172396e+02,5.034332343718409541e-01,1.100000010988609489e+01,5.700973616635891458e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954039067187778755e+01,7.056925722950921909e+02,5.034389353451488303e-01,1.100000010988609489e+01,5.699513762620514283e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954129976277779690e+01,7.057025722934679379e+02,5.034446348586029130e-01,1.100000010988609489e+01,5.698053908605137108e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954220885367780625e+01,7.057125722918445945e+02,5.034503329122032023e-01,1.100000010988609489e+01,5.696594054589759933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954311794457781559e+01,7.057225722902220468e+02,5.034560295059496982e-01,1.100000010988609489e+01,5.695134200574382757e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954402703547782494e+01,7.057325722886002950e+02,5.034617246398424006e-01,1.100000010988609489e+01,5.693674346559005582e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954493612637783428e+01,7.057425722869794527e+02,5.034674183138813097e-01,1.100000010988609489e+01,5.692214492543628407e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954584521727784363e+01,7.057525722853594061e+02,5.034731105280664254e-01,1.100000010988609489e+01,5.690754638528251232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954675430817785298e+01,7.057625722837401554e+02,5.034788012823977477e-01,1.100000010988609489e+01,5.689294784512874056e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954766339907786232e+01,7.057725722821217005e+02,5.034844905768753875e-01,1.100000010988609489e+01,5.687834930497496881e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954857248997787167e+01,7.057825722805041551e+02,5.034901784114992340e-01,1.100000010988609489e+01,5.686375076482119706e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.954948158087788102e+01,7.057925722788874054e+02,5.034958647862692871e-01,1.100000010988609489e+01,5.684915222466742531e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955039067177789036e+01,7.058025722772714516e+02,5.035015497011855468e-01,1.100000010988609489e+01,5.683455368451365355e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955129976267789971e+01,7.058125722756564073e+02,5.035072331562480130e-01,1.100000010988609489e+01,5.681995514435988180e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955220885357790905e+01,7.058225722740421588e+02,5.035129151514566859e-01,1.100000010988609489e+01,5.680535660420611005e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955311794447791840e+01,7.058325722724287061e+02,5.035185956868115653e-01,1.100000010988609489e+01,5.679075806405233830e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955402703537792775e+01,7.058425722708161629e+02,5.035242747623126514e-01,1.100000010988609489e+01,5.677615952389856654e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955493612627793709e+01,7.058525722692044155e+02,5.035299523779600550e-01,1.100000010988609489e+01,5.676156098374479479e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955584521717794644e+01,7.058625722675934639e+02,5.035356285337536653e-01,1.100000010988609489e+01,5.674696244359102304e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955675430807795578e+01,7.058725722659833082e+02,5.035413032296934821e-01,1.100000010988609489e+01,5.673236390343725129e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955766339897796513e+01,7.058825722643740619e+02,5.035469764657795055e-01,1.100000010988609489e+01,5.671776536328347953e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955857248987797448e+01,7.058925722627656114e+02,5.035526482420117356e-01,1.100000010988609489e+01,5.670316682312970778e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.955948158077798382e+01,7.059025722611579567e+02,5.035583185583901722e-01,1.100000010988609489e+01,5.668856828297593603e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956039067167799317e+01,7.059125722595512116e+02,5.035639874149148154e-01,1.100000010988609489e+01,5.667396974282216428e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956129976257800251e+01,7.059225722579452622e+02,5.035696548115856652e-01,1.100000010988609489e+01,5.665937120266839253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956220885347801186e+01,7.059325722563401087e+02,5.035753207484028326e-01,1.100000010988609489e+01,5.664477266251462077e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956311794437802121e+01,7.059425722547357509e+02,5.035809852253662067e-01,1.100000010988609489e+01,5.663017412236084902e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956402703527803055e+01,7.059525722531323026e+02,5.035866482424757873e-01,1.100000010988609489e+01,5.661557558220707727e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956493612617803990e+01,7.059625722515296502e+02,5.035923097997315745e-01,1.100000010988609489e+01,5.660097704205330552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956584521707804925e+01,7.059725722499277936e+02,5.035979698971335683e-01,1.100000010988609489e+01,5.658637850189953376e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956675430797805859e+01,7.059825722483267327e+02,5.036036285346817687e-01,1.100000010988609489e+01,5.657177996174576201e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956766339887806794e+01,7.059925722467265814e+02,5.036092857123761757e-01,1.100000010988609489e+01,5.655718142159199026e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956857248977807728e+01,7.060025722451272259e+02,5.036149414302167893e-01,1.100000010988609489e+01,5.654258288143821851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.956948158067808663e+01,7.060125722435286661e+02,5.036205956882036094e-01,1.100000010988609489e+01,5.652798434128444675e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957039067157809598e+01,7.060225722419310159e+02,5.036262484863366362e-01,1.100000010988609489e+01,5.651338580113067500e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957129976247810532e+01,7.060325722403341615e+02,5.036318998246159806e-01,1.100000010988609489e+01,5.649878726097690325e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957220885337811467e+01,7.060425722387381029e+02,5.036375497030415316e-01,1.100000010988609489e+01,5.648418872082313150e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957311794427812401e+01,7.060525722371428401e+02,5.036431981216132892e-01,1.100000010988609489e+01,5.646959018066935974e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957402703517813336e+01,7.060625722355484868e+02,5.036488450803312533e-01,1.100000010988609489e+01,5.645499164051558799e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957493612607814271e+01,7.060725722339549293e+02,5.036544905791954241e-01,1.100000010988609489e+01,5.644039310036181624e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957584521697815205e+01,7.060825722323621676e+02,5.036601346182058014e-01,1.100000010988609489e+01,5.642579456020804449e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957675430787816140e+01,7.060925722307702017e+02,5.036657771973623854e-01,1.100000010988609489e+01,5.641119602005427273e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957766339877817074e+01,7.061025722291791453e+02,5.036714183166651759e-01,1.100000010988609489e+01,5.639659747990050098e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957857248967818009e+01,7.061125722275888847e+02,5.036770579761141731e-01,1.100000010988609489e+01,5.638199893974672923e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.957948158057818944e+01,7.061225722259994200e+02,5.036826961757093768e-01,1.100000010988609489e+01,5.636740039959295748e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958039067147819878e+01,7.061325722244107510e+02,5.036883329154508981e-01,1.100000010988609489e+01,5.635280185943918572e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958129976237820813e+01,7.061425722228228778e+02,5.036939681953386261e-01,1.100000010988609489e+01,5.633820331928541397e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958220885327821748e+01,7.061525722212359142e+02,5.036996020153725606e-01,1.100000010988609489e+01,5.632360477913164222e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958311794417822682e+01,7.061625722196497463e+02,5.037052343755527017e-01,1.100000010988609489e+01,5.630900623897787047e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958402703507823617e+01,7.061725722180643743e+02,5.037108652758790495e-01,1.100000010988609489e+01,5.629440769882409872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958493612597824551e+01,7.061825722164797980e+02,5.037164947163516038e-01,1.100000010988609489e+01,5.627980915867032696e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958584521687825486e+01,7.061925722148961313e+02,5.037221226969703647e-01,1.100000010988609489e+01,5.626521061851655521e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958675430777826421e+01,7.062025722133132604e+02,5.037277492177353322e-01,1.100000010988609489e+01,5.625061207836278346e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958766339867827355e+01,7.062125722117311852e+02,5.037333742786465063e-01,1.100000010988609489e+01,5.623601353820901171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958857248957828290e+01,7.062225722101499059e+02,5.037389978797038870e-01,1.100000010988609489e+01,5.622141499805523995e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.958948158047829224e+01,7.062325722085695361e+02,5.037446200209074743e-01,1.100000010988609489e+01,5.620681645790146820e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959039067137830159e+01,7.062425722069899621e+02,5.037502407022572681e-01,1.100000010988609489e+01,5.619221791774769645e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959129976227831094e+01,7.062525722054111839e+02,5.037558599237533796e-01,1.100000010988609489e+01,5.617761937759392470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959220885317832028e+01,7.062625722038332015e+02,5.037614776853956977e-01,1.100000010988609489e+01,5.616302083744015294e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959311794407832963e+01,7.062725722022560149e+02,5.037670939871842224e-01,1.100000010988609489e+01,5.614842229728638119e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959402703497833897e+01,7.062825722006797378e+02,5.037727088291189537e-01,1.100000010988609489e+01,5.613382375713260944e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959493612587834832e+01,7.062925721991042565e+02,5.037783222111998915e-01,1.100000010988609489e+01,5.611922521697883769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959584521677835767e+01,7.063025721975295710e+02,5.037839341334270360e-01,1.100000010988609489e+01,5.610462667682506593e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959675430767836701e+01,7.063125721959556813e+02,5.037895445958003871e-01,1.100000010988609489e+01,5.609002813667129418e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959766339857837636e+01,7.063225721943825874e+02,5.037951535983199447e-01,1.100000010988609489e+01,5.607542959651752243e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959857248947838571e+01,7.063325721928104031e+02,5.038007611409857089e-01,1.100000010988609489e+01,5.606083105636375068e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.959948158037839505e+01,7.063425721912390145e+02,5.038063672237976798e-01,1.100000010988609489e+01,5.604623251620997892e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960039067127840440e+01,7.063525721896684217e+02,5.038119718467558572e-01,1.100000010988609489e+01,5.603163397605620717e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960129976217841374e+01,7.063625721880986248e+02,5.038175750098602412e-01,1.100000010988609489e+01,5.601703543590243542e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960220885307842309e+01,7.063725721865296237e+02,5.038231767131108318e-01,1.100000010988609489e+01,5.600243689574866367e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960311794397843244e+01,7.063825721849615320e+02,5.038287769565076291e-01,1.100000010988609489e+01,5.598783835559489191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960402703487844178e+01,7.063925721833942362e+02,5.038343757400506329e-01,1.100000010988609489e+01,5.597323981544112016e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960493612577845113e+01,7.064025721818277361e+02,5.038399730637399543e-01,1.100000010988609489e+01,5.595864127528734841e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960584521667846047e+01,7.064125721802620319e+02,5.038455689275754823e-01,1.100000010988609489e+01,5.594404273513357666e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960675430757846982e+01,7.064225721786971235e+02,5.038511633315572169e-01,1.100000010988609489e+01,5.592944419497980491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960766339847847917e+01,7.064325721771331246e+02,5.038567562756851581e-01,1.100000010988609489e+01,5.591484565482603315e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960857248937848851e+01,7.064425721755699215e+02,5.038623477599593059e-01,1.100000010988609489e+01,5.590024711467226140e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.960948158027849786e+01,7.064525721740075141e+02,5.038679377843796603e-01,1.100000010988609489e+01,5.588564857451848965e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961039067117850720e+01,7.064625721724459027e+02,5.038735263489462213e-01,1.100000010988609489e+01,5.587105003436471790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961129976207851655e+01,7.064725721708850870e+02,5.038791134536589889e-01,1.100000010988609489e+01,5.585645149421094614e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961220885297852590e+01,7.064825721693250671e+02,5.038846990985179630e-01,1.100000010988609489e+01,5.584185295405717439e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961311794387853524e+01,7.064925721677659567e+02,5.038902832835231438e-01,1.100000010988609489e+01,5.582725441390340264e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961402703477854459e+01,7.065025721662076421e+02,5.038958660086745311e-01,1.100000010988609489e+01,5.581265587374963089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961493612567855394e+01,7.065125721646501233e+02,5.039014472739721251e-01,1.100000010988609489e+01,5.579805733359585913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961584521657856328e+01,7.065225721630934004e+02,5.039070270794159256e-01,1.100000010988609489e+01,5.578345879344208738e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961675430747857263e+01,7.065325721615374732e+02,5.039126054250059328e-01,1.100000010988609489e+01,5.576886025328831563e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961766339837858197e+01,7.065425721599823419e+02,5.039181823107421465e-01,1.100000010988609489e+01,5.575426171313454388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961857248927859132e+01,7.065525721584281200e+02,5.039237577366245668e-01,1.100000010988609489e+01,5.573966317298077212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.961948158017860067e+01,7.065625721568746940e+02,5.039293317026531938e-01,1.100000010988609489e+01,5.572506463282700037e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962039067107861001e+01,7.065725721553220637e+02,5.039349042088280273e-01,1.100000010988609489e+01,5.571046609267322862e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962129976197861936e+01,7.065825721537702293e+02,5.039404752551490674e-01,1.100000010988609489e+01,5.569586755251945687e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962220885287862870e+01,7.065925721522191907e+02,5.039460448416163141e-01,1.100000010988609489e+01,5.568126901236568511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962311794377863805e+01,7.066025721506689479e+02,5.039516129682298784e-01,1.100000010988609489e+01,5.566667047221191336e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962402703467864740e+01,7.066125721491196146e+02,5.039571796349896493e-01,1.100000010988609489e+01,5.565207193205814161e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962493612557865674e+01,7.066225721475710770e+02,5.039627448418956268e-01,1.100000010988609489e+01,5.563747339190436986e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962584521647866609e+01,7.066325721460233353e+02,5.039683085889478109e-01,1.100000010988609489e+01,5.562287485175059810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962675430737867543e+01,7.066425721444763894e+02,5.039738708761462016e-01,1.100000010988609489e+01,5.560827631159682635e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962766339827868478e+01,7.066525721429302394e+02,5.039794317034907989e-01,1.100000010988609489e+01,5.559367777144305460e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962857248917869413e+01,7.066625721413848851e+02,5.039849910709816028e-01,1.100000010988609489e+01,5.557907923128928285e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.962948158007870347e+01,7.066725721398403266e+02,5.039905489786186132e-01,1.100000010988609489e+01,5.556448069113551110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963039067097871282e+01,7.066825721382966776e+02,5.039961054264018303e-01,1.100000010988609489e+01,5.554988215098173934e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963129976187872217e+01,7.066925721367538245e+02,5.040016604143312540e-01,1.100000010988609489e+01,5.553528361082796759e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963220885277873151e+01,7.067025721352117671e+02,5.040072139424068842e-01,1.100000010988609489e+01,5.552068507067419584e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963311794367874086e+01,7.067125721336705055e+02,5.040127660106287211e-01,1.100000010988609489e+01,5.550608653052042409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963402703457875020e+01,7.067225721321300398e+02,5.040183166189967645e-01,1.100000010988609489e+01,5.549148799036665233e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963493612547875955e+01,7.067325721305903699e+02,5.040238657675110145e-01,1.100000010988609489e+01,5.547688945021288058e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963584521637876890e+01,7.067425721290514957e+02,5.040294134561714712e-01,1.100000010988609489e+01,5.546229091005910883e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963675430727877824e+01,7.067525721275134174e+02,5.040349596849781344e-01,1.100000010988609489e+01,5.544769236990533708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963766339817878759e+01,7.067625721259762486e+02,5.040405044539310042e-01,1.100000010988609489e+01,5.543309382975156532e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963857248907879693e+01,7.067725721244398756e+02,5.040460477630300806e-01,1.100000010988609489e+01,5.541849528959779357e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.963948157997880628e+01,7.067825721229042983e+02,5.040515896122753636e-01,1.100000010988609489e+01,5.540389674944402182e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964039067087881563e+01,7.067925721213695169e+02,5.040571300016668532e-01,1.100000010988609489e+01,5.538929820929025007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964129976177882497e+01,7.068025721198355313e+02,5.040626689312045494e-01,1.100000010988609489e+01,5.537469966913647831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964220885267883432e+01,7.068125721183023416e+02,5.040682064008884522e-01,1.100000010988609489e+01,5.536010112898270656e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964311794357884366e+01,7.068225721167699476e+02,5.040737424107185616e-01,1.100000010988609489e+01,5.534550258882893481e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964402703447885301e+01,7.068325721152383494e+02,5.040792769606948776e-01,1.100000010988609489e+01,5.533090404867516306e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964493612537886236e+01,7.068425721137075470e+02,5.040848100508174001e-01,1.100000010988609489e+01,5.531630550852139130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964584521627887170e+01,7.068525721121776542e+02,5.040903416810861293e-01,1.100000010988609489e+01,5.530170696836761955e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964675430717888105e+01,7.068625721106485571e+02,5.040958718515010650e-01,1.100000010988609489e+01,5.528710842821384780e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964766339807889040e+01,7.068725721091202558e+02,5.041014005620622074e-01,1.100000010988609489e+01,5.527250988806007605e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964857248897889974e+01,7.068825721075927504e+02,5.041069278127695563e-01,1.100000010988609489e+01,5.525791134790630429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.964948157987890909e+01,7.068925721060660408e+02,5.041124536036231119e-01,1.100000010988609489e+01,5.524331280775253254e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965039067077891843e+01,7.069025721045401269e+02,5.041179779346228740e-01,1.100000010988609489e+01,5.522871426759876079e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965129976167892778e+01,7.069125721030150089e+02,5.041235008057688427e-01,1.100000010988609489e+01,5.521411572744498904e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965220885257893713e+01,7.069225721014906867e+02,5.041290222170610180e-01,1.100000010988609489e+01,5.519951718729121729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965311794347894647e+01,7.069325720999671603e+02,5.041345421684993999e-01,1.100000010988609489e+01,5.518491864713744553e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965402703437895582e+01,7.069425720984444297e+02,5.041400606600839884e-01,1.100000010988609489e+01,5.517032010698367378e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965493612527896516e+01,7.069525720969224949e+02,5.041455776918147835e-01,1.100000010988609489e+01,5.515572156682990203e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965584521617897451e+01,7.069625720954014696e+02,5.041510932636917852e-01,1.100000010988609489e+01,5.514112302667613028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965675430707898386e+01,7.069725720938812401e+02,5.041566073757149935e-01,1.100000010988609489e+01,5.512652448652235852e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965766339797899320e+01,7.069825720923618064e+02,5.041621200278844084e-01,1.100000010988609489e+01,5.511192594636858677e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965857248887900255e+01,7.069925720908431686e+02,5.041676312202000299e-01,1.100000010988609489e+01,5.509732740621481502e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.965948157977901189e+01,7.070025720893253265e+02,5.041731409526618579e-01,1.100000010988609489e+01,5.508272886606104327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966039067067902124e+01,7.070125720878082802e+02,5.041786492252698926e-01,1.100000010988609489e+01,5.506813032590727151e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966129976157903059e+01,7.070225720862920298e+02,5.041841560380241338e-01,1.100000010988609489e+01,5.505353178575349976e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966220885247903993e+01,7.070325720847765751e+02,5.041896613909245817e-01,1.100000010988609489e+01,5.503893324559972801e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966311794337904928e+01,7.070425720832619163e+02,5.041951652839712361e-01,1.100000010988609489e+01,5.502433470544595626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966402703427905863e+01,7.070525720817480533e+02,5.042006677171640971e-01,1.100000010988609489e+01,5.500973616529218450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966493612517906797e+01,7.070625720802349861e+02,5.042061686905031648e-01,1.100000010988609489e+01,5.499513762513841275e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966584521607907732e+01,7.070725720787227147e+02,5.042116682039884390e-01,1.100000010988609489e+01,5.498053908498464100e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966675430697908666e+01,7.070825720772112390e+02,5.042171662576199198e-01,1.100000010988609489e+01,5.496594054483086925e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966766339787909601e+01,7.070925720757005593e+02,5.042226628513976072e-01,1.100000010988609489e+01,5.495134200467709749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966857248877910536e+01,7.071025720741907890e+02,5.042281579853215012e-01,1.100000010988609489e+01,5.493674346452332574e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.966948157967911470e+01,7.071125720726818145e+02,5.042336516593916018e-01,1.100000010988609489e+01,5.492214492436955399e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967039067057912405e+01,7.071225720711736358e+02,5.042391438736079090e-01,1.100000010988609489e+01,5.490754638421578224e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967129976147913339e+01,7.071325720696662529e+02,5.042446346279704228e-01,1.100000010988609489e+01,5.489294784406201048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967220885237914274e+01,7.071425720681596658e+02,5.042501239224791432e-01,1.100000010988609489e+01,5.487834930390823873e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967311794327915209e+01,7.071525720666538746e+02,5.042556117571340701e-01,1.100000010988609489e+01,5.486375076375446698e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967402703417916143e+01,7.071625720651488791e+02,5.042610981319352037e-01,1.100000010988609489e+01,5.484915222360069523e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967493612507917078e+01,7.071725720636446795e+02,5.042665830468825439e-01,1.100000010988609489e+01,5.483455368344692347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967584521597918013e+01,7.071825720621412756e+02,5.042720665019760906e-01,1.100000010988609489e+01,5.481995514329315172e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967675430687918947e+01,7.071925720606386676e+02,5.042775484972158440e-01,1.100000010988609489e+01,5.480535660313937997e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967766339777919882e+01,7.072025720591368554e+02,5.042830290326018039e-01,1.100000010988609489e+01,5.479075806298560822e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967857248867920816e+01,7.072125720576358390e+02,5.042885081081339704e-01,1.100000010988609489e+01,5.477615952283183647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.967948157957921751e+01,7.072225720561356184e+02,5.042939857238123436e-01,1.100000010988609489e+01,5.476156098267806471e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968039067047922686e+01,7.072325720546361936e+02,5.042994618796369233e-01,1.100000010988609489e+01,5.474696244252429296e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968129976137923620e+01,7.072425720531375646e+02,5.043049365756077096e-01,1.100000010988609489e+01,5.473236390237052121e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968220885227924555e+01,7.072525720516397314e+02,5.043104098117247025e-01,1.100000010988609489e+01,5.471776536221674946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968311794317925489e+01,7.072625720501426940e+02,5.043158815879879020e-01,1.100000010988609489e+01,5.470316682206297770e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968402703407926424e+01,7.072725720486464525e+02,5.043213519043973081e-01,1.100000010988609489e+01,5.468856828190920595e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968493612497927359e+01,7.072825720471510067e+02,5.043268207609529208e-01,1.100000010988609489e+01,5.467396974175543420e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968584521587928293e+01,7.072925720456563567e+02,5.043322881576547401e-01,1.100000010988609489e+01,5.465937120160166245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968675430677929228e+01,7.073025720441625026e+02,5.043377540945027659e-01,1.100000010988609489e+01,5.464477266144789069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968766339767930162e+01,7.073125720426694443e+02,5.043432185714969984e-01,1.100000010988609489e+01,5.463017412129411894e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968857248857931097e+01,7.073225720411771817e+02,5.043486815886374375e-01,1.100000010988609489e+01,5.461557558114034719e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.968948157947932032e+01,7.073325720396857150e+02,5.043541431459240831e-01,1.100000010988609489e+01,5.460097704098657544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969039067037932966e+01,7.073425720381950441e+02,5.043596032433569354e-01,1.100000010988609489e+01,5.458637850083280368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969129976127933901e+01,7.073525720367051690e+02,5.043650618809358832e-01,1.100000010988609489e+01,5.457177996067903193e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969220885217934836e+01,7.073625720352160897e+02,5.043705190586610376e-01,1.100000010988609489e+01,5.455718142052526018e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969311794307935770e+01,7.073725720337278062e+02,5.043759747765323986e-01,1.100000010988609489e+01,5.454258288037148843e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969402703397936705e+01,7.073825720322403185e+02,5.043814290345499662e-01,1.100000010988609489e+01,5.452798434021771667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969493612487937639e+01,7.073925720307536267e+02,5.043868818327137404e-01,1.100000010988609489e+01,5.451338580006394492e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969584521577938574e+01,7.074025720292677306e+02,5.043923331710237212e-01,1.100000010988609489e+01,5.449878725991017317e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969675430667939509e+01,7.074125720277826304e+02,5.043977830494799086e-01,1.100000010988609489e+01,5.448418871975640142e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969766339757940443e+01,7.074225720262983259e+02,5.044032314680823026e-01,1.100000010988609489e+01,5.446959017960262966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969857248847941378e+01,7.074325720248148173e+02,5.044086784268309032e-01,1.100000010988609489e+01,5.445499163944885791e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.969948157937942312e+01,7.074425720233321044e+02,5.044141239257257103e-01,1.100000010988609489e+01,5.444039309929508616e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970039067027943247e+01,7.074525720218501874e+02,5.044195679647667241e-01,1.100000010988609489e+01,5.442579455914131441e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970129976117944182e+01,7.074625720203690662e+02,5.044250105439539444e-01,1.100000010988609489e+01,5.441119601898754266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970220885207945116e+01,7.074725720188887408e+02,5.044304516632873714e-01,1.100000010988609489e+01,5.439659747883377090e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970311794297946051e+01,7.074825720174092112e+02,5.044358913227670049e-01,1.100000010988609489e+01,5.438199893867999915e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970402703387946985e+01,7.074925720159304774e+02,5.044413295223928451e-01,1.100000010988609489e+01,5.436740039852622740e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970493612477947920e+01,7.075025720144525394e+02,5.044467662621648918e-01,1.100000010988609489e+01,5.435280185837245565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970584521567948855e+01,7.075125720129753972e+02,5.044522015420831451e-01,1.100000010988609489e+01,5.433820331821868389e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970675430657949789e+01,7.075225720114990509e+02,5.044576353621476050e-01,1.100000010988609489e+01,5.432360477806491214e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970766339747950724e+01,7.075325720100235003e+02,5.044630677223582715e-01,1.100000010988609489e+01,5.430900623791114039e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970857248837951659e+01,7.075425720085487455e+02,5.044684986227151446e-01,1.100000010988609489e+01,5.429440769775736864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.970948157927952593e+01,7.075525720070747866e+02,5.044739280632181133e-01,1.100000010988609489e+01,5.427980915760359688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971039067017953528e+01,7.075625720056016235e+02,5.044793560438672886e-01,1.100000010988609489e+01,5.426521061744982513e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971129976107954462e+01,7.075725720041292561e+02,5.044847825646626704e-01,1.100000010988609489e+01,5.425061207729605338e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971220885197955397e+01,7.075825720026576846e+02,5.044902076256042589e-01,1.100000010988609489e+01,5.423601353714228163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971311794287956332e+01,7.075925720011869089e+02,5.044956312266920539e-01,1.100000010988609489e+01,5.422141499698850987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971402703377957266e+01,7.076025719997169290e+02,5.045010533679260556e-01,1.100000010988609489e+01,5.420681645683473812e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971493612467958201e+01,7.076125719982477449e+02,5.045064740493062638e-01,1.100000010988609489e+01,5.419221791668096637e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971584521557959135e+01,7.076225719967793566e+02,5.045118932708326787e-01,1.100000010988609489e+01,5.417761937652719462e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971675430647960070e+01,7.076325719953117641e+02,5.045173110325053001e-01,1.100000010988609489e+01,5.416302083637342286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971766339737961005e+01,7.076425719938449674e+02,5.045227273343241281e-01,1.100000010988609489e+01,5.414842229621965111e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971857248827961939e+01,7.076525719923789666e+02,5.045281421762891627e-01,1.100000010988609489e+01,5.413382375606587936e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.971948157917962874e+01,7.076625719909137615e+02,5.045335555584004039e-01,1.100000010988609489e+01,5.411922521591210761e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972039067007963808e+01,7.076725719894493523e+02,5.045389674806578517e-01,1.100000010988609489e+01,5.410462667575833585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972129976097964743e+01,7.076825719879857388e+02,5.045443779430615061e-01,1.100000010988609489e+01,5.409002813560456410e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972220885187965678e+01,7.076925719865229212e+02,5.045497869456113671e-01,1.100000010988609489e+01,5.407542959545079235e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972311794277966612e+01,7.077025719850608994e+02,5.045551944883073237e-01,1.100000010988609489e+01,5.406083105529702060e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972402703367967547e+01,7.077125719835995596e+02,5.045606005711494868e-01,1.100000010988609489e+01,5.404623251514324885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972493612457968482e+01,7.077225719821390157e+02,5.045660051941378565e-01,1.100000010988609489e+01,5.403163397498947709e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972584521547969416e+01,7.077325719806792677e+02,5.045714083572724329e-01,1.100000010988609489e+01,5.401703543483570534e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972675430637970351e+01,7.077425719792203154e+02,5.045768100605532158e-01,1.100000010988609489e+01,5.400243689468193359e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972766339727971285e+01,7.077525719777621589e+02,5.045822103039802053e-01,1.100000010988609489e+01,5.398783835452816184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972857248817972220e+01,7.077625719763047982e+02,5.045876090875534015e-01,1.100000010988609489e+01,5.397323981437439008e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.972948157907973155e+01,7.077725719748482334e+02,5.045930064112728042e-01,1.100000010988609489e+01,5.395864127422061833e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973039066997974089e+01,7.077825719733924643e+02,5.045984022751384135e-01,1.100000010988609489e+01,5.394404273406684658e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973129976087975024e+01,7.077925719719374911e+02,5.046037966791502294e-01,1.100000010988609489e+01,5.392944419391307483e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973220885177975958e+01,7.078025719704833136e+02,5.046091896233082519e-01,1.100000010988609489e+01,5.391484565375930307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973311794267976893e+01,7.078125719690299320e+02,5.046145811076124810e-01,1.100000010988609489e+01,5.390024711360553132e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973402703357977828e+01,7.078225719675773462e+02,5.046199711320628056e-01,1.100000010988609489e+01,5.388564857345175957e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973493612447978762e+01,7.078325719661255562e+02,5.046253596966593369e-01,1.100000010988609489e+01,5.387105003329798782e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973584521537979697e+01,7.078425719646745620e+02,5.046307468014020747e-01,1.100000010988609489e+01,5.385645149314421606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973675430627980631e+01,7.078525719632242499e+02,5.046361324462910192e-01,1.100000010988609489e+01,5.384185295299044431e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973766339717981566e+01,7.078625719617747336e+02,5.046415166313261702e-01,1.100000010988609489e+01,5.382725441283667256e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973857248807982501e+01,7.078725719603260131e+02,5.046468993565075278e-01,1.100000010988609489e+01,5.381265587268290081e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.973948157897983435e+01,7.078825719588780885e+02,5.046522806218350921e-01,1.100000010988609489e+01,5.379805733252912905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974039066987984370e+01,7.078925719574309596e+02,5.046576604273088629e-01,1.100000010988609489e+01,5.378345879237535730e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974129976077985305e+01,7.079025719559846266e+02,5.046630387729288403e-01,1.100000010988609489e+01,5.376886025222158555e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974220885167986239e+01,7.079125719545390893e+02,5.046684156586950243e-01,1.100000010988609489e+01,5.375426171206781380e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974311794257987174e+01,7.079225719530943479e+02,5.046737910846073039e-01,1.100000010988609489e+01,5.373966317191404204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974402703347988108e+01,7.079325719516504023e+02,5.046791650506657900e-01,1.100000010988609489e+01,5.372506463176027029e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974493612437989043e+01,7.079425719502072525e+02,5.046845375568704828e-01,1.100000010988609489e+01,5.371046609160649854e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974584521527989978e+01,7.079525719487648985e+02,5.046899086032213821e-01,1.100000010988609489e+01,5.369586755145272679e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974675430617990912e+01,7.079625719473232266e+02,5.046952781897184881e-01,1.100000010988609489e+01,5.368126901129895504e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974766339707991847e+01,7.079725719458823505e+02,5.047006463163618006e-01,1.100000010988609489e+01,5.366667047114518328e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974857248797992781e+01,7.079825719444422703e+02,5.047060129831513198e-01,1.100000010988609489e+01,5.365207193099141153e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.974948157887993716e+01,7.079925719430029858e+02,5.047113781900870455e-01,1.100000010988609489e+01,5.363747339083763978e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975039066977994651e+01,7.080025719415644971e+02,5.047167419371689778e-01,1.100000010988609489e+01,5.362287485068386803e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975129976067995585e+01,7.080125719401268043e+02,5.047221042243971167e-01,1.100000010988609489e+01,5.360827631053009627e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975220885157996520e+01,7.080225719386899073e+02,5.047274650517713512e-01,1.100000010988609489e+01,5.359367777037632452e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975311794247997454e+01,7.080325719372538060e+02,5.047328244192917923e-01,1.100000010988609489e+01,5.357907923022255277e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975402703337998389e+01,7.080425719358185006e+02,5.047381823269584400e-01,1.100000010988609489e+01,5.356448069006878102e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975493612427999324e+01,7.080525719343838773e+02,5.047435387747712943e-01,1.100000010988609489e+01,5.354988214991500926e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975584521518000258e+01,7.080625719329500498e+02,5.047488937627303551e-01,1.100000010988609489e+01,5.353528360976123751e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975675430608001193e+01,7.080725719315170181e+02,5.047542472908356226e-01,1.100000010988609489e+01,5.352068506960746576e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975766339698002128e+01,7.080825719300847823e+02,5.047595993590870966e-01,1.100000010988609489e+01,5.350608652945369401e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975857248788003062e+01,7.080925719286533422e+02,5.047649499674847773e-01,1.100000010988609489e+01,5.349148798929992225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.975948157878003997e+01,7.081025719272226979e+02,5.047702991160286645e-01,1.100000010988609489e+01,5.347688944914615050e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976039066968004931e+01,7.081125719257928495e+02,5.047756468047186473e-01,1.100000010988609489e+01,5.346229090899237875e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976129976058005866e+01,7.081225719243637968e+02,5.047809930335548367e-01,1.100000010988609489e+01,5.344769236883860700e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976220885148006801e+01,7.081325719229354263e+02,5.047863378025372327e-01,1.100000010988609489e+01,5.343309382868483524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976311794238007735e+01,7.081425719215078516e+02,5.047916811116658353e-01,1.100000010988609489e+01,5.341849528853106349e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976402703328008670e+01,7.081525719200810727e+02,5.047970229609406445e-01,1.100000010988609489e+01,5.340389674837729174e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976493612418009604e+01,7.081625719186550896e+02,5.048023633503616603e-01,1.100000010988609489e+01,5.338929820822351999e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976584521508010539e+01,7.081725719172299023e+02,5.048077022799288827e-01,1.100000010988609489e+01,5.337469966806974823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976675430598011474e+01,7.081825719158055108e+02,5.048130397496423116e-01,1.100000010988609489e+01,5.336010112791597648e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976766339688012408e+01,7.081925719143819151e+02,5.048183757595018362e-01,1.100000010988609489e+01,5.334550258776220473e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976857248778013343e+01,7.082025719129590016e+02,5.048237103095075673e-01,1.100000010988609489e+01,5.333090404760843298e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.976948157868014277e+01,7.082125719115368838e+02,5.048290433996595050e-01,1.100000010988609489e+01,5.331630550745466122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977039066958015212e+01,7.082225719101155619e+02,5.048343750299576493e-01,1.100000010988609489e+01,5.330170696730088947e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977129976048016147e+01,7.082325719086950357e+02,5.048397052004020003e-01,1.100000010988609489e+01,5.328710842714711772e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977220885138017081e+01,7.082425719072753054e+02,5.048450339109925578e-01,1.100000010988609489e+01,5.327250988699334597e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977311794228018016e+01,7.082525719058563709e+02,5.048503611617293219e-01,1.100000010988609489e+01,5.325791134683957422e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977402703318018951e+01,7.082625719044381185e+02,5.048556869526122926e-01,1.100000010988609489e+01,5.324331280668580246e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977493612408019885e+01,7.082725719030206619e+02,5.048610112836413588e-01,1.100000010988609489e+01,5.322871426653203071e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977584521498020820e+01,7.082825719016040011e+02,5.048663341548166317e-01,1.100000010988609489e+01,5.321411572637825896e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977675430588021754e+01,7.082925719001881362e+02,5.048716555661381111e-01,1.100000010988609489e+01,5.319951718622448721e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977766339678022689e+01,7.083025718987730670e+02,5.048769755176057972e-01,1.100000010988609489e+01,5.318491864607071545e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977857248768023624e+01,7.083125718973587936e+02,5.048822940092196898e-01,1.100000010988609489e+01,5.317032010591694370e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.977948157858024558e+01,7.083225718959452024e+02,5.048876110409797890e-01,1.100000010988609489e+01,5.315572156576317195e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978039066948025493e+01,7.083325718945324070e+02,5.048929266128860949e-01,1.100000010988609489e+01,5.314112302560940020e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978129976038026427e+01,7.083425718931204074e+02,5.048982407249384963e-01,1.100000010988609489e+01,5.312652448545562844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978220885128027362e+01,7.083525718917092036e+02,5.049035533771371043e-01,1.100000010988609489e+01,5.311192594530185669e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978311794218028297e+01,7.083625718902987956e+02,5.049088645694819188e-01,1.100000010988609489e+01,5.309732740514808494e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978402703308029231e+01,7.083725718888891834e+02,5.049141743019729400e-01,1.100000010988609489e+01,5.308272886499431319e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978493612398030166e+01,7.083825718874802533e+02,5.049194825746101678e-01,1.100000010988609489e+01,5.306813032484054143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978584521488031100e+01,7.083925718860721190e+02,5.049247893873936022e-01,1.100000010988609489e+01,5.305353178468676968e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978675430578032035e+01,7.084025718846647806e+02,5.049300947403232431e-01,1.100000010988609489e+01,5.303893324453299793e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978766339668032970e+01,7.084125718832582379e+02,5.049353986333989797e-01,1.100000010988609489e+01,5.302433470437922618e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978857248758033904e+01,7.084225718818524911e+02,5.049407010666209228e-01,1.100000010988609489e+01,5.300973616422545442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.978948157848034839e+01,7.084325718804474263e+02,5.049460020399890725e-01,1.100000010988609489e+01,5.299513762407168267e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979039066938035774e+01,7.084425718790431574e+02,5.049513015535034288e-01,1.100000010988609489e+01,5.298053908391791092e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979129976028036708e+01,7.084525718776396843e+02,5.049565996071639917e-01,1.100000010988609489e+01,5.296594054376413917e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979220885118037643e+01,7.084625718762370070e+02,5.049618962009707612e-01,1.100000010988609489e+01,5.295134200361036741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979311794208038577e+01,7.084725718748351255e+02,5.049671913349236263e-01,1.100000010988609489e+01,5.293674346345659566e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979402703298039512e+01,7.084825718734339262e+02,5.049724850090226980e-01,1.100000010988609489e+01,5.292214492330282391e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979493612388040447e+01,7.084925718720335226e+02,5.049777772232679762e-01,1.100000010988609489e+01,5.290754638314905216e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979584521478041381e+01,7.085025718706339148e+02,5.049830679776594611e-01,1.100000010988609489e+01,5.289294784299528041e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979675430568042316e+01,7.085125718692351029e+02,5.049883572721971525e-01,1.100000010988609489e+01,5.287834930284150865e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979766339658043250e+01,7.085225718678370868e+02,5.049936451068810506e-01,1.100000010988609489e+01,5.286375076268773690e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979857248748044185e+01,7.085325718664397527e+02,5.049989314817111552e-01,1.100000010988609489e+01,5.284915222253396515e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.979948157838045120e+01,7.085425718650432145e+02,5.050042163966873554e-01,1.100000010988609489e+01,5.283455368238019340e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980039066928046054e+01,7.085525718636474721e+02,5.050094998518097622e-01,1.100000010988609489e+01,5.281995514222642164e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980129976018046989e+01,7.085625718622525255e+02,5.050147818470783756e-01,1.100000010988609489e+01,5.280535660207264989e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980220885108047923e+01,7.085725718608583747e+02,5.050200623824931956e-01,1.100000010988609489e+01,5.279075806191887814e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980311794198048858e+01,7.085825718594649061e+02,5.050253414580542222e-01,1.100000010988609489e+01,5.277615952176510639e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980402703288049793e+01,7.085925718580722332e+02,5.050306190737614553e-01,1.100000010988609489e+01,5.276156098161133463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980493612378050727e+01,7.086025718566803562e+02,5.050358952296147841e-01,1.100000010988609489e+01,5.274696244145756288e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980584521468051662e+01,7.086125718552892749e+02,5.050411699256143194e-01,1.100000010988609489e+01,5.273236390130379113e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980675430558052597e+01,7.086225718538988758e+02,5.050464431617600614e-01,1.100000010988609489e+01,5.271776536115001938e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980766339648053531e+01,7.086325718525092725e+02,5.050517149380520099e-01,1.100000010988609489e+01,5.270316682099624762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980857248738054466e+01,7.086425718511204650e+02,5.050569852544901650e-01,1.100000010988609489e+01,5.268856828084247587e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.980948157828055400e+01,7.086525718497324533e+02,5.050622541110744157e-01,1.100000010988609489e+01,5.267396974068870412e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981039066918056335e+01,7.086625718483451237e+02,5.050675215078048730e-01,1.100000010988609489e+01,5.265937120053493237e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981129976008057270e+01,7.086725718469585900e+02,5.050727874446815369e-01,1.100000010988609489e+01,5.264477266038116061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981220885098058204e+01,7.086825718455728520e+02,5.050780519217044073e-01,1.100000010988609489e+01,5.263017412022738886e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981311794188059139e+01,7.086925718441879098e+02,5.050833149388734844e-01,1.100000010988609489e+01,5.261557558007361711e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981402703278060073e+01,7.087025718428037635e+02,5.050885764961887681e-01,1.100000010988609489e+01,5.260097703991984536e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981493612368061008e+01,7.087125718414202993e+02,5.050938365936501473e-01,1.100000010988609489e+01,5.258637849976607360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981584521458061943e+01,7.087225718400376309e+02,5.050990952312577331e-01,1.100000010988609489e+01,5.257177995961230185e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981675430548062877e+01,7.087325718386557583e+02,5.051043524090115255e-01,1.100000010988609489e+01,5.255718141945853010e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981766339638063812e+01,7.087425718372746815e+02,5.051096081269115246e-01,1.100000010988609489e+01,5.254258287930475835e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981857248728064747e+01,7.087525718358942868e+02,5.051148623849577302e-01,1.100000010988609489e+01,5.252798433915098660e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.981948157818065681e+01,7.087625718345146879e+02,5.051201151831501424e-01,1.100000010988609489e+01,5.251338579899721484e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982039066908066616e+01,7.087725718331358848e+02,5.051253665214886501e-01,1.100000010988609489e+01,5.249878725884344309e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982129975998067550e+01,7.087825718317578776e+02,5.051306163999733645e-01,1.100000010988609489e+01,5.248418871868967134e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982220885088068485e+01,7.087925718303805525e+02,5.051358648186042855e-01,1.100000010988609489e+01,5.246959017853589959e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982311794178069420e+01,7.088025718290040231e+02,5.051411117773814130e-01,1.100000010988609489e+01,5.245499163838212783e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982402703268070354e+01,7.088125718276282896e+02,5.051463572763047472e-01,1.100000010988609489e+01,5.244039309822835608e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982493612358071289e+01,7.088225718262532382e+02,5.051516013153741769e-01,1.100000010988609489e+01,5.242579455807458433e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982584521448072223e+01,7.088325718248789826e+02,5.051568438945898132e-01,1.100000010988609489e+01,5.241119601792081258e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982675430538073158e+01,7.088425718235055228e+02,5.051620850139516561e-01,1.100000010988609489e+01,5.239659747776704082e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982766339628074093e+01,7.088525718221328589e+02,5.051673246734597056e-01,1.100000010988609489e+01,5.238199893761326907e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982857248718075027e+01,7.088625718207608770e+02,5.051725628731139617e-01,1.100000010988609489e+01,5.236740039745949732e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.982948157808075962e+01,7.088725718193896910e+02,5.051777996129143133e-01,1.100000010988609489e+01,5.235280185730572557e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983039066898076896e+01,7.088825718180193007e+02,5.051830348928608716e-01,1.100000010988609489e+01,5.233820331715195381e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983129975988077831e+01,7.088925718166497063e+02,5.051882687129536365e-01,1.100000010988609489e+01,5.232360477699818206e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983220885078078766e+01,7.089025718152807940e+02,5.051935010731926079e-01,1.100000010988609489e+01,5.230900623684441031e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983311794168079700e+01,7.089125718139126775e+02,5.051987319735777859e-01,1.100000010988609489e+01,5.229440769669063856e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983402703258080635e+01,7.089225718125453568e+02,5.052039614141090595e-01,1.100000010988609489e+01,5.227980915653686680e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983493612348081570e+01,7.089325718111787182e+02,5.052091893947865398e-01,1.100000010988609489e+01,5.226521061638309505e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983584521438082504e+01,7.089425718098128755e+02,5.052144159156102265e-01,1.100000010988609489e+01,5.225061207622932330e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983675430528083439e+01,7.089525718084478285e+02,5.052196409765801199e-01,1.100000010988609489e+01,5.223601353607555155e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983766339618084373e+01,7.089625718070835774e+02,5.052248645776962199e-01,1.100000010988609489e+01,5.222141499592177979e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983857248708085308e+01,7.089725718057200083e+02,5.052300867189584155e-01,1.100000010988609489e+01,5.220681645576800804e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.983948157798086243e+01,7.089825718043572351e+02,5.052353074003668176e-01,1.100000010988609489e+01,5.219221791561423629e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984039066888087177e+01,7.089925718029952577e+02,5.052405266219214264e-01,1.100000010988609489e+01,5.217761937546046454e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984129975978088112e+01,7.090025718016339624e+02,5.052457443836222417e-01,1.100000010988609489e+01,5.216302083530669279e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984220885068089046e+01,7.090125718002734629e+02,5.052509606854692636e-01,1.100000010988609489e+01,5.214842229515292103e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984311794158089981e+01,7.090225717989137593e+02,5.052561755274623811e-01,1.100000010988609489e+01,5.213382375499914928e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984402703248090916e+01,7.090325717975547377e+02,5.052613889096017052e-01,1.100000010988609489e+01,5.211922521484537753e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984493612338091850e+01,7.090425717961965120e+02,5.052666008318872359e-01,1.100000010988609489e+01,5.210462667469160578e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984584521428092785e+01,7.090525717948390820e+02,5.052718112943189732e-01,1.100000010988609489e+01,5.209002813453783402e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984675430518093719e+01,7.090625717934824479e+02,5.052770202968968061e-01,1.100000010988609489e+01,5.207542959438406227e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984766339608094654e+01,7.090725717921264959e+02,5.052822278396208455e-01,1.100000010988609489e+01,5.206083105423029052e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984857248698095589e+01,7.090825717907713397e+02,5.052874339224910916e-01,1.100000010988609489e+01,5.204623251407651877e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.984948157788096523e+01,7.090925717894169793e+02,5.052926385455075442e-01,1.100000010988609489e+01,5.203163397392274701e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985039066878097458e+01,7.091025717880633010e+02,5.052978417086702034e-01,1.100000010988609489e+01,5.201703543376897526e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985129975968098393e+01,7.091125717867104186e+02,5.053030434119789582e-01,1.100000010988609489e+01,5.200243689361520351e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985220885058099327e+01,7.091225717853583319e+02,5.053082436554339196e-01,1.100000010988609489e+01,5.198783835346143176e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985311794148100262e+01,7.091325717840069274e+02,5.053134424390350876e-01,1.100000010988609489e+01,5.197323981330766000e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985402703238101196e+01,7.091425717826563186e+02,5.053186397627824622e-01,1.100000010988609489e+01,5.195864127315388825e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985493612328102131e+01,7.091525717813065057e+02,5.053238356266760434e-01,1.100000010988609489e+01,5.194404273300011650e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985584521418103066e+01,7.091625717799573749e+02,5.053290300307157201e-01,1.100000010988609489e+01,5.192944419284634475e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985675430508104000e+01,7.091725717786090399e+02,5.053342229749016035e-01,1.100000010988609489e+01,5.191484565269257299e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985766339598104935e+01,7.091825717772615008e+02,5.053394144592336934e-01,1.100000010988609489e+01,5.190024711253880124e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985857248688105869e+01,7.091925717759146437e+02,5.053446044837119899e-01,1.100000010988609489e+01,5.188564857238502949e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.985948157778106804e+01,7.092025717745685824e+02,5.053497930483363820e-01,1.100000010988609489e+01,5.187105003223125774e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986039066868107739e+01,7.092125717732233170e+02,5.053549801531069807e-01,1.100000010988609489e+01,5.185645149207748598e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986129975958108673e+01,7.092225717718787337e+02,5.053601657980237860e-01,1.100000010988609489e+01,5.184185295192371423e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986220885048109608e+01,7.092325717705349462e+02,5.053653499830867979e-01,1.100000010988609489e+01,5.182725441176994248e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986311794138110542e+01,7.092425717691919544e+02,5.053705327082959053e-01,1.100000010988609489e+01,5.181265587161617073e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986402703228111477e+01,7.092525717678496449e+02,5.053757139736512194e-01,1.100000010988609489e+01,5.179805733146239898e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986493612318112412e+01,7.092625717665081311e+02,5.053808937791527400e-01,1.100000010988609489e+01,5.178345879130862722e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986584521408113346e+01,7.092725717651674131e+02,5.053860721248004673e-01,1.100000010988609489e+01,5.176886025115485547e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986675430498114281e+01,7.092825717638273773e+02,5.053912490105944011e-01,1.100000010988609489e+01,5.175426171100108372e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986766339588115216e+01,7.092925717624881372e+02,5.053964244365344305e-01,1.100000010988609489e+01,5.173966317084731197e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986857248678116150e+01,7.093025717611496930e+02,5.054015984026206665e-01,1.100000010988609489e+01,5.172506463069354021e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.986948157768117085e+01,7.093125717598119309e+02,5.054067709088531091e-01,1.100000010988609489e+01,5.171046609053976846e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987039066858118019e+01,7.093225717584749646e+02,5.054119419552317583e-01,1.100000010988609489e+01,5.169586755038599671e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987129975948118954e+01,7.093325717571386804e+02,5.054171115417565030e-01,1.100000010988609489e+01,5.168126901023222496e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987220885038119889e+01,7.093425717558031920e+02,5.054222796684274543e-01,1.100000010988609489e+01,5.166667047007845320e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987311794128120823e+01,7.093525717544684994e+02,5.054274463352446123e-01,1.100000010988609489e+01,5.165207192992468145e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987402703218121758e+01,7.093625717531344890e+02,5.054326115422079768e-01,1.100000010988609489e+01,5.163747338977090970e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987493612308122692e+01,7.093725717518012743e+02,5.054377752893174369e-01,1.100000010988609489e+01,5.162287484961713795e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987584521398123627e+01,7.093825717504688555e+02,5.054429375765731036e-01,1.100000010988609489e+01,5.160827630946336619e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987675430488124562e+01,7.093925717491371188e+02,5.054480984039749769e-01,1.100000010988609489e+01,5.159367776930959444e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987766339578125496e+01,7.094025717478061779e+02,5.054532577715230568e-01,1.100000010988609489e+01,5.157907922915582269e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987857248668126431e+01,7.094125717464760328e+02,5.054584156792172323e-01,1.100000010988609489e+01,5.156448068900205094e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.987948157758127365e+01,7.094225717451465698e+02,5.054635721270576143e-01,1.100000010988609489e+01,5.154988214884827918e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988039066848128300e+01,7.094325717438179026e+02,5.054687271150442029e-01,1.100000010988609489e+01,5.153528360869450743e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988129975938129235e+01,7.094425717424899176e+02,5.054738806431769982e-01,1.100000010988609489e+01,5.152068506854073568e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988220885028130169e+01,7.094525717411627284e+02,5.054790327114558890e-01,1.100000010988609489e+01,5.150608652838696393e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988311794118131104e+01,7.094625717398363349e+02,5.054841833198809864e-01,1.100000010988609489e+01,5.149148798823319217e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988402703208132039e+01,7.094725717385106236e+02,5.054893324684522904e-01,1.100000010988609489e+01,5.147688944807942042e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988493612298132973e+01,7.094825717371857081e+02,5.054944801571698010e-01,1.100000010988609489e+01,5.146229090792564867e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988584521388133908e+01,7.094925717358614747e+02,5.054996263860334071e-01,1.100000010988609489e+01,5.144769236777187692e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988675430478134842e+01,7.095025717345380372e+02,5.055047711550432199e-01,1.100000010988609489e+01,5.143309382761810516e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988766339568135777e+01,7.095125717332153954e+02,5.055099144641992392e-01,1.100000010988609489e+01,5.141849528746433341e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988857248658136712e+01,7.095225717318934358e+02,5.055150563135014652e-01,1.100000010988609489e+01,5.140389674731056166e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.988948157748137646e+01,7.095325717305722719e+02,5.055201967029497867e-01,1.100000010988609489e+01,5.138929820715678991e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989039066838138581e+01,7.095425717292517902e+02,5.055253356325443148e-01,1.100000010988609489e+01,5.137469966700301816e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989129975928139515e+01,7.095525717279321043e+02,5.055304731022850495e-01,1.100000010988609489e+01,5.136010112684924640e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989220885018140450e+01,7.095625717266132142e+02,5.055356091121718798e-01,1.100000010988609489e+01,5.134550258669547465e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989311794108141385e+01,7.095725717252950062e+02,5.055407436622049167e-01,1.100000010988609489e+01,5.133090404654170290e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989402703198142319e+01,7.095825717239775940e+02,5.055458767523841601e-01,1.100000010988609489e+01,5.131630550638793115e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989493612288143254e+01,7.095925717226608640e+02,5.055510083827096102e-01,1.100000010988609489e+01,5.130170696623415939e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989584521378144188e+01,7.096025717213449298e+02,5.055561385531811558e-01,1.100000010988609489e+01,5.128710842608038764e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989675430468145123e+01,7.096125717200297913e+02,5.055612672637989080e-01,1.100000010988609489e+01,5.127250988592661589e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989766339558146058e+01,7.096225717187153350e+02,5.055663945145628668e-01,1.100000010988609489e+01,5.125791134577284414e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989857248648146992e+01,7.096325717174016745e+02,5.055715203054730322e-01,1.100000010988609489e+01,5.124331280561907238e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.989948157738147927e+01,7.096425717160886961e+02,5.055766446365292932e-01,1.100000010988609489e+01,5.122871426546530063e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990039066828148862e+01,7.096525717147765135e+02,5.055817675077317608e-01,1.100000010988609489e+01,5.121411572531152888e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990129975918149796e+01,7.096625717134651268e+02,5.055868889190804349e-01,1.100000010988609489e+01,5.119951718515775713e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990220885008150731e+01,7.096725717121544221e+02,5.055920088705753157e-01,1.100000010988609489e+01,5.118491864500398537e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990311794098151665e+01,7.096825717108445133e+02,5.055971273622162920e-01,1.100000010988609489e+01,5.117032010485021362e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990402703188152600e+01,7.096925717095352866e+02,5.056022443940034750e-01,1.100000010988609489e+01,5.115572156469644187e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990493612278153535e+01,7.097025717082268557e+02,5.056073599659368645e-01,1.100000010988609489e+01,5.114112302454267012e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990584521368154469e+01,7.097125717069191069e+02,5.056124740780163496e-01,1.100000010988609489e+01,5.112652448438889836e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990675430458155404e+01,7.097225717056121539e+02,5.056175867302420412e-01,1.100000010988609489e+01,5.111192594423512661e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990766339548156338e+01,7.097325717043058830e+02,5.056226979226139395e-01,1.100000010988609489e+01,5.109732740408135486e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990857248638157273e+01,7.097425717030004080e+02,5.056278076551320444e-01,1.100000010988609489e+01,5.108272886392758311e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.990948157728158208e+01,7.097525717016957287e+02,5.056329159277962448e-01,1.100000010988609489e+01,5.106813032377381135e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991039066818159142e+01,7.097625717003917316e+02,5.056380227406066519e-01,1.100000010988609489e+01,5.105353178362003960e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991129975908160077e+01,7.097725716990885303e+02,5.056431280935632655e-01,1.100000010988609489e+01,5.103893324346626785e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991220884998161011e+01,7.097825716977860111e+02,5.056482319866659747e-01,1.100000010988609489e+01,5.102433470331249610e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991311794088161946e+01,7.097925716964842877e+02,5.056533344199148905e-01,1.100000010988609489e+01,5.100973616315872435e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991402703178162881e+01,7.098025716951832464e+02,5.056584353933100129e-01,1.100000010988609489e+01,5.099513762300495259e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991493612268163815e+01,7.098125716938830010e+02,5.056635349068513419e-01,1.100000010988609489e+01,5.098053908285118084e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991584521358164750e+01,7.098225716925834377e+02,5.056686329605387664e-01,1.100000010988609489e+01,5.096594054269740909e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991675430448165685e+01,7.098325716912846701e+02,5.056737295543723976e-01,1.100000010988609489e+01,5.095134200254363734e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991766339538166619e+01,7.098425716899866984e+02,5.056788246883522353e-01,1.100000010988609489e+01,5.093674346238986558e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991857248628167554e+01,7.098525716886894088e+02,5.056839183624781686e-01,1.100000010988609489e+01,5.092214492223609383e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.991948157718168488e+01,7.098625716873929150e+02,5.056890105767503085e-01,1.100000010988609489e+01,5.090754638208232208e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992039066808169423e+01,7.098725716860971033e+02,5.056941013311686550e-01,1.100000010988609489e+01,5.089294784192855033e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992129975898170358e+01,7.098825716848020875e+02,5.056991906257330971e-01,1.100000010988609489e+01,5.087834930177477857e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992220884988171292e+01,7.098925716835077537e+02,5.057042784604437458e-01,1.100000010988609489e+01,5.086375076162100682e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992311794078172227e+01,7.099025716822142158e+02,5.057093648353006010e-01,1.100000010988609489e+01,5.084915222146723507e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992402703168173161e+01,7.099125716809213600e+02,5.057144497503036629e-01,1.100000010988609489e+01,5.083455368131346332e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992493612258174096e+01,7.099225716796293000e+02,5.057195332054528203e-01,1.100000010988609489e+01,5.081995514115969156e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992584521348175031e+01,7.099325716783379221e+02,5.057246152007481843e-01,1.100000010988609489e+01,5.080535660100591981e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992675430438175965e+01,7.099425716770473400e+02,5.057296957361897549e-01,1.100000010988609489e+01,5.079075806085214806e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992766339528176900e+01,7.099525716757574401e+02,5.057347748117774211e-01,1.100000010988609489e+01,5.077615952069837631e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992857248618177834e+01,7.099625716744683359e+02,5.057398524275112939e-01,1.100000010988609489e+01,5.076156098054460455e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.992948157708178769e+01,7.099725716731799139e+02,5.057449285833913732e-01,1.100000010988609489e+01,5.074696244039083280e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993039066798179704e+01,7.099825716718922877e+02,5.057500032794175482e-01,1.100000010988609489e+01,5.073236390023706105e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993129975888180638e+01,7.099925716706054573e+02,5.057550765155899297e-01,1.100000010988609489e+01,5.071776536008328930e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993220884978181573e+01,7.100025716693193090e+02,5.057601482919085178e-01,1.100000010988609489e+01,5.070316681992951754e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993311794068182508e+01,7.100125716680339565e+02,5.057652186083733126e-01,1.100000010988609489e+01,5.068856827977574579e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993402703158183442e+01,7.100225716667492861e+02,5.057702874649842029e-01,1.100000010988609489e+01,5.067396973962197404e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993493612248184377e+01,7.100325716654654116e+02,5.057753548617412998e-01,1.100000010988609489e+01,5.065937119946820229e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993584521338185311e+01,7.100425716641822191e+02,5.057804207986446032e-01,1.100000010988609489e+01,5.064477265931443054e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993675430428186246e+01,7.100525716628998225e+02,5.057854852756940023e-01,1.100000010988609489e+01,5.063017411916065878e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993766339518187181e+01,7.100625716616181080e+02,5.057905482928896079e-01,1.100000010988609489e+01,5.061557557900688703e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993857248608188115e+01,7.100725716603371893e+02,5.057956098502314202e-01,1.100000010988609489e+01,5.060097703885311528e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.993948157698189050e+01,7.100825716590569527e+02,5.058006699477193280e-01,1.100000010988609489e+01,5.058637849869934353e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994039066788189984e+01,7.100925716577775120e+02,5.058057285853534424e-01,1.100000010988609489e+01,5.057177995854557177e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994129975878190919e+01,7.101025716564987533e+02,5.058107857631337634e-01,1.100000010988609489e+01,5.055718141839180002e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994220884968191854e+01,7.101125716552207905e+02,5.058158414810601800e-01,1.100000010988609489e+01,5.054258287823802827e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994311794058192788e+01,7.101225716539435098e+02,5.058208957391328031e-01,1.100000010988609489e+01,5.052798433808425652e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994402703148193723e+01,7.101325716526670249e+02,5.058259485373516329e-01,1.100000010988609489e+01,5.051338579793048476e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994493612238194657e+01,7.101425716513912221e+02,5.058309998757165582e-01,1.100000010988609489e+01,5.049878725777671301e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994584521328195592e+01,7.101525716501162151e+02,5.058360497542276901e-01,1.100000010988609489e+01,5.048418871762294126e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994675430418196527e+01,7.101625716488418902e+02,5.058410981728850286e-01,1.100000010988609489e+01,5.046959017746916951e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994766339508197461e+01,7.101725716475682475e+02,5.058461451316884627e-01,1.100000010988609489e+01,5.045499163731539775e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994857248598198396e+01,7.101825716462954006e+02,5.058511906306381034e-01,1.100000010988609489e+01,5.044039309716162600e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.994948157688199331e+01,7.101925716450232358e+02,5.058562346697339507e-01,1.100000010988609489e+01,5.042579455700785425e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995039066778200265e+01,7.102025716437518668e+02,5.058612772489760046e-01,1.100000010988609489e+01,5.041119601685408250e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995129975868201200e+01,7.102125716424811799e+02,5.058663183683641540e-01,1.100000010988609489e+01,5.039659747670031074e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995220884958202134e+01,7.102225716412112888e+02,5.058713580278985100e-01,1.100000010988609489e+01,5.038199893654653899e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995311794048203069e+01,7.102325716399420799e+02,5.058763962275790727e-01,1.100000010988609489e+01,5.036740039639276724e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995402703138204004e+01,7.102425716386736667e+02,5.058814329674057308e-01,1.100000010988609489e+01,5.035280185623899549e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995493612228204938e+01,7.102525716374059357e+02,5.058864682473785956e-01,1.100000010988609489e+01,5.033820331608522373e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995584521318205873e+01,7.102625716361390005e+02,5.058915020674976670e-01,1.100000010988609489e+01,5.032360477593145198e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995675430408206807e+01,7.102725716348727474e+02,5.058965344277628340e-01,1.100000010988609489e+01,5.030900623577768023e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995766339498207742e+01,7.102825716336072901e+02,5.059015653281742075e-01,1.100000010988609489e+01,5.029440769562390848e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995857248588208677e+01,7.102925716323425149e+02,5.059065947687317877e-01,1.100000010988609489e+01,5.027980915547013673e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.995948157678209611e+01,7.103025716310785356e+02,5.059116227494354634e-01,1.100000010988609489e+01,5.026521061531636497e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996039066768210546e+01,7.103125716298152383e+02,5.059166492702853457e-01,1.100000010988609489e+01,5.025061207516259322e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996129975858211480e+01,7.103225716285526232e+02,5.059216743312814346e-01,1.100000010988609489e+01,5.023601353500882147e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996220884948212415e+01,7.103325716272908039e+02,5.059266979324236191e-01,1.100000010988609489e+01,5.022141499485504972e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996311794038213350e+01,7.103425716260296667e+02,5.059317200737120102e-01,1.100000010988609489e+01,5.020681645470127796e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996402703128214284e+01,7.103525716247693254e+02,5.059367407551464968e-01,1.100000010988609489e+01,5.019221791454750621e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996493612218215219e+01,7.103625716235096661e+02,5.059417599767271900e-01,1.100000010988609489e+01,5.017761937439373446e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996584521308216154e+01,7.103725716222508026e+02,5.059467777384540899e-01,1.100000010988609489e+01,5.016302083423996271e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996675430398217088e+01,7.103825716209926213e+02,5.059517940403270853e-01,1.100000010988609489e+01,5.014842229408619095e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996766339488218023e+01,7.103925716197352358e+02,5.059568088823462872e-01,1.100000010988609489e+01,5.013382375393241920e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996857248578218957e+01,7.104025716184785324e+02,5.059618222645116958e-01,1.100000010988609489e+01,5.011922521377864745e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.996948157668219892e+01,7.104125716172225111e+02,5.059668341868232000e-01,1.100000010988609489e+01,5.010462667362487570e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997039066758220827e+01,7.104225716159672857e+02,5.059718446492809107e-01,1.100000010988609489e+01,5.009002813347110394e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997129975848221761e+01,7.104325716147127423e+02,5.059768536518848281e-01,1.100000010988609489e+01,5.007542959331733219e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997220884938222696e+01,7.104425716134589948e+02,5.059818611946348410e-01,1.100000010988609489e+01,5.006083105316356044e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997311794028223630e+01,7.104525716122059293e+02,5.059868672775310605e-01,1.100000010988609489e+01,5.004623251300978869e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997402703118224565e+01,7.104625716109536597e+02,5.059918719005734866e-01,1.100000010988609489e+01,5.003163397285601693e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997493612208225500e+01,7.104725716097020722e+02,5.059968750637620083e-01,1.100000010988609489e+01,5.001703543270224518e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997584521298226434e+01,7.104825716084511669e+02,5.060018767670967366e-01,1.100000010988609489e+01,5.000243689254847343e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997675430388227369e+01,7.104925716072010573e+02,5.060068770105776714e-01,1.100000010988609489e+01,4.998783835239470168e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997766339478228304e+01,7.105025716059516299e+02,5.060118757942047019e-01,1.100000010988609489e+01,4.997323981224092992e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997857248568229238e+01,7.105125716047029982e+02,5.060168731179779389e-01,1.100000010988609489e+01,4.995864127208715817e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.997948157658230173e+01,7.105225716034550487e+02,5.060218689818973825e-01,1.100000010988609489e+01,4.994404273193338642e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998039066748231107e+01,7.105325716022078950e+02,5.060268633859629217e-01,1.100000010988609489e+01,4.992944419177961467e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998129975838232042e+01,7.105425716009614234e+02,5.060318563301746675e-01,1.100000010988609489e+01,4.991484565162584291e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998220884928232977e+01,7.105525715997156340e+02,5.060368478145325088e-01,1.100000010988609489e+01,4.990024711147207116e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998311794018233911e+01,7.105625715984706403e+02,5.060418378390365568e-01,1.100000010988609489e+01,4.988564857131829941e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998402703108234846e+01,7.105725715972263288e+02,5.060468264036868113e-01,1.100000010988609489e+01,4.987105003116452766e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998493612198235780e+01,7.105825715959828131e+02,5.060518135084831615e-01,1.100000010988609489e+01,4.985645149101075591e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998584521288236715e+01,7.105925715947399794e+02,5.060567991534257182e-01,1.100000010988609489e+01,4.984185295085698415e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998675430378237650e+01,7.106025715934978280e+02,5.060617833385144815e-01,1.100000010988609489e+01,4.982725441070321240e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998766339468238584e+01,7.106125715922564723e+02,5.060667660637493404e-01,1.100000010988609489e+01,4.981265587054944065e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998857248558239519e+01,7.106225715910157987e+02,5.060717473291304058e-01,1.100000010988609489e+01,4.979805733039566890e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.998948157648240453e+01,7.106325715897759210e+02,5.060767271346576779e-01,1.100000010988609489e+01,4.978345879024189714e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999039066738241388e+01,7.106425715885367254e+02,5.060817054803310455e-01,1.100000010988609489e+01,4.976886025008812539e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999129975828242323e+01,7.106525715872982119e+02,5.060866823661506197e-01,1.100000010988609489e+01,4.975426170993435364e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999220884918243257e+01,7.106625715860604942e+02,5.060916577921162895e-01,1.100000010988609489e+01,4.973966316978058189e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999311794008244192e+01,7.106725715848234586e+02,5.060966317582281659e-01,1.100000010988609489e+01,4.972506462962681013e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999402703098245127e+01,7.106825715835872188e+02,5.061016042644862489e-01,1.100000010988609489e+01,4.971046608947303838e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999493612188246061e+01,7.106925715823516612e+02,5.061065753108904275e-01,1.100000010988609489e+01,4.969586754931926663e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999584521278246996e+01,7.107025715811167856e+02,5.061115448974408126e-01,1.100000010988609489e+01,4.968126900916549488e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999675430368247930e+01,7.107125715798827059e+02,5.061165130241374044e-01,1.100000010988609489e+01,4.966667046901172312e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999766339458248865e+01,7.107225715786493083e+02,5.061214796909800917e-01,1.100000010988609489e+01,4.965207192885795137e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999857248548249800e+01,7.107325715774165928e+02,5.061264448979689856e-01,1.100000010988609489e+01,4.963747338870417962e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +9.999948157638250734e+01,7.107425715761846732e+02,5.061314086451039751e-01,1.100000010988609489e+01,4.962287484855040787e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000003906672825167e+02,7.107525715749534356e+02,5.061363709323851712e-01,1.100000010988609489e+01,4.960827630839663611e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000012997581825260e+02,7.107625715737229939e+02,5.061413317598125738e-01,1.100000010988609489e+01,4.959367776824286436e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000022088490825354e+02,7.107725715724932343e+02,5.061462911273860721e-01,1.100000010988609489e+01,4.957907922808909261e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000031179399825447e+02,7.107825715712641568e+02,5.061512490351057769e-01,1.100000010988609489e+01,4.956448068793532086e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000040270308825541e+02,7.107925715700358751e+02,5.061562054829716883e-01,1.100000010988609489e+01,4.954988214778154910e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000049361217825634e+02,7.108025715688082755e+02,5.061611604709836953e-01,1.100000010988609489e+01,4.953528360762777735e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000058452126825728e+02,7.108125715675813581e+02,5.061661139991419089e-01,1.100000010988609489e+01,4.952068506747400560e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000067543035825821e+02,7.108225715663552364e+02,5.061710660674462181e-01,1.100000010988609489e+01,4.950608652732023385e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000076633944825915e+02,7.108325715651297969e+02,5.061760166758967339e-01,1.100000010988609489e+01,4.949148798716646210e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000085724853826008e+02,7.108425715639050395e+02,5.061809658244934562e-01,1.100000010988609489e+01,4.947688944701269034e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000094815762826101e+02,7.108525715626810779e+02,5.061859135132362741e-01,1.100000010988609489e+01,4.946229090685891859e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000103906671826195e+02,7.108625715614577985e+02,5.061908597421252987e-01,1.100000010988609489e+01,4.944769236670514684e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000112997580826288e+02,7.108725715602353148e+02,5.061958045111604187e-01,1.100000010988609489e+01,4.943309382655137509e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000122088489826382e+02,7.108825715590135133e+02,5.062007478203417454e-01,1.100000010988609489e+01,4.941849528639760333e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000131179398826475e+02,7.108925715577923938e+02,5.062056896696692787e-01,1.100000010988609489e+01,4.940389674624383158e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000140270307826569e+02,7.109025715565720702e+02,5.062106300591429076e-01,1.100000010988609489e+01,4.938929820609005983e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000149361216826662e+02,7.109125715553524287e+02,5.062155689887627430e-01,1.100000010988609489e+01,4.937469966593628808e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000158452125826756e+02,7.109225715541334694e+02,5.062205064585286740e-01,1.100000010988609489e+01,4.936010112578251632e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000167543034826849e+02,7.109325715529153058e+02,5.062254424684408116e-01,1.100000010988609489e+01,4.934550258562874457e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000176633943826943e+02,7.109425715516978244e+02,5.062303770184991558e-01,1.100000010988609489e+01,4.933090404547497282e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000185724852827036e+02,7.109525715504810250e+02,5.062353101087035956e-01,1.100000010988609489e+01,4.931630550532120107e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000194815761827130e+02,7.109625715492650215e+02,5.062402417390542420e-01,1.100000010988609489e+01,4.930170696516742931e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000203906670827223e+02,7.109725715480497001e+02,5.062451719095509839e-01,1.100000010988609489e+01,4.928710842501365756e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000212997579827316e+02,7.109825715468350609e+02,5.062501006201939324e-01,1.100000010988609489e+01,4.927250988485988581e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000222088488827410e+02,7.109925715456212174e+02,5.062550278709830875e-01,1.100000010988609489e+01,4.925791134470611406e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000231179397827503e+02,7.110025715444080561e+02,5.062599536619183382e-01,1.100000010988609489e+01,4.924331280455234230e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000240270306827597e+02,7.110125715431955769e+02,5.062648779929997955e-01,1.100000010988609489e+01,4.922871426439857055e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000249361215827690e+02,7.110225715419838934e+02,5.062698008642273484e-01,1.100000010988609489e+01,4.921411572424479880e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000258452124827784e+02,7.110325715407728921e+02,5.062747222756011078e-01,1.100000010988609489e+01,4.919951718409102705e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000267543033827877e+02,7.110425715395625730e+02,5.062796422271210739e-01,1.100000010988609489e+01,4.918491864393725529e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000276633942827971e+02,7.110525715383530496e+02,5.062845607187871355e-01,1.100000010988609489e+01,4.917032010378348354e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000285724851828064e+02,7.110625715371442084e+02,5.062894777505994037e-01,1.100000010988609489e+01,4.915572156362971179e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000294815760828158e+02,7.110725715359360493e+02,5.062943933225577675e-01,1.100000010988609489e+01,4.914112302347594004e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000303906669828251e+02,7.110825715347285723e+02,5.062993074346623379e-01,1.100000010988609489e+01,4.912652448332216829e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000312997578828345e+02,7.110925715335218911e+02,5.063042200869131149e-01,1.100000010988609489e+01,4.911192594316839653e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000322088487828438e+02,7.111025715323158920e+02,5.063091312793099874e-01,1.100000010988609489e+01,4.909732740301462478e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000331179396828531e+02,7.111125715311105751e+02,5.063140410118530665e-01,1.100000010988609489e+01,4.908272886286085303e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000340270305828625e+02,7.111225715299060539e+02,5.063189492845422413e-01,1.100000010988609489e+01,4.906813032270708128e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000349361214828718e+02,7.111325715287022149e+02,5.063238560973776226e-01,1.100000010988609489e+01,4.905353178255330952e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000358452123828812e+02,7.111425715274990580e+02,5.063287614503590994e-01,1.100000010988609489e+01,4.903893324239953777e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000367543032828905e+02,7.111525715262966969e+02,5.063336653434867829e-01,1.100000010988609489e+01,4.902433470224576602e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000376633941828999e+02,7.111625715250950179e+02,5.063385677767606730e-01,1.100000010988609489e+01,4.900973616209199427e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000385724850829092e+02,7.111725715238940211e+02,5.063434687501806586e-01,1.100000010988609489e+01,4.899513762193822251e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000394815759829186e+02,7.111825715226937064e+02,5.063483682637468508e-01,1.100000010988609489e+01,4.898053908178445076e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000403906668829279e+02,7.111925715214941874e+02,5.063532663174591386e-01,1.100000010988609489e+01,4.896594054163067901e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000412997577829373e+02,7.112025715202953506e+02,5.063581629113176330e-01,1.100000010988609489e+01,4.895134200147690726e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000422088486829466e+02,7.112125715190971960e+02,5.063630580453223340e-01,1.100000010988609489e+01,4.893674346132313550e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000431179395829560e+02,7.112225715178998371e+02,5.063679517194731305e-01,1.100000010988609489e+01,4.892214492116936375e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000440270304829653e+02,7.112325715167031603e+02,5.063728439337701337e-01,1.100000010988609489e+01,4.890754638101559200e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000449361213829746e+02,7.112425715155071657e+02,5.063777346882132324e-01,1.100000010988609489e+01,4.889294784086182025e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000458452122829840e+02,7.112525715143118532e+02,5.063826239828025377e-01,1.100000010988609489e+01,4.887834930070804849e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000467543031829933e+02,7.112625715131173365e+02,5.063875118175379386e-01,1.100000010988609489e+01,4.886375076055427674e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000476633940830027e+02,7.112725715119235019e+02,5.063923981924195461e-01,1.100000010988609489e+01,4.884915222040050499e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000485724849830120e+02,7.112825715107303495e+02,5.063972831074473602e-01,1.100000010988609489e+01,4.883455368024673324e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000494815758830214e+02,7.112925715095379928e+02,5.064021665626212698e-01,1.100000010988609489e+01,4.881995514009296148e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000503906667830307e+02,7.113025715083463183e+02,5.064070485579413861e-01,1.100000010988609489e+01,4.880535659993918973e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000512997576830401e+02,7.113125715071553259e+02,5.064119290934075979e-01,1.100000010988609489e+01,4.879075805978541798e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000522088485830494e+02,7.113225715059650156e+02,5.064168081690200163e-01,1.100000010988609489e+01,4.877615951963164623e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000531179394830588e+02,7.113325715047755011e+02,5.064216857847785302e-01,1.100000010988609489e+01,4.876156097947787448e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000540270303830681e+02,7.113425715035866688e+02,5.064265619406832508e-01,1.100000010988609489e+01,4.874696243932410272e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000549361212830775e+02,7.113525715023985185e+02,5.064314366367341780e-01,1.100000010988609489e+01,4.873236389917033097e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000558452121830868e+02,7.113625715012110504e+02,5.064363098729312007e-01,1.100000010988609489e+01,4.871776535901655922e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000567543030830961e+02,7.113725715000243781e+02,5.064411816492744300e-01,1.100000010988609489e+01,4.870316681886278747e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000576633939831055e+02,7.113825714988383879e+02,5.064460519657637549e-01,1.100000010988609489e+01,4.868856827870901571e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000585724848831148e+02,7.113925714976530799e+02,5.064509208223992864e-01,1.100000010988609489e+01,4.867396973855524396e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000594815757831242e+02,7.114025714964684539e+02,5.064557882191809135e-01,1.100000010988609489e+01,4.865937119840147221e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000603906666831335e+02,7.114125714952846238e+02,5.064606541561087472e-01,1.100000010988609489e+01,4.864477265824770046e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000612997575831429e+02,7.114225714941014758e+02,5.064655186331826764e-01,1.100000010988609489e+01,4.863017411809392870e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000622088484831522e+02,7.114325714929190099e+02,5.064703816504028122e-01,1.100000010988609489e+01,4.861557557794015695e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000631179393831616e+02,7.114425714917372261e+02,5.064752432077691546e-01,1.100000010988609489e+01,4.860097703778638520e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000640270302831709e+02,7.114525714905562381e+02,5.064801033052815926e-01,1.100000010988609489e+01,4.858637849763261345e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000649361211831803e+02,7.114625714893759323e+02,5.064849619429402372e-01,1.100000010988609489e+01,4.857177995747884169e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000658452120831896e+02,7.114725714881963086e+02,5.064898191207449774e-01,1.100000010988609489e+01,4.855718141732506994e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000667543029831990e+02,7.114825714870173670e+02,5.064946748386959241e-01,1.100000010988609489e+01,4.854258287717129819e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000676633938832083e+02,7.114925714858392212e+02,5.064995290967929664e-01,1.100000010988609489e+01,4.852798433701752644e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000685724847832176e+02,7.115025714846617575e+02,5.065043818950362153e-01,1.100000010988609489e+01,4.851338579686375468e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000694815756832270e+02,7.115125714834849759e+02,5.065092332334255598e-01,1.100000010988609489e+01,4.849878725670998293e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000703906665832363e+02,7.115225714823088765e+02,5.065140831119611109e-01,1.100000010988609489e+01,4.848418871655621118e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000712997574832457e+02,7.115325714811335729e+02,5.065189315306427575e-01,1.100000010988609489e+01,4.846959017640243943e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000722088483832550e+02,7.115425714799589514e+02,5.065237784894706108e-01,1.100000010988609489e+01,4.845499163624866767e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000731179392832644e+02,7.115525714787850120e+02,5.065286239884446706e-01,1.100000010988609489e+01,4.844039309609489592e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000740270301832737e+02,7.115625714776117547e+02,5.065334680275648260e-01,1.100000010988609489e+01,4.842579455594112417e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000749361210832831e+02,7.115725714764391796e+02,5.065383106068311880e-01,1.100000010988609489e+01,4.841119601578735242e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000758452119832924e+02,7.115825714752674003e+02,5.065431517262436456e-01,1.100000010988609489e+01,4.839659747563358067e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000767543028833018e+02,7.115925714740963031e+02,5.065479913858023098e-01,1.100000010988609489e+01,4.838199893547980891e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000776633937833111e+02,7.116025714729258880e+02,5.065528295855070695e-01,1.100000010988609489e+01,4.836740039532603716e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000785724846833205e+02,7.116125714717561550e+02,5.065576663253580358e-01,1.100000010988609489e+01,4.835280185517226541e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000794815755833298e+02,7.116225714705871042e+02,5.065625016053550977e-01,1.100000010988609489e+01,4.833820331501849366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000803906664833391e+02,7.116325714694188491e+02,5.065673354254983662e-01,1.100000010988609489e+01,4.832360477486472190e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000812997573833485e+02,7.116425714682512762e+02,5.065721677857877303e-01,1.100000010988609489e+01,4.830900623471095015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000822088482833578e+02,7.116525714670843854e+02,5.065769986862233010e-01,1.100000010988609489e+01,4.829440769455717840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000831179391833672e+02,7.116625714659181767e+02,5.065818281268050782e-01,1.100000010988609489e+01,4.827980915440340665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000840270300833765e+02,7.116725714647526502e+02,5.065866561075329511e-01,1.100000010988609489e+01,4.826521061424963489e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000849361209833859e+02,7.116825714635879194e+02,5.065914826284070305e-01,1.100000010988609489e+01,4.825061207409586314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000858452118833952e+02,7.116925714624238708e+02,5.065963076894272055e-01,1.100000010988609489e+01,4.823601353394209139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000867543027834046e+02,7.117025714612605043e+02,5.066011312905935871e-01,1.100000010988609489e+01,4.822141499378831964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000876633936834139e+02,7.117125714600978199e+02,5.066059534319060642e-01,1.100000010988609489e+01,4.820681645363454788e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000885724845834233e+02,7.117225714589358176e+02,5.066107741133647480e-01,1.100000010988609489e+01,4.819221791348077613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000894815754834326e+02,7.117325714577746112e+02,5.066155933349695273e-01,1.100000010988609489e+01,4.817761937332700438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000903906663834420e+02,7.117425714566140869e+02,5.066204110967205132e-01,1.100000010988609489e+01,4.816302083317323263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000912997572834513e+02,7.117525714554542446e+02,5.066252273986175947e-01,1.100000010988609489e+01,4.814842229301946087e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000922088481834606e+02,7.117625714542950845e+02,5.066300422406608828e-01,1.100000010988609489e+01,4.813382375286568912e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000931179390834700e+02,7.117725714531366066e+02,5.066348556228502664e-01,1.100000010988609489e+01,4.811922521271191737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000940270299834793e+02,7.117825714519789244e+02,5.066396675451858567e-01,1.100000010988609489e+01,4.810462667255814562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000949361208834887e+02,7.117925714508219244e+02,5.066444780076675425e-01,1.100000010988609489e+01,4.809002813240437386e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000958452117834980e+02,7.118025714496656065e+02,5.066492870102954349e-01,1.100000010988609489e+01,4.807542959225060211e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000967543026835074e+02,7.118125714485099707e+02,5.066540945530694229e-01,1.100000010988609489e+01,4.806083105209683036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000976633935835167e+02,7.118225714473550170e+02,5.066589006359896175e-01,1.100000010988609489e+01,4.804623251194305861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000985724844835261e+02,7.118325714462007454e+02,5.066637052590559076e-01,1.100000010988609489e+01,4.803163397178928685e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.000994815753835354e+02,7.118425714450472697e+02,5.066685084222684043e-01,1.100000010988609489e+01,4.801703543163551510e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001003906662835448e+02,7.118525714438944760e+02,5.066733101256269967e-01,1.100000010988609489e+01,4.800243689148174335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001012997571835541e+02,7.118625714427423645e+02,5.066781103691317956e-01,1.100000010988609489e+01,4.798783835132797160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001022088480835635e+02,7.118725714415909351e+02,5.066829091527828011e-01,1.100000010988609489e+01,4.797323981117419985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001031179389835728e+02,7.118825714404401879e+02,5.066877064765799021e-01,1.100000010988609489e+01,4.795864127102042809e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001040270298835821e+02,7.118925714392901227e+02,5.066925023405232098e-01,1.100000010988609489e+01,4.794404273086665634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001049361207835915e+02,7.119025714381408534e+02,5.066972967446126130e-01,1.100000010988609489e+01,4.792944419071288459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001058452116836008e+02,7.119125714369922662e+02,5.067020896888482229e-01,1.100000010988609489e+01,4.791484565055911284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001067543025836102e+02,7.119225714358443611e+02,5.067068811732299283e-01,1.100000010988609489e+01,4.790024711040534108e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001076633934836195e+02,7.119325714346971381e+02,5.067116711977578403e-01,1.100000010988609489e+01,4.788564857025156933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001085724843836289e+02,7.119425714335505972e+02,5.067164597624318478e-01,1.100000010988609489e+01,4.787105003009779758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001094815752836382e+02,7.119525714324047385e+02,5.067212468672520620e-01,1.100000010988609489e+01,4.785645148994402583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001103906661836476e+02,7.119625714312595619e+02,5.067260325122183717e-01,1.100000010988609489e+01,4.784185294979025407e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001112997570836569e+02,7.119725714301151811e+02,5.067308166973308881e-01,1.100000010988609489e+01,4.782725440963648232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001122088479836663e+02,7.119825714289714824e+02,5.067355994225895000e-01,1.100000010988609489e+01,4.781265586948271057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001131179388836756e+02,7.119925714278284659e+02,5.067403806879943184e-01,1.100000010988609489e+01,4.779805732932893882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001140270297836850e+02,7.120025714266861314e+02,5.067451604935452325e-01,1.100000010988609489e+01,4.778345878917516706e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001149361206836943e+02,7.120125714255444791e+02,5.067499388392423532e-01,1.100000010988609489e+01,4.776886024902139531e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001158452115837036e+02,7.120225714244035089e+02,5.067547157250855694e-01,1.100000010988609489e+01,4.775426170886762356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001167543024837130e+02,7.120325714232632208e+02,5.067594911510749922e-01,1.100000010988609489e+01,4.773966316871385181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001176633933837223e+02,7.120425714221237286e+02,5.067642651172105106e-01,1.100000010988609489e+01,4.772506462856008005e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001185724842837317e+02,7.120525714209849184e+02,5.067690376234922356e-01,1.100000010988609489e+01,4.771046608840630830e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001194815751837410e+02,7.120625714198467904e+02,5.067738086699200561e-01,1.100000010988609489e+01,4.769586754825253655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001203906660837504e+02,7.120725714187093445e+02,5.067785782564940833e-01,1.100000010988609489e+01,4.768126900809876480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001212997569837597e+02,7.120825714175725807e+02,5.067833463832142060e-01,1.100000010988609489e+01,4.766667046794499304e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001222088478837691e+02,7.120925714164364990e+02,5.067881130500805353e-01,1.100000010988609489e+01,4.765207192779122129e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001231179387837784e+02,7.121025714153010995e+02,5.067928782570929602e-01,1.100000010988609489e+01,4.763747338763744954e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001240270296837878e+02,7.121125714141663821e+02,5.067976420042515917e-01,1.100000010988609489e+01,4.762287484748367779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001249361205837971e+02,7.121225714130324604e+02,5.068024042915563188e-01,1.100000010988609489e+01,4.760827630732990604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001258452114838065e+02,7.121325714118992209e+02,5.068071651190072524e-01,1.100000010988609489e+01,4.759367776717613428e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001267543023838158e+02,7.121425714107666636e+02,5.068119244866042816e-01,1.100000010988609489e+01,4.757907922702236253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001276633932838251e+02,7.121525714096347883e+02,5.068166823943475174e-01,1.100000010988609489e+01,4.756448068686859078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001285724841838345e+02,7.121625714085035952e+02,5.068214388422368488e-01,1.100000010988609489e+01,4.754988214671481903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001294815750838438e+02,7.121725714073730842e+02,5.068261938302723868e-01,1.100000010988609489e+01,4.753528360656104727e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001303906659838532e+02,7.121825714062432553e+02,5.068309473584540203e-01,1.100000010988609489e+01,4.752068506640727552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001312997568838625e+02,7.121925714051141085e+02,5.068356994267818605e-01,1.100000010988609489e+01,4.750608652625350377e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001322088477838719e+02,7.122025714039856439e+02,5.068404500352557962e-01,1.100000010988609489e+01,4.749148798609973202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001331179386838812e+02,7.122125714028579750e+02,5.068451991838758275e-01,1.100000010988609489e+01,4.747688944594596026e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001340270295838906e+02,7.122225714017309883e+02,5.068499468726420654e-01,1.100000010988609489e+01,4.746229090579218851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001349361204838999e+02,7.122325714006046837e+02,5.068546931015543988e-01,1.100000010988609489e+01,4.744769236563841676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001358452113839093e+02,7.122425713994790613e+02,5.068594378706129389e-01,1.100000010988609489e+01,4.743309382548464501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001367543022839186e+02,7.122525713983541209e+02,5.068641811798175745e-01,1.100000010988609489e+01,4.741849528533087325e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001376633931839280e+02,7.122625713972298627e+02,5.068689230291684167e-01,1.100000010988609489e+01,4.740389674517710150e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001385724840839373e+02,7.122725713961062866e+02,5.068736634186653545e-01,1.100000010988609489e+01,4.738929820502332975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001394815749839466e+02,7.122825713949833926e+02,5.068784023483084988e-01,1.100000010988609489e+01,4.737469966486955800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001403906658839560e+02,7.122925713938611807e+02,5.068831398180977388e-01,1.100000010988609489e+01,4.736010112471578624e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001412997567839653e+02,7.123025713927396509e+02,5.068878758280331853e-01,1.100000010988609489e+01,4.734550258456201449e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001422088476839747e+02,7.123125713916188033e+02,5.068926103781147274e-01,1.100000010988609489e+01,4.733090404440824274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001431179385839840e+02,7.123225713904987515e+02,5.068973434683424761e-01,1.100000010988609489e+01,4.731630550425447099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001440270294839934e+02,7.123325713893793818e+02,5.069020750987163204e-01,1.100000010988609489e+01,4.730170696410069923e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001449361203840027e+02,7.123425713882606942e+02,5.069068052692363713e-01,1.100000010988609489e+01,4.728710842394692748e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001458452112840121e+02,7.123525713871426888e+02,5.069115339799025177e-01,1.100000010988609489e+01,4.727250988379315573e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001467543021840214e+02,7.123625713860253654e+02,5.069162612307148708e-01,1.100000010988609489e+01,4.725791134363938398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001476633930840308e+02,7.123725713849087242e+02,5.069209870216733194e-01,1.100000010988609489e+01,4.724331280348561223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001485724839840401e+02,7.123825713837927651e+02,5.069257113527779746e-01,1.100000010988609489e+01,4.722871426333184047e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001494815748840495e+02,7.123925713826774881e+02,5.069304342240287253e-01,1.100000010988609489e+01,4.721411572317806872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001503906657840588e+02,7.124025713815628933e+02,5.069351556354256827e-01,1.100000010988609489e+01,4.719951718302429697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001512997566840681e+02,7.124125713804489806e+02,5.069398755869687356e-01,1.100000010988609489e+01,4.718491864287052522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001522088475840775e+02,7.124225713793357500e+02,5.069445940786578841e-01,1.100000010988609489e+01,4.717032010271675346e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001531179384840868e+02,7.124325713782232015e+02,5.069493111104932392e-01,1.100000010988609489e+01,4.715572156256298171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001540270293840962e+02,7.124425713771113351e+02,5.069540266824746899e-01,1.100000010988609489e+01,4.714112302240920996e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001549361202841055e+02,7.124525713760001508e+02,5.069587407946023472e-01,1.100000010988609489e+01,4.712652448225543821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001558452111841149e+02,7.124625713748896487e+02,5.069634534468761000e-01,1.100000010988609489e+01,4.711192594210166645e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001567543020841242e+02,7.124725713737798287e+02,5.069681646392960594e-01,1.100000010988609489e+01,4.709732740194789470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001576633929841336e+02,7.124825713726708045e+02,5.069728743718621145e-01,1.100000010988609489e+01,4.708272886179412295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001585724838841429e+02,7.124925713715624624e+02,5.069775826445743760e-01,1.100000010988609489e+01,4.706813032164035120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001594815747841523e+02,7.125025713704548025e+02,5.069822894574327332e-01,1.100000010988609489e+01,4.705353178148657944e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001603906656841616e+02,7.125125713693478247e+02,5.069869948104372970e-01,1.100000010988609489e+01,4.703893324133280769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001612997565841710e+02,7.125225713682415289e+02,5.069916987035879563e-01,1.100000010988609489e+01,4.702433470117903594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001622088474841803e+02,7.125325713671359154e+02,5.069964011368848222e-01,1.100000010988609489e+01,4.700973616102526419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001631179383841896e+02,7.125425713660309839e+02,5.070011021103277837e-01,1.100000010988609489e+01,4.699513762087149243e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001640270292841990e+02,7.125525713649267345e+02,5.070058016239168408e-01,1.100000010988609489e+01,4.698053908071772068e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001649361201842083e+02,7.125625713638231673e+02,5.070104996776521045e-01,1.100000010988609489e+01,4.696594054056394893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001658452110842177e+02,7.125725713627202822e+02,5.070151962715334637e-01,1.100000010988609489e+01,4.695134200041017718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001667543019842270e+02,7.125825713616180792e+02,5.070198914055610295e-01,1.100000010988609489e+01,4.693674346025640542e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001676633928842364e+02,7.125925713605165583e+02,5.070245850797346909e-01,1.100000010988609489e+01,4.692214492010263367e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001685724837842457e+02,7.126025713594157196e+02,5.070292772940545589e-01,1.100000010988609489e+01,4.690754637994886192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001694815746842551e+02,7.126125713583155630e+02,5.070339680485205225e-01,1.100000010988609489e+01,4.689294783979509017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001703906655842644e+02,7.126225713572160885e+02,5.070386573431326926e-01,1.100000010988609489e+01,4.687834929964131842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001712997564842738e+02,7.126325713561172961e+02,5.070433451778909584e-01,1.100000010988609489e+01,4.686375075948754666e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001722088473842831e+02,7.126425713550191858e+02,5.070480315527953197e-01,1.100000010988609489e+01,4.684915221933377491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001731179382842924e+02,7.126525713539217577e+02,5.070527164678458876e-01,1.100000010988609489e+01,4.683455367918000316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001740270291843018e+02,7.126625713528250117e+02,5.070573999230425510e-01,1.100000010988609489e+01,4.681995513902623141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001749361200843111e+02,7.126725713517289478e+02,5.070620819183854211e-01,1.100000010988609489e+01,4.680535659887245965e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001758452109843205e+02,7.126825713506335660e+02,5.070667624538743867e-01,1.100000010988609489e+01,4.679075805871868790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001767543018843298e+02,7.126925713495388663e+02,5.070714415295095590e-01,1.100000010988609489e+01,4.677615951856491615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001776633927843392e+02,7.127025713484448488e+02,5.070761191452908268e-01,1.100000010988609489e+01,4.676156097841114440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001785724836843485e+02,7.127125713473515134e+02,5.070807953012183011e-01,1.100000010988609489e+01,4.674696243825737264e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001794815745843579e+02,7.127225713462588601e+02,5.070854699972918711e-01,1.100000010988609489e+01,4.673236389810360089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001803906654843672e+02,7.127325713451668889e+02,5.070901432335115366e-01,1.100000010988609489e+01,4.671776535794982914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001812997563843766e+02,7.127425713440755999e+02,5.070948150098774088e-01,1.100000010988609489e+01,4.670316681779605739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001822088472843859e+02,7.127525713429849930e+02,5.070994853263893765e-01,1.100000010988609489e+01,4.668856827764228563e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001831179381843953e+02,7.127625713418950681e+02,5.071041541830475508e-01,1.100000010988609489e+01,4.667396973748851388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001840270290844046e+02,7.127725713408058255e+02,5.071088215798518206e-01,1.100000010988609489e+01,4.665937119733474213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001849361199844139e+02,7.127825713397172649e+02,5.071134875168022971e-01,1.100000010988609489e+01,4.664477265718097038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001858452108844233e+02,7.127925713386293864e+02,5.071181519938988691e-01,1.100000010988609489e+01,4.663017411702719862e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001867543017844326e+02,7.128025713375421901e+02,5.071228150111415367e-01,1.100000010988609489e+01,4.661557557687342687e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001876633926844420e+02,7.128125713364556759e+02,5.071274765685304109e-01,1.100000010988609489e+01,4.660097703671965512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001885724835844513e+02,7.128225713353698438e+02,5.071321366660653807e-01,1.100000010988609489e+01,4.658637849656588337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001894815744844607e+02,7.128325713342846939e+02,5.071367953037465570e-01,1.100000010988609489e+01,4.657177995641211161e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001903906653844700e+02,7.128425713332002260e+02,5.071414524815738289e-01,1.100000010988609489e+01,4.655718141625833986e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001912997562844794e+02,7.128525713321164403e+02,5.071461081995473075e-01,1.100000010988609489e+01,4.654258287610456811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001922088471844887e+02,7.128625713310333367e+02,5.071507624576668816e-01,1.100000010988609489e+01,4.652798433595079636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001931179380844981e+02,7.128725713299509152e+02,5.071554152559325512e-01,1.100000010988609489e+01,4.651338579579702460e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001940270289845074e+02,7.128825713288691759e+02,5.071600665943444275e-01,1.100000010988609489e+01,4.649878725564325285e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001949361198845168e+02,7.128925713277881187e+02,5.071647164729023993e-01,1.100000010988609489e+01,4.648418871548948110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001958452107845261e+02,7.129025713267077435e+02,5.071693648916065777e-01,1.100000010988609489e+01,4.646959017533570935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001967543016845354e+02,7.129125713256280505e+02,5.071740118504568517e-01,1.100000010988609489e+01,4.645499163518193760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001976633925845448e+02,7.129225713245490397e+02,5.071786573494533323e-01,1.100000010988609489e+01,4.644039309502816584e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001985724834845541e+02,7.129325713234707109e+02,5.071833013885959085e-01,1.100000010988609489e+01,4.642579455487439409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.001994815743845635e+02,7.129425713223930643e+02,5.071879439678845802e-01,1.100000010988609489e+01,4.641119601472062234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002003906652845728e+02,7.129525713213160998e+02,5.071925850873194586e-01,1.100000010988609489e+01,4.639659747456685059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002012997561845822e+02,7.129625713202398174e+02,5.071972247469004325e-01,1.100000010988609489e+01,4.638199893441307883e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002022088470845915e+02,7.129725713191642171e+02,5.072018629466276129e-01,1.100000010988609489e+01,4.636740039425930708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002031179379846009e+02,7.129825713180892990e+02,5.072064996865008890e-01,1.100000010988609489e+01,4.635280185410553533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002040270288846102e+02,7.129925713170150630e+02,5.072111349665202606e-01,1.100000010988609489e+01,4.633820331395176358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002049361197846196e+02,7.130025713159413954e+02,5.072157687866858389e-01,1.100000010988609489e+01,4.632360477379799182e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002058452106846289e+02,7.130125713148684099e+02,5.072204011469975127e-01,1.100000010988609489e+01,4.630900623364422007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002067543015846383e+02,7.130225713137961066e+02,5.072250320474553931e-01,1.100000010988609489e+01,4.629440769349044832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002076633924846476e+02,7.130325713127244853e+02,5.072296614880593690e-01,1.100000010988609489e+01,4.627980915333667657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002085724833846569e+02,7.130425713116535462e+02,5.072342894688095516e-01,1.100000010988609489e+01,4.626521061318290481e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002094815742846663e+02,7.130525713105832892e+02,5.072389159897058297e-01,1.100000010988609489e+01,4.625061207302913306e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002103906651846756e+02,7.130625713095137144e+02,5.072435410507482034e-01,1.100000010988609489e+01,4.623601353287536131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002112997560846850e+02,7.130725713084448216e+02,5.072481646519367837e-01,1.100000010988609489e+01,4.622141499272158956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002122088469846943e+02,7.130825713073766110e+02,5.072527867932714596e-01,1.100000010988609489e+01,4.620681645256781780e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002131179378847037e+02,7.130925713063090825e+02,5.072574074747523420e-01,1.100000010988609489e+01,4.619221791241404605e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002140270287847130e+02,7.131025713052422361e+02,5.072620266963793201e-01,1.100000010988609489e+01,4.617761937226027430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002149361196847224e+02,7.131125713041760719e+02,5.072666444581523937e-01,1.100000010988609489e+01,4.616302083210650255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002158452105847317e+02,7.131225713031105897e+02,5.072712607600716739e-01,1.100000010988609489e+01,4.614842229195273079e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002167543014847411e+02,7.131325713020457897e+02,5.072758756021370496e-01,1.100000010988609489e+01,4.613382375179895904e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002176633923847504e+02,7.131425713009816718e+02,5.072804889843486320e-01,1.100000010988609489e+01,4.611922521164518729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002185724832847598e+02,7.131525712999182360e+02,5.072851009067063099e-01,1.100000010988609489e+01,4.610462667149141554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002194815741847691e+02,7.131625712988553687e+02,5.072897113692100834e-01,1.100000010988609489e+01,4.609002813133764379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002203906650847784e+02,7.131725712977931835e+02,5.072943203718600635e-01,1.100000010988609489e+01,4.607542959118387203e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002212997559847878e+02,7.131825712967316804e+02,5.072989279146561392e-01,1.100000010988609489e+01,4.606083105103010028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002222088468847971e+02,7.131925712956708594e+02,5.073035339975984215e-01,1.100000010988609489e+01,4.604623251087632853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002231179377848065e+02,7.132025712946107205e+02,5.073081386206867993e-01,1.100000010988609489e+01,4.603163397072255678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002240270286848158e+02,7.132125712935512638e+02,5.073127417839212727e-01,1.100000010988609489e+01,4.601703543056878502e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002249361195848252e+02,7.132225712924924892e+02,5.073173434873019527e-01,1.100000010988609489e+01,4.600243689041501327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002258452104848345e+02,7.132325712914343967e+02,5.073219437308287283e-01,1.100000010988609489e+01,4.598783835026124152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002267543013848439e+02,7.132425712903769863e+02,5.073265425145017105e-01,1.100000010988609489e+01,4.597323981010746977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002276633922848532e+02,7.132525712893202581e+02,5.073311398383207882e-01,1.100000010988609489e+01,4.595864126995369801e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002285724831848626e+02,7.132625712882642119e+02,5.073357357022859615e-01,1.100000010988609489e+01,4.594404272979992626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002294815740848719e+02,7.132725712872087342e+02,5.073403301063973414e-01,1.100000010988609489e+01,4.592944418964615451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002303906649848813e+02,7.132825712861539387e+02,5.073449230506548169e-01,1.100000010988609489e+01,4.591484564949238276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002312997558848906e+02,7.132925712850998252e+02,5.073495145350583879e-01,1.100000010988609489e+01,4.590024710933861100e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002322088467848999e+02,7.133025712840463939e+02,5.073541045596081656e-01,1.100000010988609489e+01,4.588564856918483925e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002331179376849093e+02,7.133125712829936447e+02,5.073586931243040388e-01,1.100000010988609489e+01,4.587105002903106750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002340270285849186e+02,7.133225712819415776e+02,5.073632802291461186e-01,1.100000010988609489e+01,4.585645148887729575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002349361194849280e+02,7.133325712808901926e+02,5.073678658741342939e-01,1.100000010988609489e+01,4.584185294872352399e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002358452103849373e+02,7.133425712798394898e+02,5.073724500592685649e-01,1.100000010988609489e+01,4.582725440856975224e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002367543012849467e+02,7.133525712787894690e+02,5.073770327845490424e-01,1.100000010988609489e+01,4.581265586841598049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002376633921849560e+02,7.133625712777400167e+02,5.073816140499756155e-01,1.100000010988609489e+01,4.579805732826220874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002385724830849654e+02,7.133725712766912466e+02,5.073861938555483952e-01,1.100000010988609489e+01,4.578345878810843698e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002394815739849747e+02,7.133825712756431585e+02,5.073907722012672705e-01,1.100000010988609489e+01,4.576886024795466523e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002403906648849841e+02,7.133925712745957526e+02,5.073953490871322414e-01,1.100000010988609489e+01,4.575426170780089348e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002412997557849934e+02,7.134025712735490288e+02,5.073999245131434188e-01,1.100000010988609489e+01,4.573966316764712173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002422088466850028e+02,7.134125712725029871e+02,5.074044984793006918e-01,1.100000010988609489e+01,4.572506462749334998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002431179375850121e+02,7.134225712714576275e+02,5.074090709856040604e-01,1.100000010988609489e+01,4.571046608733957822e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002440270284850214e+02,7.134325712704129501e+02,5.074136420320536356e-01,1.100000010988609489e+01,4.569586754718580647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002449361193850308e+02,7.134425712693688411e+02,5.074182116186493063e-01,1.100000010988609489e+01,4.568126900703203472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002458452102850401e+02,7.134525712683254142e+02,5.074227797453911837e-01,1.100000010988609489e+01,4.566667046687826297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002467543011850495e+02,7.134625712672826694e+02,5.074273464122791566e-01,1.100000010988609489e+01,4.565207192672449121e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002476633920850588e+02,7.134725712662406067e+02,5.074319116193132251e-01,1.100000010988609489e+01,4.563747338657071946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002485724829850682e+02,7.134825712651992262e+02,5.074364753664935002e-01,1.100000010988609489e+01,4.562287484641694771e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002494815738850775e+02,7.134925712641585278e+02,5.074410376538198708e-01,1.100000010988609489e+01,4.560827630626317596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002503906647850869e+02,7.135025712631185115e+02,5.074455984812923370e-01,1.100000010988609489e+01,4.559367776610940420e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002512997556850962e+02,7.135125712620790637e+02,5.074501578489110099e-01,1.100000010988609489e+01,4.557907922595563245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002522088465851056e+02,7.135225712610402979e+02,5.074547157566757782e-01,1.100000010988609489e+01,4.556448068580186070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002531179374851149e+02,7.135325712600022143e+02,5.074592722045866422e-01,1.100000010988609489e+01,4.554988214564808895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002540270283851243e+02,7.135425712589648128e+02,5.074638271926437127e-01,1.100000010988609489e+01,4.553528360549431719e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002549361192851336e+02,7.135525712579280935e+02,5.074683807208468789e-01,1.100000010988609489e+01,4.552068506534054544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002558452101851429e+02,7.135625712568920562e+02,5.074729327891962516e-01,1.100000010988609489e+01,4.550608652518677369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002567543010851523e+02,7.135725712558567011e+02,5.074774833976917199e-01,1.100000010988609489e+01,4.549148798503300194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002576633919851616e+02,7.135825712548219144e+02,5.074820325463332837e-01,1.100000010988609489e+01,4.547688944487923018e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002585724828851710e+02,7.135925712537878098e+02,5.074865802351210542e-01,1.100000010988609489e+01,4.546229090472545843e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002594815737851803e+02,7.136025712527543874e+02,5.074911264640549202e-01,1.100000010988609489e+01,4.544769236457168668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002603906646851897e+02,7.136125712517216471e+02,5.074956712331348818e-01,1.100000010988609489e+01,4.543309382441791493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002612997555851990e+02,7.136225712506895889e+02,5.075002145423610500e-01,1.100000010988609489e+01,4.541849528426414317e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002622088464852084e+02,7.136325712496582128e+02,5.075047563917333138e-01,1.100000010988609489e+01,4.540389674411037142e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002631179373852177e+02,7.136425712486274051e+02,5.075092967812516731e-01,1.100000010988609489e+01,4.538929820395659967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002640270282852271e+02,7.136525712475972796e+02,5.075138357109162390e-01,1.100000010988609489e+01,4.537469966380282792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002649361191852364e+02,7.136625712465678362e+02,5.075183731807269005e-01,1.100000010988609489e+01,4.536010112364905617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002658452100852458e+02,7.136725712455390749e+02,5.075229091906837686e-01,1.100000010988609489e+01,4.534550258349528441e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002667543009852551e+02,7.136825712445109957e+02,5.075274437407867323e-01,1.100000010988609489e+01,4.533090404334151266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002676633918852644e+02,7.136925712434835987e+02,5.075319768310357915e-01,1.100000010988609489e+01,4.531630550318774091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002685724827852738e+02,7.137025712424567701e+02,5.075365084614310573e-01,1.100000010988609489e+01,4.530170696303396916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002694815736852831e+02,7.137125712414306236e+02,5.075410386319724187e-01,1.100000010988609489e+01,4.528710842288019740e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002703906645852925e+02,7.137225712404051592e+02,5.075455673426598757e-01,1.100000010988609489e+01,4.527250988272642565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002712997554853018e+02,7.137325712393803769e+02,5.075500945934935393e-01,1.100000010988609489e+01,4.525791134257265390e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002722088463853112e+02,7.137425712383562768e+02,5.075546203844732984e-01,1.100000010988609489e+01,4.524331280241888215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002731179372853205e+02,7.137525712373327451e+02,5.075591447155991531e-01,1.100000010988609489e+01,4.522871426226511039e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002740270281853299e+02,7.137625712363098955e+02,5.075636675868712144e-01,1.100000010988609489e+01,4.521411572211133864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002749361190853392e+02,7.137725712352877281e+02,5.075681889982893713e-01,1.100000010988609489e+01,4.519951718195756689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002758452099853486e+02,7.137825712342662428e+02,5.075727089498536237e-01,1.100000010988609489e+01,4.518491864180379514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002767543008853579e+02,7.137925712332454395e+02,5.075772274415640828e-01,1.100000010988609489e+01,4.517032010165002338e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002776633917853673e+02,7.138025712322252048e+02,5.075817444734206374e-01,1.100000010988609489e+01,4.515572156149625163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002785724826853766e+02,7.138125712312056521e+02,5.075862600454232876e-01,1.100000010988609489e+01,4.514112302134247988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002794815735853859e+02,7.138225712301867816e+02,5.075907741575721444e-01,1.100000010988609489e+01,4.512652448118870813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002803906644853953e+02,7.138325712291685932e+02,5.075952868098670967e-01,1.100000010988609489e+01,4.511192594103493637e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002812997553854046e+02,7.138425712281510869e+02,5.075997980023081446e-01,1.100000010988609489e+01,4.509732740088116462e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002822088462854140e+02,7.138525712271341490e+02,5.076043077348953991e-01,1.100000010988609489e+01,4.508272886072739287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002831179371854233e+02,7.138625712261178933e+02,5.076088160076287492e-01,1.100000010988609489e+01,4.506813032057362112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002840270280854327e+02,7.138725712251023197e+02,5.076133228205081949e-01,1.100000010988609489e+01,4.505353178041984936e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002849361189854420e+02,7.138825712240874282e+02,5.076178281735338471e-01,1.100000010988609489e+01,4.503893324026607761e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002858452098854514e+02,7.138925712230732188e+02,5.076223320667055949e-01,1.100000010988609489e+01,4.502433470011230586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002867543007854607e+02,7.139025712220595778e+02,5.076268345000234383e-01,1.100000010988609489e+01,4.500973615995853411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002876633916854701e+02,7.139125712210466190e+02,5.076313354734874883e-01,1.100000010988609489e+01,4.499513761980476236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002885724825854794e+02,7.139225712200343423e+02,5.076358349870976339e-01,1.100000010988609489e+01,4.498053907965099060e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002894815734854888e+02,7.139325712190227478e+02,5.076403330408538750e-01,1.100000010988609489e+01,4.496594053949721885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002903906643854981e+02,7.139425712180118353e+02,5.076448296347563227e-01,1.100000010988609489e+01,4.495134199934344710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002912997552855074e+02,7.139525712170014913e+02,5.076493247688048660e-01,1.100000010988609489e+01,4.493674345918967535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002922088461855168e+02,7.139625712159918294e+02,5.076538184429995049e-01,1.100000010988609489e+01,4.492214491903590359e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002931179370855261e+02,7.139725712149828496e+02,5.076583106573403503e-01,1.100000010988609489e+01,4.490754637888213184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002940270279855355e+02,7.139825712139745519e+02,5.076628014118272914e-01,1.100000010988609489e+01,4.489294783872836009e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002949361188855448e+02,7.139925712129668227e+02,5.076672907064603280e-01,1.100000010988609489e+01,4.487834929857458834e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002958452097855542e+02,7.140025712119597756e+02,5.076717785412395711e-01,1.100000010988609489e+01,4.486375075842081658e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002967543006855635e+02,7.140125712109534106e+02,5.076762649161649099e-01,1.100000010988609489e+01,4.484915221826704483e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002976633915855729e+02,7.140225712099477278e+02,5.076807498312363442e-01,1.100000010988609489e+01,4.483455367811327308e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002985724824855822e+02,7.140325712089426133e+02,5.076852332864539852e-01,1.100000010988609489e+01,4.481995513795950133e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.002994815733855916e+02,7.140425712079381810e+02,5.076897152818177217e-01,1.100000010988609489e+01,4.480535659780572957e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003003906642856009e+02,7.140525712069344308e+02,5.076941958173275538e-01,1.100000010988609489e+01,4.479075805765195782e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003012997551856103e+02,7.140625712059313628e+02,5.076986748929835924e-01,1.100000010988609489e+01,4.477615951749818607e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003022088460856196e+02,7.140725712049288632e+02,5.077031525087857267e-01,1.100000010988609489e+01,4.476156097734441432e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003031179369856289e+02,7.140825712039270456e+02,5.077076286647339565e-01,1.100000010988609489e+01,4.474696243719064256e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003040270278856383e+02,7.140925712029259103e+02,5.077121033608283929e-01,1.100000010988609489e+01,4.473236389703687081e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003049361187856476e+02,7.141025712019254570e+02,5.077165765970689248e-01,1.100000010988609489e+01,4.471776535688309906e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003058452096856570e+02,7.141125712009255722e+02,5.077210483734555524e-01,1.100000010988609489e+01,4.470316681672932731e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003067543005856663e+02,7.141225711999263694e+02,5.077255186899883865e-01,1.100000010988609489e+01,4.468856827657555555e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003076633914856757e+02,7.141325711989278489e+02,5.077299875466673162e-01,1.100000010988609489e+01,4.467396973642178380e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003085724823856850e+02,7.141425711979300104e+02,5.077344549434923415e-01,1.100000010988609489e+01,4.465937119626801205e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003094815732856944e+02,7.141525711969327403e+02,5.077389208804634624e-01,1.100000010988609489e+01,4.464477265611424030e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003103906641857037e+02,7.141625711959361524e+02,5.077433853575807898e-01,1.100000010988609489e+01,4.463017411596046854e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003112997550857131e+02,7.141725711949402466e+02,5.077478483748442128e-01,1.100000010988609489e+01,4.461557557580669679e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003122088459857224e+02,7.141825711939450230e+02,5.077523099322537314e-01,1.100000010988609489e+01,4.460097703565292504e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003131179368857318e+02,7.141925711929503677e+02,5.077567700298094566e-01,1.100000010988609489e+01,4.458637849549915329e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003140270277857411e+02,7.142025711919563946e+02,5.077612286675112774e-01,1.100000010988609489e+01,4.457177995534538154e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003149361186857504e+02,7.142125711909631036e+02,5.077656858453591937e-01,1.100000010988609489e+01,4.455718141519160978e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003158452095857598e+02,7.142225711899703811e+02,5.077701415633533166e-01,1.100000010988609489e+01,4.454258287503783803e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003167543004857691e+02,7.142325711889783406e+02,5.077745958214935351e-01,1.100000010988609489e+01,4.452798433488406628e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003176633913857785e+02,7.142425711879869823e+02,5.077790486197798492e-01,1.100000010988609489e+01,4.451338579473029453e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003185724822857878e+02,7.142525711869963061e+02,5.077834999582123698e-01,1.100000010988609489e+01,4.449878725457652277e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003194815731857972e+02,7.142625711860061983e+02,5.077879498367909861e-01,1.100000010988609489e+01,4.448418871442275102e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003203906640858065e+02,7.142725711850167727e+02,5.077923982555156979e-01,1.100000010988609489e+01,4.446959017426897927e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003212997549858159e+02,7.142825711840280292e+02,5.077968452143865052e-01,1.100000010988609489e+01,4.445499163411520752e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003222088458858252e+02,7.142925711830398541e+02,5.078012907134035192e-01,1.100000010988609489e+01,4.444039309396143576e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003231179367858346e+02,7.143025711820523611e+02,5.078057347525666287e-01,1.100000010988609489e+01,4.442579455380766401e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003240270276858439e+02,7.143125711810655503e+02,5.078101773318758339e-01,1.100000010988609489e+01,4.441119601365389226e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003249361185858533e+02,7.143225711800794215e+02,5.078146184513312456e-01,1.100000010988609489e+01,4.439659747350012051e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003258452094858626e+02,7.143325711790938612e+02,5.078190581109327528e-01,1.100000010988609489e+01,4.438199893334634875e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003267543003858719e+02,7.143425711781089831e+02,5.078234963106803557e-01,1.100000010988609489e+01,4.436740039319257700e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003276633912858813e+02,7.143525711771247870e+02,5.078279330505741651e-01,1.100000010988609489e+01,4.435280185303880525e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003285724821858906e+02,7.143625711761411594e+02,5.078323683306140701e-01,1.100000010988609489e+01,4.433820331288503350e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003294815730859000e+02,7.143725711751582139e+02,5.078368021508000707e-01,1.100000010988609489e+01,4.432360477273126174e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003303906639859093e+02,7.143825711741759505e+02,5.078412345111321669e-01,1.100000010988609489e+01,4.430900623257748999e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003312997548859187e+02,7.143925711731942556e+02,5.078456654116104696e-01,1.100000010988609489e+01,4.429440769242371824e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003322088457859280e+02,7.144025711722132428e+02,5.078500948522348679e-01,1.100000010988609489e+01,4.427980915226994649e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003331179366859374e+02,7.144125711712329121e+02,5.078545228330053618e-01,1.100000010988609489e+01,4.426521061211617473e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003340270275859467e+02,7.144225711702532635e+02,5.078589493539220623e-01,1.100000010988609489e+01,4.425061207196240298e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003349361184859561e+02,7.144325711692741834e+02,5.078633744149848583e-01,1.100000010988609489e+01,4.423601353180863123e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003358452093859654e+02,7.144425711682957854e+02,5.078677980161937500e-01,1.100000010988609489e+01,4.422141499165485948e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003367543002859748e+02,7.144525711673180695e+02,5.078722201575487372e-01,1.100000010988609489e+01,4.420681645150108773e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003376633911859841e+02,7.144625711663409220e+02,5.078766408390499310e-01,1.100000010988609489e+01,4.419221791134731597e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003385724820859934e+02,7.144725711653644566e+02,5.078810600606972203e-01,1.100000010988609489e+01,4.417761937119354422e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003394815729860028e+02,7.144825711643886734e+02,5.078854778224906052e-01,1.100000010988609489e+01,4.416302083103977247e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003403906638860121e+02,7.144925711634134586e+02,5.078898941244301968e-01,1.100000010988609489e+01,4.414842229088600072e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003412997547860215e+02,7.145025711624389260e+02,5.078943089665158839e-01,1.100000010988609489e+01,4.413382375073222896e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003422088456860308e+02,7.145125711614650754e+02,5.078987223487476665e-01,1.100000010988609489e+01,4.411922521057845721e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003431179365860402e+02,7.145225711604917933e+02,5.079031342711255448e-01,1.100000010988609489e+01,4.410462667042468546e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003440270274860495e+02,7.145325711595191933e+02,5.079075447336496296e-01,1.100000010988609489e+01,4.409002813027091371e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003449361183860589e+02,7.145425711585472754e+02,5.079119537363198100e-01,1.100000010988609489e+01,4.407542959011714195e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003458452092860682e+02,7.145525711575759260e+02,5.079163612791360860e-01,1.100000010988609489e+01,4.406083104996337020e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003467543001860776e+02,7.145625711566052587e+02,5.079207673620985686e-01,1.100000010988609489e+01,4.404623250980959845e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003476633910860869e+02,7.145725711556352735e+02,5.079251719852071467e-01,1.100000010988609489e+01,4.403163396965582670e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003485724819860962e+02,7.145825711546658567e+02,5.079295751484618204e-01,1.100000010988609489e+01,4.401703542950205494e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003494815728861056e+02,7.145925711536971221e+02,5.079339768518625897e-01,1.100000010988609489e+01,4.400243688934828319e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003503906637861149e+02,7.146025711527290696e+02,5.079383770954095656e-01,1.100000010988609489e+01,4.398783834919451144e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003512997546861243e+02,7.146125711517615855e+02,5.079427758791026370e-01,1.100000010988609489e+01,4.397323980904073969e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003522088455861336e+02,7.146225711507947835e+02,5.079471732029418041e-01,1.100000010988609489e+01,4.395864126888696793e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003531179364861430e+02,7.146325711498285500e+02,5.079515690669270667e-01,1.100000010988609489e+01,4.394404272873319618e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003540270273861523e+02,7.146425711488629986e+02,5.079559634710585359e-01,1.100000010988609489e+01,4.392944418857942443e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003549361182861617e+02,7.146525711478981293e+02,5.079603564153361006e-01,1.100000010988609489e+01,4.391484564842565268e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003558452091861710e+02,7.146625711469338285e+02,5.079647478997597609e-01,1.100000010988609489e+01,4.390024710827188092e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003567543000861804e+02,7.146725711459702097e+02,5.079691379243296279e-01,1.100000010988609489e+01,4.388564856811810917e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003576633909861897e+02,7.146825711450072731e+02,5.079735264890455904e-01,1.100000010988609489e+01,4.387105002796433742e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003585724818861991e+02,7.146925711440449049e+02,5.079779135939076484e-01,1.100000010988609489e+01,4.385645148781056567e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003594815727862084e+02,7.147025711430832189e+02,5.079822992389158021e-01,1.100000010988609489e+01,4.384185294765679392e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003603906636862177e+02,7.147125711421222150e+02,5.079866834240701623e-01,1.100000010988609489e+01,4.382725440750302216e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003612997545862271e+02,7.147225711411617795e+02,5.079910661493706181e-01,1.100000010988609489e+01,4.381265586734925041e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003622088454862364e+02,7.147325711402020261e+02,5.079954474148171695e-01,1.100000010988609489e+01,4.379805732719547866e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003631179363862458e+02,7.147425711392428411e+02,5.079998272204098164e-01,1.100000010988609489e+01,4.378345878704170691e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003640270272862551e+02,7.147525711382843383e+02,5.080042055661486700e-01,1.100000010988609489e+01,4.376886024688793515e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003649361181862645e+02,7.147625711373265176e+02,5.080085824520336191e-01,1.100000010988609489e+01,4.375426170673416340e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003658452090862738e+02,7.147725711363692653e+02,5.080129578780646638e-01,1.100000010988609489e+01,4.373966316658039165e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003667542999862832e+02,7.147825711354126952e+02,5.080173318442418040e-01,1.100000010988609489e+01,4.372506462642661990e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003676633908862925e+02,7.147925711344568072e+02,5.080217043505651509e-01,1.100000010988609489e+01,4.371046608627284814e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003685724817863019e+02,7.148025711335014876e+02,5.080260753970345933e-01,1.100000010988609489e+01,4.369586754611907639e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003694815726863112e+02,7.148125711325468501e+02,5.080304449836501313e-01,1.100000010988609489e+01,4.368126900596530464e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003703906635863206e+02,7.148225711315927811e+02,5.080348131104117648e-01,1.100000010988609489e+01,4.366667046581153289e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003712997544863299e+02,7.148325711306393941e+02,5.080391797773196050e-01,1.100000010988609489e+01,4.365207192565776113e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003722088453863392e+02,7.148425711296866893e+02,5.080435449843735407e-01,1.100000010988609489e+01,4.363747338550398938e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003731179362863486e+02,7.148525711287345530e+02,5.080479087315735720e-01,1.100000010988609489e+01,4.362287484535021763e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003740270271863579e+02,7.148625711277830987e+02,5.080522710189196989e-01,1.100000010988609489e+01,4.360827630519644588e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003749361180863673e+02,7.148725711268322129e+02,5.080566318464120323e-01,1.100000010988609489e+01,4.359367776504267412e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003758452089863766e+02,7.148825711258820093e+02,5.080609912140504614e-01,1.100000010988609489e+01,4.357907922488890237e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003767542998863860e+02,7.148925711249324877e+02,5.080653491218349860e-01,1.100000010988609489e+01,4.356448068473513062e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003776633907863953e+02,7.149025711239835346e+02,5.080697055697656062e-01,1.100000010988609489e+01,4.354988214458135887e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003785724816864047e+02,7.149125711230352636e+02,5.080740605578424329e-01,1.100000010988609489e+01,4.353528360442758711e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003794815725864140e+02,7.149225711220875610e+02,5.080784140860653553e-01,1.100000010988609489e+01,4.352068506427381536e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003803906634864234e+02,7.149325711211405405e+02,5.080827661544343732e-01,1.100000010988609489e+01,4.350608652412004361e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003812997543864327e+02,7.149425711201942022e+02,5.080871167629494867e-01,1.100000010988609489e+01,4.349148798396627186e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003822088452864421e+02,7.149525711192484323e+02,5.080914659116108067e-01,1.100000010988609489e+01,4.347688944381250011e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003831179361864514e+02,7.149625711183033445e+02,5.080958136004182224e-01,1.100000010988609489e+01,4.346229090365872835e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003840270270864607e+02,7.149725711173588252e+02,5.081001598293717336e-01,1.100000010988609489e+01,4.344769236350495660e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003849361179864701e+02,7.149825711164149880e+02,5.081045045984713404e-01,1.100000010988609489e+01,4.343309382335118485e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003858452088864794e+02,7.149925711154717192e+02,5.081088479077171538e-01,1.100000010988609489e+01,4.341849528319741310e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003867542997864888e+02,7.150025711145291325e+02,5.081131897571090628e-01,1.100000010988609489e+01,4.340389674304364134e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003876633906864981e+02,7.150125711135872280e+02,5.081175301466470673e-01,1.100000010988609489e+01,4.338929820288986959e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003885724815865075e+02,7.150225711126458918e+02,5.081218690763311674e-01,1.100000010988609489e+01,4.337469966273609784e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003894815724865168e+02,7.150325711117052379e+02,5.081262065461614741e-01,1.100000010988609489e+01,4.336010112258232609e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003903906633865262e+02,7.150425711107651523e+02,5.081305425561378764e-01,1.100000010988609489e+01,4.334550258242855433e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003912997542865355e+02,7.150525711098257489e+02,5.081348771062603742e-01,1.100000010988609489e+01,4.333090404227478258e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003922088451865449e+02,7.150625711088869139e+02,5.081392101965289676e-01,1.100000010988609489e+01,4.331630550212101083e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003931179360865542e+02,7.150725711079487610e+02,5.081435418269437676e-01,1.100000010988609489e+01,4.330170696196723908e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003940270269865636e+02,7.150825711070112902e+02,5.081478719975046632e-01,1.100000010988609489e+01,4.328710842181346732e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003949361178865729e+02,7.150925711060743879e+02,5.081522007082116543e-01,1.100000010988609489e+01,4.327250988165969557e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003958452087865822e+02,7.151025711051381677e+02,5.081565279590647410e-01,1.100000010988609489e+01,4.325791134150592382e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003967542996865916e+02,7.151125711042025159e+02,5.081608537500640344e-01,1.100000010988609489e+01,4.324331280135215207e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003976633905866009e+02,7.151225711032675463e+02,5.081651780812094232e-01,1.100000010988609489e+01,4.322871426119838031e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003985724814866103e+02,7.151325711023331451e+02,5.081695009525009077e-01,1.100000010988609489e+01,4.321411572104460856e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.003994815723866196e+02,7.151425711013994260e+02,5.081738223639384877e-01,1.100000010988609489e+01,4.319951718089083681e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004003906632866290e+02,7.151525711004662753e+02,5.081781423155221633e-01,1.100000010988609489e+01,4.318491864073706506e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004012997541866383e+02,7.151625710995338068e+02,5.081824608072520455e-01,1.100000010988609489e+01,4.317032010058329330e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004022088450866477e+02,7.151725710986020204e+02,5.081867778391280233e-01,1.100000010988609489e+01,4.315572156042952155e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004031179359866570e+02,7.151825710976708024e+02,5.081910934111500966e-01,1.100000010988609489e+01,4.314112302027574980e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004040270268866664e+02,7.151925710967402665e+02,5.081954075233182655e-01,1.100000010988609489e+01,4.312652448012197805e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004049361177866757e+02,7.152025710958102991e+02,5.081997201756326410e-01,1.100000010988609489e+01,4.311192593996820629e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004058452086866851e+02,7.152125710948810138e+02,5.082040313680931121e-01,1.100000010988609489e+01,4.309732739981443454e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004067542995866944e+02,7.152225710939522969e+02,5.082083411006996787e-01,1.100000010988609489e+01,4.308272885966066279e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004076633904867037e+02,7.152325710930242622e+02,5.082126493734523409e-01,1.100000010988609489e+01,4.306813031950689104e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004085724813867131e+02,7.152425710920967958e+02,5.082169561863510987e-01,1.100000010988609489e+01,4.305353177935311929e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004094815722867224e+02,7.152525710911700116e+02,5.082212615393960631e-01,1.100000010988609489e+01,4.303893323919934753e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004103906631867318e+02,7.152625710902437959e+02,5.082255654325871230e-01,1.100000010988609489e+01,4.302433469904557578e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004112997540867411e+02,7.152725710893182622e+02,5.082298678659242785e-01,1.100000010988609489e+01,4.300973615889180403e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004122088449867505e+02,7.152825710883932970e+02,5.082341688394075296e-01,1.100000010988609489e+01,4.299513761873803228e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004131179358867598e+02,7.152925710874690139e+02,5.082384683530369873e-01,1.100000010988609489e+01,4.298053907858426052e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004140270267867692e+02,7.153025710865452993e+02,5.082427664068125406e-01,1.100000010988609489e+01,4.296594053843048877e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004149361176867785e+02,7.153125710856222668e+02,5.082470630007341894e-01,1.100000010988609489e+01,4.295134199827671702e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004158452085867879e+02,7.153225710846998027e+02,5.082513581348019338e-01,1.100000010988609489e+01,4.293674345812294527e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004167542994867972e+02,7.153325710837780207e+02,5.082556518090157738e-01,1.100000010988609489e+01,4.292214491796917351e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004176633903868066e+02,7.153425710828569208e+02,5.082599440233758203e-01,1.100000010988609489e+01,4.290754637781540176e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004185724812868159e+02,7.153525710819363894e+02,5.082642347778819625e-01,1.100000010988609489e+01,4.289294783766163001e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004194815721868252e+02,7.153625710810165401e+02,5.082685240725342002e-01,1.100000010988609489e+01,4.287834929750785826e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004203906630868346e+02,7.153725710800972593e+02,5.082728119073325335e-01,1.100000010988609489e+01,4.286375075735408650e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004212997539868439e+02,7.153825710791786605e+02,5.082770982822769623e-01,1.100000010988609489e+01,4.284915221720031475e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004222088448868533e+02,7.153925710782606302e+02,5.082813831973675978e-01,1.100000010988609489e+01,4.283455367704654300e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004231179357868626e+02,7.154025710773432820e+02,5.082856666526043288e-01,1.100000010988609489e+01,4.281995513689277125e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004240270266868720e+02,7.154125710764265023e+02,5.082899486479871554e-01,1.100000010988609489e+01,4.280535659673899949e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004249361175868813e+02,7.154225710755104046e+02,5.082942291835160775e-01,1.100000010988609489e+01,4.279075805658522774e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004258452084868907e+02,7.154325710745948754e+02,5.082985082591910952e-01,1.100000010988609489e+01,4.277615951643145599e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004267542993869000e+02,7.154425710736800283e+02,5.083027858750123196e-01,1.100000010988609489e+01,4.276156097627768424e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004276633902869094e+02,7.154525710727657497e+02,5.083070620309796395e-01,1.100000010988609489e+01,4.274696243612391248e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004285724811869187e+02,7.154625710718521532e+02,5.083113367270930549e-01,1.100000010988609489e+01,4.273236389597014073e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004294815720869281e+02,7.154725710709391251e+02,5.083156099633525660e-01,1.100000010988609489e+01,4.271776535581636898e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004303906629869374e+02,7.154825710700266654e+02,5.083198817397582836e-01,1.100000010988609489e+01,4.270316681566259723e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004312997538869467e+02,7.154925710691148879e+02,5.083241520563100968e-01,1.100000010988609489e+01,4.268856827550882548e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004322088447869561e+02,7.155025710682036788e+02,5.083284209130080056e-01,1.100000010988609489e+01,4.267396973535505372e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004331179356869654e+02,7.155125710672931518e+02,5.083326883098520099e-01,1.100000010988609489e+01,4.265937119520128197e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004340270265869748e+02,7.155225710663831933e+02,5.083369542468421098e-01,1.100000010988609489e+01,4.264477265504751022e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004349361174869841e+02,7.155325710654739169e+02,5.083412187239783053e-01,1.100000010988609489e+01,4.263017411489373847e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004358452083869935e+02,7.155425710645652089e+02,5.083454817412607074e-01,1.100000010988609489e+01,4.261557557473996671e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004367542992870028e+02,7.155525710636571830e+02,5.083497432986892051e-01,1.100000010988609489e+01,4.260097703458619496e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004376633901870122e+02,7.155625710627497256e+02,5.083540033962637983e-01,1.100000010988609489e+01,4.258637849443242321e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004385724810870215e+02,7.155725710618429503e+02,5.083582620339844871e-01,1.100000010988609489e+01,4.257177995427865146e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004394815719870309e+02,7.155825710609367434e+02,5.083625192118512715e-01,1.100000010988609489e+01,4.255718141412487970e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004403906628870402e+02,7.155925710600312186e+02,5.083667749298642624e-01,1.100000010988609489e+01,4.254258287397110795e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004412997537870496e+02,7.156025710591262623e+02,5.083710291880233489e-01,1.100000010988609489e+01,4.252798433381733620e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004422088446870589e+02,7.156125710582219881e+02,5.083752819863285310e-01,1.100000010988609489e+01,4.251338579366356445e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004431179355870682e+02,7.156225710573182823e+02,5.083795333247798087e-01,1.100000010988609489e+01,4.249878725350979269e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004440270264870776e+02,7.156325710564152587e+02,5.083837832033771820e-01,1.100000010988609489e+01,4.248418871335602094e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004449361173870869e+02,7.156425710555128035e+02,5.083880316221207618e-01,1.100000010988609489e+01,4.246959017320224919e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004458452082870963e+02,7.156525710546109167e+02,5.083922785810104372e-01,1.100000010988609489e+01,4.245499163304847744e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004467542991871056e+02,7.156625710537097120e+02,5.083965240800462082e-01,1.100000010988609489e+01,4.244039309289470568e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004476633900871150e+02,7.156725710528090758e+02,5.084007681192280748e-01,1.100000010988609489e+01,4.242579455274093393e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004485724809871243e+02,7.156825710519091217e+02,5.084050106985560369e-01,1.100000010988609489e+01,4.241119601258716218e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004494815718871337e+02,7.156925710510097360e+02,5.084092518180302056e-01,1.100000010988609489e+01,4.239659747243339043e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004503906627871430e+02,7.157025710501110325e+02,5.084134914776504699e-01,1.100000010988609489e+01,4.238199893227961867e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004512997536871524e+02,7.157125710492128974e+02,5.084177296774168298e-01,1.100000010988609489e+01,4.236740039212584692e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004522088445871617e+02,7.157225710483154444e+02,5.084219664173292852e-01,1.100000010988609489e+01,4.235280185197207517e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004531179354871711e+02,7.157325710474185598e+02,5.084262016973878362e-01,1.100000010988609489e+01,4.233820331181830342e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004540270263871804e+02,7.157425710465222437e+02,5.084304355175924828e-01,1.100000010988609489e+01,4.232360477166453167e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004549361172871897e+02,7.157525710456266097e+02,5.084346678779433359e-01,1.100000010988609489e+01,4.230900623151075991e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004558452081871991e+02,7.157625710447315441e+02,5.084388987784402847e-01,1.100000010988609489e+01,4.229440769135698816e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004567542990872084e+02,7.157725710438371607e+02,5.084431282190833290e-01,1.100000010988609489e+01,4.227980915120321641e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004576633899872178e+02,7.157825710429433457e+02,5.084473561998724689e-01,1.100000010988609489e+01,4.226521061104944466e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004585724808872271e+02,7.157925710420502128e+02,5.084515827208077043e-01,1.100000010988609489e+01,4.225061207089567290e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004594815717872365e+02,7.158025710411576483e+02,5.084558077818890354e-01,1.100000010988609489e+01,4.223601353074190115e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004603906626872458e+02,7.158125710402656523e+02,5.084600313831165730e-01,1.100000010988609489e+01,4.222141499058812940e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004612997535872552e+02,7.158225710393743384e+02,5.084642535244902062e-01,1.100000010988609489e+01,4.220681645043435765e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004622088444872645e+02,7.158325710384835929e+02,5.084684742060099349e-01,1.100000010988609489e+01,4.219221791028058589e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004631179353872739e+02,7.158425710375935296e+02,5.084726934276757593e-01,1.100000010988609489e+01,4.217761937012681414e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004640270262872832e+02,7.158525710367040347e+02,5.084769111894876792e-01,1.100000010988609489e+01,4.216302082997304239e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004649361171872926e+02,7.158625710358152219e+02,5.084811274914458057e-01,1.100000010988609489e+01,4.214842228981927064e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004658452080873019e+02,7.158725710349269775e+02,5.084853423335500278e-01,1.100000010988609489e+01,4.213382374966549888e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004667542989873112e+02,7.158825710340393016e+02,5.084895557158003454e-01,1.100000010988609489e+01,4.211922520951172713e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004676633898873206e+02,7.158925710331523078e+02,5.084937676381967586e-01,1.100000010988609489e+01,4.210462666935795538e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004685724807873299e+02,7.159025710322658824e+02,5.084979781007392674e-01,1.100000010988609489e+01,4.209002812920418363e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004694815716873393e+02,7.159125710313801392e+02,5.085021871034278718e-01,1.100000010988609489e+01,4.207542958905041187e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004703906625873486e+02,7.159225710304949644e+02,5.085063946462626827e-01,1.100000010988609489e+01,4.206083104889664012e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004712997534873580e+02,7.159325710296103580e+02,5.085106007292435892e-01,1.100000010988609489e+01,4.204623250874286837e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004722088443873673e+02,7.159425710287264337e+02,5.085148053523705913e-01,1.100000010988609489e+01,4.203163396858909662e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004731179352873767e+02,7.159525710278430779e+02,5.085190085156436890e-01,1.100000010988609489e+01,4.201703542843532486e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004740270261873860e+02,7.159625710269604042e+02,5.085232102190628822e-01,1.100000010988609489e+01,4.200243688828155311e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004749361170873954e+02,7.159725710260782989e+02,5.085274104626281710e-01,1.100000010988609489e+01,4.198783834812778136e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004758452079874047e+02,7.159825710251967621e+02,5.085316092463396664e-01,1.100000010988609489e+01,4.197323980797400961e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004767542988874141e+02,7.159925710243159074e+02,5.085358065701972574e-01,1.100000010988609489e+01,4.195864126782023786e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004776633897874234e+02,7.160025710234356211e+02,5.085400024342009440e-01,1.100000010988609489e+01,4.194404272766646610e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004785724806874327e+02,7.160125710225560169e+02,5.085441968383507261e-01,1.100000010988609489e+01,4.192944418751269435e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004794815715874421e+02,7.160225710216769812e+02,5.085483897826466038e-01,1.100000010988609489e+01,4.191484564735892260e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004803906624874514e+02,7.160325710207985139e+02,5.085525812670885770e-01,1.100000010988609489e+01,4.190024710720515085e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004812997533874608e+02,7.160425710199207288e+02,5.085567712916766459e-01,1.100000010988609489e+01,4.188564856705137909e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004822088442874701e+02,7.160525710190435120e+02,5.085609598564109213e-01,1.100000010988609489e+01,4.187105002689760734e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004831179351874795e+02,7.160625710181668637e+02,5.085651469612912923e-01,1.100000010988609489e+01,4.185645148674383559e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004840270260874888e+02,7.160725710172908975e+02,5.085693326063177588e-01,1.100000010988609489e+01,4.184185294659006384e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004849361169874982e+02,7.160825710164154998e+02,5.085735167914903210e-01,1.100000010988609489e+01,4.182725440643629208e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004858452078875075e+02,7.160925710155407842e+02,5.085776995168089787e-01,1.100000010988609489e+01,4.181265586628252033e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004867542987875169e+02,7.161025710146666370e+02,5.085818807822737320e-01,1.100000010988609489e+01,4.179805732612874858e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004876633896875262e+02,7.161125710137930582e+02,5.085860605878846918e-01,1.100000010988609489e+01,4.178345878597497683e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004885724805875356e+02,7.161225710129201616e+02,5.085902389336417473e-01,1.100000010988609489e+01,4.176886024582120507e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004894815714875449e+02,7.161325710120478334e+02,5.085944158195448983e-01,1.100000010988609489e+01,4.175426170566743332e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004903906623875542e+02,7.161425710111760736e+02,5.085985912455941449e-01,1.100000010988609489e+01,4.173966316551366157e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004912997532875636e+02,7.161525710103049960e+02,5.086027652117894871e-01,1.100000010988609489e+01,4.172506462535988982e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004922088441875729e+02,7.161625710094344868e+02,5.086069377181309248e-01,1.100000010988609489e+01,4.171046608520611806e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004931179350875823e+02,7.161725710085646597e+02,5.086111087646184581e-01,1.100000010988609489e+01,4.169586754505234631e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004940270259875916e+02,7.161825710076954010e+02,5.086152783512521980e-01,1.100000010988609489e+01,4.168126900489857456e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004949361168876010e+02,7.161925710068267108e+02,5.086194464780320335e-01,1.100000010988609489e+01,4.166667046474480281e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004958452077876103e+02,7.162025710059587027e+02,5.086236131449579645e-01,1.100000010988609489e+01,4.165207192459103105e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004967542986876197e+02,7.162125710050912630e+02,5.086277783520299911e-01,1.100000010988609489e+01,4.163747338443725930e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004976633895876290e+02,7.162225710042243918e+02,5.086319420992481133e-01,1.100000010988609489e+01,4.162287484428348755e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004985724804876384e+02,7.162325710033582027e+02,5.086361043866123310e-01,1.100000010988609489e+01,4.160827630412971580e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.004994815713876477e+02,7.162425710024925820e+02,5.086402652141226444e-01,1.100000010988609489e+01,4.159367776397594405e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005003906622876571e+02,7.162525710016275298e+02,5.086444245817791643e-01,1.100000010988609489e+01,4.157907922382217229e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005012997531876664e+02,7.162625710007631596e+02,5.086485824895817798e-01,1.100000010988609489e+01,4.156448068366840054e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005022088440876757e+02,7.162725709998993580e+02,5.086527389375304908e-01,1.100000010988609489e+01,4.154988214351462879e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005031179349876851e+02,7.162825709990361247e+02,5.086568939256252975e-01,1.100000010988609489e+01,4.153528360336085704e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005040270258876944e+02,7.162925709981735736e+02,5.086610474538661997e-01,1.100000010988609489e+01,4.152068506320708528e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005049361167877038e+02,7.163025709973115909e+02,5.086651995222531975e-01,1.100000010988609489e+01,4.150608652305331353e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005058452076877131e+02,7.163125709964501766e+02,5.086693501307862908e-01,1.100000010988609489e+01,4.149148798289954178e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005067542985877225e+02,7.163225709955894445e+02,5.086734992794654797e-01,1.100000010988609489e+01,4.147688944274577003e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005076633894877318e+02,7.163325709947292808e+02,5.086776469682908752e-01,1.100000010988609489e+01,4.146229090259199827e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005085724803877412e+02,7.163425709938696855e+02,5.086817931972623663e-01,1.100000010988609489e+01,4.144769236243822652e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005094815712877505e+02,7.163525709930107723e+02,5.086859379663799530e-01,1.100000010988609489e+01,4.143309382228445477e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005103906621877599e+02,7.163625709921524276e+02,5.086900812756436352e-01,1.100000010988609489e+01,4.141849528213068302e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005112997530877692e+02,7.163725709912946513e+02,5.086942231250534130e-01,1.100000010988609489e+01,4.140389674197691126e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005122088439877786e+02,7.163825709904375572e+02,5.086983635146092864e-01,1.100000010988609489e+01,4.138929820182313951e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005131179348877879e+02,7.163925709895810314e+02,5.087025024443112553e-01,1.100000010988609489e+01,4.137469966166936776e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005140270257877972e+02,7.164025709887250741e+02,5.087066399141594308e-01,1.100000010988609489e+01,4.136010112151559601e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005149361166878066e+02,7.164125709878697990e+02,5.087107759241537019e-01,1.100000010988609489e+01,4.134550258136182425e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005158452075878159e+02,7.164225709870150922e+02,5.087149104742940686e-01,1.100000010988609489e+01,4.133090404120805250e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005167542984878253e+02,7.164325709861609539e+02,5.087190435645805309e-01,1.100000010988609489e+01,4.131630550105428075e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005176633893878346e+02,7.164425709853073840e+02,5.087231751950130887e-01,1.100000010988609489e+01,4.130170696090050900e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005185724802878440e+02,7.164525709844544963e+02,5.087273053655917421e-01,1.100000010988609489e+01,4.128710842074673724e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005194815711878533e+02,7.164625709836021770e+02,5.087314340763164910e-01,1.100000010988609489e+01,4.127250988059296549e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005203906620878627e+02,7.164725709827504261e+02,5.087355613271873356e-01,1.100000010988609489e+01,4.125791134043919374e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005212997529878720e+02,7.164825709818993573e+02,5.087396871182042757e-01,1.100000010988609489e+01,4.124331280028542199e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005222088438878814e+02,7.164925709810488570e+02,5.087438114493674224e-01,1.100000010988609489e+01,4.122871426013165023e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005231179347878907e+02,7.165025709801989251e+02,5.087479343206766647e-01,1.100000010988609489e+01,4.121411571997787848e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005240270256879000e+02,7.165125709793496753e+02,5.087520557321320025e-01,1.100000010988609489e+01,4.119951717982410673e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005249361165879094e+02,7.165225709785009940e+02,5.087561756837334359e-01,1.100000010988609489e+01,4.118491863967033498e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005258452074879187e+02,7.165325709776528811e+02,5.087602941754809649e-01,1.100000010988609489e+01,4.117032009951656323e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005267542983879281e+02,7.165425709768053366e+02,5.087644112073745895e-01,1.100000010988609489e+01,4.115572155936279147e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005276633892879374e+02,7.165525709759584743e+02,5.087685267794143096e-01,1.100000010988609489e+01,4.114112301920901972e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005285724801879468e+02,7.165625709751121803e+02,5.087726408916001253e-01,1.100000010988609489e+01,4.112652447905524797e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005294815710879561e+02,7.165725709742664549e+02,5.087767535439321476e-01,1.100000010988609489e+01,4.111192593890147622e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005303906619879655e+02,7.165825709734214115e+02,5.087808647364102654e-01,1.100000010988609489e+01,4.109732739874770446e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005312997528879748e+02,7.165925709725769366e+02,5.087849744690344789e-01,1.100000010988609489e+01,4.108272885859393271e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005322088437879842e+02,7.166025709717330301e+02,5.087890827418047879e-01,1.100000010988609489e+01,4.106813031844016096e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005331179346879935e+02,7.166125709708896920e+02,5.087931895547211925e-01,1.100000010988609489e+01,4.105353177828638921e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005340270255880029e+02,7.166225709700470361e+02,5.087972949077836926e-01,1.100000010988609489e+01,4.103893323813261745e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005349361164880122e+02,7.166325709692049486e+02,5.088013988009922883e-01,1.100000010988609489e+01,4.102433469797884570e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005358452073880215e+02,7.166425709683634295e+02,5.088055012343469796e-01,1.100000010988609489e+01,4.100973615782507395e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005367542982880309e+02,7.166525709675224789e+02,5.088096022078477665e-01,1.100000010988609489e+01,4.099513761767130220e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005376633891880402e+02,7.166625709666822104e+02,5.088137017214947599e-01,1.100000010988609489e+01,4.098053907751753044e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005385724800880496e+02,7.166725709658425103e+02,5.088177997752878490e-01,1.100000010988609489e+01,4.096594053736375869e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005394815709880589e+02,7.166825709650033787e+02,5.088218963692270336e-01,1.100000010988609489e+01,4.095134199720998694e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005403906618880683e+02,7.166925709641649291e+02,5.088259915033123137e-01,1.100000010988609489e+01,4.093674345705621519e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005412997527880776e+02,7.167025709633270480e+02,5.088300851775436895e-01,1.100000010988609489e+01,4.092214491690244343e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005422088436880870e+02,7.167125709624897354e+02,5.088341773919211608e-01,1.100000010988609489e+01,4.090754637674867168e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005431179345880963e+02,7.167225709616529912e+02,5.088382681464447277e-01,1.100000010988609489e+01,4.089294783659489993e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005440270254881057e+02,7.167325709608169291e+02,5.088423574411143901e-01,1.100000010988609489e+01,4.087834929644112818e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005449361163881150e+02,7.167425709599814354e+02,5.088464452759301482e-01,1.100000010988609489e+01,4.086375075628735642e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005458452072881244e+02,7.167525709591465102e+02,5.088505316508920018e-01,1.100000010988609489e+01,4.084915221613358467e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005467542981881337e+02,7.167625709583121534e+02,5.088546165660000620e-01,1.100000010988609489e+01,4.083455367597981292e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005476633890881430e+02,7.167725709574784787e+02,5.088587000212542177e-01,1.100000010988609489e+01,4.081995513582604117e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005485724799881524e+02,7.167825709566453725e+02,5.088627820166544691e-01,1.100000010988609489e+01,4.080535659567226942e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005494815708881617e+02,7.167925709558128347e+02,5.088668625522008160e-01,1.100000010988609489e+01,4.079075805551849766e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005503906617881711e+02,7.168025709549808653e+02,5.088709416278932585e-01,1.100000010988609489e+01,4.077615951536472591e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005512997526881804e+02,7.168125709541494643e+02,5.088750192437317965e-01,1.100000010988609489e+01,4.076156097521095416e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005522088435881898e+02,7.168225709533187455e+02,5.088790953997164301e-01,1.100000010988609489e+01,4.074696243505718241e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005531179344881991e+02,7.168325709524885951e+02,5.088831700958471593e-01,1.100000010988609489e+01,4.073236389490341065e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005540270253882085e+02,7.168425709516590132e+02,5.088872433321239841e-01,1.100000010988609489e+01,4.071776535474963890e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005549361162882178e+02,7.168525709508299997e+02,5.088913151085469044e-01,1.100000010988609489e+01,4.070316681459586715e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005558452071882272e+02,7.168625709500016683e+02,5.088953854251159203e-01,1.100000010988609489e+01,4.068856827444209540e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005567542980882365e+02,7.168725709491739053e+02,5.088994542818311428e-01,1.100000010988609489e+01,4.067396973428832364e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005576633889882459e+02,7.168825709483467108e+02,5.089035216786924609e-01,1.100000010988609489e+01,4.065937119413455189e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005585724798882552e+02,7.168925709475200847e+02,5.089075876156998746e-01,1.100000010988609489e+01,4.064477265398078014e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005594815707882645e+02,7.169025709466941407e+02,5.089116520928533838e-01,1.100000010988609489e+01,4.063017411382700839e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005603906616882739e+02,7.169125709458687652e+02,5.089157151101529886e-01,1.100000010988609489e+01,4.061557557367323663e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005612997525882832e+02,7.169225709450439581e+02,5.089197766675986889e-01,1.100000010988609489e+01,4.060097703351946488e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005622088434882926e+02,7.169325709442197194e+02,5.089238367651904849e-01,1.100000010988609489e+01,4.058637849336569313e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005631179343883019e+02,7.169425709433960492e+02,5.089278954029283764e-01,1.100000010988609489e+01,4.057177995321192138e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005640270252883113e+02,7.169525709425730611e+02,5.089319525808123634e-01,1.100000010988609489e+01,4.055718141305814962e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005649361161883206e+02,7.169625709417506414e+02,5.089360082988424461e-01,1.100000010988609489e+01,4.054258287290437787e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005658452070883300e+02,7.169725709409287902e+02,5.089400625570186243e-01,1.100000010988609489e+01,4.052798433275060612e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005667542979883393e+02,7.169825709401075073e+02,5.089441153553408981e-01,1.100000010988609489e+01,4.051338579259683437e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005676633888883487e+02,7.169925709392867930e+02,5.089481666938093785e-01,1.100000010988609489e+01,4.049878725244306261e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005685724797883580e+02,7.170025709384667607e+02,5.089522165724239544e-01,1.100000010988609489e+01,4.048418871228929086e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005694815706883674e+02,7.170125709376472969e+02,5.089562649911846259e-01,1.100000010988609489e+01,4.046959017213551911e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005703906615883767e+02,7.170225709368284015e+02,5.089603119500913930e-01,1.100000010988609489e+01,4.045499163198174736e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005712997524883860e+02,7.170325709360100745e+02,5.089643574491442557e-01,1.100000010988609489e+01,4.044039309182797561e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005722088433883954e+02,7.170425709351923160e+02,5.089684014883432139e-01,1.100000010988609489e+01,4.042579455167420385e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005731179342884047e+02,7.170525709343752396e+02,5.089724440676882677e-01,1.100000010988609489e+01,4.041119601152043210e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005740270251884141e+02,7.170625709335587317e+02,5.089764851871794171e-01,1.100000010988609489e+01,4.039659747136666035e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005749361160884234e+02,7.170725709327427921e+02,5.089805248468166621e-01,1.100000010988609489e+01,4.038199893121288860e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005758452069884328e+02,7.170825709319274210e+02,5.089845630466000026e-01,1.100000010988609489e+01,4.036740039105911684e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005767542978884421e+02,7.170925709311126184e+02,5.089885997865294387e-01,1.100000010988609489e+01,4.035280185090534509e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005776633887884515e+02,7.171025709302984978e+02,5.089926350666049704e-01,1.100000010988609489e+01,4.033820331075157334e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005785724796884608e+02,7.171125709294849457e+02,5.089966688868265976e-01,1.100000010988609489e+01,4.032360477059780159e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005794815705884702e+02,7.171225709286719621e+02,5.090007012471944314e-01,1.100000010988609489e+01,4.030900623044402983e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005803906614884795e+02,7.171325709278595468e+02,5.090047321477083608e-01,1.100000010988609489e+01,4.029440769029025808e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005812997523884889e+02,7.171425709270477000e+02,5.090087615883683858e-01,1.100000010988609489e+01,4.027980915013648633e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005822088432884982e+02,7.171525709262364217e+02,5.090127895691745064e-01,1.100000010988609489e+01,4.026521060998271458e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005831179341885075e+02,7.171625709254258254e+02,5.090168160901267225e-01,1.100000010988609489e+01,4.025061206982894282e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005840270250885169e+02,7.171725709246157976e+02,5.090208411512250342e-01,1.100000010988609489e+01,4.023601352967517107e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005849361159885262e+02,7.171825709238063382e+02,5.090248647524694414e-01,1.100000010988609489e+01,4.022141498952139932e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005858452068885356e+02,7.171925709229974473e+02,5.090288868938599443e-01,1.100000010988609489e+01,4.020681644936762757e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005867542977885449e+02,7.172025709221891248e+02,5.090329075753965427e-01,1.100000010988609489e+01,4.019221790921385581e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005876633886885543e+02,7.172125709213813707e+02,5.090369267970792366e-01,1.100000010988609489e+01,4.017761936906008406e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005885724795885636e+02,7.172225709205742987e+02,5.090409445589080262e-01,1.100000010988609489e+01,4.016302082890631231e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005894815704885730e+02,7.172325709197677952e+02,5.090449608608829113e-01,1.100000010988609489e+01,4.014842228875254056e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005903906613885823e+02,7.172425709189618601e+02,5.090489757030038920e-01,1.100000010988609489e+01,4.013382374859876880e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005912997522885917e+02,7.172525709181564935e+02,5.090529890852709682e-01,1.100000010988609489e+01,4.011922520844499705e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005922088431886010e+02,7.172625709173516952e+02,5.090570010076841401e-01,1.100000010988609489e+01,4.010462666829122530e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005931179340886104e+02,7.172725709165474655e+02,5.090610114702435185e-01,1.100000010988609489e+01,4.009002812813745355e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005940270249886197e+02,7.172825709157438041e+02,5.090650204729489925e-01,1.100000010988609489e+01,4.007542958798368180e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005949361158886290e+02,7.172925709149408249e+02,5.090690280158005621e-01,1.100000010988609489e+01,4.006083104782991004e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005958452067886384e+02,7.173025709141384141e+02,5.090730340987982272e-01,1.100000010988609489e+01,4.004623250767613829e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005967542976886477e+02,7.173125709133365717e+02,5.090770387219419879e-01,1.100000010988609489e+01,4.003163396752236654e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005976633885886571e+02,7.173225709125352978e+02,5.090810418852318442e-01,1.100000010988609489e+01,4.001703542736859479e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005985724794886664e+02,7.173325709117345923e+02,5.090850435886677960e-01,1.100000010988609489e+01,4.000243688721482303e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.005994815703886758e+02,7.173425709109344552e+02,5.090890438322498435e-01,1.100000010988609489e+01,3.998783834706105128e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006003906612886851e+02,7.173525709101348866e+02,5.090930426159779865e-01,1.100000010988609489e+01,3.997323980690727953e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006012997521886945e+02,7.173625709093360001e+02,5.090970399398522250e-01,1.100000010988609489e+01,3.995864126675350778e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006022088430887038e+02,7.173725709085376820e+02,5.091010358038725592e-01,1.100000010988609489e+01,3.994404272659973602e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006031179339887132e+02,7.173825709077399324e+02,5.091050302080389889e-01,1.100000010988609489e+01,3.992944418644596427e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006040270248887225e+02,7.173925709069427512e+02,5.091090231523515142e-01,1.100000010988609489e+01,3.991484564629219252e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006049361157887319e+02,7.174025709061461384e+02,5.091130146368101350e-01,1.100000010988609489e+01,3.990024710613842077e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006058452066887412e+02,7.174125709053500941e+02,5.091170046614148514e-01,1.100000010988609489e+01,3.988564856598464901e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006067542975887505e+02,7.174225709045546182e+02,5.091209932261656634e-01,1.100000010988609489e+01,3.987105002583087726e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006076633884887599e+02,7.174325709037598244e+02,5.091249803310625710e-01,1.100000010988609489e+01,3.985645148567710551e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006085724793887692e+02,7.174425709029655991e+02,5.091289659761055741e-01,1.100000010988609489e+01,3.984185294552333376e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006094815702887786e+02,7.174525709021719422e+02,5.091329501612946729e-01,1.100000010988609489e+01,3.982725440536956200e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006103906611887879e+02,7.174625709013788537e+02,5.091369328866298671e-01,1.100000010988609489e+01,3.981265586521579025e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006112997520887973e+02,7.174725709005863337e+02,5.091409141521112680e-01,1.100000010988609489e+01,3.979805732506201850e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006122088429888066e+02,7.174825708997943821e+02,5.091448939577387645e-01,1.100000010988609489e+01,3.978345878490824675e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006131179338888160e+02,7.174925708990029989e+02,5.091488723035123565e-01,1.100000010988609489e+01,3.976886024475447499e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006140270247888253e+02,7.175025708982121841e+02,5.091528491894320441e-01,1.100000010988609489e+01,3.975426170460070324e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006149361156888347e+02,7.175125708974219378e+02,5.091568246154978272e-01,1.100000010988609489e+01,3.973966316444693149e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006158452065888440e+02,7.175225708966323737e+02,5.091607985817097060e-01,1.100000010988609489e+01,3.972506462429315974e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006167542974888534e+02,7.175325708958433779e+02,5.091647710880676803e-01,1.100000010988609489e+01,3.971046608413938798e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006176633883888627e+02,7.175425708950549506e+02,5.091687421345717501e-01,1.100000010988609489e+01,3.969586754398561623e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006185724792888720e+02,7.175525708942670917e+02,5.091727117212219156e-01,1.100000010988609489e+01,3.968126900383184448e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006194815701888814e+02,7.175625708934798013e+02,5.091766798480181766e-01,1.100000010988609489e+01,3.966667046367807273e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006203906610888907e+02,7.175725708926930793e+02,5.091806465149605332e-01,1.100000010988609489e+01,3.965207192352430098e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006212997519889001e+02,7.175825708919069257e+02,5.091846117220489853e-01,1.100000010988609489e+01,3.963747338337052922e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006222088428889094e+02,7.175925708911213405e+02,5.091885754692835331e-01,1.100000010988609489e+01,3.962287484321675747e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006231179337889188e+02,7.176025708903363238e+02,5.091925377566641764e-01,1.100000010988609489e+01,3.960827630306298572e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006240270246889281e+02,7.176125708895518756e+02,5.091964985841909153e-01,1.100000010988609489e+01,3.959367776290921397e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006249361155889375e+02,7.176225708887679957e+02,5.092004579518637497e-01,1.100000010988609489e+01,3.957907922275544221e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006258452064889468e+02,7.176325708879847980e+02,5.092044158596826797e-01,1.100000010988609489e+01,3.956448068260167046e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006267542973889562e+02,7.176425708872021687e+02,5.092083723076477053e-01,1.100000010988609489e+01,3.954988214244789871e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006276633882889655e+02,7.176525708864201079e+02,5.092123272957588265e-01,1.100000010988609489e+01,3.953528360229412696e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006285724791889749e+02,7.176625708856386154e+02,5.092162808240160432e-01,1.100000010988609489e+01,3.952068506214035520e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006294815700889842e+02,7.176725708848576915e+02,5.092202328924193555e-01,1.100000010988609489e+01,3.950608652198658345e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006303906609889935e+02,7.176825708840773359e+02,5.092241835009687634e-01,1.100000010988609489e+01,3.949148798183281170e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006312997518890029e+02,7.176925708832975488e+02,5.092281326496642668e-01,1.100000010988609489e+01,3.947688944167903995e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006322088427890122e+02,7.177025708825183301e+02,5.092320803385058658e-01,1.100000010988609489e+01,3.946229090152526819e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006331179336890216e+02,7.177125708817396799e+02,5.092360265674935604e-01,1.100000010988609489e+01,3.944769236137149644e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006340270245890309e+02,7.177225708809615980e+02,5.092399713366273506e-01,1.100000010988609489e+01,3.943309382121772469e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006349361154890403e+02,7.177325708801840847e+02,5.092439146459072363e-01,1.100000010988609489e+01,3.941849528106395294e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006358452063890496e+02,7.177425708794071397e+02,5.092478564953332176e-01,1.100000010988609489e+01,3.940389674091018118e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006367542972890590e+02,7.177525708786307632e+02,5.092517968849052945e-01,1.100000010988609489e+01,3.938929820075640943e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006376633881890683e+02,7.177625708778549551e+02,5.092557358146234670e-01,1.100000010988609489e+01,3.937469966060263768e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006385724790890777e+02,7.177725708770797155e+02,5.092596732844877350e-01,1.100000010988609489e+01,3.936010112044886593e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006394815699890870e+02,7.177825708763051580e+02,5.092636092944980986e-01,1.100000010988609489e+01,3.934550258029509417e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006403906608890964e+02,7.177925708755311689e+02,5.092675438446545577e-01,1.100000010988609489e+01,3.933090404014132242e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006412997517891057e+02,7.178025708747577482e+02,5.092714769349572235e-01,1.100000010988609489e+01,3.931630549998755067e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006422088426891150e+02,7.178125708739848960e+02,5.092754085654059848e-01,1.100000010988609489e+01,3.930170695983377892e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006431179335891244e+02,7.178225708732126122e+02,5.092793387360008417e-01,1.100000010988609489e+01,3.928710841968000717e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006440270244891337e+02,7.178325708724408969e+02,5.092832674467417942e-01,1.100000010988609489e+01,3.927250987952623541e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006449361153891431e+02,7.178425708716697500e+02,5.092871946976288422e-01,1.100000010988609489e+01,3.925791133937246366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006458452062891524e+02,7.178525708708991715e+02,5.092911204886619858e-01,1.100000010988609489e+01,3.924331279921869191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006467542971891618e+02,7.178625708701291614e+02,5.092950448198412250e-01,1.100000010988609489e+01,3.922871425906492016e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006476633880891711e+02,7.178725708693597198e+02,5.092989676911665597e-01,1.100000010988609489e+01,3.921411571891114840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006485724789891805e+02,7.178825708685908467e+02,5.093028891026379901e-01,1.100000010988609489e+01,3.919951717875737665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006494815698891898e+02,7.178925708678225419e+02,5.093068090542555160e-01,1.100000010988609489e+01,3.918491863860360490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006503906607891992e+02,7.179025708670548056e+02,5.093107275460191374e-01,1.100000010988609489e+01,3.917032009844983315e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006512997516892085e+02,7.179125708662876377e+02,5.093146445779288545e-01,1.100000010988609489e+01,3.915572155829606139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006522088425892179e+02,7.179225708655210383e+02,5.093185601499846671e-01,1.100000010988609489e+01,3.914112301814228964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006531179334892272e+02,7.179325708647550073e+02,5.093224742621865753e-01,1.100000010988609489e+01,3.912652447798851789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006540270243892365e+02,7.179425708639895447e+02,5.093263869145345790e-01,1.100000010988609489e+01,3.911192593783474614e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006549361152892459e+02,7.179525708632246506e+02,5.093302981070286783e-01,1.100000010988609489e+01,3.909732739768097438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006558452061892552e+02,7.179625708624603249e+02,5.093342078396688732e-01,1.100000010988609489e+01,3.908272885752720263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006567542970892646e+02,7.179725708616965676e+02,5.093381161124551637e-01,1.100000010988609489e+01,3.906813031737343088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006576633879892739e+02,7.179825708609333788e+02,5.093420229253875497e-01,1.100000010988609489e+01,3.905353177721965913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006585724788892833e+02,7.179925708601707584e+02,5.093459282784660314e-01,1.100000010988609489e+01,3.903893323706588737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006594815697892926e+02,7.180025708594087064e+02,5.093498321716906085e-01,1.100000010988609489e+01,3.902433469691211562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006603906606893020e+02,7.180125708586472228e+02,5.093537346050612813e-01,1.100000010988609489e+01,3.900973615675834387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006612997515893113e+02,7.180225708578863077e+02,5.093576355785780496e-01,1.100000010988609489e+01,3.899513761660457212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006622088424893207e+02,7.180325708571259611e+02,5.093615350922409135e-01,1.100000010988609489e+01,3.898053907645080036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006631179333893300e+02,7.180425708563661829e+02,5.093654331460498730e-01,1.100000010988609489e+01,3.896594053629702861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006640270242893394e+02,7.180525708556069731e+02,5.093693297400049280e-01,1.100000010988609489e+01,3.895134199614325686e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006649361151893487e+02,7.180625708548483317e+02,5.093732248741060786e-01,1.100000010988609489e+01,3.893674345598948511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006658452060893580e+02,7.180725708540902588e+02,5.093771185483533248e-01,1.100000010988609489e+01,3.892214491583571336e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006667542969893674e+02,7.180825708533327543e+02,5.093810107627466666e-01,1.100000010988609489e+01,3.890754637568194160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006676633878893767e+02,7.180925708525758182e+02,5.093849015172861039e-01,1.100000010988609489e+01,3.889294783552816985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006685724787893861e+02,7.181025708518194506e+02,5.093887908119716368e-01,1.100000010988609489e+01,3.887834929537439810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006694815696893954e+02,7.181125708510636514e+02,5.093926786468032653e-01,1.100000010988609489e+01,3.886375075522062635e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006703906605894048e+02,7.181225708503084206e+02,5.093965650217809893e-01,1.100000010988609489e+01,3.884915221506685459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006712997514894141e+02,7.181325708495537583e+02,5.094004499369048089e-01,1.100000010988609489e+01,3.883455367491308284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006722088423894235e+02,7.181425708487996644e+02,5.094043333921747241e-01,1.100000010988609489e+01,3.881995513475931109e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006731179332894328e+02,7.181525708480461390e+02,5.094082153875907348e-01,1.100000010988609489e+01,3.880535659460553934e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006740270241894422e+02,7.181625708472931819e+02,5.094120959231528412e-01,1.100000010988609489e+01,3.879075805445176758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006749361150894515e+02,7.181725708465407934e+02,5.094159749988610431e-01,1.100000010988609489e+01,3.877615951429799583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006758452059894609e+02,7.181825708457889732e+02,5.094198526147153405e-01,1.100000010988609489e+01,3.876156097414422408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006767542968894702e+02,7.181925708450377215e+02,5.094237287707157336e-01,1.100000010988609489e+01,3.874696243399045233e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006776633877894795e+02,7.182025708442870382e+02,5.094276034668622222e-01,1.100000010988609489e+01,3.873236389383668057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006785724786894889e+02,7.182125708435369233e+02,5.094314767031548064e-01,1.100000010988609489e+01,3.871776535368290882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006794815695894982e+02,7.182225708427873769e+02,5.094353484795934861e-01,1.100000010988609489e+01,3.870316681352913707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006803906604895076e+02,7.182325708420383990e+02,5.094392187961782614e-01,1.100000010988609489e+01,3.868856827337536532e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006812997513895169e+02,7.182425708412899894e+02,5.094430876529091323e-01,1.100000010988609489e+01,3.867396973322159356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006822088422895263e+02,7.182525708405421483e+02,5.094469550497860988e-01,1.100000010988609489e+01,3.865937119306782181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006831179331895356e+02,7.182625708397948756e+02,5.094508209868091608e-01,1.100000010988609489e+01,3.864477265291405006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006840270240895450e+02,7.182725708390481714e+02,5.094546854639783184e-01,1.100000010988609489e+01,3.863017411276027831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006849361149895543e+02,7.182825708383020356e+02,5.094585484812934606e-01,1.100000010988609489e+01,3.861557557260650655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006858452058895637e+02,7.182925708375564682e+02,5.094624100387546983e-01,1.100000010988609489e+01,3.860097703245273480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006867542967895730e+02,7.183025708368114692e+02,5.094662701363620316e-01,1.100000010988609489e+01,3.858637849229896305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006876633876895824e+02,7.183125708360670387e+02,5.094701287741154605e-01,1.100000010988609489e+01,3.857177995214519130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006885724785895917e+02,7.183225708353231767e+02,5.094739859520149849e-01,1.100000010988609489e+01,3.855718141199141955e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006894815694896010e+02,7.183325708345798830e+02,5.094778416700606050e-01,1.100000010988609489e+01,3.854258287183764779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006903906603896104e+02,7.183425708338371578e+02,5.094816959282523205e-01,1.100000010988609489e+01,3.852798433168387604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006912997512896197e+02,7.183525708330950010e+02,5.094855487265901317e-01,1.100000010988609489e+01,3.851338579153010429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006922088421896291e+02,7.183625708323534127e+02,5.094894000650740384e-01,1.100000010988609489e+01,3.849878725137633254e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006931179330896384e+02,7.183725708316122791e+02,5.094932499437040407e-01,1.100000010988609489e+01,3.848418871122256078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006940270239896478e+02,7.183825708308717140e+02,5.094970983624801386e-01,1.100000010988609489e+01,3.846959017106878903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006949361148896571e+02,7.183925708301317172e+02,5.095009453214023321e-01,1.100000010988609489e+01,3.845499163091501728e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006958452057896665e+02,7.184025708293922889e+02,5.095047908204706211e-01,1.100000010988609489e+01,3.844039309076124553e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006967542966896758e+02,7.184125708286534291e+02,5.095086348596850057e-01,1.100000010988609489e+01,3.842579455060747377e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006976633875896852e+02,7.184225708279151377e+02,5.095124774390454858e-01,1.100000010988609489e+01,3.841119601045370202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006985724784896945e+02,7.184325708271774147e+02,5.095163185585520615e-01,1.100000010988609489e+01,3.839659747029993027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.006994815693897038e+02,7.184425708264402601e+02,5.095201582182047328e-01,1.100000010988609489e+01,3.838199893014615852e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007003906602897132e+02,7.184525708257036740e+02,5.095239964180034997e-01,1.100000010988609489e+01,3.836740038999238676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007012997511897225e+02,7.184625708249676563e+02,5.095278331579483622e-01,1.100000010988609489e+01,3.835280184983861501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007022088420897319e+02,7.184725708242322071e+02,5.095316684380393202e-01,1.100000010988609489e+01,3.833820330968484326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007031179329897412e+02,7.184825708234973263e+02,5.095355022582763738e-01,1.100000010988609489e+01,3.832360476953107151e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007040270238897506e+02,7.184925708227630139e+02,5.095393346186595229e-01,1.100000010988609489e+01,3.830900622937729975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007049361147897599e+02,7.185025708220292699e+02,5.095431655191887677e-01,1.100000010988609489e+01,3.829440768922352800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007058452056897693e+02,7.185125708212960944e+02,5.095469949598641080e-01,1.100000010988609489e+01,3.827980914906975625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007067542965897786e+02,7.185225708205633737e+02,5.095508229406855438e-01,1.100000010988609489e+01,3.826521060891598450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007076633874897880e+02,7.185325708198312213e+02,5.095546494616530753e-01,1.100000010988609489e+01,3.825061206876221274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007085724783897973e+02,7.185425708190996374e+02,5.095584745227667023e-01,1.100000010988609489e+01,3.823601352860844099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007094815692898067e+02,7.185525708183686220e+02,5.095622981240264249e-01,1.100000010988609489e+01,3.822141498845466924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007103906601898160e+02,7.185625708176381750e+02,5.095661202654322430e-01,1.100000010988609489e+01,3.820681644830089749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007112997510898253e+02,7.185725708169082964e+02,5.095699409469841568e-01,1.100000010988609489e+01,3.819221790814712574e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007122088419898347e+02,7.185825708161789862e+02,5.095737601686821661e-01,1.100000010988609489e+01,3.817761936799335398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007131179328898440e+02,7.185925708154502445e+02,5.095775779305262709e-01,1.100000010988609489e+01,3.816302082783958223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007140270237898534e+02,7.186025708147220712e+02,5.095813942325164714e-01,1.100000010988609489e+01,3.814842228768581048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007149361146898627e+02,7.186125708139944663e+02,5.095852090746526564e-01,1.100000010988609489e+01,3.813382374753203873e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007158452055898721e+02,7.186225708132673162e+02,5.095890224569349369e-01,1.100000010988609489e+01,3.811922520737826697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007167542964898814e+02,7.186325708125407346e+02,5.095928343793633131e-01,1.100000010988609489e+01,3.810462666722449522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007176633873898908e+02,7.186425708118147213e+02,5.095966448419377848e-01,1.100000010988609489e+01,3.809002812707072347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007185724782899001e+02,7.186525708110892765e+02,5.096004538446583521e-01,1.100000010988609489e+01,3.807542958691695172e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007194815691899095e+02,7.186625708103644001e+02,5.096042613875250149e-01,1.100000010988609489e+01,3.806083104676317996e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007203906600899188e+02,7.186725708096400922e+02,5.096080674705377733e-01,1.100000010988609489e+01,3.804623250660940821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007212997509899282e+02,7.186825708089163527e+02,5.096118720936966273e-01,1.100000010988609489e+01,3.803163396645563646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007222088418899375e+02,7.186925708081931816e+02,5.096156752570015769e-01,1.100000010988609489e+01,3.801703542630186471e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007231179327899468e+02,7.187025708074705790e+02,5.096194769604526220e-01,1.100000010988609489e+01,3.800243688614809295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007240270236899562e+02,7.187125708067484311e+02,5.096232772040497627e-01,1.100000010988609489e+01,3.798783834599432120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007249361145899655e+02,7.187225708060268516e+02,5.096270759877929990e-01,1.100000010988609489e+01,3.797323980584054945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007258452054899749e+02,7.187325708053058406e+02,5.096308733116823309e-01,1.100000010988609489e+01,3.795864126568677770e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007267542963899842e+02,7.187425708045853980e+02,5.096346691757177583e-01,1.100000010988609489e+01,3.794404272553300594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007276633872899936e+02,7.187525708038655239e+02,5.096384635798992813e-01,1.100000010988609489e+01,3.792944418537923419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007285724781900029e+02,7.187625708031462182e+02,5.096422565242268998e-01,1.100000010988609489e+01,3.791484564522546244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007294815690900123e+02,7.187725708024274809e+02,5.096460480087006140e-01,1.100000010988609489e+01,3.790024710507169069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007303906599900216e+02,7.187825708017093120e+02,5.096498380333204237e-01,1.100000010988609489e+01,3.788564856491791893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007312997508900310e+02,7.187925708009915979e+02,5.096536265980863289e-01,1.100000010988609489e+01,3.787105002476414718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007322088417900403e+02,7.188025708002744523e+02,5.096574137029983298e-01,1.100000010988609489e+01,3.785645148461037543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007331179326900497e+02,7.188125707995578750e+02,5.096611993480563152e-01,1.100000010988609489e+01,3.784185294445660368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007340270235900590e+02,7.188225707988418662e+02,5.096649835332603962e-01,1.100000010988609489e+01,3.782725440430283192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007349361144900683e+02,7.188325707981264259e+02,5.096687662586105727e-01,1.100000010988609489e+01,3.781265586414906017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007358452053900777e+02,7.188425707974115539e+02,5.096725475241068448e-01,1.100000010988609489e+01,3.779805732399528842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007367542962900870e+02,7.188525707966972504e+02,5.096763273297492125e-01,1.100000010988609489e+01,3.778345878384151667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007376633871900964e+02,7.188625707959834017e+02,5.096801056755376758e-01,1.100000010988609489e+01,3.776886024368774492e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007385724780901057e+02,7.188725707952701214e+02,5.096838825614722346e-01,1.100000010988609489e+01,3.775426170353397316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007394815689901151e+02,7.188825707945574095e+02,5.096876579875528890e-01,1.100000010988609489e+01,3.773966316338020141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007403906598901244e+02,7.188925707938452661e+02,5.096914319537796390e-01,1.100000010988609489e+01,3.772506462322642966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007412997507901338e+02,7.189025707931336910e+02,5.096952044601524845e-01,1.100000010988609489e+01,3.771046608307265791e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007422088416901431e+02,7.189125707924226845e+02,5.096989755066714256e-01,1.100000010988609489e+01,3.769586754291888615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007431179325901525e+02,7.189225707917122463e+02,5.097027450933364623e-01,1.100000010988609489e+01,3.768126900276511440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007440270234901618e+02,7.189325707910022629e+02,5.097065132201475945e-01,1.100000010988609489e+01,3.766667046261134265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007449361143901712e+02,7.189425707902928480e+02,5.097102798871048224e-01,1.100000010988609489e+01,3.765207192245757090e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007458452052901805e+02,7.189525707895840014e+02,5.097140450942081458e-01,1.100000010988609489e+01,3.763747338230379914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007467542961901898e+02,7.189625707888757233e+02,5.097178088414575647e-01,1.100000010988609489e+01,3.762287484215002739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007476633870901992e+02,7.189725707881680137e+02,5.097215711288529683e-01,1.100000010988609489e+01,3.760827630199625564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007485724779902085e+02,7.189825707874608725e+02,5.097253319563944673e-01,1.100000010988609489e+01,3.759367776184248389e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007494815688902179e+02,7.189925707867541860e+02,5.097290913240820620e-01,1.100000010988609489e+01,3.757907922168871213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007503906597902272e+02,7.190025707860480679e+02,5.097328492319157522e-01,1.100000010988609489e+01,3.756448068153494038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007512997506902366e+02,7.190125707853425183e+02,5.097366056798955380e-01,1.100000010988609489e+01,3.754988214138116863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007522088415902459e+02,7.190225707846375371e+02,5.097403606680214194e-01,1.100000010988609489e+01,3.753528360122739688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007531179324902553e+02,7.190325707839331244e+02,5.097441141962933964e-01,1.100000010988609489e+01,3.752068506107362512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007540270233902646e+02,7.190425707832292801e+02,5.097478662647114689e-01,1.100000010988609489e+01,3.750608652091985337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007549361142902740e+02,7.190525707825258905e+02,5.097516168732756370e-01,1.100000010988609489e+01,3.749148798076608162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007558452051902833e+02,7.190625707818230694e+02,5.097553660219859006e-01,1.100000010988609489e+01,3.747688944061230987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007567542960902927e+02,7.190725707811208167e+02,5.097591137108422599e-01,1.100000010988609489e+01,3.746229090045853811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007576633869903020e+02,7.190825707804191325e+02,5.097628599398447147e-01,1.100000010988609489e+01,3.744769236030476636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007585724778903113e+02,7.190925707797180166e+02,5.097666047089932650e-01,1.100000010988609489e+01,3.743309382015099461e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007594815687903207e+02,7.191025707790173556e+02,5.097703480182879110e-01,1.100000010988609489e+01,3.741849527999722286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007603906596903300e+02,7.191125707783172629e+02,5.097740898677285415e-01,1.100000010988609489e+01,3.740389673984345111e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007612997505903394e+02,7.191225707776177387e+02,5.097778302573152676e-01,1.100000010988609489e+01,3.738929819968967935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007622088414903487e+02,7.191325707769187829e+02,5.097815691870480892e-01,1.100000010988609489e+01,3.737469965953590760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007631179323903581e+02,7.191425707762203956e+02,5.097853066569270064e-01,1.100000010988609489e+01,3.736010111938213585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007640270232903674e+02,7.191525707755224630e+02,5.097890426669520192e-01,1.100000010988609489e+01,3.734550257922836410e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007649361141903768e+02,7.191625707748250989e+02,5.097927772171231275e-01,1.100000010988609489e+01,3.733090403907459234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007658452050903861e+02,7.191725707741283031e+02,5.097965103074403315e-01,1.100000010988609489e+01,3.731630549892082059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007667542959903955e+02,7.191825707734320758e+02,5.098002419379036310e-01,1.100000010988609489e+01,3.730170695876704884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007676633868904048e+02,7.191925707727364170e+02,5.098039721085130260e-01,1.100000010988609489e+01,3.728710841861327709e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007685724777904142e+02,7.192025707720412129e+02,5.098077008192685167e-01,1.100000010988609489e+01,3.727250987845950533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007694815686904235e+02,7.192125707713465772e+02,5.098114280701701029e-01,1.100000010988609489e+01,3.725791133830573358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007703906595904328e+02,7.192225707706525100e+02,5.098151538612177847e-01,1.100000010988609489e+01,3.724331279815196183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007712997504904422e+02,7.192325707699590112e+02,5.098188781924114510e-01,1.100000010988609489e+01,3.722871425799819008e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007722088413904515e+02,7.192425707692659671e+02,5.098226010637512129e-01,1.100000010988609489e+01,3.721411571784441832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007731179322904609e+02,7.192525707685734915e+02,5.098263224752370704e-01,1.100000010988609489e+01,3.719951717769064657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007740270231904702e+02,7.192625707678815843e+02,5.098300424268690234e-01,1.100000010988609489e+01,3.718491863753687482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007749361140904796e+02,7.192725707671902455e+02,5.098337609186470720e-01,1.100000010988609489e+01,3.717032009738310307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007758452049904889e+02,7.192825707664994752e+02,5.098374779505712162e-01,1.100000010988609489e+01,3.715572155722933131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007767542958904983e+02,7.192925707658091596e+02,5.098411935226414560e-01,1.100000010988609489e+01,3.714112301707555956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007776633867905076e+02,7.193025707651194125e+02,5.098449076348577913e-01,1.100000010988609489e+01,3.712652447692178781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007785724776905170e+02,7.193125707644302338e+02,5.098486202872202222e-01,1.100000010988609489e+01,3.711192593676801606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007794815685905263e+02,7.193225707637416235e+02,5.098523314797287487e-01,1.100000010988609489e+01,3.709732739661424430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007803906594905357e+02,7.193325707630534680e+02,5.098560412123833707e-01,1.100000010988609489e+01,3.708272885646047255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007812997503905450e+02,7.193425707623658809e+02,5.098597494851839773e-01,1.100000010988609489e+01,3.706813031630670080e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007822088412905543e+02,7.193525707616788623e+02,5.098634562981306795e-01,1.100000010988609489e+01,3.705353177615292905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007831179321905637e+02,7.193625707609924120e+02,5.098671616512234772e-01,1.100000010988609489e+01,3.703893323599915730e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007840270230905730e+02,7.193725707603064166e+02,5.098708655444623705e-01,1.100000010988609489e+01,3.702433469584538554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007849361139905824e+02,7.193825707596209895e+02,5.098745679778473594e-01,1.100000010988609489e+01,3.700973615569161379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007858452048905917e+02,7.193925707589361309e+02,5.098782689513784439e-01,1.100000010988609489e+01,3.699513761553784204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007867542957906011e+02,7.194025707582518407e+02,5.098819684650556239e-01,1.100000010988609489e+01,3.698053907538407029e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007876633866906104e+02,7.194125707575680053e+02,5.098856665188788995e-01,1.100000010988609489e+01,3.696594053523029853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007885724775906198e+02,7.194225707568847383e+02,5.098893631128482706e-01,1.100000010988609489e+01,3.695134199507652678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007894815684906291e+02,7.194325707562020398e+02,5.098930582469637374e-01,1.100000010988609489e+01,3.693674345492275503e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007903906593906385e+02,7.194425707555199097e+02,5.098967519212251887e-01,1.100000010988609489e+01,3.692214491476898328e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007912997502906478e+02,7.194525707548382343e+02,5.099004441356327355e-01,1.100000010988609489e+01,3.690754637461521152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007922088411906572e+02,7.194625707541571273e+02,5.099041348901863779e-01,1.100000010988609489e+01,3.689294783446143977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007931179320906665e+02,7.194725707534765888e+02,5.099078241848861159e-01,1.100000010988609489e+01,3.687834929430766802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007940270229906758e+02,7.194825707527966188e+02,5.099115120197319495e-01,1.100000010988609489e+01,3.686375075415389627e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007949361138906852e+02,7.194925707521171034e+02,5.099151983947238786e-01,1.100000010988609489e+01,3.684915221400012451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007958452047906945e+02,7.195025707514381565e+02,5.099188833098619034e-01,1.100000010988609489e+01,3.683455367384635276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007967542956907039e+02,7.195125707507597781e+02,5.099225667651460236e-01,1.100000010988609489e+01,3.681995513369258101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007976633865907132e+02,7.195225707500819681e+02,5.099262487605762395e-01,1.100000010988609489e+01,3.680535659353880926e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007985724774907226e+02,7.195325707494046128e+02,5.099299292961525509e-01,1.100000010988609489e+01,3.679075805338503750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.007994815683907319e+02,7.195425707487278260e+02,5.099336083718748469e-01,1.100000010988609489e+01,3.677615951323126575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008003906592907413e+02,7.195525707480516076e+02,5.099372859877432385e-01,1.100000010988609489e+01,3.676156097307749400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008012997501907506e+02,7.195625707473759576e+02,5.099409621437577256e-01,1.100000010988609489e+01,3.674696243292372225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008022088410907600e+02,7.195725707467007624e+02,5.099446368399183083e-01,1.100000010988609489e+01,3.673236389276995049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008031179319907693e+02,7.195825707460261356e+02,5.099483100762249865e-01,1.100000010988609489e+01,3.671776535261617874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008040270228907787e+02,7.195925707453520772e+02,5.099519818526777604e-01,1.100000010988609489e+01,3.670316681246240699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008049361137907880e+02,7.196025707446784736e+02,5.099556521692766298e-01,1.100000010988609489e+01,3.668856827230863524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008058452046907973e+02,7.196125707440054384e+02,5.099593210260215947e-01,1.100000010988609489e+01,3.667396973215486349e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008067542955908067e+02,7.196225707433329717e+02,5.099629884229126553e-01,1.100000010988609489e+01,3.665937119200109173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008076633864908160e+02,7.196325707426610734e+02,5.099666543599497004e-01,1.100000010988609489e+01,3.664477265184731998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008085724773908254e+02,7.196425707419896298e+02,5.099703188371328411e-01,1.100000010988609489e+01,3.663017411169354823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008094815682908347e+02,7.196525707413187547e+02,5.099739818544620773e-01,1.100000010988609489e+01,3.661557557153977648e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008103906591908441e+02,7.196625707406484480e+02,5.099776434119374091e-01,1.100000010988609489e+01,3.660097703138600472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008112997500908534e+02,7.196725707399785961e+02,5.099813035095588365e-01,1.100000010988609489e+01,3.658637849123223297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008122088409908628e+02,7.196825707393093126e+02,5.099849621473263594e-01,1.100000010988609489e+01,3.657177995107846122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008131179318908721e+02,7.196925707386405975e+02,5.099886193252399780e-01,1.100000010988609489e+01,3.655718141092468947e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008140270227908815e+02,7.197025707379723372e+02,5.099922750432996921e-01,1.100000010988609489e+01,3.654258287077091771e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008149361136908908e+02,7.197125707373046453e+02,5.099959293015053907e-01,1.100000010988609489e+01,3.652798433061714596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008158452045909002e+02,7.197225707366375218e+02,5.099995820998571849e-01,1.100000010988609489e+01,3.651338579046337421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008167542954909095e+02,7.197325707359708531e+02,5.100032334383550747e-01,1.100000010988609489e+01,3.649878725030960246e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008176633863909188e+02,7.197425707353047528e+02,5.100068833169990601e-01,1.100000010988609489e+01,3.648418871015583070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008185724772909282e+02,7.197525707346392210e+02,5.100105317357891410e-01,1.100000010988609489e+01,3.646959017000205895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008194815681909375e+02,7.197625707339742576e+02,5.100141786947253175e-01,1.100000010988609489e+01,3.645499162984828720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008203906590909469e+02,7.197725707333097489e+02,5.100178241938075896e-01,1.100000010988609489e+01,3.644039308969451545e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008212997499909562e+02,7.197825707326458087e+02,5.100214682330359572e-01,1.100000010988609489e+01,3.642579454954074369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008222088408909656e+02,7.197925707319824369e+02,5.100251108124103094e-01,1.100000010988609489e+01,3.641119600938697194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008231179317909749e+02,7.198025707313195198e+02,5.100287519319307572e-01,1.100000010988609489e+01,3.639659746923320019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008240270226909843e+02,7.198125707306571712e+02,5.100323915915973005e-01,1.100000010988609489e+01,3.638199892907942844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008249361135909936e+02,7.198225707299953910e+02,5.100360297914099394e-01,1.100000010988609489e+01,3.636740038892565668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008258452044910030e+02,7.198325707293340656e+02,5.100396665313686739e-01,1.100000010988609489e+01,3.635280184877188493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008267542953910123e+02,7.198425707286733086e+02,5.100433018114735040e-01,1.100000010988609489e+01,3.633820330861811318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008276633862910217e+02,7.198525707280131201e+02,5.100469356317244296e-01,1.100000010988609489e+01,3.632360476846434143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008285724771910310e+02,7.198625707273533862e+02,5.100505679921214508e-01,1.100000010988609489e+01,3.630900622831056967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008294815680910403e+02,7.198725707266942209e+02,5.100541988926644565e-01,1.100000010988609489e+01,3.629440768815679792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008303906589910497e+02,7.198825707260356239e+02,5.100578283333535579e-01,1.100000010988609489e+01,3.627980914800302617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008312997498910590e+02,7.198925707253774817e+02,5.100614563141887547e-01,1.100000010988609489e+01,3.626521060784925442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008322088407910684e+02,7.199025707247199080e+02,5.100650828351700472e-01,1.100000010988609489e+01,3.625061206769548267e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008331179316910777e+02,7.199125707240629026e+02,5.100687078962974352e-01,1.100000010988609489e+01,3.623601352754171091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008340270225910871e+02,7.199225707234063520e+02,5.100723314975709188e-01,1.100000010988609489e+01,3.622141498738793916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008349361134910964e+02,7.199325707227503699e+02,5.100759536389904980e-01,1.100000010988609489e+01,3.620681644723416741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008358452043911058e+02,7.199425707220949562e+02,5.100795743205560617e-01,1.100000010988609489e+01,3.619221790708039566e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008367542952911151e+02,7.199525707214399972e+02,5.100831935422677210e-01,1.100000010988609489e+01,3.617761936692662390e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008376633861911245e+02,7.199625707207856067e+02,5.100868113041254759e-01,1.100000010988609489e+01,3.616302082677285215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008385724770911338e+02,7.199725707201316709e+02,5.100904276061293263e-01,1.100000010988609489e+01,3.614842228661908040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008394815679911432e+02,7.199825707194783035e+02,5.100940424482792723e-01,1.100000010988609489e+01,3.613382374646530865e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008403906588911525e+02,7.199925707188255046e+02,5.100976558305753139e-01,1.100000010988609489e+01,3.611922520631153689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008412997497911618e+02,7.200025707181731605e+02,5.101012677530174511e-01,1.100000010988609489e+01,3.610462666615776514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008422088406911712e+02,7.200125707175213847e+02,5.101048782156055728e-01,1.100000010988609489e+01,3.609002812600399339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008431179315911805e+02,7.200225707168701774e+02,5.101084872183397900e-01,1.100000010988609489e+01,3.607542958585022164e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008440270224911899e+02,7.200325707162194249e+02,5.101120947612201029e-01,1.100000010988609489e+01,3.606083104569644988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008449361133911992e+02,7.200425707155692407e+02,5.101157008442465113e-01,1.100000010988609489e+01,3.604623250554267813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008458452042912086e+02,7.200525707149196251e+02,5.101193054674190153e-01,1.100000010988609489e+01,3.603163396538890638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008467542951912179e+02,7.200625707142704641e+02,5.101229086307376148e-01,1.100000010988609489e+01,3.601703542523513463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008476633860912273e+02,7.200725707136218716e+02,5.101265103342023099e-01,1.100000010988609489e+01,3.600243688508136287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008485724769912366e+02,7.200825707129737339e+02,5.101301105778129896e-01,1.100000010988609489e+01,3.598783834492759112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008494815678912460e+02,7.200925707123261645e+02,5.101337093615697649e-01,1.100000010988609489e+01,3.597323980477381937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008503906587912553e+02,7.201025707116791637e+02,5.101373066854726357e-01,1.100000010988609489e+01,3.595864126462004762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008512997496912647e+02,7.201125707110326175e+02,5.101409025495216021e-01,1.100000010988609489e+01,3.594404272446627586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008522088405912740e+02,7.201225707103866398e+02,5.101444969537166640e-01,1.100000010988609489e+01,3.592944418431250411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008531179314912833e+02,7.201325707097412305e+02,5.101480898980578216e-01,1.100000010988609489e+01,3.591484564415873236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008540270223912927e+02,7.201425707090962760e+02,5.101516813825450747e-01,1.100000010988609489e+01,3.590024710400496061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008549361132913020e+02,7.201525707084518899e+02,5.101552714071783123e-01,1.100000010988609489e+01,3.588564856385118886e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008558452041913114e+02,7.201625707078079586e+02,5.101588599719576456e-01,1.100000010988609489e+01,3.587105002369741710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008567542950913207e+02,7.201725707071645957e+02,5.101624470768830744e-01,1.100000010988609489e+01,3.585645148354364535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008576633859913301e+02,7.201825707065218012e+02,5.101660327219545987e-01,1.100000010988609489e+01,3.584185294338987360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008585724768913394e+02,7.201925707058794615e+02,5.101696169071722187e-01,1.100000010988609489e+01,3.582725440323610185e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008594815677913488e+02,7.202025707052376902e+02,5.101731996325359342e-01,1.100000010988609489e+01,3.581265586308233009e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008603906586913581e+02,7.202125707045963736e+02,5.101767808980457453e-01,1.100000010988609489e+01,3.579805732292855834e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008612997495913675e+02,7.202225707039556255e+02,5.101803607037015409e-01,1.100000010988609489e+01,3.578345878277478659e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008622088404913768e+02,7.202325707033154458e+02,5.101839390495034321e-01,1.100000010988609489e+01,3.576886024262101484e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008631179313913862e+02,7.202425707026757209e+02,5.101875159354514189e-01,1.100000010988609489e+01,3.575426170246724308e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008640270222913955e+02,7.202525707020365644e+02,5.101910913615455012e-01,1.100000010988609489e+01,3.573966316231347133e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008649361131914048e+02,7.202625707013978626e+02,5.101946653277856791e-01,1.100000010988609489e+01,3.572506462215969958e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008658452040914142e+02,7.202725707007597293e+02,5.101982378341719526e-01,1.100000010988609489e+01,3.571046608200592783e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008667542949914235e+02,7.202825707001221645e+02,5.102018088807042107e-01,1.100000010988609489e+01,3.569586754185215607e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008676633858914329e+02,7.202925706994850543e+02,5.102053784673825643e-01,1.100000010988609489e+01,3.568126900169838432e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008685724767914422e+02,7.203025706988485126e+02,5.102089465942070134e-01,1.100000010988609489e+01,3.566667046154461257e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008694815676914516e+02,7.203125706982124257e+02,5.102125132611775582e-01,1.100000010988609489e+01,3.565207192139084082e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008703906585914609e+02,7.203225706975769072e+02,5.102160784682941985e-01,1.100000010988609489e+01,3.563747338123706906e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008712997494914703e+02,7.203325706969418434e+02,5.102196422155569344e-01,1.100000010988609489e+01,3.562287484108329731e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008722088403914796e+02,7.203425706963073480e+02,5.102232045029656549e-01,1.100000010988609489e+01,3.560827630092952556e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008731179312914890e+02,7.203525706956734211e+02,5.102267653305204709e-01,1.100000010988609489e+01,3.559367776077575381e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008740270221914983e+02,7.203625706950399490e+02,5.102303246982213825e-01,1.100000010988609489e+01,3.557907922062198205e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008749361130915077e+02,7.203725706944070453e+02,5.102338826060683896e-01,1.100000010988609489e+01,3.556448068046821030e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008758452039915170e+02,7.203825706937745963e+02,5.102374390540614923e-01,1.100000010988609489e+01,3.554988214031443855e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008767542948915263e+02,7.203925706931427158e+02,5.102409940422006907e-01,1.100000010988609489e+01,3.553528360016066680e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008776633857915357e+02,7.204025706925112900e+02,5.102445475704858735e-01,1.100000010988609489e+01,3.552068506000689505e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008785724766915450e+02,7.204125706918804326e+02,5.102480996389171519e-01,1.100000010988609489e+01,3.550608651985312329e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008794815675915544e+02,7.204225706912501437e+02,5.102516502474945259e-01,1.100000010988609489e+01,3.549148797969935154e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008803906584915637e+02,7.204325706906203095e+02,5.102551993962179955e-01,1.100000010988609489e+01,3.547688943954557979e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008812997493915731e+02,7.204425706899910438e+02,5.102587470850875606e-01,1.100000010988609489e+01,3.546229089939180804e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008822088402915824e+02,7.204525706893622328e+02,5.102622933141032213e-01,1.100000010988609489e+01,3.544769235923803628e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008831179311915918e+02,7.204625706887339902e+02,5.102658380832648666e-01,1.100000010988609489e+01,3.543309381908426453e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008840270220916011e+02,7.204725706881062024e+02,5.102693813925726074e-01,1.100000010988609489e+01,3.541849527893049278e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008849361129916105e+02,7.204825706874789830e+02,5.102729232420264438e-01,1.100000010988609489e+01,3.540389673877672103e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008858452038916198e+02,7.204925706868522184e+02,5.102764636316263758e-01,1.100000010988609489e+01,3.538929819862294927e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008867542947916291e+02,7.205025706862260222e+02,5.102800025613724033e-01,1.100000010988609489e+01,3.537469965846917752e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008876633856916385e+02,7.205125706856002807e+02,5.102835400312645264e-01,1.100000010988609489e+01,3.536010111831540577e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008885724765916478e+02,7.205225706849751077e+02,5.102870760413026341e-01,1.100000010988609489e+01,3.534550257816163402e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008894815674916572e+02,7.205325706843505031e+02,5.102906105914868373e-01,1.100000010988609489e+01,3.533090403800786226e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008903906583916665e+02,7.205425706837263533e+02,5.102941436818171361e-01,1.100000010988609489e+01,3.531630549785409051e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008912997492916759e+02,7.205525706831027719e+02,5.102976753122935305e-01,1.100000010988609489e+01,3.530170695770031876e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008922088401916852e+02,7.205625706824796453e+02,5.103012054829160205e-01,1.100000010988609489e+01,3.528710841754654701e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008931179310916946e+02,7.205725706818570870e+02,5.103047341936844949e-01,1.100000010988609489e+01,3.527250987739277525e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008940270219917039e+02,7.205825706812349836e+02,5.103082614445990650e-01,1.100000010988609489e+01,3.525791133723900350e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008949361128917133e+02,7.205925706806134485e+02,5.103117872356597307e-01,1.100000010988609489e+01,3.524331279708523175e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008958452037917226e+02,7.206025706799923682e+02,5.103153115668664919e-01,1.100000010988609489e+01,3.522871425693146000e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008967542946917320e+02,7.206125706793718564e+02,5.103188344382193486e-01,1.100000010988609489e+01,3.521411571677768824e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008976633855917413e+02,7.206225706787517993e+02,5.103223558497183010e-01,1.100000010988609489e+01,3.519951717662391649e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008985724764917506e+02,7.206325706781323106e+02,5.103258758013632379e-01,1.100000010988609489e+01,3.518491863647014474e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.008994815673917600e+02,7.206425706775132767e+02,5.103293942931542704e-01,1.100000010988609489e+01,3.517032009631637299e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009003906582917693e+02,7.206525706768948112e+02,5.103329113250913984e-01,1.100000010988609489e+01,3.515572155616260124e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009012997491917787e+02,7.206625706762768004e+02,5.103364268971746220e-01,1.100000010988609489e+01,3.514112301600882948e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009022088400917880e+02,7.206725706756593581e+02,5.103399410094039412e-01,1.100000010988609489e+01,3.512652447585505773e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009031179309917974e+02,7.206825706750423706e+02,5.103434536617792450e-01,1.100000010988609489e+01,3.511192593570128598e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009040270218918067e+02,7.206925706744259514e+02,5.103469648543006443e-01,1.100000010988609489e+01,3.509732739554751423e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009049361127918161e+02,7.207025706738099871e+02,5.103504745869681392e-01,1.100000010988609489e+01,3.508272885539374247e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009058452036918254e+02,7.207125706731945911e+02,5.103539828597817296e-01,1.100000010988609489e+01,3.506813031523997072e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009067542945918348e+02,7.207225706725796499e+02,5.103574896727414156e-01,1.100000010988609489e+01,3.505353177508619897e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009076633854918441e+02,7.207325706719652771e+02,5.103609950258470862e-01,1.100000010988609489e+01,3.503893323493242722e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009085724763918535e+02,7.207425706713513591e+02,5.103644989190988523e-01,1.100000010988609489e+01,3.502433469477865546e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009094815672918628e+02,7.207525706707380095e+02,5.103680013524967141e-01,1.100000010988609489e+01,3.500973615462488371e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009103906581918721e+02,7.207625706701251147e+02,5.103715023260406713e-01,1.100000010988609489e+01,3.499513761447111196e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009112997490918815e+02,7.207725706695127883e+02,5.103750018397307242e-01,1.100000010988609489e+01,3.498053907431734021e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009122088399918908e+02,7.207825706689009166e+02,5.103784998935667616e-01,1.100000010988609489e+01,3.496594053416356845e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009131179308919002e+02,7.207925706682896134e+02,5.103819964875488946e-01,1.100000010988609489e+01,3.495134199400979670e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009140270217919095e+02,7.208025706676787649e+02,5.103854916216771231e-01,1.100000010988609489e+01,3.493674345385602495e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009149361126919189e+02,7.208125706670684849e+02,5.103889852959514473e-01,1.100000010988609489e+01,3.492214491370225320e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009158452035919282e+02,7.208225706664586596e+02,5.103924775103718670e-01,1.100000010988609489e+01,3.490754637354848144e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009167542944919376e+02,7.208325706658494028e+02,5.103959682649383822e-01,1.100000010988609489e+01,3.489294783339470969e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009176633853919469e+02,7.208425706652406006e+02,5.103994575596508820e-01,1.100000010988609489e+01,3.487834929324093794e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009185724762919563e+02,7.208525706646323670e+02,5.104029453945094774e-01,1.100000010988609489e+01,3.486375075308716619e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009194815671919656e+02,7.208625706640245880e+02,5.104064317695141684e-01,1.100000010988609489e+01,3.484915221293339443e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009203906580919750e+02,7.208725706634173775e+02,5.104099166846649549e-01,1.100000010988609489e+01,3.483455367277962268e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009212997489919843e+02,7.208825706628106218e+02,5.104134001399618370e-01,1.100000010988609489e+01,3.481995513262585093e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009222088398919936e+02,7.208925706622044345e+02,5.104168821354047036e-01,1.100000010988609489e+01,3.480535659247207918e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009231179307920030e+02,7.209025706615987019e+02,5.104203626709936659e-01,1.100000010988609489e+01,3.479075805231830743e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009240270216920123e+02,7.209125706609935378e+02,5.104238417467287237e-01,1.100000010988609489e+01,3.477615951216453567e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009249361125920217e+02,7.209225706603888284e+02,5.104273193626098770e-01,1.100000010988609489e+01,3.476156097201076392e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009258452034920310e+02,7.209325706597846875e+02,5.104307955186370149e-01,1.100000010988609489e+01,3.474696243185699217e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009267542943920404e+02,7.209425706591810012e+02,5.104342702148102484e-01,1.100000010988609489e+01,3.473236389170322042e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009276633852920497e+02,7.209525706585778835e+02,5.104377434511295775e-01,1.100000010988609489e+01,3.471776535154944866e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009285724761920591e+02,7.209625706579752205e+02,5.104412152275950021e-01,1.100000010988609489e+01,3.470316681139567691e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009294815670920684e+02,7.209725706573730122e+02,5.104446855442065223e-01,1.100000010988609489e+01,3.468856827124190516e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009303906579920778e+02,7.209825706567713723e+02,5.104481544009640270e-01,1.100000010988609489e+01,3.467396973108813341e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009312997488920871e+02,7.209925706561701872e+02,5.104516217978676274e-01,1.100000010988609489e+01,3.465937119093436165e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009322088397920965e+02,7.210025706555695706e+02,5.104550877349173232e-01,1.100000010988609489e+01,3.464477265078058990e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009331179306921058e+02,7.210125706549694087e+02,5.104585522121131147e-01,1.100000010988609489e+01,3.463017411062681815e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009340270215921151e+02,7.210225706543698152e+02,5.104620152294550017e-01,1.100000010988609489e+01,3.461557557047304640e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009349361124921245e+02,7.210325706537706765e+02,5.104654767869428733e-01,1.100000010988609489e+01,3.460097703031927464e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009358452033921338e+02,7.210425706531721062e+02,5.104689368845768405e-01,1.100000010988609489e+01,3.458637849016550289e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009367542942921432e+02,7.210525706525739906e+02,5.104723955223569032e-01,1.100000010988609489e+01,3.457177995001173114e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009376633851921525e+02,7.210625706519763298e+02,5.104758527002830615e-01,1.100000010988609489e+01,3.455718140985795939e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009385724760921619e+02,7.210725706513792375e+02,5.104793084183553153e-01,1.100000010988609489e+01,3.454258286970418763e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009394815669921712e+02,7.210825706507825998e+02,5.104827626765735538e-01,1.100000010988609489e+01,3.452798432955041588e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009403906578921806e+02,7.210925706501865307e+02,5.104862154749378877e-01,1.100000010988609489e+01,3.451338578939664413e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009412997487921899e+02,7.211025706495909162e+02,5.104896668134483173e-01,1.100000010988609489e+01,3.449878724924287238e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009422088396921993e+02,7.211125706489958702e+02,5.104931166921048424e-01,1.100000010988609489e+01,3.448418870908910062e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009431179305922086e+02,7.211225706484012790e+02,5.104965651109073521e-01,1.100000010988609489e+01,3.446959016893532887e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009440270214922180e+02,7.211325706478072561e+02,5.105000120698559574e-01,1.100000010988609489e+01,3.445499162878155712e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009449361123922273e+02,7.211425706472136881e+02,5.105034575689506582e-01,1.100000010988609489e+01,3.444039308862778537e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009458452032922366e+02,7.211525706466205747e+02,5.105069016081914546e-01,1.100000010988609489e+01,3.442579454847401361e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009467542941922460e+02,7.211625706460280298e+02,5.105103441875783465e-01,1.100000010988609489e+01,3.441119600832024186e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009476633850922553e+02,7.211725706454359397e+02,5.105137853071112231e-01,1.100000010988609489e+01,3.439659746816647011e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009485724759922647e+02,7.211825706448444180e+02,5.105172249667901951e-01,1.100000010988609489e+01,3.438199892801269836e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009494815668922740e+02,7.211925706442533510e+02,5.105206631666152628e-01,1.100000010988609489e+01,3.436740038785892661e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009503906577922834e+02,7.212025706436627388e+02,5.105240999065864260e-01,1.100000010988609489e+01,3.435280184770515485e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009512997486922927e+02,7.212125706430726950e+02,5.105275351867036848e-01,1.100000010988609489e+01,3.433820330755138310e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009522088395923021e+02,7.212225706424831060e+02,5.105309690069669282e-01,1.100000010988609489e+01,3.432360476739761135e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009531179304923114e+02,7.212325706418940854e+02,5.105344013673762671e-01,1.100000010988609489e+01,3.430900622724383960e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009540270213923208e+02,7.212425706413055195e+02,5.105378322679317016e-01,1.100000010988609489e+01,3.429440768709006784e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009549361122923301e+02,7.212525706407175221e+02,5.105412617086332316e-01,1.100000010988609489e+01,3.427980914693629609e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009558452031923395e+02,7.212625706401299794e+02,5.105446896894807463e-01,1.100000010988609489e+01,3.426521060678252434e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009567542940923488e+02,7.212725706395428915e+02,5.105481162104743564e-01,1.100000010988609489e+01,3.425061206662875259e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009576633849923581e+02,7.212825706389563720e+02,5.105515412716140622e-01,1.100000010988609489e+01,3.423601352647498083e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009585724758923675e+02,7.212925706383703073e+02,5.105549648728998635e-01,1.100000010988609489e+01,3.422141498632120908e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009594815667923768e+02,7.213025706377848110e+02,5.105583870143316494e-01,1.100000010988609489e+01,3.420681644616743733e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009603906576923862e+02,7.213125706371997694e+02,5.105618076959095308e-01,1.100000010988609489e+01,3.419221790601366558e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009612997485923955e+02,7.213225706366151826e+02,5.105652269176335079e-01,1.100000010988609489e+01,3.417761936585989382e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009622088394924049e+02,7.213325706360311642e+02,5.105686446795035804e-01,1.100000010988609489e+01,3.416302082570612207e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009631179303924142e+02,7.213425706354476006e+02,5.105720609815197486e-01,1.100000010988609489e+01,3.414842228555235032e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009640270212924236e+02,7.213525706348644917e+02,5.105754758236819013e-01,1.100000010988609489e+01,3.413382374539857857e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009649361121924329e+02,7.213625706342819512e+02,5.105788892059901496e-01,1.100000010988609489e+01,3.411922520524480681e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009658452030924423e+02,7.213725706336998655e+02,5.105823011284444934e-01,1.100000010988609489e+01,3.410462666509103506e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009667542939924516e+02,7.213825706331183483e+02,5.105857115910449329e-01,1.100000010988609489e+01,3.409002812493726331e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009676633848924610e+02,7.213925706325372857e+02,5.105891205937913568e-01,1.100000010988609489e+01,3.407542958478349156e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009685724757924703e+02,7.214025706319566780e+02,5.105925281366838764e-01,1.100000010988609489e+01,3.406083104462971980e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009694815666924796e+02,7.214125706313766386e+02,5.105959342197224915e-01,1.100000010988609489e+01,3.404623250447594805e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009703906575924890e+02,7.214225706307970540e+02,5.105993388429072022e-01,1.100000010988609489e+01,3.403163396432217630e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009712997484924983e+02,7.214325706302179242e+02,5.106027420062378974e-01,1.100000010988609489e+01,3.401703542416840455e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009722088393925077e+02,7.214425706296393628e+02,5.106061437097146882e-01,1.100000010988609489e+01,3.400243688401463280e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009731179302925170e+02,7.214525706290612561e+02,5.106095439533375746e-01,1.100000010988609489e+01,3.398783834386086104e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009740270211925264e+02,7.214625706284837179e+02,5.106129427371065566e-01,1.100000010988609489e+01,3.397323980370708929e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009749361120925357e+02,7.214725706279066344e+02,5.106163400610215231e-01,1.100000010988609489e+01,3.395864126355331754e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009758452029925451e+02,7.214825706273300057e+02,5.106197359250825851e-01,1.100000010988609489e+01,3.394404272339954579e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009767542938925544e+02,7.214925706267539454e+02,5.106231303292897428e-01,1.100000010988609489e+01,3.392944418324577403e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009776633847925638e+02,7.215025706261783398e+02,5.106265232736429960e-01,1.100000010988609489e+01,3.391484564309200228e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009785724756925731e+02,7.215125706256031890e+02,5.106299147581423448e-01,1.100000010988609489e+01,3.390024710293823053e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009794815665925825e+02,7.215225706250286066e+02,5.106333047827876781e-01,1.100000010988609489e+01,3.388564856278445878e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009803906574925918e+02,7.215325706244544790e+02,5.106366933475791070e-01,1.100000010988609489e+01,3.387105002263068702e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009812997483926011e+02,7.215425706238808061e+02,5.106400804525166315e-01,1.100000010988609489e+01,3.385645148247691527e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009822088392926105e+02,7.215525706233077017e+02,5.106434660976002515e-01,1.100000010988609489e+01,3.384185294232314352e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009831179301926198e+02,7.215625706227350520e+02,5.106468502828298561e-01,1.100000010988609489e+01,3.382725440216937177e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009840270210926292e+02,7.215725706221628570e+02,5.106502330082055563e-01,1.100000010988609489e+01,3.381265586201560001e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009849361119926385e+02,7.215825706215912305e+02,5.106536142737273520e-01,1.100000010988609489e+01,3.379805732186182826e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009858452028926479e+02,7.215925706210200588e+02,5.106569940793952433e-01,1.100000010988609489e+01,3.378345878170805651e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009867542937926572e+02,7.216025706204493417e+02,5.106603724252091192e-01,1.100000010988609489e+01,3.376886024155428476e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009876633846926666e+02,7.216125706198791931e+02,5.106637493111690906e-01,1.100000010988609489e+01,3.375426170140051300e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009885724755926759e+02,7.216225706193094993e+02,5.106671247372751576e-01,1.100000010988609489e+01,3.373966316124674125e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009894815664926853e+02,7.216325706187402602e+02,5.106704987035273202e-01,1.100000010988609489e+01,3.372506462109296950e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009903906573926946e+02,7.216425706181715896e+02,5.106738712099254673e-01,1.100000010988609489e+01,3.371046608093919775e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009912997482927040e+02,7.216525706176033736e+02,5.106772422564697100e-01,1.100000010988609489e+01,3.369586754078542599e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009922088391927133e+02,7.216625706170356125e+02,5.106806118431600483e-01,1.100000010988609489e+01,3.368126900063165424e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009931179300927226e+02,7.216725706164684198e+02,5.106839799699964821e-01,1.100000010988609489e+01,3.366667046047788249e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009940270209927320e+02,7.216825706159016818e+02,5.106873466369789005e-01,1.100000010988609489e+01,3.365207192032411074e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009949361118927413e+02,7.216925706153353985e+02,5.106907118441074145e-01,1.100000010988609489e+01,3.363747338017033899e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009958452027927507e+02,7.217025706147696837e+02,5.106940755913820240e-01,1.100000010988609489e+01,3.362287484001656723e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009967542936927600e+02,7.217125706142044237e+02,5.106974378788027291e-01,1.100000010988609489e+01,3.360827629986279548e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009976633845927694e+02,7.217225706136396184e+02,5.107007987063694188e-01,1.100000010988609489e+01,3.359367775970902373e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009985724754927787e+02,7.217325706130753815e+02,5.107041580740822040e-01,1.100000010988609489e+01,3.357907921955525198e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.009994815663927881e+02,7.217425706125115994e+02,5.107075159819410848e-01,1.100000010988609489e+01,3.356448067940148022e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010003906572927974e+02,7.217525706119482720e+02,5.107108724299459501e-01,1.100000010988609489e+01,3.354988213924770847e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010012997481928068e+02,7.217625706113855131e+02,5.107142274180969110e-01,1.100000010988609489e+01,3.353528359909393672e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010022088390928161e+02,7.217725706108232089e+02,5.107175809463939675e-01,1.100000010988609489e+01,3.352068505894016497e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010031179299928255e+02,7.217825706102613594e+02,5.107209330148371196e-01,1.100000010988609489e+01,3.350608651878639321e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010040270208928348e+02,7.217925706097000784e+02,5.107242836234262562e-01,1.100000010988609489e+01,3.349148797863262146e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010049361117928441e+02,7.218025706091392522e+02,5.107276327721614884e-01,1.100000010988609489e+01,3.347688943847884971e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010058452026928535e+02,7.218125706085788806e+02,5.107309804610428161e-01,1.100000010988609489e+01,3.346229089832507796e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010067542935928628e+02,7.218225706080189639e+02,5.107343266900702394e-01,1.100000010988609489e+01,3.344769235817130620e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010076633844928722e+02,7.218325706074596155e+02,5.107376714592436473e-01,1.100000010988609489e+01,3.343309381801753445e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010085724753928815e+02,7.218425706069007219e+02,5.107410147685631507e-01,1.100000010988609489e+01,3.341849527786376270e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010094815662928909e+02,7.218525706063422831e+02,5.107443566180287498e-01,1.100000010988609489e+01,3.340389673770999095e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010103906571929002e+02,7.218625706057844127e+02,5.107476970076404443e-01,1.100000010988609489e+01,3.338929819755621919e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010112997480929096e+02,7.218725706052269970e+02,5.107510359373981235e-01,1.100000010988609489e+01,3.337469965740244744e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010122088389929189e+02,7.218825706046700361e+02,5.107543734073018982e-01,1.100000010988609489e+01,3.336010111724867569e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010131179298929283e+02,7.218925706041136436e+02,5.107577094173517684e-01,1.100000010988609489e+01,3.334550257709490394e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010140270207929376e+02,7.219025706035577059e+02,5.107610439675477343e-01,1.100000010988609489e+01,3.333090403694113218e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010149361116929470e+02,7.219125706030022229e+02,5.107643770578896847e-01,1.100000010988609489e+01,3.331630549678736043e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010158452025929563e+02,7.219225706024471947e+02,5.107677086883777307e-01,1.100000010988609489e+01,3.330170695663358868e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010167542934929656e+02,7.219325706018927349e+02,5.107710388590118722e-01,1.100000010988609489e+01,3.328710841647981693e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010176633843929750e+02,7.219425706013387298e+02,5.107743675697919983e-01,1.100000010988609489e+01,3.327250987632604518e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010185724752929843e+02,7.219525706007851795e+02,5.107776948207182199e-01,1.100000010988609489e+01,3.325791133617227342e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010194815661929937e+02,7.219625706002320840e+02,5.107810206117905372e-01,1.100000010988609489e+01,3.324331279601850167e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010203906570930030e+02,7.219725705996795568e+02,5.107843449430089500e-01,1.100000010988609489e+01,3.322871425586472992e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010212997479930124e+02,7.219825705991274845e+02,5.107876678143733473e-01,1.100000010988609489e+01,3.321411571571095817e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010222088388930217e+02,7.219925705985758668e+02,5.107909892258838402e-01,1.100000010988609489e+01,3.319951717555718641e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010231179297930311e+02,7.220025705980248176e+02,5.107943091775404287e-01,1.100000010988609489e+01,3.318491863540341466e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010240270206930404e+02,7.220125705974742232e+02,5.107976276693431128e-01,1.100000010988609489e+01,3.317032009524964291e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010249361115930498e+02,7.220225705969240835e+02,5.108009447012917814e-01,1.100000010988609489e+01,3.315572155509587116e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010258452024930591e+02,7.220325705963743985e+02,5.108042602733865456e-01,1.100000010988609489e+01,3.314112301494209940e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010267542933930685e+02,7.220425705958252820e+02,5.108075743856274054e-01,1.100000010988609489e+01,3.312652447478832765e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010276633842930778e+02,7.220525705952766202e+02,5.108108870380142497e-01,1.100000010988609489e+01,3.311192593463455590e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010285724751930871e+02,7.220625705947284132e+02,5.108141982305471895e-01,1.100000010988609489e+01,3.309732739448078415e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010294815660930965e+02,7.220725705941806609e+02,5.108175079632262250e-01,1.100000010988609489e+01,3.308272885432701239e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010303906569931058e+02,7.220825705936334771e+02,5.108208162360513560e-01,1.100000010988609489e+01,3.306813031417324064e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010312997478931152e+02,7.220925705930867480e+02,5.108241230490224716e-01,1.100000010988609489e+01,3.305353177401946889e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010322088387931245e+02,7.221025705925404736e+02,5.108274284021396827e-01,1.100000010988609489e+01,3.303893323386569714e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010331179296931339e+02,7.221125705919946540e+02,5.108307322954029894e-01,1.100000010988609489e+01,3.302433469371192538e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010340270205931432e+02,7.221225705914494029e+02,5.108340347288122807e-01,1.100000010988609489e+01,3.300973615355815363e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010349361114931526e+02,7.221325705909046064e+02,5.108373357023676675e-01,1.100000010988609489e+01,3.299513761340438188e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010358452023931619e+02,7.221425705903602648e+02,5.108406352160691499e-01,1.100000010988609489e+01,3.298053907325061013e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010367542932931713e+02,7.221525705898163778e+02,5.108439332699167279e-01,1.100000010988609489e+01,3.296594053309683837e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010376633841931806e+02,7.221625705892729457e+02,5.108472298639102904e-01,1.100000010988609489e+01,3.295134199294306662e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010385724750931900e+02,7.221725705887300819e+02,5.108505249980499485e-01,1.100000010988609489e+01,3.293674345278929487e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010394815659931993e+02,7.221825705881876729e+02,5.108538186723357022e-01,1.100000010988609489e+01,3.292214491263552312e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010403906568932086e+02,7.221925705876457187e+02,5.108571108867674404e-01,1.100000010988609489e+01,3.290754637248175136e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010412997477932180e+02,7.222025705871042192e+02,5.108604016413452742e-01,1.100000010988609489e+01,3.289294783232797961e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010422088386932273e+02,7.222125705865632881e+02,5.108636909360692036e-01,1.100000010988609489e+01,3.287834929217420786e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010431179295932367e+02,7.222225705860228118e+02,5.108669787709392285e-01,1.100000010988609489e+01,3.286375075202043611e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010440270204932460e+02,7.222325705854827902e+02,5.108702651459552380e-01,1.100000010988609489e+01,3.284915221186666436e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010449361113932554e+02,7.222425705849432234e+02,5.108735500611173430e-01,1.100000010988609489e+01,3.283455367171289260e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010458452022932647e+02,7.222525705844042250e+02,5.108768335164255436e-01,1.100000010988609489e+01,3.281995513155912085e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010467542931932741e+02,7.222625705838656813e+02,5.108801155118797288e-01,1.100000010988609489e+01,3.280535659140534910e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010476633840932834e+02,7.222725705833275924e+02,5.108833960474800095e-01,1.100000010988609489e+01,3.279075805125157735e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010485724749932928e+02,7.222825705827899583e+02,5.108866751232263859e-01,1.100000010988609489e+01,3.277615951109780559e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010494815658933021e+02,7.222925705822527789e+02,5.108899527391188577e-01,1.100000010988609489e+01,3.276156097094403384e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010503906567933115e+02,7.223025705817161679e+02,5.108932288951573142e-01,1.100000010988609489e+01,3.274696243079026209e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010512997476933208e+02,7.223125705811800117e+02,5.108965035913418662e-01,1.100000010988609489e+01,3.273236389063649034e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010522088385933301e+02,7.223225705806443102e+02,5.108997768276725138e-01,1.100000010988609489e+01,3.271776535048271858e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010531179294933395e+02,7.223325705801090635e+02,5.109030486041491459e-01,1.100000010988609489e+01,3.270316681032894683e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010540270203933488e+02,7.223425705795742715e+02,5.109063189207718736e-01,1.100000010988609489e+01,3.268856827017517508e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010549361112933582e+02,7.223525705790400480e+02,5.109095877775406969e-01,1.100000010988609489e+01,3.267396973002140333e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010558452021933675e+02,7.223625705785062792e+02,5.109128551744556157e-01,1.100000010988609489e+01,3.265937118986763157e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010567542930933769e+02,7.223725705779729651e+02,5.109161211115165191e-01,1.100000010988609489e+01,3.264477264971385982e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010576633839933862e+02,7.223825705774401058e+02,5.109193855887235181e-01,1.100000010988609489e+01,3.263017410956008807e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010585724748933956e+02,7.223925705769077013e+02,5.109226486060766126e-01,1.100000010988609489e+01,3.261557556940631632e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010594815657934049e+02,7.224025705763758651e+02,5.109259101635756917e-01,1.100000010988609489e+01,3.260097702925254456e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010603906566934143e+02,7.224125705758444838e+02,5.109291702612208663e-01,1.100000010988609489e+01,3.258637848909877281e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010612997475934236e+02,7.224225705753135571e+02,5.109324288990121365e-01,1.100000010988609489e+01,3.257177994894500106e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010622088384934329e+02,7.224325705747830852e+02,5.109356860769493913e-01,1.100000010988609489e+01,3.255718140879122931e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010631179293934423e+02,7.224425705742530681e+02,5.109389417950327417e-01,1.100000010988609489e+01,3.254258286863745755e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010640270202934516e+02,7.224525705737235057e+02,5.109421960532621876e-01,1.100000010988609489e+01,3.252798432848368580e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010649361111934610e+02,7.224625705731945118e+02,5.109454488516377291e-01,1.100000010988609489e+01,3.251338578832991405e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010658452020934703e+02,7.224725705726659726e+02,5.109487001901592551e-01,1.100000010988609489e+01,3.249878724817614230e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010667542929934797e+02,7.224825705721378881e+02,5.109519500688268767e-01,1.100000010988609489e+01,3.248418870802237055e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010676633838934890e+02,7.224925705716102584e+02,5.109551984876405939e-01,1.100000010988609489e+01,3.246959016786859879e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010685724747934984e+02,7.225025705710830835e+02,5.109584454466002956e-01,1.100000010988609489e+01,3.245499162771482704e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010694815656935077e+02,7.225125705705564769e+02,5.109616909457060929e-01,1.100000010988609489e+01,3.244039308756105529e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010703906565935171e+02,7.225225705700303251e+02,5.109649349849579858e-01,1.100000010988609489e+01,3.242579454740728354e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010712997474935264e+02,7.225325705695046281e+02,5.109681775643558632e-01,1.100000010988609489e+01,3.241119600725351178e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010722088383935358e+02,7.225425705689793858e+02,5.109714186838998362e-01,1.100000010988609489e+01,3.239659746709974003e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010731179292935451e+02,7.225525705684545983e+02,5.109746583435899048e-01,1.100000010988609489e+01,3.238199892694596828e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010740270201935544e+02,7.225625705679302655e+02,5.109778965434259579e-01,1.100000010988609489e+01,3.236740038679219653e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010749361110935638e+02,7.225725705674063875e+02,5.109811332834081066e-01,1.100000010988609489e+01,3.235280184663842477e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010758452019935731e+02,7.225825705668830778e+02,5.109843685635363508e-01,1.100000010988609489e+01,3.233820330648465302e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010767542928935825e+02,7.225925705663602230e+02,5.109876023838106907e-01,1.100000010988609489e+01,3.232360476633088127e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010776633837935918e+02,7.226025705658378229e+02,5.109908347442310150e-01,1.100000010988609489e+01,3.230900622617710952e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010785724746936012e+02,7.226125705653158775e+02,5.109940656447974350e-01,1.100000010988609489e+01,3.229440768602333776e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010794815655936105e+02,7.226225705647943869e+02,5.109972950855099505e-01,1.100000010988609489e+01,3.227980914586956601e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010803906564936199e+02,7.226325705642733510e+02,5.110005230663684506e-01,1.100000010988609489e+01,3.226521060571579426e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010812997473936292e+02,7.226425705637528836e+02,5.110037495873730462e-01,1.100000010988609489e+01,3.225061206556202251e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010822088382936386e+02,7.226525705632328709e+02,5.110069746485237374e-01,1.100000010988609489e+01,3.223601352540825075e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010831179291936479e+02,7.226625705627133129e+02,5.110101982498204132e-01,1.100000010988609489e+01,3.222141498525447900e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010840270200936573e+02,7.226725705621942097e+02,5.110134203912631845e-01,1.100000010988609489e+01,3.220681644510070725e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010849361109936666e+02,7.226825705616755613e+02,5.110166410728520514e-01,1.100000010988609489e+01,3.219221790494693550e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010858452018936759e+02,7.226925705611573676e+02,5.110198602945869029e-01,1.100000010988609489e+01,3.217761936479316374e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010867542927936853e+02,7.227025705606396286e+02,5.110230780564678499e-01,1.100000010988609489e+01,3.216302082463939199e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010876633836936946e+02,7.227125705601223444e+02,5.110262943584948925e-01,1.100000010988609489e+01,3.214842228448562024e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010885724745937040e+02,7.227225705596056287e+02,5.110295092006679196e-01,1.100000010988609489e+01,3.213382374433184849e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010894815654937133e+02,7.227325705590893676e+02,5.110327225829870423e-01,1.100000010988609489e+01,3.211922520417807674e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010903906563937227e+02,7.227425705585735614e+02,5.110359345054522606e-01,1.100000010988609489e+01,3.210462666402430498e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010912997472937320e+02,7.227525705580582098e+02,5.110391449680634635e-01,1.100000010988609489e+01,3.209002812387053323e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010922088381937414e+02,7.227625705575433130e+02,5.110423539708207619e-01,1.100000010988609489e+01,3.207542958371676148e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010931179290937507e+02,7.227725705570288710e+02,5.110455615137241558e-01,1.100000010988609489e+01,3.206083104356298973e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010940270199937601e+02,7.227825705565148837e+02,5.110487675967735344e-01,1.100000010988609489e+01,3.204623250340921797e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010949361108937694e+02,7.227925705560013512e+02,5.110519722199690085e-01,1.100000010988609489e+01,3.203163396325544622e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010958452017937788e+02,7.228025705554883871e+02,5.110551753833105781e-01,1.100000010988609489e+01,3.201703542310167447e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010967542926937881e+02,7.228125705549758777e+02,5.110583770867981324e-01,1.100000010988609489e+01,3.200243688294790272e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010976633835937974e+02,7.228225705544638231e+02,5.110615773304317822e-01,1.100000010988609489e+01,3.198783834279413096e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010985724744938068e+02,7.228325705539522232e+02,5.110647761142115275e-01,1.100000010988609489e+01,3.197323980264035921e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.010994815653938161e+02,7.228425705534410781e+02,5.110679734381373684e-01,1.100000010988609489e+01,3.195864126248658746e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011003906562938255e+02,7.228525705529303877e+02,5.110711693022091939e-01,1.100000010988609489e+01,3.194404272233281571e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011012997471938348e+02,7.228625705524201521e+02,5.110743637064271150e-01,1.100000010988609489e+01,3.192944418217904395e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011022088380938442e+02,7.228725705519103713e+02,5.110775566507911316e-01,1.100000010988609489e+01,3.191484564202527220e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011031179289938535e+02,7.228825705514010451e+02,5.110807481353011328e-01,1.100000010988609489e+01,3.190024710187150045e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011040270198938629e+02,7.228925705508922874e+02,5.110839381599572295e-01,1.100000010988609489e+01,3.188564856171772870e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011049361107938722e+02,7.229025705503839845e+02,5.110871267247594218e-01,1.100000010988609489e+01,3.187105002156395694e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011058452016938816e+02,7.229125705498761363e+02,5.110903138297075987e-01,1.100000010988609489e+01,3.185645148141018519e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011067542925938909e+02,7.229225705493687428e+02,5.110934994748018712e-01,1.100000010988609489e+01,3.184185294125641344e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011076633834939003e+02,7.229325705488618041e+02,5.110966836600422392e-01,1.100000010988609489e+01,3.182725440110264169e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011085724743939096e+02,7.229425705483553202e+02,5.110998663854285917e-01,1.100000010988609489e+01,3.181265586094886993e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011094815652939189e+02,7.229525705478492910e+02,5.111030476509610398e-01,1.100000010988609489e+01,3.179805732079509818e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011103906561939283e+02,7.229625705473437165e+02,5.111062274566395836e-01,1.100000010988609489e+01,3.178345878064132643e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011112997470939376e+02,7.229725705468385968e+02,5.111094058024641118e-01,1.100000010988609489e+01,3.176886024048755468e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011122088379939470e+02,7.229825705463339318e+02,5.111125826884347356e-01,1.100000010988609489e+01,3.175426170033378293e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011131179288939563e+02,7.229925705458297216e+02,5.111157581145514550e-01,1.100000010988609489e+01,3.173966316018001117e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011140270197939657e+02,7.230025705453259661e+02,5.111189320808141590e-01,1.100000010988609489e+01,3.172506462002623942e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011149361106939750e+02,7.230125705448227791e+02,5.111221045872229585e-01,1.100000010988609489e+01,3.171046607987246767e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011158452015939844e+02,7.230225705443200468e+02,5.111252756337778536e-01,1.100000010988609489e+01,3.169586753971869592e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011167542924939937e+02,7.230325705438177692e+02,5.111284452204787332e-01,1.100000010988609489e+01,3.168126899956492416e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011176633833940031e+02,7.230425705433159465e+02,5.111316133473257084e-01,1.100000010988609489e+01,3.166667045941115241e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011185724742940124e+02,7.230525705428145784e+02,5.111347800143187792e-01,1.100000010988609489e+01,3.165207191925738066e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011194815651940218e+02,7.230625705423136651e+02,5.111379452214578345e-01,1.100000010988609489e+01,3.163747337910360891e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011203906560940311e+02,7.230725705418132065e+02,5.111411089687429854e-01,1.100000010988609489e+01,3.162287483894983715e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011212997469940404e+02,7.230825705413132027e+02,5.111442712561741208e-01,1.100000010988609489e+01,3.160827629879606540e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011222088378940498e+02,7.230925705408136537e+02,5.111474320837513519e-01,1.100000010988609489e+01,3.159367775864229365e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011231179287940591e+02,7.231025705403145594e+02,5.111505914514746785e-01,1.100000010988609489e+01,3.157907921848852190e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011240270196940685e+02,7.231125705398159198e+02,5.111537493593439896e-01,1.100000010988609489e+01,3.156448067833475014e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011249361105940778e+02,7.231225705393177350e+02,5.111569058073593963e-01,1.100000010988609489e+01,3.154988213818097839e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011258452014940872e+02,7.231325705388200049e+02,5.111600607955208986e-01,1.100000010988609489e+01,3.153528359802720664e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011267542923940965e+02,7.231425705383227296e+02,5.111632143238283854e-01,1.100000010988609489e+01,3.152068505787343489e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011276633832941059e+02,7.231525705378259090e+02,5.111663663922819678e-01,1.100000010988609489e+01,3.150608651771966313e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011285724741941152e+02,7.231625705373295432e+02,5.111695170008816458e-01,1.100000010988609489e+01,3.149148797756589138e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011294815650941246e+02,7.231725705368336321e+02,5.111726661496273083e-01,1.100000010988609489e+01,3.147688943741211963e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011303906559941339e+02,7.231825705363382895e+02,5.111758138385190664e-01,1.100000010988609489e+01,3.146229089725834788e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011312997468941433e+02,7.231925705358434016e+02,5.111789600675569201e-01,1.100000010988609489e+01,3.144769235710457612e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011322088377941526e+02,7.232025705353489684e+02,5.111821048367407583e-01,1.100000010988609489e+01,3.143309381695080437e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011331179286941619e+02,7.232125705348549900e+02,5.111852481460706921e-01,1.100000010988609489e+01,3.141849527679703262e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011340270195941713e+02,7.232225705343614663e+02,5.111883899955467214e-01,1.100000010988609489e+01,3.140389673664326087e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011349361104941806e+02,7.232325705338683974e+02,5.111915303851687353e-01,1.100000010988609489e+01,3.138929819648948912e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011358452013941900e+02,7.232425705333757833e+02,5.111946693149368448e-01,1.100000010988609489e+01,3.137469965633571736e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011367542922941993e+02,7.232525705328836239e+02,5.111978067848510499e-01,1.100000010988609489e+01,3.136010111618194561e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011376633831942087e+02,7.232625705323919192e+02,5.112009427949112395e-01,1.100000010988609489e+01,3.134550257602817386e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011385724740942180e+02,7.232725705319006693e+02,5.112040773451175246e-01,1.100000010988609489e+01,3.133090403587440211e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011394815649942274e+02,7.232825705314098741e+02,5.112072104354699054e-01,1.100000010988609489e+01,3.131630549572063035e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011403906558942367e+02,7.232925705309195337e+02,5.112103420659682707e-01,1.100000010988609489e+01,3.130170695556685860e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011412997467942461e+02,7.233025705304296480e+02,5.112134722366127315e-01,1.100000010988609489e+01,3.128710841541308685e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011422088376942554e+02,7.233125705299402171e+02,5.112166009474031769e-01,1.100000010988609489e+01,3.127250987525931510e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011431179285942648e+02,7.233225705294512409e+02,5.112197281983397179e-01,1.100000010988609489e+01,3.125791133510554334e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011440270194942741e+02,7.233325705289627194e+02,5.112228539894223545e-01,1.100000010988609489e+01,3.124331279495177159e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011449361103942834e+02,7.233425705284746527e+02,5.112259783206509756e-01,1.100000010988609489e+01,3.122871425479799984e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011458452012942928e+02,7.233525705279870408e+02,5.112291011920256922e-01,1.100000010988609489e+01,3.121411571464422809e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011467542921943021e+02,7.233625705274998836e+02,5.112322226035465045e-01,1.100000010988609489e+01,3.119951717449045633e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011476633830943115e+02,7.233725705270131812e+02,5.112353425552133013e-01,1.100000010988609489e+01,3.118491863433668458e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011485724739943208e+02,7.233825705265269335e+02,5.112384610470261936e-01,1.100000010988609489e+01,3.117032009418291283e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011494815648943302e+02,7.233925705260411405e+02,5.112415780789851816e-01,1.100000010988609489e+01,3.115572155402914108e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011503906557943395e+02,7.234025705255558023e+02,5.112446936510901541e-01,1.100000010988609489e+01,3.114112301387536932e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011512997466943489e+02,7.234125705250709188e+02,5.112478077633412221e-01,1.100000010988609489e+01,3.112652447372159757e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011522088375943582e+02,7.234225705245864901e+02,5.112509204157383857e-01,1.100000010988609489e+01,3.111192593356782582e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011531179284943676e+02,7.234325705241025162e+02,5.112540316082815339e-01,1.100000010988609489e+01,3.109732739341405407e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011540270193943769e+02,7.234425705236189970e+02,5.112571413409707777e-01,1.100000010988609489e+01,3.108272885326028231e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011549361102943863e+02,7.234525705231359325e+02,5.112602496138060060e-01,1.100000010988609489e+01,3.106813031310651056e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011558452011943956e+02,7.234625705226533228e+02,5.112633564267873298e-01,1.100000010988609489e+01,3.105353177295273881e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011567542920944049e+02,7.234725705221711678e+02,5.112664617799147493e-01,1.100000010988609489e+01,3.103893323279896706e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011576633829944143e+02,7.234825705216894676e+02,5.112695656731881533e-01,1.100000010988609489e+01,3.102433469264519530e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011585724738944236e+02,7.234925705212082221e+02,5.112726681066076528e-01,1.100000010988609489e+01,3.100973615249142355e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011594815647944330e+02,7.235025705207274314e+02,5.112757690801732480e-01,1.100000010988609489e+01,3.099513761233765180e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011603906556944423e+02,7.235125705202470954e+02,5.112788685938848277e-01,1.100000010988609489e+01,3.098053907218388005e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011612997465944517e+02,7.235225705197672141e+02,5.112819666477425029e-01,1.100000010988609489e+01,3.096594053203010830e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011622088374944610e+02,7.235325705192877876e+02,5.112850632417461627e-01,1.100000010988609489e+01,3.095134199187633654e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011631179283944704e+02,7.235425705188088159e+02,5.112881583758959181e-01,1.100000010988609489e+01,3.093674345172256479e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011640270192944797e+02,7.235525705183302989e+02,5.112912520501917690e-01,1.100000010988609489e+01,3.092214491156879304e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011649361101944891e+02,7.235625705178522367e+02,5.112943442646336045e-01,1.100000010988609489e+01,3.090754637141502129e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011658452010944984e+02,7.235725705173746292e+02,5.112974350192215356e-01,1.100000010988609489e+01,3.089294783126124953e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011667542919945078e+02,7.235825705168974764e+02,5.113005243139555622e-01,1.100000010988609489e+01,3.087834929110747778e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011676633828945171e+02,7.235925705164207784e+02,5.113036121488355734e-01,1.100000010988609489e+01,3.086375075095370603e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011685724737945264e+02,7.236025705159445351e+02,5.113066985238616802e-01,1.100000010988609489e+01,3.084915221079993428e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011694815646945358e+02,7.236125705154687466e+02,5.113097834390338825e-01,1.100000010988609489e+01,3.083455367064616252e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011703906555945451e+02,7.236225705149934129e+02,5.113128668943520694e-01,1.100000010988609489e+01,3.081995513049239077e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011712997464945545e+02,7.236325705145185339e+02,5.113159488898163518e-01,1.100000010988609489e+01,3.080535659033861902e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011722088373945638e+02,7.236425705140439959e+02,5.113190294254266188e-01,1.100000010988609489e+01,3.079075805018484727e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011731179282945732e+02,7.236525705135699127e+02,5.113221085011829814e-01,1.100000010988609489e+01,3.077615951003107551e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011740270191945825e+02,7.236625705130962842e+02,5.113251861170854395e-01,1.100000010988609489e+01,3.076156096987730376e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011749361100945919e+02,7.236725705126231105e+02,5.113282622731338822e-01,1.100000010988609489e+01,3.074696242972353201e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011758452009946012e+02,7.236825705121503916e+02,5.113313369693284205e-01,1.100000010988609489e+01,3.073236388956976026e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011767542918946106e+02,7.236925705116781273e+02,5.113344102056690543e-01,1.100000010988609489e+01,3.071776534941598850e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011776633827946199e+02,7.237025705112063179e+02,5.113374819821556727e-01,1.100000010988609489e+01,3.070316680926221675e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011785724736946293e+02,7.237125705107349631e+02,5.113405522987883867e-01,1.100000010988609489e+01,3.068856826910844500e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011794815645946386e+02,7.237225705102640632e+02,5.113436211555670852e-01,1.100000010988609489e+01,3.067396972895467325e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011803906554946479e+02,7.237325705097936179e+02,5.113466885524918792e-01,1.100000010988609489e+01,3.065937118880090149e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011812997463946573e+02,7.237425705093236274e+02,5.113497544895627689e-01,1.100000010988609489e+01,3.064477264864712974e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011822088372946666e+02,7.237525705088540917e+02,5.113528189667796431e-01,1.100000010988609489e+01,3.063017410849335799e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011831179281946760e+02,7.237625705083850107e+02,5.113558819841426129e-01,1.100000010988609489e+01,3.061557556833958624e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011840270190946853e+02,7.237725705079163845e+02,5.113589435416515672e-01,1.100000010988609489e+01,3.060097702818581449e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011849361099946947e+02,7.237825705074482130e+02,5.113620036393066171e-01,1.100000010988609489e+01,3.058637848803204273e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011858452008947040e+02,7.237925705069804962e+02,5.113650622771077625e-01,1.100000010988609489e+01,3.057177994787827098e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011867542917947134e+02,7.238025705065132342e+02,5.113681194550548925e-01,1.100000010988609489e+01,3.055718140772449923e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011876633826947227e+02,7.238125705060463133e+02,5.113711751731481181e-01,1.100000010988609489e+01,3.054258286757072748e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011885724735947321e+02,7.238225705055798471e+02,5.113742294313874392e-01,1.100000010988609489e+01,3.052798432741695572e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011894815644947414e+02,7.238325705051138357e+02,5.113772822297727449e-01,1.100000010988609489e+01,3.051338578726318397e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011903906553947508e+02,7.238425705046482790e+02,5.113803335683041462e-01,1.100000010988609489e+01,3.049878724710941222e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011912997462947601e+02,7.238525705041831770e+02,5.113833834469815320e-01,1.100000010988609489e+01,3.048418870695564047e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011922088371947694e+02,7.238625705037185298e+02,5.113864318658050134e-01,1.100000010988609489e+01,3.046959016680186871e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011931179280947788e+02,7.238725705032543374e+02,5.113894788247745904e-01,1.100000010988609489e+01,3.045499162664809696e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011940270189947881e+02,7.238825705027905997e+02,5.113925243238901519e-01,1.100000010988609489e+01,3.044039308649432521e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011949361098947975e+02,7.238925705023273167e+02,5.113955683631518090e-01,1.100000010988609489e+01,3.042579454634055346e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011958452007948068e+02,7.239025705018644885e+02,5.113986109425594506e-01,1.100000010988609489e+01,3.041119600618678170e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011967542916948162e+02,7.239125705014021150e+02,5.114016520621131878e-01,1.100000010988609489e+01,3.039659746603300995e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011976633825948255e+02,7.239225705009400826e+02,5.114046917218130206e-01,1.100000010988609489e+01,3.038199892587923820e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011985724734948349e+02,7.239325705004785050e+02,5.114077299216588379e-01,1.100000010988609489e+01,3.036740038572546645e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.011994815643948442e+02,7.239425705000173821e+02,5.114107666616507508e-01,1.100000010988609489e+01,3.035280184557169469e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012003906552948536e+02,7.239525704995567139e+02,5.114138019417886483e-01,1.100000010988609489e+01,3.033820330541792294e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012012997461948629e+02,7.239625704990965005e+02,5.114168357620726413e-01,1.100000010988609489e+01,3.032360476526415119e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012022088370948723e+02,7.239725704986367418e+02,5.114198681225027299e-01,1.100000010988609489e+01,3.030900622511037944e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012031179279948816e+02,7.239825704981774379e+02,5.114228990230788030e-01,1.100000010988609489e+01,3.029440768495660768e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012040270188948909e+02,7.239925704977185887e+02,5.114259284638009717e-01,1.100000010988609489e+01,3.027980914480283593e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012049361097949003e+02,7.240025704972601943e+02,5.114289564446692360e-01,1.100000010988609489e+01,3.026521060464906418e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012058452006949096e+02,7.240125704968022546e+02,5.114319829656834848e-01,1.100000010988609489e+01,3.025061206449529243e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012067542915949190e+02,7.240225704963446560e+02,5.114350080268438292e-01,1.100000010988609489e+01,3.023601352434152068e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012076633824949283e+02,7.240325704958875122e+02,5.114380316281501582e-01,1.100000010988609489e+01,3.022141498418774892e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012085724733949377e+02,7.240425704954308230e+02,5.114410537696025827e-01,1.100000010988609489e+01,3.020681644403397717e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012094815642949470e+02,7.240525704949745887e+02,5.114440744512011028e-01,1.100000010988609489e+01,3.019221790388020542e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012103906551949564e+02,7.240625704945188090e+02,5.114470936729456074e-01,1.100000010988609489e+01,3.017761936372643367e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012112997460949657e+02,7.240725704940634841e+02,5.114501114348362076e-01,1.100000010988609489e+01,3.016302082357266191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012122088369949751e+02,7.240825704936086140e+02,5.114531277368727924e-01,1.100000010988609489e+01,3.014842228341889016e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012131179278949844e+02,7.240925704931541986e+02,5.114561425790554727e-01,1.100000010988609489e+01,3.013382374326511841e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012140270187949938e+02,7.241025704927001243e+02,5.114591559613842486e-01,1.100000010988609489e+01,3.011922520311134666e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012149361096950031e+02,7.241125704922465047e+02,5.114621678838590091e-01,1.100000010988609489e+01,3.010462666295757490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012158452005950124e+02,7.241225704917933399e+02,5.114651783464798651e-01,1.100000010988609489e+01,3.009002812280380315e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012167542914950218e+02,7.241325704913406298e+02,5.114681873492467057e-01,1.100000010988609489e+01,3.007542958265003140e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012176633823950311e+02,7.241425704908883745e+02,5.114711948921596418e-01,1.100000010988609489e+01,3.006083104249625965e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012185724732950405e+02,7.241525704904365739e+02,5.114742009752185625e-01,1.100000010988609489e+01,3.004623250234248789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012194815641950498e+02,7.241625704899852281e+02,5.114772055984235788e-01,1.100000010988609489e+01,3.003163396218871614e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012203906550950592e+02,7.241725704895342233e+02,5.114802087617746906e-01,1.100000010988609489e+01,3.001703542203494439e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012212997459950685e+02,7.241825704890836732e+02,5.114832104652717870e-01,1.100000010988609489e+01,3.000243688188117264e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012222088368950779e+02,7.241925704886335780e+02,5.114862107089149790e-01,1.100000010988609489e+01,2.998783834172740088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012231179277950872e+02,7.242025704881839374e+02,5.114892094927041555e-01,1.100000010988609489e+01,2.997323980157362913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012240270186950966e+02,7.242125704877347516e+02,5.114922068166394276e-01,1.100000010988609489e+01,2.995864126141985738e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012249361095951059e+02,7.242225704872860206e+02,5.114952026807207952e-01,1.100000010988609489e+01,2.994404272126608563e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012258452004951153e+02,7.242325704868377443e+02,5.114981970849481474e-01,1.100000010988609489e+01,2.992944418111231387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012267542913951246e+02,7.242425704863898090e+02,5.115011900293215952e-01,1.100000010988609489e+01,2.991484564095854212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012276633822951339e+02,7.242525704859423286e+02,5.115041815138410275e-01,1.100000010988609489e+01,2.990024710080477037e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012285724731951433e+02,7.242625704854953028e+02,5.115071715385065554e-01,1.100000010988609489e+01,2.988564856065099862e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012294815640951526e+02,7.242725704850487318e+02,5.115101601033181788e-01,1.100000010988609489e+01,2.987105002049722687e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012303906549951620e+02,7.242825704846026156e+02,5.115131472082757869e-01,1.100000010988609489e+01,2.985645148034345511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012312997458951713e+02,7.242925704841569541e+02,5.115161328533794904e-01,1.100000010988609489e+01,2.984185294018968336e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012322088367951807e+02,7.243025704837116336e+02,5.115191170386291786e-01,1.100000010988609489e+01,2.982725440003591161e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012331179276951900e+02,7.243125704832667680e+02,5.115220997640249623e-01,1.100000010988609489e+01,2.981265585988213986e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012340270185951994e+02,7.243225704828223570e+02,5.115250810295668416e-01,1.100000010988609489e+01,2.979805731972836810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012349361094952087e+02,7.243325704823784008e+02,5.115280608352547054e-01,1.100000010988609489e+01,2.978345877957459635e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012358452003952181e+02,7.243425704819348994e+02,5.115310391810886648e-01,1.100000010988609489e+01,2.976886023942082460e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012367542912952274e+02,7.243525704814918527e+02,5.115340160670686087e-01,1.100000010988609489e+01,2.975426169926705285e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012376633821952367e+02,7.243625704810491470e+02,5.115369914931946482e-01,1.100000010988609489e+01,2.973966315911328109e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012385724730952461e+02,7.243725704806068961e+02,5.115399654594666723e-01,1.100000010988609489e+01,2.972506461895950934e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012394815639952554e+02,7.243825704801651000e+02,5.115429379658847919e-01,1.100000010988609489e+01,2.971046607880573759e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012403906548952648e+02,7.243925704797237586e+02,5.115459090124490071e-01,1.100000010988609489e+01,2.969586753865196584e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012412997457952741e+02,7.244025704792828719e+02,5.115488785991592069e-01,1.100000010988609489e+01,2.968126899849819408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012422088366952835e+02,7.244125704788423263e+02,5.115518467260155022e-01,1.100000010988609489e+01,2.966667045834442233e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012431179275952928e+02,7.244225704784022355e+02,5.115548133930177821e-01,1.100000010988609489e+01,2.965207191819065058e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012440270184953022e+02,7.244325704779625994e+02,5.115577786001661575e-01,1.100000010988609489e+01,2.963747337803687883e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012449361093953115e+02,7.244425704775234180e+02,5.115607423474605175e-01,1.100000010988609489e+01,2.962287483788310707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012458452002953209e+02,7.244525704770846914e+02,5.115637046349009731e-01,1.100000010988609489e+01,2.960827629772933532e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012467542911953302e+02,7.244625704766464196e+02,5.115666654624875243e-01,1.100000010988609489e+01,2.959367775757556357e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012476633820953396e+02,7.244725704762084888e+02,5.115696248302200599e-01,1.100000010988609489e+01,2.957907921742179182e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012485724729953489e+02,7.244825704757710128e+02,5.115725827380986912e-01,1.100000010988609489e+01,2.956448067726802006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012494815638953582e+02,7.244925704753339915e+02,5.115755391861233070e-01,1.100000010988609489e+01,2.954988213711424831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012503906547953676e+02,7.245025704748974249e+02,5.115784941742940184e-01,1.100000010988609489e+01,2.953528359696047656e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012512997456953769e+02,7.245125704744613131e+02,5.115814477026108253e-01,1.100000010988609489e+01,2.952068505680670481e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012522088365953863e+02,7.245225704740255424e+02,5.115843997710736168e-01,1.100000010988609489e+01,2.950608651665293305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012531179274953956e+02,7.245325704735902264e+02,5.115873503796825039e-01,1.100000010988609489e+01,2.949148797649916130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012540270183954050e+02,7.245425704731553651e+02,5.115902995284373755e-01,1.100000010988609489e+01,2.947688943634538955e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012549361092954143e+02,7.245525704727209586e+02,5.115932472173383427e-01,1.100000010988609489e+01,2.946229089619161780e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012558452001954237e+02,7.245625704722868932e+02,5.115961934463852945e-01,1.100000010988609489e+01,2.944769235603784605e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012567542910954330e+02,7.245725704718532825e+02,5.115991382155783418e-01,1.100000010988609489e+01,2.943309381588407429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012576633819954424e+02,7.245825704714201265e+02,5.116020815249174847e-01,1.100000010988609489e+01,2.941849527573030254e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012585724728954517e+02,7.245925704709874253e+02,5.116050233744026121e-01,1.100000010988609489e+01,2.940389673557653079e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012594815637954611e+02,7.246025704705551789e+02,5.116079637640338351e-01,1.100000010988609489e+01,2.938929819542275904e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012603906546954704e+02,7.246125704701232735e+02,5.116109026938110427e-01,1.100000010988609489e+01,2.937469965526898728e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012612997455954797e+02,7.246225704696918228e+02,5.116138401637343458e-01,1.100000010988609489e+01,2.936010111511521553e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012622088364954891e+02,7.246325704692608269e+02,5.116167761738036335e-01,1.100000010988609489e+01,2.934550257496144378e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012631179273954984e+02,7.246425704688302858e+02,5.116197107240190167e-01,1.100000010988609489e+01,2.933090403480767203e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012640270182955078e+02,7.246525704684000857e+02,5.116226438143804955e-01,1.100000010988609489e+01,2.931630549465390027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012649361091955171e+02,7.246625704679703404e+02,5.116255754448879589e-01,1.100000010988609489e+01,2.930170695450012852e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012658452000955265e+02,7.246725704675410498e+02,5.116285056155415178e-01,1.100000010988609489e+01,2.928710841434635677e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012667542909955358e+02,7.246825704671122139e+02,5.116314343263410613e-01,1.100000010988609489e+01,2.927250987419258502e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012676633818955452e+02,7.246925704666837191e+02,5.116343615772867004e-01,1.100000010988609489e+01,2.925791133403881326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012685724727955545e+02,7.247025704662556791e+02,5.116372873683783240e-01,1.100000010988609489e+01,2.924331279388504151e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012694815636955639e+02,7.247125704658280938e+02,5.116402116996160432e-01,1.100000010988609489e+01,2.922871425373126976e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012703906545955732e+02,7.247225704654009633e+02,5.116431345709997469e-01,1.100000010988609489e+01,2.921411571357749801e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012712997454955826e+02,7.247325704649742875e+02,5.116460559825295462e-01,1.100000010988609489e+01,2.919951717342372625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012722088363955919e+02,7.247425704645479527e+02,5.116489759342054411e-01,1.100000010988609489e+01,2.918491863326995450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012731179272956012e+02,7.247525704641220727e+02,5.116518944260273205e-01,1.100000010988609489e+01,2.917032009311618275e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012740270181956106e+02,7.247625704636966475e+02,5.116548114579952955e-01,1.100000010988609489e+01,2.915572155296241100e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012749361090956199e+02,7.247725704632715633e+02,5.116577270301092550e-01,1.100000010988609489e+01,2.914112301280863924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012758451999956293e+02,7.247825704628469339e+02,5.116606411423693102e-01,1.100000010988609489e+01,2.912652447265486749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012767542908956386e+02,7.247925704624227592e+02,5.116635537947753498e-01,1.100000010988609489e+01,2.911192593250109574e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012776633817956480e+02,7.248025704619990393e+02,5.116664649873274850e-01,1.100000010988609489e+01,2.909732739234732399e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012785724726956573e+02,7.248125704615756604e+02,5.116693747200257159e-01,1.100000010988609489e+01,2.908272885219355224e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012794815635956667e+02,7.248225704611527362e+02,5.116722829928699312e-01,1.100000010988609489e+01,2.906813031203978048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012803906544956760e+02,7.248325704607302669e+02,5.116751898058602421e-01,1.100000010988609489e+01,2.905353177188600873e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012812997453956854e+02,7.248425704603082522e+02,5.116780951589965376e-01,1.100000010988609489e+01,2.903893323173223698e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012822088362956947e+02,7.248525704598865786e+02,5.116809990522789287e-01,1.100000010988609489e+01,2.902433469157846523e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012831179271957041e+02,7.248625704594653598e+02,5.116839014857073042e-01,1.100000010988609489e+01,2.900973615142469347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012840270180957134e+02,7.248725704590445957e+02,5.116868024592817754e-01,1.100000010988609489e+01,2.899513761127092172e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012849361089957227e+02,7.248825704586242864e+02,5.116897019730022311e-01,1.100000010988609489e+01,2.898053907111714997e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012858451998957321e+02,7.248925704582043181e+02,5.116926000268687824e-01,1.100000010988609489e+01,2.896594053096337822e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012867542907957414e+02,7.249025704577848046e+02,5.116954966208813183e-01,1.100000010988609489e+01,2.895134199080960646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012876633816957508e+02,7.249125704573657458e+02,5.116983917550399497e-01,1.100000010988609489e+01,2.893674345065583471e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012885724725957601e+02,7.249225704569470281e+02,5.117012854293446766e-01,1.100000010988609489e+01,2.892214491050206296e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012894815634957695e+02,7.249325704565287651e+02,5.117041776437953882e-01,1.100000010988609489e+01,2.890754637034829121e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012903906543957788e+02,7.249425704561109569e+02,5.117070683983921953e-01,1.100000010988609489e+01,2.889294783019451945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012912997452957882e+02,7.249525704556936034e+02,5.117099576931349869e-01,1.100000010988609489e+01,2.887834929004074770e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012922088361957975e+02,7.249625704552765910e+02,5.117128455280238741e-01,1.100000010988609489e+01,2.886375074988697595e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012931179270958069e+02,7.249725704548600334e+02,5.117157319030587459e-01,1.100000010988609489e+01,2.884915220973320420e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012940270179958162e+02,7.249825704544439304e+02,5.117186168182397132e-01,1.100000010988609489e+01,2.883455366957943244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012949361088958256e+02,7.249925704540281686e+02,5.117215002735666651e-01,1.100000010988609489e+01,2.881995512942566069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012958451997958349e+02,7.250025704536128615e+02,5.117243822690397126e-01,1.100000010988609489e+01,2.880535658927188894e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012967542906958442e+02,7.250125704531980091e+02,5.117272628046588556e-01,1.100000010988609489e+01,2.879075804911811719e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012976633815958536e+02,7.250225704527836115e+02,5.117301418804239832e-01,1.100000010988609489e+01,2.877615950896434543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012985724724958629e+02,7.250325704523695549e+02,5.117330194963352064e-01,1.100000010988609489e+01,2.876156096881057368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.012994815633958723e+02,7.250425704519559531e+02,5.117358956523924141e-01,1.100000010988609489e+01,2.874696242865680193e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013003906542958816e+02,7.250525704515428060e+02,5.117387703485957173e-01,1.100000010988609489e+01,2.873236388850303018e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013012997451958910e+02,7.250625704511300000e+02,5.117416435849450052e-01,1.100000010988609489e+01,2.871776534834925843e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013022088360959003e+02,7.250725704507176488e+02,5.117445153614403885e-01,1.100000010988609489e+01,2.870316680819548667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013031179269959097e+02,7.250825704503057523e+02,5.117473856780817565e-01,1.100000010988609489e+01,2.868856826804171492e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013040270178959190e+02,7.250925704498941968e+02,5.117502545348692200e-01,1.100000010988609489e+01,2.867396972788794317e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013049361087959284e+02,7.251025704494830961e+02,5.117531219318026681e-01,1.100000010988609489e+01,2.865937118773417142e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013058451996959377e+02,7.251125704490724502e+02,5.117559878688822117e-01,1.100000010988609489e+01,2.864477264758039966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013067542905959471e+02,7.251225704486621453e+02,5.117588523461078509e-01,1.100000010988609489e+01,2.863017410742662791e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013076633814959564e+02,7.251325704482522951e+02,5.117617153634794747e-01,1.100000010988609489e+01,2.861557556727285616e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013085724723959657e+02,7.251425704478428997e+02,5.117645769209971940e-01,1.100000010988609489e+01,2.860097702711908441e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013094815632959751e+02,7.251525704474338454e+02,5.117674370186608979e-01,1.100000010988609489e+01,2.858637848696531265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013103906541959844e+02,7.251625704470252458e+02,5.117702956564706973e-01,1.100000010988609489e+01,2.857177994681154090e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013112997450959938e+02,7.251725704466171010e+02,5.117731528344264813e-01,1.100000010988609489e+01,2.855718140665776915e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013122088359960031e+02,7.251825704462092972e+02,5.117760085525283609e-01,1.100000010988609489e+01,2.854258286650399740e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013131179268960125e+02,7.251925704458019482e+02,5.117788628107762250e-01,1.100000010988609489e+01,2.852798432635022564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013140270177960218e+02,7.252025704453950539e+02,5.117817156091701847e-01,1.100000010988609489e+01,2.851338578619645389e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013149361086960312e+02,7.252125704449885006e+02,5.117845669477101289e-01,1.100000010988609489e+01,2.849878724604268214e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013158451995960405e+02,7.252225704445824022e+02,5.117874168263961687e-01,1.100000010988609489e+01,2.848418870588891039e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013167542904960499e+02,7.252325704441767584e+02,5.117902652452281931e-01,1.100000010988609489e+01,2.846959016573513863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013176633813960592e+02,7.252425704437714558e+02,5.117931122042063130e-01,1.100000010988609489e+01,2.845499162558136688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013185724722960686e+02,7.252525704433666078e+02,5.117959577033304175e-01,1.100000010988609489e+01,2.844039308542759513e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013194815631960779e+02,7.252625704429622147e+02,5.117988017426006175e-01,1.100000010988609489e+01,2.842579454527382338e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013203906540960872e+02,7.252725704425581625e+02,5.118016443220169132e-01,1.100000010988609489e+01,2.841119600512005162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013212997449960966e+02,7.252825704421545652e+02,5.118044854415791933e-01,1.100000010988609489e+01,2.839659746496627987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013222088358961059e+02,7.252925704417514225e+02,5.118073251012875691e-01,1.100000010988609489e+01,2.838199892481250812e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013231179267961153e+02,7.253025704413486210e+02,5.118101633011419294e-01,1.100000010988609489e+01,2.836740038465873637e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013240270176961246e+02,7.253125704409462742e+02,5.118130000411423852e-01,1.100000010988609489e+01,2.835280184450496462e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013249361085961340e+02,7.253225704405443821e+02,5.118158353212888256e-01,1.100000010988609489e+01,2.833820330435119286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013258451994961433e+02,7.253325704401428311e+02,5.118186691415813616e-01,1.100000010988609489e+01,2.832360476419742111e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013267542903961527e+02,7.253425704397417348e+02,5.118215015020198821e-01,1.100000010988609489e+01,2.830900622404364936e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013276633812961620e+02,7.253525704393409796e+02,5.118243324026044982e-01,1.100000010988609489e+01,2.829440768388987761e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013285724721961714e+02,7.253625704389406792e+02,5.118271618433350989e-01,1.100000010988609489e+01,2.827980914373610585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013294815630961807e+02,7.253725704385408335e+02,5.118299898242117951e-01,1.100000010988609489e+01,2.826521060358233410e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013303906539961901e+02,7.253825704381413289e+02,5.118328163452344759e-01,1.100000010988609489e+01,2.825061206342856235e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013312997448961994e+02,7.253925704377422790e+02,5.118356414064032522e-01,1.100000010988609489e+01,2.823601352327479060e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013322088357962087e+02,7.254025704373436838e+02,5.118384650077180131e-01,1.100000010988609489e+01,2.822141498312101884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013331179266962181e+02,7.254125704369454297e+02,5.118412871491788696e-01,1.100000010988609489e+01,2.820681644296724709e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013340270175962274e+02,7.254225704365476304e+02,5.118441078307857106e-01,1.100000010988609489e+01,2.819221790281347534e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013349361084962368e+02,7.254325704361502858e+02,5.118469270525386472e-01,1.100000010988609489e+01,2.817761936265970359e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013358451993962461e+02,7.254425704357532823e+02,5.118497448144376794e-01,1.100000010988609489e+01,2.816302082250593183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013367542902962555e+02,7.254525704353567335e+02,5.118525611164826961e-01,1.100000010988609489e+01,2.814842228235216008e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013376633811962648e+02,7.254625704349605257e+02,5.118553759586738083e-01,1.100000010988609489e+01,2.813382374219838833e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013385724720962742e+02,7.254725704345647728e+02,5.118581893410109052e-01,1.100000010988609489e+01,2.811922520204461658e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013394815629962835e+02,7.254825704341694745e+02,5.118610012634940976e-01,1.100000010988609489e+01,2.810462666189084482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013403906538962929e+02,7.254925704337745174e+02,5.118638117261232745e-01,1.100000010988609489e+01,2.809002812173707307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013412997447963022e+02,7.255025704333800149e+02,5.118666207288985470e-01,1.100000010988609489e+01,2.807542958158330132e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013422088356963116e+02,7.255125704329858536e+02,5.118694282718198041e-01,1.100000010988609489e+01,2.806083104142952957e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013431179265963209e+02,7.255225704325921470e+02,5.118722343548871567e-01,1.100000010988609489e+01,2.804623250127575781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013440270174963302e+02,7.255325704321988951e+02,5.118750389781004939e-01,1.100000010988609489e+01,2.803163396112198606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013449361083963396e+02,7.255425704318059843e+02,5.118778421414599267e-01,1.100000010988609489e+01,2.801703542096821431e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013458451992963489e+02,7.255525704314135282e+02,5.118806438449653440e-01,1.100000010988609489e+01,2.800243688081444256e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013467542901963583e+02,7.255625704310214132e+02,5.118834440886168569e-01,1.100000010988609489e+01,2.798783834066067081e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013476633810963676e+02,7.255725704306297530e+02,5.118862428724143543e-01,1.100000010988609489e+01,2.797323980050689905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013485724719963770e+02,7.255825704302385475e+02,5.118890401963579473e-01,1.100000010988609489e+01,2.795864126035312730e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013494815628963863e+02,7.255925704298476830e+02,5.118918360604475248e-01,1.100000010988609489e+01,2.794404272019935555e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013503906537963957e+02,7.256025704294572733e+02,5.118946304646831980e-01,1.100000010988609489e+01,2.792944418004558380e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013512997446964050e+02,7.256125704290672047e+02,5.118974234090648556e-01,1.100000010988609489e+01,2.791484563989181204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013522088355964144e+02,7.256225704286775908e+02,5.119002148935926089e-01,1.100000010988609489e+01,2.790024709973804029e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013531179264964237e+02,7.256325704282884317e+02,5.119030049182663467e-01,1.100000010988609489e+01,2.788564855958426854e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013540270173964331e+02,7.256425704278996136e+02,5.119057934830861800e-01,1.100000010988609489e+01,2.787105001943049679e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013549361082964424e+02,7.256525704275112503e+02,5.119085805880519979e-01,1.100000010988609489e+01,2.785645147927672503e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013558451991964517e+02,7.256625704271232280e+02,5.119113662331639114e-01,1.100000010988609489e+01,2.784185293912295328e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013567542900964611e+02,7.256725704267356605e+02,5.119141504184218094e-01,1.100000010988609489e+01,2.782725439896918153e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013576633809964704e+02,7.256825704263484340e+02,5.119169331438258030e-01,1.100000010988609489e+01,2.781265585881540978e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013585724718964798e+02,7.256925704259616623e+02,5.119197144093757812e-01,1.100000010988609489e+01,2.779805731866163802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013594815627964891e+02,7.257025704255753453e+02,5.119224942150718549e-01,1.100000010988609489e+01,2.778345877850786627e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013603906536964985e+02,7.257125704251893694e+02,5.119252725609139132e-01,1.100000010988609489e+01,2.776886023835409452e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013612997445965078e+02,7.257225704248038483e+02,5.119280494469020670e-01,1.100000010988609489e+01,2.775426169820032277e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013622088354965172e+02,7.257325704244186682e+02,5.119308248730362054e-01,1.100000010988609489e+01,2.773966315804655101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013631179263965265e+02,7.257425704240339428e+02,5.119335988393164394e-01,1.100000010988609489e+01,2.772506461789277926e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013640270172965359e+02,7.257525704236495585e+02,5.119363713457426579e-01,1.100000010988609489e+01,2.771046607773900751e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013649361081965452e+02,7.257625704232656290e+02,5.119391423923149720e-01,1.100000010988609489e+01,2.769586753758523576e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013658451990965546e+02,7.257725704228821542e+02,5.119419119790332706e-01,1.100000010988609489e+01,2.768126899743146400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013667542899965639e+02,7.257825704224990204e+02,5.119446801058976648e-01,1.100000010988609489e+01,2.766667045727769225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013676633808965732e+02,7.257925704221163414e+02,5.119474467729080436e-01,1.100000010988609489e+01,2.765207191712392050e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013685724717965826e+02,7.258025704217340035e+02,5.119502119800645179e-01,1.100000010988609489e+01,2.763747337697014875e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013694815626965919e+02,7.258125704213521203e+02,5.119529757273669768e-01,1.100000010988609489e+01,2.762287483681637699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013703906535966013e+02,7.258225704209705782e+02,5.119557380148155312e-01,1.100000010988609489e+01,2.760827629666260524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013712997444966106e+02,7.258325704205894908e+02,5.119584988424100702e-01,1.100000010988609489e+01,2.759367775650883349e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013722088353966200e+02,7.258425704202087445e+02,5.119612582101507048e-01,1.100000010988609489e+01,2.757907921635506174e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013731179262966293e+02,7.258525704198284529e+02,5.119640161180373239e-01,1.100000010988609489e+01,2.756448067620128999e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013740270171966387e+02,7.258625704194485024e+02,5.119667725660700386e-01,1.100000010988609489e+01,2.754988213604751823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013749361080966480e+02,7.258725704190690067e+02,5.119695275542487378e-01,1.100000010988609489e+01,2.753528359589374648e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013758451989966574e+02,7.258825704186899657e+02,5.119722810825735326e-01,1.100000010988609489e+01,2.752068505573997473e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013767542898966667e+02,7.258925704183112657e+02,5.119750331510443120e-01,1.100000010988609489e+01,2.750608651558620298e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013776633807966761e+02,7.259025704179330205e+02,5.119777837596611869e-01,1.100000010988609489e+01,2.749148797543243122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013785724716966854e+02,7.259125704175551164e+02,5.119805329084240464e-01,1.100000010988609489e+01,2.747688943527865947e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013794815625966947e+02,7.259225704171776670e+02,5.119832805973330014e-01,1.100000010988609489e+01,2.746229089512488772e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013803906534967041e+02,7.259325704168005586e+02,5.119860268263879410e-01,1.100000010988609489e+01,2.744769235497111597e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013812997443967134e+02,7.259425704164239050e+02,5.119887715955889762e-01,1.100000010988609489e+01,2.743309381481734421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013822088352967228e+02,7.259525704160475925e+02,5.119915149049359959e-01,1.100000010988609489e+01,2.741849527466357246e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013831179261967321e+02,7.259625704156717347e+02,5.119942567544291112e-01,1.100000010988609489e+01,2.740389673450980071e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013840270170967415e+02,7.259725704152962180e+02,5.119969971440682110e-01,1.100000010988609489e+01,2.738929819435602896e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013849361079967508e+02,7.259825704149211560e+02,5.119997360738534065e-01,1.100000010988609489e+01,2.737469965420225720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013858451988967602e+02,7.259925704145464351e+02,5.120024735437845864e-01,1.100000010988609489e+01,2.736010111404848545e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013867542897967695e+02,7.260025704141721690e+02,5.120052095538618619e-01,1.100000010988609489e+01,2.734550257389471370e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013876633806967789e+02,7.260125704137982439e+02,5.120079441040851220e-01,1.100000010988609489e+01,2.733090403374094195e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013885724715967882e+02,7.260225704134247735e+02,5.120106771944544777e-01,1.100000010988609489e+01,2.731630549358717019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013894815624967976e+02,7.260325704130516442e+02,5.120134088249698179e-01,1.100000010988609489e+01,2.730170695343339844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013903906533968069e+02,7.260425704126789697e+02,5.120161389956312536e-01,1.100000010988609489e+01,2.728710841327962669e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013912997442968162e+02,7.260525704123066362e+02,5.120188677064386740e-01,1.100000010988609489e+01,2.727250987312585494e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013922088351968256e+02,7.260625704119347574e+02,5.120215949573921899e-01,1.100000010988609489e+01,2.725791133297208318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013931179260968349e+02,7.260725704115632197e+02,5.120243207484916903e-01,1.100000010988609489e+01,2.724331279281831143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013940270169968443e+02,7.260825704111921368e+02,5.120270450797372863e-01,1.100000010988609489e+01,2.722871425266453968e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013949361078968536e+02,7.260925704108213949e+02,5.120297679511288669e-01,1.100000010988609489e+01,2.721411571251076793e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013958451987968630e+02,7.261025704104511078e+02,5.120324893626665430e-01,1.100000010988609489e+01,2.719951717235699618e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013967542896968723e+02,7.261125704100811618e+02,5.120352093143502037e-01,1.100000010988609489e+01,2.718491863220322442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013976633805968817e+02,7.261225704097116704e+02,5.120379278061799599e-01,1.100000010988609489e+01,2.717032009204945267e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013985724714968910e+02,7.261325704093425202e+02,5.120406448381557007e-01,1.100000010988609489e+01,2.715572155189568092e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.013994815623969004e+02,7.261425704089738247e+02,5.120433604102775371e-01,1.100000010988609489e+01,2.714112301174190917e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014003906532969097e+02,7.261525704086054702e+02,5.120460745225453580e-01,1.100000010988609489e+01,2.712652447158813741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014012997441969191e+02,7.261625704082375705e+02,5.120487871749592745e-01,1.100000010988609489e+01,2.711192593143436566e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014022088350969284e+02,7.261725704078700119e+02,5.120514983675191756e-01,1.100000010988609489e+01,2.709732739128059391e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014031179259969377e+02,7.261825704075029080e+02,5.120542081002251722e-01,1.100000010988609489e+01,2.708272885112682216e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014040270168969471e+02,7.261925704071361451e+02,5.120569163730771534e-01,1.100000010988609489e+01,2.706813031097305040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014049361077969564e+02,7.262025704067698371e+02,5.120596231860752301e-01,1.100000010988609489e+01,2.705353177081927865e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014058451986969658e+02,7.262125704064038700e+02,5.120623285392192914e-01,1.100000010988609489e+01,2.703893323066550690e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014067542895969751e+02,7.262225704060383578e+02,5.120650324325094482e-01,1.100000010988609489e+01,2.702433469051173515e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014076633804969845e+02,7.262325704056731865e+02,5.120677348659455896e-01,1.100000010988609489e+01,2.700973615035796339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014085724713969938e+02,7.262425704053084701e+02,5.120704358395278266e-01,1.100000010988609489e+01,2.699513761020419164e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014094815622970032e+02,7.262525704049440947e+02,5.120731353532560481e-01,1.100000010988609489e+01,2.698053907005041989e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014103906531970125e+02,7.262625704045801740e+02,5.120758334071303652e-01,1.100000010988609489e+01,2.696594052989664814e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014112997440970219e+02,7.262725704042165944e+02,5.120785300011506669e-01,1.100000010988609489e+01,2.695134198974287638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014122088349970312e+02,7.262825704038533559e+02,5.120812251353170641e-01,1.100000010988609489e+01,2.693674344958910463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014131179258970405e+02,7.262925704034905721e+02,5.120839188096294459e-01,1.100000010988609489e+01,2.692214490943533288e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014140270167970499e+02,7.263025704031281293e+02,5.120866110240878122e-01,1.100000010988609489e+01,2.690754636928156113e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014149361076970592e+02,7.263125704027661413e+02,5.120893017786922741e-01,1.100000010988609489e+01,2.689294782912778937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014158451985970686e+02,7.263225704024044944e+02,5.120919910734427205e-01,1.100000010988609489e+01,2.687834928897401762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014167542894970779e+02,7.263325704020433022e+02,5.120946789083392625e-01,1.100000010988609489e+01,2.686375074882024587e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014176633803970873e+02,7.263425704016824511e+02,5.120973652833817891e-01,1.100000010988609489e+01,2.684915220866647412e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014185724712970966e+02,7.263525704013220547e+02,5.121000501985704112e-01,1.100000010988609489e+01,2.683455366851270237e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014194815621971060e+02,7.263625704009619994e+02,5.121027336539050179e-01,1.100000010988609489e+01,2.681995512835893061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014203906530971153e+02,7.263725704006023989e+02,5.121054156493857201e-01,1.100000010988609489e+01,2.680535658820515886e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014212997439971247e+02,7.263825704002431394e+02,5.121080961850124069e-01,1.100000010988609489e+01,2.679075804805138711e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014222088348971340e+02,7.263925703998842209e+02,5.121107752607851893e-01,1.100000010988609489e+01,2.677615950789761536e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014231179257971434e+02,7.264025703995257572e+02,5.121134528767039562e-01,1.100000010988609489e+01,2.676156096774384360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014240270166971527e+02,7.264125703991676346e+02,5.121161290327688187e-01,1.100000010988609489e+01,2.674696242759007185e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014249361075971620e+02,7.264225703988099667e+02,5.121188037289796657e-01,1.100000010988609489e+01,2.673236388743630010e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014258451984971714e+02,7.264325703984526399e+02,5.121214769653366083e-01,1.100000010988609489e+01,2.671776534728252835e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014267542893971807e+02,7.264425703980957678e+02,5.121241487418395355e-01,1.100000010988609489e+01,2.670316680712875659e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014276633802971901e+02,7.264525703977392368e+02,5.121268190584885582e-01,1.100000010988609489e+01,2.668856826697498484e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014285724711971994e+02,7.264625703973830468e+02,5.121294879152835655e-01,1.100000010988609489e+01,2.667396972682121309e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014294815620972088e+02,7.264725703970273116e+02,5.121321553122246684e-01,1.100000010988609489e+01,2.665937118666744134e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014303906529972181e+02,7.264825703966719175e+02,5.121348212493117558e-01,1.100000010988609489e+01,2.664477264651366958e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014312997438972275e+02,7.264925703963169781e+02,5.121374857265448277e-01,1.100000010988609489e+01,2.663017410635989783e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014322088347972368e+02,7.265025703959623797e+02,5.121401487439239952e-01,1.100000010988609489e+01,2.661557556620612608e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014331179256972462e+02,7.265125703956082361e+02,5.121428103014491473e-01,1.100000010988609489e+01,2.660097702605235433e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014340270165972555e+02,7.265225703952544336e+02,5.121454703991203949e-01,1.100000010988609489e+01,2.658637848589858257e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014349361074972649e+02,7.265325703949009721e+02,5.121481290369376271e-01,1.100000010988609489e+01,2.657177994574481082e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014358451983972742e+02,7.265425703945479654e+02,5.121507862149009549e-01,1.100000010988609489e+01,2.655718140559103907e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014367542892972835e+02,7.265525703941952997e+02,5.121534419330102672e-01,1.100000010988609489e+01,2.654258286543726732e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014376633801972929e+02,7.265625703938430888e+02,5.121560961912656751e-01,1.100000010988609489e+01,2.652798432528349556e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014385724710973022e+02,7.265725703934912190e+02,5.121587489896670675e-01,1.100000010988609489e+01,2.651338578512972381e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014394815619973116e+02,7.265825703931396902e+02,5.121614003282145555e-01,1.100000010988609489e+01,2.649878724497595206e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014403906528973209e+02,7.265925703927886161e+02,5.121640502069080281e-01,1.100000010988609489e+01,2.648418870482218031e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014412997437973303e+02,7.266025703924378831e+02,5.121666986257475962e-01,1.100000010988609489e+01,2.646959016466840856e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014422088346973396e+02,7.266125703920876049e+02,5.121693455847331489e-01,1.100000010988609489e+01,2.645499162451463680e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014431179255973490e+02,7.266225703917376677e+02,5.121719910838647971e-01,1.100000010988609489e+01,2.644039308436086505e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014440270164973583e+02,7.266325703913880716e+02,5.121746351231424299e-01,1.100000010988609489e+01,2.642579454420709330e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014449361073973677e+02,7.266425703910389302e+02,5.121772777025660472e-01,1.100000010988609489e+01,2.641119600405332155e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014458451982973770e+02,7.266525703906901299e+02,5.121799188221357602e-01,1.100000010988609489e+01,2.639659746389954979e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014467542891973864e+02,7.266625703903417843e+02,5.121825584818514576e-01,1.100000010988609489e+01,2.638199892374577804e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014476633800973957e+02,7.266725703899937798e+02,5.121851966817132507e-01,1.100000010988609489e+01,2.636740038359200629e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014485724709974050e+02,7.266825703896461164e+02,5.121878334217210282e-01,1.100000010988609489e+01,2.635280184343823454e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014494815618974144e+02,7.266925703892989077e+02,5.121904687018749014e-01,1.100000010988609489e+01,2.633820330328446278e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014503906527974237e+02,7.267025703889520400e+02,5.121931025221747591e-01,1.100000010988609489e+01,2.632360476313069103e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014512997436974331e+02,7.267125703886056272e+02,5.121957348826207124e-01,1.100000010988609489e+01,2.630900622297691928e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014522088345974424e+02,7.267225703882595553e+02,5.121983657832126502e-01,1.100000010988609489e+01,2.629440768282314753e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014531179254974518e+02,7.267325703879138246e+02,5.122009952239506836e-01,1.100000010988609489e+01,2.627980914266937577e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014540270163974611e+02,7.267425703875685485e+02,5.122036232048347015e-01,1.100000010988609489e+01,2.626521060251560402e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014549361072974705e+02,7.267525703872236136e+02,5.122062497258647040e-01,1.100000010988609489e+01,2.625061206236183227e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014558451981974798e+02,7.267625703868790197e+02,5.122088747870408021e-01,1.100000010988609489e+01,2.623601352220806052e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014567542890974892e+02,7.267725703865348805e+02,5.122114983883628847e-01,1.100000010988609489e+01,2.622141498205428876e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014576633799974985e+02,7.267825703861910824e+02,5.122141205298310629e-01,1.100000010988609489e+01,2.620681644190051701e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014585724708975079e+02,7.267925703858477391e+02,5.122167412114452256e-01,1.100000010988609489e+01,2.619221790174674526e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014594815617975172e+02,7.268025703855047368e+02,5.122193604332054839e-01,1.100000010988609489e+01,2.617761936159297351e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014603906526975265e+02,7.268125703851620756e+02,5.122219781951117268e-01,1.100000010988609489e+01,2.616302082143920175e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014612997435975359e+02,7.268225703848198691e+02,5.122245944971640652e-01,1.100000010988609489e+01,2.614842228128543000e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014622088344975452e+02,7.268325703844780037e+02,5.122272093393623882e-01,1.100000010988609489e+01,2.613382374113165825e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014631179253975546e+02,7.268425703841364793e+02,5.122298227217068067e-01,1.100000010988609489e+01,2.611922520097788650e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014640270162975639e+02,7.268525703837954097e+02,5.122324346441972098e-01,1.100000010988609489e+01,2.610462666082411474e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014649361071975733e+02,7.268625703834546812e+02,5.122350451068335975e-01,1.100000010988609489e+01,2.609002812067034299e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014658451980975826e+02,7.268725703831142937e+02,5.122376541096160807e-01,1.100000010988609489e+01,2.607542958051657124e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014667542889975920e+02,7.268825703827743610e+02,5.122402616525445485e-01,1.100000010988609489e+01,2.606083104036279949e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014676633798976013e+02,7.268925703824347693e+02,5.122428677356191118e-01,1.100000010988609489e+01,2.604623250020902774e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014685724707976107e+02,7.269025703820955187e+02,5.122454723588396597e-01,1.100000010988609489e+01,2.603163396005525598e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014694815616976200e+02,7.269125703817567228e+02,5.122480755222063031e-01,1.100000010988609489e+01,2.601703541990148423e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014703906525976294e+02,7.269225703814182680e+02,5.122506772257189311e-01,1.100000010988609489e+01,2.600243687974771248e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014712997434976387e+02,7.269325703810801542e+02,5.122532774693776547e-01,1.100000010988609489e+01,2.598783833959394073e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014722088343976480e+02,7.269425703807424952e+02,5.122558762531823628e-01,1.100000010988609489e+01,2.597323979944016897e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014731179252976574e+02,7.269525703804051773e+02,5.122584735771330555e-01,1.100000010988609489e+01,2.595864125928639722e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014740270161976667e+02,7.269625703800682004e+02,5.122610694412298438e-01,1.100000010988609489e+01,2.594404271913262547e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014749361070976761e+02,7.269725703797316783e+02,5.122636638454726166e-01,1.100000010988609489e+01,2.592944417897885372e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014758451979976854e+02,7.269825703793954972e+02,5.122662567898614849e-01,1.100000010988609489e+01,2.591484563882508196e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014767542888976948e+02,7.269925703790596572e+02,5.122688482743963378e-01,1.100000010988609489e+01,2.590024709867131021e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014776633797977041e+02,7.270025703787242719e+02,5.122714382990772863e-01,1.100000010988609489e+01,2.588564855851753846e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014785724706977135e+02,7.270125703783892277e+02,5.122740268639042194e-01,1.100000010988609489e+01,2.587105001836376671e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014794815615977228e+02,7.270225703780545246e+02,5.122766139688772480e-01,1.100000010988609489e+01,2.585645147820999495e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014803906524977322e+02,7.270325703777202762e+02,5.122791996139962611e-01,1.100000010988609489e+01,2.584185293805622320e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014812997433977415e+02,7.270425703773863688e+02,5.122817837992612588e-01,1.100000010988609489e+01,2.582725439790245145e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014822088342977509e+02,7.270525703770528025e+02,5.122843665246723521e-01,1.100000010988609489e+01,2.581265585774867970e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014831179251977602e+02,7.270625703767196910e+02,5.122869477902294300e-01,1.100000010988609489e+01,2.579805731759490794e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014840270160977695e+02,7.270725703763869205e+02,5.122895275959326034e-01,1.100000010988609489e+01,2.578345877744113619e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014849361069977789e+02,7.270825703760544911e+02,5.122921059417817613e-01,1.100000010988609489e+01,2.576886023728736444e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014858451978977882e+02,7.270925703757225165e+02,5.122946828277770148e-01,1.100000010988609489e+01,2.575426169713359269e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014867542887977976e+02,7.271025703753908829e+02,5.122972582539182529e-01,1.100000010988609489e+01,2.573966315697982093e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014876633796978069e+02,7.271125703750595903e+02,5.122998322202054755e-01,1.100000010988609489e+01,2.572506461682604918e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014885724705978163e+02,7.271225703747287525e+02,5.123024047266387937e-01,1.100000010988609489e+01,2.571046607667227743e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014894815614978256e+02,7.271325703743982558e+02,5.123049757732180964e-01,1.100000010988609489e+01,2.569586753651850568e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014903906523978350e+02,7.271425703740681001e+02,5.123075453599434947e-01,1.100000010988609489e+01,2.568126899636473393e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014912997432978443e+02,7.271525703737382855e+02,5.123101134868148776e-01,1.100000010988609489e+01,2.566667045621096217e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014922088341978537e+02,7.271625703734089257e+02,5.123126801538323560e-01,1.100000010988609489e+01,2.565207191605719042e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014931179250978630e+02,7.271725703730799069e+02,5.123152453609958190e-01,1.100000010988609489e+01,2.563747337590341867e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014940270159978724e+02,7.271825703727512291e+02,5.123178091083053776e-01,1.100000010988609489e+01,2.562287483574964692e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014949361068978817e+02,7.271925703724230061e+02,5.123203713957609207e-01,1.100000010988609489e+01,2.560827629559587516e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014958451977978910e+02,7.272025703720951242e+02,5.123229322233624483e-01,1.100000010988609489e+01,2.559367775544210341e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014967542886979004e+02,7.272125703717675833e+02,5.123254915911100715e-01,1.100000010988609489e+01,2.557907921528833166e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014976633795979097e+02,7.272225703714403835e+02,5.123280494990036793e-01,1.100000010988609489e+01,2.556448067513455991e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014985724704979191e+02,7.272325703711136384e+02,5.123306059470433826e-01,1.100000010988609489e+01,2.554988213498078815e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.014994815613979284e+02,7.272425703707872344e+02,5.123331609352290705e-01,1.100000010988609489e+01,2.553528359482701640e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015003906522979378e+02,7.272525703704611715e+02,5.123357144635608540e-01,1.100000010988609489e+01,2.552068505467324465e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015012997431979471e+02,7.272625703701355633e+02,5.123382665320386220e-01,1.100000010988609489e+01,2.550608651451947290e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015022088340979565e+02,7.272725703698102961e+02,5.123408171406623746e-01,1.100000010988609489e+01,2.549148797436570114e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015031179249979658e+02,7.272825703694853701e+02,5.123433662894322227e-01,1.100000010988609489e+01,2.547688943421192939e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015040270158979752e+02,7.272925703691607850e+02,5.123459139783480554e-01,1.100000010988609489e+01,2.546229089405815764e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015049361067979845e+02,7.273025703688366548e+02,5.123484602074099836e-01,1.100000010988609489e+01,2.544769235390438589e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015058451976979939e+02,7.273125703685128656e+02,5.123510049766178964e-01,1.100000010988609489e+01,2.543309381375061413e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015067542885980032e+02,7.273225703681894174e+02,5.123535482859719048e-01,1.100000010988609489e+01,2.541849527359684238e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015076633794980125e+02,7.273325703678664240e+02,5.123560901354718977e-01,1.100000010988609489e+01,2.540389673344307063e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015085724703980219e+02,7.273425703675437717e+02,5.123586305251178752e-01,1.100000010988609489e+01,2.538929819328929888e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015094815612980312e+02,7.273525703672214604e+02,5.123611694549099482e-01,1.100000010988609489e+01,2.537469965313552712e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015103906521980406e+02,7.273625703668994902e+02,5.123637069248480058e-01,1.100000010988609489e+01,2.536010111298175537e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015112997430980499e+02,7.273725703665779747e+02,5.123662429349321590e-01,1.100000010988609489e+01,2.534550257282798362e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015122088339980593e+02,7.273825703662568003e+02,5.123687774851622967e-01,1.100000010988609489e+01,2.533090403267421187e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015131179248980686e+02,7.273925703659359669e+02,5.123713105755385300e-01,1.100000010988609489e+01,2.531630549252044012e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015140270157980780e+02,7.274025703656154747e+02,5.123738422060607478e-01,1.100000010988609489e+01,2.530170695236666836e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015149361066980873e+02,7.274125703652954371e+02,5.123763723767289502e-01,1.100000010988609489e+01,2.528710841221289661e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015158451975980967e+02,7.274225703649757406e+02,5.123789010875432481e-01,1.100000010988609489e+01,2.527250987205912486e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015167542884981060e+02,7.274325703646563852e+02,5.123814283385035306e-01,1.100000010988609489e+01,2.525791133190535311e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015176633793981154e+02,7.274425703643373708e+02,5.123839541296099087e-01,1.100000010988609489e+01,2.524331279175158135e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015185724702981247e+02,7.274525703640188112e+02,5.123864784608622713e-01,1.100000010988609489e+01,2.522871425159780960e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015194815611981340e+02,7.274625703637005927e+02,5.123890013322606185e-01,1.100000010988609489e+01,2.521411571144403785e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015203906520981434e+02,7.274725703633827152e+02,5.123915227438050612e-01,1.100000010988609489e+01,2.519951717129026610e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015212997429981527e+02,7.274825703630651788e+02,5.123940426954954885e-01,1.100000010988609489e+01,2.518491863113649434e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015222088338981621e+02,7.274925703627479834e+02,5.123965611873320114e-01,1.100000010988609489e+01,2.517032009098272259e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015231179247981714e+02,7.275025703624312428e+02,5.123990782193145188e-01,1.100000010988609489e+01,2.515572155082895084e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015240270156981808e+02,7.275125703621148432e+02,5.124015937914431218e-01,1.100000010988609489e+01,2.514112301067517909e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015249361065981901e+02,7.275225703617987847e+02,5.124041079037177093e-01,1.100000010988609489e+01,2.512652447052140733e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015258451974981995e+02,7.275325703614830672e+02,5.124066205561382814e-01,1.100000010988609489e+01,2.511192593036763558e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015267542883982088e+02,7.275425703611678045e+02,5.124091317487049491e-01,1.100000010988609489e+01,2.509732739021386383e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015276633792982182e+02,7.275525703608528829e+02,5.124116414814176013e-01,1.100000010988609489e+01,2.508272885006009208e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015285724701982275e+02,7.275625703605383023e+02,5.124141497542763490e-01,1.100000010988609489e+01,2.506813030990632032e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015294815610982369e+02,7.275725703602240628e+02,5.124166565672810814e-01,1.100000010988609489e+01,2.505353176975254857e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015303906519982462e+02,7.275825703599102781e+02,5.124191619204317982e-01,1.100000010988609489e+01,2.503893322959877682e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015312997428982555e+02,7.275925703595968344e+02,5.124216658137286107e-01,1.100000010988609489e+01,2.502433468944500507e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015322088337982649e+02,7.276025703592837317e+02,5.124241682471714077e-01,1.100000010988609489e+01,2.500973614929123331e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015331179246982742e+02,7.276125703589709701e+02,5.124266692207603002e-01,1.100000010988609489e+01,2.499513760913746156e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015340270155982836e+02,7.276225703586585496e+02,5.124291687344951773e-01,1.100000010988609489e+01,2.498053906898368981e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015349361064982929e+02,7.276325703583465838e+02,5.124316667883761500e-01,1.100000010988609489e+01,2.496594052882991806e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015358451973983023e+02,7.276425703580349591e+02,5.124341633824031073e-01,1.100000010988609489e+01,2.495134198867614631e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015367542882983116e+02,7.276525703577236754e+02,5.124366585165760490e-01,1.100000010988609489e+01,2.493674344852237455e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015376633791983210e+02,7.276625703574127328e+02,5.124391521908950864e-01,1.100000010988609489e+01,2.492214490836860280e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015385724700983303e+02,7.276725703571021313e+02,5.124416444053601083e-01,1.100000010988609489e+01,2.490754636821483105e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015394815609983397e+02,7.276825703567919845e+02,5.124441351599712258e-01,1.100000010988609489e+01,2.489294782806105930e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015403906518983490e+02,7.276925703564821788e+02,5.124466244547283278e-01,1.100000010988609489e+01,2.487834928790728754e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015412997427983584e+02,7.277025703561727141e+02,5.124491122896314144e-01,1.100000010988609489e+01,2.486375074775351579e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015422088336983677e+02,7.277125703558635905e+02,5.124515986646805965e-01,1.100000010988609489e+01,2.484915220759974404e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015431179245983770e+02,7.277225703555548080e+02,5.124540835798757632e-01,1.100000010988609489e+01,2.483455366744597229e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015440270154983864e+02,7.277325703552464802e+02,5.124565670352170255e-01,1.100000010988609489e+01,2.481995512729220053e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015449361063983957e+02,7.277425703549384934e+02,5.124590490307042723e-01,1.100000010988609489e+01,2.480535658713842878e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015458451972984051e+02,7.277525703546308478e+02,5.124615295663375036e-01,1.100000010988609489e+01,2.479075804698465703e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015467542881984144e+02,7.277625703543235431e+02,5.124640086421168306e-01,1.100000010988609489e+01,2.477615950683088528e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015476633790984238e+02,7.277725703540165796e+02,5.124664862580421421e-01,1.100000010988609489e+01,2.476156096667711352e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015485724699984331e+02,7.277825703537099571e+02,5.124689624141135491e-01,1.100000010988609489e+01,2.474696242652334177e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015494815608984425e+02,7.277925703534037893e+02,5.124714371103309407e-01,1.100000010988609489e+01,2.473236388636957002e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015503906517984518e+02,7.278025703530979627e+02,5.124739103466943169e-01,1.100000010988609489e+01,2.471776534621579827e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015512997426984612e+02,7.278125703527924770e+02,5.124763821232037886e-01,1.100000010988609489e+01,2.470316680606202651e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015522088335984705e+02,7.278225703524873325e+02,5.124788524398592449e-01,1.100000010988609489e+01,2.468856826590825476e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015531179244984799e+02,7.278325703521825289e+02,5.124813212966607967e-01,1.100000010988609489e+01,2.467396972575448301e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015540270153984892e+02,7.278425703518781802e+02,5.124837886936083331e-01,1.100000010988609489e+01,2.465937118560071126e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015549361062984985e+02,7.278525703515741725e+02,5.124862546307018540e-01,1.100000010988609489e+01,2.464477264544693950e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015558451971985079e+02,7.278625703512705059e+02,5.124887191079414706e-01,1.100000010988609489e+01,2.463017410529316775e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015567542880985172e+02,7.278725703509671803e+02,5.124911821253270716e-01,1.100000010988609489e+01,2.461557556513939600e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015576633789985266e+02,7.278825703506641958e+02,5.124936436828587683e-01,1.100000010988609489e+01,2.460097702498562425e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015585724698985359e+02,7.278925703503615523e+02,5.124961037805364494e-01,1.100000010988609489e+01,2.458637848483185250e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015594815607985453e+02,7.279025703500593636e+02,5.124985624183601152e-01,1.100000010988609489e+01,2.457177994467808074e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015603906516985546e+02,7.279125703497575159e+02,5.125010195963298765e-01,1.100000010988609489e+01,2.455718140452430899e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015612997425985640e+02,7.279225703494560094e+02,5.125034753144456223e-01,1.100000010988609489e+01,2.454258286437053724e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015622088334985733e+02,7.279325703491548438e+02,5.125059295727074637e-01,1.100000010988609489e+01,2.452798432421676549e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015631179243985827e+02,7.279425703488540194e+02,5.125083823711152897e-01,1.100000010988609489e+01,2.451338578406299373e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015640270152985920e+02,7.279525703485535360e+02,5.125108337096691002e-01,1.100000010988609489e+01,2.449878724390922198e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015649361061986014e+02,7.279625703482533936e+02,5.125132835883690063e-01,1.100000010988609489e+01,2.448418870375545023e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015658451970986107e+02,7.279725703479537060e+02,5.125157320072148970e-01,1.100000010988609489e+01,2.446959016360167848e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015667542879986200e+02,7.279825703476543595e+02,5.125181789662068832e-01,1.100000010988609489e+01,2.445499162344790672e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015676633788986294e+02,7.279925703473553540e+02,5.125206244653448540e-01,1.100000010988609489e+01,2.444039308329413497e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015685724697986387e+02,7.280025703470566896e+02,5.125230685046288093e-01,1.100000010988609489e+01,2.442579454314036322e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015694815606986481e+02,7.280125703467583662e+02,5.125255110840588602e-01,1.100000010988609489e+01,2.441119600298659147e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015703906515986574e+02,7.280225703464603839e+02,5.125279522036348956e-01,1.100000010988609489e+01,2.439659746283281971e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015712997424986668e+02,7.280325703461627427e+02,5.125303918633570266e-01,1.100000010988609489e+01,2.438199892267904796e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015722088333986761e+02,7.280425703458655562e+02,5.125328300632251421e-01,1.100000010988609489e+01,2.436740038252527621e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015731179242986855e+02,7.280525703455687108e+02,5.125352668032392423e-01,1.100000010988609489e+01,2.435280184237150446e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015740270151986948e+02,7.280625703452722064e+02,5.125377020833994379e-01,1.100000010988609489e+01,2.433820330221773270e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015749361060987042e+02,7.280725703449760431e+02,5.125401359037056181e-01,1.100000010988609489e+01,2.432360476206396095e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015758451969987135e+02,7.280825703446802208e+02,5.125425682641578939e-01,1.100000010988609489e+01,2.430900622191018920e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015767542878987229e+02,7.280925703443847397e+02,5.125449991647561543e-01,1.100000010988609489e+01,2.429440768175641745e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015776633787987322e+02,7.281025703440895995e+02,5.125474286055003992e-01,1.100000010988609489e+01,2.427980914160264569e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015785724696987415e+02,7.281125703437948005e+02,5.125498565863907396e-01,1.100000010988609489e+01,2.426521060144887394e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015794815605987509e+02,7.281225703435004561e+02,5.125522831074270647e-01,1.100000010988609489e+01,2.425061206129510219e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015803906514987602e+02,7.281325703432064529e+02,5.125547081686093742e-01,1.100000010988609489e+01,2.423601352114133044e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015812997423987696e+02,7.281425703429127907e+02,5.125571317699377794e-01,1.100000010988609489e+01,2.422141498098755868e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015822088332987789e+02,7.281525703426194696e+02,5.125595539114121690e-01,1.100000010988609489e+01,2.420681644083378693e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015831179241987883e+02,7.281625703423264895e+02,5.125619745930326543e-01,1.100000010988609489e+01,2.419221790068001518e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015840270150987976e+02,7.281725703420338505e+02,5.125643938147991241e-01,1.100000010988609489e+01,2.417761936052624343e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015849361059988070e+02,7.281825703417415525e+02,5.125668115767115784e-01,1.100000010988609489e+01,2.416302082037247168e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015858451968988163e+02,7.281925703414495956e+02,5.125692278787701284e-01,1.100000010988609489e+01,2.414842228021869992e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015867542877988257e+02,7.282025703411579798e+02,5.125716427209746628e-01,1.100000010988609489e+01,2.413382374006492817e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015876633786988350e+02,7.282125703408667050e+02,5.125740561033252929e-01,1.100000010988609489e+01,2.411922519991115642e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015885724695988444e+02,7.282225703405758850e+02,5.125764680258219075e-01,1.100000010988609489e+01,2.410462665975738467e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015894815604988537e+02,7.282325703402854060e+02,5.125788784884645066e-01,1.100000010988609489e+01,2.409002811960361291e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015903906513988630e+02,7.282425703399952681e+02,5.125812874912532013e-01,1.100000010988609489e+01,2.407542957944984116e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015912997422988724e+02,7.282525703397054713e+02,5.125836950341878806e-01,1.100000010988609489e+01,2.406083103929606941e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015922088331988817e+02,7.282625703394160155e+02,5.125861011172685444e-01,1.100000010988609489e+01,2.404623249914229766e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015931179240988911e+02,7.282725703391269008e+02,5.125885057404953038e-01,1.100000010988609489e+01,2.403163395898852590e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015940270149989004e+02,7.282825703388381271e+02,5.125909089038680477e-01,1.100000010988609489e+01,2.401703541883475415e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015949361058989098e+02,7.282925703385496945e+02,5.125933106073868872e-01,1.100000010988609489e+01,2.400243687868098240e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015958451967989191e+02,7.283025703382616030e+02,5.125957108510517113e-01,1.100000010988609489e+01,2.398783833852721065e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015967542876989285e+02,7.283125703379738525e+02,5.125981096348625199e-01,1.100000010988609489e+01,2.397323979837343889e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015976633785989378e+02,7.283225703376864431e+02,5.126005069588194241e-01,1.100000010988609489e+01,2.395864125821966714e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015985724694989472e+02,7.283325703373994884e+02,5.126029028229223128e-01,1.100000010988609489e+01,2.394404271806589539e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.015994815603989565e+02,7.283425703371128748e+02,5.126052972271711861e-01,1.100000010988609489e+01,2.392944417791212364e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016003906512989658e+02,7.283525703368266022e+02,5.126076901715661549e-01,1.100000010988609489e+01,2.391484563775835188e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016012997421989752e+02,7.283625703365406707e+02,5.126100816561071083e-01,1.100000010988609489e+01,2.390024709760458013e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016022088330989845e+02,7.283725703362550803e+02,5.126124716807941573e-01,1.100000010988609489e+01,2.388564855745080838e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016031179239989939e+02,7.283825703359698309e+02,5.126148602456271908e-01,1.100000010988609489e+01,2.387105001729703663e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016040270148990032e+02,7.283925703356849226e+02,5.126172473506062088e-01,1.100000010988609489e+01,2.385645147714326487e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016049361057990126e+02,7.284025703354003554e+02,5.126196329957313225e-01,1.100000010988609489e+01,2.384185293698949312e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016058451966990219e+02,7.284125703351161292e+02,5.126220171810024206e-01,1.100000010988609489e+01,2.382725439683572137e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016067542875990313e+02,7.284225703348322440e+02,5.126243999064195034e-01,1.100000010988609489e+01,2.381265585668194962e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016076633784990406e+02,7.284325703345487000e+02,5.126267811719826817e-01,1.100000010988609489e+01,2.379805731652817787e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016085724693990500e+02,7.284425703342654970e+02,5.126291609776918445e-01,1.100000010988609489e+01,2.378345877637440611e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016094815602990593e+02,7.284525703339826350e+02,5.126315393235471030e-01,1.100000010988609489e+01,2.376886023622063436e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016103906511990687e+02,7.284625703337001141e+02,5.126339162095483459e-01,1.100000010988609489e+01,2.375426169606686261e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016112997420990780e+02,7.284725703334179343e+02,5.126362916356955735e-01,1.100000010988609489e+01,2.373966315591309086e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016122088329990873e+02,7.284825703331360955e+02,5.126386656019888965e-01,1.100000010988609489e+01,2.372506461575931910e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016131179238990967e+02,7.284925703328547115e+02,5.126410381084282042e-01,1.100000010988609489e+01,2.371046607560554735e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016140270147991060e+02,7.285025703325736686e+02,5.126434091550134964e-01,1.100000010988609489e+01,2.369586753545177560e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016149361056991154e+02,7.285125703322929667e+02,5.126457787417448841e-01,1.100000010988609489e+01,2.368126899529800385e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016158451965991247e+02,7.285225703320126058e+02,5.126481468686222565e-01,1.100000010988609489e+01,2.366667045514423209e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016167542874991341e+02,7.285325703317325861e+02,5.126505135356457243e-01,1.100000010988609489e+01,2.365207191499046034e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016176633783991434e+02,7.285425703314529073e+02,5.126528787428151768e-01,1.100000010988609489e+01,2.363747337483668859e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016185724692991528e+02,7.285525703311735697e+02,5.126552424901306138e-01,1.100000010988609489e+01,2.362287483468291684e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016194815601991621e+02,7.285625703308945731e+02,5.126576047775921463e-01,1.100000010988609489e+01,2.360827629452914508e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016203906510991715e+02,7.285725703306159176e+02,5.126599656051996634e-01,1.100000010988609489e+01,2.359367775437537333e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016212997419991808e+02,7.285825703303376031e+02,5.126623249729531651e-01,1.100000010988609489e+01,2.357907921422160158e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016222088328991902e+02,7.285925703300596297e+02,5.126646828808527623e-01,1.100000010988609489e+01,2.356448067406782983e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016231179237991995e+02,7.286025703297819973e+02,5.126670393288983441e-01,1.100000010988609489e+01,2.354988213391405807e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016240270146992088e+02,7.286125703295047060e+02,5.126693943170900214e-01,1.100000010988609489e+01,2.353528359376028632e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016249361055992182e+02,7.286225703292277558e+02,5.126717478454276833e-01,1.100000010988609489e+01,2.352068505360651457e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016258451964992275e+02,7.286325703289511466e+02,5.126740999139113297e-01,1.100000010988609489e+01,2.350608651345274282e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016267542873992369e+02,7.286425703286748785e+02,5.126764505225410717e-01,1.100000010988609489e+01,2.349148797329897106e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016276633782992462e+02,7.286525703283989515e+02,5.126787996713167983e-01,1.100000010988609489e+01,2.347688943314519931e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016285724691992556e+02,7.286625703281233655e+02,5.126811473602385094e-01,1.100000010988609489e+01,2.346229089299142756e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016294815600992649e+02,7.286725703278481205e+02,5.126834935893063161e-01,1.100000010988609489e+01,2.344769235283765581e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016303906509992743e+02,7.286825703275732167e+02,5.126858383585201073e-01,1.100000010988609489e+01,2.343309381268388406e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016312997418992836e+02,7.286925703272986539e+02,5.126881816678798831e-01,1.100000010988609489e+01,2.341849527253011230e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016322088327992930e+02,7.287025703270244321e+02,5.126905235173857545e-01,1.100000010988609489e+01,2.340389673237634055e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016331179236993023e+02,7.287125703267505514e+02,5.126928639070376104e-01,1.100000010988609489e+01,2.338929819222256880e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016340270145993117e+02,7.287225703264770118e+02,5.126952028368355618e-01,1.100000010988609489e+01,2.337469965206879705e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016349361054993210e+02,7.287325703262038132e+02,5.126975403067794979e-01,1.100000010988609489e+01,2.336010111191502529e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016358451963993303e+02,7.287425703259309557e+02,5.126998763168694184e-01,1.100000010988609489e+01,2.334550257176125354e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016367542872993397e+02,7.287525703256584393e+02,5.127022108671054346e-01,1.100000010988609489e+01,2.333090403160748179e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016376633781993490e+02,7.287625703253862639e+02,5.127045439574874353e-01,1.100000010988609489e+01,2.331630549145371004e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016385724690993584e+02,7.287725703251144296e+02,5.127068755880154205e-01,1.100000010988609489e+01,2.330170695129993828e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016394815599993677e+02,7.287825703248429363e+02,5.127092057586895013e-01,1.100000010988609489e+01,2.328710841114616653e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016403906508993771e+02,7.287925703245717841e+02,5.127115344695095667e-01,1.100000010988609489e+01,2.327250987099239478e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016412997417993864e+02,7.288025703243009730e+02,5.127138617204756166e-01,1.100000010988609489e+01,2.325791133083862303e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016422088326993958e+02,7.288125703240305029e+02,5.127161875115877621e-01,1.100000010988609489e+01,2.324331279068485127e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016431179235994051e+02,7.288225703237603739e+02,5.127185118428458921e-01,1.100000010988609489e+01,2.322871425053107952e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016440270144994145e+02,7.288325703234905859e+02,5.127208347142500067e-01,1.100000010988609489e+01,2.321411571037730777e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016449361053994238e+02,7.288425703232211390e+02,5.127231561258002168e-01,1.100000010988609489e+01,2.319951717022353602e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016458451962994332e+02,7.288525703229520332e+02,5.127254760774964115e-01,1.100000010988609489e+01,2.318491863006976426e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016467542871994425e+02,7.288625703226832684e+02,5.127277945693387018e-01,1.100000010988609489e+01,2.317032008991599251e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016476633780994518e+02,7.288725703224148447e+02,5.127301116013269766e-01,1.100000010988609489e+01,2.315572154976222076e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016485724689994612e+02,7.288825703221467620e+02,5.127324271734612360e-01,1.100000010988609489e+01,2.314112300960844901e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016494815598994705e+02,7.288925703218790204e+02,5.127347412857415909e-01,1.100000010988609489e+01,2.312652446945467725e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016503906507994799e+02,7.289025703216116199e+02,5.127370539381679304e-01,1.100000010988609489e+01,2.311192592930090550e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016512997416994892e+02,7.289125703213445604e+02,5.127393651307402545e-01,1.100000010988609489e+01,2.309732738914713375e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016522088325994986e+02,7.289225703210778420e+02,5.127416748634586741e-01,1.100000010988609489e+01,2.308272884899336200e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016531179234995079e+02,7.289325703208114646e+02,5.127439831363230782e-01,1.100000010988609489e+01,2.306813030883959025e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016540270143995173e+02,7.289425703205454283e+02,5.127462899493334669e-01,1.100000010988609489e+01,2.305353176868581849e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016549361052995266e+02,7.289525703202797331e+02,5.127485953024899512e-01,1.100000010988609489e+01,2.303893322853204674e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016558451961995360e+02,7.289625703200143789e+02,5.127508991957924200e-01,1.100000010988609489e+01,2.302433468837827499e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016567542870995453e+02,7.289725703197493658e+02,5.127532016292408734e-01,1.100000010988609489e+01,2.300973614822450324e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016576633779995547e+02,7.289825703194846938e+02,5.127555026028354224e-01,1.100000010988609489e+01,2.299513760807073148e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016585724688995640e+02,7.289925703192202491e+02,5.127578021165759559e-01,1.100000010988609489e+01,2.298053906791695973e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016594815597995733e+02,7.290025703189561455e+02,5.127601001704624739e-01,1.100000010988609489e+01,2.296594052776318798e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016603906506995827e+02,7.290125703186923829e+02,5.127623967644950875e-01,1.100000010988609489e+01,2.295134198760941623e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016612997415995920e+02,7.290225703184289614e+02,5.127646918986736857e-01,1.100000010988609489e+01,2.293674344745564447e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016622088324996014e+02,7.290325703181658810e+02,5.127669855729982684e-01,1.100000010988609489e+01,2.292214490730187272e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016631179233996107e+02,7.290425703179031416e+02,5.127692777874689467e-01,1.100000010988609489e+01,2.290754636714810097e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016640270142996201e+02,7.290525703176407433e+02,5.127715685420856095e-01,1.100000010988609489e+01,2.289294782699432922e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016649361051996294e+02,7.290625703173786860e+02,5.127738578368483680e-01,1.100000010988609489e+01,2.287834928684055746e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016658451960996388e+02,7.290725703171169698e+02,5.127761456717571109e-01,1.100000010988609489e+01,2.286375074668678571e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016667542869996481e+02,7.290825703168555947e+02,5.127784320468118384e-01,1.100000010988609489e+01,2.284915220653301396e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016676633778996575e+02,7.290925703165945606e+02,5.127807169620126615e-01,1.100000010988609489e+01,2.283455366637924221e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016685724687996668e+02,7.291025703163338676e+02,5.127830004173594691e-01,1.100000010988609489e+01,2.281995512622547045e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016694815596996762e+02,7.291125703160735156e+02,5.127852824128522613e-01,1.100000010988609489e+01,2.280535658607169870e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016703906505996855e+02,7.291225703158135047e+02,5.127875629484911491e-01,1.100000010988609489e+01,2.279075804591792695e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016712997414996948e+02,7.291325703155538349e+02,5.127898420242760213e-01,1.100000010988609489e+01,2.277615950576415520e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016722088323997042e+02,7.291425703152945061e+02,5.127921196402068782e-01,1.100000010988609489e+01,2.276156096561038344e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016731179232997135e+02,7.291525703150355184e+02,5.127943957962838306e-01,1.100000010988609489e+01,2.274696242545661169e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016740270141997229e+02,7.291625703147767581e+02,5.127966704925067676e-01,1.100000010988609489e+01,2.273236388530283994e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016749361050997322e+02,7.291725703145183388e+02,5.127989437288756891e-01,1.100000010988609489e+01,2.271776534514906819e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016758451959997416e+02,7.291825703142602606e+02,5.128012155053907062e-01,1.100000010988609489e+01,2.270316680499529643e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016767542868997509e+02,7.291925703140025234e+02,5.128034858220517078e-01,1.100000010988609489e+01,2.268856826484152468e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016776633777997603e+02,7.292025703137451274e+02,5.128057546788586940e-01,1.100000010988609489e+01,2.267396972468775293e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016785724686997696e+02,7.292125703134880723e+02,5.128080220758117758e-01,1.100000010988609489e+01,2.265937118453398118e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016794815595997790e+02,7.292225703132313583e+02,5.128102880129108421e-01,1.100000010988609489e+01,2.264477264438020943e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016803906504997883e+02,7.292325703129749854e+02,5.128125524901558929e-01,1.100000010988609489e+01,2.263017410422643767e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016812997413997977e+02,7.292425703127189536e+02,5.128148155075470394e-01,1.100000010988609489e+01,2.261557556407266592e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016822088322998070e+02,7.292525703124632628e+02,5.128170770650841703e-01,1.100000010988609489e+01,2.260097702391889417e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016831179231998163e+02,7.292625703122079130e+02,5.128193371627672859e-01,1.100000010988609489e+01,2.258637848376512242e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016840270140998257e+02,7.292725703119527907e+02,5.128215958005964970e-01,1.100000010988609489e+01,2.257177994361135066e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016849361049998350e+02,7.292825703116980094e+02,5.128238529785716926e-01,1.100000010988609489e+01,2.255718140345757891e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016858451958998444e+02,7.292925703114435692e+02,5.128261086966928728e-01,1.100000010988609489e+01,2.254258286330380716e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016867542867998537e+02,7.293025703111894700e+02,5.128283629549601486e-01,1.100000010988609489e+01,2.252798432315003541e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016876633776998631e+02,7.293125703109357119e+02,5.128306157533734089e-01,1.100000010988609489e+01,2.251338578299626365e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016885724685998724e+02,7.293225703106822948e+02,5.128328670919326537e-01,1.100000010988609489e+01,2.249878724284249190e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016894815594998818e+02,7.293325703104292188e+02,5.128351169706379942e-01,1.100000010988609489e+01,2.248418870268872015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016903906503998911e+02,7.293425703101764839e+02,5.128373653894893192e-01,1.100000010988609489e+01,2.246959016253494840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016912997412999005e+02,7.293525703099240900e+02,5.128396123484866287e-01,1.100000010988609489e+01,2.245499162238117664e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016922088321999098e+02,7.293625703096719235e+02,5.128418578476300338e-01,1.100000010988609489e+01,2.244039308222740489e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016931179230999192e+02,7.293725703094200981e+02,5.128441018869194234e-01,1.100000010988609489e+01,2.242579454207363314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016940270139999285e+02,7.293825703091686137e+02,5.128463444663547977e-01,1.100000010988609489e+01,2.241119600191986139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016949361048999378e+02,7.293925703089174704e+02,5.128485855859362674e-01,1.100000010988609489e+01,2.239659746176608963e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016958451957999472e+02,7.294025703086666681e+02,5.128508252456637218e-01,1.100000010988609489e+01,2.238199892161231788e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016967542866999565e+02,7.294125703084162069e+02,5.128530634455371606e-01,1.100000010988609489e+01,2.236740038145854613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016976633775999659e+02,7.294225703081660868e+02,5.128553001855566951e-01,1.100000010988609489e+01,2.235280184130477438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016985724684999752e+02,7.294325703079163077e+02,5.128575354657222141e-01,1.100000010988609489e+01,2.233820330115100262e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.016994815593999846e+02,7.294425703076667560e+02,5.128597692860337176e-01,1.100000010988609489e+01,2.232360476099723087e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017003906502999939e+02,7.294525703074175453e+02,5.128620016464913167e-01,1.100000010988609489e+01,2.230900622084345912e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017012997412000033e+02,7.294625703071686758e+02,5.128642325470949004e-01,1.100000010988609489e+01,2.229440768068968737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017022088321000126e+02,7.294725703069201472e+02,5.128664619878444686e-01,1.100000010988609489e+01,2.227980914053591562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017031179230000220e+02,7.294825703066719598e+02,5.128686899687401324e-01,1.100000010988609489e+01,2.226521060038214386e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017040270139000313e+02,7.294925703064241134e+02,5.128709164897817807e-01,1.100000010988609489e+01,2.225061206022837211e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017049361048000407e+02,7.295025703061766080e+02,5.128731415509694136e-01,1.100000010988609489e+01,2.223601352007460036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017058451957000500e+02,7.295125703059294437e+02,5.128753651523031420e-01,1.100000010988609489e+01,2.222141497992082861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017067542866000593e+02,7.295225703056825068e+02,5.128775872937828550e-01,1.100000010988609489e+01,2.220681643976705685e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017076633775000687e+02,7.295325703054359110e+02,5.128798079754085526e-01,1.100000010988609489e+01,2.219221789961328510e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017085724684000780e+02,7.295425703051896562e+02,5.128820271971803457e-01,1.100000010988609489e+01,2.217761935945951335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017094815593000874e+02,7.295525703049437425e+02,5.128842449590981234e-01,1.100000010988609489e+01,2.216302081930574160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017103906502000967e+02,7.295625703046981698e+02,5.128864612611618856e-01,1.100000010988609489e+01,2.214842227915196984e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017112997411001061e+02,7.295725703044529382e+02,5.128886761033717434e-01,1.100000010988609489e+01,2.213382373899819809e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017122088320001154e+02,7.295825703042079340e+02,5.128908894857275858e-01,1.100000010988609489e+01,2.211922519884442634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017131179229001248e+02,7.295925703039632708e+02,5.128931014082294126e-01,1.100000010988609489e+01,2.210462665869065459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017140270138001341e+02,7.296025703037189487e+02,5.128953118708773351e-01,1.100000010988609489e+01,2.209002811853688283e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017149361047001435e+02,7.296125703034749677e+02,5.128975208736712421e-01,1.100000010988609489e+01,2.207542957838311108e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017158451956001528e+02,7.296225703032313277e+02,5.128997284166111337e-01,1.100000010988609489e+01,2.206083103822933933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017167542865001622e+02,7.296325703029880287e+02,5.129019344996970098e-01,1.100000010988609489e+01,2.204623249807556758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017176633774001715e+02,7.296425703027449572e+02,5.129041391229289815e-01,1.100000010988609489e+01,2.203163395792179582e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017185724683001808e+02,7.296525703025022267e+02,5.129063422863069377e-01,1.100000010988609489e+01,2.201703541776802407e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017194815592001902e+02,7.296625703022598373e+02,5.129085439898308785e-01,1.100000010988609489e+01,2.200243687761425232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017203906501001995e+02,7.296725703020177889e+02,5.129107442335009148e-01,1.100000010988609489e+01,2.198783833746048057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017212997410002089e+02,7.296825703017760816e+02,5.129129430173169357e-01,1.100000010988609489e+01,2.197323979730670881e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017222088319002182e+02,7.296925703015347153e+02,5.129151403412789412e-01,1.100000010988609489e+01,2.195864125715293706e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017231179228002276e+02,7.297025703012935764e+02,5.129173362053870422e-01,1.100000010988609489e+01,2.194404271699916531e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017240270137002369e+02,7.297125703010527786e+02,5.129195306096411278e-01,1.100000010988609489e+01,2.192944417684539356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017249361046002463e+02,7.297225703008123219e+02,5.129217235540411979e-01,1.100000010988609489e+01,2.191484563669162181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017258451955002556e+02,7.297325703005722062e+02,5.129239150385873636e-01,1.100000010988609489e+01,2.190024709653785005e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017267542864002650e+02,7.297425703003324315e+02,5.129261050632795138e-01,1.100000010988609489e+01,2.188564855638407830e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017276633773002743e+02,7.297525703000928843e+02,5.129282936281176486e-01,1.100000010988609489e+01,2.187105001623030655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017285724682002837e+02,7.297625702998536781e+02,5.129304807331018790e-01,1.100000010988609489e+01,2.185645147607653480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017294815591002930e+02,7.297725702996148129e+02,5.129326663782320939e-01,1.100000010988609489e+01,2.184185293592276304e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017303906500003023e+02,7.297825702993762889e+02,5.129348505635082933e-01,1.100000010988609489e+01,2.182725439576899129e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017312997409003117e+02,7.297925702991381058e+02,5.129370332889305883e-01,1.100000010988609489e+01,2.181265585561521954e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017322088318003210e+02,7.298025702989002639e+02,5.129392145544988679e-01,1.100000010988609489e+01,2.179805731546144779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017331179227003304e+02,7.298125702986626493e+02,5.129413943602131321e-01,1.100000010988609489e+01,2.178345877530767603e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017340270136003397e+02,7.298225702984253758e+02,5.129435727060733807e-01,1.100000010988609489e+01,2.176886023515390428e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017349361045003491e+02,7.298325702981884433e+02,5.129457495920797250e-01,1.100000010988609489e+01,2.175426169500013253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017358451954003584e+02,7.298425702979518519e+02,5.129479250182320538e-01,1.100000010988609489e+01,2.173966315484636078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017367542863003678e+02,7.298525702977156016e+02,5.129500989845303671e-01,1.100000010988609489e+01,2.172506461469258902e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017376633772003771e+02,7.298625702974795786e+02,5.129522714909747760e-01,1.100000010988609489e+01,2.171046607453881727e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017385724681003865e+02,7.298725702972438967e+02,5.129544425375651695e-01,1.100000010988609489e+01,2.169586753438504552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017394815590003958e+02,7.298825702970085558e+02,5.129566121243015475e-01,1.100000010988609489e+01,2.168126899423127377e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017403906499004052e+02,7.298925702967735560e+02,5.129587802511840211e-01,1.100000010988609489e+01,2.166667045407750201e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017412997408004145e+02,7.299025702965387836e+02,5.129609469182124792e-01,1.100000010988609489e+01,2.165207191392373026e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017422088317004238e+02,7.299125702963043523e+02,5.129631121253869219e-01,1.100000010988609489e+01,2.163747337376995851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017431179226004332e+02,7.299225702960702620e+02,5.129652758727074602e-01,1.100000010988609489e+01,2.162287483361618676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017440270135004425e+02,7.299325702958365127e+02,5.129674381601739830e-01,1.100000010988609489e+01,2.160827629346241500e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017449361044004519e+02,7.299425702956031046e+02,5.129695989877864903e-01,1.100000010988609489e+01,2.159367775330864325e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017458451953004612e+02,7.299525702953699238e+02,5.129717583555450933e-01,1.100000010988609489e+01,2.157907921315487150e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017467542862004706e+02,7.299625702951370840e+02,5.129739162634496807e-01,1.100000010988609489e+01,2.156448067300109975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017476633771004799e+02,7.299725702949045854e+02,5.129760727115002528e-01,1.100000010988609489e+01,2.154988213284732800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017485724680004893e+02,7.299825702946724277e+02,5.129782276996968093e-01,1.100000010988609489e+01,2.153528359269355624e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017494815589004986e+02,7.299925702944404975e+02,5.129803812280394615e-01,1.100000010988609489e+01,2.152068505253978449e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017503906498005080e+02,7.300025702942089083e+02,5.129825332965280982e-01,1.100000010988609489e+01,2.150608651238601274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017512997407005173e+02,7.300125702939776602e+02,5.129846839051627194e-01,1.100000010988609489e+01,2.149148797223224099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017522088316005267e+02,7.300225702937467531e+02,5.129868330539434362e-01,1.100000010988609489e+01,2.147688943207846923e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017531179225005360e+02,7.300325702935160734e+02,5.129889807428701376e-01,1.100000010988609489e+01,2.146229089192469748e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017540270134005453e+02,7.300425702932857348e+02,5.129911269719428235e-01,1.100000010988609489e+01,2.144769235177092573e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017549361043005547e+02,7.300525702930557372e+02,5.129932717411616050e-01,1.100000010988609489e+01,2.143309381161715398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017558451952005640e+02,7.300625702928260807e+02,5.129954150505263710e-01,1.100000010988609489e+01,2.141849527146338222e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017567542861005734e+02,7.300725702925966516e+02,5.129975569000371216e-01,1.100000010988609489e+01,2.140389673130961047e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017576633770005827e+02,7.300825702923675635e+02,5.129996972896938567e-01,1.100000010988609489e+01,2.138929819115583872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017585724679005921e+02,7.300925702921388165e+02,5.130018362194966874e-01,1.100000010988609489e+01,2.137469965100206697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017594815588006014e+02,7.301025702919104106e+02,5.130039736894455027e-01,1.100000010988609489e+01,2.136010111084829521e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017603906497006108e+02,7.301125702916822320e+02,5.130061096995403025e-01,1.100000010988609489e+01,2.134550257069452346e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017612997406006201e+02,7.301225702914543945e+02,5.130082442497811979e-01,1.100000010988609489e+01,2.133090403054075171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017622088315006295e+02,7.301325702912268980e+02,5.130103773401680778e-01,1.100000010988609489e+01,2.131630549038697996e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017631179224006388e+02,7.301425702909997426e+02,5.130125089707009423e-01,1.100000010988609489e+01,2.130170695023320820e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017640270133006482e+02,7.301525702907728146e+02,5.130146391413799023e-01,1.100000010988609489e+01,2.128710841007943645e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017649361042006575e+02,7.301625702905462276e+02,5.130167678522048469e-01,1.100000010988609489e+01,2.127250986992566470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017658451951006668e+02,7.301725702903199817e+02,5.130188951031757760e-01,1.100000010988609489e+01,2.125791132977189295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017667542860006762e+02,7.301825702900940769e+02,5.130210208942926897e-01,1.100000010988609489e+01,2.124331278961812119e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017676633769006855e+02,7.301925702898683994e+02,5.130231452255556990e-01,1.100000010988609489e+01,2.122871424946434944e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017685724678006949e+02,7.302025702896430630e+02,5.130252680969646928e-01,1.100000010988609489e+01,2.121411570931057769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017694815587007042e+02,7.302125702894180677e+02,5.130273895085196711e-01,1.100000010988609489e+01,2.119951716915680594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017703906496007136e+02,7.302225702891934134e+02,5.130295094602207451e-01,1.100000010988609489e+01,2.118491862900303419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017712997405007229e+02,7.302325702889689865e+02,5.130316279520678036e-01,1.100000010988609489e+01,2.117032008884926243e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017722088314007323e+02,7.302425702887449006e+02,5.130337449840608466e-01,1.100000010988609489e+01,2.115572154869549068e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017731179223007416e+02,7.302525702885211558e+02,5.130358605561999852e-01,1.100000010988609489e+01,2.114112300854171893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017740270132007510e+02,7.302625702882976384e+02,5.130379746684851083e-01,1.100000010988609489e+01,2.112652446838794718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017749361041007603e+02,7.302725702880744620e+02,5.130400873209162160e-01,1.100000010988609489e+01,2.111192592823417542e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017758451950007696e+02,7.302825702878516267e+02,5.130421985134933083e-01,1.100000010988609489e+01,2.109732738808040367e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017767542859007790e+02,7.302925702876291325e+02,5.130443082462164961e-01,1.100000010988609489e+01,2.108272884792663192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017776633768007883e+02,7.303025702874068656e+02,5.130464165190856685e-01,1.100000010988609489e+01,2.106813030777286017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017785724677007977e+02,7.303125702871849398e+02,5.130485233321008254e-01,1.100000010988609489e+01,2.105353176761908841e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017794815586008070e+02,7.303225702869633551e+02,5.130506286852620779e-01,1.100000010988609489e+01,2.103893322746531666e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017803906495008164e+02,7.303325702867419977e+02,5.130527325785693149e-01,1.100000010988609489e+01,2.102433468731154491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017812997404008257e+02,7.303425702865209814e+02,5.130548350120225365e-01,1.100000010988609489e+01,2.100973614715777316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017822088313008351e+02,7.303525702863003062e+02,5.130569359856217426e-01,1.100000010988609489e+01,2.099513760700400140e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017831179222008444e+02,7.303625702860798583e+02,5.130590354993670443e-01,1.100000010988609489e+01,2.098053906685022965e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017840270131008538e+02,7.303725702858597515e+02,5.130611335532583306e-01,1.100000010988609489e+01,2.096594052669645790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017849361040008631e+02,7.303825702856399857e+02,5.130632301472956014e-01,1.100000010988609489e+01,2.095134198654268615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017858451949008725e+02,7.303925702854205610e+02,5.130653252814789678e-01,1.100000010988609489e+01,2.093674344638891439e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017867542858008818e+02,7.304025702852013637e+02,5.130674189558083187e-01,1.100000010988609489e+01,2.092214490623514264e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017876633767008911e+02,7.304125702849825075e+02,5.130695111702836542e-01,1.100000010988609489e+01,2.090754636608137089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017885724676009005e+02,7.304225702847639923e+02,5.130716019249050852e-01,1.100000010988609489e+01,2.089294782592759914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017894815585009098e+02,7.304325702845457045e+02,5.130736912196725008e-01,1.100000010988609489e+01,2.087834928577382738e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017903906494009192e+02,7.304425702843277577e+02,5.130757790545859010e-01,1.100000010988609489e+01,2.086375074562005563e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017912997403009285e+02,7.304525702841101520e+02,5.130778654296452856e-01,1.100000010988609489e+01,2.084915220546628388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017922088312009379e+02,7.304625702838927737e+02,5.130799503448507659e-01,1.100000010988609489e+01,2.083455366531251213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017931179221009472e+02,7.304725702836757364e+02,5.130820338002022307e-01,1.100000010988609489e+01,2.081995512515874037e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017940270130009566e+02,7.304825702834590402e+02,5.130841157956996801e-01,1.100000010988609489e+01,2.080535658500496862e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017949361039009659e+02,7.304925702832425713e+02,5.130861963313432250e-01,1.100000010988609489e+01,2.079075804485119687e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017958451948009753e+02,7.305025702830264436e+02,5.130882754071327545e-01,1.100000010988609489e+01,2.077615950469742512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017967542857009846e+02,7.305125702828106569e+02,5.130903530230682685e-01,1.100000010988609489e+01,2.076156096454365337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017976633766009940e+02,7.305225702825950975e+02,5.130924291791497671e-01,1.100000010988609489e+01,2.074696242438988161e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017985724675010033e+02,7.305325702823798792e+02,5.130945038753773613e-01,1.100000010988609489e+01,2.073236388423610986e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.017994815584010126e+02,7.305425702821650020e+02,5.130965771117509400e-01,1.100000010988609489e+01,2.071776534408233811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018003906493010220e+02,7.305525702819503522e+02,5.130986488882705032e-01,1.100000010988609489e+01,2.070316680392856636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018012997402010313e+02,7.305625702817360434e+02,5.131007192049360510e-01,1.100000010988609489e+01,2.068856826377479460e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018022088311010407e+02,7.305725702815220757e+02,5.131027880617476944e-01,1.100000010988609489e+01,2.067396972362102285e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018031179220010500e+02,7.305825702813083353e+02,5.131048554587053223e-01,1.100000010988609489e+01,2.065937118346725110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018040270129010594e+02,7.305925702810949360e+02,5.131069213958089348e-01,1.100000010988609489e+01,2.064477264331347935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018049361038010687e+02,7.306025702808818778e+02,5.131089858730586428e-01,1.100000010988609489e+01,2.063017410315970759e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018058451947010781e+02,7.306125702806690470e+02,5.131110488904543354e-01,1.100000010988609489e+01,2.061557556300593584e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018067542856010874e+02,7.306225702804565572e+02,5.131131104479960126e-01,1.100000010988609489e+01,2.060097702285216409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018076633765010968e+02,7.306325702802444084e+02,5.131151705456836742e-01,1.100000010988609489e+01,2.058637848269839234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018085724674011061e+02,7.306425702800324871e+02,5.131172291835174315e-01,1.100000010988609489e+01,2.057177994254462058e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018094815583011155e+02,7.306525702798209068e+02,5.131192863614971733e-01,1.100000010988609489e+01,2.055718140239084883e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018103906492011248e+02,7.306625702796095538e+02,5.131213420796228997e-01,1.100000010988609489e+01,2.054258286223707708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018112997401011341e+02,7.306725702793985420e+02,5.131233963378947216e-01,1.100000010988609489e+01,2.052798432208330533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018122088310011435e+02,7.306825702791878712e+02,5.131254491363125281e-01,1.100000010988609489e+01,2.051338578192953357e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018131179219011528e+02,7.306925702789774277e+02,5.131275004748763191e-01,1.100000010988609489e+01,2.049878724177576182e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018140270128011622e+02,7.307025702787673254e+02,5.131295503535860947e-01,1.100000010988609489e+01,2.048418870162199007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018149361037011715e+02,7.307125702785575641e+02,5.131315987724419658e-01,1.100000010988609489e+01,2.046959016146821832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018158451946011809e+02,7.307225702783480301e+02,5.131336457314438215e-01,1.100000010988609489e+01,2.045499162131444656e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018167542855011902e+02,7.307325702781388372e+02,5.131356912305916618e-01,1.100000010988609489e+01,2.044039308116067481e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018176633764011996e+02,7.307425702779299854e+02,5.131377352698855976e-01,1.100000010988609489e+01,2.042579454100690306e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018185724673012089e+02,7.307525702777213610e+02,5.131397778493255180e-01,1.100000010988609489e+01,2.041119600085313131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018194815582012183e+02,7.307625702775130776e+02,5.131418189689114229e-01,1.100000010988609489e+01,2.039659746069935956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018203906491012276e+02,7.307725702773050216e+02,5.131438586286433123e-01,1.100000010988609489e+01,2.038199892054558780e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018212997400012370e+02,7.307825702770973066e+02,5.131458968285212974e-01,1.100000010988609489e+01,2.036740038039181605e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018222088309012463e+02,7.307925702768899328e+02,5.131479335685452670e-01,1.100000010988609489e+01,2.035280184023804430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018231179218012556e+02,7.308025702766827862e+02,5.131499688487152211e-01,1.100000010988609489e+01,2.033820330008427255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018240270127012650e+02,7.308125702764759808e+02,5.131520026690311598e-01,1.100000010988609489e+01,2.032360475993050079e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018249361036012743e+02,7.308225702762694027e+02,5.131540350294931940e-01,1.100000010988609489e+01,2.030900621977672904e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018258451945012837e+02,7.308325702760631657e+02,5.131560659301012128e-01,1.100000010988609489e+01,2.029440767962295729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018267542854012930e+02,7.308425702758572697e+02,5.131580953708552162e-01,1.100000010988609489e+01,2.027980913946918554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018276633763013024e+02,7.308525702756516012e+02,5.131601233517553151e-01,1.100000010988609489e+01,2.026521059931541378e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018285724672013117e+02,7.308625702754462736e+02,5.131621498728013986e-01,1.100000010988609489e+01,2.025061205916164203e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018294815581013211e+02,7.308725702752411735e+02,5.131641749339934666e-01,1.100000010988609489e+01,2.023601351900787028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018303906490013304e+02,7.308825702750364144e+02,5.131661985353315192e-01,1.100000010988609489e+01,2.022141497885409853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018312997399013398e+02,7.308925702748319964e+02,5.131682206768156673e-01,1.100000010988609489e+01,2.020681643870032677e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018322088308013491e+02,7.309025702746278057e+02,5.131702413584458000e-01,1.100000010988609489e+01,2.019221789854655502e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018331179217013585e+02,7.309125702744239561e+02,5.131722605802219173e-01,1.100000010988609489e+01,2.017761935839278327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018340270126013678e+02,7.309225702742203339e+02,5.131742783421440190e-01,1.100000010988609489e+01,2.016302081823901152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018349361035013771e+02,7.309325702740170527e+02,5.131762946442122164e-01,1.100000010988609489e+01,2.014842227808523976e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018358451944013865e+02,7.309425702738141126e+02,5.131783094864263983e-01,1.100000010988609489e+01,2.013382373793146801e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018367542853013958e+02,7.309525702736113999e+02,5.131803228687865648e-01,1.100000010988609489e+01,2.011922519777769626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018376633762014052e+02,7.309625702734090282e+02,5.131823347912927158e-01,1.100000010988609489e+01,2.010462665762392451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018385724671014145e+02,7.309725702732068839e+02,5.131843452539449624e-01,1.100000010988609489e+01,2.009002811747015275e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018394815580014239e+02,7.309825702730050807e+02,5.131863542567431935e-01,1.100000010988609489e+01,2.007542957731638100e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018403906489014332e+02,7.309925702728036185e+02,5.131883617996874092e-01,1.100000010988609489e+01,2.006083103716260925e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018412997398014426e+02,7.310025702726023837e+02,5.131903678827777204e-01,1.100000010988609489e+01,2.004623249700883750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018422088307014519e+02,7.310125702724014900e+02,5.131923725060140162e-01,1.100000010988609489e+01,2.003163395685506575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018431179216014613e+02,7.310225702722008236e+02,5.131943756693962966e-01,1.100000010988609489e+01,2.001703541670129399e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018440270125014706e+02,7.310325702720004983e+02,5.131963773729245615e-01,1.100000010988609489e+01,2.000243687654752224e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018449361034014800e+02,7.310425702718004004e+02,5.131983776165989219e-01,1.100000010988609489e+01,1.998783833639375049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018458451943014893e+02,7.310525702716006435e+02,5.132003764004192670e-01,1.100000010988609489e+01,1.997323979623997874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018467542852014986e+02,7.310625702714012277e+02,5.132023737243855965e-01,1.100000010988609489e+01,1.995864125608620698e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018476633761015080e+02,7.310725702712020393e+02,5.132043695884979106e-01,1.100000010988609489e+01,1.994404271593243523e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018485724670015173e+02,7.310825702710031919e+02,5.132063639927563203e-01,1.100000010988609489e+01,1.992944417577866348e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018494815579015267e+02,7.310925702708045719e+02,5.132083569371607146e-01,1.100000010988609489e+01,1.991484563562489173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018503906488015360e+02,7.311025702706062930e+02,5.132103484217110934e-01,1.100000010988609489e+01,1.990024709547111997e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018512997397015454e+02,7.311125702704082414e+02,5.132123384464074567e-01,1.100000010988609489e+01,1.988564855531734822e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018522088306015547e+02,7.311225702702105309e+02,5.132143270112499156e-01,1.100000010988609489e+01,1.987105001516357647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018531179215015641e+02,7.311325702700130478e+02,5.132163141162383591e-01,1.100000010988609489e+01,1.985645147500980472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018540270124015734e+02,7.311425702698159057e+02,5.132182997613727871e-01,1.100000010988609489e+01,1.984185293485603296e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018549361033015828e+02,7.311525702696191047e+02,5.132202839466531996e-01,1.100000010988609489e+01,1.982725439470226121e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018558451942015921e+02,7.311625702694225311e+02,5.132222666720797077e-01,1.100000010988609489e+01,1.981265585454848946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018567542851016015e+02,7.311725702692262985e+02,5.132242479376522004e-01,1.100000010988609489e+01,1.979805731439471771e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018576633760016108e+02,7.311825702690302933e+02,5.132262277433706776e-01,1.100000010988609489e+01,1.978345877424094595e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018585724669016201e+02,7.311925702688346291e+02,5.132282060892352504e-01,1.100000010988609489e+01,1.976886023408717420e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018594815578016295e+02,7.312025702686391924e+02,5.132301829752458078e-01,1.100000010988609489e+01,1.975426169393340245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018603906487016388e+02,7.312125702684440967e+02,5.132321584014023497e-01,1.100000010988609489e+01,1.973966315377963070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018612997396016482e+02,7.312225702682492283e+02,5.132341323677048761e-01,1.100000010988609489e+01,1.972506461362585894e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018622088305016575e+02,7.312325702680547010e+02,5.132361048741534981e-01,1.100000010988609489e+01,1.971046607347208719e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018631179214016669e+02,7.312425702678604011e+02,5.132380759207481047e-01,1.100000010988609489e+01,1.969586753331831544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018640270123016762e+02,7.312525702676664423e+02,5.132400455074886958e-01,1.100000010988609489e+01,1.968126899316454369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018649361032016856e+02,7.312625702674727108e+02,5.132420136343752715e-01,1.100000010988609489e+01,1.966667045301077194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018658451941016949e+02,7.312725702672793204e+02,5.132439803014079427e-01,1.100000010988609489e+01,1.965207191285700018e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018667542850017043e+02,7.312825702670862711e+02,5.132459455085865985e-01,1.100000010988609489e+01,1.963747337270322843e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018676633759017136e+02,7.312925702668934491e+02,5.132479092559112388e-01,1.100000010988609489e+01,1.962287483254945668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018685724668017230e+02,7.313025702667009682e+02,5.132498715433818637e-01,1.100000010988609489e+01,1.960827629239568493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018694815577017323e+02,7.313125702665087147e+02,5.132518323709985841e-01,1.100000010988609489e+01,1.959367775224191317e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018703906486017416e+02,7.313225702663168022e+02,5.132537917387612891e-01,1.100000010988609489e+01,1.957907921208814142e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018712997395017510e+02,7.313325702661251171e+02,5.132557496466699787e-01,1.100000010988609489e+01,1.956448067193436967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018722088304017603e+02,7.313425702659337730e+02,5.132577060947246528e-01,1.100000010988609489e+01,1.954988213178059792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018731179213017697e+02,7.313525702657426564e+02,5.132596610829254224e-01,1.100000010988609489e+01,1.953528359162682616e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018740270122017790e+02,7.313625702655518808e+02,5.132616146112721767e-01,1.100000010988609489e+01,1.952068505147305441e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018749361031017884e+02,7.313725702653613325e+02,5.132635666797649154e-01,1.100000010988609489e+01,1.950608651131928266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018758451940017977e+02,7.313825702651711254e+02,5.132655172884036388e-01,1.100000010988609489e+01,1.949148797116551091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018767542849018071e+02,7.313925702649811456e+02,5.132674664371884576e-01,1.100000010988609489e+01,1.947688943101173915e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018776633758018164e+02,7.314025702647915068e+02,5.132694141261192611e-01,1.100000010988609489e+01,1.946229089085796740e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018785724667018258e+02,7.314125702646020954e+02,5.132713603551960491e-01,1.100000010988609489e+01,1.944769235070419565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018794815576018351e+02,7.314225702644130251e+02,5.132733051244188216e-01,1.100000010988609489e+01,1.943309381055042390e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018803906485018445e+02,7.314325702642241822e+02,5.132752484337876897e-01,1.100000010988609489e+01,1.941849527039665214e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018812997394018538e+02,7.314425702640356803e+02,5.132771902833025424e-01,1.100000010988609489e+01,1.940389673024288039e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018822088303018631e+02,7.314525702638474058e+02,5.132791306729633796e-01,1.100000010988609489e+01,1.938929819008910864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018831179212018725e+02,7.314625702636594724e+02,5.132810696027702013e-01,1.100000010988609489e+01,1.937469964993533689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018840270121018818e+02,7.314725702634717663e+02,5.132830070727231186e-01,1.100000010988609489e+01,1.936010110978156513e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018849361030018912e+02,7.314825702632844013e+02,5.132849430828220205e-01,1.100000010988609489e+01,1.934550256962779338e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018858451939019005e+02,7.314925702630972637e+02,5.132868776330669069e-01,1.100000010988609489e+01,1.933090402947402163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018867542848019099e+02,7.315025702629104671e+02,5.132888107234577779e-01,1.100000010988609489e+01,1.931630548932024988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018876633757019192e+02,7.315125702627238979e+02,5.132907423539947445e-01,1.100000010988609489e+01,1.930170694916647813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018885724666019286e+02,7.315225702625376698e+02,5.132926725246776956e-01,1.100000010988609489e+01,1.928710840901270637e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018894815575019379e+02,7.315325702623516690e+02,5.132946012355066312e-01,1.100000010988609489e+01,1.927250986885893462e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018903906484019473e+02,7.315425702621660093e+02,5.132965284864815514e-01,1.100000010988609489e+01,1.925791132870516287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018912997393019566e+02,7.315525702619805770e+02,5.132984542776025672e-01,1.100000010988609489e+01,1.924331278855139112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018922088302019660e+02,7.315625702617953721e+02,5.133003786088695675e-01,1.100000010988609489e+01,1.922871424839761936e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018931179211019753e+02,7.315725702616105082e+02,5.133023014802825523e-01,1.100000010988609489e+01,1.921411570824384761e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018940270120019846e+02,7.315825702614258716e+02,5.133042228918415217e-01,1.100000010988609489e+01,1.919951716809007586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018949361029019940e+02,7.315925702612415762e+02,5.133061428435465867e-01,1.100000010988609489e+01,1.918491862793630411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018958451938020033e+02,7.316025702610575081e+02,5.133080613353976362e-01,1.100000010988609489e+01,1.917032008778253235e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018967542847020127e+02,7.316125702608737811e+02,5.133099783673946703e-01,1.100000010988609489e+01,1.915572154762876060e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018976633756020220e+02,7.316225702606902814e+02,5.133118939395376890e-01,1.100000010988609489e+01,1.914112300747498885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018985724665020314e+02,7.316325702605071228e+02,5.133138080518268032e-01,1.100000010988609489e+01,1.912652446732121710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.018994815574020407e+02,7.316425702603241916e+02,5.133157207042619019e-01,1.100000010988609489e+01,1.911192592716744534e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019003906483020501e+02,7.316525702601416015e+02,5.133176318968429852e-01,1.100000010988609489e+01,1.909732738701367359e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019012997392020594e+02,7.316625702599592387e+02,5.133195416295700531e-01,1.100000010988609489e+01,1.908272884685990184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019022088301020688e+02,7.316725702597772170e+02,5.133214499024431055e-01,1.100000010988609489e+01,1.906813030670613009e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019031179210020781e+02,7.316825702595954226e+02,5.133233567154622534e-01,1.100000010988609489e+01,1.905353176655235833e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019040270119020875e+02,7.316925702594138556e+02,5.133252620686273859e-01,1.100000010988609489e+01,1.903893322639858658e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019049361028020968e+02,7.317025702592326297e+02,5.133271659619385030e-01,1.100000010988609489e+01,1.902433468624481483e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019058451937021061e+02,7.317125702590516312e+02,5.133290683953956046e-01,1.100000010988609489e+01,1.900973614609104308e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019067542846021155e+02,7.317225702588709737e+02,5.133309693689988018e-01,1.100000010988609489e+01,1.899513760593727132e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019076633755021248e+02,7.317325702586905436e+02,5.133328688827479835e-01,1.100000010988609489e+01,1.898053906578349957e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019085724664021342e+02,7.317425702585104546e+02,5.133347669366431498e-01,1.100000010988609489e+01,1.896594052562972782e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019094815573021435e+02,7.317525702583305929e+02,5.133366635306843007e-01,1.100000010988609489e+01,1.895134198547595607e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019103906482021529e+02,7.317625702581510723e+02,5.133385586648715471e-01,1.100000010988609489e+01,1.893674344532218431e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019112997391021622e+02,7.317725702579717790e+02,5.133404523392047780e-01,1.100000010988609489e+01,1.892214490516841256e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019122088300021716e+02,7.317825702577927132e+02,5.133423445536839935e-01,1.100000010988609489e+01,1.890754636501464081e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019131179209021809e+02,7.317925702576139884e+02,5.133442353083091936e-01,1.100000010988609489e+01,1.889294782486086906e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019140270118021903e+02,7.318025702574354909e+02,5.133461246030804892e-01,1.100000010988609489e+01,1.887834928470709731e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019149361027021996e+02,7.318125702572573346e+02,5.133480124379977694e-01,1.100000010988609489e+01,1.886375074455332555e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019158451936022090e+02,7.318225702570794056e+02,5.133498988130610341e-01,1.100000010988609489e+01,1.884915220439955380e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019167542845022183e+02,7.318325702569017039e+02,5.133517837282702834e-01,1.100000010988609489e+01,1.883455366424578205e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019176633754022276e+02,7.318425702567243434e+02,5.133536671836255172e-01,1.100000010988609489e+01,1.881995512409201030e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019185724663022370e+02,7.318525702565472102e+02,5.133555491791268466e-01,1.100000010988609489e+01,1.880535658393823854e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019194815572022463e+02,7.318625702563704181e+02,5.133574297147741605e-01,1.100000010988609489e+01,1.879075804378446679e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019203906481022557e+02,7.318725702561938533e+02,5.133593087905674590e-01,1.100000010988609489e+01,1.877615950363069504e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019212997390022650e+02,7.318825702560176296e+02,5.133611864065067421e-01,1.100000010988609489e+01,1.876156096347692329e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019222088299022744e+02,7.318925702558416333e+02,5.133630625625921207e-01,1.100000010988609489e+01,1.874696242332315153e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019231179208022837e+02,7.319025702556658644e+02,5.133649372588234838e-01,1.100000010988609489e+01,1.873236388316937978e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019240270117022931e+02,7.319125702554904365e+02,5.133668104952008315e-01,1.100000010988609489e+01,1.871776534301560803e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019249361026023024e+02,7.319225702553152360e+02,5.133686822717241638e-01,1.100000010988609489e+01,1.870316680286183628e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019258451935023118e+02,7.319325702551403765e+02,5.133705525883935916e-01,1.100000010988609489e+01,1.868856826270806452e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019267542844023211e+02,7.319425702549657444e+02,5.133724214452090040e-01,1.100000010988609489e+01,1.867396972255429277e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019276633753023305e+02,7.319525702547913397e+02,5.133742888421704009e-01,1.100000010988609489e+01,1.865937118240052102e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019285724662023398e+02,7.319625702546172761e+02,5.133761547792777824e-01,1.100000010988609489e+01,1.864477264224674927e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019294815571023491e+02,7.319725702544434398e+02,5.133780192565312595e-01,1.100000010988609489e+01,1.863017410209297751e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019303906480023585e+02,7.319825702542699446e+02,5.133798822739307210e-01,1.100000010988609489e+01,1.861557556193920576e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019312997389023678e+02,7.319925702540966768e+02,5.133817438314761672e-01,1.100000010988609489e+01,1.860097702178543401e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019322088298023772e+02,7.320025702539236363e+02,5.133836039291675979e-01,1.100000010988609489e+01,1.858637848163166226e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019331179207023865e+02,7.320125702537509369e+02,5.133854625670050131e-01,1.100000010988609489e+01,1.857177994147789050e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019340270116023959e+02,7.320225702535784649e+02,5.133873197449885240e-01,1.100000010988609489e+01,1.855718140132411875e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019349361025024052e+02,7.320325702534063339e+02,5.133891754631180193e-01,1.100000010988609489e+01,1.854258286117034700e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019358451934024146e+02,7.320425702532344303e+02,5.133910297213934992e-01,1.100000010988609489e+01,1.852798432101657525e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019367542843024239e+02,7.320525702530627541e+02,5.133928825198149637e-01,1.100000010988609489e+01,1.851338578086280350e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019376633752024333e+02,7.320625702528914189e+02,5.133947338583825237e-01,1.100000010988609489e+01,1.849878724070903174e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019385724661024426e+02,7.320725702527203111e+02,5.133965837370960683e-01,1.100000010988609489e+01,1.848418870055525999e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019394815570024520e+02,7.320825702525494307e+02,5.133984321559555974e-01,1.100000010988609489e+01,1.846959016040148824e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019403906479024613e+02,7.320925702523788914e+02,5.134002791149611111e-01,1.100000010988609489e+01,1.845499162024771649e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019412997388024706e+02,7.321025702522085794e+02,5.134021246141126094e-01,1.100000010988609489e+01,1.844039308009394473e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019422088297024800e+02,7.321125702520386085e+02,5.134039686534102032e-01,1.100000010988609489e+01,1.842579453994017298e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019431179206024893e+02,7.321225702518688649e+02,5.134058112328537815e-01,1.100000010988609489e+01,1.841119599978640123e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019440270115024987e+02,7.321325702516993488e+02,5.134076523524433444e-01,1.100000010988609489e+01,1.839659745963262948e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019449361024025080e+02,7.321425702515301737e+02,5.134094920121788919e-01,1.100000010988609489e+01,1.838199891947885772e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019458451933025174e+02,7.321525702513612259e+02,5.134113302120605349e-01,1.100000010988609489e+01,1.836740037932508597e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019467542842025267e+02,7.321625702511925056e+02,5.134131669520881625e-01,1.100000010988609489e+01,1.835280183917131422e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019476633751025361e+02,7.321725702510241263e+02,5.134150022322617746e-01,1.100000010988609489e+01,1.833820329901754247e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019485724660025454e+02,7.321825702508559743e+02,5.134168360525813712e-01,1.100000010988609489e+01,1.832360475886377071e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019494815569025548e+02,7.321925702506880498e+02,5.134186684130469525e-01,1.100000010988609489e+01,1.830900621870999896e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019503906478025641e+02,7.322025702505204663e+02,5.134204993136586292e-01,1.100000010988609489e+01,1.829440767855622721e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019512997387025734e+02,7.322125702503531102e+02,5.134223287544162906e-01,1.100000010988609489e+01,1.827980913840245546e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019522088296025828e+02,7.322225702501859814e+02,5.134241567353199365e-01,1.100000010988609489e+01,1.826521059824868370e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019531179205025921e+02,7.322325702500191937e+02,5.134259832563695669e-01,1.100000010988609489e+01,1.825061205809491195e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019540270114026015e+02,7.322425702498526334e+02,5.134278083175652929e-01,1.100000010988609489e+01,1.823601351794114020e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019549361023026108e+02,7.322525702496864142e+02,5.134296319189070035e-01,1.100000010988609489e+01,1.822141497778736845e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019558451932026202e+02,7.322625702495204223e+02,5.134314540603946986e-01,1.100000010988609489e+01,1.820681643763359669e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019567542841026295e+02,7.322725702493546578e+02,5.134332747420283782e-01,1.100000010988609489e+01,1.819221789747982494e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019576633750026389e+02,7.322825702491892343e+02,5.134350939638080424e-01,1.100000010988609489e+01,1.817761935732605319e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019585724659026482e+02,7.322925702490240383e+02,5.134369117257338022e-01,1.100000010988609489e+01,1.816302081717228144e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019594815568026576e+02,7.323025702488590696e+02,5.134387280278055465e-01,1.100000010988609489e+01,1.814842227701850969e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019603906477026669e+02,7.323125702486944419e+02,5.134405428700232754e-01,1.100000010988609489e+01,1.813382373686473793e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019612997386026763e+02,7.323225702485300417e+02,5.134423562523869888e-01,1.100000010988609489e+01,1.811922519671096618e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019622088295026856e+02,7.323325702483658688e+02,5.134441681748967978e-01,1.100000010988609489e+01,1.810462665655719443e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019631179204026949e+02,7.323425702482019233e+02,5.134459786375525914e-01,1.100000010988609489e+01,1.809002811640342268e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019640270113027043e+02,7.323525702480383188e+02,5.134477876403543695e-01,1.100000010988609489e+01,1.807542957624965092e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019649361022027136e+02,7.323625702478749417e+02,5.134495951833021321e-01,1.100000010988609489e+01,1.806083103609587917e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019658451931027230e+02,7.323725702477117920e+02,5.134514012663958793e-01,1.100000010988609489e+01,1.804623249594210742e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019667542840027323e+02,7.323825702475489834e+02,5.134532058896357221e-01,1.100000010988609489e+01,1.803163395578833567e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019676633749027417e+02,7.323925702473864021e+02,5.134550090530215494e-01,1.100000010988609489e+01,1.801703541563456391e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019685724658027510e+02,7.324025702472240482e+02,5.134568107565533612e-01,1.100000010988609489e+01,1.800243687548079216e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019694815567027604e+02,7.324125702470620354e+02,5.134586110002311576e-01,1.100000010988609489e+01,1.798783833532702041e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019703906476027697e+02,7.324225702469002499e+02,5.134604097840549386e-01,1.100000010988609489e+01,1.797323979517324866e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019712997385027791e+02,7.324325702467386918e+02,5.134622071080248151e-01,1.100000010988609489e+01,1.795864125501947690e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019722088294027884e+02,7.324425702465774748e+02,5.134640029721406762e-01,1.100000010988609489e+01,1.794404271486570515e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019731179203027978e+02,7.324525702464164851e+02,5.134657973764025218e-01,1.100000010988609489e+01,1.792944417471193340e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019740270112028071e+02,7.324625702462557229e+02,5.134675903208103520e-01,1.100000010988609489e+01,1.791484563455816165e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019749361021028164e+02,7.324725702460953016e+02,5.134693818053642778e-01,1.100000010988609489e+01,1.790024709440438989e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019758451930028258e+02,7.324825702459351078e+02,5.134711718300641881e-01,1.100000010988609489e+01,1.788564855425061814e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019767542839028351e+02,7.324925702457751413e+02,5.134729603949100829e-01,1.100000010988609489e+01,1.787105001409684639e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019776633748028445e+02,7.325025702456154022e+02,5.134747474999019623e-01,1.100000010988609489e+01,1.785645147394307464e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019785724657028538e+02,7.325125702454560042e+02,5.134765331450398262e-01,1.100000010988609489e+01,1.784185293378930288e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019794815566028632e+02,7.325225702452968335e+02,5.134783173303237858e-01,1.100000010988609489e+01,1.782725439363553113e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019803906475028725e+02,7.325325702451378902e+02,5.134801000557537298e-01,1.100000010988609489e+01,1.781265585348175938e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019812997384028819e+02,7.325425702449792880e+02,5.134818813213296584e-01,1.100000010988609489e+01,1.779805731332798763e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019822088293028912e+02,7.325525702448209131e+02,5.134836611270515716e-01,1.100000010988609489e+01,1.778345877317421588e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019831179202029006e+02,7.325625702446627656e+02,5.134854394729194693e-01,1.100000010988609489e+01,1.776886023302044412e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019840270111029099e+02,7.325725702445048455e+02,5.134872163589334626e-01,1.100000010988609489e+01,1.775426169286667237e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019849361020029193e+02,7.325825702443472665e+02,5.134889917850934404e-01,1.100000010988609489e+01,1.773966315271290062e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019858451929029286e+02,7.325925702441899148e+02,5.134907657513994028e-01,1.100000010988609489e+01,1.772506461255912887e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019867542838029379e+02,7.326025702440327905e+02,5.134925382578513497e-01,1.100000010988609489e+01,1.771046607240535711e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019876633747029473e+02,7.326125702438760072e+02,5.134943093044492812e-01,1.100000010988609489e+01,1.769586753225158536e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019885724656029566e+02,7.326225702437194514e+02,5.134960788911933083e-01,1.100000010988609489e+01,1.768126899209781361e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019894815565029660e+02,7.326325702435631229e+02,5.134978470180833199e-01,1.100000010988609489e+01,1.766667045194404186e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019903906474029753e+02,7.326425702434070217e+02,5.134996136851193160e-01,1.100000010988609489e+01,1.765207191179027010e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019912997383029847e+02,7.326525702432512617e+02,5.135013788923012967e-01,1.100000010988609489e+01,1.763747337163649835e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019922088292029940e+02,7.326625702430957290e+02,5.135031426396292620e-01,1.100000010988609489e+01,1.762287483148272660e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019931179201030034e+02,7.326725702429404237e+02,5.135049049271033228e-01,1.100000010988609489e+01,1.760827629132895485e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019940270110030127e+02,7.326825702427853457e+02,5.135066657547233682e-01,1.100000010988609489e+01,1.759367775117518309e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019949361019030221e+02,7.326925702426306088e+02,5.135084251224893981e-01,1.100000010988609489e+01,1.757907921102141134e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019958451928030314e+02,7.327025702424760993e+02,5.135101830304014126e-01,1.100000010988609489e+01,1.756448067086763959e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019967542837030408e+02,7.327125702423218172e+02,5.135119394784595226e-01,1.100000010988609489e+01,1.754988213071386784e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019976633746030501e+02,7.327225702421677624e+02,5.135136944666636172e-01,1.100000010988609489e+01,1.753528359056009608e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019985724655030594e+02,7.327325702420140487e+02,5.135154479950136963e-01,1.100000010988609489e+01,1.752068505040632433e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.019994815564030688e+02,7.327425702418605624e+02,5.135172000635097600e-01,1.100000010988609489e+01,1.750608651025255258e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020003906473030781e+02,7.327525702417073035e+02,5.135189506721518082e-01,1.100000010988609489e+01,1.749148797009878083e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020012997382030875e+02,7.327625702415542719e+02,5.135206998209399520e-01,1.100000010988609489e+01,1.747688942994500907e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020022088291030968e+02,7.327725702414015814e+02,5.135224475098740804e-01,1.100000010988609489e+01,1.746229088979123732e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020031179200031062e+02,7.327825702412491182e+02,5.135241937389541933e-01,1.100000010988609489e+01,1.744769234963746557e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020040270109031155e+02,7.327925702410968825e+02,5.135259385081802908e-01,1.100000010988609489e+01,1.743309380948369382e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020049361018031249e+02,7.328025702409448741e+02,5.135276818175523728e-01,1.100000010988609489e+01,1.741849526932992206e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020058451927031342e+02,7.328125702407932067e+02,5.135294236670705503e-01,1.100000010988609489e+01,1.740389672917615031e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020067542836031436e+02,7.328225702406417668e+02,5.135311640567347125e-01,1.100000010988609489e+01,1.738929818902237856e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020076633745031529e+02,7.328325702404905542e+02,5.135329029865448591e-01,1.100000010988609489e+01,1.737469964886860681e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020085724654031623e+02,7.328425702403395690e+02,5.135346404565009903e-01,1.100000010988609489e+01,1.736010110871483506e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020094815563031716e+02,7.328525702401889248e+02,5.135363764666031061e-01,1.100000010988609489e+01,1.734550256856106330e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020103906472031809e+02,7.328625702400385080e+02,5.135381110168513175e-01,1.100000010988609489e+01,1.733090402840729155e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020112997381031903e+02,7.328725702398883186e+02,5.135398441072455133e-01,1.100000010988609489e+01,1.731630548825351980e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020122088290031996e+02,7.328825702397383566e+02,5.135415757377856938e-01,1.100000010988609489e+01,1.730170694809974805e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020131179199032090e+02,7.328925702395887356e+02,5.135433059084718588e-01,1.100000010988609489e+01,1.728710840794597629e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020140270108032183e+02,7.329025702394393420e+02,5.135450346193040083e-01,1.100000010988609489e+01,1.727250986779220454e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020149361017032277e+02,7.329125702392901758e+02,5.135467618702822534e-01,1.100000010988609489e+01,1.725791132763843279e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020158451926032370e+02,7.329225702391412369e+02,5.135484876614064831e-01,1.100000010988609489e+01,1.724331278748466104e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020167542835032464e+02,7.329325702389925254e+02,5.135502119926766973e-01,1.100000010988609489e+01,1.722871424733088928e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020176633744032557e+02,7.329425702388441550e+02,5.135519348640928960e-01,1.100000010988609489e+01,1.721411570717711753e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020185724653032651e+02,7.329525702386960120e+02,5.135536562756550794e-01,1.100000010988609489e+01,1.719951716702334578e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020194815562032744e+02,7.329625702385480963e+02,5.135553762273632472e-01,1.100000010988609489e+01,1.718491862686957403e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020203906471032838e+02,7.329725702384004080e+02,5.135570947192175106e-01,1.100000010988609489e+01,1.717032008671580227e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020212997380032931e+02,7.329825702382529471e+02,5.135588117512177586e-01,1.100000010988609489e+01,1.715572154656203052e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020222088289033024e+02,7.329925702381058272e+02,5.135605273233639911e-01,1.100000010988609489e+01,1.714112300640825877e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020231179198033118e+02,7.330025702379589347e+02,5.135622414356562082e-01,1.100000010988609489e+01,1.712652446625448702e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020240270107033211e+02,7.330125702378122696e+02,5.135639540880944098e-01,1.100000010988609489e+01,1.711192592610071526e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020249361016033305e+02,7.330225702376658319e+02,5.135656652806787070e-01,1.100000010988609489e+01,1.709732738594694351e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020258451925033398e+02,7.330325702375196215e+02,5.135673750134089888e-01,1.100000010988609489e+01,1.708272884579317176e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020267542834033492e+02,7.330425702373737522e+02,5.135690832862852551e-01,1.100000010988609489e+01,1.706813030563940001e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020276633743033585e+02,7.330525702372281103e+02,5.135707900993075059e-01,1.100000010988609489e+01,1.705353176548562825e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020285724652033679e+02,7.330625702370826957e+02,5.135724954524757413e-01,1.100000010988609489e+01,1.703893322533185650e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020294815561033772e+02,7.330725702369375085e+02,5.135741993457900723e-01,1.100000010988609489e+01,1.702433468517808475e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020303906470033866e+02,7.330825702367925487e+02,5.135759017792503878e-01,1.100000010988609489e+01,1.700973614502431300e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020312997379033959e+02,7.330925702366479300e+02,5.135776027528566878e-01,1.100000010988609489e+01,1.699513760487054125e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020322088288034053e+02,7.331025702365035386e+02,5.135793022666089724e-01,1.100000010988609489e+01,1.698053906471676949e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020331179197034146e+02,7.331125702363593746e+02,5.135810003205072416e-01,1.100000010988609489e+01,1.696594052456299774e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020340270106034239e+02,7.331225702362154379e+02,5.135826969145516063e-01,1.100000010988609489e+01,1.695134198440922599e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020349361015034333e+02,7.331325702360717287e+02,5.135843920487419556e-01,1.100000010988609489e+01,1.693674344425545424e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020358451924034426e+02,7.331425702359282468e+02,5.135860857230782894e-01,1.100000010988609489e+01,1.692214490410168248e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020367542833034520e+02,7.331525702357851060e+02,5.135877779375606078e-01,1.100000010988609489e+01,1.690754636394791073e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020376633742034613e+02,7.331625702356421925e+02,5.135894686921889107e-01,1.100000010988609489e+01,1.689294782379413898e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020385724651034707e+02,7.331725702354995065e+02,5.135911579869633092e-01,1.100000010988609489e+01,1.687834928364036723e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020394815560034800e+02,7.331825702353570477e+02,5.135928458218836923e-01,1.100000010988609489e+01,1.686375074348659547e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020403906469034894e+02,7.331925702352148164e+02,5.135945321969500599e-01,1.100000010988609489e+01,1.684915220333282372e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020412997378034987e+02,7.332025702350729262e+02,5.135962171121624120e-01,1.100000010988609489e+01,1.683455366317905197e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020422088287035081e+02,7.332125702349312633e+02,5.135979005675207487e-01,1.100000010988609489e+01,1.681995512302528022e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020431179196035174e+02,7.332225702347898277e+02,5.135995825630250700e-01,1.100000010988609489e+01,1.680535658287150846e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020440270105035268e+02,7.332325702346486196e+02,5.136012630986754868e-01,1.100000010988609489e+01,1.679075804271773671e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020449361014035361e+02,7.332425702345076388e+02,5.136029421744718881e-01,1.100000010988609489e+01,1.677615950256396496e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020458451923035454e+02,7.332525702343668854e+02,5.136046197904142740e-01,1.100000010988609489e+01,1.676156096241019321e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020467542832035548e+02,7.332625702342263594e+02,5.136062959465026445e-01,1.100000010988609489e+01,1.674696242225642145e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020476633741035641e+02,7.332725702340861744e+02,5.136079706427369995e-01,1.100000010988609489e+01,1.673236388210264970e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020485724650035735e+02,7.332825702339462168e+02,5.136096438791174501e-01,1.100000010988609489e+01,1.671776534194887795e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020494815559035828e+02,7.332925702338064866e+02,5.136113156556438852e-01,1.100000010988609489e+01,1.670316680179510620e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020503906468035922e+02,7.333025702336669838e+02,5.136129859723163049e-01,1.100000010988609489e+01,1.668856826164133444e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020512997377036015e+02,7.333125702335277083e+02,5.136146548291347091e-01,1.100000010988609489e+01,1.667396972148756269e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020522088286036109e+02,7.333225702333886602e+02,5.136163222260990979e-01,1.100000010988609489e+01,1.665937118133379094e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020531179195036202e+02,7.333325702332498395e+02,5.136179881632094713e-01,1.100000010988609489e+01,1.664477264118001919e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020540270104036296e+02,7.333425702331113598e+02,5.136196526404659402e-01,1.100000010988609489e+01,1.663017410102624744e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020549361013036389e+02,7.333525702329731075e+02,5.136213156578683936e-01,1.100000010988609489e+01,1.661557556087247568e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020558451922036483e+02,7.333625702328350826e+02,5.136229772154168316e-01,1.100000010988609489e+01,1.660097702071870393e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020567542831036576e+02,7.333725702326972851e+02,5.136246373131112541e-01,1.100000010988609489e+01,1.658637848056493218e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020576633740036669e+02,7.333825702325597149e+02,5.136262959509516612e-01,1.100000010988609489e+01,1.657177994041116043e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020585724649036763e+02,7.333925702324223721e+02,5.136279531289381639e-01,1.100000010988609489e+01,1.655718140025738867e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020594815558036856e+02,7.334025702322852567e+02,5.136296088470706511e-01,1.100000010988609489e+01,1.654258286010361692e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020603906467036950e+02,7.334125702321484823e+02,5.136312631053491229e-01,1.100000010988609489e+01,1.652798431994984517e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020612997376037043e+02,7.334225702320119353e+02,5.136329159037735792e-01,1.100000010988609489e+01,1.651338577979607342e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020622088285037137e+02,7.334325702318756157e+02,5.136345672423440201e-01,1.100000010988609489e+01,1.649878723964230166e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020631179194037230e+02,7.334425702317395235e+02,5.136362171210604455e-01,1.100000010988609489e+01,1.648418869948852991e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020640270103037324e+02,7.334525702316036586e+02,5.136378655399229665e-01,1.100000010988609489e+01,1.646959015933475816e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020649361012037417e+02,7.334625702314680211e+02,5.136395124989314720e-01,1.100000010988609489e+01,1.645499161918098641e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020658451921037511e+02,7.334725702313326110e+02,5.136411579980859621e-01,1.100000010988609489e+01,1.644039307902721465e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020667542830037604e+02,7.334825702311974283e+02,5.136428020373864367e-01,1.100000010988609489e+01,1.642579453887344290e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020676633739037698e+02,7.334925702310624729e+02,5.136444446168328959e-01,1.100000010988609489e+01,1.641119599871967115e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020685724648037791e+02,7.335025702309278586e+02,5.136460857364254506e-01,1.100000010988609489e+01,1.639659745856589940e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020694815557037884e+02,7.335125702307934716e+02,5.136477253961639899e-01,1.100000010988609489e+01,1.638199891841212764e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020703906466037978e+02,7.335225702306593121e+02,5.136493635960485138e-01,1.100000010988609489e+01,1.636740037825835589e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020712997375038071e+02,7.335325702305253799e+02,5.136510003360790222e-01,1.100000010988609489e+01,1.635280183810458414e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020722088284038165e+02,7.335425702303916751e+02,5.136526356162555151e-01,1.100000010988609489e+01,1.633820329795081239e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020731179193038258e+02,7.335525702302581976e+02,5.136542694365779926e-01,1.100000010988609489e+01,1.632360475779704063e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020740270102038352e+02,7.335625702301249476e+02,5.136559017970465657e-01,1.100000010988609489e+01,1.630900621764326888e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020749361011038445e+02,7.335725702299919249e+02,5.136575326976611233e-01,1.100000010988609489e+01,1.629440767748949713e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020758451920038539e+02,7.335825702298591295e+02,5.136591621384216655e-01,1.100000010988609489e+01,1.627980913733572538e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020767542829038632e+02,7.335925702297265616e+02,5.136607901193281922e-01,1.100000010988609489e+01,1.626521059718195363e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020776633738038726e+02,7.336025702295943347e+02,5.136624166403807035e-01,1.100000010988609489e+01,1.625061205702818187e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020785724647038819e+02,7.336125702294623352e+02,5.136640417015791993e-01,1.100000010988609489e+01,1.623601351687441012e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020794815556038913e+02,7.336225702293305631e+02,5.136656653029237907e-01,1.100000010988609489e+01,1.622141497672063837e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020803906465039006e+02,7.336325702291990183e+02,5.136672874444143666e-01,1.100000010988609489e+01,1.620681643656686662e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020812997374039099e+02,7.336425702290677009e+02,5.136689081260509271e-01,1.100000010988609489e+01,1.619221789641309486e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020822088283039193e+02,7.336525702289366109e+02,5.136705273478334721e-01,1.100000010988609489e+01,1.617761935625932311e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020831179192039286e+02,7.336625702288057482e+02,5.136721451097620017e-01,1.100000010988609489e+01,1.616302081610555136e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020840270101039380e+02,7.336725702286751130e+02,5.136737614118366269e-01,1.100000010988609489e+01,1.614842227595177961e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020849361010039473e+02,7.336825702285447051e+02,5.136753762540572366e-01,1.100000010988609489e+01,1.613382373579800785e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020858451919039567e+02,7.336925702284145245e+02,5.136769896364238308e-01,1.100000010988609489e+01,1.611922519564423610e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020867542828039660e+02,7.337025702282845714e+02,5.136786015589364096e-01,1.100000010988609489e+01,1.610462665549046435e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020876633737039754e+02,7.337125702281548456e+02,5.136802120215949730e-01,1.100000010988609489e+01,1.609002811533669260e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020885724646039847e+02,7.337225702280253472e+02,5.136818210243995209e-01,1.100000010988609489e+01,1.607542957518292084e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020894815555039941e+02,7.337325702278961899e+02,5.136834285673501643e-01,1.100000010988609489e+01,1.606083103502914909e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020903906464040034e+02,7.337425702277672599e+02,5.136850346504467923e-01,1.100000010988609489e+01,1.604623249487537734e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020912997373040128e+02,7.337525702276385573e+02,5.136866392736894049e-01,1.100000010988609489e+01,1.603163395472160559e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020922088282040221e+02,7.337625702275100821e+02,5.136882424370780020e-01,1.100000010988609489e+01,1.601703541456783383e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020931179191040314e+02,7.337725702273818342e+02,5.136898441406125837e-01,1.100000010988609489e+01,1.600243687441406208e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020940270100040408e+02,7.337825702272538138e+02,5.136914443842931499e-01,1.100000010988609489e+01,1.598783833426029033e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020949361009040501e+02,7.337925702271260207e+02,5.136930431681198117e-01,1.100000010988609489e+01,1.597323979410651858e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020958451918040595e+02,7.338025702269984549e+02,5.136946404920924580e-01,1.100000010988609489e+01,1.595864125395274682e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020967542827040688e+02,7.338125702268711166e+02,5.136962363562110889e-01,1.100000010988609489e+01,1.594404271379897507e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020976633736040782e+02,7.338225702267440056e+02,5.136978307604757044e-01,1.100000010988609489e+01,1.592944417364520332e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020985724645040875e+02,7.338325702266171220e+02,5.136994237048863043e-01,1.100000010988609489e+01,1.591484563349143157e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.020994815554040969e+02,7.338425702264904658e+02,5.137010151894428889e-01,1.100000010988609489e+01,1.590024709333765982e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021003906463041062e+02,7.338525702263640369e+02,5.137026052141455690e-01,1.100000010988609489e+01,1.588564855318388806e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021012997372041156e+02,7.338625702262378354e+02,5.137041937789942336e-01,1.100000010988609489e+01,1.587105001303011631e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021022088281041249e+02,7.338725702261118613e+02,5.137057808839888828e-01,1.100000010988609489e+01,1.585645147287634456e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021031179190041343e+02,7.338825702259861146e+02,5.137073665291295166e-01,1.100000010988609489e+01,1.584185293272257281e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021040270099041436e+02,7.338925702258605952e+02,5.137089507144161349e-01,1.100000010988609489e+01,1.582725439256880105e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021049361008041529e+02,7.339025702257353032e+02,5.137105334398487377e-01,1.100000010988609489e+01,1.581265585241502930e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021058451917041623e+02,7.339125702256102386e+02,5.137121147054274362e-01,1.100000010988609489e+01,1.579805731226125755e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021067542826041716e+02,7.339225702254854014e+02,5.137136945111521191e-01,1.100000010988609489e+01,1.578345877210748580e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021076633735041810e+02,7.339325702253607915e+02,5.137152728570227866e-01,1.100000010988609489e+01,1.576886023195371404e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021085724644041903e+02,7.339425702252364090e+02,5.137168497430394387e-01,1.100000010988609489e+01,1.575426169179994229e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021094815553041997e+02,7.339525702251122539e+02,5.137184251692020753e-01,1.100000010988609489e+01,1.573966315164617054e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021103906462042090e+02,7.339625702249884398e+02,5.137199991355106965e-01,1.100000010988609489e+01,1.572506461149239879e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021112997371042184e+02,7.339725702248648531e+02,5.137215716419654132e-01,1.100000010988609489e+01,1.571046607133862703e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021122088280042277e+02,7.339825702247414938e+02,5.137231426885661145e-01,1.100000010988609489e+01,1.569586753118485528e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021131179189042371e+02,7.339925702246183619e+02,5.137247122753128004e-01,1.100000010988609489e+01,1.568126899103108353e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021140270098042464e+02,7.340025702244954573e+02,5.137262804022054707e-01,1.100000010988609489e+01,1.566667045087731178e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021149361007042558e+02,7.340125702243727801e+02,5.137278470692441257e-01,1.100000010988609489e+01,1.565207191072354002e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021158451916042651e+02,7.340225702242503303e+02,5.137294122764287652e-01,1.100000010988609489e+01,1.563747337056976827e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021167542825042744e+02,7.340325702241281078e+02,5.137309760237595002e-01,1.100000010988609489e+01,1.562287483041599652e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021176633734042838e+02,7.340425702240061128e+02,5.137325383112362198e-01,1.100000010988609489e+01,1.560827629026222477e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021185724643042931e+02,7.340525702238843451e+02,5.137340991388589240e-01,1.100000010988609489e+01,1.559367775010845301e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021194815552043025e+02,7.340625702237628047e+02,5.137356585066276127e-01,1.100000010988609489e+01,1.557907920995468126e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021203906461043118e+02,7.340725702236414918e+02,5.137372164145422859e-01,1.100000010988609489e+01,1.556448066980090951e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021212997370043212e+02,7.340825702235204062e+02,5.137387728626029437e-01,1.100000010988609489e+01,1.554988212964713776e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021222088279043305e+02,7.340925702233995480e+02,5.137403278508096971e-01,1.100000010988609489e+01,1.553528358949336600e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021231179188043399e+02,7.341025702232789172e+02,5.137418813791624350e-01,1.100000010988609489e+01,1.552068504933959425e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021240270097043492e+02,7.341125702231585137e+02,5.137434334476611575e-01,1.100000010988609489e+01,1.550608650918582250e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021249361006043586e+02,7.341225702230383376e+02,5.137449840563058645e-01,1.100000010988609489e+01,1.549148796903205075e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021258451915043679e+02,7.341325702229183889e+02,5.137465332050965561e-01,1.100000010988609489e+01,1.547688942887827900e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021267542824043772e+02,7.341425702227986676e+02,5.137480808940332322e-01,1.100000010988609489e+01,1.546229088872450724e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021276633733043866e+02,7.341525702226791736e+02,5.137496271231158929e-01,1.100000010988609489e+01,1.544769234857073549e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021285724642043959e+02,7.341625702225599071e+02,5.137511718923446491e-01,1.100000010988609489e+01,1.543309380841696374e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021294815551044053e+02,7.341725702224408678e+02,5.137527152017193899e-01,1.100000010988609489e+01,1.541849526826319199e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021303906460044146e+02,7.341825702223220560e+02,5.137542570512401152e-01,1.100000010988609489e+01,1.540389672810942023e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021312997369044240e+02,7.341925702222034715e+02,5.137557974409068251e-01,1.100000010988609489e+01,1.538929818795564848e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021322088278044333e+02,7.342025702220850008e+02,5.137573363707195195e-01,1.100000010988609489e+01,1.537469964780187673e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021331179187044427e+02,7.342125702219667573e+02,5.137588738406781985e-01,1.100000010988609489e+01,1.536010110764810498e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021340270096044520e+02,7.342225702218487413e+02,5.137604098507829731e-01,1.100000010988609489e+01,1.534550256749433322e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021349361005044614e+02,7.342325702217309527e+02,5.137619444010337322e-01,1.100000010988609489e+01,1.533090402734056147e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021358451914044707e+02,7.342425702216133914e+02,5.137634774914304758e-01,1.100000010988609489e+01,1.531630548718678972e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021367542823044801e+02,7.342525702214960575e+02,5.137650091219732040e-01,1.100000010988609489e+01,1.530170694703301797e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021376633732044894e+02,7.342625702213789509e+02,5.137665392926619168e-01,1.100000010988609489e+01,1.528710840687924621e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021385724641044987e+02,7.342725702212620718e+02,5.137680680034966141e-01,1.100000010988609489e+01,1.527250986672547446e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021394815550045081e+02,7.342825702211454200e+02,5.137695952544772959e-01,1.100000010988609489e+01,1.525791132657170271e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021403906459045174e+02,7.342925702210289955e+02,5.137711210456040734e-01,1.100000010988609489e+01,1.524331278641793096e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021412997368045268e+02,7.343025702209127985e+02,5.137726453768768353e-01,1.100000010988609489e+01,1.522871424626415920e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021422088277045361e+02,7.343125702207968288e+02,5.137741682482955818e-01,1.100000010988609489e+01,1.521411570611038745e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021431179186045455e+02,7.343225702206810865e+02,5.137756896598603129e-01,1.100000010988609489e+01,1.519951716595661570e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021440270095045548e+02,7.343325702205655716e+02,5.137772096115710285e-01,1.100000010988609489e+01,1.518491862580284395e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021449361004045642e+02,7.343425702204502841e+02,5.137787281034277287e-01,1.100000010988609489e+01,1.517032008564907219e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021458451913045735e+02,7.343525702203352239e+02,5.137802451354305244e-01,1.100000010988609489e+01,1.515572154549530044e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021467542822045829e+02,7.343625702202203911e+02,5.137817607075793047e-01,1.100000010988609489e+01,1.514112300534152869e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021476633731045922e+02,7.343725702201057857e+02,5.137832748198740695e-01,1.100000010988609489e+01,1.512652446518775694e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021485724640046016e+02,7.343825702199914076e+02,5.137847874723148189e-01,1.100000010988609489e+01,1.511192592503398519e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021494815549046109e+02,7.343925702198772569e+02,5.137862986649015529e-01,1.100000010988609489e+01,1.509732738488021343e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021503906458046202e+02,7.344025702197633336e+02,5.137878083976342714e-01,1.100000010988609489e+01,1.508272884472644168e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021512997367046296e+02,7.344125702196496377e+02,5.137893166705129744e-01,1.100000010988609489e+01,1.506813030457266993e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021522088276046389e+02,7.344225702195361691e+02,5.137908234835377730e-01,1.100000010988609489e+01,1.505353176441889818e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021531179185046483e+02,7.344325702194228143e+02,5.137923288367085561e-01,1.100000010988609489e+01,1.503893322426512642e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021540270094046576e+02,7.344425702193096868e+02,5.137938327300253238e-01,1.100000010988609489e+01,1.502433468411135467e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021549361003046670e+02,7.344525702191967866e+02,5.137953351634880761e-01,1.100000010988609489e+01,1.500973614395758292e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021558451912046763e+02,7.344625702190841139e+02,5.137968361370968129e-01,1.100000010988609489e+01,1.499513760380381117e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021567542821046857e+02,7.344725702189716685e+02,5.137983356508515342e-01,1.100000010988609489e+01,1.498053906365003941e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021576633730046950e+02,7.344825702188594505e+02,5.137998337047523512e-01,1.100000010988609489e+01,1.496594052349626766e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021585724639047044e+02,7.344925702187474599e+02,5.138013302987991526e-01,1.100000010988609489e+01,1.495134198334249591e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021594815548047137e+02,7.345025702186356966e+02,5.138028254329919386e-01,1.100000010988609489e+01,1.493674344318872416e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021603906457047231e+02,7.345125702185241607e+02,5.138043191073307092e-01,1.100000010988609489e+01,1.492214490303495240e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021612997366047324e+02,7.345225702184128522e+02,5.138058113218154643e-01,1.100000010988609489e+01,1.490754636288118065e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021622088275047417e+02,7.345325702183017711e+02,5.138073020764462040e-01,1.100000010988609489e+01,1.489294782272740890e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021631179184047511e+02,7.345425702181909173e+02,5.138087913712229282e-01,1.100000010988609489e+01,1.487834928257363715e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021640270093047604e+02,7.345525702180802909e+02,5.138102792061457480e-01,1.100000010988609489e+01,1.486375074241986539e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021649361002047698e+02,7.345625702179697782e+02,5.138117655812145523e-01,1.100000010988609489e+01,1.484915220226609364e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021658451911047791e+02,7.345725702178594929e+02,5.138132504964293412e-01,1.100000010988609489e+01,1.483455366211232189e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021667542820047885e+02,7.345825702177494350e+02,5.138147339517901147e-01,1.100000010988609489e+01,1.481995512195855014e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021676633729047978e+02,7.345925702176396044e+02,5.138162159472968726e-01,1.100000010988609489e+01,1.480535658180477838e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021685724638048072e+02,7.346025702175300012e+02,5.138176964829496152e-01,1.100000010988609489e+01,1.479075804165100663e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021694815547048165e+02,7.346125702174206253e+02,5.138191755587483422e-01,1.100000010988609489e+01,1.477615950149723488e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021703906456048259e+02,7.346225702173114769e+02,5.138206531746931649e-01,1.100000010988609489e+01,1.476156096134346313e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021712997365048352e+02,7.346325702172025558e+02,5.138221293307839721e-01,1.100000010988609489e+01,1.474696242118969138e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021722088274048446e+02,7.346425702170938621e+02,5.138236040270207639e-01,1.100000010988609489e+01,1.473236388103591962e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021731179183048539e+02,7.346525702169853957e+02,5.138250772634035402e-01,1.100000010988609489e+01,1.471776534088214787e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021740270092048632e+02,7.346625702168770431e+02,5.138265490399323010e-01,1.100000010988609489e+01,1.470316680072837612e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021749361001048726e+02,7.346725702167689178e+02,5.138280193566070464e-01,1.100000010988609489e+01,1.468856826057460437e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021758451910048819e+02,7.346825702166610199e+02,5.138294882134277763e-01,1.100000010988609489e+01,1.467396972042083261e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021767542819048913e+02,7.346925702165533494e+02,5.138309556103946019e-01,1.100000010988609489e+01,1.465937118026706086e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021776633728049006e+02,7.347025702164459062e+02,5.138324215475074119e-01,1.100000010988609489e+01,1.464477264011328911e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021785724637049100e+02,7.347125702163386904e+02,5.138338860247662065e-01,1.100000010988609489e+01,1.463017409995951736e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021794815546049193e+02,7.347225702162317020e+02,5.138353490421709857e-01,1.100000010988609489e+01,1.461557555980574560e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021803906455049287e+02,7.347325702161249410e+02,5.138368105997217494e-01,1.100000010988609489e+01,1.460097701965197385e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021812997364049380e+02,7.347425702160182936e+02,5.138382706974184977e-01,1.100000010988609489e+01,1.458637847949820210e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021822088273049474e+02,7.347525702159118737e+02,5.138397293352612305e-01,1.100000010988609489e+01,1.457177993934443035e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021831179182049567e+02,7.347625702158056811e+02,5.138411865132500589e-01,1.100000010988609489e+01,1.455718139919065859e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021840270091049661e+02,7.347725702156997158e+02,5.138426422313848718e-01,1.100000010988609489e+01,1.454258285903688684e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021849361000049754e+02,7.347825702155939780e+02,5.138440964896656693e-01,1.100000010988609489e+01,1.452798431888311509e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021858451909049847e+02,7.347925702154884675e+02,5.138455492880924513e-01,1.100000010988609489e+01,1.451338577872934334e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021867542818049941e+02,7.348025702153831844e+02,5.138470006266652179e-01,1.100000010988609489e+01,1.449878723857557158e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021876633727050034e+02,7.348125702152781287e+02,5.138484505053839690e-01,1.100000010988609489e+01,1.448418869842179983e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021885724636050128e+02,7.348225702151731866e+02,5.138498989242487047e-01,1.100000010988609489e+01,1.446959015826802808e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021894815545050221e+02,7.348325702150684720e+02,5.138513458832595360e-01,1.100000010988609489e+01,1.445499161811425633e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021903906454050315e+02,7.348425702149639847e+02,5.138527913824163518e-01,1.100000010988609489e+01,1.444039307796048457e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021912997363050408e+02,7.348525702148597247e+02,5.138542354217191521e-01,1.100000010988609489e+01,1.442579453780671282e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021922088272050502e+02,7.348625702147556922e+02,5.138556780011679370e-01,1.100000010988609489e+01,1.441119599765294107e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021931179181050595e+02,7.348725702146518870e+02,5.138571191207627065e-01,1.100000010988609489e+01,1.439659745749916932e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021940270090050689e+02,7.348825702145483092e+02,5.138585587805034605e-01,1.100000010988609489e+01,1.438199891734539757e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021949360999050782e+02,7.348925702144448451e+02,5.138599969803901990e-01,1.100000010988609489e+01,1.436740037719162581e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021958451908050876e+02,7.349025702143416083e+02,5.138614337204229221e-01,1.100000010988609489e+01,1.435280183703785406e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021967542817050969e+02,7.349125702142385990e+02,5.138628690006017408e-01,1.100000010988609489e+01,1.433820329688408231e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021976633726051062e+02,7.349225702141358170e+02,5.138643028209265440e-01,1.100000010988609489e+01,1.432360475673031056e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021985724635051156e+02,7.349325702140332623e+02,5.138657351813973317e-01,1.100000010988609489e+01,1.430900621657653880e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.021994815544051249e+02,7.349425702139309351e+02,5.138671660820141041e-01,1.100000010988609489e+01,1.429440767642276705e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022003906453051343e+02,7.349525702138287215e+02,5.138685955227768609e-01,1.100000010988609489e+01,1.427980913626899530e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022012997362051436e+02,7.349625702137267353e+02,5.138700235036856023e-01,1.100000010988609489e+01,1.426521059611522355e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022022088271051530e+02,7.349725702136249765e+02,5.138714500247403283e-01,1.100000010988609489e+01,1.425061205596145179e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022031179180051623e+02,7.349825702135234451e+02,5.138728750859411498e-01,1.100000010988609489e+01,1.423601351580768004e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022040270089051717e+02,7.349925702134221410e+02,5.138742986872879559e-01,1.100000010988609489e+01,1.422141497565390829e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022049360998051810e+02,7.350025702133210643e+02,5.138757208287807465e-01,1.100000010988609489e+01,1.420681643550013654e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022058451907051904e+02,7.350125702132201013e+02,5.138771415104195217e-01,1.100000010988609489e+01,1.419221789534636478e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022067542816051997e+02,7.350225702131193657e+02,5.138785607322042814e-01,1.100000010988609489e+01,1.417761935519259303e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022076633725052091e+02,7.350325702130188574e+02,5.138799784941350257e-01,1.100000010988609489e+01,1.416302081503882128e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022085724634052184e+02,7.350425702129185765e+02,5.138813947962117545e-01,1.100000010988609489e+01,1.414842227488504953e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022094815543052277e+02,7.350525702128185230e+02,5.138828096384344679e-01,1.100000010988609489e+01,1.413382373473127777e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022103906452052371e+02,7.350625702127186969e+02,5.138842230208032769e-01,1.100000010988609489e+01,1.411922519457750602e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022112997361052464e+02,7.350725702126189844e+02,5.138856349433180704e-01,1.100000010988609489e+01,1.410462665442373427e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022122088270052558e+02,7.350825702125194994e+02,5.138870454059788484e-01,1.100000010988609489e+01,1.409002811426996252e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022131179179052651e+02,7.350925702124202417e+02,5.138884544087856110e-01,1.100000010988609489e+01,1.407542957411619076e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022140270088052745e+02,7.351025702123212113e+02,5.138898619517383581e-01,1.100000010988609489e+01,1.406083103396241901e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022149360997052838e+02,7.351125702122224084e+02,5.138912680348370898e-01,1.100000010988609489e+01,1.404623249380864726e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022158451906052932e+02,7.351225702121237191e+02,5.138926726580818061e-01,1.100000010988609489e+01,1.403163395365487551e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022167542815053025e+02,7.351325702120252572e+02,5.138940758214726179e-01,1.100000010988609489e+01,1.401703541350110375e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022176633724053119e+02,7.351425702119270227e+02,5.138954775250094142e-01,1.100000010988609489e+01,1.400243687334733200e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022185724633053212e+02,7.351525702118290155e+02,5.138968777686921952e-01,1.100000010988609489e+01,1.398783833319356025e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022194815542053306e+02,7.351625702117312358e+02,5.138982765525209606e-01,1.100000010988609489e+01,1.397323979303978850e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022203906451053399e+02,7.351725702116335697e+02,5.138996738764957106e-01,1.100000010988609489e+01,1.395864125288601675e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022212997360053492e+02,7.351825702115361310e+02,5.139010697406164452e-01,1.100000010988609489e+01,1.394404271273224499e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022222088269053586e+02,7.351925702114389196e+02,5.139024641448831643e-01,1.100000010988609489e+01,1.392944417257847324e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022231179178053679e+02,7.352025702113419356e+02,5.139038570892958679e-01,1.100000010988609489e+01,1.391484563242470149e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022240270087053773e+02,7.352125702112451791e+02,5.139052485738546672e-01,1.100000010988609489e+01,1.390024709227092974e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022249360996053866e+02,7.352225702111485361e+02,5.139066385985594509e-01,1.100000010988609489e+01,1.388564855211715798e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022258451905053960e+02,7.352325702110521206e+02,5.139080271634102193e-01,1.100000010988609489e+01,1.387105001196338623e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022267542814054053e+02,7.352425702109559325e+02,5.139094142684069721e-01,1.100000010988609489e+01,1.385645147180961448e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022276633723054147e+02,7.352525702108599717e+02,5.139107999135497096e-01,1.100000010988609489e+01,1.384185293165584273e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022285724632054240e+02,7.352625702107641246e+02,5.139121840988384315e-01,1.100000010988609489e+01,1.382725439150207097e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022294815541054334e+02,7.352725702106685048e+02,5.139135668242731381e-01,1.100000010988609489e+01,1.381265585134829922e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022303906450054427e+02,7.352825702105731125e+02,5.139149480898538291e-01,1.100000010988609489e+01,1.379805731119452747e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022312997359054521e+02,7.352925702104779475e+02,5.139163278955806158e-01,1.100000010988609489e+01,1.378345877104075572e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022322088268054614e+02,7.353025702103830099e+02,5.139177062414533870e-01,1.100000010988609489e+01,1.376886023088698396e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022331179177054707e+02,7.353125702102881860e+02,5.139190831274721427e-01,1.100000010988609489e+01,1.375426169073321221e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022340270086054801e+02,7.353225702101935894e+02,5.139204585536368830e-01,1.100000010988609489e+01,1.373966315057944046e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022349360995054894e+02,7.353325702100992203e+02,5.139218325199476078e-01,1.100000010988609489e+01,1.372506461042566871e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022358451904054988e+02,7.353425702100050785e+02,5.139232050264043172e-01,1.100000010988609489e+01,1.371046607027189695e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022367542813055081e+02,7.353525702099110504e+02,5.139245760730070112e-01,1.100000010988609489e+01,1.369586753011812520e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022376633722055175e+02,7.353625702098172496e+02,5.139259456597556897e-01,1.100000010988609489e+01,1.368126898996435345e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022385724631055268e+02,7.353725702097236763e+02,5.139273137866504637e-01,1.100000010988609489e+01,1.366667044981058170e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022394815540055362e+02,7.353825702096303303e+02,5.139286804536912223e-01,1.100000010988609489e+01,1.365207190965680994e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022403906449055455e+02,7.353925702095370980e+02,5.139300456608779655e-01,1.100000010988609489e+01,1.363747336950303819e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022412997358055549e+02,7.354025702094440931e+02,5.139314094082106932e-01,1.100000010988609489e+01,1.362287482934926644e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022422088267055642e+02,7.354125702093513155e+02,5.139327716956894054e-01,1.100000010988609489e+01,1.360827628919549469e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022431179176055736e+02,7.354225702092587653e+02,5.139341325233141022e-01,1.100000010988609489e+01,1.359367774904172294e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022440270085055829e+02,7.354325702091663288e+02,5.139354918910847836e-01,1.100000010988609489e+01,1.357907920888795118e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022449360994055922e+02,7.354425702090741197e+02,5.139368497990014495e-01,1.100000010988609489e+01,1.356448066873417943e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022458451903056016e+02,7.354525702089821380e+02,5.139382062470642110e-01,1.100000010988609489e+01,1.354988212858040768e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022467542812056109e+02,7.354625702088903836e+02,5.139395612352729570e-01,1.100000010988609489e+01,1.353528358842663593e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022476633721056203e+02,7.354725702087987429e+02,5.139409147636276876e-01,1.100000010988609489e+01,1.352068504827286417e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022485724630056296e+02,7.354825702087073296e+02,5.139422668321284027e-01,1.100000010988609489e+01,1.350608650811909242e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022494815539056390e+02,7.354925702086161436e+02,5.139436174407751023e-01,1.100000010988609489e+01,1.349148796796532067e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022503906448056483e+02,7.355025702085251851e+02,5.139449665895677866e-01,1.100000010988609489e+01,1.347688942781154892e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022512997357056577e+02,7.355125702084343402e+02,5.139463142785064553e-01,1.100000010988609489e+01,1.346229088765777716e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022522088266056670e+02,7.355225702083437227e+02,5.139476605075911086e-01,1.100000010988609489e+01,1.344769234750400541e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022531179175056764e+02,7.355325702082533326e+02,5.139490052768218575e-01,1.100000010988609489e+01,1.343309380735023366e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022540270084056857e+02,7.355425702081630561e+02,5.139503485861985910e-01,1.100000010988609489e+01,1.341849526719646191e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022549360993056951e+02,7.355525702080730071e+02,5.139516904357213090e-01,1.100000010988609489e+01,1.340389672704269015e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022558451902057044e+02,7.355625702079831854e+02,5.139530308253900115e-01,1.100000010988609489e+01,1.338929818688891840e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022567542811057137e+02,7.355725702078935910e+02,5.139543697552046986e-01,1.100000010988609489e+01,1.337469964673514665e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022576633720057231e+02,7.355825702078041104e+02,5.139557072251653702e-01,1.100000010988609489e+01,1.336010110658137490e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022585724629057324e+02,7.355925702077148571e+02,5.139570432352720264e-01,1.100000010988609489e+01,1.334550256642760314e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022594815538057418e+02,7.356025702076258312e+02,5.139583777855246671e-01,1.100000010988609489e+01,1.333090402627383139e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022603906447057511e+02,7.356125702075369190e+02,5.139597108759232924e-01,1.100000010988609489e+01,1.331630548612005964e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022612997356057605e+02,7.356225702074482342e+02,5.139610425064680133e-01,1.100000010988609489e+01,1.330170694596628789e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022622088265057698e+02,7.356325702073597768e+02,5.139623726771587187e-01,1.100000010988609489e+01,1.328710840581251613e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022631179174057792e+02,7.356425702072715467e+02,5.139637013879954086e-01,1.100000010988609489e+01,1.327250986565874438e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022640270083057885e+02,7.356525702071834303e+02,5.139650286389780831e-01,1.100000010988609489e+01,1.325791132550497263e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022649360992057979e+02,7.356625702070955413e+02,5.139663544301067422e-01,1.100000010988609489e+01,1.324331278535120088e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022658451901058072e+02,7.356725702070078796e+02,5.139676787613813858e-01,1.100000010988609489e+01,1.322871424519742913e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022667542810058166e+02,7.356825702069203317e+02,5.139690016328020139e-01,1.100000010988609489e+01,1.321411570504365737e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022676633719058259e+02,7.356925702068330111e+02,5.139703230443686266e-01,1.100000010988609489e+01,1.319951716488988562e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022685724628058352e+02,7.357025702067459179e+02,5.139716429960813349e-01,1.100000010988609489e+01,1.318491862473611387e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022694815537058446e+02,7.357125702066590520e+02,5.139729614879400277e-01,1.100000010988609489e+01,1.317032008458234212e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022703906446058539e+02,7.357225702065722999e+02,5.139742785199447050e-01,1.100000010988609489e+01,1.315572154442857036e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022712997355058633e+02,7.357325702064857751e+02,5.139755940920953670e-01,1.100000010988609489e+01,1.314112300427479861e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022722088264058726e+02,7.357425702063994777e+02,5.139769082043920134e-01,1.100000010988609489e+01,1.312652446412102686e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022731179173058820e+02,7.357525702063132940e+02,5.139782208568346444e-01,1.100000010988609489e+01,1.311192592396725511e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022740270082058913e+02,7.357625702062273376e+02,5.139795320494232600e-01,1.100000010988609489e+01,1.309732738381348335e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022749360991059007e+02,7.357725702061416087e+02,5.139808417821578601e-01,1.100000010988609489e+01,1.308272884365971160e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022758451900059100e+02,7.357825702060559934e+02,5.139821500550384448e-01,1.100000010988609489e+01,1.306813030350593985e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022767542809059194e+02,7.357925702059706055e+02,5.139834568680651250e-01,1.100000010988609489e+01,1.305353176335216810e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022776633718059287e+02,7.358025702058854449e+02,5.139847622212377898e-01,1.100000010988609489e+01,1.303893322319839634e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022785724627059381e+02,7.358125702058003981e+02,5.139860661145564391e-01,1.100000010988609489e+01,1.302433468304462459e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022794815536059474e+02,7.358225702057155786e+02,5.139873685480210730e-01,1.100000010988609489e+01,1.300973614289085284e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022803906445059567e+02,7.358325702056309865e+02,5.139886695216316914e-01,1.100000010988609489e+01,1.299513760273708109e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022812997354059661e+02,7.358425702055465081e+02,5.139899690353882944e-01,1.100000010988609489e+01,1.298053906258330933e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022822088263059754e+02,7.358525702054622570e+02,5.139912670892908819e-01,1.100000010988609489e+01,1.296594052242953758e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022831179172059848e+02,7.358625702053782334e+02,5.139925636833394540e-01,1.100000010988609489e+01,1.295134198227576583e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022840270081059941e+02,7.358725702052943234e+02,5.139938588175340106e-01,1.100000010988609489e+01,1.293674344212199408e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022849360990060035e+02,7.358825702052106408e+02,5.139951524918746628e-01,1.100000010988609489e+01,1.292214490196822232e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022858451899060128e+02,7.358925702051271855e+02,5.139964447063612996e-01,1.100000010988609489e+01,1.290754636181445057e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022867542808060222e+02,7.359025702050438440e+02,5.139977354609939209e-01,1.100000010988609489e+01,1.289294782166067882e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022876633717060315e+02,7.359125702049607298e+02,5.139990247557725267e-01,1.100000010988609489e+01,1.287834928150690707e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022885724626060409e+02,7.359225702048778430e+02,5.140003125906971171e-01,1.100000010988609489e+01,1.286375074135313532e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022894815535060502e+02,7.359325702047950699e+02,5.140015989657676920e-01,1.100000010988609489e+01,1.284915220119936356e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022903906444060596e+02,7.359425702047125242e+02,5.140028838809842515e-01,1.100000010988609489e+01,1.283455366104559181e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022912997353060689e+02,7.359525702046302058e+02,5.140041673363467956e-01,1.100000010988609489e+01,1.281995512089182006e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022922088262060782e+02,7.359625702045480011e+02,5.140054493318553241e-01,1.100000010988609489e+01,1.280535658073804831e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022931179171060876e+02,7.359725702044660238e+02,5.140067298675099483e-01,1.100000010988609489e+01,1.279075804058427655e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022940270080060969e+02,7.359825702043842739e+02,5.140080089433105570e-01,1.100000010988609489e+01,1.277615950043050480e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022949360989061063e+02,7.359925702043026376e+02,5.140092865592571503e-01,1.100000010988609489e+01,1.276156096027673305e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022958451898061156e+02,7.360025702042212288e+02,5.140105627153497281e-01,1.100000010988609489e+01,1.274696242012296130e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022967542807061250e+02,7.360125702041399336e+02,5.140118374115882904e-01,1.100000010988609489e+01,1.273236387996918954e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022976633716061343e+02,7.360225702040588658e+02,5.140131106479728373e-01,1.100000010988609489e+01,1.271776533981541779e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022985724625061437e+02,7.360325702039780253e+02,5.140143824245033688e-01,1.100000010988609489e+01,1.270316679966164604e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.022994815534061530e+02,7.360425702038972986e+02,5.140156527411798848e-01,1.100000010988609489e+01,1.268856825950787429e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023003906443061624e+02,7.360525702038167992e+02,5.140169215980023854e-01,1.100000010988609489e+01,1.267396971935410253e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023012997352061717e+02,7.360625702037365272e+02,5.140181889949709815e-01,1.100000010988609489e+01,1.265937117920033078e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023022088261061810e+02,7.360725702036563689e+02,5.140194549320855621e-01,1.100000010988609489e+01,1.264477263904655903e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023031179170061904e+02,7.360825702035764380e+02,5.140207194093461274e-01,1.100000010988609489e+01,1.263017409889278728e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023040270079061997e+02,7.360925702034966207e+02,5.140219824267526771e-01,1.100000010988609489e+01,1.261557555873901552e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023049360988062091e+02,7.361025702034170308e+02,5.140232439843052115e-01,1.100000010988609489e+01,1.260097701858524377e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023058451897062184e+02,7.361125702033376683e+02,5.140245040820037303e-01,1.100000010988609489e+01,1.258637847843147202e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023067542806062278e+02,7.361225702032584195e+02,5.140257627198482338e-01,1.100000010988609489e+01,1.257177993827770027e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023076633715062371e+02,7.361325702031793980e+02,5.140270198978387217e-01,1.100000010988609489e+01,1.255718139812392851e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023085724624062465e+02,7.361425702031006040e+02,5.140282756159751942e-01,1.100000010988609489e+01,1.254258285797015676e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023094815533062558e+02,7.361525702030219236e+02,5.140295298742576513e-01,1.100000010988609489e+01,1.252798431781638501e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023103906442062652e+02,7.361625702029434706e+02,5.140307826726862039e-01,1.100000010988609489e+01,1.251338577766261326e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023112997351062745e+02,7.361725702028651313e+02,5.140320340112607411e-01,1.100000010988609489e+01,1.249878723750884151e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023122088260062839e+02,7.361825702027870193e+02,5.140332838899812629e-01,1.100000010988609489e+01,1.248418869735506975e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023131179169062932e+02,7.361925702027091347e+02,5.140345323088477691e-01,1.100000010988609489e+01,1.246959015720129800e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023140270078063025e+02,7.362025702026313638e+02,5.140357792678602600e-01,1.100000010988609489e+01,1.245499161704752625e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023149360987063119e+02,7.362125702025538203e+02,5.140370247670187354e-01,1.100000010988609489e+01,1.244039307689375450e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023158451896063212e+02,7.362225702024763905e+02,5.140382688063231953e-01,1.100000010988609489e+01,1.242579453673998274e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023167542805063306e+02,7.362325702023991880e+02,5.140395113857736398e-01,1.100000010988609489e+01,1.241119599658621099e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023176633714063399e+02,7.362425702023222129e+02,5.140407525053700688e-01,1.100000010988609489e+01,1.239659745643243924e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023185724623063493e+02,7.362525702022453515e+02,5.140419921651124824e-01,1.100000010988609489e+01,1.238199891627866749e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023194815532063586e+02,7.362625702021687175e+02,5.140432303650009915e-01,1.100000010988609489e+01,1.236740037612489573e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023203906441063680e+02,7.362725702020921972e+02,5.140444671050354852e-01,1.100000010988609489e+01,1.235280183597112398e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023212997350063773e+02,7.362825702020159042e+02,5.140457023852159635e-01,1.100000010988609489e+01,1.233820329581735223e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023222088259063867e+02,7.362925702019398386e+02,5.140469362055424263e-01,1.100000010988609489e+01,1.232360475566358048e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023231179168063960e+02,7.363025702018638867e+02,5.140481685660148736e-01,1.100000010988609489e+01,1.230900621550980872e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023240270077064054e+02,7.363125702017881622e+02,5.140493994666333055e-01,1.100000010988609489e+01,1.229440767535603697e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023249360986064147e+02,7.363225702017125514e+02,5.140506289073977220e-01,1.100000010988609489e+01,1.227980913520226522e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023258451895064240e+02,7.363325702016371679e+02,5.140518568883081230e-01,1.100000010988609489e+01,1.226521059504849347e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023267542804064334e+02,7.363425702015618981e+02,5.140530834093645085e-01,1.100000010988609489e+01,1.225061205489472171e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023276633713064427e+02,7.363525702014868557e+02,5.140543084705668786e-01,1.100000010988609489e+01,1.223601351474094996e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023285724622064521e+02,7.363625702014120407e+02,5.140555320719153443e-01,1.100000010988609489e+01,1.222141497458717821e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023294815531064614e+02,7.363725702013373393e+02,5.140567542134097945e-01,1.100000010988609489e+01,1.220681643443340646e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023303906440064708e+02,7.363825702012628653e+02,5.140579748950502292e-01,1.100000010988609489e+01,1.219221789427963470e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023312997349064801e+02,7.363925702011885051e+02,5.140591941168366485e-01,1.100000010988609489e+01,1.217761935412586295e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023322088258064895e+02,7.364025702011143721e+02,5.140604118787690524e-01,1.100000010988609489e+01,1.216302081397209120e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023331179167064988e+02,7.364125702010403529e+02,5.140616281808474408e-01,1.100000010988609489e+01,1.214842227381831945e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023340270076065082e+02,7.364225702009665611e+02,5.140628430230718138e-01,1.100000010988609489e+01,1.213382373366454769e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023349360985065175e+02,7.364325702008929966e+02,5.140640564054421713e-01,1.100000010988609489e+01,1.211922519351077594e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023358451894065269e+02,7.364425702008195458e+02,5.140652683279585133e-01,1.100000010988609489e+01,1.210462665335700419e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023367542803065362e+02,7.364525702007463224e+02,5.140664787906208399e-01,1.100000010988609489e+01,1.209002811320323244e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023376633712065455e+02,7.364625702006732126e+02,5.140676877934292621e-01,1.100000010988609489e+01,1.207542957304946069e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023385724621065549e+02,7.364725702006003303e+02,5.140688953363836688e-01,1.100000010988609489e+01,1.206083103289568893e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023394815530065642e+02,7.364825702005275616e+02,5.140701014194840601e-01,1.100000010988609489e+01,1.204623249274191718e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023403906439065736e+02,7.364925702004550203e+02,5.140713060427304359e-01,1.100000010988609489e+01,1.203163395258814543e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023412997348065829e+02,7.365025702003825927e+02,5.140725092061227963e-01,1.100000010988609489e+01,1.201703541243437368e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023422088257065923e+02,7.365125702003103925e+02,5.140737109096611412e-01,1.100000010988609489e+01,1.200243687228060192e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023431179166066016e+02,7.365225702002384196e+02,5.140749111533454707e-01,1.100000010988609489e+01,1.198783833212683017e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023440270075066110e+02,7.365325702001665604e+02,5.140761099371757847e-01,1.100000010988609489e+01,1.197323979197305842e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023449360984066203e+02,7.365425702000949286e+02,5.140773072611520833e-01,1.100000010988609489e+01,1.195864125181928667e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023458451893066297e+02,7.365525702000234105e+02,5.140785031252743664e-01,1.100000010988609489e+01,1.194404271166551491e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023467542802066390e+02,7.365625701999521198e+02,5.140796975295427451e-01,1.100000010988609489e+01,1.192944417151174316e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023476633711066484e+02,7.365725701998809427e+02,5.140808904739571084e-01,1.100000010988609489e+01,1.191484563135797141e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023485724620066577e+02,7.365825701998099930e+02,5.140820819585174561e-01,1.100000010988609489e+01,1.190024709120419966e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023494815529066670e+02,7.365925701997391570e+02,5.140832719832237885e-01,1.100000010988609489e+01,1.188564855105042790e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023503906438066764e+02,7.366025701996685484e+02,5.140844605480761054e-01,1.100000010988609489e+01,1.187105001089665615e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023512997347066857e+02,7.366125701995980535e+02,5.140856476530744068e-01,1.100000010988609489e+01,1.185645147074288440e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023522088256066951e+02,7.366225701995277859e+02,5.140868332982186928e-01,1.100000010988609489e+01,1.184185293058911265e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023531179165067044e+02,7.366325701994576320e+02,5.140880174835089633e-01,1.100000010988609489e+01,1.182725439043534089e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023540270074067138e+02,7.366425701993877055e+02,5.140892002089452184e-01,1.100000010988609489e+01,1.181265585028156914e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023549360983067231e+02,7.366525701993178927e+02,5.140903814745274580e-01,1.100000010988609489e+01,1.179805731012779739e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023558451892067325e+02,7.366625701992483073e+02,5.140915612802556822e-01,1.100000010988609489e+01,1.178345876997402564e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023567542801067418e+02,7.366725701991788355e+02,5.140927396261300020e-01,1.100000010988609489e+01,1.176886022982025388e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023576633710067512e+02,7.366825701991095912e+02,5.140939165121503063e-01,1.100000010988609489e+01,1.175426168966648213e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023585724619067605e+02,7.366925701990404605e+02,5.140950919383165951e-01,1.100000010988609489e+01,1.173966314951271038e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023594815528067699e+02,7.367025701989715571e+02,5.140962659046288685e-01,1.100000010988609489e+01,1.172506460935893863e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023603906437067792e+02,7.367125701989027675e+02,5.140974384110871265e-01,1.100000010988609489e+01,1.171046606920516688e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023612997346067885e+02,7.367225701988342053e+02,5.140986094576913690e-01,1.100000010988609489e+01,1.169586752905139512e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023622088255067979e+02,7.367325701987657567e+02,5.140997790444415960e-01,1.100000010988609489e+01,1.168126898889762337e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023631179164068072e+02,7.367425701986975355e+02,5.141009471713378076e-01,1.100000010988609489e+01,1.166667044874385162e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023640270073068166e+02,7.367525701986294280e+02,5.141021138383800038e-01,1.100000010988609489e+01,1.165207190859007987e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023649360982068259e+02,7.367625701985615478e+02,5.141032790455681845e-01,1.100000010988609489e+01,1.163747336843630811e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023658451891068353e+02,7.367725701984937814e+02,5.141044427929023497e-01,1.100000010988609489e+01,1.162287482828253636e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023667542800068446e+02,7.367825701984262423e+02,5.141056050803826105e-01,1.100000010988609489e+01,1.160827628812876461e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023676633709068540e+02,7.367925701983588169e+02,5.141067659080088559e-01,1.100000010988609489e+01,1.159367774797499286e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023685724618068633e+02,7.368025701982916189e+02,5.141079252757810858e-01,1.100000010988609489e+01,1.157907920782122110e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023694815527068727e+02,7.368125701982245346e+02,5.141090831836993003e-01,1.100000010988609489e+01,1.156448066766744935e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023703906436068820e+02,7.368225701981576776e+02,5.141102396317634993e-01,1.100000010988609489e+01,1.154988212751367760e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023712997345068914e+02,7.368325701980909344e+02,5.141113946199736828e-01,1.100000010988609489e+01,1.153528358735990585e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023722088254069007e+02,7.368425701980244185e+02,5.141125481483298509e-01,1.100000010988609489e+01,1.152068504720613409e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023731179163069100e+02,7.368525701979580163e+02,5.141137002168320036e-01,1.100000010988609489e+01,1.150608650705236234e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023740270072069194e+02,7.368625701978918414e+02,5.141148508254801408e-01,1.100000010988609489e+01,1.149148796689859059e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023749360981069287e+02,7.368725701978257803e+02,5.141159999742742626e-01,1.100000010988609489e+01,1.147688942674481884e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023758451890069381e+02,7.368825701977599465e+02,5.141171476632143689e-01,1.100000010988609489e+01,1.146229088659104708e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023767542799069474e+02,7.368925701976942264e+02,5.141182938923005707e-01,1.100000010988609489e+01,1.144769234643727533e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023776633708069568e+02,7.369025701976287337e+02,5.141194386615327572e-01,1.100000010988609489e+01,1.143309380628350358e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023785724617069661e+02,7.369125701975633547e+02,5.141205819709109281e-01,1.100000010988609489e+01,1.141849526612973183e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023794815526069755e+02,7.369225701974982030e+02,5.141217238204350837e-01,1.100000010988609489e+01,1.140389672597596007e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023803906435069848e+02,7.369325701974331650e+02,5.141228642101052237e-01,1.100000010988609489e+01,1.138929818582218832e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023812997344069942e+02,7.369425701973683545e+02,5.141240031399213484e-01,1.100000010988609489e+01,1.137469964566841657e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023822088253070035e+02,7.369525701973036576e+02,5.141251406098834575e-01,1.100000010988609489e+01,1.136010110551464482e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023831179162070129e+02,7.369625701972391880e+02,5.141262766199915513e-01,1.100000010988609489e+01,1.134550256536087307e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023840270071070222e+02,7.369725701971748322e+02,5.141274111702456295e-01,1.100000010988609489e+01,1.133090402520710131e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023849360980070315e+02,7.369825701971105900e+02,5.141285442606456924e-01,1.100000010988609489e+01,1.131630548505332956e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023858451889070409e+02,7.369925701970465752e+02,5.141296758911917397e-01,1.100000010988609489e+01,1.130170694489955781e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023867542798070502e+02,7.370025701969826741e+02,5.141308060618837716e-01,1.100000010988609489e+01,1.128710840474578606e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023876633707070596e+02,7.370125701969190004e+02,5.141319347727218991e-01,1.100000010988609489e+01,1.127250986459201430e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023885724616070689e+02,7.370225701968554404e+02,5.141330620237060112e-01,1.100000010988609489e+01,1.125791132443824255e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023894815525070783e+02,7.370325701967921077e+02,5.141341878148361078e-01,1.100000010988609489e+01,1.124331278428447080e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023903906434070876e+02,7.370425701967288887e+02,5.141353121461121889e-01,1.100000010988609489e+01,1.122871424413069905e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023912997343070970e+02,7.370525701966658971e+02,5.141364350175342546e-01,1.100000010988609489e+01,1.121411570397692729e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023922088252071063e+02,7.370625701966030192e+02,5.141375564291023048e-01,1.100000010988609489e+01,1.119951716382315554e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023931179161071157e+02,7.370725701965402550e+02,5.141386763808163396e-01,1.100000010988609489e+01,1.118491862366938379e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023940270070071250e+02,7.370825701964777181e+02,5.141397948726763589e-01,1.100000010988609489e+01,1.117032008351561204e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023949360979071344e+02,7.370925701964152950e+02,5.141409119046823628e-01,1.100000010988609489e+01,1.115572154336184028e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023958451888071437e+02,7.371025701963530992e+02,5.141420274768343512e-01,1.100000010988609489e+01,1.114112300320806853e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023967542797071530e+02,7.371125701962910171e+02,5.141431415891323242e-01,1.100000010988609489e+01,1.112652446305429678e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023976633706071624e+02,7.371225701962291623e+02,5.141442542415762817e-01,1.100000010988609489e+01,1.111192592290052503e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023985724615071717e+02,7.371325701961674213e+02,5.141453654341663349e-01,1.100000010988609489e+01,1.109732738274675327e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.023994815524071811e+02,7.371425701961057939e+02,5.141464751669023725e-01,1.100000010988609489e+01,1.108272884259298152e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024003906433071904e+02,7.371525701960443939e+02,5.141475834397843947e-01,1.100000010988609489e+01,1.106813030243920977e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024012997342071998e+02,7.371625701959831076e+02,5.141486902528124014e-01,1.100000010988609489e+01,1.105353176228543802e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024022088251072091e+02,7.371725701959220487e+02,5.141497956059863927e-01,1.100000010988609489e+01,1.103893322213166626e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024031179160072185e+02,7.371825701958611035e+02,5.141508994993063686e-01,1.100000010988609489e+01,1.102433468197789451e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024040270069072278e+02,7.371925701958003856e+02,5.141520019327723290e-01,1.100000010988609489e+01,1.100973614182412276e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024049360978072372e+02,7.372025701957397814e+02,5.141531029063842739e-01,1.100000010988609489e+01,1.099513760167035101e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024058451887072465e+02,7.372125701956792909e+02,5.141542024201422034e-01,1.100000010988609489e+01,1.098053906151657926e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024067542796072559e+02,7.372225701956190278e+02,5.141553004740461175e-01,1.100000010988609489e+01,1.096594052136280750e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024076633705072652e+02,7.372325701955588784e+02,5.141563970680960161e-01,1.100000010988609489e+01,1.095134198120903575e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024085724614072745e+02,7.372425701954989563e+02,5.141574922022918992e-01,1.100000010988609489e+01,1.093674344105526400e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024094815523072839e+02,7.372525701954391479e+02,5.141585858766338779e-01,1.100000010988609489e+01,1.092214490090149225e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024103906432072932e+02,7.372625701953794533e+02,5.141596780911218412e-01,1.100000010988609489e+01,1.090754636074772049e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024112997341073026e+02,7.372725701953199859e+02,5.141607688457557890e-01,1.100000010988609489e+01,1.089294782059394874e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024122088250073119e+02,7.372825701952606323e+02,5.141618581405357213e-01,1.100000010988609489e+01,1.087834928044017699e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024131179159073213e+02,7.372925701952015061e+02,5.141629459754616382e-01,1.100000010988609489e+01,1.086375074028640524e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024140270068073306e+02,7.373025701951424935e+02,5.141640323505335397e-01,1.100000010988609489e+01,1.084915220013263348e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024149360977073400e+02,7.373125701950835946e+02,5.141651172657514257e-01,1.100000010988609489e+01,1.083455365997886173e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024158451886073493e+02,7.373225701950249231e+02,5.141662007211152963e-01,1.100000010988609489e+01,1.081995511982508998e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024167542795073587e+02,7.373325701949663653e+02,5.141672827166251514e-01,1.100000010988609489e+01,1.080535657967131823e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024176633704073680e+02,7.373425701949080349e+02,5.141683632522809910e-01,1.100000010988609489e+01,1.079075803951754647e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024185724613073774e+02,7.373525701948498181e+02,5.141694423280828152e-01,1.100000010988609489e+01,1.077615949936377472e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024194815522073867e+02,7.373625701947917150e+02,5.141705199440306240e-01,1.100000010988609489e+01,1.076156095921000297e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024203906431073960e+02,7.373725701947338393e+02,5.141715961001244173e-01,1.100000010988609489e+01,1.074696241905623122e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024212997340074054e+02,7.373825701946760773e+02,5.141726707963643062e-01,1.100000010988609489e+01,1.073236387890245946e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024222088249074147e+02,7.373925701946184290e+02,5.141737440327501796e-01,1.100000010988609489e+01,1.071776533874868771e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024231179158074241e+02,7.374025701945610081e+02,5.141748158092820375e-01,1.100000010988609489e+01,1.070316679859491596e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024240270067074334e+02,7.374125701945037008e+02,5.141758861259598801e-01,1.100000010988609489e+01,1.068856825844114421e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024249360976074428e+02,7.374225701944466209e+02,5.141769549827837071e-01,1.100000010988609489e+01,1.067396971828737245e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024258451885074521e+02,7.374325701943896547e+02,5.141780223797535188e-01,1.100000010988609489e+01,1.065937117813360070e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024267542794074615e+02,7.374425701943328022e+02,5.141790883168693149e-01,1.100000010988609489e+01,1.064477263797982895e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024276633703074708e+02,7.374525701942761771e+02,5.141801527941310956e-01,1.100000010988609489e+01,1.063017409782605720e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024285724612074802e+02,7.374625701942196656e+02,5.141812158115388609e-01,1.100000010988609489e+01,1.061557555767228544e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024294815521074895e+02,7.374725701941632678e+02,5.141822773690926107e-01,1.100000010988609489e+01,1.060097701751851369e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024303906430074989e+02,7.374825701941070974e+02,5.141833374667923451e-01,1.100000010988609489e+01,1.058637847736474194e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024312997339075082e+02,7.374925701940510407e+02,5.141843961046380640e-01,1.100000010988609489e+01,1.057177993721097019e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024322088248075175e+02,7.375025701939952114e+02,5.141854532826297675e-01,1.100000010988609489e+01,1.055718139705719844e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024331179157075269e+02,7.375125701939394958e+02,5.141865090007675665e-01,1.100000010988609489e+01,1.054258285690342668e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024340270066075362e+02,7.375225701938838938e+02,5.141875632590513501e-01,1.100000010988609489e+01,1.052798431674965493e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024349360975075456e+02,7.375325701938285192e+02,5.141886160574811182e-01,1.100000010988609489e+01,1.051338577659588318e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024358451884075549e+02,7.375425701937732583e+02,5.141896673960568709e-01,1.100000010988609489e+01,1.049878723644211143e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024367542793075643e+02,7.375525701937181111e+02,5.141907172747786081e-01,1.100000010988609489e+01,1.048418869628833967e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024376633702075736e+02,7.375625701936631913e+02,5.141917656936463299e-01,1.100000010988609489e+01,1.046959015613456792e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024385724611075830e+02,7.375725701936083851e+02,5.141928126526600362e-01,1.100000010988609489e+01,1.045499161598079617e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024394815520075923e+02,7.375825701935536927e+02,5.141938581518197271e-01,1.100000010988609489e+01,1.044039307582702442e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024403906429076017e+02,7.375925701934992276e+02,5.141949021911254025e-01,1.100000010988609489e+01,1.042579453567325266e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024412997338076110e+02,7.376025701934448762e+02,5.141959447705770625e-01,1.100000010988609489e+01,1.041119599551948091e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024422088247076204e+02,7.376125701933906385e+02,5.141969858901747070e-01,1.100000010988609489e+01,1.039659745536570916e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024431179156076297e+02,7.376225701933366281e+02,5.141980255499183361e-01,1.100000010988609489e+01,1.038199891521193741e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024440270065076390e+02,7.376325701932827315e+02,5.141990637498079497e-01,1.100000010988609489e+01,1.036740037505816565e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024449360974076484e+02,7.376425701932289485e+02,5.142001004898435479e-01,1.100000010988609489e+01,1.035280183490439390e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024458451883076577e+02,7.376525701931753929e+02,5.142011357700252416e-01,1.100000010988609489e+01,1.033820329475062215e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024467542792076671e+02,7.376625701931219510e+02,5.142021695903529199e-01,1.100000010988609489e+01,1.032360475459685040e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024476633701076764e+02,7.376725701930686228e+02,5.142032019508265828e-01,1.100000010988609489e+01,1.030900621444307864e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024485724610076858e+02,7.376825701930155219e+02,5.142042328514462302e-01,1.100000010988609489e+01,1.029440767428930689e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024494815519076951e+02,7.376925701929625347e+02,5.142052622922118621e-01,1.100000010988609489e+01,1.027980913413553514e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024503906428077045e+02,7.377025701929096613e+02,5.142062902731234786e-01,1.100000010988609489e+01,1.026521059398176339e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024512997337077138e+02,7.377125701928570152e+02,5.142073167941810796e-01,1.100000010988609489e+01,1.025061205382799163e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024522088246077232e+02,7.377225701928044828e+02,5.142083418553846652e-01,1.100000010988609489e+01,1.023601351367421988e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024531179155077325e+02,7.377325701927520640e+02,5.142093654567342353e-01,1.100000010988609489e+01,1.022141497352044813e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024540270064077419e+02,7.377425701926998727e+02,5.142103875982297900e-01,1.100000010988609489e+01,1.020681643336667638e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024549360973077512e+02,7.377525701926477950e+02,5.142114082798713293e-01,1.100000010988609489e+01,1.019221789321290463e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024558451882077605e+02,7.377625701925958310e+02,5.142124275016588530e-01,1.100000010988609489e+01,1.017761935305913287e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024567542791077699e+02,7.377725701925440944e+02,5.142134452635923614e-01,1.100000010988609489e+01,1.016302081290536112e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024576633700077792e+02,7.377825701924924715e+02,5.142144615656718543e-01,1.100000010988609489e+01,1.014842227275158937e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024585724609077886e+02,7.377925701924409623e+02,5.142154764078974427e-01,1.100000010988609489e+01,1.013382373259781762e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024594815518077979e+02,7.378025701923895667e+02,5.142164897902690157e-01,1.100000010988609489e+01,1.011922519244404586e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024603906427078073e+02,7.378125701923383986e+02,5.142175017127865733e-01,1.100000010988609489e+01,1.010462665229027411e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024612997336078166e+02,7.378225701922873441e+02,5.142185121754501154e-01,1.100000010988609489e+01,1.009002811213650236e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024622088245078260e+02,7.378325701922364033e+02,5.142195211782596420e-01,1.100000010988609489e+01,1.007542957198273061e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024631179154078353e+02,7.378425701921856898e+02,5.142205287212151532e-01,1.100000010988609489e+01,1.006083103182895885e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024640270063078447e+02,7.378525701921350901e+02,5.142215348043166490e-01,1.100000010988609489e+01,1.004623249167518710e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024649360972078540e+02,7.378625701920846041e+02,5.142225394275641293e-01,1.100000010988609489e+01,1.003163395152141535e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024658451881078634e+02,7.378725701920342317e+02,5.142235425909575941e-01,1.100000010988609489e+01,1.001703541136764360e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024667542790078727e+02,7.378825701919840867e+02,5.142245442944970435e-01,1.100000010988609489e+01,1.000243687121387184e-04,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024676633699078820e+02,7.378925701919340554e+02,5.142255445381824774e-01,1.100000010988609489e+01,9.987838331060100092e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024685724608078914e+02,7.379025701918841378e+02,5.142265433220138959e-01,1.100000010988609489e+01,9.973239790906328339e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024694815517079007e+02,7.379125701918344475e+02,5.142275406459912990e-01,1.100000010988609489e+01,9.958641250752556587e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024703906426079101e+02,7.379225701917848710e+02,5.142285365101146866e-01,1.100000010988609489e+01,9.944042710598784834e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024712997335079194e+02,7.379325701917354081e+02,5.142295309143840587e-01,1.100000010988609489e+01,9.929444170445013082e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024722088244079288e+02,7.379425701916860589e+02,5.142305238587995264e-01,1.100000010988609489e+01,9.914845630291241330e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024731179153079381e+02,7.379525701916369371e+02,5.142315153433609787e-01,1.100000010988609489e+01,9.900247090137469577e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024740270062079475e+02,7.379625701915879290e+02,5.142325053680684155e-01,1.100000010988609489e+01,9.885648549983697825e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024749360971079568e+02,7.379725701915390346e+02,5.142334939329218368e-01,1.100000010988609489e+01,9.871050009829926072e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024758451880079662e+02,7.379825701914903675e+02,5.142344810379212428e-01,1.100000010988609489e+01,9.856451469676154320e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024767542789079755e+02,7.379925701914418141e+02,5.142354666830666332e-01,1.100000010988609489e+01,9.841852929522382568e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024776633698079849e+02,7.380025701913933744e+02,5.142364508683580082e-01,1.100000010988609489e+01,9.827254389368610815e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024785724607079942e+02,7.380125701913450484e+02,5.142374335937953678e-01,1.100000010988609489e+01,9.812655849214839063e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024794815516080035e+02,7.380225701912969498e+02,5.142384148593787119e-01,1.100000010988609489e+01,9.798057309061067310e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024803906425080129e+02,7.380325701912489649e+02,5.142393946651080405e-01,1.100000010988609489e+01,9.783458768907295558e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024812997334080222e+02,7.380425701912010936e+02,5.142403730109833537e-01,1.100000010988609489e+01,9.768860228753523806e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024822088243080316e+02,7.380525701911533361e+02,5.142413498970046515e-01,1.100000010988609489e+01,9.754261688599752053e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024831179152080409e+02,7.380625701911058059e+02,5.142423253231719338e-01,1.100000010988609489e+01,9.739663148445980301e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024840270061080503e+02,7.380725701910583894e+02,5.142432992894852006e-01,1.100000010988609489e+01,9.725064608292208548e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024849360970080596e+02,7.380825701910110865e+02,5.142442717959444520e-01,1.100000010988609489e+01,9.710466068138436796e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024858451879080690e+02,7.380925701909638974e+02,5.142452428425496880e-01,1.100000010988609489e+01,9.695867527984665044e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024867542788080783e+02,7.381025701909169356e+02,5.142462124293010195e-01,1.100000010988609489e+01,9.681268987830893291e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024876633697080877e+02,7.381125701908700876e+02,5.142471805561983356e-01,1.100000010988609489e+01,9.666670447677121539e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024885724606080970e+02,7.381225701908233532e+02,5.142481472232416362e-01,1.100000010988609489e+01,9.652071907523349786e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024894815515081063e+02,7.381325701907767325e+02,5.142491124304309213e-01,1.100000010988609489e+01,9.637473367369578034e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024903906424081157e+02,7.381425701907303392e+02,5.142500761777661911e-01,1.100000010988609489e+01,9.622874827215806282e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024912997333081250e+02,7.381525701906840595e+02,5.142510384652474453e-01,1.100000010988609489e+01,9.608276287062034529e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024922088242081344e+02,7.381625701906378936e+02,5.142519992928746841e-01,1.100000010988609489e+01,9.593677746908262777e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024931179151081437e+02,7.381725701905918413e+02,5.142529586606479075e-01,1.100000010988609489e+01,9.579079206754491024e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024940270060081531e+02,7.381825701905460164e+02,5.142539165685671154e-01,1.100000010988609489e+01,9.564480666600719272e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024949360969081624e+02,7.381925701905003052e+02,5.142548730166323079e-01,1.100000010988609489e+01,9.549882126446947520e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024958451878081718e+02,7.382025701904547077e+02,5.142558280048434849e-01,1.100000010988609489e+01,9.535283586293175767e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024967542787081811e+02,7.382125701904092239e+02,5.142567815332006465e-01,1.100000010988609489e+01,9.520685046139404015e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024976633696081905e+02,7.382225701903638537e+02,5.142577336017037926e-01,1.100000010988609489e+01,9.506086505985632262e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024985724605081998e+02,7.382325701903187110e+02,5.142586842103529232e-01,1.100000010988609489e+01,9.491487965831860510e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.024994815514082092e+02,7.382425701902736819e+02,5.142596333591480384e-01,1.100000010988609489e+01,9.476889425678088757e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025003906423082185e+02,7.382525701902287665e+02,5.142605810480891382e-01,1.100000010988609489e+01,9.462290885524317005e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025012997332082278e+02,7.382625701901839648e+02,5.142615272771763335e-01,1.100000010988609489e+01,9.447692345370545253e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025022088241082372e+02,7.382725701901393904e+02,5.142624720464095134e-01,1.100000010988609489e+01,9.433093805216773500e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025031179150082465e+02,7.382825701900949298e+02,5.142634153557886778e-01,1.100000010988609489e+01,9.418495265063001748e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025040270059082559e+02,7.382925701900505828e+02,5.142643572053138268e-01,1.100000010988609489e+01,9.403896724909229995e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025049360968082652e+02,7.383025701900063495e+02,5.142652975949849603e-01,1.100000010988609489e+01,9.389298184755458243e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025058451877082746e+02,7.383125701899622300e+02,5.142662365248020784e-01,1.100000010988609489e+01,9.374699644601686491e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025067542786082839e+02,7.383225701899183377e+02,5.142671739947651810e-01,1.100000010988609489e+01,9.360101104447914738e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025076633695082933e+02,7.383325701898745592e+02,5.142681100048742682e-01,1.100000010988609489e+01,9.345502564294142986e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025085724604083026e+02,7.383425701898308944e+02,5.142690445551293399e-01,1.100000010988609489e+01,9.330904024140371233e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025094815513083120e+02,7.383525701897873432e+02,5.142699776455303962e-01,1.100000010988609489e+01,9.316305483986599481e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025103906422083213e+02,7.383625701897439058e+02,5.142709092760774370e-01,1.100000010988609489e+01,9.301706943832827729e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025112997331083307e+02,7.383725701897006957e+02,5.142718394467704623e-01,1.100000010988609489e+01,9.287108403679055976e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025122088240083400e+02,7.383825701896575993e+02,5.142727681576094723e-01,1.100000010988609489e+01,9.272509863525284224e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025131179149083493e+02,7.383925701896146165e+02,5.142736954085944667e-01,1.100000010988609489e+01,9.257911323371512471e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025140270058083587e+02,7.384025701895717475e+02,5.142746211997254457e-01,1.100000010988609489e+01,9.243312783217740719e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025149360967083680e+02,7.384125701895289922e+02,5.142755455310024093e-01,1.100000010988609489e+01,9.228714243063968967e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025158451876083774e+02,7.384225701894864642e+02,5.142764684024253574e-01,1.100000010988609489e+01,9.214115702910197214e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025167542785083867e+02,7.384325701894440499e+02,5.142773898139942901e-01,1.100000010988609489e+01,9.199517162756425462e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025176633694083961e+02,7.384425701894017493e+02,5.142783097657093183e-01,1.100000010988609489e+01,9.184918622602653709e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025185724603084054e+02,7.384525701893595624e+02,5.142792282575703311e-01,1.100000010988609489e+01,9.170320082448881957e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025194815512084148e+02,7.384625701893174892e+02,5.142801452895773284e-01,1.100000010988609489e+01,9.155721542295110205e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025203906421084241e+02,7.384725701892755296e+02,5.142810608617303103e-01,1.100000010988609489e+01,9.141123002141338452e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025212997330084335e+02,7.384825701892337975e+02,5.142819749740292767e-01,1.100000010988609489e+01,9.126524461987566700e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025222088239084428e+02,7.384925701891921790e+02,5.142828876264742277e-01,1.100000010988609489e+01,9.111925921833794947e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025231179148084522e+02,7.385025701891506742e+02,5.142837988190651632e-01,1.100000010988609489e+01,9.097327381680023195e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025240270057084615e+02,7.385125701891092831e+02,5.142847085518020833e-01,1.100000010988609489e+01,9.082728841526251443e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025249360966084708e+02,7.385225701890680057e+02,5.142856168246849879e-01,1.100000010988609489e+01,9.068130301372479690e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025258451875084802e+02,7.385325701890268419e+02,5.142865236377138771e-01,1.100000010988609489e+01,9.053531761218707938e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025267542784084895e+02,7.385425701889859056e+02,5.142874289908887508e-01,1.100000010988609489e+01,9.038933221064936185e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025276633693084989e+02,7.385525701889450829e+02,5.142883328842096091e-01,1.100000010988609489e+01,9.024334680911164433e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025285724602085082e+02,7.385625701889043739e+02,5.142892353176764519e-01,1.100000010988609489e+01,9.009736140757392681e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025294815511085176e+02,7.385725701888637786e+02,5.142901362912892793e-01,1.100000010988609489e+01,8.995137600603620928e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025303906420085269e+02,7.385825701888232970e+02,5.142910358050480912e-01,1.100000010988609489e+01,8.980539060449849176e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025312997329085363e+02,7.385925701887829291e+02,5.142919338589528877e-01,1.100000010988609489e+01,8.965940520296077423e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025322088238085456e+02,7.386025701887427886e+02,5.142928304530036687e-01,1.100000010988609489e+01,8.951341980142305671e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025331179147085550e+02,7.386125701887027617e+02,5.142937255872004343e-01,1.100000010988609489e+01,8.936743439988533919e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025340270056085643e+02,7.386225701886628485e+02,5.142946192615432954e-01,1.100000010988609489e+01,8.922144899834762166e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025349360965085737e+02,7.386325701886230490e+02,5.142955114760321411e-01,1.100000010988609489e+01,8.907546359680990414e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025358451874085830e+02,7.386425701885833632e+02,5.142964022306669714e-01,1.100000010988609489e+01,8.892947819527218661e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025367542783085923e+02,7.386525701885437911e+02,5.142972915254477861e-01,1.100000010988609489e+01,8.878349279373446909e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025376633692086017e+02,7.386625701885043327e+02,5.142981793603745855e-01,1.100000010988609489e+01,8.863750739219675157e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025385724601086110e+02,7.386725701884651016e+02,5.142990657354473694e-01,1.100000010988609489e+01,8.849152199065903404e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025394815510086204e+02,7.386825701884259843e+02,5.142999506506661378e-01,1.100000010988609489e+01,8.834553658912131652e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025403906419086297e+02,7.386925701883869806e+02,5.143008341060308908e-01,1.100000010988609489e+01,8.819955118758359899e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025412997328086391e+02,7.387025701883480906e+02,5.143017161015416283e-01,1.100000010988609489e+01,8.805356578604588147e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025422088237086484e+02,7.387125701883093143e+02,5.143025966371983504e-01,1.100000010988609489e+01,8.790758038450816395e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025431179146086578e+02,7.387225701882706517e+02,5.143034757130010570e-01,1.100000010988609489e+01,8.776159498297044642e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025440270055086671e+02,7.387325701882321027e+02,5.143043533289497482e-01,1.100000010988609489e+01,8.761560958143272890e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025449360964086765e+02,7.387425701881936675e+02,5.143052294850444239e-01,1.100000010988609489e+01,8.746962417989501137e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025458451873086858e+02,7.387525701881554596e+02,5.143061041812850842e-01,1.100000010988609489e+01,8.732363877835729385e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025467542782086952e+02,7.387625701881173654e+02,5.143069774176717290e-01,1.100000010988609489e+01,8.717765337681957633e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025476633691087045e+02,7.387725701880793849e+02,5.143078491942043584e-01,1.100000010988609489e+01,8.703166797528185880e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025485724600087138e+02,7.387825701880415181e+02,5.143087195108829723e-01,1.100000010988609489e+01,8.688568257374414128e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025494815509087232e+02,7.387925701880037650e+02,5.143095883677075708e-01,1.100000010988609489e+01,8.673969717220642375e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025503906418087325e+02,7.388025701879661256e+02,5.143104557646781538e-01,1.100000010988609489e+01,8.659371177066870623e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025512997327087419e+02,7.388125701879285998e+02,5.143113217017948324e-01,1.100000010988609489e+01,8.644772636913098871e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025522088236087512e+02,7.388225701878911877e+02,5.143121861790574956e-01,1.100000010988609489e+01,8.630174096759327118e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025531179145087606e+02,7.388325701878540031e+02,5.143130491964661433e-01,1.100000010988609489e+01,8.615575556605555366e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025540270054087699e+02,7.388425701878169320e+02,5.143139107540207755e-01,1.100000010988609489e+01,8.600977016451783613e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025549360963087793e+02,7.388525701877799747e+02,5.143147708517213923e-01,1.100000010988609489e+01,8.586378476298011861e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025558451872087886e+02,7.388625701877431311e+02,5.143156294895679936e-01,1.100000010988609489e+01,8.571779936144240108e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025567542781087980e+02,7.388725701877064012e+02,5.143164866675605795e-01,1.100000010988609489e+01,8.557181395990468356e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025576633690088073e+02,7.388825701876697849e+02,5.143173423856991500e-01,1.100000010988609489e+01,8.542582855836696604e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025585724599088167e+02,7.388925701876332823e+02,5.143181966439837050e-01,1.100000010988609489e+01,8.527984315682924851e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025594815508088260e+02,7.389025701875968934e+02,5.143190494424142445e-01,1.100000010988609489e+01,8.513385775529153099e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025603906417088353e+02,7.389125701875606183e+02,5.143199007809907686e-01,1.100000010988609489e+01,8.498787235375381346e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025612997326088447e+02,7.389225701875244567e+02,5.143207506597132772e-01,1.100000010988609489e+01,8.484188695221609594e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025622088235088540e+02,7.389325701874885226e+02,5.143215990785817704e-01,1.100000010988609489e+01,8.469590155067837842e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025631179144088634e+02,7.389425701874527022e+02,5.143224460375962481e-01,1.100000010988609489e+01,8.454991614914066089e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025640270053088727e+02,7.389525701874169954e+02,5.143232915367567104e-01,1.100000010988609489e+01,8.440393074760294337e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025649360962088821e+02,7.389625701873814023e+02,5.143241355760631572e-01,1.100000010988609489e+01,8.425794534606522584e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025658451871088914e+02,7.389725701873459229e+02,5.143249781555155886e-01,1.100000010988609489e+01,8.411195994452750832e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025667542780089008e+02,7.389825701873105572e+02,5.143258192751140045e-01,1.100000010988609489e+01,8.396597454298979080e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025676633689089101e+02,7.389925701872753052e+02,5.143266589348584050e-01,1.100000010988609489e+01,8.381998914145207327e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025685724598089195e+02,7.390025701872401669e+02,5.143274971347487901e-01,1.100000010988609489e+01,8.367400373991435575e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025694815507089288e+02,7.390125701872051422e+02,5.143283338747851596e-01,1.100000010988609489e+01,8.352801833837663822e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025703906416089382e+02,7.390225701871702313e+02,5.143291691549676248e-01,1.100000010988609489e+01,8.338203293683892070e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025712997325089475e+02,7.390325701871354340e+02,5.143300029752960745e-01,1.100000010988609489e+01,8.323604753530120318e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025722088234089568e+02,7.390425701871007504e+02,5.143308353357705087e-01,1.100000010988609489e+01,8.309006213376348565e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025731179143089662e+02,7.390525701870661806e+02,5.143316662363909275e-01,1.100000010988609489e+01,8.294407673222576813e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025740270052089755e+02,7.390625701870318380e+02,5.143324956771573309e-01,1.100000010988609489e+01,8.279809133068805060e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025749360961089849e+02,7.390725701869976092e+02,5.143333236580697188e-01,1.100000010988609489e+01,8.265210592915033308e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025758451870089942e+02,7.390825701869634941e+02,5.143341501791280912e-01,1.100000010988609489e+01,8.250612052761261556e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025767542779090036e+02,7.390925701869294926e+02,5.143349752403324482e-01,1.100000010988609489e+01,8.236013512607489803e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025776633688090129e+02,7.391025701868956048e+02,5.143357988416827897e-01,1.100000010988609489e+01,8.221414972453718051e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025785724597090223e+02,7.391125701868618307e+02,5.143366209831791158e-01,1.100000010988609489e+01,8.206816432299946298e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025794815506090316e+02,7.391225701868281703e+02,5.143374416648214265e-01,1.100000010988609489e+01,8.192217892146174546e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025803906415090410e+02,7.391325701867946236e+02,5.143382608866097216e-01,1.100000010988609489e+01,8.177619351992402794e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025812997324090503e+02,7.391425701867611906e+02,5.143390786485440014e-01,1.100000010988609489e+01,8.163020811838631041e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025822088233090597e+02,7.391525701867278713e+02,5.143398949506242657e-01,1.100000010988609489e+01,8.148422271684859289e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025831179142090690e+02,7.391625701866946656e+02,5.143407097928505145e-01,1.100000010988609489e+01,8.133823731531087536e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025840270051090783e+02,7.391725701866615736e+02,5.143415231752227479e-01,1.100000010988609489e+01,8.119225191377315784e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025849360960090877e+02,7.391825701866285954e+02,5.143423350977409658e-01,1.100000010988609489e+01,8.104626651223544032e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025858451869090970e+02,7.391925701865957308e+02,5.143431455604051683e-01,1.100000010988609489e+01,8.090028111069772279e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025867542778091064e+02,7.392025701865629799e+02,5.143439545632153553e-01,1.100000010988609489e+01,8.075429570916000527e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025876633687091157e+02,7.392125701865303427e+02,5.143447621061715269e-01,1.100000010988609489e+01,8.060831030762228774e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025885724596091251e+02,7.392225701864978191e+02,5.143455681892736830e-01,1.100000010988609489e+01,8.046232490608457022e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025894815505091344e+02,7.392325701864654093e+02,5.143463728125218237e-01,1.100000010988609489e+01,8.031633950454685270e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025903906414091438e+02,7.392425701864331131e+02,5.143471759759160600e-01,1.100000010988609489e+01,8.017035410300913517e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025912997323091531e+02,7.392525701864009307e+02,5.143479776794562808e-01,1.100000010988609489e+01,8.002436870147141765e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025922088232091625e+02,7.392625701863688619e+02,5.143487779231424861e-01,1.100000010988609489e+01,7.987838329993370012e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025931179141091718e+02,7.392725701863369068e+02,5.143495767069746760e-01,1.100000010988609489e+01,7.973239789839598260e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025940270050091812e+02,7.392825701863050654e+02,5.143503740309528505e-01,1.100000010988609489e+01,7.958641249685826508e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025949360959091905e+02,7.392925701862734513e+02,5.143511698950770095e-01,1.100000010988609489e+01,7.944042709532054755e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025958451868091998e+02,7.393025701862419510e+02,5.143519642993471530e-01,1.100000010988609489e+01,7.929444169378283003e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025967542777092092e+02,7.393125701862105643e+02,5.143527572437632811e-01,1.100000010988609489e+01,7.914845629224511250e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025976633686092185e+02,7.393225701861792913e+02,5.143535487283253937e-01,1.100000010988609489e+01,7.900247089070739498e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025985724595092279e+02,7.393325701861481321e+02,5.143543387530334909e-01,1.100000010988609489e+01,7.885648548916967746e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.025994815504092372e+02,7.393425701861170865e+02,5.143551273178875727e-01,1.100000010988609489e+01,7.871050008763195993e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026003906413092466e+02,7.393525701860861545e+02,5.143559144228876390e-01,1.100000010988609489e+01,7.856451468609424241e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026012997322092559e+02,7.393625701860553363e+02,5.143567000680336898e-01,1.100000010988609489e+01,7.841852928455652488e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026022088231092653e+02,7.393725701860246318e+02,5.143574842533257252e-01,1.100000010988609489e+01,7.827254388301880736e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026031179140092746e+02,7.393825701859940409e+02,5.143582669787637451e-01,1.100000010988609489e+01,7.812655848148108984e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026040270049092840e+02,7.393925701859635637e+02,5.143590482443477496e-01,1.100000010988609489e+01,7.798057307994337231e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026049360958092933e+02,7.394025701859332003e+02,5.143598280500777387e-01,1.100000010988609489e+01,7.783458767840565479e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026058451867093027e+02,7.394125701859029505e+02,5.143606063959537122e-01,1.100000010988609489e+01,7.768860227686793726e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026067542776093120e+02,7.394225701858728144e+02,5.143613832819756704e-01,1.100000010988609489e+01,7.754261687533021974e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026076633685093213e+02,7.394325701858427919e+02,5.143621587081436131e-01,1.100000010988609489e+01,7.739663147379250221e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026085724594093307e+02,7.394425701858128832e+02,5.143629326744575403e-01,1.100000010988609489e+01,7.725064607225478469e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026094815503093400e+02,7.394525701857830882e+02,5.143637051809174521e-01,1.100000010988609489e+01,7.710466067071706717e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026103906412093494e+02,7.394625701857534068e+02,5.143644762275233484e-01,1.100000010988609489e+01,7.695867526917934964e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026112997321093587e+02,7.394725701857238391e+02,5.143652458142752293e-01,1.100000010988609489e+01,7.681268986764163212e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026122088230093681e+02,7.394825701856943851e+02,5.143660139411732057e-01,1.100000010988609489e+01,7.666670446610391459e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026131179139093774e+02,7.394925701856650448e+02,5.143667806082171667e-01,1.100000010988609489e+01,7.652071906456619707e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026140270048093868e+02,7.395025701856358182e+02,5.143675458154071123e-01,1.100000010988609489e+01,7.637473366302847955e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026149360957093961e+02,7.395125701856067053e+02,5.143683095627430424e-01,1.100000010988609489e+01,7.622874826149076202e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026158451866094055e+02,7.395225701855777061e+02,5.143690718502249570e-01,1.100000010988609489e+01,7.608276285995304450e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026167542775094148e+02,7.395325701855487068e+02,5.143698326778528562e-01,1.100000010988609489e+01,7.593677745841532697e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026176633684094242e+02,7.395425701855198213e+02,5.143705920456267400e-01,1.100000010988609489e+01,7.579079205687760945e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026185724593094335e+02,7.395525701854910494e+02,5.143713499535466083e-01,1.100000010988609489e+01,7.564480665533989193e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026194815502094428e+02,7.395625701854623912e+02,5.143721064016124611e-01,1.100000010988609489e+01,7.549882125380217440e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026203906411094522e+02,7.395725701854338467e+02,5.143728613898242985e-01,1.100000010988609489e+01,7.535283585226445688e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026212997320094615e+02,7.395825701854054159e+02,5.143736149181821204e-01,1.100000010988609489e+01,7.520685045072673935e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026222088229094709e+02,7.395925701853770988e+02,5.143743669866859269e-01,1.100000010988609489e+01,7.506086504918902183e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026231179138094802e+02,7.396025701853488954e+02,5.143751175953357180e-01,1.100000010988609489e+01,7.491487964765130431e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026240270047094896e+02,7.396125701853208056e+02,5.143758667441314936e-01,1.100000010988609489e+01,7.476889424611358678e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026249360956094989e+02,7.396225701852928296e+02,5.143766144330732537e-01,1.100000010988609489e+01,7.462290884457586926e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026258451865095083e+02,7.396325701852649672e+02,5.143773606621609984e-01,1.100000010988609489e+01,7.447692344303815173e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026267542774095176e+02,7.396425701852372185e+02,5.143781054313947276e-01,1.100000010988609489e+01,7.433093804150043421e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026276633683095270e+02,7.396525701852095835e+02,5.143788487407744414e-01,1.100000010988609489e+01,7.418495263996271669e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026285724592095363e+02,7.396625701851820622e+02,5.143795905903001398e-01,1.100000010988609489e+01,7.403896723842499916e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026294815501095457e+02,7.396725701851546546e+02,5.143803309799718226e-01,1.100000010988609489e+01,7.389298183688728164e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026303906410095550e+02,7.396825701851273607e+02,5.143810699097894901e-01,1.100000010988609489e+01,7.374699643534956411e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026312997319095643e+02,7.396925701851001804e+02,5.143818073797531421e-01,1.100000010988609489e+01,7.360101103381184659e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026322088228095737e+02,7.397025701850731139e+02,5.143825433898627786e-01,1.100000010988609489e+01,7.345502563227412907e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026331179137095830e+02,7.397125701850461610e+02,5.143832779401183997e-01,1.100000010988609489e+01,7.330904023073641154e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026340270046095924e+02,7.397225701850193218e+02,5.143840110305200053e-01,1.100000010988609489e+01,7.316305482919869402e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026349360955096017e+02,7.397325701849925963e+02,5.143847426610675955e-01,1.100000010988609489e+01,7.301706942766097649e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026358451864096111e+02,7.397425701849659845e+02,5.143854728317611702e-01,1.100000010988609489e+01,7.287108402612325897e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026367542773096204e+02,7.397525701849394864e+02,5.143862015426008405e-01,1.100000010988609489e+01,7.272509862458554145e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026376633682096298e+02,7.397625701849129882e+02,5.143869287935864953e-01,1.100000010988609489e+01,7.257911322304782392e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026385724591096391e+02,7.397725701848866038e+02,5.143876545847181347e-01,1.100000010988609489e+01,7.243312782151010640e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026394815500096485e+02,7.397825701848603330e+02,5.143883789159957587e-01,1.100000010988609489e+01,7.228714241997238887e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026403906409096578e+02,7.397925701848341760e+02,5.143891017874193672e-01,1.100000010988609489e+01,7.214115701843467135e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026412997318096672e+02,7.398025701848081326e+02,5.143898231989889602e-01,1.100000010988609489e+01,7.199517161689695383e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026422088227096765e+02,7.398125701847822029e+02,5.143905431507045378e-01,1.100000010988609489e+01,7.184918621535923630e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026431179136096858e+02,7.398225701847563869e+02,5.143912616425661000e-01,1.100000010988609489e+01,7.170320081382151878e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026440270045096952e+02,7.398325701847306846e+02,5.143919786745736467e-01,1.100000010988609489e+01,7.155721541228380125e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026449360954097045e+02,7.398425701847050959e+02,5.143926942467271779e-01,1.100000010988609489e+01,7.141123001074608373e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026458451863097139e+02,7.398525701846796210e+02,5.143934083590266937e-01,1.100000010988609489e+01,7.126524460920836621e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026467542772097232e+02,7.398625701846542597e+02,5.143941210114721940e-01,1.100000010988609489e+01,7.111925920767064868e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026476633681097326e+02,7.398725701846290121e+02,5.143948322040636789e-01,1.100000010988609489e+01,7.097327380613293116e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026485724590097419e+02,7.398825701846038783e+02,5.143955419368011484e-01,1.100000010988609489e+01,7.082728840459521363e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026494815499097513e+02,7.398925701845787444e+02,5.143962502096846023e-01,1.100000010988609489e+01,7.068130300305749611e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026503906408097606e+02,7.399025701845537242e+02,5.143969570227140409e-01,1.100000010988609489e+01,7.053531760151977859e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026512997317097700e+02,7.399125701845288177e+02,5.143976623758894640e-01,1.100000010988609489e+01,7.038933219998206106e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026522088226097793e+02,7.399225701845040248e+02,5.143983662692108716e-01,1.100000010988609489e+01,7.024334679844434354e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026531179135097887e+02,7.399325701844793457e+02,5.143990687026782638e-01,1.100000010988609489e+01,7.009736139690662601e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026540270044097980e+02,7.399425701844547802e+02,5.143997696762916405e-01,1.100000010988609489e+01,6.995137599536890849e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026549360953098073e+02,7.399525701844303285e+02,5.144004691900510018e-01,1.100000010988609489e+01,6.980539059383119097e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026558451862098167e+02,7.399625701844059904e+02,5.144011672439563476e-01,1.100000010988609489e+01,6.965940519229347344e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026567542771098260e+02,7.399725701843817660e+02,5.144018638380076780e-01,1.100000010988609489e+01,6.951341979075575592e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026576633680098354e+02,7.399825701843576553e+02,5.144025589722049929e-01,1.100000010988609489e+01,6.936743438921803839e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026585724589098447e+02,7.399925701843335446e+02,5.144032526465482924e-01,1.100000010988609489e+01,6.922144898768032087e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026594815498098541e+02,7.400025701843095476e+02,5.144039448610375764e-01,1.100000010988609489e+01,6.907546358614260334e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026603906407098634e+02,7.400125701842856643e+02,5.144046356156728450e-01,1.100000010988609489e+01,6.892947818460488582e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026612997316098728e+02,7.400225701842618946e+02,5.144053249104540981e-01,1.100000010988609489e+01,6.878349278306716830e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026622088225098821e+02,7.400325701842382387e+02,5.144060127453813358e-01,1.100000010988609489e+01,6.863750738152945077e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026631179134098915e+02,7.400425701842146964e+02,5.144066991204545580e-01,1.100000010988609489e+01,6.849152197999173325e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026640270043099008e+02,7.400525701841912678e+02,5.144073840356738758e-01,1.100000010988609489e+01,6.834553657845401572e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026649360952099101e+02,7.400625701841679529e+02,5.144080674910391782e-01,1.100000010988609489e+01,6.819955117691629820e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026658451861099195e+02,7.400725701841447517e+02,5.144087494865504651e-01,1.100000010988609489e+01,6.805356577537858068e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026667542770099288e+02,7.400825701841215505e+02,5.144094300222077365e-01,1.100000010988609489e+01,6.790758037384086315e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026676633679099382e+02,7.400925701840984630e+02,5.144101090980109925e-01,1.100000010988609489e+01,6.776159497230314563e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026685724588099475e+02,7.401025701840754891e+02,5.144107867139602330e-01,1.100000010988609489e+01,6.761560957076542810e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026694815497099569e+02,7.401125701840526290e+02,5.144114628700554581e-01,1.100000010988609489e+01,6.746962416922771058e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026703906406099662e+02,7.401225701840298825e+02,5.144121375662966678e-01,1.100000010988609489e+01,6.732363876768999306e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026712997315099756e+02,7.401325701840072497e+02,5.144128108026838619e-01,1.100000010988609489e+01,6.717765336615227553e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026722088224099849e+02,7.401425701839847306e+02,5.144134825792170407e-01,1.100000010988609489e+01,6.703166796461455801e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026731179133099943e+02,7.401525701839622116e+02,5.144141528958962040e-01,1.100000010988609489e+01,6.688568256307684048e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026740270042100036e+02,7.401625701839398062e+02,5.144148217527213518e-01,1.100000010988609489e+01,6.673969716153912296e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026749360951100130e+02,7.401725701839175144e+02,5.144154891496924842e-01,1.100000010988609489e+01,6.659371176000140544e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026758451860100223e+02,7.401825701838953364e+02,5.144161550868096011e-01,1.100000010988609489e+01,6.644772635846368791e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026767542769100316e+02,7.401925701838732721e+02,5.144168195640727026e-01,1.100000010988609489e+01,6.630174095692597039e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026776633678100410e+02,7.402025701838513214e+02,5.144174825814817886e-01,1.100000010988609489e+01,6.615575555538825286e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026785724587100503e+02,7.402125701838294844e+02,5.144181441390368592e-01,1.100000010988609489e+01,6.600977015385053534e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026794815496100597e+02,7.402225701838076475e+02,5.144188042367379143e-01,1.100000010988609489e+01,6.586378475231281782e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026803906405100690e+02,7.402325701837859242e+02,5.144194628745849540e-01,1.100000010988609489e+01,6.571779935077510029e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026812997314100784e+02,7.402425701837643146e+02,5.144201200525779782e-01,1.100000010988609489e+01,6.557181394923738277e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026822088223100877e+02,7.402525701837428187e+02,5.144207757707169870e-01,1.100000010988609489e+01,6.542582854769966524e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026831179132100971e+02,7.402625701837214365e+02,5.144214300290019803e-01,1.100000010988609489e+01,6.527984314616194772e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026840270041101064e+02,7.402725701837001679e+02,5.144220828274329582e-01,1.100000010988609489e+01,6.513385774462423020e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026849360950101158e+02,7.402825701836788994e+02,5.144227341660099206e-01,1.100000010988609489e+01,6.498787234308651267e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026858451859101251e+02,7.402925701836577446e+02,5.144233840447328676e-01,1.100000010988609489e+01,6.484188694154879515e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026867542768101345e+02,7.403025701836367034e+02,5.144240324636017991e-01,1.100000010988609489e+01,6.469590154001107762e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026876633677101438e+02,7.403125701836157759e+02,5.144246794226167152e-01,1.100000010988609489e+01,6.454991613847336010e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026885724586101531e+02,7.403225701835949621e+02,5.144253249217776158e-01,1.100000010988609489e+01,6.440393073693564258e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026894815495101625e+02,7.403325701835742620e+02,5.144259689610845010e-01,1.100000010988609489e+01,6.425794533539792505e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026903906404101718e+02,7.403425701835535619e+02,5.144266115405373707e-01,1.100000010988609489e+01,6.411195993386020753e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026912997313101812e+02,7.403525701835329755e+02,5.144272526601362250e-01,1.100000010988609489e+01,6.396597453232249000e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026922088222101905e+02,7.403625701835125028e+02,5.144278923198810638e-01,1.100000010988609489e+01,6.381998913078477248e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026931179131101999e+02,7.403725701834921438e+02,5.144285305197718872e-01,1.100000010988609489e+01,6.367400372924705496e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026940270040102092e+02,7.403825701834718984e+02,5.144291672598086951e-01,1.100000010988609489e+01,6.352801832770933743e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026949360949102186e+02,7.403925701834517668e+02,5.144298025399915986e-01,1.100000010988609489e+01,6.338203292617161991e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026958451858102279e+02,7.404025701834316351e+02,5.144304363603204866e-01,1.100000010988609489e+01,6.323604752463390238e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026967542767102373e+02,7.404125701834116171e+02,5.144310687207953592e-01,1.100000010988609489e+01,6.309006212309618486e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026976633676102466e+02,7.404225701833917128e+02,5.144316996214162163e-01,1.100000010988609489e+01,6.294407672155846734e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026985724585102560e+02,7.404325701833719222e+02,5.144323290621830580e-01,1.100000010988609489e+01,6.279809132002074981e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.026994815494102653e+02,7.404425701833522453e+02,5.144329570430958842e-01,1.100000010988609489e+01,6.265210591848303229e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027003906403102746e+02,7.404525701833325684e+02,5.144335835641546950e-01,1.100000010988609489e+01,6.250612051694531476e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027012997312102840e+02,7.404625701833130051e+02,5.144342086253594903e-01,1.100000010988609489e+01,6.236013511540759724e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027022088221102933e+02,7.404725701832935556e+02,5.144348322267102702e-01,1.100000010988609489e+01,6.221414971386987972e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027031179130103027e+02,7.404825701832742197e+02,5.144354543682070346e-01,1.100000010988609489e+01,6.206816431233216219e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027040270039103120e+02,7.404925701832549976e+02,5.144360750498497836e-01,1.100000010988609489e+01,6.192217891079444467e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027049360948103214e+02,7.405025701832357754e+02,5.144366942716385172e-01,1.100000010988609489e+01,6.177619350925672714e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027058451857103307e+02,7.405125701832166669e+02,5.144373120335732352e-01,1.100000010988609489e+01,6.163020810771900962e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027067542766103401e+02,7.405225701831976721e+02,5.144379283356539379e-01,1.100000010988609489e+01,6.148422270618129210e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027076633675103494e+02,7.405325701831787910e+02,5.144385431778806250e-01,1.100000010988609489e+01,6.133823730464357457e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027085724584103588e+02,7.405425701831600236e+02,5.144391565602532967e-01,1.100000010988609489e+01,6.119225190310585705e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027094815493103681e+02,7.405525701831412562e+02,5.144397684827719530e-01,1.100000010988609489e+01,6.104626650156813952e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027103906402103775e+02,7.405625701831226024e+02,5.144403789454365938e-01,1.100000010988609489e+01,6.090028110003042878e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027112997311103868e+02,7.405725701831040624e+02,5.144409879482472192e-01,1.100000010988609489e+01,6.075429569849271803e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027122088220103961e+02,7.405825701830856360e+02,5.144415954912038291e-01,1.100000010988609489e+01,6.060831029695500728e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027131179129104055e+02,7.405925701830673233e+02,5.144422015743064236e-01,1.100000010988609489e+01,6.046232489541729653e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027140270038104148e+02,7.406025701830490107e+02,5.144428061975550026e-01,1.100000010988609489e+01,6.031633949387958578e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027149360947104242e+02,7.406125701830308117e+02,5.144434093609495662e-01,1.100000010988609489e+01,6.017035409234187504e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027158451856104335e+02,7.406225701830127264e+02,5.144440110644901143e-01,1.100000010988609489e+01,6.002436869080416429e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027167542765104429e+02,7.406325701829947548e+02,5.144446113081766470e-01,1.100000010988609489e+01,5.987838328926645354e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027176633674104522e+02,7.406425701829767831e+02,5.144452100920091642e-01,1.100000010988609489e+01,5.973239788772874279e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027185724583104616e+02,7.406525701829589252e+02,5.144458074159876659e-01,1.100000010988609489e+01,5.958641248619103205e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027194815492104709e+02,7.406625701829411810e+02,5.144464032801121522e-01,1.100000010988609489e+01,5.944042708465332130e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027203906401104803e+02,7.406725701829235504e+02,5.144469976843826231e-01,1.100000010988609489e+01,5.929444168311561055e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027212997310104896e+02,7.406825701829059199e+02,5.144475906287990785e-01,1.100000010988609489e+01,5.914845628157789980e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027222088219104990e+02,7.406925701828884030e+02,5.144481821133615185e-01,1.100000010988609489e+01,5.900247088004018905e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027231179128105083e+02,7.407025701828709998e+02,5.144487721380699430e-01,1.100000010988609489e+01,5.885648547850247831e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027240270037105176e+02,7.407125701828537103e+02,5.144493607029243520e-01,1.100000010988609489e+01,5.871050007696476756e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027249360946105270e+02,7.407225701828364208e+02,5.144499478079247456e-01,1.100000010988609489e+01,5.856451467542705681e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027258451855105363e+02,7.407325701828192450e+02,5.144505334530711238e-01,1.100000010988609489e+01,5.841852927388934606e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027267542764105457e+02,7.407425701828021829e+02,5.144511176383634865e-01,1.100000010988609489e+01,5.827254387235163532e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027276633673105550e+02,7.407525701827852345e+02,5.144517003638018338e-01,1.100000010988609489e+01,5.812655847081392457e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027285724582105644e+02,7.407625701827682860e+02,5.144522816293861656e-01,1.100000010988609489e+01,5.798057306927621382e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027294815491105737e+02,7.407725701827514513e+02,5.144528614351164819e-01,1.100000010988609489e+01,5.783458766773850307e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027303906400105831e+02,7.407825701827347302e+02,5.144534397809927828e-01,1.100000010988609489e+01,5.768860226620079232e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027312997309105924e+02,7.407925701827181229e+02,5.144540166670151793e-01,1.100000010988609489e+01,5.754261686466308158e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027322088218106018e+02,7.408025701827015155e+02,5.144545920931835603e-01,1.100000010988609489e+01,5.739663146312537083e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027331179127106111e+02,7.408125701826850218e+02,5.144551660594979259e-01,1.100000010988609489e+01,5.725064606158766008e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027340270036106205e+02,7.408225701826686418e+02,5.144557385659582760e-01,1.100000010988609489e+01,5.710466066004994933e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027349360945106298e+02,7.408325701826523755e+02,5.144563096125646107e-01,1.100000010988609489e+01,5.695867525851223859e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027358451854106391e+02,7.408425701826361092e+02,5.144568791993169299e-01,1.100000010988609489e+01,5.681268985697452784e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027367542763106485e+02,7.408525701826199565e+02,5.144574473262152337e-01,1.100000010988609489e+01,5.666670445543681709e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027376633672106578e+02,7.408625701826039176e+02,5.144580139932595220e-01,1.100000010988609489e+01,5.652071905389910634e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027385724581106672e+02,7.408725701825879923e+02,5.144585792004497948e-01,1.100000010988609489e+01,5.637473365236139559e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027394815490106765e+02,7.408825701825720671e+02,5.144591429477860522e-01,1.100000010988609489e+01,5.622874825082368485e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027403906399106859e+02,7.408925701825562555e+02,5.144597052352682942e-01,1.100000010988609489e+01,5.608276284928597410e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027412997308106952e+02,7.409025701825405577e+02,5.144602660628965207e-01,1.100000010988609489e+01,5.593677744774826335e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027422088217107046e+02,7.409125701825248598e+02,5.144608254306707318e-01,1.100000010988609489e+01,5.579079204621055260e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027431179126107139e+02,7.409225701825092756e+02,5.144613833385909274e-01,1.100000010988609489e+01,5.564480664467284186e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027440270035107233e+02,7.409325701824938051e+02,5.144619397866571076e-01,1.100000010988609489e+01,5.549882124313513111e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027449360944107326e+02,7.409425701824784483e+02,5.144624947748692723e-01,1.100000010988609489e+01,5.535283584159742036e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027458451853107420e+02,7.409525701824630914e+02,5.144630483032274215e-01,1.100000010988609489e+01,5.520685044005970961e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027467542762107513e+02,7.409625701824478483e+02,5.144636003717315553e-01,1.100000010988609489e+01,5.506086503852199886e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027476633671107606e+02,7.409725701824327189e+02,5.144641509803816737e-01,1.100000010988609489e+01,5.491487963698428812e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027485724580107700e+02,7.409825701824175894e+02,5.144647001291777766e-01,1.100000010988609489e+01,5.476889423544657737e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027494815489107793e+02,7.409925701824025737e+02,5.144652478181198640e-01,1.100000010988609489e+01,5.462290883390886662e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027503906398107887e+02,7.410025701823876716e+02,5.144657940472079360e-01,1.100000010988609489e+01,5.447692343237115587e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027512997307107980e+02,7.410125701823728832e+02,5.144663388164419926e-01,1.100000010988609489e+01,5.433093803083344513e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027522088216108074e+02,7.410225701823580948e+02,5.144668821258220337e-01,1.100000010988609489e+01,5.418495262929573438e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027531179125108167e+02,7.410325701823434201e+02,5.144674239753480594e-01,1.100000010988609489e+01,5.403896722775802363e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027540270034108261e+02,7.410425701823288591e+02,5.144679643650200696e-01,1.100000010988609489e+01,5.389298182622031288e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027549360943108354e+02,7.410525701823142981e+02,5.144685032948380643e-01,1.100000010988609489e+01,5.374699642468260213e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027558451852108448e+02,7.410625701822998508e+02,5.144690407648020436e-01,1.100000010988609489e+01,5.360101102314489139e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027567542761108541e+02,7.410725701822855171e+02,5.144695767749120074e-01,1.100000010988609489e+01,5.345502562160718064e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027576633670108635e+02,7.410825701822711835e+02,5.144701113251679558e-01,1.100000010988609489e+01,5.330904022006946989e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027585724579108728e+02,7.410925701822569636e+02,5.144706444155698888e-01,1.100000010988609489e+01,5.316305481853175914e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027594815488108821e+02,7.411025701822428573e+02,5.144711760461178063e-01,1.100000010988609489e+01,5.301706941699404840e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027603906397108915e+02,7.411125701822287510e+02,5.144717062168117083e-01,1.100000010988609489e+01,5.287108401545633765e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027612997306109008e+02,7.411225701822147585e+02,5.144722349276515949e-01,1.100000010988609489e+01,5.272509861391862690e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027622088215109102e+02,7.411325701822008796e+02,5.144727621786374661e-01,1.100000010988609489e+01,5.257911321238091615e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027631179124109195e+02,7.411425701821870007e+02,5.144732879697693217e-01,1.100000010988609489e+01,5.243312781084320540e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027640270033109289e+02,7.411525701821732355e+02,5.144738123010471620e-01,1.100000010988609489e+01,5.228714240930549466e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027649360942109382e+02,7.411625701821595840e+02,5.144743351724709868e-01,1.100000010988609489e+01,5.214115700776778391e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027658451851109476e+02,7.411725701821460461e+02,5.144748565840407961e-01,1.100000010988609489e+01,5.199517160623007316e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027667542760109569e+02,7.411825701821325083e+02,5.144753765357565900e-01,1.100000010988609489e+01,5.184918620469236241e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027676633669109663e+02,7.411925701821190842e+02,5.144758950276183684e-01,1.100000010988609489e+01,5.170320080315465167e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027685724578109756e+02,7.412025701821057737e+02,5.144764120596261314e-01,1.100000010988609489e+01,5.155721540161694092e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027694815487109850e+02,7.412125701820924633e+02,5.144769276317798790e-01,1.100000010988609489e+01,5.141123000007923017e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027703906396109943e+02,7.412225701820792665e+02,5.144774417440796110e-01,1.100000010988609489e+01,5.126524459854151942e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027712997305110036e+02,7.412325701820660697e+02,5.144779543965253277e-01,1.100000010988609489e+01,5.111925919700380867e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027722088214110130e+02,7.412425701820529866e+02,5.144784655891170289e-01,1.100000010988609489e+01,5.097327379546609793e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027731179123110223e+02,7.412525701820400172e+02,5.144789753218547146e-01,1.100000010988609489e+01,5.082728839392838718e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027740270032110317e+02,7.412625701820270478e+02,5.144794835947383849e-01,1.100000010988609489e+01,5.068130299239067643e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027749360941110410e+02,7.412725701820141921e+02,5.144799904077680397e-01,1.100000010988609489e+01,5.053531759085296568e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027758451850110504e+02,7.412825701820014501e+02,5.144804957609436791e-01,1.100000010988609489e+01,5.038933218931525494e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027767542759110597e+02,7.412925701819887081e+02,5.144809996542654140e-01,1.100000010988609489e+01,5.024334678777754419e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027776633668110691e+02,7.413025701819760798e+02,5.144815020877331335e-01,1.100000010988609489e+01,5.009736138623983344e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027785724577110784e+02,7.413125701819635651e+02,5.144820030613468376e-01,1.100000010988609489e+01,4.995137598470212269e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027794815486110878e+02,7.413225701819510505e+02,5.144825025751065262e-01,1.100000010988609489e+01,4.980539058316441194e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027803906395110971e+02,7.413325701819386495e+02,5.144830006290121993e-01,1.100000010988609489e+01,4.965940518162670120e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027812997304111065e+02,7.413425701819263622e+02,5.144834972230638570e-01,1.100000010988609489e+01,4.951341978008899045e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027822088213111158e+02,7.413525701819140750e+02,5.144839923572614993e-01,1.100000010988609489e+01,4.936743437855127970e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027831179122111251e+02,7.413625701819019014e+02,5.144844860316051260e-01,1.100000010988609489e+01,4.922144897701356895e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027840270031111345e+02,7.413725701818898415e+02,5.144849782460947374e-01,1.100000010988609489e+01,4.907546357547585821e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027849360940111438e+02,7.413825701818777816e+02,5.144854690007303333e-01,1.100000010988609489e+01,4.892947817393814746e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027858451849111532e+02,7.413925701818658354e+02,5.144859582955119137e-01,1.100000010988609489e+01,4.878349277240043671e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027867542758111625e+02,7.414025701818538892e+02,5.144864461304394787e-01,1.100000010988609489e+01,4.863750737086272596e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027876633667111719e+02,7.414125701818420566e+02,5.144869325055130282e-01,1.100000010988609489e+01,4.849152196932501521e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027885724576111812e+02,7.414225701818303378e+02,5.144874174207325623e-01,1.100000010988609489e+01,4.834553656778730447e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027894815485111906e+02,7.414325701818186189e+02,5.144879008760980810e-01,1.100000010988609489e+01,4.819955116624959372e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027903906394111999e+02,7.414425701818070138e+02,5.144883828716095842e-01,1.100000010988609489e+01,4.805356576471188297e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027912997303112093e+02,7.414525701817955223e+02,5.144888634072670719e-01,1.100000010988609489e+01,4.790758036317417222e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027922088212112186e+02,7.414625701817840309e+02,5.144893424830705442e-01,1.100000010988609489e+01,4.776159496163646148e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027931179121112280e+02,7.414725701817726531e+02,5.144898200990200010e-01,1.100000010988609489e+01,4.761560956009875073e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027940270030112373e+02,7.414825701817612753e+02,5.144902962551154424e-01,1.100000010988609489e+01,4.746962415856103998e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027949360939112466e+02,7.414925701817500112e+02,5.144907709513568683e-01,1.100000010988609489e+01,4.732363875702332923e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027958451848112560e+02,7.415025701817388608e+02,5.144912441877442788e-01,1.100000010988609489e+01,4.717765335548561848e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027967542757112653e+02,7.415125701817277104e+02,5.144917159642776738e-01,1.100000010988609489e+01,4.703166795394790774e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027976633666112747e+02,7.415225701817166737e+02,5.144921862809570534e-01,1.100000010988609489e+01,4.688568255241019699e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027985724575112840e+02,7.415325701817056370e+02,5.144926551377824175e-01,1.100000010988609489e+01,4.673969715087248624e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.027994815484112934e+02,7.415425701816947139e+02,5.144931225347537662e-01,1.100000010988609489e+01,4.659371174933477549e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028003906393113027e+02,7.415525701816839046e+02,5.144935884718710994e-01,1.100000010988609489e+01,4.644772634779706475e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028012997302113121e+02,7.415625701816730952e+02,5.144940529491344172e-01,1.100000010988609489e+01,4.630174094625935400e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028022088211113214e+02,7.415725701816623996e+02,5.144945159665437195e-01,1.100000010988609489e+01,4.615575554472164325e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028031179120113308e+02,7.415825701816517039e+02,5.144949775240990064e-01,1.100000010988609489e+01,4.600977014318393250e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028040270029113401e+02,7.415925701816411220e+02,5.144954376218002778e-01,1.100000010988609489e+01,4.586378474164622175e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028049360938113495e+02,7.416025701816306537e+02,5.144958962596475338e-01,1.100000010988609489e+01,4.571779934010851101e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028058451847113588e+02,7.416125701816201854e+02,5.144963534376407743e-01,1.100000010988609489e+01,4.557181393857080026e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028067542756113681e+02,7.416225701816098308e+02,5.144968091557799994e-01,1.100000010988609489e+01,4.542582853703308951e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028076633665113775e+02,7.416325701815994762e+02,5.144972634140652090e-01,1.100000010988609489e+01,4.527984313549537876e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028085724574113868e+02,7.416425701815892353e+02,5.144977162124964032e-01,1.100000010988609489e+01,4.513385773395766802e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028094815483113962e+02,7.416525701815789944e+02,5.144981675510735819e-01,1.100000010988609489e+01,4.498787233241995727e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028103906392114055e+02,7.416625701815688672e+02,5.144986174297967452e-01,1.100000010988609489e+01,4.484188693088224652e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028112997301114149e+02,7.416725701815588536e+02,5.144990658486658930e-01,1.100000010988609489e+01,4.469590152934453577e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028122088210114242e+02,7.416825701815488401e+02,5.144995128076810254e-01,1.100000010988609489e+01,4.454991612780682502e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028131179119114336e+02,7.416925701815389402e+02,5.144999583068421423e-01,1.100000010988609489e+01,4.440393072626911428e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028140270028114429e+02,7.417025701815290404e+02,5.145004023461492437e-01,1.100000010988609489e+01,4.425794532473140353e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028149360937114523e+02,7.417125701815192542e+02,5.145008449256023297e-01,1.100000010988609489e+01,4.411195992319369278e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028158451846114616e+02,7.417225701815094681e+02,5.145012860452014003e-01,1.100000010988609489e+01,4.396597452165598203e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028167542755114710e+02,7.417325701814997956e+02,5.145017257049464554e-01,1.100000010988609489e+01,4.381998912011827129e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028176633664114803e+02,7.417425701814902368e+02,5.145021639048374951e-01,1.100000010988609489e+01,4.367400371858056054e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028185724573114896e+02,7.417525701814806780e+02,5.145026006448745193e-01,1.100000010988609489e+01,4.352801831704284979e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028194815482114990e+02,7.417625701814712329e+02,5.145030359250575280e-01,1.100000010988609489e+01,4.338203291550513904e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028203906391115083e+02,7.417725701814617878e+02,5.145034697453865213e-01,1.100000010988609489e+01,4.323604751396742830e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028212997300115177e+02,7.417825701814524564e+02,5.145039021058614992e-01,1.100000010988609489e+01,4.309006211242971755e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028222088209115270e+02,7.417925701814431250e+02,5.145043330064824616e-01,1.100000010988609489e+01,4.294407671089200680e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028231179118115364e+02,7.418025701814339072e+02,5.145047624472494086e-01,1.100000010988609489e+01,4.279809130935429605e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028240270027115457e+02,7.418125701814248032e+02,5.145051904281623401e-01,1.100000010988609489e+01,4.265210590781658530e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028249360936115551e+02,7.418225701814156992e+02,5.145056169492212561e-01,1.100000010988609489e+01,4.250612050627887456e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028258451845115644e+02,7.418325701814067088e+02,5.145060420104261567e-01,1.100000010988609489e+01,4.236013510474116381e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028267542754115738e+02,7.418425701813977184e+02,5.145064656117770419e-01,1.100000010988609489e+01,4.221414970320345306e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028276633663115831e+02,7.418525701813888418e+02,5.145068877532739116e-01,1.100000010988609489e+01,4.206816430166574231e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028285724572115925e+02,7.418625701813799651e+02,5.145073084349167658e-01,1.100000010988609489e+01,4.192217890012803157e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028294815481116018e+02,7.418725701813712021e+02,5.145077276567056046e-01,1.100000010988609489e+01,4.177619349859032082e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028303906390116111e+02,7.418825701813624391e+02,5.145081454186404279e-01,1.100000010988609489e+01,4.163020809705261007e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028312997299116205e+02,7.418925701813537898e+02,5.145085617207212358e-01,1.100000010988609489e+01,4.148422269551489932e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028322088208116298e+02,7.419025701813451406e+02,5.145089765629480283e-01,1.100000010988609489e+01,4.133823729397718857e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028331179117116392e+02,7.419125701813366049e+02,5.145093899453208053e-01,1.100000010988609489e+01,4.119225189243947783e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028340270026116485e+02,7.419225701813280693e+02,5.145098018678395668e-01,1.100000010988609489e+01,4.104626649090176708e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028349360935116579e+02,7.419325701813196474e+02,5.145102123305043129e-01,1.100000010988609489e+01,4.090028108936405633e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028358451844116672e+02,7.419425701813113392e+02,5.145106213333150436e-01,1.100000010988609489e+01,4.075429568782634558e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028367542753116766e+02,7.419525701813030309e+02,5.145110288762717587e-01,1.100000010988609489e+01,4.060831028628863484e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028376633662116859e+02,7.419625701812948364e+02,5.145114349593744585e-01,1.100000010988609489e+01,4.046232488475092409e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028385724571116953e+02,7.419725701812866419e+02,5.145118395826231428e-01,1.100000010988609489e+01,4.031633948321321334e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028394815480117046e+02,7.419825701812785610e+02,5.145122427460178116e-01,1.100000010988609489e+01,4.017035408167550259e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028403906389117139e+02,7.419925701812704801e+02,5.145126444495584650e-01,1.100000010988609489e+01,4.002436868013779184e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028412997298117233e+02,7.420025701812625130e+02,5.145130446932452140e-01,1.100000010988609489e+01,3.987838327860008110e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028422088207117326e+02,7.420125701812545458e+02,5.145134434770779475e-01,1.100000010988609489e+01,3.973239787706237035e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028431179116117420e+02,7.420225701812466923e+02,5.145138408010566655e-01,1.100000010988609489e+01,3.958641247552465960e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028440270025117513e+02,7.420325701812388388e+02,5.145142366651813681e-01,1.100000010988609489e+01,3.944042707398694885e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028449360934117607e+02,7.420425701812310990e+02,5.145146310694520553e-01,1.100000010988609489e+01,3.929444167244923811e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028458451843117700e+02,7.420525701812233592e+02,5.145150240138687270e-01,1.100000010988609489e+01,3.914845627091152736e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028467542752117794e+02,7.420625701812157331e+02,5.145154154984313832e-01,1.100000010988609489e+01,3.900247086937381661e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028476633661117887e+02,7.420725701812081070e+02,5.145158055231400240e-01,1.100000010988609489e+01,3.885648546783610586e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028485724570117981e+02,7.420825701812005946e+02,5.145161940879946494e-01,1.100000010988609489e+01,3.871050006629839511e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028494815479118074e+02,7.420925701811930821e+02,5.145165811929952593e-01,1.100000010988609489e+01,3.856451466476068437e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028503906388118168e+02,7.421025701811856834e+02,5.145169668381418537e-01,1.100000010988609489e+01,3.841852926322297362e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028512997297118261e+02,7.421125701811782847e+02,5.145173510234344327e-01,1.100000010988609489e+01,3.827254386168526287e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028522088206118354e+02,7.421225701811709996e+02,5.145177337488729963e-01,1.100000010988609489e+01,3.812655846014755212e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028531179115118448e+02,7.421325701811637146e+02,5.145181150144575444e-01,1.100000010988609489e+01,3.798057305860984138e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028540270024118541e+02,7.421425701811565432e+02,5.145184948201880770e-01,1.100000010988609489e+01,3.783458765707213063e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028549360933118635e+02,7.421525701811493718e+02,5.145188731660645942e-01,1.100000010988609489e+01,3.768860225553441988e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028558451842118728e+02,7.421625701811423141e+02,5.145192500520870960e-01,1.100000010988609489e+01,3.754261685399670913e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028567542751118822e+02,7.421725701811352565e+02,5.145196254782555823e-01,1.100000010988609489e+01,3.739663145245899838e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028576633660118915e+02,7.421825701811283125e+02,5.145199994445700531e-01,1.100000010988609489e+01,3.725064605092128764e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028585724569119009e+02,7.421925701811213685e+02,5.145203719510305085e-01,1.100000010988609489e+01,3.710466064938357689e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028594815478119102e+02,7.422025701811145382e+02,5.145207429976369484e-01,1.100000010988609489e+01,3.695867524784586614e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028603906387119196e+02,7.422125701811077079e+02,5.145211125843893729e-01,1.100000010988609489e+01,3.681268984630815539e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028612997296119289e+02,7.422225701811008776e+02,5.145214807112877820e-01,1.100000010988609489e+01,3.666670444477044465e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028622088205119383e+02,7.422325701810941609e+02,5.145218473783321755e-01,1.100000010988609489e+01,3.652071904323273390e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028631179114119476e+02,7.422425701810874443e+02,5.145222125855225537e-01,1.100000010988609489e+01,3.637473364169502315e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028640270023119569e+02,7.422525701810808414e+02,5.145225763328589164e-01,1.100000010988609489e+01,3.622874824015731240e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028649360932119663e+02,7.422625701810742385e+02,5.145229386203412636e-01,1.100000010988609489e+01,3.608276283861960165e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028658451841119756e+02,7.422725701810677492e+02,5.145232994479695954e-01,1.100000010988609489e+01,3.593677743708189091e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028667542750119850e+02,7.422825701810612600e+02,5.145236588157439117e-01,1.100000010988609489e+01,3.579079203554418016e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028676633659119943e+02,7.422925701810548844e+02,5.145240167236642126e-01,1.100000010988609489e+01,3.564480663400646941e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028685724568120037e+02,7.423025701810485089e+02,5.145243731717304980e-01,1.100000010988609489e+01,3.549882123246875866e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028694815477120130e+02,7.423125701810422470e+02,5.145247281599427680e-01,1.100000010988609489e+01,3.535283583093104792e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028703906386120224e+02,7.423225701810359851e+02,5.145250816883010225e-01,1.100000010988609489e+01,3.520685042939333717e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028712997295120317e+02,7.423325701810298369e+02,5.145254337568052616e-01,1.100000010988609489e+01,3.506086502785562642e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028722088204120411e+02,7.423425701810236887e+02,5.145257843654554852e-01,1.100000010988609489e+01,3.491487962631791567e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028731179113120504e+02,7.423525701810175406e+02,5.145261335142516934e-01,1.100000010988609489e+01,3.476889422478020492e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028740270022120598e+02,7.423625701810115061e+02,5.145264812031938861e-01,1.100000010988609489e+01,3.462290882324249418e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028749360931120691e+02,7.423725701810054716e+02,5.145268274322820634e-01,1.100000010988609489e+01,3.447692342170478343e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028758451840120784e+02,7.423825701809995508e+02,5.145271722015162252e-01,1.100000010988609489e+01,3.433093802016707268e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028767542749120878e+02,7.423925701809936299e+02,5.145275155108963716e-01,1.100000010988609489e+01,3.418495261862936193e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028776633658120971e+02,7.424025701809878228e+02,5.145278573604225025e-01,1.100000010988609489e+01,3.403896721709165119e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028785724567121065e+02,7.424125701809820157e+02,5.145281977500946180e-01,1.100000010988609489e+01,3.389298181555394044e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028794815476121158e+02,7.424225701809763223e+02,5.145285366799127180e-01,1.100000010988609489e+01,3.374699641401622969e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028803906385121252e+02,7.424325701809706288e+02,5.145288741498768026e-01,1.100000010988609489e+01,3.360101101247851894e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028812997294121345e+02,7.424425701809649354e+02,5.145292101599868717e-01,1.100000010988609489e+01,3.345502561094080819e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028822088203121439e+02,7.424525701809593556e+02,5.145295447102429254e-01,1.100000010988609489e+01,3.330904020940309745e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028831179112121532e+02,7.424625701809537759e+02,5.145298778006449636e-01,1.100000010988609489e+01,3.316305480786538670e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028840270021121626e+02,7.424725701809483098e+02,5.145302094311929864e-01,1.100000010988609489e+01,3.301706940632767595e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028849360930121719e+02,7.424825701809428438e+02,5.145305396018869937e-01,1.100000010988609489e+01,3.287108400478996520e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028858451839121813e+02,7.424925701809374914e+02,5.145308683127269855e-01,1.100000010988609489e+01,3.272509860325225446e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028867542748121906e+02,7.425025701809321390e+02,5.145311955637129619e-01,1.100000010988609489e+01,3.257911320171454371e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028876633657121999e+02,7.425125701809267866e+02,5.145315213548449229e-01,1.100000010988609489e+01,3.243312780017683296e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028885724566122093e+02,7.425225701809215479e+02,5.145318456861228684e-01,1.100000010988609489e+01,3.228714239863912221e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028894815475122186e+02,7.425325701809163093e+02,5.145321685575467985e-01,1.100000010988609489e+01,3.214115699710141146e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028903906384122280e+02,7.425425701809111843e+02,5.145324899691167131e-01,1.100000010988609489e+01,3.199517159556370072e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028912997293122373e+02,7.425525701809060592e+02,5.145328099208326122e-01,1.100000010988609489e+01,3.184918619402598997e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028922088202122467e+02,7.425625701809009342e+02,5.145331284126944960e-01,1.100000010988609489e+01,3.170320079248827922e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028931179111122560e+02,7.425725701808959229e+02,5.145334454447023642e-01,1.100000010988609489e+01,3.155721539095056847e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028940270020122654e+02,7.425825701808909116e+02,5.145337610168562170e-01,1.100000010988609489e+01,3.141122998941285773e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028949360929122747e+02,7.425925701808860140e+02,5.145340751291560544e-01,1.100000010988609489e+01,3.126524458787514698e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028958451838122841e+02,7.426025701808811164e+02,5.145343877816018763e-01,1.100000010988609489e+01,3.111925918633743623e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028967542747122934e+02,7.426125701808762187e+02,5.145346989741936827e-01,1.100000010988609489e+01,3.097327378479972548e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028976633656123028e+02,7.426225701808714348e+02,5.145350087069314737e-01,1.100000010988609489e+01,3.082728838326201473e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028985724565123121e+02,7.426325701808666508e+02,5.145353169798152493e-01,1.100000010988609489e+01,3.068130298172430399e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.028994815474123214e+02,7.426425701808619806e+02,5.145356237928450094e-01,1.100000010988609489e+01,3.053531758018659324e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029003906383123308e+02,7.426525701808573103e+02,5.145359291460207540e-01,1.100000010988609489e+01,3.038933217864887910e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029012997292123401e+02,7.426625701808526401e+02,5.145362330393424832e-01,1.100000010988609489e+01,3.024334677711116497e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029022088201123495e+02,7.426725701808480835e+02,5.145365354728101970e-01,1.100000010988609489e+01,3.009736137557345083e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029031179110123588e+02,7.426825701808435269e+02,5.145368364464238953e-01,1.100000010988609489e+01,2.995137597403573670e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029040270019123682e+02,7.426925701808390841e+02,5.145371359601835781e-01,1.100000010988609489e+01,2.980539057249802256e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029049360928123775e+02,7.427025701808346412e+02,5.145374340140892455e-01,1.100000010988609489e+01,2.965940517096030842e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029058451837123869e+02,7.427125701808301983e+02,5.145377306081408975e-01,1.100000010988609489e+01,2.951341976942259429e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029067542746123962e+02,7.427225701808258691e+02,5.145380257423385340e-01,1.100000010988609489e+01,2.936743436788488015e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029076633655124056e+02,7.427325701808215399e+02,5.145383194166821550e-01,1.100000010988609489e+01,2.922144896634716602e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029085724564124149e+02,7.427425701808173244e+02,5.145386116311717606e-01,1.100000010988609489e+01,2.907546356480945188e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029094815473124243e+02,7.427525701808131089e+02,5.145389023858073507e-01,1.100000010988609489e+01,2.892947816327173774e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029103906382124336e+02,7.427625701808088934e+02,5.145391916805889254e-01,1.100000010988609489e+01,2.878349276173402361e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029112997291124429e+02,7.427725701808047916e+02,5.145394795155164847e-01,1.100000010988609489e+01,2.863750736019630947e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029122088200124523e+02,7.427825701808006897e+02,5.145397658905900284e-01,1.100000010988609489e+01,2.849152195865859534e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029131179109124616e+02,7.427925701807965879e+02,5.145400508058095568e-01,1.100000010988609489e+01,2.834553655712088120e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029140270018124710e+02,7.428025701807925998e+02,5.145403342611750697e-01,1.100000010988609489e+01,2.819955115558316706e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029149360927124803e+02,7.428125701807886117e+02,5.145406162566865671e-01,1.100000010988609489e+01,2.805356575404545293e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029158451836124897e+02,7.428225701807846235e+02,5.145408967923440491e-01,1.100000010988609489e+01,2.790758035250773879e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029167542745124990e+02,7.428325701807807491e+02,5.145411758681475156e-01,1.100000010988609489e+01,2.776159495097002466e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029176633654125084e+02,7.428425701807768746e+02,5.145414534840969667e-01,1.100000010988609489e+01,2.761560954943231052e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029185724563125177e+02,7.428525701807731139e+02,5.145417296401924023e-01,1.100000010988609489e+01,2.746962414789459639e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029194815472125271e+02,7.428625701807693531e+02,5.145420043364338225e-01,1.100000010988609489e+01,2.732363874635688225e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029203906381125364e+02,7.428725701807655923e+02,5.145422775728212272e-01,1.100000010988609489e+01,2.717765334481916811e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029212997290125458e+02,7.428825701807619453e+02,5.145425493493546165e-01,1.100000010988609489e+01,2.703166794328145398e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029222088199125551e+02,7.428925701807582982e+02,5.145428196660339903e-01,1.100000010988609489e+01,2.688568254174373984e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029231179108125644e+02,7.429025701807546511e+02,5.145430885228593487e-01,1.100000010988609489e+01,2.673969714020602571e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029240270017125738e+02,7.429125701807511177e+02,5.145433559198306916e-01,1.100000010988609489e+01,2.659371173866831157e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029249360926125831e+02,7.429225701807475843e+02,5.145436218569480191e-01,1.100000010988609489e+01,2.644772633713059743e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029258451835125925e+02,7.429325701807440510e+02,5.145438863342113311e-01,1.100000010988609489e+01,2.630174093559288330e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029267542744126018e+02,7.429425701807406313e+02,5.145441493516206277e-01,1.100000010988609489e+01,2.615575553405516916e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029276633653126112e+02,7.429525701807372116e+02,5.145444109091759088e-01,1.100000010988609489e+01,2.600977013251745503e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029285724562126205e+02,7.429625701807337919e+02,5.145446710068771745e-01,1.100000010988609489e+01,2.586378473097974089e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029294815471126299e+02,7.429725701807304858e+02,5.145449296447244247e-01,1.100000010988609489e+01,2.571779932944202675e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029303906380126392e+02,7.429825701807271798e+02,5.145451868227176595e-01,1.100000010988609489e+01,2.557181392790431262e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029312997289126486e+02,7.429925701807238738e+02,5.145454425408568788e-01,1.100000010988609489e+01,2.542582852636659848e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029322088198126579e+02,7.430025701807206815e+02,5.145456967991420827e-01,1.100000010988609489e+01,2.527984312482888435e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029331179107126673e+02,7.430125701807174892e+02,5.145459495975732711e-01,1.100000010988609489e+01,2.513385772329117021e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029340270016126766e+02,7.430225701807142968e+02,5.145462009361504441e-01,1.100000010988609489e+01,2.498787232175345607e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029349360925126859e+02,7.430325701807112182e+02,5.145464508148736016e-01,1.100000010988609489e+01,2.484188692021574194e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029358451834126953e+02,7.430425701807081396e+02,5.145466992337427437e-01,1.100000010988609489e+01,2.469590151867802780e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029367542743127046e+02,7.430525701807050609e+02,5.145469461927578703e-01,1.100000010988609489e+01,2.454991611714031367e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029376633652127140e+02,7.430625701807020960e+02,5.145471916919189814e-01,1.100000010988609489e+01,2.440393071560259953e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029385724561127233e+02,7.430725701806991310e+02,5.145474357312260771e-01,1.100000010988609489e+01,2.425794531406488540e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029394815470127327e+02,7.430825701806961661e+02,5.145476783106791574e-01,1.100000010988609489e+01,2.411195991252717126e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029403906379127420e+02,7.430925701806933148e+02,5.145479194302782222e-01,1.100000010988609489e+01,2.396597451098945712e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029412997288127514e+02,7.431025701806904635e+02,5.145481590900232716e-01,1.100000010988609489e+01,2.381998910945174299e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029422088197127607e+02,7.431125701806876123e+02,5.145483972899143055e-01,1.100000010988609489e+01,2.367400370791402885e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029431179106127701e+02,7.431225701806847610e+02,5.145486340299513239e-01,1.100000010988609489e+01,2.352801830637631472e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029440270015127794e+02,7.431325701806820234e+02,5.145488693101343269e-01,1.100000010988609489e+01,2.338203290483860058e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029449360924127888e+02,7.431425701806792858e+02,5.145491031304633145e-01,1.100000010988609489e+01,2.323604750330088644e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029458451833127981e+02,7.431525701806765483e+02,5.145493354909382866e-01,1.100000010988609489e+01,2.309006210176317231e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029467542742128074e+02,7.431625701806739244e+02,5.145495663915592433e-01,1.100000010988609489e+01,2.294407670022545817e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029476633651128168e+02,7.431725701806713005e+02,5.145497958323261845e-01,1.100000010988609489e+01,2.279809129868774404e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029485724560128261e+02,7.431825701806686766e+02,5.145500238132391102e-01,1.100000010988609489e+01,2.265210589715002990e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029494815469128355e+02,7.431925701806661664e+02,5.145502503342980205e-01,1.100000010988609489e+01,2.250612049561231576e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029503906378128448e+02,7.432025701806636562e+02,5.145504753955029154e-01,1.100000010988609489e+01,2.236013509407460163e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029512997287128542e+02,7.432125701806611460e+02,5.145506989968537948e-01,1.100000010988609489e+01,2.221414969253688749e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029522088196128635e+02,7.432225701806586358e+02,5.145509211383506587e-01,1.100000010988609489e+01,2.206816429099917336e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029531179105128729e+02,7.432325701806562392e+02,5.145511418199935072e-01,1.100000010988609489e+01,2.192217888946145922e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029540270014128822e+02,7.432425701806538427e+02,5.145513610417823402e-01,1.100000010988609489e+01,2.177619348792374508e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029549360923128916e+02,7.432525701806514462e+02,5.145515788037171578e-01,1.100000010988609489e+01,2.163020808638603095e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029558451832129009e+02,7.432625701806491634e+02,5.145517951057979600e-01,1.100000010988609489e+01,2.148422268484831681e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029567542741129103e+02,7.432725701806468805e+02,5.145520099480247467e-01,1.100000010988609489e+01,2.133823728331060268e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029576633650129196e+02,7.432825701806445977e+02,5.145522233303975179e-01,1.100000010988609489e+01,2.119225188177288854e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029585724559129289e+02,7.432925701806423149e+02,5.145524352529162737e-01,1.100000010988609489e+01,2.104626648023517441e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029594815468129383e+02,7.433025701806401457e+02,5.145526457155810141e-01,1.100000010988609489e+01,2.090028107869746027e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029603906377129476e+02,7.433125701806379766e+02,5.145528547183917389e-01,1.100000010988609489e+01,2.075429567715974613e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029612997286129570e+02,7.433225701806358074e+02,5.145530622613484484e-01,1.100000010988609489e+01,2.060831027562203200e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029622088195129663e+02,7.433325701806336383e+02,5.145532683444511424e-01,1.100000010988609489e+01,2.046232487408431786e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029631179104129757e+02,7.433425701806315828e+02,5.145534729676998209e-01,1.100000010988609489e+01,2.031633947254660373e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029640270013129850e+02,7.433525701806295274e+02,5.145536761310944840e-01,1.100000010988609489e+01,2.017035407100888959e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029649360922129944e+02,7.433625701806274719e+02,5.145538778346351316e-01,1.100000010988609489e+01,2.002436866947117545e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029658451831130037e+02,7.433725701806254165e+02,5.145540780783217638e-01,1.100000010988609489e+01,1.987838326793346132e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029667542740130131e+02,7.433825701806234747e+02,5.145542768621543805e-01,1.100000010988609489e+01,1.973239786639574718e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029676633649130224e+02,7.433925701806215329e+02,5.145544741861329818e-01,1.100000010988609489e+01,1.958641246485803305e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029685724558130318e+02,7.434025701806195912e+02,5.145546700502575677e-01,1.100000010988609489e+01,1.944042706332031891e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029694815467130411e+02,7.434125701806176494e+02,5.145548644545281380e-01,1.100000010988609489e+01,1.929444166178260477e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029703906376130504e+02,7.434225701806158213e+02,5.145550573989446930e-01,1.100000010988609489e+01,1.914845626024489064e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029712997285130598e+02,7.434325701806139932e+02,5.145552488835072324e-01,1.100000010988609489e+01,1.900247085870717650e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029722088194130691e+02,7.434425701806121651e+02,5.145554389082157565e-01,1.100000010988609489e+01,1.885648545716946237e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029731179103130785e+02,7.434525701806103370e+02,5.145556274730702651e-01,1.100000010988609489e+01,1.871050005563174823e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029740270012130878e+02,7.434625701806086226e+02,5.145558145780707582e-01,1.100000010988609489e+01,1.856451465409403410e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029749360921130972e+02,7.434725701806069083e+02,5.145560002232172359e-01,1.100000010988609489e+01,1.841852925255631996e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029758451830131065e+02,7.434825701806051939e+02,5.145561844085096981e-01,1.100000010988609489e+01,1.827254385101860582e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029767542739131159e+02,7.434925701806034795e+02,5.145563671339481449e-01,1.100000010988609489e+01,1.812655844948089169e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029776633648131252e+02,7.435025701806018787e+02,5.145565483995325762e-01,1.100000010988609489e+01,1.798057304794317755e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029785724557131346e+02,7.435125701806002780e+02,5.145567282052629920e-01,1.100000010988609489e+01,1.783458764640546342e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029794815466131439e+02,7.435225701805986773e+02,5.145569065511393925e-01,1.100000010988609489e+01,1.768860224486774928e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029803906375131533e+02,7.435325701805970766e+02,5.145570834371617774e-01,1.100000010988609489e+01,1.754261684333003514e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029812997284131626e+02,7.435425701805955896e+02,5.145572588633301470e-01,1.100000010988609489e+01,1.739663144179232101e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029822088193131719e+02,7.435525701805941026e+02,5.145574328296445010e-01,1.100000010988609489e+01,1.725064604025460687e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029831179102131813e+02,7.435625701805926155e+02,5.145576053361048396e-01,1.100000010988609489e+01,1.710466063871689274e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029840270011131906e+02,7.435725701805911285e+02,5.145577763827112738e-01,1.100000010988609489e+01,1.695867523717917860e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029849360920132000e+02,7.435825701805896415e+02,5.145579459694636926e-01,1.100000010988609489e+01,1.681268983564146446e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029858451829132093e+02,7.435925701805882682e+02,5.145581140963620959e-01,1.100000010988609489e+01,1.666670443410375033e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029867542738132187e+02,7.436025701805868948e+02,5.145582807634064837e-01,1.100000010988609489e+01,1.652071903256603619e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029876633647132280e+02,7.436125701805855215e+02,5.145584459705968561e-01,1.100000010988609489e+01,1.637473363102832206e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029885724556132374e+02,7.436225701805841481e+02,5.145586097179332130e-01,1.100000010988609489e+01,1.622874822949060792e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029894815465132467e+02,7.436325701805827748e+02,5.145587720054155545e-01,1.100000010988609489e+01,1.608276282795289378e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029903906374132561e+02,7.436425701805815152e+02,5.145589328330438805e-01,1.100000010988609489e+01,1.593677742641517965e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029912997283132654e+02,7.436525701805802555e+02,5.145590922008181911e-01,1.100000010988609489e+01,1.579079202487746551e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029922088192132748e+02,7.436625701805789959e+02,5.145592501087384862e-01,1.100000010988609489e+01,1.564480662333975138e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029931179101132841e+02,7.436725701805777362e+02,5.145594065568047659e-01,1.100000010988609489e+01,1.549882122180203724e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029940270010132934e+02,7.436825701805765902e+02,5.145595615450170301e-01,1.100000010988609489e+01,1.535283582026432311e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029949360919133028e+02,7.436925701805754443e+02,5.145597150733752789e-01,1.100000010988609489e+01,1.520685041872661066e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029958451828133121e+02,7.437025701805742983e+02,5.145598671418795123e-01,1.100000010988609489e+01,1.506086501718889822e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029967542737133215e+02,7.437125701805731524e+02,5.145600177505297301e-01,1.100000010988609489e+01,1.491487961565118578e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029976633646133308e+02,7.437225701805720064e+02,5.145601668993259326e-01,1.100000010988609489e+01,1.476889421411347334e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029985724555133402e+02,7.437325701805708604e+02,5.145603145882681195e-01,1.100000010988609489e+01,1.462290881257576090e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.029994815464133495e+02,7.437425701805698282e+02,5.145604608173562911e-01,1.100000010988609489e+01,1.447692341103804845e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030003906373133589e+02,7.437525701805687959e+02,5.145606055865904471e-01,1.100000010988609489e+01,1.433093800950033601e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030012997282133682e+02,7.437625701805677636e+02,5.145607488959705877e-01,1.100000010988609489e+01,1.418495260796262357e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030022088191133776e+02,7.437725701805667313e+02,5.145608907454967129e-01,1.100000010988609489e+01,1.403896720642491113e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030031179100133869e+02,7.437825701805656990e+02,5.145610311351688226e-01,1.100000010988609489e+01,1.389298180488719869e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030040270009133963e+02,7.437925701805647805e+02,5.145611700649869169e-01,1.100000010988609489e+01,1.374699640334948624e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030049360918134056e+02,7.438025701805638619e+02,5.145613075349509957e-01,1.100000010988609489e+01,1.360101100181177380e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030058451827134149e+02,7.438125701805629433e+02,5.145614435450610591e-01,1.100000010988609489e+01,1.345502560027406136e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030067542736134243e+02,7.438225701805620247e+02,5.145615780953171070e-01,1.100000010988609489e+01,1.330904019873634892e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030076633645134336e+02,7.438325701805611061e+02,5.145617111857191395e-01,1.100000010988609489e+01,1.316305479719863648e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030085724554134430e+02,7.438425701805601875e+02,5.145618428162671565e-01,1.100000010988609489e+01,1.301706939566092404e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030094815463134523e+02,7.438525701805593826e+02,5.145619729869611580e-01,1.100000010988609489e+01,1.287108399412321159e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030103906372134617e+02,7.438625701805585777e+02,5.145621016978011442e-01,1.100000010988609489e+01,1.272509859258549915e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030112997281134710e+02,7.438725701805577728e+02,5.145622289487871148e-01,1.100000010988609489e+01,1.257911319104778671e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030122088190134804e+02,7.438825701805569679e+02,5.145623547399190700e-01,1.100000010988609489e+01,1.243312778951007427e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030131179099134897e+02,7.438925701805561630e+02,5.145624790711970098e-01,1.100000010988609489e+01,1.228714238797236183e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030140270008134991e+02,7.439025701805553581e+02,5.145626019426209341e-01,1.100000010988609489e+01,1.214115698643464938e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030149360917135084e+02,7.439125701805546669e+02,5.145627233541908430e-01,1.100000010988609489e+01,1.199517158489693694e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030158451826135177e+02,7.439225701805539757e+02,5.145628433059067364e-01,1.100000010988609489e+01,1.184918618335922450e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030167542735135271e+02,7.439325701805532844e+02,5.145629617977686143e-01,1.100000010988609489e+01,1.170320078182151206e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030176633644135364e+02,7.439425701805525932e+02,5.145630788297764768e-01,1.100000010988609489e+01,1.155721538028379962e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030185724553135458e+02,7.439525701805519020e+02,5.145631944019303239e-01,1.100000010988609489e+01,1.141122997874608718e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030194815462135551e+02,7.439625701805512108e+02,5.145633085142301555e-01,1.100000010988609489e+01,1.126524457720837473e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030203906371135645e+02,7.439725701805505196e+02,5.145634211666759716e-01,1.100000010988609489e+01,1.111925917567066229e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030212997280135738e+02,7.439825701805499421e+02,5.145635323592677723e-01,1.100000010988609489e+01,1.097327377413294985e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030222088189135832e+02,7.439925701805493645e+02,5.145636420920055576e-01,1.100000010988609489e+01,1.082728837259523741e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030231179098135925e+02,7.440025701805487870e+02,5.145637503648893274e-01,1.100000010988609489e+01,1.068130297105752497e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030240270007136019e+02,7.440125701805482095e+02,5.145638571779190817e-01,1.100000010988609489e+01,1.053531756951981252e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030249360916136112e+02,7.440225701805476319e+02,5.145639625310948206e-01,1.100000010988609489e+01,1.038933216798210008e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030258451825136206e+02,7.440325701805470544e+02,5.145640664244165441e-01,1.100000010988609489e+01,1.024334676644438764e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030267542734136299e+02,7.440425701805464769e+02,5.145641688578842521e-01,1.100000010988609489e+01,1.009736136490667520e-05,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030276633643136392e+02,7.440525701805460130e+02,5.145642698314979446e-01,1.100000010988609489e+01,9.951375963368962757e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030285724552136486e+02,7.440625701805455492e+02,5.145643693452576217e-01,1.100000010988609489e+01,9.805390561831250315e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030294815461136579e+02,7.440725701805450853e+02,5.145644673991632834e-01,1.100000010988609489e+01,9.659405160293537874e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030303906370136673e+02,7.440825701805446215e+02,5.145645639932149296e-01,1.100000010988609489e+01,9.513419758755825432e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030312997279136766e+02,7.440925701805441577e+02,5.145646591274125603e-01,1.100000010988609489e+01,9.367434357218112990e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030322088188136860e+02,7.441025701805436938e+02,5.145647528017561756e-01,1.100000010988609489e+01,9.221448955680400548e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030331179097136953e+02,7.441125701805432300e+02,5.145648450162457754e-01,1.100000010988609489e+01,9.075463554142688106e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030340270006137047e+02,7.441225701805427661e+02,5.145649357708813598e-01,1.100000010988609489e+01,8.929478152604975664e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030349360915137140e+02,7.441325701805424160e+02,5.145650250656629288e-01,1.100000010988609489e+01,8.783492751067263223e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030358451824137234e+02,7.441425701805420658e+02,5.145651129005904822e-01,1.100000010988609489e+01,8.637507349529550781e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030367542733137327e+02,7.441525701805417157e+02,5.145651992756640203e-01,1.100000010988609489e+01,8.491521947991838339e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030376633642137421e+02,7.441625701805413655e+02,5.145652841908835429e-01,1.100000010988609489e+01,8.345536546454125897e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030385724551137514e+02,7.441725701805410154e+02,5.145653676462490500e-01,1.100000010988609489e+01,8.199551144916413455e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030394815460137607e+02,7.441825701805406652e+02,5.145654496417605417e-01,1.100000010988609489e+01,8.053565743378701013e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030403906369137701e+02,7.441925701805403151e+02,5.145655301774180179e-01,1.100000010988609489e+01,7.907580341840988572e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030412997278137794e+02,7.442025701805399649e+02,5.145656092532214787e-01,1.100000010988609489e+01,7.761594940303276130e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030422088187137888e+02,7.442125701805396147e+02,5.145656868691709240e-01,1.100000010988609489e+01,7.615609538765562841e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030431179096137981e+02,7.442225701805393783e+02,5.145657630252663539e-01,1.100000010988609489e+01,7.469624137227849552e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030440270005138075e+02,7.442325701805391418e+02,5.145658377215077683e-01,1.100000010988609489e+01,7.323638735690136263e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030449360914138168e+02,7.442425701805389053e+02,5.145659109578951673e-01,1.100000010988609489e+01,7.177653334152422974e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030458451823138262e+02,7.442525701805386689e+02,5.145659827344285508e-01,1.100000010988609489e+01,7.031667932614709685e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030467542732138355e+02,7.442625701805384324e+02,5.145660530511079189e-01,1.100000010988609489e+01,6.885682531076996396e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030476633641138449e+02,7.442725701805381959e+02,5.145661219079332716e-01,1.100000010988609489e+01,6.739697129539283108e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030485724550138542e+02,7.442825701805379595e+02,5.145661893049046087e-01,1.100000010988609489e+01,6.593711728001569819e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030494815459138636e+02,7.442925701805377230e+02,5.145662552420219304e-01,1.100000010988609489e+01,6.447726326463856530e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030503906368138729e+02,7.443025701805374865e+02,5.145663197192852367e-01,1.100000010988609489e+01,6.301740924926143241e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030512997277138822e+02,7.443125701805372501e+02,5.145663827366945275e-01,1.100000010988609489e+01,6.155755523388429952e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030522088186138916e+02,7.443225701805370136e+02,5.145664442942498029e-01,1.100000010988609489e+01,6.009770121850716663e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030531179095139009e+02,7.443325701805367771e+02,5.145665043919510628e-01,1.100000010988609489e+01,5.863784720313003374e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030540270004139103e+02,7.443425701805366543e+02,5.145665630297983073e-01,1.100000010988609489e+01,5.717799318775290085e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030549360913139196e+02,7.443525701805365316e+02,5.145666202077915363e-01,1.100000010988609489e+01,5.571813917237576797e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030558451822139290e+02,7.443625701805364088e+02,5.145666759259307499e-01,1.100000010988609489e+01,5.425828515699863508e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030567542731139383e+02,7.443725701805362860e+02,5.145667301842159480e-01,1.100000010988609489e+01,5.279843114162150219e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030576633640139477e+02,7.443825701805361632e+02,5.145667829826471307e-01,1.100000010988609489e+01,5.133857712624436930e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030585724549139570e+02,7.443925701805360404e+02,5.145668343212242979e-01,1.100000010988609489e+01,4.987872311086723641e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030594815458139664e+02,7.444025701805359176e+02,5.145668841999474497e-01,1.100000010988609489e+01,4.841886909549010352e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030603906367139757e+02,7.444125701805357949e+02,5.145669326188165860e-01,1.100000010988609489e+01,4.695901508011297063e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030612997276139851e+02,7.444225701805356721e+02,5.145669795778317068e-01,1.100000010988609489e+01,4.549916106473583775e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030622088185139944e+02,7.444325701805355493e+02,5.145670250769928122e-01,1.100000010988609489e+01,4.403930704935870486e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030631179094140037e+02,7.444425701805354265e+02,5.145670691162999022e-01,1.100000010988609489e+01,4.257945303398157197e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030640270003140131e+02,7.444525701805353037e+02,5.145671116957529767e-01,1.100000010988609489e+01,4.111959901860443908e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030649360912140224e+02,7.444625701805351810e+02,5.145671528153520358e-01,1.100000010988609489e+01,3.965974500322730619e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030658451821140318e+02,7.444725701805350582e+02,5.145671924750970794e-01,1.100000010988609489e+01,3.819989098785017330e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030667542730140411e+02,7.444825701805349354e+02,5.145672306749881075e-01,1.100000010988609489e+01,3.674003697247304465e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030676633639140505e+02,7.444925701805348126e+02,5.145672674150251202e-01,1.100000010988609489e+01,3.528018295709591599e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030685724548140598e+02,7.445025701805348035e+02,5.145673026952081175e-01,1.100000010988609489e+01,3.382032894171878734e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030694815457140692e+02,7.445125701805347944e+02,5.145673365155370993e-01,1.100000010988609489e+01,3.236047492634165869e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030703906366140785e+02,7.445225701805347853e+02,5.145673688760120656e-01,1.100000010988609489e+01,3.090062091096453003e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030712997275140879e+02,7.445325701805347762e+02,5.145673997766330166e-01,1.100000010988609489e+01,2.944076689558740138e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030722088184140972e+02,7.445425701805347671e+02,5.145674292173999520e-01,1.100000010988609489e+01,2.798091288021027273e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030731179093141066e+02,7.445525701805347580e+02,5.145674571983128720e-01,1.100000010988609489e+01,2.652105886483314407e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030740270002141159e+02,7.445625701805347489e+02,5.145674837193717766e-01,1.100000010988609489e+01,2.506120484945601542e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030749360911141252e+02,7.445725701805347398e+02,5.145675087805766657e-01,1.100000010988609489e+01,2.360135083407888677e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030758451820141346e+02,7.445825701805347308e+02,5.145675323819275393e-01,1.100000010988609489e+01,2.214149681870175811e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030767542729141439e+02,7.445925701805347217e+02,5.145675545234243975e-01,1.100000010988609489e+01,2.068164280332462946e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030776633638141533e+02,7.446025701805347126e+02,5.145675752050672402e-01,1.100000010988609489e+01,1.922178878794750081e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030785724547141626e+02,7.446125701805347035e+02,5.145675944268560675e-01,1.100000010988609489e+01,1.776193477257037215e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030794815456141720e+02,7.446225701805346944e+02,5.145676121887908794e-01,1.100000010988609489e+01,1.630208075719324350e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030803906365141813e+02,7.446325701805346853e+02,5.145676284908716758e-01,1.100000010988609489e+01,1.484222674181611485e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030812997274141907e+02,7.446425701805346762e+02,5.145676433330984567e-01,1.100000010988609489e+01,1.338237272643898619e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030822088183142000e+02,7.446525701805346671e+02,5.145676567154712222e-01,1.100000010988609489e+01,1.192251871106185754e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030831179092142094e+02,7.446625701805346580e+02,5.145676686379899722e-01,1.100000010988609489e+01,1.046266469568472888e-06,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030840270001142187e+02,7.446725701805346489e+02,5.145676791006547068e-01,1.100000010988609489e+01,9.002810680307600231e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030849360910142281e+02,7.446825701805346398e+02,5.145676881034654260e-01,1.100000010988609489e+01,7.542956664930471578e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030858451819142374e+02,7.446925701805346307e+02,5.145676956464221297e-01,1.100000010988609489e+01,6.083102649553342924e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030867542728142467e+02,7.447025701805346216e+02,5.145677017295248179e-01,1.100000010988609489e+01,4.623248634176214271e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030876633637142561e+02,7.447125701805346125e+02,5.145677063527734907e-01,1.100000010988609489e+01,3.163394618799085617e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030885724546142654e+02,7.447225701805346034e+02,5.145677095161681480e-01,1.100000010988609489e+01,1.703540603421956699e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030894815455142748e+02,7.447325701805345943e+02,5.145677112197087899e-01,1.100000010988609489e+01,2.436865880448277807e-08,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030903906364142841e+02,7.447425701805345852e+02,5.145677114633954163e-01,1.100000010988609489e+01,-1.216167427332301138e-07,0.000000000000000000e+00,-4.000000000000000327e-05,0.000000000000000000e+00,8.800000087908876889e-02 +1.030912997273142935e+02,7.447525701805345761e+02,5.145677102472280273e-01,1.100000010988609489e+01,-2.676021442709430056e-07,0.000000000000000000e+00,4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030922088182143028e+02,7.447625701805345670e+02,5.145677075712066229e-01,1.100000010988609489e+01,-1.216167427332301138e-07,0.000000000000000000e+00,4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 +1.030931179091143122e+02,7.447725701805345579e+02,5.145677063550392338e-01,1.100000010988609489e+01,2.436865880448277807e-08,0.000000000000000000e+00,4.000000000000000327e-05,0.000000000000000000e+00,0.000000000000000000e+00 diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/.gitignore b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/.gitignore new file mode 100644 index 0000000000000..8018116a6fc6b --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/.gitignore @@ -0,0 +1,7 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/__init__.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/__init__.py new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py new file mode 100644 index 0000000000000..e75eedcb4bf65 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_GP.py @@ -0,0 +1,110 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore numba njit fastmath + +from functools import partial + +from numba import njit +import numpy as np +from smart_mpc_trajectory_follower.scripts import drive_functions + +sqrt_mpc_time_step = np.sqrt(drive_functions.mpc_time_step) + + +@njit(cache=True, fastmath=True) +def get_pred(x_input, theta_1, theta_2, Z, mean_mtr, cov_mtr): + """Calculate the prediction and its derivative, the deviation and its derivative based on the Gaussian process.""" + Z_norm = (Z - x_input) * theta_2 + k_ast = theta_1 * np.exp(-0.5 * ((Z - x_input) * Z_norm).sum(axis=1)) + k_ = cov_mtr @ k_ast + Z_k = Z_norm.T * k_ast + deviation = np.sqrt(theta_1 - np.dot(k_ast, k_)) + return np.dot(mean_mtr, k_ast), deviation, Z_k @ mean_mtr, -Z_k @ k_ / deviation + + +@njit(cache=True, fastmath=True) +def get_pred_deviation(x_input, theta_1, theta_2, Z, cov_mtr): + """Calculate the deviation of the prediction and its derivative based on the Gaussian process.""" + coef = np.abs(x_input[0]) + coef = coef * coef * coef * coef * coef * coef * coef + if coef > 1.0: + coef = 1.0 + Z_norm = (Z - x_input) * theta_2 + k_ast = theta_1 * np.exp(-0.5 * ((Z - x_input) * Z_norm).sum(axis=1)) + k_ = cov_mtr @ k_ast + Z_k = Z_norm.T * k_ast + deviation = np.sqrt(theta_1 - np.dot(k_ast, k_)) + return coef * deviation, -coef * Z_k @ k_ / deviation + + +@njit(cache=True, fastmath=True) +def get_pred_deviations(x_inputs, theta_1, theta_2, Z, cov_mtr, indices): + """Calculate the deviation of the predictions and their derivatives for multiple inputs based on the Gaussian process.""" + deviation = np.zeros(x_inputs.shape[0]) + deviation_dot = np.zeros((x_inputs.shape[0], x_inputs.shape[1] + 3)) + for i in range(x_inputs.shape[0]): + deviation[i], deviation_dot[i, indices] = get_pred_deviation( + x_inputs[i], theta_1, theta_2, Z, cov_mtr + ) + return sqrt_mpc_time_step * deviation, sqrt_mpc_time_step * deviation_dot + + +class transform_GP_to_numba: + """Class for fast computation of necessary calculations based on Gaussian processes with numba.""" + + def __init__(self, i, dir_name="."): + indices = np.concatenate( + ( + np.array([2, 4, 5]), + np.arange( + drive_functions.acc_ctrl_queue_size + drive_functions.steer_ctrl_queue_size + ) + + 6, + ) + ) + file_names = [ + "/GP_x_info.npz", + "/GP_y_info.npz", + "/GP_v_info.npz", + "/GP_theta_info.npz", + "/GP_acc_info.npz", + "/GP_steer_info.npz", + ] + file_name = file_names[i] + GP_info = np.load(dir_name + file_name) + theta_1 = 1 * GP_info["theta_1"] + theta_2 = GP_info["theta_2"] + Z = GP_info["Z"] + mean_mtr = GP_info["mean_mtr"] + cov_mtr = GP_info["cov_mtr"] + self.get_pred = partial( + get_pred, + theta_1=theta_1, + theta_2=theta_2, + Z=Z, + mean_mtr=mean_mtr, + cov_mtr=cov_mtr, + ) + self.pred_deviation = partial( + get_pred_deviation, theta_1=theta_1, theta_2=theta_2, Z=Z, cov_mtr=cov_mtr + ) + self.pred_deviations = partial( + get_pred_deviations, + theta_1=theta_1, + theta_2=theta_2, + Z=Z, + cov_mtr=cov_mtr, + indices=indices, + ) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py new file mode 100644 index 0000000000000..f35789ee39fd3 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_NN.py @@ -0,0 +1,247 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +import numpy as np +from smart_mpc_trajectory_follower.scripts import drive_functions +from smart_mpc_trajectory_follower.scripts import proxima_calc +import torch +from torch import nn + +dim_steer_layer_1_head = 32 +dim_steer_layer_1_tail = 16 +dim_steer_layer_2 = 8 +dim_acc_layer_1 = 16 +dim_acc_layer_2 = 16 + + +def nominal_model_input(Var, lam, step): + """Calculate prediction with nominal model that takes into account time constants for the first order and time delays related to the input.""" + nominal_pred = Var[:, 0] + nominal_pred = ( + nominal_pred + (Var[:, step] - nominal_pred) * drive_functions.ctrl_time_step / lam + ) + nominal_pred = ( + nominal_pred + (Var[:, step - 1] - nominal_pred) * drive_functions.ctrl_time_step / lam + ) + nominal_pred = ( + nominal_pred + (Var[:, step - 2] - nominal_pred) * drive_functions.ctrl_time_step / lam + ) + return nominal_pred + + +def loss_fn_plus_tanh(loss_fn, pred, Y, tanh_gain, tanh_weight): + """Compute the loss function to be used in the training.""" + loss = loss_fn(pred, Y) + loss += tanh_weight * loss_fn( + torch.tanh(tanh_gain * (pred[:, -1] - Y[:, -1])), torch.zeros(Y.shape[0]) + ) + return loss + + +# example usage: `model = DriveNeuralNetwork(params...).to("cpu")` +class DriveNeuralNetwork(nn.Module): + """Define the neural net model to be used in vehicle control.""" + + def __init__( + self, + hidden_layer_sizes=(32, 16), + randomize=0.01, + acc_drop_out=0.0, + steer_drop_out=0.0, + acc_delay_step=drive_functions.acc_delay_step, + steer_delay_step=drive_functions.steer_delay_step, + acc_time_constant_ctrl=drive_functions.acc_time_constant, + steer_time_constant_ctrl=drive_functions.steer_time_constant, + acc_queue_size=drive_functions.acc_ctrl_queue_size, + steer_queue_size=drive_functions.steer_ctrl_queue_size, + steer_queue_size_core=drive_functions.steer_ctrl_queue_size_core, + ): + super().__init__() + self.acc_time_constant_ctrl = acc_time_constant_ctrl + self.acc_delay_step = acc_delay_step + self.steer_time_constant_ctrl = steer_time_constant_ctrl + self.steer_delay_step = steer_delay_step + + lb = -randomize + ub = randomize + self.acc_input_index = np.concatenate(([1], np.arange(acc_queue_size) + 3)) + self.steer_input_index = np.concatenate( + ([2], np.arange(steer_queue_size_core) + acc_queue_size + 3) + ) + self.acc_input_index_ = np.arange(acc_queue_size) + 3 + self.steer_input_index_ = np.arange(steer_queue_size_core) + acc_queue_size + 3 + self.steer_input_index_full = np.arange(steer_queue_size) + acc_queue_size + 3 + self.acc_layer_1 = nn.Sequential( + nn.Linear(self.acc_input_index.shape[0], dim_acc_layer_1), + nn.ReLU(), + ) + nn.init.uniform_(self.acc_layer_1[0].weight, a=lb, b=ub) + nn.init.uniform_(self.acc_layer_1[0].bias, a=lb, b=ub) + self.steer_layer_1_head = nn.Sequential( + nn.Linear(self.steer_input_index.shape[0], dim_steer_layer_1_head), + nn.ReLU(), + ) + nn.init.uniform_(self.steer_layer_1_head[0].weight, a=lb, b=ub) + nn.init.uniform_(self.steer_layer_1_head[0].bias, a=lb, b=ub) + + self.steer_layer_1_tail = nn.Sequential( + nn.Linear(self.steer_input_index_full.shape[0], dim_steer_layer_1_tail), nn.ReLU() + ) + nn.init.uniform_(self.steer_layer_1_tail[0].weight, a=lb, b=ub) + nn.init.uniform_(self.steer_layer_1_tail[0].bias, a=lb, b=ub) + + self.acc_layer_2 = nn.Sequential(nn.Linear(dim_acc_layer_1, dim_acc_layer_2), nn.Tanh()) + nn.init.uniform_(self.acc_layer_2[0].weight, a=lb, b=ub) + nn.init.uniform_(self.acc_layer_2[0].bias, a=lb, b=ub) + + self.steer_layer_2 = nn.Sequential( + nn.Linear(dim_steer_layer_1_head + dim_steer_layer_1_tail, dim_steer_layer_2), nn.Tanh() + ) + nn.init.uniform_(self.steer_layer_2[0].weight, a=lb, b=ub) + nn.init.uniform_(self.steer_layer_2[0].bias, a=lb, b=ub) + + self.linear_relu_stack = nn.Sequential( + nn.Linear(1 + dim_acc_layer_2 + dim_steer_layer_2, hidden_layer_sizes[0]), + nn.ReLU(), + nn.Linear(hidden_layer_sizes[0], hidden_layer_sizes[1]), + nn.ReLU(), + ) + nn.init.uniform_(self.linear_relu_stack[0].weight, a=lb, b=ub) + nn.init.uniform_(self.linear_relu_stack[0].bias, a=lb, b=ub) + nn.init.uniform_(self.linear_relu_stack[2].weight, a=lb, b=ub) + nn.init.uniform_(self.linear_relu_stack[2].bias, a=lb, b=ub) + + self.finalize = nn.Linear(hidden_layer_sizes[1] + dim_acc_layer_2 + dim_steer_layer_2, 6) + + nn.init.uniform_(self.finalize.weight, a=lb, b=ub) + nn.init.uniform_(self.finalize.bias, a=lb, b=ub) + + self.acc_dropout = nn.Dropout(acc_drop_out) + self.steer_dropout = nn.Dropout(steer_drop_out) + + def forward(self, x): + acc_layer_1 = self.acc_layer_1(x[:, self.acc_input_index]) + steer_layer_1 = torch.cat( + ( + self.steer_layer_1_head(x[:, self.steer_input_index]), + self.steer_layer_1_tail(x[:, self.steer_input_index_full]), + ), + dim=1, + ) + acc_layer_2 = self.acc_layer_2(self.acc_dropout(acc_layer_1)) + steer_layer_2 = self.steer_layer_2(self.steer_dropout(steer_layer_1)) + + pre_pred = self.linear_relu_stack(torch.cat((x[:, [0]], acc_layer_2, steer_layer_2), dim=1)) + pred = self.finalize(torch.cat((pre_pred, acc_layer_2, steer_layer_2), dim=1)) + return pred + + +class EarlyStopping: + """Class for early stopping in NN training.""" + + def __init__(self, initial_loss, tol=0.01, patience=30): + self.epoch = 0 # Initialise the counter for the number of epochs being monitored. + self.best_loss = float("inf") # Initialise loss of comparison with infinity 'inf'. + self.patience = patience # Initialise the number of epochs to be monitored with a parameter + self.initial_loss = initial_loss.detach().item() + self.tol = tol + + def __call__(self, current_loss): + current_loss_num = current_loss.detach().item() + if current_loss_num + self.tol * self.initial_loss > self.best_loss: + self.epoch += 1 + else: + self.epoch = 0 + if current_loss_num < self.best_loss: + self.best_loss = current_loss_num + if self.epoch >= self.patience: + return True + return False + + +class transform_model_to_c: + """Pass the necessary information to the C++ program to call the trained model at high speed.""" + + def __init__( + self, + model, + A_for_linear_reg, + b_for_linear_reg, + deg, + acc_time_constant, + acc_delay_step, + steer_time_constant, + steer_delay_step, + acc_queue_size, + steer_queue_size, + steer_queue_size_core, + ): + transformer = proxima_calc.transform_model_to_eigen() + + numpy_weight_list = [] + numpy_bias_list = [] + for i, w in enumerate(model.parameters()): + if i % 2 == 0: + numpy_weight_list.append(w.detach().numpy().astype(np.float64)) + else: + numpy_bias_list.append(w.detach().numpy().astype(np.float64)) + array_weight_list_0 = numpy_weight_list[0] + array_bias_list_0 = numpy_bias_list[0] + array_weight_list_1 = numpy_weight_list[1] + array_bias_list_1 = numpy_bias_list[1] + array_weight_list_2 = numpy_weight_list[2] + array_bias_list_2 = numpy_bias_list[2] + array_weight_list_3 = numpy_weight_list[3] + array_bias_list_3 = numpy_bias_list[3] + array_weight_list_4 = numpy_weight_list[4] + array_bias_list_4 = numpy_bias_list[4] + array_weight_list_5 = numpy_weight_list[5] + array_bias_list_5 = numpy_bias_list[5] + array_weight_list_6 = numpy_weight_list[6] + array_bias_list_6 = numpy_bias_list[6] + array_weight_list_7 = numpy_weight_list[7] + array_bias_list_7 = numpy_bias_list[7] + + transformer.set_params( + array_weight_list_0, + array_weight_list_1, + array_weight_list_2, + array_weight_list_3, + array_weight_list_4, + array_weight_list_5, + array_weight_list_6, + array_weight_list_7, + array_bias_list_0, + array_bias_list_1, + array_bias_list_2, + array_bias_list_3, + array_bias_list_4, + array_bias_list_5, + array_bias_list_6, + array_bias_list_7, + A_for_linear_reg, + b_for_linear_reg, + deg, + acc_time_constant, + acc_delay_step, + steer_time_constant, + steer_delay_step, + acc_queue_size, + steer_queue_size, + steer_queue_size_core, + ) + self.pred = transformer.rot_and_d_rot_error_prediction + self.pred_with_diff = transformer.rot_and_d_rot_error_prediction_with_diff + self.Pred = transformer.Rotated_error_prediction diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py new file mode 100644 index 0000000000000..b21fcf72da931 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_controller.py @@ -0,0 +1,943 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore optim numba interp + + +"""Define a drive_controller class that calculates the final input of the Proxima-side MPC.""" +from functools import partial +from importlib import reload as ir +import threading +import time + +import numpy as np +import scipy.interpolate # type: ignore +from sklearn.preprocessing import PolynomialFeatures +from smart_mpc_trajectory_follower.scripts import drive_GP +from smart_mpc_trajectory_follower.scripts import drive_NN +from smart_mpc_trajectory_follower.scripts import drive_functions +from smart_mpc_trajectory_follower.scripts import drive_iLQR +from smart_mpc_trajectory_follower.scripts import drive_mppi +import torch + +ctrl_index_for_polynomial_reg = np.concatenate( + ( + np.arange(3), + [3 + drive_functions.acc_delay_step], + [3 + drive_functions.acc_ctrl_queue_size + drive_functions.steer_delay_step], + ) +) + + +class drive_controller: + """Calculate the final input of the Proxima-side MPC. + + Fields that can take None follow these specifications unless otherwise noted. + * If None, read from drive_functions.py + * If Bool, the input value is used + """ + + use_trained_model: bool | None + """Whether to use trained models """ + + use_trained_model_diff: bool | None + """Assuming a trained model is used, whether or not to use even its derivatives.""" + + update_trained_model: bool | None + """Whether to update the model online with the data under control.""" + + mode: str | None + """which algorithm to use, "mppi", "ilqr", or "mppi_ilqr" """ + + use_x_noise: bool | None + """Whether to reflect the uncertainty of the straight-line position when performing iLQG""" + + use_y_noise: bool | None + """Whether to reflect the uncertainty of the lateral position when performing iLQG""" + + use_v_noise: bool | None + """ Whether to reflect the uncertainty of the straight-line velocity when performing iLQG""" + + use_theta_noise: bool | None + """ Whether to reflect the uncertainty of the yaw angle when performing iLQG""" + + use_acc_noise: bool | None + """ Whether to reflect the uncertainty of the straight-line acceleration when performing iLQG""" + + use_steer_noise: bool | None + """ Whether to reflect the uncertainty of the steer when performing iLQG""" + + tanh_gain: float + """ Gain of the tanh term in the loss function in learning. """ + + lam: float + """ Weight fir the tanh term in the loss function in learning.""" + + alpha_1: float + """ Coefficients of the L¹ regularization term in online learning.""" + + alpha_2: float + """ Coefficients of the L² regularization term in online learning.""" + + drive_batch_size: int + """ Online learning batch sizes """ + + drive_learning_rate: float + """ Learning rate for online learning """ + + model_file_name: str + """ file name of the trained model to be loaded """ + + load_train_data_dir: str + """ directory for training data to be loaded during online learning """ + + load_GP_dir: str | None + """ directory to load the GP (Gaussian process regression) models for iLQG. """ + + def __init__( + self, + use_trained_model: bool | None = None, + use_trained_model_diff=None, + update_trained_model=None, + mode=None, + use_x_noise=None, + use_y_noise=None, + use_v_noise=None, + use_theta_noise=None, + use_acc_noise=None, + use_steer_noise=None, + tanh_gain=10.0, + lam=0.1, + alpha_1=1e-7, + alpha_2=0.0, + drive_batch_size=200, + drive_learning_rate=1e-6, + model_file_name="model_for_test_drive.pth", + load_train_data_dir=".", + load_GP_dir=None, + load_polynomial_reg_dir=None, + ): + """Initialize. + + Some arguments have a default value of None in order to reload drive_functions and update the parameters. + """ + # reload drive_functions + ir(drive_functions) + ir(drive_NN) + ir(drive_iLQR) + ir(drive_mppi) + + if use_trained_model is None: + self.use_trained_model = drive_functions.use_trained_model + else: + self.use_trained_model = use_trained_model + if not self.use_trained_model: + self.use_trained_model_diff = False + self.update_trained_model = False + else: + if use_trained_model_diff is None: + self.use_trained_model_diff = drive_functions.use_trained_model_diff + else: + self.use_trained_model_diff = use_trained_model_diff + if update_trained_model is None: + self.update_trained_model = drive_functions.update_trained_model + else: + self.update_trained_model = update_trained_model + if mode is None: + self.mode = drive_functions.mode + else: + self.mode = mode + + self.acc_delay_step = drive_functions.acc_delay_step + self.steer_delay_step = drive_functions.steer_delay_step + self.acc_time_constant_ctrl = drive_functions.acc_time_constant + self.steer_time_constant_ctrl = drive_functions.steer_time_constant + + # Term to consider noise in iLQG + if use_x_noise is None: + self.use_x_noise = drive_functions.use_x_noise + else: + self.use_x_noise = use_x_noise + if use_y_noise is None: + self.use_y_noise = drive_functions.use_y_noise + else: + self.use_y_noise = use_y_noise + if use_v_noise is None: + self.use_v_noise = drive_functions.use_v_noise + else: + self.use_v_noise = use_v_noise + if use_theta_noise is None: + self.use_theta_noise = drive_functions.use_theta_noise + else: + self.use_theta_noise = use_theta_noise + if use_acc_noise is None: + self.use_acc_noise = drive_functions.use_acc_noise + else: + self.use_acc_noise = use_acc_noise + if use_steer_noise is None: + self.use_steer_noise = drive_functions.use_steer_noise + else: + self.use_steer_noise = use_steer_noise + if not self.use_trained_model: + self.use_x_noise = False + self.use_y_noise = False + self.use_v_noise = False + self.use_theta_noise = False + self.use_acc_noise = False + self.use_steer_noise = False + + if load_GP_dir is None: + self.load_GP_dir = drive_functions.load_dir + else: + self.load_GP_dir = load_GP_dir + if load_polynomial_reg_dir is None: + self.load_polynomial_reg_dir = drive_functions.load_dir + else: + self.load_polynomial_reg_dir = load_polynomial_reg_dir + + self.drive_batch_size = drive_batch_size + self.alpha_1 = alpha_1 + self.alpha_2 = alpha_2 + self.tanh_gain = tanh_gain + self.lam = lam + + self.init = True + self.initialize_input_queue = True + self.mppi = drive_mppi.drive_mppi( + drive_functions.lam, + drive_functions.Sigma, + drive_functions.max_iter_mppi, + drive_functions.sample_num, + drive_functions.mppi_tol, + drive_functions.mppi_step, + ) + self.ilqr = drive_iLQR.drive_iLQR( + drive_functions.ls_step, + drive_functions.max_iter_ls, + drive_functions.max_iter_ilqr, + drive_functions.ilqr_tol, + self.use_trained_model_diff, + ) + self.err = 0 + if self.use_trained_model: + self.model = torch.load(model_file_name) + polynomial_reg_info = np.load(self.load_polynomial_reg_dir + "/polynomial_reg_info.npz") + self.A_for_polynomial_reg = polynomial_reg_info["A"] + self.b_for_polynomial_reg = polynomial_reg_info["b"] + self.deg = int(polynomial_reg_info["deg"]) + self.polynomial_features = PolynomialFeatures(degree=self.deg, include_bias=False) + transform_model = drive_NN.transform_model_to_c( + self.model, + self.A_for_polynomial_reg, + self.b_for_polynomial_reg, + self.deg, + self.acc_time_constant_ctrl, + self.acc_delay_step, + self.steer_time_constant_ctrl, + self.steer_delay_step, + drive_functions.acc_ctrl_queue_size, + drive_functions.steer_ctrl_queue_size, + drive_functions.steer_ctrl_queue_size_core, + ) + pred = transform_model.pred + Pred = transform_model.Pred + self.pred = pred + self.pred_with_diff = transform_model.pred_with_diff + self.loss_fn = torch.nn.L1Loss() + self.drive_optimizer = torch.optim.Adam( + params=self.model.parameters(), lr=drive_learning_rate + ) + self.F_N_initial_diff = partial( + drive_functions.F_with_model_initial_diff, + pred=pred, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + + self.F_N_diff = partial( + drive_functions.F_with_model_diff, + pred=self.pred_with_diff, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + self.F_N_for_candidates = partial( + drive_functions.F_with_model_for_candidates, + Pred=Pred, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + else: + self.F_N_diff = partial( + drive_functions.F_with_history_and_diff, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + self.F_N_initial_diff = self.F_N_diff + self.F_N_for_candidates = partial( + drive_functions.F_with_history_for_candidates, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + + if self.use_x_noise: + self.x_noise = drive_GP.transform_GP_to_numba( + 0, dir_name=self.load_GP_dir + ).pred_deviations + else: + self.x_noise = None + if self.use_y_noise: + self.y_noise = drive_GP.transform_GP_to_numba( + 1, dir_name=self.load_GP_dir + ).pred_deviations + else: + self.y_noise = None + if self.use_v_noise: + self.v_noise = drive_GP.transform_GP_to_numba( + 2, dir_name=self.load_GP_dir + ).pred_deviations + else: + self.v_noise = None + if self.use_theta_noise: + self.theta_noise = drive_GP.transform_GP_to_numba( + 3, dir_name=self.load_GP_dir + ).pred_deviations + else: + self.theta_noise = None + if self.use_acc_noise: + self.acc_noise = drive_GP.transform_GP_to_numba( + 4, dir_name=self.load_GP_dir + ).pred_deviations + else: + self.acc_noise = None + if self.use_steer_noise: + self.steer_noise = drive_GP.transform_GP_to_numba( + 5, dir_name=self.load_GP_dir + ).pred_deviations + else: + self.steer_noise = None + + self.X_des_history: list[np.ndarray] = [] + + self.X_input_list = [] + self.Y_output_list = [] + # Initial data during online training + + self.emergency = False + + self.counter = 0 + self.model_update_flag = True + if self.update_trained_model: + train_data = np.load(load_train_data_dir + "/train_data.npz") + self.X_input_list = train_data["X_input"][ + -drive_functions.max_train_data_size : + ].tolist() + self.Y_output_list = ( + train_data["Y_output"][-drive_functions.max_train_data_size :] + - self.polynomial_features.fit_transform( + train_data["X_input"][ + -drive_functions.max_train_data_size :, ctrl_index_for_polynomial_reg + ] + ) + @ (self.A_for_polynomial_reg).T + - self.b_for_polynomial_reg + ).tolist() + self.model_updater = threading.Thread(target=self.update_model) + self.model_updater.start() + + self.x_old = np.empty(6) + + def __del__(self): + print("control finished") + + def get_optimal_control( + self, + x_current_: np.ndarray, + X_des_: np.ndarray, + U_des: np.ndarray = np.zeros((drive_functions.N, drive_functions.nu_0)), + ) -> np.ndarray: + """Calculate the optimal control input from the current state, target trajectory, and target input trajectory. + + The return value is an np.ndarray of the form `(drive_functions.nu_0, )`. + """ + if self.initialize_input_queue: + x_current = x_current_.copy() + X_des, diff_delta = drive_functions.transform_yaw_for_X_des( + x_current, + X_des_, + ) + self.u_opt = X_des[0, drive_functions.nx_0 + np.arange(drive_functions.nu_0)] + self.u_old = self.u_opt.copy() + self.u_old2 = self.u_opt.copy() + self.acc_input_queue = self.u_opt[0] * np.ones(drive_functions.acc_ctrl_queue_size) + self.steer_input_queue = self.u_opt[1] * np.ones(drive_functions.steer_ctrl_queue_size) + self.nominal_inputs = drive_functions.U_des_from_X_des(self.u_old, X_des, diff_delta) + self.previous_error = np.zeros(8) + + self.X_queue_for_learning: list[np.ndarray] = [] + self.acc_input_queue_for_learning: list[np.ndarray] = [] + self.steer_input_queue_for_learning: list[np.ndarray] = [] + self.time_stamp_queue_for_learning: list[float] = [] + self.X_smoothed_queue: list[np.ndarray] = [] + + self.pre_X_input_list: list[np.ndarray] = [] + self.pre_Y_output_list: list[np.ndarray] = [] + + self.initialize_X_smoothing_time_stamp = True + else: + x_current = drive_functions.transform_yaw_for_x_current(self.x_old, x_current_) + X_des, diff_delta = drive_functions.transform_yaw_for_X_des( + x_current, + X_des_, + ) + self.u_old2 = self.u_old.copy() + self.u_old = self.u_opt.copy() + + if self.init: + self.X_current_queue = [] + self.init = False + self.X_des = X_des + + self.X_current = np.concatenate( + (x_current, self.acc_input_queue[::-1], self.steer_input_queue[::-1]) + ) + + self.X_current_queue.append(self.X_current.copy()) + if len(self.X_current_queue) > drive_functions.mpc_freq: + self.X_current_queue.pop(0) + if self.mode == "mppi": # Avoid duplicate filtering for "mppi_ilqr" mode + self.nominal_inputs = drive_functions.sg_filter_for_nominal_inputs(self.nominal_inputs) + if self.mode == "mppi" or self.mode == "mppi_ilqr": # Run mppi + self.start_mppi = time.time() + self.mppi.receive_model(self.F_N_for_candidates) + self.nominal_inputs, self.u_opt_dot, nominal_traj = (self.mppi).compute_optimal_control( + self.X_current, + self.nominal_inputs, + X_des, + U_des, + self.previous_error[:6], + ) + self.nominal_traj_mppi = nominal_traj.copy() + self.end_mppi = time.time() + if self.mode != "mppi": + self.start_ilqr = time.time() + proceed = True + for k in range(drive_functions.max_iter_ilqr): + if not proceed: + break + self.nominal_inputs = drive_functions.sg_filter_for_nominal_inputs( + self.nominal_inputs + ) + self.ilqr.receive_model( + self.F_N_initial_diff, self.F_N_diff, self.F_N_for_candidates + ) + self.nominal_inputs, self.u_opt_dot, nominal_traj, proceed = ( + self.ilqr + ).compute_optimal_control( + self.X_current, + self.nominal_inputs, + X_des, + U_des, + self.previous_error, + self.x_noise, + self.y_noise, + self.v_noise, + self.theta_noise, + self.acc_noise, + self.steer_noise, + ) + self.nominal_traj_ilqr = nominal_traj.copy() + self.nominal_inputs_ilqr = self.nominal_inputs.copy() + err = drive_functions.calc_maximum_trajectory_error(self.nominal_traj_ilqr, X_des) + if err > drive_functions.cap_pred_error[0]: + if err < drive_functions.cap_pred_error[1]: + mix_ratio = (drive_functions.cap_pred_error[1] - err) / ( + drive_functions.cap_pred_error[1] - drive_functions.cap_pred_error[0] + ) + else: + mix_ratio = 0.0 + self.nominal_inputs = mix_ratio * self.nominal_inputs + ( + 1 - mix_ratio + ) * drive_functions.U_des_from_X_des(self.u_old, X_des, diff_delta) + self.err = err + if err > 1.0: + self.emergency = True + + self.time_1 = self.ilqr.time_1 + self.time_2 = self.ilqr.time_2 + self.time_3 = self.ilqr.time_3 + self.time_4 = self.ilqr.time_4 + self.time_5 = self.ilqr.time_5 + self.end_ilqr = time.time() + + if self.use_trained_model: + self.previous_error = drive_functions.error_decay * self.previous_error + ( + 1 - drive_functions.error_decay + ) * self.pred(self.X_current) + + self.nominal_traj = nominal_traj + + self.u_opt = self.u_old + self.u_opt_dot * drive_functions.ctrl_time_step + ( + steer_lim, + steer_rate_lim_lb, + steer_rate_lim_ub, + acc_lim, + acc_rate_lim, + ) = drive_functions.calc_limits(x_current[2], x_current[4], x_current[5]) + + self.u_opt = drive_functions.u_cut_off( + self.u_opt, + self.u_old, + steer_lim, + steer_rate_lim_lb, + steer_rate_lim_ub, + acc_lim, + acc_rate_lim, + ) + + self.initialize_input_queue = False + self.X_des_history.append(X_des[0]) + self.initial_guess_for_debug = (self.nominal_inputs).copy() + + self.x_old = x_current + return self.u_opt + + def update_input_queue( + self, + time_stamp: list[float], + acc_history: list[float], + steer_history: list[float], + x_current_: np.ndarray, + ) -> None: + """Receives the history of the acceleration and steer inputs and their time stamps. + + And interpolates them to be the history of the time steps used by the controller. + The return value can be passed to get_optimal_control. + """ + if not self.initialize_input_queue: + if len(time_stamp) == 1: + self.acc_input_queue[-1] = acc_history[0] + self.steer_input_queue[-1] = steer_history[0] + elif len(time_stamp) > 1: + ctrl_num = int((time_stamp[-1] - time_stamp[0]) / drive_functions.ctrl_time_step) + acc_num = min(drive_functions.acc_ctrl_queue_size, ctrl_num) + steer_num = min(drive_functions.steer_ctrl_queue_size, ctrl_num) + time_stamp_acc = ( + drive_functions.ctrl_time_step * np.arange(acc_num) + - (acc_num - 1) * drive_functions.ctrl_time_step + + time_stamp[-1] + ) + time_stamp_steer = ( + drive_functions.ctrl_time_step * np.arange(steer_num) + - (steer_num - 1) * drive_functions.ctrl_time_step + + time_stamp[-1] + ) + acc_interpolate = scipy.interpolate.interp1d( + np.array(time_stamp), np.array(acc_history) + ) + steer_interpolate = scipy.interpolate.interp1d( + np.array(time_stamp), np.array(steer_history) + ) + + self.acc_input_queue[ + drive_functions.acc_ctrl_queue_size - acc_num : + ] = acc_interpolate(time_stamp_acc) + self.steer_input_queue[ + drive_functions.steer_ctrl_queue_size - steer_num : + ] = steer_interpolate(time_stamp_steer) + + if ( + acc_num == drive_functions.acc_ctrl_queue_size + and steer_num == drive_functions.steer_ctrl_queue_size + ): + self.X_queue_for_learning.append(x_current_) + self.acc_input_queue_for_learning.append(np.array(self.acc_input_queue)[::-1]) + self.steer_input_queue_for_learning.append( + np.array(self.steer_input_queue)[::-1] + ) + self.time_stamp_queue_for_learning.append(time_stamp[-1]) + if ( + self.initialize_X_smoothing_time_stamp + and self.time_stamp_queue_for_learning[-1] + - self.time_stamp_queue_for_learning[0] + > drive_functions.ctrl_time_step + * drive_functions.max_input_queue_size_for_learning + ): + self.initialize_X_smoothing_time_stamp = False + self.X_smoothing_time_stamp = ( + time_stamp[-1] - drive_functions.ctrl_time_step + ) + + if not self.initialize_X_smoothing_time_stamp: + while ( + self.time_stamp_queue_for_learning[-1] + > drive_functions.ctrl_time_step + self.X_smoothing_time_stamp + ): + self.X_smoothing_time_stamp += drive_functions.ctrl_time_step + time_stamp_smoothing = ( + drive_functions.ctrl_time_step + * np.arange(drive_functions.max_input_queue_size_for_learning) + - (drive_functions.max_input_queue_size_for_learning - 1) + * drive_functions.ctrl_time_step + + self.X_smoothing_time_stamp + ) + x_queue = scipy.interpolate.interp1d( + np.array(self.time_stamp_queue_for_learning), + np.array(self.X_queue_for_learning).T, + )(time_stamp_smoothing).T + acc_input_queue = scipy.interpolate.interp1d( + np.array(self.time_stamp_queue_for_learning), + np.array(self.acc_input_queue_for_learning).T, + )(time_stamp_smoothing).T + steer_input_queue = scipy.interpolate.interp1d( + np.array(self.time_stamp_queue_for_learning), + np.array(self.steer_input_queue_for_learning).T, + )(time_stamp_smoothing).T + X_smoothed = np.zeros( + drive_functions.nx_0 + + drive_functions.acc_ctrl_queue_size + + drive_functions.steer_ctrl_queue_size + ) + X_smoothed[0:4] = x_queue[ + drive_functions.max_input_queue_size_for_learning // 2, 0:4 + ] + X_smoothed[4] = np.dot( + x_queue[ + drive_functions.max_input_queue_size_for_learning // 2 + - drive_functions.kernel_acc_for_learning.shape[0] + // 2 : drive_functions.max_input_queue_size_for_learning + // 2 + + drive_functions.kernel_acc_for_learning.shape[0] // 2 + + 1, + 4, + ], + drive_functions.kernel_acc_for_learning, + ) + X_smoothed[5] = np.dot( + x_queue[ + drive_functions.max_input_queue_size_for_learning // 2 + - drive_functions.kernel_steer_for_learning.shape[0] + // 2 : drive_functions.max_input_queue_size_for_learning + // 2 + + drive_functions.kernel_steer_for_learning.shape[0] // 2 + + 1, + 5, + ], + drive_functions.kernel_steer_for_learning, + ) + X_smoothed[ + drive_functions.nx_0 : drive_functions.nx_0 + + drive_functions.acc_ctrl_queue_size + ] = ( + acc_input_queue[ + drive_functions.max_input_queue_size_for_learning // 2 + - drive_functions.kernel_acc_des_for_learning.shape[0] + // 2 : drive_functions.max_input_queue_size_for_learning + // 2 + + drive_functions.kernel_acc_des_for_learning.shape[0] // 2 + + 1 + ].T + * drive_functions.kernel_acc_des_for_learning + ).sum( + axis=1 + ) + X_smoothed[ + drive_functions.nx_0 + + drive_functions.acc_ctrl_queue_size : drive_functions.nx_0 + + drive_functions.acc_ctrl_queue_size + + drive_functions.steer_ctrl_queue_size + ] = ( + steer_input_queue[ + drive_functions.max_input_queue_size_for_learning // 2 + - drive_functions.kernel_steer_des_for_learning.shape[0] + // 2 : drive_functions.max_input_queue_size_for_learning + // 2 + + drive_functions.kernel_steer_des_for_learning.shape[0] // 2 + + 1 + ].T + * drive_functions.kernel_steer_des_for_learning + ).sum( + axis=1 + ) + self.X_smoothed_queue.append(X_smoothed) + if len(self.X_smoothed_queue) > drive_functions.mpc_freq + 1: + self.X_smoothed_queue.pop() + if len(self.X_smoothed_queue) == drive_functions.mpc_freq + 1: + acc_start = ( + drive_functions.acc_ctrl_queue_size + - drive_functions.acc_delay_step + ) + acc_end = ( + drive_functions.acc_ctrl_queue_size + - drive_functions.acc_delay_step + + drive_functions.mpc_freq + ) + steer_start = ( + drive_functions.steer_ctrl_queue_size + - drive_functions.steer_delay_step + ) + steer_end = ( + drive_functions.steer_ctrl_queue_size + - drive_functions.steer_delay_step + + drive_functions.mpc_freq + ) + + u_for_predict_x_current = np.zeros((drive_functions.mpc_freq, 2)) + u_for_predict_x_current[:, 0] = self.X_smoothed_queue[0][ + 6 : 6 + drive_functions.acc_ctrl_queue_size + ][::-1][acc_start:acc_end] + u_for_predict_x_current[:, 1] = self.X_smoothed_queue[0][ + 6 + drive_functions.acc_ctrl_queue_size : + ][::-1][steer_start:steer_end] + var_dot = self.X_smoothed_queue[-1][ + :6 + ] - drive_functions.F_multiple( + self.X_smoothed_queue[0][:6], + u_for_predict_x_current, + drive_functions.acc_time_constant, + drive_functions.steer_time_constant, + ) + var_dot /= drive_functions.mpc_time_step + + self.pre_X_input_list.append( + np.concatenate( + ( + self.X_smoothed_queue[0][[2, 4, 5]], + self.X_smoothed_queue[0][6:], + ) + ) + ) + self.pre_Y_output_list.append( + drive_functions.rotate_data( + self.X_smoothed_queue[0][:6], var_dot + ) + ) + if ( + len(self.pre_X_input_list) + > drive_functions.max_output_queue_size_for_learning + ): + self.pre_X_input_list.pop() + self.pre_Y_output_list.pop() + if ( + len(self.pre_X_input_list) + == drive_functions.max_output_queue_size_for_learning + and self.update_trained_model + ): + X_input = self.pre_X_input_list[ + drive_functions.max_output_queue_size_for_learning // 2 + ] + self.X_input_list.append(X_input) + pre_Y_output = np.array(np.array(self.pre_Y_output_list)) + Y_output = np.zeros(self.pre_Y_output_list[0].shape) + Y_output[0] = np.dot( + pre_Y_output[ + drive_functions.max_output_queue_size_for_learning // 2 + - drive_functions.kernel_x_out_for_learning.shape[0] + // 2 : drive_functions.max_output_queue_size_for_learning + // 2 + + drive_functions.kernel_x_out_for_learning.shape[0] + // 2 + + 1, + 0, + ], + drive_functions.kernel_x_out_for_learning, + ) + Y_output[1] = np.dot( + pre_Y_output[ + drive_functions.max_output_queue_size_for_learning // 2 + - drive_functions.kernel_y_out_for_learning.shape[0] + // 2 : drive_functions.max_output_queue_size_for_learning + // 2 + + drive_functions.kernel_y_out_for_learning.shape[0] + // 2 + + 1, + 1, + ], + drive_functions.kernel_y_out_for_learning, + ) + Y_output[2] = np.dot( + pre_Y_output[ + drive_functions.max_output_queue_size_for_learning // 2 + - drive_functions.kernel_v_out_for_learning.shape[0] + // 2 : drive_functions.max_output_queue_size_for_learning + // 2 + + drive_functions.kernel_v_out_for_learning.shape[0] + // 2 + + 1, + 2, + ], + drive_functions.kernel_v_out_for_learning, + ) + Y_output[3] = np.dot( + pre_Y_output[ + drive_functions.max_output_queue_size_for_learning // 2 + - drive_functions.kernel_theta_out_for_learning.shape[0] + // 2 : drive_functions.max_output_queue_size_for_learning + // 2 + + drive_functions.kernel_theta_out_for_learning.shape[0] + // 2 + + 1, + 3, + ], + drive_functions.kernel_theta_out_for_learning, + ) + Y_output[4] = np.dot( + pre_Y_output[ + drive_functions.max_output_queue_size_for_learning // 2 + - drive_functions.kernel_acc_out_for_learning.shape[0] + // 2 : drive_functions.max_output_queue_size_for_learning + // 2 + + drive_functions.kernel_acc_out_for_learning.shape[0] + // 2 + + 1, + 4, + ], + drive_functions.kernel_acc_out_for_learning, + ) + Y_output[5] = np.dot( + pre_Y_output[ + drive_functions.max_output_queue_size_for_learning // 2 + - drive_functions.kernel_steer_out_for_learning.shape[0] + // 2 : drive_functions.max_output_queue_size_for_learning + // 2 + + drive_functions.kernel_steer_out_for_learning.shape[0] + // 2 + + 1, + 5, + ], + drive_functions.kernel_steer_out_for_learning, + ) + self.Y_output_list.append( + Y_output + - self.A_for_polynomial_reg + @ self.polynomial_features.fit_transform( + X_input[ctrl_index_for_polynomial_reg].reshape(1, -1) + )[0] + - self.b_for_polynomial_reg + ) + if len(self.X_input_list) > drive_functions.max_train_data_size: + self.X_input_list.pop(0) + self.Y_output_list.pop(0) + while ( + self.X_smoothing_time_stamp - self.time_stamp_queue_for_learning[1] + > drive_functions.ctrl_time_step + * drive_functions.max_input_queue_size_for_learning + ): + self.X_queue_for_learning.pop(0) + self.acc_input_queue_for_learning.pop(0) + self.steer_input_queue_for_learning.pop(0) + self.time_stamp_queue_for_learning.pop(0) + + def update_input_queue_and_get_optimal_control( + self, + time_stamp, + acc_history, + steer_history, + x_current_, + X_des_, + U_des=np.zeros((drive_functions.N, drive_functions.nu_0)), + ): + """Run update_input_queue and get_optimal_control all at once.""" + self.update_input_queue(time_stamp, acc_history, steer_history, x_current_) + u_opt = self.get_optimal_control(x_current_, X_des_, U_des) + return u_opt + + def update_model(self): + """Update the learning model online.""" + while True: + if not self.model_update_flag: + break + if not self.initialize_input_queue and len(self.X_input_list) > self.drive_batch_size: + X_input = np.array(self.X_input_list) + Y_output = np.array(self.Y_output_list) + batch_index = np.random.choice( + X_input.shape[0], self.drive_batch_size, replace=False + ) + X_batch = torch.tensor(X_input[batch_index].astype(np.float32)).clone() + Y_batch = torch.tensor(Y_output[batch_index].astype(np.float32)).clone() + Y_pred = self.model(X_batch) + loss = drive_NN.loss_fn_plus_tanh( + self.loss_fn, Y_pred, Y_batch, self.tanh_gain, self.lam + ) + for w in self.model.parameters(): + loss = ( + loss + self.alpha_1 * torch.norm(w, p=1) + self.alpha_2 * torch.norm(w) ** 2 + ) + self.drive_optimizer.zero_grad() + loss.backward() + self.drive_optimizer.step() + + transform_model = drive_NN.transform_model_to_c( + self.model, + self.A_for_polynomial_reg, + self.b_for_polynomial_reg, + self.deg, + self.acc_time_constant_ctrl, + self.acc_delay_step, + self.steer_time_constant_ctrl, + self.steer_delay_step, + drive_functions.acc_ctrl_queue_size, + drive_functions.steer_ctrl_queue_size, + drive_functions.steer_ctrl_queue_size_core, + ) + self.pred = transform_model.pred + self.Pred = transform_model.Pred + self.pred_with_diff = transform_model.pred_with_diff + self.F_N_initial_diff = partial( + drive_functions.F_with_model_initial_diff, + pred=self.pred, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + self.F_N_diff = partial( + drive_functions.F_with_model_diff, + pred=self.pred_with_diff, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + self.F_N_for_candidates = partial( + drive_functions.F_with_model_for_candidates, + Pred=self.Pred, + i=self.acc_delay_step, + j=self.steer_delay_step, + acc_time_constant_ctrl=self.acc_time_constant_ctrl, + steer_time_constant_ctrl=self.steer_time_constant_ctrl, + ) + + print("updated!!!!!!!!!!!") + time.sleep(0.1) + + def send_initialize_input_queue(self): + """Flag initialization of the history of inputs passed to the control side.""" + self.initialize_input_queue = True + + def stop_model_update(self): + """Terminate the model update.""" + self.model_update_flag = False + if self.update_trained_model: + self.model_updater.join() diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py new file mode 100644 index 0000000000000..c11b5c886b49a --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_functions.py @@ -0,0 +1,1540 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore numba njit fastmath ndim + + +"""Define primary parameters and functions to be used elsewhere.""" +from functools import partial +import json +import os +from pathlib import Path +import sys +from typing import Callable + +from numba import njit +import numpy as np +import yaml + +package_path_json = str(Path(__file__).parent.parent) + "/package_path.json" +with open(package_path_json, "r") as file: + package_path = json.load(file) + +mpc_param_path = package_path["path"] + "/smart_mpc_trajectory_follower/param/mpc_param.yaml" +with open(mpc_param_path, "r") as yml: + mpc_param = yaml.safe_load(yml) + +mpc_freq = int( + mpc_param["mpc_parameter"]["mpc_setting"]["mpc_freq"] +) # Int, mpc horizon interval/control interval + +# information on MPC +ctrl_time_step = float( + mpc_param["mpc_parameter"]["mpc_setting"]["ctrl_time_step"] +) # Time interval of control. +mpc_time_step = mpc_freq * ctrl_time_step # MPC Horizon interval. +N = int(mpc_param["mpc_parameter"]["mpc_setting"]["N"]) # Length of MPC Horizon. +steer_ctrl_queue_size = int( + mpc_param["mpc_parameter"]["mpc_setting"]["steer_ctrl_queue_size"] +) # Queue for training and control +steer_ctrl_queue_size_core = int( + mpc_param["mpc_parameter"]["mpc_setting"]["steer_ctrl_queue_size_core"] +) +acc_ctrl_queue_size = int(mpc_param["mpc_parameter"]["mpc_setting"]["acc_ctrl_queue_size"]) +nx_0 = int(mpc_param["mpc_parameter"]["mpc_setting"]["nx_0"]) # dimension of the state +nu_0 = int(mpc_param["mpc_parameter"]["mpc_setting"]["nu_0"]) # dimension of the input + +################################################################# + +# Control parameters that may be changed in the experiment## + +################################################################# +mode = str(mpc_param["mpc_parameter"]["system"]["mode"]) +# cost function weights +Q = np.diag(np.array(mpc_param["mpc_parameter"]["cost_parameters"]["Q"], dtype=float)) # stage cost +Q_c = np.diag( + np.array(mpc_param["mpc_parameter"]["cost_parameters"]["Q_c"], dtype=float) +) # Stage costs in MPC `timing_Q_c`th horizon. +Q_f = np.diag( + np.array(mpc_param["mpc_parameter"]["cost_parameters"]["Q_f"], dtype=float) +) # terminal cost +R = np.diag( + np.array(mpc_param["mpc_parameter"]["cost_parameters"]["R"], dtype=float) +) # Cost for control inputs. Here acceleration rate of change and steer rate of change. +timing_Q_c = np.array( + mpc_param["mpc_parameter"]["mpc_setting"]["timing_Q_c"], dtype=int +) # Horizon numbers to change stage costs. +reference_horizon = int(mpc_param["mpc_parameter"]["preprocessing"]["reference_horizon"]) # 50 + +acc_lim_weight = float(mpc_param["mpc_parameter"]["cost_parameters"]["acc_lim_weight"]) +steer_lim_weight = float(mpc_param["mpc_parameter"]["cost_parameters"]["steer_lim_weight"]) +acc_rate_lim_weight = float(mpc_param["mpc_parameter"]["cost_parameters"]["acc_rate_lim_weight"]) +steer_rate_lim_weight = float( + mpc_param["mpc_parameter"]["cost_parameters"]["steer_rate_lim_weight"] +) + +# iLQR parameters +ls_step = float(mpc_param["mpc_parameter"]["ilqr"]["ls_step"]) # 0.9 +max_iter_ls = int(mpc_param["mpc_parameter"]["ilqr"]["max_iter_ls"]) # 10 +max_iter_ilqr = int(mpc_param["mpc_parameter"]["ilqr"]["max_iter_ilqr"]) # 1 +ilqr_tol = float(mpc_param["mpc_parameter"]["ilqr"]["ilqr_tol"]) # 0.01 + +# MPPI parameters +lam = float(mpc_param["mpc_parameter"]["mppi"]["lam"]) # 0.1 +Sigma = np.array(mpc_param["mpc_parameter"]["mppi"]["Sigma"], dtype=float) +max_iter_mppi = int(mpc_param["mpc_parameter"]["mppi"]["max_iter_mppi"]) +sample_num = int(mpc_param["mpc_parameter"]["mppi"]["sample_num"]) +mppi_tol = float(mpc_param["mpc_parameter"]["mppi"]["mppi_tol"]) +mppi_step = int(mpc_param["mpc_parameter"]["mppi"]["mppi_step"]) + +cap_pred_error = np.array(mpc_param["mpc_parameter"]["preprocessing"]["cap_pred_error"]) + +nominal_param_path = ( + package_path["path"] + "/smart_mpc_trajectory_follower/param/nominal_param.yaml" +) +with open(nominal_param_path, "r") as yml: + nominal_param = yaml.safe_load(yml) +# Vehicle body information given by default. +L = float(nominal_param["nominal_parameter"]["vehicle_info"]["wheel_base"]) # Length of vehicle [m] +steer_dead_band_for_ctrl = 0.00 # Size of the steering dead band zone given to the control side. + +acc_time_delay = float(nominal_param["nominal_parameter"]["acceleration"]["acc_time_delay"]) +acc_delay_step = min(round(acc_time_delay / ctrl_time_step), acc_ctrl_queue_size - mpc_freq) +acc_time_constant = float(nominal_param["nominal_parameter"]["acceleration"]["acc_time_constant"]) + +steer_time_delay = float(nominal_param["nominal_parameter"]["steering"]["steer_time_delay"]) +steer_delay_step = min( + round(steer_time_delay / ctrl_time_step), steer_ctrl_queue_size_core - mpc_freq +) +steer_time_constant = float(nominal_param["nominal_parameter"]["steering"]["steer_time_constant"]) + +min_steer_rate_transform_for_start = float( + mpc_param["mpc_parameter"]["cost_parameters"]["min_steer_rate_transform_for_start"] +) +power_steer_rate_transform_for_start = int( + mpc_param["mpc_parameter"]["cost_parameters"]["power_steer_rate_transform_for_start"] +) +coef_steer_rate_transform_for_start = float( + mpc_param["mpc_parameter"]["cost_parameters"]["coef_steer_rate_transform_for_start"] +) + +min_tighten_steer_rate = float( + mpc_param["mpc_parameter"]["to_be_deprecated"]["min_tighten_steer_rate"] +) +power_tighten_steer_rate_by_lateral_error = int( + mpc_param["mpc_parameter"]["to_be_deprecated"]["power_tighten_steer_rate_by_lateral_error"] +) +threshold_tighten_steer_rate_by_lateral_error = float( + mpc_param["mpc_parameter"]["to_be_deprecated"]["threshold_tighten_steer_rate_by_lateral_error"] +) +power_tighten_steer_rate_by_yaw_error = int( + mpc_param["mpc_parameter"]["to_be_deprecated"]["power_tighten_steer_rate_by_yaw_error"] +) +threshold_tighten_steer_rate_by_yaw_error = float( + mpc_param["mpc_parameter"]["to_be_deprecated"]["threshold_tighten_steer_rate_by_yaw_error"] +) +tighten_horizon = int(mpc_param["mpc_parameter"]["to_be_deprecated"]["tighten_horizon"]) + +min_loose_lateral_cost = float( + mpc_param["mpc_parameter"]["cost_parameters"]["min_loose_lateral_cost"] +) +power_loose_lateral_cost = int( + mpc_param["mpc_parameter"]["cost_parameters"]["power_loose_lateral_cost"] +) +threshold_loose_lateral_cost = float( + mpc_param["mpc_parameter"]["cost_parameters"]["threshold_loose_lateral_cost"] +) + +min_loose_yaw_cost = float(mpc_param["mpc_parameter"]["cost_parameters"]["min_loose_yaw_cost"]) +power_loose_yaw_cost = int(mpc_param["mpc_parameter"]["cost_parameters"]["power_loose_yaw_cost"]) +threshold_loose_yaw_cost = float( + mpc_param["mpc_parameter"]["cost_parameters"]["threshold_loose_yaw_cost"] +) + +use_sg_for_nominal_inputs = bool( + mpc_param["mpc_parameter"]["preprocessing"]["use_sg_for_nominal_inputs"] +) +sg_deg_for_nominal_inputs = int( + mpc_param["mpc_parameter"]["preprocessing"]["sg_deg_for_nominal_inputs"] +) +sg_window_size_for_nominal_inputs = int( + mpc_param["mpc_parameter"]["preprocessing"]["sg_window_size_for_nominal_inputs"] +) +trained_model_param_path = ( + package_path["path"] + "/smart_mpc_trajectory_follower/param/trained_model_param.yaml" +) +with open(trained_model_param_path, "r") as yml: + trained_model_param = yaml.safe_load(yml) +use_trained_model_diff = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_trained_model_diff"] +) +use_sg_for_trained_model_diff = bool( + trained_model_param["trained_model_parameter"]["control_application"][ + "use_sg_for_trained_model_diff" + ] +) +sg_deg_for_trained_model_diff = int( + trained_model_param["trained_model_parameter"]["control_application"][ + "sg_deg_for_trained_model_diff" + ] +) +sg_window_size_for_trained_model_diff = int( + trained_model_param["trained_model_parameter"]["control_application"][ + "sg_window_size_for_trained_model_diff" + ] +) + +use_sg_for_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_sg_for_noise"] +) +sg_deg_for_noise = int( + trained_model_param["trained_model_parameter"]["control_application"]["sg_deg_for_noise"] +) +sg_window_size_for_noise = int( + trained_model_param["trained_model_parameter"]["control_application"][ + "sg_window_size_for_noise" + ] +) + + +load_dir = os.environ["HOME"] +save_dir = os.environ["HOME"] # +"/autoware" +use_trained_model = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_trained_model"] +) +update_trained_model = bool( + trained_model_param["trained_model_parameter"]["control_application"]["update_trained_model"] +) +max_train_data_size = int( + trained_model_param["trained_model_parameter"]["control_application"]["max_train_data_size"] +) + +error_decay = np.array( + trained_model_param["trained_model_parameter"]["control_application"]["error_decay"], + dtype=float, +) + +Error_decay = error_decay[:6] + +use_x_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_x_noise"] +) +use_y_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_y_noise"] +) +use_v_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_v_noise"] +) +use_theta_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_theta_noise"] +) +use_acc_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_acc_noise"] +) +use_steer_noise = bool( + trained_model_param["trained_model_parameter"]["control_application"]["use_steer_noise"] +) + +# smoothing parameter in training +acc_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["acc_sigma_for_learning"] +) +steer_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["steer_sigma_for_learning"] +) +acc_des_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["acc_des_sigma_for_learning"] +) +steer_des_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["steer_des_sigma_for_learning"] +) + +x_out_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["x_out_sigma_for_learning"] +) +y_out_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["y_out_sigma_for_learning"] +) +v_out_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["v_out_sigma_for_learning"] +) +theta_out_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["theta_out_sigma_for_learning"] +) +acc_out_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["acc_out_sigma_for_learning"] +) +steer_out_sigma_for_learning = float( + trained_model_param["trained_model_parameter"]["smoothing"]["steer_out_sigma_for_learning"] +) + + +# upper limit of input + + +package_path_split = str(package_path["path"]).split("/") +control_dir_path = "" +for i in range(len(package_path_split)): + control_dir_path += package_path_split[i] + if package_path_split[i] == "control": + break + control_dir_path += "/" + +limit_yaml_path = None +for curDir, dirs, files in os.walk(control_dir_path): + for name in files: + if name == "vehicle_cmd_gate.param.yaml": + if curDir.split("/")[-2] == "vehicle_cmd_gate": + limit_yaml_path = curDir + "/" + name + break + +limit_params = None +if limit_yaml_path is not None: + with open(limit_yaml_path, "r") as yml: + limit_params = yaml.safe_load(yml) +else: + print("Error: limit_yaml_path is None") + +if limit_params is not None: + reference_speed_points = np.array( + limit_params["/**"]["ros__parameters"]["nominal"]["reference_speed_points"] + ) + steer_lim_points = np.array(limit_params["/**"]["ros__parameters"]["nominal"]["steer_lim"]) + steer_rate_lim_points = np.array( + limit_params["/**"]["ros__parameters"]["nominal"]["steer_rate_lim"] + ) + acc_lim_points = np.array(limit_params["/**"]["ros__parameters"]["nominal"]["lon_acc_lim"]) + acc_rate_lim_points = np.array( + limit_params["/**"]["ros__parameters"]["nominal"]["lon_jerk_lim"] + ) + lat_acc_lim_points = np.array(limit_params["/**"]["ros__parameters"]["nominal"]["lat_acc_lim"]) + lat_jerk_lim_points = np.array( + limit_params["/**"]["ros__parameters"]["nominal"]["lat_jerk_lim"] + ) +else: + print("Error: limit_params is None") + sys.exit(1) + + +@njit(cache=True, fastmath=True) +def calc_limits( + vel: float, + acc: float, + steer: float, + reference_speed_points=reference_speed_points, + steer_lim_points=steer_lim_points, + steer_rate_lim_points=steer_rate_lim_points, + acc_lim_points=acc_lim_points, + lat_acc_lim_points=lat_acc_lim_points, + lat_jerk_lim_points=lat_jerk_lim_points, +) -> tuple[float, float, float, float, float]: + """Calculate the constraints according to the current velocity, acceleration and steer. + + Returns: + float: upper and lower limit of steer + float: upper limit of steer change rate + float: lower limit of steer change rate + float: upper and lower limit of acceleration + float: upper and lower limit of acceleration change rate + + However, we write the upper limit of the "upper and lower limits". lower limit is equal to `(-1) * upper limit`. + """ + interval_index = 0 + for i in range(reference_speed_points.shape[0]): + if np.abs(vel) > reference_speed_points[i]: + interval_index += 1 + else: + break + if interval_index == 0: + steer_lim = steer_lim_points[0] + steer_rate_lim = steer_rate_lim_points[0] + acc_lim = acc_lim_points[0] + acc_rate_lim = acc_rate_lim_points[0] + lat_acc_lim = lat_acc_lim_points[0] + lat_jerk_lim = lat_jerk_lim_points[0] + elif interval_index == reference_speed_points.shape[0]: + steer_lim = steer_lim_points[-1] + steer_rate_lim = steer_rate_lim_points[-1] + acc_lim = acc_lim_points[-1] + acc_rate_lim = acc_rate_lim_points[-1] + lat_acc_lim = lat_acc_lim_points[-1] + lat_jerk_lim = lat_jerk_lim_points[-1] + else: + r = (np.abs(vel) - reference_speed_points[interval_index - 1]) / ( + reference_speed_points[interval_index] - reference_speed_points[interval_index - 1] + ) + steer_lim = (1 - r) * steer_lim_points[interval_index - 1] + r * steer_lim_points[ + interval_index + ] + steer_rate_lim = (1 - r) * steer_rate_lim_points[ + interval_index - 1 + ] + r * steer_rate_lim_points[interval_index] + acc_lim = (1 - r) * acc_lim_points[interval_index - 1] + r * acc_lim_points[interval_index] + acc_rate_lim = (1 - r) * acc_rate_lim_points[interval_index - 1] + r * acc_rate_lim_points[ + interval_index + ] + lat_acc_lim = (1 - r) * lat_acc_lim_points[interval_index - 1] + r * lat_acc_lim_points[ + interval_index + ] + lat_jerk_lim = (1 - r) * lat_jerk_lim_points[interval_index - 1] + r * lat_jerk_lim_points[ + interval_index + ] + lat_jerk_lim_coef = L * np.cos(steer) * np.cos(steer) / (vel * vel + 1e-16) + lat_jerk_lim_const = vel * acc * np.sin(2 * steer) / (vel * vel + 1e-16) + steer_rate_lat_jerk_lim_lb = np.array( + [-lat_jerk_lim_coef * lat_jerk_lim - lat_jerk_lim_const, -0.01] + ).min() + steer_rate_lat_jerk_lim_ub = np.array( + [lat_jerk_lim_coef * lat_jerk_lim - lat_jerk_lim_const, 0.01] + ).max() + + steer_rate_lb = np.array([-steer_rate_lim, steer_rate_lat_jerk_lim_lb]).max() + steer_rate_ub = np.array([steer_rate_lim, steer_rate_lat_jerk_lim_ub]).min() + + return ( + np.array([steer_lim, np.arctan(lat_acc_lim * L / (vel * vel + 1e-16))]).min(), + steer_rate_lb, + steer_rate_ub, + acc_lim, + acc_rate_lim, + ) + + +@njit(cache=True, fastmath=True) +def transform_yaw(yaw_old: float, yaw_current_: float) -> float: + """Transform the yaw angle so that the difference in yaw angle is less than or equal to π.""" + rotate_num = (yaw_current_ - yaw_old) // (2 * np.pi) + if yaw_current_ - yaw_old - 2 * rotate_num * np.pi < np.pi: + return yaw_current_ - 2 * rotate_num * np.pi + else: + return yaw_current_ - 2 * (rotate_num + 1) * np.pi + + +@njit(cache=True, fastmath=True) +def transform_yaw_for_x_current(x_old: np.ndarray, x_current_: np.ndarray) -> np.ndarray: + """Apply `transform_yaw` to x_current_ and return the result.""" + x_current = x_current_.copy() + x_current[3] = transform_yaw(x_old[3], x_current_[3]) + return x_current + + +def transform_yaw_for_X_des(x_current: np.ndarray, X_des_: np.ndarray) -> np.ndarray: + """Transform the yaw angle with respect to the target trajectory. + + X_des[0] is set to the current state. + """ + X_des = X_des_.copy() + + initial_error = X_des[0, :3] - x_current[:3] + + len_journey = max(mpc_time_step * X_des[:, 2].sum(), 5.0) + theta_des = X_des[0, 3] + diff_position = -initial_error[:2] + signed_lat_err = -np.sin(theta_des) * diff_position[0] + np.cos(theta_des) * diff_position[1] + + X_des[: reference_horizon + 1, :3] -= ( + np.arange(reference_horizon + 1)[::-1].reshape(-1, 1) + @ initial_error.reshape(1, -1) + / reference_horizon + ) + X_des[0, 3] = transform_yaw(x_current[3], X_des[0, 3]) + yaw_initial_error = X_des[0, 3] - x_current[3] + X_des[0, 3] -= yaw_initial_error + + diff_theta = -yaw_initial_error + np.arctan(signed_lat_err / len_journey) + diff_delta = L * diff_theta / len_journey + + for i in range(X_des.shape[0] - 1): + if i < reference_horizon: + X_des[i + 1, 3] = ( + transform_yaw(X_des[i, 3], X_des[i + 1, 3]) + - yaw_initial_error * (reference_horizon - i - 1) / reference_horizon + ) + else: + X_des[i + 1, 3] = transform_yaw(X_des[i, 3], X_des[i + 1, 3]) + + return X_des, diff_delta + + +@njit(cache=True, fastmath=True) +def U_des_from_X_des(u_opt: np.ndarray, X_des: np.ndarray, diff_delta: float) -> np.ndarray: + """Calculate the initial value of the MPC from the target trajectory. + + This is used for the first control or when the error calculated by calc_maximum_trajectory_error is large. + """ + U_des = np.zeros((X_des.shape[0] - 1, nu_0)) + for i in range(U_des.shape[0]): + U_des[i] = (X_des[i + 1, 6:8] - X_des[i, 6:8]) / mpc_time_step + init_error = X_des[0, 6:8] - u_opt + U_des = U_des + init_error / ((X_des.shape[0] - 1) * mpc_time_step) - diff_delta + return U_des + + +@njit(cache=True, fastmath=True) +def calc_maximum_trajectory_error(traj: np.ndarray, X_des: np.ndarray) -> float: + """Calculate the maximum trajectory error. + + It calculates + * predicted trajectory produced by the MPC, + * the lateral error of the target trajectory + * the maximum value of the yaw error. + """ + err = 0.0 + for i in range(traj.shape[0]): + theta_des = X_des[i, 3] + diff_position = traj[i, 0:2] - X_des[i, 0:2] + lat_err = np.abs( + -np.sin(theta_des) * diff_position[0] + np.cos(theta_des) * diff_position[1] + ) + err = max(err, lat_err) + err = max(err, np.abs(theta_des - traj[i, 3])) + return err + + +@njit(cache=False, fastmath=True) +def transform_Q_R( + X_des: np.ndarray, U_des: np.ndarray, nominal_traj: np.ndarray, nominal_input: np.ndarray +) -> tuple: + """Calculate the MPC cost weight matrix from the current predicted trajectory and target trajectory. + + This calculates the information to add the constraints to the MPC cost. + """ + Q_total = np.zeros((X_des.shape[0], Q.shape[0], Q.shape[1])) + R_total = np.zeros((U_des.shape[0], R.shape[0], R.shape[1])) + acc_lim_weights = np.zeros(X_des.shape[0]) + acc_lim_center = np.zeros(X_des.shape[0]) + steer_lim_weights = np.zeros(X_des.shape[0]) + steer_lim_center = np.zeros(X_des.shape[0]) + acc_rate_lim_weights = np.zeros(U_des.shape[0]) + acc_rate_lim_center = np.zeros(U_des.shape[0]) + steer_rate_lim_weights = np.zeros(U_des.shape[0]) + steer_rate_lim_center = np.zeros(U_des.shape[0]) + for i in range(X_des.shape[0]): + if i == X_des.shape[0] - 1: + Q_ = Q_f.copy() + elif i in timing_Q_c: + Q_ = Q_c.copy() + else: + Q_ = Q.copy() + x_current = nominal_traj[i] + v = x_current[2] + acc = X_des[i, 4] + theta = X_des[i, 3] + + cos = np.cos(theta) + sin = np.sin(theta) + Rot = np.array([[cos, -sin], [sin, cos]]) + + lateral_error = np.abs((Rot.T @ (X_des[i, :2] - x_current[:2]))[1]) + yaw_error = np.abs(X_des[i, 3] - x_current[3]) + cost_tr_steer_rate_by_error = max( + min_tighten_steer_rate, + max( + (lateral_error / threshold_tighten_steer_rate_by_lateral_error) + ** power_tighten_steer_rate_by_lateral_error, + (yaw_error / threshold_tighten_steer_rate_by_yaw_error) + ** power_tighten_steer_rate_by_yaw_error, + ), + ) + cost_tr_steer_rate = 1 / ( + min( + max( + min_steer_rate_transform_for_start, + (coef_steer_rate_transform_for_start * np.abs(v)) + ** power_steer_rate_transform_for_start, + ), + 1.0, + ) + ) + if i >= tighten_horizon: + cost_tr_steer_rate = max(cost_tr_steer_rate, 1 / cost_tr_steer_rate_by_error) + if i in timing_Q_c or i == X_des.shape[0] - 1: + lateral_cost_coef = min( + max( + min_loose_lateral_cost, + (lateral_error / threshold_loose_lateral_cost) ** power_loose_lateral_cost, + ), + 1.0, + ) + Q_[1, 1] = lateral_cost_coef * Q_[1, 1] + yaw_cost_coef = min( + max( + min_loose_yaw_cost, + (yaw_error / threshold_loose_yaw_cost) ** power_loose_yaw_cost, + ), + 1.0, + ) + Q_[3, 3] = yaw_cost_coef * Q_[3, 3] + + Q_[:2, :2] = Rot @ Q_[:2, :2] @ Rot.T + Q_total[i] = Q_ + + steer_lim, steer_rate_lim_lb, steer_rate_lim_ub, acc_lim, acc_rate_lim = calc_limits( + v, x_current[4], x_current[5] + ) + + if x_current[2] <= 0.0 and x_current[nx_0] <= 0.0: + acc_lim_weights[i] = acc_lim_weight + acc_lim_center[i] = 0.0 + else: + if x_current[nx_0] > acc_lim: # acc inputs + acc_lim_weights[i] = acc_lim_weight + acc_lim_center[i] = acc_lim + elif x_current[nx_0] < -acc_lim: + acc_lim_weights[i] = acc_lim_weight + acc_lim_center[i] = -acc_lim + + if x_current[nx_0 + acc_ctrl_queue_size] > steer_lim: # steer inputs + steer_lim_weights[i] = steer_lim_weight + steer_lim_center[i] = steer_lim + elif x_current[nx_0 + acc_ctrl_queue_size] < -steer_lim: + steer_lim_weights[i] = steer_lim_weight + steer_lim_center[i] = -steer_lim + if i != X_des.shape[0] - 1: + R_ = R.copy() + if acc >= 0: + R_[1, 1] = cost_tr_steer_rate * R_[1, 1] + R_total[i] = R_ + + if nominal_input[i, 0] > acc_rate_lim: + acc_rate_lim_weights[i] = acc_rate_lim_weight + acc_rate_lim_center[i] = acc_rate_lim + elif nominal_input[i, 0] < -acc_rate_lim: + acc_rate_lim_weights[i] = acc_rate_lim_weight + acc_rate_lim_center[i] = -acc_rate_lim + + if nominal_input[i, 1] > steer_rate_lim_ub: + steer_rate_lim_weights[i] = steer_rate_lim_weight + steer_rate_lim_center[i] = steer_rate_lim_ub + elif nominal_input[i, 1] < steer_rate_lim_lb: + steer_rate_lim_weights[i] = steer_rate_lim_weight + steer_rate_lim_center[i] = steer_rate_lim_lb + + return ( + Q_total, + R_total, + acc_lim_weights, + acc_lim_center, + steer_lim_weights, + steer_lim_center, + acc_rate_lim_weights, + acc_rate_lim_center, + steer_rate_lim_weights, + steer_rate_lim_center, + ) + + +@njit(cache=False, fastmath=True) +def calc_cost( + X_des: np.ndarray, U_des: np.ndarray, Traj: np.ndarray, Inputs: np.ndarray, n: int +) -> np.ndarray: + """Calculate the MPC cost of the nth horizon from several candidate predicted trajectories and target trajectories.""" + Cost = np.zeros(Traj.shape[0]) + if n == N: + Q_ = Q_f.copy() + elif n in timing_Q_c: + Q_ = Q_c.copy() + else: + Q_ = Q.copy() + acc = X_des[4] + theta = X_des[3] + cos = np.cos(theta) + sin = np.sin(theta) + Rot = np.array([[cos, -sin], [sin, cos]]) + for i in range(Traj.shape[0]): + x_current = Traj[i] + v = x_current[2] + + Qi = Q_.copy() + lateral_error = np.abs((Rot.T @ (X_des[:2] - x_current[:2]))[1]) + yaw_error = np.abs(X_des[3] - x_current[3]) + cost_tr_steer_rate_by_error = max( + min_tighten_steer_rate, + max( + (lateral_error / threshold_tighten_steer_rate_by_lateral_error) + ** power_tighten_steer_rate_by_lateral_error, + (yaw_error / threshold_tighten_steer_rate_by_yaw_error) + ** power_tighten_steer_rate_by_yaw_error, + ), + ) + cost_tr_steer_rate = 1 / ( + min( + max( + min_steer_rate_transform_for_start, + (coef_steer_rate_transform_for_start * np.abs(v)) + ** power_steer_rate_transform_for_start, + ), + 1.0, + ) + ) + if n >= tighten_horizon: + cost_tr_steer_rate = max(cost_tr_steer_rate, 1 / cost_tr_steer_rate_by_error) + if n in timing_Q_c or n == N: + lateral_cost_coef = min( + max( + min_loose_lateral_cost, + (lateral_error / threshold_loose_lateral_cost) ** power_loose_lateral_cost, + ), + 1.0, + ) + Qi[1, 1] = lateral_cost_coef * Qi[1, 1] + yaw_cost_coef = min( + max( + min_loose_yaw_cost, + (yaw_error / threshold_loose_yaw_cost) ** power_loose_yaw_cost, + ), + 1.0, + ) + Qi[3, 3] = yaw_cost_coef * Qi[3, 3] + Qi[:2, :2] = Rot @ Qi[:2, :2] @ Rot.T + Cost[i] += 0.5 * np.dot(Qi @ (x_current - X_des), x_current - X_des) + + steer_lim, steer_rate_lim_lb, steer_rate_lim_ub, acc_lim, acc_rate_lim = calc_limits( + v, x_current[4], x_current[5] + ) + if x_current[2] <= 0.0 and x_current[nx_0] <= 0.0: + Cost[i] += 0.5 * acc_lim_weight * (x_current[nx_0] - 0.0) * (x_current[nx_0] - 0.0) + + else: + if x_current[nx_0] > acc_lim: + Cost[i] += ( + 0.5 * acc_lim_weight * (x_current[nx_0] - acc_lim) * (x_current[nx_0] - acc_lim) + ) + elif x_current[nx_0] < -acc_lim: + Cost[i] += ( + 0.5 * acc_lim_weight * (x_current[nx_0] + acc_lim) * (x_current[nx_0] + acc_lim) + ) + + if x_current[nx_0 + 1] > steer_lim: + Cost[i] += ( + 0.5 + * steer_lim_weight + * (x_current[nx_0 + 1] - steer_lim) + * (x_current[nx_0 + 1] - steer_lim) + ) + + elif x_current[nx_0 + 1] < -steer_lim: + Cost[i] += ( + 0.5 + * steer_lim_weight + * (x_current[nx_0 + 1] + steer_lim) + * (x_current[nx_0 + 1] + steer_lim) + ) + + if n != N: + R_ = R.copy() + if acc >= 0: + R_[1, 1] = cost_tr_steer_rate * R_[1, 1] + + Cost[i] += 0.5 * np.dot(R_ @ (Inputs[i] - U_des), Inputs[i] - U_des) + + if Inputs[i, 0] > acc_rate_lim: + Cost[i] += ( + 0.5 + * acc_rate_lim_weight + * (Inputs[i, 0] - acc_rate_lim) + * (Inputs[i, 0] - acc_rate_lim) + ) + elif Inputs[i, 0] < -acc_rate_lim: + Cost[i] += ( + 0.5 + * acc_rate_lim_weight + * (Inputs[i, 0] + acc_rate_lim) + * (Inputs[i, 0] + acc_rate_lim) + ) + + if Inputs[i, 1] > steer_rate_lim_ub: + Cost[i] += ( + 0.5 + * steer_rate_lim_weight + * (Inputs[i, 1] - steer_rate_lim_ub) + * (Inputs[i, 1] - steer_rate_lim_ub) + ) + elif Inputs[i, 1] < steer_rate_lim_lb: + Cost[i] += ( + 0.5 + * steer_rate_lim_weight + * (Inputs[i, 1] - steer_rate_lim_lb) + * (Inputs[i, 1] - steer_rate_lim_lb) + ) + + return Cost + + +@njit(cache=False, fastmath=True) +def calc_cost_only_for_states(X_des: np.ndarray, Traj: np.ndarray, n: int) -> np.ndarray: + """Calculate the MPC cost for states of the nth horizon from several candidate predicted trajectories and target trajectories.""" + Cost = np.zeros(Traj.shape[0]) + if n == N: + Q_ = Q_f.copy() + elif n in timing_Q_c: + Q_ = Q_c.copy() + else: + Q_ = Q.copy() + theta = X_des[3] + cos = np.cos(theta) + sin = np.sin(theta) + Rot = np.array([[cos, -sin], [sin, cos]]) + for i in range(Traj.shape[0]): + x_current = Traj[i] + v = x_current[2] + + Qi = Q_.copy() + if n in timing_Q_c or n == N: + lateral_error = np.abs((Rot.T @ (X_des[:2] - x_current[:2]))[1]) + lateral_cost_coef = min( + max( + min_loose_lateral_cost, + (lateral_error / threshold_loose_lateral_cost) ** power_loose_lateral_cost, + ), + 1.0, + ) + Qi[1, 1] = lateral_cost_coef * Qi[1, 1] + yaw_error = np.abs(X_des[3] - x_current[3]) + yaw_cost_coef = min( + max( + min_loose_yaw_cost, + (yaw_error / threshold_loose_yaw_cost) ** power_loose_yaw_cost, + ), + 1.0, + ) + Qi[3, 3] = yaw_cost_coef * Qi[3, 3] + Qi[:2, :2] = Rot @ Qi[:2, :2] @ Rot.T + Cost[i] += 0.5 * np.dot(Qi @ (x_current - X_des), x_current - X_des) + + steer_lim, _, _, acc_lim, _ = calc_limits(v, x_current[4], x_current[5]) + if x_current[2] <= 0.0 and x_current[nx_0] <= 0.0: + Cost[i] += 0.5 * acc_lim_weight * (x_current[nx_0] - 0.0) * (x_current[nx_0] - 0.0) + + else: + if x_current[nx_0] > acc_lim: + Cost[i] += ( + 0.5 * acc_lim_weight * (x_current[nx_0] - acc_lim) * (x_current[nx_0] - acc_lim) + ) + elif x_current[nx_0] < -acc_lim: + Cost[i] += ( + 0.5 * acc_lim_weight * (x_current[nx_0] + acc_lim) * (x_current[nx_0] + acc_lim) + ) + + if x_current[nx_0 + 1] > steer_lim: + Cost[i] += ( + 0.5 + * steer_lim_weight + * (x_current[nx_0 + 1] - steer_lim) + * (x_current[nx_0 + 1] - steer_lim) + ) + + elif x_current[nx_0 + 1] < -steer_lim: + Cost[i] += ( + 0.5 + * steer_lim_weight + * (x_current[nx_0 + 1] + steer_lim) + * (x_current[nx_0 + 1] + steer_lim) + ) + + return Cost + + +def rotate_data(x_old: np.ndarray, var_dot: np.ndarray) -> np.ndarray: + """Apply a rotation that converts the x, y velocity relative to the world to the x, y velocity relative to the vehicle body.""" + theta_old = x_old[3] + cos = np.cos(theta_old) + sin = np.sin(theta_old) + + var_dot_ = var_dot.copy() + var_dot_[:2] = np.array([[cos, sin], [-sin, cos]]) @ var_dot[:2] + + return var_dot_ + + +@njit(cache=True, fastmath=True) +def f_init( + states: np.ndarray, + inputs: np.ndarray, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> np.ndarray: + """Time derivative of nominal model dynamics.""" + v = states[2] + theta = states[3] + alpha = states[4] + delta = states[5] + + delta_diff = inputs[1] - delta + if delta_diff >= steer_dead_band_for_ctrl: + delta_diff = delta_diff - steer_dead_band_for_ctrl + elif delta_diff <= -steer_dead_band_for_ctrl: + delta_diff = delta_diff + steer_dead_band_for_ctrl + else: + delta_diff = 0.0 + + states_dot = np.zeros(nx_0) + states_dot[0] = v * np.cos(theta) + states_dot[1] = v * np.sin(theta) + states_dot[2] = alpha + states_dot[3] = v * np.tan(delta) / L + states_dot[4] = (inputs[0] - alpha) / acc_time_constant_ctrl + states_dot[5] = delta_diff / steer_time_constant_ctrl + return states_dot + + +@njit(cache=True, fastmath=True) +def F_init( + states: np.ndarray, + inputs: np.ndarray, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> np.ndarray: + """Nominal model dynamics.""" + states_next = ( + states + + f_init( + states, + inputs, + acc_time_constant_ctrl, + steer_time_constant_ctrl, + steer_dead_band_for_ctrl, + ) + * ctrl_time_step + ) + return states_next + + +@njit(cache=True, fastmath=True) +def F_multiple( + states: np.ndarray, + inputs: np.ndarray, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> np.ndarray: + """Discretize and integrate up to the MPC time width according to the nominal model dynamics.""" + states_next = states + for i in range(mpc_freq): + states_next = F_init( + states_next, + inputs[i], + acc_time_constant_ctrl, + steer_time_constant_ctrl, + steer_dead_band_for_ctrl, + ) + return states_next + + +@njit(cache=True, fastmath=True) +def F_init_with_diff( + states: np.ndarray, + inputs: np.ndarray, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + """Compute the dynamics of the nominal model while computing derivatives.""" + states_next = ( + states + + f_init( + states, + inputs, + acc_time_constant_ctrl, + steer_time_constant_ctrl, + steer_dead_band_for_ctrl, + ) + * ctrl_time_step + ) + dF_dx = np.eye(nx_0) + dF_du = np.zeros((nx_0, nu_0)) + v = states[2] + theta = states[3] + delta = states[5] + + dF_dx[0, 2] += np.cos(theta) * ctrl_time_step + dF_dx[0, 3] -= v * np.sin(theta) * ctrl_time_step + dF_dx[1, 2] += np.sin(theta) * ctrl_time_step + dF_dx[1, 3] += v * np.cos(theta) * ctrl_time_step + dF_dx[2, 4] += ctrl_time_step + dF_dx[3, 2] += np.tan(delta) * ctrl_time_step / L + dF_dx[3, 5] += v * ctrl_time_step / (L * np.cos(delta) * np.cos(delta)) + dF_dx[4, 4] -= ctrl_time_step / acc_time_constant_ctrl + + dF_du[4, 0] = ctrl_time_step / acc_time_constant_ctrl + if abs(inputs[1] - delta) >= steer_dead_band_for_ctrl: + dF_dx[5, 5] -= ctrl_time_step / steer_time_constant_ctrl + dF_du[5, 1] = ctrl_time_step / steer_time_constant_ctrl + return states_next, dF_dx, dF_du + + +@njit(cache=True, fastmath=True) +def F_multiple_with_diff( + states: np.ndarray, + inputs: np.ndarray, + acc_time_constant_ctrl: float = ctrl_time_step, + steer_time_constant_ctrl: float = ctrl_time_step, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + """Integrate up to the MPC time width according to the nominal model while calculating the derivative.""" + F_0, dFx_0, dFu_0 = F_init_with_diff( + states, + inputs[0], + acc_time_constant_ctrl=acc_time_constant_ctrl, + steer_time_constant_ctrl=steer_time_constant_ctrl, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, + ) + F_1, dFx_1, dFu_1 = F_init_with_diff( + F_0, + inputs[1], + acc_time_constant_ctrl=acc_time_constant_ctrl, + steer_time_constant_ctrl=steer_time_constant_ctrl, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, + ) + F_2, dFx_2, dFu_2 = F_init_with_diff( + F_1, + inputs[2], + acc_time_constant_ctrl=acc_time_constant_ctrl, + steer_time_constant_ctrl=steer_time_constant_ctrl, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, + ) + dF_dx = dFx_2 @ dFx_1 @ dFx_0 + + dF_du = np.zeros((nx_0, 3 * nu_0)) + dF_du[:, :nu_0] = dFx_2 @ dFx_1 @ dFu_0 + dF_du[:, nu_0 : 2 * nu_0] = dFx_2 @ dFu_1 + dF_du[:, 2 * nu_0 : 3 * nu_0] = dFu_2 + return F_2, dF_dx, dF_du + + +@njit(cache=True, fastmath=True) +def f_init_for_candidates( + States: np.ndarray, + Inputs: np.ndarray, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> np.ndarray: + """Time derivative of nominal model dynamics for multiple candidates.""" + v = States[:, 2] + theta = States[:, 3] + alpha = States[:, 4] + delta = States[:, 5] + smaller_than_band = Inputs[:, 1] - delta < steer_dead_band_for_ctrl + larger_than_band = Inputs[:, 1] - delta > -steer_dead_band_for_ctrl + + delta_diff = (1 - smaller_than_band * larger_than_band) * ( + (Inputs[:, 1] - delta) + - (1 * larger_than_band - 1 * smaller_than_band) * steer_dead_band_for_ctrl + ) + States_dot = np.zeros(States.shape) + States_dot[:, 0] = v * np.cos(theta) + States_dot[:, 1] = v * np.sin(theta) + States_dot[:, 2] = alpha + States_dot[:, 3] = v * np.tan(delta) / L + States_dot[:, 4] = (Inputs[:, 0] - alpha) / acc_time_constant_ctrl + States_dot[:, 5] = delta_diff / steer_time_constant_ctrl + return States_dot + + +@njit(cache=True, fastmath=True) +def F_multiple_for_candidates( + States: np.ndarray, + Inputs: np.ndarray, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> np.ndarray: + """Discretize and integrate up to the MPC time width according to the nominal model dynamics for several candidates.""" + # Euler method + States_next = States.copy() + for i in range(mpc_freq): + States_next = ( + States_next + + f_init_for_candidates( + States_next, + Inputs[:, i, :], + acc_time_constant_ctrl, + steer_time_constant_ctrl, + steer_dead_band_for_ctrl, + ) + * ctrl_time_step + ) + return States_next + + +@njit(cache=True, fastmath=True) +def F_with_history( + states: np.ndarray, + inputs: np.ndarray, + i: int = acc_delay_step, + j: int = steer_delay_step, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, + steer_dead_band_for_ctrl=steer_dead_band_for_ctrl, +) -> np.ndarray: + """Integrate up to the MPC time width according to the nominal model. + + This includes the history of the input to the state. + """ + # Function from extended state + states_next = np.zeros(states.shape) + states_next[nx_0 + mpc_freq : nx_0 + acc_ctrl_queue_size] = states[ + nx_0 : nx_0 + acc_ctrl_queue_size - mpc_freq + ].copy() + states_next[ + nx_0 + acc_ctrl_queue_size + mpc_freq : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size + ] = states[ + nx_0 + acc_ctrl_queue_size : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size - mpc_freq + ].copy() + for k in range(mpc_freq): + states_next[nx_0 + mpc_freq - k - 1] = ( + states_next[nx_0 + mpc_freq - k] + ctrl_time_step * inputs[0] + ) + states_next[nx_0 + acc_ctrl_queue_size + mpc_freq - k - 1] = ( + states_next[nx_0 + acc_ctrl_queue_size + mpc_freq - k] + ctrl_time_step * inputs[1] + ) + + actual_inputs = np.zeros((mpc_freq, inputs.shape[0])) + actual_inputs[:, 0] = states_next[nx_0 + i + np.arange(mpc_freq)[::-1]] + actual_inputs[:, 1] = states_next[nx_0 + acc_ctrl_queue_size + j + np.arange(mpc_freq)[::-1]] + + states_next[:nx_0] = F_multiple( + states[:nx_0], + actual_inputs, + acc_time_constant_ctrl, + steer_time_constant_ctrl, + steer_dead_band_for_ctrl, + ) + + return states_next + + +def F_with_history_and_diff( + states: np.ndarray, + inputs: np.ndarray, + previous_error: None = None, + init: None = None, + i: int = acc_delay_step, + j: int = steer_delay_step, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, +) -> tuple[np.ndarray, np.ndarray, np.ndarray, None]: + """While computing the derivative, integrate up to the MPC time width according to the nominal model. + + This includes the history of the input to the state. + """ + nx = states.shape[0] + states_next = np.zeros(nx) + dF_dx = np.zeros((nx, nx)) + dF_du = np.zeros((nx, nu_0)) + + states_next[nx_0 + mpc_freq : nx_0 + acc_ctrl_queue_size] = states[ + nx_0 : nx_0 + acc_ctrl_queue_size - mpc_freq + ].copy() + states_next[ + nx_0 + acc_ctrl_queue_size + mpc_freq : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size + ] = states[ + nx_0 + acc_ctrl_queue_size : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size - mpc_freq + ].copy() + + dF_dx[ + nx_0 + mpc_freq : nx_0 + acc_ctrl_queue_size, nx_0 : nx_0 + acc_ctrl_queue_size - mpc_freq + ] = np.eye(acc_ctrl_queue_size - mpc_freq) + dF_dx[ + nx_0 + acc_ctrl_queue_size + mpc_freq : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size, + nx_0 + acc_ctrl_queue_size : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size - mpc_freq, + ] = np.eye(steer_ctrl_queue_size - mpc_freq) + + for k in range(mpc_freq): + states_next[nx_0 + mpc_freq - k - 1] = ( + states_next[nx_0 + mpc_freq - k] + ctrl_time_step * inputs[0] + ) + states_next[nx_0 + acc_ctrl_queue_size + mpc_freq - k - 1] = ( + states_next[nx_0 + acc_ctrl_queue_size + mpc_freq - k] + ctrl_time_step * inputs[1] + ) + dF_dx[nx_0 + mpc_freq - k - 1, nx_0] = 1 + dF_dx[nx_0 + acc_ctrl_queue_size + mpc_freq - k - 1, nx_0 + acc_ctrl_queue_size] = 1 + + dF_du[nx_0 + mpc_freq - k - 1, 0] = (k + 1) * ctrl_time_step + dF_du[nx_0 + acc_ctrl_queue_size + mpc_freq - k - 1, 1] = (k + 1) * ctrl_time_step + + actual_inputs = np.zeros((mpc_freq, inputs.shape[0])) + actual_inputs[:, 0] = states_next[nx_0 + i + np.arange(mpc_freq)[::-1]].copy() + + actual_inputs[:, 1] = states_next[ + nx_0 + acc_ctrl_queue_size + j + np.arange(mpc_freq)[::-1] + ].copy() + control_index = np.vstack( + ( + nx_0 + max(i - mpc_freq, 0) + np.arange(mpc_freq)[::-1], + nx_0 + acc_ctrl_queue_size + max(j - mpc_freq, 0) + np.arange(mpc_freq)[::-1], + ) + ).T.flatten() + states_next[:nx_0], dF_dx[:nx_0, :nx_0], dF_dx[:nx_0, control_index] = F_multiple_with_diff( + states[:nx_0], actual_inputs, acc_time_constant_ctrl, steer_time_constant_ctrl + ) + + return states_next, dF_dx, dF_du, None + + +@njit(cache=True, fastmath=True) +def F_with_history_for_candidates( + States: np.ndarray, + Inputs: np.ndarray, + Previous_error=None, + init=None, + i: int = acc_delay_step, + j: int = steer_delay_step, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, +) -> tuple[np.ndarray, None]: + """For several candidates, discretize and integrate up to the MPC time-width according to the nominal model dynamics. + + This includes the history of the input to the state. + """ + States_next = np.zeros(States.shape) + + States_next[:, nx_0 + mpc_freq : nx_0 + acc_ctrl_queue_size] = States[ + :, nx_0 : nx_0 + acc_ctrl_queue_size - mpc_freq + ].copy() + States_next[ + :, + nx_0 + acc_ctrl_queue_size + mpc_freq : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size, + ] = States[ + :, + nx_0 + acc_ctrl_queue_size : nx_0 + acc_ctrl_queue_size + steer_ctrl_queue_size - mpc_freq, + ].copy() + for k in range(mpc_freq): + States_next[:, nx_0 + mpc_freq - k - 1] = ( + States_next[:, nx_0 + mpc_freq - k] + ctrl_time_step * Inputs[:, 0] + ) + States_next[:, nx_0 + acc_ctrl_queue_size + mpc_freq - k - 1] = ( + States_next[:, nx_0 + acc_ctrl_queue_size + mpc_freq - k] + + ctrl_time_step * Inputs[:, 1] + ) + actual_Inputs = np.zeros((Inputs.shape[0], mpc_freq, nu_0)) + + actual_Inputs[:, :, 0] = States_next[:, nx_0 + i + np.arange(mpc_freq)[::-1]].copy() + actual_Inputs[:, :, 1] = States_next[ + :, nx_0 + acc_ctrl_queue_size + j + np.arange(mpc_freq)[::-1] + ].copy() + States_next[:, :nx_0] = F_multiple_for_candidates( + States[:, :nx_0], actual_Inputs, acc_time_constant_ctrl, steer_time_constant_ctrl + ) + return States_next, None + + +def F_with_model_initial_diff( + states: np.ndarray, + inputs: np.ndarray, + previous_error: np.ndarray, + k: int, + pred: Callable, + i: int = acc_delay_step, + j: int = steer_delay_step, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, +) -> tuple[np.ndarray, np.ndarray, np.ndarray, np.ndarray]: + """While computing the derivative, integrate up to the MPC time width according to the trained model. + + This includes the history of the input to the state. + The derivative follows the nominal model. + This verifies whether the learning is working on the predictions or on the derivatives. + """ + if k == 0: + error = error_decay * previous_error + (1 - error_decay) * pred(states) + else: + error = error_decay * error_decay * error_decay * previous_error + ( + 1 - error_decay * error_decay * error_decay + ) * pred(states) + previous_error_ = error + + rot_error, d_rot_error = np.split(error, [nx_0]) + states_next, dF_dx, dF_du, _ = F_with_history_and_diff( + states, + inputs, + i=i, + j=j, + acc_time_constant_ctrl=acc_time_constant_ctrl, + steer_time_constant_ctrl=steer_time_constant_ctrl, + ) + + dF_dx[:2, 3] += d_rot_error * mpc_time_step + states_next[:nx_0] += rot_error * mpc_time_step + + return states_next, dF_dx, dF_du, previous_error_ + + +def F_with_model_diff( + states: np.ndarray, + inputs: np.ndarray, + previous_error: np.ndarray, + k: int, + pred: Callable, + i: int = acc_delay_step, + j: int = steer_delay_step, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, +) -> tuple[np.ndarray, np.ndarray, np.ndarray, np.ndarray, np.ndarray]: + """While computing the derivative, it integrates up to the MPC time width according to the trained model. + + This includes the history of the input to the state. + The derivatives also follow a trained model. + """ + pred_with_diff = pred(states) + + if k == 0: + rot_error = ( + error_decay[:nx_0] * previous_error[:nx_0] + + (1 - error_decay[:nx_0]) * pred_with_diff[:, 0] + ) + d_rot_error = ( + error_decay[nx_0:] * previous_error[nx_0:] + + (1 - error_decay[nx_0:]) * pred_with_diff[:2, 1] + ) + else: + rot_error = ( + error_decay[:nx_0] * error_decay[:nx_0] * error_decay[:nx_0] * previous_error[:nx_0] + + (1 - error_decay[:nx_0] * error_decay[:nx_0] * error_decay[:nx_0]) + * pred_with_diff[:, 0] + ) + d_rot_error = ( + error_decay[nx_0:] * error_decay[nx_0:] * error_decay[nx_0:] * previous_error[nx_0:] + + (1 - error_decay[nx_0:] * error_decay[nx_0:] * error_decay[nx_0:]) + * pred_with_diff[:2, 1] + ) + pred_error_ = np.concatenate((rot_error, d_rot_error)) + states_next, dF_dx, dF_du, _ = F_with_history_and_diff( + states, + inputs, + i=i, + j=j, + acc_time_constant_ctrl=acc_time_constant_ctrl, + steer_time_constant_ctrl=steer_time_constant_ctrl, + ) + + dF_dx[:2, 3] += d_rot_error * mpc_time_step + states_next[:nx_0] += rot_error * mpc_time_step + return states_next, dF_dx, dF_du, pred_with_diff[:, 2:] * mpc_time_step, pred_error_ + + +def F_with_model_for_candidates( + States: np.ndarray, + Inputs: np.ndarray, + Previous_error: np.ndarray, + k: int, + Pred: Callable, + i: int = acc_delay_step, + j: int = steer_delay_step, + acc_time_constant_ctrl: float = acc_time_constant, + steer_time_constant_ctrl: float = steer_time_constant, +) -> tuple[np.ndarray, np.ndarray]: + """For several candidates, integrate up to the MPC time width according to the trained model. + + This includes the history of the input to the state. + """ + if k == 0: + Error = Error_decay * Previous_error + (1 - Error_decay) * Pred(States.T).T + else: + Error = ( + Error_decay * Error_decay * Error_decay * Previous_error + + (1 - Error_decay * Error_decay * Error_decay) * Pred(States.T).T + ) + Previous_error_ = Error + + States_next, _ = F_with_history_for_candidates( + States, + Inputs, + i=i, + j=j, + acc_time_constant_ctrl=acc_time_constant_ctrl, + steer_time_constant_ctrl=steer_time_constant_ctrl, + ) + States_next[:, :nx_0] += Error * mpc_time_step + + return States_next, Previous_error_ + + +def sg_filter( + inputs: np.ndarray, + use_sg: bool, + sg_window_size: int, + sg_vector_left_edge: list[np.ndarray], + sg_vector_right_edge: list[np.ndarray], + sg_vector: np.ndarray, +) -> np.ndarray: + """SG Filter. Used for smoothing.""" + if use_sg: + input_len = inputs.shape[0] + filtered_inputs = np.zeros(inputs.shape) + for i in range(input_len): + if i < sg_window_size: + filtered_inputs[i] = ( + (inputs[: sg_window_size + i + 1].T * sg_vector_left_edge[i]) + .sum(axis=inputs.ndim - 1) + .T + ) + elif i > input_len - sg_window_size - 1: + filtered_inputs[i] = ( + (inputs[i - sg_window_size :].T * sg_vector_right_edge[input_len - i - 1]) + .sum(axis=inputs.ndim - 1) + .T + ) + else: + filtered_inputs[i] = ( + (inputs[i - sg_window_size : i + sg_window_size + 1].T * sg_vector) + .sum(axis=inputs.ndim - 1) + .T + ) + return filtered_inputs + else: + return inputs + + +def calc_sg_filter_weight(sg_deg, sg_window_size): + """Calculate weighted average weights from SG filter degree and window size.""" + sg_vector_left_edge = [] + sg_vector_right_edge = [] + e_0 = np.zeros(sg_deg + 1) + e_0[0] = 1.0 + for i in range(sg_window_size): + reg_times = (np.arange(sg_window_size + i + 1) - i) * mpc_time_step + T = np.ones((sg_window_size + i + 1, sg_deg + 1)) + W = np.eye(T.shape[0]) + for j in range(sg_deg): + T[:, j + 1] = T[:, j] * reg_times + sg_vector_left_edge.append(W @ T @ np.linalg.inv(T.T @ W @ T) @ e_0) + reg_times = (np.arange(sg_window_size + i + 1) - sg_window_size) * mpc_time_step + T = np.ones((sg_window_size + i + 1, sg_deg + 1)) + W = np.eye(T.shape[0]) + for j in range(sg_deg): + T[:, j + 1] = T[:, j] * reg_times + sg_vector_right_edge.append(W @ T @ np.linalg.inv(T.T @ W @ T) @ e_0) + reg_times = (np.arange(2 * sg_window_size + 1) - sg_window_size) * mpc_time_step + T = np.ones((2 * sg_window_size + 1, sg_deg + 1)) + for j in range(sg_deg): + T[:, j + 1] = T[:, j] * reg_times + sg_vector = T @ np.linalg.inv(T.T @ T) @ e_0 + return sg_vector, sg_vector_left_edge, sg_vector_right_edge + + +( + sg_vector_for_nominal_inputs, + sg_vector_left_edge_for_nominal_inputs, + sg_vector_right_edge_for_nominal_inputs, +) = calc_sg_filter_weight(sg_deg_for_nominal_inputs, sg_window_size_for_nominal_inputs) +( + sg_vector_for_trained_model_diff, + sg_vector_left_edge_for_trained_model_diff, + sg_vector_right_edge_for_trained_model_diff, +) = calc_sg_filter_weight(sg_deg_for_trained_model_diff, sg_window_size_for_trained_model_diff) +( + sg_vector_for_noise, + sg_vector_left_edge_for_noise, + sg_vector_right_edge_for_noise, +) = calc_sg_filter_weight(sg_deg_for_noise, sg_window_size_for_noise) + +sg_filter_for_nominal_inputs = partial( + sg_filter, + use_sg=use_sg_for_nominal_inputs, + sg_window_size=sg_window_size_for_nominal_inputs, + sg_vector_left_edge=sg_vector_left_edge_for_nominal_inputs, + sg_vector_right_edge=sg_vector_right_edge_for_nominal_inputs, + sg_vector=sg_vector_for_nominal_inputs, +) + +sg_filter_for_trained_model_diff = partial( + sg_filter, + use_sg=use_sg_for_trained_model_diff, + sg_window_size=sg_window_size_for_trained_model_diff, + sg_vector_left_edge=sg_vector_left_edge_for_trained_model_diff, + sg_vector_right_edge=sg_vector_right_edge_for_trained_model_diff, + sg_vector=sg_vector_for_trained_model_diff, +) + +sg_filter_for_noise = partial( + sg_filter, + use_sg=use_sg_for_noise, + sg_window_size=sg_window_size_for_noise, + sg_vector_left_edge=sg_vector_left_edge_for_noise, + sg_vector_right_edge=sg_vector_right_edge_for_noise, + sg_vector=sg_vector_for_noise, +) + + +def calc_gf_kernel(sigma): + """Calculate the kernel of the Gaussian filter from the variance.""" + kernel = np.zeros(int(round(4 * sigma)) * 2 + 1) + for i in range(kernel.shape[0]): + kernel[i] = np.exp(-((i - round(4 * sigma)) ** 2) / (2 * sigma**2)) + + kernel = kernel / kernel.sum() + return kernel + + +kernel_acc_for_learning = calc_gf_kernel(acc_sigma_for_learning) +kernel_steer_for_learning = calc_gf_kernel(steer_sigma_for_learning) +kernel_acc_des_for_learning = calc_gf_kernel(acc_des_sigma_for_learning) +kernel_steer_des_for_learning = calc_gf_kernel(steer_des_sigma_for_learning) + +max_input_queue_size_for_learning = max( + [ + kernel_acc_for_learning.shape[0], + kernel_steer_for_learning.shape[0], + kernel_acc_des_for_learning.shape[0], + kernel_steer_des_for_learning.shape[0], + ] +) + +kernel_x_out_for_learning = calc_gf_kernel(x_out_sigma_for_learning) +kernel_y_out_for_learning = calc_gf_kernel(y_out_sigma_for_learning) +kernel_v_out_for_learning = calc_gf_kernel(v_out_sigma_for_learning) +kernel_theta_out_for_learning = calc_gf_kernel(theta_out_sigma_for_learning) +kernel_acc_out_for_learning = calc_gf_kernel(acc_out_sigma_for_learning) +kernel_steer_out_for_learning = calc_gf_kernel(steer_out_sigma_for_learning) + +max_output_queue_size_for_learning = max( + [ + kernel_x_out_for_learning.shape[0], + kernel_y_out_for_learning.shape[0], + kernel_v_out_for_learning.shape[0], + kernel_theta_out_for_learning.shape[0], + kernel_acc_out_for_learning.shape[0], + kernel_steer_out_for_learning.shape[0], + ] +) + + +def u_cut_off( + u_input: np.ndarray, + u_old: np.ndarray, + steer_lim: float, + steer_rate_lim_lb: float, + steer_rate_lim_ub: float, + acc_lim: float, + acc_rate_lim: float, +) -> np.ndarray: + """Process input values to satisfy constraints.""" + u_input_ = u_input.copy() + lb_0 = max(-acc_lim, u_old[0] - acc_rate_lim * ctrl_time_step) + ub_0 = min(acc_lim, u_old[0] + acc_rate_lim * ctrl_time_step) + lb_1 = max(-steer_lim, u_old[1] + steer_rate_lim_lb * ctrl_time_step) + ub_1 = min(steer_lim, u_old[1] + steer_rate_lim_ub * ctrl_time_step) + if u_input[0] >= ub_0: + u_input_[0] = ub_0 + elif u_input[0] < lb_0: + u_input_[0] = lb_0 + if u_input[1] >= ub_1: + u_input_[1] = ub_1 + elif u_input[1] < lb_1: + u_input_[1] = lb_1 + return u_input_ diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py new file mode 100644 index 0000000000000..261a72e680778 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_iLQR.py @@ -0,0 +1,644 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore numba njit fastmath Riccati Jacobians + +"""Optimize input based on iLQR.""" + + +from importlib import reload as ir +import time +from typing import Callable + +from numba import njit +import numpy as np +from smart_mpc_trajectory_follower.scripts import drive_functions + +index_cost = np.concatenate( + ( + np.arange(drive_functions.nx_0 + 1), + np.array([drive_functions.nx_0 + drive_functions.acc_ctrl_queue_size]), + ) +) +acc_index = drive_functions.nx_0 +steer_index = drive_functions.nx_0 + drive_functions.acc_ctrl_queue_size +actual_control_index = np.arange( + drive_functions.nx_0 + + drive_functions.acc_ctrl_queue_size + + drive_functions.steer_ctrl_queue_size_core +) +actual_state_dim = drive_functions.nx_0 +input_dim = drive_functions.nu_0 +mpc_freq = drive_functions.mpc_freq +acc_delay_step = drive_functions.acc_delay_step +steer_delay_step = drive_functions.steer_delay_step +acc_ctrl_queue_size = drive_functions.acc_ctrl_queue_size +steer_ctrl_queue_size = drive_functions.steer_ctrl_queue_size +ctrl_time_step = drive_functions.ctrl_time_step + + +@njit(cache=True, fastmath=True) +def sparse_right_action_for_state_diff( + Mat: np.ndarray, + A: np.ndarray, + actual_control_index=actual_control_index, + actual_state_dim=actual_state_dim, + acc_ctrl_queue_size=acc_ctrl_queue_size, + steer_ctrl_queue_size=steer_ctrl_queue_size, +) -> np.ndarray: + """Receives the sparse matrix `A₀` and computes `Mat @ A₀`. + + The argument A is part of A₀ . + The remaining A₀ components are known a priori. + """ + result = np.zeros( + (Mat.shape[0], actual_state_dim + acc_ctrl_queue_size + steer_ctrl_queue_size) + ) + result[:, actual_control_index] += Mat[:, :actual_state_dim] @ A + + result[:, actual_state_dim : actual_state_dim + acc_ctrl_queue_size - mpc_freq] += Mat[ + :, actual_state_dim + mpc_freq : actual_state_dim + acc_ctrl_queue_size + ] + result[ + :, + actual_state_dim + + acc_ctrl_queue_size : actual_state_dim + + acc_ctrl_queue_size + + steer_ctrl_queue_size + - mpc_freq, + ] += Mat[ + :, + actual_state_dim + + acc_ctrl_queue_size + + mpc_freq : actual_state_dim + + acc_ctrl_queue_size + + steer_ctrl_queue_size, + ] + for i in range(mpc_freq): + result[:, actual_state_dim] += Mat[:, actual_state_dim + i] + result[:, actual_state_dim + acc_ctrl_queue_size] += Mat[ + :, actual_state_dim + acc_ctrl_queue_size + i + ] + return result + + +@njit(cache=True, fastmath=True) +def sparse_left_action_for_state_diff( + A: np.ndarray, + Mat: np.ndarray, + actual_control_index=actual_control_index, + actual_state_dim=actual_state_dim, + acc_ctrl_queue_size=acc_ctrl_queue_size, + steer_ctrl_queue_size=steer_ctrl_queue_size, +) -> np.ndarray: + """Receives the sparse matrix A₀ and computes A₀.T @ Mat . + + The argument A is part of A₀ . + The remaining A₀ components are known a priori. + """ + result = np.zeros( + (actual_state_dim + acc_ctrl_queue_size + steer_ctrl_queue_size, Mat.shape[1]) + ) + result[actual_control_index] += A.T @ Mat[:actual_state_dim] + + result[actual_state_dim : actual_state_dim + acc_ctrl_queue_size - mpc_freq] += Mat[ + actual_state_dim + mpc_freq : actual_state_dim + acc_ctrl_queue_size + ] + result[ + actual_state_dim + + acc_ctrl_queue_size : actual_state_dim + + acc_ctrl_queue_size + + steer_ctrl_queue_size + - mpc_freq + ] += Mat[ + actual_state_dim + + acc_ctrl_queue_size + + mpc_freq : actual_state_dim + + acc_ctrl_queue_size + + steer_ctrl_queue_size + ] + for i in range(mpc_freq): + result[actual_state_dim] += Mat[actual_state_dim + i] + result[actual_state_dim + acc_ctrl_queue_size] += Mat[ + actual_state_dim + acc_ctrl_queue_size + i + ] + return result + + +@njit(cache=True, fastmath=True) +def vector_sparse_left_action_for_state_diff( + A: np.ndarray, + vec: np.ndarray, + actual_control_index=actual_control_index, + actual_state_dim=actual_state_dim, + acc_ctrl_queue_size=acc_ctrl_queue_size, + steer_ctrl_queue_size=steer_ctrl_queue_size, +) -> np.ndarray: + """Receives the sparse matrix A₀ and computes A₀.T @ vec. + + The argument A is part of A₀ . + The remaining A₀ components are known a priori. + """ + result = np.zeros(actual_state_dim + acc_ctrl_queue_size + steer_ctrl_queue_size) + result[actual_control_index] += A.T @ vec[:actual_state_dim] + + result[actual_state_dim : actual_state_dim + acc_ctrl_queue_size - mpc_freq] += vec[ + actual_state_dim + mpc_freq : actual_state_dim + acc_ctrl_queue_size + ] + result[ + actual_state_dim + + acc_ctrl_queue_size : actual_state_dim + + acc_ctrl_queue_size + + steer_ctrl_queue_size + - mpc_freq + ] += vec[ + actual_state_dim + + acc_ctrl_queue_size + + mpc_freq : actual_state_dim + + acc_ctrl_queue_size + + steer_ctrl_queue_size + ] + for i in range(mpc_freq): + result[actual_state_dim] += vec[actual_state_dim + i] + result[actual_state_dim + acc_ctrl_queue_size] += vec[ + actual_state_dim + acc_ctrl_queue_size + i + ] + return result + + +@njit(cache=True, fastmath=True) +def sparse_right_action_for_input_diff( + Mat: np.ndarray, + input_dim=input_dim, + actual_state_dim=actual_state_dim, + acc_ctrl_queue_size=acc_ctrl_queue_size, +) -> np.ndarray: + """Compute Mat @ B for some sparse matrix B known a priori.""" + result = np.zeros((Mat.shape[0], input_dim)) + for i in range(mpc_freq): + result[:, 0] += (mpc_freq - i) * ctrl_time_step * Mat[:, actual_state_dim + i] + result[:, 1] += ( + (mpc_freq - i) * ctrl_time_step * Mat[:, actual_state_dim + acc_ctrl_queue_size + i] + ) + return result + + +@njit(cache=True, fastmath=True) +def sparse_left_action_for_input_diff( + Mat: np.ndarray, + input_dim=input_dim, + actual_state_dim=actual_state_dim, + acc_ctrl_queue_size=acc_ctrl_queue_size, +) -> np.ndarray: + """Compute B.T @ Mat for some sparse matrix B known a priori.""" + result = np.zeros((input_dim, Mat.shape[1])) + for i in range(mpc_freq): + result[0] += (mpc_freq - i) * ctrl_time_step * Mat[actual_state_dim + i] + result[1] += ( + (mpc_freq - i) * ctrl_time_step * Mat[actual_state_dim + acc_ctrl_queue_size + i] + ) + return result + + +@njit(cache=True, fastmath=True) +def vector_sparse_left_action_for_input_diff( + vec: np.ndarray, + input_dim=input_dim, + actual_state_dim=actual_state_dim, + acc_ctrl_queue_size=acc_ctrl_queue_size, +) -> np.ndarray: + """Compute B.T @ vec for some sparse matrix B known a priori.""" + result = np.zeros(input_dim) + for i in range(mpc_freq): + result[0] += (mpc_freq - i) * ctrl_time_step * vec[actual_state_dim + i] + result[1] += ( + (mpc_freq - i) * ctrl_time_step * vec[actual_state_dim + acc_ctrl_queue_size + i] + ) + return result + + +@njit(cache=False, fastmath=True) +def compute_iLQR_coef( + traj, + inputs, + A, + B, + Q_total, + R_total, + acc_lim_weights, + acc_lim_center, + steer_lim_weights, + steer_lim_center, + acc_rate_lim_weights, + acc_rate_lim_center, + steer_rate_lim_weights, + steer_rate_lim_center, + N, + nx, + nu, + X_des, + U_des, + Sigma_x=None, + dSigma_x=None, + Sigma_y=None, + dSigma_y=None, + Sigma_v=None, + dSigma_v=None, + Sigma_theta=None, + dSigma_theta=None, + Sigma_acc=None, + dSigma_acc=None, + Sigma_steer=None, + dSigma_steer=None, + index_cost=index_cost, + acc_index=acc_index, + steer_index=steer_index, + actual_control_index=actual_control_index, + actual_state_dim=actual_state_dim, +): + """Perform the main part of iLQR. + + Performs a Riccati recursion and returns the coefficients needed for the final output. + """ + P = np.zeros((N + 1, nx, nx)) + w = np.zeros((N + 1, nx)) + H_inv_G = np.zeros((N, nu, nx)) + H_inv_g = np.zeros((N, nu)) + P[N][:7, :7] = Q_total[-1][:7, :7] + P[N][steer_index, steer_index] = Q_total[-1][7, 7] + + P[N][acc_index, acc_index] += acc_lim_weights[N] + P[N][steer_index, steer_index] += steer_lim_weights[N] + + w[N][index_cost] = Q_total[-1] @ (traj[N] - X_des[N]) + w[N, acc_index] += acc_lim_weights[N] * (traj[N, acc_index] - acc_lim_center[N]) + w[N, steer_index] += steer_lim_weights[N] * (traj[N, acc_index + 1] - steer_lim_center[N]) + + for i in range(N): + j = N - i - 1 + Qj = Q_total[j] + Rj = R_total[j] + Aj = A[j] + Pj1Aj = sparse_right_action_for_state_diff( + P[j + 1], Aj[:actual_state_dim, actual_control_index] + ) + G = sparse_left_action_for_input_diff(Pj1Aj) + + H = sparse_left_action_for_input_diff(sparse_right_action_for_input_diff(P[j + 1])) + Rj + H[0, 0] += acc_rate_lim_weights[j] + H[1, 1] += steer_rate_lim_weights[j] + + g_ = vector_sparse_left_action_for_input_diff(w[j + 1]) + Rj @ (inputs[j] - U_des[j]) + g_[0] += acc_rate_lim_weights[j] * (inputs[j, 0] - acc_rate_lim_center[j]) + g_[1] += steer_rate_lim_weights[j] * (inputs[j, 1] - steer_rate_lim_center[j]) + + one_over_det = 1 / (H[0, 0] * H[1, 1] - H[1, 0] * H[1, 0]) + + H_inv = one_over_det * np.array([[H[1, 1], -H[1, 0]], [-H[1, 0], H[0, 0]]]) + + H_inv_G[j] = H_inv @ G + H_inv_g[j] = H_inv @ g_ + + P[j] = ( + sparse_left_action_for_state_diff(Aj[:actual_state_dim, actual_control_index], Pj1Aj) + - G.T @ H_inv_G[j] + ) + P[j][:7, :7] += Qj[:7, :7] + P[j][steer_index, steer_index] += Qj[7, 7] + + P[j][acc_index, acc_index] += acc_lim_weights[j] + P[j][steer_index, steer_index] += steer_lim_weights[j] + + w[j] = ( + vector_sparse_left_action_for_state_diff( + Aj[:actual_state_dim, actual_control_index], w[j + 1] + ) + - H_inv_G[j].T @ g_ + ) + + w[j, index_cost] += Qj @ (traj[j] - X_des[j]) + w[j, acc_index] += acc_lim_weights[j] * (traj[j, acc_index] - acc_lim_center[j]) + w[j, steer_index] += steer_lim_weights[j] * (traj[j, acc_index + 1] - steer_lim_center[j]) + P_noise = np.zeros((nx, nx)) + w_noise = np.zeros(nx) + if Sigma_x is not None: + sigma_x = Sigma_x[j] + d_sigma_x = dSigma_x[j] + vec_part = P[j][0, 0] * d_sigma_x + P_noise += d_sigma_x.reshape(-1, 1) @ vec_part.reshape(1, -1) + w_noise += sigma_x * vec_part + if Sigma_y is not None: + sigma_y = Sigma_y[j] + d_sigma_y = dSigma_y[j] + vec_part = P[j][1, 1] * d_sigma_y + P_noise += d_sigma_y.reshape(-1, 1) @ vec_part.reshape(1, -1) + w_noise += sigma_y * vec_part + if Sigma_v is not None: + sigma_v = Sigma_v[j] + d_sigma_v = dSigma_v[j] + vec_part = P[j][2, 2] * d_sigma_v + P_noise += d_sigma_v.reshape(-1, 1) @ vec_part.reshape(1, -1) + w_noise += sigma_v * vec_part + if Sigma_theta is not None: + sigma_theta = Sigma_theta[j] + d_sigma_theta = dSigma_theta[j] + vec_part = P[j][3, 3] * d_sigma_theta + P_noise += d_sigma_theta.reshape(-1, 1) @ vec_part.reshape(1, -1) + w_noise += sigma_theta * vec_part + if Sigma_acc is not None: + sigma_acc = Sigma_acc[j] + d_sigma_acc = dSigma_acc[j] + vec_part = P[j][4, 4] * d_sigma_acc + P_noise += d_sigma_acc.reshape(-1, 1) @ vec_part.reshape(1, -1) + w_noise += sigma_acc * vec_part + if Sigma_steer is not None: + sigma_steer = Sigma_steer[j] + d_sigma_steer = dSigma_steer[j] + vec_part = P[j][5, 5] * d_sigma_steer + P_noise += d_sigma_steer.reshape(-1, 1) @ vec_part.reshape(1, -1) + w_noise += sigma_steer * vec_part + + P[j] += P_noise + w[j] += w_noise + return P, w, H_inv_G, H_inv_g + + +@njit(cache=True, fastmath=True) +def calc_line_search_candidates(A, B, H_inv_g, H_inv_G, inputs, ls): + """Compute the candidate input columns for the line search in the final stage of iLQR.""" + ls_num = ls.shape[0] + nx = A.shape[2] + nu = B.shape[2] + N = A.shape[0] + + Inputs = np.zeros((ls_num, N, nu)) + delta_x_k = np.zeros((ls_num, nx)) + for k in range(N): + delta_u_k = -ls.reshape(-1, 1) @ H_inv_g[k].reshape(1, -1) - delta_x_k @ H_inv_G[k].T + Inputs[:, k, :] = inputs[k] + delta_u_k + delta_x_k = delta_x_k @ A[k].T + delta_u_k @ B[k].T + return Inputs + + +class drive_iLQR: + """Class that runs iLQR to compute optimal input values.""" + + ls_step: float + """ Line search step width """ + + max_iter_ls: int + """ Number of candidates for line search. """ + + max_iter_ilqr: int + """ Maximum number of iLQR iterations """ + + ilqr_tol: float + """ Tolerance to terminate iLQR iterations """ + + use_trained_model_diff: bool + """ Whether to use the derivative of the trained model """ + + def __init__( + self, + ls_step, + max_iter_ls, + max_iter_ilqr, + ilqr_tol, + use_trained_model_diff, + ): + ir(drive_functions) + self.ls_step = ls_step + self.max_iter_ls = max_iter_ls + self.max_iter_ilqr = max_iter_ilqr + self.ilqr_tol = ilqr_tol + self.use_trained_model_diff = use_trained_model_diff + + ls = np.ones(max_iter_ls + 1) + for i in range(max_iter_ls - 1): + ls[i + 1] = ls_step * ls[i] + ls[-1] = 0.0 + self.ls = ls + + def calc_forward_trajectories_with_cost( + self, + x_current: np.ndarray, + Inputs: np.ndarray, + X_des: np.ndarray, + U_des: np.ndarray, + previous_error: np.ndarray, + ) -> tuple[np.ndarray, np.ndarray]: + """Calculate the predicted trajectory and cost. + + Given the current state and the candidate input columns in the line search. + """ + N = Inputs.shape[1] + samples = Inputs.shape[0] + Traj = np.zeros((samples, N + 1, x_current.shape[0])) + Traj[:, 0, :] += x_current + Cost = np.zeros(samples) + + Previous_error = np.tile(previous_error[:6], (samples, 1)) + for k in range(N): + Cost += drive_functions.calc_cost( + X_des[k], + U_des[k], + Traj[:, k, index_cost], + Inputs[:, k, :], + k, + ) + Traj[:, k + 1], Previous_error = self.F_for_candidates( + Traj[:, k], Inputs[:, k], Previous_error, k + ) + Cost += drive_functions.calc_cost( + X_des[N], + U_des[N - 1], + Traj[:, N, index_cost], + Inputs[:, N - 1, :], + N, + ) + return Traj, Cost + + def calc_forward_trajectory_with_diff( + self, x_current: np.ndarray, inputs: np.ndarray, previous_error: np.ndarray + ) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + """Calculate the derivatives (Jacobians) of the predicted trajectory t with diff. + + This also calculates "the function that returns the predicted trajectory from the current state and the input sequence", + given the current state and the input sequence. + """ + N = inputs.shape[0] + nx = x_current.shape[0] + nu = inputs.shape[1] + traj = np.zeros((N + 1, nx)) + traj[0] = x_current + A = np.zeros((N, nx, nx)) + B = np.zeros((N, nx, nu)) + C = np.zeros((N, 6, nx)) + previous_error_ = previous_error.copy() + for k in range(N): + if self.use_trained_model_diff: + traj[k + 1], A[k], B[k], C[k], previous_error_ = self.F_with_diff( + traj[k], inputs[k], previous_error_, k + ) + else: + traj[k + 1], A[k], B[k], previous_error_ = self.F_with_initial_diff( + traj[k], inputs[k], previous_error_, k + ) + if self.use_trained_model_diff: + A[:, :6] += drive_functions.sg_filter_for_trained_model_diff(C) + return traj, A, B + + def compute_optimal_control( + self, + x_current: np.ndarray, + inputs: np.ndarray, + X_des: np.ndarray, + U_des: np.ndarray, + previous_error: np.ndarray, + x_noise: Callable | None, + y_noise: Callable | None, + v_noise: Callable | None, + theta_noise: Callable | None, + acc_noise: Callable | None, + steer_noise: Callable | None, + ) -> tuple[np.ndarray, np.ndarray, np.ndarray, bool]: + """Calculate the optimal predictive trajectory and the input sequence at that time. + + It also determines whether the tolerance has been reached and returns whether the optimization should continue or not. + Performs one iteration of iLQR. + """ + nx = x_current.shape[0] + nu = inputs.shape[1] + N = inputs.shape[0] + self.time_1 = time.time() + traj, A, B = self.calc_forward_trajectory_with_diff(x_current, inputs, previous_error) + ( + Q_total, + R_total, + acc_lim_weights, + acc_lim_center, + steer_lim_weights, + steer_lim_center, + acc_rate_lim_weights, + acc_rate_lim_center, + steer_rate_lim_weights, + steer_rate_lim_center, + ) = drive_functions.transform_Q_R(X_des, U_des, traj, inputs) + self.time_2 = time.time() + if x_noise is None: + Sigma_x = None + dSigma_x = None + else: + Sigma_x, dSigma_x = x_noise(np.hstack((traj[:-1, [2, 3, 5]], traj[:-1, 6:]))) + Sigma_x = drive_functions.sg_filter_for_noise(Sigma_x) + dSigma_x = drive_functions.sg_filter_for_noise(dSigma_x) + if y_noise is None: + Sigma_y = None + dSigma_y = None + else: + Sigma_y, dSigma_y = y_noise(np.hstack((traj[:-1, [2, 3, 5]], traj[:-1, 6:]))) + Sigma_y = drive_functions.sg_filter_for_noise(Sigma_y) + dSigma_y = drive_functions.sg_filter_for_noise(dSigma_y) + if v_noise is None: + Sigma_v = None + dSigma_v = None + else: + Sigma_v, dSigma_v = v_noise(np.hstack((traj[:-1, [2, 3, 5]], traj[:-1, 6:]))) + Sigma_v = drive_functions.sg_filter_for_noise(Sigma_v) + dSigma_v = drive_functions.sg_filter_for_noise(dSigma_v) + if theta_noise is None: + Sigma_theta = None + dSigma_theta = None + else: + Sigma_theta, dSigma_theta = theta_noise( + np.hstack((traj[:-1, [2, 3, 5]], traj[:-1, 6:])) + ) + Sigma_theta = drive_functions.sg_filter_for_noise(Sigma_theta) + dSigma_theta = drive_functions.sg_filter_for_noise(dSigma_theta) + if acc_noise is None: + Sigma_acc = None + dSigma_acc = None + else: + Sigma_acc, dSigma_acc = acc_noise(np.hstack((traj[:-1, [2, 3, 5]], traj[:-1, 6:]))) + Sigma_acc = drive_functions.sg_filter_for_noise(Sigma_acc) + dSigma_acc = drive_functions.sg_filter_for_noise(dSigma_acc) + + if steer_noise is None: + Sigma_steer = None + dSigma_steer = None + else: + Sigma_steer, dSigma_steer = steer_noise( + np.hstack((traj[:-1, [2, 3, 5]], traj[:-1, 6:])) + ) + Sigma_steer = drive_functions.sg_filter_for_noise(Sigma_steer) + dSigma_steer = drive_functions.sg_filter_for_noise(dSigma_steer) + P, w, H_inv_G, H_inv_g = compute_iLQR_coef( + traj[:, index_cost], + inputs, + A, + B, + Q_total, + R_total, + acc_lim_weights, + acc_lim_center, + steer_lim_weights, + steer_lim_center, + acc_rate_lim_weights, + acc_rate_lim_center, + steer_rate_lim_weights, + steer_rate_lim_center, + N, + nx, + nu, + X_des, + U_des, + Sigma_x, + dSigma_x, + Sigma_y, + dSigma_y, + Sigma_v, + dSigma_v, + Sigma_theta, + dSigma_theta, + Sigma_acc, + dSigma_acc, + Sigma_steer, + dSigma_steer, + ) + self.time_3 = time.time() + # start line search + Inputs = calc_line_search_candidates(A, B, H_inv_g, H_inv_G, inputs, self.ls) + self.time_4 = time.time() + Traj, Cost = self.calc_forward_trajectories_with_cost( + x_current, Inputs, X_des, U_des, previous_error + ) + best_index = Cost.argmin() + self.time_5 = time.time() + + if Cost[best_index] < (1 - self.ilqr_tol) * Cost[-1]: + proceed = True + else: + proceed = False + + best_traj = Traj[best_index] + best_inputs = Inputs[best_index] + return best_inputs, best_inputs[0], best_traj, proceed + + def receive_model( + self, F_with_initial_diff: Callable, F_with_diff: Callable, F_for_candidates: Callable + ): + """Receive vehicle model for control.""" + self.F_with_initial_diff = F_with_initial_diff + self.F_with_diff = F_with_diff + self.F_for_candidates = F_for_candidates diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py new file mode 100644 index 0000000000000..ca6e6f15f42ef --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/drive_mppi.py @@ -0,0 +1,170 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore numba njit fastmath + +from typing import Callable + +from numba import njit +import numpy as np +from smart_mpc_trajectory_follower.scripts import drive_functions + +index_cost = np.concatenate( + ( + np.arange(drive_functions.nx_0 + 1), + [drive_functions.nx_0 + drive_functions.acc_ctrl_queue_size], + ) +) + + +@njit(cache=False, fastmath=True) +def generate_input_perturbation(N, sample_num, step, Sigma_0, Sigma_1): + """Generate random perturbations of the input in MPPI.""" + change_input_index = np.concatenate((np.arange(N, step=step), np.array([N]))) + acc_perturbation = np.random.normal( + loc=0, scale=Sigma_0, size=(sample_num - 1, change_input_index.shape[0] - 1) + ) + steer_perturbation = np.random.normal( + loc=0, scale=Sigma_1, size=(sample_num - 1, change_input_index.shape[0] - 1) + ) + Input_perturbation = np.zeros((sample_num - 1, N, 2)) + + for i in range(change_input_index.shape[0] - 1): + Input_perturbation[ + :, change_input_index[i] : change_input_index[i + 1], 0 + ] += acc_perturbation[:, np.array([i])] + Input_perturbation[ + :, change_input_index[i] : change_input_index[i + 1], 1 + ] += steer_perturbation[:, np.array([i])] + + return Input_perturbation + + +class drive_mppi: + """Class that runs MPPI to compute optimal input values.""" + + def __init__( + self, + lam, + Sigma, + max_iter_mppi, + sample_num, + mppi_tol, + mppi_step, + ): + self.lam = lam + self.Sigma = Sigma + + self.max_iter_mppi = max_iter_mppi + self.sample_num = sample_num + self.mppi_tol = mppi_tol + self.mppi_step = mppi_step + + def generate_sample_inputs(self, inputs): + """Generate input samples in MPPI.""" + N = inputs.shape[0] + nu = inputs.shape[1] + Inputs = np.zeros((self.sample_num, N, nu)) + + Inputs += inputs + Inputs[1:] += generate_input_perturbation( + N, self.sample_num, self.mppi_step, self.Sigma[0], self.Sigma[1] + ) + return Inputs + + def calc_forward_trajectories_with_cost(self, x_current, Inputs, X_des, U_des, Previous_error): + """Calculate the predicted trajectory and cost. + + Given the current state and the candidate input columns in the line search. + """ + N = Inputs.shape[1] + samples = Inputs.shape[0] + Traj = np.zeros((samples, N + 1, x_current.shape[0])) + Traj[:, 0, :] += x_current + Cost = np.zeros(samples) + for k in range(N): + Cost += drive_functions.calc_cost_only_for_states( + X_des[k], Traj[:, k, index_cost], k + ) + self.lam * (Inputs[:, k, :] - Inputs[0, k, :]) @ ( + (1 / self.Sigma) * (Inputs[0, k, :] - U_des[k]) + ) + Traj[:, k + 1], Previous_error = self.F_for_candidates( + Traj[:, k], Inputs[:, k], Previous_error, k + ) + Cost += drive_functions.calc_cost_only_for_states(X_des[N], Traj[:, N, index_cost], N) + return Traj, Cost + + def proceed_mppi_step(self, x_current, inputs, X_des, U_des, previous_error): + """Proceed with MPPI iteration one time.""" + N = inputs.shape[0] + + previous_error_ = previous_error.reshape(1, -1).copy() + nominal_traj = np.zeros((N + 1, x_current.shape[0])) + nominal_traj[0] = x_current.copy() + for k in range(N): + if k == 0: + Traj_, previous_error_ = self.F_for_candidates( + nominal_traj[k].reshape(1, -1), inputs[k].reshape(1, -1), previous_error_, True + ) + nominal_traj[k + 1] = Traj_[0] + else: + Traj_, previous_error_ = self.F_for_candidates( + nominal_traj[k].reshape(1, -1), inputs[k].reshape(1, -1), previous_error_, False + ) + nominal_traj[k + 1] = Traj_[0] + + Inputs = self.generate_sample_inputs(inputs) + + Previous_error = np.tile(previous_error, (self.sample_num, 1)) + _, Cost = self.calc_forward_trajectories_with_cost( + x_current, Inputs, X_des, U_des, Previous_error + ) + original_cost = Cost[0] + best_cost = Cost.min() + Exps = np.exp(-(Cost - best_cost) / self.lam) + Exps = Exps / Exps.sum() + new_inputs = (Inputs.T @ Exps).T + previous_error_ = previous_error.reshape(1, -1).copy() + new_traj = np.zeros((N + 1, x_current.shape[0])) + new_traj[0] = x_current.copy() + for k in range(N): + if k == 0: + Traj_, previous_error_ = self.F_for_candidates( + new_traj[k].reshape(1, -1), new_inputs[k].reshape(1, -1), previous_error_, True + ) + new_traj[k + 1] = Traj_[0] + else: + Traj_, previous_error_ = self.F_for_candidates( + new_traj[k].reshape(1, -1), new_inputs[k].reshape(1, -1), previous_error_, False + ) + new_traj[k + 1] = Traj_[0] + if np.dot(Exps, Cost) < (1 - self.mppi_tol) * original_cost: + proceed = True + else: + proceed = False + return new_traj, new_inputs, proceed + + def compute_optimal_control(self, x_current, inputs, X_des, U_des, previous_error): + """Calculate the optimal input based on MPPI.""" + for i in range(self.max_iter_mppi): + new_traj, new_inputs, proceed = self.proceed_mppi_step( + x_current, inputs, X_des, U_des, previous_error + ) + if not proceed: + break + return new_inputs, new_inputs[0], new_traj + + def receive_model(self, F_for_candidates: Callable): + """Receive vehicle model for control.""" + self.F_for_candidates = F_for_candidates diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/proxima_calc.cpp b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/proxima_calc.cpp new file mode 100644 index 0000000000000..de65184ec9f8e --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/proxima_calc.cpp @@ -0,0 +1,487 @@ +// Copyright 2024 Proxima Technology Inc, TIER IV +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include + +#include +namespace py = pybind11; + +double nominal_model_input(Eigen::VectorXd var, double lam, int step) +{ + double nominal_pred = var[0]; + nominal_pred += (var[step] - nominal_pred) * 0.03333 / lam; + nominal_pred += (var[step - 1] - nominal_pred) * 0.03333 / lam; + nominal_pred += (var[step - 2] - nominal_pred) * 0.03333 / lam; + return nominal_pred; +} +Eigen::RowVectorXd Nominal_model_input(Eigen::MatrixXd Var, double lam, int step) +{ + Eigen::RowVectorXd nominal_pred = Var.row(0); + nominal_pred += (Var.row(step) - nominal_pred) * 0.03333 / lam; + nominal_pred += (Var.row(step - 1) - nominal_pred) * 0.03333 / lam; + nominal_pred += (Var.row(step - 2) - nominal_pred) * 0.03333 / lam; + return nominal_pred; +} + +Eigen::VectorXd d_tanh(Eigen::VectorXd v) +{ + Eigen::VectorXd result = 1 / (v.array().cosh() * v.array().cosh()); + return result; +} +Eigen::VectorXd relu(Eigen::VectorXd x) +{ + Eigen::VectorXd x_ = x; + for (int i = 0; i < x.size(); i++) { + if (x[i] < 0) { + x_[i] = 0; + } + } + return x_; +} +Eigen::VectorXd d_relu(Eigen::VectorXd x) +{ + Eigen::VectorXd result = Eigen::VectorXd::Ones(x.size()); + for (int i = 0; i < x.size(); i++) { + if (x[i] < 0) { + result[i] = 0; + } + } + return result; +} + +Eigen::MatrixXd d_relu_product(Eigen::MatrixXd m, Eigen::VectorXd x) +{ + Eigen::MatrixXd result = Eigen::MatrixXd::Zero(m.rows(), m.cols()); + for (int i = 0; i < m.cols(); i++) { + if (x[i] >= 0) { + result.col(i) = m.col(i); + } + } + return result; +} +Eigen::MatrixXd d_tanh_product(Eigen::MatrixXd m, Eigen::VectorXd x) +{ + Eigen::MatrixXd result = Eigen::MatrixXd(m.rows(), m.cols()); + for (int i = 0; i < m.cols(); i++) { + result.col(i) = m.col(i) / (std::cosh(x[i]) * std::cosh(x[i])); + } + return result; +} +Eigen::MatrixXd test_product(Eigen::VectorXd v, Eigen::MatrixXd m) +{ + return v.asDiagonal() * m; +} +Eigen::VectorXd get_polynomial_features(Eigen::VectorXd x, int deg, int dim) +{ + int n_features = x.size(); + Eigen::VectorXd result = Eigen::VectorXd(dim); + result.head(n_features) = x; + if (deg >= 2) { + std::vector index = {}; + for (int feature_idx = 0; feature_idx < n_features + 1; feature_idx++) { + index.push_back(feature_idx); + } + int current_idx = n_features; + for (int i = 0; i < deg - 1; i++) { + std::vector new_index = {}; + int end = index[index.size() - 1]; + for (int feature_idx = 0; feature_idx < n_features; feature_idx++) { + int start = index[feature_idx]; + new_index.push_back(current_idx); + int next_idx = current_idx + end - start; + result.segment(current_idx, end - start) = + x[feature_idx] * result.segment(start, end - start); + current_idx = next_idx; + } + new_index.push_back(current_idx); + index = new_index; + } + } + return result; +} +Eigen::MatrixXd get_polynomial_features_with_diff(Eigen::VectorXd x, int deg, int dim) +{ + int n_features = x.size(); + Eigen::MatrixXd result = Eigen::MatrixXd::Zero(dim, n_features + 1); + result.block(0, 0, n_features, 1) = x; + result.block(0, 1, n_features, n_features) = Eigen::MatrixXd::Identity(n_features, n_features); + if (deg >= 2) { + std::vector index = {}; + for (int feature_idx = 0; feature_idx < n_features + 1; feature_idx++) { + index.push_back(feature_idx); + } + int current_idx = n_features; + for (int i = 0; i < deg - 1; i++) { + std::vector new_index = {}; + int end = index[index.size() - 1]; + for (int feature_idx = 0; feature_idx < n_features; feature_idx++) { + int start = index[feature_idx]; + new_index.push_back(current_idx); + int next_idx = current_idx + end - start; + result.block(current_idx, 0, end - start, n_features + 1) = + x[feature_idx] * result.block(start, 0, end - start, n_features + 1); + result.block(current_idx, feature_idx + 1, end - start, 1) += + result.block(start, 0, end - start, 1); + current_idx = next_idx; + } + new_index.push_back(current_idx); + index = new_index; + } + } + return result; +} +class transform_model_to_eigen +{ +private: + Eigen::MatrixXd weight_0; + Eigen::MatrixXd weight_1; + Eigen::MatrixXd weight_2; + Eigen::MatrixXd weight_3; + Eigen::MatrixXd weight_4; + Eigen::MatrixXd weight_5; + Eigen::MatrixXd weight_6; + Eigen::MatrixXd weight_7; + Eigen::VectorXd bias_0; + Eigen::VectorXd bias_1; + Eigen::VectorXd bias_2; + Eigen::VectorXd bias_3; + Eigen::VectorXd bias_4; + Eigen::VectorXd bias_5; + Eigen::VectorXd bias_6; + Eigen::VectorXd bias_7; + Eigen::MatrixXd A_linear_reg; + Eigen::VectorXd b_linear_reg; + int deg; + double acc_time_constant; + int acc_delay_step; + double steer_time_constant; + int steer_delay_step; + int acc_ctrl_queue_size; + int steer_ctrl_queue_size; + int steer_ctrl_queue_size_core; + double max_acc_error = 20.0; + double max_steer_error = 20.0; + +public: + transform_model_to_eigen() {} + void set_params( + Eigen::MatrixXd weight_0_, Eigen::MatrixXd weight_1_, Eigen::MatrixXd weight_2_, + Eigen::MatrixXd weight_3_, Eigen::MatrixXd weight_4_, Eigen::MatrixXd weight_5_, + Eigen::MatrixXd weight_6_, Eigen::MatrixXd weight_7_, Eigen::VectorXd bias_0_, + Eigen::VectorXd bias_1_, Eigen::VectorXd bias_2_, Eigen::VectorXd bias_3_, + Eigen::VectorXd bias_4_, Eigen::VectorXd bias_5_, Eigen::VectorXd bias_6_, + Eigen::VectorXd bias_7_, Eigen::MatrixXd A_linear_reg_, Eigen::VectorXd b_linear_reg_, int deg_, + double acc_time_constant_, int acc_delay_step_, double steer_time_constant_, + int steer_delay_step_, int acc_ctrl_queue_size_, int steer_ctrl_queue_size_, + int steer_ctrl_queue_size_core_) + { + weight_0 = weight_0_; + weight_1 = weight_1_; + weight_2 = weight_2_; + weight_3 = weight_3_; + weight_4 = weight_4_; + weight_5 = weight_5_; + weight_6 = weight_6_; + weight_7 = weight_7_; + bias_0 = bias_0_; + bias_1 = bias_1_; + bias_2 = bias_2_; + bias_3 = bias_3_; + bias_4 = bias_4_; + bias_5 = bias_5_; + bias_6 = bias_6_; + bias_7 = bias_7_; + A_linear_reg = A_linear_reg_; + b_linear_reg = b_linear_reg_; + deg = deg_; + acc_time_constant = acc_time_constant_; + acc_delay_step = acc_delay_step_; + steer_time_constant = steer_time_constant_; + steer_delay_step = steer_delay_step_; + acc_ctrl_queue_size = acc_ctrl_queue_size_; + steer_ctrl_queue_size = steer_ctrl_queue_size_; + steer_ctrl_queue_size_core = steer_ctrl_queue_size_core_; + } + Eigen::VectorXd error_prediction(Eigen::VectorXd x) + { + Eigen::VectorXd acc_sub(acc_ctrl_queue_size + 1); + acc_sub[0] = x[1]; + acc_sub.tail(acc_ctrl_queue_size) = x.segment(3, acc_ctrl_queue_size); + + Eigen::VectorXd steer_sub(steer_ctrl_queue_size_core + 1); + steer_sub[0] = x[2]; + steer_sub.tail(steer_ctrl_queue_size_core) = + x.segment(3 + acc_ctrl_queue_size, steer_ctrl_queue_size_core); + Eigen::VectorXd acc_layer_1 = relu(weight_0 * acc_sub + bias_0); + + Eigen::VectorXd steer_layer_1(bias_1.size() + bias_2.size()); + steer_layer_1.head(bias_1.size()) = relu(weight_1 * steer_sub + bias_1); + + Eigen::VectorXd steer_input_full = x.segment(3 + acc_ctrl_queue_size, steer_ctrl_queue_size); + steer_layer_1.tail(bias_2.size()) = relu(weight_2 * steer_input_full + bias_2); + + Eigen::VectorXd acc_layer_2 = (weight_3 * acc_layer_1 + bias_3).array().tanh(); + + Eigen::VectorXd steer_layer_2 = (weight_4 * steer_layer_1 + bias_4).array().tanh(); + + Eigen::VectorXd h1(1 + acc_layer_2.size() + steer_layer_2.size()); + h1[0] = x[0]; + h1.segment(1, acc_layer_2.size()) = acc_layer_2; + h1.tail(steer_layer_2.size()) = steer_layer_2; + Eigen::VectorXd h2 = relu(weight_5 * h1 + bias_5); + Eigen::VectorXd h3 = relu(weight_6 * h2 + bias_6); + Eigen::VectorXd h4(h3.size() + acc_layer_2.size() + steer_layer_2.size()); + h4.head(h3.size()) = h3; + h4.segment(h3.size(), acc_layer_2.size()) = acc_layer_2; + h4.tail(steer_layer_2.size()) = steer_layer_2; + Eigen::VectorXd x_for_polynomial_reg(5); + x_for_polynomial_reg.head(3) = x.head(3); + x_for_polynomial_reg[3] = x[3 + acc_delay_step]; + x_for_polynomial_reg[4] = x[3 + acc_ctrl_queue_size + steer_delay_step]; + Eigen::VectorXd y = + weight_7 * h4 + bias_7 + + A_linear_reg * get_polynomial_features(x_for_polynomial_reg, deg, A_linear_reg.cols()) + + b_linear_reg; + y[4] = std::min(std::max(y[4], -max_acc_error), max_acc_error); + y[5] = std::min(std::max(y[5], -max_steer_error), max_steer_error); + return y; + } + Eigen::VectorXd rot_and_d_rot_error_prediction(Eigen::VectorXd x) + { + int x_dim = x.size(); + double theta = x[3]; + double v = x[2]; + double coef = 2.0 * std::abs(v); + coef = coef * coef * coef * coef * coef * coef * coef; + if (coef > 1.0) { + coef = 1.0; + } + /* + In previous implementations, the training model was unreliable in the low speed range + because data in the low speed range was excluded from the training data + in order to exclude data not under control from them. + However, now the topic /system/operation_mode/state is used to identify + whether the data is under control or not. + Therefore, it may be safe to always set coef = 1, and this variable may be eliminated + once it is confirmed safe to do so. + */ + double cos = std::cos(theta); + double sin = std::sin(theta); + Eigen::Matrix2d Rot; + Rot << cos, -sin, sin, cos; + + Eigen::Matrix2d dRot; + dRot << -sin, -cos, cos, -sin; + Eigen::VectorXd vars(x_dim - 3); + vars[0] = x[2]; + vars[1] = x[4]; + vars[2] = x[5]; + vars.tail(x_dim - 6) = x.tail(x_dim - 6); + Eigen::VectorXd pred = error_prediction(vars); + Eigen::VectorXd rot_and_d_rot_pred(8); + rot_and_d_rot_pred.head(2) = Rot * pred.head(2); + rot_and_d_rot_pred.segment(2, 4) = pred.segment(2, 4); + rot_and_d_rot_pred.tail(2) = dRot * pred.head(2); + + return coef * rot_and_d_rot_pred; + } + Eigen::MatrixXd error_prediction_with_diff(Eigen::VectorXd x) + { + Eigen::VectorXd acc_sub(acc_ctrl_queue_size + 1); + acc_sub[0] = x[1]; + acc_sub.tail(acc_ctrl_queue_size) = x.segment(3, acc_ctrl_queue_size); + + Eigen::VectorXd steer_sub(steer_ctrl_queue_size_core + 1); + steer_sub[0] = x[2]; + steer_sub.tail(steer_ctrl_queue_size_core) = + x.segment(3 + acc_ctrl_queue_size, steer_ctrl_queue_size_core); + Eigen::VectorXd steer_input_full = x.segment(3 + acc_ctrl_queue_size, steer_ctrl_queue_size); + + Eigen::VectorXd u_acc_layer_1 = weight_0 * acc_sub + bias_0; + Eigen::VectorXd acc_layer_1 = relu(u_acc_layer_1); + + Eigen::VectorXd u_steer_layer_1(bias_1.size() + bias_2.size()); + u_steer_layer_1.head(bias_1.size()) = weight_1 * steer_sub + bias_1; + u_steer_layer_1.tail(bias_2.size()) = weight_2 * steer_input_full + bias_2; + Eigen::VectorXd steer_layer_1 = relu(u_steer_layer_1); + + Eigen::VectorXd u_acc_layer_2 = weight_3 * acc_layer_1 + bias_3; + Eigen::VectorXd acc_layer_2 = u_acc_layer_2.array().tanh(); + + Eigen::VectorXd u_steer_layer_2 = weight_4 * steer_layer_1 + bias_4; + Eigen::VectorXd steer_layer_2 = u_steer_layer_2.array().tanh(); + + Eigen::VectorXd h1(1 + acc_layer_2.size() + steer_layer_2.size()); + h1[0] = x[0]; + h1.segment(1, acc_layer_2.size()) = acc_layer_2; + h1.tail(steer_layer_2.size()) = steer_layer_2; + Eigen::VectorXd u2 = weight_5 * h1 + bias_5; + Eigen::VectorXd h2 = relu(u2); + Eigen::VectorXd u3 = weight_6 * h2 + bias_6; + Eigen::VectorXd h3 = relu(u3); + Eigen::VectorXd h4(h3.size() + acc_layer_2.size() + steer_layer_2.size()); + h4.head(h3.size()) = h3; + h4.segment(h3.size(), acc_layer_2.size()) = acc_layer_2; + h4.tail(steer_layer_2.size()) = steer_layer_2; + Eigen::VectorXd x_for_polynomial_reg(5); + x_for_polynomial_reg.head(3) = x.head(3); + x_for_polynomial_reg[3] = x[3 + acc_delay_step]; + x_for_polynomial_reg[4] = x[3 + acc_ctrl_queue_size + steer_delay_step]; + Eigen::MatrixXd polynomial_features_with_diff = + get_polynomial_features_with_diff(x_for_polynomial_reg, deg, A_linear_reg.cols()); + + Eigen::VectorXd y = + weight_7 * h4 + bias_7 + + A_linear_reg * polynomial_features_with_diff.block(0, 0, A_linear_reg.cols(), 1) + + b_linear_reg; + y[4] = std::min(std::max(y[4], -max_acc_error), max_acc_error); + y[5] = std::min(std::max(y[5], -max_steer_error), max_steer_error); + // Eigen::MatrixXd dy_dh4 = weight_7; + + Eigen::MatrixXd dy_dh3 = weight_7.block(0, 0, y.size(), h3.size()); + Eigen::MatrixXd dy_dh2 = d_relu_product(dy_dh3, u3) * weight_6; + Eigen::MatrixXd dy_dh1 = d_relu_product(dy_dh2, u2) * weight_5; + + Eigen::MatrixXd dy_da2 = dy_dh1.block(0, 1, y.size(), acc_layer_2.size()) + + weight_7.block(0, h3.size(), y.size(), acc_layer_2.size()); + Eigen::MatrixXd dy_ds2 = + dy_dh1.block(0, 1 + acc_layer_2.size(), y.size(), steer_layer_2.size()) + + weight_7.block(0, h3.size() + acc_layer_2.size(), y.size(), steer_layer_2.size()); + Eigen::MatrixXd dy_da1 = d_tanh_product(dy_da2, u_acc_layer_2) * weight_3; + Eigen::MatrixXd dy_ds1 = d_tanh_product(dy_ds2, u_steer_layer_2) * weight_4; + + Eigen::MatrixXd dy_d_acc = d_relu_product(dy_da1, u_acc_layer_1) * weight_0; + Eigen::MatrixXd dy_d_steer = Eigen::MatrixXd::Zero(y.size(), steer_input_full.size() + 1); + dy_d_steer.block(0, 1, y.size(), steer_input_full.size()) += + d_relu_product( + dy_ds1.block(0, bias_1.size(), y.size(), bias_2.size()), + u_steer_layer_1.tail(bias_2.size())) * + weight_2; + dy_d_steer.block(0, 0, y.size(), steer_sub.size()) += + d_relu_product( + dy_ds1.block(0, 0, y.size(), bias_1.size()), u_steer_layer_1.head(bias_1.size())) * + weight_1; + + Eigen::MatrixXd result = Eigen::MatrixXd::Zero(y.size(), x.size() + 1); + + result.col(0) = y; + + result.col(1) = dy_dh1.col(0); + result.col(2) = dy_d_acc.col(0); + result.col(3) = dy_d_steer.col(0); + result.block(0, 4, y.size(), acc_ctrl_queue_size) = + dy_d_acc.block(0, 1, y.size(), acc_ctrl_queue_size); + result.block(0, 4 + acc_ctrl_queue_size, y.size(), steer_ctrl_queue_size) = + dy_d_steer.block(0, 1, y.size(), steer_ctrl_queue_size); + + Eigen::MatrixXd polynomial_reg_diff = + A_linear_reg * + polynomial_features_with_diff.block(0, 1, A_linear_reg.cols(), x_for_polynomial_reg.size()); + result.block(0, 1, y.size(), 3) += polynomial_reg_diff.block(0, 0, y.size(), 3); + result.block(0, 4 + acc_delay_step, y.size(), 1) += + polynomial_reg_diff.block(0, 3, y.size(), 1); + result.block(0, 4 + acc_ctrl_queue_size + steer_delay_step, y.size(), 1) += + polynomial_reg_diff.block(0, 4, y.size(), 1); + return result; + } + Eigen::MatrixXd rot_and_d_rot_error_prediction_with_diff(Eigen::VectorXd x) + { + int x_dim = x.size(); + double theta = x[3]; + double v = x[2]; + double coef = 2.0 * std::abs(v); + coef = coef * coef * coef * coef * coef * coef * coef; + if (coef > 1.0) { + coef = 1.0; + } + double cos = std::cos(theta); + double sin = std::sin(theta); + Eigen::Matrix2d Rot; + Rot << cos, -sin, sin, cos; + + Eigen::Matrix2d dRot; + dRot << -sin, -cos, cos, -sin; + Eigen::VectorXd vars(x_dim - 3); + vars[0] = x[2]; + vars[1] = x[4]; + vars[2] = x[5]; + vars.tail(x_dim - 6) = x.tail(x_dim - 6); + + Eigen::MatrixXd pred_d_pred = error_prediction_with_diff(vars); + Eigen::VectorXd pred = pred_d_pred.col(0); + Eigen::MatrixXd d_pred = pred_d_pred.block(0, 1, 6, x_dim - 3); + Eigen::MatrixXd rot_and_d_rot_pred_with_diff = Eigen::MatrixXd::Zero(6, x_dim + 2); + Eigen::MatrixXd rot_pred_with_diff(6, x_dim - 3); + rot_pred_with_diff.block(0, 0, 2, x_dim - 3) = Rot * d_pred.block(0, 0, 2, x_dim - 3); + rot_pred_with_diff.block(2, 0, 4, x_dim - 3) = d_pred.block(2, 0, 4, x_dim - 3); + + rot_and_d_rot_pred_with_diff.block(0, 0, 2, 1) = Rot * pred.head(2); + rot_and_d_rot_pred_with_diff.block(2, 0, 4, 1) = pred.segment(2, 4); + rot_and_d_rot_pred_with_diff.block(0, 1, 2, 1) = dRot * pred.head(2); + rot_and_d_rot_pred_with_diff.col(2 + 2) = rot_pred_with_diff.col(0); + rot_and_d_rot_pred_with_diff.col(2 + 4) = rot_pred_with_diff.col(1); + rot_and_d_rot_pred_with_diff.col(2 + 5) = rot_pred_with_diff.col(2); + rot_and_d_rot_pred_with_diff.block(0, 2 + 6, 6, x_dim - 6) = + rot_pred_with_diff.block(0, 3, 6, x_dim - 6); + return coef * rot_and_d_rot_pred_with_diff; + } + Eigen::MatrixXd Rotated_error_prediction(Eigen::MatrixXd X) + { + int X_cols = X.cols(); + int x_dim = X.rows(); + Eigen::MatrixXd Pred(6, X_cols); + for (int i = 0; i < X_cols; i++) { + Eigen::VectorXd x = X.col(i); + double theta = x[3]; + double v = x[2]; + double coef = 2.0 * std::abs(v); + coef = coef * coef * coef * coef * coef * coef * coef; + if (coef > 1.0) { + coef = 1.0; + } + double cos = std::cos(theta); + double sin = std::sin(theta); + Eigen::Matrix2d Rot; + Rot << cos, -sin, sin, cos; + Eigen::VectorXd vars(x_dim - 3); + + vars[0] = x[2]; + + vars[1] = x[4]; + vars[2] = x[5]; + vars.tail(x_dim - 6) = x.tail(x_dim - 6); + Eigen::VectorXd pred = error_prediction(vars); + Pred.block(0, i, 2, 1) = coef * Rot * pred.head(2); + Pred.block(2, i, 4, 1) = coef * pred.tail(4); + } + return Pred; + } +}; + +PYBIND11_MODULE(proxima_calc, m) +{ + py::class_(m, "transform_model_to_eigen") + .def(py::init()) + .def("set_params", &transform_model_to_eigen::set_params) + .def( + "rot_and_d_rot_error_prediction", &transform_model_to_eigen::rot_and_d_rot_error_prediction) + .def("error_prediction_with_diff", &transform_model_to_eigen::error_prediction_with_diff) + .def( + "rot_and_d_rot_error_prediction_with_diff", + &transform_model_to_eigen::rot_and_d_rot_error_prediction_with_diff) + .def("Rotated_error_prediction", &transform_model_to_eigen::Rotated_error_prediction); +} diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py new file mode 100755 index 0000000000000..409b6bf594c9e --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py @@ -0,0 +1,859 @@ +#!/usr/bin/env python3 + +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore interp + +import time + +from autoware_adapi_v1_msgs.msg import OperationModeState +from autoware_auto_control_msgs.msg import AckermannControlCommand +from autoware_auto_planning_msgs.msg import Trajectory +from autoware_auto_planning_msgs.msg import TrajectoryPoint +from autoware_auto_vehicle_msgs.msg import SteeringReport +from builtin_interfaces.msg import Duration +from geometry_msgs.msg import AccelWithCovarianceStamped +from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Odometry +import numpy as np +import rclpy +from rclpy.node import Node +import scipy +import scipy.interpolate +from scipy.spatial.transform import Rotation as R +from scipy.spatial.transform import Slerp +from smart_mpc_trajectory_follower.scripts import drive_controller +from smart_mpc_trajectory_follower.scripts import drive_functions +from std_msgs.msg import String +from tier4_debug_msgs.msg import BoolStamped +from tier4_debug_msgs.msg import Float32MultiArrayStamped +from tier4_debug_msgs.msg import Float32Stamped + + +def getYaw(orientation_xyzw): + return R.from_quat(orientation_xyzw.reshape(-1, 4)).as_euler("xyz")[:, 2] + + +class PyMPCTrajectoryFollower(Node): + def __init__(self): + # MPC logic + self.controller = drive_controller.drive_controller( + model_file_name=(drive_functions.load_dir + "/model_for_test_drive.pth"), + ) + + # ROS 2 + super().__init__("pympc_trajectory_follower") + self.sub_trajectory_ = self.create_subscription( + Trajectory, + "/planning/scenario_planning/trajectory", + self.onTrajectory, + 1, + ) + self.sub_trajectory_ # prevent unused variable warning + + self.sub_odometry_ = self.create_subscription( + Odometry, + "/localization/kinematic_state", + self.onOdometry, + 1, + ) + self.sub_odometry_ + + self.sub_accel_ = self.create_subscription( + AccelWithCovarianceStamped, + "/localization/acceleration", + self.onAccel, + 1, + ) + self.sub_accel_ + + self.sub_steering_ = self.create_subscription( + SteeringReport, + "/vehicle/status/steering_status", + self.onSteering, + 1, + ) + self.sub_steering_ + + self.sub_operation_mode_ = self.create_subscription( + OperationModeState, + "/system/operation_mode/state", + self.onOperationMode, + 1, + ) + self.sub_operation_mode_ + + self.sub_stop_mode_reset_request_ = self.create_subscription( + String, + "/pympc_stop_mode_reset_request", + self.onStopModeResetRequest, + 1, + ) + self.sub_stop_mode_reset_request_ + + self.sub_goal_pose_ = self.create_subscription( + PoseStamped, + "/planning/mission_planning/echo_back_goal_pose", + self.onGoalPose, + 1, + ) + self.sub_goal_pose_ + + self.sub_step_response_trigger_ = self.create_subscription( + String, + "/pympc_step_response_trigger", + self.onStepResponseTrigger, + 1, + ) + self.sub_step_response_trigger_ + + self.sub_reload_mpc_param_trigger_ = self.create_subscription( + String, + "/pympc_reload_mpc_param_trigger", + self.onReloadMpcParamTrigger, + 1, + ) + self.sub_reload_mpc_param_trigger_ + + self.sub_control_command_control_cmd_ = self.create_subscription( + AckermannControlCommand, + "/control/command/control_cmd", + self.onControlCommandControlCmd, + 3, + ) + self.sub_control_command_control_cmd_ + + self.control_cmd_pub_ = self.create_publisher( + AckermannControlCommand, + "/control/trajectory_follower/control_cmd", + 1, + ) + + self.predicted_trajectory_pub_ = self.create_publisher( + Trajectory, + "/control/trajectory_follower/lateral/predicted_trajectory", + 1, + ) + + self.timer_period_callback = 0.03 # 30ms + + self.timer = self.create_timer(self.timer_period_callback, self.timer_callback) + + self.debug_mpc_x_current_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_x_current", + 1, + ) + self.debug_mpc_x_des_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_x_des", + 1, + ) + self.debug_mpc_y_des_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_y_des", + 1, + ) + self.debug_mpc_v_des_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_v_des", + 1, + ) + self.debug_mpc_yaw_des_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_yaw_des", + 1, + ) + self.debug_mpc_acc_des_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_acc_des", + 1, + ) + self.debug_mpc_steer_des_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_steer_des", + 1, + ) + + self.debug_mpc_X_des_converted_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_X_des_converted", + 1, + ) + + self.debug_mpc_nominal_traj_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_nominal_traj", + 1, + ) + + self.debug_mpc_nominal_inputs_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_nominal_inputs", + 1, + ) + + self.debug_mpc_X_input_list_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_X_input_list", + 1, + ) + + self.debug_mpc_Y_output_list_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_Y_output_list", + 1, + ) + + self.debug_mpc_error_prediction_pub_ = self.create_publisher( + Float32MultiArrayStamped, + "/debug_mpc_error_prediction", + 1, + ) + + self.debug_mpc_emergency_stop_mode_pub_ = self.create_publisher( + BoolStamped, + "/debug_mpc_emergency_stop_mode", + 1, + ) + + self.debug_mpc_goal_stop_mode_pub_ = self.create_publisher( + BoolStamped, + "/debug_mpc_goal_stop_mode", + 1, + ) + + self.debug_mpc_max_trajectory_err_pub_ = self.create_publisher( + Float32Stamped, + "/debug_mpc_max_trajectory_err", + 1, + ) + + self.debug_mpc_calc_u_opt_time_pub_ = self.create_publisher( + Float32Stamped, + "/debug_mpc_calc_u_opt_time", + 1, + ) + + self.debug_mpc_total_ctrl_time_pub_ = self.create_publisher( + Float32Stamped, + "/debug_mpc_total_ctrl_time", + 1, + ) + + self._present_trajectory = None + self._present_kinematic_state = None + self._present_acceleration = None + self._present_steering_status = None + self._present_operation_mode = None + self._goal_pose = None + self.control_cmd_time_stamp_list = [] + self.control_cmd_steer_list = [] + self.control_cmd_acc_list = [] + + self.emergency_stop_mode_flag = False + self.stop_mode_reset_request = False + self.step_response_flag = False + self.step_response_trigger = False + self.step_response_time_step = 0 + self.last_acc_cmd = 0.0 + self.last_steer_cmd = 0.0 + self.past_control_trajectory_mode = 1 + + def onTrajectory(self, msg): + self._present_trajectory = msg + + def onOdometry(self, msg): + self._present_kinematic_state = msg + + def onAccel(self, msg): + self._present_acceleration = msg + + def onSteering(self, msg): + self._present_steering_status = msg + + def onOperationMode(self, msg): + self._present_operation_mode = msg + + def onStopModeResetRequest(self, msg): + self.stop_mode_reset_request = True + self.step_response_flag = False + self.get_logger().info("receive stop mode reset request") + + def onGoalPose(self, msg): + self._goal_pose = msg + + def onStepResponseTrigger(self, msg): + self.step_response_trigger = True + self.get_logger().info("receive step response trigger") + + def onReloadMpcParamTrigger(self, msg): + self.get_logger().info("receive reload mpc param trigger") + + # Re-starting the controller + # Reloading parameters etc. internally. + self.controller = drive_controller.drive_controller( + model_file_name=(drive_functions.load_dir + "/model_for_test_drive.pth"), + ) + + def onControlCommandControlCmd(self, msg): + present_cmd_msg = msg + if self.past_control_trajectory_mode == 0: + self.control_cmd_time_stamp_list.append( + present_cmd_msg.stamp.sec + 1e-9 * present_cmd_msg.stamp.nanosec + ) + self.control_cmd_steer_list.append(present_cmd_msg.lateral.steering_tire_angle) + self.control_cmd_acc_list.append(present_cmd_msg.longitudinal.acceleration) + if self.control_cmd_time_stamp_list[-1] - self.control_cmd_time_stamp_list[0] > 3.0: + self.control_cmd_time_stamp_list.pop(0) + self.control_cmd_steer_list.pop(0) + self.control_cmd_acc_list.pop(0) + + def timer_callback(self): + if (self._present_trajectory is not None) and (self._present_kinematic_state is not None): + self.control() + + def control(self): + start_ctrl_time = time.time() + + # [1] Processing of information received from topics. + trajectory_position = [] + trajectory_orientation = [] + trajectory_longitudinal_velocity = [] + trajectory_lateral_velocity = [] + trajectory_acceleration = [] + trajectory_heading_rate = [] + points = self._present_trajectory.points + for i in range(len(points)): + trajectory_position.append( + [points[i].pose.position.x, points[i].pose.position.y, points[i].pose.position.z] + ) + trajectory_orientation.append( + [ + points[i].pose.orientation.x, + points[i].pose.orientation.y, + points[i].pose.orientation.z, + points[i].pose.orientation.w, + ] + ) + trajectory_longitudinal_velocity.append(points[i].longitudinal_velocity_mps) + trajectory_lateral_velocity.append(points[i].lateral_velocity_mps) + trajectory_acceleration.append(points[i].acceleration_mps2) + trajectory_heading_rate.append(points[i].heading_rate_rps) + trajectory_position = np.array(trajectory_position) + trajectory_orientation = np.array(trajectory_orientation) + trajectory_longitudinal_velocity = np.array(trajectory_longitudinal_velocity) + trajectory_lateral_velocity = np.array(trajectory_lateral_velocity) + trajectory_acceleration = np.array(trajectory_acceleration) + trajectory_heading_rate = np.array(trajectory_heading_rate) + + present_position = np.array( + [ + self._present_kinematic_state.pose.pose.position.x, + self._present_kinematic_state.pose.pose.position.y, + self._present_kinematic_state.pose.pose.position.z, + ] + ) + present_orientation = np.array( + [ + self._present_kinematic_state.pose.pose.orientation.x, + self._present_kinematic_state.pose.pose.orientation.y, + self._present_kinematic_state.pose.pose.orientation.z, + self._present_kinematic_state.pose.pose.orientation.w, + ] + ) + present_linear_velocity = np.array( + [ + self._present_kinematic_state.twist.twist.linear.x, + self._present_kinematic_state.twist.twist.linear.y, + self._present_kinematic_state.twist.twist.linear.z, + ] + ) + present_linear_acceleration = np.array( + [ + self._present_acceleration.accel.accel.linear.x, + self._present_acceleration.accel.accel.linear.y, + self._present_acceleration.accel.accel.linear.z, + ] + ) + + present_steering_tire_angle = np.array([self._present_steering_status.steering_tire_angle])[ + 0 + ] + + nearestIndex = ((trajectory_position - present_position) ** 2).sum(axis=1).argmin() + + is_applying_control = False + if self._present_operation_mode is not None: + if ( + self._present_operation_mode.mode == 2 + and self._present_operation_mode.is_autoware_control_enabled + ): + is_applying_control = True + + # [2] deviation check + position_deviation = np.sqrt( + ((trajectory_position[nearestIndex] - present_position) ** 2).sum() + ) + orientation_deviation = getYaw(present_orientation) - getYaw( + trajectory_orientation[nearestIndex] + ) + while True: + if orientation_deviation > np.pi: + orientation_deviation -= 2.0 * np.pi + if orientation_deviation < (-np.pi): + orientation_deviation += 2.0 * np.pi + if np.abs(orientation_deviation) < np.pi: + break + position_deviation_threshold = 2.0 + orientation_deviation_threshold = 60 * np.pi / 180.0 + + # The moment the threshold is exceeded, it enters emergency stop mode. + if is_applying_control: + if ( + position_deviation > position_deviation_threshold + or orientation_deviation > orientation_deviation_threshold + ): + self.emergency_stop_mode_flag = True + + # Normal return from emergency stop mode when within the threshold value and a request to cancel the stop mode has been received. + if ( + not ( + position_deviation > position_deviation_threshold + or orientation_deviation > orientation_deviation_threshold + ) + and self.stop_mode_reset_request + ): + self.emergency_stop_mode_flag = False + + # Processes to ensure that requests do not continue to remain after the stop mode is cancelled. + if not self.emergency_stop_mode_flag: + self.stop_mode_reset_request = False + + # [3] Control logic calculation + # [3-1] pure pursuit + # [3-1-1] compute pure pursuit acc cmd + longitudinal_vel_err = ( + present_linear_velocity - trajectory_longitudinal_velocity[nearestIndex] + ) + acc_kp = 0.5 + acc_lim = 2.0 + pure_pursuit_acc_cmd = np.clip(-acc_kp * longitudinal_vel_err, -acc_lim, acc_lim)[0] + + # [3-1-2] compute pure pursuit steer cmd + nearest_trajectory_point_yaw = getYaw(trajectory_orientation[nearestIndex]) + cos_yaw = np.cos(nearest_trajectory_point_yaw) + sin_yaw = np.sin(nearest_trajectory_point_yaw) + diff_position = present_position - trajectory_position[nearestIndex] + lat_err = -sin_yaw * diff_position[0] + cos_yaw * diff_position[1] + yaw_err = getYaw(present_orientation) - nearest_trajectory_point_yaw + while True: + if yaw_err > np.pi: + yaw_err -= 2.0 * np.pi + if yaw_err < (-np.pi): + yaw_err += 2.0 * np.pi + if np.abs(yaw_err) < np.pi: + break + wheel_base = drive_functions.L # 4.0 + lookahead_time = 3.0 + min_lookahead = 3.0 + lookahead = min_lookahead + lookahead_time * np.abs(present_linear_velocity[0]) + steer_kp = 2.0 * wheel_base / (lookahead * lookahead) + steer_kd = 2.0 * wheel_base / lookahead + steer_lim = 0.6 + pure_pursuit_steer_cmd = np.clip( + -steer_kp * lat_err - steer_kd * yaw_err, -steer_lim, steer_lim + )[0] + + # [3-2] MPC control logic calculation + # [3-2-1] State variables in the MPC + present_mpc_x = np.array( + [ + present_position[0], + present_position[1], + present_linear_velocity[0], + getYaw(present_orientation)[0], + present_linear_acceleration[0], + present_steering_tire_angle, + ] + ) + + # [3-2-2] resampling trajectory by time (except steer angle). + X_des = np.zeros((drive_functions.N + 1, 8)) + dist = np.sqrt(((trajectory_position[1:] - trajectory_position[:-1]) ** 2).sum(axis=1)) + timestamp_from_start = [0.0] + tmp_t = 0.0 + for i in range(len(dist)): + tmp_t += dist[i] / max(np.abs(trajectory_longitudinal_velocity[i]), 0.1) + timestamp_from_start.append(1 * tmp_t) + timestamp_from_start = np.array(timestamp_from_start) + + mpc_trajectory_time_step = 0.1 + timestamp_mpc = ( + np.arange(drive_functions.N + 1) * mpc_trajectory_time_step + + timestamp_from_start[nearestIndex] + ) + for i in range(drive_functions.N + 1): + if timestamp_mpc[drive_functions.N - i] > timestamp_from_start[-1]: + timestamp_mpc[drive_functions.N - i] = timestamp_from_start[-1] + else: + break + pos_x_interpolate = scipy.interpolate.interp1d( + timestamp_from_start, trajectory_position[:, 0] + ) + pos_y_interpolate = scipy.interpolate.interp1d( + timestamp_from_start, trajectory_position[:, 1] + ) + longitudinal_velocity_interpolate = scipy.interpolate.interp1d( + timestamp_from_start, trajectory_longitudinal_velocity + ) + key_rots = R.from_quat(trajectory_orientation.reshape(-1, 4)) + orientation_interpolate = Slerp(timestamp_from_start, key_rots) + acceleration_interpolate = scipy.interpolate.interp1d( + timestamp_from_start, trajectory_acceleration + ) + + X_des[:, 0] = pos_x_interpolate(timestamp_mpc) + X_des[:, 1] = pos_y_interpolate(timestamp_mpc) + X_des[:, 2] = longitudinal_velocity_interpolate(timestamp_mpc) + X_des[:, 3] = orientation_interpolate(timestamp_mpc).as_euler("xyz")[:, 2] + X_des[:, 4] = acceleration_interpolate(timestamp_mpc) + X_des[:, 6] = 1 * X_des[:, 4] + + # [3-2-3] resampling trajectory by time (steer angle) + previous_des_steer = 0.0 + steer_trajectory2 = np.zeros(len(timestamp_mpc)) + downsampling = 5 + for ii in range(2 + (int(len(timestamp_mpc) // downsampling))): + i = ii * downsampling + if i >= len(timestamp_mpc): + i = len(timestamp_mpc) - 1 + if (i % downsampling) == 0: + continue + + tmp_des_pos = 1 * X_des[i, :2] + distance_squared = ((trajectory_position[:, :2] - tmp_des_pos[:2]) ** 2).sum(axis=1) + tmp_nearest_index = distance_squared.argmin() + curvature_calculation_distance = 3.0 + nearestIndex_in_front = ( + np.abs( + distance_squared[tmp_nearest_index:] + - curvature_calculation_distance * curvature_calculation_distance + ) + ).argmin() + tmp_nearest_index + distance_in_front = np.sqrt(distance_squared[nearestIndex_in_front]) + if distance_in_front < curvature_calculation_distance: + curvature_calculation_distance = distance_in_front + if tmp_nearest_index > 0: + nearestIndex_behind = ( + np.abs( + distance_squared[:tmp_nearest_index] + - curvature_calculation_distance * curvature_calculation_distance + ) + ).argmin() + curvature_calculation_distance_threshold = 0.5 + if distance_in_front < curvature_calculation_distance_threshold: + # If there is no point in front, fill in with the value before it. + tmp_des_steer = 1 * previous_des_steer + else: + # Normal line passing through a point 3 m behind.:b1*x + b2*y + b3 = 0 + b1 = tmp_des_pos[0] - trajectory_position[nearestIndex_behind][0] + b2 = tmp_des_pos[1] - trajectory_position[nearestIndex_behind][1] + b3 = ( + -b1 * trajectory_position[nearestIndex_behind][0] + - b2 * trajectory_position[nearestIndex_behind][1] + ) + # Normal line through a point 3 m in front:f1*x + f2*y + f3 = 0 + f1 = tmp_des_pos[0] - trajectory_position[nearestIndex_in_front][0] + f2 = tmp_des_pos[1] - trajectory_position[nearestIndex_in_front][1] + f3 = ( + -f1 * trajectory_position[nearestIndex_in_front][0] + - f2 * trajectory_position[nearestIndex_in_front][1] + ) + det = b1 * f2 - b2 * f1 + if np.abs(det) < 1e-6: + # The two normals have the same slope, so steer is 0 + tmp_des_steer = 0.0 + else: + # solve Ax+b=0 + invA = np.array([[f2, -b2], [-f1, b1]]) / det + sol = -invA @ np.array([b3, f3]) # center of the circle + curvature = np.sqrt( + ((sol - trajectory_position[nearestIndex_behind][:2]) ** 2).sum() + ) + tmp_des_steer = np.arctan(drive_functions.L / curvature) + + tmp_vec_behind = sol - trajectory_position[nearestIndex_behind][:2] + # Line segment connecting backward point - centre of circle + cross_product = b1 * tmp_vec_behind[1] - b2 * tmp_vec_behind[0] + if cross_product < 0.0: + tmp_des_steer = -tmp_des_steer + + steer_trajectory2[i] = 1.0 * tmp_des_steer + previous_des_steer = 1.0 * tmp_des_steer + else: + steer_trajectory2[i] = 0.0 + previous_des_steer = 0.0 + + for i in range(len(timestamp_mpc) - 1): + reminder = i % downsampling + i0 = i - reminder + i1 = i0 + downsampling + if reminder == 0: + continue + if i1 >= len(timestamp_mpc): + i1 = len(timestamp_mpc) - 1 + w = (1.0 * reminder) / (i1 - i0) + steer_trajectory2[i] = (1 - w) * steer_trajectory2[i0] + w * steer_trajectory2[i1] + + X_des[:, 5] = steer_trajectory2 + X_des[:, 7] = 1 * X_des[:, 5] + + # [3-2-4] mpc computation + U_des = np.zeros((drive_functions.N, 2)) + start_calc_u_opt = time.time() + u_opt = self.controller.update_input_queue_and_get_optimal_control( + self.control_cmd_time_stamp_list, + self.control_cmd_acc_list, + self.control_cmd_steer_list, + present_mpc_x, + X_des, + U_des, + ) + end_calc_u_opt = time.time() + mpc_acc_cmd = u_opt[0] + mpc_steer_cmd = u_opt[1] + + # [3-3] Enter goal stop mode (override command value) to maintain stop at goal + self.goal_stop_mode_flag = False + if self._goal_pose is not None: + goal_position = np.array( + [ + self._goal_pose.pose.position.x, + self._goal_pose.pose.position.y, + self._goal_pose.pose.position.z, + ] + ) + + distance_from_goal = np.sqrt(((goal_position[:2] - present_position[:2]) ** 2).sum()) + goal_distance_threshold = 0.8 + if distance_from_goal < goal_distance_threshold: + self.goal_stop_mode_flag = True + + # [3-4] Override when doing step response + if self.step_response_trigger: + self.step_response_time_step = 0 + self.step_response_flag = True + self.step_response_trigger = False + + if self.step_response_flag: + step_response_elapsed_time = self.step_response_time_step * self.timer_period_callback + mpc_acc_cmd = 1.0 * self.last_acc_cmd + if step_response_elapsed_time < 3.0: + mpc_steer_cmd = 0.0 + else: + mpc_steer_cmd = -0.005 + self.get_logger().info( + "step_response_elapsed_time: " + + str(step_response_elapsed_time) + + ", mpc_steer_cmd: " + + str(mpc_steer_cmd) + ) + self.step_response_time_step += 1 + + # [3-5] Determine the control logic to be finally applied and publish it + acc_cmd = 0.0 + steer_cmd = 0.0 + if (not self.emergency_stop_mode_flag) and (not self.goal_stop_mode_flag): + # in normal mode + acc_cmd = mpc_acc_cmd + steer_cmd = mpc_steer_cmd + + overwrite_cmd_by_pure_pursuit_flag = False + if overwrite_cmd_by_pure_pursuit_flag: + steer_cmd = pure_pursuit_steer_cmd + acc_cmd = pure_pursuit_acc_cmd + else: + # in stop mode + acc_cmd_decrease_limit = 5.0 * self.timer_period_callback # lon_jerk_lim + steer_cmd_decrease_limit = 0.5 * self.timer_period_callback # steer_rate_lim + acc_cmd = max( + self.last_acc_cmd - acc_cmd_decrease_limit, -drive_functions.acc_lim_points[0] + ) # lon_acc_lim + if self.last_steer_cmd > (steer_cmd_decrease_limit + 1e-6): + steer_cmd = self.last_steer_cmd - steer_cmd_decrease_limit + elif self.last_steer_cmd < -(steer_cmd_decrease_limit + 1e-6): + steer_cmd = self.last_steer_cmd + steer_cmd_decrease_limit + else: + steer_cmd = 0.0 + + cmd_msg = AckermannControlCommand() + cmd_msg.stamp = cmd_msg.lateral.stamp = cmd_msg.longitudinal.stamp = ( + self.get_clock().now().to_msg() + ) + cmd_msg.longitudinal.speed = trajectory_longitudinal_velocity[nearestIndex] + cmd_msg.longitudinal.acceleration = acc_cmd + cmd_msg.lateral.steering_tire_angle = steer_cmd + + self.control_cmd_pub_.publish(cmd_msg) + self.last_acc_cmd = 1 * acc_cmd + self.last_steer_cmd = 1 * steer_cmd + + if self.past_control_trajectory_mode == 1: + self.control_cmd_time_stamp_list.append( + cmd_msg.stamp.sec + 1e-9 * cmd_msg.stamp.nanosec + ) + self.control_cmd_steer_list.append(steer_cmd) + self.control_cmd_acc_list.append(acc_cmd) + if self.control_cmd_time_stamp_list[-1] - self.control_cmd_time_stamp_list[0] > 3.0: + self.control_cmd_time_stamp_list.pop(0) + self.control_cmd_steer_list.pop(0) + self.control_cmd_acc_list.pop(0) + + # [4] Update MPC internal variables + if not is_applying_control: + self.controller.send_initialize_input_queue() + self.controller.stop_model_update() + self.control_cmd_time_stamp_list.clear() + self.control_cmd_steer_list.clear() + self.control_cmd_acc_list.clear() + + # [5] MPC prediction trajectory publish + traj_msg = Trajectory() + traj_msg.header.stamp = cmd_msg.stamp + traj_msg.header.frame_id = "map" + downsampling = 3 + for ii in range(int(self.controller.nominal_traj.shape[0] // downsampling)): + i = ii * downsampling + traj_msg.points += [TrajectoryPoint()] + int_sec = int(i * mpc_trajectory_time_step) + traj_msg.points[ii].time_from_start = Duration() + traj_msg.points[ii].time_from_start.sec = int_sec + traj_msg.points[ii].time_from_start.nanosec = int( + (i * mpc_trajectory_time_step - int_sec) * 1e9 + ) + traj_msg.points[ii].pose.position.x = self.controller.nominal_traj[i, 0] + traj_msg.points[ii].pose.position.y = self.controller.nominal_traj[i, 1] + traj_msg.points[ii].pose.position.z = present_position[2] + tmp_orientation_xyzw = R.from_euler("z", self.controller.nominal_traj[i, 3]).as_quat() + traj_msg.points[ii].pose.orientation.x = tmp_orientation_xyzw[0] + traj_msg.points[ii].pose.orientation.y = tmp_orientation_xyzw[1] + traj_msg.points[ii].pose.orientation.z = tmp_orientation_xyzw[2] + traj_msg.points[ii].pose.orientation.w = tmp_orientation_xyzw[3] + traj_msg.points[ii].longitudinal_velocity_mps = self.controller.nominal_traj[i, 2] + traj_msg.points[ii].acceleration_mps2 = self.controller.nominal_traj[i, 4] + + self.predicted_trajectory_pub_.publish(traj_msg) + + # [-1] Publish internal information for debugging + enable_debug_pub = True + if enable_debug_pub: + self.debug_mpc_emergency_stop_mode_pub_.publish( + BoolStamped(stamp=cmd_msg.stamp, data=self.emergency_stop_mode_flag) + ) + self.debug_mpc_goal_stop_mode_pub_.publish( + BoolStamped(stamp=cmd_msg.stamp, data=self.goal_stop_mode_flag) + ) + self.debug_mpc_x_des_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=X_des[:, 0]) + ) + self.debug_mpc_y_des_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=X_des[:, 1]) + ) + self.debug_mpc_v_des_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=X_des[:, 2]) + ) + self.debug_mpc_yaw_des_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=X_des[:, 3]) + ) + self.debug_mpc_acc_des_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=X_des[:, 4]) + ) + self.debug_mpc_steer_des_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=X_des[:, 5]) + ) + self.debug_mpc_x_current_pub_.publish( + Float32MultiArrayStamped(stamp=cmd_msg.stamp, data=present_mpc_x.tolist()) + ) + self.debug_mpc_X_des_converted_pub_.publish( + Float32MultiArrayStamped( + stamp=cmd_msg.stamp, data=self.controller.X_des.flatten().tolist() + ) + ) + self.debug_mpc_nominal_traj_pub_.publish( + Float32MultiArrayStamped( + stamp=cmd_msg.stamp, data=self.controller.nominal_traj.flatten().tolist() + ) + ) + self.debug_mpc_nominal_inputs_pub_.publish( + Float32MultiArrayStamped( + stamp=cmd_msg.stamp, data=self.controller.nominal_inputs.flatten().tolist() + ) + ) + self.debug_mpc_X_input_list_pub_.publish( + Float32MultiArrayStamped( + stamp=cmd_msg.stamp, + data=np.array(self.controller.X_input_list[-1:]).flatten().tolist(), + ) + ) + self.debug_mpc_Y_output_list_pub_.publish( + Float32MultiArrayStamped( + stamp=cmd_msg.stamp, + data=np.array(self.controller.Y_output_list[-1:]).flatten().tolist(), + ) + ) + self.debug_mpc_max_trajectory_err_pub_.publish( + Float32Stamped( + stamp=cmd_msg.stamp, + data=self.controller.err, + ) + ) + if self.controller.use_trained_model: + self.debug_mpc_error_prediction_pub_.publish( + Float32MultiArrayStamped( + stamp=cmd_msg.stamp, data=self.controller.previous_error[:6] + ) + ) + + end_ctrl_time = time.time() + + self.debug_mpc_calc_u_opt_time_pub_.publish( + Float32Stamped( + stamp=cmd_msg.stamp, + data=(end_calc_u_opt - start_calc_u_opt), + ) + ) + + self.debug_mpc_total_ctrl_time_pub_.publish( + Float32Stamped( + stamp=cmd_msg.stamp, + data=(end_ctrl_time - start_ctrl_time), + ) + ) + + +def main(args=None): + rclpy.init(args=args) + + pympc_trajectory_follower = PyMPCTrajectoryFollower() + + rclpy.spin(pympc_trajectory_follower) + + pympc_trajectory_follower.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/.gitignore b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/.gitignore new file mode 100644 index 0000000000000..749ccdafd4f66 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/.gitignore @@ -0,0 +1,4 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/__init__.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/__init__.py new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py new file mode 100644 index 0000000000000..3f6ef7a9f78d1 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py @@ -0,0 +1,293 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore ndimage usecols ndim interp savez + + +"""Class for preprocessing CSV data to obtain training data for training.""" + +import csv +import glob +import json +import os +from pathlib import Path + +import numpy as np +import scipy.interpolate +from scipy.ndimage import gaussian_filter +from scipy.spatial.transform import Rotation +from smart_mpc_trajectory_follower.scripts import drive_functions + + +def data_smoothing(data: np.ndarray, sigma: float) -> np.ndarray: + """Apply a Gaussian filter to the data.""" + data_ = gaussian_filter(data, sigma) + return data_ + + +def yaw_transform(raw_yaw: np.ndarray) -> np.ndarray: + """Adjust and transform within a period of 2π so that the yaw angle is continuous.""" + transformed_yaw = np.zeros(raw_yaw.shape) + transformed_yaw[0] = raw_yaw[0] + for i in range(raw_yaw.shape[0] - 1): + rotate_num = (raw_yaw[i + 1] - transformed_yaw[i]) // (2 * np.pi) + if raw_yaw[i + 1] - transformed_yaw[i] - 2 * rotate_num * np.pi < np.pi: + transformed_yaw[i + 1] = raw_yaw[i + 1] - 2 * rotate_num * np.pi + else: + transformed_yaw[i + 1] = raw_yaw[i + 1] - 2 * (rotate_num + 1) * np.pi + return transformed_yaw + + +class add_data_from_csv: + """Class for loading csv files containing driving data, converting them into teacher data for the NN training, and storing them in lists.""" + + X_input_list: list[np.ndarray] + """Input side of NN teacher data""" + + Y_output_list: list[np.ndarray] + """Output side of NN teacher data""" + + def __init__(self): + self.X_input_list = [] + self.Y_output_list = [] + + def clear_data(self): + """Clear the teacher data for the training.""" + self.X_input_list.clear() + self.Y_output_list.clear() + + def transform_rosbag_to_csv(self, dir_name: str, delete_csv_first: bool = True) -> None: + """Convert rosbag file to CSV format.""" + package_path_json = str(Path(__file__).parent.parent) + "/package_path.json" + with open(package_path_json, "r") as file: + package_path = json.load(file) + dir_exe = os.getcwd() + os.system( + "cp " + + package_path["path"] + + "/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash " + + dir_name + ) + os.chdir(dir_name) + if len(glob.glob("*.csv")) > 0 and delete_csv_first: + os.system("rm *.csv") + os.system("bash rosbag2.bash") + os.chdir(dir_exe) + + def add_data_from_csv(self, dir_name: str) -> None: + """Adding teacher data for training from a CSV file.""" + acc_ctrl_queue_size = drive_functions.acc_ctrl_queue_size + steer_ctrl_queue_size = drive_functions.steer_ctrl_queue_size + ctrl_time_step = drive_functions.ctrl_time_step + mpc_time_step = drive_functions.mpc_time_step + mpc_freq = drive_functions.mpc_freq + acc_delay_step_ctrl = drive_functions.acc_delay_step + steer_delay_step_ctrl = drive_functions.steer_delay_step + acc_time_constant_ctrl = drive_functions.acc_time_constant + steer_time_constant_ctrl = drive_functions.steer_time_constant + + kinematic = np.loadtxt( + dir_name + "/kinematic_state.csv", delimiter=",", usecols=[0, 1, 4, 5, 7, 8, 9, 10, 47] + ) + pose_position_x = kinematic[:, 2] + pose_position_y = kinematic[:, 3] + vel = kinematic[:, 8] + raw_yaw = Rotation.from_quat(kinematic[:, 4:8]).as_euler("xyz")[:, 2] + yaw = yaw_transform(raw_yaw) + + loc_acc = np.loadtxt(dir_name + "/acceleration.csv", delimiter=",", usecols=[0, 1, 3]) + acc = loc_acc[:, 2] + + acc_sm = data_smoothing(acc, drive_functions.acc_sigma_for_learning) + + vehicle_steer = np.loadtxt( + dir_name + "/steering_status.csv", delimiter=",", usecols=[0, 1, 2] + ) + steer = vehicle_steer[:, 2] + steer_sm = steer.copy() + steer_sm = data_smoothing(steer, drive_functions.steer_sigma_for_learning) + + control_cmd = np.loadtxt( + dir_name + "/control_cmd_orig.csv", delimiter=",", usecols=[0, 1, 4, 9] + ) + acc_des = control_cmd[:, 3] + acc_des_sm = data_smoothing(acc_des, drive_functions.acc_des_sigma_for_learning) + + steer_des = control_cmd[:, 2] + steer_des_sm = steer_des.copy() + steer_des_sm = data_smoothing(steer_des, drive_functions.steer_des_sigma_for_learning) + + operation_mode = np.loadtxt( + dir_name + "/system_operation_mode_state.csv", delimiter=",", usecols=[0, 1, 2] + ) + if operation_mode.ndim == 1: + operation_mode = operation_mode.reshape(1, -1) + with open(dir_name + "/system_operation_mode_state.csv") as f: + reader = csv.reader(f, delimiter=",") + autoware_control_enabled_str = np.array([row[3] for row in reader]) + + proxima_control_enabled = np.zeros(operation_mode.shape[0]) + for i in range(operation_mode.shape[0]): + if operation_mode[i, 2] > 1.5 and autoware_control_enabled_str[i] == "True": + proxima_control_enabled[i] = 1.0 + for i in range(operation_mode.shape[0] - 1): + if proxima_control_enabled[i] < 0.5 and proxima_control_enabled[i + 1] > 0.5: + operation_start_time = operation_mode[i + 1, 0] + 1e-9 * operation_mode[i + 1, 1] + elif proxima_control_enabled[i] > 0.5 and proxima_control_enabled[i + 1] < 0.5: + operation_end_time = operation_mode[i + 1, 0] + 1e-9 * operation_mode[i + 1, 1] + break + operation_end_time = kinematic[-1, 0] + 1e-9 * kinematic[-1, 1] + if operation_mode.shape[0] == 1: + operation_end_time = kinematic[-1, 0] + 1e-9 * kinematic[-1, 1] + if proxima_control_enabled[0] > 0.5: + operation_start_time = operation_mode[0, 0] + 1e-9 * operation_mode[0, 1] + print("operation_start_time", operation_start_time) + print("operation_end_time", operation_end_time) + min_time_stamp = max( + [ + operation_start_time, + kinematic[0, 0] + 1e-9 * kinematic[0, 1], + loc_acc[0, 0] + 1e-9 * loc_acc[0, 1], + vehicle_steer[0, 0] + 1e-9 * vehicle_steer[0, 1], + control_cmd[0, 0] + 1e-9 * control_cmd[0, 1], + ] + ) + max_time_stamp = min( + [ + operation_end_time, + kinematic[-1, 0] + 1e-9 * kinematic[-1, 1], + loc_acc[-1, 0] + 1e-9 * loc_acc[-1, 1], + vehicle_steer[-1, 0] + 1e-9 * vehicle_steer[-1, 1], + control_cmd[-1, 0] + 1e-9 * control_cmd[-1, 1], + ] + ) + + trajectory_interpolator_list = [] + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(kinematic[:, 0] + 1e-9 * kinematic[:, 1], pose_position_x) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(kinematic[:, 0] + 1e-9 * kinematic[:, 1], pose_position_y) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(kinematic[:, 0] + 1e-9 * kinematic[:, 1], vel) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(kinematic[:, 0] + 1e-9 * kinematic[:, 1], yaw) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(loc_acc[:, 0] + 1e-9 * loc_acc[:, 1], acc_sm) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(vehicle_steer[:, 0] + 1e-9 * vehicle_steer[:, 1], steer_sm) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(control_cmd[:, 0] + 1e-9 * control_cmd[:, 1], acc_des_sm) + ) + trajectory_interpolator_list.append( + scipy.interpolate.interp1d(control_cmd[:, 0] + 1e-9 * control_cmd[:, 1], steer_des_sm) + ) + + def get_interpolated_state(s): + x_current = np.zeros(6) + for i in range(6): + x_current[i] = trajectory_interpolator_list[i](s) + return x_current + + def get_interpolated_input(s): + u_input = np.zeros(2) + for i in range(2): + u_input[i] = trajectory_interpolator_list[6 + i](s) + return u_input + + s = min_time_stamp + X = [] + U = [] + + Timestamp = [] + while True: + if s > max_time_stamp: + break + X.append(get_interpolated_state(s)) + + U.append(get_interpolated_input(s)) + + Timestamp.append(s) + s += ctrl_time_step + + X_array = np.array(X) + U_array = np.array(U) + X_input_list = [] + Y_output_list = [] + Timestamp_learn = [] + for i in range( + max(acc_ctrl_queue_size, steer_ctrl_queue_size) + 1, X_array.shape[0] - mpc_freq - 1 + ): + acc_input_queue = U_array[i - acc_ctrl_queue_size : i, 0].copy() + steer_input_queue = U_array[i - steer_ctrl_queue_size : i, 1].copy() + x_current = X_array[i + 3] + x_old = X_array[i] + + Timestamp_learn.append(Timestamp[i]) + X_input_list.append( + np.concatenate((x_old[[2, 4, 5]], acc_input_queue[::-1], steer_input_queue[::-1])) + ) + acc_start = acc_ctrl_queue_size - acc_delay_step_ctrl + acc_end = acc_ctrl_queue_size - acc_delay_step_ctrl + mpc_freq + steer_start = steer_ctrl_queue_size - steer_delay_step_ctrl + steer_end = steer_ctrl_queue_size - steer_delay_step_ctrl + mpc_freq + + u_for_predict_x_current = np.zeros((mpc_freq, 2)) + u_for_predict_x_current[:, 0] = acc_input_queue[acc_start:acc_end] + u_for_predict_x_current[:, 1] = steer_input_queue[steer_start:steer_end] + var_dot = x_current - drive_functions.F_multiple( + x_old, u_for_predict_x_current, acc_time_constant_ctrl, steer_time_constant_ctrl + ) + var_dot /= mpc_time_step + if var_dot[3] > 1: + print(i) + Y_output_list.append(drive_functions.rotate_data(x_old, var_dot)) + + Y_output_list_array = np.array(Y_output_list) + Y_smooth = Y_output_list_array.copy() + Y_smooth[:, 0] = data_smoothing( + Y_output_list_array[:, 0], drive_functions.x_out_sigma_for_learning + ) + Y_smooth[:, 1] = data_smoothing( + Y_output_list_array[:, 1], drive_functions.y_out_sigma_for_learning + ) + Y_smooth[:, 2] = data_smoothing( + Y_output_list_array[:, 2], drive_functions.v_out_sigma_for_learning + ) + Y_smooth[:, 3] = data_smoothing( + Y_output_list_array[:, 3], drive_functions.theta_out_sigma_for_learning + ) + Y_smooth[:, 4] = data_smoothing( + Y_output_list_array[:, 4], drive_functions.acc_out_sigma_for_learning + ) + Y_smooth[:, 5] = data_smoothing( + Y_output_list_array[:, 5], drive_functions.steer_out_sigma_for_learning + ) + + for i in range(len(X_input_list)): + self.X_input_list.append(X_input_list[i]) + self.Y_output_list.append(Y_smooth[i]) + + def save_train_data(self, save_dir=".") -> None: + """Save neural net teacher data.""" + np.savez( + save_dir + "/train_data", + X_input=np.array(self.X_input_list), + Y_output=np.array(self.Y_output_list), + ) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb new file mode 100644 index 0000000000000..9ddd5fb6fad2a --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/data_checker.ipynb @@ -0,0 +1,252 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": null, + "id": "85844bd8-91fa-4238-9bcf-cf45c9ef8c33", + "metadata": {}, + "outputs": [], + "source": [ + "# cspell: ignore ndimage usecols kernelspec ipykernel codemirror ipython nbconvert pygments nbformat \n", + "import numpy as np\n", + "from scipy.spatial.transform import Rotation\n", + "import scipy.interpolate\n", + "from scipy.ndimage import gaussian_filter\n", + "import os\n", + "import matplotlib.pyplot as plt\n", + "import csv\n", + "def yaw_transform(raw_yaw):\n", + " transformed_yaw = np.zeros(raw_yaw.shape)\n", + " transformed_yaw[0] = raw_yaw[0]\n", + " for i in range(raw_yaw.shape[0]-1):\n", + " rotate_num = (raw_yaw[i+1]-transformed_yaw[i])//(2*np.pi)\n", + " if raw_yaw[i+1]-transformed_yaw[i] - 2*rotate_num*np.pi < np.pi:\n", + " transformed_yaw[i+1] = raw_yaw[i+1] - 2*rotate_num*np.pi\n", + " else:\n", + " transformed_yaw[i+1] = raw_yaw[i+1] - 2*(rotate_num+1)*np.pi\n", + " return transformed_yaw\n", + "def steer_visualize(skip_time = 0,total_time = None,dir_name = \".\",ylim = [-0.025,0.025] ):\n", + " kinematic=np.loadtxt(dir_name+\"/kinematic_state.csv\",delimiter=',',usecols=[0,1,4,5,7,8,9,10,47])\n", + " start_time= kinematic[0,0]+1e-9*kinematic[0,1]\n", + " total_time_default=kinematic[-1,0]+1e-9*kinematic[-1,1]-start_time\n", + " vehicle_steer = np.loadtxt(dir_name+\"/steering_status.csv\",delimiter=',',usecols=[0,1,2])\n", + " steer = vehicle_steer[:,2]\n", + " control_cmd = np.loadtxt(dir_name+\"/control_cmd_orig.csv\",delimiter=',',usecols=[0,1,4,9])\n", + " steer_des = control_cmd[:,2]\n", + " plt.plot(control_cmd[:,0] + 1e-9*control_cmd[:,1],steer_des,label=\"proxima_input\")\n", + " plt.plot(vehicle_steer[:,0] + 1e-9*vehicle_steer[:,1],steer,label=\"observed\")\n", + " \"\"\"\n", + " operation_mode = np.loadtxt(dir_name + \"/system_operation_mode_state.csv\", delimiter=\",\", usecols=[0, 1, 2])\n", + " operation_mode_time = np.zeros(2*operation_mode.shape[0])\n", + " operation_mode_time[::2] = operation_mode[:,0] + 1e-9*operation_mode[:,1]\n", + " operation_mode_time[1::2][:-1] = operation_mode_time[2::2]-1e-16\n", + " operation_mode_time[-1] = start_time+total_time_default\n", + " with open(dir_name+\"/system_operation_mode_state.csv\") as f:\n", + " reader=csv.reader(f,delimiter=',')\n", + " autoware_control_enabled_str=np.array([row[3] for row in reader])\n", + " with open(dir_name+\"/system_operation_mode_state.csv\") as f:\n", + " reader=csv.reader(f,delimiter=',')\n", + " autonomous_mode_available_str=np.array([row[6] for row in reader])\n", + " autoware_control_enabled = np.zeros(2*operation_mode.shape[0])\n", + " autonomous_mode_available = np.zeros(2*operation_mode.shape[0])\n", + " operation_mode_ = np.ones(2*operation_mode.shape[0])\n", + " for i in range(operation_mode.shape[0]):\n", + " if autoware_control_enabled_str[i] == \"True\":\n", + " autoware_control_enabled[2*i] = 1\n", + " autoware_control_enabled[2*i+1] = 1\n", + "\n", + " if operation_mode[i,2] > 1.5:\n", + " operation_mode_[2*i] = 2.0\n", + " operation_mode_[2*i+1] = 2.0\n", + " \"\"\"\n", + " # plt.plot(operation_mode_time,0.01*operation_mode_,label=\"operation_mode\")\n", + " # plt.plot(operation_mode_time,0.01*autoware_control_enabled,label=\"autoware_control_enabled\")\n", + "\n", + "\n", + " if total_time is None:\n", + " plt.xlim([start_time+skip_time,start_time+total_time_default])\n", + " else:\n", + " plt.xlim([start_time+skip_time,start_time+skip_time+total_time])\n", + " plt.ylabel(\"steer [rad]\")\n", + " plt.xlabel(\"Time [s]\")\n", + "\n", + " plt.ylim(ylim)\n", + " plt.legend()\n", + " plt.show()\n", + "def acc_visualize(skip_time = 0,total_time = None,dir_name = \".\",ylim = [-0.005,0.02] ):\n", + " kinematic=np.loadtxt(dir_name+\"/kinematic_state.csv\",delimiter=',',usecols=[0,1,4,5,7,8,9,10,47])\n", + " start_time= kinematic[0,0]+1e-9*kinematic[0,1]\n", + " total_time_default=kinematic[-1,0]+1e-9*kinematic[-1,1]-start_time\n", + " loc_acc = np.loadtxt(dir_name + \"/acceleration.csv\", delimiter=\",\", usecols=[0, 1, 3])\n", + " acc = loc_acc[:,2]\n", + " control_cmd = np.loadtxt(dir_name+\"/control_cmd_orig.csv\",delimiter=',',usecols=[0,1,4,9])\n", + " acc_des = control_cmd[:,3]\n", + " plt.plot(control_cmd[:,0] + 1e-9*control_cmd[:,1],acc_des,label=\"proxima_input\")\n", + " plt.plot(loc_acc[:,0] + 1e-9*loc_acc[:,1],acc,label=\"observed\")\n", + " \"\"\"\n", + " goal_stop_mode = np.loadtxt(dir_name + \"/debug_mpc_goal_stop_mode.csv\", delimiter=\",\",usecols=[0,1])\n", + "\n", + " with open(dir_name+\"/debug_mpc_goal_stop_mode.csv\") as f:\n", + " reader=csv.reader(f,delimiter=',')\n", + " stop_mode_str=np.array([row[2] for row in reader])\n", + "\n", + " stop_mode = np.zeros(goal_stop_mode.shape[0])\n", + " for i in range(goal_stop_mode.shape[0]):\n", + " if stop_mode_str[i] == \"True\":\n", + " stop_mode[i] = 1\n", + " plt.plot(goal_stop_mode[:,0] + 1e-9*goal_stop_mode[:,1],stop_mode,label=\"stop_mode\")\n", + " operation_mode = np.loadtxt(dir_name + \"/system_operation_mode_state.csv\", delimiter=\",\", usecols=[0, 1, 2])\n", + " operation_mode_time = np.zeros(2*operation_mode.shape[0])\n", + " operation_mode_time[::2] = operation_mode[:,0] + 1e-9*operation_mode[:,1]\n", + " operation_mode_time[1::2][:-1] = operation_mode_time[2::2]-1e-16\n", + " operation_mode_time[-1] = start_time+total_time_default\n", + " with open(dir_name+\"/system_operation_mode_state.csv\") as f:\n", + " reader=csv.reader(f,delimiter=',')\n", + " autoware_control_enabled_str=np.array([row[3] for row in reader])\n", + " with open(dir_name+\"/system_operation_mode_state.csv\") as f:\n", + " reader=csv.reader(f,delimiter=',')\n", + " autonomous_mode_available_str=np.array([row[6] for row in reader])\n", + " autoware_control_enabled = np.zeros(2*operation_mode.shape[0])\n", + " operation_mode_ = np.ones(2*operation_mode.shape[0])\n", + " for i in range(operation_mode.shape[0]):\n", + " if autoware_control_enabled_str[i] == \"True\":\n", + " autoware_control_enabled[2*i] = 1\n", + " autoware_control_enabled[2*i+1] = 1\n", + "\n", + " if operation_mode[i,2] > 1.5:\n", + " operation_mode_[2*i] = 2.0\n", + " operation_mode_[2*i+1] = 2.0\n", + " \"\"\"\n", + " # plt.plot(operation_mode_time,operation_mode_,label=\"operation_mode\")\n", + " # plt.plot(operation_mode_time,autoware_control_enabled,label=\"autoware_control_enabled\")\n", + "\n", + " if total_time is None:\n", + " plt.xlim([start_time+skip_time,start_time+total_time_default])\n", + " else:\n", + " plt.xlim([start_time+skip_time,start_time+skip_time+total_time])\n", + " plt.ylabel(\"acc [m/s^2]\")\n", + " plt.xlabel(\"Time [s]\")\n", + " plt.ylim(ylim)\n", + " plt.legend()\n", + " plt.show()\n", + "def yaw_visualize(skip_time = 0,total_time = None,dir_name = \".\",ylim = [-0.15,0.0]):\n", + " kinematic=np.loadtxt(dir_name+\"/kinematic_state.csv\",delimiter=',',usecols=[0,1,4,5,7,8,9,10,47])\n", + " raw_yaw = Rotation.from_quat(kinematic[:,4:8]).as_euler(\"xyz\")[:,2]\n", + " yaw = yaw_transform(raw_yaw)\n", + " start_time= kinematic[0,0]+1e-9*kinematic[0,1]\n", + " total_time_default=kinematic[-1,0]+1e-9*kinematic[-1,1]-start_time\n", + " plt.plot(kinematic[:,0] + 1e-9*kinematic[:,1],yaw,label=\"observed\")\n", + " if total_time is None:\n", + " plt.xlim([start_time+skip_time,start_time+total_time_default])\n", + " else:\n", + " plt.xlim([start_time+skip_time,start_time+skip_time+total_time])\n", + " plt.ylabel(\"yaw [rad]\")\n", + " plt.xlabel(\"Time [s]\")\n", + "\n", + " plt.ylim(ylim)\n", + " plt.legend()\n", + " plt.show()\n", + "def vel_visualize(skip_time = 0,total_time = None,dir_name = \".\",ylim = [-0.1,12.0]):\n", + " kinematic=np.loadtxt(dir_name+\"/kinematic_state.csv\",delimiter=',',usecols=[0,1,4,5,7,8,9,10,47])\n", + " vel = kinematic[:,8]\n", + " mpc_v_des=np.loadtxt(dir_name+\"/debug_mpc_v_des.csv\",delimiter=',',usecols=[0,1,3])\n", + " vel_des = mpc_v_des[:,2]\n", + " start_time= kinematic[0,0]+1e-9*kinematic[0,1]\n", + " total_time_default=kinematic[-1,0]+1e-9*kinematic[-1,1]-start_time\n", + " plt.plot(kinematic[:,0] + 1e-9*kinematic[:,1],vel,label=\"observed\")\n", + " plt.plot(mpc_v_des[:,0] + 1e-9*mpc_v_des[:,1],vel_des,label=\"des\")\n", + "\n", + " if total_time is None:\n", + " plt.xlim([start_time+skip_time,start_time+total_time_default])\n", + " else:\n", + " plt.xlim([start_time+skip_time,start_time+skip_time+total_time])\n", + " plt.ylabel(\"vel [m/s]\")\n", + " plt.xlabel(\"Time [s]\")\n", + "\n", + " plt.ylim(ylim)\n", + " plt.legend()\n", + " plt.show()\n", + "def lateral_error_visualize(skip_time = 0,total_time = None,dir_name = \".\",ylim = [-0.25,0.25],title=None):\n", + " lateral_error = np.loadtxt(dir_name+\"/lateral_error.csv\",delimiter=',')\n", + " start_time= lateral_error[0,0]+1e-9*lateral_error[0,1]\n", + " total_time_default=lateral_error[-1,0]+1e-9*lateral_error[-1,1]-start_time\n", + " plt.plot(lateral_error[:,0] + 1e-9*lateral_error[:,1],lateral_error[:,2],label=\"lateral_error\")\n", + " if total_time is None:\n", + " plt.xlim([start_time+skip_time,start_time+total_time_default])\n", + " else:\n", + " plt.xlim([start_time+skip_time,start_time+skip_time+total_time])\n", + " plt.legend()\n", + " plt.ylim(ylim)\n", + " plt.ylabel(\"lateral_error [m]\")\n", + " plt.xlabel(\"Time [s]\")\n", + " if title is not None:\n", + " plt.title(title)\n", + " plt.savefig(\"lateral_error_\"+title+\".png\")\n", + " plt.show()\n", + "def computation_time_visualize(skip_time = 0,total_time = None,dir_name = \".\",ylim = [-0.05,0.5]):\n", + " control_cmd = np.loadtxt(dir_name+\"/control_cmd_orig.csv\",delimiter=',',usecols=[0,1])\n", + " cmd_time_stamp = control_cmd[:,0]+1e-9*control_cmd[:,1]\n", + " cmd_time_stamp_diff = cmd_time_stamp[1:] - cmd_time_stamp[:-1]\n", + " calc_u_opt_time = np.loadtxt(dir_name+\"/debug_mpc_calc_u_opt_time.csv\",delimiter=',')\n", + " total_ctrl_time = np.loadtxt(dir_name+\"/debug_mpc_total_ctrl_time.csv\",delimiter=',')\n", + " start_time= control_cmd[0,0]+1e-9*control_cmd[0,1]\n", + " total_time_default=control_cmd[-1,0]+1e-9*control_cmd[-1,1]-start_time\n", + "\n", + " plt.plot(cmd_time_stamp[1:],cmd_time_stamp_diff,label=\"/control/trajectory_follower/control_cmd publish_interval\")\n", + " plt.plot(total_ctrl_time[:,0] + 1e-9*total_ctrl_time[:,1],total_ctrl_time[:,2],label=\"total_ctrl_time\")\n", + " plt.plot(calc_u_opt_time[:,0] + 1e-9*calc_u_opt_time[:,1],calc_u_opt_time[:,2],label=\"calc_u_opt_time\")\n", + " plt.legend()\n", + " plt.ylim(ylim)\n", + " if total_time is None:\n", + " plt.xlim([start_time+skip_time,start_time+total_time_default])\n", + " else:\n", + " plt.xlim([start_time+skip_time,start_time+skip_time+total_time])\n", + " plt.xlabel(\"Time [s]\")\n", + " plt.ylabel(\"Processing Time [s]\")\n", + " plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "b07ed62c-a5b0-4c5f-b52d-633b0c61271b", + "metadata": {}, + "outputs": [], + "source": [ + "dirname = #specify rosbag dir\n", + "steer_visualize(20,20,dirname,ylim=[-0.05,0.05])\n", + "lateral_error_visualize(0,None,dirname,ylim=[-0.6,0.6])\n", + "vel_visualize(20,20,dirname,ylim=[-0.6,12.0])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "f7012be5-0259-4618-a380-8ec7a29f59af", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.12" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb new file mode 100644 index 0000000000000..c2955883d5699 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/execute_train_drive_NN_model.ipynb @@ -0,0 +1,77 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": null, + "id": "c445f7e1-6d75-405d-be86-1b9c8f9eaae3", + "metadata": {}, + "outputs": [], + "source": [ + "# cspell: ignore kernelspec ipykernel codemirror ipython nbconvert pygments nbformat \n", + "import train_drive_NN_model" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "dc7aa5b8-15fa-4ad0-a776-664748a747ac", + "metadata": {}, + "outputs": [], + "source": [ + "model_trainer = train_drive_NN_model.train_drive_NN_model()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "6559bc06-d55d-4230-a640-e1730e333df3", + "metadata": {}, + "outputs": [], + "source": [ + "load_dir = #specify rosbag dir\n", + "model_trainer.add_data_from_csv(load_dir)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "bdcd80a2-6484-4957-a34c-3ed193cc10e2", + "metadata": {}, + "outputs": [], + "source": [ + "model_trainer.get_trained_model(use_polynomial_reg=False)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "dc4c2c45-60b1-4ff7-996b-4f1f60305f97", + "metadata": {}, + "outputs": [], + "source": [ + "model_trainer.save_models()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.10.12" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash new file mode 100644 index 0000000000000..524dfe5a169df --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/rosbag2.bash @@ -0,0 +1,40 @@ +#!/bin/bash + +gnome-terminal -- bash -c 'ros2 topic echo /localization/kinematic_state nav_msgs/msg/Odometry --csv --qos-history keep_all --qos-reliability reliable > kinematic_state.csv' +gnome-terminal -- bash -c 'ros2 topic echo /localization/acceleration geometry_msgs/msg/AccelWithCovarianceStamped --csv --qos-history keep_all --qos-reliability reliable > acceleration.csv' +gnome-terminal -- bash -c 'ros2 topic echo /vehicle/status/steering_status autoware_auto_vehicle_msgs/msg/SteeringReport --csv --qos-history keep_all --qos-reliability reliable > steering_status.csv' + +gnome-terminal -- bash -c 'ros2 topic echo /control/command/control_cmd autoware_auto_control_msgs/msg/AckermannControlCommand --csv --qos-history keep_all --qos-reliability reliable > control_cmd.csv' +gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/control_cmd autoware_auto_control_msgs/msg/AckermannControlCommand --csv --qos-history keep_all --qos-reliability reliable > control_cmd_orig.csv' + +gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/lane_departure_checker_node/debug/deviation/lateral tier4_debug_msgs/msg/Float64Stamped --csv --qos-history keep_all --qos-reliability reliable > lateral_error.csv' +gnome-terminal -- bash -c 'ros2 topic echo /control/trajectory_follower/lane_departure_checker_node/debug/deviation/yaw tier4_debug_msgs/msg/Float64Stamped --csv --qos-history keep_all --qos-reliability reliable > yaw_error.csv' + +gnome-terminal -- bash -c 'ros2 topic echo /system/operation_mode/state autoware_adapi_v1_msgs/msg/OperationModeState --csv --qos-history keep_all --qos-reliability reliable > system_operation_mode_state.csv' +gnome-terminal -- bash -c 'ros2 topic echo /vehicle/status/control_mode autoware_auto_vehicle_msgs/msg/ControlModeReport --csv --qos-history keep_all --qos-reliability reliable > vehicle_status_control_mode.csv' +gnome-terminal -- bash -c 'ros2 topic echo /sensing/imu/imu_data sensor_msgs/msg/Imu --csv --qos-history keep_all --qos-reliability reliable > imu.csv' + +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_x_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_x_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_y_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_y_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_v_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_v_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_yaw_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_yaw_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_acc_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_acc_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_steer_des tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_steer_des.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_X_des_converted tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_X_des_converted.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_x_current tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_x_current.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_error_prediction tier4_debug_msgs/msg/Float32MultiArrayStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_error_prediction.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_max_trajectory_err tier4_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_max_trajectory_err.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_emergency_stop_mode tier4_debug_msgs/msg/BoolStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_emergency_stop_mode.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_goal_stop_mode tier4_debug_msgs/msg/BoolStamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_goal_stop_mode.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_total_ctrl_time tier4_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_total_ctrl_time.csv' +gnome-terminal -- bash -c 'ros2 topic echo /debug_mpc_calc_u_opt_time tier4_debug_msgs/msg/Float32Stamped --csv --qos-history keep_all --qos-reliability reliable > debug_mpc_calc_u_opt_time.csv' + +# wait a moment to open new terminals converting rosbag2 to csv +sleep 8 + +ros2 bag play rosbag2_*.db3 -r 10 + +sleep 3 + +# kill terminals converting rosbag2 to csv +pgrep -f "\ --csv\ --qos-history\ keep_all\ --qos-reliability\ reliable" | xargs kill -9 diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py new file mode 100644 index 0000000000000..914ed7b53c6ec --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_GP_model.py @@ -0,0 +1,88 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore lengthscale savez + +import GPy +import numpy as np +from smart_mpc_trajectory_follower.training_and_data_check import add_training_data_from_csv + + +class train_drive_GP_model(add_training_data_from_csv.add_data_from_csv): + """Class for training the Gaussian process from driving data.""" + + def __init__(self): + super(train_drive_GP_model, self).__init__() + + def get_optimized_GP(self, i, save_name, inducting_num=100): + """Train Gaussian processes and save the information needed for vehicle control.""" + X_input = np.array(self.X_input_list) + Y_output = np.array(self.Y_output_list) + induction_index = np.random.choice(X_input.shape[0], inducting_num, replace=False) + kernel = GPy.kern.RBF(input_dim=X_input.shape[1], ARD=True) + m = GPy.models.SparseGPRegression( + X_input, Y_output[:, [i]], kernel, Z=X_input[induction_index] + ) + m.optimize() + theta_1 = kernel.variance[0] + theta_2 = 1 / np.array(np.array(kernel.lengthscale) ** 2) + Z_post = np.array(m.inducing_inputs) + + K_MM = kernel.K(Z_post, Z_post) + K_MN = kernel.K(Z_post, X_input) + K_MM_inv = np.linalg.inv(K_MM) + Lam_with_noise_inv = np.zeros(K_MN.shape[1]) + for n in range(K_MN.shape[1]): + Lam_with_noise_inv[n] = 1 / ( + kernel.variance + - np.dot(K_MM_inv @ K_MN[:, n], K_MN[:, n]) + + m.Gaussian_noise.variance + ) + Q_MM = K_MM + K_MN @ np.diag(Lam_with_noise_inv) @ K_MN.T + Q_MM_inv = np.linalg.inv(Q_MM) + U = K_MM @ Q_MM_inv @ K_MN @ (np.diag(Lam_with_noise_inv) @ Y_output[:, 4]) + K_MM_invUT = (K_MM_inv @ U).T + + np.savez( + save_name, + theta_1=theta_1, + theta_2=theta_2, + Z=Z_post, + mean_mtr=K_MM_invUT, + cov_mtr=K_MM_inv - Q_MM_inv, + ) + + def get_optimized_GP_x(self, dir_name=".", inducting_num=100): + """Save the information of the Gaussian process about the prediction error of the longitudinal position.""" + self.get_optimized_GP(0, dir_name + "/GP_x_info", inducting_num) + + def get_optimized_GP_y(self, dir_name=".", inducting_num=100): + """Save the information of the Gaussian process about the prediction error of the lateral position.""" + self.get_optimized_GP(1, dir_name + "/GP_y_info", inducting_num) + + def get_optimized_GP_v(self, dir_name=".", inducting_num=100): + """Save the information of the Gaussian process about the prediction error of the velocity.""" + self.get_optimized_GP(2, dir_name + "/GP_v_info", inducting_num) + + def get_optimized_GP_theta(self, dir_name=".", inducting_num=100): + """Save the information of the Gaussian process about the prediction error of the yaw angle.""" + self.get_optimized_GP(3, dir_name + "/GP_theta_info", inducting_num) + + def get_optimized_GP_acc(self, dir_name=".", inducting_num=100): + """Save the information of the Gaussian process about the prediction error of the acceleration.""" + self.get_optimized_GP(4, dir_name + "/GP_acc_info", inducting_num) + + def get_optimized_GP_steer(self, dir_name=".", inducting_num=100): + """Save the information of the Gaussian process about the prediction error of the steering angle.""" + self.get_optimized_GP(5, dir_name + "/GP_steer_info", inducting_num) diff --git a/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py new file mode 100644 index 0000000000000..269b577f83c25 --- /dev/null +++ b/control/smart_mpc_trajectory_follower/smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py @@ -0,0 +1,716 @@ +# Copyright 2024 Proxima Technology Inc, TIER IV +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# cspell: ignore optim savez suptitle + +"""Class for training neural nets from driving data.""" +import matplotlib.pyplot as plt +import numpy as np +from sklearn import linear_model +from sklearn.preprocessing import PolynomialFeatures +from smart_mpc_trajectory_follower.scripts import drive_NN +from smart_mpc_trajectory_follower.scripts import drive_functions +from smart_mpc_trajectory_follower.training_and_data_check import add_training_data_from_csv +import torch +from torch import nn +from torch.utils.data import DataLoader +from torch.utils.data import TensorDataset + +ctrl_index_for_polynomial_reg = np.concatenate( + ( + np.arange(3), + [3 + drive_functions.acc_delay_step], + [3 + drive_functions.acc_ctrl_queue_size + drive_functions.steer_delay_step], + ) +) + + +def nominal_model_acc(v: float, alpha_0: float, alpha: float) -> np.ndarray: + """Predicted acceleration value according to the nominal model.""" + nominal_pred = alpha_0 + nominal_v = v + nominal_pred * drive_functions.ctrl_time_step + nominal_pred = ( + nominal_pred + + (alpha - nominal_pred) + * drive_functions.ctrl_time_step + / drive_functions.acc_time_constant + ) + nominal_v = v + nominal_pred * drive_functions.ctrl_time_step + nominal_pred = ( + nominal_pred + + (alpha - nominal_pred) + * drive_functions.ctrl_time_step + / drive_functions.acc_time_constant + ) + nominal_v = v + nominal_pred * drive_functions.ctrl_time_step + nominal_pred = ( + nominal_pred + + (alpha - nominal_pred) + * drive_functions.ctrl_time_step + / drive_functions.acc_time_constant + ) + return np.array([nominal_v, nominal_pred]) + + +def nominal_model_steer(delta_0: float, delta: float) -> float: + """Predicted steer angle according to the nominal model.""" + nominal_pred = delta_0 + nominal_pred = ( + nominal_pred + + (delta - nominal_pred) + * drive_functions.ctrl_time_step + / drive_functions.steer_time_constant + ) + nominal_pred = ( + nominal_pred + + (delta - nominal_pred) + * drive_functions.ctrl_time_step + / drive_functions.steer_time_constant + ) + nominal_pred = ( + nominal_pred + + (delta - nominal_pred) + * drive_functions.ctrl_time_step + / drive_functions.steer_time_constant + ) + return nominal_pred + + +class train_drive_NN_model(add_training_data_from_csv.add_data_from_csv): + """Class for training neural nets from driving data.""" + + tanh_gain: float + """Gain of tanh in the NN cost function""" + + lam: float + """Weights of the tanh term in the NN cost function.""" + + tol: float + """Tolerances for terminating training iterations.""" + + alpha_1: float + """L¹ regularization weights in the NN cost function""" + + alpha_2: float + """L² regularization weights in the NN cost function.""" + + alpha_1_for_polynomial_regression: float + """L¹ regularization weights for polynomial regression""" + + alpha_2_for_polynomial_regression: float + """L² regularization weights for polynomial regression""" + + x_loss: list[float] + """List of values for the loss function of the x component in the NN training.""" + + y_loss: list[float] + """List of values for the loss function of the y component in the NN training.""" + + v_loss: list[float] + """List of values for the loss function of the velocity component in the NN training.""" + + theta_loss: list[float] + """List of values for the loss function of the yaw angle component in the NN training.""" + + acc_loss: list[float] + """List of values for the loss function of the acceleration component in the NN training.""" + + steer_loss: list[float] + """List of values for the loss function of the steer angle component in the NN training.""" + + steer_loss_plus_tanh: list[float] + """List of values of the loss function for the steer angle component with tanh term in the NN training.""" + + total_loss: list[float] + """In NN training x_loss, ... , acc_loss, steer_loss_plus_tanh summed list of values""" + + model: drive_NN.DriveNeuralNetwork + """trained neural network model""" + + A: np.ndarray + """Coefficient matrix of polynomial regression model.""" + + b: np.ndarray + """Constant terms in polynomial regression models (bias)""" + + def __init__( + self, + tanh_gain=10, + lam=0.1, + tol=0.00001, + alpha_1=0.1**7, + alpha_2=0.1**7, + alpha_1_for_polynomial_regression=0.1**5, + alpha_2_for_polynomial_regression=0.1**5, + ): + super(train_drive_NN_model, self).__init__() + self.tanh_gain = tanh_gain + self.lam = lam + self.tol = tol + self.alpha_1 = alpha_1 + self.alpha_2 = alpha_2 + self.alpha_1_for_polynomial_regression = alpha_1_for_polynomial_regression + self.alpha_2_for_polynomial_regression = alpha_2_for_polynomial_regression + self.x_loss = [] + self.y_loss = [] + self.v_loss = [] + self.theta_loss = [] + self.acc_loss = [] + self.steer_loss = [] + self.steer_loss_plus_tanh = [] + self.total_loss = [] + + def train_model( + self, + model: drive_NN.DriveNeuralNetwork, + X_input: np.ndarray, + Y_output: np.ndarray, + learning_rates: list[float], + patience: int = 10, + batch_size: int | None = 50, + max_iter: int = 100000, + ) -> None: + """Train the model.""" + if batch_size is None: + batch_size = X_input.shape[0] // 50 + self.x_loss.clear() + self.y_loss.clear() + self.v_loss.clear() + self.theta_loss.clear() + self.acc_loss.clear() + self.steer_loss.clear() + self.steer_loss_plus_tanh.clear() + self.total_loss.clear() + sample_size = X_input.shape[0] + num_train = int(3 * sample_size / 4) + id_all = np.random.choice(sample_size, sample_size, replace=False) + id_train = id_all[:num_train] + id_val = id_all[num_train:] + X_tensor = torch.tensor(X_input.astype(np.float32)).clone() + Y_tensor = torch.tensor(Y_output.astype(np.float32)).clone() + X_train = X_tensor[id_train] + Y_train = Y_tensor[id_train] + X_val = X_tensor[id_val] + Y_val = Y_tensor[id_val] + + print("sample_size: ", X_input.shape[0]) + print("patience:", patience) + loss_fn = torch.nn.L1Loss() + learning_rate = learning_rates[0] + optimizer = torch.optim.Adam(params=model.parameters(), lr=learning_rate) + + drive_data = DataLoader( + TensorDataset(X_train, Y_train), batch_size=batch_size, shuffle=True + ) + initial_loss = drive_NN.loss_fn_plus_tanh( + loss_fn, + torch.tensor(np.zeros(Y_val.shape), dtype=torch.float32), + Y_val, + self.tanh_gain, + self.lam, + ) + print("initial_loss:", initial_loss.detach().item()) + early_stopping = drive_NN.EarlyStopping( + initial_loss=initial_loss, tol=self.tol, patience=patience + ) + k = 0 + print("learning_rate:", learning_rates[0]) + for i in range(max_iter): + model.train() + for X_batch, y_batch in drive_data: + y_pred = model(X_batch) + loss = drive_NN.loss_fn_plus_tanh( + loss_fn, y_pred, y_batch, self.tanh_gain, self.lam + ) + for w in model.parameters(): + loss = ( + loss + self.alpha_1 * torch.norm(w, p=1) + self.alpha_2 * torch.norm(w) ** 2 + ) + optimizer.zero_grad() + loss.backward() + optimizer.step() + + model.eval() + pred = model(X_val) + self.total_loss.append( + drive_NN.loss_fn_plus_tanh(loss_fn, pred, Y_val, self.tanh_gain, self.lam) + .detach() + .item() + ) + self.x_loss.append(loss_fn(pred[:, [0]], Y_val[:, [0]]).detach().item()) + self.y_loss.append(loss_fn(pred[:, [1]], Y_val[:, [1]]).detach().item()) + self.v_loss.append(loss_fn(pred[:, [2]], Y_val[:, [2]]).detach().item()) + self.theta_loss.append(loss_fn(pred[:, [3]], Y_val[:, [3]]).detach().item()) + self.acc_loss.append(loss_fn(pred[:, [4]], Y_val[:, [4]]).detach().item()) + self.steer_loss.append(loss_fn(pred[:, [5]], Y_val[:, [5]]).detach().item()) + self.steer_loss_plus_tanh.append( + loss_fn(pred[:, [5]], Y_val[:, [5]]).detach().item() + + self.lam + * loss_fn( + torch.tanh(self.tanh_gain * (pred[:, -1] - Y_val[:, -1])), + torch.zeros(Y_val.shape[0]), + ) + .detach() + .item() + ) + if i % 10 == 1: + current_loss = drive_NN.loss_fn_plus_tanh( + loss_fn, model(X_val), Y_val, self.tanh_gain, self.lam + ) + print(current_loss.detach().item(), i) + if early_stopping(current_loss): + k += 1 + if k == len(learning_rates): + break + else: + learning_rate = learning_rates[k] + print("update learning_rate to ", learning_rates[k]) + optimizer = torch.optim.Adam(params=model.parameters(), lr=learning_rate) + early_stopping = drive_NN.EarlyStopping( + initial_loss=initial_loss, tol=self.tol, patience=patience + ) + + def get_polynomial_regression_result( + self, + X_input_list: list[np.ndarray], + Y_output_list: list[np.ndarray], + use_polynomial_reg: bool, + use_selected_polynomial: bool, + deg: int, + fit_intercept: bool, + use_intercept: bool, + ) -> tuple[np.ndarray, np.ndarray]: + """Get the results of a polynomial regression.""" + X_input = np.array(X_input_list) + X_input_core = X_input[ + :, + : 3 + drive_functions.acc_ctrl_queue_size + drive_functions.steer_ctrl_queue_size_core, + ].copy() + Y_output = np.array(Y_output_list) + if use_selected_polynomial: + self.deg = 2 + else: + self.deg = deg + self.A, self.b, Y_output_minus = polynomial_regression( + X_input_core, + Y_output, + self.alpha_1_for_polynomial_regression, + self.alpha_2_for_polynomial_regression, + use_polynomial_reg, + use_selected_polynomial, + self.deg, + fit_intercept, + use_intercept, + ) + return X_input, Y_output_minus + + def plot_trained_result( + self, show_flag=False, save_dir=".", plot_range=np.arange(500, 1200) + ) -> None: + """Plot the results of the training.""" + polynomial_features = PolynomialFeatures(degree=self.deg, include_bias=False) + + X_input = np.array(self.X_input_list) + Y_output = np.array(self.Y_output_list) + X_tensor = torch.tensor(X_input.astype(np.float32)).clone() + acc_ctrl_queue_size = drive_functions.acc_ctrl_queue_size + steer_ctrl_queue_size = drive_functions.steer_ctrl_queue_size + ctrl_time_step = drive_functions.ctrl_time_step + Y_pred = ( + self.model(X_tensor).detach().numpy() + + polynomial_features.fit_transform(X_input[:, ctrl_index_for_polynomial_reg]) + @ (self.A).T + + self.b + ) + x = max(acc_ctrl_queue_size, steer_ctrl_queue_size) * ctrl_time_step + y_labels = [ + "x_error [m]", + "y_error [m]", + "vel_error [m/s]", + "yaw_error [rad]", + "acc_error [m/s^2]", + "steer_error [rad]", + ] + + plt.figure(figsize=(24, 15), tight_layout=True) + plt.subplot(231) + ax = [] + for i in range(6): + ax.append(plt.subplot(2, 3, i + 1)) + ax[-1].plot( + drive_functions.ctrl_time_step * plot_range + x, + Y_output[plot_range, i] * drive_functions.mpc_time_step, + label="nominal_error", + ) + ax[-1].plot( + drive_functions.ctrl_time_step * plot_range + x, + Y_pred[plot_range, i] * drive_functions.mpc_time_step, + label="pred_error", + ) + ax[-1].set_xlabel("sec") + ax[-1].set_ylabel(y_labels[i]) + ax[-1].legend() + if show_flag: + plt.show() + else: + plt.savefig(save_dir + "/train_drive_NN_model_fig.png") + plt.close() + + def plot_loss(self, show_flag=False, save_dir=".") -> None: + """Plot the progression of values of the loss function of the training.""" + plt.figure(figsize=(24, 15), tight_layout=True) + + y_loss_labels = [ + "total_loss", + "x_loss", + "y_loss", + "vel_loss", + "yaw_loss", + "acc_loss", + "steer_loss", + "steer_plus_tanh_loss", + ] + plt.subplot(241) + ax_2 = [] + loss_list = [ + np.array(self.total_loss), + np.array(self.x_loss), + np.array(self.y_loss), + np.array(self.v_loss), + np.array(self.theta_loss), + np.array(self.acc_loss), + np.array(self.steer_loss), + np.array(self.steer_loss_plus_tanh), + ] + for i in range(8): + ax_2.append(plt.subplot(2, 4, i + 1)) + ax_2[-1].plot( + np.arange(loss_list[i].shape[0]), + loss_list[i], + label="loss", + ) + ax_2[-1].set_xlabel("iteration") + ax_2[-1].set_ylabel(y_loss_labels[i]) + ax_2[-1].legend() + if show_flag: + plt.show() + else: + plt.savefig(save_dir + "/loss.png") + plt.close() + + def get_trained_model( + self, + learning_rates: list[float] = [1e-3, 1e-4, 1e-5, 1e-6], + randomize=0.01, + acc_drop_out=0.0, + steer_drop_out=0.0, + patience: int = 10, + batch_size: int | None = 50, + max_iter=100000, + use_polynomial_reg=False, + use_selected_polynomial=True, + force_NN_model_to_zero=False, + fit_intercept=True, + use_intercept=None, + deg: int = 2, + ): + """Train on a model for which initial values are randomly given in a suitable range.""" + if use_intercept is None: + if force_NN_model_to_zero: + use_intercept = True + else: + use_intercept = False + X_input, Y_output_minus = self.get_polynomial_regression_result( + self.X_input_list, + self.Y_output_list, + use_polynomial_reg, + use_selected_polynomial, + deg, + fit_intercept, + use_intercept, + ) + self.model = drive_NN.DriveNeuralNetwork( + randomize=randomize, + acc_drop_out=acc_drop_out, + steer_drop_out=steer_drop_out, + acc_queue_size=drive_functions.acc_ctrl_queue_size, + steer_queue_size=drive_functions.steer_ctrl_queue_size, + ) + if force_NN_model_to_zero: + for w in self.model.parameters(): + w.data = nn.Parameter(torch.zeros(w.shape)) + else: + self.train_model( + self.model, X_input, Y_output_minus, learning_rates, patience, batch_size, max_iter + ) + + def update_trained_model( + self, + learning_rates=[1e-4, 1e-5, 1e-6], + patience=5, + batch_size=50, + max_iter=100000, + use_polynomial_reg=False, + use_selected_polynomial=True, + force_NN_model_to_zero=False, + fit_intercept=True, + use_intercept=None, + deg: int = 2, + ): + """Update `self.model` with additional learning.""" + if use_intercept is None: + if force_NN_model_to_zero: + use_intercept = True + else: + use_intercept = False + X_input, Y_output_minus = self.get_polynomial_regression_result( + self.X_input_list, + self.Y_output_list, + use_polynomial_reg, + use_selected_polynomial, + deg, + fit_intercept, + use_intercept, + ) + if force_NN_model_to_zero: + for w in self.model.parameters(): + w.data = nn.Parameter(torch.zeros(w.shape)) + else: + self.train_model( + self.model, X_input, Y_output_minus, learning_rates, patience, batch_size, max_iter + ) + + def update_saved_trained_model( + self, + path="model_for_test_drive.pth", + learning_rates: list[float] = [1e-4, 1e-5, 1e-6], + patience=5, + batch_size: int | None = 50, + max_iter=100000, + use_polynomial_reg=False, + use_selected_polynomial=True, + force_NN_model_to_zero=False, + fit_intercept=True, + use_intercept=None, + deg: int = 2, + ) -> None: + """Load the saved model and update the model with additional training.""" + if use_intercept is None: + if force_NN_model_to_zero: + use_intercept = True + else: + use_intercept = False + X_input, Y_output_minus = self.get_polynomial_regression_result( + self.X_input_list, + self.Y_output_list, + use_polynomial_reg, + use_selected_polynomial, + deg, + fit_intercept, + use_intercept, + ) + self.model = torch.load(path) + if force_NN_model_to_zero: + for w in self.model.parameters(): + w.data = nn.Parameter(torch.zeros(w.shape)) + else: + self.train_model( + self.model, X_input, Y_output_minus, learning_rates, patience, batch_size, max_iter + ) + + def save_model(self, save_dir=".", path="model_for_test_drive.pth") -> None: + """Save trained NN models.""" + torch.save(self.model, save_dir + "/" + path) + + def save_polynomial_reg_info(self, save_dir=".", path="polynomial_reg_info") -> None: + """Save the coefficients and degree of the resulting polynomial regression.""" + np.savez(save_dir + "/" + path, A=self.A, b=self.b, deg=self.deg) + + def save_models( + self, + save_dir=".", + model_name="model_for_test_drive.pth", + polynomial_reg_info_name="polynomial_reg_info", + ) -> None: + """Run save_model and save_polynomial_reg_info.""" + self.save_model(save_dir, model_name) + self.save_polynomial_reg_info(save_dir, polynomial_reg_info_name) + + def predict_error( + self, v: float, alpha_0: float, delta_0: float, alpha: float, delta: float + ) -> np.ndarray: + """Predicts the prediction error when following a nominal model.""" + polynomial_features = PolynomialFeatures(degree=self.deg, include_bias=False) + x_input = np.zeros( + 3 + drive_functions.acc_ctrl_queue_size + drive_functions.steer_ctrl_queue_size + ) + x_input[0] = v + x_input[1] = alpha_0 + x_input[2] = delta_0 + x_input[3 : 3 + drive_functions.acc_ctrl_queue_size] += alpha + x_input[3 + drive_functions.acc_ctrl_queue_size :] += delta + x_input_tensor = torch.tensor(x_input.reshape(1, -1).astype(np.float32)) + return ( + self.model(x_input_tensor)[0].detach().numpy() + + self.A + @ polynomial_features.fit_transform( + x_input[ctrl_index_for_polynomial_reg].reshape(1, -1) + )[0] + + self.b + ) + + def sim( + self, v: float, alpha_0: float, alpha: float, delta_0: float, delta: float, iter_times: int + ) -> tuple[float, float, float]: + """Simulate velocity, acceleration and steer changes according to a trained model.""" + v_pred = v + alpha_pred = alpha_0 + delta_pred = delta_0 + for i in range(iter_times): + pred = ( + np.concatenate( + ( + nominal_model_acc(v_pred, alpha_pred, alpha), + np.array([nominal_model_steer(delta_pred, delta)]), + ) + ) + + self.predict_error(v_pred, alpha_pred, delta_pred, alpha, delta)[[2, 4, 5]] + * drive_functions.mpc_time_step + ) + v_pred = pred[0] + alpha_pred = pred[1] + steer_pred = pred[2] + return v_pred, alpha_pred, steer_pred + + def plot_acc_map(self, iter_times: int, starting_steer=0.0, target_steer=0.0) -> None: + """Run `sim` `iter_times` times. The simulation time is approximately 0.1*iter_times. + + Draw the resulting acceleration map. + """ + acc = np.arange(-1, 1, 0.05) + v_tests = np.arange(0, 12, 0.3) + acc_result = np.zeros((acc.shape[0], v_tests.shape[0])) + v_result = np.zeros((acc.shape[0], v_tests.shape[0])) + steer_result = np.zeros((acc.shape[0], v_tests.shape[0])) + for i in range(acc.shape[0]): + v_tests_tmp = v_tests - 0.1 * iter_times * acc[i] + for j in range(v_tests.shape[0]): + v_result[i, j], acc_result[i, j], steer_result[i, j] = self.sim( + v_tests_tmp[j], acc[i], acc[i], starting_steer, target_steer, iter_times + ) + fig = plt.figure() + ax = fig.add_subplot(111, projection="3d") + ax.plot_surface(np.tile(acc, (v_tests.shape[0], 1)).T, v_result, acc_result) + ax.set_xlabel("acc_input [m/s^2]") + ax.set_ylabel("vel [m/s]") + ax.set_zlabel("acc_sim [m/s^2]") + fig.suptitle(str(iter_times * drive_functions.mpc_time_step) + " sec simulation") + plt.show() + + def plot_steer_map(self, iter_times: int, starting_acc=0.0, target_acc=0.0) -> None: + """Run `sim` `iter_times` times. The simulation time is approximately 0.1*iter_times. + + Draw the resulting steer map. + """ + steer = np.arange(-1, 1, 0.05) + v_tests = np.arange(0, 12, 0.3) + acc_result = np.zeros((steer.shape[0], v_tests.shape[0])) + v_result = np.zeros((steer.shape[0], v_tests.shape[0])) + steer_result = np.zeros((steer.shape[0], v_tests.shape[0])) + for i in range(steer.shape[0]): + for j in range(v_tests.shape[0]): + v_result[i, j], acc_result[i, j], steer_result[i, j] = self.sim( + v_tests[j], starting_acc, target_acc, steer[i], steer[i], iter_times + ) + fig = plt.figure() + ax = fig.add_subplot(111, projection="3d") + ax.plot_surface(np.tile(steer, (v_tests.shape[0], 1)).T, v_result, steer_result) + ax.set_xlabel("steer_input [rad]") + ax.set_ylabel("vel [m/s]") + ax.set_zlabel("steer_sim [rad]") + fig.suptitle(str(iter_times * drive_functions.mpc_time_step) + " sec simulation") + plt.show() + + +def polynomial_regression( + X, + Y, + alpha_1, + alpha_2, + use_polynomial_reg, + use_selected_polynomial, + deg, + fit_intercept, + use_intercept, +): + polynomial_features = PolynomialFeatures(degree=deg, include_bias=False) + alpha = alpha_1 + alpha_2 + if use_polynomial_reg: + if use_selected_polynomial: + clf_1 = linear_model.ElasticNet( + fit_intercept=fit_intercept, alpha=alpha, l1_ratio=alpha_1 / alpha, max_iter=100000 + ) + clf_2 = linear_model.ElasticNet( + fit_intercept=fit_intercept, alpha=alpha, l1_ratio=alpha_1 / alpha, max_iter=100000 + ) + clf_3 = linear_model.ElasticNet( + fit_intercept=fit_intercept, alpha=alpha, l1_ratio=alpha_1 / alpha, max_iter=100000 + ) + X_poly = polynomial_features.fit_transform(X[:, ctrl_index_for_polynomial_reg]) + Y_error = Y.copy() + A = np.zeros((Y.shape[1], X_poly.shape[1])) + b = np.zeros(Y.shape[1]) + clf_1.fit(X_poly[:, [0, 7]], Y[:, [3]]) + clf_2.fit(X_poly[:, [1, 3]], Y[:, [4]]) + clf_3.fit(X_poly[:, [2, 4]], Y[:, [5]]) + A[3, [0, 7]] = clf_1.coef_ + A[4, [1, 3]] = clf_2.coef_ + A[5, [2, 4]] = clf_3.coef_ + if fit_intercept: + b[3] = clf_1.intercept_ + b[4] = clf_2.intercept_ + b[5] = clf_3.intercept_ + Y_error[:, 3] -= clf_1.predict(X_poly[:, [0, 7]]) + Y_error[:, 4] -= clf_2.predict(X_poly[:, [1, 3]]) + Y_error[:, 5] -= clf_3.predict(X_poly[:, [2, 4]]) + if not use_intercept: + Y_error += b + b = 0 * b + return A, b, Y_error + else: + clf = linear_model.ElasticNet( + fit_intercept=fit_intercept, alpha=alpha, l1_ratio=alpha_1 / alpha, max_iter=100000 + ) + X_poly = polynomial_features.fit_transform(X[:, ctrl_index_for_polynomial_reg]) + clf.fit(X_poly, Y) + if fit_intercept: + if use_intercept: + return ( + clf.coef_, + clf.intercept_, + Y - clf.predict(X_poly), + ) + else: + return ( + clf.coef_, + 0 * clf.intercept_, + Y - clf.predict(X_poly) + clf.intercept_, + ) + else: + return clf.coef_, np.zeros(Y.shape[1]), Y - clf.predict(X_poly) + else: + poly_dim = polynomial_features.fit_transform( + X[0, ctrl_index_for_polynomial_reg].reshape(1, -1) + ).shape[1] + return np.zeros((Y.shape[1], poly_dim)), np.zeros(Y.shape[1]), Y diff --git a/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index 2ef2e07367f81..77140b0e0f630 100644 --- a/launch/tier4_control_launch/launch/control.launch.py +++ b/launch/tier4_control_launch/launch/control.launch.py @@ -24,6 +24,7 @@ from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.actions import LoadComposableNodes +from launch_ros.actions import Node from launch_ros.actions import PushRosNamespace from launch_ros.descriptions import ComposableNode from launch_ros.substitutions import FindPackageShare @@ -65,6 +66,7 @@ def launch_setup(context, *args, **kwargs): aeb_param = yaml.safe_load(f)["/**"]["ros__parameters"] with open(LaunchConfiguration("predicted_path_checker_param_path").perform(context), "r") as f: predicted_path_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"] + trajectory_follower_mode = LaunchConfiguration("trajectory_follower_mode").perform(context) controller_component = ComposableNode( package="trajectory_follower_node", @@ -328,20 +330,40 @@ def launch_setup(context, *args, **kwargs): ) # set container to run all required components in the same process - container = ComposableNodeContainer( - name="control_container", - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[ - controller_component, - lane_departure_component, - shift_decider_component, - vehicle_cmd_gate_component, - operation_mode_transition_manager_component, - glog_component, - ], - ) + if trajectory_follower_mode == "trajectory_follower_node": + container = ComposableNodeContainer( + name="control_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[ + controller_component, + lane_departure_component, + shift_decider_component, + vehicle_cmd_gate_component, + operation_mode_transition_manager_component, + glog_component, + ], + ) + + elif trajectory_follower_mode == "smart_mpc_trajectory_follower": + container = ComposableNodeContainer( + name="control_container", + namespace="", + package="rclcpp_components", + executable=LaunchConfiguration("container_executable"), + composable_node_descriptions=[ + lane_departure_component, + shift_decider_component, + vehicle_cmd_gate_component, + operation_mode_transition_manager_component, + glog_component, + ], + ) + else: + raise Exception( + f"The argument trajectory_follower_mode must be either trajectory_follower_node or smart_mpc_trajectory_follower, but {trajectory_follower_mode} was given." + ) # control evaluator control_evaluator_component = ComposableNode( @@ -408,7 +430,16 @@ def launch_setup(context, *args, **kwargs): ), ] ) - return [group, control_validator_group] + + smart_mpc_trajectory_follower = Node( + package="smart_mpc_trajectory_follower", + executable="pympc_trajectory_follower.py", + name="pympc_trajectory_follower", + ) + if trajectory_follower_mode == "trajectory_follower_node": + return [group, control_validator_group] + elif trajectory_follower_mode == "smart_mpc_trajectory_follower": + return [group, control_validator_group, smart_mpc_trajectory_follower] def generate_launch_description(): @@ -447,11 +478,17 @@ def add_launch_arg(name: str, default_value=None, description=None): # component add_launch_arg("use_intra_process", "false", "use ROS 2 component container communication") add_launch_arg("use_multithread", "true", "use multithread") + add_launch_arg( + "trajectory_follower_mode", + "trajectory_follower_node", + "Options for which trajectory_follower to use. Options: `trajectory_follower_node`, `smart_mpc_trajectory_follower`", + ) set_container_executable = SetLaunchConfiguration( "container_executable", "component_container", condition=UnlessCondition(LaunchConfiguration("use_multithread")), ) + set_container_mt_executable = SetLaunchConfiguration( "container_executable", "component_container_mt", From 2ae1716b909ebb824f0c91bde30ace82c5b4fe91 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 14 May 2024 18:33:35 +0900 Subject: [PATCH 169/192] perf(behavior_path_dynamic_avoidance_module): use const reference (#6981) * perf(behavior_path_dynamic_avoidance_module): use const reference Signed-off-by: Ryuta Kambe * style(pre-commit): autofix * add const to the other args --------- Signed-off-by: Ryuta Kambe Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> --- .../src/scene.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp b/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp index 84871ed756e81..a5368732ef3bb 100644 --- a/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp @@ -1799,11 +1799,11 @@ DynamicAvoidanceModule::EgoPathReservePoly DynamicAvoidanceModule::calcEgoPathRe ego_path_lines.push_back(tier4_autoware_utils::fromMsg(path_point.point.pose.position).to_2d()); } - auto calcReservePoly = - [&ego_path_lines]( - strategy::distance_asymmetric path_expand_strategy, - strategy::distance_asymmetric steer_expand_strategy, - std::vector outer_body_path) -> tier4_autoware_utils::Polygon2d { + auto calcReservePoly = [&ego_path_lines]( + const strategy::distance_asymmetric path_expand_strategy, + const strategy::distance_asymmetric steer_expand_strategy, + const std::vector & outer_body_path) + -> tier4_autoware_utils::Polygon2d { // reserve area based on the reference path tier4_autoware_utils::MultiPolygon2d path_poly; boost::geometry::buffer( From a4bb1779f58057e555f0ada96246628a9d75faad Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 14 May 2024 19:06:59 +0900 Subject: [PATCH 170/192] refactor(turn_signal_decider): straddle bound method (#7006) * refactor straddle bound method Signed-off-by: Daniel Sanchez * remove parenthesis Signed-off-by: Daniel Sanchez * add alias for inner lambda Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../turn_signal_decider.hpp | 34 +++++++++---------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp index fe187567cd893..29fe05775739e 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp @@ -228,23 +228,23 @@ class TurnSignalDecider using tier4_autoware_utils::transformVector; const auto footprint = vehicle_info.createFootprint(); - - for (const auto & lane : lanes) { - for (size_t i = shift_line.start_idx; i < shift_line.end_idx; ++i) { - const auto transform = pose2transform(path.path.points.at(i).point.pose); - const auto shifted_vehicle_footprint = transformVector(footprint, transform); - - if (intersects(lane.leftBound2d().basicLineString(), shifted_vehicle_footprint)) { - return true; - } - - if (intersects(lane.rightBound2d().basicLineString(), shifted_vehicle_footprint)) { - return true; - } - } - } - - return false; + const auto start_itr = std::next(path.path.points.begin(), shift_line.start_idx); + const auto end_itr = std::next(path.path.points.begin(), shift_line.end_idx); + + return std::any_of(start_itr, end_itr, [&footprint, &lanes](const auto & point) { + const auto transform = pose2transform(point.point.pose); + const auto shifted_vehicle_footprint = transformVector(footprint, transform); + + auto check_for_vehicle_and_bound_intersection = + [&shifted_vehicle_footprint](const auto & lane) { + const auto & left_bound = lane.leftBound2d().basicLineString(); + const auto & right_bound = lane.rightBound2d().basicLineString(); + return intersects(left_bound, shifted_vehicle_footprint) || + intersects(right_bound, shifted_vehicle_footprint); + }; + + return std::any_of(lanes.begin(), lanes.end(), check_for_vehicle_and_bound_intersection); + }); }; inline bool isNearEndOfShift( From ea009b89c7cb0e070ef8d5010e886e31fdcae4f0 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 14 May 2024 22:31:06 +0900 Subject: [PATCH 171/192] feat(goal_planner): reject candidate path whose start pose direction is not aligned with ego path (#6935) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 3 ++- .../src/goal_planner_module.cpp | 27 ++++++++++++++++--- 2 files changed, 26 insertions(+), 4 deletions(-) diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp index 818aa7ff79edb..8f456a57e4c78 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -582,7 +582,8 @@ class GoalPlannerModule : public SceneModuleInterface void updateStatus(const BehaviorModuleOutput & output); // validation - bool hasEnoughDistance(const PullOverPath & pull_over_path) const; + bool hasEnoughDistance( + const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const; bool isCrossingPossible( const lanelet::ConstLanelet & start_lane, const lanelet::ConstLanelet & end_lane) const; bool isCrossingPossible( diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index ef3de3b0363ce..9bfef90668e8e 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -936,6 +936,26 @@ std::optional> GoalPlannerModule::selectP const std::vector & pull_over_path_candidates, const GoalCandidates & goal_candidates, const double collision_check_margin) const { + const auto & goal_pose = planner_data_->route_handler->getOriginalGoalPose(); + const double backward_length = + parameters_->backward_goal_search_length + parameters_->decide_path_distance; + const auto & prev_module_output_path = getPreviousModuleOutput().path; + const double prev_path_front_to_goal_dist = calcSignedArcLength( + prev_module_output_path.points, prev_module_output_path.points.front().point.pose.position, + goal_pose.position); + const auto & long_tail_reference_path = [&]() { + if (prev_path_front_to_goal_dist > backward_length) { + return prev_module_output_path; + } + // get road lanes which is at least backward_length[m] behind the goal + const auto road_lanes = utils::getExtendedCurrentLanesFromPath( + prev_module_output_path, planner_data_, backward_length, 0.0, + /*forward_only_in_route*/ false); + const auto goal_pose_length = lanelet::utils::getArcCoordinates(road_lanes, goal_pose).length; + return planner_data_->route_handler->getCenterLinePath( + road_lanes, std::max(0.0, goal_pose_length - backward_length), + goal_pose_length + parameters_->forward_goal_search_length); + }(); for (const auto & pull_over_path : pull_over_path_candidates) { // check if goal is safe const auto goal_candidate_it = std::find_if( @@ -947,7 +967,7 @@ std::optional> GoalPlannerModule::selectP continue; } - if (!hasEnoughDistance(pull_over_path)) { + if (!hasEnoughDistance(pull_over_path, long_tail_reference_path)) { continue; } @@ -1873,7 +1893,8 @@ bool GoalPlannerModule::checkObjectsCollision( return utils::path_safety_checker::checkPolygonsIntersects(ego_polygons_expanded, obj_polygons); } -bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) const +bool GoalPlannerModule::hasEnoughDistance( + const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const { const Pose & current_pose = planner_data_->self_odometry->pose.pose; const double current_vel = planner_data_->self_odometry->twist.twist.linear.x; @@ -1885,7 +1906,7 @@ bool GoalPlannerModule::hasEnoughDistance(const PullOverPath & pull_over_path) c // otherwise, the goal would change immediately after departure. const bool is_separated_path = pull_over_path.partial_paths.size() > 1; const double distance_to_start = calcSignedArcLength( - pull_over_path.getFullPath().points, current_pose.position, pull_over_path.start_pose.position); + long_tail_reference_path.points, current_pose.position, pull_over_path.start_pose.position); const double distance_to_restart = parameters_->decide_path_distance / 2; const double eps_vel = 0.01; const bool is_stopped = std::abs(current_vel) < eps_vel; From 006b40eb76cc03f6fc81306ddb9458b97a97ac64 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 15 May 2024 10:57:09 +0900 Subject: [PATCH 172/192] refactor(behavior_velocity_planner_common): move VelocityFactorInterface to motion_utils (#7007) Signed-off-by: Maxime CLEMENT --- common/motion_utils/CMakeLists.txt | 10 +------ .../factor}/velocity_factor_interface.hpp | 28 ++++++++----------- common/motion_utils/package.xml | 1 + .../src/factor}/velocity_factor_interface.cpp | 13 +++++---- .../src/scene_intersection.cpp | 2 ++ .../CMakeLists.txt | 1 - .../scene_module_interface.hpp | 6 ++-- 7 files changed, 27 insertions(+), 34 deletions(-) rename {planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common => common/motion_utils/include/motion_utils/factor}/velocity_factor_interface.hpp (67%) rename {planning/behavior_velocity_planner_common/src => common/motion_utils/src/factor}/velocity_factor_interface.cpp (77%) diff --git a/common/motion_utils/CMakeLists.txt b/common/motion_utils/CMakeLists.txt index f42deaa7f8c41..cd81f16685d72 100644 --- a/common/motion_utils/CMakeLists.txt +++ b/common/motion_utils/CMakeLists.txt @@ -7,15 +7,7 @@ autoware_package() find_package(Boost REQUIRED) ament_auto_add_library(motion_utils SHARED - src/distance/distance.cpp - src/marker/marker_helper.cpp - src/marker/virtual_wall_marker_creator.cpp - src/resample/resample.cpp - src/trajectory/trajectory.cpp - src/trajectory/interpolation.cpp - src/trajectory/path_with_lane_id.cpp - src/trajectory/conversion.cpp - src/vehicle/vehicle_state_checker.cpp + DIRECTORY src ) if(BUILD_TESTING) diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp b/common/motion_utils/include/motion_utils/factor/velocity_factor_interface.hpp similarity index 67% rename from planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp rename to common/motion_utils/include/motion_utils/factor/velocity_factor_interface.hpp index eea45ec03807d..fdfd3a25eb3ad 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/velocity_factor_interface.hpp +++ b/common/motion_utils/include/motion_utils/factor/velocity_factor_interface.hpp @@ -1,5 +1,5 @@ -// Copyright 2022 TIER IV, Inc. +// Copyright 2022-2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -13,8 +13,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ -#define BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ +#ifndef MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ +#define MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ #include #include @@ -25,35 +25,31 @@ #include #include -namespace behavior_velocity_planner +namespace motion_utils { - using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; -using autoware_adapi_v1_msgs::msg::VelocityFactorArray; -using geometry_msgs::msg::Pose; using VelocityFactorBehavior = VelocityFactor::_behavior_type; using VelocityFactorStatus = VelocityFactor::_status_type; +using geometry_msgs::msg::Pose; class VelocityFactorInterface { public: - VelocityFactorInterface() { behavior_ = VelocityFactor::UNKNOWN; } - - VelocityFactor get() const { return velocity_factor_; } - void init(const VelocityFactorBehavior behavior) { behavior_ = behavior; } + [[nodiscard]] VelocityFactor get() const { return velocity_factor_; } + void init(const VelocityFactorBehavior & behavior) { behavior_ = behavior; } void reset() { velocity_factor_.behavior = PlanningBehavior::UNKNOWN; } void set( const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status, - const std::string detail = ""); + const std::string & detail = ""); private: - VelocityFactorBehavior behavior_; - VelocityFactor velocity_factor_; + VelocityFactorBehavior behavior_{VelocityFactor::UNKNOWN}; + VelocityFactor velocity_factor_{}; }; -} // namespace behavior_velocity_planner +} // namespace motion_utils -#endif // BEHAVIOR_VELOCITY_PLANNER_COMMON__VELOCITY_FACTOR_INTERFACE_HPP_ +#endif // MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_ diff --git a/common/motion_utils/package.xml b/common/motion_utils/package.xml index 5f630572c061c..dec5287b0a520 100644 --- a/common/motion_utils/package.xml +++ b/common/motion_utils/package.xml @@ -21,6 +21,7 @@ ament_cmake_auto autoware_cmake + autoware_adapi_v1_msgs autoware_auto_planning_msgs autoware_auto_vehicle_msgs builtin_interfaces diff --git a/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp b/common/motion_utils/src/factor/velocity_factor_interface.cpp similarity index 77% rename from planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp rename to common/motion_utils/src/factor/velocity_factor_interface.cpp index 7bc46846afb83..eabd00fae85d6 100644 --- a/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp +++ b/common/motion_utils/src/factor/velocity_factor_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// Copyright 2023-2024 TIER IV, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,23 +12,24 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include -namespace behavior_velocity_planner +namespace motion_utils { void VelocityFactorInterface::set( const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status, - const std::string detail) + const std::string & detail) { const auto & curr_point = curr_pose.position; const auto & stop_point = stop_pose.position; velocity_factor_.behavior = behavior_; velocity_factor_.pose = stop_pose; - velocity_factor_.distance = motion_utils::calcSignedArcLength(points, curr_point, stop_point); + velocity_factor_.distance = + static_cast(motion_utils::calcSignedArcLength(points, curr_point, stop_point)); velocity_factor_.status = status; velocity_factor_.detail = detail; } -} // namespace behavior_velocity_planner +} // namespace motion_utils diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 9d0c0c8e1defb..08e2d38a5905f 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include // for toPolygon2d #include @@ -44,6 +45,7 @@ namespace bg = boost::geometry; using intersection::make_err; using intersection::make_ok; using intersection::Result; +using motion_utils::VelocityFactorInterface; IntersectionModule::IntersectionModule( const int64_t module_id, const int64_t lane_id, diff --git a/planning/behavior_velocity_planner_common/CMakeLists.txt b/planning/behavior_velocity_planner_common/CMakeLists.txt index e958df74afe2d..c8847164851e8 100644 --- a/planning/behavior_velocity_planner_common/CMakeLists.txt +++ b/planning/behavior_velocity_planner_common/CMakeLists.txt @@ -6,7 +6,6 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/scene_module_interface.cpp - src/velocity_factor_interface.cpp src/utilization/path_utilization.cpp src/utilization/trajectory_utils.cpp src/utilization/arc_lane_util.cpp diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp index 082a88e306169..27db42d36f08b 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp @@ -16,8 +16,8 @@ #define BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ #include -#include #include +#include #include #include #include @@ -50,6 +50,8 @@ namespace behavior_velocity_planner using autoware_auto_planning_msgs::msg::PathWithLaneId; using builtin_interfaces::msg::Time; +using motion_utils::PlanningBehavior; +using motion_utils::VelocityFactor; using objects_of_interest_marker_interface::ColorName; using objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using rtc_interface::RTCInterface; @@ -128,7 +130,7 @@ class SceneModuleInterface std::shared_ptr planner_data_; std::optional infrastructure_command_; std::optional first_stop_path_point_index_; - VelocityFactorInterface velocity_factor_; + motion_utils::VelocityFactorInterface velocity_factor_; std::vector objects_of_interest_; void setSafe(const bool safe) From d0cfc9af5cf2971d698f440f833e1a1a738512bf Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 15 May 2024 12:13:35 +0900 Subject: [PATCH 173/192] fix(start_planner): issue when ego does not straddle lane bounds and starts from 0 speed (#7004) * fix issue when ego does not straddle lane bounds and starts from 0 speed Signed-off-by: Daniel Sanchez * add new status for ego departed Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../src/turn_signal_decider.cpp | 5 ++++- .../start_planner_module.hpp | 2 ++ .../src/start_planner_module.cpp | 16 ++++++++++++++-- 3 files changed, 20 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp index 320cc96577187..21937aa76da29 100644 --- a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp @@ -731,10 +731,13 @@ std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( return std::make_pair(TurnSignalInfo{}, true); } - if (!straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) { + // Check if the ego will cross lane bounds. + // Note that pull out requires blinkers, even if the ego does not cross lane bounds + if (!is_pull_out && !straddleRoadBound(path, shift_line, current_lanelets, p.vehicle_info)) { return std::make_pair(TurnSignalInfo{}, true); } + // If the ego has stopped and its close to completing its shift, turn off the blinkers constexpr double STOPPED_THRESHOLD = 0.1; // [m/s] if (ego_speed < STOPPED_THRESHOLD && !override_ego_stopped_check) { if (isNearEndOfShift( diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp index c05b7a8f94716..591d8adb60819 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/start_planner_module.hpp @@ -74,6 +74,8 @@ struct PullOutStatus //! record the first time when ego started forward-driving (maybe after backward driving //! completion) in AUTONOMOUS operation mode std::optional first_engaged_and_driving_forward_time{std::nullopt}; + // record if the ego has departed from the start point + bool has_departed{false}; PullOutStatus() {} }; diff --git a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp index bee3fb16595b7..280e1112ef7fb 100644 --- a/planning/behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_start_planner_module/src/start_planner_module.cpp @@ -247,6 +247,13 @@ void StartPlannerModule::updateData() status_.first_engaged_and_driving_forward_time = clock_->now(); } + constexpr double moving_velocity_threshold = 0.1; + const double & ego_velocity = planner_data_->self_odometry->twist.twist.linear.x; + if (status_.first_engaged_and_driving_forward_time && ego_velocity > moving_velocity_threshold) { + // Ego is engaged, and has moved + status_.has_departed = true; + } + status_.backward_driving_complete = hasFinishedBackwardDriving(); if (status_.backward_driving_complete) { updateStatusAfterBackwardDriving(); @@ -1265,8 +1272,10 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() // In Geometric pull out, the ego stops once and then steers the wheels to the opposite direction. // This sometimes causes the getBehaviorTurnSignalInfo method to detect the ego as stopped and // close to complete its shift, so it wrongly turns off the blinkers, this override helps avoid - // this issue. - const bool override_ego_stopped_check = std::invoke([&]() { + // this issue. Also, if the ego is not engaged (so it is stopped), the blinkers should still be + // activated. + + const bool geometric_planner_has_not_finished_first_path = std::invoke([&]() { if (status_.planner_type != PlannerType::GEOMETRIC) { return false; } @@ -1277,6 +1286,9 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() return distance_from_ego_to_stop_point < distance_threshold; }); + const bool override_ego_stopped_check = + !status_.has_departed || geometric_planner_has_not_finished_first_path; + const auto [new_signal, is_ignore] = planner_data_->getBehaviorTurnSignalInfo( path, shift_start_idx, shift_end_idx, current_lanes, current_shift_length, status_.driving_forward, egos_lane_is_shifted, override_ego_stopped_check, is_pull_out); From 2297b0ce85a08cd983b16b07a447c4e4778c5802 Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Wed, 15 May 2024 16:26:30 +0900 Subject: [PATCH 174/192] chore(simple_planning_simulator): publish control mode before the self-position is given (#7008) Signed-off-by: tomoya.kimura --- .../simple_planning_simulator/simple_planning_simulator_core.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 524597e927f61..7fba0431706f0 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -358,6 +358,7 @@ double SimplePlanningSimulator::calculate_ego_pitch() const void SimplePlanningSimulator::on_timer() { if (!is_initialized_) { + publish_control_mode_report(); RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 5000, "waiting initialization..."); return; } From d7c22887471808d449d69e5732783f56758494a5 Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Wed, 15 May 2024 18:13:35 +0900 Subject: [PATCH 175/192] feat: componentize-system_error_monitor (#7009) * feat: componentize-system_error_monitor Signed-off-by: TetsuKawa * modify: componentize-system_error_monitor Signed-off-by: TetsuKawa * feat: add explicit Signed-off-by: TetsuKawa --------- Signed-off-by: TetsuKawa --- system/system_error_monitor/CMakeLists.txt | 7 +++-- .../system_error_monitor_core.hpp | 2 +- .../system_error_monitor_node.launch.xml | 2 +- system/system_error_monitor/package.xml | 1 + .../src/system_error_monitor_core.cpp | 7 +++-- .../src/system_error_monitor_node.cpp | 27 ------------------- 6 files changed, 13 insertions(+), 33 deletions(-) delete mode 100644 system/system_error_monitor/src/system_error_monitor_node.cpp diff --git a/system/system_error_monitor/CMakeLists.txt b/system/system_error_monitor/CMakeLists.txt index 36edf5816f6d3..91e9e20146327 100644 --- a/system/system_error_monitor/CMakeLists.txt +++ b/system/system_error_monitor/CMakeLists.txt @@ -4,11 +4,14 @@ project(system_error_monitor) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(${PROJECT_NAME} - src/system_error_monitor_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/system_error_monitor_core.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "AutowareErrorMonitor" + EXECUTABLE ${PROJECT_NAME}_node) + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp index 4dbf8813805e3..8829bcc1edde2 100644 --- a/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp +++ b/system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp @@ -64,7 +64,7 @@ struct KeyName class AutowareErrorMonitor : public rclcpp::Node { public: - AutowareErrorMonitor(); + explicit AutowareErrorMonitor(const rclcpp::NodeOptions & options); private: // Parameter diff --git a/system/system_error_monitor/launch/system_error_monitor_node.launch.xml b/system/system_error_monitor/launch/system_error_monitor_node.launch.xml index 6741b4f22ce48..f5ed927c7d6ca 100644 --- a/system/system_error_monitor/launch/system_error_monitor_node.launch.xml +++ b/system/system_error_monitor/launch/system_error_monitor_node.launch.xml @@ -11,7 +11,7 @@ - + diff --git a/system/system_error_monitor/package.xml b/system/system_error_monitor/package.xml index c6560209854d3..ed50eda95611a 100644 --- a/system/system_error_monitor/package.xml +++ b/system/system_error_monitor/package.xml @@ -15,6 +15,7 @@ diagnostic_msgs fmt rclcpp + rclcpp_components std_srvs tier4_autoware_utils tier4_control_msgs diff --git a/system/system_error_monitor/src/system_error_monitor_core.cpp b/system/system_error_monitor/src/system_error_monitor_core.cpp index fb0a607b9825a..e4ca33204f53e 100644 --- a/system/system_error_monitor/src/system_error_monitor_core.cpp +++ b/system/system_error_monitor/src/system_error_monitor_core.cpp @@ -202,10 +202,10 @@ int isInNoFaultCondition( } } // namespace -AutowareErrorMonitor::AutowareErrorMonitor() +AutowareErrorMonitor::AutowareErrorMonitor(const rclcpp::NodeOptions & options) : Node( "system_error_monitor", - rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true)), + rclcpp::NodeOptions(options).automatically_declare_parameters_from_overrides(true)), diag_array_stamp_(0, 0, this->get_clock()->get_clock_type()), autoware_state_stamp_(0, 0, this->get_clock()->get_clock_type()), current_gate_mode_stamp_(0, 0, this->get_clock()->get_clock_type()), @@ -720,3 +720,6 @@ void AutowareErrorMonitor::loggingErrors( logger_name, get_clock(), 5000, "[Single Point Fault]: " + hazard_diag.message); } } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(AutowareErrorMonitor) diff --git a/system/system_error_monitor/src/system_error_monitor_node.cpp b/system/system_error_monitor/src/system_error_monitor_node.cpp deleted file mode 100644 index f389497b93a43..0000000000000 --- a/system/system_error_monitor/src/system_error_monitor_node.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// Copyright 2020 Tier IV, Inc. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "system_error_monitor/system_error_monitor_core.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - - return 0; -} From 23d103f635f787f72085e5a23a15bab358b50493 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 15 May 2024 19:08:43 +0900 Subject: [PATCH 176/192] refactor(autoware_planning_test_manager): rename package (#6995) * refactor(autoware_planning_test_manager): rename package Signed-off-by: Zulfaqar Azmi * rename file Signed-off-by: Zulfaqar Azmi * Add maintainer for planning test utils Signed-off-by: Muhammad Zulfaqar Azmi * Add route handler back into package.xml Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Signed-off-by: Muhammad Zulfaqar Azmi --- .../CMakeLists.txt | 11 +++ .../autoware_planning_test_manager/README.md | 92 +++++++++++++++++++ .../autoware_planning_test_manager.hpp} | 6 +- .../package.xml | 47 ++++++++++ .../src/autoware_planning_test_manager.cpp} | 4 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- planning/behavior_path_planner/package.xml | 2 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- .../package.xml | 2 +- ...t_behavior_path_planner_node_interface.cpp | 4 +- .../test/src/test_node_interface.cpp | 4 +- planning/freespace_planner/package.xml | 2 +- .../test_freespace_planner_node_interface.cpp | 4 +- planning/motion_velocity_smoother/package.xml | 2 +- ...otion_velocity_smoother_node_interface.cpp | 4 +- .../obstacle_avoidance_planner/package.xml | 2 +- ...tacle_avoidance_planner_node_interface.cpp | 4 +- planning/obstacle_cruise_planner/package.xml | 2 +- ...obstacle_cruise_planner_node_interface.cpp | 4 +- planning/obstacle_stop_planner/package.xml | 2 +- ...t_obstacle_stop_planner_node_interface.cpp | 4 +- .../obstacle_velocity_limiter/package.xml | 2 +- ...stacle_velocity_limiter_node_interface.cpp | 4 +- planning/path_smoother/package.xml | 2 +- .../test_path_smoother_node_interface.cpp | 4 +- planning/planning_test_utils/CMakeLists.txt | 4 - planning/planning_test_utils/README.md | 2 +- ...ager_utils.hpp => planning_test_utils.hpp} | 6 +- planning/planning_test_utils/package.xml | 2 + planning/planning_validator/package.xml | 2 +- ...test_planning_validator_node_interface.cpp | 4 +- planning/scenario_selector/package.xml | 2 +- .../test_scenario_selector_node_interface.cpp | 4 +- 37 files changed, 206 insertions(+), 58 deletions(-) create mode 100644 planning/autoware_planning_test_manager/CMakeLists.txt create mode 100644 planning/autoware_planning_test_manager/README.md rename planning/{planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp => autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp} (98%) create mode 100644 planning/autoware_planning_test_manager/package.xml rename planning/{planning_test_utils/src/planning_interface_test_manager.cpp => autoware_planning_test_manager/src/autoware_planning_test_manager.cpp} (99%) rename planning/planning_test_utils/include/planning_test_utils/{planning_interface_test_manager_utils.hpp => planning_test_utils.hpp} (98%) diff --git a/planning/autoware_planning_test_manager/CMakeLists.txt b/planning/autoware_planning_test_manager/CMakeLists.txt new file mode 100644 index 0000000000000..1f0a62aae0026 --- /dev/null +++ b/planning/autoware_planning_test_manager/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_planning_test_manager) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(autoware_planning_test_manager SHARED + src/autoware_planning_test_manager.cpp +) + +ament_auto_package() diff --git a/planning/autoware_planning_test_manager/README.md b/planning/autoware_planning_test_manager/README.md new file mode 100644 index 0000000000000..63f1bf53a4954 --- /dev/null +++ b/planning/autoware_planning_test_manager/README.md @@ -0,0 +1,92 @@ +# Planning Interface Test Manager + +## Background + +In each node of the planning module, when exceptional input, such as unusual routes or significantly deviated ego-position, is given, the node may not be prepared for such input and could crash. As a result, debugging node crashes can be time-consuming. For example, if an empty trajectory is given as input and it was not anticipated during implementation, the node might crash due to the unaddressed exceptional input when changes are merged, during scenario testing or while the system is running on an actual vehicle. + +## Purpose + +The purpose is to provide a utility for implementing tests to ensure that node operates correctly when receiving exceptional input. By utilizing this utility and implementing tests for exceptional input, the purpose is to reduce bugs that are only discovered when actually running the system, by requiring measures for exceptional input before merging PRs. + +## Features + +### Confirmation of normal operation + +For the test target node, confirm that the node operates correctly and publishes the required messages for subsequent nodes. To do this, test_node publish the necessary messages and confirm that the node's output is being published. + +### Robustness confirmation for special inputs + +After confirming normal operation, ensure that the test target node does not crash when given exceptional input. To do this, provide exceptional input from the test_node and confirm that the node does not crash. + +(WIP) + +## Usage + +```cpp + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) +{ + rclcpp::init(0, nullptr); + + // instantiate test_manager with PlanningInterfaceTestManager type + auto test_manager = std::make_shared(); + + // get package directories for necessary configuration files + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto target_node_dir = + ament_index_cpp::get_package_share_directory("target_node"); + + // set arguments to get the config file + node_options.arguments( + {"--ros-args", "--params-file", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file", + planning_validator_dir + "/config/planning_validator.param.yaml"}); + + // instantiate the TargetNode with node_options + auto test_target_node = std::make_shared(node_options); + + // publish the necessary topics from test_manager second argument is topic name + test_manager->publishOdometry(test_target_node, "/localization/kinematic_state"); + test_manager->publishMaxVelocity( + test_target_node, "motion_velocity_smoother/input/external_velocity_limit_mps"); + + // set scenario_selector's input topic name(this topic is changed to test node) + test_manager->setTrajectoryInputTopicName("input/parking/trajectory"); + + // test with normal trajectory + ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node)); + + // make sure target_node is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with trajectory input with empty/one point/overlapping point + ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node)); + + // shutdown ROS context + rclcpp::shutdown(); +} +``` + +## Implemented tests + +| Node | Test name | exceptional input | output | Exceptional input pattern | +| -------------------------- | ----------------------------------------------------------------------------------------- | ----------------- | -------------- | ------------------------------------------------------------------------------------- | +| planning_validator | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| motion_velocity_smoother | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_cruise_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_stop_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_velocity_limiter | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| obstacle_avoidance_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points | +| scenario_selector | NodeTestWithExceptionTrajectoryLaneDrivingMode NodeTestWithExceptionTrajectoryParkingMode | trajectory | scenario | Empty, single point, path with duplicate points for scenarios:LANEDRIVING and PARKING | +| freespace_planner | NodeTestWithExceptionRoute | route | trajectory | Empty route | +| behavior_path_planner | NodeTestWithExceptionRoute NodeTestWithOffTrackEgoPose | route | route odometry | Empty route Off-lane ego-position | +| behavior_velocity_planner | NodeTestWithExceptionPathWithLaneID | path_with_lane_id | path | Empty path | + +## Important Notes + +During test execution, when launching a node, parameters are loaded from the parameter file within each package. Therefore, when adding parameters, it is necessary to add the required parameters to the parameter file in the target node package. This is to prevent the node from being unable to launch if there are missing parameters when retrieving them from the parameter file during node launch. + +## Future extensions / Unimplemented parts + +(WIP) diff --git a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp similarity index 98% rename from planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp rename to planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp index a63b0d02152f0..82636af20579d 100644 --- a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_ -#define PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_ +#ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_ +#define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_ // since ASSERT_NO_THROW in gtest masks the exception message, redefine it. #define ASSERT_NO_THROW_WITH_ERROR_MSG(statement) \ @@ -266,4 +266,4 @@ class PlanningInterfaceTestManager } // namespace planning_test_utils -#endif // PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_ +#endif // AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_ diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml new file mode 100644 index 0000000000000..e2c00756c2ba4 --- /dev/null +++ b/planning/autoware_planning_test_manager/package.xml @@ -0,0 +1,47 @@ + + + + autoware_planning_test_manager + 0.1.0 + ROS 2 node for testing interface of the nodes in planning module + Kyoichi Sugahara + Takamasa Horibe + Apache License 2.0 + + Kyoichi Sugahara + + ament_cmake_auto + autoware_cmake + + autoware_auto_control_msgs + autoware_auto_mapping_msgs + autoware_auto_planning_msgs + autoware_auto_vehicle_msgs + autoware_perception_msgs + autoware_planning_msgs + component_interface_specs + component_interface_utils + lanelet2_extension + lanelet2_io + motion_utils + nav_msgs + planning_test_utils + rclcpp + route_handler + tf2_msgs + tf2_ros + tier4_api_msgs + tier4_autoware_utils + tier4_planning_msgs + tier4_v2x_msgs + unique_identifier_msgs + yaml_cpp_vendor + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/planning_test_utils/src/planning_interface_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp similarity index 99% rename from planning/planning_test_utils/src/planning_interface_test_manager.cpp rename to planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 0a6b4246348eb..3aee408a76306 100644 --- a/planning/planning_test_utils/src/planning_interface_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -14,8 +14,8 @@ #include "motion_utils/trajectory/conversion.hpp" -#include -#include +#include +#include namespace planning_test_utils { diff --git a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 1167fa4414752..f66e944cb7cbc 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "behavior_path_planner/behavior_path_planner_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 8cf85554e2b2c..4ae77249b5d0f 100644 --- a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "behavior_path_planner/behavior_path_planner_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 16b4ffbc688ae..cf38a0b4993fe 100644 --- a/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "behavior_path_planner/behavior_path_planner_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 434988cc3ab08..1eb5118cd94b2 100644 --- a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -13,9 +13,9 @@ // limitations under the License. #include "ament_index_cpp/get_package_share_directory.hpp" +#include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_test_utils/planning_interface_test_manager.hpp" -#include "planning_test_utils/planning_interface_test_manager_utils.hpp" +#include "planning_test_utils/planning_test_utils.hpp" #include diff --git a/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 82f721411d5a4..7b36bf475646b 100644 --- a/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -13,9 +13,9 @@ // limitations under the License. #include "ament_index_cpp/get_package_share_directory.hpp" +#include "autoware_planning_test_manager/autoware_planning_test_manager.hpp" #include "behavior_path_planner/behavior_path_planner_node.hpp" -#include "planning_test_utils/planning_interface_test_manager.hpp" -#include "planning_test_utils/planning_interface_test_manager_utils.hpp" +#include "planning_test_utils/planning_test_utils.hpp" #include diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index f6bd82430c389..14220c09880de 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -42,6 +42,7 @@ autoware_auto_tf2 autoware_auto_vehicle_msgs autoware_perception_msgs + autoware_planning_test_manager behavior_path_planner_common freespace_planning_algorithms frenet_planner @@ -55,7 +56,6 @@ motion_utils object_recognition_utils path_sampler - planning_test_utils pluginlib rclcpp rclcpp_components diff --git a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp index 7ba934e873a8d..f8630a0c61973 100644 --- a/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/test/test_behavior_path_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "behavior_path_planner/behavior_path_planner_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/behavior_path_sampling_planner_module/package.xml b/planning/behavior_path_sampling_planner_module/package.xml index cfac87b3c557f..f016cb6de1e7c 100644 --- a/planning/behavior_path_sampling_planner_module/package.xml +++ b/planning/behavior_path_sampling_planner_module/package.xml @@ -18,6 +18,7 @@ autoware_auto_tf2 autoware_auto_vehicle_msgs autoware_perception_msgs + autoware_planning_test_manager behavior_path_planner_common bezier_sampler frenet_planner @@ -26,7 +27,6 @@ lanelet2_extension motion_utils path_sampler - planning_test_utils pluginlib rclcpp rclcpp_components diff --git a/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp index eb7d1afe27549..db1f5ee3560b1 100644 --- a/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "behavior_path_planner/behavior_path_planner_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp index 935530b52e175..f70259b6a1f80 100644 --- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/test/src/test_node_interface.cpp @@ -15,8 +15,8 @@ #include "node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/freespace_planner/package.xml b/planning/freespace_planner/package.xml index 22557f8a0bbb3..8ebb22fdb5c2f 100644 --- a/planning/freespace_planner/package.xml +++ b/planning/freespace_planner/package.xml @@ -16,11 +16,11 @@ autoware_cmake autoware_auto_planning_msgs + autoware_planning_test_manager freespace_planning_algorithms geometry_msgs motion_utils nav_msgs - planning_test_utils rclcpp rclcpp_components route_handler diff --git a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp index 013eb3c33cbad..881ce269a7895 100644 --- a/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp +++ b/planning/freespace_planner/test/test_freespace_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "freespace_planner/freespace_planner_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/motion_velocity_smoother/package.xml b/planning/motion_velocity_smoother/package.xml index 9792aa2bdd60b..b9b368d917535 100644 --- a/planning/motion_velocity_smoother/package.xml +++ b/planning/motion_velocity_smoother/package.xml @@ -21,12 +21,12 @@ eigen3_cmake_module autoware_auto_planning_msgs + autoware_planning_test_manager geometry_msgs interpolation motion_utils nav_msgs osqp_interface - planning_test_utils rclcpp tf2 tf2_ros diff --git a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp index 430f8b78ec88c..56813a37941a6 100644 --- a/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp +++ b/planning/motion_velocity_smoother/test/test_motion_velocity_smoother_node_interface.cpp @@ -15,8 +15,8 @@ #include "motion_velocity_smoother/motion_velocity_smoother_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/obstacle_avoidance_planner/package.xml b/planning/obstacle_avoidance_planner/package.xml index 81429368fc7e4..40caf7ef300aa 100644 --- a/planning/obstacle_avoidance_planner/package.xml +++ b/planning/obstacle_avoidance_planner/package.xml @@ -15,12 +15,12 @@ autoware_cmake autoware_auto_planning_msgs + autoware_planning_test_manager geometry_msgs interpolation motion_utils nav_msgs osqp_interface - planning_test_utils rclcpp rclcpp_components std_msgs diff --git a/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp b/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp index 9c567487e9cac..d5af4c7e1180f 100644 --- a/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp +++ b/planning/obstacle_avoidance_planner/test/test_obstacle_avoidance_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "obstacle_avoidance_planner/node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/obstacle_cruise_planner/package.xml b/planning/obstacle_cruise_planner/package.xml index f6263521bd337..eaba45a31869a 100644 --- a/planning/obstacle_cruise_planner/package.xml +++ b/planning/obstacle_cruise_planner/package.xml @@ -20,6 +20,7 @@ autoware_adapi_v1_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_planning_test_manager geometry_msgs interpolation lanelet2_extension @@ -27,7 +28,6 @@ nav_msgs object_recognition_utils osqp_interface - planning_test_utils rclcpp rclcpp_components signal_processing diff --git a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp index d412286d77d53..bd11effb774da 100644 --- a/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp +++ b/planning/obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "obstacle_cruise_planner/node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/obstacle_stop_planner/package.xml b/planning/obstacle_stop_planner/package.xml index 14cdd862bb41e..1a6f8433875ce 100644 --- a/planning/obstacle_stop_planner/package.xml +++ b/planning/obstacle_stop_planner/package.xml @@ -23,12 +23,12 @@ autoware_adapi_v1_msgs autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_planning_test_manager diagnostic_msgs motion_utils nav_msgs pcl_conversions pcl_ros - planning_test_utils rclcpp rclcpp_components sensor_msgs diff --git a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp index 7f986bf848777..4e846d9ff1417 100644 --- a/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp +++ b/planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp @@ -15,8 +15,8 @@ #include "obstacle_stop_planner/node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/obstacle_velocity_limiter/package.xml b/planning/obstacle_velocity_limiter/package.xml index 377f061faffd7..8c9c89094f5f0 100644 --- a/planning/obstacle_velocity_limiter/package.xml +++ b/planning/obstacle_velocity_limiter/package.xml @@ -13,6 +13,7 @@ autoware_auto_perception_msgs autoware_auto_planning_msgs + autoware_planning_test_manager eigen grid_map_msgs grid_map_ros @@ -23,7 +24,6 @@ motion_utils nav_msgs pcl_ros - planning_test_utils rclcpp rclcpp_components sensor_msgs diff --git a/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp b/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp index a89042ef210d5..fb7f9bb85e2c5 100644 --- a/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp +++ b/planning/obstacle_velocity_limiter/test/test_obstacle_velocity_limiter_node_interface.cpp @@ -15,8 +15,8 @@ #include "obstacle_velocity_limiter/obstacle_velocity_limiter_node.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/path_smoother/package.xml b/planning/path_smoother/package.xml index f0e0381f1706b..0cba14254e492 100644 --- a/planning/path_smoother/package.xml +++ b/planning/path_smoother/package.xml @@ -15,12 +15,12 @@ autoware_cmake autoware_auto_planning_msgs + autoware_planning_test_manager geometry_msgs interpolation motion_utils nav_msgs osqp_interface - planning_test_utils rclcpp rclcpp_components std_msgs diff --git a/planning/path_smoother/test/test_path_smoother_node_interface.cpp b/planning/path_smoother/test/test_path_smoother_node_interface.cpp index 3598e07f84fd6..30e9fba1433cb 100644 --- a/planning/path_smoother/test/test_path_smoother_node_interface.cpp +++ b/planning/path_smoother/test/test_path_smoother_node_interface.cpp @@ -15,8 +15,8 @@ #include "path_smoother/elastic_band_smoother.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/planning_test_utils/CMakeLists.txt b/planning/planning_test_utils/CMakeLists.txt index a192f1756b9be..29ee79c2cab1a 100644 --- a/planning/planning_test_utils/CMakeLists.txt +++ b/planning/planning_test_utils/CMakeLists.txt @@ -4,10 +4,6 @@ project(planning_test_utils) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(planning_test_utils SHARED - src/planning_interface_test_manager.cpp -) - ament_auto_package(INSTALL_TO_SHARE config test_map diff --git a/planning/planning_test_utils/README.md b/planning/planning_test_utils/README.md index 63f1bf53a4954..b72625be999dd 100644 --- a/planning/planning_test_utils/README.md +++ b/planning/planning_test_utils/README.md @@ -1,4 +1,4 @@ -# Planning Interface Test Manager +# Autoware Planning Test Manager ## Background diff --git a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp b/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp similarity index 98% rename from planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp rename to planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp index 371a6316ce993..7b52f3860592e 100644 --- a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp +++ b/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ -#define PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ +#ifndef PLANNING_TEST_UTILS__PLANNING_TEST_UTILS_HPP_ +#define PLANNING_TEST_UTILS__PLANNING_TEST_UTILS_HPP_ #include "ament_index_cpp/get_package_share_directory.hpp" #include "rclcpp/rclcpp.hpp" @@ -556,4 +556,4 @@ PathWithLaneId loadPathWithLaneIdInYaml() } // namespace test_utils -#endif // PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ +#endif // PLANNING_TEST_UTILS__PLANNING_TEST_UTILS_HPP_ diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml index 278813818de0d..47540d6d3751f 100644 --- a/planning/planning_test_utils/package.xml +++ b/planning/planning_test_utils/package.xml @@ -6,6 +6,8 @@ ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe + Zulfaqar Azmi + Mamoru Sobue Apache License 2.0 Kyoichi Sugahara diff --git a/planning/planning_validator/package.xml b/planning/planning_validator/package.xml index 1f1c1cc55e93c..9ecc760efd7e3 100644 --- a/planning/planning_validator/package.xml +++ b/planning/planning_validator/package.xml @@ -16,11 +16,11 @@ rosidl_default_generators autoware_auto_planning_msgs + autoware_planning_test_manager diagnostic_updater geometry_msgs motion_utils nav_msgs - planning_test_utils rclcpp rclcpp_components tier4_autoware_utils diff --git a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp index 606dc182504a2..2b2a32bf54618 100644 --- a/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -15,8 +15,8 @@ #include "planning_validator/planning_validator.hpp" #include -#include -#include +#include +#include #include diff --git a/planning/scenario_selector/package.xml b/planning/scenario_selector/package.xml index b985cac0b6ae7..341076505d5b8 100644 --- a/planning/scenario_selector/package.xml +++ b/planning/scenario_selector/package.xml @@ -18,9 +18,9 @@ autoware_auto_mapping_msgs autoware_auto_planning_msgs + autoware_planning_test_manager lanelet2_extension nav_msgs - planning_test_utils rclcpp rclcpp_components route_handler diff --git a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp b/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp index 7413be07ef904..90995e4e2ae72 100644 --- a/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp +++ b/planning/scenario_selector/test/test_scenario_selector_node_interface.cpp @@ -15,8 +15,8 @@ #include "scenario_selector/scenario_selector_node.hpp" #include -#include -#include +#include +#include #include From 85fdcb0847e164994602215ea31b570325c8b976 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 15 May 2024 19:24:27 +0900 Subject: [PATCH 177/192] feat(diagnostic_graph_aggregator): componentize node (#7025) Signed-off-by: Takagi, Isamu --- .../diagnostic_graph_aggregator/CMakeLists.txt | 17 +++++++++++------ .../launch/aggregator.launch.xml | 2 +- system/diagnostic_graph_aggregator/package.xml | 1 + .../src/node/aggregator.cpp | 15 +++------------ .../src/node/aggregator.hpp | 2 +- 5 files changed, 17 insertions(+), 20 deletions(-) diff --git a/system/diagnostic_graph_aggregator/CMakeLists.txt b/system/diagnostic_graph_aggregator/CMakeLists.txt index 905cc07d81da1..4f18407e2a108 100644 --- a/system/diagnostic_graph_aggregator/CMakeLists.txt +++ b/system/diagnostic_graph_aggregator/CMakeLists.txt @@ -13,12 +13,6 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/common/graph/units.cpp ) -ament_auto_add_executable(aggregator - src/node/aggregator.cpp - src/node/availability.cpp -) -target_include_directories(aggregator PRIVATE src/common) - ament_auto_add_executable(tree src/tool/tree.cpp ) @@ -29,6 +23,17 @@ ament_auto_add_executable(plantuml ) target_include_directories(plantuml PRIVATE src/common) +ament_auto_add_library(aggregator SHARED + src/node/aggregator.cpp + src/node/availability.cpp +) +target_include_directories(aggregator PRIVATE src/common) + +rclcpp_components_register_node(aggregator + PLUGIN "diagnostic_graph_aggregator::AggregatorNode" + EXECUTABLE aggregator_node +) + if(BUILD_TESTING) get_filename_component(RESOURCE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/test/files ABSOLUTE) ament_auto_add_gtest(gtest_${PROJECT_NAME} diff --git a/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml b/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml index 272901a3f8045..c06c3d1d96cfa 100644 --- a/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml +++ b/system/diagnostic_graph_aggregator/launch/aggregator.launch.xml @@ -1,7 +1,7 @@ - + diff --git a/system/diagnostic_graph_aggregator/package.xml b/system/diagnostic_graph_aggregator/package.xml index 2a9efad2c0d6e..a89196f25a78d 100644 --- a/system/diagnostic_graph_aggregator/package.xml +++ b/system/diagnostic_graph_aggregator/package.xml @@ -12,6 +12,7 @@ diagnostic_msgs rclcpp + rclcpp_components tier4_system_msgs yaml_cpp_vendor diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp index 3287d30d4de18..4d2ec73bfceca 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.cpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.cpp @@ -21,7 +21,7 @@ namespace diagnostic_graph_aggregator { -AggregatorNode::AggregatorNode() : Node("aggregator") +AggregatorNode::AggregatorNode(const rclcpp::NodeOptions & options) : Node("aggregator", options) { const auto stamp = now(); @@ -99,14 +99,5 @@ void AggregatorNode::on_diag(const DiagnosticArray & msg) } // namespace diagnostic_graph_aggregator -int main(int argc, char ** argv) -{ - using diagnostic_graph_aggregator::AggregatorNode; - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_aggregator::AggregatorNode) diff --git a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp index 8a0e12edb25e5..f71780f19a5c7 100644 --- a/system/diagnostic_graph_aggregator/src/node/aggregator.hpp +++ b/system/diagnostic_graph_aggregator/src/node/aggregator.hpp @@ -30,7 +30,7 @@ namespace diagnostic_graph_aggregator class AggregatorNode : public rclcpp::Node { public: - AggregatorNode(); + explicit AggregatorNode(const rclcpp::NodeOptions & options); ~AggregatorNode(); private: From c86524050af5ac92390e6200592a949c638a7299 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 15 May 2024 19:24:51 +0900 Subject: [PATCH 178/192] feat(component_interface_tools): componentize node (#7023) Signed-off-by: Takagi, Isamu --- common/component_interface_tools/CMakeLists.txt | 11 ++++++++++- .../launch/service_log_checker.launch.xml | 2 +- common/component_interface_tools/package.xml | 1 + .../src/service_log_checker.cpp | 15 ++++----------- .../src/service_log_checker.hpp | 2 +- 5 files changed, 17 insertions(+), 14 deletions(-) diff --git a/common/component_interface_tools/CMakeLists.txt b/common/component_interface_tools/CMakeLists.txt index a5ebc29463bec..2b896a951b8ed 100644 --- a/common/component_interface_tools/CMakeLists.txt +++ b/common/component_interface_tools/CMakeLists.txt @@ -3,5 +3,14 @@ project(component_interface_tools) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(service_log_checker src/service_log_checker.cpp) + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/service_log_checker.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ServiceLogChecker" + EXECUTABLE service_log_checker_node +) + ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/common/component_interface_tools/launch/service_log_checker.launch.xml b/common/component_interface_tools/launch/service_log_checker.launch.xml index f3099b3238096..c7845198955c1 100644 --- a/common/component_interface_tools/launch/service_log_checker.launch.xml +++ b/common/component_interface_tools/launch/service_log_checker.launch.xml @@ -1,3 +1,3 @@ - + diff --git a/common/component_interface_tools/package.xml b/common/component_interface_tools/package.xml index cff1829473e86..6df07af8729ff 100644 --- a/common/component_interface_tools/package.xml +++ b/common/component_interface_tools/package.xml @@ -13,6 +13,7 @@ diagnostic_updater fmt rclcpp + rclcpp_components tier4_system_msgs yaml_cpp_vendor diff --git a/common/component_interface_tools/src/service_log_checker.cpp b/common/component_interface_tools/src/service_log_checker.cpp index ce89573356412..18f90af5737d2 100644 --- a/common/component_interface_tools/src/service_log_checker.cpp +++ b/common/component_interface_tools/src/service_log_checker.cpp @@ -22,7 +22,8 @@ #define FMT_HEADER_ONLY #include -ServiceLogChecker::ServiceLogChecker() : Node("service_log_checker"), diagnostics_(this) +ServiceLogChecker::ServiceLogChecker(const rclcpp::NodeOptions & options) +: Node("service_log_checker", options), diagnostics_(this) { sub_ = create_subscription( "/service_log", 50, std::bind(&ServiceLogChecker::on_service_log, this, std::placeholders::_1)); @@ -98,13 +99,5 @@ void ServiceLogChecker::update_diagnostics(diagnostic_updater::DiagnosticStatusW } } -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ServiceLogChecker) diff --git a/common/component_interface_tools/src/service_log_checker.hpp b/common/component_interface_tools/src/service_log_checker.hpp index 32c7f02e757c6..9579753dfd900 100644 --- a/common/component_interface_tools/src/service_log_checker.hpp +++ b/common/component_interface_tools/src/service_log_checker.hpp @@ -26,7 +26,7 @@ class ServiceLogChecker : public rclcpp::Node { public: - ServiceLogChecker(); + explicit ServiceLogChecker(const rclcpp::NodeOptions & options); private: using ServiceLog = tier4_system_msgs::msg::ServiceLog; From d47430cdab35b3447b4ff4be3ca6e1e6da027f02 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Wed, 15 May 2024 20:02:08 +0900 Subject: [PATCH 179/192] chore(simple_planning_simulator): add maintainer (#7026) Signed-off-by: Zulfaqar Azmi --- simulator/simple_planning_simulator/package.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index 14509f83ae2fe..7618ef4204335 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -6,6 +6,10 @@ simple_planning_simulator as a ROS 2 node Takamasa Horibe Tomoya Kimura + Maxime Clement + Mamoru Sobue + Zulfaqar Azmi + Temkei Kem Apache License 2.0 ament_cmake_auto From dbc96b3e86630bea387bc33c9dd0503ab5d9b87a Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 15 May 2024 14:25:39 +0200 Subject: [PATCH 180/192] build(static_centerline_generator): prefix package and namespace with autoware_ (#6817) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * build(static_centerline_generator): prefix package and namespace with autoware_ Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * build: fix CMake target Signed-off-by: Esteve Fernandez * build(autoware_static_centerline_generator): more renames Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * build(autoware_static_centerline_generator): fix namespace Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix clang-tidy issues Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix clang-tidy issues Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix build issues Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix build issues Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_optimizer): fix clang-tidy issues Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * build: fix build errors Signed-off-by: Esteve Fernandez * fix: remove else statements after return Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix clang-tidy issues Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * revert changes for static_centerline_generator Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): add autoware_ prefix Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix filenames Signed-off-by: Esteve Fernandez * fix(autoware_static_centerline_generator): fix namespaces Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * fix: added prefix to missing strings Signed-off-by: Esteve Fernandez * refactor(autoware_static_centerline_generator): move header files to src Signed-off-by: Esteve Fernandez * refactor(autoware_static_centerline_generator): fix include paths Signed-off-by: Esteve Fernandez * style(pre-commit): autofix Signed-off-by: Esteve Fernandez * refactor(autoware_static_centerline_generator): rename base folder Signed-off-by: Esteve Fernandez * Update planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml Co-authored-by: M. Fatih Cırıt Signed-off-by: Esteve Fernandez * build(autoware_static_centerline_generator): fix include in CMake Signed-off-by: Esteve Fernandez * build(autoware_static_centerline_generator): fix missing includes Signed-off-by: Esteve Fernandez --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: M. Fatih Cırıt --- .github/CODEOWNERS | 2 +- planning/.pages | 2 +- .../CMakeLists.txt | 12 ++++--- .../README.md | 4 +-- .../config/common.param.yaml | 0 .../config/nearest_search.param.yaml | 0 .../static_centerline_generator.param.yaml | 0 .../config/vehicle_info.param.yaml | 0 .../launch/run_planning_server.launch.xml | 4 +-- .../static_centerline_generator.launch.xml | 6 ++-- .../media/rviz.png | Bin .../media/unsafe_footprints.png | Bin .../msg/PointsWithLaneId.msg | 0 .../package.xml | 4 +-- .../rviz/static_centerline_generator.rviz | 8 ++--- .../scripts/app.py | 12 +++---- .../scripts/centerline_updater_helper.py | 2 +- .../scripts/show_lanelet2_map_diff.py | 6 ++-- .../bag_ego_trajectory_based_centerline.sh | 3 ++ ...ptimization_trajectory_based_centerline.sh | 3 ++ .../bag_ego_trajectory_based_centerline.cpp | 11 +++--- .../bag_ego_trajectory_based_centerline.hpp | 12 +++---- ...timization_trajectory_based_centerline.cpp | 12 ++++--- ...timization_trajectory_based_centerline.hpp | 12 +++---- .../src/main.cpp | 5 +-- .../src/static_centerline_generator_node.cpp | 33 +++++++++--------- .../src}/static_centerline_generator_node.hpp | 26 +++++++------- .../src}/type_alias.hpp | 10 +++--- .../src/utils.cpp | 9 +++-- .../src}/utils.hpp | 12 +++---- .../srv/LoadMap.srv | 0 .../srv/PlanPath.srv | 6 ++++ .../srv/PlanRoute.srv | 0 .../test/data/bag_ego_trajectory.db3 | Bin .../test/data/lanelet2_map.osm | 0 .../test_static_centerline_generator.test.py | 15 ++++---- .../bag_ego_trajectory_based_centerline.sh | 3 -- ...ptimization_trajectory_based_centerline.sh | 3 -- .../srv/PlanPath.srv | 6 ---- 39 files changed, 129 insertions(+), 114 deletions(-) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/CMakeLists.txt (78%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/README.md (88%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/config/common.param.yaml (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/config/nearest_search.param.yaml (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/config/static_centerline_generator.param.yaml (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/config/vehicle_info.param.yaml (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/launch/run_planning_server.launch.xml (53%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/launch/static_centerline_generator.launch.xml (93%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/media/rviz.png (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/media/unsafe_footprints.png (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/msg/PointsWithLaneId.msg (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/package.xml (93%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/rviz/static_centerline_generator.rviz (97%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/scripts/app.py (91%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/scripts/centerline_updater_helper.py (98%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/scripts/show_lanelet2_map_diff.py (94%) create mode 100755 planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh create mode 100755 planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh rename planning/{static_centerline_generator => autoware_static_centerline_generator}/src/centerline_source/bag_ego_trajectory_based_centerline.cpp (91%) rename planning/{static_centerline_generator/include/static_centerline_generator => autoware_static_centerline_generator/src}/centerline_source/bag_ego_trajectory_based_centerline.hpp (62%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/src/centerline_source/optimization_trajectory_based_centerline.cpp (95%) rename planning/{static_centerline_generator/include/static_centerline_generator => autoware_static_centerline_generator/src}/centerline_source/optimization_trajectory_based_centerline.hpp (72%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/src/main.cpp (85%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/src/static_centerline_generator_node.cpp (95%) rename planning/{static_centerline_generator/include/static_centerline_generator => autoware_static_centerline_generator/src}/static_centerline_generator_node.hpp (82%) rename planning/{static_centerline_generator/include/static_centerline_generator => autoware_static_centerline_generator/src}/type_alias.hpp (87%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/src/utils.cpp (98%) rename planning/{static_centerline_generator/include/static_centerline_generator => autoware_static_centerline_generator/src}/utils.hpp (86%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/srv/LoadMap.srv (100%) create mode 100644 planning/autoware_static_centerline_generator/srv/PlanPath.srv rename planning/{static_centerline_generator => autoware_static_centerline_generator}/srv/PlanRoute.srv (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/test/data/bag_ego_trajectory.db3 (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/test/data/lanelet2_map.osm (100%) rename planning/{static_centerline_generator => autoware_static_centerline_generator}/test/test_static_centerline_generator.test.py (84%) delete mode 100755 planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh delete mode 100755 planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh delete mode 100644 planning/static_centerline_generator/srv/PlanPath.srv diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index dc745760cb7d0..4c01604c51ee4 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -156,6 +156,7 @@ perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhon perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai +planning/autoware_static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_dynamic_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp @@ -208,7 +209,6 @@ planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp planning/surround_obstacle_checker/** satoshi.ota@tier4.jp sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp sensing/image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp diff --git a/planning/.pages b/planning/.pages index 942a5a0b32158..645a32b4b05fa 100644 --- a/planning/.pages +++ b/planning/.pages @@ -67,7 +67,7 @@ nav: - 'About Motion Velocity Smoother': planning/motion_velocity_smoother - 'About Motion Velocity Smoother (Japanese)': planning/motion_velocity_smoother/README.ja - 'Scenario Selector': planning/scenario_selector - - 'Static Centerline Generator': planning/static_centerline_generator + - 'Static Centerline Generator': planning/autoware_static_centerline_generator - 'API and Library': - 'Costmap Generator': planning/costmap_generator - 'External Velocity Limit Selector': planning/external_velocity_limit_selector diff --git a/planning/static_centerline_generator/CMakeLists.txt b/planning/autoware_static_centerline_generator/CMakeLists.txt similarity index 78% rename from planning/static_centerline_generator/CMakeLists.txt rename to planning/autoware_static_centerline_generator/CMakeLists.txt index 991d12097cc08..08a97c9010008 100644 --- a/planning/static_centerline_generator/CMakeLists.txt +++ b/planning/autoware_static_centerline_generator/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(static_centerline_generator) +project(autoware_static_centerline_generator) find_package(autoware_cmake REQUIRED) @@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) rosidl_generate_interfaces( - static_centerline_generator + autoware_static_centerline_generator "srv/LoadMap.srv" "srv/PlanRoute.srv" "srv/PlanPath.srv" @@ -29,10 +29,10 @@ ament_auto_add_executable(main if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) rosidl_target_interfaces(main - static_centerline_generator "rosidl_typesupport_cpp") + autoware_static_centerline_generator "rosidl_typesupport_cpp") else() rosidl_get_typesupport_target( - cpp_typesupport_target static_centerline_generator "rosidl_typesupport_cpp") + cpp_typesupport_target autoware_static_centerline_generator "rosidl_typesupport_cpp") target_link_libraries(main "${cpp_typesupport_target}") endif() @@ -43,6 +43,10 @@ ament_auto_package( rviz ) +target_include_directories(main PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/src +) + if(BUILD_TESTING) add_launch_test( test/test_static_centerline_generator.test.py diff --git a/planning/static_centerline_generator/README.md b/planning/autoware_static_centerline_generator/README.md similarity index 88% rename from planning/static_centerline_generator/README.md rename to planning/autoware_static_centerline_generator/README.md index 00572b754645c..844d0af15f2a5 100644 --- a/planning/static_centerline_generator/README.md +++ b/planning/autoware_static_centerline_generator/README.md @@ -34,7 +34,7 @@ We can run with the following command by designating `` ```sh -ros2 launch static_centerline_generator run_planning_server.launch.xml vehicle_model:= +ros2 launch autoware_static_centerline_generator run_planning_server.launch.xml vehicle_model:= ``` FYI, port ID of the http server is 4010 by default. @@ -50,7 +50,7 @@ The optimized centerline can be generated from the command line interface by des - `` ```sh -ros2 launch static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:= lanelet2_output_file_path:= start_lanelet_id:= end_lanelet_id:= vehicle_model:= ``` The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`. diff --git a/planning/static_centerline_generator/config/common.param.yaml b/planning/autoware_static_centerline_generator/config/common.param.yaml similarity index 100% rename from planning/static_centerline_generator/config/common.param.yaml rename to planning/autoware_static_centerline_generator/config/common.param.yaml diff --git a/planning/static_centerline_generator/config/nearest_search.param.yaml b/planning/autoware_static_centerline_generator/config/nearest_search.param.yaml similarity index 100% rename from planning/static_centerline_generator/config/nearest_search.param.yaml rename to planning/autoware_static_centerline_generator/config/nearest_search.param.yaml diff --git a/planning/static_centerline_generator/config/static_centerline_generator.param.yaml b/planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml similarity index 100% rename from planning/static_centerline_generator/config/static_centerline_generator.param.yaml rename to planning/autoware_static_centerline_generator/config/static_centerline_generator.param.yaml diff --git a/planning/static_centerline_generator/config/vehicle_info.param.yaml b/planning/autoware_static_centerline_generator/config/vehicle_info.param.yaml similarity index 100% rename from planning/static_centerline_generator/config/vehicle_info.param.yaml rename to planning/autoware_static_centerline_generator/config/vehicle_info.param.yaml diff --git a/planning/static_centerline_generator/launch/run_planning_server.launch.xml b/planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml similarity index 53% rename from planning/static_centerline_generator/launch/run_planning_server.launch.xml rename to planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml index 1493078317458..cb368ca336316 100644 --- a/planning/static_centerline_generator/launch/run_planning_server.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml @@ -2,11 +2,11 @@ - + - + diff --git a/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml similarity index 93% rename from planning/static_centerline_generator/launch/static_centerline_generator.launch.xml rename to planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index ae71b0ae6e925..2a2fbe4340fa8 100644 --- a/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -55,7 +55,7 @@ - + @@ -79,11 +79,11 @@ - + - + diff --git a/planning/static_centerline_generator/media/rviz.png b/planning/autoware_static_centerline_generator/media/rviz.png similarity index 100% rename from planning/static_centerline_generator/media/rviz.png rename to planning/autoware_static_centerline_generator/media/rviz.png diff --git a/planning/static_centerline_generator/media/unsafe_footprints.png b/planning/autoware_static_centerline_generator/media/unsafe_footprints.png similarity index 100% rename from planning/static_centerline_generator/media/unsafe_footprints.png rename to planning/autoware_static_centerline_generator/media/unsafe_footprints.png diff --git a/planning/static_centerline_generator/msg/PointsWithLaneId.msg b/planning/autoware_static_centerline_generator/msg/PointsWithLaneId.msg similarity index 100% rename from planning/static_centerline_generator/msg/PointsWithLaneId.msg rename to planning/autoware_static_centerline_generator/msg/PointsWithLaneId.msg diff --git a/planning/static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml similarity index 93% rename from planning/static_centerline_generator/package.xml rename to planning/autoware_static_centerline_generator/package.xml index 6573f6e439c43..96e17595d49ee 100644 --- a/planning/static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -1,9 +1,9 @@ - static_centerline_generator + autoware_static_centerline_generator 0.1.0 - The static_centerline_generator package + The autoware_static_centerline_generator package Takayuki Murooka Kosuke Takeuchi Apache License 2.0 diff --git a/planning/static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz similarity index 97% rename from planning/static_centerline_generator/rviz/static_centerline_generator.rviz rename to planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz index 62b4c9b75ec87..002af580c2f00 100644 --- a/planning/static_centerline_generator/rviz/static_centerline_generator.rviz +++ b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz @@ -130,7 +130,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/input_centerline + Value: /autoware_static_centerline_generator/input_centerline Value: true View Drivable Area: Alpha: 0.9990000128746033 @@ -179,7 +179,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/output_centerline + Value: /autoware_static_centerline_generator/output_centerline Value: true View Footprint: Alpha: 1 @@ -222,7 +222,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/debug/raw_centerline + Value: /autoware_static_centerline_generator/debug/raw_centerline Value: false View Drivable Area: Alpha: 0.9990000128746033 @@ -268,7 +268,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /static_centerline_generator/debug/unsafe_footprints + Value: /autoware_static_centerline_generator/debug/unsafe_footprints Value: true Enabled: false Name: debug diff --git a/planning/static_centerline_generator/scripts/app.py b/planning/autoware_static_centerline_generator/scripts/app.py similarity index 91% rename from planning/static_centerline_generator/scripts/app.py rename to planning/autoware_static_centerline_generator/scripts/app.py index c1cb0473da040..f37737a0de4e4 100755 --- a/planning/static_centerline_generator/scripts/app.py +++ b/planning/autoware_static_centerline_generator/scripts/app.py @@ -17,15 +17,15 @@ import json import uuid +from autoware_static_centerline_generator.srv import LoadMap +from autoware_static_centerline_generator.srv import PlanPath +from autoware_static_centerline_generator.srv import PlanRoute from flask import Flask from flask import jsonify from flask import request from flask_cors import CORS import rclpy from rclpy.node import Node -from static_centerline_generator.srv import LoadMap -from static_centerline_generator.srv import PlanPath -from static_centerline_generator.srv import PlanRoute rclpy.init() node = Node("static_centerline_generator_http_server") @@ -51,7 +51,7 @@ def get_map(): map_id = map_uuid # create client - cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map") + cli = create_client(LoadMap, "/planning/autoware_static_centerline_generator/load_map") # request map loading req = LoadMap.Request(map=data["map"]) @@ -85,7 +85,7 @@ def post_planned_route(): print("map_id is not correct.") # create client - cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route") + cli = create_client(PlanRoute, "/planning/autoware_static_centerline_generator/plan_route") # request route planning req = PlanRoute.Request( @@ -123,7 +123,7 @@ def post_planned_path(): print("map_id is not correct.") # create client - cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path") + cli = create_client(PlanPath, "/planning/autoware_static_centerline_generator/plan_path") # request path planning route_lane_ids = [eval(i) for i in request.args.getlist("route[]")] diff --git a/planning/static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py similarity index 98% rename from planning/static_centerline_generator/scripts/centerline_updater_helper.py rename to planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index fec3d21d20bec..cec4e5b457c7f 100755 --- a/planning/static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -155,7 +155,7 @@ def __init__(self): transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) self.sub_whole_centerline = self.create_subscription( Trajectory, - "/static_centerline_generator/output_whole_centerline", + "/autoware_static_centerline_generator/output_whole_centerline", self.onWholeCenterline, transient_local_qos, ) diff --git a/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py b/planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py similarity index 94% rename from planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py rename to planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py index 912226511f1d9..00d06ca2213d1 100755 --- a/planning/static_centerline_generator/scripts/show_lanelet2_map_diff.py +++ b/planning/autoware_static_centerline_generator/scripts/show_lanelet2_map_diff.py @@ -98,8 +98,8 @@ def remove_diff_to_ignore(osm_root): ) args = parser.parse_args() - original_osm_file_name = "/tmp/static_centerline_generator/input/lanelet2_map.osm" - modified_osm_file_name = "/tmp/static_centerline_generator/output/lanelet2_map.osm" + original_osm_file_name = "/tmp/autoware_static_centerline_generator/input/lanelet2_map.osm" + modified_osm_file_name = "/tmp/autoware_static_centerline_generator/output/lanelet2_map.osm" # load LL2 maps original_osm_tree = ET.parse(original_osm_file_name) @@ -118,7 +118,7 @@ def remove_diff_to_ignore(osm_root): remove_diff_to_ignore(modified_osm_root) # write LL2 maps - output_dir_path = "/tmp/static_centerline_generator/show_lanelet2_map_diff/" + output_dir_path = "/tmp/autoware_static_centerline_generator/show_lanelet2_map_diff/" os.makedirs(output_dir_path + "original/", exist_ok=True) os.makedirs(output_dir_path + "modified/", exist_ok=True) diff --git a/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..e7f86062a9d20 --- /dev/null +++ b/planning/autoware_static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh new file mode 100755 index 0000000000000..488091989d1fa --- /dev/null +++ b/planning/autoware_static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp similarity index 91% rename from planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp rename to planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index 4e541b1aff527..447773d7a6535 100644 --- a/planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -12,15 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" +#include "centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "rclcpp/serialization.hpp" #include "rosbag2_cpp/reader.hpp" -#include "static_centerline_generator/static_centerline_generator_node.hpp" +#include "static_centerline_generator_node.hpp" #include -namespace static_centerline_generator +#include +#include + +namespace autoware::static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node) { @@ -79,4 +82,4 @@ std::vector generate_centerline_with_bag(rclcpp::Node & node) return centerline_traj_points; } -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp similarity index 62% rename from planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp rename to planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp index 30b2e55c36bba..2275f88184c6f 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ -#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#ifndef CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +#define CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ #include "rclcpp/rclcpp.hpp" -#include "static_centerline_generator/type_alias.hpp" +#include "type_alias.hpp" #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { std::vector generate_centerline_with_bag(rclcpp::Node & node); -} // namespace static_centerline_generator -#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ +} // namespace autoware::static_centerline_generator +#endif // CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_ diff --git a/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp similarity index 95% rename from planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp rename to planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 7980ae4e8d2d7..2825381937674 100644 --- a/planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -12,17 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" +#include "centerline_source/optimization_trajectory_based_centerline.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" #include "obstacle_avoidance_planner/node.hpp" #include "path_smoother/elastic_band_smoother.hpp" -#include "static_centerline_generator/static_centerline_generator_node.hpp" -#include "static_centerline_generator/utils.hpp" +#include "static_centerline_generator_node.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" +#include "utils.hpp" -namespace static_centerline_generator +#include + +namespace autoware::static_centerline_generator { namespace { @@ -180,4 +182,4 @@ std::vector OptimizationTrajectoryBasedCenterline::optimize_tra return whole_optimized_traj_points; } -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp similarity index 72% rename from planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp rename to planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp index 7e7cdea31e9f1..88def6fa7bd4c 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT -#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#ifndef CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#define CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT #include "rclcpp/rclcpp.hpp" -#include "static_centerline_generator/type_alias.hpp" +#include "type_alias.hpp" #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { class OptimizationTrajectoryBasedCenterline { @@ -37,7 +37,7 @@ class OptimizationTrajectoryBasedCenterline rclcpp::Publisher::SharedPtr pub_raw_path_with_lane_id_{nullptr}; rclcpp::Publisher::SharedPtr pub_raw_path_{nullptr}; }; -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator // clang-format off -#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT +#endif // CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT // clang-format on diff --git a/planning/static_centerline_generator/src/main.cpp b/planning/autoware_static_centerline_generator/src/main.cpp similarity index 85% rename from planning/static_centerline_generator/src/main.cpp rename to planning/autoware_static_centerline_generator/src/main.cpp index 981cf54fc9274..9f52f271cd5e5 100644 --- a/planning/static_centerline_generator/src/main.cpp +++ b/planning/autoware_static_centerline_generator/src/main.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_generator/static_centerline_generator_node.hpp" +#include "static_centerline_generator_node.hpp" int main(int argc, char * argv[]) { @@ -21,7 +21,8 @@ int main(int argc, char * argv[]) // initialize node rclcpp::NodeOptions node_options; auto node = - std::make_shared(node_options); + std::make_shared( + node_options); // get ros parameter const bool run_background = node->declare_parameter("run_background"); diff --git a/planning/static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp similarity index 95% rename from planning/static_centerline_generator/src/static_centerline_generator_node.cpp rename to planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index ec24f47dacc27..8388bb61748f1 100644 --- a/planning/static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_generator/static_centerline_generator_node.hpp" +#include "static_centerline_generator_node.hpp" +#include "autoware_static_centerline_generator/msg/points_with_lane_id.hpp" +#include "centerline_source/bag_ego_trajectory_based_centerline.hpp" #include "lanelet2_extension/utility/message_conversion.hpp" #include "lanelet2_extension/utility/query.hpp" #include "lanelet2_extension/utility/utilities.hpp" @@ -21,12 +23,10 @@ #include "map_projection_loader/load_info_from_lanelet2_map.hpp" #include "motion_utils/resample/resample.hpp" #include "motion_utils/trajectory/conversion.hpp" -#include "static_centerline_generator/centerline_source/bag_ego_trajectory_based_centerline.hpp" -#include "static_centerline_generator/msg/points_with_lane_id.hpp" -#include "static_centerline_generator/type_alias.hpp" -#include "static_centerline_generator/utils.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" +#include "type_alias.hpp" +#include "utils.hpp" #include #include @@ -46,6 +46,7 @@ #include #include +#include #include #include #include @@ -54,7 +55,7 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { namespace { @@ -168,7 +169,7 @@ std::vector resample_trajectory_points( StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( const rclcpp::NodeOptions & node_options) -: Node("static_centerline_generator", node_options) +: Node("autoware_static_centerline_generator", node_options) { // publishers pub_map_bin_ = @@ -216,19 +217,19 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( - "/planning/static_centerline_generator/load_map", + "/planning/autoware_static_centerline_generator/load_map", std::bind( &StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_route_ = create_service( - "/planning/static_centerline_generator/plan_route", + "/planning/autoware_static_centerline_generator/plan_route", std::bind( &StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_path_ = create_service( - "/planning/static_centerline_generator/plan_path", + "/planning/autoware_static_centerline_generator/plan_path", std::bind( &StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1, std::placeholders::_2), @@ -246,7 +247,7 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( return CenterlineSource::BagEgoTrajectoryBase; } throw std::logic_error( - "The centerline source is not supported in static_centerline_generator."); + "The centerline source is not supported in autoware_static_centerline_generator."); }(); } @@ -319,7 +320,7 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout return CenterlineWithRoute{bag_centerline, route_lane_ids}; } throw std::logic_error( - "The centerline source is not supported in static_centerline_generator."); + "The centerline source is not supported in autoware_static_centerline_generator."); }(); // resample @@ -339,7 +340,7 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_file_path) { // copy the input LL2 map to the temporary file for debugging - const std::string debug_input_file_dir{"/tmp/static_centerline_generator/input/"}; + const std::string debug_input_file_dir{"/tmp/autoware_static_centerline_generator/input/"}; std::filesystem::create_directories(debug_input_file_dir); std::filesystem::copy( lanelet2_input_file_path, debug_input_file_dir + "lanelet2_map.osm", @@ -542,7 +543,7 @@ void StaticCenterlineGeneratorNode::on_plan_path( if (!current_lanelet_points.empty()) { // register points with lane_id - static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; + autoware_static_centerline_generator::msg::PointsWithLaneId points_with_lane_id; points_with_lane_id.lane_id = lanelet.id(); points_with_lane_id.points = current_lanelet_points; response->points_with_lane_ids.push_back(points_with_lane_id); @@ -646,10 +647,10 @@ void StaticCenterlineGeneratorNode::save_map( RCLCPP_INFO(get_logger(), "Saved map."); // copy the output LL2 map to the temporary file for debugging - const std::string debug_output_file_dir{"/tmp/static_centerline_generator/output/"}; + const std::string debug_output_file_dir{"/tmp/autoware_static_centerline_generator/output/"}; std::filesystem::create_directories(debug_output_file_dir); std::filesystem::copy( lanelet2_output_file_path, debug_output_file_dir + "lanelet2_map.osm", std::filesystem::copy_options::overwrite_existing); } -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp similarity index 82% rename from planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp rename to planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp index c1d92c06a8e05..9baa1c3fbb892 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ -#define STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +#ifndef STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +#define STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +#include "autoware_static_centerline_generator/srv/load_map.hpp" +#include "autoware_static_centerline_generator/srv/plan_path.hpp" +#include "autoware_static_centerline_generator/srv/plan_route.hpp" +#include "centerline_source/optimization_trajectory_based_centerline.hpp" #include "rclcpp/rclcpp.hpp" -#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" -#include "static_centerline_generator/srv/load_map.hpp" -#include "static_centerline_generator/srv/plan_path.hpp" -#include "static_centerline_generator/srv/plan_route.hpp" -#include "static_centerline_generator/type_alias.hpp" +#include "type_alias.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -34,11 +34,11 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { -using static_centerline_generator::srv::LoadMap; -using static_centerline_generator::srv::PlanPath; -using static_centerline_generator::srv::PlanRoute; +using autoware_static_centerline_generator::srv::LoadMap; +using autoware_static_centerline_generator::srv::PlanPath; +using autoware_static_centerline_generator::srv::PlanRoute; struct CenterlineWithRoute { @@ -115,5 +115,5 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node // vehicle info vehicle_info_util::VehicleInfo vehicle_info_; }; -} // namespace static_centerline_generator -#endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ +} // namespace autoware::static_centerline_generator +#endif // STATIC_CENTERLINE_GENERATOR_NODE_HPP_ diff --git a/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp b/planning/autoware_static_centerline_generator/src/type_alias.hpp similarity index 87% rename from planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp rename to planning/autoware_static_centerline_generator/src/type_alias.hpp index 2dcb9cbbd099f..fb54804db105d 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/type_alias.hpp +++ b/planning/autoware_static_centerline_generator/src/type_alias.hpp @@ -11,8 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ -#define STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ +#ifndef TYPE_ALIAS_HPP_ +#define TYPE_ALIAS_HPP_ #include "route_handler/route_handler.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" @@ -26,7 +26,7 @@ #include "autoware_planning_msgs/msg/lanelet_route.hpp" #include "visualization_msgs/msg/marker_array.hpp" -namespace static_centerline_generator +namespace autoware::static_centerline_generator { using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_auto_perception_msgs::msg::PredictedObjects; @@ -41,6 +41,6 @@ using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; using visualization_msgs::msg::MarkerArray; -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator -#endif // STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_ +#endif // TYPE_ALIAS_HPP_ diff --git a/planning/static_centerline_generator/src/utils.cpp b/planning/autoware_static_centerline_generator/src/utils.cpp similarity index 98% rename from planning/static_centerline_generator/src/utils.cpp rename to planning/autoware_static_centerline_generator/src/utils.cpp index ddfd3e11036ce..4ea56e10935b2 100644 --- a/planning/static_centerline_generator/src/utils.cpp +++ b/planning/autoware_static_centerline_generator/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "static_centerline_generator/utils.hpp" +#include "utils.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" @@ -21,7 +21,10 @@ #include #include -namespace static_centerline_generator + +#include + +namespace autoware::static_centerline_generator { namespace { @@ -228,4 +231,4 @@ MarkerArray create_distance_text_marker( return marker_array; } } // namespace utils -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator diff --git a/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp b/planning/autoware_static_centerline_generator/src/utils.hpp similarity index 86% rename from planning/static_centerline_generator/include/static_centerline_generator/utils.hpp rename to planning/autoware_static_centerline_generator/src/utils.hpp index c8cf8f8b90590..6c6257bee59a3 100644 --- a/planning/static_centerline_generator/include/static_centerline_generator/utils.hpp +++ b/planning/autoware_static_centerline_generator/src/utils.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ -#define STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ +#ifndef UTILS_HPP_ +#define UTILS_HPP_ #include "route_handler/route_handler.hpp" -#include "static_centerline_generator/type_alias.hpp" +#include "type_alias.hpp" #include @@ -24,7 +24,7 @@ #include #include -namespace static_centerline_generator +namespace autoware::static_centerline_generator { namespace utils { @@ -53,6 +53,6 @@ MarkerArray create_distance_text_marker( const geometry_msgs::msg::Pose & pose, const double dist, const std::array & marker_color, const rclcpp::Time & now, const size_t idx); } // namespace utils -} // namespace static_centerline_generator +} // namespace autoware::static_centerline_generator -#endif // STATIC_CENTERLINE_GENERATOR__UTILS_HPP_ +#endif // UTILS_HPP_ diff --git a/planning/static_centerline_generator/srv/LoadMap.srv b/planning/autoware_static_centerline_generator/srv/LoadMap.srv similarity index 100% rename from planning/static_centerline_generator/srv/LoadMap.srv rename to planning/autoware_static_centerline_generator/srv/LoadMap.srv diff --git a/planning/autoware_static_centerline_generator/srv/PlanPath.srv b/planning/autoware_static_centerline_generator/srv/PlanPath.srv new file mode 100644 index 0000000000000..3a8d0321ffb9a --- /dev/null +++ b/planning/autoware_static_centerline_generator/srv/PlanPath.srv @@ -0,0 +1,6 @@ +uint32 map_id +int64[] route +--- +autoware_static_centerline_generator/PointsWithLaneId[] points_with_lane_ids +string message +int64[] unconnected_lane_ids diff --git a/planning/static_centerline_generator/srv/PlanRoute.srv b/planning/autoware_static_centerline_generator/srv/PlanRoute.srv similarity index 100% rename from planning/static_centerline_generator/srv/PlanRoute.srv rename to planning/autoware_static_centerline_generator/srv/PlanRoute.srv diff --git a/planning/static_centerline_generator/test/data/bag_ego_trajectory.db3 b/planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory.db3 similarity index 100% rename from planning/static_centerline_generator/test/data/bag_ego_trajectory.db3 rename to planning/autoware_static_centerline_generator/test/data/bag_ego_trajectory.db3 diff --git a/planning/static_centerline_generator/test/data/lanelet2_map.osm b/planning/autoware_static_centerline_generator/test/data/lanelet2_map.osm similarity index 100% rename from planning/static_centerline_generator/test/data/lanelet2_map.osm rename to planning/autoware_static_centerline_generator/test/data/lanelet2_map.osm diff --git a/planning/static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py similarity index 84% rename from planning/static_centerline_generator/test/test_static_centerline_generator.test.py rename to planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 29ee49a11e3b3..3011abccd48ca 100644 --- a/planning/static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -28,11 +28,12 @@ @pytest.mark.launch_test def generate_test_description(): lanelet2_map_path = os.path.join( - get_package_share_directory("static_centerline_generator"), "test/data/lanelet2_map.osm" + get_package_share_directory("autoware_static_centerline_generator"), + "test/data/lanelet2_map.osm", ) static_centerline_generator_node = Node( - package="static_centerline_generator", + package="autoware_static_centerline_generator", executable="main", output="screen", parameters=[ @@ -50,7 +51,7 @@ def generate_test_description(): "mission_planner.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/static_centerline_generator.param.yaml", ), os.path.join( @@ -74,15 +75,15 @@ def generate_test_description(): "config/lanelet2_map_loader.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/common.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/nearest_search.param.yaml", ), os.path.join( - get_package_share_directory("static_centerline_generator"), + get_package_share_directory("autoware_static_centerline_generator"), "config/vehicle_info.param.yaml", ), ], @@ -94,7 +95,7 @@ def generate_test_description(): LaunchDescription( [ static_centerline_generator_node, - # Start test after 1s - gives time for the static_centerline_generator to finish initialization + # Start test after 1s - gives time for the autoware_static_centerline_generator to finish initialization launch.actions.TimerAction( period=1.0, actions=[launch_testing.actions.ReadyToTest()] ), diff --git a/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh deleted file mode 100755 index 30ed667dd3732..0000000000000 --- a/planning/static_centerline_generator/scripts/tmp/bag_ego_trajectory_based_centerline.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus diff --git a/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh b/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh deleted file mode 100755 index 809bbb46a179e..0000000000000 --- a/planning/static_centerline_generator/scripts/tmp/optimization_trajectory_based_centerline.sh +++ /dev/null @@ -1,3 +0,0 @@ -#!/bin/bash - -ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus diff --git a/planning/static_centerline_generator/srv/PlanPath.srv b/planning/static_centerline_generator/srv/PlanPath.srv deleted file mode 100644 index 7d823b4eccbf9..0000000000000 --- a/planning/static_centerline_generator/srv/PlanPath.srv +++ /dev/null @@ -1,6 +0,0 @@ -uint32 map_id -int64[] route ---- -static_centerline_generator/PointsWithLaneId[] points_with_lane_ids -string message -int64[] unconnected_lane_ids From 017b3fbe25c90b84cc714b64a9719c8110979011 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Wed, 15 May 2024 23:43:56 +0900 Subject: [PATCH 181/192] perf(map_height_fitter): find z value with a more efficient closest point query (#7020) Signed-off-by: Maxime CLEMENT --- map/map_height_fitter/src/map_height_fitter.cpp | 14 +++----------- 1 file changed, 3 insertions(+), 11 deletions(-) diff --git a/map/map_height_fitter/src/map_height_fitter.cpp b/map/map_height_fitter/src/map_height_fitter.cpp index 095574125d9a0..0c99d33772aea 100644 --- a/map/map_height_fitter/src/map_height_fitter.cpp +++ b/map/map_height_fitter/src/map_height_fitter.cpp @@ -200,20 +200,12 @@ double MapHeightFitter::Impl::get_ground_height(const Point & point) const } } } else if (fit_target_ == "vector_map") { - lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(vector_map_); - - geometry_msgs::msg::Pose pose; - pose.position.x = x; - pose.position.y = y; - pose.position.z = 0.0; - lanelet::ConstLanelet closest_lanelet; - const bool result = - lanelet::utils::query::getClosestLanelet(all_lanelets, pose, &closest_lanelet); - if (!result) { + const auto closest_points = vector_map_->pointLayer.nearest(lanelet::BasicPoint2d{x, y}, 1); + if (closest_points.empty()) { RCLCPP_WARN_STREAM(logger, "failed to get closest lanelet"); return point.z; } - height = closest_lanelet.centerline().back().z(); + height = closest_points.front().z(); } return std::isfinite(height) ? height : point.z; From 5889e9a3c72e9255e8a4ba09b67b1e62cab6c5ae Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 15 May 2024 17:59:06 +0200 Subject: [PATCH 182/192] fix(autoware_static_centerline_generator): remove prefix from topics and node names (#7028) Signed-off-by: Esteve Fernandez --- .../rviz/static_centerline_generator.rviz | 8 ++++---- .../autoware_static_centerline_generator/scripts/app.py | 6 +++--- .../scripts/centerline_updater_helper.py | 2 +- .../src/static_centerline_generator_node.cpp | 8 ++++---- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz index 002af580c2f00..62b4c9b75ec87 100644 --- a/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz +++ b/planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz @@ -130,7 +130,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /autoware_static_centerline_generator/input_centerline + Value: /static_centerline_generator/input_centerline Value: true View Drivable Area: Alpha: 0.9990000128746033 @@ -179,7 +179,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /autoware_static_centerline_generator/output_centerline + Value: /static_centerline_generator/output_centerline Value: true View Footprint: Alpha: 1 @@ -222,7 +222,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /autoware_static_centerline_generator/debug/raw_centerline + Value: /static_centerline_generator/debug/raw_centerline Value: false View Drivable Area: Alpha: 0.9990000128746033 @@ -268,7 +268,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /autoware_static_centerline_generator/debug/unsafe_footprints + Value: /static_centerline_generator/debug/unsafe_footprints Value: true Enabled: false Name: debug diff --git a/planning/autoware_static_centerline_generator/scripts/app.py b/planning/autoware_static_centerline_generator/scripts/app.py index f37737a0de4e4..08bff8b80dcb7 100755 --- a/planning/autoware_static_centerline_generator/scripts/app.py +++ b/planning/autoware_static_centerline_generator/scripts/app.py @@ -51,7 +51,7 @@ def get_map(): map_id = map_uuid # create client - cli = create_client(LoadMap, "/planning/autoware_static_centerline_generator/load_map") + cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map") # request map loading req = LoadMap.Request(map=data["map"]) @@ -85,7 +85,7 @@ def post_planned_route(): print("map_id is not correct.") # create client - cli = create_client(PlanRoute, "/planning/autoware_static_centerline_generator/plan_route") + cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route") # request route planning req = PlanRoute.Request( @@ -123,7 +123,7 @@ def post_planned_path(): print("map_id is not correct.") # create client - cli = create_client(PlanPath, "/planning/autoware_static_centerline_generator/plan_path") + cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path") # request path planning route_lane_ids = [eval(i) for i in request.args.getlist("route[]")] diff --git a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py index cec4e5b457c7f..fec3d21d20bec 100755 --- a/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py +++ b/planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py @@ -155,7 +155,7 @@ def __init__(self): transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) self.sub_whole_centerline = self.create_subscription( Trajectory, - "/autoware_static_centerline_generator/output_whole_centerline", + "/static_centerline_generator/output_whole_centerline", self.onWholeCenterline, transient_local_qos, ) diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index 8388bb61748f1..57d292c348f2c 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -169,7 +169,7 @@ std::vector resample_trajectory_points( StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( const rclcpp::NodeOptions & node_options) -: Node("autoware_static_centerline_generator", node_options) +: Node("static_centerline_generator", node_options) { // publishers pub_map_bin_ = @@ -217,19 +217,19 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( // services callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); srv_load_map_ = create_service( - "/planning/autoware_static_centerline_generator/load_map", + "/planning/static_centerline_generator/load_map", std::bind( &StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_route_ = create_service( - "/planning/autoware_static_centerline_generator/plan_route", + "/planning/static_centerline_generator/plan_route", std::bind( &StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1, std::placeholders::_2), rmw_qos_profile_services_default, callback_group_); srv_plan_path_ = create_service( - "/planning/autoware_static_centerline_generator/plan_path", + "/planning/static_centerline_generator/plan_path", std::bind( &StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1, std::placeholders::_2), From ad46e3c35c18ca4e8e505f2fd0d22f899b578024 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 16 May 2024 10:52:19 +0900 Subject: [PATCH 183/192] refactor(route_handler): remove unused functions in route_handler (#7012) remove unused functions in route_handler --- .../include/route_handler/route_handler.hpp | 77 ---- planning/route_handler/src/route_handler.cpp | 358 ------------------ 2 files changed, 435 deletions(-) diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index d13c0536cf3c1..73bf99962ea82 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -205,54 +205,6 @@ class RouteHandler const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false, const bool get_shoulder_lane = false) const; - /** - * @brief Searches the furthest linestring to the right side of the lanelet - * Only lanelet with same direction is considered - * @param the lanelet of interest - * @return right most linestring of the lane with same direction - */ - lanelet::ConstLineString3d getRightMostSameDirectionLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const noexcept; - - /** - * @brief Searches the furthest linestring to the right side of the lanelet - * Used to search for road shoulders. Lane direction is ignored - * @param the lanelet of interest - * @return right most linestring - */ - lanelet::ConstLineString3d getRightMostLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const noexcept; - - /** - * @brief Searches the furthest linestring to the left side of the lanelet - * Only lanelet with same direction is considered - * @param the lanelet of interest - * @return left most linestring of the lane with same direction - */ - lanelet::ConstLineString3d getLeftMostSameDirectionLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const noexcept; - - /** - * @brief Searches the furthest linestring to the left side of the lanelet - * Used to search for road shoulders. Lane direction is ignored - * @param the lanelet of interest - * @return left most linestring - */ - lanelet::ConstLineString3d getLeftMostLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root = false) const noexcept; - - /** - * @brief Return furthest linestring on both side of the lanelet - * @param the lanelet of interest - * @param (optional) search furthest right side - * @param (optional) search furthest left side - * @param (optional) include opposite lane as well - * @return right and left linestrings - */ - lanelet::ConstLineStrings3d getFurthestLinestring( - const lanelet::ConstLanelet & lanelet, bool is_right = true, bool is_left = true, - bool is_opposite = true, bool enable_same_root = false) const noexcept; - /** * Retrieves a sequence of lanelets before the given lanelet. * The total length of retrieved lanelet sequence at least given length. Returned lanelet sequence @@ -276,18 +228,6 @@ class RouteHandler int getNumLaneToPreferredLane( const lanelet::ConstLanelet & lanelet, const Direction direction = Direction::NONE) const; - /** - * Query input lanelet to see whether it exist in the preferred lane. If it doesn't exist, return - * the distance to the preferred lane from the give lane. - * The total distance is computed from the front point of the centerline of the given lane to - * the front point of the preferred lane. - * @param lanelet lanelet to query - * @param direction change direction - * @return number of lanes from input to the preferred lane - */ - double getTotalLateralDistanceToPreferredLane( - const lanelet::ConstLanelet & lanelet, const Direction direction = Direction::NONE) const; - /** * Query input lanelet to see whether it exist in the preferred lane. If it doesn't exist, return * the distance to the preferred lane from the give lane. @@ -321,11 +261,6 @@ class RouteHandler const lanelet::ConstLanelet & lanelet, const Pose & pose, const double backward_distance = std::numeric_limits::max(), const double forward_distance = std::numeric_limits::max()) const; - lanelet::ConstLanelets getCheckTargetLanesFromPath( - const PathWithLaneId & path, const lanelet::ConstLanelets & target_lanes, - const double check_length) const; - lanelet::routing::RelationType getRelation( - const lanelet::ConstLanelet & prev_lane, const lanelet::ConstLanelet & next_lane) const; bool isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const; bool isRouteLanelet(const lanelet::ConstLanelet & lanelet) const; bool isRoadLanelet(const lanelet::ConstLanelet & lanelet) const; @@ -339,14 +274,9 @@ class RouteHandler const lanelet::ConstLanelets & lanelets, const Direction direction = Direction::NONE) const; std::optional getLaneChangeTargetExceptPreferredLane( const lanelet::ConstLanelets & lanelets, const Direction direction) const; - bool getRightLaneChangeTargetExceptPreferredLane( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const; - bool getLeftLaneChangeTargetExceptPreferredLane( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const; std::optional getPullOverTarget(const Pose & goal_pose) const; std::optional getPullOutStartLane( const Pose & pose, const double vehicle_width) const; - double getLaneChangeableDistance(const Pose & current_pose, const Direction & direction) const; lanelet::ConstLanelets getRoadLaneletsAtPose(const Pose & pose) const; std::optional getLeftShoulderLanelet( const lanelet::ConstLanelet & lanelet) const; @@ -354,7 +284,6 @@ class RouteHandler const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getShoulderLaneletsAtPose(const Pose & pose) const; lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const; - bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const; private: // MUST @@ -385,8 +314,6 @@ class RouteHandler lanelet::ConstLanelets getMainLanelets(const lanelet::ConstLanelets & path_lanelets) const; // for lanelet - bool isInTargetLane(const PoseStamped & pose, const lanelet::ConstLanelets & target) const; - bool isInPreferredLane(const PoseStamped & pose) const; bool isBijectiveConnection( const lanelet::ConstLanelets & lanelet_section1, const lanelet::ConstLanelets & lanelet_section2) const; @@ -419,17 +346,13 @@ class RouteHandler const double min_length = std::numeric_limits::max()) const; lanelet::ConstLanelets getPreviousLaneletSequence( const lanelet::ConstLanelets & lanelet_sequence) const; - lanelet::ConstLanelets getLaneChangeTargetLanes(const Pose & pose) const; lanelet::ConstLanelets getLaneSequenceUpTo(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getLaneSequenceAfter(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getLaneSequence(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getNeighborsWithinRoute(const lanelet::ConstLanelet & lanelet) const; - std::vector getLaneSection(const lanelet::ConstLanelet & lanelet) const; - lanelet::ConstLanelets getNextLaneSequence(const lanelet::ConstLanelets & lane_sequence) const; // for path - PathWithLaneId updatePathTwist(const PathWithLaneId & path) const; /** * @brief Checks if a path has a no_drivable_lane or not * @param path lanelet path diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 589a98d7d5ab4..e9fb3cc7d2fd7 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -1324,98 +1324,6 @@ lanelet::ConstLanelet RouteHandler::getMostLeftLanelet( return lanelet; } -lanelet::ConstLineString3d RouteHandler::getRightMostSameDirectionLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const noexcept -{ - // recursively compute the width of the lanes - const auto & same = getRightLanelet(lanelet, enable_same_root); - - if (same) { - return getRightMostSameDirectionLinestring(same.value(), enable_same_root); - } - - return lanelet.rightBound(); -} - -lanelet::ConstLineString3d RouteHandler::getRightMostLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const noexcept -{ - const auto & same = getRightLanelet(lanelet, enable_same_root); - const auto & opposite = getRightOppositeLanelets(lanelet); - if (!same && opposite.empty()) { - return lanelet.rightBound(); - } - - if (same) { - return getRightMostLinestring(same.value(), enable_same_root); - } - - if (!opposite.empty()) { - return getLeftMostLinestring(lanelet::ConstLanelet(opposite.front()), false); - } - - return lanelet.rightBound(); -} - -lanelet::ConstLineString3d RouteHandler::getLeftMostSameDirectionLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const noexcept -{ - // recursively compute the width of the lanes - const auto & same = getLeftLanelet(lanelet, enable_same_root); - - if (same) { - return getLeftMostSameDirectionLinestring(same.value(), enable_same_root); - } - - return lanelet.leftBound(); -} - -lanelet::ConstLineString3d RouteHandler::getLeftMostLinestring( - const lanelet::ConstLanelet & lanelet, const bool enable_same_root) const noexcept -{ - // recursively compute the width of the lanes - const auto & same = getLeftLanelet(lanelet, enable_same_root); - const auto & opposite = getLeftOppositeLanelets(lanelet); - if (!same && opposite.empty()) { - return lanelet.leftBound(); - } - - if (same) { - return getLeftMostLinestring(same.value(), enable_same_root); - } - - if (!opposite.empty()) { - return getRightMostLinestring(lanelet::ConstLanelet(opposite.front()), false); - } - - return lanelet.leftBound(); -} - -lanelet::ConstLineStrings3d RouteHandler::getFurthestLinestring( - const lanelet::ConstLanelet & lanelet, bool is_right, bool is_left, bool is_opposite, - bool enable_same_root) const noexcept -{ - lanelet::ConstLineStrings3d linestrings; - linestrings.reserve(2); - - if (is_right && is_opposite) { - linestrings.emplace_back(getRightMostLinestring(lanelet, enable_same_root)); - } else if (is_right && !is_opposite) { - linestrings.emplace_back(getRightMostSameDirectionLinestring(lanelet, enable_same_root)); - } else { - linestrings.emplace_back(lanelet.rightBound()); - } - - if (is_left && is_opposite) { - linestrings.emplace_back(getLeftMostLinestring(lanelet, enable_same_root)); - } else if (is_left && !is_opposite) { - linestrings.emplace_back(getLeftMostSameDirectionLinestring(lanelet, enable_same_root)); - } else { - linestrings.emplace_back(lanelet.leftBound()); - } - return linestrings; -} - std::vector RouteHandler::getPrecedingLaneletSequence( const lanelet::ConstLanelet & lanelet, const double length, const lanelet::ConstLanelets & exclude_lanelets) const @@ -1486,46 +1394,6 @@ std::optional RouteHandler::getLaneChangeTargetExceptPref return std::nullopt; } -bool RouteHandler::getRightLaneChangeTargetExceptPreferredLane( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const -{ - for (const auto & lanelet : lanelets) { - const int num = getNumLaneToPreferredLane(lanelet); - - // Get right lanelet if preferred lane is on the left - if (num >= 0) { - if (!!routing_graph_ptr_->right(lanelet)) { - const auto right_lanelet = routing_graph_ptr_->right(lanelet); - *target_lanelet = right_lanelet.value(); - return true; - } - } - } - - *target_lanelet = lanelets.front(); - return false; -} - -bool RouteHandler::getLeftLaneChangeTargetExceptPreferredLane( - const lanelet::ConstLanelets & lanelets, lanelet::ConstLanelet * target_lanelet) const -{ - for (const auto & lanelet : lanelets) { - const int num = getNumLaneToPreferredLane(lanelet); - - // Get left lanelet if preferred lane is on the right - if (num <= 0) { - if (!!routing_graph_ptr_->left(lanelet)) { - const auto left_lanelet = routing_graph_ptr_->left(lanelet); - *target_lanelet = left_lanelet.value(); - return true; - } - } - } - - *target_lanelet = lanelets.front(); - return false; -} - std::optional RouteHandler::getPullOverTarget(const Pose & goal_pose) const { const lanelet::BasicPoint2d p(goal_pose.position.x, goal_pose.position.y); @@ -1589,13 +1457,6 @@ int RouteHandler::getNumLaneToPreferredLane( return 0; // TODO(Horibe) check if return 0 is appropriate. } -double RouteHandler::getTotalLateralDistanceToPreferredLane( - const lanelet::ConstLanelet & lanelet, const Direction direction) const -{ - const auto intervals = getLateralIntervalsToPreferredLane(lanelet, direction); - return std::accumulate(intervals.begin(), intervals.end(), 0); -} - std::vector RouteHandler::getLateralIntervalsToPreferredLane( const lanelet::ConstLanelet & lanelet, const Direction direction) const { @@ -1650,30 +1511,6 @@ std::vector RouteHandler::getLateralIntervalsToPreferredLane( return {}; } -bool RouteHandler::isPreferredLane(const lanelet::ConstLanelet & lanelet) const -{ - return exists(preferred_lanelets_, lanelet); -} - -bool RouteHandler::isInPreferredLane(const PoseStamped & pose) const -{ - lanelet::ConstLanelet lanelet; - if (!getClosestLaneletWithinRoute(pose.pose, &lanelet)) { - return false; - } - return exists(preferred_lanelets_, lanelet); -} - -bool RouteHandler::isInTargetLane( - const PoseStamped & pose, const lanelet::ConstLanelets & target) const -{ - lanelet::ConstLanelet lanelet; - if (!getClosestLaneletWithinRoute(pose.pose, &lanelet)) { - return false; - } - return exists(target, lanelet); -} - PathWithLaneId RouteHandler::getCenterLinePath( const lanelet::ConstLanelets & lanelet_sequence, const double s_start, const double s_end, bool use_exact) const @@ -1749,139 +1586,6 @@ PathWithLaneId RouteHandler::getCenterLinePath( return reference_path; } -PathWithLaneId RouteHandler::updatePathTwist(const PathWithLaneId & path) const -{ - PathWithLaneId updated_path = path; - for (auto & point : updated_path.points) { - const auto id = point.lane_ids.at(0); - const auto llt = lanelet_map_ptr_->laneletLayer.get(id); - const auto limit = traffic_rules_ptr_->speedLimit(llt); - point.point.longitudinal_velocity_mps = static_cast(limit.speedLimit.value()); - } - return updated_path; -} - -lanelet::ConstLanelets RouteHandler::getLaneChangeTargetLanes(const Pose & pose) const -{ - lanelet::ConstLanelet lanelet; - lanelet::ConstLanelets target_lanelets; - if (!getClosestLaneletWithinRoute(pose, &lanelet)) { - return target_lanelets; - } - - const int num = getNumLaneToPreferredLane(lanelet); - if (num < 0) { - const auto right_lanelet = (!!routing_graph_ptr_->right(lanelet)) - ? routing_graph_ptr_->right(lanelet) - : routing_graph_ptr_->adjacentRight(lanelet); - target_lanelets = getLaneletSequence(right_lanelet.value()); - } - if (num > 0) { - const auto left_lanelet = (!!routing_graph_ptr_->left(lanelet)) - ? routing_graph_ptr_->left(lanelet) - : routing_graph_ptr_->adjacentLeft(lanelet); - target_lanelets = getLaneletSequence(left_lanelet.value()); - } - return target_lanelets; -} - -double RouteHandler::getLaneChangeableDistance( - const Pose & current_pose, const Direction & direction) const -{ - lanelet::ConstLanelet current_lane; - if (!getClosestLaneletWithinRoute(current_pose, ¤t_lane)) { - return 0; - } - - // get lanelets after current lane - auto lanelet_sequence = getLaneletSequenceAfter(current_lane); - lanelet_sequence.insert(lanelet_sequence.begin(), current_lane); - - double accumulated_distance = 0; - for (const auto & lane : lanelet_sequence) { - lanelet::ConstLanelet target_lane; - if (direction == Direction::RIGHT) { - if (!getRightLaneletWithinRoute(lane, &target_lane)) { - break; - } - } - if (direction == Direction::LEFT) { - if (!getLeftLaneletWithinRoute(lane, &target_lane)) { - break; - } - } - double lane_length = lanelet::utils::getLaneletLength3d(lane); - - // overwrite goal because lane change must be finished before reaching goal - if (isInGoalRouteSection(lane)) { - const auto goal_position = lanelet::utils::conversion::toLaneletPoint(getGoalPose().position); - const auto goal_arc_coordinates = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(lane.centerline()), lanelet::utils::to2D(goal_position).basicPoint()); - lane_length = std::min(goal_arc_coordinates.length, lane_length); - } - - // subtract distance up to current position for first lane - if (lane == current_lane) { - const auto current_position = - lanelet::utils::conversion::toLaneletPoint(current_pose.position); - const auto arc_coordinate = lanelet::geometry::toArcCoordinates( - lanelet::utils::to2D(lane.centerline()), - lanelet::utils::to2D(current_position).basicPoint()); - lane_length = std::max(lane_length - arc_coordinate.length, 0.0); - } - accumulated_distance += lane_length; - } - return accumulated_distance; -} - -lanelet::ConstLanelets RouteHandler::getCheckTargetLanesFromPath( - const PathWithLaneId & path, const lanelet::ConstLanelets & target_lanes, - const double check_length) const -{ - std::vector target_lane_ids; - target_lane_ids.reserve(target_lanes.size()); - for (const auto & llt : target_lanes) { - target_lane_ids.push_back(llt.id()); - } - - // find first lanelet in target lanes along path - int64_t root_lane_id = lanelet::InvalId; - for (const auto & point : path.points) { - for (const auto & lane_id : point.lane_ids) { - if (exists(target_lane_ids, lane_id)) { - root_lane_id = lane_id; - } - } - } - // return emtpy lane if failed to find root lane_id - if (root_lane_id == lanelet::InvalId) { - return target_lanes; - } - lanelet::ConstLanelet root_lanelet; - for (const auto & llt : target_lanes) { - if (llt.id() == root_lane_id) { - root_lanelet = llt; - } - } - - const auto sequences = lanelet::utils::query::getPrecedingLaneletSequences( - routing_graph_ptr_, root_lanelet, check_length); - lanelet::ConstLanelets check_lanelets; - for (const auto & sequence : sequences) { - for (const auto & llt : sequence) { - if (!lanelet::utils::contains(check_lanelets, llt)) { - check_lanelets.push_back(llt); - } - } - } - for (const auto & llt : target_lanes) { - if (!lanelet::utils::contains(check_lanelets, llt)) { - check_lanelets.push_back(llt); - } - } - return check_lanelets; -} - bool RouteHandler::isMapMsgReady() const { return is_map_msg_ready_; @@ -1908,41 +1612,6 @@ lanelet::LaneletMapPtr RouteHandler::getLaneletMapPtr() const return lanelet_map_ptr_; } -lanelet::routing::RelationType RouteHandler::getRelation( - const lanelet::ConstLanelet & prev_lane, const lanelet::ConstLanelet & next_lane) const -{ - if (prev_lane == next_lane) { - return lanelet::routing::RelationType::None; - } - const auto & relation = routing_graph_ptr_->routingRelation(prev_lane, next_lane); - if (relation) { - return relation.value(); - } - - // check if lane change extends across multiple lanes - const auto shortest_path = routing_graph_ptr_->shortestPath(prev_lane, next_lane); - if (shortest_path) { - auto prev_llt = shortest_path->front(); - for (const auto & llt : shortest_path.value()) { - if (prev_llt == llt) { - continue; - } - const auto & relation = routing_graph_ptr_->routingRelation(prev_llt, llt); - if (!relation) { - continue; - } - if ( - relation.value() == lanelet::routing::RelationType::Left || - relation.value() == lanelet::routing::RelationType::Right) { - return relation.value(); - } - prev_llt = llt; - } - } - - return lanelet::routing::RelationType::None; -} - bool RouteHandler::isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const { return lanelet.hasAttribute(lanelet::AttributeName::Subtype) && @@ -2100,33 +1769,6 @@ lanelet::ConstLanelets RouteHandler::getNeighborsWithinRoute( return neighbors_within_route; } -std::vector RouteHandler::getLaneSection( - const lanelet::ConstLanelet & lanelet) const -{ - const lanelet::ConstLanelets neighbors = getNeighborsWithinRoute(lanelet); - std::vector lane_section; - lane_section.reserve(neighbors.size()); - for (const auto & llt : neighbors) { - lane_section.push_back(getLaneSequence(llt)); - } - return lane_section; -} - -lanelet::ConstLanelets RouteHandler::getNextLaneSequence( - const lanelet::ConstLanelets & lane_sequence) const -{ - lanelet::ConstLanelets next_lane_sequence; - if (lane_sequence.empty()) { - return next_lane_sequence; - } - const auto & final_lanelet = lane_sequence.back(); - lanelet::ConstLanelet next_lanelet; - if (!getNextLaneletWithinRoute(final_lanelet, &next_lanelet)) { - return next_lane_sequence; - } - return getLaneSequence(next_lanelet); -} - bool RouteHandler::planPathLaneletsBetweenCheckpoints( const Pose & start_checkpoint, const Pose & goal_checkpoint, lanelet::ConstLanelets * path_lanelets, const bool consider_no_drivable_lanes) const From ac8d50b5b96428488d2a2eed1b952506fa7a2bce Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 16 May 2024 14:46:54 +0900 Subject: [PATCH 184/192] revert(lane_change): remove terminal in abort path (#6930) Signed-off-by: Muhammad Zulfaqar Azmi --- .../behavior_path_lane_change_module/src/scene.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 1052a283efc47..2d88a820e0fae 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -1974,11 +1974,11 @@ bool NormalLaneChange::calcAbortPath() auto reference_lane_segment = prev_module_output_.path; { - const auto terminal_path = - calcTerminalLaneChangePath(reference_lanelets, selected_path.info.target_lanes); - if (terminal_path) { - reference_lane_segment = terminal_path->path; - } + // const auto terminal_path = + // calcTerminalLaneChangePath(reference_lanelets, selected_path.info.target_lanes); + // if (terminal_path) { + // reference_lane_segment = terminal_path->path; + // } const auto return_pose = shifted_path.path.points.at(abort_return_idx).point.pose; const auto seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( reference_lane_segment.points, return_pose, common_param.ego_nearest_dist_threshold, From 2c65ee9cd4a50b2ca18681bcd130e573229997cd Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 16 May 2024 15:37:56 +0900 Subject: [PATCH 185/192] feat(automatic_pose_initializer): componentize node (#7021) Signed-off-by: Takagi, Isamu --- .../automatic_pose_initializer/CMakeLists.txt | 8 +++++++- .../launch/automatic_pose_initializer.launch.xml | 2 +- .../automatic_pose_initializer/package.xml | 1 + .../src/automatic_pose_initializer.cpp | 15 ++++----------- .../src/automatic_pose_initializer.hpp | 2 +- 5 files changed, 14 insertions(+), 14 deletions(-) diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt b/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt index ad65f04356f4d..a8d16cc17609f 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt +++ b/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt @@ -4,8 +4,14 @@ project(automatic_pose_initializer) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(automatic_pose_initializer +ament_auto_add_library(${PROJECT_NAME} SHARED src/automatic_pose_initializer.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ServiceLogChecker" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) + ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml b/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml index ac5e63e84092a..e9a94efd6be7b 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml +++ b/system/default_ad_api_helpers/automatic_pose_initializer/launch/automatic_pose_initializer.launch.xml @@ -1,6 +1,6 @@ - + diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml index be192c3dade4b..7321de4b1811d 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml +++ b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml @@ -16,6 +16,7 @@ autoware_adapi_v1_msgs component_interface_utils rclcpp + rclcpp_components ament_lint_auto autoware_lint_common diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp b/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp index 6970d489ff340..8347b479b22c1 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp +++ b/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.cpp @@ -19,7 +19,8 @@ namespace automatic_pose_initializer { -AutomaticPoseInitializer::AutomaticPoseInitializer() : Node("automatic_pose_initializer") +AutomaticPoseInitializer::AutomaticPoseInitializer(const rclcpp::NodeOptions & options) +: Node("automatic_pose_initializer", options) { const auto adaptor = component_interface_utils::NodeAdaptor(this); group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -48,13 +49,5 @@ void AutomaticPoseInitializer::on_timer() } // namespace automatic_pose_initializer -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::executors::MultiThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(automatic_pose_initializer::AutomaticPoseInitializer) diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp b/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp index 80fe78832026d..91d70dfca3761 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp +++ b/system/default_ad_api_helpers/automatic_pose_initializer/src/automatic_pose_initializer.hpp @@ -25,7 +25,7 @@ namespace automatic_pose_initializer class AutomaticPoseInitializer : public rclcpp::Node { public: - AutomaticPoseInitializer(); + explicit AutomaticPoseInitializer(const rclcpp::NodeOptions & options); private: void on_timer(); From 1bf48565df5ec4b5ba05cf3df919e4426d696fea Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 16 May 2024 15:41:52 +0900 Subject: [PATCH 186/192] feat(ad_api_adaptors): componentize nodes (#7022) Signed-off-by: Takagi, Isamu --- .../ad_api_adaptors/CMakeLists.txt | 15 ++++++++++++--- .../launch/rviz_adaptors.launch.xml | 4 ++-- .../ad_api_adaptors/package.xml | 1 + .../ad_api_adaptors/src/initial_pose_adaptor.cpp | 15 ++++----------- .../ad_api_adaptors/src/initial_pose_adaptor.hpp | 2 +- .../ad_api_adaptors/src/routing_adaptor.cpp | 15 ++++----------- .../ad_api_adaptors/src/routing_adaptor.hpp | 2 +- 7 files changed, 25 insertions(+), 29 deletions(-) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt b/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt index 35cb599995b31..c14f71571d272 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt +++ b/system/default_ad_api_helpers/ad_api_adaptors/CMakeLists.txt @@ -4,12 +4,21 @@ project(ad_api_adaptors) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(initial_pose_adaptor +ament_auto_add_library(${PROJECT_NAME} SHARED src/initial_pose_adaptor.cpp + src/routing_adaptor.cpp ) -ament_auto_add_executable(routing_adaptor - src/routing_adaptor.cpp +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ad_api_adaptors::InitialPoseAdaptor" + EXECUTABLE initial_pose_adaptor_node + EXECUTOR MultiThreadedExecutor +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ad_api_adaptors::RoutingAdaptor" + EXECUTABLE routing_adaptor_node + EXECUTOR SingleThreadedExecutor ) ament_auto_package(INSTALL_TO_SHARE config launch) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml b/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml index 4d00e254e78d5..855f57345ed15 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/launch/rviz_adaptors.launch.xml @@ -3,7 +3,7 @@ - + @@ -12,7 +12,7 @@ - + diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/default_ad_api_helpers/ad_api_adaptors/package.xml index 785ff58db1f81..b070131f1d567 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/package.xml @@ -17,6 +17,7 @@ component_interface_utils map_height_fitter rclcpp + rclcpp_components ament_lint_auto autoware_lint_common diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp index 5d34653244ea2..f3c0ab9213656 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.cpp @@ -34,7 +34,8 @@ std::array get_covariance_parameter(rclcpp::Node * node, const std:: return array; } -InitialPoseAdaptor::InitialPoseAdaptor() : Node("initial_pose_adaptor"), fitter_(this) +InitialPoseAdaptor::InitialPoseAdaptor(const rclcpp::NodeOptions & options) +: Node("initial_pose_adaptor", options), fitter_(this) { rviz_particle_covariance_ = get_covariance_parameter(this, "initial_pose_particle_covariance"); sub_initial_pose_ = create_subscription( @@ -61,13 +62,5 @@ void InitialPoseAdaptor::on_initial_pose(const PoseWithCovarianceStamped::ConstS } // namespace ad_api_adaptors -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::executors::MultiThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::InitialPoseAdaptor) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp index 0531afd55ac21..340bc3b0a3058 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/initial_pose_adaptor.hpp @@ -28,7 +28,7 @@ namespace ad_api_adaptors class InitialPoseAdaptor : public rclcpp::Node { public: - InitialPoseAdaptor(); + explicit InitialPoseAdaptor(const rclcpp::NodeOptions & options); private: using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped; diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp index 7151902a972d6..18421c976cf41 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.cpp @@ -19,7 +19,8 @@ namespace ad_api_adaptors { -RoutingAdaptor::RoutingAdaptor() : Node("routing_adaptor") +RoutingAdaptor::RoutingAdaptor(const rclcpp::NodeOptions & options) +: Node("routing_adaptor", options) { using std::placeholders::_1; @@ -110,13 +111,5 @@ void RoutingAdaptor::on_reroute(const PoseStamped::ConstSharedPtr pose) } // namespace ad_api_adaptors -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor executor; - auto node = std::make_shared(); - executor.add_node(node); - executor.spin(); - executor.remove_node(node); - rclcpp::shutdown(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ad_api_adaptors::RoutingAdaptor) diff --git a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp index 4040ee37ead3e..877d705825733 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp +++ b/system/default_ad_api_helpers/ad_api_adaptors/src/routing_adaptor.hpp @@ -29,7 +29,7 @@ namespace ad_api_adaptors class RoutingAdaptor : public rclcpp::Node { public: - RoutingAdaptor(); + explicit RoutingAdaptor(const rclcpp::NodeOptions & options); private: using PoseStamped = geometry_msgs::msg::PoseStamped; From de53828028aafefbd9722de4bd66a562187249fb Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Thu, 16 May 2024 16:56:27 +0900 Subject: [PATCH 187/192] fix(automatic_pose_initializer): fix plugin name (#7035) Fixed automatic_pose_initializer plugin name Signed-off-by: Shintaro Sakoda --- .../automatic_pose_initializer/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt b/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt index a8d16cc17609f..b777df8675bef 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt +++ b/system/default_ad_api_helpers/automatic_pose_initializer/CMakeLists.txt @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "ServiceLogChecker" + PLUGIN "automatic_pose_initializer::AutomaticPoseInitializer" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR MultiThreadedExecutor ) From d4cb23c5d5114481b97d60c31dbdefabc098cfd7 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 16 May 2024 18:19:53 +0900 Subject: [PATCH 188/192] perf(lanelet2_map_preprocessor): use set.find instead of std::find (#7033) Signed-off-by: Maxime CLEMENT --- .../src/fix_lane_change_tags.cpp | 5 ----- .../lanelet2_map_preprocessor/src/fix_z_value_by_pcd.cpp | 9 ++------- .../lanelet2_map_preprocessor/src/merge_close_lines.cpp | 2 +- .../lanelet2_map_preprocessor/src/merge_close_points.cpp | 2 +- .../src/remove_unreferenced_geometry.cpp | 5 ----- 5 files changed, 4 insertions(+), 19 deletions(-) diff --git a/map/util/lanelet2_map_preprocessor/src/fix_lane_change_tags.cpp b/map/util/lanelet2_map_preprocessor/src/fix_lane_change_tags.cpp index 8900381060472..a406e5381357d 100644 --- a/map/util/lanelet2_map_preprocessor/src/fix_lane_change_tags.cpp +++ b/map/util/lanelet2_map_preprocessor/src/fix_lane_change_tags.cpp @@ -48,11 +48,6 @@ bool loadLaneletMap( return true; } -bool exists(std::unordered_set & set, lanelet::Id element) -{ - return std::find(set.begin(), set.end(), element) != set.end(); -} - lanelet::Lanelets convertToVector(lanelet::LaneletMapPtr & lanelet_map_ptr) { lanelet::Lanelets lanelets; diff --git a/map/util/lanelet2_map_preprocessor/src/fix_z_value_by_pcd.cpp b/map/util/lanelet2_map_preprocessor/src/fix_z_value_by_pcd.cpp index b0eca472ee1f3..758fee3addc06 100644 --- a/map/util/lanelet2_map_preprocessor/src/fix_z_value_by_pcd.cpp +++ b/map/util/lanelet2_map_preprocessor/src/fix_z_value_by_pcd.cpp @@ -91,11 +91,6 @@ double getMinHeightAroundPoint( return min_height; } -bool exists(std::unordered_set & set, lanelet::Id element) -{ - return std::find(set.begin(), set.end(), element) != set.end(); -} - void adjustHeight( const pcl::PointCloud::Ptr & pcd_map_ptr, lanelet::LaneletMapPtr & lanelet_map_ptr) { @@ -108,7 +103,7 @@ void adjustHeight( for (lanelet::Lanelet & llt : lanelet_map_ptr->laneletLayer) { for (lanelet::Point3d & pt : llt.leftBound()) { - if (exists(done, pt.id())) { + if (done.find(pt.id()) != done.end()) { continue; } pcl::PointXYZ pcl_pt; @@ -122,7 +117,7 @@ void adjustHeight( done.insert(pt.id()); } for (lanelet::Point3d & pt : llt.rightBound()) { - if (exists(done, pt.id())) { + if (done.find(pt.id()) != done.end()) { continue; } pcl::PointXYZ pcl_pt; diff --git a/map/util/lanelet2_map_preprocessor/src/merge_close_lines.cpp b/map/util/lanelet2_map_preprocessor/src/merge_close_lines.cpp index a9e45b3b31785..d001bdc54a680 100644 --- a/map/util/lanelet2_map_preprocessor/src/merge_close_lines.cpp +++ b/map/util/lanelet2_map_preprocessor/src/merge_close_lines.cpp @@ -49,7 +49,7 @@ bool loadLaneletMap( bool exists(std::unordered_set & set, lanelet::Id element) { - return std::find(set.begin(), set.end(), element) != set.end(); + return set.find(element) != set.end(); } lanelet::LineStrings3d convertLineLayerToLineStrings(lanelet::LaneletMapPtr & lanelet_map_ptr) diff --git a/map/util/lanelet2_map_preprocessor/src/merge_close_points.cpp b/map/util/lanelet2_map_preprocessor/src/merge_close_points.cpp index ab77b18493120..beb736e809275 100644 --- a/map/util/lanelet2_map_preprocessor/src/merge_close_points.cpp +++ b/map/util/lanelet2_map_preprocessor/src/merge_close_points.cpp @@ -45,7 +45,7 @@ bool loadLaneletMap( bool exists(std::unordered_set & set, lanelet::Id element) { - return std::find(set.begin(), set.end(), element) != set.end(); + return set.find(element) != set.end(); } lanelet::Points3d convertPointsLayerToPoints(lanelet::LaneletMapPtr & lanelet_map_ptr) diff --git a/map/util/lanelet2_map_preprocessor/src/remove_unreferenced_geometry.cpp b/map/util/lanelet2_map_preprocessor/src/remove_unreferenced_geometry.cpp index ca488b3acb790..e6c4feb4cee9a 100644 --- a/map/util/lanelet2_map_preprocessor/src/remove_unreferenced_geometry.cpp +++ b/map/util/lanelet2_map_preprocessor/src/remove_unreferenced_geometry.cpp @@ -43,11 +43,6 @@ bool loadLaneletMap( return true; } -bool exists(std::unordered_set & set, lanelet::Id element) -{ - return std::find(set.begin(), set.end(), element) != set.end(); -} - lanelet::Points3d convertPointsLayerToPoints(lanelet::LaneletMapPtr & lanelet_map_ptr) { lanelet::Points3d points; From 8265f9383e5e29354eff3369e34bf25cc99aae0d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 16 May 2024 19:14:36 +0900 Subject: [PATCH 189/192] fix(avoidance): unexpected road shoulder distance calculation result (#6911) * fix(avoidance): unexpected road shoulder distance calculation result Signed-off-by: satoshi-ota * fix(avoidance): prevent division by zero Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- planning/behavior_path_avoidance_module/src/utils.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/behavior_path_avoidance_module/src/utils.cpp index 7ae5a97b77fff..1e83769dde599 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_avoidance_module/src/utils.cpp @@ -912,8 +912,14 @@ double getRoadShoulderDistance( } } + const auto envelope_polygon_width = + boost::geometry::area(object.envelope_poly) / + std::max(object.length, 1e-3); // prevent division by zero + { - const auto p2 = calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -1.0 : 1.0), 0.0).position; + const auto p2 = + calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -0.5 : 0.5) * envelope_polygon_width, 0.0) + .position; const auto opt_intersect = tier4_autoware_utils::intersect(p1.second, p2, bound.at(i - 1), bound.at(i)); From a233cd9a1c85696e4f9a791b5c660e6519b00bfb Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 16 May 2024 19:44:45 +0900 Subject: [PATCH 190/192] refactor(planning_test_utils): remove route_handler dependencies (#7005) * refactor(planning_test_utils): remove route_handler dependencies Signed-off-by: Muhammad Zulfaqar Azmi * style(pre-commit): autofix * Fix precommit Signed-off-by: Muhammad Zulfaqar Azmi --------- Signed-off-by: Muhammad Zulfaqar Azmi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware_planning_test_manager_utils.hpp | 124 ++++++++++++++++++ .../src/autoware_planning_test_manager.cpp | 6 +- .../planning_test_utils.hpp | 91 +------------ planning/planning_test_utils/package.xml | 2 - 4 files changed, 130 insertions(+), 93 deletions(-) create mode 100644 planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp new file mode 100644 index 0000000000000..63474c5e458cd --- /dev/null +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -0,0 +1,124 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ +#define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ +#include +#include + +#include +#include +#include + +#include +#include + +namespace autoware_planning_test_manager::utils +{ +using autoware_planning_msgs::msg::LaneletRoute; +using geometry_msgs::msg::Pose; +using nav_msgs::msg::Odometry; +using route_handler::RouteHandler; +using RouteSections = std::vector; + +Pose createPoseFromLaneID(const lanelet::Id & lane_id) +{ + auto map_bin_msg = test_utils::makeMapBinMsg(); + // create route_handler + auto route_handler = std::make_shared(); + route_handler->setMap(map_bin_msg); + + // get middle idx of the lanelet + const auto lanelet = route_handler->getLaneletsFromId(lane_id); + const auto center_line = lanelet.centerline(); + const size_t middle_point_idx = std::floor(center_line.size() / 2.0); + + // get middle position of the lanelet + geometry_msgs::msg::Point middle_pos; + middle_pos.x = center_line[middle_point_idx].x(); + middle_pos.y = center_line[middle_point_idx].y(); + + // get next middle position of the lanelet + geometry_msgs::msg::Point next_middle_pos; + next_middle_pos.x = center_line[middle_point_idx + 1].x(); + next_middle_pos.y = center_line[middle_point_idx + 1].y(); + + // calculate middle pose + geometry_msgs::msg::Pose middle_pose; + middle_pose.position = middle_pos; + const double yaw = tier4_autoware_utils::calcAzimuthAngle(middle_pos, next_middle_pos); + middle_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); + + return middle_pose; +} + +// Function to create a route from given start and goal lanelet ids +// start pose and goal pose are set to the middle of the lanelet +LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & goal_lane_id) +{ + LaneletRoute route; + route.header.frame_id = "map"; + auto start_pose = createPoseFromLaneID(start_lane_id); + auto goal_pose = createPoseFromLaneID(goal_lane_id); + route.start_pose = start_pose; + route.goal_pose = goal_pose; + + auto map_bin_msg = test_utils::makeMapBinMsg(); + // create route_handler + auto route_handler = std::make_shared(); + route_handler->setMap(map_bin_msg); + + LaneletRoute route_msg; + RouteSections route_sections; + lanelet::ConstLanelets all_route_lanelets; + + // Plan the path between checkpoints (start and goal poses) + lanelet::ConstLanelets path_lanelets; + if (!route_handler->planPathLaneletsBetweenCheckpoints(start_pose, goal_pose, &path_lanelets)) { + return route_msg; + } + + // Add all path_lanelets to all_route_lanelets + for (const auto & lane : path_lanelets) { + all_route_lanelets.push_back(lane); + } + // create local route sections + route_handler->setRouteLanelets(path_lanelets); + const auto local_route_sections = route_handler->createMapSegments(path_lanelets); + route_sections = + test_utils::combineConsecutiveRouteSections(route_sections, local_route_sections); + for (const auto & route_section : route_sections) { + for (const auto & primitive : route_section.primitives) { + std::cerr << "primitive: " << primitive.id << std::endl; + } + std::cerr << "preferred_primitive id : " << route_section.preferred_primitive.id << std::endl; + } + route_handler->setRouteLanelets(all_route_lanelets); + route.segments = route_sections; + + route.allow_modification = false; + return route; +} + +Odometry makeInitialPoseFromLaneId(const lanelet::Id & lane_id) +{ + Odometry current_odometry; + current_odometry.pose.pose = createPoseFromLaneID(lane_id); + current_odometry.header.frame_id = "map"; + + return current_odometry; +} + +} // namespace autoware_planning_test_manager::utils +#endif // AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 3aee408a76306..9ee162ec02d1f 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -15,7 +15,9 @@ #include "motion_utils/trajectory/conversion.hpp" #include +#include #include +#include namespace planning_test_utils { @@ -115,7 +117,7 @@ void PlanningInterfaceTestManager::publishInitialPose( if (module_name == ModuleName::START_PLANNER) { test_utils::publishToTargetNode( test_node_, target_node, topic_name, initial_pose_pub_, - test_utils::makeInitialPoseFromLaneId(10291)); + autoware_planning_test_manager::utils::makeInitialPoseFromLaneId(10291)); } else { test_utils::publishToTargetNode( test_node_, target_node, topic_name, initial_pose_pub_, test_utils::makeInitialPose(shift)); @@ -256,7 +258,7 @@ void PlanningInterfaceTestManager::publishBehaviorNominalRoute( if (module_name == ModuleName::START_PLANNER) { test_utils::publishToTargetNode( test_node_, target_node, topic_name, behavior_normal_route_pub_, - test_utils::makeBehaviorRouteFromLaneId(10291, 10333), 5); + autoware_planning_test_manager::utils::makeBehaviorRouteFromLaneId(10291, 10333), 5); } else { test_utils::publishToTargetNode( test_node_, target_node, topic_name, behavior_normal_route_pub_, diff --git a/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp b/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp index 7b52f3860592e..c47404b45bb5d 100644 --- a/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp +++ b/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp @@ -23,7 +23,6 @@ #include #include #include -#include #include #include @@ -37,7 +36,9 @@ #include #include #include +#include #include +#include #include #include @@ -71,7 +72,6 @@ using geometry_msgs::msg::PoseStamped; using geometry_msgs::msg::TransformStamped; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; -using route_handler::RouteHandler; using sensor_msgs::msg::PointCloud2; using tf2_msgs::msg::TFMessage; using tier4_autoware_utils::createPoint; @@ -267,46 +267,6 @@ Scenario makeScenarioMsg(const std::string scenario) return scenario_msg; } -Pose createPoseFromLaneID(const lanelet::Id & lane_id) -{ - auto map_bin_msg = makeMapBinMsg(); - // create route_handler - auto route_handler = std::make_shared(); - route_handler->setMap(map_bin_msg); - - // get middle idx of the lanelet - const auto lanelet = route_handler->getLaneletsFromId(lane_id); - const auto center_line = lanelet.centerline(); - const size_t middle_point_idx = std::floor(center_line.size() / 2.0); - - // get middle position of the lanelet - geometry_msgs::msg::Point middle_pos; - middle_pos.x = center_line[middle_point_idx].x(); - middle_pos.y = center_line[middle_point_idx].y(); - - // get next middle position of the lanelet - geometry_msgs::msg::Point next_middle_pos; - next_middle_pos.x = center_line[middle_point_idx + 1].x(); - next_middle_pos.y = center_line[middle_point_idx + 1].y(); - - // calculate middle pose - geometry_msgs::msg::Pose middle_pose; - middle_pose.position = middle_pos; - const double yaw = tier4_autoware_utils::calcAzimuthAngle(middle_pos, next_middle_pos); - middle_pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(yaw); - - return middle_pose; -} - -Odometry makeInitialPoseFromLaneId(const lanelet::Id & lane_id) -{ - Odometry current_odometry; - current_odometry.pose.pose = createPoseFromLaneID(lane_id); - current_odometry.header.frame_id = "map"; - - return current_odometry; -} - RouteSections combineConsecutiveRouteSections( const RouteSections & route_sections1, const RouteSections & route_sections2) { @@ -322,53 +282,6 @@ RouteSections combineConsecutiveRouteSections( return route_sections; } -// Function to create a route from given start and goal lanelet ids -// start pose and goal pose are set to the middle of the lanelet -LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & goal_lane_id) -{ - LaneletRoute route; - route.header.frame_id = "map"; - auto start_pose = createPoseFromLaneID(start_lane_id); - auto goal_pose = createPoseFromLaneID(goal_lane_id); - route.start_pose = start_pose; - route.goal_pose = goal_pose; - - auto map_bin_msg = makeMapBinMsg(); - // create route_handler - auto route_handler = std::make_shared(); - route_handler->setMap(map_bin_msg); - - LaneletRoute route_msg; - RouteSections route_sections; - lanelet::ConstLanelets all_route_lanelets; - - // Plan the path between checkpoints (start and goal poses) - lanelet::ConstLanelets path_lanelets; - if (!route_handler->planPathLaneletsBetweenCheckpoints(start_pose, goal_pose, &path_lanelets)) { - return route_msg; - } - - // Add all path_lanelets to all_route_lanelets - for (const auto & lane : path_lanelets) { - all_route_lanelets.push_back(lane); - } - // create local route sections - route_handler->setRouteLanelets(path_lanelets); - const auto local_route_sections = route_handler->createMapSegments(path_lanelets); - route_sections = combineConsecutiveRouteSections(route_sections, local_route_sections); - for (const auto & route_section : route_sections) { - for (const auto & primitive : route_section.primitives) { - std::cerr << "primitive: " << primitive.id << std::endl; - } - std::cerr << "preferred_primitive id : " << route_section.preferred_primitive.id << std::endl; - } - route_handler->setRouteLanelets(all_route_lanelets); - route.segments = route_sections; - - route.allow_modification = false; - return route; -} - // this is for the test lanelet2_map.osm // file hash: a9f84cff03b55a64917bc066451276d2293b0a54f5c088febca0c7fdf2f245d5 LaneletRoute makeBehaviorNormalRoute() diff --git a/planning/planning_test_utils/package.xml b/planning/planning_test_utils/package.xml index 47540d6d3751f..b236a64f48da0 100644 --- a/planning/planning_test_utils/package.xml +++ b/planning/planning_test_utils/package.xml @@ -25,10 +25,8 @@ component_interface_utils lanelet2_extension lanelet2_io - motion_utils nav_msgs rclcpp - route_handler tf2_msgs tf2_ros tier4_api_msgs From 0de4a0a9cca7dd845b39b1f182295ab2ab1d2573 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 17 May 2024 06:59:14 +0900 Subject: [PATCH 191/192] feat(tier4_autoware_utils): default QoS setting of polling subscriber (#6976) Signed-off-by: Mamoru Sobue --- .../ros/polling_subscriber.hpp | 34 ++++----- .../include/obstacle_cruise_planner/node.hpp | 22 +++--- planning/obstacle_cruise_planner/src/node.cpp | 71 ++++++++++--------- 3 files changed, 71 insertions(+), 56 deletions(-) diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp index f8d5baaf02777..b842261d56cfa 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/polling_subscriber.hpp @@ -17,6 +17,8 @@ #include +#include +#include #include namespace tier4_autoware_utils @@ -27,10 +29,11 @@ class InterProcessPollingSubscriber { private: typename rclcpp::Subscription::SharedPtr subscriber_; - std::optional data_; + typename T::SharedPtr data_; public: - explicit InterProcessPollingSubscriber(rclcpp::Node * node, const std::string & topic_name) + explicit InterProcessPollingSubscriber( + rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1}) { auto noexec_callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); @@ -38,26 +41,25 @@ class InterProcessPollingSubscriber noexec_subscription_options.callback_group = noexec_callback_group; subscriber_ = node->create_subscription( - topic_name, rclcpp::QoS{1}, + topic_name, qos, [node]([[maybe_unused]] const typename T::ConstSharedPtr msg) { assert(false); }, noexec_subscription_options); - }; - bool updateLatestData() - { - rclcpp::MessageInfo message_info; - T tmp; - // The queue size (QoS) must be 1 to get the last message data. - if (subscriber_->take(tmp, message_info)) { - data_ = tmp; + if (qos.get_rmw_qos_profile().depth > 1) { + throw std::invalid_argument( + "InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient " + "serialization while updateLatestData()"); } - return data_.has_value(); }; - const T & getData() const + typename T::ConstSharedPtr takeData() { - if (!data_.has_value()) { - throw std::runtime_error("Bad_optional_access in class InterProcessPollingSubscriber"); + auto new_data = std::make_shared(); + rclcpp::MessageInfo message_info; + const bool success = subscriber_->take(*new_data, message_info); + if (success) { + data_ = new_data; } - return data_.value(); + + return data_; }; }; diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index c368265ea0f66..a819f000412b1 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp @@ -55,15 +55,19 @@ class ObstacleCruisePlannerNode : public rclcpp::Node const std::vector & traj_points, const vehicle_info_util::VehicleInfo & vehicle_info, const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin = 0.0) const; - std::vector convertToObstacles(const std::vector & traj_points) const; + std::vector convertToObstacles( + const Odometry & odometry, const PredictedObjects & objects, + const std::vector & traj_points) const; std::tuple, std::vector, std::vector> determineEgoBehaviorAgainstObstacles( + const Odometry & odometry, const PredictedObjects & objecrts, const std::vector & traj_points, const std::vector & obstacles); std::vector decimateTrajectoryPoints( - const std::vector & traj_points) const; + const Odometry & odometry, const std::vector & traj_points) const; std::optional createStopObstacle( - const std::vector & traj_points, const std::vector & traj_polys, - const Obstacle & obstacle, const double precise_lateral_dist) const; + const Odometry & odometry, const std::vector & traj_points, + const std::vector & traj_polys, const Obstacle & obstacle, + const double precise_lateral_dist) const; bool isStopObstacle(const uint8_t label) const; bool isInsideCruiseObstacle(const uint8_t label) const; bool isOutsideCruiseObstacle(const uint8_t label) const; @@ -88,12 +92,14 @@ class ObstacleCruisePlannerNode : public rclcpp::Node bool isObstacleCrossing( const std::vector & traj_points, const Obstacle & obstacle) const; double calcCollisionTimeMargin( - const std::vector & collision_points, + const Odometry & odometry, const std::vector & collision_points, const std::vector & traj_points, const bool is_driving_forward) const; std::optional createSlowDownObstacle( - const std::vector & traj_points, const Obstacle & obstacle, - const double precise_lat_dist); - PlannerData createPlannerData(const std::vector & traj_points) const; + const Odometry & odometry, const std::vector & traj_points, + const Obstacle & obstacle, const double precise_lat_dist); + PlannerData createPlannerData( + const Odometry & odometry, const AccelWithCovarianceStamped & acc, + const std::vector & traj_points) const; void checkConsistency( const rclcpp::Time & current_time, const PredictedObjects & predicted_objects, diff --git a/planning/obstacle_cruise_planner/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 43400acb86bd9..94e9707d55c4f 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -484,12 +484,17 @@ rcl_interfaces::msg::SetParametersResult ObstacleCruisePlannerNode::onParam( void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr msg) { - if ( - !ego_odom_sub_.updateLatestData() || !objects_sub_.updateLatestData() || - !acc_sub_.updateLatestData()) { + const auto ego_odom_ptr = ego_odom_sub_.takeData(); + const auto objects_ptr = objects_sub_.takeData(); + const auto acc_ptr = acc_sub_.takeData(); + if (!ego_odom_ptr || !objects_ptr || !acc_ptr) { return; } + const auto & ego_odom = *ego_odom_ptr; + const auto & objects = *objects_ptr; + const auto & acc = *acc_ptr; + const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg); // check if subscribed variables are ready if (traj_points.empty()) { @@ -506,14 +511,14 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms // (1) with a proper label // (2) in front of ego // (3) not too far from trajectory - const auto target_obstacles = convertToObstacles(traj_points); + const auto target_obstacles = convertToObstacles(ego_odom, objects, traj_points); // 2. Determine ego's behavior against each obstacle from stop, cruise and slow down. const auto & [stop_obstacles, cruise_obstacles, slow_down_obstacles] = - determineEgoBehaviorAgainstObstacles(traj_points, target_obstacles); + determineEgoBehaviorAgainstObstacles(ego_odom, objects, traj_points, target_obstacles); // 3. Create data for planning - const auto planner_data = createPlannerData(traj_points); + const auto planner_data = createPlannerData(ego_odom, acc, traj_points); // 4. Stop planning const auto stop_traj_points = planner_ptr_->generateStopTrajectory(planner_data, stop_obstacles); @@ -629,15 +634,16 @@ std::vector ObstacleCruisePlannerNode::createOneStepPolygons( } std::vector ObstacleCruisePlannerNode::convertToObstacles( + const Odometry & odometry, const PredictedObjects & objects, const std::vector & traj_points) const { stop_watch_.tic(__func__); - const auto obj_stamp = rclcpp::Time(objects_sub_.getData().header.stamp); + const auto obj_stamp = rclcpp::Time(objects.header.stamp); const auto & p = behavior_determination_param_; std::vector target_obstacles; - for (const auto & predicted_object : objects_sub_.getData().objects) { + for (const auto & predicted_object : objects.objects) { const auto & object_id = tier4_autoware_utils::toHexString(predicted_object.object_id).substr(0, 4); const auto & current_obstacle_pose = @@ -655,8 +661,7 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( } // 2. Check if the obstacle is in front of the ego. - const size_t ego_idx = - ego_nearest_param_.findIndex(traj_points, ego_odom_sub_.getData().pose.pose); + const size_t ego_idx = ego_nearest_param_.findIndex(traj_points, odometry.pose.pose); const auto ego_to_obstacle_distance = calcDistanceToFrontVehicle(traj_points, ego_idx, current_obstacle_pose.pose.position); if (!ego_to_obstacle_distance) { @@ -745,14 +750,15 @@ bool ObstacleCruisePlannerNode::isFrontCollideObstacle( std::tuple, std::vector, std::vector> ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( + const Odometry & odometry, const PredictedObjects & objects, const std::vector & traj_points, const std::vector & obstacles) { stop_watch_.tic(__func__); // calculated decimated trajectory points and trajectory polygon - const auto decimated_traj_points = decimateTrajectoryPoints(traj_points); + const auto decimated_traj_points = decimateTrajectoryPoints(odometry, traj_points); const auto decimated_traj_polys = - createOneStepPolygons(decimated_traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose); + createOneStepPolygons(decimated_traj_points, vehicle_info_, odometry.pose.pose); debug_data_ptr_->detection_polygons = decimated_traj_polys; // determine ego's behavior from stop, cruise and slow down @@ -777,14 +783,14 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( cruise_obstacles.push_back(*cruise_obstacle); continue; } - const auto stop_obstacle = - createStopObstacle(decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist); + const auto stop_obstacle = createStopObstacle( + odometry, decimated_traj_points, decimated_traj_polys, obstacle, precise_lat_dist); if (stop_obstacle) { stop_obstacles.push_back(*stop_obstacle); continue; } const auto slow_down_obstacle = - createSlowDownObstacle(decimated_traj_points, obstacle, precise_lat_dist); + createSlowDownObstacle(odometry, decimated_traj_points, obstacle, precise_lat_dist); if (slow_down_obstacle) { slow_down_obstacles.push_back(*slow_down_obstacle); continue; @@ -810,7 +816,7 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( slow_down_condition_counter_.removeCounterUnlessUpdated(); // Check target obstacles' consistency - checkConsistency(objects_sub_.getData().header.stamp, objects_sub_.getData(), stop_obstacles); + checkConsistency(objects.header.stamp, objects, stop_obstacles); // update previous obstacles prev_stop_obstacles_ = stop_obstacles; @@ -826,13 +832,12 @@ ObstacleCruisePlannerNode::determineEgoBehaviorAgainstObstacles( } std::vector ObstacleCruisePlannerNode::decimateTrajectoryPoints( - const std::vector & traj_points) const + const Odometry & odometry, const std::vector & traj_points) const { const auto & p = behavior_determination_param_; // trim trajectory - const size_t ego_seg_idx = - ego_nearest_param_.findSegmentIndex(traj_points, ego_odom_sub_.getData().pose.pose); + const size_t ego_seg_idx = ego_nearest_param_.findSegmentIndex(traj_points, odometry.pose.pose); const size_t traj_start_point_idx = ego_seg_idx; const auto trimmed_traj_points = std::vector(traj_points.begin() + traj_start_point_idx, traj_points.end()); @@ -1151,8 +1156,9 @@ ObstacleCruisePlannerNode::createCollisionPointsForOutsideCruiseObstacle( } std::optional ObstacleCruisePlannerNode::createStopObstacle( - const std::vector & traj_points, const std::vector & traj_polys, - const Obstacle & obstacle, const double precise_lat_dist) const + const Odometry & odometry, const std::vector & traj_points, + const std::vector & traj_polys, const Obstacle & obstacle, + const double precise_lat_dist) const { const auto & p = behavior_determination_param_; const auto & object_id = obstacle.uuid.substr(0, 4); @@ -1203,7 +1209,7 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( } const double collision_time_margin = - calcCollisionTimeMargin(collision_points, traj_points, is_driving_forward_); + calcCollisionTimeMargin(odometry, collision_points, traj_points, is_driving_forward_); if (p.collision_time_margin < collision_time_margin) { RCLCPP_INFO_EXPRESSION( get_logger(), enable_debug_info_, @@ -1216,7 +1222,7 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( // calculate collision points with trajectory with lateral stop margin const auto traj_polys_with_lat_margin = createOneStepPolygons( - traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, p.max_lat_margin_for_stop); + traj_points, vehicle_info_, odometry.pose.pose, p.max_lat_margin_for_stop); const auto collision_point = polygon_utils::getCollisionPoint( traj_points, traj_polys_with_lat_margin, obstacle, is_driving_forward_, vehicle_info_); @@ -1231,8 +1237,8 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( } std::optional ObstacleCruisePlannerNode::createSlowDownObstacle( - const std::vector & traj_points, const Obstacle & obstacle, - const double precise_lat_dist) + const Odometry & odometry, const std::vector & traj_points, + const Obstacle & obstacle, const double precise_lat_dist) { const auto & object_id = obstacle.uuid.substr(0, 4); const auto & p = behavior_determination_param_; @@ -1286,7 +1292,7 @@ std::optional ObstacleCruisePlannerNode::createSlowDownObstacl // calculate collision points with trajectory with lateral stop margin // NOTE: For additional margin, hysteresis is not divided by two. const auto traj_polys_with_lat_margin = createOneStepPolygons( - traj_points, vehicle_info_, ego_odom_sub_.getData().pose.pose, + traj_points, vehicle_info_, odometry.pose.pose, p.max_lat_margin_for_slow_down + p.lat_hysteresis_margin_for_slow_down); std::vector front_collision_polygons; @@ -1446,11 +1452,11 @@ bool ObstacleCruisePlannerNode::isObstacleCrossing( } double ObstacleCruisePlannerNode::calcCollisionTimeMargin( - const std::vector & collision_points, + const Odometry & odometry, const std::vector & collision_points, const std::vector & traj_points, const bool is_driving_forward) const { - const auto & ego_pose = ego_odom_sub_.getData().pose.pose; - const double ego_vel = ego_odom_sub_.getData().twist.twist.linear.x; + const auto & ego_pose = odometry.pose.pose; + const double ego_vel = odometry.twist.twist.linear.x; const double time_to_reach_collision_point = [&]() { const double abs_ego_offset = is_driving_forward @@ -1477,14 +1483,15 @@ double ObstacleCruisePlannerNode::calcCollisionTimeMargin( } PlannerData ObstacleCruisePlannerNode::createPlannerData( + const Odometry & odometry, const AccelWithCovarianceStamped & acc, const std::vector & traj_points) const { PlannerData planner_data; planner_data.current_time = now(); planner_data.traj_points = traj_points; - planner_data.ego_pose = ego_odom_sub_.getData().pose.pose; - planner_data.ego_vel = ego_odom_sub_.getData().twist.twist.linear.x; - planner_data.ego_acc = acc_sub_.getData().accel.accel.linear.x; + planner_data.ego_pose = odometry.pose.pose; + planner_data.ego_vel = odometry.twist.twist.linear.x; + planner_data.ego_acc = acc.accel.accel.linear.x; planner_data.is_driving_forward = is_driving_forward_; return planner_data; } From 7da5afd02d7cd4d2098e0818a84127ce3d8a9dc1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 17 May 2024 10:10:33 +0900 Subject: [PATCH 192/192] fix(bpp, bvp): keep rtc cooperate status even after manager stops module execution (#7032) * feat(rtc_interface): add new function to remove old status Signed-off-by: satoshi-ota * fix(bpp): don't remove rtc cooperate status Signed-off-by: satoshi-ota * fix(bvp): don't remove rtc cooperate status Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../interface/scene_module_interface.hpp | 1 - .../interface/scene_module_manager_interface.hpp | 1 + .../scene_module_interface.hpp | 6 +++++- .../src/scene_module_interface.cpp | 5 ++++- .../include/rtc_interface/rtc_interface.hpp | 1 + planning/rtc_interface/src/rtc_interface.cpp | 12 ++++++++++++ 6 files changed, 23 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp index b4e1ffce8104a..bd7949a83a1d7 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -187,7 +187,6 @@ class SceneModuleInterface RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); clearWaitingApproval(); - removeRTCStatus(); unlockNewModuleLaunch(); unlockOutputPath(); steering_factor_interface_ptr_->clearSteeringFactors(); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 0bea7c08c6601..2eb56104ec831 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -103,6 +103,7 @@ class SceneModuleManagerInterface { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { if (ptr) { + ptr->removeExpiredCooperateStatus(); ptr->publishCooperateStatus(rclcpp::Clock(RCL_ROS_TIME).now()); } } diff --git a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp index 27db42d36f08b..3a2b474e3d730 100644 --- a/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner_common/include/behavior_velocity_planner_common/scene_module_interface.hpp @@ -247,7 +247,11 @@ class SceneModuleManagerInterfaceWithRTC : public SceneModuleManagerInterface void removeRTCStatus(const UUID & uuid) { rtc_interface_.removeCooperateStatus(uuid); } - void publishRTCStatus(const Time & stamp) { rtc_interface_.publishCooperateStatus(stamp); } + void publishRTCStatus(const Time & stamp) + { + rtc_interface_.removeExpiredCooperateStatus(); + rtc_interface_.publishCooperateStatus(stamp); + } UUID getUUID(const int64_t & module_id) const; diff --git a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp index 803682489ebde..eb43e45d55711 100644 --- a/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -272,7 +272,10 @@ void SceneModuleManagerInterfaceWithRTC::deleteExpiredModules( for (const auto & scene_module : copied_scene_modules) { if (isModuleExpired(scene_module)) { - removeRTCStatus(getUUID(scene_module->getModuleId())); + const UUID uuid = getUUID(scene_module->getModuleId()); + updateRTCStatus( + uuid, scene_module->isSafe(), State::SUCCEEDED, std::numeric_limits::lowest(), + clock_->now()); removeUUID(scene_module->getModuleId()); unregisterModule(scene_module); } diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index 8d6e8c8fc1c7c..7180812c7500b 100644 --- a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp +++ b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp @@ -56,6 +56,7 @@ class RTCInterface const UUID & uuid, const bool safe, const uint8_t state, const double start_distance, const double finish_distance, const rclcpp::Time & stamp); void removeCooperateStatus(const UUID & uuid); + void removeExpiredCooperateStatus(); void clearCooperateStatus(); bool isActivated(const UUID & uuid) const; bool isRegistered(const UUID & uuid) const; diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index c7afea57afce3..623f899f55c70 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -265,6 +265,18 @@ void RTCInterface::removeStoredCommand(const UUID & uuid) } } +void RTCInterface::removeExpiredCooperateStatus() +{ + std::lock_guard lock(mutex_); + const auto itr = std::remove_if( + registered_status_.statuses.begin(), registered_status_.statuses.end(), + [](const auto & status) { + return (rclcpp::Clock{RCL_ROS_TIME}.now() - status.stamp).seconds() > 10.0; + }); + + registered_status_.statuses.erase(itr, registered_status_.statuses.end()); +} + void RTCInterface::clearCooperateStatus() { std::lock_guard lock(mutex_);

    DI9_gkrs9C}GO9i(IFOmLAi!ig-kNuOx?XTSp>8x~>T?EIDT@fB@l`(E z#}!jnCc_&tNgobvy=>6{y|P;iAdgbUzPRteMZuu(THO{)Xak{L2iZziUl8|6YdO~DCPgx8yo$MlM|slUNeu-EUk^Y-=`8i@GyCuXY3nT4U)HKq5r_Gv<;Ly!w%L0W2UjqMnE}= z=agbL>JsQb_fE?FES`lV(U%~IIEYPb4-fUqD7M|Ak!aT)n19f|BI%qvpqc#v=R`DR zF1oZjK|30zKPr>|kE+mL28OHSd_Tq_?5?*Bn3R<;NzeEI;sz1tKFnWxS~=O2$QHiqOx4@X37RP)od#K!-DF zTGs&SESCFmO8fP=uz1f=J6#B2C4M7)C1}llG@W%pYeiqX>hLH2g}3heTTL3y2;ry+JOAy>2dpY3Z#uZvL7;ST(GL``pj|zu05!t=RJcK|AD8&JXH58 zzav;BNhmuc#AxK{;zR3f`?5K%zKxeeoyjs2fn2b^dMDQ>a=d6^gXclrI`9ACJ^h0K zTtK#ITZQ1Yrt%30h;DZ>TI^oF_o4ifz8aW0F}2wQ%S{Whg2TYHg1WfYWE)+99TtF| z$QdX>uek|;f zboJRx-p|fUHuGIp^x5-&Av5d*slZQOqxxOUd*IFo1pUAcdkFbn>_sgo!N6(gATQ)) z^+I?8+Hf||bz~1@awMU~r7DY~B9G zN!94b3Fq|`8=+Riv1A?RE!PWC|1~^jy;i%L(U}{^i zKOs<-0Wkwp%=pE?gPpzjTTK@y%+zl~&Eq>N`?qN~s8aQ0NZ^_q!6@_u_q_{j+KlDq z7k=Spit%Z9`R6)hair4@8>cH_T=LPD<_+T$5~gY1U5Y0Ea$-Y3mw9SU4LKw zofIVnO(3_0)5V^%3#!3Pp{9oRI$bg9Z&cvw{S}|{KatbB1IqupZYbN8Zq3utOyw>e zbjP?%ez_!L;(LfemAn$=t<43@0H;HD|HJ!mb%D50F3^^@1&)A*Em^|}`>jA10ANva zA@|cJ9(^u)0n#=vr-<2nvs6B{?+MNSS{R|t8(L>P$G5FIA}Bu+dNDzaDr8HJU-bTU zp75(RjX3iD_I$+gMnOQxGN9ceTv@ol3n*%86Y>7r6z6dtrkL(aObM}7%0=LFGBV_E zTiAojw$)h$YPar$?(_k;00=^%?aDAGAX_v}Xj#xao94Z>FXG&J?})tn6AtlC2xn}s zO_KV~EutFtZb#AD-A8=Nd8RHns1T=k;m)kEXNu9gb3pS8ZE!Vm?q&g9*gja#(-22M zI#C#8P7dK{paSAA0!tD*AT5HVaUqxMA!|_JBeb;#xYdOm3~0w7QDZ2{O<+tD`oGAS zsQa=Km>guSC-i^K0ta+J9AO6=f_qIVaB<*~4g&7Kv_+7d{SE}4~ zEy%}_jyczT=JF|G;vOdLMX;5DOVERGgL_s{{l5&JqHea(e**+Qr!BOe`cGNeyG>p# zQ%tkHb0IBfXwFBu)_B|JBmuEZ`zd?tSy$+N{stKoA09{snLhn>-QZ6Hg#tzG+cfJ{ zJN~JUtN2!P^R(v|Pt2woD75|J&xpGz5!aVi%;mpw$*d-vd-w8-`AgS14KRwvRT>3( z*;o9l<3zCgYvLd!xrdVqUPO}c(^`b9l@kb9*?r)A!;yF0?cGDlMWV46IAUYIBO^O* zG_E@*F+&DHa~LAj^{p*-!9G+_{-jf4{r(LF=C_k`w6;HZ9pX2%{kd@DNAa%}AKY2_ zdG(mdrwxIk^CymS4vMP2m|5U%4wANdC8vC;Fs&vP6UA;Vqq6%=Riwuy+`N(8H2}87 zMuy}Q{bc)rR+%={y(iewq@W|2Pew~Mr*h=^H?fi#QtYcgyawWMM&ELnkr_yOG~o)p zBlJ~5M@>hAKf`I}Wcuy5)<*#$qBE72zW3iTYE9qMjV-(QOZ9j}D&A(BM37mmav?WUNZ=V3To2$fJD|x7 z1P}ys$oWB7@TuajH+0yiXEEG*N;E1u>cVoQ-*x;C8t=%0LVA{Hk;v6o0!y3vV`Cei z94iSj(eoT|fzdwJoB-&(7K7DsY2b+QF{Z&`x`^93ifrY1HuA6snrB{}KbVAZkg|Ul zwen_s6Q*dLmVGjUC;Y-fVO);6N6NFElmx*a->q=R7I|2cajghHxw{k9)Ixpny?vU( z@1#8{ft47CatfZ|ji#CH+)wuM-6vTjne80XSl>FFPMq*vS-wNyvH5R~rvxcAwnx~g zM)PJB&}mW7zLBncyvE}+rxwj!@M-oTC6;)CMxXXfwX*%e1E+57C2l50wQNXXp*-H{y^M^twFzQL4!Nab%9)dt2boxF=+5w z96580&cVHM4KHcrR9DzU?9sdjYr0$*P8V0(r7blal!{;=qfcMw&0V7$}xa@Pp zi;l14O~AU2D&F(Dn3%jITT0RE1f+>X{NQ;&LJ9H9(K+YoJ6<}k=J&t=FRRSEwu2Jq z2dg!8@jEL5H}96msk_2z88N1%B*n{Y?}`z;{jhDP{_Pf3c9Ah?qXa%PtL~s}%OY<8 zHt+S|(=a=~es};7^`rHlN^%dls6Uy`$t@h82A+`Hd(tX0hl86RmBi{<8Y>$%kar}A zUhNr-!c!9G#4EEM1-^ujO&$P;GAVZnLN`E0!#XPw?^;>EIA|1YZXt)M>QcQ+sj6US zRbZefDAN3{C4O5z*M}34bk&bkPI8B5n`~z%&>BNNA3~gYt#+hhz3PV`mv~mMHj}ol z+1W~i>uFr(pC31yXHTzWdP^8@?Bmg>uvKb=`3VZTod=rC(m~S^x#7~;2(H9kQ@9qz zpS~?*vo|5wNG?d_#a3PS!&_0vo;o4TQ?lRq?*g;4|Kn;0#wy|ktQP5vFc$HxeSXko zJUZ80FuN)2jX}EHeaJpK#ExEd_q`7WKfL?ncSw&){|LB)qbu5OZT9M*A+D4dWa2br zRDVByr2xw7jh&slwy@sRzWkOqxZ*Cjs3B^ML(?5 z`F`0LvAnqVZIhP0Uw_SCdi{)~IVA({{rHUP2) zl9Q>S^&tdO7*&{l1&f*Jd|uvIOTq=9CI|5ynG@dDf_6T}%f-)SF9`+wtW*10Yu z=JP^nnZSLS1mKk*eU$uj*Zn=oy#<6HntI{OC!GIs$Xa+}Q@ zdJ$Px?MVrmS-mW(-mU zh=vZOg62sCaM`SP5sH1n0cwVwdtUhj@weAT5AOgx2MkqYob2r%YZ_m z*JMjGE@XeWSyf9QK*vKqW|36+G(*}anJkKxm_Z<>i4YGH+Ql?|H|pvWU4x!fm81Kx zvV|!?Y(86vPd>Us6JxVk?3Pi7i@C?IY$$IC@>)ln!7O3K_-&h#?A~xLJVX?EUGVRC35`3=m31fK9wvWe_kcY6P|O{B$s6 z4H|}B8xIJ;p3*$Z1-xQ0Bb(m=b#E19*Fz@nl;E4U4s0OFIqdvDtk2!t86FS}0v7tf z$l?Tu*?qy43^DuSESm{@L8`~e_{Zi>5DU`{SkwPx0|;BGL>)q0P{2f9hv=QalVIT# z+Nu_5cK!V=TYvEi1crb%(icn{|76uWJAXf2&)GZh+Ev%SX>9!(Oi}+7 z_0y zhKD$73oUm?6|!`i4ABJW>1ooTGOBRG)qyZ9@5))%dkq26C&#yrDTX$>+pVLhhFh25 zA(Bi^@f2S)-;tu*i41udnf8K{Dw%b0unQjgF0zW&BVp z|8R=3!qyES2}#LUxP`ml**pMy*?XU!l{hw@{xF!^`1~YF~{@?Z3OfO|8gnE2=E+1FI`>A1@R zfSeA%JwkPFJ)XNDg;XiWHzP{OSA=`EetAD(a+Wynp6+O_?UvWPM-t_Ja&hFsD9nlr z)TUfY0^tl|Av33U=I4%Yir%o@|6OIyI@DYG?j8FZ4H2-L2gjHYvUh}8ZJYnUM5o98 ze@CaQ#EnLhF#%!`50q-Vb7%tb&^67^|88gbyk;?M{VS*cq-7>Rje_VImjPT?NnSZN z^tWM3KCLt=$UIPa$hd=?gDouwe;Y}ul>RM%jOeZ1oeb-Mg{BLw(+hXowfTmimvh?$ zgX?}rQ*&?X0rZ_B?J;m1*pg;*0AiqG^Es%B!JD)G6M(51z#63MkuAspG6g}fAR7uW zo2M`qxWLni1#qSgQtEUK4e{jxaZN!szI$khGAt|%vI~RKaL|Cf;&)hCzs7iX{~5*p zhsvP-4DU&cD7x|$ke#p&+`Rz611ul<0iCA%9))ZN#F_@|X$gl5^N@?*rtY0|W^?m^ z>u|>0Dw(>YzIN4N0$vsk?}nENZ1cEeWS-?JFRr!>1)kxS1C7qtiBx(82Dc84q94SV zwHUXB`(f9^ZL?tys6b?17R>TvgDWvU)%K<`0Y6d=kpto&GH?ey_J~qp zgY`;S>y6?iv^d}D1B*|Z2ux`rtcxCXT|HFv<6M(`_y^7(Z=I=1Zb11CDsG!N|42&&Q*qm?`6oH*s9Fl6L9desp-={Zf~ zCvxQJ3tKPsTLFJ4P!_#1g&-S>Bb1UYRYD#Qc_b$7{6`6I>1IQE1f9hAX^ z&U-jFZxO}P1#Le;QTAOpo9`YBJ`(+tg)FV|1=}wWIVKIxh*E)W{xB~9he3EY2!v6P zxn>8+?txZh{v2?z?ld2efiLS~DnMEE&*^Cf?T9vroi{dCH8wVG6#*eYnLG?Qz872O zgCMR)sDH{`fbZ6=buf)D0t)OZ%bqWx9Ee487-Xu&0P9Gw)k`6or~-b$nhbVI#sqC?GC1Lyk;c_9@T6nDZ=8@Ot$W7#pCZ-}`&)p~n)^ z*U@z9(JSUuS?q)Y=%>RKx{K(sEE?2mcV1WT8WO!)+i4FgR75w9P@x1XJPCe_Ns&hc zWLv4(geN~ws4v~br7fm&5hzSS%-4S!&W%>Ol%^MzWQ zNeRcpLt2!OaO$EeNgsGbrR4bRW~Nvax#J@@&k>4`yA9~XdbwqjSTNhpw~q(Sq)~=7 zpEwj7`0$Vlvada`jN0f`V*C}NP`Uxh(zwr$N<4phF2I>*HV_!^$=}Q-n^x^GpqSy) zm2)h?Xvq+kYeeQQ<0@I($H*#OzvsNey!Jk7bi3u}AXn8B*k``3E-KWfLSO56Xs0d5 zuK3K|pVHDGpH|7`hL<{P(gQ*P@CuP-@AzKP92Rn+(H!=zIIMr@)%r~=0V3={?Dw<1 zmK@fL4b^jC6m@G*MzoG!OW?{%NkQT=$PL*k@dJMN9n4X0axS**@HyCg9-S(6xxdf6 zaW|)OF+^Fnk^J{N;9~iV4W=|Z-@FfK_sI|&5XuRM6eRyR3;~~rMIg%H6l+U;D!@Hm z`SnLgX-TQn`-|*%JL*TAn=){t7Jlr{n(n%2P2=O`IFvMwfH*bx_Jok3d$!}DGWZ7@ zIM@9G?CbMNY4JU4Iqt;DB)UB0{Xv@K5&xYT11pWiNhxH88yQ}&TM2b}Zj4;d;L?;&Mm~o|I>IXmF_ z=O{rI!hN5l74(=5eb}-D=^ByQW7}mjP{R?(c1~uDL4--AnCe*HM5BH`4jHv|JY+0;k9CQO z0v>za&Ij2(UXT`+PoWXkV~-XozWfkNETD?E8B9K$Pf`2zDXAN#6i<71B$q?vB{@fmCahb)m@`p@3$s7pz*3=3abAZlpE!1QZqQl&`u=PgZBwZCIw%N+XN-W4^AZXu zTjX&ZHGBx!O|H?qu{AIwiAHX|Q;wcxPp`~g8YUjdP;+5<`k?A}EF zot|j!g1{fZGsXg5I@EK&_#+3$jZD@q2ENyB}~C1V-Zc zSV*J<8o~g`2ky4ZbO&frPXHxVcJ<Q!L@JS_~#$|#7D-8e+)CnVe;Pp(|@~Lrc7az!}}=u z_-kY}C0w>r>jyb~%gls(N1GmOeCL|H{!culNT|;Lc5u*d$+!f3*gq6)3{(myIcwSSb>3x@M*teEdmQB9lf5f0`v^YiI1bl&EO3np#~(}6@NS6;M?m>N z>EW~Z4N7%M&O-{lqoGk29%=Jg(xNbz^?I_{3w@pacXze-e`K?s-S8H-64sVsMm95l zsfVq_>CnGZM33FXhq^t+%-Vgf=3k$0^?yDg&INj4FvX?-MsF5?jP_G210x{9MW*+( z1B5(77NDSWO9$03+jp6$ZAl17n0NvI`1{;mFm&dZL3ATmsyZN|lVSm4)d6O14~S?3 z47eB}=h5KbW#;`cxZ_}4Rt0j4*H(#3`Z<4SA$PS`rcYz;07~88yMP_P2$_jxdJHU) zn4jP*HQEt9o~Q>n(aBfsU`0@8GwqnIy z1UX-#P;e^1%6WiGlmv84K|1Po%CX&z-@sTfBpWdEUO_T|iI&UXKv;fI;nP%xl7;el zfwLP2ltl?>s{}y(d>a4*GsVz(zG^40!loXgs6?3-aq+tDAshB-jvaRgtDq;A*q$K~ zcf2u%t&bihIapOxN<}20DBO+To7r=zMQ=#MA%OO!PaTF8X2Z(b;@C2s2n9rk!)`BA zh2%-KARmk`_`W=8P6tmm`Pmj$tX_w8nuZV7K%_5oCvc#>o8Wi zEg2G_WRwk3xU-&0;go0D(!t_xaAZr=48fhYor>8)b?BEf-wHC$(ND7QB5QwfOZdB= zj`oVNZcGu#zcf@;`=Tnu#`re^H?73UCLH$)!dSq`_qDu=Ku)zX;g?nu{x`MC4_q@> z$CS^kC~OmdQA(^UuDVhnIyFpoZN(OVRJK#wqN>&1sNYG`5jQ*OQHVFn}i1w#>j{(Uj@UiRj z1OBPmN9Zuf2p@c~XMX`2zXm=xk!xU=zYadPUauXVe!Bd#1+92w*8G7RWc^w?(+nxFch$K<{+=CeC1={OB!WyF^`<(FQM*TIq!`mp-ESzfjT z0%bW`4QY_omlMDjC4TQEXNq-UL=x!Y>7bqn_^#q zv5`NHfKwtq(wk!)ZR5lk>+lUrN8TJ%`81=GaxCyLG?=>$o*1`J3WM92e7D zktgzlhjGY*9BBgM-$h`$Jg_}+Y`+F{MRC(v<*qWO%;QeOouVEOR+l2K>MQl({m$j_ z*1uP<)$yLfTm@07SN9CRT;~y(yIBYq53!g}gIz=~+@(IxTDeGu8voT3zOk^qHN!(6 zTE2qZEPLNShZ{w*_e@RsI;!}c_5FYSvrUCe-Uj_nIme$_L>q>6L}d8z+Ozoi=C8)D zz%#{Vv}j4pi!B-O+eF($uRpp+XA=Q_v?*$oawi+r^4#bopMkT0vI0MUuOzC!>Ou0= zJrysFVv){5*eJ4QKYRBx>bH2!7x$Nr?(;Ro9EkPF(;2O`>6!RTiT7F=ouSoKds+ZP z7`*bOLzceWtAVhIL9zEPY%c8je;z5vDTPfXxRe3cHj+=;d?k*BTEltVmR(&>L`TLBA()-L^4>J~!13@8SL z3`wgCJzk5JWbAw!6liyWc}}k8B3kp#vX+U>F5>9J^3gUHN5|l8+8rwb4TWJ7U*>>#6X15V#}Pz(o2p_~!75Qo*qM`W(2PGJ)~M zS(O;|R|W-eNKz-sk>{m1Wq}4%T+jG2Rc--MKN~TYruU;{U~p`tx4*kfqHJss~a9y z^0yw)x9-}ZawC*iD+y6{d-m{gQ&r08&Dr|rI~%z{I+-J0g{^J)agOXJBvs@az7g$L zM)xOPnLKQ{Xk-3V%s}wTxZcP56#}{ z0>`zJby?_a7@3Oszad5jvuM&Km^tcrrk{~EzOKS$?1noru&WdQXf?&NsItfVJvRD$ z?n9ij-NbB)JEOHvT%>-;N~o!Igo7mybvBIuUChjcVqu)z;0w(4kx_&F7XCJg=k6sDpb6Yq!Wpj#e#Lk+el1-|Fx1s6`gA+YpHiBSd7-P6#>eDR_P!Awj&zGgN^kkM;7H%{fc?&F#OOP z$Oys$m*-L>ZLYdy@!u!@9o0S_kQc<_#I!(x{UaM@|3JLj$mpN5{qJ@} z56>{LB^Xg`U&L&{{ zTkxh9N^Hzju4>#7r$2Y?Hwrro?x16|!O0hG^*Vv;;4HiHi~mViW7^amSqlvW6QpQo zq~lCv_6|&J$}7{1>R=iCb<$$9s5sAxsTCN8aCmtqC%JlGQNq*sT+ZtseEP&UP%piA z)gI3OAQt9gfGNMx^IZRyg5c{o8`6YbB{wUg9i>?G6*iY5HN%@x^V~+f0lu||utuXu z6Zpp4Otg09quq-yPnT6cEL;AHC1%I|*nF1Cf9$9adb!7-RXWVtsfYbhj?ypq*3S72 z{s8oJ+~4J?Zwi_>2Uf(fz0io~SNW-WRpZSkHP=FR)*_qyRcX}k-`bz0X8iu@h%t4l z(;PW43Cjuk$3f<4$ z)XG>l(fB$(pD0lu-dl~mpkErH{j+?vlxn?6vil(UzpjQC_lpLYKU%6C(NE1a!1u*R z3sTc?d~vcSL@HqXtE}u??wNs}Bzl{;eW|uwX{*YVU37WxNbTX}t!)TJ^Y@e}8)@nF z+~*^lav)rtb`Zapk&)v&VpA`Ae6BN{GUvmu?GXBMjgiFAzjM(T+^Ybwq#--a3tY1;XC+*0uv5KAK7T= z$&nH`0v_3ocC-jgCd;TtSV-gX*rb3os`E3Vv(v-Qm90moXCLeeOk+KlWs!?4XY**c zwpcE^yu0cwgyqk!9-imUJxe^2~N5 zP+onm@H9!W@YR&L1>O#RM_sBlENsm!9+eOsqb7Oa=JhMrva06JKzdj5g~_-sIkIMK zv6o|}jNhw0T&DW{P6{QdSU_HSf5pzi?{#gBYw#FFVp-bq zq2F@HDvwb6eJmz9G#M4zHyC8p3$BJ8QJ*HrLsUc+m|m9ibvS-w{Mb*=%hmNHD?0TV5>JD;F7ukL?J0OkDeyL(fu4X z0-!-=Y1A9^5BqGXp!~ZyRjqFp(wGz^FeCzT%5)a~mJa?O_ug{5R!RC`d%jP(jW*WzTF==Uy4|rRL(yx9r+rIHxcuZ!x4!sbe>#DjfUWPi zsJG;9a3c*wDFI)bo>D=X`Qf@UC732n?u5DplVD~~6yE2z(RkY{D_g^ze4}%@@dWuq zaZ4$3QVY}WdLM0v@YM8?FQE%3#w=<-ws2d@&XGS)F`sQX#7Abk4O5}|yH5t3Iee~Z zNQPpJ5tzC+A7BC%(LyLv808Rdy;h$4Y$dF=WJQmbKI>-o{i6G(K6FR0&W@>Jx|I`~ zRQ=fu$u2t7)Ng?b(gLSadhx3UIN6gfeW07I*tSmADO{QS9y^?3gtc{A--mN!sq;(7 z8#41TWL@@z0`EUDH1$xSyu5bCY@J8?z^x|cTX6i?qI8{i%~RsmxDt=)16NaUnI2{X zcY^~6uqg2u%tXx8odUjrvQ!XEl5l|Ia|I1~)aLGP*ZN^z>9;S)pE+?h4?TT+z*mQV z2RVLwzD?#w6%HDBhsh|1I6GJIN+SCkd)e6~3sk5GT&bd!?eZxU@(_E`O_N1eAPM%U zw-(@KLsgz#F%neaRZrs04z?#)dGmSF2-eR~S^&y7)1cj(+|%u7K)d>00nH{^ZVAek zZTxF~tkA96Uo@^$_-H!vd~Ur%d30)k@oi}-6xC>IB4_T+Qkt7~2RAnYBR(W}VQ*@X z=&Z#cbpL}|fH^#6vUt1)a^E^XUzb~ltcw<*#UGTFz{z@wXaV*sFtd^6Y}^~% zC0U?~^{l#7n~dD>kum6HA`TeP&5n!Hwg>hjFrRm*X_X}`@IRo;@bV~8r;gP{ry4?%3R3Ssch8q?S7jd12{_vp|Fown&`ou7vj$#> zmDD1UIF5~%82oAV=iA!(2HRklN4Nao>&dhTk%v59W}{~AI>ln!1vLv)j1Hhy6e@wG z^1H;>*!Y-$#7C}th7tMx3{R}yeH%Ecz~wEf_K}8Z8p-ySc3fW99DYGr_w)&k6$yr! zu-x}%s1RKRp7M3a?h;$HU>4!z?__!fLSKia>nFV?< z%FHlAl2@uiqkDL`Ond#bbYNGd)zVHowBSnW-o>RF*ICT1;Db0|JErY01wnZ=rs=qZ zU{_jJRsdM0X=!QoHxrda)=Nrz0E5{kpxyL27=oYTAy+M0c&LYe)^b#o1adUmxy(g6 zhhntbb)GJBi)KXD-+u0;WLGB_Yg>;~J`1}g{-d#SAdRzn9qdMj=g8zkbP$-)(?zh{ z;x^x_edIn*LGZ^e_)$7VER%&BJ!viGlVV2*Q({=Tu6abr*{&bhLlbmJzZ{<-tJ8e^ zRf4BFA3&b^r{;##xcX>-tUqB8EP#jI4g`ECeh3pleq!37U z1PNiL)^XHrBg;8y55#ZE6GbVEV8w)^BD=R`Lf$WWBa6=?wC=*Zu}PL(!up4UopvT2 zN<1O23`t8FSeU^CV44a%|80MnEbUr(`dDRf_sAq{xv^jZ{cr@{Psa2!U*pJMADA%M zRAk5MNlgtmgs@=rGVX-gBt@$O1D`w}Y$1Jf$e)$eg_Mo&7IV2V^q^;vj z=KiYokXyjLp4^lNPRWh#>rZY#bgMsq{yY>IeipH?x1JkD{xg4qEBUYWd2owoXa>K? zfV6gQbaVI?dbPVY99ANa9-ETfL?iYdKKjT`!%00PG&R391Bfwb7|+`YD<^a@oNDZf*&H+|7wLl?|^k=IwQK zv{)5xlK(nFN>6h!+BoF^=mV65*5%H)CI>PyGMQgP_cA@dshPU9;-4X9zG}R1R~95; z)TPCLUxM&J!JK>%jzw#VZfwi9*SIe@)XQNl6w8$?aHBhg_UV+U2ff)|Ny5}6Im~X9NXOGaod&*#V6tbfp8|fdQ zQ?vCQEI4@qq8uR%w;=`XObn+Ob;SC!RCP_>OdMinjA=2?#4vve;UNctbEQHtA=b}G zfLlo%JCv^|ol5JY0+q0?t#V7F)|1ms`^3Q5q#m^PQIyL7*Ud1YEwb#6<{a@t& zYQfUWrRKjQ62Q)^BSEU-- zo;2YcGyT8QkKh>>_A}&r3fZI_GBPsy0zWU`#b<;^HZ;jsv0g2D57ZmUE#H?!3n&i# zGyzdn5B{`Po|3H9;|NHLQ!siSU^6A$@SZ}@qGqEnav*pndVbgIpJ-XM>Yd3)2xCO0({ zPRXrh;AsUhe4zYryoJqSzL-qm437o6V?|yP{an52?N4oi{Hul0Ovc;Houy%{Kf5x7 zgS__=oV7g4k{ie?wgTC4F{03UkeHOz_VMhLu(X((-&wrOcjAO)Xt=Z7d{2Fr{ZCu4 z(h>8W1f!U~;YNc~eh((m_mPQoa-44E%c&XtA`xaqcxNAIoU!#OWpvF$-gR03tQ^~?-U;IROJ2v))arFe-Wi9h47 znRZu9*U>lF|7qJ8n0R^X`8w^kGUdSX8R{(~r(phwi=oXI)*_y?R&P$k`p*DSGX@2F zKH{(Usca5{`Iu8vd|VKDgnoRIssDyKx7ivj zYu#m)O4;VgSSsC+R-7#^sStDS-=NnEW_yjnGz&Z^B@fWnSbTy(;Q+ynm(9+KBDmHp z@H9E|p=F7q^I{29;du|>L5#(?R;}NA+sc4^M|%&rQ7k_GyALeVm@VWR9`7ns0>JMh zQ^ewOnRn*HX=&TMj zZmXtJENDZt9k5_hWIjsrU+ayFd7#km2xHu2Q;KyVR3x>S;D*&rCy1p)M&pH>&CnFZ zG}nRe=FsA@lF|A?-xE}KiGUeR3Z4i}`sa2~l7GY~Qia%A82fb;*Q_IdA&04CS@|0ewf+@FFOX6$)^a9`)c5+HXk@{qJcqn) zGZ|~Lh>j4Cx~Ud(O@RM+-k$Hq6o;@x>&8yT=}sz`NS|FXFtqsaLn6g+BHz)H>xI;- zB3&yf6q%l}lmcE}{&!Q%^h8x%72e0Mw^PM!3t#{DX}NEk9rP6Y^hF}cVTMNB3h(z0 z3LN|Ff+43_IR8z?WokI@FfRV#C`yN+zF6dNmwBMBu6nD0KH0$m9!}HKX8yNSUTJ*^ zfh)zQs#}A4w%~y9!H3_hD2SbDm0S3-J%tO3=2$4Qv$N0Tf0%w-hHaVkv&KBC?*gcElw9aCWt@iVH4_-mAH6gli2tf%>9r#G4CZ0+v%$iRZ3ePd@DcSw@X53n0PJy`Aii8wkz}7#Xj4 z+#8Bd0vTFM0^!VhZaDOG-lWJ5#w>J_k#a>y8$O&&vLSg9y^AnECnK{qG5Mk;a?-6H zz3#(~Ri`|XZWE-#L5qXE=H{$)b{?SzRe0;H=qq~FM7O1Jb#8B)InlDlNQsO8osIO*mO%ZsTq8;ppefgv=?($u&P{iVbSohp(s9;)-t(RFoNq=(f2hMSYp-?RS875=9_I0( zU=PMdn^>E`i2WN zJ9?n&DchU!1Qz}1U!g-wM> z3$6`E3D#YQB&pThZqhJMPlf1cyw}lItglP@H7pVB5JP@#y@JoadIn5F_|B`G?> zS4w3eaKM%@&@W5zd+V#+vKG%$AZBHWjJ|bkl&%&_RDylaVpa7VV&KLH!loG@wmj z8R%Z0p8h4GHD(K&sdFcy?Y<~)s!)%#D1m2#gUcr-wH>64z62?LXpHcIaWFssV;h1b zM_}G|yFTIRTfK6Ka%+Fn=hOMPL1evhq-2zoZ-7m=HWPd238;0oJKA=1CLJ{>=|~$p zYoLUZ-*+qd|7KOJrSEw%^#5GobforDQw*E*ZyG72n|obgKq2VqEl6 z{g}_g1IvG(j2?5aKUe9+fS7z7^L!Rro{9lJ0i?C@z28&0X`COK@@SqZBsSB!9k(4%wo{=VI%=q#5lQ_{tdBXF9&$7cYT){h(g`NZK1-Ngp~Jx z5QOFax5)k+-y zZpHqzKXZ8JBN(MVDP6m2#B(W0{%l#TQ~*%rSvSJ4T7kly#9$o|{_P8M2jaUTmIXf@ z@W7O#&y&dd$lk+iF7%bYBF+dQxjH)bKxWQOh~AH9WBJp5xAa>;(|2A2Dr_&9QGSkn z{e-Hr=iVa`g5`?HQ4k4){omZ?g%bM1#)6T$6kX$upEZ=Snacow)vMk97oq}M>n zZ`kjwQVFBG!v*B|XUeD?Lm%zyy=bn~7XSN&x+|&#RBmSGQ@DnUPjwTx1G5Hs6yJTT zWrrEu(d>YC1zGR?BqE2{Gi1c~`*)G*yv;4UxBn^-id$~j{OjtjZ0)``UeQB*121a2 z@B|NaWt0eP?!HB+sfck=e6LFY9B^zL#P0IYhZW*NU5Us*^`g%M#-jdJ=BeP?L?6*LjLzNG%;i5?qL9}}>^d8E zK_EU!t~fYyAGC{xr@q2#F+fql%4u@LadJcJ2k_^^mLqXT(9+z*l?k6N`^;c2j%@mp zJa!2$K6n@N{qA;0mMj5q4$ebLHBvH8ieO0z{)OGQ6217O4D$wCfsp6;y_Gn8+aA35 z9K_J3xPrr)^{~c6y7jW(0SoDQ?@hm5%;b$qp79cfZGP$O` z20$&$HdOj)rmj<}N@B#DS1%&>wvYzx{X4!oaNIby;fQ>pbH7@bRTt__Gr7sUgnXKB z@3zZEh0aCN)b{L5l`+a9*s4UlmG66UMe$ckqmmF~9CGjIt5kaWB5??bL1la5BG?BO~zp{duWtFz{6bZYWbr zy<~8m0FZ0^B%tm!`@rR}CIqF zZQcy#H_5OrH~eNv@KTOBLYFKK%-+8rLs9eN=L=h~QaC#p)fVu61N7G^22 z2q8XnVoZ|&N96Tqad-@a`-IZm0@eMDs|Z*u?s}!hNH99vXkw@$E(<(tAT>1=kn!!E z3w3tzGH5tY14e8rw~-fa#-i{=CZ;zVNFt2adhu@flK^~Hxr{Dd6;Y9cfFByOk6|>u zyzQYIjDml$2L^2Z?f*~=#6X&qevgHWwMgcQtEUw~YrpXMwm&^L&%c&p+66Yn##S5? zb*YXti(nT=tT1+)xJ%|(S?B;TMlb3&9SktKRB&M3v<^JE@3m^%saN!9&)fs5) zGLD~7PbD<<#?t&OEuGA5Qga`5gZVnd=hrYr(7th?D>=4u5OxwzaSGhT40L`Z<>_1E z1N~U!_d!=k5E3%eunk!Zh&5xAH9LC-S?8J{v`)Vuc(+%)_(hcy2waeA4+8)L;0O zh`7gy5Oi#(x2niob3F;eK*pzx&45Tbzy|-w;+Obb8a8yhbm?`!7^tmhrq?9p_=K2f{|hm~LB0rCdL!3C#=A8%3GnL*0ay!Pd{*2r`Om)g5gVwL zPzg6us-Nx40G1zNn1p3_W+rdwHneF>2n%-Jfb?D0> zgy8_PZ(YIZ?pigM4GwBE2&GZ>ntbcmB_-e42#?-na#)okgPAMqzzsD|aFkrmL+#n6 zy%01hYTL531*3Pqk16+?+Ig0+?u%_TN}MR?8dWyT0I3rWi4;mIh{wn1aR)uTMm3X{ zlo!}z&Qkv^diy+r>cwU-A&D@>IMMI6{VXxZ8BP|C4|r4A&ok`Sf|$ zC^LUV^`;2~5fwR6(DbDv)7{SF$$FN==rL6c7uD4!O;z~E6K+HK^ZYNETdb+!8-kwV$m@%<6dqs1A#6UI3_djfvI0`kCm!VFV-!kQ3i zWZvvJSGG9a_J}ErYYSXjLI&Sea*w^|Qbb*pDk2`{-bFPwR;6c#_~NsR%b}G;2%?SX zagY&gN5!27Gm{#XzO1SWIHa8Dr)FGjA_#WSVPLn#I-)y#u(o-j8PqDQLEM{0=6W+C z`XV(K*0l){lwa;rZb7~9B)drQSLn>7bh0=e6H&mzKnr6jnJGsmCQbZ^$$*|=XTm;) zVQGw3YOl~A2EWtd7+|MVB;mdHKh~b=wU7q$r#g=(aOou=#lkCufPmK(ShGp*;26Kf z)6*%Z-lGKhn~e>+3XXl*^`_AG=?W^n+hBe}WQw!&L<=r%#?e2qCq1?K=9u63!VR&k z2a9{+B-YNlziB|e)xUHlhbaY6P8tkNt^nZE2qmf^H*j0}tdYw{QB^5db z!Im>3vmx@8E&xqmE$4qS+*@_ZZb*%&?ctMmiggAK*9IbknY7p`A)!w%) zPMez@K5sjO-|DAe2Xx%D{`10>fK#Sp7g^w`!b6+Q-B{9mU%i7m zIUf}v=i|KWTeMg2Lya1oMS%)aON%O7@LTk>M+PY2f>IEK#i4VPa>oq1+lXQYch69_ zP6-QuRNJxmDq%(rB4JY$XkOc=P`lHf_+-UjuIUvCxeO{e@dv?-TSAB&MMGGB%_dJE zt!m37_2uNDgZJFNb*f*)z8af6|8b!Fs5%}WWYoA8?Cfh@6?R-*#j$^&EQuBKM5Mq}G4We__}9w6axb{Sz^*)+8IE;-o~tJtR?*-*K-%yru9p?Xqe%9~odqavT!lQg z`+%nkEi4Lr(^)7_PWGQ->;P?8Qbx*lPY&AC>_1CqJCCDIHbWX|XTwhHccz}b(z@p;Cp@~(&+hg`2ZA9@oM zf|R@$XvzNR;!mU^kBj%oEK92OCoJ;Ht9-o9@3V-`A0GUsL^9WIf*h8eEUBB%)M5@D z&r>OsR$R8e4Hrvk1d70q>i&TUOWp#om}v)%eJ;p=D~HyOlns(}jOfS`P~vB`nsj)Cy& zWy@zv?a2^*8=10FVB1#YNdDW?YT(1=up)#x;mik7C|K%Am zdg|}6$Vf*hcZ0Q^@y->p&7MF?f0CNmWcYdUM_RBM0c#hBesx%RITtYWRJ7l)!A(8z z3P3!GyJI6VbvTs7F!)WD~JcFO*RchfyG6G*>~cYsuHeN_JDzlI9cJ&dJ;WqI{fYVXje_( zcW;w1_h_qC*$;xVH-yp?FRgI(!2I<@IcL!gmKp*n%_rzChpB9*+G#JEwZ+i>w=ed0 zFcbhF5Cv)vVvzkYp^_-agO#5a1{szBRK43Yc_y{Ul~3>!BI=plV9cn5XsyL_yn!C_ zpJ8iVSsubw@wdoSp137uXGp8@*Z&wQPM5~!$xwh=_UQ2z1@dP*i`z)659ZLy;S8f7 z%@Y&ZcV&x~HMf_<`;CksXD*A+Wq|!VU1tkx_lNW`sZo{L$hB=IY>=pdoB>6T6Pu}K z|4=!uDQ*{9pt*lNQt<8m9vM$4thpixw21Z@n`D@U-um~c74!^vg3CxU3-EgH>+OA3 zRP+k?tJv;&BO~<>05OgiS7`0SSI?)Ad&Ms+7Rr4{q3Q5T%;-J!;K@`1* zm`z#h-wrMB_>rR`6QD`e(aa5(adlDp=4*IC(6tMR_*4^+gV+i z+fo`K`7~s7)!L;-@ zl8-uz0Y(8nTraUta1pJ=vC25epU?+VYq?QZUIaMz!w!P__K*5IEHGjP?mpdseo7RH z+b8ShaR}Osb%A0IrVp!C5`aG<{mjP$B)Z-J(Awq^Ke>e#es5X}TKtv@8Qvj0G%p#K z=Koj>G&3ne@wCL_C&|2$us0-Zxd_B^QWeCw)$(5BBTfRED88TURj_4w?RwWfuH+LX ziT4wPMQtQ1YmkFUb#y+CRTiHOlhsbY^I4X|l=!z?JL^Zhwf~0fWO>9c^n+0<&8RxV zEF7zNp74lxA>!+`w?Z@bg5_Qsu2GyBbh+mKoCY-be8hz*M_KW!muHLqMX#(4 zW)|0qhA$V%(f4XjtKtLu(#Mklj2<&0E`hA7(_A_pb3temL0Bq|gAT!ucOL}QYiJADj0zu< zR>j+*mji0>d0${SZma5q=9?Pfz2jL|<))=R3*$FDkWbboX*O)y{&h}|PEBAU3T9Vw zpMS6G2=C;=Ucp(0=$4zJrjNIANxEb@?_$QvaOq$RP|iZ0zeV+eUbv0r(7>5^02~$q zgh4&h&-y*N>I}5ADma49->m)#fVR7H^2Hyu28NpXwXO7M$QHEQ!B3 z-cgyy@}$c*cF7N$ToWFI>JqBHi{wa(K=1u=`iVM}6rB_|9Uv-9k+doTvF@-`10XKu z%zZfjgi*!C7Tt4EbNDT)DQd}$9-ULQl}r!wjlA6axj{dI16x<#ZZ6B~=1(yUFjuta z=g-p7yP9m_Vkmqt3*LqFd2|FT^K$flZVykP{D;y1-@s3T&v*=ar92NG zUk|m{QYT2?e`o$Lfi=O#7I9jZlkJp3-1z4!@^n;HH*0IIDBWO(Me_T5UPA6Qps*=S z58MxaiXWRMLW2ZtV+(ur-afNNxsrV4S_Z;3aa7cNB-ifsxbK0uP_KG49)v47FGM37 z9Y^B=PhJ^Hr8<_UJE~%5^$@3ceQ$!DNf8@og!9lF4PYTuv=@Gt6?-GH`3+Hhhrl+I z3A3@rMk|X7mBb^c{{q}V7xS4NkM)b>&1YN_d=%v^W6^|Z=nb9Asrj7&h0oDY$y@ih zZUS!&!)g3Kfel3*>#q?SD?_&Vc1xcSi;`N*RhbKZfx(y*>!%O-Tib#jL<$QP&i5S` z@mM;xdpZm4cOCnp+cNvtG0rNAx3mlkEib+dB2G@eUJw%S?eSPvW-iHIXL7JOGJ}J)qoE!5y5U56mMB^fu;@WF9j(zZ$!;f+PvfJCzcOvqusB>js;M-a7OsVc!HPNNdepUZz#*zO=;I9pV zcN2jKR`)pN{|v+$ApS;*4%dc;c--?J&_BHq0O`{wLWt@1vvat5$-K_5FpyunXMOt? zNrY=nUIL;d_}?cC4|wIS-yZc_J1MYp7hO>wk=OY{ftTOOKTq!>=c7W!^G#9S+q`GI z`b)aB9${|(1_pLc2KKGlIF9(JE6=l0P8_*Io*x_@8iB+Mg0T9t2Xj`;KLi>A?G%%^ z{Fz7#;#$?g_9~*GWSqv>l3pW`wCQ=Wed!Qo^lpwfwFV7O3z=X_9;EfroNPq>H-DCq zcr|7JO9k)>NEyJ%UwM4EblZ#-K>Vb_Bm{~?e1OS$8~|^?^7X(&l=f*KWmi-o=kugZ zRPJv%ictp(gN^HLo4{>-d%yb=d$9|_=0NA=xiOCE9@icejG(b6Q5PPcp3)b}T5Ik> zjwwCg^8Kp*vOaJIxr#etzB`N@6_rrd2s>fUdiL+sH&HV9)NMS&c|IK}nZb-4-;p&S z@zb+cihBE2RZk$yuBw#X2+BC9ZId~>2O{#LSy%vwb$a8zmL1w>1Q7UYvu+`mX!e~6 zcWY6KVDp(#(Z$xwe)flRUiZLT5y(&f-Duf35l^Kotv0>!c`q16<0fu>$HAM0_A5r= z$0N%9>)%Cl4_ja0Lm$uaw!~2#{xHdm1yU}-B1v--i^$>G!(n|CtFGIRg$Isjx~(|D z&8e%dPLE%`J!i|?*!mNPQdOn`x^duyJT{mCo|*c8{>feek@ipWym8upQ%&nxQRh^2 zm1oBbNmE_dtgWt}Xd57bqMY9NF@eW8gn^xuAwQNB8nAYVcT8sHpI4op_tU|Cj`x*s z6g3yGTzjaATR-~eS_dF3=X$3qvp!(wWg23Dzeoc8z(fY!{a$u?9pdJ8Z3q#R@=Jm| z$xOE-<5;Y=zCC)RTl^L7v@ZP@6o(MY5tQqS(-eT{bLSqrkCwL8rhO6%VXSr znp6RNZn8TO_mYln(zN*1T@;ne-G+(cJE183oY(s`wIpKaz0kBnj zgt%RKAqDz1FL`21Li&&i0;uW?cq~*6Brbhk(lnxq-`- zF$F><0vOX6`InGmOG;Vxw<*v;awGKazRQV_hzD zrX%Uq#O-ueH3%g;HL|)Ookd{ZCF68L;Dm_Kpsit;lPDIwpU5hB9gK2Z?qBei8_#zi2*L6N*iT4ez*@%yI~$Xc35F1^o}z9rV-IIb85<;*t}2UB|HTwx z7M^7~>K2TLIo!GbqHXp4lOC}LU*qLsa&9v9HNIpdQkdBb+iP+UUP=SB$bupPO$yq@ z1*JVJ39LfJ6OmP^d7o|7>lz`c&3zN~fR1a;lsE|tRm^m)ER+MuEUI7RCX8HZ|FgC0LdYSY*!D5+-Y7_#ZNprq8|&X-&r+o&6U zE>uh$=1el%ULC{rL@To6qY|jyw7#c<#91!k4Jr#?iJU-M_`1vwtAdA!NIxG&_dn4jY&yv3d(^#7u zLpDlf`YXvFjTS#I{BgkIW|INbAp3Yq%xdP>CS*O%%;=AEqk!y<(s;^}L z==`7(;ia|S+CeTDdN7jG;Q#j#?9Mkgvo!}eP8Q=<5+XO`6i<#?E44w?oAd`Fshv`i z(3NVfn3XiHaLq^uwruIm&Mq;xxfe6q+w=)9=JE6eLQK*-NZAT-_}9+fTfTKy+edv@ z+hBfyN6IolnjFz=++pRMWnA(9Vvk(B^e_q#sMgv_6%3Ecf~ReSb-x`0;1)<|lX&qa zVKN`&SvjY_YG?xXQn4ErKk*aAefQLXNT-eLqRjmDj}o#NA0j|0PXtH5js=&@rrDHMAES(tfKu* z|1h#nr%wKcHr?ID-E*)+5#@Mq*Uo0S!3a%p5X97BUln0v z{gqS!rVaz)7F;}ISsxN5u!{nx)9PujdA1+V30~HXr?dRn9IBYQd<=X~61{HN_$i#` z;Zt9lV?MZhkCPQ|B{2lezQ18&HbDMaJNu>BPL$zWFGJxbLk7Toy(NzX6eTul=m9Fy)RK(}f+q>1wLJ8iU3K8B(S26ghj4@DK-UNXA4A`5*1pMD}IM=PNQ!WZ3>;N+rV> zcAJNvc(}2F}n*M*t4aN(~QC0qm0=;rI@O=#fcf$!omsckK}9$8S8q+TD65 z+~I;F_)o%ryshV{f2DIy*k(*Yv0h0ro|Z;2kjDUHm1iEuttx;qMZxK-UEH_8|dJgBK>)8(-3(q!f0C4tP$>ZGR?Oj}}#LG21qh3{S`d2mD$|qB$rX#Gn{diA9yHw#n zGxH@--UHlA;*I3SWQ@*yEha$*5lOAm2{kw>nmhMK*;ID2cIiTfj!nW7BPr{e50bHZ?fCv|`b{O_Myld%uh1KizIew% z&dOnx?bYO%lke7*Dyc(-cRO&_W~1=ku<84D-csQ7*Xt>o%)9_+-#PJ8b!SYYp>6D{v5cXAg5N(ytnFyjgXbWSG?=W6{MMm2QJ7758@7*Q5WB*!`J;$ST7<;BZJ3% zJXQM9(fCxr(20qwk&+=YxW5#+ajA8kqWt}?hgt7twxfDu-b(LeWIC~Ra|A=e^mysl zlBn6Av6^ZLX|@!%-KVSoQfN#eYQ^&nxwTZ*a6j?!i(364|CJraL&vpLS(1xjui(u0 z1rdzgJB_EMb1B%LH{*-$y5bR^UtJP}`lnw>b&;$Is{K*Gzp-VG%U;s0?w0o7ijQ)$ zkn))$f_|?7M2gr6@`0|2;%$;{0!ZPT#KNwNT4jt~IjJO0x=Fxq|6t}U|L(FJqv11v z@H$D9tEe0@-WgKW$QmicJEScmi2mP?C74DpVxJH|jX}+b|BehzZdDcVMES0OJVYe= zROiuDe%>mKLB1DgXfK3&Sh`_S<}H{uy|>If4$ovRm&Y@exx2^SvHIRF+O!@vhgetS zeo@c;y ze(V)hMYjp@L}g6c3r4qaNRUscO-g%ro%fRk$zQu8_Uxre5993pd%u^p>ZK~z*efn* z5V@jErIX#FyyB*c=epVGpDtLhy2q};#khqrc^-qY`<8qOCj!0e1$8C1i`X^rcPCO+ zo+ejqx*Um8KXEA$%ur^w;|77M-|F875EaJC!Ds$!QySXor5J-ZvRB{CCzO=?jeb#) z;|J{rq6U-wAfak2w*M)#wZhDR40GSJbVcJ}e@e4hg#n!(T;tBobd1xicRga~6%k%h zVuEvQ<`)-)f>%)6io2mi@uDR3OKvww!Cn5vI*#u#*(FL+#Cbw2?GiH}&jW&}yxce& ziK3UX+)`Dep9pncx>Z*T6BeyU_n17%{>zd5MZO@d-*P*~BJ-@{@wUSspa6vxPQGzT z@Kct;00d;hRMpNq;v@RA@>;6-U^I;@K2W7)A3@pr@%f0aC+b%KOE~k@9%| z#F4R#4_HmOdW^9wakQgv-uzVxy&~g)(6-oJhAk=zIWXkpnZzHo9xlj-6D4E4U)x;t zd-v|+f4zhBpGPpk0DAMASz=I2U91;)S+U@Co^Oh@{CB4c{JSHE6ZTD~)XwuvbOk^a zYOukx!Xs`pj>Y=jmIHxWlRzPI)LyGh#qP^?5!>G^k~3D^3MbdE#2*m{znZR;9_YuF zDo?#|Ik~h)viD7N^<{kvoHN0H1mv-viFW;Q?!$vL%08my9R9mIUcDtPOVDqzh_NWP!%K-iR)0U_Ye}oWpdQ!wbBP9n768?OJERu9;hQEc${`q)p zb^>%v8>?{+xxuFT2;9mD8PZnE#niRb{gp26PKvS$&laV3bk7R7355>lY>v7IPDh^w zG^{9X3&@q3_A-8b{jX_UjeI=+>K?@SazT)S9)@e{!5XeP#+X8r*I&+z@T$bjfJsP& zwu1ZFnvueFzpT(kxAWFN^7lMCr6SiE0VrN~56nhxm+~rhF{CFCq}A~z{h6jFFd~Vj z#H>{piE$x~gn9>F_oDzvV(VE(o_Ok!Uh;_)3q3NQt*{JJW=nsPd(ZQF%%Y;FN>82* zMFGubvcqSWFbiKLcVd;_=f4jsO15Mbs=fhe-U5rda>+YMptwSF4F6GY_2q7Jk<25_ z1ME;)Je*%tWoLjv-*dH%qxs(~)%jeWIhRwfIlWo6j3911l)7g!T0x<!oLqseh zxVj<-2FW^dm=|=}D9?@2$~L+h<-fvsiWr>wFEEBvJ=5zEmA{grV_^;b4z$9-0%^+A$pdci=DVY5~F zDlh*mw+;yDe{PsLU(Ay;I1?|?uQOUtA?ZPzZ z9^oZt+7k?<;)x%`6rOva5DEwQmv%XN-+ZkTffczqIL)QPMrYs(7fRz@&GVhN9j{NKw z>to?DkzQ?k#-_a zzf9+oDhH+2OYy%Q_di?|@@{NxS;RN7AvYk2uWf}(a;hSmUD&q*|Jt695gEZd04vQd#5gMAhCHn(ywoa+z|F&A-AyR zSOeed?Pre4V9uF$oBsn%O-%o%HZ&&URB>s}_L*q9;Apm^@GNZ>@%2enJjUA%ZAPGwx45WPYi^AO{L@|T$x1Y+V)Z%6c%hp9ao0NsGMq(X_UX<%p-xrshG8em zm(XtggqT$^aHAtGp{TvLx5GCzC$T2vA;Ti*@$Ej%)9|CtQXBhgN+;__{_T!)gh0Tm zpWa$|eRilxysS0#6RXEbOZV%HO1186 zHhRJEn;yMrBN(NLT$&d|oG7h*zs@;y=HpPC&0LTB`c6LBk`k4A*8fXfX~$Ojv{luy zZig&4H=2BZej`Znowy*>L(NE>RATJsV5O-`_lu9D*k}jITD2Ift6 zavq0S?~IIy;GbgcNb|i+8alBsp=ZMM{ZX{Y$J}YTNXhIl3g$rkQ!_Q->h~fxym<#v z)10je9EXHP4pK8bOK95IuNmLM0s*4%Owa9fH(U@Ks?!+{2NSoRTmv}~k`C}@S(5g( z`yg_h#96t=dct_j&5oleVtqr2U-hHkdSC+uwFn6s2LT$HxGxQ|-pnR?FQC+TQ8!8Gp@YE{)$fbw@{&R6zPwrw{HxP z7XX?Gb`J1c%R4;7E8Q`L}p<1UgVQwtc3i(+Tsx!euAqX=XUnczIrvq((?x|ibLUTs8QgOt{>+4c*53Q9^J5VbHUvU;rsYK5*? zBaxrgDELk@K|9|&de?xGhurML-ghb%$fA~sl4NvM}Z%7p0yWB-;Aq7vY^&HsEx z04)kYGsrZXcczp$xetzieA!dM?L%Zosa&L8_+DaJ?X=+Q>+ZMknXR_`3;5hC#qfP8OZpVACG+?F0>jE!1%~iIba**kFJa1+hpZ2j@s4~3a*0k_NRV4RL(C^lur=6^5(YRS_3w0=tx?I=O z_9*lOlh--#u&Y5fa~^R?ILN1RWY$02oSEw7;J_ogAbVQsuMzz>qQ^*}Xz+EO#?F3E zR4k|l8}Hkd_^mRuFnbbsKoB_n05n9@79QQ_hc4GZ`LY=Fh$rK$v?| z|99&ycJc7L2>br*>4XRA-Bo{B(OO|mjujG)2HlkA(yfDzdjtqRYr4e;Hs&vK_|1rA zpEX`GymBHtyB`M0D1-b!&71)qfuQab;<+CEou0-C_#%$#y1D zMo|3+z~4xJqz*TExp1OFpW*V+gp*%|I&G_-Sv^CUBC}D*kljAQuq`ViTug)48cxG;_gUNzBiU5 zR@!Z?R5e9td0w@UVWlEDA#kk9W#-=GUK?Gq)HRaV$$soK#@{RCF&Ls%6Wafd1+cAm zR}W}AAWBnFC{Fo0%=A*2qP&BP>*yUmM@{7-$t(_{!l4#DfF28 z!NSmRaNnNJ|EI=g@}N?|&ehH1+lzm|lRz*ee$}aXNe41DbD6OB&7|f#=R8+hIxJ%e zhg83Iiad-RBRwJ-7d;rx=3dg2Ak*9x)PQ_aQKPp{L4cQ`k#d`;JSYD> zXCD7&-YP4@`5IpM6pAPQ4f=clbdg-a>znp0(>Z}k5cQ}Ti#>zuTc**`T(UZ??cmYK zGFdoH;5TX~k)*f^6S=#|{^tt|Rc0^fWL=h0&le1aBu)vE?>D*FxEi5K)O(%UrRZgP z2=g4>c%sh_T=mDS7c5|rntLwDdY)p+rMcEVAvg?Avb-%nD_tFDRUyeyl{#(}-O*&- z>;~NVP4CG6J{jr}<9K)+*r5d~OYTE#MG~ ziLL^8GjmZ9^ODnW4Ki=D{0Z68bs?YKQ|EE%+wN}K^ya$`$-MTEHq*&xx~NlC0LB68~hNN zA5BYjWL(Fp(s9@T$1U(?rw3P&=gv_&U3N@yIwsYcN zsR)AikZ>3SSyE0sox!=8T1_sI3sSM^94R_@!CVP9Ih0 zf1QY?8uNjfcyEZ^is`6rjD|6dbo^D}%ZrwjEy3~B`#bvl~jNMZmGDB6=Y=J-|x3y5dtwt3@E2!36z-BQp-79u+x8-2rcv9l_OpD zWcQWJfiYM9jQr(jGpGvwC4EwUdUKU_-I`cWhxf_Ocx>kybtS^i_z+?DR_@!mBV8PNp{z{S z-T>dz{}Dk>|CFt73s?xLOo6?`CX9pf+}%u8xn38SL!Xm&SKPGivN9yO*&^!wQ)6+= z_AO3Q{~NSzcuDNGpMYtroPJZ|APj~?0##DXsSJ$f zpY$&?WL2{jNVNXvdwm>!4?FfK5wdQVRCygV!L@iMf`u_MS%=Slky@OsV|nY!>=t`8 zbyb0&0SZ^)4?yHMMX#n}#39e}iHMppX7WW5XX$EZ$=8RTf`!$qi5r>5^F&}O=M>Lc zsQxg=5O3yQnw@-Iipqs|2FCqk|DF#LmHmVS2UJ zlN?`Fc%r@rA_YArUfr%cbtyh#F$dZ>4nG61JJ$S|TKMBX?wHJ{`?8366Lx|4AF?1%@El7^v@-IykKnb@tUyQ5Ii8TYv<+%={q-x#bqoA0 zL=H|!Dqi=KtC!$}Ib1&X^-~xf=8L|PdQ9lu&<9ILy3w;l2QtgknP1X9tXgH!L&Y@1 zPjtWQfy|sI%geR?S4KRXoZyoDLl&3_*H>x!#WLqFH1P_&$OOxM(FbKR+qcVC8Arz< zu#W;DzH-v9;|W4eN$_djU6f9( zpMi_nQfEle5PQ{&X7`67!j7LiGYQE-dh@LfSIgzJ|F7x^JKN)#7}A_3>)vvtUn>}u zH-VQT>i*iEhfQxlSBSZM=mA!5QI`Cr$LweC3n4n&6xlb4@r&QmfPV2_1i`xcuh5ta z58c{FS2u z$3;U4F(;2RoX8^N3Zn?|J?sjmOw!H17%N!*ROid~%Y_6<^S!nMeL|qEDC}1`W0NEG z33KMRdYA*#E62HD5|9v?=$)t7-@QmPEvsw^%2ld$JZlFOF1r^W@E-0oxTYWba%Gum z+H8U!1CP=KUF1lXL754F!=JoK3O@?)nmSNJ1F4@3Dd$Emg~JnVmv9LWLh;>i=I?hS zMVAIU_`>_n6MWS_eprZzv=J;5eg044l5Y-VkHin7G;gE%)JkqYTNxH?!KA@b@`M%F z<-2j{kvSe>CHB>jH;Tc{J8;X*7MT=SWK;5~qAM^-Y4ahjFI_ub;APVx>#6cH8Nhl} z?85vs%bw&-E{GL@E}7CV-$9O+U-Xk`f+!Hmke9m=Jo5LlD_q1!j8bUYKdNF$qw|Lq zXTe#iF5KBXxfdtP60mw(d^N{t5*o1T6sSC|DuD3%c7~l*{Qewc`0HtR2d=J9f6WGY zg<*-a*)H1%vp}_<7Rso?FW1vf^B||je}t}aw{IBG54^jG&i>5G(5DeeFp{9CHDMk$ zCyrk~jOGc0fN?br%RI2Bm+lbwM1YY;FzzOMr+)(ws=;Mr2^;%W`YiT;$ zjvH;ImFu{WBU(4>h~GCj&t^MRfDK2nt@WuJG1vm9UdI?E}>mw4w{%*tUa*zu6lfo+z$R&zP_7->G`WQ>6PSm zV*$wET zK$9hA7qiRpr+m!i`Bbh3y5P}H3W(=!l1|<4K`hG$ISp;`z&YClH#{g6eUNcoAP^C< z~i>k8>YO4*`HSX?Cfl?^$?vPT7ySux)ySux)yE~NPP~6?!iUh*R zx6hBW&p((e-lv7&ct&MMV_7aF3JA7!K#gD(FjuZfHr`vTVTPBn+PXsBYKaXFyrGJJb`Wo1 zu2%v8DSe;5D!N{06VzP+!<_Ctm$;~{vQ9XkxZ~=y% zXHKW+tQtKq{&^ZEE7iRj$E&FBfeAl8M2i-L!L^BOdl0?Zs8!U?9a>U(zTD(8!LG&t zJO`2b@sG!=wZHOQf^P6x*UFj=blm$*w%WpHCEYd=f#P!D$?wS9#R3kg?^k5>Y0bU% z8-lO6 zG)m|3N?-EKCvzk({mkkCQ$96ud8ohwhp<wfNsuju+wH^ z9)&+^Ovl~?u|jD6Puh9g_;KsTd3RT&T8$Zxa%3m9Y%p%gTAeYNzzvGy`6Z1R{f0(u zs4}m-Hzt$9+M&l0vCPa&fq}RD46Td!#xD{4Hn*-!xNeK#??H@9Kho4H9gPS8Q0*zm zCvCUg9S~aM;bSx5O`<)Qp02U`m8vo`P%6>!MeajecDbQ~mseh4bZXdq`#;_KlAV`(E@E3lzj;@zV+d+YjQadfE)JW^+IyGxek9>u(-wrAxs-~omac_ zM3wj6A8X%V@h?`JyK|}ZJ)i=%FNjnh{2Ap?;d8Kzofjez#!pTC_ zbR@dEBGZk|_ht0Qw2TtRcJY#UBZwWg@pGvUx7tu2rO?}_vmpdx8` z8{#f%$z+P?p4vv2QG5hm(jDdT6+gK`Lw3|5N1@o_a;K*>Gm!CH^cxa?=(T@iq%LYY z=2=gsvUvZVx;DJWaWA7mXaoI9l5QtLa~Tw8p2$uke64@PWo>`yNqm3lgDgGaVw%FM z47*CrH_yMUHuZIkJo&@XBFGVZa?k4~UVBH^>EGpR%gV(zjTa0Wsfm zz!pZiziX22QLN2mPwIibUFlc7n9g^Pu$^bUWnnradg!HHW>-Gu9`BF>s`$69OqYY@qo${cLszk;Q#ssM21dCK)+Ykc+ zRhqCi{sp79u{mi*i>#936eLKg8fp36_#=Uu5W}3I5!fn`Y@~BONk2Bu9_;t$gRxhU zXt_#M?|A!1g=DjB{2+LQ_6{ypKd1NXbNh;qb(}%3C$p}Y5SWG_u$?YFE)ETi|B}V; zv6$R(iuFJ;ZQBocrQ>;&db!z|9E`>nVeb#z$jPJeYPHR-uIq~W?>P8xFd4?(6ZoG` z5qy&~bLBZ4=P%xbUexMvC(iMC=C9H8TF&4Ly3k2s`t~EEC}75YyE|=R`O+VLiEyxu zVvU(^0(vxW@=wpVZRpu|7_J>uLG8hbAZC=MaD@4{zu1O@jY=s`L_;JbU%@cL)w39f zjVIt8H`i`G6Wnw@Hp4WAZ~I5sjCCDkNVdx9?Xcpo;i5&#ZdEYi`$PZFr>slQnjos~ zHU->e#M4f9lwmG~+?!LM#whSI8k{JuQK>SRTlPTHNDR2OYc(G#=z=zNY`y@V59f zzr1uwB}Tmk@9eYKKWpM5WsU|$0=XlE9&<0ykt3jk~NH3&C8d8=7c z0_zyO($bk<1W&Zm(i}-`y+3!DN65R-!dR){Yh02Y29OwZ;RKMNhia?J7-$BXrpI*$ z_rVP|a6tWEPA4Q3Jh=?G*Hv;j#Xd&rf+Zl)lWnrG&SK2kQmDpST!F?xy1`49sBoP} zqS2Of_`sa7-DSJ@mQ>#ZwJq}NWO@OUBC8Eb`x=sJn9%y7<0KUg^kzh#?|TsiHD>Vt z-5WXoS5(W&&VGF?7oG;ocVy^hrT(1vAQ|rV-53!S*&Tu>bwooR5$1 zw@x3`j+r0KnM+m+I~1CM1@o4zS~F7YfW7UCpxY*&!5HqtH1n#tGSPWBheY)@!j^P{JST=E~96f($Y#}%f&F%K=@M*POB9Gbl_wf!}l#slKr3EYdws4mBbD?@!;(^aP&9XW5% z0#8sGLIa!zd=2*4QSYZS2WK=u+;*YMF7NFEyr)GT@fthw&m@A|Skml+2)`40c?Pe1$Z&66=x_uB}Z z+|6lW*;PjJ71}H0J;6{?tvBW5!8HxHIdt16P1RW39fy=N$m5du)Q8SuDK}e zZ3S%nu~4^#E3CQS8w*hY_S)=s7QtZni`~pBv=Xhw|b6qmNIJ>!-M$wV^dK5y}>A%9r*I=@%}iejAJHgozb-x3S?%Nv0iG|tO@_~VlejCovolYfYY8D zisX~drV^^EVCvU{uslNGZT`-kdD~WQ(Gl*vrW4V=jyICQwACtX_>t|!C{Szl&ghxI z+l`=xH^y|BIO0V@Qg)>o&U8z4n@_N9fN5766J7kEX|d%`iHF^O1X+Us0JJ1}6k zy4?|~%J1&zabmmqZ`Mt(|AOJmw42`3vib-`&Tk4@L^kHIlrk13f*Q~DJI)sQdHGp0dTs^dDq!Te3ZCab~vb)Dm*qc)#33XC)pPs)kn-#A2lm`_#tT0UJ5C@omTqk}pQF*js!`-o zO^jX7G23oUB)SV%{tHinW7sxXHOeyHAjp2WRl4UZa2F2Ax3lYmTSD4s@#nT-ovMl&X>%(AG+CL{mp z>pdX8k?eUp-W%wBPCRTjn#D+-HOeqOo2|nr2zYY&@s^pm;6cl z4KDD|3~=(ki?Nz^Dx(eoz@&r$-1*@E977CdKCSG?_{qdPug74b;S?WkP}g8ugqZ!v zfMlAZvvK>zo^|KC9QfqXb=IdcCx63@A=I%gboPt)-0|$ZaanZ^3!Yyc zuTYI+WW`TSlVdJLbXo}|*RJ9g^g9q^eo$&XzWEX%|F?#gS8cTxE-W*hUQdfNL15{@ z5~v6EZp*VI?0nzHxC=34h-tpMcEjvbG=SI(P;o_lH===XZy`{fG&Fgvidu|C_+I8W=OIG z0~7%`ovJG+kz+g7RS^TGc74MlCj9t#+;m}w_-_PbdxsnGcDJ;W3=T@#Xm?{6jOIQU zI#8d*G?P=!0QAL!X>2CJ`{{-jhmA;leahFr(zHV40DEs@aBx6y6hUkZ@?uxK5Rt$N zcA=n-gGQ#M=I&zoSNU1Tn>7mP%HAlbOws3jgBExjj!5b_QX;pgB^8PPJp=sL8g>Ye z6gMFP_EBtNLcsjFKwPnu+-)wcfK-obUWg&dBi`dKGz~8TCEJDr(QU6k+LbYIrv$$o zXX#0MjBQDONW%Y+uYbr5>~PDyA-L%VC@OvkJw}AGZKCZV(dvGY=pKjEc-CIMD`-Z4 zQs~5*z!SH^2%?^ID9I37$j}6*C&9_?@wPT2;xLT-DkLi(8lvI-Z8F-R`%;YBH6YNd z2wksBHlh)q1b$NP-*x~0&Xivw{}*w+4Hu5F-FV-}?=L7TGpna+KBoVVBdQNvUpej~ zfY6AN(#C~Rn$Dm@ksMqsDAN{g{z4cM70A>?bjjyIXiZoA^%qcqao)pn9nX>-pn%*Y z&_v*GO{11qP-A6?c{Z{dt8&z8bf~}b+%H*H8d@|#7M0FSYoX)%y^i71qRJv-7deKs z8~^)vn?u_AXdI3rjbU+Wo#adHW%$Q3J)L5>}bbY8VXW<2=3RSK1h3)e; zD@|>MFsiCQ?bm{GF2-#utLvVtPV1 z4cDH=u80V%FN(`!4sH>qf_zrL!KAfH{P5$4lXD>@tOBpbixd-n*Mz~9)d)4cIOdF- zl*3tVH;zDs>(%h0zR2|0Q&@lXCD@SBKBz&}aGV^;LW?>`CXBzmPi5Tpzh_KtnYDih zq!kG-$*X#Hx?fUy!48*(J`oenDE-X`Kr)ynWbY6kj*mXopfVD)+6a{%Dcbi2ddzoB zYPA6vSVT^4?OOKXR3=M`R&V!dekiFVc5~sV7J50dy72+LqA?m@(wW6kk@w^rRhgJX z6*C(Aq^po5kJXr&z)6dt(^C<8#?f{b8V$Nyvc}6IqnH|i7m({xBB{+O0^ZQ|h-d<; z+Ym#K6%RrIPbT5os#q8)kRil*UFEG>xkQG1%nmbldftW``p6jBVcMZ+H;a7|3kCjn z#eq#ySQ{in7T$7WSrc40!)Qaj!&*qXx#Ro(vL-(x>oR#5eMr>inhlVV1d{PjrL)4)fh3N#va8e25~ z0(D23JvD?mULUr2^BL{ZIGpdx1K;SkF3A`MaR30(nr>ucdvvP+h;-a^=<`7WJa@FV(nk0gY~ z@Gv-rrzj>01y3rWT@$O&d3}{_Wd#d7mi}6CjkzPmsOslqilgIg|}M$~QTJFhuIcdiIqy9p?@FiT3S+F9AAI@!SKat3d7 zqN)7HotibBE=-QKCOh0|P1f*-_Pw^6;N5zIlcZ zIY8UKHx+!3bPZ+!2;ByvU-sv2s54-@Ar;yh?Pb5L+A`0jtGyUs(R3K?(#b`C#J2mr zNBaPIgYyNKr>4%-ML9F7> zoBWn2svUf?Yf(Iar|&DYCT|2%s~<5hp7(GJIB<`2HUyN!&UZOc(Gb!FN=IY&$ z;3|#t$pnu#OYk<<@bNLCi`;WT)gi84=?mF|glX|{Yz`X1_xZhCA`z*l=>BA1S~Dm? zlfrNrA46n#VH)E zruYE`cF^EAC|~VcbdF*(V_Gw$rJuzbggErbWr0S7`}UI}q^4JVyusnRVmpZH*k1n} z-#&rS3Df&vp?iJpsN87dI#=>pJK;7d<=RED;jQJ+bUYi5=9Gg6WLIWUy$k0?x=)5l z1stq`ZLmWXvGhYCYD&=gvtBEBmaV8#{IVV!^JU5-RaQ zNy*>t__N7@CCCyCS2*t70E^k{yRyKY5EHOJ0Bodj0`rfGc!DM)NsE+-LxHLWulG>q zwY`A)8XTw^y_0oPOi>Hop)b=)6ffeP4B#FIljg7N-& znd{y`qB{5~ywJA2t?ecDGax~PR`d%FWa2iC1S|jp60-4K4_9i>UulP+xa;ycYDL-P8SE&uUj{uY0!>G#9|cgFjF&GQ^aCf zgi1N0dKv2kRmCr?%f|$*Z<30ZwtRtYl{5>Q-aKX+i|o$nif_IUu%QOCKPYvr=cah7 zQtv-i?R+wd($qD*ALA|ZJ&6=Y3*TUc!TR|~SJod=avez{Lgk5>UN~k?eyh~7v~^#kAsuXR z*aMRyi_45@&-4~m;C~fCbIu1QJ%U^dHKbS;Xw{HvIHFR+WT46`(iRE(MG$|?tH7FW zs2R-)Nqa4r{rUPOdAD|%+k>|$xt}pEfem0Rt$=PO%)guAh%-qU3QG&)xIqz^0{o5; zLc+sq>g<}%Pq2&->COxYlwsqa29ng`40Q(!Apy;F|A$fgUv}}o<_8K0pT|Q z0MPS(KRHEu6fvBbBv%d|B!Tzh{<~mp;bXbJ%RIov&Fy|p9Q{e#?0m6O$9>CH$NQ=k z)bih&93EWM1%J1*9k@a{4B#}K!0GDhqWw;&gTZRXgSL4`w)#CsN-1t;Ma?H8zQ$)N z-*obl$j*BQ9GS0f9ojLM3ydf{FtcdK-eT2AS5P}KltY?%&z2>WA7Zirjw`d5BXB{+VMn@7=rr< z;P|R&OVMe<PoGN2M`s9lbNQf2@*^ z>$?0AI4>87BxC8^637j=W;$?BCzW&jvpT93b{xCR-LboeToJu|cY%*T|B>FW^bpFd z@Ol@I>P@=Q_h{M$dZdZk_7+g~dp}T2rAg28|IB90?+V%#0hnmaNnq zS>spq2o4*(N~RC*)CHUNAJQD3y>mHX`p5Q3ZIB8d%?IO@ar0kh8$Y{UxU%!SRUq@8 zGVEz7g9?!=y7$5Yxw&N6o^_|Q>OZjIJ1%>)J>JR|-~=SouQYy-fhgi$d!jsjj&AGc zoZjFoZXlX#5PF-_KYa|)^8e=jZnV_{9iSAMMTPe{aXe?t-gl1X9~6CrK(7gNy$8<< zzVf2g31-x9!QbKQ73_KMls={?yJ>E>>4T!cC2F)%^BlQh#`c$mc>i4wx8Kb{=~)h_ z@;AX1?n<3#LsTzBw3R; z?eb=NN68Q3^ZA0-lM4Cs&|an?cX{4H+D63nWHz^jyu_XL*58po`-nJVee?X|X!!N^ zv;6gk1DD|M{crG@BGm;QapmnilgRCP)3UlhrOrA}=5Ax{QCfM`NS$ci zCn5WJzues5;@1v1l5pw!@ix-rQ)&0VL65|<;VQ7BTH+4P)WYb)6lc?jG=RewtCC~56>Bg8^dvz z3eUbS^>cn%crmaL`a z*+?&Zd{SeDaE*3*oMyAx-FbC=lf#~ve_p9{`hP$8y$lDEo_td#J-87DQUct2r?P?i z$@p7mvmul_?#f00aUG%8EK(6E>nE!^(oTUD~J|(3}cxi<91(cM_wO>>h}u_=!wSqeF%SR9S@+$%*K-Prraz$fy=q4kG*5QQuuMU6#}21x7-LjTl?Fvjk+ zyzT>aUV1GM=C~jMxD~`i|M8Zj88dCJY{^G=gY=h6o0-|sYmR%#vu{2>9<1|6q`rk- z$gxBi5r~XMQl>)qQR- z3rjcAP;XA*03xP0oA6uf_f`qBEjlzeC$GEDV7=CX=CvEWtdw`8IiI!9SPfi5_Hsvo zb>x5droLp#V6n*BsEWG7-{Yu-s~u?IJ?p*`cLldr3}O(xLZ6B$2FHW!mlNOX z+k1ciYt4lwW9Q7>75scdQB~IweHxoNn7_C&QTC#MiI$?qCMXN7tva={*)eU8x^Nuh z?jQHpSFxxSCZKNL8gKJWZ%6mHV~QLD$z5EvH-kP_nn%grbwNYSWPi#^hcNq|-gX|A zo3leF3ot1TXe|&M`KHq~%_E+>z0mx51oL|#$Ytyo9`kVzrYkkPhxl`!c_n9F&3V+sF{%@QBPV?gTk zhr(vN$8!@_BTyvZzbXotXgG8u(rBCgAKDPSJ+>M!O=Hj;!j>0ETnW6N^#>(WOT$Gx zI3vOZ!-P}F5pmUJ%$!a& zFcIY?sbO(qVN#vj5O;SIw|03AOndUg4bRy7!;^&nWuGCy2Txrys^@wtPv&OWKapR$tu!`^weXHAiukR>wtCIQ&DXkGF;$0I?3kRk3eWisv=X*v zpa>d7pZnLGpXdd&^&<04NlKO{bLbn1;pa~l#5;ApyHWL}{NA_;c^{~wR^aZSykjT`pNnI~ zX;cvMy6YuDakSop>BpT6No~gnqy9=mI=8m=+1rIaWX0PEjaxSfG^W$dc%|!w!(Ypk zfw{Cdy#w$*3uAH9Td$fRxBIu9iJB{B6*UYcB(|6@+_#NLm~okZS*xji+zXpBK5J}X z3{8=A+TmDE$H@BTLx+x`^bccO=_%n8=euiL2ns=opXiBB8w{;>tozCouyNCHy|^T!DI(AHT#&f4Lj(9 zx8~3I0iWa%XLl?+{m3$&5|ZHboX#E%C(6Q5^4;q2*~i=ro)4~sNiN8~9D-A<;lN^!8 zTi|q;kGXUIIZ}rAi{jVorn1+%=?4KW$IAy;EP5{DEB5r1szKwwucmEE^5VYV938+< zmGvzGd!<><&v#d;_R?t-T8&}dVf+TdKUF5C&S~Lg8OfV`^7S6iz_5BrM?U_2J`?i{ z?d;e^Y0Z64EUBmmZAQkeBgY7`S2Cq)HB9g0OaVx>%T9Ah1ag--CSBrpp#E&#jlUbE z=<~u5Y?F;z%toxXr^Sc#=KB^k1J9)g8ZCEZTkV&|58KDI)Wv^2Qmc{4-Yr;i0cI0t zs?vW>N52N+_UQSe$-nHjJuhXY-wu@ zn5itdJ^5m2V4=%Iyja;AFi=kQeo7KK3svg4*&=8lsm(kr4m-%IGH6pB3spm#MFjxm z0-)m3>S>TP;HaPFT_RLUWG@#`<99EgvboB;+NiPB*~r?0UbY^>n-)Efm+$_M zD-`QFvD-0fW<6@~BzL|>Y5Tj7z2%%oxz(*_c}s;#=kc$N3l2W(x7iENe*#?^g&T3f zsFo^FZ5i!1o@Eg5weuD3_T06&boI;x`x&-M7VF<;p5xd;Wv@BQp#p`%M9qFvreWSV zVvY*V>bOtzJV zoIGAh#dBDXuR0Pznb!E$VSF;X;lJ}XYaL)0K|a{DS&TL4vgroRjW(|o%oAL*@fQW0 z*5^qJEwVIGN?R3f&q?dgp<7M{o57^Cpwl(c4Xs5VyZBDAxL0B-6UQ|y2sFA9+xt5& ze)ilWm3jNOzkf^=oxQrUunYbqgpkF3-kFLc#jqazD)KurVh8!o`)Nx^WYxp}8Dobl&kQh2l)FeKl)m zeo$0vVMwDF^FO+Og$XK~;77g9b>^T`=A-Fje{uCc0irCcT3j|S?G4BhQHu*$PkO7O zt$v$WQG}~!BJtVQ+~6#;#T%>aUNu`A3|_G;yIjod6!p1|t?2Qv0C_pb{}~R4^RVmU zDU3?y!|wxcm~dR6woOY=KFA7r!EX!a0i{8*{Z}kmqNy1|hc?Ij!4uSS)UuPF``Uc$ z5yC@3N(;h8myHa%8mk})+K7E2VQy98ksrK28<;I+sZbwLSkP$P*NL-!FBMw(brgqc z*1rc^{(szPx9A{*hW~mAO#SapZFXA|AmB~B;h{PnJ_CWz*Gr4e>#mEA)1qjN9uL-V za7&_n+l#(YV=5l!^;A;$m$5Mw_l^%c#D8Wh>2#(e?;Rjnd5#lOKXB_tqs@j;`15sk ztR}{IsIUA5s-~S1{w^1tsmSo{jzb5C`7&Opf;A?i)zjKL=6)4W^OM5xo5KH?i^1n_ zbve8*K2*(1G&81t8w!|K`NqByx0Hwa^Q8dr-}yUIU4Q7RhaLvbF%3bIEPXqT5^LjA z9U%*Zs0PmaH#~J+474GV`>=540~z+9(J+d?F(Qv~47P<1ph`?`R`p|Q zJ=^!$zQ@GBH|Jp=ub|OV5+*rdoCcPhzUv!vW3Z_ZZN&wrWQsMDET#}>UL%USg{rCj z7#+o5@B&_4zMQWhOy}q0BPZ&#MlF+nhUEEo#nE@kt!bKL3K}7rY4ekQKKqw&+Za5U z=9k=Krz`kgwR$FEL(e;-g2)a7?tl~)Z8^^~QuR4mqbs`))JNzeVlH}7YjuE-FosDctwxBGAZAnS7# z#!`J!bF+|#4`$go)T1TupDL*HxO#` zF)#b&7oGC|z8L>8Jc!(m7rnQ|(?Cf?ZT>$YZopR2)|Xo^usFSC-$8B=pJ)A&R&lV0MIquT*a@iJEbY zIz_>F;W*N0Lk=!54VX5C`})M@if~3w5L({Xe87}1hceFvud(yZg6^1fQuN{3P)(LK zFh{OaH~oHVxSjcRLjqs43I7&MX-d2R^U^>6vv44!h8QlBc?y8ok^~kPRa|e_bNXW+cCRL1nt1y6%R!C1N>hq^Cdqqhp z`c9IvMz<+d^EE??M3qKaCmy#>Y(9R}15{7Yo853>rmVO#{7}83xYivNytp)_)($+< zi5fj_B{%70&(?z{v#>bob*AIhyDGDo#LLMe`)LjV-^vi&H#=^?Z?Hj<>4`!j-IK4; zc8W1;;^5__=*_2KRW-7U1K7Kj6&_Puv`NXUDxjsKEifvc$wZ7p+|uTCx#D(I!KE%4 z8q(|$yb#H=LvQQ@Q!qz(Ew&{;w=>TSW`f`Z)FD#FTWvbo>>V9kRouY*qm3y0(OM^%XHTgzEhQmfY7tpH6jhh_wwg+;zbq6KI0sZCAG|iQK zN6QgHTrV|97@`Zd#>4x15IEalK{q-G>4T=9$H(>hlb-Uuqj7|z1Nb9%(L|mXTRu;m zCEH%vUG+Nh^YfC1FwHB0b`_ov{{ZNR)tEx>Ps5ho7b`BC-sGj=X2(-`eMq_=?Cf?} zU;jmjHB#!Bkhc9ng8no99e>$qSaN;13|w<7YH?fG1IV0}Q5eXZi~b(?cR{}RZNaF) z;3OX;0lX3p@2UYVX6EZ2M!O0mRjW52MODwy|5Aj;kMiK$ZE31E(!XQd0q(W)9?X}o zsgduU?tlm}6cfp|;z7aC+ddhmku=J{(AoL)zMB*pA0OcwQ6qA1GXI=Be^E0aS469W z&G=Qu(Zep4|6%v1GqrhNPgpGcqT~Cse{wsx$S=wEJgINK+!dbT1e8aZ$&|g%U9#ys zU)bg0*!oB1BL0+H@ejRsczy-_`m4DhqfSZ?ySdY8CA-ES-P_~*y$1P4!+)?QOg#9o z6rN`IJ^_X&xLM;fbI&i@FS z5q=Nce6xkED%R0UsK5`mvDgrAO(^(HVbb!K z?U%5pWH@wu1Zfny*JXUioVEOhK(ZRzbc6EKRVl^JSnB*@zmqsZqys02TH!Ck4+3L1 z&L}quS|mkDL#boc)%&1|g&)-s)4Yi%HEwY-fmPWT*EwdNYe8hn(hSu_K@$Vm#U?-#~_>qpiFyhrlV|ZkI zro(wj@+Zjx`}Gz?&N0=a2&%ZFYO3HR#j#_zbAkdΜ%taR}y6&Uind4t6Tk3~3?jYO=gbyE2syfQsB9PHHdXK5) z15z8=dFo!k>qkzqJfP~CW%k@0QJGJ}bwWnS@*hc!oZCAN@0kDq;O# z0!pnmZS?+-o-h@-RDXlfm=%<~CBh6(W@(Ny%VU}T85KvvDe!_|fUX~ad&4~NS2eeC zRC#T&IWo)wy0JWu^6B3OZ6ZQyx{pu##kJ(COUi>^tn;&GPPO1@)Ch`@r+WraxYJ~J zRWN<{0^J;NfrO`GKDu8R=W4>i!jPe!=}*$@OpQa{2SMND!K&qot0qm~3$8)j-HjQ$ zxnOv!Nu1*3I}9%X6cgu3H^eX@1tfu=m=7f|FK%C=v9G z%Ct!yCsbxc3%Rnkvg11qr63gz2K5mA`YLXe_3e4vo0%rpMM-$2qOq*13Q2as!p?3c zdwX+JX6wsMyQ{0K_{`164)|AJU*By3@ZxKiXGU2jk7OVF9i_v+QfRSZ9? z`{b8|L8C<{eS*9VY@2wc)qM@0Ur! zj??7ock$fWuj|JAughz$KD!A*Msv3I0jUF-yx})}Bu9%T^n2U6m;6*aYrJiK{JIG0 zrGL+BGE5EN({G=?$pwW%obe4rNOeg z2Xq?q|FA`+RyE{X>HG0@?bi_``}c)+_A(-D!%T{Qu~^b3I=rg!jEi3Sdl6e8mfm$ zWs*uH)xxw`^gC6|)2d3NmjV;}u|MahPs?+E&4TOYU+2ZfEz1?X7bzR-uLY@oI{n$P z8`GvAEzA(kcW?}FFs80qhg`Ngo~km?t-_s#q_-$OLNQ@wW38bfqf8oS`B=bz<~Mgj z1fYt|>+)dAVm~RFUi^siW>oQom$5E!?FG1&#r|XqR=PZl{P=~g`*S}rTtQtx((=jF z2xDR)9z&{4>3N%qC1}ml74Y7sd_fdJ<^|XCj(id;+Cng?_omAK31*A)t&p zuhW*0n;PC!dd-71+RUS&%A=w<#|f*e%3IKwQkgp3&-6QIX4(O`m!JpTc)~l8yQ$>G za>MY>ln$suBqACW%@sFOQD~uAQI*p~>K7zkANj&fQm{wMbC%6er$3O`-;tKS@4tUD zk1!s?W*}o=7h|BLDB`H=jJaOl62we-vE+V0SVP-0=gbzp?R|Xu{J#t;+od=q$8UG> z{yBhXJjWg1XGLvo{u26O4TmLFbyOnW7qDQae5VD>%87rNA@;jmD><6Vf6OmCQxL>= z>zV1BFjKRcju(3vp-eMQY-F#XrfzV(V1lJmvu75Jk4D>Sa-Lz5d6g9Lm=}d8+4h9z zC)+7~h&o9~K_nDOQuu)Y-}Vm-NsNkn+T#I(Fs@A|Ial^g*uWoYP*3{(hyY@<;2&!^ zDcJpJ{@rP_7thZ3VW9%IPE_OqCH)B|EF9d|(v71PeeF4wo^m2m^k>KoDL+jlhQ3i_ z7);Fi|1Oi)`E`EPZuz?X+^kg~!{i-*m|!;lD5ChY6!LpMTRM`(G$8 zW`)AT?05doE{)pQn?Izg8$Lf`@a;nU+B%)vV*?-Z*Zqj*Nkzu-6myG<=H|FO2Q+h? zkxA3cx5x*;oM#0>_NpQh)@mz>BghB>UQ%Smc@04lQ7REI`!I=KEuc*C9u!ziE-CGB zEQ7_|FXQ#`MsecIMwrv$ATJG9pn)v5K?I?disTi^(%gk$T24POAu@M`qB!x(k&jPN z$?|Vx&D?M8d`YiKyf!^w)bUjML6!>Oefocavqo?4vyKzJb^ixqwruX^18eTV6}$WN z=$Y?S8eOrYneHziZ{lz+pNN*4i82bvSbxPz-gKa{%kuvU;CEmF=KbcEWV^3ERJ2Sr&c zhx4}WiW6{DvcccjPe6~B^kgypx_tTrSo*h8$N9Xl$J`B9?Mk$O)`ZLc+bZ>lN8Tw? z(+~$EwVwwk8+b3(Aq3|%0QIsY)xY08**7V9>>mu_3NI9(rp9$Co-j6LtRVNo zC-Bd-&uDWxy&b;etq(&OG$$JDHmC2md!!OVr=ioXA;Y2^vc8hIILXSe+Fun9F^PRT zx^ox2Uucd3Fq%l5q9fIvLJ*(W}>*sKNmnT z@aO(3Hu4Q0{2q>#;Y5pjgKt;B*Wi(^o$~WHn(j&`IOOGdQQQ98cf%OdP{{Z<%K7=Z z$9^P@&!DQiJ2!LBEmZ#7V)<_;_uo0Ed*O-?ud~e$Y1;44^zjq&y5PG!VL^kC+lWjr z0-sYqkH_dC-{uOqGNwSyv7#wo;Uxg43N(D2pL8gIeK$dRw;j(aGy?rRn*=Ryq|NlEn0(cG6&@0|3SGlm$s1=nE6SYL>gQ%R*JRsKQvmR zr|nB%(D~BGIwksoyd}Aljq4NkMVC|}SyB8n^$dA}7Fo?w4r91~-7`m429dfKRo8Jr z{f8(3*H%lQVmN+Tf6` z<8@|`RS{cVgma zYvPA`)Y;z4p7t@FY`i4CpmuZAI+WP8WftyL@%bh*>NH?`A-8`A|Ecn1SM;>#nf(N^ zAX2nqtIwMJEb%46Wtmt1*@YfPN=E|c*QYz;BcoVU-6AVV!X4}P;Xbq^tLyfM1bE>* zsywYEK~P&4zc7e>NJNuwRPKFaqW08ypIPmi-;g*t44(H|BA4TntEEBb`zYD~H^D+{-^lv`lMe9f|i+XZ)pAzPMm1GTZO~o^awFWbl8N$JZRn&(Ecj@Z<77o3kk zCIUr!drmAmEq*0e>@(jVNY6E-l4W$(cs}#`EnQe??zGZtuRj;v3qY z9jLFJZ#=$_^4%&eP?Dsa(8Lu~=yc~AQvSug^cTgT^`4;aIKDf2l#^4bW?_Xel}DUu zj7kJgEGMgvfZmTFjJpit+e;V|Qtc3>IqeVZh`~g`F~BDwJ~}QOX`pv%&)O|c)0=l4 zuQcN}K3&z^^lM)pL4I#CJ3T>h-bPxL}B8!148aPk}iWur6)#XkEbd&R?kbNb>9}Rl{C! z&gT0^w8PiuJ~SqC)0X!K&%z9sR;lP5t(Lg)xO?e_Sd_4i;`EHwTyp}ID-6TiUUPq< z8{Wbk|Bh5Xs(_C)q4?%%WbDwquD0smb}^Lg8o`D-rdk=cA@a+tInL;#nd{lS?9+Sn z7$fNhSDAOdGT47tuINTI?1B>E$$3Vh7;rPMwqHXM`be0guZl<>{S3^%2|2O9-*<_W zy5_2ozNK(#|3?BLAq(_0803r!(KG%yxfnaS5E{SsJyG?h@H2ePt!9Tq?rnN=@gI}! zybrVk$LoV>dbt`W@tRv09tv6w=W}nadPLfOWQuvD@>!ypT@C2l+1dS7Fn!CPOxK*c zy!War+YgP^GGDQPnC2~4d??oMR*7rhh8=~KO2H9if5n)hXuQ9H8tGdJAE~7v$<mv^KKlp}Q-brUeR7a09(s8EupHvGd z!6uVQ%%QKKq%uuplU`3=qD6M9R*=X&Dfo(6E8`sEAC7OHw(k@qCO@0sHTJlPX&@hG zrLuH-`iJ|<4bCUSR!YEju@ExU9RA+>IQO?paT}LPo}g$`l2;0<=YqZRsre8Y1HQ`J ziXvmzej8A{IGQ_+!H|`x_PXBrnaAK5scN2h_OhM1o1yClPSN5S=iK3)G_^pe=}U!m zRvv|K0~9EQ{=HVNTIrVa%qCDDyEaY)#|er-h9)uUd|;TMPtQrp85&7SrYZS_y@D2o zTGn&-_2*-)96zGy<;!N~8q-35ujQRLk|GJ%5~e=QI(?7pDSiATa{U`rGoa(`^)#l` zyXwt^BJ}N@88QRe{xPOsPw#8@+7A1Nf_ROa60tzLt&RnMj4hN;;858VnIm*zK8u(B zM&GFft*O*wp5IACt)%*KMZGsWU|fJZJ43HU zG!x}{I){50rE_^s7P%p863|@u!7Hdq%3(cp0dzt&R7@Sf8|#{2ght8L&Yz^%hIV~7 zxNKdC4CmVk2mU}5&1=0>Zr#nsc?@)}`uK0Y7nJ(RG9VL}_sePrw$Ga@(C?_V-v@aI zT{L^%+(B0dQvhwr<&upkeR2|S{K`=gPGvMl)~4yAAd1VcgfGhW;GRq>=p zi=iIV{h57(^#MN1Eec`hTR12y=^_wR$OHJJ!Fc$y-jqIo(r3IPS%{Up~CS@JDY^yJH= z(M~4LI*&;=kK+_v2eB+3ysa`i*6~f-fHBd`vY$`G#~%^T;|-;$JFFY2xp<=yQz~!` z#~oADA?tYpON^*}D+!1Oho_FfXAywHZRB zOz>X*c!WgifHuxz(FIwjNYn2~p=RMq)zG<>1O_SeBL!1s!zxx~^MN=prWgXSs9Md>KyMHq7Rn{&-^18(^WcJCW$yZ8=URIIqev;b*{lzIS5JaH5%9e(InVJTK)ry^?My6MgumJYvz z#Yc#pUd^BYjGX?iA6qEPCoAp82A9MdhgVXN_P)%IF;O~tu?6;QDdDqY3A|W7H2MGV zYDO2X%Nnaud+W4xNy?0He*Z-^@Q3I=lYb2sJKmQV;cmc^7x%=Uk!bdny^N6M)63X} zCA%+ehjw@AkT!9KxxFV>CeGwbq@}ObYruSaw$hic;P+bS#TVhE84UVXS)4CNJ6PaLu8O9?hJH()-T(dw zbwT)`QW+uOeu#=Il4wo1j=G6lSgIE+tONMr6G_a4~nB z8{Q45^5k8QDydWkV3*aSw>G8cGsWg!wjL^AqIkP3EMCn4Vv^;2=^jb*G@D7&hXvnW zoP2$P4)ILiwc?Id?;x{>>`t@GiHwUf{@0W858M5xpQ7y8U{YOYe=K^}y37K!lDxKO zO!Q4Z$oqG`hZbDB44_9AZ&USvBz-qviEHawxq%##{y<<&hoVzT{%xh^PFY|(5> zbso&yJ$4e#cWBlWCO~Qv9-P;BjRl?3_@FL^#Pz~XH_3bYYiTDT74)veniWXLt-@fA zkRq26^IFe*U`r;o2e+trYcOOSbsX92b|CiIJ}cw$)iOGq|N2bz{AmEwCB^avlq?SL z3|SYqcqg?Y2z4=)bQMO$F0vx_enGr&H}G=&o9~1qWozYLpuP+zYKIQH;G5hN`;gbW zZxkf&O=}Lsdw3HFHLcjo)jjLEy{c6UN-84Lw+HL_on8o}lD2chJ>SgA_M7BiH&=qc zk1GheyGvOX1>U;G7f<(-N!|Rl_@>X8hA|?29{{Or`{xjxp3inyJ@6gPTaukPJobq` zad?JvQzZDZ|K$fxtJUX;1J=73GJ($>N_RNH4JiI$mP9`Ye}(Gydb?Wun5~N$I;R1d8oeH6J5;g;Cb&&_MUk_=KWdpB_SS87i=pR#+6(i< zS%{g^K_^&Cov%m65rtd&jB*Y@;o=f*T-YqEAx~0-M>F4D@P1x4UU5%0WI?O$GQ;<3 z>sx)=!SupWFrxGGhfS+YR>A0|ee_m|$oFVu=6)JlE2!ZfeA8uRDi^2b2ftPD!yud~ zif1SWJIlQ``j`2FZ~t1ZHu{H?@eD;}MD2cGZOz_i48fn7&8i6PG7CawO_cps#`MJU zpY!J`-gjS}1Do~9jw%p!BVP_Nrlz6Txi_6;V<$6~%%(&K`VU>DjJ`_y!2#|3<={7S zAD@Dky7*%9Xi=*Fb<6oF*drjj$Ai4+J>+QkC1g^|8=qVmSjlqM>Iu<#x`$1leTs#r}L!(QoCAMokAvV&=1eXiZ; z(L7-^-#W3S*ROkMGHdg*%>%P)qEuPc}s9+1Bj7%P?Q&ibXFgeikI%h89uVfuKKc7MbYdbi=?-?bb3}1*)5F(_gqvxGwAB^n=V-s4Y%blVAAFm0mW^QHbq@6~# z&v#VW|9GT0>6mB^Z3_9L^#?V+I2^tDU2Vsq8pMiXke;w4OK8e`aI{^oXOa2m6Cbg* zUKE`6JS&HInokq=&=6L*F9(~v{Tck)$1C2LA>aGChNPQ_w=cdf?#LC($cwnwIg1qm zCif)Mzx9VYr>WIVw&`O9>u{;E8UBd2g&J~O^=>UUe|KWR71>MV zH{7WC&k{1aTSblkTZI5t#yMTaw4rjd_MrS|`iCty^;3xkunJHA`SXLlicaa#CV4taxtUT%_y^DK$<1jXsYMuY#?bbM*A@(&~GZIH4;38UU< zUZReQEsGB%6O#+qCj3&siNDG*{cS=?HmwuPLje~p&HLwlykRq*5G4R;1^*6Q%j2In zAsyuxs$Pq|QTea?$CyS9;0x>d(D_i+$FNm#jL!uu;;9vm>-#iPnE^6&TKr$4V>iDf z4~b*puFR~(Jo!lNzm@CEvnFe|*!BQp+bY{q^eN&$HYUn~t-(jWo+>cYnkMBYsy)Fs zdGu6%Z+25NM0ThBe6mAu!XAy^VVab`{w{++AjE8hI97KQnm&M*v zRpTzVnRj_0=7upk`eTFJ@CXlWSQD8|{ZL_B2`rsvN0Cdg4H5Razk<>tZN0C8c`Z!? zF_nhD(oU^1sAnpDh0Bt!1X&f2KNFYgHtX+^{b*fYOo?GGDEMi%DH+T_&oJO&g~=3n z5I%zK=~`5nlLia+K=@3LhZI(W3WfJCnV5)Oj#M}0UXLIulj5W6CC-l}HY?$OSF?y~ zTe@G(1&ftkwBM}e*@|9ot6u(VM6d2MO%u6(F{~3wbqJX~M#&FEF>rP~NJ@E15O%Qn z=}my(?@L)o_Y+`|n`uQ@=3@>`aTeceH!PRbR=y}R&VT88T+jCO$_PTeezzN)x4xtl z(}Px1%27V0w^8%n;FU{)V4@Wc!!Zi|HrA(nCRapM?{%Q9w~Wel$&-x;aozW%MQ3#+XnG^$xA#+{7{)C_%N?8=5-nGgVwU>93&&V`>5fH zs#B=0%eLODllnjE_|ns{<|x?XKcbFfkyAYQz$R!B@`M&V&5(B5-hB7-k!Z7)zEVgz z#z1e(IF&Lrp1Yw21d>eMXm=&AX?8QDwtp-~cGbcI7QX2J| z$YFu{PnZDGmdD)s8jukU0&9Mw!ieJ6t z%FC0J*QYu24QHn*JyHpA_83~Ydu*qI-PO=Wi@-QHx^v0XG z_a&b4rDHfwOTBrbm7WC>?I&~~#58X5cb~0w{$aumo88f78$yZY&`E_?MW3is&wGAD zV~N?@dcG=(Ln*tJx7EZuMMW$f0*{02rdleRIR78}JIhWsLq+C9QiUTE_y$MDt6HY^ z0^xG(DtX348LIcldN1f{f;jgcshc|d5=@k9pCCAGTlZ2A8u`_VF>n3ksEEtI@F)`ufT(V{!5ovq;L|N9p zB?wwL6qW;-qrLb)=YK5`Ydg@3B zwhXuX&vAn`*WyjH`&FuTzQzj)Qh~Zijd1X)#o8@|_h?=>5V2w9-O7L5-^*GhVX$Di znUR99@;p7{Uro$o!nihNvYd*4ax2Bw8;lD3w%yK9yKUWeyETvev-w{RgsXZZVYKTo zN5g9HKvY9Gs!IPio#HA?$ng8my?2MaM`R{HP8mMnT(-*d&o*2iH2eJomekLlAyX|x z6h0Vq0Lipni0b2qdyw~Jr+YbXC>9Ks<^*Ao9$l?CWfxMuO&g=K)Y?*h2^|nhg@FZ4 z5tgZ;l>w@-daiJitg?gal*w^q`-?12O*KjDy!p_>oDcc-#O)WY5YNS6X^8b^=6LY0 z7+zt@02#~UVG-zq9{D~T9F{i>F{eQOB3B~^+Zg>Zc<6mvsI9?dkpE0{qE46gC1K?rh7K`f0 zzTs?5&A2mis;XkVf)kfOR@C@AK^We443$FQ;**HB%?O6iiT}IE1(x~U_PhuC;(|_@ z5<Ee_{K>(BPg-YTq;%tE?I2QtQ1A6;fKWSK%frTeu zs8*N?{AmHX;#_Q$ts!-tc*U7>2{$wBlO(Y-$fD*#_lF`?O-&dh8A|KjWN~$uS0xJ^l&hq-4n)pK+3p(&~JDADTvOTONAO6o7z+ zFT|Vkas7Mp13L(rt_8iUA)cc!!*A!Yn$miMQ+3+swy;B!Q<|q99Z%Wv%8}E)%88~1 zn`{XQX;LeAhOo~sZN@M69-N82s5f?FxjwzZ{D|oe6Dv`~xYx+?b7((o z!OKo_4mKQ6v$nhdYP%J04*B;WKM0o|;r_3SC~jN%;KCT&;{`)*>TiOEWc2KyETyHH z#o#s(I+SItYkakOOYX$Aoedgv2xwc$eu&ZfuFn0)o^_jsy5^&f6ZX3{0D!ImtOoer zUoX9|wJoN5WvZvwQ&GPtUKRfE>Gyxy@{&7cX2hr#Z9~=z9#zThCn@d-&ec!^ z%1g7$4l+A?3PW>7cKVlcC4#E6J@4xbvLm{D5d77622=ES2HRe{Ue z(_n1VnxMO{g4vy6iQx_FYU-!+BDCf5wWd}6L}NZkMGur{q3Q*9yJmD5Tiv%KVF`+* zNjxAyay|CGoW}j!^+hx<0&9*GyEx@)$q&y!!G3h65qQEobgu?@5n^U~HZ5I5lE_UE z8^SZHkj}6*HQI4uWoPL24tHethjHH?b!Mp<>!=89NAtaRPgZTYdaS_#HXVfdiz^qp zs7SJBg<;EG-5zWM0MsiIZ5!5I&E4qsQN)v$Y(7w)@JYb_g8{G6ysOo7-N=ga-hbmd zYPK!9&trOx@W}K!L%z8idox=Ye7RxAd;sns<o@ z{mq)U{veHSjh$$i0tBJhIa*B>1lykLyx`woeETa3t>nd@h&O0VM@5{79U`+W3G=f9 zd9R$jQsjz8q;mBR`yn>-8+w@OKIo1GH3cz}F`;_0G;l8J-n^5zV5`n>I-6k?)~b!I zLMvfsxw6Xqn@+lecGtAsiQl!eWaeK*9k-P~1?+M|fG9Yhv?05c4NFlslPoQ@r%q#< z+lLH58XeIdH8iWdZ5SUd!dm~Ak_1I71U~<)3OJ5juEi-WDRd?(F^(=-DD%J99Y!;! zbCS?N(>vU=kkz61v<9<&tQoD)nI#pGp}6Wb3ME|(4o;FWNBH$5E)TtebjH%}3Gu%c z>&^3{N9UUU(LEw2JsgWy7rg%lqHF4oxpIsBM(ePE0?6xDaztFe-eIsh8w?CmNr?Iy zUcstAG}Xtu@z%d$K~wm#SGyUB6xGsK(<&J9WO{aRXJ6r4UlU9$_SqN+_d2YEV4MH& zgL_f5{MBi5`Tb-2o5=BCk@i!!i6L1s0K%7laowJ4^3wc33F|5wR1kY4ZfA@lsu&6= z>8Ak508{gJuH7HprjU%`6!LiB=nMtC<(;h%wIXixp&SK6M@V_|@6>#XCu?>Cwg{OZ z>Bg8{dzyi>yO@1LH_XT8UDY8^5B;&26>R$su;6GO4kvaE>qbn5E)0CSp~t@v7nHmy z1(jkk&JF;Nz*POsq`F5>KeE3<{ka@c7MxkUu-Pi3)hkLOW{gI6Bb_O+G|1P|Q@C+> zIdQMxw|vY(`~k=Jpcf)(!7Ue)^z0WzJGI|&wv|oMWYo<#@6Z>^G;n$Viem7vpG$~2 zp=@OwmPOca_o_WeDw>pgM?{JohmcC9<{?)&p+D4A#1)0X86}TjMm~owy3LzA*2%IC zk4Bc<6J6C_FBqCK`FY0a=EXb?`9)^_s>>8C{Sr}G@IH*~|9`7(W#`?@vfM-ELOpt8o9Tu|BK8`y zpL|W+T-_3#lJt#{e;_mk)NOv9Hlv?1S&fi>ktGx~ayKzqkW5!z`>a_3P{#{RnxS7J z5@d@jb0C~cS>07!b%A%-2EgOYX5`Dx04J8=T@ZBupX8O(xr&R$*MH*Df!|}z0z6^L z;=K&No8H${Lhw8WPN>qPdb1G6UuBZJS#P-Yxsn5r;w z1Wcs+-?Un`#ey7eU>>yWwqPPXOfwN$-fPV7*^AizK?4u?oQ{ebyG4bv1bst}RGtK$ zoapv?EfwZm5c1K4072zR$}@5FLtcon&gR%+sy9g>BYR-$5QdsdMrMihE-c*I$gXrl z34ceWO2EO>>N>#-R9P8(lkZmYyEME2(Kw>=@#e2p5N!rEgeB!It=$|v6Z*juK`Hyu z?MKNx-Fl7D%FmoX1Lm6RSByw5c#b z@7;pk=RFpKo;@>oa1b1r)R!bt0rRb%g*_JU5$xmGVNWu0F;?1S#zaVZVzaH7xrS=NF++2C0^%U%LIqk1D z54_v8E%@>6r&o;)D_VY+Ha7rdUVmiN8|e-<6F>(>2A{c+$Ghwt%Z+KooQ_!@u=v<<$Y2ZntAi=t$wTtuHC*O4vP2$qZ zmV~W@2Y+~^YMZ=`2I@_%^j+9XWKlK{v($l01>=hfKAejpAZfR-v6YyQGJ&SNm7LJR zfJ>s6Pt19Nqr>(N=Gm0|-v>28z!{0FUsPud#h-jZ?TNx{e^ZL%W<4u{&{@iPZ55K$ z_=zMc>^$T0QWl2bS^-QB9NH_0{!tj_h++{3YDR5$&{Xn<$kf#;%$J%q%Vz#_o7!HQ zEdUBA+wWU{P+edtln~=JVPxN9e%^U>vXYGc-NyD&^_zd92DL5fqN6Gq4AgHn&PmK0 zL*n5e?%7p-%QOU#IyBK|9;wgU7`o7ZhD#Ew z!Q!~r&lQ6CG?YDP;6r;t*0}EK&>)nKlJM7^^54jC&o|EZMeC$;$3L-tQbFxLhe9|nB$X*|L z=^vf}a;8zFNSNii6@i*6bMtD`Zspnl=QrlGhs_3F;K6^f;6wMY_zDtMH|5D*JkZw9 za+5z7poEHkB?g@&O1gXt{X;++jNF(HC&XjpQ^1M3|J~IKxYLB)1lcJ>49}nyC6tjP zU>QSBq|Frv?FuwMS^EblG^g}OH3~CC<}r%8Yc6cN=YsfEwmHc3{#^vOOU*CUBjB&O zONz)v3&dZcbActzXN1Gq`Eo#wsD4TTO71qyuhp0)1Gm6V<$f6g0)?y+sikP6S8L1=xu| z#y4$n-J37@-&Ym%1|OsNMy})4$V+#6@kg}l*1^h0m2!t#ZsThL)~p_l!ehM^1JeHb zCDOq?5k8O(53ehPl0IvnvF)_^VdN&2iJ{8u=nvUUeEKbpohimzRQkxhzM zB$gi69JX0jVc&|~xN8c=>MohLeSeoDB_`9dn$C(L5lbg4TFu-}@RLX>Oy_`Y5Y&Hs zcSYula{}`ULsVkT30>n4$M2R_OT>%qe|mWTV|eO!F~~f2OVt;sRgfm{fhrZMfIoL6 zYA+%uAQ&7F76X*mY*-qPLno(%?HVD3m6gn?#7N%(ly_!*)xjc^G@{eHFH3)PB)Hqa}G zLpYqxz9GMc0Sp;L%m^gWb5+-|;TgkE6b=H=?muQzatD zg9FjtMZ@P{2(vV`4gSnP+0nG8oezy!)eKtuJURngq+cZhBC-7B&jRb`IhyVrn3lEJ zx9k~M*IAedmVZo=4FR0<&4gDcfF5zSS*&$B@gc;Y-+eAhV`EX2N(zfzec4#D|Gu&}gkpF#rR! zCQ&0aU?GOevUqWG(48PR5?`IDxkFP{dNOs-FsdpyZ*-FgXgC^q?4GUANC4&( zh?Nf2e01-^a@pX2uqJl(Rx^X?GJd{Ide3>+kyGjS?a;j#rOU-?Q=Y}YH;hv%;FnbyZL%k2*tv#kqQN}`qlbQDIOqOl$?_2lA(m2k34_D=Bw91eE54>w(KGDdx zDdBxNesj?(Yy2r+DFWkQXsQB??B|g>Kxp*Ulres<`R(I0X@jAizl<2Y;A#-H_%vA) z2KSDWHqpr%K%i~H4aj;9lN@8aQ+X&z@^Mf7m)AkRykOqfIoWqZ-1KwbrIaH-;&JEK!AtPrq0NckhpCaL>S29d%JYA5pD+h z59+->fN?KD%V4qQ@u8&qcTNBIO~clP)r#n_hp|;BIhDJ_STq(00ngK@Qk!n1K&FMo z03z6OiyxEACFL_PL?K=B$ORr{20+A-^N-3FDs$^<+Ark*S#tHcUGu&o+z!NAmymQd(er7#RCB80GU-hjXg$fm5BA2~urO3T1`gWbuiA@$; z)X@B*2FrTsLcqG6WzWbg{Sbjq?Ct6utMl3C8@Jm&Mr%a+5hLf{q4s<0Iw!K;=_eR! z+>S#Z<@r-mi~85%q(?x;rTR>uv*UbS%pwCy`9rs!MosSJ1+l6F`RX?q9q(xJ^Oa~~ z^h^)#O+5Fit^_U#!uaIG&LS5L+B_Vlpk?kCSkfrzWLJA)v1r}RfiAJgQzft0jRP!3 zAV}pvJdBoWw>|a)^#Dww18@s%43xO-=lttF389yNx@ zN+dJ3x-mh11fH|+p#f!ED~ZFS+~?aH=ZHsFi%a@{k9)j>NqMIPctc#DpqJM#5)OW> zhYWhn^BWnW-7JFou$x~fnnW7x;=^ILMI@Ul!T$>PgBH{3p*iRq1douIcunyUICdq^ z@0GGQ-K`8(FI4C4sq6bqRT?x5m^=|<#^_CLj6YiTHNXRvz@(;{#=d0Dn@-T{+R!V{ zhvO=NhZe3F43bd8e+C|S5E+X<41Rl9t)>xghiGOohJwRv6) z;7WIj803^9Esq6THt}Pr=K2u+Y3N{WjyBDQs8~MFcBHMjDB3z%ogZ~2&%L$GNCEOV zA=?$vDT|46^YdMrz{Sox@BbNJAO17k%FwCBkD!S(B8s;(#j$WUro`d0gDO{;V9U6U z>{apZVmv8|Qmj4QP)81OX~Zpb(9)y-W%E)?1cp5IWwpy?IoCD)ToOH%v*C!>MJ}Jn zc9s``90_5;{F6US$&tZ`$JzX)(sjYU=igB6@>VoduqoiE}HTYfpTy&E&x{ZrF> z-mmTJ)$PGCA6Y1uJDssT$DZe3#giaMyWFJ0<*>WG-|-^m!jbicTxsCcA58Os);#ZL zZ6ar-b_c`6r^}~crJw|b_0C@)e|8svgY%o<6P0W#RV}(qzy*qdLp&Lgh&+mghUGsi zX8qI@IN{w1VT+^UNq5UyhQ~Coj&bIqPykQ4|^n!;Z_fSTnaq!>1QLS za6YD#^CT48qA$An(+lD+?c1)|E}eD0yd6ab{G)Hs?X)Avf5$$A75altz4C1tCnBm4 z@Ei_Ml*8-@kTS)2wBruYe=y7w(^Px@B_Rf&HT#i9iTJNXeia)oeu=QHz7i@bXv#)x zQx)N_4LoXr7Fn)>$lp}lfzdR#z%` z25t5f%1%KCcMb-OBy06B6hf+5KSMa5C}6<(L&eOyjYmW0x4!|HS%amPg@_k}BB2Rc z6R!;eMn@@av%7o0QehT=!!q0L&>a6+G__`TOXw4F3aG3hKU&^5wc@tRN-DvUN$7?S zmLkm9IBfDW16d(-qjapJb>X&p*aRxh<(o3=C$7{VlBlvMQpMgl4v1kW#*j0#a-x@; zng|wsp#D%1YbQ@T2jvV|_0B{ur-n{3gLtyAY9ubNPqC2hm^1-3Hy~}IQXh3S)|!hz zH9(F)$x?e9+?>}RD6Q=g7oBz*ZqEc{*CkqfF5pEv>Y=*ZETU6;dcg@9CLs_9D zL{q)_3w&`?w$doW-)767P1l}&V@)$RWTc1!srBi*-`cZfa(q&@$BV1IcBe2ok{|xq z@1w!lv-SpPw%XB1^E{rG7(rNisbv$l-jO^I5dox$grvDXi{UT&M3?+qOvOs%l(JF^ zh4Rb~bd%FS3w|5n+Rh<K^ zjz>lWA;w6in6m;c9&k>YYirFZfx62-(wa{0b(>iMtONg1$R`u`)qAiA<&dm#M|{I^ zGIy`gGkTdb#M-cNiTY*1+f*Q}&xp&q5TltA>cv}Mcmd}2j$7*-qC7V~h-&S$uU(^^ zBOsSg89AGp{&73k)kK`=yu=(zeOhO|-^s&-VN#_P$0H62iR~mc!hrv4>IDox1)4*w zhl*B5%v+50=(@)t=7PH#U)YgF0^af{nWE(RnBh3cX3iX7!UMG4xCE)$@Fbcrr|sgT z2v&F0XwH$CD|`TJ9g^r=7u3kgmByGd{oBPcmzS|*K_B$RuQQLr1_|ziB--!{p13-? zj_w%(X1f&*}lR)eLb4;L5zPUJ%%+o0->Vo;j@x{+Hi z(g3^)9*D6X8Q6MjhGF*Bpa)R*yk*i@jEJ56{e2OC8pIQvCJ%YS1kBv$ z7}_?a^RvGmQ@-y=r~15sg$p{C*(Huv(}q*K$(I1jUVAxbk*BYZeL+6|xZ266{ZL9D zpOsDH5Qc0b&l-%v5YZPNeTQ`2@(4ZLrttkYg|;p++w8$Yr4g3>I?IeBgT>b>0=uw6 zb#1<9d3}mP60r@KaF3JARZ)#24YM!qye` z!K~vvVXFMdqH%imKoNf<$}r37`%g8?KNEWNElU#~XeZfZc{Nnc{DkP`%J&!@6Gkr4 zXTuq0pN?Zun>ZPD!6%rF&z(t3qqepWLwyxrK}NMVBfMR^y2w9E&B>CGCwkOH)Oa>! zblXm%kXK*-8JNerA>Psar#m&aTepT7WM$peIHIfoJl`1VT#9ZoS@nC8*_|4`XGO@m z(&YE~^WmcRd&JudA8iV1bUrw4MBz{f7M!@E9mqKftpV&;QdlVenTx_7b(EtjTi1Iz zZgr;SjJY4Y5Vc_V9$+5za=RHm5Ow1F2_016Ru))0(BhES%SP6FWl${4gA$_n?Ac2F z^uD;aA_t}#!Rog;Uvw{pSEI?mk66$7t-f7Op!eJV!$>Ok#D(CfODw~X8}9F}8-d}+ zanb#OPrK#aP5*r3zsg((yz;=1R|CS?E@UxQz;Oax!ZV+76od+I42<)l?s62Qc&{S(U$7BdM1Z`Oqo z4Iwa}0%Sd#HAM*0crk8+nrxak3Ix6EjorR_b!p=Vcs7ZU0}JTVdfkp030g0IEPp)m zNv0Zr4!TjBQIA((SE=;50S%*;+1ye;hYxclWn?Y@YS>^2YC3!A)VLI%`80el#PQ=p zkXOXCD2ft!1;^xO_z3vK+|kSL2*SMim!N|l=&9wGz1<#Y9yw$`Y9zh~$`gd$q8jwq zFCx(kx-5kN8_!>Iuj#;?7es71Mv_kwbALMpx;UDtA+Xb^&Hl?vI$xi0mgsWvqODhj zHLL69>O|#nV!+ljy4Pnrle#ZoJ}h^udmcTElHajw#;T{pUnclQ@cjy{tN8>M5SVLn9&Nj~}%IU*Pb4C6mW7 ziU}K?F}U1sJPJ(`{6`QbbmZ+2RoyEy?i0NH5-e=r{zMhq{J%r57^*!5*t2Tun6=Fr zo~wN$2BKsj54}>uVcWIu@;mhZbQap|D7pg4G>-df=7!!=6}>UqW6$L~zit*mKN;?V z^_;I6@A<4bzD~aBb6iAeVLg=irZb1tfD5a$t6g9Ma}q^g6)QP}KegX?@z0mEAw_)B zn0BT?-!ae|S2+O?28s`wpgrtgzW8jEXEj<%RJ<;G%gbV*>{dde)zDbu`-n1P#I zgnJ0GhykZ8*ki2vT_Pm}BU)<3kmH@2?6-pJuuqud7suI+QP6w8;a?G}IRk6+U*v5E zl{3$8$jS6!)?Pk|v)@r+zuFSP4-H6MLW#E(0Stz6nOoT~KgpvJ-ov!4#Tp8jj3v{6 zytl6kGt-x^Un9ZVQq1*Xd(Ol6#YIz|#y^BSEq~=YRwCo79)SP;UnL3(9oqxnfje~9 zb#M=fIYj}n`7DL*e2-^YS3j89omVcukdPI8d^ev!i1Y8-+Ll<5NvQIFVp;AIVoZb%Y$tr>ZujqZvITSBB*h{LzFO_`=2}`9l*vq4;xT=%+r6Qmd zR(z%Te_K!mS^pgkiG4xZfWNYBSHmvHAAr%5tLRV&Dz@*(CQRUm!p1Pjp|o4kAkOMh-Z5oF=D7MINf-85~G$zKYmK+R1={E z=i7VgW}^Zm#;!<=RXtz_+5qqeaxzxr@Bm>|b?{=w8rTy^eD9vdnW9G08I#foQc~cB#;|G{X z%@r7P*_K6Tq@+rIn76+n9j6`@@1^1md15X%p!P4sgo#DmND(-mdMdf^;+`e)tO}Dc zaSc@1d~Z+o2|^)qX8nyKiszt^-I?BiUL=BvE@Qbf;l>*+&rg}{zr!9Yx{C2|Rvx~B zo9xpc`Z?;r(@`RW|2N)(_`v6?Rde%I;>}MS-e7~U;EKT=J*+_=!~hnYtDd%`3C}oO zQHyv2SQ0l=&FeDYGo+9nhQ43#(IjKkFddGgS96(t?%#>_OECWfUEA*Z86<2#lW2Cv zW3o!cd5NcuHX5)@2C>L`ZzcAnDyy47oyQ@(ed?T~-tC5Ju%5*j1ZOdRDm)qiN|Qa& zes@QBx%jB;SLf>SECs3<$Zmcdp=r&hUqRO~-*f+am{snH4td1_HmlelzQPT&zGyZe zm46-3Kv?L!&14sHHcls#HOM?Hf=0ZTrhgLH(?H_IOs*rZ$Ycb|t+E;Ei?3@Z|n=q1vW?-9i9epiP45~>{(UC{6y&;Z-sqMR_*bnvI z1Y_NHb79H&G+<2wxNgcZr;Pv2GOagF^4hpG(~m06*VlV3EMi$#10>bP#jGsU9a;*T za=+YW6j=_rsSK1~0)+T#_mHXK7)6pu#o&?0bYwpA@}Gfs5_T=_ltr$nrw7s9MG~bZ z(>^r!qdr++;Lr_Q7!L(2u%<6357V>u@C+K;&BRGqNeI`$+`GeuVqlu2Xt(5t%D!u` z0uXqL`J4^0cNA`Jommlm`uDV3Q85BwV&DQu_-v=>`HbakTcCtcAT>M4uzC2g>hV>e z_QPxl1{HCrBAsl>cJ2p+T7KFqsGj&N;N2x2#X*6?QGrZugzta{!o6KYkr#2iTUi&g zCfap(Z3gK;rxgu|57xqUV4RNyArNVL1O*2QzsNFuIsJc0;n&4X&13&yEB$4r-h!;R zO-wxvZ!D?6h0(0=HxW_{Frwm*tdFgWn*2fgkr!_2X3 zmv{y#yG1LhkGCscGn<*u{qdZ5LK)uL-01Wc$lEYFK0X%jbL!14@?Gtw50`1cd6%`v zgy7c+({cW@YDz1+C8RhnCFOjR3;4{qOWC;eE69*m9o#|b5l245bd5T{cTXJ4i8#6p zM$eGVC_YuD7-$R;Mv^Gn>W*B zET2fsS%$wHy6QSc;SmT?4o4eP^OSB*Y%Ip@$uk~aw*|itc1JbP<5szp2E&beJ((QIBd62GYnET6N1h9f|Z_%aNu{iq7FF)TzT0NoerTBX{H#Mc` z88#C7pEi_SQbeb$Oh@gBNxg0$F(b9ed(A=STZ|4}{{3L5xM&E-jhHJ!QVcV_pfT{V zJl8FN00KsiWsvc1H5wuxC;Ix5Gjb|-L-ILE?+<$yGV6+RYA*_O=BbeU5K7Xs!tc6| zpz6aw98m))b1Vg;ln(~q+=w!&k$6w;-DH**Vs0+0h{YHU*60@vKI75eXa9vu5cW4{ z<2R>rerrkK4OqdZ_MWlu8?Oge!rb-0`Ex~8`8CKH*eX9{@2hEfgXk=N2v=`Mje7ga zm^TfaU&0$^4+7FHZH=U#x0Eyvo!=pG{Ul+oz+?!wM*q5~ieg~cN0M~vHr^jYuN!@S zprN|t)>But<~BwJWLP!!Yx)tC4Aisw^Uoiz!7HRVe<`Q2*Cc53gPY8s5oVMD5-Noi z-6)zns8F52{Z_vS;|qHxBLbbz3w7t;V!}5MukyId26UBw9nKuR7P*6F#3mAuClXPT zScg5G-3_2%H`L;LJYVJC73kHg@7#C2=z*D9&L)=iT#q00cPz%6#eIJd1pu@7eq-P0 z)Av{s27OrJqh(lOuOxauCZLDTQLDP!=6-zh1q4|rQS^(#C6K`#pdRa;f?^{^O7J5HU%bULsD!BU z!Vs<}8O4dA&m9C+~>r`qW|EIPz8Rb3J% z4UO856lZl^Q4MyywGN$Pld21uM($!zD?eT zN5%BqOq}|az=Hdq2qCv&O++%MKIv-#C8s3}k?(QxrNeO9b>D)+nhaj*)I;A_Lq}?EmNQZ!w(j_3$ zB?v0vdvTugyyJPt_wmPb#!z72*L|%u*P3(91*X&hQ7xG>?!63>{?puDj)w&dvx-5{ zkSDku*EwoC8d}Djea9@W{QjWLBuCQU0{~i3px370unt_G7sW{9kVQQ;(bbWJga*(P zf|KQA%a$4*Bkknl9AZ~+341npX$ayzp1dQNQ~pJjsyn^YQd*}kE`51jV1NDR+<|?0TM8gH% z+~p-Q&~(c2TF~~0l42;tmP>@R!)z-wj zgh;gw-aVkxP$!Hf8N~VIYLf(2Tgr3kcu0#ZE*~f*lyQW?I0pZF(}Q{dY|apV_)zGbR_)y7(egBV;6)zF=$qc}J2@pyr|Xwu z9o40rRKS-?I4wf@wXA>Z?znG3AX3_b#$#SixmX2{O;5q)R^t2z{eLICn7dQehy+F! ztg0`G(0Qa;6!6uC#`6lnKMh8&?J|Rxb5w$Kd~{^ADoso*M^P8yATnSAW`?ZIpCr7Z zW3pmX$;Q;P{2~U2)V#L38C{G9s>jU|tEJeO1D0ve?z= zu|Y3}DO_NU`SM9CNMd~wut7@`G+Bq^6~Zoi;yNY6h$&@XSzjKe2Ri7pHA5+ zs9KoasBTx~G(#M@oLJ2HX`7DdpnuN~2fBESz6DK$P;sTU*<|KKokIV%Y!bxTE6G0n ze;Y-DQ6vhqzM!uAac>z7CK5*IXV(@NKW2TnVAT}ch>&-Y7o-|}gDjxvX!kUT1{D5# zjL&i?RE1(qnDX87K@FC{bkymnZUN0K;Q%Nc7)=hYG%#zyZLc~W7@8mns4S**4MCq^ zcOup5vAG9=Mi|vS9%C@Guf6oEozR>yjX3(-rbK|GcY@tOb_w!u1@Hu+BSWGSQcdCS z+5cfb=~94#RGUi$87~NC#uyZ_j#f~<$6vc&1k0J2@?S-T`MV(*MTt7Dp8qLnE1mbH z)~#wg0VroQaR&6c_Xb_uF5gTB?Dk4Oei0dC-xSoNT7H8e&&nv#twi)`x7~KJfuc&p z8GU3#F7PKAD z$W8d#p^#Z_9?G3|%8c>(USf2~gz;oZAY1@QE~=h`ZXf{H)TQp0BfdRx{J=^56f*JS zF;SgT?-{BQny4)&BQUBNuACrr_MGQOv9PVONGO5q+j#b1DR}<*A_QKa@R?@)8%sU( z+}^n)6w(wyNUf_RWDkB%%l{X9f9y;NZ%TM^)w#aCTbgXQ)a1xx(u4sAy1S>QrelDP zHILCyQF@$1P@%44vYTMPt7e1Y2*v;fh%0Rgwe=CMwa0EV;6NX^{=h;&5;`Pioae#h zv9x;!`8ApMvO=0>_I}p@l>4g$tg2#LvJp-IQ`B{PX+OPo!m<%-s_Sg<(lH!p9_EtV z8LO`%akYe$S4Uq;24RZCwsn@}lzoZE$SVVDJ?^L6z>fjfP(G<&snc)a>?OoWGa{Wd z`>PJnA-S#tu1MKi-J*G4uppNu{Y^$r&3{0*6j(u5_ub1R=5O!*};SWqXH*-@wXARsxKv zrKM5OeGh*0vq~#*vE^R9s7rB!(U+vj0P0s^CK@mZlGdY3+S99^?2hvK>dwh_1*0#W z8#I{^B-SK^@pnp%$Oiv-yL>BFWHwc9qWa`nkm;GR(pmAQCbo8SmKcmO zrM5F;X9VdtVZ;&u;uwoLtw_k4IXD;kP6@gA3f+wqZJ_;Ktf{kdDDrxLvfO*4xe3zasz)t#&`*~h{uXX zSPpnB#L_5LELLnB8sX3X>~Wj~^NWaxC@}T=$8n?hNobfr74>z-#u{*to14;m0^+q< zgIJTc2$F{v+n-|i9vmDDyO_QOOG{*a_2NT*_0!+Unw!(U{qTn?^k$3xzSUaxPiDP@ zGzmWR0!+v_=p9)LBk|}I&E7BA)dPBK;K4)t7@fx*5(eg~&YCKj!RHAJL-$WWQPhce znr&-!Ob}i`C?b@f;9t?CTEIFIReWh=^&OhTU&{ptXm{FADx zUIUR9A26)-#^dA&ROhP9k{ziFcs^w9C9UZMIG4Vg|H~dJG+sSLWTrR>kJ@IL8&uA! zVyW(tK=vIJd+ki^!$E)c7>+n;?dSkKDi!x799h_YdMxLO!1TdB-pk5NyF9tODYIe*R>!?7o^fmp(699@56Spj5ya$Gq$akENyy8^ua~0y zX$SxJ&8v0pj{jJnT z7kW3=pWfot2AH+YL3_p1fTi%4a2uZ~!B+{sI&lGZn(xBJhIz^>8dFCb_7|v-l;?wc ztGwUdjhH%&hlu#)$hxYv`>wfm+@lQz1`6vNfbQ|v!tssop>>8cmfGNa0uh(5W zCS?dGh%im}9|zKFoYq9^1%(5&`%*l>0AkaCg{WMa z#EQ(M%_nstaz*XpOsiLjYE*$C%9WH_!E5FEW3?Fx_jh-Z&;LUgep^+RGgUIEH~Uzj zk*Bh=(2txS@@Fq{CBddFT^NFe#-{J{u8VtP*b_kYy0+|lV=9pMk<5#?{8E zV#eqKy`k&_c;q{BOhh=LI;ju!nIyEr^_iq7A-~{}IS>)jB7h+ AK3=rc6CLKqn@ ziFc(m)ovzPrD+92UXt!gl9la8#|#%&V`=U3(gP>wn;%dcJ8BiKJ7W^ z6Z{ja2iZ_$A~HWN#ZeM+T?SSqbuiZPM?4Cn_lm zdzqaxnSu9pCFr6M)LtA|j*l7BJynJj+ku2wZB!fQ<*9=Bi|=i>&nLse2fnJXh%1<7 zb*i%o*&)>~zOz67`V!x3&e$Hr1}2Q3s^8&}xxxOJq9Qs^X>9DZ;(pdWAk*M|1*v%|HvCi~ zl9#sRk-5Hkl7UIwEUQ9z3l}Zo|0Z_OmVMr;^C~k1P}iQ|7jJkrh()5<>$#HR?uK5s zofw|3j*|-=^qqQF5LljASD-2rE?^a#5?H-Fonh8a1S$Ox;zD(Z6{EwiL~aL|toIYa zA~vsd6^EOm|HlIX-$^1E07+0!j>fBO!U25wi3d%t zKt8R45{zU02`jdW8~#{gI{s(@c)V{UAjJvZHN4@AtHvVCbhTz5{LO`GlqxSo*O2>g z#RHlC&s6lUar;O8XT$W9sjN>R8&S;;(yC0G%9#ocS;Jw#YjKRa=W#hepK%fc+kVBThH^|8a_{HcYgn4rLzpe)7~-m< zL0z-oQnR=KP)EzRbR_V4220;xgDAMXF{y|4L_lwF|{|4I+pWb7+Csh;$3&l+hb-*1B@dBO4kR&zGRG~v7rr0)u!VNvd?%L1t z!u|@2F_vmZwWA(ooq@2;IC0PImcH}eLTCSDc2UAH-r^UU3#MuO24eQoX)8D?KWj_eBt?QN z?~8KglLqD2oYXA82`WjUDFE4;j8@se|6$H2rn%XLeiR_o0Hr#Z#cA$D;>qecTqF*m z#UURfc&l2az|Z+)#ryX9h@u?{7v1t^8*>fRtc~bi$L%|fj-S~wc}<7Fe)kt4Ax`;A@>YTywT`@<{Qt{->wwaK)TfE zqfPS6k$CkZ9?utS3b|dvrO<~cM!>>Q?+6<)N?dZcNK9u9HE0@5F5(eP(?cQAo2Pa0 zQXsG!g9(cYyiv-3T9X%qX8PoCu>B4a=rVCiZN?Fd35= z$6y=+tDaHk;-#7-wnLgFjd`Brl2d04ol_{)2ean0Yu~lbX%MMN9PTT8&-^r|V-y72 zLFe#Utu%D7%kI!;lzed)uv5<;r0@Ma09FJ7I5<~@&2Od*;rcGId6OzYBy06+nBp?w zmmL06^0%sc3UB|u$9ZEu{TT%e&fN}Jf@iV#w5q1Ydb&ihQhfgNz4_yZ>to5V@_RV) z(L)EPKlDUIQUX+KO3ZzpvI%cCU=lUU+*ka`3?>O* zg-53m%Q@&NoWj;V++b~R%VQQ1pi;i{QOGi)!O5+ zMh-vfRd8wx-#fb0^F$N%YYa&5n_ioeux2cDp1NcpCZq6NLF@U*K(a{c#PKb;t6)oHe8~J%foynE50Q_;}Qn37?!`62mgEp>x8v>}Tn11>l?U zht#7Fw}2Vpv>s#4w*)$b$l|ba8vlVN^S+g(6p^KxltbSNv@0HHrlEz1>r5VD;*UW2 zN-BSuaBZ{rHH=%?$Ngo=zDMy?Bqf~u;RvyJK}b9!GD$(HkTFq(9SsS>^TFpSP1pOv zVMsizZ=R}7|BNMl`5zmX=Z0IeAM27P`VqIK~ z{?u>bY@yf6+XY5l%tpncQR;pL7WrE-v2(vPpQIdXLQE1Lcnu~sw=LIJNEf~yi;q7% zRsd(J=SqZwGxGeQXrJn3)lV7(7E8}Q5#Dfw8l&E5rlwAj8&@(+_?s9^6`J{fA3rE! zPb9ErtXqM6;e5&YE!1PdD*EimJv8s{-BtIB&u5MCeDQY#d9M;OXE-5WxLt*>$}k-I z7Fq7IoQb9K>wKM{G|H|PGRQkcVHCiKn?$8AFX+>)bplM~7F3Z&gp^X2@q!!+;Wc5{ zFZ;H>FgsjN9UYdtq|UR4g{WnzCXe0_TWBx>9hJ?oP-pC z!E?b}!udZ&et(XLc(4Dkt-k$FR##^+c}@v2um{Bt$66Yg7}LXV0rIWsyip05W9RRr zM`kaenKj9ACIrpiH$R5+OKMR5390H-L*^=5N11ug%AhA4@zv#ErQQNCtPIBSjp>DX!`5#38oy zEQuR5Qf!T;GKd;zoxp9F-97fTs08jgVVpt5kQyy8okI*eQi{%MZdL-ug(1A>>JeQm|_kO)yc zup(gtTsqd$!AsE6{JI0rXo-aYhDv0dk}=a<*r)=}eWpYIJSgaD_u*G;L`6dvcbKCj zMXtPtCx-d|dz?S&D?slatRYGL`~327@%`=Pa#L&TQwxhE!7$qNR2tBfP|_D3DPQH_ z1gZurXrl4o$BN8tU#=h?&c zNr?cBO>pk5JO;w9QnHs+B#=)WYyh$oj9nFKM*$0M4F0Kk<01!dml}{m)cZZ|>6}Z% zg4ST-l92j~ltd!`!KzMbIf__}up~($DFI(KsG7tFpx+_7CJ<4aoH&k|0ZvAL-+hP{ z<3SRuZ~Le|bh~4_a1?W{pq;e!YQ$*Eq`nC?(~)>Coe&f8tbt_S1S9^Tuj}iR3@x4yk}t^Ioc8DY&KbY>J!bj6wfmNL&nH(I zsKsmjbpFW)AL+tDdD_ytqd<^UQpLGD_gJ@UA-D2sFG-ch){ge=FmNi1^_Lv>@la1& zOOH%ic=)vR>yeq_FpXqfXf zdvJzS3lrQ~eXoHdY9v;kFl-=tK3aiCruCL$6;0w{+~2W^#s-Z6d`-^e;wm+Z0!z7; z=>NU3KisUxO_aE}lopE_IeA!tq(hD!jqPL8!JIWf(c;gr6@lj-^%c`Gp2daP5O_a5 zl?TvhQsW4)^-dH^%I<+8nBd2ZZ))-fHwJ_t1)z09ujP`M&UZm!WO#;QY9g?_6dd-| zh5)vg0Tk2(F!735T4GvCX*VyJ3jS~Ai0CJ7C>w>};pH7VL18PxaS;SFRVko}!wKkc zv%~o1gsLF$@0P&S*QV0RktWLP+0R>{YiSXSnzAu@wKjd-EnU~V_2(8$)(`$hg{mu@ z1^m9@L{VbskpQCSA9r`NZ$lJ)eMRmmD4FE5YGvIzVb8l6|LWpLU3_qsbj^zQeI zBWKI=H?%;$RJwxvpJW~+VPZ@P@iWW<& zi0PBNj*CsmZmp$bv9L`Hkr4rb;>mR`c8gJXe3F6b)VnJ@cl>#yQKC9og%+$6s$JEi zMRk>}5YOoU!5Tnz%E89b`b6+pp+*+FWK+AQDNUuFcDT?~OBEEvZ>!~TQP|3|nFmj4 z5GDgE>LB5_215;wELhaA4y*v*0eC7fDSH6_=|%{v65lz9z(VwG!!RDGRWa*PeyGVe z9s06A3tI+5)VbUtxhfY}pmQ{!{0+-G@NvoZhl)yv0j3cv3ZDv&7EN2o4OpL{9RrfaXiYyoSw=O z1`)tonkb;L80{rE0!<0&hMk%cSykqyx{7gCLgpZiD%Q>SPr7c&AWFfvWdtq`U`9YH znr#*y!B(I1CpE=V2q<8d22OTVz}%QyXo|ly)S)y+;Aa6UDQanzW9z(-4o8@aFthB4 z_tG*h)ZpjrJOIZEMG01j3vdQ(o zcQqwfFY;S*ya%|JH=E?b!osj+QJ`Xz0ddeHV0U-QJorEM3g1>$!6gPf6c@eS`lz7J@4P2?e$D3k6pVE}t zvZg5rT9iTH)y}&wiKo7PMCE!Sfjl*hTz7&9-7;f>Cbk&mK5X&xmVLT+?A`-_vWD&B z8Zc`A``97=fA|ex7a$yDz~64;la2+IeL16~B`<7aH^|hUBp+0ApZs52ZB^LnSegia zZ46=pv`kKf!|oHnH9In5P#mQ6q+z~&9oiSkd+e*fjUktR!ez)a(fMt;2L9389K=mc zrZC!MYv0a#&nVSVQeM%F#P<(OaBa=sDoK|FqF-%)d^s^0(FlxiK6hMrJ}?U4XV?U^LXj9XI@ccmUlq>3#4dMM+|nEDb9 zEHzj_ftjnTYpqFh-2G$%n3gMie*S%WdU_+Y8`g`I$#1FI$vts6cCWMpT%MA**uR%2 z(xJTM80PC2#@<5(29WIFY-xr+RW#h4!@} zL((sFdoKXkpt(57pz}aF9j?sN|F>pJIa~xoOP#T)z{=!llj)x%y7q$2An-GvU;|^3 zPEV(n6jHce#8qKROqA0rQH291Ahk$lpouh{EL8eATU2rQ-W!uX;OhX{04Yo#@QEMh z^_*5EAQ!4$=A0=Qaom}L%gYTNoscP%?2=P)lJlkAmLt`l<6(pQ5vRQZO24TY<5|)~;S$YF=3Eo{dMmy}hkx zVDJO%!ps+Oo;wBLF8-g*x_9B&e8m7G2u(_*-B%s8rmaabcW22`S1aC-m4L0p760|% z`#;|U^?0pOLpYd6D=)tO4*_R034&t|?NJ{qrV_av#s}=ot+)aoNttku@q!|u2YRg< zjMKa=l)k)$F0QGVAY9*sULH$HRsV7O`|CP?@m*RX0Sc333`RIdT%0_&uB)*LcC-E$ zr!4wruDR`oIEU5dW|OQAXZoz+y12m-vMeqx1}YLc1u|pxh16HlIomgPVnS&+ECdW6 z)l;v1&D&EKCw^;=M2zPI9VgE^sQ#>?gd92?K@3=YzFmY%=9ugM#D&(P?i0gs{Iz%)YX z%Pleg`SJ}(gUzlO_&v$CSp9KI}t z`uFz=C%@YgnG_xtz~RXX7LX+BsmA@H^cd>;D2_4A=H}P%McdiXV`}$ls+l0@)M{hs z;}NrwfuBmNyZbaKeO8Q2dhW~v zD&|ISn_+X2e+nNTQPAiEISGZFWv;%z9RWDDK9M_@tU zSUG3;&fnq2-CbgH9lq_oRQk?Y_weCi!?7!Z=fgwcWRm2xpOQ5JfAb2^ThEBDaSeP9 zKDES|>?1MeSIA8!M0u|Ey3yABG*tM{mxTlnKz7p7!$ynaHdg8@Z8dYZcGkwbo$IrOcpGBZ!p5 z7P8$JHFSfL7!p*d-#h(DkK#$Hc-NSWJbt^&ANiN)|+C}pK3Y| z&bD+(D-%?po5_A+lqryi}%`Ro~ZcR(0m~BZ^1u3C0 zwn>8~CYG4J(P_3i`|JY-s4Lay3NQz88y6F!vO`KMx8Trp#)uAh z0%2IBGJ(>X$1EK)1}%8n!HTS}q9)a+AY=rBI6W3`Q*uyy>Z=XhdaAKn%~)*-F`_u? zF1OAiipV46r)$KCilJjWjs4oriI8~R&&Bl=k3w-eNIm*apOMwA4Hc~|#;i+IY{{-a zZ8*bK`5~vo=REg5OlaHL>#6kn*5-}G(Dge90&AJ;I8y6I%9*&UC;y%SQ4x}nxvCg^ zwx46L@vukE#*7MnHDaa5Zya|O!@Sw}{^j=grv_xB&#|PBKNir1 zUpC`1pQLttbwETA(#b8vd-cdQ%K+Juv?sFBG+J${c?8!XB(vXEhuUrCtm8d;^J>3k zK;fT6>N7n0H3@82_Ne7M=?$FZr6-sRe?{o_w>S^_uvNvkNu-d`XlDF2S&6_Q*!j#V zfnV_rbZn#9@_obpf%Q<=koQe7xce$hvBI!Hv2TPCDQLB)kK`Gv_mLyGj>vXJ-9s)7 zt;CMBb%Je4Uq#I${<3KT)IsnWzCGFkKFgS?Bz$%XuCMFb>O9*iMe&HloNC27B{jJlJfy90ZaZq^cmN=Wc^y6^CSW#3vPwATO5{ZQelR z@lHnL@t-U_>T0wTZ#;bYBg~w2`T<>qWQ5F(N%*i-TSGz8#RcBtB?+Yvxnqx-YdIuy z!{aNh@b0S?LaphOCt}&(Yu^n!=6*Eihuh9wSK)q1)gyN!bJ$prAyk!OWo5kqQ#)JD z^A`QW8Wmba6PADf80ub5SLg!$2H2Jp0D9q-H8opJpEbAcu20?sT^&y!2>%S)040*` z5Kh+x7gIrAN;(Rkq0fcHg2rq#i_{Vy5l@^jOtGl5>F4>{AFgo^0OTJCL7?gz+5 zxVT2DtKP41S~BL3&qdLBX5bn5pX$}FAqsY>)b<8scf6)0hTdXZp*Y{KgFj3*ZrUE! zFXR3MQjzjtxht!$nsz~ow0Tbst(Ch3(?&F;;XB>S220E1R6P|Y{E}SzyM@Qw2qk6= zC{4vn?uPt zIkT0}nxzoA-VHoL;g=Nf`R5+EMzk3lc*#rH=!vPfm)z3kT{?V!f-%uQ(==a_o9|t3 z{#dXQDt#pDipcyn5}M=GL$rsOcy#R&7Z(=*Hr1V8-{u4RA2Xk6MXB>~p-*eyfx^!g zECaa@`(fd-%*$?#U#9((lSSAy7GWmz`Pcll7yWIQ zvl%xh!+A#Myk+DzUS|=|{3#jdb@wI&Pg^8MNoL5Ox+ zf`oPdmHO)f>zQF{K5`T?I-}rYzb9JY!2oBf^FF*pA$D?j2krq>Kt0|hD|l-BXg5MG zRRvPBM#rg5T{%cz$TyV{PKepR{qh^ldq(aTQHsHpk1C*Ji(tL-I_g>+O->>e!jBB9 zy>kh-LU-vfgK$eYO+KoFWY(Qs4PqFJG2t4SJD|K4dSR&%DzE}4{UD2L#6&v-Oi7H} zJQ$OueqapK1@Qob0I-z!WV?N*aI5p=gYys3PXCkd_nkdJjtPNLS*}v0#7)2f?)2l! zd;JJuk8avs(qcmC$w z$Uh?=*+nj=-sttDpkJR%T$f3Zxr1TQz4XVxEC`yPmg}EC|2YAsnQfM}6lO=s3e2kK5T91AQu}#S)3ahT8ZmEx<8A{x zp<_Ogm4b(e_<2u{(l10glpzl$tDFC>?uYw=@GmMuz^n1(C~UZ~gxwjrS!{+H$*BJ3 zCZM+3IFT9=UVbS#>)-M80nYWK0Evw)J4>cIuM~)ZZWof#)b2GAN^r0nq@AT1ji8G&8wPEVh+Y39c`=JFUfmVI32vHU>Oy*@b*OI*5x zODC1R))jOPj$_d5>hEp$Uu8c(QR|_EjfP>mey5ApuoxBl?<$iqA+BO3jPR`%WL|*X zUK8m5gvw{=%SuX})V=NVi9$96DQ_8}Wr|7B)2K|alrO$`q0*X6Nz(eAqOaPc-&j{v zl3E0&SZInAq3%He{+8Nk#Q7brbW-?|V8B+Wz@1dKrCWF8pp38Av1gZxpQKT1XsrJtT@y214W+})y@ErEXz;n|b-%*rz@x`W34>8_OI@zFJsewtZOc&{u+%Z1+S{DEqmp3J&{oJP1^XldR%;bURUDs(VBBU z?CN;c+ReKk_u=Wy`Q-VWsr!TAKRzMX%j;ezU0286(m>pno|QHHA|}R1A+hMXN$vck z5ZCB6fryB&k%(WK|1vtFx)j&wO9Zmff>y_4OtEl;C&zeBhT@g*^>4H3<2f9dh*M8> z(>hLO!Dj5ERul|M7!_t<_Jc0=n;))XTW%xLNJ!16gXcEg7uMfhrSi12{-jHGXQ{3q z+Hg4`OWoX|X@1x;zgrh7YV2aV30^sCz7@A8uyk3)m0iy#d0&r$QxN-~^q^wKvYSHa zDCFn|;hy9eM3~9$V8Rr|%ozPPkr@_Oe}}W+6$P(XwmxMt(C_aQ>-V3){DXX8VBkfm;adyW4kf~rmS+_rRK0UlP#%9V7^&N?uL+}> zFYYk!(#6SzHisRG6$_k{QqDn~nBT=(60cofbUk6J|TIZ^uL zsNo)z9frMVsltJ$bO~5}P8W zyWYV;Q^o4`9QWva(63SF%0%F{h=qmGfnR zXY|)|UH@&Vm8M3hOAL9d_QMNHzb16|y5L;F^o>v-5JSetB}7){R)2}w)mmAmZ3+(L*{^CdPwI?yp3fOE)LX8k@H z2xz6=wt1iymwX5ZI48>vJ-|w}4Ey89kBs)ovLR20l4zd*87%18+JC9kf!uRP5%P>l z(w7Tt?m|vqIL!FSfv@bd`z~*-@w+IEJkbY!hYNOB`bI`7U!KEV8Ha}`$^f_2-M(0+b?d>uDena7jBPg~6I85g#w$=E68P5Uhz-GYWEp$JVQHoVmHo~? z!T39ZScOWO%k7DC+=icZMfqU9;R-;UHL(dx@d*q*^W1P$+;wtzsWdXYejdK9(MZo; z&j5h4hOT+rcTHvtd=)u4C}<}6zt3Xqd&T%TTiB5ZFpZ2)viNMzHV1)hJ&#hz?iIaT z%}R$a_e*qqyS1O)i;{K z4WuUS_cPsX;6Hw^o`jIMUUMx<|suV){6 zFG}%C`PVmUx%<5WjrCF!WgMm-vgd?|yWX60{F_B-)s$tVn9#XsNIv?fTNxKH!%@GE zPb7u7cF3nwU-r&SP_V@&40wH6Mu*diT=r_AA~rcz;2Gh!?v1?QB1yQDbmVXQSzyM;|OzU9@Cwh3_A5Uj(Llp;V6N*3cPHdn@u^ zU4!+#@1nq7>fPs|fF=|Jl5jA(E&*s&A^;)Z17-O1m^mN$y*H@!aFXpn4B^e~N$Ac! z_VnJFaGk$qVc5G{t)YMO9$ky)*F2&DmXF9rn2T`R zzphjlk;ONXfp!a%N1|CRUJ!0^>aoTJ3pe_gBN{)K62Do!o|qw$bdk8Afd0%l-H^UH zLx241!wEO!Lz&F{tursgo@S9bDV~JzpRW{!GQtRR4RFFF^1;wb%$6Csb}=tI`=_mT zxR8pmk{Lw5ZGmTgE;lEL80ZZ=*vfU%Sj9E1KL_+dABX4%GM=BF!GOOs@7Iy>h(zk6 zx2ue!8rKb*-hN#=nJGF!Zr36ipn+8*Q-KqWY{qwbjhUH_1ZrAROsx)Nm@#AOK7^mb zsYil=mlBtK#zIg?==t{?``oVg#l;YAsX2+hgP&f&PvPEELF9R!Y8u-EP%jynzll*% zepb=)12pc+^hfSGS17R*l?fzLm#aYg1r-UjEIpPznM7fPxUfZBqu@V_q3=#AD@!{b z$);Wt;NR*mZe6NORJ<3JHSf8z_*NF^LE(1&2{Uu{fii*UpaAS<_ViH8YLD4R^6u(J z!Ws1tKJS!N#xl)R<=N}hgVyBUoh*f=a(jC;JBIb9d7tWtub%^oOeTIg| z?+(Sor*xcUDmnro*gZI{Fw`gg&|1E^ruhJzQf>^@pDEZ9-)o*=lk?fEw0YXt*u2Wf z7^Jk%@9pqCD9LgMjx{+#_Nh5Js$O1#rOL^6A5&SU$1H=6M3Th6Q@pp}UtC;NFOX0e^2}KkrS+OY|y%4i_n{~f+6%6$$z4ZnL zqe9OHVzO^ng0EIdNJtd;Lw|f^fBtjU@Bt2Tzd!(Z$xZJ*5fKumka-K!xvx<{S(9mZ z1rt4lTt}S#f}ZO`y0-q_x1ir@!VH@mtv&T_FMfzZs%XQ~u6niTuC}bF+x0fDMcuay z${kHhdU?e>doXa|wUB7PSGD2mGv1w&CwwYALXCIF6>#G-F`aF`KU z5>@l4q5_f%c+={CN;`tfF}tW?1QB-YY2>+%>acrdZw57>Mb z&XMrt0^*Q+Ey<(bHZ5Qp7Cds}hG(dTW}c|8PfwarvB?B{_x0}k#`ZwLn>`_Tm6VJZzIa^3~x8ia) zh&L)uLiz_e=NBwbnwIAhw?aN?vC|AcXQ$CjzNnw4;r;i*T)zR~M#lty!8mNPu@c?s zC9Mp6d&CU{I34S33ZDsq*vTw;3`uEYLw!x%f?K5bLgKzft!bi}xzVj5%pg$LdA#aO z6ak2!jh3R~c2mh7hxb@(>s4Ya-Z=brQ_T>YT7;FVhwC7h83Q*f{uQ(W)iIH7PH78` zCsbr5fBh~V`B%|N&+3n&&%ohpI6vgDVR+=@N2}Rt{TIJBq7N4uUfPajrsU*c%Kp8( zEuHV$tH`@wJ$?TDQ+%O6&^pmx%-Da*9Rw^k^gd~Vrb3WWhmYepMQgkF&X2B>V0<`x z(Tmi6JjsO6yYr%Z^~m*Vh?*MKqoU-F4v8N>e&7WbfQQi-3aV=ydu|%LxC90q`vRIw zMK2JA6aOk*Er(v@sN!Cqp&fWeJl?CDIh`Ff$X`ig#}@T|Yz!G?hSu6VT5rtLV6B^) zFl!#W%TK3u?HP3>=_xUlaM`uNHG;fk>!l10(|;@fcI#`I%s`OhzfV8)E73_^(9C6@ zHAb4e-$*f=Hu2A> zB2S&EIT~)=IP+N`jBuW>xBWhzb8)ns)zs9q+x7wALLDQck&zVU(v2EvQZh0@tG);W z)3MWy{!&YJcJ{Q)%%OXbUoQmEMUvi_7GVMC_Lid6 zVi^iXO+R0L@j{b+R`V34xTOQh613;PpP*z0Kl#+(*&h;C+{kzKI57!yHEUMsr1-8Q zQzs})R`|2V@V*!sG;NQZ2Ab}yUelV{NLeGAaCUQFH^IjSw((QRCiIU<<-J)KHT2HD zN+3d$?}^4o!GBJ{z;IeokroHZvjv3Jm-+dv^P`}I(K|jFZN4n-?@d+|)1J}1R=I3* zbj%c{5{25}_ct-z0vZrsZYgp>9FI3cHfx{zdO3vJ3y_QoZE%Y4Yf6yZi}8e{!U>d- z&=7rF4ZQvERZ~WiGRykl7qFw2xX0^q;2W5NcTQ=NT8If+oAjFv^*_*oFlBCra=nP{ zI&H51&SsHc&o2&Qp!pb5GmwL12ieUBlOcHgKR4#<4r;hh7l&n*?+SVv-K(TeqYedR zGrH~G!emQ4MXBVBwtsA#FZ4#=KOFjgfs)e8nLb`+DjA3PBnBQ%Xonqyo5D?81wZp3dNEfE@Bl zr?VTp3ka0O8QbsBld-5?J2gSo$ma#G_e;zj`|xO7U;K&yK{Ba zpfr}cn0gErY&^U#+V0cS^qBobzN&=<-O~znD^ON|b(e)eLlv9+=nn?`KB^tQn-ugv zHoI5wkXyd!1^aO3Dx5!ni8iAq2SOmcvYD$jwz0PtvK=LX3?PCAH zd+#}NYd1@6?VkJOl`G=B0Jc_AHG;QuDNKJ^&HeO8*;j{ZXiXhpIk}G}>uqX1kR753 zdrp@pPk8J>Kh>M!a=pet_g9iZ`S)Ut7W=>&}BtNa8E_}00ohAt!2s_Q2xi)A` zeFc)Gd0B%pu90WP5^@nKU6Jjt(i0p_y(Bk~<5wqaq>k&C;i#}E0zgU%T27D}G~gK2o;mxUX|6K6+0|5C7O6qZDTm(F)pNT&;)7+&@@lT3-@S3T}f1x5@3d_kP^PaxW>Q1BJ!K#epcbO=F%L z1pc}O__k)Rl@Usxa-D8Ju9557jTt@QoS43W{^1RQ%2zZVW>7@YxS{bICy!YP3QXQv z)Nygi{7Q_Lzo&f`4=ZC57+eC@C`Ox>Tafrr5&y=;GUtDqo|iL+XticekcXWI)tjA# z1~3Y=V18+`gEV#{SYrRif;_<~Xf|E&3hkP?I%&dZP>y&*5c%7=E$aUKnXSa}Q zM^R*Qk(c?8FYBX~2?&bBj&%hqlZKXcS`y^L)E4Ks$8eNU=QA(~+!(r1;UDhT^gq1r z>B0XGuM5Vo8y16=(lauSeAn7Mw~X4oY~L;4{(Kwy3FtTuvd`~!LhsoB_yWY_{^9rc zFkS=jq3~k$y<=RT5Ehb*J7MI0#Q`wG3E-7_mT)?LO@`GUj{|BOQb5NLH1zk-AW@ep z*4uMlkJfdE%B-FPCVfc|BXYSQ?cJiq87rh6a2GeF$zQt&(ejc;zg@gsj{h(D_@)@G zww|LI9b(LQ4Y5-+=cZ*y6e_i2uR!)Q+RMfZ8rOc~(&H6a3azcK)_so!V~zSk2b$hd z#=|Wr?mdDlxSy0n81Xgj15m8kUyL^?u)sxTX32MRHMH(;K9hvkuU(iiU8k1-uVDDp zyvXCY`|QsEP=+`oxZ>+K& zpJrvK#&4l0jd}>bqkwJik>LdwBR9!Ay#MC3dako18r5ZQF-BH$cLWVQS2i47(WKgo z8X{SX!&6FEJ0YpbyDJ#RATrwtdf<4dN}FQ>r_Yc4DI`Ccv}DZ>K9{@JF_i13cVX7v zf|Xx+L}g!cU?#sik0dkg0~|VbCI@^ry9$j*8{%A~luV~#Wo1?4<_&})8cCd>C{N)V zNDJ==9ERxJC9cti%%2t2U*?zVeILO`>cOL=ZW)Fc|AZFG$s9Q{el8RI>g^B#v%G8TdKG$ji({;V0p1p?Cp!_di z0(*D&ag9n%T@XYkT{YhdOD!ux) zy~0;?SF?c{ahd&V{`)@{NzfN`mUR(y%=Z{%GYJr!B~n2Q>9vu#Cw;}A#X?|${Cxb| zmfZ867aQnjW^Z3$XQTbyRXIW}T7!i`s$PCgR14Tze7Pc5WbxG!)$%U;iyVSV z>~*Yb74*N#kd6+#V4rUwMSmaT@BRjaMw>tjK>io>nA$-X>oTYloB#c*l9H0$;iJ~| zHM|-P0Y~Z6$l+_0S`_+>IiieZXl3sc-%@{bzd27Q1AzBSYl-0S<**I)_sG5Gi4WT) zA(@o_hqbp3tE&CFMmK_hG$#ukEKW9W_kI5tp%HbCz8unq`k&7mZFxxMWZJwQVN;0PtMpvinZ8a^mAeErViQ5Y^Fd5j zl_h;CG*8Txlt@nTPUt+96a zj!t55P06Yf)Qf+n6PIoF5?DlY23*v4uGeU*sxrPZwtM%_-AE95K7g44Ioa!gfB>UC z9G$7UH!wc|bgMf~!-#YB(vq1EK2<}nini?YqV)uUzg;{#$5barIQJvmznh}3Yl2+> z$kGZFC@FT_tfN-i)nCwABub~{sQbSZJ)1-Ff-nE7PNmcYAtrNbTF|E7&L!%qA%n!w z72Ah&dFZM!ym>`*l==PKwKP-^?5SM>iaA_0HxKAxqjzNqGrREU^zw^5?%R*5lr??L zt8@9G!BEFHk>fgxsxwxRavDjv;Vr(VJ**m@i_-^I7v9IM?2hixQ=%{PQrnD z;hUaa5s6qX93IY#jn7wD6wi`%b$7?pl{;?_&2I~N=g~UeI6!^T#TcZdHR#uURm&s< zY*$~mTLs_V(qYh3lS!xMo!~0u@q*k(fs&TE8 z?&ovROm8+G<51HM#A)$BV-#IG?~Au?!4Dl9F}eB zV@MKswfs`FafEw;N>9Bt&jGP{)&0vtgA$rWXf2CBBgJIqpd~Dgqa$v{o|*2`MePzu z--9cMd`|QBP``5kX!ptyelQ;#qcOVhz~<^hivcv&XPV{`=wVzOR5^MHGc_FK1KKBx zoGHxHh0_NddG{zw(|!r;eoZuE9(6b`jN(aDct*!^{rT=|-sIi(9x9SQ``}Jwh!t9f zfbCq4^Y$+{cLYl)D-$lT9H+G%zD0jaTKXKo?l;E9fj@v-1vJd=rRT!5gvQ3k9CS2V zCbVo-ctMvAEgYVm(@6{^ZpXHpgYZU+JLgxn&-dho=N+A-*=hVithrG`(&6(ZXz98b zx`j;7xIKG6((xU1Irh+ce#{^zrRR<4Q;Ley7#lbkRjMTP{qpIPCvZ!I##&wnzcxhx z(7VE^{H*?;jPG=$Sv#j@nAQT7FkT^~`qOfll$L>?kM9i@BVz>(hn5R>NA> zv$?As@Wmz4*Rnvx=J)98X4Ao9YSwt;?zb)V16vycs_)A;T@3fuN~qh$|A`8?GDRy} z(b3d4Ha0shh_GqoL zFv)z~HBCvUG8H?c>&xuTa$V9gFJtUhuF%;A-6fNF;aN8!+h{6&hM5%B2<{4)9aauRd>E&EHNs&F*1BP?Ne!3+;9+K*D% zTq|>Nl_D?3g^!q7c*EC|&!!hY>r}gf-!h%YxWWI~!``gOL}f3~@1xsbPWSQHg{KZ} z^BBnDLtZz6fyH%$=V=qs71_u-q%7)6lzCF-$nou2hat%1XXfY8bDl3MV-nJ~!cWjt zp-$x+b7VxCnLrjo$ho%d0=}Vgf^Q~keH%Ad^2BOAdxXoN@nudU>e&lkO-N=v=oIA| zT_JKtm01uwk_ZnyTlYk*jaz0wxs#YOr%OuS!coO395AvvAHfS%x%DvVG_vy9NX7e~ z{b6uW_AN@0v1v3xX#yM>dKMOcu6BM#LyS#;aU%q5uK?1;boDA1oOofZPe{rSf$29L zq5rmeaXTa?rmZJcaksPs$ztG4w*mLeyZ5Bgmxl8F0sQa!_Dnt`B!nN3eJ8LY*)3UK z8vIr~6C%^p-aZF>Ky;ns!+ksoc2stM3v+UGO{l!+8(j)0lq4+=s;!`eB;1lWy*M-HnNEd=Tp^Lc1YF?8=7WAE*^Otg5L zvrKlrnW@cuckY|W-mV#iV1C;9@j`R)T1Lt}C) zM189%7@z26Izs>1FGw%(vn3vm32e1~nTD$6C z$SIEaHXA)4`h%5N(Mji%2gS!aN54OS#4dGxH!+=ex!4U~4EHnBs+KNIOK!@JO5R zS|rIe>tH6azmbvX6#VkKW&3ZA>w1X)GOyV{6(C~zNe@2O_>r>gfj+LDr(ff|Z4`Kd zK=+IZp^G9w%*oOC$vQl7c9)$cw=8M6^CYi@&SDXnU8qX4*u>1RLbVv29H|TexeHhi z0)lE(&*HwWorKjq6hrSms~)a@d|;DQaUe1#eM~1Rx}jYb{+#7xN3+Ffngy8TWbRK| zSL2TGOb@QRPzgxv>7|dNgc9zlQLhHTYC>L8dW%1@^PU+RZnScBaJx8(i;K7Vhr%g6 zRlYlB8kG1P4-(a|EG!+B=U4;)^5&tLCV!9qH*KI;iIUVbL#@IMFJq2Drc(IgM&{KAX#8Xdl7acYHM{|%y|@1JwwZ# z-Eyq#rxV~WJ?^{k!#A~)^gKKt%F4=q?u)qW%pibF>@oDy8)0Zb^=5|{-T5U-b{$mV zxVy{NmXeBQJpeVxuyhm!w-FH{T}+Cy@Y9+PQ@5BzGWif0wl@~jU=A@k6DmLV0*ltj zUKRpd$gKzGle=Yff{49I^UVi6NomC?EUJcjuN@iqjF%bOC17T}eor0o8|Au+sk)Bm znvdeWSwB$WS0>ej<0!f*9u~V!*Y4&_x|%U4ZZLQM(F=uk9UQ)JG$;`7YOK8c&trkk z>W|MCcmQMbRNlIXuq*<#G_Ul zzw`NMEF%;u;+*c$Op>%*G5mQ&Vhyyi@;<32w3m?MQoTAl@Jx1WUMqjr%#TdX(l8`g z69GTJkd2LSg$1pDXSJ`z04Vi@FtIAb)owlZD5{0d^V z7c>s)H7tR8!jasc@uZfck@~#tSgfoDvb)|~jim>M^l$4S<78r-SAdmEq>o}DsIEFe za*$5ESWCL*SOJar&+M;ar6JfptoFVSZr2sW*{8svcE9<>d3QqcvU4gKzI0*)@rKnu zm{Ac*!va|*#I_Y;L^q!^DOqCb#B}=m4WYEcn6T!{XZoyKy$7F8hJ*AbX*7e&XjlGL^NxDTS#TT8&AxlnU9vfPI33%_c3!X(d3}ZV(MM7GJb=* zFZh9I49zS;La{^k{r!F5;Xoa5*Ue2tbiAT4zp{m}2bl(mFvM3X4lLdZZ%BoNh9W0I zN_KWovDSt-#>sUSmVG2p)RSwM^&6DC?27*60lZ4;fKyZS%v&G6{2qRh2y@CR96p`m zkd$?-YW9@pCDJ(D+*CrsF*C9((jVE)B9GA4Cd=36=q9^8td7rq8`x{UO+8DN_|{D8 zpy4<+?#E4`_1Iw$T%5j`h|cDe0e>%ONeC%k?KCAv4^^>en?mvA0*IiC{}5}L^} z;FJdqDg%&Y%FxFOhnKHV;59@SLOgZfilT!nHc^$7}oXSz@<1Q``%49kD@( zE`$*=5#9Ib+_=+~GyN`p9th!qa$ic%TF?yx=+|j6v>63>045B_jY>cE-Bq04s>8?; zoWZUM<2Si-_>9(dm$`kJrTA$Tn<~L-KjB1dVI|tcJw}%Xr{L2}2EM(KwbWev4$uTH zplG#mMblk7SE;M66AYrUCfB-)=fiDs4AC<^(KM;LPoX8x-!qffsKPWeeSO4JNiR{C za>DNUG0+N(dbGOrYVK)rNAx{$=LNFBU1eo5LXj<^ao0_JBuxz0w12X-fshA)SNEP- zQ5Eu~#s2L1#Bi-CaML-XvocaF3{B_O7@=_Jziq-wu^Kin%r_c8d-m)h*c}=y_GK=O z7-QYS0wRIBW%+6R1SW8UZvJ=2SD7#j}kvuqkzorPY0A2t@QJMw&?;9;FRAVQBmfwFEWqC zc!~#yVf#uW*efPQ65Y=cbJ5s@0ZdlQ-(%*NN$5ngX)x>_;;Wj;G@-(1cn1s;gFh}c z(B+PIj(%*kUy*N3DJP)LH8$r!W7Y0I+&3CI)7JxDk2Tz~h`A34G~07@Ym2tJWQrl) ze+e%gwHSk`zc#kEABCMb!AyXuaLk#7z!%*UN#|;CZ?bzFyWS0;s7_6e{SMiwdfqBx zR1iqT*Ojd;23bC8Z<_9;3HZ`&#>p`ad+XEjli4sCcdgcGy`J1@e>VIgw7&?2*HFmB zGgRza$09USoq*W82TN7}?)F6i8z#gC0Yb%})Q-%T<;?^wz|Fr4%&Kr8zF$=&1%Z?0 zg$6=OoyfNZ!yaWcyHp38&rWco!cmyyCp#p^wu91#t7jXh*aM5$JLB#wL4q*bORgg4J8k?^Q? z#~V*)@N<1kLhy&B&%8MxkPrHJ^yXrIGD`V9W9Dbgn~y_1#afo>uXu-zfNlwO{;J$l zXxekkKMAJi{gEtBr{%g{Z)hoIKEw_B3j3-95zykPe$|s~b%F!B3|7}c*(j7~!!!G0 zhm(Z+lY|}=B5vKXeAZwfGr7&{jS&P48F(~p=xV3=E}5^;N1gaG#r$rsK>)A-K6~D&oQ=gxk=oL15U9BZd2fD+TYYw5Dy|7XE>oHzg4iAvfT(~#`k5^ zQVwU6^tJ*yUg5sol(os&jNLD)7<&^8-I}$MWzV~rx<5v*>8d+vMyvFA{{oz6=+n`_ zE`O;7iiP)SJWAPn(rk~by7LC3JMNqK2>U#O5hzGUJWh_NZCg2>8W?1hxY+!%A`IY9QnDyu@1iw~u{doVdpFF<}K-|G8GoeR(3NJDe~ zs+bMa!L)56YJ0EszTf$;smYfa&{(^g6v_;7*dImH$?j?Tv&)p@zLC`_>;uCesLC-K5N*y2-Vv5#}?CwbBb z!(JnMJcxb-lK;?OpGA%Cg_gZ-9|mpY)vu+U#ymSrZ>3(R_OUO>8S9B=)i7c^1UG!T z5JZ`Ss?EgAm`ex{dhy=+YMskPYkgiod`5gO7j(woQ&d$Q$T~P|(LS!xKHdnoA5DhO znkVKfbXFy2(k`&ut5Q^o{ploo;GCsn4rL&HM%Fh6>Mfo!0Y;;jEkElRvH#Fb@65b| zo~z<5B+9LFCil?>fU!PsmX_<_JeQ#y z8mn=gm0-0lAI;udO5*W)BmuCyBqx7;&J}em3e^LKAwJJ3ppRUERQKr`YcAd) z_i;mUO%6HlTpe*&GE5+@k_LwN5F7hT1(NU%-Jp~d9{i05rN$;M41t&MAjOfTy!0R! zPwYbE}C15PpfBGAP3+A>GCQTk+8F7cBEDx=v^Jm*d zao@W{e^WN8O}m*C|INf540;`JE21S&G}clyQ}rJNp-+>Gc;sZK07OsYc#xa%2=DfV zRk=@%O1*L@d+$eRP4|ttU*HB=1gmC_3=Y`_C%)=}s*9HcRFm#o3vEXKdT1_M` z!ge9C$9?~D>iun8-5~NTp?MF~JVC+u)58Yq#Orb`wh!yGXv8D8(2^r%3igq>~op zQGIMIff*P0JSlT(IFsaFq$*C8;{~(bq`=doz)ZS$aON2l3>Jk4o`nuMg^(!)?{SKx zc4m9!&n6TtOQwmi)&``s*brElnPTQpbBw z-NEt8y8|q#6=T}NOJZbXD2sdZ?q9e2;>7BASlk;jLgrAd>v+4WysQ|8aozar#oh^`h*8m9* zDG3DxK0-A9_Ov?EgsNTp&tU^%FvgizTRGI$cwrWU@SCL0OsU40ed1o zTnv&SV9+87mk$ArU*ohcQi5K%U^N}cXVWe){|?A!fU{s!$=ocjBfdxdqH+2&g7dDF zuo!x@jmp6a6(mbu@N=ihUc1MNggKtfbnPFBG17oEP8CCGrmB9JhqQ%`q{V%C)SWuVoJ))2{r3KS4F42$0kBe$7U} z37J`06G}=V0p{qN0zRlkJ*`Opzj2h0w zYe;lT#T^hQM@LtQcWCj;BTrta)8)rj6F0#RU3s6ASw_~9OK|O4ry(4}OPR#p48E;t zsk&{Q@l(00;&E(^Quj^Px0B`LXl;K(-+=MzRbS-lCw=L1^&1HgX04&&71YteZjjb4 zAT@dbBDY5I-EFpfmyY>YkP9E zyPDqyuB;!Rb8$yL&TVH9;EfkR>LK%dfsO?p1=mmWH&kEj>F#@*Y(4xqry}~X{7uw# zli?h+mJfJ7;s*SlAKr)EPoQG?`2+hl5O1+Iv zN;e*B^Pha-Eg+DG1s+*Lq`daB)Af>(-#HZu;M>pr^p& zw3@i}=+UDubWmw%weCp(;R))F-IAl9o$>l|AliyNFUNmrt_;4vfL{%$PE>h})E#Ko z0MD5h+B2{dtw6P+@Z?Ex$1p-s3!oE=&CBD)tNoObk)c!oRHlRZyrqun5}YnqNIA{d zN75?3A1}!<5aB&sEL6W0+8r9NaxPLQQZV4k-<(#qTYVQJyH>*OQzYv%{?^A@GIAzZ z6p~~Xm1)&7mql&5%X-c(9ejFdLL#r_8-Cq`l*dP0{vPw*XCnvvg$n+{++Gz4x3egr zOuJk-p;ACsiT-TQ74Ns5)5wk+eY^1H1HhVVK{xyW9y}1cb!&ZK69rj{4G)dawxwod z)J<9;`Wx!E1HmG|*X9_uyv`pJ9bMM%bi+EQFtmLY;J&1kl-E!M;({jDX+EYAfp&rM z*}Y_*mY)6**xR93WT%i^IDgsibW?QLZY=wG(A|j%>JT1?UPv{x%^^a_dBRXV-m~$l14why|>Cbg6$(R5=d* zp3Dx!$j4KXb20@(0f8u zLuLaxFA`Y_uR&d1jE3#JaZ+&hamos zv=$OvyBVo9pIQbUA8C30tLiO+_fai?H{Zpy@RhzB;$H%}1k-UDkSN2hl6t!8laF7n znMRmWfX&rvD*IifRKqw+E-A>>&Fut!6si@j0<}K)(_n}&`&MY>wbqJ#sT0spo7>t9 zHfEZsoo0eZoEI}Yl~ez3k&s3@59IdvLJVa$`azGhI6$oh_2Mqtco3jek zA6kz-@3#hxGdoa((Z|BT+bb-73E;g3-2>M<9;@RSN z6294Zqsv$SzTf3)|HdT>{4nkj{Z7gF2HrD{OGlDtRK>CQ@%~){K(eaWka+olLc(R} zrVnRW%p^In9hg5=FL!<}l$kV}Rq^{*#Fdhb4Vzbxbni^C zQ|s)X>rn~02;fc@;S`~dm4Mp%zDzu^H}E_sb3SyqyOY~dIJf^L^f9zOLdk#$5yV7& ztQJ94lxb;i;K<|B_3NB+ZPOrou9M&5m~FxMl>F77=gnGC8W2Q;GPoZJ%ayTV@$~ML zY(+pK`PKwxiyxSaFAf*pgx0*-c!kK^;Xj>vtnw4D(X7Vl>gmptN(k{lLsXJXE1V=! zmNfTled@5dd<}N=9Rv7~x41n?IRpEKyYmzb zBm-BBC#z(tEULP&Z@;;!?U?Z_vx9a!+;V9q<_?Zdu(-0{k)GsJvt+gDJ2N_E;3SL; zJ!sR?dh%rOZF+FlbvXW`qoa?sEI|$ejnS_V!0!f9o~;_TtdzZWVG4#ki2OV%?6sG? zgF&5y{*ovyyKaG9+FmFnjqs7ywB;zY`T?AjgK(O72VHe%Qz)H>s_;Jr4WxnH58U}>+kGhP=oFy~!kz|sYO1?ZbJxLjno!TGPAHxh}*SD%5gYik6D*WsZn3XvOm zpF8geu2Uc?!b8D^xIj)0J8&Ge1`F<8WaRzTv2xfOW}R?pGZXxH2RTagBMKkpYzNUY z)I1hfn&`j?$AtUk4;s;@VP;r4XXO4v^g^yJ!3jr4x)r-dYfcVTF{~+38U5ao&2*d< z0R z(@yJbeA*Sxm+T`rqI%c(I;?)Q0Yve4nRCk@!GUFrb=w5r%P##4UB20k^f#MnJB)xf z=q4!mMvZ{-oEz%zYm_E-Lzj}NP00yfx{|LpDixubUR`+V1C3FPWu8pcQm!=(TZ#g1cujw^5tQ9l?( zcs&!@-_$8`_fTZK+KNTZG#*$h72|uV)k^Sad;EHuU1Ov7+J?}&20)e%^431m2JSw%=H5Yio;-AIk%1TnkHmN^Y^owhR@Hs-yPWzrO`OTnawCf9fWDp1#|KwP-)}&7RpB^Hjeh zjgwTe!1{D8g5Z{NE^OX&1G+LIhIbM&kpddZ>qeK0=Oz(9Y~~#33}TEwVfpgr_c!8tYA4<6>kc*dm?tK z>uTGURms+A!VAOz&roKGI&8pKMJsK)r%UoCIfB^xBfuh6BR*nA5A%fNg3UwZ~0{@5{?yWn^Sr83u%O;TrYi^aXLxpH6NJ;5K&=oeAsf9=P6K?#>w^(Z}QE}-q%t0;~18=olnyC@lAiOj5A)|0lFjGVb;kY9#31 zg#kiwp_ZK;@4%r0hR%tDeG#H3`T66sqcAO$rFGCILK?n$1stH!F>H$@712}y-b%Q( zTt}>kw4B@=oN2Q#_szU>mp*qK%&%Xep<_;LI}0r5bq|y|*=`92e|>=%Dj{Qyw6c$c z%E1vG0lh&%g}@|8vkJ&2dIcV!TInixad@PtSUm9(HzhMOu-LU@{RPxUaC*iZA014u zJ0bu-->BVrlrNnHmgBv*)IdOjYOkW%ya%8fXk&#&MfvwH8i2wXtUFkp_n~j&uS)?E z+SdT|guZ`Y2QePfAXBw15rC@RTus*X{RFFt$KW)?L@I+l!4m})3y)=KQ|_1SWvd`K z2K~Taxc&5`sx8X1%5;xZ5*PenHgYlfQ`2#e(k=6gC`sica7nLu1EGRIXI8azO`)Uk zvNd2+%P1YJi+1v+j;=kJON{|gVF?1_a-FSoiBoic<~)eZyp1CfEw#e6I|c@qK?KUF zUT9$eWGlo1lqIW(Vd#GT|D5pSr=_f^*#=UpQ>zAm6hJ#<;lI)dWUhTMRzeKk_Q1Vo zzggbBCP6w>wbb6+-$EPyi!9%0-Jj_%%q%RxC%VYde`@o93|R&kES?eNu@M@V<91+w z3?%Vyklef#{cUvRK?K5`L;=<#3@4QcFeka-!w z2tNjnI0&% zuQ8U>W1b)G%KaMqEScZ%Cac=#8b z|N8$73yrPv!h1cybqSf=jphg%@r$7C0zFrt&-Y)8i%yWHfif8lDXDe9)&ufpnxIC4 zuVa7_Ani=B5cWrG<`5~q1|TQM7wQnuwkbgCI<#)65|fgWB7%omK;EdJC}KlF9jXs| z3f1ZM%)nrIyWBq|Eo}71;q{wJH zWJ~k9LXF7uW=T7jX%(}^iAL$aW{zQiIVQYTCP&^6SBw9efn3B z$G{-lIlP;otD%;I$$5bGqj8|2!SSplLTDJ$GeCbAH%3(D=Pf-#;Bb&F!^C>U(}3cg zaZvCteKUPU>FAe%AHYrln#U|8YL88$r4F1;dwJPhf1Qs#v|=O|-9BfTIn+0Ipiydn zgX>v)g5`KcLSo`W1qIZ==Okdi-hE4b5np>bH7DoYx${@@emRd=@Bs}(?9(tbj>$2+ z#4!n|r2w(mng;rr|Hb5@o4_#Fe=Bgs*?DcE8qg_(Z~W5 zu(41&2RqAH<(6>D?GVw3zlP(m`9W^nVm}r*{$Z&yb_tx&#UEL6!A~YFuQIdPX3i_v>d^N4Y z)P6V%`WH5>gRvUwNG{9qC>tDZr{gevC?s( zZjPXfZ|>;0dI5(6Ty9}yuJ5}Zlr4kom_jtpGP@6_oBJy(%balKINec6ZZ3&$Z8hM( z*8Fnq41zvTjeHDS$LhDzt9lg0>cyx=YI;-lMX zI@6u?tGwo{c~%y6&17ASvS6{Xi!T{f_LDn9V*~C_I@gqb5Z0efO>j)xZ~OVv_)89&r6p(#<!`3_2>AC+1xzra zAf+Tg3$?{lNR0giU_q*E1D@lx4->--<@^X_HZ@%FsdQ&GcjnaWUxnz(L8@E;O z`mZzKkQY^IJe-nu?}5@q>7FS#P*tfEz$s1G)zZj;R`eP7H@RyQleTvYoeq@#&*5lf z%canwK@`Vkqa`0=gdA2jOAw1knE3%9+F68sbU4RX`8gv4(u%4V=!lPo01T2qPR79; zU35fF3oJ}sc<&9hpqAMwhspyQnJ`w}{f*hyNFIOS@Vw>FZ{T)`0tG6k{gNtzK_LUz z0FFWEOT}}MreAck5H_+fgmqyUL55&;2E+?fw~0!b7plO?)u}r*B_CbYxWZ>nDvs zuCry-f)C`jSBi^^5l9yitpHPuM{v&ae{YOUwtV12WuXJ4{H?|QAi!kYw00rsnTNL2 zEC7KBJ2na8e6-DXW{!R*us1;-WdzqV0xwK_#JLGs|KKiJXe1&nEse0w4ws&ZO+zdO ze&{P04RSI(Z;n?x0j2poKnDmytq&+Hf|npk^~&h7M4)WVIMA$^Ur(HBm?tL#85Ht!E@Bs^s!uN4|Z&GAf-7K!Lyw%7cj8k%gDc zNU@Fo)pLy-tGG(x^P+zt5quxb(~cPQe3axUKV*zQY;H#1J<>BSWjP?rL04@wxGdT6 zHsBFDkB;=AQ;Zgb@YHjCx0F3l&N=9W+pgcrLms+u4qI{{0*B9F(AtT8J8=2J0wS$>;#HpCFkFy$S&RT$0WhdEDTTF*?=`{FdqL z7aN%Q$(e7+hu+8d0?`mZgB4&V+7Kky+q%Qs!bs6yGYjORHh zJoUK0ypw)EHz_)z5ULy4ZRL-CG_!V|4Qxni)hJt#d*3dQ2Jbb*kd z`?b~ur;$5-EDSdEV;(1Na0Epj8Cjn4s!WkNg2QeiaLqPGUl_4DmXfZwFo4xZPD1X7 zdqmFN*Rt~)@ssxd#kL>_fE9I1LLEHR8wmU|T%ukykc|y!y)bw};qx`_MqX$aKFZZ} z_6%k@6|kA`2V_Ml#jd@f2W;R(BSeUT*P|6>i+j>P)@Jiz7&Ty=*e!BnXPx*-9MnoP zIsvpIku^0njyD;9Axmv`*=#zg%%f!7P z6mq3h#LQ!2>cAl$UA3YdT;luwt|x}B3){)KIrA{g_8Mp1 zIt|LSP^HdX(}np7Vbzs%A>ZdReisv!slauHS&HEt{goc<&dyjbYW1(Is+I9+M`Y(u z!JW{kKBB5L+#bnFWvhn>Qg??$)(-5A4_y~@VCY(yNZjHeQNs|iIQ{!f>wqPd)GYTa3H^+vg|0zHEgc@s zZ@Dy?rH+c$D^xiQnbmTNmpA@?gf8K;IT%LVY&R6pEAXV2(W+4TxZ0#wfu+3(uy({9 zaS~|^pm|9(G4l`#FYseq7d@=|^<`t{i4;5PLp|!klaF7a5%D!f%NJDZk!8iFh>KJi z_$$85TBDLqvws(}RBcSDO16}eGTfM{o??yOCwfNp{|Z`?e0pPTTr7b`p=UAGl36;P zpP~Ah{=NAb9mQ+mqEEo$U$TY?qQU8d(4oNB#}2%aahMfD3pb$(hq$Vmt!rTnEO-wc zclk-x{=?C!`=)}fJZt};8=%jlvZSIzqDCS$WiCc+pn2b}j>!Lu4V{9RXiJ#XMm>F@ zVrM)V1Gh8SvW#NXP9&5{h;O_9vQoT5c4Vul$M)7oy2tbKIr`rbINZ+S^s7>+x9ogt zvktSWVW6sJJ|Xa2eo9gkP@#Zk5_rm74z44+ct9RdW}NVyHaj-lLM(f*;D88Sb^8NR zu6ni<#JY$TQwlzc+}j+cf1yTVV=$&aFJWT1j_U(%4w1> z>;jDmilxha*6O^?-nDGltEpg+aYmWm@V^&_7)E*;YW&x_;@TWj!Chk%uT9>+f5S{@ z8P(VSId)HjV58fOgB)fYoFZ*@8PBX%QGHgn=$Mz3EpE)`SV+r`mTiOTyI%Qq5QGc@3lV|e%&*>g&;=eo_~ z9$p;w+#da0k$PFsojr7;1ohcU+WPLJ^NiTC{|e=E3(GENxJ?${cuRI|ToNG1y5vJS zp1V;xYOSHE3h=vm%2hYp5TJ_9O_h8aor||N3BlgM;W;ydhnXD2WWqmk%}~ij7@?f{ zXRvN?xl-J%oxal5o(N#2G&lITDHTjx@i(=!)Gi3`?NaA8@De-*qaIrM#UqjPc$nv2 zk?2I{y?)(<28JDWaM=KOyX7wN<+`drax)T2VfzZP;_J6Ai(a{H!F7JB8f6FsK4Z22 z9E5F(C>c*5)Lm{?J&M2~=f2JTu)1?PZu;9Jrib)K(UDAHO&z+e*tdPpJL6$ZNa>5j znX{Q5yy6Cv)sMu(l;rp~(s<+&WK_X!9g;LaQoSItZs(uIgS?i!+!Z?bFpd+kpN2g4 zA{f&^CjCb17`&0KTR9p5UuanyiH>dsa0{af1m52Ppa|?=OoZeQIzK_T=!wcl!467bAt7|lxg3v1@IAt+H!PJ6 zTs?sHxB!@PO3BDDf<_DA(bM7Bkd$vi`nUna3LwDw=&r4luJRTK?vA+xL4H30ASG0* zfO#mjmLQf!&>w3hRnZU!9uV{}H9U^CZ~S(bte^{2FWT7xVm%koUtC4$lA~>K0Px0u z?VzlTS@pleVtb~J0LWtU1MuWtQE-|K7V7MiW|Y~;ljlZ4kh(mNPxwxtV~|`YDu(0z zuXArl{$3CgS~IOx6XrWn)W%uQV0-lRU`>DJjxwlj&qh-<-A?dmA47vo8h}t|AvLd=USHc8wnV_ncCi!JGcQg_R?lLdlL0yA3vAynUl?Ep z)83Ur4yTQ$h}R_mG}Y*Y!c~xJe@Aloh(!_LOMs>pc!DGrl}GlVt@J5h*{lY5n+qE4 z(;z}j0Bi^WwKbrP?xL9uw7Fr6(m>E?cthoq`fthl@9wik7s%e6(+NB?q1vc+#@)YzH{8ax za>^~2w7EC8$1lx{5b410k^{dyv@@Ux-Y)2=m zz4l=%B66T&D6H6J503Bwrh5kRBNV8XJ(0ITBjDPcC|v*+t)r*=(Qj)|v!Ee-kiTS_ zh{gRQ_m#?%WAxt+!1$HshVv>$CxU20qSteh1I?(rH9CLu83tLfbwJ_k2E%6c)M|V=Il*4g8A`)CtU#IEi#A+&MkoHmJ=9h7 z%}2W>enYNI!B7hmebS*uNdyEYJgmP;B{O6}Oj@s?EsY&2tL#9q*!KX{l8OqGDn0o1 z+|l9+>wf9cetQ3~YxsY2M&!o9!9fk=8J`CsQ~JKa4;{7_SY$D-F)ARPfl z3GI~5O*#Ha3{d_J<{HRsl_661k*s?`v;Z_8ecBy%JOM4NS*w%msAb`Bc|T&eC>Yr^ zP>H%Eg?|#K{riTTuXOeUA-jC*XWP}QpOV13wk08fle+5u8+@G){o&~EriKmz|Lax~ z!>E)`4^GK#E#Hrb8m17bFP|H9 zWS7pSI=$`G)R+`Vv98yv+$} z^>Ojum_Pn7%ef%t)(r!ijibM5S#Y}yQpIqvEw6>@v^;8vOfPcQKgY8z?z+O?vqJ7h zQ1x8_O@ctCmV4J-oPz{u36qG2>WeVqG*o9<^0#ZWjrY^ZUwg{4&*j!+pLtft{0D7f zFP{+a$fqA)q^L=wvFXOgiE3~Pr}IDj&jpZQB8XpLO~C+^vBj--mktQ*=>UI(MCpp* z1wDO)sRt&gfMh}oF6hecw`5o_$O$^Ndk|$-ZBsgm;Z^Nsp%1o-2-gj05BU5DsjsK! zF(}z{+{Oxc0Mzu}-<${8WaR;5eO(U&TWQ{OEW`tP@s$`O`TXJR4wg>ICk7o4YVPFo zFO_bQCgG;tR!|~!A@!ZqkusznfBz4$^PD_#1BuB54w)QJ+1tPRMO|Oq+bFepE6iHHP5u?CB{j?K zPwFB50SN;SDV}BBu%@1O0{E=$ z!EzyDm^kLVctgu^@+=&!IUU0q4x`Vbts5?Gt&B#|o$NJ&!4I@m!MyIW$M5dA2;hl9 zc%DJvFJRDpDl3aN%_=sG8;%Bo3}h}h!76wH5}GR_A~66EgKupE5*8tv0A-L*6`*D4 zS0p5_9+mDR!;HaLp0Dy?bTtD0H<09XA;cnfkP(K%^1H`~Q=X>7XgvZvBH&9d9KEqH zVv=_}8;(HXtp^Lui``n!)VF!}X3nV|^WzE9G-%gjnL5}E*JM*fMAc}D(O6pvIU4Yq z9h|9fKtEB8XeL*8u-)IqvflU<9g#l!+ooCiyRjkTKfxAQ7^BYNs$3BFlX$oU5Su=@b>gQ5E)|6MT{L4mY;=h~v~!9OBaJ4law$0-VN z;Q?ns?GdY5{1N+M^CAs4#9-tmn8N>b`#mpq(u_>Mg=Yd{_X&`O>UJeaw^?vO5dy9N zQHUln8hoPpsRkck45cm^D=Kz=}PNQF2IAdn?A=+F@hNYFPT z&A-F-AP=+k-Dw46@gV-4Kni#dkbt6o*EP$)BF>{SBJ(I{&e$jG)o{~o}_a;1wF{jJbyq>tZmV|b*(e>fM<^X6?g0R}Oepzh9@ zUWD`|J^j@^*h(j$+TON#eeSvq^K5U;s+t2@B2_icBmKPrIZQX(9RfBJfU2p}{;_I& zY6)&GcHhRc8Q=0VjI{uyA#LXNwookFgWQwRWe9%|jDBeL3exO7Nzc?KT+_iS1|I1n z;p_h7f0kS@djIF3>!WtvvWRR2I=axng;v=?d7!})q`v~xl!)A1P9&*8N=8gPBd>LB z8mZ|YkIX;u^485rzhd;ji#zff7o6X0>A#@P>UY~_O zO~y4kkF?THXQSM-E!M!wZv*I>PpAPfz68Yu z7n}^&bA9FL$;ZLLjpG{&NnPmU%93A?1O$Aia7y#}Z)!H4KYhmVZDzvmCuYX) z-_Gv9;#i9sKTN7GEC#n-#EIN-ts3h|?$dM7agDYgGVbZ?E10~0KCattigTI#h(W(u zkJ^JHf=%xE1YrzPB==R!W0$$-y^Wpa0Y!DVdP^!U2BDeyhvB6T=27M`b1}Z}GTpX}e*=pEKUg>N zSdIxJ^HjmCqKQm%JeL)5t~lOn6x)cWJ9>>|9w1j*2g1_&cb4qDWj!HJDeQROA9pBj zJfn|xyolP=kbktdjj44|majN}u z4pP_ApU@U(wB;ZyE6v)ruRsbcUuX6lm+J(!tA?3Pr$lD>fWZWpj@X-Mje-b9)<>gG{-7y*e634w@0=DtJ^ZhxWRvqHccY__?;0$;xTbv>`=^&raO%4k?q%d|yn zmZycOE4xg_HPMZL@xK>jGv+s`f<;WS8fgQk`&(e@l{%Lum2~mA-Lsr52yG1>uDv>atxa|H5g#<>|6N6#OJaJR=woZ?vnI5y z5qh>~Hvg!XI)0S$Q1;u!lRtcz zDt4@=&U9Me{4=HFwq@L_((&A(9H+q*<*ZLLYJ1*%NE$&gOybhjPy}ym}oH z&H5h78d)5~6&M>GeXAYqB80*f;2|0SriZi_5&WG<%d+c_aJR+$6r#T`J}xdiJ^c~H zA|DTdlR1j!l=2W8;8e3FWtEJw)-`JfKGBxn9Juvt`+>csIdl-z3C5u<$DE z;^&x-)(XqeQ0OEbAEvDuEPJ$F`irHIAhRN;`NRq1qpD;5PN@sqRj0Qtrm|oD zsZx2kf1s32LU^!4QZ-n7xwA`8MCr=rNgc_>FPC=aG29TvH4^#`15f3V^))S+*yL0c zh883rLNXCkGGafroKsQ3_)Sitvk|J9tzRbyy)7P0>g*qAY-~KQnRoZ@ExWT{Qu$K{ zq*NE_W!QzO8orllspQSyV^kd$_T9U4wZ5#6n5$~Qa?xgzLSTJZb&NU%#sdE3ZnK8m zTBXwilBAzs!_F3Q$aGXzRq3INr@mO(&Q2Kl&@Vzo)AGSz)0FnpJ+_c&ROwWo-D#=0 z7;f8DWIIzc;%7G{JJT2A*PF>Fzuwv6jH|HQ=JyBuI43CL0C z2G4A{MVYNqP~w>EkZpVXZq-duhMl*R&#fS$$$1OkjfLwTW&;j&Kwjz#Au%<1_R~A0 zC|~Ue)R07EkZ59qBrdDd)R!9&j+?!ac0`Xz-~krV!ks1M2Gr>M&tj~8Ssrs=LGa0& z{p@6DXgI!_15sZ2Oeo5E%>`~3%+C6$#JA*!*tpu=NQ?5#>hrAV;bY->{%K{#WtUgd zQ8WP={#Icg++sx1=GX0^+of-dT=$HKzT8clUV=~u;tckMVB28&SV0YuEdsP&>2i@t z!=iErL4VT)5sgAn`a_KM=uoQ%{o5Y5C$*T0@hZ$0Gu7V4^e&oz%Th5f@ohKj zo-OLRJLyz?ms}g&zJ9yyK>22kg%6Se&g!3D4x7%d%S?)9-?d23UdrHOIJ2Dp;px&Z zt^+HnIOGF@brcY z+b^W)4~&T3`;O!_(WkXqo8nZ+p|uSHaM_hxO&6gEzXRdG!|gH_6>K($80qbTaR5CF zpM3}unq$mNy7q%hVmQa|oR44i4#ByxhNKsaCJP@HLYjPPJ%%5Cr^dzB?QD!1)51u6P+>ETHnBo)gOkB00c-_M(!$f_hhgAPn@Ri|e3n5KN$SxuDA;z{4 zI;Y4?e8;7b^RWdaVnr1dMlnq-Ehkwc*txSmWL$T(n!K3l;3YM3I8w9={}{;lvYb`4 zNLR;MBs)nCW(0p>Oi^fX+)yda=6qe^uHJy#+>iJ(aml8!8^e<+#WUQj zd8yBI%51kcoC~*Ni=}e1;_#eXPG8ztn@nTo{GBdPtjP5UU;1K8iqq;;Rkp!up6zaa z)Lc_rwq^cb$>kO4lm&1lgpiDFf!52kG|VV6^!TZcaSgy%Y+}Yt)CBRH&@#llA<)9n zFF)7cgOo1Mor~y9q`bqx;Y}Xuf%=SI&)YlKJm z%;!1p?UR_2LUbh|cS)5(J_&+hHW*itfr0-1-w8Etpop#sdt!RR;taV+Hxt@#rhMSN zf!pxUC?ozr35dZVo3soPmaqUh=-|@h(FP59yNvhip^5!a%|s$5?QvC@ZRbh|2k6!~ zpqlWrrTGQ&{#Ha$XS_Wp$0wz5CPAJ|jLG9iG5|lL2K@>~#4II#rF4hz=40+XnvQeot1{f zFP-1ucITR4?N3`j`%&vxeDVHWDVDubA3>%1p5ifmzYT4ncER#pbL=iT$QrM=&6@Vhlf*j)()(IBxUy3msL|p(-Gp5u~+wFwv=SV8h?L(BH2Jt4fyiq_hPcHS=PU{RZNjgDRQ1k! zVbop13?}BqwU7HDPjv`lbl+#^_kCIb6}$!$t2VAa3L-Kwdun9tAo4H_=uGIF?hC^d zCBeh<;|=vkRM1lgz;cDCI*cqX@Di0FVmihbgB5pGR8%Zsuzo<%((MvF5Lk^9o0`^n|5<|->J}>ADqy69&=vt~!m=u>l z@!}*3sUTtc4QT&Axn&JOIjh#{LoQ99Fp)mh!9rPsNP&wKEUec( zbA=&QV%L?Uxon2=do{~0RE$${`>HIYINC{b%zc!ao-AfLG?v5mh)mt@=l|N={Ypmr zr$4<14Fh%CSHw{9v+j)UsaLJZqy%Vp#56 z{5nFcKP-41ImYAl?W-jW3v{vT1H@k&C%aEgFji{N&h@2()d z+4R|$$D@1NK919$^a$L))0FPnxOhzUq!75vj~jf%elj5kf|SaA2nIetH6ayeZvTPd z@1p-!;DF7#&gcnpAgIhP>wug=FOjBbbCtSnphf zTvzEx-6Hh4G3w+I)Z}D>mB55%v2;KSJm~JSMNac1A}cBM*-Yx)e9lmE9#I@byNJ`F z-(^FB&|Z6Zj1G+@a0DA*382vN3Q`SIpi4GHP6%Cbo*kyc1*s-5Xz}0naT+%XV(64^ zP_Nc@29`0~!?uTMPoM!Y{idJG$>9`BYN=Yq)qy=eF0H{|@@fw)-dZ))A63>(owb(l zbG}oFhepw;`iaa&DrFE8OoGK(8$R1aMgLylZwfI6`;*Vb;yvWzdzPffefGXv)wR1B zeRwY0WN>h=(#m6siha}+p*7dQT-)@F!Fw$7c;_2Fo%hCOjkRXXTfbShme%mLb^0#u z{hYTlv5Q-Frm`RDHQ#S&?m)0u})07cm~O@ zNEAkiyeVMS7%l;6-o4!1-KnMYEqxybA)yF0`fwDE>Suu>%AhTnjm{rgIk|gI1RlHZ zeNzM9WYw*EtZU@eD}zd>JYO)U`2f5DwIu_1G~afXc@Qn0$X;)ekl=7hQqS6NJF0_M zmA`b=tkT=HuJ z(k$5b*5?f0rcFE)z5b4}k2X`{@giBp(X#WElxFg~_wXu)?@*YKE}-0ZlPhVr@ek!x zB%mV@#U*5CtFBzR(n2Kkgq&PG`~+6Y^-8jq$-;@{G&Ff)S*qO0!}KiMwrn|a=VG>( zpp`=jM*~{F*u?D5Vc>Fo`@&BlugwRffzj;YewnT28S`RCbPqeuq;q08`4r9GeU8p7 zrBylahfJQ2&G^9%7=g3Py#LZ&N=k5Q8h4|9^g&QtMP-+JX#~tqb~)4(zh%y-qc?bm z98_}~(fG81nK=OknyYR3b|N<4LZEytpjS@U)7K}|ew)JOf;Ef7_wU_dCtIBNvVGjj zCJ|n^(P)R9L(&sNjt$8-h0>d)N<|WnrwTi>Q<8{V`1g93+r3v_$Yvep66Te42y6P< zA^1LC@co_v*R|mnto{5$_+=;CJ}>+jS^oH_&I5s&4I;%!=wrMhMHQ?Q|AS{&_m{(k%>AnF)>$R9^Y10UVVS4$P~Qr6Q@o+;tV}( zcNX0S=PfK=Mw@1Z?B(S}$@1k~yCEa8q9!Q}D_1HyI?itlJ+OcOS*+`(4=?ltfs9tO z96Yt_bO<^Zf(T#E2C)v`M4fr2yw>Dfx0X4g4e4!7O<_Mja)|a=aMnM+ULbR+I!u1E z7VXU)N>-AW_cAmx+Q`n%GvH2kjOh~$?(a89x{%f@)7O$=H0ic83zT2tbV$qu0n06J zQ6Z6dJ%)D!$IOiHi?>bX_T3N|`((1F{vBySVfnA4PV$1FxUGBHwpO*>Wma{!LsxCI zij{P4JepWyY1I&}ZE#AOh0J@7LY9`^uRMSE@QqV7ix(mV*sSFpOva9kKT3F3aK$gh2~v@J%U-`WD7(M$zK;(XI{5-d&D>M#lI@87@M18qEd@E{!X_Ts|BkD%UyC+t(t+`WJQ`-z$B!=DCF zgLqK-Md8#bPmE-7N+cgF3l<0DcRYFK3+Sxnu+fS95OjhF)AJ6 zwANogD54(wkb9E{)P0-7ho&L@k%$7w9xkpEkkx2_Cr)=>bRw<_D0|L;z7Y@cR3j*B z*ds!k76K|u*1_mB@-Vp3h&-su}>pgVe{tAgCEnLiO-KK8MozMpje#r_ykgmGHPy(xK^xD zM;(OROK#-GOmtwfi$TFwEyp4TS#Lp|Vp5V?25hCAFK1#?0(N5%d?yuq`&|9nr%4#> znq44cWtFaFKd^)NY7pSn@~#i>P|-JhV@E+6RVP~qSWKRXT2O!6Iyr2)blAi1sd_Gc z)}snk*3?Xji`yM4V*S=Q28*Vn9THuMsKj&a*;APz&&o_j%ZbfuW&zn2=)VmO?&?kSQS^cG2lEh4Q0KDvi zK?tzHKy1xL2F&lq7kV+A1(d;h%7^!rVuQK@T3SNwTKJYbKcScM-+D_FM4 zt~kSWmgV=W9dGN1y{$X)>eVaXXgCF1;dS8yH*B1pZHlP=yy?AbJ{z96q^zK$!@*Fx zd^v_Q9@qR!RcKNjt zc2=_}3pxFaAWtDmd87M6V0Jn&F|i4sh8)qA`<|ZHevU=iJv1HL+Se;tSbh6OuuoCX zXFj^7#>U-Sw;rXS_^RLbIF7$A`E?rpJSTPFaNkfcFo*-)0ia-TSfP&Y&lh30-9t)M%u<4|HO3#t;@zLI73?kX z`RwZ#=t}wW*_QqNGCZ2v_TMa&zwcVQO8-759X>`C;Bx^62VB%==m?Lq8EL};{eE56 zfD>V_3YzUVu3Z}eyN7njll1PT!;jHwz$GN4LbwvOBxXUwM_gQ7`5X9|l@t{TTMrc} z4ZZG`B320}jiQ;Rlnv|GM`2cJOl+(nP*Ad6DW3o)bCy+90Fj>p(wdp-@+n~APlo(^ z0VeH6VX!ygbG(#0JqF4+?JDKdsCZ!6J^>JKh{l-{va%1#bnBr)*L$%2!RM!k%q2mO z#u>-DXh8NS31(HOOPRFj!(1w%sQs8_;*ATenQ>Jk+id_PrSu`~_=XyWk*SmAj~t0AKq3i-}VLIVY1`w&pn3^Yk>Zn2n#t>_U21GOs@fwu=Xg7jHAKX5WRhB*=7-F zr0f*A6Ed6p>601|q&!;x3i@wISp}o%z5xkRwyH$eJ#Fag@ z^L+7-wSBc=WXQ8Y*=B%w)ru7g`ued*;dPb0sXKQ%RAh%740-@3+aa?f5F0a@JQB#G z`RMWEH)0*7&^fn;Ongp{^0xMcUa(eFq^0i=T9Jf*9~cDnc+WY?f zv$#wuvwQ|yvQjY9DH%TKq;H$!q~>s2fjXW99;=zZAZ3wvrIsBS>GGvZ+1}_NItSzg zMLF_U{?h!V^TLX=`6ycrh^66`8;!D>+Kij$CVU6om;5UL1(P*GFNNyg>W)Cq-!TFAjXMy7Sg zy^z@#ce*q4^EKc`t_L&F(w?=l5}1}ri!A437+hr;UdYF2NM{*Q$R}h-N1Tn()o>N$ za0qU)iCD?z*^K7fw|GpRX``o+e>Y&o1uu=Y?;DMJGx2UTW0GIr zTVKG+7F0qgZ6|3JsG$a+h=r$o{(LNkXzk$Sd|*jBk``4s>fFfKE9G^Or;(A^EJ+*6gK0XDc^Gv$%9}3!IXU`eXVr+0dNO9?weWx`+j8Fa!*BL6|tcBS@CKZ+p zQ?Wn^aW7wgt*flYrn(6(e5&pu1aqURP8MAi4_;XP^+1Q0~yz5xU+f+U;^IW4}`GW)h*Q`q_3YHfgXL^WF$4bC?*^&WA& zNdM;t^h*EoL!`o+)Z83v*R6|W7qd4&JeADYIe4uO zV_z^{wEJK?D1Ah%+e$_6E>+>p*2O-06cIuF>_|}xs3v4IJV?P{CZ|+pE%uXB!dU6u zTRwoD(3EMcE{BA*Z)a!c=O3EDZZJy^O*yQ4-)&yLEZg}VEpSQ0z@w#$xdrO=I93B_ zM^4tmob#>NFMxC*hj)CuXswfWBu>LWXXEdW*|)+`*2$?5J(_VqvM9`*JR>&o2%(w3 zpI_H-UEK;Sy$ncX%_9;3)8y9Ms;V7wii(O5?o>K=?h%nbL6p2#L_`g>s2~yR1SnZX zVZ2RcReje900E%#GGlI-Qn;pM^B==p%;_+?B-l-AXa#7Wl$#k}f6o=r-Yl;rk@R`nHc{r75C5NV}yfOOMz!=|_J z5iw{|wqe5brI<-q=_pL>ap8BIu_9Yysl!bfAl1bb5fLE`^X7@)on0*&dRhGCU?N&5R7KG$L)rWa{wpQI$rfm}HeMAmXhlItRNxnuK^jf1t>`wPG0Cvpdz ztYO@+p&!v}z(uC&4G;6)ypa`VrN8a&F4RAT?gBNSS_Jf_oo|Q@YtSv7d=lx#O29*x z#GfcaEW@){Z%ZazNnI_J)vTQ5xjz>c#^#}|)I zesEnwGHb#b)_{ilZZhxoLI>5PW{ztNgxIZos0b?fc7{y}{$H=>!4@j3t0!V~6qZgL z(k-9hUt4nM*+imY52_3^-kM|?fet)_l0x#KUi8VFCsqnNXf9>7AT86MIDdus1$DB2 zH%|lsw$%gyx2(K8Av*dPut5`1qH2W%4B;T@*$>A--oX&xD`MH}$r+!JaKep-;XFdl zpCj!l@F@tLC9zm@BFDb97ipu6-hh4>E~L|l*TC44H@`=0HE8YcBdzP4*S~tOtLFTUL z4v&JP9zx^3L7g4C6=Fw6&03viAzph|p(WGU|LN1VDMljP3%{@go^Ua3m|-MF0C356%J9vR8|bfNT^=qkTGKZgE7S<42|WOo4mVJt zQb{k6fvF^pD=-xo!aK0I33Uo2wyh@^i7>g?=+6mSO+>Auo8i{TXh};zdS}n>{z0c( zsCw=>a6k!Y9At|JK+ zr&;4BGT8_sU?=3|l>u(99So+VWM0@_t)Di4W}P%5fzsW5X`gnX2GF-Ma6mAhJ@I{H zbaWH<2pp-=C~_yu4JRue6{8cl;89b|?If#lZ!-RndK9b?FZN#$q5asBmnFF@zNSTh zTx2uYxaUIB`RWkiw4)X6s0Jgxk!RgVe5>~H-|rpKTh2{#(N2tyS3G|FHqw~O?|FF@ zd^N%uLB?aB9G13vj=^*;c+$+r0b literal 0 HcmV?d00001 diff --git a/control/smart_mpc_trajectory_follower/images/test_route.png b/control/smart_mpc_trajectory_follower/images/test_route.png new file mode 100644 index 0000000000000000000000000000000000000000..1387776e1a0466152ce8b3e8e09e5a46c0d867c1 GIT binary patch literal 676745 zcmXtgcRben`@c#`Nf}v*$R>LwtFl){S;@*yWF%W9D$$EwOj}F&$RUP9L_|bKR8LHy%;&?*#vrgv8~bk}pXald2XYE5M8Y!MBh@at-E;J2_LAuBuWTYl(y`xMo_$}KwJScOLs{}T zz20x11QA==T{fb<#OJG-zi+PAQrJ~=EDeY-s7ii3J28+y6|h|}*7L2WXVx%J--Mrb zl0){6RLb(&+UE{U4l3EyOFMZxRsY-;0&Z`<>o`KPuhv{}_F7yj`@e{P&xd!@kNRBO zeJAwRIFC5+yaopqkxemuY>R@fF6Eus{#r-zuED{8j&oeQd6m7{GU_tViAVzX1lHcw z%Ff8np3vKT#nklV360Z0rB{a!eT35e+EelI@s5s;Z$Ercv#?<4w4;t{y6EL~wy&>G zLqmh8K4Q?+PgS(EwOr41ZhCt3YnHmpnn;p{sJOVWxVVzNJ@?hCR~1+(jE#*YeOCDf zx5g#t85u{vq?~K}^2Jg-x%02P^v?Q-NsWKX%aShd|s-CYV; zUoEX^57=D`==%OWv}t7MJRi-2d4!D$?Fv|KSPEIzQQjfBzlBhw1M(!77Aw{T=<&nPF0PYfr^5@{ixXQD_>Gg@=cKpYaF| z2^m=pTik8kd@k$9kkj2tSUk=+XP@@eTJzuE3$Ir$G@e*%D_`I3%uwFg=m^l#(~FHe zmp(_-6nS!FEWvEN&oG#NjLZRGvY(y3B776E2Up%XWxsm{&a8O z0ne$tQqSd1WiR~uRepY>W#O&uf46&jd+qJ)UVQlQw7mSRxVZSipbONrv?FVqWBqI~ ziazbfKk8kQ3F@61Bb+bc)#BD-g^rDPtM+SsIVaD$J_x53Xtmu_X2SpU=~JRtxw)g* zk$3Oke;pj`c&(Rhc=hT?Nv~-}adB)~8Vi0zFu8qeIa_Y*u-W?F8#iwBf4F_P;@6if z^@LZiUq>(Lnwow&EKvDTz<=Rz`JH-S32|}P&DERS0n;Amii?Zg-QDN2<+j5_Y`;8? zi+eCQ$9e4Ff4_c3^f^9Rd|z4lOq;8|v9XbJc;9Wac+Ch^M)Ct#%(cCiC(B`84G`DtLIBE1w!^H5l?qv1KsP#zi5#E3acPaXlC*#*Hi`NVa z6r3Oq|3cca1Oc-~r_$oGG8L2yREh77;&^v#3L9mZdFju-@82KK6&oQdA_|)6=7(u6~-EI}9KC{rmUL9UW20$_q}dvJ4SQ8z+nV zG*nedQ8sz@jCod=@N;l*%x`WJURFx#A+BF*Jg@Zb*3#C_T8-^swI4M#_2XyH9(7EN z)E;0S#km=|VYbPTrX89r;k+2(>>C&sM*6j@tMKOxKJWO%#70-@PW|;L86{24BXXO4 z9nJ0S>|$c^NlEm&dV091F={q;cA<-lt^-~ZCm%k17^;*J7a#AkGI<5n?)#4)pUees z4cC)anhM}na?*tBT)EQF5Kg<`UG*q3GA1c0tlJ^${d=11u9o3pR`KMBqq6HnIo)bp z)Wd(XQwcBq^eMy6e2AR(<;(RmKTEj<1hOkClKnPUhg{1gZ~Z3Pw{Kr=em-S{QcHV# zR#jEX!-t1n%QrAwDezfgFqqYG(ahBwlhWDII@_yO=j`kIY-`IG+bQX_$R<#=OxfMt zjq1&BR!ug|;Qs5^ul|7DZ4E6g;j?F3e*Zp&?a9r{>+I=KQd2v`dFi>;&6`JvlG}r^ zcVG^*NlE?XZXu10O1R_LgxrFHrEhwdhL$!|G&T4C zZsAPLEGUR-ZB=`ubo%GdpICra85{BBh0Sf$&hhc_QB<=l<(C@Px=+dHbT>w1eW$YQ z$4d#)k>R0+mo_|cg9I5OJf)e+$+NSw$DC8NI3=719wqOy(0*`%MPFYZ%TIRXNJD#G z*{r+N$be!qacW0XYwN@508xhcZ96BYmv{m+1`-mIdG9J+|MhMENM<=L6y5{mjOI>G zktHQ!$3Ei&#Ky$1p05<-prxhdK657P)vM6zYFXTajEoGT#ks63_V=Zw zMy96Y|D|2b&CPuqueDYs2=DEZ+-UD9b6 zcSE;Xr-a{CD#i6?a{IU>{mXCHCI`c&lrk2cmpoRP2zz1|@Kl2Xk2$(KH93hIcQL0s z=E;-Bgz9DXf18_Lf6_we=;(f59sEb*=H_Nn?Mt80sbXr%gv-Tv&g0R}j{mZE)wk~3 zw{KfnS^bB%NB?+m;o`-80@drRxVO|aH0ixlMyQ=hw$Cj*Jf2){iWCwP3u>`qJ$EiS zFYk=I)Jf$?#vxoEMwH;fLZSR?6^*^st73-^9V+wN6emLGe^*kXI{&KYcq>QGQ=)!L zlLje@n=URwTFg8F1)X+Q0g63-N?IW*awv%I|g zqIZh^#0hoJ4!i+Qg-1oo%F6B6gTI_g>nSbIh>3}H{`z$$Ag7VW(vecEX7G|IgJv1W zxpU`Q+S=mg1fG7UO^=U@GZ$r`XJ(G7PPB36a2DAWOS;>7 zvR7s9gjMgVZr&^yza?pS?OOcx-2S@M_oiqVp$(RFC?#v_>ypNKG~dNM8cdJP;b4*m zU0^#w7R=1$%t4|kBX2n$cS`5=vu~&LxLzxmoA~Ave`r0DVKv^sdf7=dOX#;p#hi}s zh0a&C+5gsB_w2BF+z_a{a96qZzekTAsl1(C+W7PLZ!KzPWu*pcXG24SVP22q+kt@r zEjG&NZN1g=_HRQw8c1jxAJ|zAvF%-QIF?4uc!A<@odT)CJL5BGPIyXO-sa}!$L2O( zUP*SMt)D*a-M@eT^z`&^cPVUUot1DQkeszOd!gZ@fB(GE`q3knc2q}>RFF;7*At&O zabk3I6sum?=UBNpTR{L!@~1v_1njuEy1KsYbHwe@F)|8kw;{Y#b@dm#!Nix8k>$T# zmH#Glwi?W~_783jtV#NBNiswbFbm4Nauib*iqh(;2L~tTS6$`Physmk|;iB}ZrH;*t_YG$p`7V`DW@hOyF` z?K2(HOJsAEOXMNsCs|Q;QTL)_Vm<+VOifJzpdJfvAR@Gkxit}#AvZS>JZtQI>Qgk~ zo!#B+5&T)!0uM3_nbqzk*+sqCpXllwdRE83cgDkQYu&}h);3Hj1FNB}r*{$eePbfE zY0Q;^JOn_n)=GHcci_>*(b!9iBh0&WDO$=#MoHA)86tv*hb{9>t6Km4lfn*SXWy2W zwUV_1z+?0C z)1NbxqlR6}6O)oGe0@!LtXV>cZ#g+QuriVl?t4|gj$> z1Kbx+K9cac0XPjsllu7aLcDo4_`=h9+rgr7qw@ZkBaKw^^)SbsYyng*U;NRD; zUkT+tU~7bVWSpk#z@t~S59bwbIy;YeRGjr*enoulei#!S-D5v49-a#so%03(D+UBa znAmR9^6kSfC%{FKzRmCfzZ z@o`~ENiO>3CMF-U;=V_9L%)Gg>W+~N5@C#O8#pVgD%tG zg|Ln`#YqhfiYRGHd^9-e(Md@yW1kbscXu{bwX`_SoQVK_2UI~*c&s!&Imv?)ZOBJ+ zzxKtliI}*!uD13^e2P)ohIp1;d%Nb3pFc^7_a?TF%hWl>eY$2(%^ei@qfB@2{z8}f3$%k2OF7T< z_DK24GE1dI-jXChJQN8qC%2_>%}+yusADK1Lg&t@OENy;OBkF>$k(_#I%@Uznw`Bp zq1?!yI%Skqac9mI;EVJV0|SHSOi8cjc#`dU!R|kSfB*h@P8T*AnwVtfGT(94#-qKY8+mZBtKMTmH(G zfKmOsL?oe%>4TGzz`NLT(|-0A|c8A(3Fn7yQd;+d>;h> z0##L2_zys<^+t*6TC{_dloa3fp^*M6A6j5O#JEE0MH`N)!5jW z`|aBeE9#_0j^ZbXK*In-1Vu!sIF%ois%?Ei>k_*mNJn?#M4e@!%0A61+J;>pAD=Ng zA897w0MMtRw_4d$6~FjpEOB7$MAbYz-Y?(BG6RrZFfd5C?5bwOFSY;5~Oo*)qCsgd9L^}&f1%1uUJr2a)kt<`N(aa99bo!R zIJsaFAnI6JoH{}$2M-dImev5pEOj0n2k-u~;tjwmL`PO{DTEi?08v%d)U?J$;5EoU zc96Kar6t<&jd3aW?R?!vz-C+m%Ds{<*JM0~MZgJqr?wSh{+n20x9Xx2TM?^Jf}Xu}eY%gY~W zZJ3LfKYxTKE|v4pc^&d+U)6q0eeeuX=#?XF<4w9VCeOW@sA9;&$wzT6uaaMuc7)5a z;~GCLNLq{wfM$Ai^>YxgXIh*%+r@ok@_v3Y(JBhY1(UL~Vn;0<8*Z2AWHBCQZ#Hl? z%;*fo!OHH^(bhgj+f-gz$wxb|yev9&E74p~1(&(2tINvT8Vy24OUvf^^?g&j4{q@B z^T#}Y{sl4<;E}tBhwH+yBBVL6^UTsx+6bkt{pji8IPmKdcyk5!p= z;3(3B2SEzL$z5-`JfYxjG_o81Qhfb#yF zf+lHeyyn}w3(esrL+(=8*iR!1{l&8oOi!LXiDHJIwYRq)0wK-J%zT`j{26uOfoVZD zdIPuyS_l+ElocQbP&vHz?^Jxc{&iefmW%gU9fY9->q$D1a-}8VSFI0vy-wk0s zJw5b!p|fX6<*{Jc0>~dAfLX_|ij58>u4}W`0MP&Z`D1?jHsM#xo#TAukL`g*Tl%y8 z>sQ_WJN4g5IaH?if4{9rvUksxf6e8~KINwIBs!2%O$!VdC@p6J49Y!bo^Dk=j<|m% z=hZ87dwbPjjTC9Gn1KOP(otI*o8g{&+Lp$7Pw)mUqK94xP-hsPMju)f!44~BMDNlD z`=YSn2e5O}Oi^U&6hi;}YnW3z5*~9uPforLnwy@^ijPFcz>r>87~R>aL#pE8;Q>~Z zg%kR-)OlpZ+sN41^46`#@7{@Gw?XwmXlMJ&Pa7#lC;=_AF+}KIz501;OZw)`n_ut# z7#Ohe@wqyS_fQ6+p`xN9rT<)2>D6lc+Gx5f`%+U7Md(Yi*A!=>nRM^#u_!y-xKVz4 z>It#>owoCA3%;$}mAWxu|xV z43KzWlS79OLoo(*YTjP%ck3Wvvhvk$n-?^hu$fS%DJ3}fTCsoP@+nNZpQn{Mfu>t% z$d{<`^1*LGou7w^dBTKoM_a6hKLs5IFxgj8IFC*RMj**Jw%|FsqwO6QNB6S4oIX$g zbIQ3pnM|~EX>lh$-J)Wl1U>-mdoY*tZGV`1@WE2C^(CUGM5Ux!zkZGBpTbW7 zutGu_ZftWXX|3WQ^DOD*(mD8eF(t6}6#9}&IsfE;jD^lY5_(kyYkRjL9iivS6sEZj z)F*PUE#p?ctr&l2oHrf7M#&-~5{s)#xaV40k&Krp91^ymuy2DW{i6E%f>ECRyB4)& zx^JI?{6_KH9<{gm9u=V-@h7x4$QH`ANhTAuR;=FqYD?!n<5p6_m7h~*Cp+`Om8@GM z$@@{fx#_{&*;yw@70|}wKN3XJtEEml`ueD?N{q$NpFh`9RNN2F9{1$Qz{rj`Lj+|# z=j7>An~$3h#J7{z2jWuuHJXB%(gsKPOo}lQ- z$#tx*isN8IcQL+twcKqY(xl(NCKd08JvIWGOHaR#0t?82_uKl{TQffUt72=+Y=?b! z)p@sZaI1ZAe)XqwEQ;j#IEO&Zmhj5T3RpEgiR;FqHKZnpi`jVB*RQ$1JUd%AJr667AVU3yU zpW)VeKCkQhxkrQ>o>M*4J9rlC4_nI+!7=2oEj$iP41jVA&yFg@&BgVix|%8Bvm$Q4 zgj4_Twj>c~Qjb$pJ8(~N)2wkt8+m)beG`Y-$22 zW@BfM#&3bnf+qk;*P7s`@zQr8&d^`~P*tVr?fv1=puy*ZEVjfO<|qeCdG5asW%Nz0 zsIfv!68~~M|1!CyG&(f+Fp#2wtOz6dXYHg9AEe+Fu-D}AB9tQBYoZM}!XIO*u=AxZ$N-v2rCva-^IA(>#$p+jJ+ z;2A(Ey=-8Ba&^(({`K-*bSNM!g33)3p4K~+#n=JTPe-=cCem>WA_|m#=w0acL3alI z5>V9tp4@DA_K!Vg#eQg$;)Oola|cRCfnXD_nyT;aLaW$G+z+fX6@%KYgr=t<4J|G1 z#%Oc&X&gX(0|R(5AFY0zA&Gwal;`3Im_=rE$-8$75P5;Shu@%H$3khu?E>Slv9}K! zAGdk!6Mu7eXB*vAIXH(+*ra}ky715aX7sAq5rUp}_3CNJGZ0pxjqn7R85o4rnx8s- zIxr|`KXxH=D9`cJM~XFSVRuVQ*2v|byp*guR7@6G3A$Sp!q>v+_giF{%Bel(AIQtk z*BW2pnoAQkj$1d#yLvG#YH1q{$lBVP@5~ucmrQAZ9Hs0oAqff2q$OM=ur}4m21~hP zDaTZK)yDXw(yj6oIpb>or8YVQP#W&?v2aaJIW!s^90WD>UhK{-aV=VNz2QfhXkcnk zWIHLe{!XDsAy?d&F+@yIP#%jwP=dX^pWeH-2li-hff*+q8RelF4o|>Iii5-4lEY=W_Lt}|!iheRDlCW}4Q;z)uMFV)77lan{H8w6dbpkG1XgxyMnpUfJjmbXUZ zC4c}Y36N~4H_$dAQ^vPSQiiGgW_^x-foFNm-dd9@{<()U?4#!VRE_ zRv||J#Y2KvKt%KQ_Fmtbkn4amV7*!z8scPUXYSyDqIrLCPPw30L{d`4$LAbsi}cof z9Smd8Ju8(qXaA)W)jKN%u}Mj)q73Z3yx~Jb7GSHYkiqlv@-#Fx@j0!8FW z$;ox*hZwgbdaBoA3#Zpuya5o-$ElUp+gXfj+FWt}tz?THYj~>nfwHNwaag`wm|vf* zgz%1lRcw!HuZU-NsS465K){ZTy$FzvYYMW3Yd|Pca0Li{F(6;dsBlPK?Uyg)a7reo z%yy*;s#Y1^PVK!dl|n{N{`JQXwe#oi5t~DUQ%~S;xN;Q;LZ5M+>bfYlO-U(Oba~rf zj-V4lEn{!x4miDv!W8#>FF0g`rpqbCR8vc+>ges=`Ej(7PB^c1cHTnLz) zocuF21^r9498$g_q$j9MKtwA0+yMR1zJd5ILf|EsevaZ9y;HAqa;{rg+yj#YH2H%- z0Co-%BM&d{->Iq7I7qnfXd&D@Jn1<(>i3&a?+Ngj!f$=v0;>gppqSIWh`oJ^$0L*_ zL&Fz&c}D)Em`uxMW|9s1w72&K~nVK2KKtht6tZuI_V zCkj;#&D<(7S}>H6T-hY@vFn%aa?RFNd$(AX0iM1ag&~wdLfms{Yho~t;9|46;D6XKJd+B5GEh4tmnR7c>|v6Cer;`J*_To|&Yn#gJ*^zM zWo}_{{*cB(%<$*EhGCgnEcJLGKR-X=jLSDwx$+JV=~D-$yDNw8p?F~-(Bmy|iZAh) z4y&!exD3UASBiTk8(!E5tnOVx^%LZ8yh!T4_F+f0t-4HBOpKi>k0A5ldOXP{x%_w|K=C_0MkL5EjTA|VMp-?;X==_;u{B{yYkOFcpvTG@Iw6ueEB zO=$CPSxbft&Q1KT4RkqvL7^?R&yjgzAXo0igv^h7r)+5}<7~2;cblOR^@qlP3u(2~Gt1(5-Tlt-jQ4 z`oDkw5^mMrP}IGhow;3LR3?;CNvPqM>ru0TOnju7Srx7e9D6~{KfJ4{sfo_V>16ha zzigntUm>GY5a}0xe_7miVS9DIfIX%`z1MARLkJHT7e`IF95XXnFJA_m?JOoB>QG!* zSlif0f{%gi&Nr)x?D`w0S`Oh1X&ZoJ0+|N$M!v#-gWX0yTzF zIWqbzrdF4MlL*TS^oRlm=R!CeoI4O6Iy5Z;*9JR-VuyqcpPNfeObh}XXoY}Ns_N?3 zaZ=!v6up1n2<;Kj239*Hjl|Sc;JVL;j6U7cmMD?9I7;$rLLxdrghEh{b7gi#dZDx^ zJ>2jH>^vwG|NeatQ4L*CVg$cqt=FJ|5%LdiML@%GAduSFN`bVarvN&v@>=I(X?{z@A|T z4zq|8abdBzW(+mG`PT?Zhn^mNWDj6C!^14X=0J-i4+)%|o%JDt+?WA`Tw8mduwJB+ z(JJ(ZW`ZlNZERwqqgmGUVDUo8S*y%|Chlc+|HZtgvfkhCX2l1$4^<5< zcp^bYNXD#x|A^|H0aXO*LiP5Ha}x!zWdN6qe5=8-SGvHW*q6y%s0yftY*D zTz>=B6WMP|GJ-TUu&0Ga9`5;2P#~an_oI_^TVrGJyXp9a7>1cw4xtwrn5-7HfDHFoY? zb9nwB7MC@cqLevkIM~@+CW#&1lCNSWDJrU9YnyEq7-xR%tpP-B zgv{LLf1d|F=H}-IJ_tcCv$r?JrzjotPmYK<0-$VYY#funoSo|bRE6z=x3?5(JWT9c zqsklRE8p}?Dm|kK7Fmi`2;y(^ zLv;{eO})mBqyG_P7b~j=C`_|8yZ*?3mCsdg(lIkn5YkM}HQVA)_F&hfb=uiEI1t1e zW~4)aM_k?9tlQk6C!$wtC2|*#9DpLQwYBxY0=l9iUHgCkX*25aOOvzKTim*(Z8OOm z>;6Fa$~Y@-F~lCPp&(kxJF|>%p1?kf3JcEzVnRG8-n+-f#)j~zT_X7t!l41tGr9cv zkEN)%_$(+bM83nc{PXoxm*$fPw+Pl~(((^ zAi(kQ4Fp@D7MFRs`@FqeQ&KhtIjwU^8AM6<$8xEX}XU`Y`|4>I0OsU7{NLf{L zx(U%Z@S0~|AR7^Eu)a)D)42L4-sImB8|T(IzvZRABVQHHtgqx$o26olF;s>O@>S2V zxDT1LvR_X0_wCWfQ&TyiHsRu17ACSCeGqA8WMqK@4S$XMM*JypSU?G%*&`<58}Su?XLoTI zhEX2i3dpIy=R=X)%BUnHJ1N688sob2jmVf@wa{Sruj%tk3z4nWq5XwGeNg$v`c6ot zkV6}78i`IcxO~B_;+JrJ5mcVl)zx*W(P3*bh9e-p9%?BR`Br&rma5?oA6k*63rD_& zl!c2(+S9H7xGdFkNP&eb?E9>Ox#?M<)OxA#n)qZf3b%sleBz}r;v$CW9EnozXs-Pm zrfoi~r}zf^VCjKMQ-vuES1%b2ui@N2(xf@i#gOVvekx% zI@^5TED6v49WmW~Z=C0L+JVhm7b zRlAEFrzgP$tA(^i0BluN*La4Z0YfB`HA<+C~ zIKHVNC~@E7O5l<3hEILPwuQ!di*E@kFkG8!*RDM~>lO@1Mlc2t9%J+T>QDmc4F=fS z+Inbnb!McuW=9N5;5+Mj98A53{I?hUQOegqG=(-#GzQ1cty$|2_ISN0}@{{XayCwMuX(>2# z@Oi(a%5|KMlKynnxvBx7*aoBmAwkAyen8|3DrnKy;8*>GpbV-Z;vMkSoA%`6W*e!A z0z3mif=gIi({z3#{>%xAvn%5n@2SO-j`_F=;!8Jd?{w*DQHTjfX}1ERWR>swo-t)qg&; z|3z-?K|&B;UHvd{V8-j$Vb#^ulIDk+Z_$?oA!tUW`N-V9{`N|`?mqLC`}!3hzdbQY z&!iGEZD<(#5|Hgu>TdrxnEJ}ju; z6VvDWKtB59M5kVVzI3aJk;u-|O(RV$&db9uiZUMub>8zCzevxS_v~oe14`0MLSOd2 z!<{8KVubJo0{5_}hjGnp(BYrS1w4nEfg~Xz$}`@c>^pUJa2WrF5IR4ZQ_$+TKx^uG z4{`45`5=M$*wn2DP0Rt$5=^~GL4mJTq4dBK+8L4C2}Is?Yv)&DFX}XKMN(qoZ>S3& zL{A}j2KE5|l;Y4#kH>1QGJ$?P)PCJ6Vq|L<^^wf3c^%30_hT=X)m&O-# z0@kmB{=L|rMh0fd4Lw8sBTCapC)RXVP43>V;o)@Z7+@qwk zaEVb`gnQnnrJd(^$00?eME9FD*Ah>RZVjOn*)yCRaeiK2ysZ*UrXpC!=o3h=RBo^S{5bnM z3;dE&-V8{7bFL;eI+_Am<4^@w;b3V5ZLmoMt4D6TORliE_@cA301{;Am4u>Ah`gp< z41q5S9_BjRe-?y9cL@<=J!}oUF#Tz$r>RCXr zK^y5?GatYZPfD#%t}kyDtlUQ;{2P`>|D zEGPLnN}o&MyyZkH&bMLo;N(IfO=9MJc$SS>)_47Y{Dot$p4r_#PQ#v&^PWK#j~sNN zsE(Cf-}lnDh~v2j>YMC&YBLVr)UM7T8VMV2X>j`{uitlIY+|xHlo))T5<(<)LwLOG z!w)T^q=@_XDW_K*?$;8bp&^F?^38WN5TiniQDq4o6R`(~L5B!_7Nm8~F0^Wbmk45 zChbb9ZT2L@_ICW~U?TE%o^1Ce>UipCy)moPT^dVuwq@2{cMZ2G^xcitAB{awW30Gu zZKLreWbp+tdPHqy;`Kry&^JQYs}G}!`9t)Jh?(w}E;1O^bUA!eE^Avpmw zVR@l7k8KX_$_{SN-XSE&7|E9^2Dc-j?jX%xk4PHsXc4&|=ZNAWwePjmE&-k5 zx}V>*{52|0Eds*c$4&fz^3lOMMS2l#>R97K&P8oa4UNaq(Y1?o{gw2+NQlXTgZG6J=ez^5wbA=fUk?g9{nV+Xv;Dc%MCaq69J&@UJWN)tfgl zO5G?#m!ubnfo36;5QJccJbiWO1;8={zKl(6k@BfB#qJ{=2w^Y{>TBLI=X1~dIFe3- z)daFcyn;MM#V@T>$3Bj^HgMlXSRJOT^$K(JGFzjuOz@|3oOcO)>bUQPG;PK}vSz`j z+IFR`?S!cx=!&1ZF3Gi{Xp}nriXnMoZqSgXg7!@4E%0_Bl>y-5Ui~E(OVU_;d#L1I zGB5}t2fV~SA1yhnnC!ro(SZ&Gu6!W@3{$K|^YlHTPfDlX$655RfI=%hO!{!R0B0A+*5 z;l~Bt4la_6aH72ouOXZWqX7dnm^~q^If@kUx(gyfUbj>&EYkWjY9RO6J310tA+q8| z%sVM}28M=0n8y+P8AWmsLul$fwD2O4FAALVoj6Cx7bPdF!zIDurNgRwuFI!&?QT#0B$BZ$E$2#h{_)tqD=>>I2^m9J>f3{Dz2T^1eN(bngs zv=9VWhmwcRINQRxCzJ0xZ|0rbw^yFqzFzrm8oYwo@W`8cGu^23!>w&R$qYv~ePxZv zg&87-Z%LwUExNn8e0tYWdX-*-$U}(PyUKKYlAeqN=ov;$1q&}ESh0eqc?Bf zjIxMAJwU0$1P9qUf(Hw~8Xhd5J*vs$08C~Ojv61IwviFHdfznDXtcVM6BDv<3K>F^ zQ){s)H`y4;qn|wSxD*=Zs*6Y)++X}3^&XYChd|j~qYv$&j!?3`*@Ga|Ml$Z)?~(6k z;WxpQz$ir8+qaLApuxK!XR}DnW6dmaXpO@2&xuiH?@$%%!)7jY_8LdDzX*?x3Kx8~ z;(N*dG%5VXfbzFv0R5kGEhT+%2^-qP zBZ_75Mzx_W=Y^BsCEfPisxYtOEBYAdB?S8Sxl(!^bnnN@CZDkmJjFQ`t#I=X_Ey{2N`UoL|weJA= zu`mVLm8akhK)YGoTIyIr)@-psz&{##G@)Q2<$)OrM8*gz@TGu%dPWNu5a>)>CCmX9 z_|4p?T>h$#Tu*bAn6U8ucAM)Mg?#jgEZ?O36A}{Y>gxDaL|g03FdczOt*!I3Nae9o zU60$;%zO6jwn_X$`EnXX$|zS&p0%oDI~WyRt5>MlnJ}lb?mjZablm4k{Shs^J2It^ zckp_m;^JxvB}AoW8?6R7bP(aZzJEi3!ED$m7@X;)r3qjYh$ww8b!JZBzZT#&zEumoIHe34pn{p^0-e4IYCp^#SX!FB^GBPqqFj$BuW2Bb-*g>Q%TETJI z@4dv~fBjmuF&4vt=;cW%DVVRjB3uA{54qg3eTKv?ti$106#&D2gE!NoB*ex{sv%4^uwD@RZ zP1zw!paDar`QY9e{`QmYbFW}f9E?xC{W;TL>801>Ni%iL{*gn8G1S}$&h{73qtW;SjSjpG#gdWW1Zb`j}T;h$qU}z>*Pu5?T#kA+Lki zIYx4*f}`g>P)ru9k&%N~`L`?EdV3dYxvIvYB&c;Tt4Wnj1pP? zx*@l@lNWu`eaf}D`kD*;p)!so#+_3usOhR) zsb}3tvbzX#kg$v=q4207z=I|XM+j<-&fa?;XKUqghM^=-9SX`U65!<}SR`m{@PRPW zU2z~c$LM~QeEF>o_PtA~^~T|0lr`rtg#?dD_?+2g|F_0>L|(0USGAdF!QZ3|d(rh5 z)^!|TA!K=+f2h`8e-x&lxwHIV769o~Y&%o|&=HKY$K7^rV21Ar%m7=1kY>{7!1VU$ z*zp*+P{YIdH~gKxw2#}6{dbIfPCu24n;RgZ;p8Z*gS~Qwj**$ZVLC*6nEM-d!1}iC zz)(ljb4MxeD78`7CqENiT~>9Y63}y)g!A)nrN4+Fo8J;=qC_rxcvW0Bp<1JJRhZ+( z+1~rV!`VfqpW0OH3ad&CX0b{tuYa+g6p1x@%G8t_l*cY`Vo1>bwLNuWdv3u2!DJ1* zrTd8-t2xJ*>0}Opw|C=@(Z`l@x!uk*S+Ki}`i&j{8)2%!2k_ zw!(5nvDmf20Os#kn$_OxJxbF42e^qLho{NOUSR%E=m{k)=NHVZ_wSKv32|@w(%z2P zE{J?uR#p(=3r*j;yQ2{mw6@L?eTq5&55@*F@JJLvm4{!886kpvLDl)-F6|4g>4fz3 z^fK?c*3pyJi_!lC3jpv~@4oskt-nLVq6dC}d*1#u#GUez)s9bCcTQh2*@&V+Egrse`d zVDp{I%zK(m2vgsPHlnrt#ysBQEglz3CusbHz6Wy#!TP>6_`1L@nbA49?~9R41PVb% zgf@~?&(`xGGz7f()5MbMX{BQafw+r^Goc}PdKwD%0Jvbv24??}BS#3+9Rvd;B}J2s zGA%dv5yAh0Gzn3VZL_zpk2~U)br!8PZu2}9esBEe@aE?@A>;^zH$Y%;c!qX1|EKtYMIy5g zq)LuUzqKT{D^j!hYYskgjN`G*%O^cv5noB4RN-27$+Od8yzofz;>Ez+otI1oE__vs z^lJUlq0Pq{Z(zn~dwZK;#6wp9d}n}{!cf$Dy69;Z6YMv{c&;OWcYxVfJ9q}}bfu|t ze-+_PhSxTeo<1cE&4P&;iNDRu(`0g;@TeFWp6IqXdpFmgwUr`gr5^1Y?!R!HE`9!K z%ar|l-eBeF3Jr_XpXL7hcrv+N$;YRH?K*VKG1W5E)hG3d45!~zF+uw+@-I!arTCXk z&b?=N^}R69#j_lr==6fEb5wcutYgLn9%ND5tFK+Gf_Yy>I8|6&A}`q3ykxr;uo#=# zT!Q^l1sLa(LACdUaSt!=M+A#O#dgqJiifs#b_Y|P*UIj!)8+m|jE9E@rlKXL1WWFKMU z+RtQJQ8u(g-8#(>AuPI_sBO1YJSY@3$jrt#5XbUnm#Sc;{)wl#4mpM&L_KDHu-Coc z8^=kmU~wh^6`-o*%-5$;MelaSBKsm3i?iOoQNOMg`z4q^_OH5Jt z^2~Rqt!@f4gq6`~pV2ZmOwN+k3-qrHzjou|tAEbF7uQutJ?XFgG#8?_7SDc|mPeiI zb=J{NEYo@8RgZFC$qxZ*!KeL}!ZTNLr@f-DW_83EnKpR}l3rK0wiz> zgfMAi;BUZ46m%j2Q#w;C;H&KzX$4An|6Uwl4+HJ=Flx9kw;FXbf=^%TuH@-2;j0j+ zG0ncURhetEw!UyZ>F=y-Ibj-k1Y+Jj*ajH&K)edt3+A5~O6Nm2VKoTE+QxayjwMnY z4iO$b6LVbA<)~03)zSKMXO>$hDCvpW-MIX77LR3OB>CrzNrguQtV0A|laiBTiFgM z06(0319s0NlFToj2C?VS#77i5zB0DZM8&l z6`=Am&vA&N5XnvbR<1xFB8>9)~E{O@zkHOPk&lKHOrnwlXL$2=hAq)KDa7 zb^t?II0?{%!xUH(H8`Z1E-`-BkMtQcfob}6Rg36Riu}DI(znI2`Lv#s{nW|j(ChBL z$3WeWzA)DFAnJhUM&kpPh4}Im1o{bSI|RPE1_r*sbu4!sI|TX3*>~gwh65Kc7)BVb zPDG*$62(y_=@$r00m26a$bpZ6rK26&;rn+mUCmB}LinoN!GAuG`7z{|iKH^lbL>YR z+7$QU%OQ$7l$DecF&x?{xk6t(@-)M@?zl&&_K!@bj&Tvj z^CTtL>t*g#{9=@H4+Uw%%qqq-kz0#IFy-%*Ke8$~@PJ0=3!=(Bx_f%mNXKB|{x4^> zl34d}o@JNSCrKeJjA-iaJCDD}Fs$l+x})c)#k$2&`3Qg-gbL9#b(*Vu-Z-WpXDxg; zSq9NGg}odQ@-!FZy4i-T@|7!B5ZO_sG3tALlvy@TOJKM$RBsiDJA9o%boi^UG|h8S zfAa}<&rnK8NcV31y?g%B&&8fR8Sni24)K!TYny@$M?9r(ES7}vbEk)$UlpCHh#AxH z#bG-Zp@flm)St#ZMC&G9cBMbd%c-p@X7)ddWbmNxo<`2%=hTL~f6AvJ^7K;w+MeGh zU2m)M@t@giE|d&~u+ZnK`E?r)lB>6w!l#xTCqio9?T^%KK6?FUYJ|v&(EF#-G`iU= za*RG-3d7_EBQoB^HKm1&{wPZ7d&WvhTKqTc-bU6KyW{@-j~+!>wzaXn6;yP;8TM@~ z?0f2Kf5sCcg13?_JJ@Eg(1u$WhB=B@a@*D$s}?Fosg7lHS;sC-(l5T37EPd~R4aXK zUvR-~{dmu0>X?oa_jtN4Q}EZfvp$iq7v5EO#LCtW*;`uPM+HjC?CI-kfzY%;_@*UH zwdS&Njn~(O9PM-{LEgclxX*KaK26#l85s4KMTp5k!uSuMi#G%01CW^@+m_#%V*;N> z4oFB)@Ki}9;tiP3@8b_`A$*;M6`gju3-7(Vk0tOGXqb?8aVcCbHqcMg&?r(PTj9tj z4ZD8ja+KZ?l2FBsdQ449iT<=^ z-YKM4W~E5dIMc()a+BgZkBEpK)Aud^nrB^j%_5$^cr~4zZV1ANx+&siiCG;=o+9VR zBmYahvz)y43W)I7OA$ zpiFmlcPk1(;tS%ts&KJpW@Z4xkZL6eh`7$$TnbQxku-I25^b%FP3bvm z(e&Et>;8MJF_+`lE=@ZR7uPdzTAfsTTpH`XY=3|~ZR65be~RlZ;tamVKzw`5nsWbX z3w8vi@$E0~iJPH?d~FHa_Wx-5?szWSzJIGCEfi_U-dkx94P?v6ijox(p+sd=6d`*>NQ8`x%#6yG zQpnB>iIPz$suXCRDF}2`kd^2=K zxkv_(khV4lR}P3GJPA#crx`i?vx-zxhvB=H=~(aGHH3@^(%b$+I4ujVELiV`4rJ42T`~Gh?a!r+6o+ zAw|=YXD>A4JPM;K`sL?yZIT@$(_Ri-3u>Z73W4zPFMuKX2I=ox_=Y>MUe~@gdq(h% z)b{TuzUh3PPuZUPr%`5V^Luf5Y5q6G6obqKtet-tqo|lX>jnEav9zzB*=1tbBt@6< z?{&H2bB;(qX`h4N-Xs_2e+v+iX0C`lwm9cB`asws&)Co`sy%-D+fq-uE_$^&*7JLx z<{k+y{kZAVH|7fiQI>-RSw`yb)nTZPjfpqwojh?={(*x#akJ63u4uB7g+-Z7JT-%*<_RVTFGWm>jRUC^*I zJ7K}`)OD*`&ViSeI}lC=1r1et+NiGIO+jg;Vj2AtAk||{U%5I#YhiS?_EI59pdwey z^fXBi!8c5RTF_X?Ht~z3b;KiWW_GOXgrE67Y@Xmd@NK3Dvx7mYlIP_+{qSbqA^#a( zZd%pLrEb}7vUy=?9|HqAd2==oJB{8d?ERthv=<`@h!`Szgs%gVdsZ-@uuouo!aEci zAK#p3QLhXoCulTLas|%MLzjLEJU+=Xu(E=(sR6=t!2Zj?d?Wn*5JZCW82Bb` zeXp(u17JqX4LF=}Sn;DAc=a>SP+5N33Jf0i`xP)T_*)5$pMjZ<#x2=VkugFDzF7ogV6nCd+nMF+hvG2d;6*X_yAC zApA^BEEu0hv{t`r#Uv!u!6HZV5r{sVZq@~db0lqm8NilDm{%Mw|FcE&@$mQ}5Ct9$ z+&&zL1`CTQ#T%h=B`HGBZ`Teg8-K~kJD(USAd>pn*2c9}5P@sVcX}#r9t8Fa#GOsn zjeR`0+rAF;7^L_3WNqy1M!+X=?AZdBzQ1wyGek3hR>zqxY!$@GcTB+=5{+1B%z9ZA zm_~XX*82Xsnwy_!qBwZ)AoLT}6IWsM9^N=4KpEn!L9WC;v51~71#8nKnFQX8+H89w zrkSkTA~%&aWKs=3U-zKF1;-oi6EccJ`-Y(&FFW7%jmSf48XJ4o9I%8ipF@BJL6!1w zah;?Z0bl}XmDmzslq7a6LT4a#0&!`QZIJ&|<6 z(GI{#xi4*=?|zG^zLJs>4)v&qmgctt{?ZLUf_{-GW4YTkBSjQ@3+-6&fXOsfut)9L zz0ue8mgDebS(vK_jQiAF^z>vaG~R2lXG;iO8M2yM z-(JUUfuJRP96Q=V0s_yDj)@4~nz(voc5cq<&_MwKI+(n1!NCI}nu~=IE45J)2NxGL zw3&QuP>#HmMf?OCUZh1$?}k>s6RBPm1(+EFKZ3Y;dGy!5mVLM zG33efieJtG6e3k-jc%FQYlW^6s18Yf$kOu0u~V%2YO=rOgMR3Je+t70pj0d-r4#{8 zrWBX{iOR_?ul*Y55fpxN_^*0upw^+rbGOtxX2sphEbpB2Dnq;Z@(q&- z`YvN-N+LKVT3IlZDp7w35_wta7Hr~_SW|I^s%K_qrsU?MgalEh2*tO3|FKL+QSBs4 zX#V0xqHB!bioqz%gDJ}e$dBbVjE+{7J|S-YOy&GFOhHPwV=Mx6ss*HvNOaUVwjd3U z{!2huzn0Lx7na@YxI(Z*etC8MFdPl?e?JBP7q1GK%Ud-ytjHRJ;nbH`(fC4JkyGaE zoGl0!$yvgB#=rcMmMC4`w?WrsxCq2rwk(HYgc*XeXzqqvQTFRj{%S0j?z5 z?ZCf^fsyL1@+r8rampe`K?TW11kW5;{V}lkRQ@klzt@@vu_D43d$la%#fys|+YHXR z`@-ylygK4ELGl3jRjktpE{UqFy1DQZ@p4!spkjJfQSlfWZKFG7*d$?XCi)%3v@E@< z`X_^@m-zGWgyXT?4Oa+!L+Xx>FWUK$vj>qkNiI!CJlDAV+F``d!BJ*p1D*<_cVmE9 zCI7WPbJMD;6JhNO^ie!Xf-6QsYmH-}zO#b!LA4rO60Wea6lK^F*BtJ*Tf~pl?7d@OqEo;Lf<6 z&!fM0yGrpLafX!UwqrKK({~n+YH(AZ*tF-`_3Q6e6w38Yo(}8_Kjm+3bHk(g-?{BE z-Bn&y!fa0wVzYD$$TM-KgRr>eh=m;Y^Q_c?T|qDXO^u9(fW+i`#~e!e{`&@4&=cgl zVrF1)id6M|Z_Nb-8Ps2U|4}AE;gzFx!z1hEtG0>2f*dCAGbY8~sGXD% zr++Odo2i&rhv7_BAo<&Qr~>m8IlbREHwQ{pgO?=FEI?c}dV^15{@SUSt?+QR$gh=O z)pmaMg|TGv_l?7q>r{XfHDdE38XaGjb0KqFdH5!t=ww(jRxNH$_MhR}KRFx{>GoQ~ zUUgQ_FcSc{DwPdi-Rkwini($7ecPgGCtY7z&7WQB$HOMD!1&1*fB+y+n9dYUPoMsU zP$I!E)VSxY{uJtG)*^aKO6u+>o0^HMs(*~Tp7<+NKc@J_LV00y&RpU=M0mhm@OLH| zyXw5*H08ibu>74iG;APfk(+G(39I3;MB3cQa3?;;X@#V?^jgoJ1GMj+DKrLC%-#9S zOegR*Q7<=AG}`WzM-FZ2)K}H;F320MwYGJQ%#gShI7$6BZjQE{pF(w_d`|ys9hmPp7KKa+h(K&m0 z|5DIRBfX2c_QDUoRM#4M(Y_Lu7>jtK_hye0Cj)3jcq7iQ{q2mG^LT_%;kv!^5jU=k zCMQ|0z=(z;v~}{x&P@RH0peNV4Fr(Mv}wInx6_-KgulA}a(`AR6bh^r3Yp} zJcF>UeeCU313QF$5JpWzZ~Nh+aZV}jzd?_<68KO-8ZRTNLIQ^t@`j9zSYbRRnay)c zfP)urE31aLXK9m|QYf#<0SWIfPXAY&+T zbv_NB)cx!I?j+nBdmZ@Yy4Bd#8?d*)P)v230-2Q1m*d~N9U}{d>tz0C%nSI*_1UqU zM@k?xr2NtL)nIrAv!8nsvmGL;%-q~|Li>VQ9slV0?k2o`KF0jSm#Ksfxo?e?=T5!R{iQ2hIOW2;jVIqnQ5{?j@kwPMv~( zPbq9la35nWd-aOvsmE9|D-JtL?Fw926H?Px4#7njcALdg{m>q37|fO0`W%Y0PKJED zAj)n3HrNZu2}mJ#Z#_22;-Vrrc~f$7e$vS(e9{yA%=FtV!s0~3`s=NcLR@d4_;mWc zGl7{$`}@Q?Hno>Gwhsu@1%|xyZ~4c0&opqeQ_>~a2$AnqSUt2z-1hkNz*jh}t$M&- zf;C=}L8s&f!U8ZmEcx8B;7iJ!%1z7b@oz5gTCT0x##%^~6>$11?ApZIx&Mrzp)!({ zAYpE$Q__2==lU|N!fn^b9n4l*H|1t_MGD`Wo#*Y_>MD4In=zR2+ACES@5l3FLb^Ue z|EC3L8aOm#WL1eTXm-{-V5F~a6Kr2^SNLMmW!`tHJG{NIH!;WVpT>eI4c-*dUJ zO!rYFacxr#{l^^pP@6+rrjR5yQ~chr#@uGhSzF5fmuHrlw;q!27Tv<|VUt;-#E911 zP-k}i?Q5ME8$(syHFHG$eJgK*bF%*s7$(`jIoKih^Yy!--RoY)TK{~gkyo~tdXm*h zf6w|IXSyf2H*_o>eR|(`K>YnHLAss!R^}N)gYImWhxiY>K9sw@(_`c~)XCh2EIlVf zY544W6exFE)#^(iw&2$A9=)bV5phAiKM)F{a>O4`ILHf}Xcr;0f|(bAQeYQ3f$n|x z>+R`D;dz|CN8m)bd7sc;Q^w44o*Nse!wRt%ASXcW5*MH%WCo0YUU4c)OKyEuJ;V;r zC4@+;i@|F#m~XvOag4r;79;B;iP4*gmAYuIQf{2BuFMiQ2KNXaaKd)rZNenB6FLoN zZYL269I%K2g!g8_9HS!+B-KvtH#(Xc8f4l$dp6F*3*_?JKd&{%iQt6jXui>XCmd#e zzwp`{Tz?nwV8z7-yf)Jak%H>STmJ7;c}QtVkZp$8^->e8+_PYupXz72udOT)Z50%j zQ05^(yV;+K4~d z@k!@NS_OhZ5NksctBG@pga966KL#a5^9pY3>jCB=0x57qnH? zPWrkUF0YZn7k|hedCzz-PKTfQ6s^d^lff@2_|~C#u4Qex1!NF8Qy}?w13OiM@f$o; zs6w=vsc$)ljLcaoYmW1CZnE$Wl9k~Yg9oj0X#{-B3qW!bAp>y#$h@HFo~_zpYV=!Y zsatg+Rv}EQJFTf@hh4<1#HdG)f9;N}Jj1n!q=R|>2aE&hE>sA94TRGH(!VpttoN$( z_@_ydK(+}+*9Zx~HY%@?T=5oYiRJJTm`f&6PSs6T1>JxOf?W!qXJ?bL2g!PC1QPam zZ)6Qhcj4HmM0e%+=S$%D!#qSfZry(G`hcB+L^S~}v3&*q3LH@QHX8@dYis8{ReX}4 z$h5M!?h3QZr8HVSZEfwo73LV-7o7z+7aSlUNsI|^nn?|uwFcXA;C%V1Kvv4!-Me<- z$#MFcW0P#0<|hhK6j(}}dw6%+Vpq_nO`FW5<3=>MHsuEA{?L_d;%s(D zjB$pko~Sbv@5rUAwcX4lqeNk9#dzA>Po+_OW3K3tA2TEMVKZgdrxS#;xHJoa`#>HD z11q_f17c<^zb@4C>C1`CNWvepk~F_tUvy*BLVz8J+vuUqpIVxx#$t*~k?5T^&y)}o z6LMiJIa#%+D2&#Z(@j>0d*5G4l|ROnmwLw}t%X<5=<~_mU;LtfD7-Mzd z8lB7Yby7yn_tFwJ`c%9zL%qEX&`CgaF4{RQz^_AXD|H)`0y}es> z2lxu7=CZ}&T6^B9M||S_TCNT6dzAMHjC`^G{l%cXK;zpjdj*?~$Yo+hgrJze6it6xa(VKdZd`^U9I__}Q57U=AJ!3-_M# z(@MS(aej+ub7f@|uhqot7~m4Le4t^0!w*!M(cudx(-GaIVFENSzM5Rk2vijeYO0>l zoVsgRf{suNk zw!#RE@p1A+l_q`xpt3q2!f5x<3^LheITx_d6>{boHz&d}0G<~@%Rito6ys~uzADhU zUUok`_9`cko2O_kZd=((!7|^BoP?ZD-&JSlF!&=H%KbrG;CsSlG&AD_)6iZ0%u$@V zWSZ{mypL-U*%5c&y#D$%g(eF0%PoW@P4yOQMIGBff`5k37NNhX|03_S;y+6{TA^Y2mZ@<+Pn_WVxR!+tC3JL1M!+=Rz-cR^C{%lE z$C>NC^W0#kfT-f~2}IsmXc_XLV2&ZKt@LzSfN`-`E9CT#yCAm%zc=_coRMd$`y2SQ`gr1;U z^HAPx-yznYUKZ6q8?me&ah-Oo3`TrBX?2uFq1z;2Km~2yUM|4*JZ$C*-8Vs_s>g;u z6r@j=8V;4P`Z$bXf9>u5vLn|HX=(YGsPMF{>tR>T0UVpe^H$&|k%E0vh)7 z!@DB+Bq{$W>VzuiBUW27RH0D;;~cwxSlFfHPuvvER)w<9dDrpm#P-|-Rb3J4pZCwx`mlJ+O-U9dZ+Z6QxJaU! zqE>9)1FHc>tL{-@-j>>9&W1d1iYWU1&E(5>Jd94iRo6UC(?Pk!s@d7aWOly6!j)?B zm~h5^+x3_Rr5??+n40N$B=y#rOAYCWX&dP<@ZIjF%i0hA*TV0@sHxiY%;XfrInZ+q0>#DMZY#mM(HDvDV_IwTTG;=F$*WDqgAClaNFI(q za_s?`S%7are?y{{;RMB~#Yjs7nQi_t|Bo~JXU+hY0X!Fyzd5|o=iO*n+{3Ocp!dVl z7vJYU9^BfO#m|!XsBVK8Iv`N8&h}qryUg zdw(1Xb?n?E`eekl{=qcPtG2#Ab&%#J_XwDP1 zCTC=SsB9s%C&3jp1)+ zX+A5}BFmN8_bfFPuO-5;EnHpokL;kU(?!CNygc#+SxNpJCQz76F$LfaCVL!783OME zbn~9lQzCu(TPr`;EJb`|dk$Uk1_BCaEu`IMXq7_lEGAQ8kHCaTZ~~AV)s0Oa>U1A# zZe+%vYP!}py(U|Fnr_iVG+Ou|h8SdgpD_92jgQZE1D~8O>tD~FvBbqi&1MVEUy#aT z<9ruSOcoFbl4b_asze+@$ojY%xs5jn?Y*qPu`Be}qM}A@^U}*ngFmq)^>;op-dt*nF}Ur-$o0Kxa(m)=6O+Jq zqtI;Ed^wf(kXL{3jJ{v{`o^*9KMwK;<^018*NT_W+c2W74C{u zRRp(eCN7R#4z4I1b+VqzG2j?y;HXtGKmDQ;mmEMw4qTK7qp;;vu9vu zlrZu^ue?=R<~?<)LwQLFkrKr=2>yJE0b-T&`IGXrCh9(frblcRdT~53TA@{KLMFkj zOZOp5w*GFualIx}pLshdPGPfGj+W9sc{2NxO=UsbeZlI1rcI7B<<7^|+UNZi0@fzM z%*@Vy{hEzf+suv>nlHokLb2wfj@r`2y(==uRm|)CPx??yCdb_Qc$c1)7?VJ;GiKdC z!I80~SB5B!fW;vH3lGGo=DaP(t_yz36b|Hm?I|4F5~LY@Pbpkg-)IMy(JMC&M<%i)_U<=L_-dk z6H7~EMRK_qKnn;}H!_E`_1A#jKf&1u4>UA|e3|CwO0L`{n=TQ)5Sb$i2ExI8BhHCb zm4Fu|eit}1PfI!iHzbEoPL3!zZ5#xI;KmL_w3;XykY5{LYbNX8Ea?xyt7fRW5gBuL zP+|a{9mc~?A3weZZA2(0;$VgV3ftl8;MP@duf_XbW`JAqxe+!2#U;Q7kUtXwi~Y46 z{OiPUg(Q^%6ob?Yue*Ev+>Hqy+X;6PN-2Qwkgd3kAc-Wg8^1eY{05Q<`qBwY`&8nD zx#CO`C@H)lNU9>2b5K29l>{V-=NketM zol!-Ar&^SeYh4MWnW@`~U185&D?jtLHBQ$uN07 za3CT@#&&03ZZ3k`&7gK_Z*MQLNw-lo;BaE!@%1TM-S%t&n5zYaF2IM~2OX}Uy}~F) zM_HLhg|jZ^ z7OGh+oPuM{rIs%p?CsSbMdJ#UJa~}BqJb&AgeJtpnDGI{+p5flAm<_7D5D)0G%ljBoD4TJjd!bM2b=*T zvoo%ISbs)+7}K0aPdqkE=W}A%ai4}ViSg|45dXQ|QzwcS_ETEOotG5*blkyh}!aKxM zcGF(`HLMNrmDw3U5_Ps@c>ttjp?uCL5#{l#QJz3=>|XVLqW}tuIw6 z_kf3o-k_DyQgQh84MoizAKo)$J)bJ!)=Kr^VK56AH{C77Xht8B-5y8pzv=aJFRN2G zm1b_t7=^iOeOW)peEaIYqE@PSm6Kq>4aK$UZeL3rxSO3qG5*Uk{@h-3GY{N0v-VOW z!8Zi-@Bfnf$!ojFW*eLnS|R!2+t=-7?N@o3qd$Jrx$=F^P`pREGs7mA+al2IaCp9Q zVbjTk&)${kd&2hb+8A3QxPuZAFXW`q>}to^Q9 zHSk=l-Z#tVHOu#34!qkhZ}@)U*IDXcsN@THgr`us`!zHua8-|D@*s^8IJQWlL&oTK z^^Xwz5`D(RRSYZGtHAB#1MyN#HNSc_0`^@9=mZXUaW0+S-a>?y2!A9qkL3r9Iq;`q zLB_y=jcf@*YA6u9??Nct$u9WINSK)bU4ObSVyYOzUZ{r@CX`>|9}8DyEz zAoB>jD#=7aQur;@osN;JD=eZWWmo-)xL0Hg^k)H>Ly+%=g}*dmWoX|j$A7(B?z1WL zpJ8-~`h3^-Xk6O_vM5RRn$q8U^qmYylz5{GH$9GfNOnW96Ia|^Kq1Z$P%T(7Zj+e? zAsocHiWA=IxG-kv6{)4u5H*4$~c5$uQxsj>(DZl6G_o2%flCof!R`rQ?Q-N-tw7xR3}} zAM*;v#pC6!pe!V3Pq00gU8FU=I($L7k9uZr)7wMlUMy}ZvHPFTXRYGu(?pZdf^C{? zDIOL7P(srqI}0{6(ijM_0udFtw_t>~vNRDmyMsH4UCNd798Dg&ppJp304snkBT&gA zUcUI-U0|0gY!7VIpi;m<04p~VUc~BO&axdZr%~P$p)i})khtwITk@_+z>{~-EgDI- z0-i(2lX8lDuQ)*0%>VZ(hEU+Dw)--;Z${3kEfs&V3DmXY_wwR=BKXMfkYCTvVRnA* z0RK>cJczPH4O-|%GPSB&SE7s!4m6K&vAk8)AbPry*Kc~8 znW>Fe#OJvhf5q*y4B?u6x1Ka=Gh1T&in>s&@JmSWnZG}WrqOUQf9%rZoZ}N+oSq}I zv-z@n*HFK^jva#E-TF{bA};~>j4*VPxKSa(`}!}E{+*`Ls{fNF1@RZ<``%@b&qVzg zbDujx9lA-9xz2CP7am6c&AcwUN9aqL^tKyF=F4&q@Eywr-GKu$O#9FJqgnZP4##Ue zJd$|K|Ngq_?Y?82&x&~)=8cpGK3Lkx`DVSeZw;GY?C9*)zwd9a6uY1iX4f1}+&-0D0Whc+3=dE|9YxbpeySv?*dFX1ec8vD2yY`bT+HX%6ix2WQ z3)GZKGcUyc@?zK4=1vv;JC>@ZZsMHIIic4h?zw(2@;=q*2xIeE5t>#H{0ACKA|L7q zt1fpB^E>=D$|26rHb9wMJv5be{Hu>}F88BG8_Nr}p?3oH#@PC6pKX*}_$4avfh{oD zF{DDa3CC#Nl!=moYC^4r^U=QK>s&tK8g7x|Lk#cyYGA$NIa zf$#foe-f-U>_Uoyq^K*L*v--orToOEJ4baV5F+#SE3l_z7ESAUQLLe)$HnENk<&~ ze=0j1Qq4WZ-S)tw8$0`vScEoRlC3r&H7-&>7R3NTv*Q3uaF>@o@L(18?7I_3N0OEgu106Bl5RiVmdIS*;U~usY zR{Cp4&BXA z5Vv-9@f&F(u?O4^$u|cyKxm_a#FZ(3iQd*$&f``%Ni9VpDOPOFmTfh}kx)_LERP(H z2$cjJ7CMyz&e;)j0t{{s>U~vi`_b@cJHgU_TvWQlj;t<9s5$b#TZfq-V{=lsG7P1UYn1(7gJnpwj8Nx zkBBHs^iexWnsCI$#mAHXn}YE*y)Z-*Rv9;|!(J(w=*|0vfFel&tz%ted z7z%-$0u#cNsLOjn@SnEHKSau4f}H(Tj6FG92hvTePeu4jVp+J7sgvmf-U1aT?9pK@ zK(+V=$gR%z9I_1(P)z1X%U0s68yWJ8s+CjwMd!PQL3kJfsr>Ai{0mj} z&nomqj2Jh+z!IN!BY{32NmFNf&e7Xyi|-5!FQ>~_Q+`0kegd&hT!mN3W$-m6z)0|k zcGjrl}@nj-t#cg<6Gkar?lh*4DRZ6w%K- z@Uw=0-tkT$6Mfbpir3?R6q|0x7#6wlvB!5sbc)Xy9XK^}N?ka#1ic}meA>7;pqc>i z1w8-;obbOrHQPotHFq`rlhE<>DXKfNh3EZTLD2rIx)nawN`4A&Et%7Xu4ggkx{bW- zkm1qXxO7j^ktfOMqKtg=rB&I&C)Q&oE>qHlZSo(ro;>%dEnLUBdO1wxjs1tDn@h~4 zOG@`-w<>?i{N?*4ak4hsS2#zsVS2|dr_l??s4jR>Oh4M1DHvCqT6-urXJe*vTiWo( zteP;1&AO+zQGJoNDVnkC;4v(o2uM_B+re;KjA~M=;G%llGmj@nEs{ISbgVJn&SV_) zizyaoe)P-I-LTQP?sVdtsXv>Jgg-P>3K3~zMlo*Iex#}e7&coQ@tj%Ay6JIlqohvk zMCI|-KkMJ!{gR^f`@){`hc~{ltp;tL?~r8^$*5x|DU%&L%87b~HNI-g(dLt=2^a*_x`%TQJ$6Um>K+&#pps%!o+* z|7iilmSD4ZfXaDTUP7xBUvwf$j<@hTd8{eS%|PiX-usNl7$U_a+`!n41@g!MNlGLG z0j>Y5n(MK9p;Dy3-R19mn-;=7Do?-*Pm_a8k73eF2PZtJlbO#iJR{L55P<^~Pd-?Y zx2v(uPv8WKKJOWe1dM2q5vTE!56dUjMTH{Ic(+C;`ztk|y8 z{Rj`bdtIG_20*pXp_I91xN$#?gi!K;eph`y9G)Y;9niLA0i%>F*X@BnQL_HFU2cObN zK`R0mss3?%rvrMfM%ro==v!+^QPzjC`rJ8qUv1@bdQ(+^Sd>bOcuI_Sn=7t+a(2iPg68ahx#5;dw`$uD^<+HA8ZhoG9q^e z5r9%H)SbhUwF|3;#6mXYa?`XQ|GwhpKX17qX3>pvKBn4DH*eBeCm zubX4m5!twhb3c#j7W!u9O=)%m;p3;PAyt=H5ah0}IWPS8jlJb1r)C@CvT zJ^%RIBB$y83e=X!X@6=)?4W$6|M@KE z^Ze-ciLL{N?-#q--=}lw#x*uK%|AT%UA1CKQ&Zf(C|Ks`+J1vaLAi$G4WN0+wvtzrt z4GQ0|T7>WhMHf9gq94}EZRmCS`oo}Q!Dhu&*`6k|7J8Nv&*E^Z$AS*Jx=IP`%=ehJ zMXi{!3d}w*jX!igCvY$c3PJ$zF4qCoVHa<_0m;OK^=y;Si!10=gCPZ6PvnIk82X@R zCOw>Zs-0qIx7?=&Oph?KEY~=&$^h^1PoSR}e_>`#x@`#LIW?7amHl*v9v*gbaEW=& z&_hwXga9Xw%<6Uj#p5h$txd>-5!Zs&i{v5ErJz;C>H9Z?*G<%ZhgjAp^2d+sTc!KES&p@mnwlKU&7r`OJ!%H@AgrB(s&LvS^ zhu4#T8#Y7)=fc*^h_hA$VdW7sw~*z1YeMb(aK%DD%0=ghRr-U>G$Q&)69Z@+h#c`7 z2t@WfP+7!!kE2t7>n6Ex z&~5=V_I~wk|hM=xMOiIku-a-E<;xirKq1&*z1!S z+ocw1W-=f5#esA&g2zH|=KOF!9sBX-7Gv?zri$~quTDHm?W#<~-($okp z63N4-1**P53=1;>2s`*kWv@*9zCjGHlwxqqhr1(#8I7!*2nQlD{2-%1b}1t59D$wy zgl9-%fr3!SM|{xe6-MzJ-1n;bh)IGjR~5_uBwB8nVSUmu*?+vzhrW+w1UymMKF7GQ z1eIF8PN`Yd-YpxTIs+f|3o&^*=qUlnWSRebXB9-&`HMY(?gb+sAYReEWLs1=mM~b` z$;E+GtflT2&wIGNE?wG)Y%x4Hz+G{nGNY{xm3%J;0N6)otsvR;>q@VH4!Y#8_XR7Y zC>-WhIPagw9d>EqNAG>jGz)Avs0k((Pbl+c73d@l8?0b;k}F6~2ycaB$nww6FYkZ` z5W){Ef-Go3!tf&%)m$?6^yKfq)5`O2o~qwUJr%E%;i-8?(7E|*VEjE#lkDfD?0rv#<bUkO})Iq&k@c9 z2|lAOmy8#*M{m5oazU!+{94uQ^+$27u^RhszU8qxm9%>vgw9CI>|kfkQ)A7#@9!OAH0dp7INZ_llKT=qW7J>X6&74xRKo!_Ns zBOUUen+8!{I~kG0p{(t|Q5kuyTu!WrYPW8iE>b+2#e@g9E;cqO^OY6RwB6N9QRv!J za`%f2oyT69d#{YnIps0lW>{FC`G+?r-MQi5GjsJ>-K5PrJ4}aCr!GrgyR;>0$6#v; z-Yhk(ZYQdi^0yJC@wprUhdtO3G%kFZ$K~ad2UtQK`but_4!vX_>+R@>+H~zfeQmtk zqquNGYM+si*(JCNI`3gSg3?FyG7>q`Y36W18JzbZD$J#$oHO>YniE+MqCfGzlk5is z?bM>?DG7nKuf5i$*B-+i0h$}a5#n(HHA6bVkYDt_+675j*+A$hRf1uekOgpwehG}k zjupR|$v+ra`fwdM5o&(uk%|>vInRSPos^RS6Trq#_>ishI0Q+}@c)8j@M6L*gH%4? z>ps;NGB`X@#tpiA1cUUGygY_T)!Lxl2N$EgmRK;THlR|b5r00a0-$0EaKQ|Q!|^Tg zD4}g@ZNzJND+Eu-eSjEJ`^*_d2x%b6IePOCbRK?qM-UrD-hZ+i=NW?GPeY&~-pR_P z_m0@L-{U@sSU|XPC{8R~2zYa$iur^pHu!x>CJH(!$|4czwPE~cqdJ?M!g@3dO0wGy#A;sbFApzrl)0StSo%xbGmY@} zD(;6&XU|z2j@sMXWA%Vj(TPFP={#kap|W=ut+(5n_s`!a{a((+$*mdIQB%1U-E28J zFn4sEA7eCxwXNuB0FXQ57LR!yAO(^qNI=8-b`b9%yLqzvOhh}MHAm)asdy`-?w>TE z92xdV7S5re8cxtCI>jW{0!R)6CDm;Ob~Tv7;_uS1Z~tsE(@SILP}~dHS#tk4#QVT2 zbigvgS&y%X@Ygcee}TlEK#%arsc(*tkFT+mgwCB9#1zP-{FE{=Gkl3}mXWG#q*aEHd@*eKtU%?TdVT z6MywFFPvfzvEldp^=1PgG%~M)&LWmzU|*vxtEmm*-d7u;+3pj2087ulgU$s zu~Gr~s!1>RGakIN^J7tdZ14A-weH*h@d5V7JB~&rwBG)6&^0qKFra!l9(AGDC1xs8 zV7cgqWKQLYGgds8Z!UyH#;Wvfe{!NKsC4wO;HERezRc3`j&xV=a_tmyxst)GEyD9i zRKqsv=F2XZRaVz@SBd)eqh_83No;hQEB;~H;@eW1bTsUb3XbkG4tjWJ>I6k|Ec2Lw zwMu_P)cv!0t!MLk`p-C?Nc(wpfV$%h!w$;Gec>JP6yJH)Q>_=fy+`a@=O^1j1p%?E#sU`r|ccTJWa?bP{(@=jN7wa~GYYFC6&Y_7WzD(1m z=mo;%?a1G zAwMLscO+#PZEtvd_4n~9Yk2=2h&j$*=qk!gqbKrf(G0vcdGepvN4 zv+AvR9@?_%F#wac60ctyyj~;Pq7m~WIeP(vV#Fsb9;)XLU;7@xZH)|CNFq2OKv3V$F z>jSDGR!|Vxqo}F_{(!as+(sPC0kG`jMJ=EEAOj-Myr4S<$y1|FFFIdQ`uXLpzbF{rO>2w%t;f}K7L(i?ad87HR$;ScNAFh?FA8+PW}7-?OVu@Sfk;I z<}XbWW(67z?lq-5I-MLG9PVbF^xs``=*b=fpLPZ1pAmDvfxd1%I=>C~G!W_ym`P#j zM!t3T$B?p;5@pn<0P$&M)Voy~q9(9gGws@TV_~@+P0zK;) zl$a*`f=QjoOAC#0{6Y*^;I-yCv03z?R#)lUdJiW295D8(*KViVKe#yn!Dw`J{pU;r zxaGnFq@2!=BO`WAOjL9XmlCX}5O4h09QG9MjeOLL>6*W5YJvj^>R(n=MgBPF+t$3Y zFwlbUv%Atm24PV|_C|`ZNQO8r1kkj&FiG12Xi)TH`n8Ndg^xmiJS=b2+N~Xh+JZKK zLl8s)QI_pR{+Jo;1kkgQmb{@WgI5l96myw`=lA$-)PRMQ_*ZP|Lt5ImQ0!t$Y;i?s(t!2yV~wyPP)C?=g%j$vpi_oPF)$} zS7bgWufdqI=a9nq0dCbWe2Nq%hiBGizc%fV6PCX-!XjUHP$pEl>Xj3nvka@4wU*{=17n{rjCG`fU59@M-*@SgHDBQxBgyT5${av@g ze)fI3MRbp)?kDxMB)4!ZOcxbNj3%(la51p$uaXQ!d8=2>N%bIXenK8j*)NQ&Li1T zI|}c&#!E8yJ=C~1GHgP_NxA8U)T*-gXXRs(gWk&vsy6H9Omh>;&qqJ2p1AH%cD}rR z;<`?p!Mhl{O$Ggd=YQ~72Qo<2Nqhe``kWQDBj+S99*TJ6_2ko?qJIN`#SfYH&VcNFtjCZAMYG?6lL}U7l8p_g|HDR0PCmX3P~~K9B;}U~Cw{1gR|@lL7nOen5xa!QwcRdNn6770zDY!DQ1D~YfeUsAjurF~!l(3Aer-;kRL0@^LGxW8 zRE@vRul+s`t3I4R76IR>ecG_LO{^fAQ zS9Na2q0m!oLzoG<9pmz@m@_4c$rM?$bLCDbn%gYTcj~zs22jQ}oznzjd?=8BF@HR}~_gcoQN1bO9 z(b>@2bPzgG%mAd&1@W}F5P?BJ7Qx9Qa;MM{-yBFToyyq;u3(bu0*e`(jxYw8755&- zH-eB9K&(W2flC0%U9;UgR<<(2pl3pA40T-a$;`U}WI53dh;8-e2Ho2wCEr|8V<8%CSvTAo{=P5WY za75vD1(Cei8eLgKY#4C8A#)J~DoUW1kX&IvemhEWS=nY%bVcwyP=mN_W{>z=UijoD z{BxhS#2E)j<#2dozpF*{bxPEE_Yds1D~QH#yW*{c74>doXFX>ec{1ad&qidq z&YtA+d}qz{N8ij#sKdCg#5{NV-D{BEA=*DdJns?1U4#N55&sJHNiqHYru(P8|73H^ z$33P-M>HIGQ2oM-`YDQOXl3dWroe_rt_7s+I$*2!SHb;NQYNU7QqTm#~C{QD6zRC{Ayt)_>Dh z*+(zYrf!Q5)Y+9|nSXJ8LB-DN(TRh4+dsP<85=#pTy}IS|HshZAP3dYqs+0`uLfJR#(hd>qBas|Ok#hv&C$m9d%5xa#Er&udiMCKlW4mOH`Tdn zdt~YFdVduKU%`+t8$nY;<^8#uqCC6QR_N678ooT!yMKdO*IhJ6eZ#j-D+__LYjhpH z4!0irTvdeONL%2Yhy~Bfd`e3)LECKjdB=^i>GAa!_jP)7qR!UgSs!z`N&GbR8~5qk|3kx_K|+Lx1hPdgh31p4IXZdAURui+c=d?-aE!Fd$fXIGGdu z9p<$!s66(2d!g8* z5Cn8W3kk#)k0}{*K^#G)`g(j0Xa;J>DPgcV%}?M09JDyI5X#gIP?=!OY~Qi5iR<@?iA`q@aB#g7g@>c-TqY-F|5B@Z69CDS+ z6~6EY!l6b&<6$R7k!o1S75o{bk7g8{Bc!UXQ(bS6ccq}A5fl**pZt*PE1nQ~8pbC= z@C##w!Ss(Y^H_48PJ_5_usgD8aK>VujOF7@IIb)#=d+B=7KQJQQ1(mn42Bhd6%P68 zVcvXtHM?Qg>EW%Z^JltW3h%18Xl)JoKt!w5kSG^3i#Z4Jh_Eg`&8qYp;MgM%*#fv( zgn^LeM)bifk|PmvQ&>FnRrFIh5L4$2*`RwcKrU6KTUhH5Q;wTGWkeOf5Vi+wNstR$ znnlhY;$SdNsgWNpfIlns&%pQ`iGxhsK*_DRg8~%v&6A&xdz%7bhK3`{1i^eNG9Mu3 z18n%gakou$bZl^5`**>q*bT@=OSvNjn_aydQ|Sl#d~lJ1>XgS8YKO+l*6 zM`1^IH51yvm}+7zlSt_k{M=o>~>ogK`w;t=7rs3yys`lU>;1Uf7)S@TriN zMTg8?kH&|)`JVS3I#}K*J{}u;HsNWr*?yVe;Q!MCaIrnmWh~TA&euuKXI#ikKe(TP zKAY)0b#eXO7dJP5F2_+FGibQUCEa`Q7R~gqAn#+==-vtr@l(s4a(TxxKGaQJmJ!qv ze7>|_Z)Bo*L0J2FfuyALBZ|oc+dG%m?mg3e(|1;KjxjNVqPzd&#vsM_3Y|}F+8=Fx z|D>^J>1(HNAn##4o4X@TrjTl+Y%`&|@NjG-!Dw}7mff)bwD@kPnsNRNL32Tict6j_ z>Aafi#UIKX9_PnPTE|O;eb#qS6;IgI5!qboTxHg^ZYRqN`g^7nUL5ze@3_Ayk7kaN ztdbUcb0dZSj?6%i?fuYCzi21!T^)PsIy`nraEE24i*j3v_F2>F<|$#`@X#~9uT+mK zZCnkF+dpb!`2E#`_cDqp^1Q=rl3Br;O;BSnnDsUqRW`U6A1572dN&DK)m zi;2nbSqx2!6}`-J?iI`Rd!fgi_TC;Yt8qUY6E)IkJ<@Kib0qcUu|SJEJWLk^L6zNS zyWxklIL5^=F>;i-iLpe}D z@Q_waQHGnaOG7(;3dg|wd*(RjDTdUGaP%w$)Jej=iD?=G1OQ?N#C+Ya*4Zi?wt##n z@m)axqEGASyv00HLQ0w0*hu>Yg7q@gs_@@Q5H?LS6m~?Zd`kW=1Na|OT!j-Byd@cp zNQG3@>SWc2_Vx&S!EDIJdJ63bMYH^VV0klX7L{L_&>|}>LIFrmV!niaio>6U1vU3- zmdao2fD&{eaSzV9wPpgEVDp5Rqs8N=3-QHDF5=R};G9wMzNKZnDN=|cKSQmL?}TUi z{`K49l%968x1D}iU-dm|IhNCfOG?V+Zcxtb3QE1u83Ojp_%dpn0I5PX2t7yX>+SwQ z<{!F{2sK|?h1}+W#kzy!F6l0HNy{1rn$KDefSs>x7hu3t>N*4z0a~%b2n`L2%a5MI z%`VfVL~sknU<>e-s6GMn4=q9xqQ6L<7vzMV2&hL44Z=?w%vDOB0Uj_H-)VVH8Etk` zVhkP4~);3x3u-aPo~9u*(|d8FwbPu0OHUJL77bzk2e=rxG`Fws+c244{c zT=Gesd^$n+1Rok_*Etl!(Zxxb1a6xC62qUi&d&Ox%e^G^5q%Z%xPc){FwZk=Xlx_` z8vy2w`45`>tA|2_%Rs*WaEdUjavt6k@RdV(VwtyV|PY1b_-1^dG zT+?=%Pw@DO6FlOHr!{Er^`myWqoa-xv=|Zw)>apmP*rJxfdCo5M6uplR0MG^pnNbc zq`WRRKK?6M&Hv(nHpnkh63SJq{1+8w;PS=c0C<6bY;$EEA(>d8zi&Rn@AN~lY9qJF zYo9%C7cN|=PBw`(2#FWXoRZPGb1lygxf)N)${qpJz`2cWWB1QdH(6BBAn#r^U>ax? zP%Lv*Y^z zN7HwJbJ_QAH&hhLj!M~EQBgu#EIFJv`+QWp;1FIW4P*Ti~ZCZmo~ zi><4%wVVz4TMW-69n^*f{Q`TVsE3*NC+40htXUH{#HQ*2soO-%RD8*a@_V+E6WN{| z?@mu9R+SA09^$&GLe;y@XmIF4QJ2N$-F?c|l5&h3kM6FW(mkzdTV6tM5KV8((acdP z@rxoS7SHUcaq5~n61M}CEK1J>H-DNKt3K~bQ*%i<{Oq+Y&ed#jThh$YvUQ%a7@^|C z-%E7VbeMtn-lTiIuOeO0G(bEjkUVAQBM;b&=?7 z?(HJ>B;R-38S-{rdr6(oCHjDOC3K+kwtw{F?OdFt!E#Hik&jPbFksmcx2@wobIJFT zN2HfDZ3G$$T+{gapY^0izKm0Xe;-?La88@&-N;jZR^xpYALHno`_>9czW?>e-8; zQFy|=S?+5l$%%*W@j z_w^;|4n(EuOrC+G`VDq3R+-1dutfMGm_5F+Y{F#V=eu6vI{^$B(;EavGC;{-u(xtQ z8>ztCumN7CjVJ*AFVQjpfJBbs16c$?FrR$`q68ybvA&AOU(OD`rbqE$?66-$IDo6S zV|N`<5nZA^?{*mCB4V7y$&E{t!OTm;!}SpPZek|EEaZkB`qkIxH)QG-ljktOa+PIa zn#DnLbEcPLCIFPq1##wh)k3045p-nSpEgNYD~PHPfD>3d+e#|R%D|2jnq^puxe-W@ zJWyDNk(`b+uV@I6FkC-X55i!HJGg$?u3jD)fG>8g_dM_+0t>LH;xvKW{|FiRz5UNW zJH$KCLwkyo-`?g~V0iED?QdksE2$szP1K(c4yIG1hRqL~z0#As$FJ>gC!N0UbtZUro+^#;1;1h_Ed;7(90YKq%}{Q(b)s{ttvO#)yC%YPW5J9+`-sC(6CBN#MED zgDQIva6LA(0M=&PbW!394uZ}+sM^2Lp+x7Drp|HAbLSTzub@?q1Y#pxNzbi zG^b8WSzDWtg( zj6juU1eFQjEx&CBoi8#WB%M$21FnDO2iKvB-9~A&05p{qS z6?#*LgN{kFL~67vqH=&heUNk`mDPvTauiMCQt)>Zj{sf|y*Wl&oK2WC!7=s$97e=9j$ zDoiux?7zG-#Eu?Ciyy6}W)eft*43HzX+AxH~^ z<~r8Q@5V_BlACB}{I9<90i@{STN{f+whipmGx`|=--+}{aN(84g#xL^!{uK?>4W3E zWURcjbdg!^Zng!Ka4?;7-gvJ6BuFm2vRigl57+@ZW{F>eI0~Y+9qBxXCV#vS z$_-2roQTfQ=jZg?4jNt3)j&h|Wm|OoyVecf{PL18eyL3Ax1oFZs}4W$+E%e+eXD{x z=F+EB@~PO8CnQ07FDiYG<3@i+IhF|-M91;>1&q_&$wr*Iy>~ncB>7F>`84S#gYWUgi_Lbwh4k@B4ptec zG-v+){x99AcmCk8jqPb!URK#sR$7BleT(29KMwc5w`t35OvyLCYA8m^`^7CP-0u@HOC_-D#Ki@e?1WFe)&lh3{7$dXs;bnqHO8^26Na z)3kAI8STQi5Ic+_q|3;25&h!k4@<-5!tt#rRK)E@+Ai*}=g$oFT<3Q+}`P#VW=+}&R({V6!;2sx}=e+hnV1&m9vJ*kz@5KK=HXxMpkQRdM zMkO!-j&BgAIGp>Bk>&`1mq?C<0|~AOJdhY)O}SP>L=v~%UP)1@#9sZZTIdaLWZJ!E z->0Cf+ve;*-@rQc3=1rtaQH2UrYHb*A2E-bq%yibzVgyo5W2neNfX3CsD#sP8>?IY zl?JISb_mE4pAXst5Jj%QUERD4D7~{%eG=>HBvU+Qc?bhD@J=8ej=t+dL@Weh@P0Tt zVqFShA@T45%}FFV73*6D^&(#<0>)XyUjNk?sl4Hj^Ib8Z7i&D!tRr(=IBT)()NM>2 zSLTV#mVAIBmG|$PP!kVgGB@^VLec20xj|Ayc-@xQW=^W+S(-S>}MW645vdnNVq(jBqxz3%uXLl8h1AMc9Z4-%OYn4nB&Zcr!|wHWoiRt0f^}fZd8)3EA~P>JCWwljy93{e1RvxW z?Q9LWKK82uq$S<~=uZv_i6dYy(AS7BOzIVx{NIPZOb2u+h1-AXMLyy7D~y`bi_3@^ zDWkKir8~L*sA%5?uelFjZI!+o_xYQpp-c6*GN{50@1E8Zw3L0_1Zd7(^n-kXP;4we z+jp7dO3r}6&n2OUL_HOUGM}YbTMuNCQGYxvZa6@ydhyt^s5|EpR2fD!)A|qGD!7s& zz~N?>{Dh0&K&{WDB|f)ZNuF(n|L57}?7~O6GF z$(Hw>C&S02`1__=S?Mnh#@;#?7v~>F`$MXtHay|Py@htN$=IE|`UX*VR5wHoHZ_42 zj73CiCR2>K+!>Xu)w-=~C0&f3JZ0gls76Ma>i_nS3jLK(w_fok)f+Cl0`t9R+y&f8 z+IPD3>7MvHDNK{l`1s13B0~<27}okrZUy_SO=$Gx@lW+BMa8!rw%viJ1RspnZP3r! zkhFY!{^ELAZ2#|$m>sV4Rug8ov|=;H)qjhq&Pa!li;?RrrQ7rl)};me%}#{9kO;5O z))k5WGVs!W%Y9nhZdnmaBA{Yo?I%J?u}=c@%?2JoWaRsRk2;$VVjnzfkk0 z*VQpUXkkmbMWRn{AK_HU4c`WYPhj(q%B6Dbz>|uKc!+6hvKdPhNf2fG34USwQ9RfiXFeo8eYMKy36Q_c19v$Enm{%_# zHVO=(^Rs#kh}cg7tyq*9W;|FX##*z@NwbC8IqwGuwuZ|0z5mqLuh{rI=Fo|n)?-7w zX69kk;$ie6J2N`ruHYu+s57t1soNxu)54~ zm6(1vihv` z#`QkQKqF!LnjCLO(i3K9a6UwN`WiaFx?#t@?t_HhXgFt5Jb#^qS_{KF9Cm~bCE;Q1 z^XCmWyCqt{OcEr)q%$FTJml2uZGzW{=9c0X<_U)S)m^v}fX5I9n$^`xmD}2a#^t%? zp{i%&_dQPvlf&?bc7`cfBQ&2KD|AFd?5E!d23D>p#XRdJnfi7+6(tA0WqjRO2a$~l zL(z<=grsEGRmnw0Li<^SOvrR3%iuJJ!dR4KE=cYh0z%x!gSqfA?XiQlD5t7TNEt;4%RQVF@@3rWx2RdCCT0fC@Mvm!?5{ zMvDVjyslhHb2NmChPUcrXARm*o> z3iH%V(JgkyF5S2QB|DMHc12_U%K|S9=%kHLOcsZ(_*f1%;y7jR-?`!eeH%t~d<>u#YewT+8}^ZqoxieeWFHlFwCr-aW*`tG+o zQWA4g_x9r{R<_;#NL7DG^ZRaJqgz01q`KJc@!f&~vX#Y&Z>m#H9X>0v$*0-2o)b%c z|JHEup@R{VB?1(j4Bq-D%N|Me9Tv@QZGX!yQ1s|W?_QVF0xGd(Q3LP0!vC;7`)f?r zpXRZ17b6cpzo5EFnW_>S`X`f`1FjB-3dY=bJQd_#^)Tnb)cl|xnVU>Z=Fp=`3DumZ zVG5rT?bUU1v=5#7nh_wpEr7v6<8t9A^X}{q-_pNwogF)=_G-at>DN_`omMOqRQQy1 z&mAOlfbce&x0=_h8#|1+Ie}`bC1L%(HW^N@rYkT;Kle+#J`+=#?gC{*Bd*TbaF`hx3bM z=_r+Qnh1OqUDBHa1WpK30CoN1x%$^wP^&zaa>>`II`!{10=| zaRC7g!R#MHWLbfS1;-3l~w zL~I=IlW?rf-D^(Rwymx9LVKo>jA#oR ze9zT&aX~yGj4WnAr$+EZP!u;G4-XNK5oJOz%vB7@i4%|}LgYbYzA69y<#Yy_#^d-p zrs2>WC3?L9sPshcc2gfd`qw%ILA*sZE71K1jbre<(QrV+OiNGOH zu^TWUzB=j;>aI#EJ3k*+!vmlK;>-_fDs~;9^|n_U5XJsM!x=lR==OL&Ir(q6E9ugD zxYtkITQ(d{0(JuWt_RaURLal^;p&12#p-l+MuyzWUEa_nqh-<=soju5Kfp2wS^&>% zWWy7=?C=I0_nuM4%0i@yfH#GB6YTDNeSQMAcZU>z^~cro9ljeazTm-|U%k2;a|`1K zmZkI*)0}zwB>gj?)2eRE`vzk0BUr&+T~-;JO7lu-9{&Yn3<~1fZ^)$eC?t&I8iW`U zuN1_p)kLmSI|`KHR%$ohPxa!oh{zkfc<`4{k{bB!BiWJt&u1%jkH0kdXDbk(#dO*o#4* zNg;cB-gIMG_WiF&^HGSMhdf;MJ##0{xyo!5QCA^P3bsojI%Aqq09Tv`AQ3;-cl{ zM4y(u6$~|hX87DM4g~2YOE;B&42~4J}bmZyl3KyTUWN5qsyC?s}}b zDV;_nPHT>b7v3_YN!F&U6}$63ql3D6Be$tcBr*KVAIgw|=C|Lh0e7#?m*y&d`!JDs zrcvrQbGcF5`0Lu`uq2`HNn(!T@Txcc?NHx*N9l}{dJeAIka zeCl?%g2uhcXI9sS^zHfH6wE6;FVvfv|Lb*#_e}dP%Q#*oFAs&gx0al^be5CO6xI3f zrAsTMBkON*+10e<5fZx4dL?$Rf5hSSV-!4ms}@4PJV#l&!o{-Bdz~+;JmobXYW8*O zZGqMkowUL7Xc^U88*QSSN6~twnV{FyM&YP{xSH^~cr5XP zA|w(QgoL(B;mUQa|0jajX`+@JKisw(eqZ>~Rv~02GA;oF^oluSxPo!p3EMbE93ov8 z(U$~S2G*Mxf{;&ekdZMmV-cP)Bos=V0+gb9VYf4cBLqm_M(Q)?IT9V_D9+q6F>ii~ z2|BB>oUD|nj4P{;s2HNiCO=juq$vp}r2v9Vl8dE#VEOKNVKQkk^??2#7P38pEJh#6 zjdy4Y5BBvDnI90T;7%s0Mld@57b(Yr_nh%K17;bdua@B10i|(UdwW#)-5u|(EG?h( z%{)p-81vi1JPMeGND~5uhtdLTg5@~LuCsWtRkvjpTn9!RLkqX#@ za5Ugtbb?d_t)dY4zMhy@S66R96jEzPhfLmwao1|78}a!8oDv}+=jpC)wy2sG)8{`b zO2O%5ED2seKOnRF(!{w7ju@i(SgYifn#pVTDDFi6e{PZZ^ibBnd0vBt~SH2VW za&q@K!m;hZW6#@wR$^EO+c!x;S$z7$gpY8+v_zkuEIt-!p*PKvhXf#+omf%zKGio_ z2!R%WgH|r9?{X=}D>hj+bzyx5|BrZanNqrsD=+n0Y&ka6^a|fNd7_@tF8OT@Uq@hD zYQ~0O@v*_Tx8!T;=pK#yxEb%d#Z>n9OrHF{@(=D_Y2afxltgCanCMSh(@;k*k>;Kv z^^kdgDDiim_n9)vyH%#n^a4$6w(Wn0e#^#**yMp=Y-~P}D=on5$<(lWw{U4ml%+2Yd(aDi)*I6W<()IVVH4WC>Sm?V`sFwD+ zYS*JZzb+TVnoIm3*P<#g_pxA3;$#U89=UZlc=An<;WJvJP{!_q2-#OKzw7s8W1}-s z3K`}H$XZ8Ueh>;7Nvx5xpgJtMM=YE&u-i{A_0gSD;gW6KqH!mGF=xFoe63(<=}!|@ z|F(X6ez)9oFr!8Gof!4K$l00Az3%Kcv*bSc?`QInc5$4Zz&e)-p@&i#&RTI)@Y&R>NH|ovp%9&c40N_Hnd=X^-`SZtR-0vNhZF=k}&Wv*v z5k&|Lg9eV{5lt80HqcUO*n%;rr^12!_{$elASe7>udtJ1;OV$sw|Hc8*>Nk5kR5=l zBL-3VGy-YIh=gMaBg`JSV5S#Sx5Sa_gV72xMmdFrQxIqLo|e5A4M`yCfq-og9el_7 zfnO9DRY1wdB$7k{775yKFr{EQ(QZR1oRO*!OW_Uu=qIwhPqr&KrI5dY&j!A!SS1d> zYW*7SybPsR7wtW~Sv7RC`r5v;Yo5jNV-fFfoH$poTLW#!MnUvp z!Ak=Y4`(zE3B+m6qdri{J^1+#3FKRV;9KxUq}?=J^#Dwt!@vPp8^DV2fl0hQq(Gqt z2rYx>2n7oMZzR28eSd_y32?A{dWG-$`#G&nfGmY>@B|ucfawsWY&c^G6`B8Q6%Y`n zMGWu^{oC@RxM_9lz(@69^{x*|e$M87K`xQo&~PTAE!MOlDI_EfMHuocIO{{?h7c2S z7W^!JV~LO>+)L=_0jzE*mTklBg+m*O!I<{9@tLrw%BPj0DNfV{^lPMZwN4P55DmPw2t< z%`^B&feI5z(3t7}2wcMR8u{~tfD+juhz)i4;x<9S8W}`RPrXeH1}Z0>d9Ul4Y6pf8 zFpj+>mYUCMRnwWS(Y6dWa>6YOKKA~d-}Anh)eVe{qFqy8sc9QW1G*trvtt_GR96(C zK!v>Ykk^P@#s&Ug6uV`1JPbWrmp~%-t)MBMxAEmF6{L2cdb!x?4Gf6XLSzUj`|k*H z;QankrJhSfi0t|sdT*vjdL_N7r^p;Kxfn*0$UimDa~8c4?Tg;xZF$5W7&#=#!M~-#=Kl`gIyXw^-;CbP$B59V& zxwdv{U;Cg@?MGI@gEO3xKGDNt%9x%@7aEEGI0-Xy>jKm5I4|QzD}AwscZ=Tz^wr7c zh$NrtW*vIwFuO?3pJi#@+J>|4#kA1l0O8^9JeE4A$Bmb%Zw$^w%5vwCY`dqa?ygDJ zb&*>~=Y+dEWpvTQsxfyJ9`{P?__p9fk8X9o(;sX~&bS;hcXwg+^A+uv>D=3wb*1!9 z>23nB&*M~swdD2BkK6h`@XcN#`TnfRMVxKy?a8AlI6xnm`V{v12t6aUqJCSqaQpf# z^7ciG_l!4I58r#n;=*(!a*6cI^Z312cJ0gCrys6sy!pUiu&J2P&s9kVKYf2J>B<1_ zYslkU4?&#`d+;(h|v&;@qFkfV$N}D z`49cfL?ha%AeiE)K+2%bBa1kM|y30WBOkdFUXTt*w@bK+*knLl#k0R}2GFY;K4w5yWT;kc^G)`-v2$wzWB1oeMn2~LlWB3z<4?Bzg`Mnf2jYTQ-6p@bMZ=>3%RuFgiQQoCOKzN? z4t|G72ym^C4nyIxxX^K&@QCZ{j}pN4e;PMfC0Dy{*S*GlOfdcc9`R8r>zbwa7#8RT z1O$8)pL4B-0_G_`6x5}KLQhN!#f4f{8lVWXjd6xUU&S!`Vmwtm{u3_yj$NeBpIStU z>)CS(Y3|;`!$I0Mgs~HMGSTS>AOn(D$ghd=BYX{tRcb(j%BzKq<|P|vMNgf22o$rS z;m)542yLLhwJ0V4O-)<8cX=Sj|MtBqttl)-V$Vgm5eO&7iUrzz(KD<|iwEVwg9o1g zo5EqPAW>QwFUNKnj|Ir4U;qt=ymydYFtHTo=Q|`?_Qm>OWWfg~0D|tgLf4u7YPKjn z{T_JLHcKdy2^-!6<$F;aq8GY5JB0wsB33V-KE#|2pbbuZqKgR&4xzTdj}Q)Z#%q2> zkSXJWLQ+T!eC1BS&I#0dg>Q~(ULvWAWzb#(qcsp6`;odMzz-0L0sTyr;^5QTwwB11*!GYEireEtlWX!u8Gc2>uJ9_&{x;u~&q;Y@@;B}EmzW=m9@3AgzmdDSoicu^B)3mULiD16$K(4Ma?T|; zNoW4amf7W(lr&!Tvh)eFF;=}*Nnh~kRr}r4>vB57#V9ZCnDHL3 z#8L{cPh;jg{g6cg;{#F35nG}qS>xn%VJ^z9-btR1GFE)#zqFG}h^`x4>|8R~A3w18 zts|G?yw-!hx+am@fQ>3?=3bAU3_F7k;Yhmz_Ui*XU4|$l4F-cmbpp@j-BC9^Yg%+k z$-G9=@s%s@Iiq%S>uGBmKZQ`cZ1Ehot2-Xa>{9VQb?Nj_!pqY#318Z0A0NFL!MGBY z^d?09*O@tcCq<1+XU?626w~H3PpT6xxeI$13`aHAy#CpcTQPofon8MpDgEjLxD;Xvf-ia*o~fTJ%DbiH|}%uYWSmePK2{dr(r~AP*N?VC=iSg?IKT zXYLB@mM#>D?|rO!x98sXFpaA<)73F84#G)~j8oGqpB=2|5@`HuXmv2PpR3Ws!HTlc zTwNqSF-(4Upu^?X)9<{~4z=9fnT!%`Ip zIr?fnQByY^4rYnuiSx9KTRs=833VK)Q#CP3wq%RF5^*pU&?s^eIP9rrK11pb{MMo3 zP-=Hz-;5qJ!|3Ggo2eWMH@XJu`TSKn^j$ZZ3Xb-=jcP#r9#`E|d4J%vI-#XrsM-x;6a4wj7{ydFjV5V^S z9qWLUaa{Azhawo_H!`Pw6B+dX5t;vKrNPr7kq+`epFe3wg)j-jM}g&>_2&!%& zIeDg=2j~IPEE0rI@fo600a4+^o(}iLr%#3mOIOV5gRBH9ntZ_owXCzK^Tj<0gP+13 z9fPU5`g$|xUcTn!>Lcx{YLkYZfB#$?G=)qBV=45pcF$>+F^ z*x@h5x{gj!IO+l+RkjqS3T-AHMPN?j`%zI;z)npDugi0Ne$5J^l(sk>FU8brUe3K9 z=babQiGh_6&_5cW|MaFLCcYYTa>DZ$i;>mWdeFufo*pYDf29K%+z}+ZLt}{B!r==- zQ=w>ts;>_^NyvA2X!k-)vMcX{5;v^{MCY`jax<;0N^j~RvB56@M9j7R7}s#ZjvN04 z!y_~1LBJwB z^eZ09Q30G&I|E;{40&(t@XB8@)WWGsNYw-ctHebLmx63pcvd4Gx2_6 z9*IZ^iHYObX3z{^E)pNIh4CDX0J6Bs@oC`8g*u*HeTxu}5_NpYw}xaf@vTyjB&Sr> zY%_z|F#RxZhD0ZN<67nHnyg#d56p^Rzl|n|DGSYZ1$UF#_~~tQAV!Ew!$~^y}u6X z=pLDfj3RBw=A$dWCS0Kzd(&L_`?Xfll845eVf)L@wpa`63rcz&&f*wS6ia^A_Ms{I z>ZRhEKLR^+MR!KZ^)m&0^!m-yvwtfRwEO}HqPQ};2ErY7e&hA|7>WH-@_%Ku9f~{; zL%dU0RlQXDIi*jpY}&NDc;b({1J_ceidesz~r}w$ddqbS~hT|El^tn&WN>ZLk87*XpP37TcZ?kkBu)7;oRJ^)@A5fH_>Q+%# zzJ2bC$9DlF9lyop^Uk&mC*nJlmd2F4C&G7KT(k|x?!Ugg`L}2*ksy35ot)G^QHh*B zJ^y=5W?@Yn0@V`r9%Mrhc|hlVO+6IPC95GBVH+Wy*pIpnr!z{sbkQOVg&S4^Q2KZV z#Vy|f3>f`Aug&t)VoKeQvzr(9KghD2S1kp|zi>;th8JU^m zCZ@nbwg8rdxDZzASA+;S^;Y#~e7evN-@hPj&4BD75S%Q?MF!$im9hi*QbIyP8X}S- zUW=;OSAbDN|M+{m`Ya9MMhDdeUCX7t_V`i=JDb(W2u1bM@^X|~7LmjXXhz_sxAU39 zpgqwrfM;s-k3gb&ek$wyKOTbR#i73NZ~WysWR1Y@*gh49v>~)@w)(C+ZmEW700BXS zDq>G8Duz0^MImUTo^Xf!eLv3wD4IdZ;f#tZ`X}t&Y3eN-#wL`>H-CT7n0Ge)1^?&o zp5Pd^r)S^7qYXiQxS$}*u(*8LFE%!6O6A2O%%fE|rzweatxDf5Nhm)M@0!3uJpuvW zTGalkQ8FFpoaRDp;}^nz_jTVF-lF=8zHY=MCTjC?2m~NNU^_D4iFOxRRu;DJFpNie z<;b#1L*K5Q5hBAVz))>JsnK>(@7En(w%_BoZ#;-y4)fGdceV4c{l?fHDA+Z<=>Gn= z@BWIMR`byC*p)3RDf*5eQTyI^7A*`0%?<+d@%J6w#ECe;dB)HNLwba_Tcs%0L&qB_dqm zs-zB%Qb!F_2c=-INc%E9hqas;ft<*Z#UzB|Ep_Y*ZH*P?D>d@eTUNA6@(^dHXZGnD z6QekkYS#QCsYz^!=jD3*$JGs9T(rhXrW{O{7JYJ4l9pblFTRtH>y)~up+(h~8ShWI z&*(JetZjk*kQmwi$Cq=zlPCM9z0C+Yv**F{%g#|sSJ}-ZQrrZ^Xk89&Ip5JW;v4e2 zUcPhaMV?rz$dlg3AAj^wUW$jx(=>yq(iM!;_;( zox4{f`}lK%QXZZY^RowEsvV&Sr*J!IYM40u_7Z>VG{3;v`gh!wNuNpLt%Y{ePoD35 ze|LSvdy*GN9-4>Dwh+FCu#7a|{T@lNwZwxe$g<7Jz0A3k*2y}Jzf*<+O=)v^$! z8-G`us#!blgSh(wNnn~bZAMjmG4sL-8b^hAN`$22V2*dj>@0hJ0#RFiUte!QP2=;wlE+e8}5T#+opO2LgcanA{q% zy3vPoZ@M+r#H+XKH{KX7ASv#pbP~OsG0LI?W1TWquPAeGFbDWXl$AqYe4KX^Ur7C( zO*`JJbPP=}&z_~X{jjd*{&l-((L$zVKw|H)mxuI=YUuA=HCsQwD$yr)R6M20Bq(-p z?E^WJL3?M7bt~3^IGly{?VF!)B{O>bG z##O95g6)3gFJ3fZwuX4g)?h@vd_`}5i%+^OWq7&mqT50e`}xZ}#GQ7}joMYdTpsJR zbE0HsNmOXNt5EC~EcWi>yVmyEy(UMJ@4dP#JjOp8#-v=B`1tsxE18k6N?BE@7!se; zYqcuedYaf|ORa5QI;1eE_3f0Hibo%1JPpSY`8H8K`Q+HRz*sr|y0FT!Z5xf#G>)yq<^631t8>S41Y%8R+dU6V-yV7tSN_+49`MvZwUVsyE zh6!3(YTGkPrr^%S;6}+T&h5T|#9L~1vVkDtW;EMeh%X7rYcwB)3Swg>b(05P+yzEh z92QZrkpu?j5dl&{$_1YS(J4YWk!fY&%h=&}XCnm{_{`lNcw%qd8U3ZZ<9degi!;kR zCUDx6aL4yfzC!EcxpT@mf?)%mf(Z>4i@Suc2DL^}O0jMYgqTkT+G=R85hykgjk5t$ z;HK(cMPQv+xKZOC4-6dl`-!AZLLzN*N(qZ5USpK)X*4fGVui5&loaNYLH?^u{ZroEUICX!0F#xx{1$n zlz4+{UZ!1F5>$2vrlk)eS1K+-fHF`<^CnU!mG1k+MB7iMBc?1!rYbatWFh4^2^A*g z5~UtfS3l1i#m)C}yw2d67*!<5{0r}=ZBofd?uQ%J3lHtFRW?#Ttez6Gcu}Ek#I-pzETF~X&oh_kZ(r0e1B@*d*4?mt!r+# z=9cxZ^IK06ohe{GmKgdl^AA(fVAq@1>TSQ~_61UzwP?H)J2$9eKVfDl`|rz^Dwxqo zg&Yq9ICpqs_tu&oH(|P$p~V|J4hc0JE2Tf&bzb(8PAB6F#|8eiHng>}S6*?0Hs_pB zTdHP9U`!tWX$>$*5 zU*=T#PyP`3`MTwipQ%%&lv|}#x<=bd#(C}1tV;2+fAsyk{CNbBIgpsN^q{sD0lYFws#t*IpmYmKfYS zZhKj-mbE!U$SB76D*g4;0F~>8cb8nmRK2g%l6<$YKNKzxBV&4lA)`SBzhpzn>b9Rv z0wT;Kapn>gwViZjq1Rd@!#vpa&-a)=5vpl8#7sk+G>PH|lg^Vb_XD1qJc=0CmlhHp|)<*D(n+ z2pUCfbAw;Lz@4PL>1kw?6qb82tw-3WvQmC*7=%h;nv%kF1+s(lvc=qU>+ta$_sQmp4=Dyrq0+*6Zj}P#*ehv0V8cIcS_I# zpL9Xx6o6ga>T+=<3wao<<04cbo21Aux%VK`?2m@HW_L!+S}Q&C9A=f+yr_L@{u{8m1-iTgDANh zF!McvxQR=b9=u?rJ^UL|*cli0)nS~kP{=|>1n`rHpn=PgCbStx|9K*}4zTI%%G+}( zKPJWpL(8tCtPf(N*jSkqx?|wAg1?{RA6K#(q8fG{`}_b< zvHdinOH0ej?n7<@k=2~{oF^>EN{`bubChD}=Eopd;8Ugu3f5EciZ%BxqK(uHFU;@C zsVP>HtaRQM(yc3aV7yVsIi%UWvB1dKIL1q+xDUZ|y=0ly)kc5wkc-i=Yhr-PPj?}N zw`g);*J8Dti?=lcgDvaEGY69I$G7O!E2R(LKF}9vC3JNAn_VX^oxZ5Kvfdy@va|EcdvPPkV$$TRh8`U4?nX~BTZisW~}sqI?wsQfPPybTjd|y z-OozH(ra8i#Ps=W27O1j(R8NS|2!8_fBEQ*?h~8Cu5IOTWs>LbB>!>9+%{9Yc*q&KdG*2>Y# z+?_5Dr}w{a!x>_jA=qPI-dkz+x#{MOKTO_j@F0a-YZfVA%1!CZ8Ek&paOxk8F*gZP{_G%nh^d}7elOR-?Y(^a%sBq#9o!j8>wQz7 z{;2xOkC7g=VT&7`4+QBZdpt<5>(JHne@wXcqa}M!JjlRe)0G$&K*sm7x*7=sz^GhMPZ=&uk#Bq{#;WALK5fcX z54rb-{NI%9WG^e0*VGU;Z%kw-=-T`Pv* zTqTmoG4=4Ax$fwg1wMqE7V+=c*?tqtHVzU9mY@?tfzmD%)Z?t#&iubfc?cb#FjAB# zpsfj!NiZqIJ-;}zyyhi*Y|+ZxSiByPgEPFT;N!WjAC`MK11~6%?2Tw;LF3AXA;)?F ziH+?BxtnvFzvhS{AtDTRV*beoTcnE-!vRWWV76zIF3naS>g#)r@E`19IJuN}e82!) zTwL6Ub(2`LF)b1ulF(lQ?f@$X62l235vB>ZwaIuqXRL8Rpoj+%T9dUr*EB3TX*dSu zs^J&Gzlh{r{IajkXF-WrMIOm`UJk!D_I}KYt83l9U8s$gE!K~T;N3C0*9nXmAuyuF zK>)8Ty@OwXl~*A&XCg6EiZ=z5dSxS5BusoXobiN)CGw;s}_Q z2$A>wH{jbmO(W8>77@}g(cHSVMA;}a8IT?| z!7XCezRRHMN$8(X(BJB5sy7Mh4{pVD%d~AT@Ty0nY5STw_dT^NzNA0R_ugX|mrOmr z$o21*FbkB*zkA7d{v}_V?`GE@_*~!Af3^OJe9>5!bC8XAr)RFK!*zP00nstD{m&FL zW< zxYGeleR0y^^ctQ3robTahN|QwbcS}exX2P+e zA>?2lt3|;^wNtC6e2#45fNdGk0{ndm6CbvhR!d|Mfe9jKq0dqP-4NFGeIp#AtBSu5K)L69#^}2^=v%g02E{gAfa}0?t4DrG(T4 zY9XYiLD54KE)Rs3E490$cgey*$GQQz>S4^GA~@i!ZdSW_XAG>GUgV99>h?r=2H14W zcJR-am|)(6*cM7lnqXNXDh0x#zov+VP`JZeQj6aMj;WpEHU7QTy0n+Rd&UJA#A@Sy zA0p31F+-`jnwT6RxGAbx*h>f;h|C@rQK|;D0$oHI5Zo9_hI@Maz;|HmBkJPtErCv%`SnY_Ko>J&>+~YP*#M$< z*NBRF61OtkvQX_p4FN~8QgTo$FBv}@FL|hsn6U7xjg1=eQP4uao-mOqC7gNIll^!< z{K++Xla;Wp8635`H$1&K4Vnq=IZe z%_ z#_QSXw|->0>FluNu*o5rsg@&^_2)Yzb+(vqPeEm7t<;lk?$z5b-`IcGj8q}zFKRk) zG9lr(@#Scq4B2Qf*|mzOmGRTnJ)*AF^2G-~)GgB+W!kEE&@D~qb$AzRDOawWXg(r~ zF<|a8;(UJn9N8`zt7+96`vkK>tL~pQWc^%nru|dG(ccB{X}9!zjvn{@JMhhges-3r z*zm}=r4MHgtL^Z+HK>c0C|zb6-fL868KgXmJZXPEHGasqW@0u~O8yS)dbWEb8IHu;1MiS z^A5Q+t5s5Qo_*zMAg^HVgUwYp)i}{28JJ%DElQOb$k`e+-ZC)E{ zmR?I_72LSJ{hxGq+?2k?V$++XPb#3mk`a`?Z$4|=mpw_8!bdgJ8R@ny zckE^RsiSREwD)O8qm{VF{zHBgk9oNUrRcA#hl*rp6ub-{Y~sHjCsHHi$f)0~Yc=!Y zwr~n_*2}uYAG-83oCXiM&E8IwRJwMudL=Zc+n_?QXdzV3nvu7$rqkid>*vxpFP>a{ z>26D@AN1lL&wEFzyig6t(qcp7jEdU84{OP;P8axCn=%YXRCr42gu`(T`bRQe5cQE3 zWVVXtP08OyHY+g9r=6CUm)3vzb*@^EnaNjC9aGAttKWY8G+wmX&bRuAPXgSZDO@w_gXFM3N&`0E#xVv7bV98=T7N#l9v zP45sx4%pl^Un>#K7jnW0F&uMpYq!x$?wy5k69`w${F_5KYN>;9mcZcH+Lv|dMwKzf zA*6h)0_Vey8-0i+zT-anUvK~rf&RXKvwX)fnSmCD=@Y@}Sj2ye`YwuQYxClOBBmpV zR7yOi-@FO<)1>>QT3CsPwU~AN2|2k=?;+Q7b^OP;H@AKao+Q>i9EMO^Hhf=F!a`7B z?d0?jVOJ=CyMz@#-6-UiOo8rAOlehWT-0P3y_~8)3oo+mwLpVeIQDMbA1*zoIPiekO+gaCE7g@ zb%n({T~gW!$;>ans{y9~jF<^2Q-nJt!kagR$jBP5VV{$>l-^aL+|#?&iwmefo6Jkd7J`!NWqYj)bwl9pU0|W^T0qLi2R2= zUtLe4=fp5Aa?@`+{nT`h@Ilwkd)f}$R%W@{$!eoUj?;c_pXS&bg)esI_p!>^_EW{# z4SIuF;(J;0oOf0o()Z1H-8H^s7B~N4r{A`}O`Q9^$D%4vneru@->Y;{PkIw;JndAP zoL|LUJ9xLOAUdO8gRFmGk(dAf(R3ZqSnvP8L`9`S6fLres1zZUy+>wNc2*Lym4=KDQ~@|P z>iBiaX7tsyq?rH_d`s zzthwe^Lx03PAie9yu3!v%FoGKvV{6T3tM}mKE+NPZx+_xYX6AS?PgYb&u5=of4GNs z@TRQxEzkGdqh_D75O#k;Hs>Fh#r5S7pDkzcOQXFUw@f09yZIOQdv!G@9UgXHIM<9(qJe0n&!^?o{(TE9X~+581aZPG#rIz9LIYr%jh=y4|M#PjmZFoj{g!_v9=^zv%T zWul=SH$A-^i2*j{P?#MXg-bw{9?8li~F(8N+iM%F{h9O7CCb(vl7K$$97HjF+F5cG-r=yd5{Pwu0`$r;OrTk$3_wP}xf;}Thv%s*MJN8R znEH@;Gv}Pk|CXzT2|rEnC7_{;dUIL=9i5zHw_g%&a2dY4xKibCkE)B>^n_~B1=7p9 z7Bcu+@F<0PxIymeAk>O(1*Jq$Q|NTUNT~Nljn_bK3Z+v5?@uKd@d3#u!PWF9k?X-# z7Co_FJ4t^?YSpm|>d6kWIC*>TVE&%}TsZQD#IJJ^U5~4s$|JvI2x}gZIp~$`ZpS3c znal+rF|>-RcMg<31IL7=10Qq5xTkbm;wCK8wS-6*^L&Hh8KOEBX;dfy#@QG(Gh+jv zl7gBVeiqMPAWlMOM`>A^s-9je0ds;uPfz#J<hvS`BC+l$a!niReiu7IJ?q<7tht)*^asd$RNU83XFLCo zs#;{g`U3@xruoNj?umd8m_iS?w%Qb(eDLKGM{X9WO^OzGlYqKp88&mgdA$es^)-{F zh27BUz2_aeyA^pY4vtBkmW^~2T|Hd|M<@!5Ui(VsexKJ%PMj?ZRkLMYPCoA^FFVHA z7GPP-#K5#O-uD?7-FDM+tw=`4<@vJlfPj6aUJCnk_GoTelzC%5FW-xH!@bVZP%s-;7wZ{Ye*hdzEw@pp+Yu8c9CVWByqYE@{$-NMt- zp=^D!g7z`f=%4aqWr2||Dm$s&FT4@_MOsm`K|>Q`$oZP>E1j28dM8!R1?%%6zu7+R zEd43qpjE07)hQQK!g@99z|MdNSBr->DxSI#CqvkVs-FJ(8{qdsxt3Y66l_< zRR0@yJEW*u=JU^u#e(j~&EkGv&4%W;t|JyZtbpp1XdOyr`9*W<0~Vqnm7%-byCM zIxOEacTHGfS8!2M;o#ZIg1tx0Og&Qe=4hH7UhcEgwDgLYc)Y{=a5RZD#w@hhKym|K zQN~bIL}Xt?^3=SuZUxdT$s5&coadP?Z_Wo}4vLJRxOs`q;xLmNC+#qrl*$D-$YPA% z^ZcX()mx-vkyg-y9Jm!pEl&T8BL0gZ(#!;u59tg5KLV$R7*K{a9Qxpua%`J1@~k-E zAa}tQi^Y|&-VONd+n|x^`|vNJ0D4 z*%>y9Y*aIN1PMhUNCA+LI04hjWDUa*W(v{q`e2yrYsc zNTf#K^S?0uISk#=Ow;=VQJ*+M368wg49OjUW@V=?)#-4r#!+4N_e@$}vpr<|_z6p> zbV&Qek^f@+w;_tAVdN(6G*B^oh}wU02ZT3bz71Vn>EU;+PbB%YwGdr{WU0OTeox5$ z&i(bxi0WV$$O9#W)#l|XDqb9BB@4Qe5h4Mep{}V>UHocflgIWC^*p)!s>y*lZo&!2 zzEz7esqD;y+Z--2)n4AJbI@U;>CmW9+T5HCo2I1fRRg;_k(W}$PTofVSfs3s=V#2t z-1pJX#maR<#Qom^$hLsavcw$HkH#I5uFP(S3vbdb_STUX*CJE>X~xr}T3XxHj0+EJ zkVH(l8h2gqE})w4w4FBma9QSIT4<}ueO(WKYauy^NWv)9Y% z@Jxy_d%^mTw*UF3GyKv2ok}%Tz zku7zC<^glNEv?a2M@@wt&}NmN>2Chk7x`u8)K_tWI$$t=E(&tDoU*2H38pUV^Y zB*m^WCkoQ6X%Y_c<;NA6aGPA!KB7H$XK7F& znu(FMI#d2=1w-{n^S|-o_52+UHCauW1vV{p{50<+ijuf{m$+>z1dMtQXC$S)e9Y2K z^^|f~^Gj3zaV9dW2Q~vvu{I<6wBZKzQuz+KD*7YQD~(=}Uy#AQCm3h~ElJ+C$E%&M zDUV#GnWBhUVqI^3z#nj3*|(*pz$Qn@`r}X6H0qZ3O9#qlY>rPKb$*o%tKbm-C?DPM z^H+4Y_VWHV@?x0nWrHQdy&+WwcOrCS~2TYXbW4H?r#XW>o; ztxrNZ8eI6eeyj0H#LhI?cx>;^v|SFE++dRfgp)GmoqwF-@#s;;9`^0yFr<&3*kgIc zbTD(lHByMDwpYE=i1Q(dtmhK!fk8z;dGha-*V+Y8J48omMt=T}p+!+Vu&m*L|FDLL-Z5o2f)W9fIbt35UsXb8;yvD9mrnc_reQkX6Q4 zc#l@t)XU;bEMI~UR*J7rpkPR8MuaU6& z2uR{PytgPr5pufG8(v7>0I&xG3*_NQu$mv3^NhaES&v*HNZG5_W-AE+;>(xV`dQ(c zLRTMA5QY)}prVjo$^^ab>7fP40AK*4BkY?Mx(s_Blfc7SR1p117iIB{R&)$40_;4zdsd`T>A^jX$A5i z$AS71FobDn0XFS@M*-*ly?X0dR?8EvnaZRp`V6Y~fB*bB!^c8ej@^=>J z7JwKR8G64ZA-dV%7U+;V0RcKuqYjrN=x+|Qxv8mP#4lQ)wE53Oy)YH$CX->SAUnNKfBYLnJ@dp}ug*6>lj* z3t;rw`7p`a9yy7)%0r=Rs5i>V&zJjz;PA#V`!KbmyGcKe*>`41l9v$|CDIt7Av;`e zbPz1vhYvfUEycFu^OolhKS_6mO;U@Ok)vkMBLAMM z`ffY20FiS>@MzsYksCLS?7LRH{i0(L1xBf?qVsCabe!|iav!g@}+_>L0lBI;a?0FCT=UG@6)mc4(U(c9`) z%W{S@9tk$i&2M;B^7FZI8f2If~ZZ4cDQ=5Sf3)Cq1MPZV)0 zGgjm5>_ZO22q?l%RoN=|p+A_;R)OB>$`xqwdcR|}D(iqMJ^Y8s$YM4` zKE9soY7qG(HJZm#q`ADNXEiKXTvQNQ;t8gSo>~;7%u22bF&G#k9XaM6RFV>Zx;WA~ zKJLSthyUITX79Olm3@~j!{)vg&av9v*y43nG z*QsB>b#?o`b;y6DVd@S^9=}hPUrM8`*(YGj5Wu`nZoRZr_huV?&R+}$DEi;09mGMK^Zc2{$quXTou$jUHat8_h_*8EF-oGVw zj=mm~z%DYNjC7hok`H@zv&8x^(4l386ocz?0Psa0tG7)zl}of7@t)v(t^={lJ@NL) zxr58;>s4qb2uIfGZjhNcJtR{?kyTBEzGILf>cB6rb_82kSPTMy9A3FM)l@9`a{lq8OZ4By{-a(1T$Wqz$9zf!tzAm8fNt|9 zeoQ*Z7Vwf*!NW4#TWoF`>*k!Woo+Pa{E%|A03RO9MMm3Y1)r&#%wDe1@KeHXaCI^LR8uQ07 zA2#rF=9`kYKC~D!J}sSombq>H_%5@2zT^F@e>b<-r@Jz*`&U%x6!kK7cTXK#-@@hj zW@F7S{qt*jhQ{$l(hCC89xB(FLZzXrz}B9G)-Gjs=Gr&^G;iFHyLgn9hT`Ubc?fT9 zUlo^?X=v0*$cKm~=F|8E*GqpG$;r)8{y2fV13B*e5ZEFTHc;62Zyt@WI_3B31fQQ@ zD*dkA+p%bLUM)S&9a_rY80DnIr-WKs0@UZ+_V9tBazF>u}x$j z$u!ca`oG=@2<1Sx1I+H~yaKh(I3&YPA zCn`PPPiD5K3ZF4YDizv%`+l&SR)5qxPn9F*TR^~R{bGiD8_jJ}XH^y+3uo&3Q{LD$ z`mBNK*!Aa{-b=iT;rW3Dm_KLV*!Ea{$(YGw>7-)qqzT1ZKh~gs`xJFsQ&8+b zj-QI&^x-o_mTllX4&hKPx&9FW71*!P|PmGlzjgky`nNVuC4}9BY_!@ zuQGy|zz72exN4;*Uk%h9xajc-Mwm>pY9@4#NS7g`-M7I5Pg4p7uzzG8-zWA)|7eqo z)a2;NagHG=!p2^xm5Ofqw#ch>_mJjBxGIqIffXK6kOUru;Lz6?0

  • C zHTmPp)sK_hSyMo;*`z}sc|F>A`Z4_j(Wvilk=jngx9akBmopOG)0ib)$#N1bZSqf# z6U4iZoTAlV(@>R5gvyoPwwv#HTS}s;(eus9d~t7UEc@WL8M%Cq4sH13T4Gc8T6A^g zw~giAajbHZ45DBB#zt)Y}-r5)B-7;a?9=E_4XDnC8LHwQHD1x?ZIhM|iTZzI*6AFkeF zCC{+Ghie^8^|WRfLZthHTxxxG@S@A=aS+M=I@9-L_Lmrp zGMSb%^$*2-#Pl+u*7_ zx?`fpNm-W+EwA>&+Vux64M6e2CiNbDu3Op+#v36+M3;3b(Qoq3igt)gIV;6gc}Xik z+eG-Foc*G7F;_UT^ppqMUJU#VF*Zd)l=ssYW=LnF67gmU&4F&qnoAXopDy2*s$aa`6Da!%`URw zC4_<#?P4O^#4c*adrqcn2wcK zEIr$=oCW>(y;L^ziGcGZfA{J4cr+9KSY7&#Z)Fwfn$zyMJRZ0=B6&cY_J zH~#-1k&;vhMI~Eil$}C_Y_j*vrtB3GGP07rvUfQ4-XnV-duL~F-|O`L{C>CZ_kDYx zKSFgnujlLex}Mkdc-$Y_C)}=Mr4f8Gk!n_!kq4d^{O58Y&#_NAxL9ItU<_pp%-x|t zoiDb}``wDJY(Z8wN2&=8aVec$chq8)cb&5y+1E85CrP0yn;nqcoa0*20J%;@x09(@ z1^kxNmy^14(TX(hZc`jkkjJWk1KzsNDLZ}`7a_4Qsq0cI+K74Z?EJ!(^rcRKC1{II zsbj|4-fErjXC2c@#4kpv6|Ae`PLo*?S_YF%`lR>W)bGYbjl}Iz;*8wN-#@z&-JKos z=fiaq;qd_Eqvca}-PhTKL!D;h$>;bI?iGO@Z%-5eOydwBEw^Cj>=Hh5KZkI_-TZwm zrXDB8TI_YqB2l_eCUyI+44xB=env8!7+J(?uS!*^#;r?4y;{_6Tu}lm;)_IS`K-+7 zm`*76KK3V1#2d`Ys@8{yreuV-y}K^8d$+@@M&pA(#0dL8*qihXm@ycJ#>Y#UnwtKD zD?Ml*;%JC;Pf2%Yd^cb}!1|e#$e=Tw?rCK2T!r4lEF!<(NRECqL| zZ+K965`Kb7-QP_DmQ4Fvt^GE}g5&Bltrk75JbWe)T4QY|T#`)D?tta8>r zXS>J9a|VX+HA#Y(5709lk#!tX6Tm?*}m66Zj=fwVWX|GshP5%rrO32AhK5ad|sH)ethaz7o5o8?sXBSe{ml z+e(kzG7CpV?G~SD*xwA6cHpi`JDBoKA87BuFLwwUd}kc0ke4i;O*CTvEJ)$R3}@Kp zUBr&OO<_)-gjjUpsRq)rYV9#sO8cgh+O5q3XgeNzPwJ9?$f~>>?)d$n>S72tja7Xw zUKM}Xrz*`)c}t3BPv^rmb5u7c*QFuc^6@LwX@?H0SKwV+DtG9O4HVW;7C8=&NH!$= z(cfs<>m`#Jv_P?s#;Z%H>4hIE4huPR9L#yFI+ZllwhPmh*yNs*5oQEo1kk-S%V?$C!0*6(r@1(!W*yjG<@H8t1xvoDf&V{8nSX;pF$4B<{S*pNmIJjCs+>_jq&? zS_-ab~h=QaaoR5ypqblK*cyjBl?{4TBJf=;{hKP?Cp#c24~ zgO}b2OJJOAxm_H%!9h0&h#=w6)r!-<1ooO}kUTVG$>(O$=lt@xDSl}|bSjQb$pF8_ zBPZ#*l<59A@p4!8aN)-6Kz-OSLqMBQ? z%l(87zGfhTZWi;fp}u}_)XKS*1sX7C-%kVO}Xy18LswX3S{3w5Isk( z-sqiqPuBS7^+;iqSF7dCq$iCcyP{cTUVxUdEWVlY;#03qogPx>iE8?x2@AHq=(afi zd<61-P0ieFFTAv-{x$-he8U~Xf?OSo!jKgTBORzW%^$%rz{n`_{$AXKg? z%qf5K@n=yn{G9C9m5b_@rx~u<)k1sdjl8r+SWyt^ZPJ)I_{IL?4p*+kTW!lU^W1_5 zMWRgYqm2j3Ez)VlNpCd?u1GG)4yLZE4+gD&s6b^2j+Xdwrm7hznpJG1^T^*5P@~ep zGo_sZK}7*q4VlQdVITe|WaWEVE1L#yHQs5aDc#Fj0f#H``p^t`jp8B+?qfgd96@9g z3YrOYrN;y;*UO(eywmJiRnx_)6fHtb9$8Zfn(}l_X`0Orw=fsDJe3hYpvqjpOm|-R z7N-$8ZHp%CKww&KS*mpaoXN3(VW$JwQpozH!{q=9=Zpyhk;D&#XrakM!zs~kdZo#m z3W8KfDT8l$=N=i1f_BIia@Pe%8m2ge^lC^x4Rd5`qkcDUd`C~mF#E?8017@w3F0w= z%Xz!mB)8==jbu@k0ZX+HOyUI7!Cn9d{aKLk<7my)e?I-&LfIKF7!U2AD1iR$oNQ{S zP(k^0Z?Vs#=T$wCsF=HTvIVMvCnPEChi}gzvN-W&QTwC^D=tw!+Qq0qAbJ?7u?|Ah ziVG0HZH0re8vquV`}Sl3-XQq+1rF{dA(F36^+_UM?dOAEjZdaQ3J@AY2x!=GhY2{1 z#v1lLHSY5Q!9UvfEm6wA#H0s}2tLRHJ9p+00C`^NueW%V%!0KZZtVQDT1P&kI{Nbw z(R55tdoyI1bn}cChFdCbEI(lYtxJ-{Rn?TMp`-Paa!sZJA>D#4SGm8b*MC~O8MqK3 zBd@JvXb{{@p_(Hv&7vsYFoN4ROJx*H_O>I;NF`M?^iB%5NmhKhsr1t2N1~sB$8DxH zcz##Z`B$KnsG6`>>X0+F+|oQTYCjg}2H*%4*xkRy`{Iw@S7)cyol=D2+1?{X!;=dR z~U$3u- ziAC$Szb~Jx&HASGV{rc0i-=*XqSPLrnR9tHi76)*ZLD9p~eUb-iF( z$H0XN>Jw;P#AI}E*cYAj0~P0LZ4v$B*u3BW;5c>PojI#*`P5-w{P_NNi3<=ay1w5< z!@dDF#t307)M!Tz$ODDqK=9y|Yi$xv>?M$-py*Bt$Pk7nuP|?mrq|$kD_9GFi8cU{!w z0R2fwlK6m4>}B#HuB=W`dRU0w$LeFfN86+P6Qt+8Dnk^l3%NnmR~W+Y*YVO&b1GQxHc4%$Bww#LeQ$a=s2f4+B?LzI$5 FW(;$2&%jvo4r%l zhZRFdm!=&Pc*0^v7RFtgJpB3Z@i)ow{c{FD)`W?(-z-a%^VE_Ok4c7h5eMK}(QLpc zWT?&ZIxQ_=%N7A-v9%D)OEcngEuOum2D4Wm(<=?e7#k2B3skIKc^$aoL%iFp&DU$g zq{*Zr@1W__7e2azn!9_hhm3N7z6bg{@#odG4pqr#T7yeBVKu_2(#u%RH1D@?p;$;B zbWFP61N73$$_h>10s<16LWxf00}oFV5S}QT0i_&)eu3x3cJQ6%dXO;) zBYVPCO>yv@l`+J#@&guDFJUp)=s=TO&%mG$7_bneCM70@hxkH3 zDGH+ZOF+XU0gROXc&QcNPA3PfB`AXhdveuz4Li|nP@szf(N7Tg9FS`I1p?!e2j4@Z z^fXai<*u&`*{`qoFh^=g*%uS9MxNO};J6sas{JXn{#qQ@S!egN1bOO1D(Wczuw^YN z5&2&3$AMB=kF*00?eE!aYy@(33WjSo9d$5Y$q^HYlUJ-|$9ACM0wR|3Tl#PD4tzik z1#H|iWqD8rf4W>ymy;j1bXtXXZh{rA(7x>-OtnknBSq45VU^LqeL{RzqF2ta;fe|}L1z~kHVqtNHxDt;CJgx%_< z7I?P{c(Me!8>74(DlN=1oENs7YnCunIeYt?qP(})sIk<|D=vDiQ>&6N3-JP)+YkR* z>p++DP!265=Cfyo4U(6XlyrW6{@JZmF7xr%fcwbemu&FHkL3Bt0N(+v0J!lR@Sl#? zLZ93ih0Li*1>Ba9+)NNaHw)U|R+|eMoxB*ANol7{TGu6sM$0SD%_8KA`t|#JJy^dP z@~y&f1Z}IsCDem1YsAhrTo&KJK(O|6H#Rk4e2a)^0qs=je2Dm|Km=sOH|loOHGL(C zx0-ldGF}g_St~yH*Ml;!6<*6(^p^v~GN%2w=$#Apaj%}Y?SjCyNoQe{5~+h!Dob@? z@Z=F!xFTaG|F&Mm=6=MhMRUEOnu>()c$N=DRBpt@%X&hCdY_a{K9lbch>Ed=-WR@8 zFvnHE@oaaP$4SH-%1$|<%Vq6N)wniXv}4gRx3gz-v6wv;@w?p9;q;&*!1*LTPBy2I z_z!G@Xcr|ssSTGTQFa_?a0N`-Xd#*IzdP5YUjs>fCy`zENqVbh@7-*?)T(T2)ph!R zAWC_52c7Aq74f4Ej_2AR-J;Jp?NLcq)m)c7{d{kwfM^$enT`ey0S>$a5Y(R3x8%gk zYOm$Pa{O8WBx}E%_$8CS>*KI`3+J%fOHt9wkOrs)8N-457VPv5QbA% zl%msyob!Ko^ROr?)-q%ql~M?gf)rLpW^oQr!*K3(Z66LmF4+*+v|Mr2vbYa04FT?r z&J&7s#zy*;KrVp}d_gEC5&@Gw1_VqvwF^ow9_G2I$(Numtnk?t#ESk(Agg9n?OR_E3x>e$)Sv?N0MjJyG2Z@g%pFpzOGSbeU)LhtZk z-$`NAgEc?zcU!&nVm2Rc?X7pn=cGyNW`hjW9OkPM{))dBsg5KxOL<4+ZZ6TWvxk7= zGam4B94^NnAc$As-$DCoPoppEN7*~DKfZRe76=MtP6Om&dr%_>d{Iu*dSV!^LX5}4 zW0?$Q_in9!1=!flp3EQnzuJ$;I-M0(oz0s4IoP#5);ZA|FJ*BmrXu9&f&F`)bU5fP z_jYB=ljz^*Hd0tvSWls$RFKtwjaM3Gh%k>k&;@T#LikB0=657TSbV;E5v@&l{H~B} zcVIi#`ey?aiMCAUuc)9^A+KL|sSTLY>6o7qCSDnjuXhfG)^gX>6(zjdeGK*?m>edI zcN5S9QV!VV-{9;KYjuVeLNhSnL6tFR+AM2uqHAT9`CT~07hF$V>jI)J-d1!^wCOmb zICLgtyfS3GQ7ZRU9}_dBgu4yfh%x+Nv!LQh_NB!sdZ?^=B(nUcz|cQSF|nxRW06XZ zk{I8+&TO))TFm<~<2lmwGAkdJh)n3|>*OZ=Ut~NdCA4xaNJ&xRe^f(%J0aV8Yb!>l zqdh;0{~fD>NUWi$1Gi%6QlqWDo>$?@va&AK2f8)0=Z}eqlmg;Zvts44CBMGVKam~N zVb$Wamwc8^X2N+V-~Q{Mcd~R=H}`&$cW)(UIyF_zcx$DCQ+is#*3>y^c)<+WZEd8B zXjZRJO8riCrFeFm7tlz2NyOgX!E13kQq$?)uRefNbFva;E+O^N=VgDQMn-?7_VyRH z0X?et%l-@Uw{LSV5p{At6s$nR7Q{Renah_{1;8BDs}A<13Kq$QoDd zk5aGuAL~)uoF9JKpr28T3SJ{~!dQEiAYIzI`rhU{%Ug0`gB9`wNB-aKCnW|e&$8`vZVJM7)t^bv8(ZsOT4!*sW;8EuHG5q_o`_Qe zm13(3Ealkw7E=O%-md$n4(U(D4-!0o25*Hw%?e${0#k^dg#{p7egK@01B{}*e>}TB z9-t3i1T2Ezpib7jz=c$K4o_*quuc|5A|I%ii`*>}Ehs)<%Yky?b<38tp1l26L71Ug@p&v4fd+}?z{q>&q)RYc0Ba|sGXG#d$# ztz760#~Tj&t?B#Sx#kR@Q}HYrUl~8|w3;Cq!G9!h%KGM_xY+E;+En-XYVN@^#nTD9 z(Cq;ugnx@vzC|q}0<|PhdNRNM@=dYZj$v1~p;X=^WE2vR3B#R($p0Q*P@(!XsGt`M zr*A8Ow9Cw*AlQY4dcEo(2Ia(DcF8321gjKymBPn{@jN95*Gn;NG~!T7W)-$ij`qoy z_Tleru|F+EDZSk>cye-NxU~OC)uJiiE*>bM$9u--OAnX!6KCvXtIeWON(yRsA1mg3 zFsCfLzz`eG0e)`JAEV;G7EAlREtF|`ZL%c=h#b2OOAUeZ-8+87Oj~zQ+ne}wYdGE< z@ot|yC|$SiL>E|NuN>MVB&$!^9c*ggC)R=ld!7^(=kx6~OIRCr@83b~ra5>Sj@*o~ zo^*;|E180?97gB$7F!TJ-!P1~+8!L{Yfk+g`BIMn#q<5(_fx&MG4pK5nQS}XjbQ?J zk9gPAUXJdqoH@}Gr{9Tn{=>dyD+~xf;>WWib8%7vSqFXMjn}IQ-Dej%xR2v;_?uJx zDPNuDYa_zU52G9GCIMFLup9aatVouNWL7+yxr7Q$*v0{ewQ#|nk=2_BKiP_%;~t^p z`eEXg+3swAuGzKfStbfb?It(==!pZDO}3#a6R%#=#DiQSzRCqB|Fo*9dy<+|l6*V< zEmkfCqD4R3H@nG^Zf8}ZP)zIoNy2w7*&;&hck*y>0k9|8@ozNpTRBg0L^x?`otPN(?l{;7i>_SzAe)k z{NsaFp26;_;r~}OKGgtCb-Qe-oT3AVdv7m5Df(2%_Hch0}v z{#9Q%cm8i7(9m|Jb3Vo;VN!YyObVq6+sA0iH&k%2xSK~qw$vajAq4Ka0+4`EIByA| zL!^-wQyXlqfE~Pj`}Q+82rQNDPosiZ8tr05V zZ7z;^Y|=YFeSBxMuUb)w8iPS}b?J0ToT27tPLw-!ju{xwbYRS^=CU_9?s~HRGc7GN zF0O06WU31t`2xg*TWkN&0<)Mi=>lrnyK1A1H@30H7g^+8O4ksgEDA%=C;&ZDD1pGC zyJ5TwadG)J?+<`v7XaVPhGG-`q*SZ9W>BU$?k?Aj6`NEwyTMbj==~sGj-oiIXpTT_ zuWk-fKXW$?mpuhT2^e;Em%6MBWGwLknz-~E|3&2zgJeO~!S(Y`IN+-Q>26Q9GRI_=H8SKW2zS86gNKLbq`B0!nuzTRd=Y;ZPgUK#)@&_U`XzDl4sAt(lUn-x?+tsLm)dj1|8?Il~ z7Xpr^`1zMZgO^b)f46>|Fs}5w4WEGE*wkgR=8Ay=Wku&r$yKupoLVHw<(otrS$>*$ z4_^4^9e9e1iH($W+uFK9cgH8Y?|Mq^m3_l&Sxp{;(vjKf+U)&?EAh7#enh$~iR_w3 zs*P4J7mf7O%V%=vFiIF)uB!6D8ci9WtRlRXYhvDNn0MddgroFjT-wXtmFYnSuw1-91nltk?HdD*k-+y~zkkOdSHMGhJ@ zt}NWvsA=;4tblyT5t$#wM|dbcYmL`3~vzVGF9Gg3~39xtiE1+@W^7LiJfbRBQT-MZyQ@}{9LZd?e`NKD9I)ft} zRn7I>xwK11)q+3d>J>P?6Q;-%xSoQodm_*&aPtH+Ib1{T;%9b!YfA%XO&b^0#E)4U*5!@oBOL0yk6?S=rs8_K3%ivdNcU6p4FZfN*J8!Rbqcs7q zN1GNtMC)a39iGfZST6YMBeE&&xcfB}**?nt;1Ft)0ejz9EZ?4i$<21?OpQt8D@0Z) zJ7D*x8pU+?4u$-+o9-N@ViQ}nl7Rb4`jU-i>CmbEXn`&c^v(B3htZJ@z%oe|)m3F8 zW~g*oCI+=<=D5mHib?>q%Vogu4&KzIX5fu>zj@KyeiJpPaA|{S-dXO6dm*-Hf)Nps z(QVOdL#)u}_;-G%4-O9gu-x-tr2obUftVt9elAw-%GeLM$cq(jlD%o_SV0AYqz4Tm zP9x!lk7OvDTHQWA&*0zLOni};eqOqC<7)03ETOOXdFQU7Q##!<)0s6oL}d7Wg$!<=T*hrr2LC%QUZ?|mx*S5n8O3Zee9^-2hgp7i>~`>{$%0Mf$22NNS__*UXID92 zSU?uYJMEnPi!XvhKF~WNPVr0s(fa=PT+C4Dj`LJY%jkKH^=~a%lb-Z&3f*oVbI!?* z_{S43GwLK(j|+Cqrg|b@zw5V(EpXMKk}Xo1tjwZ)IjQj@ z80W*QB+TEQe$WR(g7L>IfVwfG9s6XFS^mgiq!25A-+$ z6na4B_P@vb9S-3f5bj3Vr3iG)m!GRd5-_ilecl{f|IB#W?~&gMEy6xnGBOOP$iUAS zra+5C(rW#|bW+TCf#Ik?h&W2&G<^wYm?X)v43n3&-*3pOS)IFa5Ww7SQ4`5>)_jpw zyrWfmBPj&V^Lr0smwO+@&Enm%bEyoZDod%0Q;ZE$)#0_G7GSp@)XEf3lzuim;Bmvq zD#Gxhl8~H`CogtVAma4bv@3BtV*$S_-I+#{QG@iDO~UEfaTxh;=U?0R5f^_@MJjFY z64Px|?%u)~&9s-)ERD8!dKZ7&--|X`G+-8#RA}se{eP-Y8mYKW_#hmBA(Y7<2#q-C zgrKp{4zaQsdJr^~ty0{+?gHif!c78J(BK9Ag#i&-%!QWi8IE&(T#*M<$MSd?2O8}} z!xH|Nfq~(F04JYvCOG$}O5*8uK1=2x{8K<10A1lEIH9Ii%kv(*%54AdaO$9wU3YXh z9yqB#tVDs$|Hw^b=YF>|xYOfQf-(c-si}0Ik#=iaI zPMcNBA9&EgipIwD=uQ`;g)Id5r3v>eL= z1gq8)8e+I@eBkl0HC@L%EO@+}3@EVAKw$-KuLdR;)p)&0Q)S)zO#D#EVD z{I_1)h8(oSH7XO$a&qjUY0+rZ@WaN=?s82b`s(^0>fO7jD8XSfAG6gkk|h3KxcHoz zKdSkJlW^YD+7B8^59Bji$ssT6#_QVlLbplW6bMkfrR8yU>;=wqcL)+92Szvs27>X3 zEdbzMt-l|GPqF&C7Vi^q2jF9mcrZauNR(@^*{1V-jr*hI0hm#?>!mIbXg}+dw|?6# zw?CIo|7lB%N|70%|XOY7VD+`y`7i&?V-uo&OMA;;Ug4+%#E&jAxUO$?xy)UJM}3l zh}*``YDvSjt02#*T$!z+lVDO;GkozI~fxdkUD4kzx~)188t4FQFCd zfKrA>#|I}Td;4c#gku(jj{^1#pIS67?K%X2>Y;&yV@1AlX?X=jlGjJJT-CzP#ss~s`gD!u@IQvZrOxQ5d1HbPKfq$WV;#KS zc?2#5-n0|RGc#J+uM9>pH|jjkqKr4K!wwxz@Q!QDIOJ(u}KhVU>GkAFa5fMvfn=1ou{vAiTHP z6UJC$ z;^ACUFxE=vIBuV1bFw+LC=(XC&c(%~CZ4Bijs~S2G9D>Mn(HdO=X5bA-x!}f9^Ra% z;9cP&PS~v3wAGlb-j$NPC$P+h>^8GYkVWl(vdvW!8#=F|&~=*RyB#p}J*>uXT`X`D zdLhV@1l1mq(fxw`i>g2>REeYi`hFg{uYYmz7oJjmsxL^>-8-nG%vGN^5}4Dif~q4m zR#hz{fmpdTT*VZK7Ta~L&2j|_UDRHMhnF|ftGUy~X{7jlWXlLwgqkR7m*#Xcj)L!W zh-H~8N2k8f&HC*ZMx=9%jQfjWEUF#;X{dR&WpWLKfS5?mB;$y$ z2s%b)ojp6vLc8DEj-W1lYOdk7<{~H7~F3|C*Qn(3(d` z?^O6FT=jKb-#sSoyOaZ*Nq;_hK6#@0Z2v^2eB#1==NMYAy@WD!MBfyxeFOz#-+GBI za6t!1*xdKiz_vuT$-%Gr{1ZjDrE<|nDNiw`2NJPNHTNT0lq^hytIoK0+aKSz`)m9C zuH@DcnGA%mmTur0mwS)*7E&Upj~omqg3`-Hv(IM8g9;M!DcO+5{4}b&Xv5DsW%f*& zBhDKi%Zpgi^z~O^WDf z2JJPvM}y`z9c)ZQvgux?rly8ySxk3e2lYdQE~r8=YvEBLI#ulw$z?`{4m5&Fo_cjS zZwUsRcBCcHzPG48@&=wo?B5@t>P8zl&~>};t5<~}-4+eJ+lGdW%+CItNcqo*otQb~ zoKz0)VYJkWs^)b2>yBwKD6jsG=m!0Thu#)MmR)x6hHB1{0icunri!n`8}PC=LwvIp z>9|lg^BxaT67BCS=;iNePa7I3s;L$%(b+Y;LDDdKxt%V=NtJ^9|pX5U8raz7&U0CcW zo)!P-)X-JkT?Sa(fU0R|*92rEah)DhrQ#i&NaCZ4Ac3jexUM^lsLX;ptnW#~LhYaL zB0KbaAN$NqUonK zp#i?TpRL@6!SV)M0aTtjnhhJAjC{@eU^DxhAw%r@uoy> ztAKSY_7_K465UeR@QBZy zD)?JXO&Z(Sug+c9m(~8onvnQ?D2uD?^6lDV29cb*ZA9LEvghXuPGci^Pt81-_dA?O z%pS_>UpXWT*14cp!dks@#`*B>GG0E>kOlq*S?}ce=A=k;f*7V^{;&^J$@tcR1uk_4 zK?Ua;RNG?sk4S&ftCU=mVq87SCPb9A1UUrkAw|;*F3#aEbUQ5+{eVqI{pXF8&!vRy z^q$qy>2gu~ulV6-KHU^<-zyCA7B(A>*3Ng{)n{*nK6z;@2u&00gD&M)9awJtviG_Q zOM*%hAb^IsVvQY|hz&4ed{yImhBlpanZ$rR&vIpe9)tkTAxRO`u;>6>K+7U554W_# z+S})sA(NC1$TCoPw{Udxp(m4qr(0Nn7qcNf0Q6Af`(k!DnQ%~W@bSe!VpIr3{KfhC z;YB?$t_KPy1Tqac@Z+G12T(a_4Ma&Ppam^giJ20l;sv_?Ss~C_jL^s=YJ_BI;pJ_+ ztM%5D$otv(?^#DLn2u7gwUeW#TT2kaV2d18rMUc}8jM^wR3sZSO^NdH#L%uYIp96=b0bUd}j-!^4Z4C5w|R z&*ru9*tmmohN45jTQQThU+a&7=J_&Wo%x++P}55yE*I;}4%@U(!#ca)dj z+0Noq%=PJMDK{-yf9fvF63&?U-sX)USuxl z^#$Ig(^;&KPfj*d@E8*$i+y+zvSV%SD3@2D;O2HyidV_Cywq_oHiEavOtMaYcpEh& z(e6)^)G(;lUtL{TtfCWsK@0zaVXM&o=7#E+aa&ATC4JL(GDW>B$y(ZWOY!x&&sas%T*jmZx~AjZB0i>lzKS%xFu;QE3_C zrm*^z)bF$u?UhyQy2$Qr2x1*O1++49YV|$pS?)7=-D@(@9JfhE_%5${7#i zo~FwMJh|)AQ)w_<(3{!e{KER<@wGn_za6TWd74*C)A9%>bzbTVJ`^QyPCMA0p5$H~ zi9u0tDl!`fzwQ{g6EPw^8Z_ec%cnv>qouc!{lniJ(xEKUswiql=fL9N7m0`j^oE0ij@@J^dxvZ@_!Y$rysVs1V5;vf-T1C*J_E16Jd5xo=!VzkJ`x?R2L?l% zxU~QF`iG^rK|DgX_D24diV7KQ_E*s3)W7Bt+yKs{sKH9uDz>AKihUJo$w=0%aAPj=L~D@KAtQ+k|h!G@lKtzx^e8y z*1drj82J||CIGtRBp>e3eay1bT0WX9pPbMoS5Nw@WK0)2IrbDP*ORhQJ{GKPj4w%+uU$IOSmP4KwQ{|_6lUGB#(B4$ zo?1Y*fw!UD(yD*Dx&=gC=5fU#W-WMsVu(A&omfPdQkzhvl*sLx!7sjFapxccF3~mn z@s&kON&1NDV-h@Urh6`=0kc$e3{U&?XJ7amFuL)N2GRHiV>k&wcf#M$twFEg*Lzd9 z6^GYDSE$i0WgdlKF)H-X-W)HgDQH80(nrb2&1>eAE9jxaF!@&MBrFKTY|8>JqKCn+2Epq(ZLnR!l*^0YHCRPieCKe zyeS(pc#;F6L z$l{bUy#*lzbKC1AnM$)MJ{9ssKJA&j*bS7~k+^o`mC&Yr$L3d;tF70MEQ_8I*jD`I zb1I%Fz2Q7@H@Z>XY3ofihqxDV(kxq8Mr@Ya{=%5vp7xS`N&Zf;hJ(ST69wrAdl*OI!7CI8bVUl z+YvB=zf)EHD=H3Ji=eSWOC+yR3XFH~Lnjw~b_Rbe^o7vkJ78;ve*Z2CqYC56N^S@; z$yO^1fdVlIwv%UW@Sq%#R|4H;c;b{t{>bEY*7mr&3sN#-DBat~92ksFDLY9`nF+O! zPisVU>$M|vESv$o?S)H7^(t__d^MMfg#~RU2VEWahvge^2wi|^>Z>47z=6cwcjggJub6MHe8aVm3MjbWO^FxI!^0fL`coC(WAvAoJ#{Grxp|i zn@o%I&vRSo0C z$V&kgPET!pH;4O%kY<14eSySZg%-q#OqgtonS+xiH49RfC&lNXLh8$~Z2 za9TTGm!rE+gG)Pa4@#zXMot}8WoNF9R4OF0X^fTHv*HQg$vx)#VksWISgL;~@2UF^ zWgeYa3JiCtHM6KnUV5x;dy%2z?V2A|axsQeTf-u$yWv6-dSjvNv!R(Cpjd8hq>B83 zHa!}u;K@q$zsf{i+T=asbx?$(@xMMQEy4Fw6b_*pjMEE}}b93oQ4a9^+h|N3`a z0G~n#LU;4yU&2~-wuo1h{&-670dOxQBUFnH86O`lGQPE0bwDAOax+{^L_`D|EfWcU zr!mvTyQv2~$hx?st>@&avvU>YJL8pR&Q<4hpnTJ*6I4ckx}DEOL40FvaAea>^>cd1 z2QnfK?+;1pF8p$?s5*k^z{36K%>Cx;xAWU=oTP}^_A7D_eB*iCXDT%Ddjfy11b3F^ z+`2fLx{Nkv#+Sq(rbGPEOhRkl^+6^=cYK^3Fz%;g%Jb6>#|eksAaZ;o9QRB>^Y&$K zj1III*6WsJ7Y$eIoA-h3s*dVPwXP9ajEW@QDjBtU1tD^>Glj@#%^Y6LTF&(q>;(=> zx;rCW;X@g0d{6AKP=Q3-TjMo=I>EbzQ%pro! zlC^{ODgd=Dp@HXu&4jWi63BK}xLFGw%S%j*Vq*9P4;#)-mhx-$vRsK0Wv~|{9HFE7 zF!VB-#;st2r-k=`Sz23Ln=Tw#Ob6Crc;xk$e>B;3$V^9VD;ugj@;p4?uNvn75Pb_c7%EZt!D} zSnFi^Y35S(h0ui&V%-%~#|S)3u(O}XsLj5K<8PxIP+5b#hA@(!#9m$d{tphv=)&=C zCfBzyF)hglTinbSV~{|1@ewbX-^<9?vo*)LV@oTUXDZ-?dEFpM?TY1vux=iZSfXX-=#U3q-e|~>_lNN;wv%I0 z)Yw2!;@h(yKwI(Q$uV){tKql366!kIMPd@fYB>17b<7&Q4_J#2dkaWamZ*Tz{ETZq zhKYurC+4ZQEzgplfD8N0qn$Qa4XJAY^Zf88NcYc%TsH4F@=~Fx>uk!-l50eu&8Ac{y#;^3h zgo8EFAuJ&DuG;MrzfCkcmMj^^7YV(OooP>kkl^4t2>bQqt0-^NDS#|S{>cp^5{KLZ z#Vn%Gw%c0}()>w9{m5$AXxF)iU%G%Mv~6xl!L7+7XI3p=ckq4jPD0+OX|qnjB|gOz zS#HM7&o9pqR+mmR zY#XZ!j0kqPD1>s{NlTEll3DdePvVA4--q|DIvphy-TA)Wr87~-x3Mzu2y#CqW#}20 z8dv4JR$sUT;J$nDqtCBNhdM3&T7U)#!~`V#yhcQb{Edi%;B9N!Hz(<;P;u3|g_Gc@Rk#j=hv^@xaRxblH&A$IGY=Bw!A=^V9p?V(6Gh z5ct&2t-GA;FF>Fl7W!s_z`Pb+Q^;g0-EL>ZXzlJs&&;;&IQ5E*W8twN(o?hOTumqBPCb_3!R}fTWF? zaUfL(V}uZr%t9eL{@@$O@fzu(S`uyB1KqLOW>B5t?Lw#^d;% zxLSfJ?a0Z2f($zUh4FL9?0oiN`5QW?n>Eg5UwLW&ou*3@{NQ*qCf~*BPFDvS*$38~ zgF7dk9Nh`MBm3e@KqCa|4u3NYd7@fdUn9U?&pQ})nXN4*| zNq>Rdl@T(lFT^8&lS3_G6zc}uF%YboO@8|Hl34(5%l_Cx&PeS%QDQNy@Au1@0-`&* z>l1V`6`nvs=#ZD z_8i54eILF2lX62~Bl0SBKgz?_Ua;pBt5vc6x|0N>40!~D7KU&}d+qDzz=)ENd2Xo+ zjh?UE@4YekxYii=M1nDt0fbhO|;tm`{7WfD(-riT0=(|rwT z1HEQSC!g)Q)2?ta3^Y>Whn(0iX53phNW4n#mz>)a-S_WF|5kp6d0!%B{y1=NwCujW zEJ1uPNE$4Ecj|YoM>ll%Y)d<&Qz%^^TwR*1rD#LZktUAesLw8{ke2e;|y?TGg-*DDJjUekR$G^?X{!uZ=OT z(Ln8Hz7Qe*80i{RN7n4ec4mCTDel$FMTWX_qFpcDi<$lyx4%>Kc@8>ZONFK;Kif|& zMo-vR#ZcS8W`TB3oF?V!@9YN>9p#>h6XfU(cS=x^b8&0)?3S{|c;xVx5A)4k_*hSI z;K1JmIcTte7m|YnW`WMUKeP6}M9Zx?Uy13?wYXbI*vkt!e~;=YFoYNGh1KZfC^8Ze z#i=qehKm_;61f8dw5Cx}Uf$k}l$e5oLbl+tXPrqFQ;y}nodJ~eaz#WQz8?t=qhAQ=J7cn|Bx1Pt7V_5TG=gZ@5?r8a;?XD z8PJSB7~dAj8o1MU>){)z9zse|$s(?6g`+PF3O*5?Y#*8KJ+Suc=%r%($Ov7f$;;LzK+(7o!zBTj?uKZqu6_hTqpXMjNWJ3CEw8NplHpF$}7{FIJ%^F3Bur zU?99T&{&&)iReHhCkGw|L}tZfnI*;24_><`c~tngw?^Ig)%hsY416t9l!jezyd^^3 zuscoWEwwc;O>r;r(uQhxMIIbE4{5qkxUw5twoXx*pSe-$F4gg5AGM7h_Bwc0+#_$b zZrHP{*|MwHTCn1cE4O{P7|eLv1QH6Dqb?qhT}kH4R(Z35WTT&Ia}g< zJi+6ohrcp4J9U^Zg_F8Ogz1Q>PYe2i262@1br02@Yq`)BY1|6QHiOB2V zl>R@?)l5PA1s?Y=@ex07ZMHqd9nW&Q?y*( z*>s)Vl5lqZiQyDDFqe7N+xwJ%R=)5WiLjokY`L@Zlj>JLX=v-QaiYdwq@C37QONYq ze!BYbS7%!+Qs(Cr6?;g)w}h9WzlXrO@;)YGiV$Tn_t@JQy0z2#Q@0r`Yp?EgY zE*0{|>&?{8<|Fw{e&K)r4OEq0)e5-7_HY`D6F&FV22G6R9uH|tOk8u{y-TsT0w{Jl z+y}d6WV(hVNcS{_lr^Meg;OZpbXA{WD#^f4exS3_M!;uX3q8=@@p1p1E?xrBWI|ux z>hRmED=QD5a6C*p3^$alWl0TagqN52ww8rHmMvv&%cu7^)p=(12b{n2IeB~M!|vlg z7Y!i{^;We!D)Y2F;`Y=Yu$!7>z1>9_d|m!-J?$$~ZDmdMP+3A+4sImol|^BF!G_73 zk=@6?m`qMc|Fi}3{`txHMwC!g1}AM^$fb~RE&O_sS?FyS)MdnF)v(&0wr0iBM+Dc@ zFQqwdkG*<@fq19RTGX*cv==8dP7q9{2C_kGhBAo26S=>-bO?Ea6}WD`GI>mEa@v zsH2PARl=)?8rVY|tNd>viJkK=ZX>3n+8R9gMUpg}p!~~+P(n4wKPe+HoMbMWzv&Ff z5p>3`>vm|ou%qL@RdhQ|hsIsM1ZDNNi9{EI2hm;+D=7MOL5dI@M@%RqZ?Zn(u@w^J zQNDIbh?}?au@X`KBMa(JoHqPMuL%1=X4ZKAY|bfSE+hr7y}_;*P6cpi~qnkbW)|9K-y z?LN4+=3x14&3ZA1xRHG37ayOxig16Yk+zC%=Pq{ zdCi&a=^rUK^c?GN1LgS*G=Ec#*)>u^cwQvCD^T8f^~;fZg^i@#d-M9?K%Y?TFQY7+E3w+A2|`zloy9M)u0){?e_QaN%B>} zW*jiXUA^1BG_RNJ<3)#0_>sErF)m7Vjr2Zla9+$}(Ac?Djx{l}n3E`M8M~KHMD^)u z@$Y3Cuk7jaQ;_CuDvl9o@O~c5qvN^DXMZC?)0G=hYxE>3Bjbw4{b^A4Gy(AF#?0uy zf2mBRUnGJUp=W5Q3;AY;P$ALym=2}dd!R057W%9Ew#hoqr&gT&72W$X6*uR<+uBc;4aBX#QeUEEn?E6a)SXQTVBrog%~|t+JFbS?$jOb{0#7A9E$bd*R%*_=D{tf zJ(#JW1VUR`Ik{pKoB_Uqy@JbwgS=F-i07{$?fZ&Kw^VBELiVt!LHe|-HG+!$3nTQ4 zdYv5-Scnldb3VIW`3T)^De?LgWdp?X&_^?W8V1z^`FW`c1=|Y{h!_fjAvd>Q9R-Fo zw9~X@f5!HTrxa|tZ9gPk5hM>wRCn8zrXK%wQP6P9U+Kv+xr+1o0|leMhmw~a>e^L}_ouy)MvM>k&KfiYP<;wDfv%@{z2bhO-#j7$ z|Nh#qaDH3dEvi;x630*bnlM{k>}>6=J;Mk0YIiZuo(M+vXyv`kz>%?vyv#KLCFe`Y z#L+Th#lHg_F{P^?Ut~O78sM{LNb0woT&35taB~;iKWckTo0{PlcUt%53BO0IN!-cb z45FAjI)z_1Yeg-r9OYhGm3>uF4A90v&Hd@R|8JJt7yiqq3Uj}xZ&|)&+1P<4wH{*o zI}X>rs_9CrT(WcOT+=ndO}f&f+JSwa!_KunmzaTPt&!1JOMxfATuZuJVMod`p$=oD zyW7FQZCm~&Rr1j>)9-0++3!m-f(4^VyED|G#SpNy=3qd(71W#J(`heWguHoE+VU)WKy1Z*v7o~wki38Ye)$i;Fqgis}JX+ris76ClQpoO=#{vGIlc7^FYa{e&L~_N}W}|veHmH)p5#X z<3$Oc!Tc~@l089@(fm;igKnd@({XCwqm59!30vg63Z%hWLzy3jWAozOFP7r<`hI++ zlNz+;tMIu=F-ECVXzLN{4wKMjD#d{h8(AAtS<+g#4^(+P+hgAbm@;Jg#M6qi(*$Xs z@T|_Vb>%D!%;e}wnJ`+6>W>x~+=+0n>!N5-TF7LwtHWm!mM-CL@)H-A{ z)e(JJ-8m)vmQd5TavTQ% z(xc9d3D_^!&!WFSpUH?_r3tAT;QM>F;9lM%>eVbLKp|3hW=|=mFw65=e>pdMV&zOl zFM8&&=xJ1{yQ&c9@x>JOqkz(*G6%x1(vFk)M8R9jiGRl*&|WluU+n$*0qu|))m{Im z{TJP?els6=eBv#jH7e~H&Ve27Bwd-~Y4BCYjbQ2#4ToYzlanq@4#(r;H=jgmre1shguf0-=4Mc;UM zhkl>2ZjsdrW5-SVU);u)??>D2^)df?CM!2>!G{jVR#x*;S+zZpE&e_jkvQapdCPxe zh`W71LeYHqBcFKj(On_77PkmC`Wdi>q_0?(U{J8-u!0Uy-AZnc$zu2P4WCkYen7mP z{R^a@Y&V@I$eYB>Hl-Qx{b;t&7;<-Kj!1>)-ETLnpkIFRzdp?_M_>s(>gJK;k?@f?uN|xO@sAku&3zU%)|^ zD6ja#2Ia-b0D%!`F}j2a)L%707{ ziHR;wL{yuCb(G|J#4j+Nxou&=f>057!KnD|kd4VYWM-lR8WJ|CX7mHQVDga)IbS9` z=22@rFNa2%OWR}C&9vJFFVtza4N%SW#tAoX%vD_EZQ9K-*D>u6Y1*WJ&agc;DWOyG ztLKZH#8Z;So#-}`z;VCEu;%?8*I(X#W;1NX$MoBOMLqAmNr_yVmK33%Ws4gTUfe3%2vaYU zYh#^V3SE@Saxc4R7GTx=uZeGJ%Xad1hwsPFL+t;S7$g*aFqof|ZJIH(`Nbbj=JkHC z@JSFVoMp2%?7DecO~Zc$UvVu(=(0p^_W_<^vewSL6RMSXnY6>>A0wI>vQy*tl!FKZ z9TSt-)m3{h^&(|YFfLcHQ}{15^jrSiO*Z?tKrR|w}#?VxWKH1B>;mC__FfyZ&Po!W1z;|a@I!NPjuHb)dhQ0 zhg)J&eT|UAxT@0m6_fdJ(;dxay;;T_|3y^6vFS?Bpg%?oGoF!0 zgTHPpTI&92rnukZLVV~LZ>G_D{fgjX^xT?>t?HL%2*Dw4M-nDX)!5$zv^Q#ZHv;+M zQtwp7<^xdTEp_~bR%J4yOo~RQ?r*$uGxAq^AFp=LnrV+effnTzTHD-K|mih@?pMn?#wt$28 zvza+LSZ02|u^CBlVVo=!c3>;`*vrdPhFvDsSHC}IJRWgBk3p$x?$XynN9}!Qu*YZ# zq;TR^kaEYEd!CfMh#$UP?V&&HE2og0^NX0S0A1YpZX2h3sP!dBRL6tDDxAFe=tWOI zkM_8}uPY5#zlWPBqEI)}ZoHyO=3bq0|E_jpG3MGfK!2>TQay{RCldMic5@N02@K@r zha^g7P9 zORD$vT3NI17{gj)sJ?|@>;sX-*8hC-P|$PTpt`!+e5p6-ywAG*y6q>{k9V(`y{-LR zKQkqG{lcyn?UvS=Fv5 zJ6>|}R%>rky|(&zP_6xWF?cIY5l0K}w?1@$x+xfl21{7m3;Vl5`$_*Rnz#g^prOn& zlD*ivqt|Lrtc=a)j8Y*oL-n!WupmnenUAa0#3^rreRpgwttU;x()wSrM1zJe%v61d zj8Lz$>?F9s7^hwbkISkvii*Y9*~H``n5Tt;`ge6;$V-f{3$h@TWzD*gTfu0^I-I|f&AWZgfH zmEx3V&BfS8=Z6v@og1rKvQ3NQE$QQR#D^)=p&7;&WNmCXU^D^iWnUPBa}zn@L?+@e zHuv}+Tpt%$J|zh}%PVlbAh{$RV|KEte*7l4i_GpRG+WASB@m&Y8; znWz4@*vGRjrhRGGrmwQNhFOP~qm!OLi0VoIQN_T0fk7_TajvW$?#!-vBICZM{r#B1 z_l`P?f4*f<1ko!p#7!CreoXlFIQ9ER+u8ad6Ut>V=J|XIvzEX=5Ds($cO4HB)C))t zMuaol@)ySCbpSvw4a%g*JzTxdRxLtb<4wTCjz)(UbD@p#P} zz*B9|rFD9tB#0`qY9TTL#VjRdQbgv_MQ3{$TF$N%456zmV6W&|vG3MQvlsM^+c4H; z0aiVzAlo!=oR=n^bWFbMLPSiG_1~?&N*_D?TM`HyERCnThEt?p)&=@o+`38P<`4dl zdo3%N1q1}x-8flU?WoEjL9AWaidrZXIy zQ7mRje!MTw?PR>@ampjOz9Al>pDJTgoEq`LcR6T$$~0iW?mBYeUWqsw-5F_yX>7O? z{C?Od8Z$p3ckzqB<%gyJ`@xCk?{=zV<%%2dx6jOS_t)Uza9IFyx+*4J zZW$XhOiWCi#XH&kYM3U4a>H|<>>5$l`P(0^GdEDs9!NG>)0~N?AZEP~YdMh2pl-kR z@#x)lErUL$SuokfW69|rRgnc3$7}YC^OFh{niq?+SFEo79@k>J)-s5Qxt}9m*oSd9;^5o7R2qqRL#6#CYjv;h0b1k#O4p#|r zyBS)=Fr6(C#+vf6GY!kY^nMFL_zDr^5G4pB2CC`O&3Ad9X%-e1%Bri!^*j1BGlBJ1 zeqkYj9i6bSFfh0E(4F}^nL(`l35WrZq_84_96_DtU2c?H_at0-Spz#uiVZ5V4m3jH zN-GOSyb|OhPQO@XbufQ42Z1V+L--?Q^iZ#fuv+H$*;-Vi^Ydi$pnO78-Ac_*s=uAs z6c1~kmnb>P(EdGXyQO;RMdWfXsbzN?eM{0$gg-EQYj-P4=3{>zQTza3q>rAlaWnuv zFXwsBK@$Srw0Dq>@*u&>e&R9rHYV%!|Cg}v_V>hXz<%t_ z+oQo_ChE>>?&oKpXY^O6*4hoG@lmVI$J7-AmI8eYt%bzjMII?JU9as_@KqT8K~8t) zdPIJ8-NGL$&-7#V_?T{yO-$6(4J-C-W@=3VV!x}M? zmGT(v^o=j>8(AH{oR3Wa!&^h5t?`Kh%R?hFg$}xYdqP%HdfZNcQL)KTf8Lm9da@x=H9&KHeD_m z@^5_|Um24X@{?L+cADx%HO97A%@(8`ULf3{(~VRhr_uP-DUtrR)i|B8+q;8r!oSSl z9cwnty*1UY)v>Bu-YG#IjZ_2Wet#dq%7HmRA69n%HosS{Illt({+%d5cvJ0@n$dhL z)qqC^11(SzlyucWz2)UFgFRt;mu4-qJ1^Xa`Jngot(8?6)a19vV4$!ZRL{t2l*3Me zfG4y6eu^THYQXX2Y*uk`v3_6g*RKkmo}TfGFtLu4@+BN7^2K1nD=3u1OcNbbJT5$h zjU87wLiHe4vAFtr8?4yaSXeTBaa5Hl>an!M6Ud;!5?6W^Jqw{gepB)DY##%)nIGJ$dYSfd9o7%8o~r8DCJ(1(0!-TAMAkTpRU&GO?(xZDAh#42!P%Vtj@ z>Pj{2?2RWcsoc5k@2=Cj1F-`CJSyb*g5VID=e7cSJOnovdN{%dC@TV^dx0Vl#0gm$ zWo}?b`wI3cIyEd&BSHt4hI{qEv>@^fOHd1(}QJRIbRl zxm`Ow2s|6jyKU*|DI%}+5u9K`UT|tG;NCn$LuXbFXcB^a1CV4kkd6tl^ktgE$NDLq zb&2ta_?EJce^t2HHVrj1x6~c#n05BgR@-%^m2|g=={jYjn~Qa97=}X&ur2s%Y}f7X z2T)%osX{nJzQ8|(Q?7%wluf5}Z&EK@j=$5r_gxXePp2WaE-fv6>gkcOw6y%cQ8ePp zHwwJEnuntcH%}LDK7(_fn#y?3wUcVB&e<#{59%^^ekP8?7i5K~nu0-%ZkaZF}|;omb0u*pJ(UJ+#>@=AaQnCJ)3 zDl`fw1l{uYi?bk@W2>g#Aa6O@aQ+Qq(M6b;AsPR}%u4_1U5s|2`38X{L%TRQt?oXJ zXv~6o>u&v>-0+ysLS$EaclB-*5#Pn;6HcXuizsmc3!O{&HCTpnyR4b>_lvWcCtK>m z7Ug1S4S`h3yTeU(=J4o1f71!A0IL+$|AG+fnWM`q$LU5YBv-RWV?gwG=S&SS zFt9s24ryM3FT*5^%|$AgYf929u>DS0-|FP|9mJWg`B`*hBbE znGDf;8HyD`J5L8ELKq$)qqsXBQm($XO^ZYj#8+SzhAff>o%*v9Q8qSA1`&r}JEzat z6lIfbHjZGH-mml+L`QyLWPH=kjh!`XQw@mYvxBXUL%|4i@x%>0a~rRs$HEdE)i*fU z={x=y&QhyTm1_@ChtA^{)HtX7BF%g2v>-?rQ0H}(Dd3owvB4=-aPOb(or8!?%?GD~d3QARMx!(~xTg)_j^lC6m2D zCHFA2CS)@H5M4Q@{`q`qA23~uvY=rs=1=Hi66h=xxY_%*_+?O^voJjp=xXoNJoa^K4Y`_z;t5=SdbXdFyX*cR0s%={wj4ah4&TVqfDHPFcj`zo9pUP%(w@l7m3ablZkB8VyDD4t>$isRpGg97nfeJ<=>>A> z8Iz^O&GSaxj;0Y%fOrLxAW7O-1@_BFdd_!^GbqkuEB5yw$Y+vFi0j5HAuEMC+xB9U z_ta2b;w^rTh&a-4lzBx4-3w}9b=4PDq$?s5yfgNrT))*GP4)wtnz3Qj$TMyh!vHgb zj|xz;N;-;0L|_P6e#AqDI|2Ia0JD`S8dEQpZ+C&{)iGlQeWv6H(q(u@?R(3ihIwcu@!3Q{m&nkK30bDrO5p;?axLPtT20xgD96Zl1~mg>-Y>`W~exggxD z?sjfUw=8E#ctn+Z4I?ll?-01DH0itr3-CdgtL%MsO3H+?D(s~7wraTco_6|Qd~oNm z9QaE=eTf9}6z+rTprd$QRLk9;Y>G^MvL# zU~mxoOiM2cKaYO0y)qUKh0tjuYt-#gvq1lxyj%ZOx&uMP=F{HGZ@nN_{03)zbHMYa zv)e>SXRAr^Q7QVT# zxLlQK%A_%xS11^FN?@GC!7ea>x`G^K?tC9~1n_0~eMpNA6(kThKDh4A)-!g{0XrFG zUYI^*xAM}!!>=u-w7FDX%6H@bw{y^!JFdvjs3Iw8Hi}IeAdn z-kU7NAv+>4xaI5Hp;tGwY;%Jh8fAuXf(8ry2Q+s(F9Q?DiJzcIa#Xn549$;!F$pz+ zJ*sb{ojMfx>nT&h-*H+(_;!kq(TE#6s^P1-pbbwrm@JM$R#veni0U16D0FdGl*Z$u zl0RuU9?-Wrz$yRs zB6~ULy`c`t$oP2hv-6h>YL8b7CBZdC>5h2A_F5G)0c3cAgzY|CJ~2KQFLX?)e<&N` zv6#mzC>U;b)ueU+ILHa3}OUu#kJNlk}8Vbry#Nnq4 zG@&k#pypv|%54vin%UnHp6jh(Z0`zW^WqB)={73;drx>_dl3w8=l0hlrqPv^+Q;6o zBhG)*tlEwocz0glgO%2PxWZ<(eJ8ndXj{vGxSl!`<_#E8=1{Lm*R??DSwA1n(0-GJ zH7nz8yQVZ%`Q<5^1Yr(5dsNXDKORF3fx$d!`x|#BT5OusN_1?AQw|4~D3|V5+y^K> zQGFm=lBYz2V%DbaVA7#>TQwA}z)Ygn>%+A?&h7cki2(k*E{2bhPf^Jere!1KY1E;s z(zksQSnd}-wei6;$dhe~wKh~}o(L8sF*TO2KnB_m4_eM*V`7LlYGKeTF)0b8_H@lg zBao)zjGY>=MQ6O&P;;P<>^?i0J)0*DJj8^cBpw?GE=YoqwE2u{iBRS>MhMp^dAwfb z1>O}ku9sindwY8aj5a*pGDRll55b#4(0j)k)e4AhNZ*zBMDbGlv>*(aDq8+8X3PuC z!J5*_^@FF-HAab+T*Ne3E+Od=SCz>R8vdb#Mb<@Nkf$`v?TB}=q^&H-29oFPLArkG z<~nQ^=&LEw_p2Hv)4_4x{P#lV^R&w#zd+Ssi~y%$x2CAFOYcmkSQ10ocQqktS(66H zN~7rJU*oeYO81q$Ca#NAH`a(8P}efE6G*)13GM3YQm>O>B%zIc(qb$2R(*Y@nE}9u z3eObvybdJC!FrG*|IaXO;NOMW3T|%`5B$8n#U4F+gzVx&JQedxO7;xF+Gem_ALRnk zRW9$l1;`fyMkhx`!o$OH(l7nj8JD5;p*6J2u-oIpO}yZdDN!Zb_I^E}hItoCFDf>Q zR%P-OEndSpJHh~FC1Ug2-_Zx|T4Jbz07F@MN_Bw5w9jL%tEH;v)vGUJ^Bo^8L|b{P zGQA%B6Y?+rfsQndZC+OZN`;UnOe}~>?N~yp2Xd%LSS?2KM1Wuq7b}ax#I*~ZFV2q2 z&f3q@nwcN@-FK>J)cQmXVaw5QS-E*zaL~)Uckf~S#$Gsa=L;z-nGOR6c+AC zd?+kbelHCN;T|l0fsjavC{u8myihm)&66TldJ$O>g@rs|B7VpxS2oJV#@1mgcCqAt z3HcC6L8KkpCay=oV$3Hh)bsoI9Vle!S^*JmJRS@l$i^y9@R)a&!K>DvvB#6a=7Xa1 z`djj}%sNcGS;ODw@i~(jFIW%z;b>-~w7_yA2$p=Ls}6MUKk_P+D3~xN>-t)Im-nr% zXsAd~?xu6+w_27cPVh^=4ktYXycbwlSkUPP~D4<%36!rCeq@T=|?_0BPw*_ADnm#DxfeqbSC07-GQ6CDBInQqBxo%m3%c92_<;a&nRj?nexclPtu zKYoqVu+!fGhnUm-x)uv?0W-=igqcmYn>SnZ`+9nNL9PONtepN0@Z6C%HBFoC{;{;Q zXD^9@;ZAyRD?`@Yf;!-7Qp8Np_DBpa^yRzjXJ+S&4rSjtpg~dtA%&Hl zHq>0-)80A#*&OlXnv1?IkE6Y8n>+{Sm9S7btE{8JWGF_*wrO?9%TiN!gl=ohh?#5= zn+rEE_dN==J%`4I9@}FVPd{CoPd?I1(uYN$weO;BdKAbnH$TePa4ex!{@({qatJo% zyp{aqZfvH6p%QUk1qQX2bu85NH;)G6x3e#u*sp(QWW4cOmn|L`HQNY#-}B!w7?){(CN54d0tdNcUS+Kxzb z4vmc9vIB4+vQY$2_8E=zI%n&kD5@H2#y=6$Qdw19&JzO4fY|B?UFF9cp3}D~Dmo*S z*st{*{Hcyc8SKWA1)r+?dQSv(0k`+SkHjn<#`7mR#9;d~mql16zDrMZUr%HqHS?#b zz@iSLZY%V74G-{dXphFMcIgrIs}ignSqfR_eCMA0RbPUwOI$+hphVQ;GZy@etCC%* z9pqn%$dG7$X=!-(BEz@oCU3XaJ|mD4mA0JvsHREM!L4qCWET1E-DPAh0~G`geu(A{ zaiT@d!RhXTOj!|d;&U(H?~)gQ1>0bcy9m7y3Uz~#1kghaeG?C=ot+&hDP*Ps&rV?Y zqZ?u$!L5Q3VYvTOkNWtL;6MMU!3AK71>jmc=h{L-D$Z+#2rjJu&J3_iSSEO1f4$vn z^wfGN^K0c;W(h|)NO-;d^h;5E@I>%-2yadFo;E$Il~4SrWr|sOsD?$x4jVNjT0zW$ zT(r(BTAXviyGj@Cg*hgB3^z@m-@&17DZYEzM7+rq_o{GpWRU~nJ z`tk)E1@ca;q@<*YL-3Thf-(p3bUUvYpv`MFJ3G=(_1_;yp|mJ}L!Pv13&utuFc+kH z00^oTR!aF9;r;&s5#CWRu(HzUEBC2bOxwrqUbh@Mx)^`dJl!}P^=;?dwt6^Vh864B z&1&?c*XF@T%Pw* zhftNHnEQ(zvU|yJ%2%5vyDnHwhI5%VK{PyseL69ay7{>J-XnMtyyT$2i0aGHZCyPcUx;PmKqbB*dwrIm z9c+j$3h{x~yYH&Qea)8)L@Sn<>h+JRYiZAuL52N4<|Vg-(WKbs0Ebw)akE}k5t+Q` zwA%TT=P9cYdBUZGfX`BmE7>+Oee=yzFp))AI5qkCXB4#-J9LwP-YELeLpZj!cgeTH z>x0+fA)#k=vSb0t7t5demVS;p8HIkm zp+S|B=#3>7Wb+56|Dvv?Q9MQQch?lr`Q(bD5GDW#_(Q0X4}~~)nCL78f_3uflTLEi zhYsy-;#Jp;7Lmvi${N3bQjK8W+lK{tCxys6NwKVwV$*8k;^JzBL8mY{!_>iKm(a$n ztlI8G79|t41nNDJSu4E1SAXJZ@ZnIZnuW8!*s8TU1bnmJ{dpSLxM8P5iu{N!W`Fyr z)yUC%jD}d-8uHU>BK4D4$I^@|qn7~=zAeZ5BAxM1!<$WF^8(xA^WM6%@cHW=0Ke@# zyj}9&73jz7@|t(*LyOFhXOf`!aFOXDL_bH$Uh2?2qzu;rMI(Ys3W5{!zh8-`1uBVL{dI|ZVFW=;b zN=wbK5xU6NV_N`)&;W|q6)mq;DLHF|Vh19QG)ujeuA$d<3v;;np~9Oph$E^?UCD>rEcKeN&xo+yPLk!R9kbU;?n_n#Dj*lSjQbvgJi-BjI0X0{044egQD|XXk+P(>G9) zusi!UYbxzuF@slc9IJg5)yiCN{!Q^6S2h6dHP{Ck@70vC$==#Z=B;g@kf;q`3mvZ< zY+4rPxE0Ho^cOXyNo{jKnxTp+zQiK>a$Xo!F^#=3ks(zA z(C!8YDUhDrN9vzgkT<0}Qlgib_%g#wkK1(S1|3TC`X8D4Dei$f5;l2nN1Y_XL9BgM zl1a?2sJtNwmCQjvT3-Z5v8wVs`B;wsa>&JI;WbBdUzSRUWkqE)3b`ML*b7hFO+gC~ zEF&K->aI%_EE2jJc}1a_BoasHS05+q8PLt~foI3FQgIJ~Re?Fc?UdPnmx(~(pEbk7 zFR)R`Kl4*AMacFCBjp#rf#v<+mA-bNnpgTaPTJHbOT9dWe#X2C`7(Q~QEpggq-A7E zA3hGRANM@GX}SUL#j(5cJCcFES_+Ykl(=9X}}%JDjmI!P`@gZr-wgBTL_^eZZ0B z8puiJ{owL?30C2H+pI#xJ-~62r$IVV5B%#k3ux*l9xGw7KU` z!cQe_ktd(UCG;_C9rI!t={h@Q%~6t8nVgZV-`jLr7<2Ye>kW`E*7NQqoEIrP(8E=U zA6zw;|NYTH1WZEWp>5Bi)e&?QV_ut2Ocjh$z8lhaRxS?6xIMbo$hsWQ?I?B0j8YE4(!(Y#tV_`d{Vu zA#(+QYW`MKa>rzVU?*i#`uH(h_oQ|OPbiuXsFRrRn4QnPB85aU*u~;o0X9BYF)tx+ z!C&{kaL)XxahQIEyHm=^jWz2uy6o=1hzLB?06RCj*jfl!H+d6Zm1q!4MRuVIr5sZ; zO&k&vP^bc}3$3gA*nD>;INnb(w0=|E_x9kFb5_j0W+)~hA@QvWiEFH@=`1s-k&2_% ziIh<yl44<-ef2L551l0}pP&Z$Hw zt~Y;~iL%rQv8YsynR>Xp-rlMelY<}d1R3t)N*h|oLS6Sw4C(1<)C)Z-kyaXwqUJ^e zzE^f>^4D*`HKHBx-_7Z?+UH@HU&zj1l3yUpSgQ9FmUBQ21pE|7Qlu6igXM||Vf!0} zB{vsO`+s59LylSx9)|sR&axUjYgu7hv_pCOSh6|8DH|RHRJvC~Xg?Mmr2Y6GqT0;a za{;-}!4LX=?{o#)*A=0em698Mxc12F!~ktL&xQKdfXf0ySXqjFW9{@=sgRPx?UEeE z`b~Zqh?(%l29NPFEC~ps%rS-6(gGh5jSZZ3sx+G7n-5q1FOxrEX)d;N@6D`!7~f4` z0R5U^1jfCDm>1BUtrIg~NB?+UepZCC>OxDBi9~KwSudrv`Wp z6RdGR0>l06`ST~RX@FT&lm?MABTQUAVXm7p8ucYW{ZJ26=5#ar1EKYKVER9G98`x| zqd2K`;yG)|-?+{0U9a1d4jRq?!7N(}t{$cVu?+MIIH+>@-{W%-WyEp+S9l(a>s^Nn z_pjkpC;MBlAg}N#hC!D4fULgaTJY@V^vptVaq2O}@Uf&6-A_kjx^>4KsHn_Q(Oj0& zXaC$%UAyQE>YOejx}-4&5mYN^F(Q}x#%rSh%Bs+f33K%QFne6Amr;Ga>Ca01H*K4* zr(?Cti_e9Nn*p~{LP+pVx|e+I+`PCxFFc;q%>E)34jRs*4h5;8y{t9qL=l?LSjDCN zjtDpQE%)@_sRebIsMY^diolSmd~#is7PBMX!zNDFk5<@xDB6ikR)g|_V=|cKq5U`} zRegi61B4r-j{t~A#S}(;lE?h~Emy@AmerX9ECP`CfKv-HxC88jybEZ$D9M9~d^>MQ z?!DSNAk*X3)W(Rg4E;Hbo0b2$!6DYU(`<6zZ;ZD~hH?q-3ou%!^CTW;bV6W9su-3) zzhf`9ZI2vqEfTN1%kqlY#pX54)eYG#7<$PcKv>p0NIn1h92Uk_^!=5;d`nFdJk*0S zscp=7Dbai>b)BXPj~sAgs!@6-+qGInDzeck1tf3N7@LnnDH$Ael4-ShN zfTv+xgIIm1^79SUpU?gVEhA8K@ffpZ-1G3YY7ZIjXgAz z_18f5^Tq6rHJt-$qUF4sWR3EW@v<{?ALrWUyZQ&oqLrg@AIKQ9yk&tBhkq66k|p6S%rIQ zL6fVjwC!~?%hn762SKSQOan2bj8t=c7QCGr8DZH5PhuNZbt0=L{trnv2fWtCZ`Zo1 zM}$1Qyfx{tZBhQcMglwXJY2-zg0VgB>2lyHE~53*($>Dvn+GcE0HR8+W7;I*Y20#k zpDhiw0X8x9BFdUNE27hYOrs@ksV-jg*v~pVS1%PgKl#3a-+OhkPR-%z_Xx}BqrEi{ zs6B&OpyXug&uLN&u#^)Bq)xCJW0R7CCmzm)!NH*%-5OV{x8$j{eq0&&r=I+o{H??} zcLI~}ILo#pkF5QB_ta$`Dvr@)PW=S@Sj~^g1~8S@H%)Etyv=L{3yO~C3ZzGN$AD|$N(-b3@sIX^{_N>-BW zeNngWe6R)@iea$4KvuTRBX{vf&kHoFU-AzTVuOlkR%s=@Twcbj!LdP5)nnL}838pm z{n^oI3!vtRI2@KpWI^Sfo0}_0pM7wK0VBfMdaZ@k9+$)mclAE?s;o^bu~*2KZ0bC4 z4l~}lC4jTV_*q=onzHj);>jnqYb>2PPqV+oZaqwKQE;+vd1+Xrha3IdQI2x$^Zjdx z+c&tR`T_pta)a>(sD6;~T17+#K7?7rqpK8&_vf>p!F|SCF5Jz9> zw9-2RMtl6%?*%7Z2Thbw3dJ>hOIXAJbVJc(Hv*DD7v2t1iP)vSm)Q*sCugNV zwk!Y&FXQA?>NyF3V-)Zwe!#u81+v1Y_hs7K7un;d7WaSg zr%c=z=qi%L4-OI%<3@`0KDsoZLPZpkX zK$xH3w)$gX!m`hcXFZul3VDIgaHOzim6t2A{86saT1! zLz*p9wdsmTgPVa>$Ke6_I&0K55K1f2OognQDDCJ?*st1P7b_@t;D|M4eN??%^Pz0MP$SFc<; z05pz~O(CWgFjfS1%!acCtF<~HuodvvSsfAtc{aaas;#NXEGaoTsmsjF9PNi@*pGN0 zyl|Zy)@oM~Xeo`?e8n9j-1hSPts2ay_HU}A4B9ek$E!Yi5z3-yU%ZX!kDG8|HbC>i z=ZSiimmVNKR{`8A{=6y-IM60fEeCs0p_D=gxw7l)FLh7YpntwTcIo~mb2#~8L$qi< z>wq*F)3`3v%X7K+8T5uwuNTwSE6#37$gH7;oJ$`VJxc0-h)I4>Qj0}nS7F=^7C zU#wm#L>GJE(JjH?_{AGksVF^PLfKj`PJ%iZXKG(Qg1Lc#sVO2b+DDa-JNz%BAoZ7! z`HA@d;#gF<5n2gDo}7zoU2>*Y>e4gpxwNkbhW9rQOzDSKJ}g+G;OXTw$v4cf>{|a{ zm~{M%bBHjD*;6ciM{CvZ-D96rn=bU!Su0*kU$t&bCxpe>D81EM#~0$xZpcAgy?9=& zsJ;N$4;m7RW|^|f+(7~Yam_FTqtg4tsfsogbNa;QckN=4^CrMLBPC#F(<{JM`3_T9 zqPl4O$Om;x&Fa#`l?&vzBVh-|6lesd9Bh*NlAK$q+?H4?1s`|u@XHw-T$R&Gz*R-T{APyPEi<-ri5uhAdiMlMW&jc9crNXl9R&kh0?ft~$W z@4ARWA$I}R0|!q!z311y3!*ZVVacs=9?Z|z4%)6RqNwSw$S6gk-Ig&@L@}@Q)Ls34 zE!P^PhVS5Ez+oW{it{Zk&TFm2{P1+Ke0Sbj1J@aKuLez;XleA67SeOo8i zN(RW9^LaO6+ddsEXy~wK=v-HOqVt~C5nW8w{Ozb`WU56_yE#XvwKt~gTH3jWWmfFV zw@FkGB0GF%V{6MM@qW3G2@-M0m-`*C?b@{sn+AmfgD9f-?(DEajNdDH=@=*+V)`8Z z$6zf549|!WqZ5pugV!fu8nQ3@gb-m(*7g|zbl{?&)``u>jh@V(cIyxafyzlx+_*se z-*f>pZuvs~moy{v+WWg|+g?8c>YkUyW<&nyi;9j0Evd5|aA&llPK;?@3;6$b^KN!R zjlgg!WgI~v4TR8l|Mi>~CBn95{^vS-T>5*X@72=;$|3db<9 zgj};$xeWX1Kivib`R;-5g^opYiK*oHW?}Zy$#l3b$EkzmrGkeJ5^Dr@ZMCJfVq{V* z#Rfk76oaif(Ysg>SLzwHFQAwWi8Mg)_-pvb??BH6(uU^7L=$CflmXE^e$*bji4KOr zDqWwy?lJ&NX^bbfA+`WnzqPl94s>A_jIfYhLH z0lg-WxGq^KqpBIu%5aJ6=;^g@cs_14NnkHA;s^C4Ym{<+kNsY=39&?^rS;FHcy=_e zJ`Xx0E-E@{()J5R)TLzeGTNsd@n4>LghgaMy*IP1dq$~hO!CPGz@V5cA zC^KLlWhrk1K}(F_UDN`mF-g4o;U|9q1`r&}N~P6)a1faF^!tWPtlZzvmky}PD--=o zDfacQOGx07A7xbx6Zf!TM!>>xAFVvcJZBz;<7UYcaRUN~w9mn2SaQm9(s8WHHr{g* zxm#dJvIvuEadV&qWR)ZS=1x?a|0F4iH#@J9JVQrd)m|DJrxTS;H*^-(9o86yhPy8L zWxYIln8C(`Qh?(62591iSxN&};gPam{U!T0UvqM#ojLt8e!P@7Z_Y`(SaC3H$!pnLIo%?8C*8Gn}D!PA@n&>-QH zf*of>Au?i{KRn;N0@bhp;vj#-V}sJ?bfUW8rHV4F6r12x>$Eht`G1pG?_NNqQ%!qg z3FZA!R)ZE$!0X*=Tu=V$CnhyN<=R3kS3Xy9_kZmt6WqxcKoN{vQnBqj@xa z>y8ws^Qx-)z=b zQByz1PeM(zK^JLh2r~Cm81!0%Ti*#bJ(wuufC9E*EAIup>3nAG157_T?kh?d%(4k{ zB>|Ma=}$}aG8~eSD#sl9Rzl*JUS-P%4aAvH+W^1Gm8Ki@QdAuW1#|!zjuy>xGCk%$ z4JW}i&8C}29+r8I`r283Hz^*n6bH+SD(m5G-#P7ge6h%qoILD%&^ahlg#&}kW0c8z zxn8`EVm6o)Q`)VzGLs;=zGak%RsO9RW-|kT1e{XFE`EiFOl=Gci?MiHM>LL2&R;%9 z>+GJ5!&Jr3n?WAMrUfy=>{3DwZc#b-A>TkBChiA%V2EVSBF_uNHv6rZa~c8=k`M96fChTxom$0_>Ar+&=JNl7o(TV(rJi z@A1t87j9!VyQC)O$hW3z4oY|ApSPp*P%x!6Ffw9#F()&VB^VIZ)%MyVw0nLK$B}ab zxdV6O{@x9vX~A49>efnMV``&>EViJec}E!ovty|s!zVXg7Kze}JcM+hb1U;}WA-+- zvCe(PDhYEgfRmikS?lqb>x$O4^LuB&&U?2hhF1DFGw%sLRM@whFJV0|Q{NT1mjjQ% zs8+Er;GUo=Z7R-Nl#Xa^W@9Fm*o;VWv+kPX1{2}NugHaIHPPvzjgvq)xb4>|ShGH@ z(6$@Z5V-jCOXw9{;#YqapKxK&)}i|DJ}VXpbwiStA%+uKBu6MShz= zqnn@=mg!oEq|~HabcEkVxX8B`PY8qd^@8T@Ww;2K*oz$TCdIeN+;drajmYe&%J20& z193R+$ojw)A8Yj9Os{E$%fK}AojWv10+wUp=jzG@8IYR#yhX(qW7(@eRwXniPK8=` zdoMD4W@Fi1reudwgVULvZjbgw$$EN#XYrPdaLt=Xe5o;Vlv}H7YyJT+f>h!C=YG@Q zpD9r1B15@aW0aJQ&BLXMYn`MjMkyb%aIK5)6<}2tkKn0S(kQFECmDuTG|1-XY57;q zWP|&gqlIAw2xS>msivah-+i+&n@{!H+Qpj2;gzzbg{Mi&KivyAgxSPYU|52-m7sNJ zsn4QrvL+oFf$!Yg z;@GqCsfqFv++IVuWZDNknYApEOUr%S=jX&A`#b)pJw3s~>c^!7e#NF@-qsmdrc_^~s6P zMYOMS9)@XYlDsOiy>g&eQg>o*AIzlSUwulmW*jayn&H>xQuzcrBlwCU4dDmHshe?} z6=pGr$jjsc;R!$G>YTxo zdddteLbc#aH2yi9WcVac!MvDpp!5=q zlB5S5af6|=px@y(GE0yjIANVl?VwE6@jY16P@e+T>S`$=cwZ)d(a~v%5Csyms|ww( zDT7fUgV9{-mG!Tp=(y^07N**qgXNyxcrq6jh%J3s;i*e(uKTxu?(+LyI|rGS*3t#1(;h1evz2J^$~haWyhOb zts(3t%T>*C9J+a-&5UM}3)YB=iI{3d6P`qD;BvEmRk*Kc!=@2%|3U`V1NN)Z=WTBu8|LIeN%6>}<^iwIt#I$3(zi&q zg#I>+I^$m9*)LGe!SQs_s(2JA8X)D({XaUf>q^lztu0`jHme+czs=6t4D=xNFmiBm zn=g}hrlaXv-(0gLu{PY?{nLH(ROs7XHrCab`}-mM1NbJptt81GStdH+=2&JAPJhAO zjlEVK4b_I4d+2>9|HMpv41>Kd{)Fbkh_s}_9SSlGYM8@BxF|oUBy{s&wtSM5L`fr5 zokof?ICKJ=?Hd|p##oj8WxB3UTF9Q zAhZdp6(G;w@Y{VK@AHYUM?dbcv$LDS-gBf)d4KT?VXeW7SYB2Z0}Rg?kz#Lj)2-ni zEQ$SyDD;2)u!cEsT9|(60z}a-SqT0Hyx_S%clGo})*7IL`cbBq(hKb^-?f9M9@3pv z(G@!u+0;`)uO~1icrS@$d3hdiM5Uc>3*B;gD3cjivXdVO#qF`fWExyXI)~)f#}Z*> z)eYg9@JI(&aI6tF-z!%S#JCvYLmF{thC~5=ZSXaqmzu8LC>qZ+(ZMwM>GHXXW&%dt zk9H5~>vlR7^oZUPOMlYDMCIF?|Bufn{eK913#cm7_sEaR*g=7@+Vkfi*BHo9nt?LFRicG_8jnFZn~tUl<3;M+iD&K{R55UbroA^DFqHKNA?Sx~>(Lr&z8z3+s~lBukzG zc_{x;Jp>tcOH6I7H?%Pbh^1m09O|tr{d@wBEcKtW*TlQ_?AJcnB@g;Pw0dmx+SGft zb>`;-$YXSOst(?`0^g7Sxk$l&3pa`ah^m+R?f|WOE!S_06}a)J!Ta3@mTB`w12=#y zuK`#V1p>9W@a#Ky4mAiYeocL|g64BJ_p;Xi+!^R3Kfl!f^y$;rp`nSOq-3<|dsBJB zV59YOq$Kp{hcp=>c!*d#gg0g)9D9*aNI?c(f$LRxe%7B5a7ow`jYs0k~iI5wOM;M~|2rR~sM_rI!3gTNs45>I1(Q1_$`GYyEYz}x3I_LR_JaA;`tm6v4G#Qb~=NIFL8cvLd+ z1`Zj3O>)|KV)IqY#jm$;t$TOE9B2w2^MT+lt zh`SjpxIklUuJG!8zk6;U-Q92j5gKqw08pNx0$7Nj5~cDFAytPI2dtVa2}C%m299rI z>Q!H&j;gkDKo%eqK57;!%zHt%J*2+`R|Ck8GqLwaGZdohqsC7+=VrMdqyRWS`QfKe z3d50>^|a{9o+WJl%aZ3aqA6vqz@dj8hCjTi5QjCuCew)Lr_WlE-;a~dfCQ(7li=qY zoP7X+z1?>P?ci1JKkE$0e2WH@C2~i{hY#dWlOh%ujdB+}JUleCwb##iwY9Z7$(O;q z+S@A&4-Er|*8DEqyW>#Z8O3SX1TSOm`ylAx3J`j4kr`n6?R6A#kOHz&tP{J34dBPO>vG?TFy=9uLC*IyHjV?1j&^Z4mqo4-@(%B-NB1{s`z&K5_ zmq`x5ea97Ijh6Q!95Z_0{OwzKY7BwZ@4u-)O-1pa^r2vu86EM7727q_vi|~Z8v`Eh z4BIs)c!o?McK-edkJkq9Z(!x#1RtOy4`+ka1>tD{!s%?ufv9@&cwoFEOdLULMkFC(m!Yf%LbRGA zb9(qCD%FpC2cDF+|Gr4$Vb6h~v$&#qoInqSBU6kBN+h;MsBjFFfb#x))(!OQAcn;N zt2@N=bs?&zF5zYGKi#K7riT7t*Ed=hXdCbZz@`Q~s^P;J@3IU&4^yTiK^HSiT_`nM zj}DhD_JK0{sZdO*oA9Bh^~!F$svuivbOos>*=rUmP|l1F#10W0L-6~~?eBNm-3@TO z*xK5{z*0qca8y@UM-xK_Y9uy2t^r*9E} z^3yp0JQhLwk26%BK6`e2Nm~$F+|aPSCD*ijspk~8sM}lbG8>kPMDatmJX8?uUeRo5`eOdzmCw^qJ}j zn`08+*k55+Zb*I9aT-z2*`qrB2Lof?T%q`VDX=09Ls_2lQ@%`|wh#gYDap&cFmi#) zt1F*IvxqM(oeKqZZ=6FRraAY|I7pjmdI57!7h_Ub2d+{3RA^e4IfZBB0&L3*lGV)j zBD5rGH`|7e3&EJ2su*v+ENR<=&?ea@85*_JB;-JwIPt~mm#Kewty3`0DAmK+u6zRp zk+k`7g8o9_eS#oyDmC@AmjdK)5P1dE$_)VTT0ZAB{1s>;*gWS2ICCFBIupP%rP%HS zeg$GyK6n}9nC>ojQyVrp%GlW0BzRn&OsM5gYyxt2qIyGK{_q)LXXPqHNYcFQ{2w0{ zeO&Za1zUPEOB0fgD?C2j02gGobKzg2)9z<7QJ#_L;eW5a^O{tRTKU|y=nF#On@550 zkCn<0>+#p%nAviY`HNnIs8jiPC4~wHZIAng{h%iS0h&VvdAxs>_D)G2{<{aqY3Sw% z*Y7*;8i;}XrdW##9C#YLyMZp2Q)uM}<8Klg7M3p0C~tP>yLlsksA>|Wab%@g8yAAj z05z6=IGVFU;$gTZ@8_iGwI*Wt+nS!W-tG5H7nsM%z8zBXeGn9)xSuzS!|RfWT-b=k z_{$5X!s#+vg8pRC3QqxdF`4s_!s8;m#k_jLVCRKtT*fi*coq==}@@%o=RR+x5E!Si!LM6zJO&EWvtJ^-<-mV-H_1U`o>1)dv& zqYx zClqFNo2Do$hhn*RHUF_jYEPBgUHm1f^a}^*9m3iMYifptLl}>bGyrVXtYx%A(RFkl z@FqHpb+DV3320zz>^RXW&5d2knt`1Rv6lHX>8M!oMV5#}!)=~nSrr*mK8{lz2Dp&1 zhtN6HQD50gk?u}a-+bktgrG8VaKy$C+c%bX3i`X{?MathqoA|gcV)p>)B>(7K|PVp zwe3MvA8|fO34?u)YiR~_L@p6_5^kq^s?09QxozNa4CCQv#5`M*{oBi52R3r*Dmkr8 zu{;9D2GGgUjGr)DYslSZ|@OAY2?PqbSVLJwd zC!Vs28cl-`__75T=J^mBYL8n)>Jjf;Qe6ka?ln)Bpz&?>IkCr&(y zA}jE&zG|x)6Mtu&H(CjB#pHtRl?ECXC-j8YBlVxciHP7bR3OCh!!-6}ko%JL&ZC!~ z7kn(F0!(6L7^swwoSXwZ3lMUt>ye<3@q^I^!*ttH%q$2M=iQ&8fJo1)e&0(JPdmB$J;?7_-7c59J1?Gu=QtZwg<_8ZT0556O$%ag@_S&X&u9m}6)7W;gZzHuU zbfl9~cvtgA18?Vn;_3fFNG;Rq3DLD|zv4!Q;EGF{Ep_qsS>^zu7$N^HKCvjcy1B-g zJ#wz`X{HvBzRe@puE&$Uw%$Cag%T=$z*B|wK7g=gOkH%tZrj9e_w!nO%$o9<3l1hu z#eoO6U#6=K zWb5p1WsF>}o_z%Y<+J6<9KXg>-jVSzldI4C{=C`M2I^iO9aWVM~jO{*&6hi(>lmNzy<-i!hz zrjq-cKEW2uL55xkHS}(t!Af6BX0lBBY3(WtT7M-J7v7dZ1>TZqM1hT1#~n$dgg8_7 zT!U&&HB+uvPZG%Hvy#te%t}0DmGh1fm22irL;bJz_M}vESwZDqDc2k0pZN z6Ue2fi;yT!dZo_GsfQT&^V2T5u`{J;S6XUFzI&%*+{&?cjj*|-va)>cDS+nS+?TwY zY#KslyBt<;?sSyrEpZ^dfe}WHU^`DmrsajF^E$_giX1;O?bTqH&88ECSQ>IVMV?y@ zd?qOo>To5+snGifp@wfv0QKRa;}-!@7ctKQF^uCzNZ%gLt+^c+Ws-G(L1wF%oe8H0 zq<{7?e*2CAE1*VhmQbp=8pCMyIZj@iZ8&G3>IevcU0Zv`hk_a^=;Ovq*-4Cxy%z+a zBjYQ-cXw{do|H{33a!Rx@x#vq2yq0+@KGV=nY~`|g*gUyGuuEmCMKh}?j0py=Xu2L zbM+#hz0)}qq4~3uU6?HLFlG_~RdN^k8`^0s37cxdS^|>|xKUsm<*0aBuW{n^`t-uU?(<4r2R6dut$FB?!psmF&PCiv*Wi#@5A_TGz zaA$fjI=>mfBv`5BLyqbg?CC;QLo1G_&_Yk=#&@^KdNTR4pJ z3sgtJ+aomOm69Inu(G5ax+`7p+P}B?@?F2hRfjhx$TX_c;!#EUqMrU1MVDqd4uZ5y zJ_RG*_R6a*Gl4-Ct}~q7T&ihIBA|&CH-6`8pv?_*747JlAnPEcexbTL7!lUmX;^Zn zowDnL@;^91$4T{nRuXX7p6Zu)8nO;wDFDM(OVzM{&zOf~W$CnssEbF9iI04_!2<+(uaKyW2g>p#nfl$ zl~zG6wLs!O0THuflKb~X7U6d^CtTu$*fts%fpZ_)O}#;MfccY@9KmcSbwoWuiAEan z=Z#`sNMQLH_R$0?@5hRMZ1TL%ag4M@%G8$)mdn2rl^X**24y+y7}c`JH=JG~t~AN< zhb2g}5(?Iedv2K2r!0#+|;+szr94Nz`9)W8-a(XEc`(~ zxqcb~4O@8)!2^_J@(6n`uP*pmOT|GIZu1hsB2W!(jxEimUCL+K7rEK5;kUr)wvnF0?gqhj)U1L+*$~$hYqeMpQi;~aaoe`=l6H{P z4w14?h21DU%LnU$q0Bpsq2XH=KeL8q&$=U`2a$a+VGCJ#0cf^}5K_ixa~w#Cx+N68 zLWN*-LRZ6u?4CgX?UzFJewxiJ@E*ZWYpMB1Dhfn8Dd!MVdgwt0HUL>NdvOd%_zUoA zu87{?Na!JT*rKWW`87w^`k8fLw20v7CDu_N?4Wsd<8(lIk3vSq!a1NnkRJEB6CCvr zSTW|KouPnljW&R_G8V7x8xbKkWR?{X)=%s;1EhZQ_9ZH|JtxKgO|!CY={~b%)IY zySL!ihg`wy?$9o0)KF7pc;zp9>4V@K0VASC5bgUR{3ew7p1(KIII;vDxTR!L1!ws$mgRnUv`SB_ciVVp{| z7bqNmoS#$%+S+oW|NPlp4Nz4^1r2Ds0xhI^8nShf@fpm<)lWkbZEv5?#w8O4BoJT0 zrtfJlj}ENB_CeIa3)5HFMpMsVp`!zGZGzLdvCT-2sSl#6RL?wQ5kop}jZncyh@&U+ z34`=qMnqrZ2>2XvfQa(vu219Ogfu4E^8?fx)mcLjL@Q@QGG_c!2#FQAb9Zz6_e5^? zyu15)BX>;=xbVoUI@w+8 z->-974x5nlToK>9Ba`~0U$`+Is1h7#7@Dn?*9yW?EMZ|TA>Eyr0oTX}%~BASr1X8C zE<}SwN*%Edc);-xLA&=T5FkPg6D-A=Xdba>5@3_&yhDaA&a7rqKdQ~AKK$rwSF4Yc z!9vw)#HEt6c$s;P#nl2idvlL{q@|0o=jCpq5PpP3n60Mz#nJm%p_X2^1 z6LY3o5bpDMvUpC#)e!``nNwVq?d&$p2EjN$9Po|-LB~Ognd__cWgm(tGy4-J70&btAg{Hbyo( zlwxlJlnj!=^zfCM1;mbk3{#NkVyyrYUFO5Sd--AY#_l5VB(A#TPy`GS=(g2CpU)7yfyD-7z=3Ivf%GQb>>~nK45DVwSrgL5?Ss6s2c;yT zNPoIGUpnF(%zm6Oz&cZ;3Mra!u7}YWI>MCzKSphwb`z3cfVB;4o|%+vV;!KqTheYHK6}CcCZK zv=Q4BjT34A^|BIg2@EqjNIHqJ(*7No{=nLI7^R3|f4df`uP5~-_?a9S_ENM-8_Epc z68tGFlK=c?1h&|E7tWzmu31~!FnOQF$&b5oCQ=9hiI|6kmQzLqS(*E2O?r*4D$i#w z&z)O?0-0Av=G*pL6bpJ z&LH#j?pr>4mb&snxBA^kX6TVSP{R~QR2+#lygykcKHj@Fy0~qUgQF-{o?K=+WFf~0 z5QsmhbK1`9I-A0DE@@t1puaXZ5gX2nhzYh)7)u~x~6QWa?!G6t*F|d{SE_Wi3kw1pt?NP(p zd~p8Obx^Ynkj_>%p4)4ZXqAMJi8O z!Cv7SbbwEj5vG~(mD%;xhxpx#|8?E*W!`DC4BT&=y3om3Omrg_=T8+I$8S!0)v{9t zw|1%Mh!x^zp_N`m=!B1K;<+~SnxIr4MOk@tpdE z>;3Ix4$<2x8wo^5$?k=L2Hi3H?y9aQe}*;KNq{g>Pj#+Vop1&93;sgJZHZ>50-De@st@`ESUu$Zqb>C3lQ5Lg82s zd36iEf1f6YOaRO}!A5;QV<2x4}uM2M?C0Ven=6!WbN>9xo6Q{x}kKrP(I?fQ1s z80-kwsj=%N3pE_Wz{7960d5rtrc}*qLj+y|VvLZ~lQMDiN{cZBj_y!)!57x3JpE!d zmZxPWuTU!h@WZmjn0Z2Kq4e3!5DPcUeMKs%oeM=2C_4)4fu_>=>>ao)d7A+uInd-d z_i&RHpeR}0O^zkH_y+Fxk2<;)5PON=AkFS4n=@QC=1Pj>ubPu0L!TIz9Nw5`g zHCUW+V0dh#6#x$=kOPV$;h9!~cYAQ!uVGL=Q3YIE$W%>N5e0q?VAow;938VBi04{3 zB(lJTwj2fLu=K-xXIzC_NKSlWtNq}h<8oe z-T<-84$`%DkRau4+!*k}HunsOds?rIAcI_EMA2@asqH(;&*bMq22^Hn_jZlD>I~x) zW{K47CKzMN@zv6)cACNr2Y}8R1q+TB)s8Ows@AFGC~j7;BF|Vloo*fZS3{EBM_bb2 z^f0af_s{3QyUn2Ep{#2Wx~X|>@C^)xq#i^yK@Bs^pZVusJ(50u>8)kPkbs>&xm2c! z4`tK9XtoedpLU>BTs`=>70)pwJoh~+keTApNxSf<`n&`Le+rmH5RCK&341PI886L} z(-;fUswsaS8K|qxYm+-IbMuAKV{60b{~OZG%rL;=1o+oIxaa*53_VM;&T{ub(qlzp z4-sS%LxEfys>ndo!IRGY4d2sx7TCXZO+pjnMr)ul+It~W`grnSqR(*Nu*LYaq#U|2 z(7&sY%~e*+6sxZHbP<&jQoQ~2LSHf^{TY#lhZ+4R==yKZb~oF`p$88Cv|-9^ z{uz+X(-@;x(rmnQktL=x(0j!k(4 zS0BZcFYh5i7^KNCSv!k3`Io5Nhhact_ zZQU-H{rQ2Ag5mEwiy!pGmsmi5m*`NcP}POo8YQ}3mropy-S~BSn+7u*NnV3qKD4Y# zcz*Gs>m$Z%hs?u3Cjx+Ft*SpKIMWs^$e+3&^#)DC^{AO{qxk%zR2E-a9a;-1E zI)BOrVj~fYZAG!4hCz@Q|y!WaHe3@$bK)CMpAb$id~| zuKD~a&)@G`N1z`x>_NsiAZmEr4*Fh`{~MAVoSgdM!IVI9kk{5mPL;6Vb($m5>7uA6 zPw1rlEHyYYd$;-D5vU(YDa*UNOd#G?h&}X?1f^jIt_%V#AI^}vTM=R(h}W5r<7F&P z(j-$lkWPB_{xP0Ux7@qRcqa^Pz)MT_uS=%B0e33{84e3;t;O-zk(S#q=yAk+P>sT6 ziRH@Ea@6&)+w*)_sp7Y^R99tHQU&@L8_DSO$9McNqSrG?tdTWAHOiR|G*iRS@|K>S z?nmTl13!~x5FKW*%h*4ABgG%W=@A&Do1N!#ZYi`gV%y2wV12@1=?3pX&^A2 z?6F6Qc`Jr?tJ-XzNyN@=FxMVqyVOcDrjI+M()iQHAEkMUx}s<6?K8d0m}uFkf86c& z9o~EeonEO7Ke2=4KQ&`Lr5^OpU**Xt%ZzNlq`i&0&HhpfBo#+_oo0{~31n8I@hL=m zb8t_5FHR-5oJ)Vw03WxJA<8SBR_IA(NI!9es}j{txjpD6bG*1IrCio|{L8Gda41hL zFDnVn^SSDzpa??jrdI_zMr)M8Z!&w{uj&)4%jCO$@%gx@w9zG7=%{A-^&4(7OrY5| z(^%NtK?VdSrQ%eUo|s6&r(uUojkU_Qm4s3P9yWF|&}!!P#F_2Odhtr^;tOnG$GK}L zvwX>664!kzl^3w@|DHcclK95Lvosgp-l{Q4o>|_ID5d_>6WUIZv#U){%To-K!5-=; zh@?S>UnD(R&xK8vMM6A(fG86BIrQWpGbf4yTQ3m%X1Vqy?gBKu#;|IAls{Dp0bj$S zCRZ(XOwS^@v0UwcL@WkKcBr+oM=)6`LJnwX3b)1Ue_9ve`#9b5nEH=x>boa9HMPSZo?EXG)B@P?Kh7|LX%?f5U;drpNLUJ|PGIV3i_ zk`OZwD=NK-KH4AR-6nZR^+CG=&u;wnbl?QiQN?N)sp**3AgNyF$_~vRa zNL2F|(@@zFXj*f~h-M*#>uq9?N{p0iSY>P#>bOECNMsqn4u#5!Qj+zCbbI4&%NEy+ z^OZg4GLYJ6R}GKu5@vf!;)$&eN1@TF_!+;FtTrKC$ASAH%pJUXlO|hZ^gHZ5mEgU1 zL}>Q^%n!bc@j~7kTUw$Ba9ABgnUPwlN~;avLaEf#(Dg@ZsJ$*~nNf!D=ICc7T~yUJK3bX27`nJ1gRU*B z8TTRJPB>FiKQ;FixI`$t0?;P-lg@Y<{q1aYL-{%VT&ZG#%*g_sfF8Ih6*DPDR3C!_ z)U`pW)Wxe{G#`0vYjS90@D%hDvF%nGtcUDbF;Vc+Y0ce%Oe9`Dc8r(5KU%! zFgSQSr3d{ZwxYlMVc|UMl9-!af4}tv#1D`zFK?F9ZYl};l!47fY~Mi_XyY8gfMX1o z8^D#N1F>ZM@OFTL8qvdf4G-rRP>@dO!KgeUhqK6$Os#Z9n((w zKdr5cCN^^&gSoaa#o;LqoB$vp2Ngncp&f{8Ry%7lt_S-@;_&&yR6+{ivi2w^JODNjRzVr9Q)g1if zz&qUOecRwsg?dc?fIWHnTe$C9 zd>?ID3#2NDXaucD&ZwgyP_T(B}7GvG;iWfp>Lqo-%7#J^_roO3h0MK5x!#}%4Z+Zqa(`iJ2@v{HxD2+Gq9&K;u$5m z8)h!7;TX1#gJArH&lQ9OK+&BD>e$UZ5RZo6kbcOC1`XJxIT;ZR5wI~cxVNStCvH%a zO%zyb@~0RtD_uS9^U!KKQsWcmL_r|Ld@7_vwSf0fAr(jfX+T-gj|ouTDJE!CphM_) zvz%Z?Ds(})aM(4mfN20X3Ml%+UT!6l2_I%32@4YPJLvJcYKb&qXC|yx4z_47RKOA{ zU^zC@(=vqCE4|tVH4ean_FuF~$w;3LFEPFqAu)SsuJ%HTkiWu&?k^FCE=}{z9Os;q zD`qpFod;%bj*JYP+Y4`FXPx2Ull>%Vzt-cF`^$k66%hhqdY$xtPCF8LYBo(Hfes_) zWBSU}c?kr?u${PimJ&|A1L>$OSeOmlZ@O>erjy1!mv4D0*e9B_)3+-~u}Hak2H)o2 zsv0>X^c|A?mv`g0cpuWN6+u%7Ok+w#dll%5u{`Rm@? z@93ql)Fnl%fQ~HlS7}b@na>6rCe?59twe_d9iwaCjY3qagxGnek{@+rOJQYEI+LPV zHO(#R%R3R3b0{Det%;aqD>F-SmtbL0*|w}pq=vuuO17FH(eVd82)7U!2XzVbKayj= zJ{6+lpNoFA-<`4aU0e0T8z)1S-yn$I6&OTUflwqAq;SKt>`HR{FhRXe&;SUdJqOX# zDa+S)HycuGAnOhl>PA=usiZ`}b>MWs1XBD75&y^|X{z{vp;K6AIqW8D^qyJgaVbK@ z-=zes)cmEu&b6Pwq|J{v3@p)=)77R4K$8krMT6cyd3cWop$?@XT8@cEX<@Nc3w5=N zHdnb5%G7~281`d6R!<^Iw#T~+@GK%g??rB8EBSt0*T2;`3i8JiffAd!(DIO77?fTo zQIuG&KVuKYi_vJpG-#KFUEguQH9+Cz9r!#|5nAqS$4ffM{*gV*73(u?d@XzJ)UIs0 zhAyoN4y`4@M@lUKJEJJO-*rLALXyTfC)ECXz?TBk0GS>Nc;e9|kM|V^_5}fZS36(U zXV2dIF;J2Z!W*tqU;(0n>aP1PzFf-Oygc~?-CGI06N#>Q-o!s$8=!Z=RPFhTj{Gu< zLj-7W|1-l!;O3zQUo8BM25PM)paJtx)Ga8o!qutb02&YJZ#WZ;2SircM<3po#kvGn zj%?Qc&qOb^qc*VXqMUku629Jp(bCn;P@-By}!aXyDU3vQXYO2 zS|6@R%I?;i8s69Vyv0m@My99`X!Z_bi(H>`wgl}>8*n4SS|avqfAT)?FDIuH{oMkSwF4A{zl(NKa?mwxF%kQt-%bI);toF zzn-F`@(6w!XyK|M8r2iMI^RHc zdn6&CPnNT`E*^7&qpehdCmJ^gucb~}Z$WrTFX-lK+$Mg@`1csJ^kE7Cp$?EHf|b~9 z5m+|0H!F_>d_tmP!HhHDG?Kk1wh2Ptua%z2BaMK_nQ@?$29-ketgINQ;Vy#fZEbDv zFe;W4(I(ti%A;HZKlwJfI=Vb5Le84PLVh^Au4ko!^#Y(4^$*ST`PL;nin03}@+S^+ zEp7g#O1NzCasDk>IKwYGdfkvXwJODk@cNH=e}``(gW2>i_eW&E7igt1ED=CB6A~92 zA{R%v$MG%8g2i9_Y4XWaump!)S24oq*R%JN0~Q{U-(BlhlE3Itm8kJUsX5^eq3LUr z713z5yq4i~6&Ujtq21umRmk4(80RqiiCCGWJz%Ck03%zWc!~rOE@D;qQU9z34;xTn z0s*Pab#{Xjmvm;cpT11KOG~T8WWaFerbJ50a3~8g(nB+Hlkkqnc2}R70l*2=w5Bc> zUl|;eoUmtAy`bIJn*-8~x;2N&5_RpoU^Fm)1Hu@7q3;bNK-fa^d5Ah_zyR0u7Mf;l zerPqQ`sNOreyYXjC6xVof9P$<@x5;AVLh5y-1cl34^^z1Ffuf2NVb5$QL+#o9H9SZ zW;qaJfpSA83KvSGX|Pb;avpxX|5?F~x`zXG`XLX?6@DEi6L&xjONt<^9qt};BMlxEJuEX%E+W@qLn4Q#!#eUzF=|*OT%SR@L9NXQ`R_k}j(*e7 z#b6Z|E4vl`ve-X8(u@v^2AO!~3sntU>^`3%ntzW0N(K@+U8wCq2Bv9Hul%O$ZPSOG&T4q-q9=_7oe?qd`mS4?1=QZ!SwMAT3VpaJrPF!Xd$#b00xuy33G zV^Zmc`H#&r++Zcf7UM{kemRQxr^31CHhI2I?{vPES=Mma+N2_ohy(^PXP2e>5~&8` zZ+i`+McC}`8^|unGM-p}Xs6PO8vD|ez5zj5$0;)(y7O}9mDM||H0AV$9$z)F?+n7z zwQnd(rJ`^KWuXZ8{QONf&}stkN?htF4n-lJNp=ckv+$7Q`{XwR)TR-e z#T2gR4!H%rycm41-Y4ClP?22`N`5%N5|?u4ta{3g_xxgO!+l0do=`)~doSYu(G~Gi zyzVDREP$tf`~tlzd#{!$y%$3(DmYX!_)y^PW4{1Ar~hprd7#07z4@`93Wy0=O}lW& z^FU+I^@};f)x(Rs`=ADJ==D1)SQQ92S`OfL++A(M9c4I=7ej!Md1>QyGz;+?I(5wg zWCck2AGWztx6lNa*Wg=K%-i%2uaej&03UmMV?PijUFQo$6V~OS7x|Yn6b@kJmY~eze!Bh6YSPZ+OV92|4lZbZ6r; zgXSb3hd*Fpo2(*{peY1;FL3Dy-^>Q2RBq{ovfuc9P#ZFS)=+z7mr50G{xg1xg^ka? zn;=}nxmw3--r*B~nvHxeaw&sm3LaucJWMGg6*RSDWW}0ycupwKsYisqt>bX*fTP?} z)81M>)ezvr{&u9j)hH7w@8)@G%B!uVr}C4`|Kj9^IznkUL#)M#zRl5Sxu8K=M_LF& zo8!PEf|^lyvSVh6y7FT1dxAhV1O+TlKlil+(f={&NPCvg74u$Gc(D?tp6Tp5?w8i~ z-0PQ{3MBNns2N9|?@X+o1$BIzn)x*!8~m&65`crAe^Vk z%ZHL`?i6EZ9go#}RO?P-Bk0Ou_Y5oTRG1`q7gJ2f+OT^~qtY);^gL{HH?@)K{+ymP z3I|Bop=ZA^mV3_))y4heiMtG1>uz0umsslGeBxHONQFplUy6#~TDRpJWdOmH zylqPIREpWL_+IgBdVW>j?2_{SeAA$l*}M!|XzUV`)R{97pgz7|YeVSCqj9_#12xs2 z44}Y4UMOTrVYaN$IKKWMbIai%bPaL0iS?VQh1;L@mdOqR)SlqW%@7`21wsPQqEqAi z6I6ol{A_Pt-UimEo+um&^_>k{m4O8&(Bu8_Ba`^m-$EeXOXD_;hZB7>pzV|gm>Gk{ zl7Y3YIZ7|(AhDa+-}zhk)|XIYglF7aiOC;Az~BwWZhM3ZWq+(iDl$|JY3F&^B9O$C zRa9W3prGh=`U%3_rKGCm*hwIIFF)hKgHyEu{OL07kO>hqV48{9_n?GADqlDMgK(Y} z7XmX?K$SOk4YZrju7tbeQ`SxFZoi(tQE>^UUK-WpHE|@6H|@luH7d9;v(n_TwxqdVA)LBrT7iYmw%H2G}u{bs1B9xjx zabq}Rj}XxfKUtB@{&^qqQq|;b!iOQO8B1R-3iYG5{GlE8@fL{cF7srt>cixM}Dd) zr8*5@xtjmdN?b)#%bvQ3^AjcOvgQ*O+May6nK10M!ze+Gvwu`M?*xA!e$&H=W@F2s zSaT=kr?y{e^h;p@?_UO?e%;N@c3eoUnNG5Oc}1c z=f9`X#dscs%mso>9aBxP9^Jk;&(-Vp${JgnYDx&%Z_;EJsLZOb8}d9qtNl6paz@*g zhzLn_-F}<183H(F-it5p%N}anP0BCr0nhx8+3rpjOA|em62pVvX4^BZ4a*t>)5(2? zsXPn7X}Ve|wC*NF%13}Q5&V5q@RM_Re06Tsg@2{zE5DY5SIsJISYXlXjRGoq7tdkHS`Q2wa^tH~5`!8$k5*O;(Dl8h6pCs(48EJXddt*geU6 zir;5?o#+Oa$4bX!dH}k+`&pC{BZSFil--5VJ$Q)~MdokI|22JH>Rgz`%9SuUBuE^A(iABd>vy}Z%8-%J?>lqrML zPxbWYsmQlTi?&Gfwzy!#UoA7U2hYVMMmGwAf2H{|AptVZM1x26OI=98>y*T)^745X zo$^qnAMei=Z1xltdbK4}XC}Aofoqgz^pZa$X8}9vhevyE*wteI4z}zx?S=>#UQ^T= zShgeTbaZb3xh`BmVzCGekPZ!-KEIg`J@9H|LR1rZXVt^^v%}qbGj<7JqM#`QC+;0Y z48`(M4zPNoo;Bl~Q^SsQVC0#}W``FFA^r<=&~k+yQ>xpkJbtYu?>G}@41>P=@%=Em?;+iP}U)Crd)icZ0izi9fcGcE~ zi<5kEJe_i+;%6V8fgtDnJ-tw$02SL7@9;T!+W=5hqT}Lrt<(W`wP{ZhI<0-!w<4Tz zGy~}{L1Bc3%LhV~IK~b=81LTUi%b-q$NUZ+&c3jwy*f#etmgIp>3DN-^&`U=f$_Bn zN4YnbLrof$f=#;$_1*ptiF8w9YqKkC{xv3JmX*>*$uXfsHgU;EZ|hRX0t63|L-T07 zUO8rLkH+SH!mHF}bKTZl-&~+(kq8i$Uj6)rX#TX$=X7DFFRI>&n+i$6JjyebEmSvG|UNYvUx zUXl1SC7|y%b|W`9M$t^N0p9L>-{U{<?oP4CZc5vBq`Q|RyN7I3ris3pp(PLbjz+sWz<7@=on4_ zZn1Pz@Z3xvspgvhnJ6$Rnr+1%*_dN7@<#m zgbZNgle&iPlHIWpJ^Z{lj!47bUp~k7i>#SN=SY#DQ?d$RaQo(Vb>D=bgJQEg7p|Y- z#wU`B*)`~@hf7QRvFpk%WBqWeJ$L3~^RLM{_x-X_^Ho`&%Oj))<+`%~owR2-cs`7= z>|1X*EuCms-#DRDQL5D?=!9ySY73{K&v(qHV)JqOj=qhqk?JK$CR-5-EiP^eOokJr#5cz#0iQS*wXtSiq`V*~xN;%8@W(%9^iB1lGz>JoB*IoZD zy1oztj|6S2O?YK>>!~q#B`UTxfwLv7(H&2K%VasC9beP@2N$~gHWB3X{l_L72F!iZ zuak`|#Ph;{EbM@`o=RnMlo2DO+v9dfrH#9pEYTwn*-WD7?XE%b^%C zyUUyX;t5?XSZb<1+2zd%KJlZ#6zqC5sCn^kUlFZSOV5UvnR%nLDY{!=nQ6CVZt&eD zO8WKn_4Y24A^eO2fB9u>V^fNzfDlm~eX>Y=+2{}7D@-&%@Z2r;=ESJ&#PjMa>K`wv zKblNa)x^A}5%>88RQ<3I_`kO50K@_mc*7ty?>Vqhw*s@T?|$dGeVd-_i}rcpN7~;4 zn{b};q#g?I8epsPWHuhDW))mCuza^LxZjM;oXmuU`=91taZM78M_Ms7+4L9@c+d^$ zH3_K?dCL;*NNZeos+77n}Kbluko*TBvIk1pd7ofp3x`6#9O>Q~I$>nzl3{!-=@ z{*-)K(W%S6oxHx_GH`hev-;e$r+1Kcd!jA9yiu2?{p;*=)INA@!?aV^Cmdm`)y{K&cdw$G++TEJcqq>1)X477dQ5Zsgf_{nSEnYX*M{wy zQ?s{(dSCIlfTuWuv_V&(w1a!swAM`H$@Yp@l>s!JlLe*xkVMj%v(d%Po~C-TxZ)9r zBZL0Ea+FFa+huI}*r~PpLwMy5_62n&=JkWKZmGHC92Dt=FP<3Pof4gfLM`s=;N+u? zz%L-KJ$qrq2W=;U?x3A8!v?qiPWQFbGN`^g4Waf%FjG#|N4m z4?zT(8(0sfUmZrY&^h`m@@BrJR!QGE-1PI~F|Jc24SA!5iIHgzDqAf0SZ#)R@QFX} zR`+Xq9cXJ$y>XJ3{ z%$@jpsPdd-x8R5q*AYm{59fZ)x>r$(c^D*DXDJsu?D!;kaVa%;Dt$~nrZo_z?jPG^ ziF>3~p19A(}&w}lPEaQJaE~?3*7I`U0mGiOQ=ly8v z)wZ*ELOCzqOH0YoC`6-J-z!sQIfO3-N8}I^rksY9-v7bXTSmpvFkOJS1P$(z1b26r zK=442A-KD{yGw9)3Bhe}cXto&?gVF>=l#y^Ir|4_V5WO!y6oOtRd85ADT58%am5*f zYSB9yL_=!J$E|%qwZ>dEW7dWme}_0*epywBftR9WYxzt@ovNuZfk@);_*3wWsO5ri z!*Vb`bsI5_hq$tZyee78G*NK+#)Kmmo9%sHMFqKd%zD_&RJf(7m z1>*a4#DJxch4Zed9~XolN@b>QAtxgZ9*e{9NncpEyYv3?Dy$adsfff2Z{dW=LNkfA z&n0=)tL6UDid5M4EfCEd)LzDlB^C@6)V@-#*+Zk<-o&r{12R*<(0)tKlT<_}Aas7C z`Os-TmE#Prt8u*V>P!N-r)f6(A%?1r9o>ZY1S9-?kZhSoZ7?urqv}26q7sJ>8Eyrj z3I0CJLsZ&j#DRc7$H)_KMMdx}_!1fskdm^MlYe}w=cyskjZCT!V+0cbTe~FXw}ebt zl`=x2S44Z<%SqOG=VO5{gZfc*-krjuB21Iu19UNFVr-~Yr5w_H8>C~Yqek1~*?wwl zQeY6z(MnWg;BSrScay{VJGZlys#4GD-ZXuCT-jzHK7#|??!yFv7f`LhBXnM%Lo?W* zC+e34CHrp3hgnffI^sc{GtXPd#c6QWoD`8M6y(gdyf8WN-{elYV0?jqaW(c(7>r$q zs%DDPp0*~Gq2O~2nFDXrSNMur{R<{0ntZAFcWt=FFZ$491??kv^jl zkR|%RVkD=bRsRx)OL#reI&lE~ns71FI%rkY<%FgjHMX^vXjv4J$UFJ4~Kf59>!#E=J&)3oX=^^MHw2F!~`NiilqNL!-P{ry_oI@5b#qqsBHL$`x&2bIT(Ms3Esp7#o`?AWn3_8nEw z2F;J-WciZ6fSL+6O&i@k-kL$DgH4dW^Nb~pcyzWQO2o?@AAH*7=}Z`M?0hOJ+YfZL z*&te1GcO$-%6@JAkeagfWbF5Z%80Qgn@ARN08I_r)n*x*lqzgycO1_Ct%XAZ^;rg! zpPaTM!GDk*xB2!>+W_!jZO^St`UcZxl;wYO{{?ejQR--uEZ;RFTVwtg>bA_4RngRO zBI1Ay%e94Xb8`#GJIUdrv$rSl%eA2hn+;gMp>2r%WB~S%-~uDZ1^}g|7_hk9qM2J% zrSu900xxPgz%)SQiI4!qdw-;lw#_t8IMeC3yuP?NZB}{&=^_!5NW1zu@*`jX?B2G} zF-^!6_QpyZi9^W7$|WSqe^`aPzyQg%Jkl&+AuOq}LWeJ9%qb=+YIi{dossg9FpN|u zzM3;u?+x@-bY$uN^42KPWebbVT0S~3sH;pPHXBX37})l#+o9DggQCWL?gX#xU0-$6 z9iGNI*KR_&(wP&+6c=w3>}Cf+{gvtimF#5kh{baO6pr*rDScP) zEpfn!U>%k>mY5WgTx(=0jKdH`yUAQ}Ux+J!2APD^NLCTCgI+4qu~jvOPVHxr~_is%p~i~Lz% z5(b$bb?b0_y&b*~$xEK@>Y<{n21@qx=W4#<-Tm~?472GN+&7e-&@h&*4aGa#Kt(UH ze~AqtRdEZy!Yw<>c&p)b@R30mKZY!_tjKDd2p5#eY8u^Vn<2`E--oEMnT(em>K|C! zO79xHX}nv}@0%%0f%RyY=$M^ayo z;m!8b#GymdkX&1F%IJQPyfYn|4Z84k+JjMO?PpYljmg|&jg_dzUjvMiXhw^kL+I z5~v`^DB+mZ6~7Ti(^B^P*4E+-DrR;1M%?vdsXcd`qASkB|IN+q8=>Pn+3W-RC}y2qCTGl(T{kfEa*33pkrFlb{_O04i`x4|dv0yI?o*)FS_-KukATWUUGNW^(~U ztLG%xFy(q*s@kxPsp{URum1LA>lq5cJ@&01NWak9asEQ=6N49Y9x?9T3jh2`hA~1G zVPHliUAxL#Udc8InwHyt1BbkqiSW0L!%-&({dq|}U-r@iI+7espOI6_gxUl4y2(m2 zYs#4IguvvjhSeq#lW)CHT)oAq$3XMXL_F1tCEV+1C)xffLqnxH)vQ5{ zAn`z46ny-jo~RKq9kv@7DzDdC8sL>$Yv{>i2Da)bt;b65!Q$Ky<!pdWignn`gY zs^A9@v{bpJ2LhcNamm5mNLf6_0>8x?c%kSBp&7edwH&GQ>h7-Jkk#&Fk)`EfAeuPe zZo4MHQrm48TigAR;yqv@>FBJp&S*;u96t{&lv7??sG?s-3j!mjbUsD%4^786uvJXi zTmK8Myb~^~HCDrza3-fbrqr+Xu+6J#U%iU1c*0Y6!OSH|Kip|P|AQ)MzLV0GdArqE zt4)*xn?Ou+v8OHq?UmBNzblp17Y4QKTgrmVWk7OPbj@zZFTyr}$?nXr@wv-J4U@`% z+QOZD$XAkb#q2zWBKT=k$)cQ}emSA?Etjs&D`?}I9`{kDN~e@aJK2fF06Kw?(=?(_ri>E z(;- z238wsf?r7`ZKv#xEat;QLW?}D`Bs8xOHR={6zMqw3;n6g>Efz%+1cV(y4w1Sqj{>lx;jEm;sB>_ z|FjPe^KH$rzR`+ue5S`)m)=-%c*Bi|7A@`1+Bo{c2Y8LULw}wuY_T@e2X4z@tp_CJ37)$+k{+~Q}%P4 zF>n5q9(8=#6}}b@8G43?VQ^TQr9ua4B*MRJZ3N#&ZC=6wOSVislb8OdshV1l*V9&P z>~DBo?39RXmP88lGP*(}oNws6sML{o1 z93W^k=fusXW13Y?;MkaP*RJ<&uk3w*c?Y4h_s*z3S98pmn0`i<7@viz#u?>U%0!ZZ z;}Pi_uf{!Q7~vc=f4rG~2oBb645_-Z?%;OE|WynuDyk zlxT~At)imx-FYq|VzTVKJb~*q`Zqb#f@g2G9oG$5XHzvbb7_>!hcmS)^bED`EFzz{ ztMpA%>YRTmfoY7KkrD!wsw|0e-g_r=s@5coNw#KL;^DL`7(Tjbq3 z*OMP&c}&-@HMcZ0qMpMCHKGDMTS&FR0ITzfI1zPW+XS`vU|)*9o)*)TH3d{o{=(&HN?yKDQoBrR1?WuxO&W7`dLn*AJZ zWj#eCp|Z)|cJhzFhSGeToqxf6=1uUa^>r;3i3s8KOXSXz2NW~Q0rpyqkZ{qq2}}dt z;H-D$<)KZ-k(&Zqmb|PzGW9oLSKB$qUZ0m(mKl}uQ(!eeXvD#MPD9Hpxg}A-SH2jHUYi?ds>(vXNm2uNvJdKD8tQ=XuJD`w*ScSvxiri`Wcw zMI`7di1!#P8ATuwLn3gnR7(Yj_jdj^IRJebMMV*+f=2w$&JZL}XQNCz@lG`Kn#sM@ zW$yI+cg#pJ0b!(k`<;DQX}vG(|~hkY0`laqj-Aa>i& zbylB6S2*)bguOC|&ss)_vFf8BFBsfc_1WGmwaGnVj4##PIemzS^cCE3fTMWjjqd0S z&Xd9F^Y671&|J%$6*42iXLUCfV(;I~)!~`As4B3HBlLT^l%K2EGCAHdHq=!aE21fv zIc_(=@^X!pAxwO>n(A=<*iApudv zgo`8Z*j~RqH}t%toG}7=hZ@r8$y|+~JnF(BQy1y?Iyh@jKEICX+WV$4Mv}9+t+-OH z;qf|TO7ErsuYn0DTbBmo(Z+g#ENitX7W)5C9dU+jQ`Rlzg`j+mCZeIiLco0Quu*Ck znt$EkKu;DYa>_n}XOSV&+?yw-p9qe2H9|puQC8eav7RM7KlkL_SYgo_ulr>xwX~r_5@cc zsb1b2(CjhXCzCYWJAp8n2<1pZEGcz$rAk&#w?#zIhoE@1be(&6(9BQm%B9TpfYERf4jpbdy3egTNW zN*kZOiu5Q_9i8S_PCsUFnIB_U{QBs`I3B&9b5FwWwN%*1kSYR znTG%p$T>x0W$jPd{$?s$y=O6iMDs*^hwM&nj#f`z(#{4lfyXMe0}j0_{t%v8)R%y< zFTEb`AVtYkILGB(mt#)|UYBL7?xdB(8Ywwrkt&?7z(pr?2DhDmRTVQp9(+q?)KafE z#|D5h4z0S8y}g}IHuCa&wKoXwwZ!qOs1i#l-m&>vWH64Gh|0o}A7|7t#^NCH`lGdL zBk$Jcmhbmi8*r>!yYJ^z9wJ_^ETI^~UsBFr;#xHuJ9le(m#{qZOvb*FKWGTx#)?YBwO57GR<@Ic) zvJixw{v8r;b)W<8o0pvcXm(!=wT5RG8933eOwG{J{4he#iZ-S*6gcP}KF+=Tz%T9V zc7dAKH=8~yF%Zm+tMxvsjR|}$oV%4b^zCbL&Ki*FKpwCbwlvVOjj9W#1`si~mkQLs z)9ojlJ^*Lv6tYB^L2hm8>=Pih1}-qgz3JFEX@^6AuvDg`Kr`+FJP$CaFp9 zgDz8g$R#0nb1Ux9(3-mq#mA3}0x4)H3<5AJ>aI$$xP_#kWMqgLQri_|57X*JpEqrL zS6XVm`#&mZRGb1M31u+{&~|~*um_cBAzU_ASnXc*IWhMIF!NtVyJISc02?*T14`aY z%k_12qzpX6`D1cQn&3&_$qy*W>NWiH8+30K(qC+lAadReEEe4+Ljc}qw&fZVDiSUZ z3>VwlcF(s^aLS--@#TIXE}0*F!rMa{e-?lI8EOc+KFelw+^}rUpYiblH7ENVB5B~~ z!CL07O#ozAVVwWSfJQpbZ-I0LzMB_?Q&06Dk)a#ZZ%f*;S z8zO&W!z{~?mWx=&YXbhgS~mcUr%vy4ys*{2UVC%4edF=3-cwJs{=Utj5KmLIDJMC*nVjD)xMrEMvA1qmQK3bt~s%g=-64K#=W zM&N2J<_rdPMZs8~Fc@vhzY_S>)|Lm5#{2aS;NR+&Z^Uj1@6-e@v=L~HSfwn#dnU;D zJ}X=z`wMq~Ik5klZ2Whs5PzV?{=rR+H|$BihUJj`-OlBCdiD~oP|!@7g>}VT9^u^C zHsEaBVcBz{9m)k9#ZlPsQR>VO%wuW5! z&KA1n5V`)!Ym9qvaCkIWg&KuFUybM&^_M4IQ>wcilU^%*bTg7@@9i!o>#m|=>|m}& zBr&0c*2zW*EdcV4RA|J6@H@l-;epn6mvy2O@De=}VtXrFVy>2gRbIbMbPsh6hDQHj z-njp9HeNB7@^&m_DL1AoGi=u4J9zbYEk%jh@waRJYrW3F-}xpQHX9p-7v2T=bI1Rc zD?iWE+?r}Ac9BEa>fliUslxKl0HJ~sRJZ`YP`>5s6BEtL((``hE~9_WWPq=V=W*y9 zE8jvpt_TkC#HH&Iw)#S$Zy;05pdq+YM-gCXNy?gx45mpnab!mZKmtzMl~U;;uQ~<` zK5EseL__un>ZTg_eH3`Jo6hh{RlP2ML0gLfM;F9SAf8=~;x!mk*eL^Fa$Z9#*99yw;+g#`xn~^Ixi>cGlS(@A)Vb< z8MI_mFQ2k53v%*1F`DIep`-wER}Mk3D={FwO# z;drC_O4kJ`8QrsBxA%nexgZ8zd|?r5FK9pL)}pj)pks=AZc?{-hH#ybv7OC@+jNLm zsg8GK1^%1IZj*p((XRL@7RppD87vUx=XI_=?7Y|&cfRZ2 za8hg)P;Z$)q{?j7gM+cveL+uuq*3N01mv+6e+41de5}5(&kD9YNcQ>LtzH~GNgi62 zX_dBF#vrcvG7~C4w)Xc5#%qvZTB(sFK+0!+zCQOe#JY6^7xkfw4pe+HmPTNac`|b{ zAby=tml{4jy}0+H%6hq5_G)jd$&_9u@KxJpQ%A*t=L-Vv$j_`8TiX%PsbyWN^Vc1x zRo>cBE&e{p7T;yxv8bTv^u5lqKyrXJ)pL<`znwXkOYM5|XC z_^#G}@^o(`aWrDaT8LQUiuSc;2#rCi!cVeC*Y^4spT6vS&us(L>(^#yaIEv@U25Pi z(4}3U-=IvpfYcQ@$@v^@Q72yp%x76Sl{}}Z@A|Mp02XmGxc&@>lg0p8^_ANf;v!2|H8TA+gdJo*ho;pQ241Htsc|jd$bTwOjJ! zl=+ZAHrC7-&3-uz^?jN1Zlk}5q*10bv2l2=a$CG(e(lEM)Qaovr*}~juMxnXT_G_PnCvAT9hTF>1iXR#E16;S%0+;( zg9{p@tFz^-^!<$ARFE+}oNq}`b2g6p*FGPu!P#20qcgZLxZYx>kum@A{(5HIQPq;S zH>}nT*?PYxf~%n-?y=PT_LzH$F9-4%EldBQUku`}r$Ige>|8`L!=6d_#5T z&d?W%3PMM7{t$VRPFjtn7Hq1Pg1t|6@b|7N571S>)jsoC3!V3$6i?>;))@#JFQ)Fhbx9aK5Vtht6p2= zy8I}N`VF3FNpPpeYf#PJHLC_n!E$NOp#(k(7fHW)aZ+p^e*TxlXGRTDeNEEoWx>EY zInA1Xs4Lp+-{4l%8*I`mcIvD$)r(~WN9plZjGj7I!CASkuQ?*Pi~Wn-pG3vNk0eI8 zT^;#X{&92xmV5ICR|&}rmwg8PgYkdMHDAF6>NdNpp`i;IJX zU3e>+_u#066xWUdIZ2u~Fi<~5GKveUy~HT9hU2TYVrBTenwUT0@hc9*f0FCu4L}|v=8LmweSb|#Ru+)Z4qf^Q6E-$$=A9Uec9g7?Rotvxc=1BIM6@!7p zsVdZ7cCLJ|$c>uCBdor-{m8QEvw-pGQ~&bK$&U$Z^$yGQQ=_I)(Y}s6So@T^%?W+f z{(usp;WCt--8nTv!MNU!&JSfS-Ut)kghR5HJ^oFwvKjh}f}!6~*-Qxw;!=DwZwYhq z?*tj~mLi+H;VJvXdw4`8v-w(<~VhTlbQN$q_WQF!DwGu1IRSXAnDyFlSMxM;6@opNkuoD zgepF33W>b70m2;IOr&sVI3T=h!#$0n1>jqyV=lJDCf!CgkGEIm9`Vi`=JWgbhT5lC zjo+{^*zek-hwBT1g+l6(Ewa+?Fw9cJY~uZid;rsS*V+@jgju|)DVze^FsI9uSEdsd z!WwC;Yp$$~?n%DGTdex^dawad`P|bDpCOVq77nvNAcjehrZI$p&{cm)jG=95CQKyE zCOHpKi{K*iw(OHw4NkH8-%wH#^VX82+qB&g zh#?~@E5Hng*-^&b$u7vDy-ou7RH>G%HcN^+JXB~8QOhqZGGuV&{4x!Nu{WnFTUn3c zf(GwE1Q03JTFL{1oS^G+)_1HRzt}AJ*H})h!iA_Q1ufUs#6hY7XuzP%E%=yx)Lozo z?gG?szGTCsz2*~pwMwm@6li-fDuVG!_*GUG0gs;AXf_1Q!F?lw&AXIIh+8(}fA-T; zA%5XX00UGO(6)V(quFC{d_g~35yli#qBa{)5VT{(5EeS=58Ro3H-~)-rYqMS^{aYq zXUTJn&FXwPhEK!Jghus1=R6yDq}&Q;#gQV!q)t2H8!CsT=3SgsL7d+q?s0YbC#zl%apIOGCP5nB=sWQZQ<_lTa;8ZB3BFC_;%W7|+%<%hL=yFbUEi`eO+jMTKNr@3o z#MVv|KWg?ARE@mhzWtUZ303Vij~i#@LE;491p)7=_@TxDX=t25z}Urzy>kCswkitV zbUTX|beo-B>jjgy@bS`nTG&`?Q5#Xz0*XAE@xO&vfZRAe8@0+z*Vd0J)tnW`Yhb#PFiL@{$XOsv3EKsFs3W(c|Wny|z8mr0L(pq@k=!s_}^nt8(TIQJZTCpg+( z`g!ead`|1OKNHyIH*+9pmET%~qQ^fE{y2_ZORw_Jvq%#-khgF@nHa>wtEzr>obe^O zTiSpDD=a3aLC2au+Cpsl=~wL}pd**!vJ-y1q5oY23T*${B*2=xhz!3QByDeAN z={o)*g|FFQLFOAvaBv_8JOVy z6OX|UyI*Jqs3Z*#QYE&vwcd;V;6p0YXMx_aDi6hT01&4k;Y>L&QNb__qFos(A)e?+b3TAxU!O?$Heh1_Q3_v5R#w>V0v0_UOU`t_MH=;j ziqaSzMm+xSgIyjPxQ0$)GQdJAdI}0JL$*(7kE6fMpT}FWgm+SP);$Ke?%(jJFaoA^ zBLf7EdassjvQ1wn8fGVL!G6pZ3(K%8i+85%3+H6Y-!*Gm54dJA_sa)ZX;QEyMiLE_ zJQVQ{7R+(NVp^khDxCjDt!#`oNbFWW`)LUrA7c->>HV~e`4%mYr|m9{wrsaprG(a5 z14pU>ZE6V}kVCEhhdTR6ALa21(DeJ7&k;en0c11)c6j@iwSxYN-zD69b#>p6o&X?N8i9UX=Y^P?iPC*HE=Sf$YN` zSXH~6R0fMm9izEIJFQPePRBR@a;lQYoGPh*58tV?%6fhb53Z^^9vgMfpn(R`;Tm#B z)OI&emNJIisMn1Xe?BRMkuVSMFN>Muc_c!u`-)odV=ohG&)}B9ET?bPPPMqd7g=&9 z%JJ#2vVBTVI~rBhwJxSW3ZuPh?kalFJjrWW_EKctT8pL7x-Ma3;i=D0d!nIC(vVYz z8wW|5b?M#{cM<{Lx`V%%lMG=6<1z8iL+qgvE8xDsp=!mq6RLu;Y9wF`mQ;-YCCz0Z z{|7sZQRiK0-b{bBYuC62*keECUu=!qsrhlag=X%2wmjp2bo=5-e{!{J|17OMEfAG7N|4(Cd+sytCN>>43m5BIJgk3t^In+M^Qd>7V z)v^s>2Fkl;Hb<>e8`$_5OD+~%1x&^u;GkVyd1`h#cD?9=PX&Zvz(#F4pkIT>WzCIB zv%$Jh4BiT_0_Ys7Hl6w;_^^Ws1qGEN=*24*jJyeSadh|f!TN@fdZ*mnII31^%ZZ3U z8uUkQ4pC+ATu;z(@2I|M7;k8V`42E)qz=;pO!cpOtq{uMv^q8za16rD^D~Wh-e72>*)okH#?Sco;vxa zq^P2!%XwuBg@$=Wr7UipqJ7Z%Abdqy+0}XInj22iXof}r4F!&4cO>XlnE6LxH1j24 z3BPi0nKS;)HL6OeE+mho3&dMl=WSR38*kUhL<8=Tf|T*elAE5C#p8`qRI{*ExfGi( zDA0{t7cg!>c@c5zRE?7i>ZIy8Mw`2gp{rQ%n<3{ZxcBp@eCR##Y`^!aa#M)olJiHh zGB{v|YEPGZzRL@Vp=2|z#q90)zIR}7sf`a~;`(dn`(17>kO-3Sr;qA7Q$Dn8k?(%z zvJ~r+gWmNWiVdM~Ma2@>kUwQd^>&3BrED?Me!2U##TvAM%mjYOdWRd9px1m`Cr&*) zX~m=>czS~riF^ZbHn4JyyGUmcK7VJ@Od26d$c>F$l#&hcz$87lR3o*^zRQ)szh$AA z>iucF9RenONTInuVKbeTD2?HWw>s((@gOz$%+e?KS(@j#3m49Sgw_?OS27Ndi#Q=Z ziPH?dD7C4V?&(T=tomSgh|6M%7Qi-GsG@Ux79I0E8)dN1i@ykm7L1U_z$-1_@QaLC~!!KNqOWe&+;Erxj#($f47hF2#p~Y8!57o z9zH=5o}F}!PIF)`t{V{2rTZn#My4dQ&Su4hSVFE_g@JYp zRcD>475n4P<8A7=$C_I-Ji5^1Y$`@91WgEr_h`h@^K#|^ zMR^KxQ%Yj3_qdejeu^_HVk#oy%nih3K{;d!7^qxhf_D7e72JT&tlqa$bR%MSQi{$( z(760WVn56dc|-Hq!z>u+2T4%MB4bUc)rz$$>cK@P9KtK=@zn?MqDfAd*BZv?sZH zwd{#rlx=zSmnBnCy3#|I8h^y(+ncuHt%L@QTqlQtJJ@%vcF3}=`NY{kDShU6o11mo ze`w@x!M&ZJF(GB68eOQ|v~BBD^Oysg@ozuMJ>oaVXV=1?D+)b9=vyC{@sJz2(`@b7 zr=%pcsks8WIv2emBTsP^XCz8kfxggX_KHmSu3k-R-7z65ZlHS-&Fco9RB$-};+*&K zYFnep6HJ~+5hiW8Zx+?W*TPP50=}EAgcalX@LvgFSAJc7{!M`E>v#s!hL8m+lx@7v zLkJnJXz1}&x=s5Kun4Csg#~0ILF#z{DfDuK2{d);0Xmn$>5iAXmG^EsV09}rIzIl; z(Ojw9zg3q9pdn20+k2ZLu)eh)m|_Fj2`o?xkBLEB_xeZt`D?V{M3z7qs6HIv;HUCK z?qaV26_XxNKL9JJvy0?L)<;^&FL@HKf(0wPNR<_hG4aMlvYXHegQrqrf*c_5l$#IV zxF*=`ZH&>8uJ6RA_^H2qE{7lMK-=D~lw{jjGb&i3m-%K6-7dtsIliEAB>{?(#^71Tc?9Ft3*iH@`w~lfrz@&0^^wtT_li^vH{|{W z!Xx~|8az*(9$jzSa4NsmGP!~ti|Mul&ko(5k8N~I7DF0X!&sf|W4$*9iO34XAjk(A zV%U>J#+#8=NT(9I)}KU%%I<{3N~_+OKgFTTwBM3tiGglyj}gMY=9|q-iN*&;@8Tg= zPZ{Gatb_-C8ZWFd&V7dzhXVnNK6#31?l35#oCyopzq2SZ?ck{5>%GfpJ67WeMCw*u zuisEX5@stC7uMmt>EV5OazcqGGAh^5_j~(s4_{?wAJO^!!Pxt?XFtdYYgwV19xwCg zDbt7>Y!_1`+WTPoYj2v(xCy_@C$#YYVGbc7-us2lOT7L(G4z~Iv3DDPu*ntWleQW_ z%dXpMM&fiO8Jp?~-Qkkr$IGY1^khIt9CnuXl0BUd-&@%=t&PMeJtTmFgOucH^>B%{ z*3WvU1vCuV>uF;pnIuET{;h7yI&0?$zX7@&r>~b-XGp*)w{>sBr+qJ^Wd;wm3P~Vm z-gAB$&XoqOBvwxt%fF$8`ST-lem*Zq@aa}WG=mE>MTG_3S}q0;=Q7VF}W@j%cfne96q~#KW)UA2hfMpq@Ga+5i;u! z)v~><+dz_H87;Q5&Df`3z0!a2O!&|x{UpS}l>D@hO)3N5a@&~@n?w2;JYZ_B&1jr% zFni}p<3?YIgC#tX)i}b^=L^%ih?OvVl(VjOtm% zV@l5nZ$1!sE$z{T8~l0}J+`tLFgWm4JX~CSxpOV2ZkS}plS-lKDxLz!iUW$K0Vt-MB`;^9|8UstTOPY6ue zymB49r|(MeT-sF}%Nfj>@M^*i zvK@_XYOQu@UpBv8JN4GxkF%o77Nd`F7AD~PH!a@Os>H;^pyFbx)YMd0*Fi;Z0ERXX zfuB;2$?>~7xwhD&{GbkO1WWNXK1!_u zzPXVg@=c%cZN(b~0zTg_suCrM6d3C8XKwB<>iEROz}Q$+W&2||-+8NYwvhQOH7hIY z{rcOhnmMtMkkGr*jB@dYmersix&7&k&-rArt1AHBZ0-;C3fL-NCYjMaZDT{X+3~P@ z#inB{jzR`lQ2xneJYy;u7YAo+YpZ)Wk*?{uqUDZd^*PfoFE6Xp&$qXGfJq4>Klcx&@^R&CUOYR@#u@cV;q1=n4Qm znDvL>3T#XZX^dI_({F6CI^LEJs42i-PE=c-oh+9XMSKPxobmrE;X&t+rH3E5Sw+*A zxS&GP_mmnBjnoN?#wBD#7uaT)3pgHhQ7KEH9sGdh6m?N zCAqOnS1BA5M)U|YU>DcQuOtnmz~k)ap{(p&UoazE=t!2ML9Z|7onj?V=t9;D%B~x0 zJZ(*V@uPp^z+=vT91pmaSUDvWxhBG$2Df`o@s~UOum>^442TSxBeqxLrBRt0)z4di ze7v%)k`IsXq9%(XhCRBhuwGEiNkl4fuGR4h%5f5)jx{?2#jV`+I`SUyNy`2WL!BgR z%s|VkqYa9NY%*7pGDbH`S`#&TMc zU}EU~rNm4bgP=b`!hyw9K`+yp==Rp7543}`a#zv;t}xN1XOpH(h@JRRa`Ggyq)~8w zg{au;vuPIO*c~uK1Jr_@XuGeQ2t)>o+m|x>HNk2!M4b) z=e8gdp@y$mBN_6Mcb;GSi$5;q&ULgNtxenRcto4(b@$ac2YAAH_(@yqpsm7G(5SF& zkp*<+3f^n5&Ar2KJfvK#lYWX+PrOZ~xpb>}`3XWT)?@E%tS=Nwj+k|SVY3)BnUXU; zZT;6bQl@}JCumYm&D(*M$>xr!0D5wrZmr_$P@gH9=df?g(%{R!mz*wL`f0UtTwjB( zqW>f!LeE~dFaoOKAM_c)3cfN>|u8hODu#Kzdax(Y+Wcfm>)0x%w`0S$!I~Bo5{!( zW9?_&nW&doSd|>N-@fD?ywsS*{5%2KG>jINEADZAlTDt>GF!7EF{@~DCk)PU0}&!( zk_{1B4(15oQ1PFVI*=M$LZ$Q=v>mzM6EMAyUe@VoR+^@8)(;vUD+g?~Vw`N; z=?iK8x6$q!O(8Jip{%vF^&|-w3yV5_sG$8}FWo+I6;v5p(wa6v11GPXqhk8|dkz+K zvDtORYXjrLey)meXVTU!9HSCso5`V>sHlov^IEOSK_|tsW9RvY1p7;F(|-%RLS(uT ztB&G<(?GXa^!L|S&D*QRM2?I+qf7S(QPJ=##ILY7S%uFp4M&GBFAcP~F<;usKC+2n zZ&G(F0mzf-Lr#KPt*ez#_|?t7b@OBsTiZ*{Z%M^F-ic*uD@N`b5lOHxmQy47=V}@& zc#Xmz`SV?~2gFN5ryyzdg{RsB;SX%SNi}wSNZlxW5$ci&3Vb>q5$%D-+WZ{~`TPC9 z3^hW*uLcLZp?Jb}?b~fPZ{;JF4SHHQHSFRNk*JM3oMHnWiOa$5UKU;`8AZudy5TaH z9@7-kEViJf2jq+*QC_Cm>&O&*kY_9~YLN6fH+MOtz?4_t(f7qWh`x5EeUpW}=x+gib0iq$P-$Pxvrj3*Xg{%o@1N(nmEMGUg-RUj1I3SL*o=Q( zuD0^4&3Jg_)~E~7K^pnY|2c9nYwH(B77lXM{+(U>2`(qQr+gpzjV}p1`z?H&373~E zIFNqksv%3+a-?V$b^;ccA?B3FdxL#->X&(**N*lFQqMd!c zSDC8c5y!aGRMr*x&AtV^6=#sGt=&qAA!wy$t6|a6d*giPFrE6< z=s>&3^@Nbl9Bw8z`ij`ppAr4s~G}h^MjDnas!xH zJ9RxcIH(J(ymvfbBL>hfJbE0YHuu{n(3VSlFmSJbtt5k6>i`c(~0u{;bG4U4&3d{hQ<7zC!Z{7;#MZr#1lX%Hn!+V8b`7GMA!vWk`(vZSlYw;vLX~lM>Vk+0mP+Gh6s6bp}$&atef< zm>zC7$C37Fl}xc<{74SE4YWg_?mu|Kh8D*Yjrhm2LC7$XJA=T@mR;bEzwB75p5BZ^ zF?#NC@uph3@aBc0__I=)1*8#iw^UJOblS@Z(cb(_Vg=_9%<6$42oi{J_BYUD|O z&dT(k>!n2D%eo*?P!1U{={{MZV+J(+V4X>((6LY7BW78ClUNDm$=Sus#QD}qgE<6D z5BOLUeHe`J$p@{+anVYnE&$HVM@)=` zY5?7?%C*DaKoZkD_|UBI`14*TS$SEAXqap?dGm^EzxCMc^rP9p(v2!MlLEJ}?4^ga ztljb<#R!SRua_G2Z%pZeS{@>H3PNh4h6Sp@p`ieH@wS|FN`OwH{oKLBoe-*+o;T3< zF_}nI+>|IVu*y(cAa14wW73d8`p^qeCM0x{drJj_rP=@iVR1Ocm%dwH6d@`i;1Jk> z65~wLDEX&waqdn#eXP%jMuRhb;d-Fv_9{;l8d-@VrFS?jyLJx|>CXSlBOJkH}d&hz^H|-MJHAVIo*s;%&sY;c1`BwML=0*DiJ}CKhO#UwPV z!;F%gibnzqtaWvDI|l|N^z`OnNR~pbOv&UZf^KWw7HHL>fn7EY=p@I;b z`*|7z-#)x`T|JGn?WSi(3W3HuUzM>%sHWB@R^LV@rjq@k4yO=MYNBQI`#uHF;U}`PvM88jddPE!a49{z!->Cy z{mb)SYz_<4eZ5?n>6){m!*}kb-f3{%dgdJCKQj|s=;}s3O{CnQyYzGEPV1|5l!g3= zLo6TnBswS7Lhm&yqHKLg=UZN8t@^=X>0P}D-$y;-QA-=7&!1zwHd-ZEQ(pP7|2d!a z5cT4f!|cst)B`df9B$V5eeAn7tNuEHIbOJV!2Muuki$Rc>9vn?y!GF=X)E8#@i)uv zXWFT+=3-IdUoLYq;a9!&%(aStcJC5Wv$t_(>e(b#%IWTajWcSC<^;bdw!6v ztLxmR;~bab?`Ay>;IgaB4rm{GrkfgEuraj4=sW91CvCnczr^QkTQs;5hXwl8nv>mo zb?jR?ZP(;%tp7E5qskZeVI1S0zCtRahUaS(x2jU}092;qW(zD{>$EiVa=&CSGG9^h z&gdvwrMdYV=SK1Oao+ZftBT_8$InN}{>c??gFA;i26tO=|4A8!5k@a}%>Bq687tjx zYBtd?M{2|Hv+ffiF{e(Q`Z+bFkD)hqe}sSICjNhg|M72?I{%CCFTOavZtK>q6GQc0 z&Wp3{EoQ}Q>;kY1#^=VX#?fY@{hxEqj6LLD^45Fz`Isx2JaqRuADfE*=_A)#yF=*y!-r)|?F*BV zgXwk`@|D?2HY}~$cxA8JT7^|N2eJ%=Aa4Bgc7_{{7bZNY8lxTGPpAGl}GqlJ_}v z>=NhP@b^jmZ@3H-=Omv&+x>6rkNj-Ro>fITbjO8-kASs7Bd<{oM?F()J$Yc*3I9H@ zf3H=s_MAn_YVPA(mcKXO`4|r=p+{x?&ayY@XWHTi_gkrx2SF~$M=0svr(`EFuT&V2 zphJkN(Zs*p|9`!XcUC9<8&Hnf7Y)S=rfNV&r!3lL@(a^=c=zg&JRuG$@0`{`2S0qT=FvVPQMT zU>e8lT7x>b$B*A?A3AjP?Q+METH{`j-!+Y!GwS@M@|D^;iyzwdc%Q%VIc!N% zQj+EO1{`WEI8@Qwq-egdut4)vhL&@yN|gTnD3_ri7MEjOoG5P+FV%Rz`_O5{H1U%3 zs+&iTz-I;d+sw*}rWmhu=G?h(-|Cw8ugn~ujmRWRr|MTl!CQsP?(FSVOtR|9KT!Di z>uC!Mix=&}ER1wYN$RoD+(y$FHE+JxdLT~zMfZU{dmGHb@?{!7BVdj|Xe=~nkpART&IkHGWfkQ)h+;1mfG~pOk98ejda^_y*iA+t&5gnceK5F_2uB_m-n`b z*rYUN7zfVaGO3xFnRdNYWy5R!Neu1Ii}^E{lUOUhI2VDI@pw(gNyXm&{ut|#wnX1& zLWvC91x*yNF5)gnUoxEgJv!qM+g$#FPv?PQdqKXWj7+`O{!2lh$-??HP!p}_zU5#o z*wH#nk*@`{TL)i6+^>=LL8x20&o7r zv$2VZ1NA~VIQ>gN{~y%onqZ4-c62BIX9|Ejagxi~D@k(haF0 zQ9^~A{3!`W7a(fZVKYa|1Xk+Rr5Rin0Gqz;KwUbm=VA4=S237m6))Ikb2`-D+xsPg zd)-)X1yx>h9=F9H8+g>Xx@HcTyIlKF43?YLtJhkUp6udD6ef1|WZ&w+&tJaCC8}r3 z%iwLXt%$+AL2g=_5ADm1v|R1N#f91O;^Nc2y}cTZJF*_5rk8P?8!eNMR@^Bpd?nqa zRV`67Uu^|F{m?qUNE2?;(kENV+Sldru}jRunUyi%)HTeq)pO%Ye~)$}$RzrfT=VW$ ztTjX)^o>)u*Hjnhi4H!Hv`+EM!shyin1~mH(FaYHxfp_42V9rn`%LF$##6*2QS6(8 z$`rpm|6XOq$v%VtTv|S9D zPZF$)?eETqNK7jtHF?XX+MQ((SF=V6W^dHSY|zNH?uF5|+P@-wXsoxdZ`^rt%K6C- z;Vt*x>@16qN$+7ht)du(bi(dmb7@Qc!?+vHkB3f&iaEN05`xugi8jXn?Af>PFv_wM zo~})jKTamIlRd3iTa3rjP~a$x*k}{0OOj<ehq6T)wZi&ns@rusBdF$ zU-R-bJ<&`)g^HW{Cp+AZh>feV_*-xuJ9ez0GFiIJOt(N-wb02ib~YaFul@m=v|<8R zL7}y0sBzQJk4LJ^;4R=fIGY~++REYAcU85t8+VeEd2hFv zKWw#C@a(*%XwJxs`BZ?L^3j)e?A>ZXPftHspPU>WTM1HY)4q#grtJl!jQu?L@xzBz zc-y&Ydxz2!>@s=c6Rn4v&dSQJ&(6-y%FP`|XtcoC)z^-**0D7eKQYic#cD_i*RNps zf;E|1AFs@dM|cjq`htv%{|+oiJ4s^y3>khMae8LT>Tg1s9YTWz2W|Y2VLL3m6{gLm!?*U zRp9rw3Yw@>sf&injWdq@FCX6c621b?3|%Zw96jWUS>9s^{QcAAw*>>@jy;eG5s|ol zeGhhGWb0g$HKX#kT%XlD+%x*rhVoX^Vh_f3<;EhWd`1M!)qadY%NDSNY+Ap*2z0y6 zWS#QXqc>TG>XXZ^A66U?Qy=EKTxQ&qcJ;%vy_SQukHGMMs|p34ar_O4VbGSB&02hv zXNsjQ%X~MovEFD`iS>9dOH$tI;CrdBU%&tGp%b)3-Ar)Sa_v>Scq$No%P<*7;^M`G zfpB%^rZj`%U&GBGK7Q})B{SSN zTrLF*eZkAantS7~<@6{%-e`^A_a?npDp)=ANU%Z_Y&%`>st)iiKG`M^_dx2lBbmvI zBj6&Cn*=mA1IC+Iha~4m1|LX>oaam^m>ZK4oBe)7Y;o=uB2g8t=f$C`OYwxMIw#$@ zuj5623>KaWH~96v@iesAWZ6eayuFF-6;vOeVnmEjI2=goU}|uEx{>myU}0j%H`iF6 ztZ;k2iEgPCASEF2Ax!IE%X;htA~#p?NP3Utj$#Z6Mnt)bpZ5Ow(=1oFew^<>lBk@V z9D!2rN=h1A>pfYI%P$rJ{E{cHl&H3WnYk?NLut#N=5rIG){k&by&O1t*XsRhhPA@l8)pU%!66fyS$vtXr3BrE1&@4jW_Qv2l<} zk6Zp|d6C)fbY*bj@Xf~8t~fWTCh>|OD=Vv+nb}S;v5>RwTRJ;BTo7<;jhRNr#=0JC zH_-+#wfLy{0MEz_8@8#^s6HuJEH6Smmq$iYk^z}hcyXq_aKhFi?=d1E-@D$lzLNB0 zuBH!NGqOy>GUkrYMQjfPkLmWj_a^uqVAmH=+8c92C>955l`PiT=}HG3^9JrvpQs~{ zwf7+Q-O!Z9P$!mL7moiE`PHD~f3X?Ms=B)ReMLq5gpB!zi3WVzKY^RrXS(z|m5 zx#h}G1`{_G^4u5#Ojm!u&6kP#8a{Qua);X%FLl2BQa1`#ZWBpX_8)Jp#Rp^FP!}FZ z1TK$Rx*11xf@Zx#~X@^mnkdP8!lc_Uz(D%;nJl`;Q50AZ5>1Y43%o)S*oaT@vk_L5nqqf$d2A@ z2&*?jC`2)i*Kk&5)22=LaG2Tl-{~ImkI8FAWbuPg0Hpoh4@1m$0IucQ;T`hE#>QGt z<^Z|n2D$*Fpk|XBbZ>9^cIqtN(n50yi6;LJHKJz?xHt&FjrS;5@Hs@+Wvg zKnw=P);v6ntxKw$PoF;dr<*F@<5nyrEq{D8hbf<;@=ne zqEZi0n^qqRaLNVWu#h_KD~RiNl{%ri2N+J zvmz3z67b0&A`E`EzPu^RJi@}vOqSF&v%iKfhdTaxLC`zk(PA_yj(VS0>H#oCM_qg& zPx5tm2AHv?Sgxk=t{H_df0l|OmdY$9HPHeDjG~<8M$c1yeTfvjy?1yxQPXK!SJZ=b zb^ZS7g^4ELXV1d1a-#G;1;w_swoXnR0_K*%2?5(lE!tlLNYzdo+;#Avbh<&!IpciriQC|MpO#9+Ov|7f^SUN_Qu;ktCtqt)vcIfNr#o>5}Sd_YPh$_vk+*`J6;i4Ii z@HxbeTq1Kk1*`@YMCY5*ji~qT-3t(RE@(>C_X=l1ki)Si331BFA!NziZng49;hkBr|M+oL;Qfo)IXPUWrltbsU1w0an7K}U z8|1?PxVrGOs}VRN$&yA8i=@}$+-s#ql@wEXmXjDn&t`K%z@YjJd8B%k0kP!YhuaIa zw0I`fY{ln(-XpYug|)R33J1l-=_=>%eiiBQ7Ebe%$}4>1xM@8$OzD9wI<;bobwGik zp62fz^B|CKn zX5R9P_WAKQ=A)vb;+8COVTmE{>hO^x!(&uZ)}?v!S{|e*V1dfVS+f^2 z&;HnR?3hZSo|+>T`XJJ=ED}r{7XKhfl-E~yjJfQYV%xVIRP(hB`t+RdG&~uIB6TE4 zkSEEyW5*wo0|sQdA?KSa-a;XVuHFs#T2^*`4ZE1SacfQ;kNEKi!-^BEqX@U$ML&+G zP(d#7SS24uiO9sts%{tzIhzA@CQ`Fh?ynR@E64pNvXZeCBj?fI_u6oAsH9c=VBg-ouJ`ZvPoq@IFCT|Tocrw3 z6#R_3B9Z`s_OdN8yp0`BAmCJSEDsZB)kxvuB}>Z*-9Dd?kWWw+c?(bcs~{}>%G=I6 z!LV*!VffUFz1WaXLqaYA0cQU(mPbZME8mL!`}Hwu8RC0V9ITeE^({Y?Rrmfz0|L_|fCPe|~C z>H^56^ADEkF7-&hk^Og|QwKad=W4asb4wT;-xz;-{ zz&W+-&!u+-@FO!KVi*c0UoCz>t42iX?&-0lJ+@NJX=_ zm5Q62TNtncNYNUa6f;SjydW3)5L2T8hajweM({z28Nr)5-+LBNjg%-Q+K1L}+_=>D zM=5b{ns=8HP8+9n_17n}6Ryd>tfb`XAr?>pQP5xs=S|8(`eVJit-nBUdBUp?cJ<7e zGqNfw?{N}!ERNFwbkuyhfM~~u8H?Mud9AeYjo^^;im-xW0Fy9j z%wgio`5@ujo(QzEnI;-bmn}me(E6T{Za-xLNcA8$R~SDnk7m06C8c79& zz?-tNhv+_@vWP$VXEVBO>w{8Nzl9VE`+OcfeY!rxdBJwy#pf=WnS$VTmhiL|hymex ziT+{%d&zH5eIMuF;gYTi=G|5mExZ;LDi4gX2D>Dk$3SU* z0_Y$Wd_1o+*=#A=OUC=Eh~Cb)_3(XySrKQKq@aDSU~$2o6rp5FseY(ql;BUP*Ve~p zp=yvFDcJ6CSuY30?hCBQ095t&6R%`$1pSUyypI?}>N1OSx6BG48@z~4pEXo_6Ue`CySF(HkuGnC`90xB%L2&_|f>ba^P1`;K0UWdb&Vm^4?3$5_ z>%ikaf9A|``>7wgb#aP}EQi8`tmXbLllW4g-@9N_01bQ5c*vnVYd6;O0d@a);o`hk zyVI;kR@Si$aH21Vw`|^g==%HhU<{>Bomz@tD1jgZ#^PCMXmYf>het1f%)8Q3Ty|&* zuyyXvq%t=9C%qN^sd%h_D8*<&bi*1(R0SRCH}i55#PZfd+LSwY?l8qg2w4rL067D* zk&BI2PEPu~;77}wI=r`i_mEdT60M}2U5;2j7$5{s2^pFF2M>DSRIi#s=fw)1{hQZ) zFmd!?7Y_jr1<%vW^+9VTq|w96U#>q@dl)2fA4HIj&WG$|3j;rwCDF%8eWuE+1*oylkWHwo7z z;%{$nKmKl$3}yY6Ev4j}aRmddxq=`*c@W#uhxXclF2W4#F{nPU7zp|r z<)XGE19?FJQ&B%xBP8Zn535ZIbNu=EcTB&!y~LZ=EQ*5cgd(=;1a9{QPChNTiE|B^ zjkN@gn|#4*{NYe%yxxkV;}o=n=F7uK2}_}Em$5r1OjV~@4#*>NxVgJ``&}_v5(c!L z2L}B4#eFEKD!^P5YL&bc(5syY2iLJ3a5@l+3&_C1W)@L9bdp}Z*^=cQB5E%$D_exE ztr@4BAT>}My9sj>J`WAyJg2?z;Gykm`tH#8ru6vQr$dsQxdUTu6}}E$e~hUixeaT% zk2}rTZPo@*7;kURGdXLb7U{m{>Gm~3|5H)l`47*s@SYTh1G6o0VlqY7k#kDgkmV(3M z;NVDUj*5ub4a$Qwa#z?Zb8K`}XWP6UsA^fAPaq zzx={@=wgb^=rx2leP&;)!HOIs{pjVPZj6g4DDrkOXH}*Y`k8I4b;zoX*Luq~A)pY|K+b2AjpJQWj z??V2fUURFM%h8`!JZwo_Q+ih_Ga0p~R+8~H#s~8G988-xHyB4F?mB?}r+rOdvn{7# z3Ip(x{122BE==;0DznXQ=pe9B`LcB)vYqUz3f~&<`1o9o6}oMf;+&w>X8+>Z$d?il zRsj}L9Hz(Q@96knR&oJZVSz+8p6opDj_sD$qPy{wo6)1csnG{o&2BG|xA@Ex2qwSl z3l~bj6hQ}(%l;}OE#3RxdpEI=xIn}_&HlIwIz8^{H9|lx5omJ#u;T`6;DQsuP*n0i zGTDTXZ4kaMLz~DoMsc=8`)DAqN(dm<__M<5vWIcADX5uFD4z88TWrWp=7mVaJbb7rXzr$~$ zjTDoRh?J<3swYj$P~5@Or&;>t%d6U3{s0KK0GY-hD=1BiUWCzs031}6yfZhP%L%YSR7v)#6SWrJ=#|_CP2pSe+wB5|_v7Qa!Ao~R zsfVG!PZGblgQR|xjwG@F2HdpidbIzT^FrR-}3I;X1+f(?$g$p~e^8geG z(oj=V%Pt=r8L5hqi@-BFfG*bHkTO7~*l0wJCv2ht%9^&W*yEcvZ&nasQd~jaNPBxI zXjF1)AB-qOr^skFi2%e9neOpn6}3}vR&_;aW1{;8M`BmwmwqoqMNO?|N5v ziqur$Ti}P#>3r)t2UJ`FqBi2od${VfHg4Sbz0|DmIbi4yM3D#U*gv6SJ_Y&uH-0dY zmtD|=6-xESP5UoJg4`#Kwy42EaDB^~KC^|7?!zpR2Na=|3~!26%Rghy)>wdtwdN zTgt_0SXdlhvSi84<_r&%*a{LMV8C?nJW$XoNRU221Q0jw5sRitU@XFs!$go;Uh!}H zS~}OBJ@@f@IBD)}0FNXmEGdlJ_}#EPI=j0s*ObI=s2k0T#9-I^>+7WdTC{k=p_4%z z>U%wIj-?J~Nz&botNz9uLp5lyD1#v2(bNY*vA{u1#%C-1dl_-h{Qa@4x1mlUxh(zY z?{XzYQC?1ihLo$-_9^STaytIj&gPRh+6zQEIXQKCW&tpg%?u2cu!7*dVy6%qJUBGH z{*ccH%SPM(_~K8ZQ!S?po#rXV{cpxlyJ}ZQN>CJ!K6&`p5f(mkK&v1K@jVDP`xDpv z)zaKhK~bESa{zC0-~Rpd6mjuFt||g`H*dX5jH*1K9H2!V_MiU!8&za0w>pN4{Qb1Q zw?iIn*WkYYXa8nt0FTRm{e{23sviFbC;hjN!{2gA{2?~}=EVQ)3&WrN|G)I-@%?!a zZblzb8DK`iO{ld|?(z|&-htA9yj7R6#@X2!QCGuwdOIWC+v4K*gNsIA5cSQlU_s;m zkxTJr(1K|qNe2}>F!d)vrZ|{>3vhYM5AeYnpOd)onDDCR(JPG(l%47&+_AhLS z=L2ke4J-g)c7BeIUWI)T759Jvp19)|MCbwL+0A(ptpVtG>Fn0#emVPzj}fm?(L@9Jt2;!K@DPaU5sy6YSCf&o0ngV@ zq#JLzIx0GPyvIjo0M;X5b8hc0kN6>-6%$Jqi;ajK*)mE>5mz*H%;>5 z#oA0q92c3Z3zHr50n)X=P3?n%S^=)(MpGImo&vvVTM(e3KlDof^1f5e&T#BW(JJ4+ z?*Iu939^q=nJ743nF&Q-4%6o^oA~PjBA5{LPuq2DA#e>ck5CJIsn1P2Ui^k3j4E} zqIMHE3T6hm!FiGL74+&>kO2Ep#uNLNWh;1(X8^rp?{|B3^!1ei9@~&%99Y2w@&lvW zHIb1?1PkmBvAK(sZr<~L15sHJT}jykCG~R+!m=+3&)6p~0CRWve0T>+;<#o1)7D?8 zl8MuE>k&Oh9v&W&>0)9yAYa`^5v?<2_7jh?`(K!IF;r~F?c29e)Mzs&)PmSrm~CJ5 zYpQ~|Y_w57l&GZr<5*p1P(hAPO!N>s6St9|RTzSgPtmQ|LbyPxsy-@aX2#D=xC3x& z#r5_6_-pM~Dg^3Co0%N~+Zzchg$ywzFrI!2dZsz7?)E(PLe%TDw+nxG5c;r_@uEtA65< z5>Q*}xkCyLEWinIGK>nG!(5;EB4;Wagnb(r`5~n{x(a~B%(%rK^0zr0Ah7z^z9yCu;U8J|u(&rc zF`ZRX+JbvKij|{-(87PSA?2gUU%sCtolBA{&81c0Q(an%OE=8n5QxGH9P~cV7W->B z?Z%f=9x(VcW$H|#A%^1wJb@aojFsNuDOCiSzEUAl6)*QlP!Ox`(LfkE0e>&TshVyx z+Er1W8cr%b3i-_jYCIM_l<@v%LuI9=? z=`uB%(7nY)ytUXh3?nk9PTgHvi}gQg3k9ECPb-3&wZS?zkr+zuR7BonHhA0>F>oR` zSB4%l4?oPpXozxEH)*P9*}9m|pJk!H{jpwVCj8U88F(S?af_FF_N;e&Wl7U~#_)9c z>-_fT5TS|ESpMl#L4pYPAUaOv5UIHK?mZitX*X%OA_g9ipU;M(qoM{UKO^lCQSXN_ zMpVRs6pSa1ySR&ZUbG+jJl9dR#$nm{U(`PuNZbYr=qTW_s+z*`#DSM#h&GW`SlCsY z!-%4vn}*QBAd5tueX z*#B{$!D}zei0TR!BC{JJ>-wuZmpo>o{qP}{T`+{TAf8pe38CzjhvI1n8=7uNv}xYx zIii`4jg3v%5?lGX2)X=;YAOE%KK}_$c`nVAGk0-$qoxJ5F9oWDWI)jW1dK3$XILP9 zA`t8RH$GF=ty{-t|D6xcC>?)2fO7Eu%b`ufzrSkbN^NXNCNAX*7gp{NveZTyw49#4 z``fp3+S*}a>M9NnB0xlM>*}b)a|v{#Y*Xkf&&Yc0DO4GYx!>lF;0VRAq9d_%XOb_X z#%{>I6|KR06l;OxdDP*)T+Y~D$O9Jx_$5O9A(h}9tCft5?;0DoYH4Y~B++}=d6!x> z$dPQ6NfTE~?WTTIBK9h9X@Hp^r3biMqF;eIB-I>pMOZW-61pgstp_ay*=fnjl`B6# z+;!p7rG3YaW!3WPB@#y;vNeyY$rW@cYlB-vs}cyzs3~6^ZV?eyG*o~mC?W6xcZjo2 z=jP|LC%;~q24We2r3j150iN34q)-(1jx0}5?S4s6Jpv5&zPx;C7#c-jh8wt>zfaL0 z?gs{+57(!RZh_BcbDlFN?%+Y@w!Kt=y!RTnTUXpT{Xj)mUw>Igcejpz26i#UT2$8& za0~ttm^CQF^<9#&79&1|h2k!)hup|`Lu?Qo>{J$yb6CC)ORjM$I}HpBfD9uhNi@NP zS7jF5)*bfwa^pa1w99CB*)0f1U!VsZ&ZItlT7 ztSAWC$dr_y;l*rz6Ue7%MX^EUJVEwvPfw3;Qz(RltNh!B+akuk>O=6LU=&wcptwcP z1z&mE1K;H!l-6iDPBP(GvID8#nK+}dEX_GB#O0@FH_$dCV-j9~RvsD{=nf<-BRc6D zqOYRD0;p70Q{w}*<8z_2Gjhf7SHP3)B&M|H!Hfbmnk*hMQ*045q~!kkMpHSkWebn` z1&{%gF9SpE24m$%+FhIG{SB*<)w7?$z}Y=G_!yBM7}Bj(wkm8=#AsN+5{-tniC6pq zVpO!85Gil{Xvwx%N3W?^urOm}l0T^g8^nYyNQ7_58Xe%@^Ll0q3JR!fe%03xcMc6* zFwBeF9l;-QrFS3JYFcJ}6xQCa&OZ zSy|Z+k%W%2ef9|0Gy)1ACzb*A%m@bOy@h-v~YgAYv>LBYXWArN75r#33FIdS{j zJJ?FHI!V5ABAO0cTs6634+y_i~vJzPwqxu@Ay)mmr0O3#8ueSs;evKRV#`u@j-^*^B<|MJCPAtnUwl?)8e=$`l7 zF1&ttE3De4kx^0M&Wj7xIS}WI(dDt8mGuCvUC6v^xy$$M8zpCEW^Q2KG_jEV+C2_G zp0}UhzBP8T9GgkxK{4|MVgb%|TZf|HEs(A!f_{%3YlxWRV?5@o0Ivjkf#A81Cc@=( zbk_h2Dn(z@u{U?cl<|yXk703M6e*NAcTrCyb}EKIu%vbSjOs# zkx_-Vowm0^pLlpIp@2KZm zuMvXxw#a0s{nO0g;2jvF?olup?%1f;Dgy+N-cFo5_drrZx_(|V zAgRxvSIZNN`n0k#^W~_ECt-speFZ2v&l~TQ1fvJ+t!--R1x7g>+;#P9v=9})e}7^4 zOnDH^K+Xm8lE#ZUjh3RoEL<8^c(^ZW*-{|XLT zz=)3EYXPvMUzC=3c6HswhZsJIm!xtTE}Ma8kC>cVa;&6i4gf`N9v&qqrv*y=E;}!O z|HB7s`NCk~M$jzy=gXDquJ2dQOl*^`nGO}Pm8Yyn*PAbvv^W%ivry#~V0^b+asns{ zr-ZzN`p&Rdzzse*%FeGz8r;;@Ec4Tp^?1>Qb&#J%_u2{y<|3$f%tN#SC|pG$bQAf@ zQ_9N95SkQdo)%p5f|unuGUp+Y#Q36?RsaDd;he0NF4^DT?*_z7wL|JvkUIWTkKrvC z9|j87P=Vc~WL8cN10V=z-8;ORL_f((5-(*hEUr26WV_&{8R6*7_aW!K#jnqyzU1n~ z7TdCK-@fBfbhT;2@-)du#LasQ{rax)@$pcWycJMq9$Ruk$8Z^nMBHL?rVLG_u&fXI z>QWbEuL?eo5@4?tlu?k&>QfTaw(qOBd7(#zqd+(81z*02@(xC>@tfV!P>;9d-uT)h@B+X9b&AK|9f;8l4kCA~zSWd2}i^& zlUE;fbbK5PIMhjMyC~{wu3qPb>F5+36N!br33E(1SFYZ;f5Qej%?5Vc%!T*3?G=<) z+HaOp$Dr9@-TtHDOw78Gi&!jZfI!#6PP@s$y;L;9NKn=T86)jm|7hXtvB*YR+YAK% zbWkxtMJ^4lmHDFH6EB=>5j?nhfuAmOR}JKdM-NS-0rRS@2Wm32^-$l)O8!5ccP@ zBXMtmg-1Rg_dB4Li=M!1C{V6_e9m_YjxjiTrD$5yQDj$TtMdRc*7+TTWTK*`7MCxc zY&vUYk*yx5ucNbj;dl4CbRigJHe!)oL-xiyo-`PjWd02R6XWo;jaGSBxBP;6KtRA_ zg#Gx*V07;60yx_TgusIrwGY%8HwDg&b1}6?`1s_eFUdCL+h;cQjRAbUh5RWg5zDD~ zQ%T7$B`s|;>4G&FK{9*`X9{IKs-}uz*}nl}gB;t01?!8mXV`0pWOnIYzrJ(Vt|e%P zyHBI-nH}f+HAf!7a{o&FVd<i%)pbPNgx+ zS_JaiY+=rp5w>p~HMBV}|Ni}(e0<8QS8q_F5L~vIQ-1j}`nA4;()fNX_}{SSS%^9< zqhl-r7wV4t)&V;Jbov~_HQB_S7(1Lt9$G8{YvWMaLvVgBdB1Sc|A6X7AfYm_G6E(# zU>!f#*PqAMuJgkX(Kpb2Nlmtm|AxzcnGkL0|2Hth^VI3nG}X#6dl6t$283}&b}`n{ z(o)ie1ww`op%H5(Hb{$CtKc1kcRrxHhQ`KTyP&b{|1&UMKukcvy9U_lT+RbeJT+V} z-?euuW7)&v<5z2FXiyqc$B~9lzLX6EGRQLPyjvS`Sb7{=O%AIJ(r!3VHE}DTm15~m z`;1`t!os00PmB5C!tT1du7LSGvYH*I=sbvxS<|bxZvW@BIpZ}u zgf?TCnaxE1211?!$5T~cz(7C_-YzmwDa<71Xhxt~21x?wzlJzQ27X}bumkSCC5=s4d zDePDG5Cg7)4Iy?uBoCOfmt)VI66#}U>f4LNMgCD_bvZlXeL+Iv4K^_t$WFkTlKP^DU4$wbjnF-zgq29s%#GRQp>8ROz=oZ`h zf7)%OP}vJt=V*a`y@whD--BKCh?TxS4;IFCc!VX`!>G&XveiAYhtM{7dT+Wm9FTZ8 zA>CmQ@XmX)Jn+C`TRPCiU5hx* zC=8!dF~QeSuD5f1kU+N(|L;}r3p&FeMUBm|h2}NU?F`;;yGG@frRDvI2%RLWu?k>g z$%>ysy4$knLflVSb3Mlb-@S7u1y5IAbqhPY7vzF2s2%UXGVY`*C#o^w#(@g_OwM38 z@8aZ?kdz_5!up&L*-+GrcqXRhi=qFt=Y`5!f9q;KPml=9z9Cth=4u&3Be_{ zHO&DXK=Y#=ZC8JLRf~&v>{~|SmHw%DFb_@wC=3!4w=)ZPk(RA-wqMdzk29> zuLaZ^4P9pnX*o{G$oP89ZQQtf&p-c^ub$oA*p?x_^tx6mM7j0YoA**vkAO40|Ktf{ zy3sGp4bz79lV#rhK(f5BKG|yrE30gr0w;+KFmkM1v*s*VIPhclkX$+uG_#!Mg*G#| z@~d!*<3++^5!!uvt?93a7P)%Pw;F*aDc9FMwZ9CtK~bJ-X`|z@-t>rlr`#Mwi@Jt~ zgY|>wWDDwD>-N9*La31BoWkp)gTf51eks7`gNys@`<^ExCVolPmmwKp9lO}aNt<=s zk1~=PO1o`fR4)f;re0Z62{r7kunrUG)vm_aA=5-6$8HPEl5%UF^=&ZRG&;pkwrk> zd}!99xPUtZZR!CLkEC9^RJ;A3T_IVkGbi`mlj z^z_u6^6h%Iq66(v@+pnWBHPj{fj+}weA#AdRv9YJ4j+=Cpe0b4cTmt1WL-)T5~5s! z3g7SPX_$~1&=Os3KR!2o>&)4+u@1aovsaOCyK#eqN2}long}H;fM0`$7C5Fjqvv64 z6-F&3(6(8~Zh|98Ge7PZe0quu&{ph+rrwiw+GNcVq<{_Z3m_A|#Aku9aZM8kjwFrZ z5Fwx7ze|*H3J4I$fUSS(;>C-1{^x#67Z1l>u2I*@w-bm{N{l*dV-B4HMEU|MH?`NAOLvn9z(|=Wdf#dJOmFR z>386Tegfzn@{jM4Pb3=>y%RMNp~WP0vG=RjIha0nb9)-Hbj54^Tefq*`ADvpPX-G} z@Fw9d$a=yOP=QZ0>2eKo)ZOp(Xg=pd&pjqr6&Dpzuzx@WQG$YlX+q`E_jd2zE%)l$ zS?VOr&mAbE2yTWh^&5QTAs{oV5Q^k1%Ylu+bg~_mE^r-W*^Wo4O=Ay7_Ldt5i8*e= z!dM}h{_Khf>Yje26j5Un2?nG)$)z6}q1xVf#wpx9zmzg)@-4Wad;5>it4PQ8@PZtTI|0{QL~5>o5c z(>5^%!@4cgv|TB8*VK$yzSymRXBOw^d&OD{o!QBMZe-ru+fjyEm&(5v@0QEp;Ayar zc{b()xrBxzh!@j;)B>Tdm5;I{g3Lp+q2WD$-`Qm`h3Cs1?Z!p9-jDizxQ@23rweT; ztB^$|UOe&id~oU|kwy3bx6+4mQ6-{r@?-Cm61?8}sYZ4eRcDdV2C78bTcvgTm*|>~heb zpzy3;R(*>Uxg==X<}07a-I`~cdSd<#Dh&~vpC`K0n*ssL?m=7WQB4NQQ7Le+^{jAb z;-(W87KS8#$+!{x-59t!DDHW z4{^2Kpk}cDAC|tkif~dnI>U6LAnEF5d3goBhju?ZmVlCS$0CiZOO&TU{Exd2z!v8l zO`{Qs{O9<1&F_@T=CoMOPkD3;O9I*>P*3d!fMsw!r5o0Tdg1ELn+HUT%oi6NTXJv9 zbl`~{sMJ6mwe%7t#{Yc#oy+rp$DALX^SxcK^HIl|gEvN+kU>m`uWAXJ^;nnwwcZ zQ_eXrFi%MYum$S?O+{QK-H-_%qFB9d=?N_R4Lf#tpx%y23`L}ijErQRqG3ZEyY-C` zN;W4I>iktO)-dCESMNzPZbqk8UJ+>T*steI?zteqQg)UFs*`d6_lo!V5OpJ`z)2@i zRmH8XJC5josy#MTgb2F2wk>eX-eIg8N-NjEb_`#*CRw%U@{$&JOu#iOvu5av^|_m`cBi(z30;tp5+ zXUX!~yKsS=CSv(!cicz`fR8z3yrneu<*$=95P%|$QtEZ}^u9GPfA9jK@V2dujgX?Y zUI3r&xO(Eun>Ha*FM>DOl_6I8l>yY`g(6_&v77OzKZuu!O~hs=b%%(}die8B!37cd z8ig@UR-H6cV$h9@5$zQ%K@Tmh1zQU6$ z?*RHp=@Qrn_S?)XrJT{Y-04A-(J%tV>6fxMf(*92FL>ZMGr_r*T`WPq00JH5Y0^~) zCIX*Qtf0B516k3$A_itu8~xQVNRL>i(ybAB??L`%?LKfJFrcjpRw`Bz8`-^|pdzG? zgy3=sgr%dS;PxF2IT0MeW6gEWy)-!tKl|WVsSS>>Nx5CM{V+ zsp75*fG&4m_8K z59x``9+7yRfYH}?sL{yWu(z21woQH6_4c2njS6(jT}U}$xNdksg~_KtbdV6wVHa~? zfdFt0ygqT1tnOgj0x;=mmKKK{Y0gP-a-;>#=YA^*m+}Bed}@(cg5|I1p}*6MA}jo`P4P zz>scbSZtSqeZk=2GJ>|CO|xv>dKHEbQ!5d;XS|?)hlAKdt40wD9}lRdggZKPbIqTQ3aD<1i{xpDA*_u72PITEphuyv3Y0|dx{CLmf!=7w0VR= zi+rl#ItgFUa%UfJeuH30Tf%hW*T=#?1mk8KiXY%PNg?1NJHUhD3Lh2}h#@bgK-WaG z6*DNQ6^553w6xesu!AT-9yAbOCvxp`;oCg0>tYyoibJLqN+<}QMyws<`=mKvw}0g= zoV!aFB^W}M!`D}C+_VY038O-c>`C2ktzd6_xs@*&D8 znAAb^`7B4x1P7%Le?&7<+bc{QEvp;O7$Vgz}KS{4u#^rx-$SaKw&lVI$2 z(imDWFAy4xfn$H)R}9zpBK{Qg&2MIvLR~WXFOKytm zwRdzR_Y6M)E_)YxRG`0wZ{7%@WFn<@773BX!`c2;SYbcOxNt2bY~U3Wfy@h|dzF@y z)T9k(xvFX?p7wQpkR`J-B)P2s{BG;uFb4>N4!DiS&(A9+cwyfaxVpj}+iIi$=nqV4 zp%{NdaZ7|Th+10%tB*DP{_UGQuEGsdKFz}r46)ayaq`dP0$5M7hm3w~1-SOYGEV6bSezp~u0Sv?^!F%-?yL@3Cl&OZ;tkyQYWr{c2uDa2&8u?>XyDcYU4a6 z2vj{zB&zaO)E*5h$M^!i4Ug6-XWCityo3V6&#EuYiaK*f8uq6JAwu(|!IdSMrd)c5 zRN$>EalN`fYs50HhbgJ`4YZYl7>lMLjdCho+uGU?3dy=kqa!hl3EUypq2+#8^08zxCawr#n`y$o`xP=Zh z{EmCRp#O}65|gN?3l}d2V;c*>7UFn&8*G2X^r3#cos>f^4e=FJvx+bSnwgme(Xv6S znDJn6Wi;x~6g(Be$B!Q`Dl5~6;>Bstrn6V_L;nzzd*4aSzcLympal!PCL;iaqsg`# z1~QL<%LLxLcQ4|3Yti%P>)=CP2TztIZd7vhJ_M*Sl0@}IVHxqDZ?wgj4=`u(lZf+Z z|9L>w+9Dqi$Mk4pn+N?d>oLkz{0fyB&AF*xmf;(*`J$5&fv$kY>Q4Z}WZf~6FTm1u zJ(-5J^$DIp-((-}Ex=NQ0iYLQa0EFR0&RK_n(U-E!6#1&F>i)K%X}km)O7e1pr!jgBDl9B=mQ3m-9_4Dw;-9SS^(bRC` zqtMfE;=~DLzNI6$aZ6pMR;&O}!SRIy=}{39h++5JYWEScb1vo+88JHrLhq~OGr z*;os7;Y8IBXQKr<^A)!;7+YTu+5m2vzpda-t{!@JspW0rsqkccdut39!%HILm3E0=Mn^-d?Jt&TTl&Pf@XpANZRiW!)Y9t zgd(87csOuIoArM5mTJw$zMBfn2e1aAK+}aHW+Gr;!<$BP=w!}V0~ziE;-K*8OK;Id zft;3NY3U)ZlG0L)`;&k%Y`Lh=wr(K^00J!mlF1mx1!NX`DpKo&xkPEh1S)=~Gh3@A zDE9^H^EmF!uJwo3=RAZq?3VG(qiEdq9OZ)l{E(m^^@HFev}4F&D7AdKC@R|EM(2T> zQ?#g$p?w)o`u!QNyze6abOJj&;l)nvTgSg!eX2^IE_!lY;{dGhS%?)174&_u;@~%~ zKrQMOom7SX4yMv^hnpGsI7Q?2>v_TGxml!w%TiT+$S*3`IvblD>e^%cpgZ=@CPUr9 zhEZ46{g*H4LMjql+#dS+^nVkBG>YOb_B7;=94oJn1ow%G^kr))>OU&Ggv`GmB^{?2 z8lA}|Dcwn!K6bY=&8}eMfF$~4`^o6ie1*{sC6r9uI?g|Y3kT4R;7TaO)b;H~&Iis| zU`5&i!g?hn)ZFV)0+DWhY4=qmwh%8SF<0{6kBU>|#q2$#byefYOb8`Z7A#X%)&g0m zVWZu<;NSZXs7VWy1Fi_s#Pf`>%a^C4e5o7!!N2HN>#2PI=J$WEi+_5pTT#pB_wO$K z*FW1fm#~=q_xJw$-M(P9J8ft0Lv!`iUYYQWy4YRSSY!ka%Ls)GWKIHA3L>F7FGKO{ zvxUCDe+|4HP27b~6Y#KqSzHTW*u<--P zR<^|?Q<;tl9tqBGJoeSi#Ty-ZbN9&k&egqL`Nq&4S7r>syq_^6EaXtT+r#W^O34YF z{(Ac2zC_5huto>0vLH4Tk5WIEE^+bnX%_5&m~6)K_Qw4Ej7is)Gofu$pse-7nrwoL z_-NRxFFy^{AvZ*i;Fsg`e618Ns# zviwF4fzxvs(Lzw!Y;o_m2JsT`j=zOfFcBqyXmvcSFWvIMK9lH^+DEW(sF#hct$}d8 zO3KNtOBqGaOML>gKd9?mKn#E3rMn>lxETh-3!{gis3`5}5XTi(RZRg0q3z^!YwP8- z1{co}3VMt3!g#(Kuw=+o1;{MI(5WJAmEu)v}(b5Dk=01fh(5vr&&Hcj%dS2_-~-BvG)ZcZHVmf89qS0 zCL#d|f*2;pf)Drs3^<#c{YroR^7tzVIC}cDAaK?Sq^^G`IAWdh9gVnQg1)fmv}r|9 zWr9I6ot}FU5D}QZVq6zQ;9Yt6OgElqvOrILUmTKL+<`HYd3Cuf`}!iF;DF@aPwWiftCf< zf4@vpQ*1*R#J*mw`&yeJN7XUMV)VOzt0qPf5;o!y!{D(n$^re(Dqw@eU85(+&k|jX z$Xrs)gOUqJtzyS+Mj=hUSBC+^CEk>-6FeDDx!OFMX{i~4aZL`?) zt0bBS)I};=boMUom2=2Kx%@zz0D?F95n2K9>vaszgsl$^bn&D35fFg|R}3hq8?yFDRJ zSPdQ;(7-B`LF6bb@HxmdLazq8ln?J|A=Gc6LI~qP`$_;Jq&U|nuLgQZhS8{W43?ig z4r7uI!t-5>_RIMqbes?{CYa`9XM$RS13ifm%t|99>W=c#;vy9ZDw2%p?F+`Ec&2Hh zZmUif!G0bBlGYZ_TK17Kb$~VUI4_`UCJ8{WyIqHz0p5lu*gFM8MM*api(ECMkLcd; z+)FQ9C;+S+{qtkACwE{F!?3k>1qT)yM6Z+*Meqg^hnmqn!$_l!@c(ciWW@mdm^+Z0 zp{Zj?mjfuU`$yAinoLoViV5)DwTnw~xFH-3Uo0vgP*aj^B80#n9cL3BWwVC|ox@5| zC)@0P=Ja-{?|`pyUv;ThgU=hFJoy8w4wdb;1j7vcD%Z^$65+0goKYuGB;z3R%=Q^x z3Y73h`fc3kU%35uk;4Jlp(C%f=K-G3IG}bwrHgYtf4a1m31cP^Btr4#7to7+7N?5xqZc> zF6|3yArC`M|KP2ds?l8jvJo#Rf}-6wtY2S0lq>giR3sBkH;X3j@9KoZ=oGaOO@;>J z@M{kep)o;#qx2kV(yT>DzXpwBPU5{ZWYN-}Vk9Z<)#wm<5>`J_ z+8`|e?l59HGnURAP7EJ1}0B*ue5mXbTJ&fp7_p zSN9eO3i^n@D;Rbec^JN7?}&`USevCxT33C7^|lCgCp-?(HBN!g-oH18dsDvL3m;}O zL+u=Q?xfZ)o45J&UKye@Rzxrnj5KyfDq33^-!i6wOV0t`jLA3})B+~M8h1S2GHBLK zhL(c`0kgP8NYTmyR#E*{)R)uh({YhMZW~*p`FCka@O{Zh3@^jtrD6^>4ab@_YtXW; z0^H|%Wv+&biWu0~V<6ALPFEn78kU}0Z&Z*+N0RN`yLrF~;*p;EYvNiwHKcaI4vw1u z&8rev%3!=@Hipm<=%os=-#e5=La(6bKd_F=AL<@59N-Z-TUJ$7Wf-f)p8fD4l7S{N zgjfMRNPgjU2K~+M-MeYOR2YR82>ao7_+^aDk@A3j>;x(ZRJg^+wMRskCK64eO9_MA zRg*dcf(Z~nCxI&vfacVPHk(FU46D;HpST=2ppC2S^5xZxn_=tc79(Ysg~1kC3e_kV z19w`K(Jmbwokuk_TP~G+-av0$Q&Tf~e*q1@6m$qI$7atSUQ8wMp;#om!V5rT2$xD2 z1V6=PW!ylTSr`-&>fb<|XrO3v<8mS1MW&(j3wS3qjo@BaQhE#KpGWWBi2@hQd2+RG zP+VA;9jqEdk%RHgiE8=qNc%x(21bG0s6>50PQb#D9tBV{jW7q)X`TVEF)jRA2gcTg zAPxZt&|k$UfL_h?eSZhezm88VRgjl|4J8S7taZ;Fl*OH&tBpd zCj8V}J2(oR1TQH66S1*UXt>EKe5xB-Hz9ccFha|ir_aWl;Rw_^-6a|sQ;ol!+vl5m z3itdv+Hl$ynROYNp-a_7-iW$luW#OAZkd|o0GAzvAf>gi7k`21*1uM zhJbP+km#IAPw}bNeI#Zetq5YxTfC1DyN%TTtB}9HgiE zuE2YE^r`?WHp^WItKIq=Bo3HHLM`K$qSh0701ShmKw^jRU>m7mn9#$58Md77hDotFvXCe z%fv{5Eob16>mne^ggRn5p{x)-zWD5py*|d0!&_Y;mmxD8WK#efX&hxJD8VqbGD|y~4xURPB)X9^?Wz$9mLd0ogTEd5+C3r4%Q5_ftc+%PaCdCF6MIb zisJC~Cj$fS2ug!DYx=;|IVVWAc>*UMSF_8op|K>vMxCeg{2tW%v;ko@0<9ef#$9 z2WZ*i%F4+=0}#Ej+usfui8{E)6*vw6=@)!FQ|0Lg+yw*-%YzV_LmGbx!KQH@{hiT@ zgx}xJql!=ihdrFEUPdRW`2$Gf^6Q7~e3NP*w~YOmUut|>8qrR6ATP}B?-JzY<&Ad$ z?vL1-O9z@QV+|zH9^r?rZpil`F)C;rcI-B)WW@rk_Qm6$=}QW=8FTe<)Mm7({!pYN zsKk7l-f2wrfD)R)C;?}gMV=MRMokzgv%UIcA+@Ql-HV}~UJpyL3FOj=loSQOZwJO% zWU$yS*u_!F^~u6N6`e>C5c!`YR-^cvyAUJ_8bb-KCN%Pr06Xvq=t5EilS-;l0hJv~nv*DB7aw6k!iuT``MJrs9W+v6S6qXg zgEE*g|IGxJe2!!0oO$z*)*ymNB{V1!`jImJ7y!vr2zqjVKIdzC%E2f?-LPey;jbH5 z?uREWt*ogz5g4cwhK7tC>Z{w`$0)Yr-ZV_#w?nE3K}4B&W8U0qIqw~z47 z>G4Bd5JShJg>fCew)d=AHwmPmK3|Iqya^xPo2i&t?*mNr=m#3n+(ReAhcqq7=#FL8 zCZbZFTBe3);dFF#7zvrd5Eu=D8?xEH{V4EWoM%HWPf7rz&f)F<%}VC^i*V$1koMwh& z#sqOcW&2>ymSK|Oxx5#d6yrPDnJ9PY5ywd%1kFcEYh5&T0?6z%JnFS|e(vc73le+z z{wEvS;KqbR0~zg`MhV(5OX`cmuZ7qF6CC%XC%gH^3St?zs-jzNfdUNNCH{1?jWT#OJ4^OLT9k@GoCd2JMYLC-?nVQb( zkwy5adlE%8((k zY(fu!gTflAdwh2Hfc)ndWk1%+VwJ}1P`XErWF zI~#~)^(F=4?Wq%pyZ{38Sh2IJ*u;*hKq{9 z4Gk;I(E5WgPrWH~`>NaeMg!+Ii1hdO7gbelo|6IF^}`7a9o2ACK5KO2#`#?MxEH@< zm|9);}gaUdEJ$;^pLIsoy!z`2}e~o6>ObY-J z$!@Bog#Fi5RmDIN7)`Iq2T|j2XqZRhJIwedM$2HU7s=(I=Bhjt+Ga>NMLQ!tKL*e~>$0?8v62t=_ zS)?)TJVUsqAE?W$s72OyK3Xp@w6av=zFJD>r4(^A)snZAQNC^gx zQ*S{_2N47d9)L5^Gs~ajRZ$oHF%&jqC#=k$H)jqZjmz=WZgt8T9U0!e=Q%2eLZ7W~ zc(@Vzjh|Oduibg|1%^=5ly7~a*j7nBiLr=BE65_|lgW)5kClO}%&D%2m6uEJp^x*x z?h)NC!m|yIAVVO(?fWo0VwPXidha2|1kx8{5|E9F0+lEYF#zhx%Ypt#=N38_76vlS z=rr87*4i*-pZFW|vZLmIt6#5l@jNb&G+<+TzVyo`F#rKY$%~9piUe|mlu|=XC~Z!r z3KTFPugS(GdryQZ#Ive|1ae@o)Cz->RD*$&jBC42u0+=e+MpObF!i@sBp?RlN}c6) zMnW-2;FC5=wDqV$JO&$@9J+2*Z6%ar-6XU7z#lf{_@l1fTmOwAPh4zT~K;4xPKudZVT>N6xy}vdy zN401Si?mK?JSK+(R79XpYqCG0Gu)2x;lh&LQ_%rRB^Y~M1(XT~k<2V$*Jc1nKwF%o z|J4FBFY44x*j)LO-Q^Due?U0X@-F{V;9eFo*!x6Q4SdL83vWF(VLt7yDf7+dET$UUjwPg(XNC^hR zJO7P%`)z5&!wRv%z6kr$8fdBYA7tU@WekytaB?fSD!tORa`$SRru z(J;S8<7AN-RTGbq)QRl`Fq=jkXJg7?KUO%DIZOvj5#%H-&59ZF=>RhWQcx1vq65?c zz|`WZfPKawfAfrTd`=zd>fJQM0-ibMj&(U6LAvw(9Klf7EPiS+Uww*0n9s_|a zwfz}AFap>CHYG}?EQe>8x^5JHCMUYLjFG1beOq7#G#)jb*#WK}i3VSC_yb#CF2@DV zAEUPl;lwr{)B4!~Piq>Bf#~ec_1|nz)-}mNKdWZ`X7SGh57`-thCvB##5lDYvyjO- zK%C-$Z%XMoIv|b;b~GnPg}igve;q$0f=DAP6=`Gh_eP4rq5wdl(&qNEDmRLBtULmg z*Kp{=OPrTv=Z#8SgrZES5kZv>=2+kVVg6zwt~%MH{!jpJ?WD?OBZzz>nhX?mym25p zgX0+)?x}1-OAPA|yp$WktRj8z+dF@l{sC1a$uC;G_%W_VMZS+W-7wAmQ`gaJf63N> zDkQ2>_aLN`AT#L5$Bi-SDF+we=t_Qu#Bsz^q6q+bR)Ue3#lGPHMxvR>k)Q8efbRum zu!@FA3X#AQ&(J{=v;cuQ(!|O%VuYdNJ+LlrO-%+U1A!yMpp(CV^Yj362EbYX_w4K% zJLKqei3}ft&+G`N{n&Ih)LGI#q9=TZJqLMwZ-z9>9z9>S_k)4hmHr|32Y4~kHX`t# zx1)w1-6|b6a`^CJIt1}Up0^0#_7hsMGOwB2_!)@KF0QY)YVKKm^X9n z%ngH^U@CB`#07oxjU!jDP<8@IRk4#9rrWPY<98jJ3)1@M*FAMSf+->pz{Dr)eX=zz zo_!O?SG8qwc zURx(7CvUsfQ*$IhvCVge`eCyn!|&Leoiy^%nMp2MGzI<0Fu3hVgo*Sw}A1Qme<&1O}dQ zzufmli>QonZ57oBn;L%#4`8cnPA%^W6no<9wr}750|!q~$j3q@rBw)s0ZiI$8k6^- z<;$XMvtLrZm63<@!HldwT_ust6XG4~&N zSMa<)b>tz4JzIoEkVE|rg7qjIrnP}k6@qNY>+1{28dQgWvu7Tm+cvIE24%`OQ!OYm zQixgu=sp7>ufi-t?lz(tv9DNJS>=eYGyyA#Zd-Pdd*1h#C&XOwsO^?mxB1AtWpKt7 zqgLL#bIGSf$E@P9Pp;=-qJ+EnN|00;vS_)y;|1yKq(2-WengrK0*%Lgp><)htrg^c&+B!(b51ku$X zLKSH8$0*c{NK{Y7;qL!~|4VEwmd5`N{x4Za?VkU=0ZgOE=@U$K4A!6G{X`q<^9{{E z7r3g%G|bIw#w6l`W{w2Z5N@9>1F{?Oj0XIz50tNA=f~wEZVvrnf_Wp3Bcu?}AllBQo zri!QB;R3s*R2}2m9|&3@qZ6C^G;qD7@aI{)Ia=9gt*_B9j61uo1b#wXRuRA;I%1M) zZ%!r@u?fmmrcmu8wQ7M6|CeR2Ab1A2PY@7LB-7+Bgu>yy*?^H851V;{-jtxS&kt5g zdf$+T*wxYC>|A6xfeNT>z+B?575lVCB~@JXLfvhTv>Kn0_EGrUw76mqMz4 zk=bb&gk~CLAmRNzZn=$kU~RAv@Hsb?_6(@^p+* zY;PLiJ(54uvC{|wq$^2|L*TIp^!br8G#8JHKWHUv0%^*s+i=otbjJ!+)!pAV<*k$G zu={Gw5?Cb>e)8mm9|iAkxLp@t9(5jyYxEwoN?XfT*#UjuEVic)|EhNQmjIg1ml-42 zDeT~wM345Mj7=8T!_@Jg9!h<~;1T(VHa4IjCf@pPWa`@Yjja%yo=K$~w6_d4l}h<( zsAW!_^N+l)T--T4Y!or_wJH&IJa$q5Vu&O01sXk5bL+v!_iy+M13rL0xCrRVFkQU3;|_MXqb_?k_cQ#g5hJgcY%lsG|{ga=ShHqW#-{0iphzNWT zE5Sf!lNA6{R4w17O-(6@=wT8pyZ0R;SGb}5)vVJRemq|b^94e{lY1=5OY@uP0BC0Q zNi*7rF;>L`z_PiVD*~lxuCl zJS{FFs0zo_XQ8iqhZA6HpTp$>@Td?M_ca7n8P2jh^`N$JOTD}D$f!7)agsjuu8cU3 z`VY|r2TCmgcE+jg9t3csvM*FtK9gSx`eDh9OboodsTMhLuHW#$Op=;F;#8w8RVs1M zV2me)6SknW4$vaJ{?+vi6B~%aaG3VW7t2%#wjkmtXD>8!bi1K@ z(sw}Lpz>GYn{aubV6q`Bnt89$0zFI(IW)l?G7OO4W7yJBqh8~H>WoetkjFw)5rlpQ zpj$KMk$EnJ8b`t>AmehXNj(MR2AUW)LK3i`-E#Mj;IXvBUPHVW4DP&8BGB#w;ru(~ zMlY6$1u6k>dk!h+h>QZErh~^DKb7PZ7&VOShRaq7V}{qljmLB!PBtwKQEyMrM-cJR z)Q@091I)6&^C!Xel7zS@A=ttEPn_VyIpo2R1xT$}F%7UF4Pwv|#;|4#E-n4y-16nH zDPI^_nvnQ132zI89T34qr3ZmS@t{Nyz>hkFZL}2iYcbz#kF%KgaY|DtmUAP3C=#lX zFaw`}#bbD03IJHa$&-(wb0+l`^ba}^W7XeEIYgGn?I^gr>T^}l`m%t@#v!XsD7Wum zIfwGDC#r{Tr&f@7`EX5?qV?!ij<0!pfg{ijqrC<~cxVJA5IJxhGY%|#2sgkpw)vt- z2Zk0dUf#&PvjI-5P4FesPi)%%tG}kwdjR|mpjn)!HI-yG2fON1DsSLq*8^;=wE3b1 zAlC?TyjY>Uc|wdV4bl)iE?l@U;%%})EGvZ$;r)|H1EaDT0_QP~EyNIVlVpvrA#=fu zNgf=hWp`=kLp}}szUBX02bf+5MWqnEM0O#JSu`;MjKJ=?99fTYKDzH~Ye^mE)OFgG zgJ;8Y_(2IBcyrr)^CbnzdH+0O?VSGKE?Dhh|DKbA>g~Uj<)D_NJkEZ2HE`P&YepUgV2p3;Kd(gwVrc-TLl}oA#F6# zID(D?PdB}9R5h3bILTyFjn5#9@P`mgvYOcMK!ld!J%nOJq(mg6JUoVUau4;@XqJdc z!=Ymm6xx7ecHZoGCi$oC6}2~D2jImMPO~m-P9z4;@E|Y+`~_KEN&N@yBJl|ss}=x+ z&_=d~3-%RC29g~>9?cF8g*Hq_*48u)BQ^37w#lZhE`IdT7&z$wD_G7_%L*fpqW+XZ z4?&t13?Ok3CKA|!I7%Muu~CoS?<wA~Pzu9~p5O88knPoPY|<-Z^%e|FSL~*_|1G?g z(yMv}gHN3jhS^gH0+Aw$g`F@V2&Ih+LjH<8??X4OVEJVvQ3EKCRF3Q!5UsRTCWHb{ zPB8Am-JwfKDTGj1@!$qlAd_v})La6_2u@|SH)Vi5b#NKql(7UM3p-VFxDTNhSZ`9u ztBZYWg)0;z!|}kb>Wdqkj8}C1WLs;6@7q zkD=Hl*-|IebJ-5!!{W^DZr6gnoDo3vmVJ)?5WE{6q1_*{e#2=t1!%G$)+>EfxR<1_PJAMPvb8a#~jwWiKa1!y^p!}bA1 zrVst(0{r4SuLVZ9AD^z@K7s)#TYWFNx;3I>255Q7O34k-Dc zB(uA5*gDVG58zEC`|QKnW%%GaxYD%Bu#X6!Wu#-OoEj#gkC=?IC<2o&`MId3@A;5z zn39Kr5(0c}Z9_0haU7t%?I39}L(eK7#|9;a4+T~gOwkHL(h!0>zd_)mUsjY=BO_ZZ58iQf3vvpB+O7*r zNbqClrVKE<+FRxCF#sq5qk=>%7B#JwFYz@Fp`8gU0>xv1;qB?u?kfF^X^hY+0EKQ> zPk(Wf3Mj-5K)5x+RM}CB3nAQOVF1)ns5*ogF==9Vh~8{_es;?kWxG*35v}HVrt3g) zuLkshzmS!_@Q=&8b%l3zsS`AWB>ci|ZL&ju$bv98On8t)&_M$~P-z_dn}}qCR6N`5 z%f_(zFaJ5s)bD4N2kK~Vb-;#>=uaD*0R-rymha0kK`k3(i$MT6BF|}^2S|hu|A&8P z6Gl)c2V|6!4jx$YeSwM-BDgLf2v5yd`tsu9F;MO8P9M>o47dJ%DrK7~Ot^H4-UY|KNm5`e;GgZ3DWpz+P0Ik_>^@ql7r zVeoiT%FA9&PedoO!e|i=&G0JpCD2Ed;K?NQAmp@32AL#!gQ)$#tZaelc}L4$ym*Y( zGob(t&d7Uy0p#XL54}6QV1y+B`h6+1tdRUaLA$uWsfgV;)nf3N^O#)$hhh-OyLHDd zq3A)fCZ?bp`H*_W@^XGc{BWBnstW!TE?AW1@1L;1eLM}b((W0!rYVztQEm+;nfW7~ z9UVLnv5mbT&!fw&rSVKEFt7Y%Y>NUcI<(iUDJm&R zc%8ZS?;Gz`f$?xC?tkOZ^UWs#6UwJW2TW0LKXtPGF)m0<@8{$eNqeNRFReWH3Z0`+ z2<+$YAL6BZ9r3b%`<4IxM_g9?^-kuGVBkN0RX6df-z_@XO_Swwhara?m2=3rD z5QDXR&G(AbIp`VidG@Y!{14+c&ET}jV~10Wd4E+4{x${O)$~few#e%)gkSc-%o|0; zf4?dC-#3-B(>FQj3*Z~-#ii)IDe`S@5mxV48m|%Sp8WX^L7%S|jIaLZ#~c5Bo5Fr( zD!q;W%U8v=Pyh3EO8n33l#eqNpz{a6zpgG;Any>28IVyNTR*qzpv?Fs(C!lEwE6EB z_F;g_d4N$z`;;+*yMogWVs`XLqN1X^{(4U129C3h*S0@zw0;qo4%kB4zJ86vmBudE zcw4jAe2SJN6nbO{g&YpM9N~n{C;lvfUMrXX_&^oj=c1!QmyltR(jipE!oQQ$`ByDc&!fKg-=l-;?(f1OIaK-M$~?NUaf&S7>VH1ffBs4q&i}_n4XU5~ zpP&2R708?OKU+r0${We1V>;Dn^BGAYZs!w!-b1fW*$cgzgIwCyx#;!b8{?oJr4wbJQJ8aS-N@{@Ih01`}~nSpW%a0c%xn#$nHjNB_#hNqlb?Fd9Q6N zE2<7M+S;`dr=yQw*vT(A_KoF?m72EK3pSZg5?UJFO6!ec3YDA1_UQ2PI+#D5tgKeK z|M8Si{e`J-gXqk=i>TvJM&0Eh>SX_!W3M`c)%cxVfqw8R76m2V6vGH%yt4SmiWYI45ns# z{+tWB0}Ey{!me@4PeAp60fH4G2XQ2{kT4qC0D(+Uv<>=nDgU|J72d@xW-%z7 z3-3J?IX%s1QhK(`Q=yAbm2n8*I+Mts6OYE84$dr|?bW4RSta0mc%D)5z@x?Ltmniw zNs2hW*5x=5$ok;v(FN((IN5t0Sos)n*WEwHjvRXvHF0^cu1kpb1o3yFa=LjoADa|~ z+x~)b?^4*~zC_R>nW$J$-FosQvZ0r;8Q&EO+k|t;;FA zwQK%6VYfj44+eFyQ}C{D=H%U8mRq%eVPq4cOD?vu8Tvfks-UZ5{L4r=-N5&oZ^|Ck z-!+Wr^p=sIci`QGiQps?=_X> zT{Oi&zF9q_%*e3!W!ZjaW}5c5XNK9vzFfCBM+(io+wRR4;=VGxQ!3=d%QbVZlK_qgM|U%YokB*u$DuL1SYQQj!6m z#-2~GH_+5;Wv)FP-4|5!-qujBGxylM8ZFys(ZKWv{MXpngvfa@6 zU~6N~v65|d+gAsE@z+(${K8Ua_V!J(+2P2;Y5DQP&PS{^dmY(MeEP1LC#l_#cRW60 zrNN4yQ+fLjt`0c7NZ)fXcWlNS>B`2UdYeeqC9HGo+n)+N$lkt{M{Gf#&F2=DS&QWC z9d<}6%x9Ue_sI*{t)NJB!c{+eo@zx-aH+_hng3ON;`tj_ zS0zL)3gRM5<*ciH}3DOT|x=I%tA=ANEk(M z6+%dmyb%E4nZ&~#u$xdM9zu8naVj|w;e=J@c$WOr()Pu6f%BxViW84faYSd?ExIDB zBBabVrA_pLX3bOarE|)zCq10^fw#rQ`?~LrH7hncUkQ=T`dm0%Efw%`_X+Oe%+;G3 zH08Rd2;Yd`vOjxSn#!$s>s1e4mw49X|8UZnw&di7hPtJpIi8XZ?~Y{m=t|1QTl!Up zrFt~E2xaPA#h(QSEmnDGr+zE&)CBuN6Hf=T%wZlAeXq~nKCuRkCHHpa9v1a~oOtN8 z-~gBOl9}mmJlbx|(^PC0J|HaiS`hy;e{E>5C35loB7wsb3bC}qvG5H`%VH=87^`}_H2M!WZs#mdYn4t%|S`SLu8 z&Rb)@W<9@_JmC1@{@|Od7Ro}_I-I*zd6~kJS|0UZlD9W?ulTk3k=;7&$j;jCk3W{b z7Q4IfSi9n(Yx^X1E0dSEl^;0fFV8ceDzPfKGAd)n+=^{$VJSsJgEXM=ro@GtI1hqm z5kn2NP%s7;hM_=AbVT6vS0mX0ZrSCBe=Wp}5{UVYdAf1SUL-I94@A%m52%JGKrjt) zC>9C}`1wbV1Mc-7Np)2n@SL%J{F=q^giZaWW&Fc2Sk7b~3v)~3*Yu`&15PT^afjTz zI@6NQ91v>P5~R%l+SaMrBAXfoltqWq z<*zK-?dQZc`nfTgzb#qa%_ZGzlUe{<^ds(aTmPMRwA4-t@;9@dFKO!Bt2~hB0bV%U(xvK#xGYnMC0pKuTf-HNq<)4vvG^C3k=J(poMP|vPPPruU?s<}IMQUr})=WB*^0>(;Rd(ZpBcW;EM_Fpt z-HUj0M{fNK`Haatf<7vH(|+@r2!?vEC~2xV!hYa@d&Z1PkuUhz%!~Q=`xneK?f0WU(zl?XH<+<6cqTnOCdVm}&Qp z!Cg^-Q#+rwjty_90BeaOOk?!(2)J|p2s}3VH${75{u`i^QT~*kCt`Q<7dku`@i)6r ztkcbW$$IhT;BxJKbM{u*h?Xh4=zI_Sx=Lf$l5?`1y3$)eGpdh2^*jmQdMYqT{m8Oc z$FDhQabYLD|M{n_{q`H35lI5Zd*6szX>_g*-oMO7xk+WgTPwfI4-(w2Ea|wh*D)nt z0)wqr1KQQb=!0xbquJg3GUZUC42CH=o9g=`JBW);48lN9W8tY|$$uN<`~z25I(Y1C zoljKFTy4-?yHCc=P3p`P&Z2j3wCZdHTkERrR1Kv%St|n<+*bX~elhG|>FKgbr@G^7 zH_06Q?Cqguc5F*G&Y>vUnye&P@nx-yP(-H$JF|S}N1^Ium;USJCar6(`de^p!MJaR zpQ#?7lswPS^ql|sJDU3kxMiPP$iC6~tUlx2^X)%+n`SH*I#gp6sck(MNq+DcZ^x5` z(EO8`#WY0WYpBhIwtd+~wSH;Kq+x&HQ2C$>GDU(0s_Zz$A!R8 z?oIZ%UJDkcV#{g`k3HJf4-i|4ie(4gUoBtY-$wm9HWh2hl|F20@(uh<<5avz($cV zorkum;U9}t^K8=HRZfN4y-45racyXR&m%4Rz~f(K{CtH&S|)qD6|4#;_XjR_SCfitWo2+DV@$MP2TH#A8;(cQ@N>R~{})T=|R6b)|Islmq$n7Y`fO zH6ce%Fi+%M_cDgzD3NuvNWG)T&qS1d_-&&^t9JaWl@kq2Y|HT{K{9Vw3>PS-ym4Ku z?ddJ#$tHYuBMT!w!ns>znmdQ<|e@@tjxk&)mxrd zjDIePibH8dX6KFz+4_C@9zCsN`MFe9M&^dc$u}*J`Nd}b`+SC}<3F?wtMX(r3o~=3 z#cjM{*YO>4(?J#{{Z?tYqT&!&7^T1@DD9NKkp{Bl07W|Om(URSdE;;gc2uGd&p z`06Too|Me^o$#7-EjcmqZrCXwrN>3$E0p~?vx?O1J^mCq{F?KLxvgliBk&c&oGK}^Bg#?AUtA6z1m0vkaRy8F|$NTq* zu8jULfq6V#^^2MAjqAsBIZ_$F?4)%PvlskZEOEaZEprtuJR2luPh7qHlgeJJ^ zL5uZyp3gk&@;piF{!>^<~@uWYA%IY(3Novd@$ z>6!C7a$tKG!zjytbWJ(G>)c94?&o0Vz)YHr#=i`G_cL!rUOj!xTchxmVLok4tHNUW zYIMdb_V5Qo#!sj36@J*h&*zqMElXixJPx{^!VAZ3vb1mGU<%zwdR%0_r~X+k^%7O_ z!wlmyY?SkMis^f{JG_(Q>JRB@_Xpix>UDZ)# z8ZKwtz!#Ilyn6&u09^W>W~63p?q^b@FIF6G3~XaFNArs_3M0;)yJ1uh9*FF#$Q@h- zE+2d)gPoRU7j#)hd5{}T0hC(V0BZIGOpjng64KGHZAYJ$^W-kfiBKQ1fMzVBt2lPMz0o=KJRo5&Q!9Q z=(g^%MaPQl$Uv>9Hgngl`W9L$A*~jN^a#n7YgHAcdW5%wexWm*uBwg=JZ!=Ty@Ml9 zDGK&4fs*c$yEZpcs!fpA9}$=;1EV=Q;N#V6>FBSIMC)t zV>vW;gpyHoz$?c32HG=zJQ75yW2M9Fj=@n@eCZq2ml;&1nK0 zPCX%fyGPOeHA7zEG&}~c-nWkrMeqi6amE5{x@<6^wM_f_Z26e?-k-tvh^Ol>;V23# zZ0eQ*2sJy$(@R5EQcTg-ztYMVTdibUqgvTIa z&Tr4#-^>98jSI4Fpym~3?i^@0ij?gu;Ix74`#8zya21h1!T8|^Y=@PIbSR*(FWdcT zqqTb-nt077Fft|&C#47Q?hTPq%RjUkJ0J^lCe2>M+_Ur+AN7ag8y+n`Qq92_tQc9b zJ?7`lJ<_rl-bBuh)Xzu$#}B?Ydl%AL>@r`oUWk#bc&%jJXFbiH|ACkA%Lc_D^+-g2 zHbPvY14X#sw>RFD(1BhTHU&~!!$9{4fdUBCBR%3`wsUwIkp@Os4{X}tuI!+X(Ob8! z7-NA8t{pw!2o2je!x}nKlBZB02&H@=M;iPSWs_DbEnKKc0-1t+^|=#aQ~@ESBP)jx z4s_q~1&Wpr0$};190zdyUOH>m5Cgt%hT@;9>EjC~hJ}%L4sCp}$}{qL_VMAw%tsZ2 zJDpExTQA2sSdV|sVwht+FX^%f&o|^gbilGHS~$3_G%Idva@YMClLdXWq|u!om7i2@ z%U;t{O=}JvjQ5;SZ-#lg@Oi@?)8HGgG+)fI&ueVt9O7-8zO!6AA;tO2Sxo5^-cPtG zgcyKJi-ESV(CHGTFjtYII}(}1$p3(zQVVBP-p|K+gGBNqtPtQpkx*?hEz%uV3F?mg zzP&`?AyS310+e940)O6&lTTnuSq20-!QT=u1bZX9lPaJc(6mMm9@ii(Cg1%9-A=S& zgH4S5na8S2nD17{Y~QS6fcVzBkL?h>(k*^dOTxh^1Kaz)R&zm(Y+YTgg994$7qkb@ z3*}2N0uJU=4z9Rz2Pj97`o5l)Z;$4!I5(%q#M*|81g#FIKqLD+Gb{=Ajer41Rbn_|JFDW zNW4c+%S1eLjh{Z9>AFA_fmq67Rj=81lhH~T$PP{h)QX#d%1RM~{Yv@=zWej#&d}FxR>x#kyc7 zMm_-IUIi>zENfnDzE_nwy*8&MIX~a|;L5W?3NNQ=_Xd7N>eWnSkb(50Gl+~lVWFnO zU@dYzNFAYt4Jp>6`A`HUVL_h-+k%OhUk31VM2^M+vK|Z}?I<)H*$Csb%JuMvE18xL zP}2*@X@@E%6ruxLh?G1tO)`-_v*#TNgiBB>pm{nDN7Ahqk=4jIBgYcym_|nitg)n; zaC!hmt>K|L|6hfqm6l4j*Bedw7q;^2iaYNVV}H+gS;G&U?o3Ecwd?GCY4*Yzvw2kZ z2!tnf?98A#EFG<$%eJLtrTs*)54#V0%{L2H=Y+zm5Q5oo4Effz<+=3U!CU*By11D;uRMn8w@XXAlX(wknUN8e<1*}r z(;;gBQalw}8-Lhbs2(_2LZJ!iHcaHP&{0BC=y37!Uxl#)O;Xe7RPf=gLuUsCn@8WCu9$Nd(VddOeqKm z(pUrPc0Z0fgUhBx^xqcdX%97er=8!7Z>(5$X1&tM zcy70UbDDhFN%a)8x5kHG)jUc|M(Q>xq^Lb&a0~}regV+$HGPR$lKAyiS=mt(U&3Wj zQ2@QraWjMUpU=DQ2@a}{6d0KN*)5&ZY7Tz^zuo3gwHnXv7WF+Mrkdv>Rw;d*kFL2( zb$y)HX^3Qi^&ss^pY5>v5(Lmuq&>weIG^aTQUj%mSR}GqK_G^-*PXMn++u1T{V6#) zjl5>@($7mo7@NVC>~phX72jhmEj*VX#qrstFDbUurG9Pt=6+t$GO;{>?9!p!?95}K z!2_HzlYPoi)%K76_FTN@SAozqsLlzE2E}r**{fi5NDcu>2#xGI>^x6FVG^#ktRmR4 ziqI3-`R^`#UehSY+{u(Xejt|9@?zmnUBfP=71BmzfBp*yP~0|2AxO^s4ondADf^*j zf>1{g+67owDh}=%{|wr_!Gqs8Y-X(Vf{^Dv1*}6d@g{nOh?WhwUl{HYCoPBs02CRn z&I!YUvfn=np~j4GSe2CSQkgbnG{<5@gb{Ew6<+b+!Pcu_T*cZQZ*C1c zjuc(3Sk3N$g^Zu0qedsk>fS&voCrZDXGALNgIGf~3x48GEdW$Pw!nl3>tA7|+CXfU z2d=(;{$A<0O(sQWA2NRDAM_7e>FRC~DL?RyVeW>1&pn?Vq!)#K2m)4rtn^q^%`RtE zidI5u>#wbdo{rt8hz6wKcMlJQZLgs^#`8h#3?yZWz0Q9}k1rdLZ7Gx)A3qzG#)*iP z)B+0n<{X4TGw9SriWX$$mEdocl=Jt&#ZYh#u>hKLk8`)k7qW7YZ~Ti9)BI^Ev$hj zMSGAGmoyz9n%*A{v;3OrkP?vkxV;M@CwxV?_eQm$GEAY|>QdGek)4fxpB%$a|CaAr zsjZ{EF9dP}$vSjT{Ls5DUf}KKci5JW>c&@W*1A8p**dy>FJlS`0+}UGJr59|Fd2#{ zgN&G!0rEK!Vbo-Co}ub`N08CpR-@T{UNyq2L!gkwtk-`|UdS=;CkmPz%S}dlIpx~h zzDk$9n7%Y^bam0GVg^L4;et5DnVN>oq26`Z_o#3FAz;{)j;K_KC&^@EGzz-_{FB-# zqcCdWgo!{BOw+M4%(cYC6A)|^ef((Yyb>v@ITlt=E2aqgcnNifGmPV09iIDE>4t`q zozlv7T?OHHg7ntGN0u>z_3ypgHu%j*;PYIZt^x7RD(LbOlz~bkmXQtd&M)@oVIKjt zpOmY<^TC1)7G|kp`EHfTLz6#FQk}5!B5Szq3F$fdj;dF*PPg|8GdRc&$`CDW301+U zm25V*EtlZmdRvtjF7$)U8bgOn)O;asIun9U%iB6a@d7BQ*t6n#xuMy@(s99Y_ph8l zQgY_C>|_|*Gh;#lOoW4#ICJgtk2|mJ{*Cq0vPp_g%v%g5Owy(;oj6ljp~@b9Xq43m ztC-;pk)NWbGmOQe?~+PVrq3&0pP$=qD#J+D=B6KHo3Gs;-N!KBZ#Io%P>Z#DmE@)! zVPR}6YIUEV7VvpbOGn;3eFCZNVFl|(b1#hmKBz_~Fm(I~bcGWbWbRSgM5_amej$h; z`Vum&%MZ1*dn?W+<}pm$rQ~wu3)3x=Co|0T7Tv)AKnYg)7_!}|e+#FCpoD~C-b^)* zYn>7G$>{{Q+PD_S4*RG;rFfNs$<=z|H=BVn&e^c-Dx5W8~2IAH&9UHlWXz|U^1F4ku zVJvQO9USKCx<1+2N-S(5XN0IA_peNVCcS}ro7M$-*Sc$R2;DT;RM#XlZHA@ghb5^K z(pshjP1N8u?yfpW5XOTeP1f(&vXiYRC&=GMe^4Q^4~`ln`&@hCKrS@*j}YUF_#%)o zW`5}HZ!Bg{-m*{kb7(c2%-AG)@B!YuQM{A)p8`zJJ3q-f5u^lMtb%l`j_f*|69VUR zclDN-@;$17s|@3&GKIg#cFvL>68LVV&av8@W4mqGIGA=tE6Vi#3Py9Z?f$u0QgPuX zrf()Ph3ls8qm_({VGAy>NdGY#Bi|V!vdi+}_EZBdFW;+UWoj|6aLp--@;`gnmhV5X!K<3=aPL4{Wvl-|- z=YL9-U}3byw*2}QZI!toX65zsyL%jD($mMGzLR@Cr7{e!g_D!YWWrGRXMJy-(pEMB zkm0(AM_>9mNG{Vp`GS=Z7;dQ_<_aJ0aPf;wgL;}EAA?Sg6KFCf2o{FcIeue{t%~s@ z=^TdcHXK|^Jp(=q890#%S<5?oeRG_#&f`LHP@mdX>ZzSBZ9KNWe(^GrDQ1%tbd7#l ztSrzii{Im|f$0#0dI0c;Ge9T^PN5CjInFf|fzPi0K+)zt&s=RH>#`}wjk zC+wt?ad{dqomn{?>aK!~^5@L9=}-69+!1FQ+oQ(DuiGB!H1QMB>p}7yU%mejZ5+6} zt7ezjC-R-Fx$B$UH>I_o@w!aSw6bo6`>P>acHuGVx7BIew(Vqh zG^|@8FmPO2XI19xJz82^@4c^F=^Ji-yUX6;%30Osk;7`Q*j!`&7iVu7R#h8yjV?e^ zLR3OpLQqn=K}A6kM5G%50YSQRi%N)6Do87$gf!AAjg-E&UN;6 z`8?*{d#!cf^PY3eF~;04&2m-tyRf}Gl!zWzrFR_FFC&{@?c-^diSJ-l>v~q(M$1j9 zKrFZbQ;1W#2BvpPW)fODe6|FD*#f=0Q(L+>Lp%xs<|$-z0R`KH-EJ6xGATzs|0wbb4g6ia%L{{}}B% zG2U6cg2cTKf-84U#y+Ly`yH;lG`3^r!;c<|=GvL{0?x_nRQgXFCyjv^n%Q_uQPF)q zv#5CDIcI8i_Dn{8`^1M(>HBaD#@RQVYfX@f_4C6<4I!@B*zmwyJOp%3ey}ruDM9*{ zJ{>rrZGZ!YMw=xp(&()ldm85m2NxZW-i3NB4{^%R;2 z>g{ac{)@uEds7|thU}X+gFB+8p^*oMD$+Y+I6#Q54fWahAnfSv3Jyx>t7*JHlaxtH zbL)4Ss3F;f-qaMk4h??)7X{)G8)nxH5tUfckqM^9uY{I7-DLO`Ql73odB*zbffoHu zIS(YUPw_@=6jDbl^YVk_VN$pB6F|f{(3YAfO1`WSaaPCa%Gl;E>_-;=+&p znAZJ9j=1+k*qA>>BuTN}ebz!Hw?$211c!>kv9T?G+4!k9ooTD%gg97%HW$}5S;@ux zK4+Cahms&MDTx_@6s!(xdH9H*?Cp8j6p!QG2%)Wsboce;gLip5RH)YyAn~+1^fWb{I^V&#q~+=4@^A5P@LsBp_(0SiL&U}#p;FL1 z$I%(^%XatmW&hA8tPwE@X3lZdG@`iaBdn!fA9`-eB?s6o3XEE(y`VL>M;UH`MJ>J-WgnFJzQ4@RDP&BI=XBcyO13 zp?cB0075FdcT}G_b$1lUD9lm9MziH|J7xG0Q(-5UL!sI2Tv7D7D{MdC)W8~3P+0EX zN&PKKat5!^Nz4v2YOGcVO~r1bU^ZU%ys66?yF;Si0=2i@_~A z2N`CRo&zDs#$Y0&5E}h}=`oq3OAYgN(HGrIqMWHzRlF&cTaqrdEhBA-I`r~;sW}lO z$d_d0JkgtDW~8wS@w{;awat}}<}*WBm?^F7g#}X0*pajkKezp#z?&!-jy<$LJt<(j z@m!hidzu(=>`NjjxC+>CeOfLs2T+|kQ;SQbhp8PO8*=P;By}|QgzPjGRbvo)LKC1! z(cnb&>Ow(9g9$Yrd%V+W*pU^>(IP1TFNc8J064M^Ej>B{;dMRGe41hPc0lPYI{x&G z+wb=QP2c9+BzRnc1Mgrx@pxfH?_b*T(@!PjTh2f~qgc$8 z|C{cm1K!&bU2_VZjXUKAc*4`zr=(0{>MgN5D9_6I^b<6Qi>M?NMSL~6lOrAxsFi9o zDDF?q^DxMCY%Eu!5v|H*g?oP0v!0V4lBUfij34wn^-frnP>1xp+IwuS@Ff*BwK}#a zy{i@$7W26a3)a$rwFu7~?)6nkn=U}}Y0%3$e;_p@W5LcJdRCVq>GHwhVQ)Z3(h1Oiz&mf$9#%ieLURN&dfe$i9Er? zrQ%lF;C8@jaU#z~G9Qj5X8S8&B%Kc{~)Q~?-9$eS+RyPOF{C3{I4d|djh4cMX z-1m>}FMbPh_>VQ5_N_Y|&eGJ;u^j0<;66%t??|wxq9V& zCVvl?yBoiJ;dgu}^m7RjlQGlaS5Arjb!tQ}o%p@*n??^98xp<3d&1@Fu(K%HwX-UW zWWTMP$$*^#w>?v`;KA3|0$;3fwa%}eL*&F2%i?azWkkJsW9Iy4SQ7+3bAS9cml`ahBiG~ z3?}QIBY}^QU@lQy7maAe&d_poj}rK==n8a-B+5zFe}OgKtMEhJP$y1qFT!t;Hjpo_ zd%vccT6|tA|b?j?xSC@FL_6q#n7Js%z(S}Xp7sa(eOT<*db1+3W<>u9;J-5U^O%J!(J16qFFOp=q|2qGf<-g0_P=rIs1+MGy z4MPrc|5r8fv=FkqpDxc&JSjfX^a>N&I{`a3NbR2Lmqs{Y??3LJ%S8GGF2IdJ@8!PO z&>Q4w{YPiZgt0J{^p_mS!*9>wVnqgG%OWR(DRFXyOzDsh!lUxeyH_|({`bcc<_$KJ zog z=94>e2}zphDwEWF$<2V-TRYTG_$+d9e}&wSn30zGlfW8T%K-iBC$$#L%OuWU|4GK+ zt3K;8slyQiloKB0@z@o(%1yosyTX|wfW5@TC<`}FMd!!qGB z#-f%R&-m?{L_bez)kH}XBJ%Z=P!1@#a*pnbA-M0a<>KOM$Dx*7$)4(O=#h8zRB}#w zs!=nJ{ui*vvSwv)wIrmy-w@Q^d>`K4l$MWBZ$2pz+`HPmLT@zFaI6)l!paA6vjc_> zWQ6=+iF2C>f(#7|NxHJu&D-Oeo%{6rK8m5wSWa%L33l^hr1*p!lBe%!VK1y3cf+GB zkN&~x*UGT3Ck7TNQ*v+A@Hr0Va?Owq$8&Xd>^v7nRH#ILqVvlkG0!f{Ai!K=p{(uQ zRJ^wocouoF7s1ofqq|dBg(G|STXSZ%v8fuD``s=iwSUFmY(UNfJF3OZ`6a=aM>rPq`aZ5jC#{oFS-=X7wmcr3v@`n09+fjpG!^^2EGUf>) zh_|1DaEe}_z}T6W7*5a6Zav!f)0#u~$wD#X7k3_$Z)8~16F-%e%#Jw}UR9UZ;V-vk`^?E8-lI1=;M8~(hSryT&2dNyzUt zWqVNf+^rKI{3`^Yjs|n@eqeeY@8H971O59eu%TUVF+7TZN}Uf3xt7Y;mBGekNGC@K ztmna;Pdm5fU_}3K;qE=(_&-%UJA*(#?Rd3K(W{u4TOf%AV}i_%4(JSngDv!$=)f3g zaI=IPHZJ;LT6oG{z;7x`EDEBZkl-#VM=)@id!7-R~=h9j%b_5*Y{`|wuPO)wo}V^Bn#A)M6aadY4kAwFz^YR zYc?z=V-itF?QyZ}bieNDXiu#qxbN3Y-Rmo1gw>B1bNuOkdZ8Aa`lX5kA%8QIMLw!> zRQtCluKQ#FxA9E)RMc)#1RnOOnanlxIez!a=XBR!8@II(rGHBHS|v9T?1MK8N%O+jvjB3R(T4+PO4A78*dTUvPwVb;Ep-gV4QREN>f zHRvIb?)vD!Nkn35a@nPN&!y1c9}fiz;V!QW&mYa+@kK`mAy5;dBQI)dYC?+JUA>2~ zK69?Et-Y1@_J}nBL9jVs-ENWzy(Z9Ew*p5(>f}$KRCRQIek}N_g7lCm>%mHPy-6!X zuW>EXld-?5TGs~y1H<}&}yd3OtXc}%|?%e)+ zYNjk{!kO7AgDVn?tL4v9&%0jF20shGAwc5XBX^^I&uk>&QiY8G67s%_Y`@&K`fRFu zXez%m?{bTD6Zd#}z2PZSYRRI9yd8St(OoxoXGXin!89uz_D4SW1}MuMI)OLKH-J2G zt4TzLs__}Us$oiA2P_TfV$Q&71op*8=L3KM-63wEd_|ycv5JeA7I0VrCkYOi4=v}w z+Tc%3wzBK>CD*5vPhyJ3?aRsp5}ZEtlyMU96H7`nUh)5G?ulK6JM%`< zpcy(DV7+x7EslY2f{qUP4>>`7A0a1c?&z=;Z~>A~f&JiaFC+s^&}+~M zrH6ivLag#_`B$%B%jxUWlaP>PHUc)U|@?wQ|$w*(U0pL()$Zxq4FV; zYeLyzRR%-=IFvfhTanTT5@28_1q~B|ow{P_t=wEMHwb(2X0aemoeChuedks7 zoaXwTc+ux)Tu~(-U%Dr9Q^lXkQ0;Zfz-7 zU&pu=w-EjceJGZK_j0`TT^nB62tKmAYPI^Nac1&q+*3?8j1SWTsz8Mv?4O3$O0^#6uz81fc}!%fZ2^TGNI?wW$TyO?sydf*IjU7+YD zI2t|P_XYh}ER})VV@R3`#AXTyZA>6vLz66!F-1g0H7fE})MXZp{H&zH-Px`>ZgcFA z0t$;nF}TD4jzH1}@$_yZ`u9DTN&@5=y=<#$N6)Dz{|ZpZ4dW$DjBcxS8Zz1MSDfd=L)P6ZOhsL>PsvQV z1$S)_JFiY6E0mU=1mTr7$60MpX}JY=YMQ9|dtn#AD>86B23PBD(5z2ve!C4Ni;z0y z?xXgERO3WwjM6kMT`eJFl3lY&khS9 zUbsC)n>%pf3XlV`Cjg1myyF3I&|qR{TANlapXhAzD}aWVy_Y>P+OH|->Dy2=cR+eY zfv0#3yIpjWSQ&aM;9~E#T2B?~W&>29W5{#d0R2XhHQve{X2>pV9oxYk-3?qf-Qjjd z!<-)WI6G`Isf|ral4fUT3htN0UFzMe6)P*0K@O-o!gCT{a1mun-57=h|Cc>(69j*Z6U)p z_^p}DPyGB)78ro=XV0Fc<8K6Pw7w{cC0#98#k1>}AN-k$BqcR9PqpQqoAPA>#4m_3lU)SUSJAwiQ?0Q+0f zgji0A#QmV_%Cv7fxu0o{YW#mi$-eJ_Yf?Fkf(fA8-t`KQI!1BCdt7*SJ?feTyKeAA zTVsSiUlXh3mXeAG=>IsU!_3^A@$w)*sL^0;PCg?Acp>Qk|LUM4bkf$tO3Yi|+BZ@9 z83MVD8Y~>8A5@;?DaOE$vA~kbvIY#BaJN=T7gqqO4 zU(oZA^}+J26;{N{*}Dwk%=M8##-q=KcqD{BaM5v5o56)n(HV7h^*^l|!^(r4dUbS1 z!0Rv`qF?Q4RXm3^hM7$~$=D5VI4n)Ub#%ye)EkWXB#q{wTA~T4weN3)Odh*%X&jKdsX*-; zq0$~y;(rzu`K<33-1ko39ygIE3%|Zwi6CZyiez8@*U1b{F1s50_Vtm z=aGb|>V(WGYUzhTte1t>Q)eC!Cq5lCXK7FUFjZ}!ibuNi>2;?jz0F{WEV@_iOY{P~ zdDuRB7U@dP#5uw&(>Y^s)gZ+SDc^kmFJ#F;$WpevNrO+qNysx`?R<9jx|abjPAuHs z34Z|dl{!=t`S3_H8aYNRoX?UIh9y;$nEuNt)0x%KBR^3mJs8V^_~y!dxpD3TtjG@^ zmnn_ZDc%mN1uveHWBlN$rRB!Ddj+R?i&CZBI}@H~9}Jhu6TkWy1Y2OEk`eMxFjnyt z;7{eCCSlzH_C8yvH#RPO#NRr7hubFcWh?os%#f}RPaoXIX3DzI0f@wDj*o*f_(q0y zq+4UB{uY>8wYs)8v&@_zhE&d#jIxvYvJ;qZvzj}g8_fG!wFZ=<|MmOP6PoifMB7ebKwDQ~|gt{|Di2WsQ zwL#th`el+u7Gd;k&T}%-6doU9r1HK#6XmSc^OG*86{WZ1&B&lCIML5z*EqVn%-!nqbCpS_-l+KM`~6ij@dB4k-zhVB5YhjR$qzj?&Vbt z`3Qy#j%|U{k89pNHWj;{5z@u-kvNvfim9c5N;CKs0J|t)oG3_TjlARccnZiUyfV5} z44>56VV{Z>tX^K1s6G9jP|}&rCvouMOMF)>m2=`@kLjs3$)y7`{IAjk7h+SLVAZ{o zd)Oxb_JLq7rv=}=qZw@%Yb{dSgpTBN*NY=X@n15=HRNAQk3m((CMsI2KLgYA;$Gd6 zj!sX%1f!HBgaTwF*P2*%yee&U@1S2nF1bn-pKJEZ&J-3MD>=q5GZ7F`kJ1M3d4$6; zb!SWgZ|X%-B*9e@D%`cONnV3=!5%gck#=gUQ89Y3n&SKscR?<=>54NEubto&P7vff2~EBn*4 zvo+sZ7f%meoa9pObOeYDCWK?9_Lo4e&OE^jYvXa-G_AqqC+q;Z!dujdZ&FP6V$=)! zF|D?u5m*E^JY-D=8bn!~C#tDpdvfhBPAjS0b@n_+NMj$^+VxCURTd&`h}-MxoqYMh zmss}3IKP)cwmNi4L7)U$eN5M^wc`OK2fxf^_Rj&e_yKS>z|a(mW^{ZaXrheg-C;M%R@IHDN*}>g-0^ru>fR{U%k4vQV$}*$5#L*u>cfu5vZoH%f=>xc|i^HX)`Xn zXs8TuD;T6>zGJt(2VQ39QKSjXw?S_Uy=J<#^>y7wcS!~xDD2Nb|NrV$Y>{E7uJiF9 zD$BeRyJn}ze0Ol5{DRpk{4itaXsf6yJTbAOnLUwM7E)AyV{lt5uWi4pu3rB!%HS6K z76jHf_vvVmEah+R{>4&TJeMmP0SAS?8A^ZwoSSidb8l3_vZ_33G!GM6bNkCi(E60t$yJ@6--vH|H1_)}QloPT zhrj9#-OKC9Q&!Ts@5RMj>!nIDR)&c@vgv~dc!-2arM#A#>HO+lnYW4`cwaxRyzgSG z{YbssU^yw6r)F|B2LQ)j6S$Ca0Gajd>nVVI;Ml8ezWPI+F&BJi(WD$W|4LV`U?I@y zX9B0gJpO!%VIV6g+`erJUQvW4Z}z%0Gj1VB^n`;0f~wi zwbz4Wvtef49;)XAgapXMmIlmXB0|4s?e3&GVRB2-gMWH4`;|o&v>iW z8f+c?;Z6=@Fb_K365vOj(yi#3<6xd(zwVwGe&Q^iSs49*_uy@GEo=y8{XC7tTs@7= z?`x5vjrnD_U4fk;S2Qqt;nE|8fCdt3e$wm?CLlKDmA~DY3VCGQubUioh>v+kZvI7# z;T%OvL(|RM7J5np4Mo)aKBW|}Ghs1;oox#!M@j&|MxcB;x&l5Fuv_Z*h#NwWACzrM zESJCPGw^%~qrM9SL4#vq)_+CLt36}|a59W#9kzrwBz2yekQSfuhT0R8DKVYu{1|A1vQQ`sE zc#BrP;B>`^VNdjm*dFm*4itk?Jzvo!gOa?Ir8dursyM zM+q>+;XxFa_Ej*B0$Ro+?+Se$Dq!KU!e|7%u^6kY@eqk6i@tehK^Xrr1{E_p?E^?q zxR|QLMcWs2VryaGoD|;z)^;Pmg#H3gi zgu%8_!tel43KgI!=ztPPjO|3};EiEPSlZY;08q2LyIVz1uN5Xb=r;B*x?H#;?ZCbb zkjv?_XHl=%pWDm~H(*P;lvT8qf~*9}mbmhATN}5Rfq@p>mDoUelCX|SZ_n}_vTrP4 zpuK#*&iG_Q$d(Se1>gkNYJ*o3<2jT_TTIgJr^@5x{WALy0N^%;rG2Ap&dr9gwsCVfXOg^7U4&abnn&# zh0MFH>bR%wmUh$k`@9hFOi5B=#LD3`tuwaW`zAWV^^K-CLQzTGz39Qo)JL|piZYKo z68Vpb?Z|sU>2(f-<-ihs00JnK+XX!>EW26~krfC__MnJCIa~lQHG!^Bw`dFJE#ywH zgUo^Zh@z%2`nWeK0}M@^(gJ7g;3ydM(la#d0A#rl@QFc5bn!#cEKzU+20Y3n6)J+& zY-}h=ZS~B$^WdJ{Z>vjxf(`SdG(@p4sl*2pMbUy6*YdeK3QNr>JKjN;_#=^9bzs1h@UCgRi$%Lf01mooSQ>2qE zV8825cy2tu^RXOHo)TGF8}@1IF@4a@d4~-W(hp2%A9pkCH`? zkG89#;RYE|nt6lv7ckNEO)XDAPteH`y`eJu3j)@{w6y_@yA4$+#0i$BU^#e>-&7%1 z9#AG2L;%?GDp=bWh1i!3!w7_>Kt}+@D6{)oo>K%YXKgv-^Mp1!)`trx$#1DY8@R;1RZoNLlmS$;Q}-X*LIB1Rx{xpu!f{6ErPbS%$j~6 zpo;p^qn`SgSk;;UN-$UGn^}^ly>%The<3;YmowV?+~V@doU0~X*!)%89D$cu@Brk* zX%sEnw%{4Wk$q$_V<2LvM~a*m@;r=8W51a>d_s0-Y*t<}Mf3rTWh~QhmQP*^_wE#_ z*OVqR_2nH?L^XxrjkgZ4H_D6s!oVo*#F1UOcM0scO`-h&b2_N9`vxB@fEy=_ZJ7j0 zp~XE+0qCCNl-avd70vY-5&?lBozq^x%d>4Lx{) zHJS%T06zPJqj|o^K1f!@md;YewgC*M`UbJ17?9Rboxs=7pf!uqZvX`LE3m0_XAS`8 z!j*+#FVLoj!(3HEtAia9AN`O?B< zH1jxnysCp=yt^Ek^wdYSUE+?e^i+F?n1d~ZO zus3Gu7jW3IPu+`$^p|`#y@t0<#BFN;kHJOaEJV2QBi5h#xUz0T;lZq>>B1bOn1*ka zU05xe>IkMQ{72gA`{oBxzkWAdtumXtcu6t1X@e4r&!VPTUiz{X4U%gnzx1Gc{)OmC zp9ALGhi`Ug0`sveP5*xYoE==0@W9Zq3eY7lxi&aRa*qEg9DIrS?LcUR!w}S+t8f!H zQ&I8G4m6Rj!67}9=qn8}nyDF?W3jfjHaU5D96KP|t>-5mzCb&NAV-4{9reI1cI|dg zg#41HeC29Z<=#V>hy4{=Vb`x+!$ENHh>iZyh#?iXg9DzX^)6K)0G&j>UNF~BD@QU z^KACl0%s_eeqL>msgw`y2-%*-uBjO`T$sEAPXa6$qCl((Jcy}m~+V-+7`o)1OCw;mD`(+e~m^rD7NCHI> znuYcNG_S(*j&5Y|Y@M^H(768)?_-^bfY;e69~)=7S>w6w7}qF<7X+>Ko0S|UOh?-)O9eoZN@y_1JBNu(&ZT6Zm4dd>!pX};Aia5iEF83<0aa@21xL@3{`2>MxCXo7 ze&!s%V{EYwGxksKrZWiym>(*XIYOnnaf1hXbj{lFG>nuCH`9zOdCd0L4kACZ6L60b zVI+2c_t8PK$~$}#npLZo)sCCj{}+_XP#n8}Y7=Y6MHfs!5{ji;BqGr{|I1Dk`~*Mt zto}I*w;TNBLPcfJ`FyqIiY6x}V zN12sFP|Fq8lYb}qMAwY;$9}^pxm9FoFMMYCGZxN7SDu8_9rxdeYP=bwEu?YNMP3?; zHvL!_7ORQN9nKd*11bPI9j5!O<*f=t?4pcyXfRDWl#uT0-MU2tg;i^!OqFil2BrL9 zh&@fbZet(Wb|y) za$5cnm2JPPJ+krEv<)TuExz@)Ud1j|c1;s44i&70U8byeUngb8($4gWBg;~r{?SSE z+|rm^czdMSd`5Mvjgq66f4lXcytrBF((}s9%sHz|*H;+o_|GhV630M-L%WkTXr%_2 z_*1lx2fD;{I8@L!8~T4n`&RCvp{q(tO7kB;14(;kn-oW08HcGhKe1sCz($2TcfGNNrJVdf8_^?ga!ml6LszDh>q~8puCp=J-<_|T z+`|fVQpa_QUs83nV?@jfPY~y(jdirGg1oei|pBdnpKs8*-*?(xBl z%r3}CIzWTk4*o)DijGpwzI@rpnE~hdxWt1gcCWQ&b}*%h0f+!4Er5ujRIDUWp~K9U z3#)oYf#kRNk03yEGqOpGKC`{Ea>m!}@j+;6RZ9i$=rs@^s>Apzn{TX)%mxvQ=d`^` z=h?!i=T(ZfgE4aAkzn6jT`qmGGtui%>UgsX>u*%7Y_f62ETO|oAo%kD@#h>I643D) zgSavEoHHv&TqnElwJ0T#49o9#rJI2l(|E`*D;YQ8isK*Nm%paXvvf$C0XvCaEyo1s z2{Aix5cvI-Q5@dsJ9Jf>P__#cucXz0p)~^oqaN)?x53hB+69%j<@zcrDdWs8uR%M; z0GRybj=m1~l8U()C|I&6PSYz|UnMd~eB8EjSKB_UuDcbJMP*k2K2z6SGVQq8tVH3@ zYAuq=zXaBG6ZAiFEVsRNHWZ6p3-^PR`40jRRK@c4K9UX%|~1t!NolM zb!PoXf4>5-onmct}Bz3nYrj? zK^|^U{X-Q?*1}pxwl5byK*dsy{0_H}8NP=%mWG1KW#q;N239#GL-Q4uaJ6q7yh9`G zL^%<%DGKftv|5o*0+x=1&=ialk!RRfi+Wwa`rTc7$7y*?L zgfM*YBd6!?UL4kkPhV5Q#xEx4R{9gjzvv0CySl&D%U828=m`!+}!+egH#g!0XqA^g61ls{MtT-nP9*<7B>IsvZwl zz8N?JP^=Wt5#A|k!*hS7Wy^+y)IG*B{Mq3zbt43nck(!@*#rEIDLC&yW+$2i|t781!j>AhoS2nV{-$B$qz z^rGe0+}7sxQW(aVBX0Po%cD^BeVHhS)h?nl{~~*&+=m#yA)yzdM}h$TKYQqsjr)$n zi#mwXd^Qu0^ql-F-lqy5qWy+-!DaXBoC0&FaI;i&dKwbN<|lv1p0j7IzwpIVPfwNRW8JIUZ2LvoCUs}$ ziGKL``Ki7BdqOgI2J~l;GI=ZB-LXT`t1eZBAGL6doRBrCp$>kvVF0baEnG6ZcTW2= zXlrgOJ?#>Ei-}D@gqY8#0%JMo9G^KuNJNwb8F1%o6(oJd-og{7amsMd%Q~jI(}tyFO;MX~Sp$2WP&&Wmp4UT{ zzL{X*;9|e@ZD)6$&pl_Yao-6hPd>B6uXSh@TNBw6i1>Rj25vY)l2P^Ww%}kTKK&5D z$+ML}WIt})Pc^V(=^xGy!yiK z?#^F^+8T`}Uo7R99&V$FDvBOL4jTmnkzD1~U^{&%{c;L(i=|MvP{TFAwbs9KBhuw zf)XjgJi*-`YN!ODz8=l^9t8kJ5A>1_2v5a^>Yo^~zFf8p+Mq_6HP|WPP}P2Yf-mN_ z!URNE4R0c5W~o~yAGKHR(Vp$&p5JADg+=i2(sJY`_Q&-8p-VY6f$U8-%WGaCXY*?v z;yxF{rEq6F5J4*IjOiJy?m#*8B7I=I@AiKSs0uKfgG=782Pl}j?#bS}7GG~!cj?(+ zFS)f_Ds#;1$4{WK{F#k78e8^83lH>F>MiAxrIHl;u*T?9vDLyy=HzAe$bnrU1A&qj zX3rP_XRv&KsSMT>0?4(j{VFg^WT2Gz^5u)&_%o`A$jIKk;^U+J%)PU6avo>R-|UXI z`iIroX!CMhBE+beUoXm_;vo4oUD(_6^`=iW@A+CTjayrhlMn6p%#=UZiA0NdU;h-k zu+txR6Crk5{INXn?@}g2^sBs;r*tDa^Em!&Zts#rf&1UmK>u@6ZAk}5*0^6~!a99@ z;d$%$8OzmyAYqz|-$vUpaUq6!l;KP80sKuRB*Y5m1fc9=?!*P&)F1AYaiVUemwRmJ z`uaK!qk>#A)p|F>iRyE`Qn*_0FQ*}LrI*UgDr7CwhR9^ES>zc`D=IWs&z`&hf}AhD zcd`!;JAuD2eGw1mG{3yF+d=jFN&8*DKw+AH@+F)w)xSx-+#ap^jX*xG>mNH83@c6DXgYwT1NS)*$&fItu4CRsj5 z=r#6O(CyjCP3DO%Byda3xy1wP9vGTwn#LG@%E!gE=W9BkQKQ%#S=_#Ki-_>@5bWj% z{AnjQF9i$g{U>(gCId}X0{QkDXI|WXNyumUGo=X5kug(dX@Dg&9O0dxuIORuM z`EyD5Cx|zYp7YasFF$%72%Ecp=J<&#TM~`|KD48wXls_{%V(u7Z2unZ5$NYu%f7eX zL|A*LL6wv7eZu-eOFWtET%cvI|11l1JCVTDA~ zt(jEfY^>m(VE8`-fmGNjJl?N&KRJF%!Av)JKx*#F*#B^Z}b0r8!_)wf2gDjE&3)< zhd+2z)|%~Z{9A=M_UOzcSu{(^*ycIbyVrNWUWL|N6Zyixnqkt53qX)DUkLiE&6*_# zdcrCyGdhj$GFaMED2mK+k~$5>98qp>&PPsF)f9YBrbFnIDvJ2pG|CteO|_Y-#MAkW zIAKc{YbIUxK`r?AwPBkca;gfj(XD{!_|SCMY|wByiHtseiF7x<)KJvNbQ}ST%MhcWd zbT`f*_7|glVnr@F6CgoLPk;(o_Dtw)y~!2(cwc>0fq>41Kl?7Os?G3!*b9vJup&>$ znM`OQFD78EhTBkSzB(yu*8s)?8{B5V_ORg4vPBop>Bh&$*xw`EBmVaOJwnn?JAN+n zFccjRzdKxL;}{67uPpBQLZQR7^zMbV?%yZt$tmWG++XpxjdGt!eV<#|V7u;;@|H5+ zjZ4y9C1nOK>tbFk?&Dv(x(5;e+=%4%M4&q^`_zm9U-qhg0$}74B|34YC0p2Gl3wZc zmV1=0Yt+cqmP(YLMHiA^5`MmIx~ijlHRW$}Jb5OSTcGG}Ho>jmz0UgYSCJhW4|6Py zN733C^}j5xHT~Oq%ms4TDyliP@O`MjLLe{YET;cU98a4%y)mVo5Pj341J9pg0RDr1 zo8*_0SeV1Z=bp$j4#l_#f|55IO9APshJ0LE%|{p4K-EU3%b!{uPz5BA|bEDnZWx z>m8F5N8vjrI9|EWeP|82kK*=E4k7Y*~!;HKuu?`)bA^oz(oNtj4r&UwKQYNTrF$bgT zXgo&e(f2`LQlTT~Ut{>Jg^6lgB?v#eWJ2@8iOTQ?9x^v^LpLsYIY{aDFQ(~d+lTI8 zNYMETM6vuW$2hW0sf-Z6(U@$W+Y|jv&PHCRD9b8T8ILLBW4dnNCY9mv6-1}z)uFU& za4lDLQt9_)M|>R!KV0gT%X{;u6G2SiqA!(Th4oS&I*c% z=*Gw=a{@t~P?buNoP6~|*p2+KCdyYMne+Y)Z*j%L6XtC6`wSOIJ|a7GSik8gW3kvy zb*fAqm*BK&SCV1&aYqMvZ@zk`ey7FG3AGiAS|>#W_= z+Vs~;A2%*uXepp2R-h5?nG^L^b)2B)*x|jxrVEASeX+!jMo4i$WM3#w)c%0XGet%= znEaN)&9okSxl%4+;Yct5C9cg82O;nVR!Ag2a&=Om)Oon6SPe<45JFelQ}MRGHipUL zcH{Si+K6Zj*`D_j=JVw;mjY2d7x#1swM2fM0Hfc{^UNp8`S(4O6#>M@dL=$_LW?AN z$y-oF=oBS`r86txJ5Y!=3+q^{JPW^Un$cswm%Q>KNChEu9z?%xNp^5HG<@KpQML^IZ!@Vu)U<=MsGGx?LHIe|5esOaF%6C&TH_1T7cxa|8X8 zcpr=TME}nnW=HRE@&n?J&p9Suh;L1Mf6cim00ImwwL%k;0of}}MmHYLCt(!m?Ikn( zi0_zQC3(Zs>4`}n|h{%0=XsP(WW?BM$kw<$5s>KR3+5&8Rl5>nop6PT~l ziE7)Ww9`p(5Bjpc*I8G!_R&e4pwTpby$q74zuO5k=L2ZP5@no!ms*$@ldf+C`NHGr zi$4)rr6CK5$@&*@98#H|8`WO>TIdXCR4&wU*i6hdd(3j06$8=l#5h#zH9O6{4sGY> zeXZbKHeCTycVWK@l*-c4AOJ?p zu6rIx`!cb)w`QB&PWLT5`6cBAQhm2*koW&?G{|}gQ~h@?Bh>Y@nIz0uRQhjD%Br9Q z!wqBqwuYnc=MlBVqZ&xVdh;Cyub@6Hsh=ATJhkFJYRero&-v=YV|P_!Y{h>!L>b!V zm-SqzPz#|+_t3!VeY}TLUbd~TmrzS3p&7Y^U;XPOv+((z<#}3RTC*$7h#KQ>NG+ks zj|y-ns^9xW3kY|W+r0UyIu`YhVkMV+tO}=^n#D9LGGT>s@*YoZx`ECHSGIE{4cbqG zG!r+l#yCfyQAlo?{+X3p#Kw;xG^FTXxb9N1p)Ba`f0dyv!$FCdE2Xi`Gb-DAUzYLS zPZ`=tq%E;s^bU|pDQpGkSMWZLMzO}3`;;z1Q8U2kk>wb)HE>NmACXFZd~gsi4bo@A zZk2o5(@|po;f20=y7aPph27*`V**W1Gn3Xftb(n3i%E6ITgxL?KmE83rS*&Vpvmn@ z8NgS@JW&ix)42O#!{-Wl36)&UUx0~O*#oe8D-T} z@$A#I<*ql5uY0WSdKK&Q=&Vev7O%Pw?RYV)?6wAQ6X=G;GkJ1+eQ%64``bh?66ZS| zU2tu$6g@rYPz(ADCZVcY4FB`2y<$J76JQ#0Oci@=NrP~ximg0vU}>m3QfT@*37IK9 zc;DfUJs~yAK`R?41dPU0my~QhzvDItu&fY%|GzWq2 zpIV)5S2rjqaW(~jtv|2iD(K#xP}7-KNw+^`)txV}e9~X}pt2{N6}eU9t9&7c*Nu;5 zVXxyB6B~&XLnY>R9|NF?S3D{{Ql($we9)*U;;6UF|A}Vg+8qn5ISk7X#zvH%?~@E> z_{Z(Q!~SRLu!p+{zCH@Aqoln4mW47l(@IG;mgXVhw$S+c6^j=_wj6ucK*(utKfM(M zvJIF?9SEXWK47$2J%K=`FsfojdAfx8pz5W8XK~HMd#rMjUy&KdkM=m>vGx9(deM1lgMc*n#Ox6QuVd-j1Sa*T_$0wAj!n9ci+UYMz9 z0U2t)Ijusi<+i}XpV5m9quna<*YqiPil}UzrAF%L{Fs?Ve@^>KCx%8wKG0Lz9Lr$o zz86YQM(WBovUZDR;queEPiKZ6U(N83A!7D^>E?ZkE_P(e{*KI{Ac$Mc!Q=dqxLsSc zKmfROLK{X5wH2e}(vk)K1dL%s8~X>#$49(dEKX&EAh!h~7dMdHz&pYZl~jNn?^HnT z507>f8pa`$tj^Le3k(gNfj=BuZDhp%X>&!?;yV)pLKgy5uUrfY6;bGCa)2Svy$t7J z=e}G3RKdG*V5tMO9&Co~wpSE@RqoDG?(n_7vw zcT`iI`uMhTbZdH&dIqOW`_*aX*zqn~%1oAUv z#Y56m+|>^&=vs;neTrdf5Ix~9_u^o+ZjOq^1YQ~Q@1E=Ev!WAz7WesBNyAAmV45KG z1+ygo^Xcga>GNBK7w@AfMTukpqs0jmxwhwUnP`lh^7$%P)>e4?Dp; zp_+?JpBZ;@h=;0j?kdfyDq|d`Hs{R3x-oU*2+=AKDJMj#c1cj`AgY>1-n@B(;xy%; z5<@u_pa*&l5Zdck%HlyVt9Cuu@BkY#2>ti4T^br1lm!XA4ioU}dL0?*@av7H1GMb_ zi2G3nDavd`QA3C6Xmbz^)&jwXG}adSH+0}4>jfklR7?*h2f)^X#9|zDgc4{w2?5?7 z*k-Q)V7L1=F(1mv4O>E+{4fr2p~i^K#UGHlTPUg*W$RC7jQ_loWv1UOjHV^|T*M!tToyv!+{zxU?Nyf=@T^Q{m2kOc|*Q!zJ=J$a8_` zwI*-?!p_Stsjs|8jxPJ}uQoEe&c1JAN4b0r z%R)E%`UeM}k(_o4!G5LZub@9tUI?A}rD2`~9eRn${pS>>x3C&kXX5;t)Lw1Gi9h*X z?EML3pmU&}`GY89U@HN-fwY|5AAl(=0C8&()G7-lUF;awSXcs(PG+J_%~H`N4UW1^ zbeQwAJ+F)VF154g0T#P>2&)2p7Xx4#PQl$f3!2D9(0p0bJuvBf-?AVpb8k9LPD;wW ze{C6FWqw==b}RVj=E5GB+t@6C`qZY~62VuTsj7(4T^T^Vi{ttcg=f&az>_8A>{wZ# zJ+0hBwxQb`o?*Qb|R~R?-jSbqvMEw-{s^3gY zi$V0WUNuKROCY&2my=tNUR4zbc?Dt%on2i)nYf5APDUw%*W+Vr1%OV~yAva#*Qx z_Htqo%yA-OAn%#IPr;zems_R_AeOPA^nbI$uH&U%^0+>7}QATpfve*!Fr7 zO}kw$A(2|@6SYq(n%Jp;v)2A)ArU_qNCf-6{lA~3T>|=!WpS)vRemVV{0p=NUw?gU z<$Iu9ZFx5|)y9!|Dqdu&w$3ojjbMFR-eLjqJka*W=1%F${H%5H z#2OU!h$0SpJqiJve1Q{!rjBlP!*d^tm#_UUkn!cjr4bgvh$Z%Y9s5)VRdwYnU9z}_ z@w3G8aZA7+9(ssOxvktqKp}vHa0Ln%3b>4BFrG&QI{~4%xGOFP-#0fm2_pEDAX)_E z+CM?mgD?X&>UIb~jd;*C0V}c3S(RerChjd<8OE`6yxuK6GX10F&8kVvQ4DXY)w9zB zSNDx^OsYphuePt_MKE}^+OynHG=!Z24&6mx0}9kaPo`Z1HRrXPuKEv4)h@9_FSBNR zG`4*>ycJNAE^Lf~y26lD8D3H7cZydSV;#!e>X?=>tg%7;6B-WhWB3ZOa5*SmbVUI0 zF%)qDQ)#490>QGZs_KWg9j$smw8EGXEP~0ztgX_Ag&5s`yhpp&KN=8U9l4KoYihq5 z`sCqxaQoPm^hW7h_qoED>6hTeSsN!F)8o}-FTSs0(h5CH9!->W#2uK}0YqemL=3A; z>?2}Tll~ms{+ngQt?g~)RF*)wv-f}d)($MSrN$j3&po!pA&;XQY@Db#?iVD8Zt(j% z#sDF!fKe=yKi?w}Jspr=hm1go{MEFS3t}fhEQ?6~L6dIr4{8P_MBl^MqYJ`FgogG9 zBygq>n=6-EU}yo$n7?M>UTJm~FZavwzjU%c)Y~pVdLVBi-88&&B~!BwvxNJhL8#WDKQL%H z?O5E4`psSWA&}u!9W={gJF|&V+!Qutyn)}9tTc`<$4@b_1{$>9xG-}}aw;D8vtu^V zSETW~Z*wawGM-z)WKNo1-gueFS4?0kXt@?ak|2u~DPZ9HsG&Jzh=IsxVc8-wS{TtF zBR-q@y`k&fq~zq^5Pe~+o)=g%Jigj`?a+Abm!?KW89H5x6ZIA$6xu|A+Ugc~OO4Nt z_YgQnKr#nEe>|w&5u1UGj7;{IBh%azaAgyNtvL03mjxkZvNvKO3;)11cOPvg6mNpp zt(}CHL3;WCdzU3%cxkDaMGP`I(9#HSeO-?Oh<0zaLnra#TV8%G#+IU zi@%gIf4EaayD- zj2~-V2+*`!9bS=*?7uux+g+OIYs$)To@N8Qc&XU|!7~t|ZAfjHs#&q*_U^d@sGox4H z3AX4V8qB(ZwVqsUzgR(^3Ppu&!_m!+#tRXZ&vIbKRhao0Krb*`@e|fz9SHBiSaA=? zwupdGfq(ugux+=7?AdEq?;*g)a{%YvbK5mXp1ae!&}pKKQ*AO*!T`-6cz4$USla!^ zNk2`Ez^LjXM30QuMC%dka$oG*0qDrJnrbCv3%SOu>Zj{16 zMcWbRva^t|cVh(_#1}cJE^>yn_tQmf@p_5BzRmg+4yvZGmddKD_~0CewlbpL4DFw; zQT}gPo52Mb_2aHBH4P2g;bse=_Vh?dM1<{H=#BbupCm4ztO0psb+S6>QO0Kgy`Ij@ zR1AK?I9VOV!(Ve#r+m@)_fdPZla%Fzf#cQ4ma*M2jHHKTZOmL-6Dx3O&KR-cC4em1 zkwpZZ11|G$z9Hb_9=QMv8mS2+bvF>@0wP`==b1(@5Abjuv4>m^zLmUEDcMpR8b)}9 zmxO75nkp$u&0dqW9~d`kcJx_TZX(y`sZBhpYC5f6O*fz@cc1w5NBWQ2pOOM&I%;s0`)cx?Qx&&B}1>&7nALVu6;Z zQ-*Cp!^Yz=X16Z%1~qkY-uT7?EEd`ZK`Zqe#$j03eyW7FuMvDlfY``aU*%pPdLATa z(bi6O14icuI8d5>&`brl;Fk;l;8F|hT^!}b3zwvNUL!-Y#-O}Y5|rK;(nJyiOX5}P zCDdxq$q#5ESzCMA5(9ruMu^ng<*-|}&mF)d0f8LPftMygNXuujuy?6Q>gBu zdh1Ais+z}?`*1QN7ig&Pk5<5u*rztIu!tH-cH{ye77QB-v;bBV78WM7`%4T!0&x01 zPv;XQ^wDAp3YRb94q=&?=Uep$(_tG35HlvB-Sm1|U0h&OuG8q^@peLVKm?lfgpF3(dQ=aGgV* zHS1_&BA*2ea=+8^k1q3_Da-azqJ00E+I)ZDl&9DH^1w;U!^uB6b8Q*v03By6f7L+| zjA84K2zV{MfO2JOHsH_vTEo8 z*&FED5$+M3=W4KlHbIC5;=ThjCMjfh0R*7?H#`isjU7jp*5J%qCFnM&a;M1@9D2uZ zrnEqs~GL&nfW&FJ<{`vV^{A%+IoVJ$fbE z`pb=*-2RCXjqwZw$BY->Pq4k8pO~GeoH!$QX5N-M+p>=XY=Joh(l_1}21mZbz-Fv_ z{^0HZZo=)FV`wY2AelcJEc9xFo4-6Lxe)0*^a~M3=>*_e)!Io#v%~2w`M6(5So%rD zia(1RpE~OM26M2BU`6_ex3@;{7~WP}f;sAIcqPO2)|aJ|B1s0(Kr@$o;`R{)=p-a0 zkLBd#YUvSB9U^FHCx?qupao}TDXs$5*ze-RPTunK`fkUed&r&RLfC7onFC%B z6P-T3m~PF^QGPQ3QZC~26G|5O3G=vXsFvk8hSv6-dRgERTB#QW7B=V^C5xl!{x3-5 z_-2=&KAkk=Wg})o&M`%@n(ZJ+S3Q?IB>E_+3v%3Sy7uY2uB9(3^3jMs5;n76P17X zggd^maNsG)b)(R?>8fmS5Qdk+&SPvVxtk=}oP4eIa2Ylqw9&6N+8?U#o(3LvJ2s)m zy}uV!xnI{-Q^fg=do(aObX&bH11Fdc^_FOe@(?`_%9rXR(Fb$;)%?OM4(rELx^G5X zv{Iel@bP*7J!0$D{ee6FeCE?@mUt@5pBpTS4*IpeH;nPHuMMh@6m9%>AtGL?b(2FI zf`G^)Xi(g`d$(<6uY&#oo*y>7iw{Hx;r0hLwi3ppCo=X|lco-b7_2DCk9gBfJeU0`N#onk1T(}WkSTKXhZGt_7B>%1p|9{By=|<+GifDl9c5QAPt{ zM^0{MpuF5#pU3pzs*R~${^-XSE)$yyJ@z`Cc6H^8cZd7~UMb}Jt>13+ErJA$^du+= zvKlf|Xw)YH#}`f2_Sx12mqdK60?7H!%nu_D-Pfm&%Kob0Sm1sS?PjjqLZKeny%61gUVysFT%JKMRY>6F@FHd;k{S7Okc-Ins)kNm zynrJs^k4pf%Sj&?de-!P&c=ADPe5PJjZgc1V@&*6arf(qK@^y8iO7G0HTQx%hKtze zO^r}Uw3IhR@s=%W^+(macfX2^lI|v(P$KTqwc?#1he7C&7LAX4M|?kMI1qje_L_fR zIOD?6t(qi_bi*;dXShX~6LrPL@OdaPDna{R*s-CUf(TH!a5XGg37lROw2Z3O;}-VF zdT0m*{SHb_S%fnPH9|`*BmFX|ah6WynG88{A{?pvW`D!fgtDVNGV`|hFM zONN0!;!_x>;5(BV+?Tu$VAg(|tDC6C)%O9^e68>9dn0-npV?W%ZlN7H6j<=N@ch6H zdTf3EuU~$p^62ym)3&s8H*gLTvMj$9k@&|Y=oC3m%63?(Y_+HXr(a=o}Z{1=P#`XbVr$sjI zcj~w0Z%>5}Hc%7X^Pi2J9F98zQ&F2^1;g3SL(!{uF|LVtnm^q3)HcZ;)hzuz)9q8} z$fpt2au^MUBP|dPAwgK@^Q>>@CwNb+V z&>n7MV5@}r!Qk}wKJ2TJUOC&*?Pw#k!hWB2tt?xl0)XPTAH4oZB$cpo+}aUu2@7P< z5FS^)g8cT;xdUuEUqDyqWS7{*i(!g3z%nTI1Krb`v`y~D5?c2!c=oa5g zxZzqZWniTD+Vo?9Km-NgH8dW!aX>o@pkBzt0tl8@@bPcly&DGf$?cz5KF z7;#~l0U~cZ_2M)D^!EhxR<*i407Gq;28#Vak2929I$lTf;BwSQ@VJOu4RsEN)BCR5 z#?Yq$pSlTzc0iB40$M*VTplZ{tv_&SkkRH z2>j!?=F~?)l%yQc;{d|Ua6ft%PtUpO461k6_3A|_1%-vri8iyy5EOa9_e?i#yj@Ij z?_SPkVtR%7QFUP>WUBQy9kp}O?`xUznb2s1tCD!p-8eKQ(+BBidndK;zue{{M>*?i z#xC$DeXV)iw5mU-I+yUn+NBY%K=fPu^r2I+f*B<*&HST1)zzJlc|5EpR(uIJO4`jf6AU8dm5bq7DT^eYiOK~LcDFgE z&V)`%>Id(K7waImWr$h_e=_F3YxWZXq>nKPK4+w*01A@(U}`|}D0m5%v}gTk37eW0 z=nm^9oz=4rC68WvLQn`SJASvEK|4(IK$=TFg)XHaz!DwX-=BL!&F*vw-}La0N*?a) z&Lder9>UZ@U1E-!zf7#GtcP&!X+@|4<^jmGuiz~x0zWmc3fZ9dCfd~T>lC1+8FU~gd7pryH0d?G`#qGq5@ahn~K6o|(@u32ScLWU~(2kJz z0Q{x_P-dvt0F1ivj^C!?$P`hjgZUoj|Fp=@(k!#C zHsaCaj8XnuhBG4sVdLAXS@Vp=Vp^5ivO!X4X`hNM>56ndnl3(36ca~Q&Y7dBU7Q|H z(Q;zZiO2hXDFf@@Ts;?(>!N%H9aq?H_#XW8W%P{zg>Zp!l_oGZK%IX;d|$e!)NRiq z1#D1a;SggOj|^&jpTJ(k24Y0KOaWzl;RP`up4>P34tmyvQYu#jcGRk7JrgMB!fo$7e( zrlsOS&G%sD3;XiGVTP;G0gaF5(?Mdck6fpmive{dJ7mv8oi>fk4o>qJ1b?kg#LV6% z_$!b~;oU8qI^D9KFzKV|;xhM#hTpC!D1Q<9;188NiD_gXyfQovl1z~K_rQMQ7D%t; zvj^_Joz6Rjn?NJxoUsIiAD8E`1455P784jQkbqJ%NhKRT)ooC+@7dtH)Y1! zv}{7X^HbrviPH6s3f^Fk8?GZ;o0p8M_Gj&Cuaq1FUX;m-7A^VRpq1oTeR6+2G{aep zq#qe{A?7Q+i(_@D0yRsFuOMc<;!!JPD1gvwmR#nyTwsxWE-sFQh0kk04?;wk)dI!jU=!~!vQ*jKqqr@ag!xwKumg?qaL5Rj4j#k#&wUB)3ae%?XakR&cZEM$0j`1q$?AD< zTs0%$R5&pgdE4P%(!6)CX37L!$J0Xd#hX|l*bZdAeK&V<4*cM$75hZOHwmDOTS#!T!?6=wa+)$kwxa^&KbjXhVV5DfB<^#3-%hVKuGn zDEI0-GITM_8rl=+OQQ}IxFFYG%bje8w-sugEYsw%-&>+oTcpoNk8l{oC0@!%Md_8& zNm~qEMxuv4r@x8Ayl|d!vtG1BlpkBauk&)p=qVoZP!QA-)#k5lY?DUc+#X7)9C=#P zyg~KfT4=p+Ypvad&Nm*t5Zq5|HX2U8fB$Y?YTW_BYBeU-M-t+@Qm=A$Ua(J~P6t5m zie{i^jr&`g3Nnz6#+sUqfc{Qmz&BcHd0+FofKyhrl$p4V3$@Q02FL81&2EahL-Chy zMuR$Y%Ew>)e@@~8CcXIC*z#J6zqYhMPvRx07?JrgvYkPEU>zi#LGfMJzvEf&I16oM z4Ol?`azi;ShuE|L0G%}6%Tx%NSztjzfa;GPJ+e+YaWcERL`U!Tml46EA`APo0#Bvz zb2!o91o;E4=VHEOI2;sI8>&^cls2y!3jCtuY2-~!KW6f^ZkCfjG0k=Nc5K3V757%U z`R<@@!eVX1y4MHVNV&NBInhGTM9_|QtG5KnJJB=7@U&UJbk)Ti_a$^ccMf^wq`I-} zfEGi1AGI%LKG&=eCK^Td_6~}VeV#8}EFJvxE~hX3E8i3ee|r0YcrVE{bVv9(;Xy%l zZ0qI|FaGn`WGOsQcY|G(MD_jZ_`(5tp1et7mC+vE;ig^pjD6LMPWje1^bNI#!;>?- zvDPBX2fqIu7`u4n>twrO2zLo!l92jExmga0vfqFeiy)1l)H0oI4HAOAT#|0iK>#ew z);sSCj%r+3>P}_hLMNH|zy|x8z~ZL1hV%jWGKx7`*$nTF7b5^;y;Y6IB;o=cXyM`U zpTOAL#~^MTrM309NsR-r8OT8OA1|?9ijk4gXVh_}7KzY0KkD&D(!TDyZ0dhj zO!fNCFPX4Yy90@5VZp&TNEx9Zu*3`qhet17EO9M%c62cE@x=ijxPm_S%NGLx4(Br{ zCh-wRw2Q%iz*zWuSet;JJ$hHpEZLD9SqRWs`&d#E1x*xW^b4MKWEPPZ&cehL@SByl zQoJyP%IUj(Sb;>sD$qPhiY~w!nkhhd7;?_ z&Zc=VcKp7{^<(KKJ9oH*^L0Ji)7ij9?@E-V-p>YwLb{l^D-WM_6?@-Y2`p?ZxPQ;o z!7ZGh$Mp5N%(RUT{jgGxu3k+_Y(-=191TNOT18sFWej%WINcEW2H&@My8cz01;UFX z45%J7M@tX;cSY%n4{`L(C!QLL8G-DpB-1KH50S0>^L2sD1CaR>(*K7e_ggq!7mR7g zgic?;c8Jgv5by|0wIVJcW#D&Z6Z15UF)+Q@Y=qGN;Fiw!Nt=*%U$1v?Ee3A+rsyK zZm0jRq-eKR*RNl{R;`wF9d37VAO+9iPg}1RBvn#b`NxAhi;$UusIp*U+=*bV8oh)8 zrZr-)D661wQ%EQYG1f&zkyuz*Xr(5?5D$vcf5a#7!)y;06Trdk=_w4xJYqOrKnx8y zCn%;aBRnpo>kP6sBzUkr=?*JvFaivrv8{`Q8~+7pbn z=wWCL)nr`sbAh1SvY%fr3C5Pxzj9BsV^}>w`9xzS4J^34dU6jnA2zSsNk(pDqerpy zg&*GgxgPYqgnRZUjnvl@R7!r_{WLv&a8BHFQG>d}&Q0Jm>pu(2E7|H?h+$)CY~|D% z3Ql<-8<)+gM2LPH4OrZ9i`P|`h#HqK&q^W06%krKx)Y*SaqcOpx>)#NP%=(WQGIk> zp~sG|%ZVc+yCLv>;8mMcC-;?}B1yyhR&uh5SWVu9r^AJs|JNb%1Z@Zj|3qNh2-6;< zL*F3)6xLVA%HBQr{38Qg1PzVcE(&UvS&^y=SUO-!MUW?+SINnbc~rdLb1l07B;J_y zw&=)FElH;PT92;vIo12{>jK@g+}qX_yIbI0oJT^T{QNEnQt8#w`cyIKSX#$D|NH-Q zg3EO0&Pve^Jn>CX#VKiOc0e{8k|@a!5aBYD`|&?lILJ9c6cxxz z3oXu$A3ua(X^lduKU!f;0|DJOJ4D2hDJ+>U2vJJ$(^i@no!#n(jU49@F|Y-dU zUtC39_B_u#RDDcB=63V?(GJb0C9CS!#k#Gb2b}+k24yxMr^`sl?cgQ2epp6}n$6Cv zE^g@G@fh#UN#?GhvBMOkBoX|iVh?s`B1>*NgXGbzz0~mw*MS}N^^4CaOJ~Q$kgSQ~ zQ52@Cb3^Wkv#aOx^T-22)IwN_R(Rx zN}!Rah+bj@oFiQ@Q}r0w^E&F%+lH)@65SnSCWmm*1B5HHvjY)%2$)GT3J!D?g|;x^ z@g&hm^r%DeutU-7RVy3xM1+`W;&h9UJM*y}v_m0MXojNkP<*8rS~8$gZGs+;zA3x|Ahit!Ny$*t zoQ|S(X<9oK}@JOW4Txnio?%h!-t=?Fh_j_cqEU`lUq?)1I_(gj}Sd8tPH#`8n^G& z*faz%M^ImBzvP(QILg8If^!u^GULLgNyk&4$K7&&_OjEu)oD^&1XeBUH+ zhtnaJiyQyyM*mO>2_H7D)4k$Te3aFFTVRto1pGgz^9d%<`>q4I99in5G$B8G( z;R?lTBsvFlhN=Gm{E*~fP&lM`9l!7bmW;Ej%~D)ph|AYb5JUu(scZRZ)=_>Ch8F0y zE-2Zrj+CO^8r`ZcH~6GDesG+6nM(*bzCGD5%;?>HcHNNHC!#Y|Z#*W;N_NspTtvF$ zv;^%23~;tPKir=1zBmhI5KTc)72r-;ZA$8tXfWs8eioi-AMX+AF z#sd(au(RjHcdj$`HQKk1N|>A0bO6{Y;&1|}DY7am{RXKa5gQZak0kFyYUWVB%Hogn z^p783|1sXdUjsf)XJ;qEfe2}sb$vq)jOigT7T7kS4K9kn7mq|&GH_}R;6mIvv! zG_-Ey?+T<$?#2_HJ?XD_cttFVw7V-j28ew%kx8qyfjdN-&fZ}4RX zQ(bkqa?QEc*a1377`++E@){ZbtbYsO(h1v{x2nr;^$#FpUk(QM$6-WsT^pJF$<3*+0pNm46 zJcDYyu-B=5R_yK+ZvBHVOxbBntapY~l^&t()!vy^94=W8HnF>FsXbic^oz{VdIVP= zL+v(`_~qn>QX3t+PTt;lRF|3GmtA=|)nIt@K;*!+dxEjUcwxfcAL9+{c~ZQiX)cKb z$${#doR{>TWP6|a%9LjAd>xdyqG1xQf2V~{h1M;sVQ?pYqWL5%grI>pz5j3Am^15z z#u?%Bvo%%rRVPM)u<(P*2EwM1AH^RXRq}3M9iVt>e8<8LJ%)pc%;J&C@NtE^pruoK zI*D2E_2!9fnM|zl1`WfKU$>}jXkT7;K6SyiwQ-Bib=Q-B!-(z!KTGi;{x8vwqV=Jkj7UbUQV{5@OZ7Z*N^FSOhzl37}b;bjYA2K80Ua^%W$?Ai;WPDF3nb z`BxYlhIUa8=eWEfdVHA?`J-3l>yR%e(Pi2l$yj#XuVe-0*uBM9R#kmD*vPG-VqPRC z-xVEENM}noi@Q$zGiaT}3O{~ff_y=$HRx|F$McVk?)dbol6^NK0t9IpTc!1(djef` zjF$-R4jQjfA3n4}YpUPoF8f=e$7OQj9rRIOnA2E|4`?nmE%(h#zsu;8D7RSmUsleS zZ+f+CgxVaelt)(+6Uvw76nOfk5C^5Qdd@s2>#ie{#}(syj4m><&v;aR=SahsYtcSRyk_GR|3CD-u2fyTs2O=`q6MiZ_9bqF*V9;; zmF2}dQeFmJClJHO%+4=J%gH0E>>^%&8J_L1LEx6xz~G}-Qpi#-yRnJI{D$u~g7cM2 z!=&if2&Z_&tSlrZ3p_?CNEOCjnhM`55{d zuewNzP&XapF`H(EL%ujv{A@J%XZaz2l;syyT)X-;nVZN;RR5MX!}`-!;!k`PD5A*m z8j2qAlj0{&O0^Reob)-~y55nJ>cDXZy(Nv;>E(^!;lGA@Vt5t5_GQw)^xaT0lW8aY z@RpaILiUxqVZS>OakNjbRkJzwoRgs4=!)H#rQN8-%TbHX5z8$B%PUn@X}uqNX?m&I zG)V6S%68lkxj`!4zwKd}Ri9Gh+Q>pBIPNe><+e9b!AJJ^vYiG1ub~AGtuyCR zzhN<_@%ML}k~iNFrQe=f6Gc6xeh^AKGhCu~B^&J?)4j(XkM0h>n;CewIiT#NLW>H{ zu#Qq6D?yLxdclGth~kot58KxrKhWY;v-y*ITA1ym9!($F?U}J|$^H4`n!Y7TQQnp2 zHyM@MTGV9O98t{1tA(F<1U$JLH;&w=Cb!um3f!)u^3zS$U)YP? zr2-ERIhW>B9RHyoXsg+yue&ywlo_OB<6_kJH|VAl&##<~J}rLzcAVl~{l%_Y+l~Ko zMOUy~(O}ABdgb4wAXQ;|#rf7Or^OvvX%$(t@2mYa`^4#}Mz9Tn>J=(k@aOfV?k-D=P(vc{l!ih1hvm#@DeBF;!NQ3^+{zKDf@Ip@Ho2A>}z zqvO@Hc7e4$tFvKoyj|;z1SvN4pOUtm^exMQiJE=*a1^3NCYAbCGD@#{&HMv)t=qY^VSdBdaYQx*Hcw$#H^0R$Z zpBE)tr4iieEe?yGI2StYVb+XtG20Prjh~GZHsT1s6h1eBQ1 zs;^wW`Siv6As(ixymk|-?2#t#%F|fO6P=Lfxwd7ZGY6%X{j99K94t?hBfjZ|%pRm$ zIADe<=?6>DLC1H2iNI;@5SZfRA&94qRzjnxw zUrlaF2@~ySxb-YbI>It>A1B@OFzWcxq#@os%~!hMku39J(^FfWR{iqJg*hhjv&M!J z&*jxN3@GKvmvg$lu#HLUb|_5D3o7O8aE;;y+EGN#at2%`44L^f-yq1C1f%fX&o$Pz~!Qfw9#$4OUs)?*vzgo|3&%j7QPF^BL^i z_xt5UR#ZmZ%uHXO^|_o8?PTsn2#$v1{M%3HsxoZ1<(XT|d9=Qnh1u>OR+vAcOpNo_ zQ~h-t4Z3VvI!e`@s^Xb<;@F1oejX>5cu@G+1$*>iHE&S1-~J08EgQ<07!UBOK6V(D zGWiu(-bA}2z@w4R+N;+$%dhW^u9kWzlAnOBZ@B*Cym}$^>S)NJ`H7^?)Xpo^>K;$t z#SC%HLZhsD&R;h?`!Q8gvN6o%-5|c7Uk)#~oFiju1rG!&6v$d%-ny1S+fpEMGO zeQRa@L=^oF9k~5}TzH6@=JsY@jcrxYQp%CD4M~N%VMxqKaro8h5;$3DN$*vp_O9zn z+nia6^tH`V$$*qGHhCcjUn9BHjogJ5JCs}9qsdf;$dz-&X z_5Hf}{&&*wyb!$iEMt_O13Slc^cI~VTP`};uTdxoSqhuwV_I?S>vTqadFGOpTW%2ojY?#n?nzRWHYAhD+(N7RbaF$E zE$9Z?$d{GJm2a-rd2zUYa7E!sTX?RF_+zrv4u`j_G^LBySQKFQOJb2$|CmZpYsWm% zCgNodEcee~)iC*@Kp`tj%}YPx`&4z1{A{9k3IF{aE~qf%mr}@C^w;u6uRL^n;ugYi z2c<49f^z&eU?fuU5nU~)9y7M*t+biI0zb)pcNCFd*zs5nISXUC33`mQnc;#@yimzD z@pGLErsx_4!{KFyz>{TD31Yd+4%reFi6_59zccDfqw)z(MXoyE)pEXz<$NP@{oX7( zV3S&Ms*14oecd^#yx&sKq}7$X4a#NmMhb}CW0%D_|L#!6MWsPf5~$F@$e537YH6Ii zk$U;2q;RbyV5`1@D*&YIS8itN_=b^uRBMTD@-%44Apx4Q5VoiQvcR9Oz?r3 z?Y~07{G&pok0WS!?!yEaaj^U_wXbR+rpp`Y^Sdg^zgMf~$E@!tb6m2AsvdFD*`7LFT(3?wy+Og1AL+nNwK@DsfZ?}-pw=&8t@#mOvm(CQhDz|XrNtTj(lqLoY&8rGY^NoQ;JNwwd)%80 zo2+qVh16(x=Xur>#6%uU6dVl9?eZs{UCwTPAY2|y9+v(ntJmNcb z;9%^w5rpn|@+w0cvohZwr(-}l zptb*c)sSw^Ql43Br?%RxUP>YFNqke1O9?)s81qjISd{HZs75dfglEumd?v#da~OSP zteN)wjVEHRqALO4<31OQF==#^>|-sb(#Bd<)y!@c$@q-WSCagh;mV!K^B)U6a|kb8 z5?A__)|`Fcuve3FIYA?N5eF?&{-8?KlWPZqkDZAvcA7M{+W97 zmW0Sw#O#%e4Ya2|sm^LL=rR9YRm+}cNi|Umxo~>-9 z&+z%!-B;qG3&;E?_4|$or3tMo&`> z48k?aD&N148PG7-qmRJ$YyM@PIK4sG@cUJ$?cd5>zFz*i^Wzl*&EdJNO^~P~-hBQt z`HbF|NZb-Aka%2wz+u&DT{$^qKK|wkDa7X(xciTpM&)0h? zdv1#1DBbWjOe&OAwVy00<_@d^_MBfjh&i8HMznsx)ZTJ)Aa>a! z#>9)v_Lm9_7K=^_AEFMKHoW;%J)q}Pd!c&K(JCy|B2ee;45++KHVhGbuVcbi@NMOQ zo61iTTUF`gP8YLkt~tSXuKqPa$4DP_+z-7tUV{;Od!#D!k7!;JrD4(N3+g{lC1*`P z=t+EBoan&VfOLZ2_(vg}fYGzuEbw)X)Ck z&(PeGsh_1jMqNgUsQNM7_2S07diTjK%&Yh!4u?8gry_UJe2t!o`ziL4{`$LRxqF!L zBU=CiEevfi-$ySbhbzruFOA1XEh3#K&3rHW%GNE3`_%QsVOXK6!MP*NzmaUljViRm@ zTN@WouZV1_M$YtNGYE#r-stRI6*b7Y-ei3_oTpYbeN8^%zBztX#?Mqt1J4d z1V~%9X5Tj$pyqlZPw9viszo|>$cLxI)%*ve&^Pm2n40RZV^kqw+waHPT6k@i($4ue z#-A$i5^df-Orpk-{=`?p;U!CwmR|bdowc51RI%@XYUR#x_<;*g4YmCTzmJhr6Qa9b z%K5iLw@r37_Bcw|p8j+wj2TdBb~4xQ;*C=R|g-B_Otm=KkJcD1HTpNDa9rA=F7 zWR<`Fi9~ux1j}GTXLpYEdmBwzH|74pWNx)PHLd#h-os`vS(?@BReIeg>v_l}nyHd| zyV%dTcmFItpz$;0%}|_54V@XSr{N)bsI4IptaqbeBCMTQ=s8#XFNV$2PL-#q^Usa( zWPWI#T1Br^(;BWu$cHGB_8PMVKaUXc^cJ?THDJtf_MS~b-z||;nJf5cK3>?mD{6l+ zlFsx@v0t?Rmj#!xseeP6tI^g-nMNc3d zYdEkqmi$TJ*0%RmT~$1-pkS2J;l&H{ePQf9Rdv$r{LG1zK%SX2n>87sp|cAthc92u zLnTnB<>iODxrs^kik@gWU2jLN81LUB_12|3&&gRZl9G9BbmivlBWvDMGBWw_T8=p^ z8(nWvz1-Y*<6hz=8im*pdLy43Br=_RhrL5LnbX1oQP*Z(&fK|!Yl9uN*UM~%=M#$7 zY;9*}p5ZIcfT6&`BUq`TtL2klLgeg7d|pGsy{{a)j+4&)f!X3t5i5K8DKFceLfY0r zvgB)-u$bu|)J{*HJWY%Eq+|4LW$0<4N_PL@7nNj}!86tP)tlLsn2kNTZ0 zJ~hJ+AH;kXWs$(J!tKLy^U!`UJx(fDiIWuz@9(dSwloW_>@;;A^D-@THDL)oREFq7 zhid$24xf&VmcIvvTdrJ}>NHMmcBwhAO0kWa!iXOv2ymFT`H>f`pO~katM0}$o$na+ zmuw7Qp-%3^GGhOdaOTX1WfomI{%V}F#3Q6a40K<<_5+~JxD`|{P)9}2=OmKG^SfVOeT_N3fSeakwRIo)Q`b>H zDDBDSl)N4;5me6dW&hRkjyIZg6HZ8Q`sD8PA>XZ{g5mtoRp(W8S!c}pW~qZ_qa_g+ zt12=6+jStaKxRG=AyTRI_!meEq#)M1uzsJK!TXd8F}6dx1QQ6}zo=w^Mf~(qa=}uT z6;R`mmgy;sk~G-J5jQzmP$;3-hNC>8-d12nBj83_S6X0N~9y=-sqH^_`d zNRNkk=RL%!`5|*A5R^%DXd!Mh@WbPRu|;_H>^WHTkit^4-i-$WyL23S#f45cTRu9y z0wbMVsz@?ulZufce#4<55&(#}`jA9FLGJvV;?V2no{Cu|S-x9$Dk*hS<7S!_`BZY3#$-beKJ_ z-JjXYJ(zs**olK_f>oTf+uBKYKI#5uiZeUCHraW}VvL zv*9Y+c>%luJN@N_G5XEI4r;4GoSgK{>41aAV)vK%2|T)FA`Kqiv%@qTC!BQ8h_WAP z_B;VXTs)-_UZlU2o8H;2v6|1N=DVJ5q$fjNhpM7zJP&_fQcoj~<>eoWB<|U6XK!CG zH`*EF+n6d0x?|%uRbpOsM96D3rH?bbS9tPw=!a;z!2KUpju#v6PNuedofZ3y>IFWy zdT)|^B-F>pq&!Q0eJCujs*yeWE9XYVix0Pa(tUqtU3RDqlUKyEO4bTd+-NU6lsaj9 za>{%6OkLL4gtW zFKidn=|hHq&#w%6^lO`aI45)5!@j`&X?LvK)2mw>`9dK_%EN>>%eil3T!R z(oL(Jcl$lL_4VU1_mSQoBY!)hrQQD+pq|C%cDT}bDU1r+cbpF2KdEH6iM6t1)Zw<( z_G?%W^vlZ*+Yz36g3s&NuST1UaF$GaT<7M!*q(lnm}Im(95Hb)jq%Wk!>Ffn>j|Hi zQM<305tqY?%y5qgu4nz?H<~RgTaTOc69=OQy?Vdf=RdBw+s22jR8A*^K7#nsh}3h6 zW39@v7&`HeCz~RIDPE1e8f{jehYKwq>rwQ?`<(?a5XRfLHbgLdTT^Ue_58ar0CcZt zF4V5h4sK^dYeor6$|tAakAGk?6iSI0weOs4xF1~HCA_hzDs(_Qh&yHTs+;EZ-bI#) zr2M9kYQr|GYGM756&~5c2{BM7?o4@e9T2KrE_A){ z>^$FcDcy0ZmGLu`Qs)l#&ruZ3+_kk&q)Xh|pa>M2!$U1MYChQ#KH%nOCx{baY_b=_ zn@D;8Bjnr8?V75k>EEa?z?b5p(8KicoR`_3+V%b!F5hra*eV~7?qh$36`ZAT$(Q3A z!zo43!qCO_izvH4>Z_lY7c=oZckd_c9KFEV2^wEdj-mhTNS@mZyMb2=Lv_u{2DLOvTOcZ9qj70F~yW^Dh7hDE2s@ivQn z?BGNa_DN^5`E__qA7&Ph~P zsY8|Io5in@8ez$$nk}PaJZV%oQUU1y>m&q0C*e|B|56o*D5~Lc`_7#?h|!pZ-s3zX zjsqRW#6Kod1KauL`KD>)PFbptOK=8H995qkxnm zAxL*BNQiVJ3J8)4h=7D_RJv0d=>|yw2~oPcIb*&5|9;;&7w2N%7_iq`bIm!%GoHv2 z@d+{-8Yk%zyA|?d2Y=;aC2+Tp4hDu~^s}vz7e8fXg+TUO2xtXffx_1j6b4&hZG{AO zBEf+`RYTQ-cG#`W8~izN$yj)Spaq0fIbB_9$ZDMiKY=IU(1EH3g4l%XxE&IItOTKi z5Y`3J3chUyC=TsB3!ttdwpX=2$7Z}#5Gj`iXGAqb1EmgI!(;;vj!=lES_$6w00I$$ zL_h-F2P8doYs(Rl!N6xuekdFaL>#~tgsd_J{(JMx^9|7A0<|gsG9%-|M~_Gmz-_$D zZWhpvYk-7hU(VkBtgIzg-7>TBOQ}<>LeSVoO4jQv0u0Vjp^XRf8;2SF zXCYd1iWwoBeG_%0v8)f~Nwb0(dOwjb)dH#hAX8hD}eZX-D<^e%1W` z=^^awK!N65bsgt=^Y>PpxB5oCqkimW9!C?MQ!QGKnzo#AUE|g`d@3K1GC*`|Z{WU7 z#+Cy5=fe+;VYxq^W)9%AdODxA>?{9zadt(+vBoIM03$5x!B^u3^S-t5d$Yal6RP_D z^7E}3S+YL~Gd!IJ%wK9hU@yRVwfiKilPhL1jfmhS7GtxnzBZ}hx@=m;AVmUO|2^SK z$t8@G^_;v0^@YY%wM&E4mlkf&tlGQhVBmNe#M!Z{guk}P$N6w~!0HsM?p|G}Krz#= z2Vwoa7FD6R6gR}e*FL@2ysV0qqq4JYD@}khPjv00m9oEEoG*vY%5uLWbekqnnZ(mK z{lfZc&ylx0RYQg#dSpRVXXDsp$}X_+Y(B?=0?YtGLoFdSl>Hobw(Attx5&zP-4L}ODbl%+9bmEv)(<6le%ZL;7}{}S;j z%aBe^khjnCF77&f7n>|OAa?_5`6>xBx?J6H8s_wja%9E zUVr1P5WwRm6d^1P_g!OXGgZAguzD_REqt^g7%g5sfZlL^g;#+ge9n&@JR!XJu+UfN z%g}S{fp25g83^bQtOU_b0Ii-6Sf+UR___rq7%vVQ z8G+|Im(RX@)5XOFaZ&;?9t0AlWDBn(29c>~bcZ?dyr2P-S^ zRm!Vc6PxR?J9==8HQ(9W%L-xJ#xG9aL-Jr?3*vbN;zMN1#MppQ2fxdb2H0LnFAE{j zjaH?4Mz=p%H-YR?1bUpp@zppb76?+N0$dEqak1)xOl%~RP^Ze33+p1$1rykfcNY5n zLCfj{5=%@~U0nr8pacifd9X*c*%EPBNjPG#>6`5J7o;Ja@;&BqIA+(UYtKwi?tsKC zh;mo_*gU=IUZBHS4Ur?jSraYsSsKg)`RxX%%NZS&fWL;!Vc-CpQx-Ry1CiSI`LwogPTox~J5ZrSP#IM_(#i@>G5Ah4IroAFXQK`Jt-TqJK?J zqv~Vc&JPMWC)HlxL<7*;OUT&LI29ozn>Mnv={Yf|_1-j}yU|ELqACy5-Ul1Qi#e+p zFE^W}rV1ymoFcR?HdyLTzx5r@FNd=E5x+GEN6GP3nqR5YzC=cvq4nvJ1Z9Q-@~Lsx z`{U64y6Ap=b6y=ZpInP+cvv$HeNeltT)))@w)bd_>(ZUw(P|;vWD~*M*ZDHXw}qB! zb{nz`j$1Aap4wLnGqnr$J#}6X5Gx6x$dwOOc{*nkPLYeY6PWxYXwpa3XR}Ks&~Sm) zf7s6`jd)euef;GyO~fth@VMP41T-=?Ma8D~XI({~15|40dRql-XXsNpBSz>?R`$iz zei30ZT+C{Hx#WU&r@tvd8PfY^cwKtdEtSx{4|`$(^VtrDu;)=Um$DPp}69Y9o`VqVs+OtOv_LobQOyqJ&&XiOC{&xGL&l?@@V0xCdZ#}( zg!x(uz@ByH)$n4GeyWQ6d~4s!D`%(W7W)!k znzwT}joNqYzedw0b+SfFKHa=cDAY@@z+=o{BY&s!E$&E(RRrZoOj`%d;edI=pQSNf{WlSk zdmRUoz-kMYGkvD?<;vkxbA>Sv52 z`&G4ad~~+Qm5-f|7rZgEzT3~&HD;Ib9F|?xY3JtP4{iU&a*H1*aQ&jPG<(L=RH|68 zma+_oV#GVy++x({Zl+EAJaCFnTgl+D?Y~L$TX~a7k5r+E>7A_tOFvz;&-A^RYfHhD zITucRvpVoI*~bEFZZo<)#uy||EvHP|tPgG@pd{tfUH2+I{;BaUtQcbjCBu-?!Q9Lkj zThcw_VzU3!!QH={xV)QegLimseuiCGZOo_c;m(r{vHdA6tWQ>BPxR|APO@a#8Ev`- zv6{5oto{#sESO9#9XJzOS}h=|Z3pAQ9>@|#JQcz8RtSc%mrh?wAj$!twL-F9` zfXVocKLor7BEA4XYc?04@mS6+ulOCp(Pt$9`Op!ty>0i&98d9XAD@D3l8)#ih2ktz zKDZBpz-9C%t~Km|7cenEG5!jD^9nh6V3u9!V9C>g14KOm8lo;xG$28@FjF`riOxq2 z=jyk@_6NV^l&e`ollk(c0yrT&_lauR#GMyX?R%&RaBv7l&#PE@c!-l!T7yZB$yUL7 zW$|Y*D>!g;Gq6TTLS;X1l}{p?u;kR*VZ!^ogDt(lqCH9#Q|szw6Yx=;@ZRoLWvf3vt+4UJz;X(`le z;xk;N$)|5#mRfd0?~3*xCoN#9lw?Kvp_%<~T&65jhJzp4H0PI-j_$wY!wlym4QInk zVy5vIq%fBim}}GFeCME(X2wUW92ZHqrq=(|S(Y~KjZiXOFNvTY7mS31H1xEvFeaX{ zK1;`n?5thCp~I|T$(uSr+eh2IK=_0}o=iR(J6bDr@zQo#tWjFJjgod{i}T+f3?E=b zrej>2{5Y^vN2?;NI_tLU;F`(3)w5Vv8o5SlYD-?PHrvW3=hUz30zx(JxIWc&{pVH7 zH&4!<$!9e1bNSymDxTP+4Fzn8>w387!#jF%iX(A(cCL(%avGN0nD^%Ns~Ez?m=mmq zB5KOM?M2>8pP;@i(Ldq+IN6-!Z$4%{>4&l3qD5&%7^CVVN-6zmCLx`utKZf8(X&|A zer8^LQfYWPty#9~u0^Pi)-3F0kLN4&m4s1vOZd+Z4dR?z&yt=z=nA|Y>_}OD^Y!cX z%)EZP{Th?=Enn2IY^3GFhLgvGJ3+wu>>aR4e)8~?A^C8ZI{8p=)TsEHho)Tfqz1a% zRCehGY#)J9*)%?J{wcHFn+pPV+dqorvzf0khX%xOPVWfC7vBMXN)8Q&R?Yh+nFQMM zFyZND$_>-u(johkw1Pi(M>jC6O5To=;TYc-%Kx`SBNvmy)RLFS0jJ)-V2NxwR`QgI zh2bb@8El1sAFV@$CZlg4nIgv1PK^;Tye1X!Fv{*0Dt6_XX@o3YZc_ooMeS>1SruJ&+uwbl$&6-E{tXf?q-^4;JBb4G%d?D#(x0{y?z7<& zj-6aVE1ex3c)y;p$9LLFR1Qbjxg;*oxvq}6bhTPoSd@6sA@vFpkGjy8O28XT?e@8lcu{%LkQAq$Dr?3phFtv+7ar4Ue6nKYP^jJ*Mn(3xb~VU&75a^tRtvw$jR_UE>#vXj>5Zqz#OPq(mSb z@ayx%=l03lx0PQ^l5c(c=Nf?m!*?#3XQ|(H8|JdQHAFb1$?cAqcWh!lQ%1jib+{*& zD3ay(Dcv&x7hNN|9HV-f55?D3JJ?6`7Xv&m5FJwJC z#FW^w*~VBP9T0jiR-UilA~nM9o%K3q3LBFDt`L6MuTI3TG^nSns+|t1ku0e7zN4AP zej9^0*@x>9ZCuIM(>I!POr)H+slDy7f2JjzeyeF8klWqM?-w4IFZvahLU!^Wx-tta z%VB^Ir~vpdZH1;`6Yv8URataed=ZY!%yQF^9TCtLQ4s!Nk<~z1aqB2q#Qt*<0UlS) zeaDl?u~kWgB@%bi%fKp!yYbQC@+nR-1#|}NA!s^Eds3*T5ilIFv;{4&3aC!0`I+LT z#UP9r&JOAFXTKt>^T1>K7U=0#T)l3-d|h< zPtZDZyet7qzkix0P_=*t z&ud|_MjRCBpN;E$ySe%^n=JRH({pI=TFU<1Pvz57SQ3rOVer5IbmrrfbnvXqE76w& zKO#>ihOCNsz4tKpfHSg{WTUWpCyFHg*K>DzSju>Ift-^yRDNrGzs3bxURyt4-Xq1d zMuq<SwY5jd#Vp6bBUi73nVdz_tr?GY|ZdlSo-a`)t%3=>DM(y9bKH@ncRiDs6I z^TBCEk>i04?zWT|0vdG>%9zTt_@jz%$GtVQQF^*b7lQ6%ttIZn`%qZuXdX&h5LM)f zx*X^~wuFZ^kCd3n8`TP9od#?m>WQ6)U;&n<&p9T_CauT9s=TF_kJA(X!(K%UP{r~5 ze%YiC8-}*7-&MN;BW78u>olcSK;r!$08n;(=?bn6;`xsF#elg&c-hF%5Fhvl)q<7( z#swBJCC5mT4Kj=3y=2iMg{HJr0pScbr9pj5IPEuZp^+J%?}~4PKahep2~l5WaLqt*)H3nS>0{!2 z?eUs9^is&!DCWb5TVN3Y)2Rg2sJ7Gnsa|Cme86T0;pU%fYm=eCfxpj@0YCZ&-))7q zhqR5s_Tgo_#dR^UgO*=FBM1%&F$3cxL|Jst$9Nr*iRB~c+95T#3o$p-%S9Y4z_@F3 zrMQ=2z+)NK2x7{I*dM_j%f!zgRkdFG5t>u53jS`MpctIyu-z>zJnmSK$^QI`Yoqu+Zg1=%#K z4V-F?Z&`W<9vwDe*sKSu?{h;~2VeF5IJ%INP=tB?B{0S;IP@Ot?P`&BzkxFOr+RtN z*_+cykBGPfi`!Wg{=d_+O8jDS%)RLF?E+DsF*6o`CoI(NwByS>O6Mp%N!Wa#7C`)hz?cMa7B#P*9(w&8%<(jx%*l&1OWf4W|p_TzjWAeMKgPFc?G<&Iiiv zjS+JQsIQ0rc#9=PAQ7l=G`<5Fr@VqPP5A4l17BzMkH77W*+d@I5>fH`!PAd_Vl?}zJ%{^eoq3)w0oR%ZHlv_VmU8n-DcUvQU8OMQf! zoR&~@r`6kA20Ldbc$isbad{u}Q;P+?>7SY1@OAw9mX6qSLxW6wqfu4uqV2anRm-m1 z^$&?Rf|_4U574IwjZr?R53&8I)$S2$)QYZXAF=57IuNzvPyhD>xHhJx!(ozZT*rXY z)I{tVn3ekHWCtqPn1R+r2r96I2S80T^KuBy z6357xGl_~G*8G*F(?R!GYP{sCv)08F%Hic%xbcyr3^|;-?Qj}%C8ue9kjl!Zv-~@0 zE+M3W(K%L$r$f>+Ey~wao+s!agE`zYmLyUgK~c(?FPtuOs&$*ZipH)tyKA;GKfiIU z6sw@*IUDfHo>5)SQ5kyc_ntcbXF}Cw(!y0T)B{JJ>-Y4q@c(yqayjXd4p{-v8w1cc zZ-#uYaF`|fX)p8RX9>P9{c9tm8LKBvOOm7WWq**)HSw3ty=*JKMJ44mV$J%Z zl3L8zav^s<^gy2wu8veTX#w3=*@C|_nG!p%FoH%JPL#KyFL!zxsklfsmEM2$ddcD` z30Jo3*wr3wJSmF@BU;_jRtik*QL?~@Q-1%EDuI6|Zhk}7Li)~4!77DclF@L|F z^FawBVM0M7{0V}pU`{iVXP6oZ%V}w8sRFRkMr!neRAty*RMVg>p8Zu!l)j;0{MqzS z_M(q`peRj0>6dp6l#Q!ZTCYW;$c$&)@-a6)J{EcNRCI<=K3K>VEUg@SMCYFmC<{Bl z?jt-V45CL6%_f{20I`(eYjE=$vz|mzZ#WGr4Dx^p0krW;z`}m-WMq2wZTs8fHm=no z`3JHES@s}E*?HFxqWQ#LIr>;r^KW1&5AV@xf0&OOr}661(px^26ta&aI3>#1oTUh%y~k=oZ?L#y<-Dm-1y`qZP4BBWU*P!)`c)o)vUxU^kHWGPN3yuDh-9rY0aUgDzQe z+2ic?@7}~DA0Z6EdgzmI#>y~<_ZTPTvomZ5Tv)lvwX^5R{&VmjU$Vi@Sy`D5rFtoK zHPJL!<$7l8a~(q6$)tm724_zhU9`FtKbHph znjl$;@E{W8C-1mx$zxY?`Z9&V#H-ttvWK7 zChu2&-DR0p4R2~HKT8Z#qHPzhs+*ZdrySP3Ja_AA{Yd775$uY6{wtTqxR+J@m8K~p z!#3{+BCjG81`4GhdshPxThtTc`0n4oLJu9*BLQ~{AT1a}W5#;SkDxRxlt1sXJ^lAN z1X%HyD%Kyt4T=+Sxb9hV7QAYUNVQ#5HLfS}SMIf@(iGl&wpE_bn!aE7;WedQy6e4- zrM~Nm4)>dGqEF@)Iy|1o{i{ZLkyqGRtd1+7`gkztf{HO9vATsw!k$EBwNo!`D#v zEN!q-W)J27$tQmmP-nag#5p&O8hF0cZH(FHZ+>|90ymt)4TtP2+|rvNKYr`bP#HEH zmZ;@E6ymoI|0DaiAkFonepXq@O$lrS z9|lz1=EYR6KF+9?VE?!5aeiXzCF~252=ELDdM3Q@&@V?B$RXR`AfU%pMc6=D#$HyM zBT#K6KK8?8h{;m=9JX;i_Vo4p)mgFb)@;A3ZcNN17FhdwF#2)zr<)4sey0luA&!o- z7(FcXxhO^M8Hmg>gSrQhHzE5;y0t#|)y@SI3nt8HfRQ(`y}1%@@N>ugxe`d9GBRK_ z6*MmKxy4XMUKZ!paqpiN3}MWT<~*K_gZ)Um`}Ge>N@`E9`VGXs_?Z@qRB=L7a`zbNhniXaKBA1QrmX1?LR>i^k5q3_#PNbZr>E7F)L19S~ zKK!VEDq9O1$Lt>L`n{o0J`RSCH_YiHY`F=F|JzsuTwdj{#npK!1)k2I`&Q>9PJCZf zNMA8kr5w13GM*XRz`1@uhq$)zX^(Xs1u5Dmo|9x{_%BMeL@g_zq*U`|>I= zi;3>6{$$y@ln>bvWqZ3iU1zssW_?F?-GKV-I<#h{ zxJv;Wb}JJX+GW4dxRe(4;fr0*#g+V5rOxX=%q4~`${wk363NX3D)V4GZ}g*0P^za* z5~4{es{1J=GgLO5F||X8I_$skIji*F)3Cq2-FOYHuJ!{5{d8hAFFl!cN{6*HX~t^HY`Nt2uIB)OZkfh* z`|FTZ{M%a?evEr(mubeKCZg#-!c+E5iPR~j@LOmaF3qyx<#o7`ef?S7v~_GCx!APMS3bwlPRTVCnBoN*l`N>D6YbDPe}d)OUC zv93FTUV8ez@`}-$H|Q~KMOgkLJKw&xI{+I^MPbtTOV-SkjSbWLQ)1MY@d~Zp|H?J@ zhS*385U&K_YASLZ{ z5xW0bcT@r;*KD6+Qb^U1;`*gMdl6cbzg36%>Wvsn5?hInP6zMRxKBe@W2`Lfd@!|? zALEKKOG#-4D_DJu_44_B{Apw%(^0d~&6t0nFgQ4@A(aN>z;5J0?dUG{<(wnuf?NDO zs8_hwg!9bZW0f76T9%-}msZK16YVP)G;N|X&v4W%%^;k4W`nt%hDIF>^hwf}Mt4?q9@Y^7~f(J1~m(fq_9qBNQPdIH?zMD&epdEoqRY zaWiB_o%yBMZ~5Cz(y$u|QpE^d@}n;m&v3cOp-Da-`f`|+24gUm5>quz7A;Jre}~cU zuFWTVZvYsUewgP6cgMj$+z?e2^Y3gB9o=Q9>HFChC7#KJ9W{nyqfY zGbd5_mYXmyafli zzn)uJXtUi;{hIQBx3+Y+b1>^6rKk64+snv+aW;E`h;(Ac4$cj)9Z^)wGeeR|6BRQ! zElQazy_bzRugrY-WpmR-r{Lx@SG$m#)qG?zldmJ)wCGUK|ie^t#*Zi+hFwR zJXtusyYKe)w%V0I#1YTEwk&SeT^)?CfE3hLvp?AhGo(h~vNA$j21SEeh0H%U)J_ef z^9z3M*`GpeV|zWr%7h2n%utEQe~GXb5bC)?X?0#*A%Uy?!?r^QuJJ zF^N3m$4)OJqWY*`iqdvWkuCe!Q^k7v5$G%fbsGsY+CLKu2FbMNbmvsZk*eZtv0Ez! zL{hpdpR~IFYZ?&I5ASTH%W{jhv5yM`vI2n3ZK$W6r%(4H3+;(D{j*94Hohj(rB_3( zVY)If8MERF*Xra}-+1u1qnfdiuKUdw@4sH~#)j3CI#`hwUT*aVda&wsMK7j(gg6iv z7bo;_-8~j8;~=jVEKJ0+Hj&^-IOuZ|X5B~XUc3O;%5R%3v}~N57Qp2?0eD|SLt_Ir z%Ruql(C3-nMMjf-?ki1J|NCuPLIVJ7+=^G7{_-fN?FCwRx)DF3d< z40lOLh~f}g%HWnq!jD^dtm#ZCuO9Ahey^mASc(Is8S&Z9Rg}8TGPQ|#WvFcHld!)N z6HfYcHvXd>f+(vZ`7%%Le;ZQi5=p}fEL6p6*?0xe+1Pk^EGH^V*w&F)OrTG10D=-E zEYiRE=%Vxxt4_AiYw@V)s7})x19ca#++XG5*-E-Z$0l>_1^H{~Our$mK`Fm5bUwzV zoioF@G!pdRN00Q3zol|P{1pL?Ohuzr)X1`2zT{5#sQH&6Yki;EakGfocEIYIz!=^4 z2U8;S^&&+p8MY|v2|)n9f^X4#{f?TV!tz_n0o7g+h|Q+^_WTKtSa&RE_5z{E=-o?L zmEvu0%PKFMW}v&GXjniR-5Jxj^o>XW&KIclVM%*vdhEPecT#E<=fthH3`R{SNQ}_A zuE4;ry6UeXN=c7Q_nj^mK1~Mqn7kNLH!2S7jf72#{n5%h+@hg)X50o%^8(3u+RwsT zzsM@z>QF~ZQR=T6XFBSBJkv1vQysfj<_~ArAJ1}s%tb7ssXf*Iy!c5nFywUs=i_bU zc0v(?WRxPGe=OPoM0^>4>m#=lw~9fbq5qeyTZZGRSTA|+Ic@!{dCCm?KDioGx*~QZ z*AA!IPM1fcFN+QCV2X1Cu_Y)YoBBt#HKW)QXssa1jSskZL>%VVp%`QCU z?PN9el55M+$)B7V5U?=xO(cW`X#y5@Js&)vDS!HHcUT``P@1lKd&}w;=opBf?qmLNz?%~eRUH5I zSMSryH0+-C(_yG{qG+@QIYP8mXY;Nh`{uY?0md6F)TmD3J3GN~)B?>wshkbtcOx9X zsl-vC?N#$W8med#@4UUgc|4Ja2YO#}gL zq>sJipED`5nMq@onO5@L5>E5Q!4(6-dL#8nqHkI1C3W0btK-^8u<` zp!8@fCSvBVv>Oi$CL4jALixv!nSr8fXr-^INp9@3OAdbBrof0Y@LDZJjKP7TwFzF% z{PvU8s+fHZE3V?edAKSh6bnYto4_S5bl?0fkE?}b&b~OAWkeP#OgOPpyti8(G=nJHL+DGX#a#h-cAf#uo*;bNv!)uBXX@v|xkS&U%-g{Bf@znUfq@e2 z>WBnV`WRUOh<|5(-B|}5kzRkuEZfK+e6Z>F@j7%cKpAdrSo9GN|;myUT3B4q6iL(^wx05xx=gM4$hIoR<&9t&j>JqipnYJtM+fS>_R0A?#-m$ zXL)WT8$)@gs~24ozJ@lrg)Y9pp`qo6n#J%G=ihFgkGF07r$P4vc?}wgX@65^LKgRcYSqo~O zh@YL$gi z44V}Y1HbQ1Ma7PDOkAVif3$})PVDKWgy+PB=HeXF=y)j3 zPCX=;Tzp(|`q7xs%-lR4uoJ}80J3&b2se+3iRn4AGb3;x>;kudIEborUi?0FwkM1j z-NRa_m6_8Ab|r*H1AdK_EjWrf4|X<>A-V%`3}s?vy#=9dV21As2E+7X&qfQrW{Wei z;BfFXwYCadI|+mG9*HSOtl3aVVxR#xCBm37UC(bYxhf_`Bd3;N`%xIl2LnU>z7cF} z?4Ts#X=o>&bi}YBtqIC`eKHA|T_8^UaCBfqw>vk9%11JE!x)!PDw5%j4y4&Vyt8}7 zGR4Q$stYk=hb2gPbcC$X74u?vTL4Pvf+2>op56vwV;w{?0N1_nrwC#xf=)|AEajxR zh`e@2jephK3eCD!5sy1=fF&a9ty|IXLn-9c7KXAZ<>cg$wGE2=i`})t%Qys7myd)8 zYrNc&!9E?~<19$H$wMbO<5qV}4=<(Z_FVVQ@<`;#iMNL4W0>FmPa71s^KhY8`_Q;B zwfZrxj+hNEhT`V%#%i)XhKTU|#9XV5Go0IvfE*QkwIxLPlU*#gTJ?|rMcyEY9;3xs7W zTtFL{^`&*Rk@Zt>kA45wM^9=C6AsTiE$3*nbxSf!3`ZbB0gusp1LIjatsk&QLpky) zFvH~=k!=I|Gf2O@IXPj_4X74rE5c43 zzB*pMz1`c8!U#`l7V%Lod8SA}@3~^nf*9?4Y|jab-9z^0f2dq}X$j_FwIAf2^x=cs z=xD^w=%2rT-^IsMKd7~~PV&z+tcv9`ZwZLX*SpTc6N!w;Za%OY2b*1p0sw`daEV>L zA4YhDqO$UroSdBIW!D%<@X$rJLo+bv1Qr3v^02_T3nA$uPQBmhlL2JpeQJeUQEPT5 zD~n-!^L5*Fv+u{<(m}6f1%6gOro)XF=gG+qo(p9PHeyQ_UvIqG(8Qh(vpbIUlFxnT z?qyG3NBw1ieS6n)hn7_D9#klcP%lhIB9ZNl2svve3@fp3ZCk z`}U8Vr!k@(?!K$r6U8eGh%p_MrOuJ7J+x#~)79Mbff1R)*eUZK?AzmlWjIeGrm?fs z49DiC68^XIZ|V6K#|Mu>Ab-XxM{3ICs+A%aBkoJj?WVyDh&?SY*?T6 zIJ(}`B6IQPRmZn~#|iP6_UWkCp3BnmJ5v*Wv5z+3QV7r0+!+wJ!1~xNLv{HB75pW~ zX-OJsE_zy9vn1quuQ-e>nHoID$O?x6M z2QP9DDS;$YbfY-F+J@K@+ty`BR<^lJ(feZPZVXtX#f-1nz(BP#ozkbnQe1L&{&z~| zbFH_w3UfPM1Jo&k3^iXjw^<)r;Eehu+*xJNf4pe)KgN5z@Bi;JOAb60j^M)Fp^Oxr z4Z9^hj-1|IPj11s{*B2bDF9tX5Xg0$e?UfW{&3Q|lEc?J_^M#G7tomOZdz`L9N;=) zdS$?H%iB>Nh9}RMDZH`#vX8NW1XdELW;p9%cbKP2I^4#+xmuarZh=H!%z^c|8TdTz zto*z+_`nXK!oZ9ih&6dGicrZREKJv`J2AW^-iM9?G=xyAAmjuHYk^()dpw*SO@{^9-wAlg>px>G?Wm^FRi_33AKK%>C`R;8iZ`kGm%Gx&X$o zX%hF8pJx1VnI3_3Y>5@Vd!DwQ`)kT~?_$8@2Ex6BzV$S~QBZ$!xV`CFqpZ~+mf$o} z1XeqI+Z` zD;R9ECYoMv5w<4!Jq}m+td%xnsmQx%?O5J^?>0-z6=Vow3X>Ux=A|$i^t_5r)||K} zWl*B7+$qgTl;fC_V%4arZulhBvgOWz?fWe9W)64DPI1(U%b>AC?#D1Ahew)4RWhUn z-bTc4teJ0KPU+{%zeiPq!@cIqN9iUh(0*o;5XX5FC(Ul1q_u2#5=3jnSF8rw*FOCb z{%`+m1cl4ObCLTh5+!3mIf*K{dRyV~9)pUM=6!TXNYtz6K~6t1#%jS|!rbkOa{9sM z)v@~qkHo|UMNum-o^tmWjUZo}xG#K81f;Ju^B0WB`z})Tke|m`JmzVdll$RV>Z;yp zRs)!r9{`!b1N3ci{Er`49Rn!=ID5kG(=RWMRyf=M<}4xwIe~yDJ6DG2_NKv1^~2Tj zsRJlo5WU=pfs^ur#}LAfL85|zX4MFtlMdu$oI{dzLLv_v8*cH>ELEQE(vL!Q?mfuI1sQvwmkUE2_o4Vj%6&kZR~i|dKDW;06!)O- zMKT~6VlK8ac25_ZfEYSD1=(|F7rm_4;&t)3?3fa@=+oU ztqS}k()zTe;DnfD~wJw3duHKSy^G3FVx}mhVw!LGKFkMc@ZP~mPp24_}8>FNbQXHL?eC4 z(cWq&!svpBm5}%_eP9!mnH#W=Ma9Op08l|Smfmj_CuBzh6cn&?+RIp9Mzk{sBDDVE z+zaq?kCnpK1p4feWe+$ke?mMM7~W0;*oMT^g|`s=f2cZ&;!ANzC626<=>~u3ptvF7 zfe9{1s#3)w-*NzU^6L9T;K?62M^Yd)~8 zGC~b;mC*_lR^a+wJljWQD{2Xk8JqFUv@{Dpf^*Z-_Td_p=S7r|AupJ_51o;xptA7F zF;%k^q|=66+Y(x@vy^h6-kcS=8h2{cGN6pN>RpZhJ8!c~S1-AW1aGwi0}djAAPs#w z6n}X*x6y)s6W)d(Q85zk$HPVzLzKTqYj7$AU}Sma_tF-M*MbPx6llXZukfHBZf)eU0-p{WDrO& z<_t8y`_W_5y&&ly{+{*_{Dq$Q-ilWAH24lbp)k{t49tgt&>>&M9RDKxn3AFf8+T@iq@ z081>pe`{g%p6HEj0&vQ8E3fX%vA0C<=>iYC9jLob-fSy`kEU3y7q4U!=^Kx&ZDJg- z`{&;i$)%<*nk+1ml~q^1f+F`SFCP~pXU1kySCGmGqqx-iqHJAMLX@dzuB02@S~^U3BhuF4DtsDqbMpQqbP_QDSmx^thAqv)jAY zL!A}fBZ{XN#))^$HwF3^!3&&bXF3n$ifaq*AKc~ud>Is~+mVGR*$I+M;8w`?~~GU^mr;tCU1 zFJ?q!?hkHnMnqy%6y-6v8OnLRcGr37^G2CL{aEvn*jru8Ipf*0=H6z>?X%(ipSo4i zUBOB%mXY(XxG6uW5mn0H;>Ug*;eM) z;-AU%{+7LW#>OM~wV1tlrFm0UJVTkD(95^+?K#(Ts9Qzzn%2)SQC{T=P@@J%3~At3 z;pA6u;i;q-xBCELbM=baz-uD<4hS+K7XSKfI0)^e2U&a2ez-Fy1WPX`3{Ow82l zqXtu#Bb4ad+Xip25-*znK=D>}j*By)uG4#A@G|{zZS&+(vwwg+E@VJnHD*URpIi!& zy*udbuV{oh_|Kt=W&;*Y!flT&wQ%(-*mYA=wGF{4Y+@4e*O}i4l!m>kPI<$?r9ix@ zz-4q%%EzD%_#0#DzuD^i@9_K>D8u_O5YcW+=yty~@OzSn^S*s6u<$kk+r&IK5PUU1!pngw{(!l@6da{s+*X~cJ%U-+febcO`e;nE*1 zvqfA#yAd8_mQAT%OoB3O`2<9ZG0l;)bYO8&G398nE?gwsu+ozSpiLSo~=yW4bj5GYKEd3 zag6(GqSw3ngZDmL39N)L;`=R^_d=Dld6)3Q{T|}7?)UKEF7-Q98}T5J3gUPA^XJcM z0EH3M4Fqp|5R*&6W7Gwpt}%kVJ`VyO&~>HPUkSiM_aJoclX*JM@{hU z5D9!W$+pPl@W$17R|{7tD#V3cp@Aa>ilR9@xAv>y2>UOxoFk2(z=et?SHo<~%m%eDXq=*0{cvI^OcR^--o(PQwMxq^dF*bGuJCm`ym=s9>eGONs>d%*x~+ z1!4PTMeW&qyQr#u1+M?AvfYS_9)}pzDY$1pT;uDk=H&@Oh^wrxGpp;_{D(N(`Vlmc zyD;!UvX~G69Oj8uUUj~w?tkBFf2WGSRK7FWV67B?CQVniQO)bge{-sm)bCEqGpmv@ zaHJa3?|nCKs@~0{)*L$&+DNaGuKjJr1tlb#Je--|LLnVY)(!Bx90<^n6mWkWLTg7Q zB_)C?*VU!bdSokSKP5Z9RWs#`I;%X%505GU8Cu+7w-RVOKHvL%%WcO1RdP&P5H`6{ z-D6TdWTrNOYGQHe!P7wvCAg!OI>&`EIyEV(FBkU=dh}vTnaT6AvE$H|RhH!^YZW@t zqr7&1ZjAwL>3_Cs2RcMzVPCz8!&9?E3UiaYUiJ6{AV{~^ev;|!%&&OA9i6Bn5YmyX z%+W~SgR97;hc9KQlmaiVSU|fiGtVA))M(X`59^4Dmv`Rn-O5Mxr8p|XL{>UDx)b7d z!BZ2@jS7BS1XeLluNe?&K)dY5RTHYfsQkO5H}6k1aqo?M_DC>wI={W00-{3KDC5+ZY?N&OO#9gxAq#nUJ}#RWm;B z?fY<39%X&w%hCJ)T;6Tu@&W?`otIq~Lh)Zpq4Gy)UkA%tKC)QDkXr2-LN+6E!(v?6 zjHY4R6$?3x;lNnX{6+=l|8rJi`BSw%AE|61HF1hB8d$Q7C5aa>J3Q_~c_2DCPvsf2vz9=S6A1xRhWHB_+M0%ZfozMo+94MlTxo1 znn+E2dm_Q8n@s;n$}ExuXjsl~C)0Y;Z58MgGz#Z}h^hGRW{C?nZ`l+Ou0@2kGcAfW z=PO+s(|{>fVPS*t8RW_%h#dg>c4fcDH|HS4lojyNq0zau^TMuv3M6)y50o!N`iR4u zh#F|_*Qgzck%#UvM5&Wn=jVT%l` zCB-q9Br0v*hR&G5FUXaY-DhU~|r-Ey1Ogowrs>R&hk z;&lCYOT_5K)mfr6wkRr%jV~(Hi!}`kO7@Lc;Q}sx>`@L=?`vanVC_&LBNEU$+hD?5 z(r(b-pKHH3K;c9Osmhmtrak7|Q+7KY9*V3b<&#tsTzB>J9dqSH#hfo9{lAsjdBeqaVo)+s;ez*k?eSHAUhbVB%#$8tLF?d{% zQ>%c%5n2}NuA)djUS3U?_y)+uU@t)IfaJl56pNjPR~Y4J^@e=Fmz;i z1sYJl-gz6>9zt3nUKlI^Gzl@V6OdRwYFj36j)Vn4=MdU&#Uv>B9=d$dlJ$CufN$R# zVtM>863eSyL456ePd4xEc-~=V4$o#l&O;d0&wX->y6Ce6;zT-eyv)MrB(Ihh6J`*7~?WuoE?|H6n> z`7xUo^8p<3e}^_UP&|<=!hSs;HQ2m^ z3uDZ*FMs#UYIZeH4=B!Wb@e-QA9`d{8|>4g3TK}Y+VlPnaQON70}^%!C>Q0J7U-b> zZDC0P;juUOJrM(@Zw#3~%2vm?MDf+~2!$pKC8 z+*^l8$uki+YyZHe`WJvnyXaD=d4kCT!G0nALN>(1D2jXgelyz}1O8AV8tL zS3i8#GP&>S%Gaf9{=+zl3laGcGqk_A|to3EY#pz zbDxd9+>4y5L)>qAI6OwFBkrgwX>04pz|=Jc6AUOaDg3~4q`Y}^6vP(tt7x3-L1gu3x*;|&*`XYWU61whtdAoZbCO)g4K~hS0Za-SegfRbMxd55 zF<8O71J+ zdg!&GyLQ;AiYbzc2|d$$50&a5;XkY#LSO{;P2;aVI^*C;<2gG=SyH zmltR+dA4+%&Cf936KcSiF9>QO4-?!e{mUn+qoY&*l@@*{Bx;iDrgV*!vOORzB*#ejj@gqQ)f-yLW4FM~w1E zCCZ)nEG+58brNi-OYgZ_l+(-bBfj*F^k>a{GxCYlZ@ERuHrj~Sl>d*=@+YGP#$PWh z4sl;DO3GLM-rlxvoj}FE;RKLr;LB+TOa@_n=5rv-1q4R1a7JIL?G!H{;+xL>g_zj@ zWK%!wxdENhhlP&LPNN^quhQli{rWP*0r+MVIRAsw<&~8QB?m3?K)h-bq}3r(e9z*5 zuOGmS_|e-)Y?UHZHpePz2Us^OpuWJj&Q4q!eG@aYpxdcv-jbj$Q))rL+ocU$!yu~+ z^6A(Y*g%})LY9NMVnko@L8fug1j=^k5CG1w!G`S1*necYvWu?ZDyyrjn^A_XsxBjQ zvuXpdB2qIl7O1Rx@+Zr)-3KscGT=bwH(u*a6Vdtz%&qGVZ1(2q59HtGG@g#Ha<;A9 zp!Fs(;&TJ60*w3>ztW0}<8xyVsL34GK)xZQRHJ{wYke;~oS=~Qz7#pW786jvx#C8& z8#rH5!}25l)kN9~(1sEqmr~Nv>GIrYXaluIUjldZGJtIWOX6pKLGi;!k8)&2Jb|=C zdn5`}i+J-l(Uc9qSuLFK^+BkNb9F@NO*Zm`aa4Y1q{62v_Rrm@Et=74$lHWDF4c~kKBcz!5< z%?HuL0*ulxF6)`pku?6ig)a

    9GPy7@?K6f0@r& zV1R1V$;>Zb7ck=^VJCd}wf~>>HPYupo^FO`$(s5xu*qEG{m?_T8Ou?L;QJhCLm~yJ z!e0EEYo|C5=CW_S*!C6^{fUpK5pf4a3C51X#U* zbz)#|Bw>-P{Xrm3+H`>Fk#Bc^Z*npDge)SC3kr#8#eIf{trTuCt7bS~J~(+FCr@Lf};VTldQxP_W)?nNO>~ zuyq27OHHDVV(|b|V0+)VXeNxGG30-|7fgO;Qbb1`J}ZstoH0f z_WUd`+T_jm-1cpX!NFbvO;;w5VVdh!)6HP+p{#jR&2Na%D)P+Ayl~ZNJS+fy3O4 zPvt7uz~Jh*C=>aYKLp`{>rb)fr$A<)skub})ZrfU6ZHuEJZ$s5+c%6E-l64}G)u^9 z=Zs7cc2>L5?nxIuMel*BK)IAfIf{uEcAaq{_o$XsVxkcnUXixDkj=+qP3=x|Eetg&-%ZHXF5qH%^T#D4{+7wlrlo0a{tHb4mElXsR^ zB5VVL+s0%M=&7hEC`G*zsO3szt)?aTD`W-ZEr>k9hP+-`3z-?T-o1i(m?dMd%6>UE zc0OlgOQ50`w)y=)sHCz`@ubW4&xLSV^yH}|)C>I?M6S9Uy)H3^KKU1MbbrLLqe%>> zUM0oLo2NIY?RUmgFXCj-d?ErRM~7HplCTh<#Z(bPZ#Cspy3lGjRZvDX7rFS6DQ2aG zl|}CIycO(>Mn$Z-5g6`!E-rgGD=!em4>oRxr1o{%0UB=K2VB6EREf|`=R1Dd-#{s&Ozdb!Oh)e11 zfAc)NUVXN|KHQqS%aHQeZ~Sgd5DAMTEoGCted98K5-mV1rE-2RGPNC!mXVG9QZisc zdR=B_0JMt(g3!fpKxWkdS*sY<+MCqm!y!;`i~1T}YAsD7Bc+m$a$S~aev~siUcT$F z+Xm5s$JR2kY|+k|aVyPQeNZ!SpfxMqWSgm^f}NqN_d!N5QKF+u0!tHCy*z|Kp?#?C zXJc^lJmJr+wE1zs&Mnb(>XIIaN+cvk4xW;-X~B&sMn0=I9)Xyk`m&zbg(5?ccEgmf=ZXF%ynnH;F1#8kVR}r3+<8B{sJ>Zc!CshmcX*kuIHK_XX@rJA= zQ{}D;I@f={*K~HhKYpCxvE=i(Bmp=b>dG~o4vyu5)m#cRn;mpnfS}NN35w{ugAFDx z*|M6cSo|O+O4iO;tX(~8#gmznW6np+L5K#>%t#k$9c^txfKU*KsHRcUczncMS=~~X zs6w!_L-qRUo=WqxpO_0oL!|b2%%RqPxz#-~HU3Wwl&`Odt{9kdlIomI5LR;s zNd_&Q13(-O2#*GU+;yOJEduk??VlS{;Es9T)7OruenQlepp}9|#}Yu)mL7JBd;j|F zpZ;E+@4*<}+6B)q_W?(~Ce!huP8#R8J#df#-GCY6KDF5@xAPJ8v;eXi&u^Bps3daL zaFRwWVUPOlHA~f55TK zuO0RidBT(VqRnmuzxxnkvEzunX%l?kPn43-b;W-=$GPmGa!bNRn``!_y5!z7nq4gK z;!XCjOH8Xt`cMDl*Y2Y`T^iMExM#MLvLb1OZGP$ssLWco9pb6`wO5w*XlrcDvnw0K zbELo9rpPKmb}57=5sC$bNck`;rEO^(;F^!+;B=6iA0Ag$lDeS%(p&LZdE;C6$DL0_ zSx*5=`4K$b3S0X@%yK=KINg*O=(b17In+6p|CJGkfo%9IS-lv6jddhu7x8}Fj3ubN zOCRNH<@JQnr9qRa_XMupmARVw!hBbbW+5$BoisdXD zIyHEdYU}W3);Bu8UsLPNtJ0#?Nkhct+F7dZ)P?9WnModMNm!;G@I7abGK$yE!J{!c zBKCPmd>vQ~*X467qMoWbH8>MINYgA%Cpiu-|Gh46r7$`oHah%be0twQ|J>laYS_h^ zV7sU{EzuP1TF+zpZAt;@Tq3y>`mmYH)!mANmx2N;Gp>^cw0_C zU)>6+95z_vY$>(;`JFRy)2nq;oQ(tE;|@2z2Y+kyI2is33A4FiN9;@8aQoPv@UT!a}3V- z&dAa%H9vNok!a{@I1MO;h=2K^WD-ws`VVQ>U0nad1ZI^vwGc`3tN~R|)0ad;to2h` zN5U;RCcle2(4#N5a8N21Pepw%+_1M+#0PM{9-_>pMS30|t?WOZan`*Wuw2kWCv~90}mZz)U)J z?Le_zbh94*u(*V=5`98d+TxP)&_+f+er7Gz6)#QI!o&LkM*GW`c3{>)jyOm#B2zXL zWJ@{F+i<;=@=cKer_Fzwoy!e=U_}Hp!2o0ku&MyaL>+HxQ%@Q9TQdFhk^909Qk_qE z%U-C$#F}^<4~EdmCWqR$jt>tbm=HPx*=kEmOObn-7Z(@4ByJ2lrm?0FL)tjYc$lGl zZQ9E$!m=2|sxFgF7ju>7A{jk@2Q7M2hEfTgl9yJF(bR4ExbM~ry`+jn&ZnV&MN4-^J zBpEF|esILjF$Izu$gd92^r~Nj7)-^u_9|Nyoc^Oat=fo)>AmwBgJfVo<+0zz2rlE^ zzhDPdzNb?n5gOEUhik{tnBNjO2QQ;PUmBhXn*#npmk{!qj(xM<{6m)S!!lCmhc?Jj zXMeR0i1c+FjxCj!IF>vIn$9w$gOz<^MTzKfr42cp{P^?pmv>J8)A%SKfaP|kT;Vyt zC^E)lH%5wh_f=(|2M&lgy?D!53k6RI$&0!4swk$ad(FS7W3GvV)z=54`oyHKQr1Dk zmSRhu4<8-whD*mKx$Z!@c_yX@JnK*Si5JasFBMpm;crP(PtzvYkS9mR{V@nVi9AHHz}i5GQf`@sa&%4^@UQ# zYs@Q=o${b~r1j77O-+|?yr2{FD6cQqe#rPr`@^B&_TBO4_TwX3P8KqPpLby$pQp!e zxw+&Qy>`qiU`!o-j{?24PDA>m&^2_IW;mHAWtON5rcMq@TIK0 zca7cUr9-u8p>k(!w^g1np%4A=TH8M*SgO2RW#gHthiGj!*xXX#-(}X99@`<&3g>Q@ zTzQYlmtK}1bPE3D4JAA8%5?J@wfHVh|0}xfT2^Oserwx9R;*)sYKt;wC4T@R!E|L2 zH>Yti*X11zFn#fS)7v(-I6wpE-tMf~+57!LezV~%5DMie{W6p9E`ZY-{ITr#ex9hG_D1k5!j z;;{Z#0>!*B@lO>nv$PRRS=9*eAD;Phn?smAP))|`K!nb!XxwcysdS-LY}1!&#Np9= z<0FR6Q?k2odqLG8TN-egxB;zoY-d6}jkA)h5zzVjJtAa*9KX#h+)+Mt*$w0TC?$x^ zS8tfI?O5~@Ch@Vjce2h&l@A@$re@w)N!cwMywThXcfP7*WAD6P|v5-Rms6UWsAhy&W+6;v5{6_B zt?6{gnuuGj81_gS78$!Q!ns`BH-pLsWt@g6M8v%t{tSid{cu%rjNPG&Ru=`I%5OX6cYjFpdh*1 z-3o7~5yi%%8$csvX&C{8R#{l29z9y|6>VS5Up@V5P>j=}r$V29GAMciOWt_uI<9yV zXm1?uG8dVd?FIk4Y(A_zQ^JQ6yUhDu$FbFN=oz%*23p$i?bt3YF8}DDEzwg3j#ex| z2ZP8GF8ItJUA14kbHc=(Fj$4F^-WHDox3ZoP%Kzy+z$8a^gYy5>fGVz^}hH%V{b=Ycm(VYmqRvk(wJ zz^Lf4qFnG73_-c7&ks;ZNy)|4rNS>NQg+l8gr1s8&B2Jg-w>DSp|t8YQ^AR zq8yBK$|Vosf5#nYjP9tEf%T=*S_7Yey#(dgdGCLba4&49HAIWa-b#hoQ^WRw8^nBg zp#kqX$mEhuv+Cm8fSu1ag?H!)QFz!`4Z_%6_Q!#50-2luAU7k_?^q+rjG^5Il(;s8KIL<~y zV~Zk?Pk&7f0_Q#x?v^0E|8*OOf1nH(JE@eqolI|47>aQr|3Y#24KWuI?@rppE8F20z)S#TduT9;I z=FZ>`45IoHKM0s~OB05=lVKxC*$O@s9|{!q7pLAB7yPpQ+*@9Gn?2D~m`L=mQE^SR zZQxJ^b9SzVNKU$J#M}cid8Fl&uczO7UCPhfxZjhNVW7Z%(v$-+u=T%Pm6ktpHnBXM zW*I<#MVC>eV+Hc?=ti06T`F#oomyN#C& zt9b;FwdLlBjAR{{A0B!TVoC!xRd!9kjVEr=Z{JPt1#Lk6joeb6rlhPb{Q%l%nVu1q z5}LPZu*+wG8y7YFVKR$oKsSzCPE@{#{ws($g*NJeg!{F*BUDeW+5e@*BhoX)qRg$W zzhL^eNzSa*5D>=%g!wY6%dcHX4DWq#B2n2NDU-v1umNUAzyuGpE#3I#E0+%f&PafW zK|_=%wef;{R?j+owp#1>yBSO8Ao{p0;86P!~FBp$2z{o@P-E~x3>Wm zJw2SaZ6pwd$O@!lgT+lI-j9D~g1 zdaA!*(me;Jv0Zn^XGGXKL5ssWjde2s^Vzn--b8BfR=k}%8v zrv+$PPvLVJR4XhRf4EHU$SNLhvmxYq>a@vcp0r(PVN_oQomsCx)6@L`9yzPy`GcQB z=>Oa8tPiR=QGC2PpWv~UzqUE*2P}|57y~O7>>Uq1lZ(XZEhWNFXn7k$HwO)-x}Czf z*y@s47Oj|T8@;WQ(zfsjsY9b=sL-#kld>WbYdz$^A2~uLR$+gVg1 zO{vW0V~o2NBGjm*vR#`Z#xhAQ3-J>+X_Q)-7pYjNxXn!(HK#QIXHDzWJN5ccqyF^U#jn8 z_PrHgQeLnSOTuZd(z^Fl!Z6E%&#IK5lRCO`k`E-i8;^WyOpKO#j-j1S`{VQBY=mR< zmq&VzrZ$l(mUY_$uf}xelz*;}F{gRSlT-@i z>?GVX_aIl5*Q27}$APBxx+nEi?|<8h5!_SMjQ4h5yP!2?(WT(bmK4N~g$xaBjmVvf z4A)?AEmiM5^AZ-PVvW!JZ6EM2T`*aFRv`X2pBHWZ0Xp!c?fVIH=c^LTqAou znI6UKhY>DPP4WuKsSgd#9M#iuH7n5rdKqV{fOrbf&;ec*!1NB7Naioxty|aAXVMz@ zFd&h96;QqA)`=BE?2?x^r@|w_R~S3?;zT(w&2TkG>+Tt&!9Ob2AyrC0pgILHiKZFn zy-Z@rQKykBcJ?HuYdgbT zeh|7;l#|%OQVlEr#1`hG;+Rmdb0Fe3HG1c*&VGBBNLPNlIO<}9YWWuw-<7|ha1m9x zoG-a?)?iO5nwQjl2;W)=$yfz~fSE_}fx`b3^*0z`2(sQK8 zTt%WBuqNb{DJzcT8SuFN*w)b)}Ne!3$J$jxl~ z$CA9=atj$dN@4qI`=B-YrS$HvbaMOr5EK(b%4{Nh`_-51!U5P8X~{tu+l$MFf1V*s z+rA-b8Ou8S9zoBCKwBLf2hNl#jvEXSBdQYvEpARxtO@hREdRASXwRpk>Q{z#yF^HnJMP)?bp)G9-5%iiGJy$RpUstQI;Ml z0L1@dA#^WPf=gc@%+}LXVEdlMoM1zA#SJZrwQVRNcS82FRIP0RmI2yRmbZxo@G z{D6mxd<_mteXP^xnTW-DE?oWN-vUzd|KpJBcH=t@g6^vELCSKP{ zL|!LtStJR3%T*eEa}L)u{-_@8p=Wf3)^AfSq0k_d%4q6sL`6?oYBds^xDmi@nr#7S zG2`0jjlO)Lq+K2@D z>9eQ!1M0N5K<7(dN!v(C#ptY=p&dhwp>Z1hXN5D$GCApFnnXDPA5!N$rOu zU$q_E*2@IX+2?K911unhtqPsktIUdb3S#6r6dXSo|IeOAgC-$0knyPaIe;cvSLeUj_`9QNE?!>5zQaRW zKm-H$4@l*6#<(?84ytjgm9uIYm^v#olou^&znQDYc_^oz4x!nJW5taCrez*po_4_D zZ#l)>*wTW~*WVvxps{c4m*mTws(?4efR+x&c2<_+-HFYM){C0H?zaTntkQT>Q6*oF zl$+zt>Mcw0Bd~pf+NtP}0cWm_WNtg0&%L@0uBa2TA>-wZPu#BwF5Ne6BeHOr2I=jM zjO}aPMq1)S{`{-3O6{nr2$t5f(>D6f&Wl96Z#VYIg^I6HQ zcV+ZO4P|(BTtxJUA}RmrUerEcT^G)YaWBoSmKQs)uKcByhcfyX<)00zDNQ*9$-Ra{@GVz zbu_8P>d*uFc)isOH+JRL@ZJ}4qvrmQmr4YtH|`}@YOS(-+o=t<9J}g6dhtz-i z|49#9jnwI&8eaq9!62@m7L5UF?))Lsho`FkAF-|I#dJoATn|ApY<#9`%ye!ou!|*; z<;QvCPsAoEL)?{zsyLJ<_ZkwzXP$5UFh#EIDvsHaP_5}EN_40P{Q z6)V7*$flPKt>MgiyPFeP;Iam*8{hCS)IgUGxp*au8)%VABs|hJ4+Llz%V$|7;=IK1 z8z$wKkA^uOnaem-a>9(Z4yxK|^N6VzbNu=RzV~NKM*%89)5Pqbwssv&Z^LzG%7PROV>eJ-DpkBV=G=j9aF+*Lw$X zjgOmUnX!}1a8LtIg^=HgiWZ@h9sVkyWa`50E1M9+!mWT*0`u;z0&Uc+x@lPY;)I*X zSu4fwQ9O4&RUOHX21y;Tp19B}Daj)0Req+On{>=9EP&Ue;xUdijxb^5zC&nu7Kx#7 zwql*V8(;x|_`RuoK^ZJKk`_z=Q`@Vbr%?Wix|=R!T^5zc=DMBdZeIJF2&PR({;8W| ztF0CW1g$IR0bD+TJXNev=r6SkIz~p*XXW#1l4bMYi+Uqkc+EX4Qv_bkQimsYS7=96 z&o809uKf;sVI{-QBuzXniO?Oz^bI}}_yhMg>irLB>1{T+{5K2>i^zuu!4N&Q?Ub(w zCHg)U9c8v%;5MVf>V_1;=d}Dk>r~ETPmCX?wzs#41=B3)!a+HF{&W83ZW(Num}dPm z9jCrQL!kalXU!L_1Hq}r=S)P!{qk>yKE#|(y2A0C!yME$Wc|h8F21s-@4gJ?vdLt# z>p>F=QK1bYPaAn$Xz)bVM7x`f8Z|DB=E`DwMIL=m>}6|sZ#obZN35nC2k>qGoP&FV zOji5Nu0BY+ipZ)Qu2d2d|L?4vBKi-_sOrIpLk!dsQtzB_2pq*BN)XV7WjVisodu+T zBjNtEB$S*BgdVL-fYZ~2(#?>=f!%>sNKxH^xN@mpk{Vd%_&$4G5j} zOEazDEt73P>OfO5h4==q;&MilYJ8N;C$ z4#^CzsboD;f|29}=(f8jNu&f#BuWM%8Pnsq09^KRbxfm9-NCY|e8^=LRTy>iR4ZcCIj6!fY3 z@BRfmZrv%w?~M`sm6FWnyg(Eix{>rOIiE-{s&vhaAv&qssSZpa@g2Mk_Z6eXBJU;1gSsbyhimih7Wz1D=5 zrvkqu@XT7vN2uO(y*`dHH+Q>opDji{o5$l-)QI_9X@aao_Mm%A^mJtW#XC$@sb}6` z{?QxW2~mS0AJWv4bbe-_s!@(JrD7r``b^<9d`E3n4R1~CILC32LM_$GRO2X^hfze| zpp6x%2@_b%yb~B7_JsMp9Y3)Bwa3t{dW)|5Upcw4xVOnzCy_g^yVJi%KW5fXgMTMT zP9KPq`TCW8J^~ty<|twdfWQ()Al4=BMyy6hc znbVXG|8J25VI`MaipB-TbMPBT6f3K%{cESh>C?Rb~_WdyT*XEususWLz)VOj(x zjcB2s;c;`VJ#i~V8-9Fc(xbK(<2iB`W(~nHpL-1v&xV8yT{i^;7M+qTvrVQX?kVxes22VMN$%3>S$j zk6;O)YHw5bVTQfg_Qvj_ZK{0SaimvUqY+vIp3(U9MILLfBpJN$*8@bH9zq(F+$@DUt!o7FLzO1$Q+iBWM%QbW5zJAtlu8#8}V>|qp3m>w+ z8heg%LRYcPac^@0SCL7vE2`|GH~C-JFhE-X0(P=Pzgm z88T1_L9K0mjEuE~u63YFXqm;QBF)Ta(Tw%>V&frXMgq!TpBR_hPr;B!rRXdQsHLD1i;# zz@;*-X>0c2bmlv`50Ntt4gUlODEzRr(H+Wo%|FQH5yprkF%X)Nfuoka%~}aEJi~u3wSbcyrOLNIG-JkOyDF7J6*2R_Xye6=n*D`90P6KLi_ z6W2SlGCg&@=K9;9=}$_q8)Z&IhUAH1-Jg<){(&X%eOX<}T!%xT!KOW)dFwPo&wQ*2 zlp_nDi)e9hjO_^wKN8Hu#6;hdkZGP0IrNBod5C*woN{>xx14K&s7L9MmvJz$$(Mu2 zuY@+Z<xPYYq3xBzB)^jnX-rmQT}JsPa!nt$B>o5wYR>dYc1OiS&B^L!E({Rk z;~xgaQk@J(3fOTE2&AW{JO2ISwD9fokW(xWg!lb>4RFIb(H2O)%&TZj^Ss`HZeZrZ=Q1HInzb_i_6mS?9xXABIuU{0 z39P?w&X?#$Zdek5*w4a+y)YXV*6QHbxeDLXRkVKboXu|qXp%BN39xIGvVA%X|DAH% z7?BZfpfP;UNA2C>6mkqzKaix6wj5Nf__I6haf&lr;KDMlQWt0AC~TAi3iWbQrKT~K zQ`JI9?>G@oC^`}^TBEkq0eWWAxda@|JU%Ia4s8Yw*9;q3o%d_x5_*au5NY%OdG$ud z6!L6dTI_FNG}ZX8=ld>k<-0I_fKT3emW84zu|`tWA-c+x!b`n_O8?u)!f)`#7|yOE zPO$*g!^)vNqu^-C?FV|(pi|?{OG`XbvlLRu;U~xoa@@Fe72K%Lf!ZR$!QC&l;z9Mx z5wK2#5bC!z2ZM-T0U}=M^S8pwn9&Gn|LSiq*!P~uE2_2zTYeTeU+k$~OL8mzixNJ; z$gYc+bkXD%mECxHs((gHu~=~1u0D@AP<2+d)1Rs)h&lVEo|;nWm*EJ#i84OYvnxe_ zHaGC-{6QgIaj78<_Y!l-aO)GgzkYi#w{hHSbMZ@P&?PH(a78)nEw46rQV~;ScA!uIckI{WC`TPB2h7DfrTI~C-@poI! zpI>oTD-$LpU=_Qs2t^T&TM)T-@%w&sI0o5T{Z2Y0m=ddquCClz@e&TXLIiY`*C9}3 zcYT?bYr28OIBp+CIClBm^%vyoxu!WIc(q*4gq=ryq56^(E(&espe%W5H!YAOmA>5#*Zx z{Y1*+^M~ekv4M7JAcU&Er6tB_Wq6Gn|gv2@)PmGZPbf$7UpAp4CpYWi}bcrUY3 zDe5hEn(5*XS>#}>2X9z#I%O1&nQnciiy0ULlZ?+wCC0?K8wXAGsw7Ehfj*(*kki>Ehz*&P$^GSMW1P7QkBxCg12OA z^6mmjtizuAB&pFw) z#~0UrT~)Wi`F18?j7C_PfL^M4{L#ZWE&t+K31!<(NLDI4T1=JP*ppDgOLZKL|TDDE2Ek>UFD9Ka4>ljK57r*0Chzj^eD4JTBjMf zJohLvg-{I_IDl}b3E>b#%@&|fQ5V$)sNas3#-T0a!aC*=-r!OmJ6#viJ|9N5C`-FVFDNIz>!m^MVUKZ89}gUkQJ zA)t|fGt=0|2QatlMHaD!?ktH9HU8LctH0TAla!>MQ9x?jDJWn}uV>^x+6fJG#7I60 z>(HPnK?}i(#RkrJEOnWw(lFm->Ugcldb`6W7cikEu3#==8t@(#(Nu zL!C?`C{r}+?5`FU2x3^|@usewN&6pb)7&)utKJ?yHZ??_NPLA)71|R|T|#jQ!JRw4 z(s#r%H@WnYIv|zL^W26w97+pqkGT^_^TU&)%sliV!B4xK+g}A9@gK4$a9K_Vb7HDd z8^n${#ZoKHSbM})+ZIdq@$XV=53ED9W@h$K=)+C~dFw{TzOi5YfM_E-<@3mDL7XC} zBFe*+MJnKm$1T|-yYf9csvjI{EVeIlVG`&)1kF?cm^dn$3RH2+u72IWVzgV1cbwQ5De;?P zf?2CqXuB(+P;c8aym*rTLfvj85S{Wh&8jZHZ~RRv+Ebsw%J=5=P8@FWqIra>oAR<} zK_!r#{LZgtr#PNk69K78o?L{?gHtF{u5BY>O~vQmeXUfo(zZixTL5k`tm}i|*qxRa z!uO)Lv=KZOO`(%5kGiyTu9tll?{Bkgy(VLxsmH6Njq*?#3^GJ4tDT6CBv(aMmNE(< zTeof1ou%CnGA+{aJMDj;OKllSdouzu$cW#K!HJ6^rY8N61y~cU))#wP=@9G&}4P7Ouy zvq`@bs`((?(WY|O57lD=oM}pv>ulJeuymJf& z_nE=FYFR^j(*p)!<%Cx+Wq_(=fo&~WOxUKT9T`mr2|=1+Ko{M_N=)AfOzzo3C-%x5 zf<>Z+Tex{ru%7fo6grSInpq)8n{P}J@B_AV@4E8X2)N~d%;NFyMPbazR2iIg%S- z=IqJ}p)6XxXB|s)#herZ+Vm~SEx;L=S}51d-vOgtsNLG#Gs&v{Z*fz+nfn~$P>!Ds zrck8zU$qZE7|FfpLF7rtbGtb*cPqUZ-(V6j*T_c?peqHpYD(Yc+G{n6Wz2j@`r}e( zkS3$yzK%4p+L=q0Yqa~OA^nfQo8O(}bDurx_6dwPwL9p>qI8ny(D z_u%C2KOYW~dn`D*uoX;sQK_fRck^LyN^AZrOK3#843S7QdwVNM^EbB~`xOdvB>K5_ z+!@Ne%F=Vjhltc|&d>Z_PP-w3@v`N&fy%aU;rR{oo>tSRRszzxiyoKN%|hUPv{G4R zp87~$DJa*Lr+qAWzU^Ojsp3Yh@q4?|%lDVgq5I{pZly=TQ`c_hs=r1DvoBKFuSjV> z#>f7;Zcrp>#ijkQOL*_nAy^Gb`?k~HmTL!Hw4XvwB{4^kD!)xfi|19AC~N#-p1b(? z2^(FLOQA`o8OGzi#TS&y>4O%laeVMjo>Z}ZXD!_hN<9T6nVjh>*g8!=mpT}&FVDI^ z6n~PQn}LKy?sRrpfOE`b^FuKN-Dy;NFtsgNYtYZ!t?0>^)fiA8>8^fXc!e+QuIUpf zNOOR3#l6TlV!hEp>UDj*)_9c2aJ)Q#)T0`7BBW>OJpx$L1Ku=)FI($QRi( z6Wm3pTel)6D22#ji9z*hXEBnN`^Vl&z{aELv&4mT)V2djh1MWPID~Thq7?C%SFSQx zT2iqZ#%nz0kcTWQUgA5|#^50#36ctJCkh+swR0~TNje~%-7|no-H+z9?|tCYE!KdcQlV8ek+DjNjA^glcVP{=y{g{_CvYNfdFK*E z1yfLJDWE2ArsBn!r+wRR{aWG8US+W=~JGGiTHQzk4`K9qRzeR&FZUA5Hmum z_Lpi2ocwr1~W|Ht9hrf&~Mjy(WE=`?%-`?UV{84Nr7`db^ zGS7%BS(gpW);<+W-oYA~UpB>?!!&@7@m0eQi!}W9KHu0A93#oRG*@d49LrBXR?&oS z7cq52v2qgg{l0O8-CnCF_9pPQp$*F#YutmA^=)O4TxqqF??Y*}V8+O_JduOpM2s5W3sqV<#Kn6E&3dy+H$2xESk!RWPq`5m#;KKXI? z5vFlMUhL@ZZCTZRYFk|zEq^cL`%dF86eIjfAf*LDOC1I0e!(VJ@)0Bj8g)J}ai&3u zj`c!~!=N?@M_gXx@Rqo_uzvILy$qOue!By7R)XE7afPkOroihzxIR!(n#2TrF?Tv^ zn3_%rHtAfQxV!f=rT7+-43)$+Q`jkwEyU0#4j)y#!L$PLQ7KmYFD64t!>Y{U#|}m> zn%vTR-OR~PTKWtIiE43Fmf94$8SxG9g6G0Ky(X-qEd3in@tK_u_8_J>9xKQKg> zu4gFn{gG^q${28sr&UfWL8)iewd4s^o3LMe+x)c|v>Wg3Ye!-d=#ODFncF+RM~hE@ zKkX>*5b%?iw%DPtjOp|rQd^$i_ z;IOmnrORp(@0$l%d@nPqzRNnxai=2bu)RY0Tw2GJ<@MKZi~DRaxc{ zIi5c9-SQL+H&2Ensim_0{ar|^mKpb*PT9Xm3Q2rA+C6^J1KGP}D$=<5`b1-nQ!XdB zT@0#ouTk5%8@rJawzWqOAIxOswa=Q@e8NR;_*i})?ow`UJJZ}R zyzO5m=={QHNTK;wXZXK3^ z4Ei&!|68*oFoNE7e-`#HyZ(0VXdbmHSMYZnCZ3V+xrys^TRE^?}>H6i{g8z1WY1;8S-uZz-l<7||^WDJ>}fw=q9 zxJ0O0k-|4@>hw9AGdMe!((8`y%*4jDLs5}>UGdTx=%ZlK5n|BIE*}Xwol)- z!U9~d;rT|q2IEJjq}=fk>lAIK<;PLDFfb4d2^`7UtHo=jH48Sz(JORk(omMf`8)rx zCa4*klqRq8sx^zWgZF>9dg+#5wWvp2ifj(_>X^?crLKw+bvC_ob@c=6Vw}!EHY=#& zCEDIU>UOwvYNbwLh%L|Lhj5v}k{@1(b@wN`A{6CQ_Tj*i5aERHGpUOu5?jIIJ=cr{ z{6mj%-+mo>SfIb%x`7HtN5Zi)htNPAH5y+fv2y+zd@NyDj}Ms1vEszJ=%dE zx#WT8G>I#p&UnBc_8*FATobAh4Xk4TIU|6Y2zy%gzWfo6n3&2kbtenPYUAyJ^ zT%^%83=1QW!cTm9f0YgAYPp;y3)+u2xGIaj%-N4DkYlDRD&KBpol4EuAQatSlf&Cj zTwVx6jOYl}WOT}AGP0%^+p-dD73>&O)q zEL-KvIfBnH|Gi7uxJXYoILs-Z=BYynFbdL5@vTDtqr-%IOxUF_P%~ql&T5Rjo1A9w4ncWuaWI>9Is2I$6B6aFy%ZvSivP(c#>U;3js8`0mD!lRXhR z-Y~dn1sh*#Sa26rYT@qfO~AAzEgjUPnIM=(*Y8uK3I7>olt#p-hA3CqB#>!oZt0G2 zy2$R5^gfg{wC7r4r}*VdSiSGCE%C;ixnA`J;@f-P(b){}dcW!y<=+~JIkZj;l-vl% zj7z#7a=(Vwxp9oLmcf0m?Fwio_n%sbRAYw5uYJQMXLJ6(j5*>bMOBq0fY#0SYg_nP zN~_FB8qXnC^X(Lx*}6o`$G@jdl9;t0u`%|JHW`1$wX16Pp;V<)YrV&o1Z}sJ;{`!U z7oi4VFYKzYfghC@QcgsaL29T+-qY1#B2!4_GT^(mPXzCi3 z(q__?))@{HlbNwhR)U}D9lN@@RDO>MH4K3Y14K6>4;*S2i~|>0`Mx^pCC9ZOKX2e@@HilV02vVbu^YAo0g1>RPA>>j&SAi| z)Z)V@PvX9>{XUAmK{u?P{)Gixi9&*c#J(NF-?`M@mT=vc_Io%IN5oS*Ev`-$ePm+E zlSN#baz8(TYkl;WVtU&aRINkEZt&7}KKsz(m|az$Cw$yO6~KFO4A)_q@0s~1tc>k1 z)%e7=5im<3-9``jE zUx-0ly9r{wLyxG)er!VsQhAx^G%Qb|URt=rNyCJZF!>lLUZ4`1TLbHtIM5O5B+}&u zIOz!$?9~M2iK9>dbdc!Trnk8)vv?R3TG1$YmgP1Ddk_^?=)E>Xsd6P^sKuRe(+iro zCahmWy)A;KQN`l`k$W95WqTZ$;D@?7ZDXAGUA@*7z$?7y7~GgAPZfg z%{F-*F6k!8{4?p>yr=aWUTrwKWxcBuo1Xe#NY(o^;G!`zgm~S{{3rtZ`%1TZwf(fq zP?7uC-aFwiphFaqDpZ#xL_`hCkgUOF+M$&wos%YJ*!mF9yD#TKvu3l_KYzn&>}P{N zd~m=i!WFmhrQ+AdFNv(?Ep>zv=9dM!0<9O>vb`uRrq6o4B*C1ft^Hs6sz{Xbj`UrS zZr;HO(xsZG7HnAe+zB6Y8w5|=`v3vxILM)(uo015NH7Xu=oaO>YArYRK@u4-f(1xC zZR^!;c9mY7^4P!u0G?FMQWYQ+adQ|j{T2rSD+_Hk%OoWtLf8m0lOAMPzVhSQL42Yb zT+)Frv{ID}w-onH^LDp?woZSCzb!c#NW zyiS0VK(?qqv7MbAP)XW_gg|tENPqk(hgyV1mrrf3=oihLW(?mvzoA=9YtPjj>bn7^ zuixqqxc*v(Tj{|ap*_<^V=hbXuFD!)=RBu$XrPQ&P^KEY8MIH6o1JWE5Fr*!s5|i$ z^)AV>Rbc7pxOzAvWcAaG5XD`aYrvJqkCNWAELoecA^=(w5)a8VKzI;|t9p+79{m~F zrZ>UizwO6rg&>+5gVL=1?C9+6X!I|KvPLp+Z2W5#9jcRL`uR1-2dL;zDUAN-Y-VX1 z!3goP?+fwg#1QVCdcNJ3K8uRH4R^Jgf&&4RL= z#RureO?rdMX12UWggiR?A-uqFi6AuC6wQUd-``u^QD!7i>Y$c9s$x(Nr<2mGTIkckA*d2!JBn9PMfZ#Bp;ERkcNqf;@bMMKdXW z7?^d>zcOh&`ilNHM3ubP=7*1XPIUlME{|igX%Xkg&!wYAHJpF=9cu)#Ae^O)co3P_ z^tIF{RmSWF-jUwXd z3%Vp6VAlyIho7nnZ?aKE5LO?8-izAa68o8;N+r{R&6Pr$;v#UX6e67$j!_lEwnpmL1_l<+X2Re`>>cEyWK$6euu)OQit1Ta z2vK6flgPK@zm>qUc-Gs4zIBNkRv4)7J=NO@Qnf@qic645q}`793dr)18Ek;O25Lulc2+AoFHw+!k1QXSVjSc5C$<$jqqaV)DnEyvyWN^vM zre|OwAHpiHBxdhu|Iw0eVC{sJ_!cp9Sm}f}!8`M7PVdbPFFifIIFmH#aAW~;7Uz&xFE zoH^?8Y>?sKchfr8Uw=Nakv~F`rb&_H8c#m#G}QT@1bpie@q(!k-k)6WaeWh4_UTg( z=j#JyNN{Xkdq+nsV{~mp1HAci4a{nPrjU;y7|Ln*A3j9niY}m_YVf=wx)dX=H`RP%rR}EcHLpDVMc* z=wo*KvBV_POJuy34&4$r&ZYSwZ32LL!#}E1AB0hLdtIeJ&ZmwbQv@AI$W|}8~FHF^*ZGjaoM8@qc z9o*mN9sdM&W~Jp-A0X-SKYBG(u6l;LIx9LidMXV#H6kpGZtf$^#kL#s<{mmH*Bc*tynh-N$P+1Y?OI$7CU%9p5}OF&Y{cBA8OC<{albNtH^+A4xWr?JAXRzH|*8uEP{0hkP!!hyUW;*9ZY*XtlCu+!A|k7_K*3VZsk zA=RaZ>F=P+A7^3M?M26SnB91jscjh1{cHbCUFE2pRjWpno+vpsXg_TiASG=)B)Z1u z$fnrIV=X9GfGVMk29EiP83qk`bLm>`QHnJh4GAu1u_kA zXU{DIwfwOwu+K1YU&IuN_lXV|Q)rlKuv^bL3b)U0ozg{bgkp+)H}Ouucp<@Et-5&o z&SZ{u{NArqc!9SErU-+DRBZVq4{ri2ILhGKW7ur6TTrRi@!A}@xAiiF_vQ0t`J+3Z zzU!blU+zdh-`BjL2HxrhhPQj3f83v;p|y$5F!lk=+H-+>&Fg5~9b85d%!SnjR}0QJ zu7HP(%;E~Qw?`Hd3UG7oeBUT5{9YM*B`ixSJ4^gd5sZ8v`+eCS_-=zVe$3KZd#=bO z1?!ouY`S=mzAE>j=n9Q~R zOmAxz$tw?qfI}#ya$&zc1g$++fqRjAUP!*k#l?k^=RG1ITe^yHOUPJk-Q@&0ToBRK90T?5}-XO}cq6LciEa|Vptl(J@tK3hu z7x_Lo!4vCD>`eZcCMgo%h*#Ahqtw159qx8eiRi#diN&AGDO05gOPVy$-$Vgyp&D1= z^hs;FWrA-Gsg3v6LLh?o%+C3*+{mC*;t%V1#k@`eM!^y)zHLE>;+2CI6cqU$pJ$IR z#_>nb%))G61i@wI*rpCNw^Tp!y2-O&dy@< zjHADaOe(GD;V{EnB!hsv1XoN9ejMm7(^?!@CNg$d0VRBkGz{uR{=QS^{rgjv5Kah8 zV26L`U=a~WF(`1<1?SaUXc@E!Zc!p7zHiH$L_wkvpA2@ahl3D@&$2$1({0CHG|C|d!C{jgNCs!ZL7jR&{1>K{%xyEH%qU#)aU1*aEYs?Uh`JP6 zrq~5H45WJI)Mu3+SH;BDj{wmlVo-gtW7(LBHd6|s>GDTC$Hv=q zV|qkkt~gKqiR#~#!NWpEL{73smX5ij_7p}3Z6l=_?Y_uWPhO2DW^^v@b>bcPfi`#E z!{0{!!)J4=86hAN5Z&>6??84KhhA^;UU@|CGq7r#I>R$e0*Ep=Oory?d6B931D+x5 zDk?iWgE6-72!>sLD6w4s__ILp&ueT=*E3Lr3;+|+;fk8B=p~atj4`W8Q!6VZlfYZN zji&`)JtJ=j6+b?~!R5gMAK-($DN#5xFf=4sZPFc&CH4sYN4-t9Y;igx-Dr6<0(v7$ zi&pWfnVzWPU2I+rXBc5Ir9iCEF2H&R{8LPZ#!pxSE)%+YUjK-_aw(_m6+&{;Rr-qcMNOZ3_vPXWurMC`fYE&`)6tCjca_v*qHS&7jP(@?47|G97aQ} z4KSzUMdfUMXSlJkF~A(P_dM`U$nU-#tFHcM^uvR9hsz<}^WbV=aO+p^#zJ<{hZ{{L z71i&{WxIb(UWu2g{lnv`;<{Xy)Qjp{x;ZDuzm)mNCC&fI{`PHfrw^`#o?-g1vF`Er z8y%gcM8Pf38nj(fLB_(L5wngCQ9<>FG>E*jj)h>17wCmyh(xTnhThcms2L-rgg(Jg zeyqZ_C`bAa9W*W>zAxqFHbKzJ8pUlv7|}E5z|A}^fD}?frX8B=e%3Qr^^`Lg!WCZ$ zAAe;G|G}lL-_+{jZe!r8_BwJ~ob}YW)yWt{5v_Eh`LqO&V;hvAr}tTpdn?W5uSHkN zj%^?(ado_<u3|8aqazX=o)LcU3eu=WG_hRWI~N ze@DkG+fEO?!J+>x>R}(x!gt}={d;P*t74ch6QY2u&E9o|PMWwFgLpC8i|0iz70<5# zf&*wJJy;fos;Bq@=x-q0n2cIcOy z)6=tgcnA127nz0Yjx2U=jzhPjqo`Ne{kr&Vxv+mc9}h>&i6|5x_L!K14&d}EYgpJs z^NuB2mN&|rd&D`h>ni9$Ao+}2PsC+xnH$(+DG^nT7n5J%Px+_u*T)(CFUVQ2o>E6A z17y#IVafRVL(Z`PxBk8>;ooJQ9m}xr715VypF{kvb;(!P)74M|k}GG;x@jt;H1t{# zuXarN+vPdZ@SGXXdV6v_(B)ZX?i0;xYuC;t64+?cbH+HGlCF79^28oxdq_IuLr{D8 z7*F-K=E%QbL-p9oa9W3@5x|uH{3+PIMU>cLoYb$?4Q;Q+tGT@2(K}0D=hqGH{F0Vi zPw8iTyKf%5D4}ZvS10|Gz3pvJ#l(Pr8JG4zZJ9 zzom>$etPs0_Ak4_oNg!hW-9rBdT==-OR;?|_DbaWd3^}rWlrV@dgLepu41P3yTk#mv(4@=9NqV*6#h3tz;shU;whd;vi%to3|E3lsD`fu zaVAyd?A63K0fk|=*hZ>boB6SCc_+hMa}_7F;er&@qF9=v+e-N%$dFGAuv#yBan@v6n#U;81^@h6aplDkoxV%X;B;?eErwxN9!s%(+?nr(X81-BrgKK|5 z7vjJ_bsRfp2Xm!s|74>u$v1*f%O2a-m~_0OX3Z}_Etsun7<2qCWJ0R3KBuZ{tw_gJ$fI*FLJ_`!dC;vVCP z9B(5|cTWr=z9#geH=prA?Qk~=^zK6Xv9sqh-iA?_sxJ|aEvjaD$e5qT*JvR%IT1h! zUi+_H{yz7!xH?7wcS5jBuz2S;?1CKy6zHC5Dq)PYM0ma7eCPPgl&yX|dS|&iYo7LH z7>}sY*n4waW}M}B^e#;^Tgi2qd|&v~f4SJ&jZ(v7&#A9aXa45N8GT>&kY=-uVOkjw zzC};&0O*6PdDTDjisJ?S2WX@~4p~FMoMn?tDUVb1f!RnKEtpmweVPIMNuaq@J|tTx z4I}|(CD3?-6c!XiIug_*ThZeB^iGA96#hG4`^yTbciprJQUCKL=1lkNO%t->`@_Mt zt0MlpRS(%KHkb=Ffm;pwUxoxI!F%Yo-i?B+&wRF+j}G@kI*kf8Er9Bc_0DRcjtfWV zS0PT_^$KGdIspz$1pq>^ZVT*K0khU=WV}WzEv=qHkg%s!p=tAjU2najLUg zBRV&u)cT}k9^~K<>J$}l52Fn3i>F@axlcLd>$)QW5Tq&Iusm=$R|k3T@l?XxsBg%ab z*_xhQs zVYf3Gj3ayauItr5+t?VW9!nR?R(abiKpF8qrau!=t41IoxI8fUY-VYRz*13hf4`eB zlbzX9JeF~J)-E;>iiGusfhpiQrF-b=ipbu+a(AgafFgt4sPA8s``>>|12!RcCjQ}h z&o`x+-@Xp5w|hG84q#@%9^*q@tzas--9 zli}`{2OhPf!W1cM_y1F=-jeV^4|)y>x`Eh3lU^VY54d5R0z7d*tYJ^Hi7&=djmfap z>m!jzbMs{(#WOUR!qn9l$HeHBShu<(gyQe-FZucR&r^B34O621cbncw940P)nE{~c`fb{4Ilik}TV`)N8ix2Uf$TK#c7qf~>Gq&!a zKH&3$hmeztV)*}4yMvpz#qjF-qGLzUq#voTtgp*OH?5Ka(ITU65hb)>@-S$pOwCuX zFb6Pw?{u@$^}d5e{LJ(3%hm<>VIvFRkG3vwHp%(x@laVV6*i7tp-pcLf-ZN=ynsg( z!5sEQzIRCsC}s7y?JoPMFHd=Y(Q$BQ+s=<`y89lFm;pM?#iY>rme>o{>l@Frwcrs1 z(dRArX&tm%eKO64hAmJstxWr>3_Ew&c>nkS?W|*%M=AV)H_-a!o_}AB1GYJr&YSs z?~pk2om$x+{|+Yo=;^}FFReNnzec=Rc-3~w{0qcSgN)R$Mf?3D96I1L0!5@zN4pxCcUDKDt-2N&ikF4XjxQxYD+; zW2L!^d-ev3oGUn5AXSZN6(a)TMJ#Io)yJokeJrASJQSN|I={nOKxjO;eg!Y^FvwN-YA(z!}m&s zZ^~W)ph<*!VT36jqR;%%)2D8U#VGZ{@6)YjiLrdS5sLqJjXD7of2A6v`$5N9oh2Pn-fX zQk@&(Z0PErN2b>FG^~I%Qe>NvTOsngqipymwU>@mA*bpPZP)5*O}jXbeF(z4vwdGP zSjLsGJTApuP?fk%qn65QM7|fFqX%7b-yH94Z8}>xj1)AWc<1z| zHVyVbGpw1)Lqztc)q2mgniI*(Rk%3_n`)#3>dha_Y9I0@p4K+B^o?FRB~$<|DHt0} z?E-aj|3$5UmeIG86?^!5x;G)xm@g~KkSmST24ydJ4O2zqzET5c`q`jkv0F+cof$LV z0P;D!zfb$~GR0xrvY-J~HYXEit`cj-8}d{v_(TI0LAl!9S!2%Oxe}G;7_oq7E|*E? zr%5uu^Qz|B+Lp+FU9i~0p=w=MR|HT@ah^+GFU6>k-&=S`&?-A$FFJJGZPZ+-zCNq| zTG<%7xj|Rq$Qwd~ahR4a454ut2ElxPyHP8tC5bVshf!{g*N{NtEiYTYTfkMd^;KQ5LV`Bkc>;eqED*sMq7}7ZK5yJsd;t zTWwMUeK-Qr)|EYV87?ug1Yq<3(ZdlRs5Jk~KkyScw&sBTo#N%i)B0U$ZBqmMQFx0# z3{&)V2Q3?L-hje6lNQdM=2sp4>}(Ge@;u-9yZMaR{kYFT)zV{E<4+P3GyHF)Aeih9 znzK?V)T!D2Ytoqzc;EdBruch#7kQ07tU@}hNYHHw>Dz=b$H!e+C-Ha_E;?@;5L|{* zydZBrz1&@V*$fOadATCEzqT^j8o&DB2fO8S+8JPC&EdxsE0dsTgSIj%yv^&AmfE^0I3$Wu_OYm*ggrs6d!is*sE08xOyK5BU>=)*0_uISAe!?Oj;mYrk`kP_-wa#== zybAU()Yftm|4W-4N0Ks{8tBE%TwT#LHB*3ZCiCmpf1J7k#-Trx?{;Wq3OA%Xb!0`N zp%763EV&kj*q-KOWkW1+<&z5*YzpTbNrDZN<@hFSvLu~?Inl+x+8cZyt$Aw9r$i$h z1eNQ7O7j%wt^Dv7hm$p8j)y2Fo6;8W)MPG?(sb)uS|Wkcv$I%b@N0cpI^B}_B(B4LSQm*GzRP7|<*?>R0u(&WpTn>Gq$Jg(_S$FI$gx7Oa%E_BfRMNd>6n(bTl^ z8fqW+6uvKn$(C>Jn!(D|r#|mKxJd1de!ygk!yRvud5J%WyD}R9s~t&%VN8FOuKf>T z9zL30724FCbZSre*#QuZCJIZ4gMX0H9`$FXB8iwt_QLXV{lw*rkK#xc6$jrp`|B7O z>22%0xk-I(_mIERMEA!%nK`2`a$@&jWA&krVi4va7&}TQpM>?MEY^}N44rT)7bl># zv|n9WDH|fw+JqeQIRXm;;695D1Ade7Y-IguEV>u}Htk0X75BRoV*hN7W_jP^4gz$@ z!J`#Houws!LL02p9;#mz|6e(il9CF5^U{pDT6o7(R+<5>uX!(rs$1UiNLUo#H>~rQ z?Ww0U#E}8JctB#llcFjrkv-sb^ZN}TyB#+N^zGja41Vct_BeCW8IYzL^R1EZtNjvF1pK83-$-G3c` zzdGMK>uhiFI29CB4_h+!CEN75G`L?xgVnYEj4vLP&NdW{o5*o+OM$@BGcGe;&o&EJ z)9ZW_*jTromm6B{cgF5FUlU$&Qs#IvGqa@%mm%h}S(z~GHY!xJH;G7@RaMHsq-@L| zh&eV^S_iyr000H_Tk_eI$aa|~!V&*2(UHOC``rD^Zzes1Xav)hOBa_E0SW7;4jo?G z)aC zV_M>Od<^JOmpfF5qccW#WAqz4e*;8Z$nXH1fW~e_`6PPO)OIr1ftkEWglvw(|sIxU4WI)V{KM_x>3U|KPy+XdVRs|8mMg z9U0)hg9?>e@i4cZG%kbG>5Zg#9^^Caamta)D{T>EbK!|pljvt}#im+gg}zzjCoT?V zyY3MoX_}Vl=v}~50Co7n4-4Qe0xi0b!^zptX~!l@dwolkD*3jDNs#!5R3v&#UOcS` ztm(z${asWlxj9_G72^J=g2NdwbQ+(S_$OHf@DTaz`~}A`F1aGbOaA!Y%tp9RN+G|< zuK~A4zgx$D%SDE`CZ}q1s^L1r=18{Yc#e~J0T%z-ecY_(vEAP6;k8?|@XfQERrr%= zW4?JIAtB(pIXk}rco6@h^^$23V4ihNt>MF^r5I)D0AF6g7u>q<_ODWRG2JMuN0I~L zQN%cn#fm%PvzO7oZr#V7t=b1oLDevzx1ks}H&u$TZPKgUGYv&{Hd!DC${cMOmM^>h_}05OKnPKBqKkPdGdBw^%)ft{ctU#0Qm{3Wst){Puzf4faJp z4>0mL!ZM>bQ)%l2dNlD||HI2Z3U$k}lA9w0fv^2|ZQb`iM9{|fN>@wG;sUBgA{Zbi z`;hxSdW%t<(Yh+41Qz@W#cN)gwFoYlVxIPbh94M~LM5pqFReI)3Ej=c3hE7^K$GHz=+#M`FD}gLS>Hd1Hu=QmV{4#*sZd-M#Tk9C^^yVw+=HLI%6Pw!Eq1G6sV#qJa2#4$coWGGQ`?S8 zxq-X%%cv#au&ujolOJa4WVsRlPl}Qye|0kz-wAc!v_jTAGK|uPqK64hav*hFiv^QE|V0o4vE?K&tUm`DC zz2ozQ#vXM-2h)VcV-v1-&^VlqSKM_RHwxRRN&wod?h-`*I#LhW1<;HcJ7!!8oI z)}2%P#IE1c6q%w_uF*X$1M77Na0JcXwMg1UW9k1@GIbFNH8Z#pS`df-wsohcA4F$) zCtCb#nQJMSvj|_?b?FkTVnVkCM~w!xsE(EH;QFt;-;m?G5batScjoc!DVoAq#9&PH zz4mCFE7I{FA+1CKq!lE?zX|P>3O}L8jBS!h3!89w^2f{#5|_v0p}@~)w4K~q@x9!H z3SVS5LSGFzB{0*<#@-%nhkPaLto=K8FHz_>nYQ=V`-MgQ_X=c+rfS0!7eR0f|x=6>XomT?}-*=(a~2hKA)#4}`72j@3(I`RTHYo);z zjHbzf%eKbbc&geocA^+YyXF}0Q7Tiyhx&$`Mn%)-Sscg=(K(#|Acd=ep2M0mhMA+( z`_8+Y)|?*Tics|!YV?iKgC==(a}wy$ZIXn3&SI)d3zb=eaWyo~MGwH>--p-uf!BWd zyby2e>`MMMqjbjTUvhgu8ut(~-DRT=CQ}(_9tl|?9HItu%=FPoA`PnbN-j=zcDA{m zX60ugP7$S~62PeTT@WZHorF*8M<4iO>D8%~M{|Y9 z<8qXt4?eL>$9hBR+0h}n!*Kv=hgx`4myT_jLyyZTo48L_I*(H0E`GqFyro`k+7j|xD9QXzJ z0X^9VI&L%}{{!CAH0+Y8iIoo+`I!MTzhB*_u8-ID_;sqCw!}^YsA70Wa-Bz3A!N9`%bf5oB z!qI+*U`l);5O67A(B)5F_-Qi5#l)<}dPeUm5+l6czD9hl_*0KBRHpv5o;RBKE00=LO)^q-LDC&EpWgUoY$Qpbm7Qd8< zsQgL!n=d63ZG&wpK*asm@ZO)U|4kn}qLN)b7o7=JF{1=gi_FUAvNfQ;K@xrbJzKGA zB!w(KCGq+hxCUbq@EulzYks1VPv0U0Q8c7pCX=^EyB^_i;kEf+ehaLcEO7}^g~49f z^kY96I1W!kH2`-`#pB&rI|eB{wZz1!lA7u&^lh6R_=~^q0^cbi@1N(}6G(KT(-B<8 zqMvV+awH&pvJKm)U$roi@}3q&{o!6a<>>I?r#8?TSL_p5U& z6u9ded1}JNeTUPh8%9XsigRa%fb`|}Sy!BSQaMu<@;92pDqvcC&w<>g?$2|TF%?RP?VefEV zn$A6N4J!wSX1UPKGXO~dwY9q{$sVPKRUkPG^~nx)j%zrz7aF*=4sCO2P?0h1V*AR; zm%O3kn8!vZ;OT-j5+%FBUfdT?9>rM4+P}c980N?4#Q0+KnjpSm(H4tzgVZpvy`v4I zireC@R5)jz?ZnzSWP|$?+^mrU)*%@r2C9TFx=*o7*Pz8n+rm7KV* zaXb>kCXimaM_wdcGcAU^w5VuNqO{=u6OPRlRM5yS{*qa=KNtCAlVpOAH%{FfsK^;h zsj{`Odsh0!v}xg|h~3YQIBNklUCPA0PoYQZ+F%$(4LXvdx2Veo0w6M`;plk6_wRJ6 z)?yZYJgNiq6ld`g4|s}-K$hlMQ`eV|bko)K8*aHPZVhV$2bOgm*oSb(urz z0N49C2P-EZ-vBD5e|NFcX-&)0dVf?hoU)3_MgLnOK~8AkUOp6O$GiQ0kkp{{iUK&A z_vXGB@ASS^1uS;DowpsQEvtEoF88BDfG*#8>%rasB01mrWYy;1U&piS(GUSP^hWfL z{~o#a7wu-3EdaH@t_JQt+UoWT3`LZfcvW?DnTO}$8WSYCg&=;_Z4lFJbL+a{)TP#=Uv}5QW93~bIhz;o(=)C|K6$k`i9TY?#AKVQeOKxqD zZJYa!uYFe-aOw1yfxL?2&+g;}{v~Ea^I88}->vLwlQu3XIycN_UM4!@8By4G@SK+d zbxtAo!EF5My~NX*%pbp7!^s@cJ^`b96i5VNMxI!p26KA68$@a&&OamZS#}%&`bi17 zS>)-~=+u;;ec8^3M^~<{MJBBzCO#f=w8-VS*4g`Do2}Q;dw;3wdNu6g$iY_U>>MNr z;+(I^cfXbEO@GFoU$@iy>&eCY zKb5lV)i6`G16OO`(VBJz~^H4{FMg|2L+z4dpp1wK5#pB~w@@S`} zXXa*a9UYMv`R`lIFU;$-`-dQ+S^^ESQ@27c7qokM&D|RxiD}YC~tjJI)@O&b0AG;tNrPR$z zphFi{;?mnQIa*)-&e}B5Gt&NCNiJ$q!B(#GTNh)a`{!l?b((wJuE;k-(35Y+rcPDu zk?OqO4DATwTZHa}5)%EDl?o^O^$2mmKMPEkwH+NYrL)BhK0-W(-+5v|*qJI2hWJ4f zvU0fFKevAM?(hn|!T8@q!}>ST<2iqDa&dt=_~q!Zl;)vbun%KPHI>?5{RwuYz$Zdh zF>HvvAD2}74Z#Iy28%VOw*A~SVBIh zzsN>-xg>0sJD`hnk36cAarA7MT)B@Wq(eI;{%wN(;+A%v-%8WJ=kd9I$oT#3*GA|F zw?u-$CE5-2jr@#EO5d>)X2M*|k0LD8ZR|0=^z|w?siD51bZ;NOJNX2d{&0Bj!L z2zV3XijAAqt~J!V4vEL5IS<%LBS$&e)$>teNQ<08%$Y)%YKgR#1A<6RU}i?)sp^a- zb>bNpV}+VEOQQC7i@-10^c6AcnOU-v= z1i&ia~6%7y!JA|4GH7x)6=rg-v>pxWepUodsm-5BPJM5p)sFF`# zAKQ`Ds1$YzdAxD(KMSEe%XNCi~qzE6Nhv0}_vuN**A)hF{rl+sFA*^T5CWOIrt94a99%Y2i6g!?u^A_V>K z7?qk%&U&DyJUn7U$yQU4gDVpLFWNR9%f46VL%?hRs4v$X(|3yL21643f6FVNZm)Iv zkvgy)lG@ojot~ZV#CrpwUqYPjfj}dLN=7oT2-~J0{g^G?80{3=Mc7Ry$E1PQ2gxkD zipr{gR)oFWy_P+rZ)-NL4Ia7o_aRRk0!wqJIgZ9Qyfvxm~0dk2wEe3uJH6 zz_@hHQF!DODp-Dd+~Ytz%r}_uW>G9}woh`@Xv=%?YryRqakTr?l=+x%Q%Kz@3VC$l zF%^zI+Tt*}DIFC99il@6O zkxj<}vYg4JF~r;bdJ(VD2-|lY0VpHEF9vYMgMqj}=VXVtTu%ShW6EKhDY3=v+`z9` zg1+ICJcpE!Z$gNvo2fE(vMNU!7p;p&2RX4(B5aIjQ&?thr07qLuzz+$oZkATOT zF{b9@eO=9*?XI%9{%)*5i(4b3&bq9A>TT)Yk$Z?S&d3+=<>?x9ndgy0qAT^FE>!6*`Nn@wT!ORPOjYLrys*5 zq{WXR{UR&z7NO$jKr%uBtyHme3VjhMl=CE09kbkPl;KL|zts1$nmjRcL+7HhrE4W~ zwt#IQM;StfC(C7%wtHNy)-npBrgp4EoXU+<@UM=5wy`Z9A$-)n39HSedLv4%1MkbC ziYLzn7?~xdsHkaQyMKPSb8=ZxH_8E^U!NBiJin} z#V%C)`y%YYSJ%FJzX3lyN5V6%TKrX1KAvpj5%wxB@w_y3xBh$!Nw~EWJ?}@(5}7b~ znX`i0ea-K>dH;Ic^(+7cD8imkJnv^;pCtf7%ErUTa6UbaYd!@uhAFRtXP9r133kU4 z*$=%m)-f<|9#O`j)ZrF$zIn`>irQkhD}UXp7Ib+MZ1BN`UAFifzjx}qN9lUn;qcy! zVz`@c>YT{r0UFT;|K7B=KTe9YKO9Uo`|fc6?>K&$^z_=zw9+v&WXa6~z~%g>Z3cr@ zx2S;I(-$@Xav@_-$?4W>2IPiL?dSUb=ackw?2A1+j1-UhrPdU$xaqGW7+b&mesKmIt^q0!Uh?{!;| z-sQ4g_4&rm*!aZc?CHQq_26NRl7r8}6KwMf0$lUEI2uw^?s4at@bk|vt*$z^>^|VVPQ5 zf@}v0*OtFe+e0pQ@tr!Zab~xY-Llzc{DT|QD7zk*0gBz8_kBfGH3aOE7-buKeErGi zm_L*2=@`Ijn9ufaACHcXIQfnC<||j8;$QD2bajo2Yw9KzfR)5*GJl9zrhKhr;kb}` zO7gYZy}j+8Jq~Kn;S(kR^9lhE;hb9q+)#S&q&fjj5|hBjuBkc8oBi)P?UJ`jD=Xu| zp%5MJdfk%P9ZuXDpI~#o`l}9Pply$rQlX6@3!;e@qlF|;p^b2V%IU9%8vgO#Bj3eg zcYe78v5Q{Qq8@DBC2zU;KY*7(p(+|PtTJ1ZhdR;!AlriTR{dcb*|o2Ka^n zemDRG)vP74=tPfvz+)+AS#9_JTAJsRWm!HFJ3yKv1Wn`AGGWtbP6) zQsHoFQ#w|7dDv~PxjivWD(fXyOE;o!T;_%ksY7JLSalVT*zhMu)O)1}{Q}A3@v5~s z=lh#KUQ0=CdT`X?1@0x}SuA631@C8i+?gIbh6TEVd!=}Yk#{O_`^fmb7kusO>Eq0@ zDz(L{?-1vm{;2HK3{n+QRcM#Z9RfgW67PqJTG1}MY0B`8d+Ib>_`7BJW})#5mR??a z^wnLm4Fk53k#|HURfsm9dYA=LDlAonwcQgB=ea7yo~VGvpp-q=KD)vZSH5W4`9(pN zkax4JbWxWEy>f*O0~l|9(zgC6PhL;ez~0eor2A>uT`N3Ghr1spg_G14NU6Wu;m-PN z#&zDgL1W+&QB;*$mc4w}J5)-oL>4qtk96*ymM$=s6Qh@v$V?!Bd$5_z%(6L1-7xA84vq6h7H1DiPymr&2|D}q@w=Je*b9}|`8rfr%oOG8&*VM;&RBVXrINC(eX^l3Vz@v#cl3MZG&J?!Toaqhd* zN`iRrKY)B92d(wOL8Q z-~Lq1Iz0W-v;kQ?ee{Dq9Zd(fNGIq>*ZHs#gLQpe_^Qopu)Uy(b zm~?k9v}G=d;(5uv~gg5 z0fAv|!%-G6U_eOC+(!fyOJ_4<9CbA{QeCjUY}gZhsY)(wG)cuQE?ie%Y(leS>a7Le79Umptmy@e8kN8Aov`pkoVC~7 zI@dIejgA^w1*bm$N~hJ2)XDwb)a{ulEEdK)w)07Y_q{2th{%fDvP1B%p-Zw4wXoBc zt-x`5*0q+t+?|!*EEM>k!n@H1Zd9`M6;SE3rCvH{LBsXsQ}bItuMPiC3oyywnQ(_@ z{_+g)B$<3gy3%QM%E~don#DAk-_d!vmSa&z%S^qSTpaKdZeq08>-94*Be1OB&HPp3oIp?=w zFZ8=U;PZdE%&+U{n0R;)rUI14n@vtnY1(ZQn-j9aYwQ3=`Om8+fwky=!PM%aoK@tu zaN-PcNpvJjc7J>_e=79_w$`ifXvr4s0sHudcFhgG*`2tI$z1A~OU-^OJAU-2K1H-q zZ>tPCm2vNY8zPzZ)8g_ny^7hNr}Ti0huFjR>l=L}sW5<|1>0ffS{&Is)HK#iPVCT$ zcV2MGzoE3e2B2?TR-=~Dp>&SRo0ZdbrU6Y=iGhu<5P&=Sy{6PX1mDjFU(sf*p8qFY z0MeyTIHS&@^O-Ion`hX==|8y}d76kNB)WATUz48q0`#PCSN=m z-J>bOoim>$-#x(v-s{vctbN*b(?Olmvtlx{s}{~x7H?jM(=8P-7IWSahqv{ix&10n z<1Q~=V*o}`oACZ^g04~yagu10LkSOnNezYQi;y0}`OOeuq%|a+&{^R0w@r~1di)B& z?5@E|_(|ycOHW^+UW%B3>%<$QAcwVPd;vvK@xM7ep^|4}h7Cnogc7b5|!ImKMZMiC#LJKNGVXYG&d>uNexpitCWEK^!~9$8eD5Y*^y zj4$jPMbR?(t;VMR@lR$L_uTpxY4y7(Ruj!Sy8pd?5ZdA$MWn;nZ6$9FFo|V?z@=-f z%J{XDS;*-8*AvVXtb{e+3VA0~$)#diq*d7{`@)HOL0D#`H$e!r-ezW!0O$vRX8KVddczvB*$;`}GoQY_AwJI)6h5-U1_;4j0HoDAdI; z#*zKaTVRmr`}^#Tm1`3=d{5M+xA+g%dentS5smaqlsq|c6~}@*o;QmxF?hUrw2coD zy(m3w>au%%-8>MneIpEeVu#*9pFR2+oQyrMt_sE?PNvFV!ean z1xm+O-l;I{{0^|4GZgY9Uo5}uUX=dNJL9uK3Pi`#QX_Ax-L7mQk_J+_?h3$PX2MnOpP%@Y>p+}y06 zVMFB$)L7FRX5%K1FZOaliGfdspUKGDzhG1JeVRS}x@L!2QB-79u8A%aGr739_-*Bw zCXqPX1#(X>knV)w?CcNEgk*{f=<(5wym#J-?wpVFOsQ2b+?{oJ>H??jTZSUJLONpA z1haEaYqI14=@YFn%nebp7DR4H00wA-23U#`Po;3Vxr9c5_h(mLzS`>kRlEFC-BQt< zZJN3Sz-krmh>TNYY>j6oi$1Pu=7>Wwu483 zvBkraBM8Z|>U zI~@4lt<+w|R4E@Osy#t`ub{@A(Bg-v&B%#ZY(RED2{>_pYWQ4j#PsS_cnv+Goz%aq z#pwh0w_)H#2>Z@zW|j@A&tR_Gx?|I%thp-#G>MirN)A0Ni6Rfs&92UZu(t8pQe0~g zg5;8m-)mfSL9D1`wY$k!dy)>Y);w{hgTHcMoO(@aOcU!p_s?ks8YdRjjEVeL^xpgC zZ?CR{22oL{A<~K}$!Z+2UeBj~&--QgQuaEm!+u7Lz7!L>a zox1uO?7r+@`z*5V6uyxtSvjopx)z4;@bs^VkJ*(Qbozvi>j8)p?>zrs-fUhG^5ww` z)vjl@Q-iKS;I3-Tw1nDZ&Mynk5Cf^{QOV8r1&&=qE2r&!Kmw(Xu5Q7?q09ZnyDFo$ zQNUZLAIlcg$hZSE|4nEor;3aLmzV`EuurK#tg^uo@wg8ZgL+l4=E=>?Pe79oouA9}@;pDkLX1aJ>xW+n#5U)qXjlFnHVbJcf4%hmEo0e2Do~_K2E14UhjWfILfi_c z%GdUM1>4edX8M+mrmI5?Zo^{A+;}v+SFQDrs$}5JM#zF{5-6 z_nK0Qv9#cO|04_h+zF=CW_cIfE$^+OIR6GkS-)^CTwNjJ+dI}z$<@!rK%@ZxT3Jly zb9a@bs5pL!blu9dSc?4kxkm(YO$ZEjEx$5Y`O~S#V2fxyQis=({|Oc5|G~$PYD4lq2_aNkfwDjp^?*4{3ulo-(%%kw z2GXO({=_ut(=tR?hOF(SV}fE(dk@W%rwI&BYwu!|sn# zX-)s>vovcve``i$gt!seVQ0Fxbg568Zf7SQikKI4o}D0-HOZ1?4&o;%1J#hYJsN&5nz~x$jffks?QoAg)Q$g*T1i_nYf?|wwwcWN6vUe*+(;m)@>iZ|Jv z{?l=l^5{>(;+wD$?kWB-y`n|eIdv`YzZX1{j9-!03!l0aHP-SA_yQ$(IaIwtUrg*+ z>zGt;$4GEr^q8^=d((3%%AAUks%U|9cJ23Cbtzo78$%nVWRZz*M1JEya53o_(t-He z_uRdJ*EROb<@Nw(anD>d;ptgatn8}7fWU)o6<)WZqZNK|1`%LwD- z4Q7Ww68ohSM-v!xsLH1bhjweOnPyC4Ix(V(Y0@xQLRaqev8`zd!v^Xc5A&_?doiS# zkunqdHB5?V@sgAyMZaV~o{Gd5n!v^RKeB$GF5#EdmV!PY9cZAzF-Qi z2444P^j`=Xrqheu8Xb{v95=f*N#EVm_JT1beTvJK6$JLpumRKxa8_@o0}3L*g}ko% zvaJe;8v!5o>BaJtG1$f?D(oIP&wrOBcX8XeFA<%6F~o5q6GDpU~Tg56v-iI}=SpvkL@z z3>IY(WcLIMkW);i-5_(i4_$o4Tc6S)av&o;D=7p(bfRHB9ZSvMY}r8sB3BAgFNlSl`Vn zhwV6lJBQJLRaml{Gv&<*%xpnKMB}ZeKL{O{AlFQa?AorsdMOsC=SsY}mklp!BnkJ_|v_JxVIPWa` z(6>PUQYA2WmaCx-E2d=jkj8PXD8I;DvU=JCe2GJkGos zvOO>Vh^sv0cl_!ir(;cLT}NL-`2wdcP<>5km1y zB3wX@@^|v{)#(QI?_s&pZsG`HZz|Wb-+qquVD2~qet|NBIE}S#=jofB*LwC~!E`6?c|lMqEuB(b(!N0bDa&c+FrJDg5Cvi~om97V_06!7 z4T8BuCdvGmMBGk^WE6K(qh9)lQ;mD|jeI=0uQ42Jiu=-p9BVZrQo(6qEVYuRVw|IQ z3%p3mW@mJd?`csa>J(pM9d;}iuRdEn*T1fX2Fy&x?X*gFW*k%E&4|w>R(sYSPCl zgKcA}u+%%_wJ1=e+SUpvORr{Qeoz)(b|%r+fEN#b2Q?`Qa*|0hoo%a?E>K}9Y{ezw zN7OT`iF@IU(^>iXD5NB0@XC}9292V`q%yu+2T{@?cP8B_B4i1k6c))crtgVQ@RrU0 z<#qq&nlxizBRLb{Iyu(!izb4L&_0o9@tRViOCFJPA!tZiEqJRp9f{_nPtx2qAF$F2 zc&UiW7ZW;fj&o@Xr0>(QZEAt}?h1;vG0Va~KdgyA8+}wmKktCsK}9lsr}l9zvN+eG zmiB`Zx!odR&|4qgDLXtYuu{^WplnuQ|a;btExefxc1(9Psm?Z zupKm;F}h6avL2z&-c$WZ{X(b#4do}HgS+lt4>6e^JGS}YnpgZ*WTl*3+Y&t*z#(A( z6!6Fh$kOT!r+|P`677|bm`}$)xp{7GZX)9o%}=m-8lL0x9&M6~U0hq-`@0V@^H&X) z_mkW!A|fAM#-Dmcr$jHYD1Gm!V<%9a{hiRD94RQ`BOiF36~&fKt~&PidOZIr$!-K! z`o`ZF^VaNaKtB3kI8g*}LSf>V&|jUGvbX0`wOH{ohT^)a_*@#5omez+sssP`}a zWxO{S2OjYC`MzS=j|7-ZJ4V$4n+vdsKi7U;<74{e^Ta?HUP~tzyMhks@y$i1CXMn; zk*@@!Qb7`*g0~xo_ijhe`n1sPrB~IFrR;0f9_0@^zXw;bVW%5&`O7wAXp^_}x?A5R zUn?TSPxP~t7hj4pmo8=Ub&YUOnAv;9GA=m*BRvf6ci%%?Y9Clf7Ns7pk=@ijXu~I7 zarU-G>YJh_>CaPDN-ddkE^x`!S3IBZMGDz)6CK|t*}(Zb!(TVPIES=%`51q9#Cuh&_OZ3U1ez(wUzM$CPUhn zSU4o;`Xq=+8K592)H9OI@J|y)x=^))KK?=c>FfhPY4*7C)LH+)SF#MTZpx<~%7kK) zDX~{F0KnVK_rGWHl~`Xq*DWcDr}-R=%QR@NRnCVqKIvkz3kL*YYuSGOo=4pn?ub9D zgnt4k>n4kDtsRaz)yqv|EUcgrth3Pi?T|%B3NpdWdX6FDyYHjT3#-)5ING}6NSA*X z3bt-hs43hw|BP|n{v9{03P$L2?50DC zo;v)*2#1F7Soh~Ivcn;e3akYZQ8~!J1>OoxO#pxZf+1R)gYJG*pWb7`(kbZp(dX6+ z!Z6+ckG65eJO)%d!Bfi7 z$U`4l0ybSG-XEI3NbTOUV1wSvWTmKB#}=p4$yBaCBu?gt{K0Ei^ z$~k78WqNLw&}cI9t=t4$>I4%E?}F zxs?BC^B&FrkU~*(@;gXLo>Nq|)xGH`E=1epQ`R6dTY1QFpL8|}c2+IEA|^NRxJ?Cm)>1`AA-w1WRX=&@T3k_t{PO^ zu5k}?5FXochU@~I#1kK!O7x5Hsz9_ZXwl$1AL;7&h+7S6BvSb66zEZYsEFMNdlyO+=%FzO+TBH zg&8CVJ`+iu6aov*SS|cA0>(Ei$a>cGZX7IO&^TbJf!9E;GRTX-4{T6iNstTV*I_$L ziT?;sq4+t0xjz}#2SYWufvLk0bC^^6*TI#7#zI8hIC3Bf`Rpk#=#g9j9Ey;-H=C-l zeHb8P$vbHNL+fo(mSncU%@=TOO1&>(8`PnKy)AtVwk(Yt96R`)2cj9u7k~eu?y8P` zS`U+U5iXcZw!^3g6UqOtdUdQO`k})9?4fK?l$=$#pbAKnC}VqZB8BxlanD>FE{wdS z1}8Sq>}WS=vR8Pdp4Q#F1(#EtKQ1YnG1@>fgo_HbuQ7vxvudLECqm#niC%WC6A`@n ze6tW$)CZ5oCf!a*1VFJ44h{k~T87yyxz_!`qG@Yt#x31`HSFkb>FqckZg4VH6luja zlNBXLUl9r09t{a(y~S%Y1fzjHUW@s&Z3FY1ZK_X)(PY!s)>e^Fop`ia{iG{lsK?$! zwefg^Z2lcBZB6Kcv)z$<%?AG&z&@Ua%3vs?NB+lE;E*S zb#*=@Q)ixW&WH5kN#g7tr2H2y$>4R5a&JUD*w;(_cysqpsoUw7{g3uOs++n1vN!;{ zS}blbpm*)O%soB3npG`K`3^e;R9XOJrF3e%`518PxvJYC!{0xnnI~^$mp!SHjHo&5 zd%a|}FOW@UB-oER6_Cmsy<`A0f!dXucca<;dKRy2z;5K{*Aa9}xHR?-uWt0n$Pw$l zza;vh#mvgaHhbcR#zGB1`?)M4I(EZugFxWXSQsXej*;H(_J}6Hzd2i3gt77|q`F-E zHVytJxBdkn!Fz9qggj3~r^IhXOI33%ZOx(uK_fnX9{l_^j{G|Moqe(83yXj3Il1`5 z_wJ8)v(3vO%wpUl+kQ|u(rx;utDn7F4rw_Jw#t)6I#VQHq^h>Grbw^oUUudcCiFFtx1 z`8{$%t}pc)(j*d~as%|!-2D7EOmhq;4!3!f6zz>w$ESaWk5C|AvC|$uO~(FH{P7>h=<@4*qcdR?HVxs#mF2`58U<7ratgGUBxu%mFD@^JuuaG3IPzZ7bvUkaY?o8(h{a_P{Cf2lv+0){P?T_o1Iruk;M6 zZaH}rcDC+E%bXO_c|3@%HN9Uf_PrUW5X(4cOo|53LPnh0)R@!nJWQ(gm=;vzzzxU_ zi3%xdcSeB(7}UN+S9rZLif5@G&8CH^j~agoQ_rHToFrHxE^(n|SzWcUZT^TD*?ekp zY)lE}&Jvqd5nsIl+Y=NfV`W>IaM#jO$36Z!4W5v+rh?Rx5=TB*7c6prK5=7P%J{BP z#^wK)^;%)(FI(_|R3*wa$@U_WRDyKI=KZ_&Z{ZEW9z68X%6TEnYmh^9&OVzs6q!M$ z?Cr0yuFu;#{X0Q2F<*iZS1ZGKXWfJixg7*Kc|wpkd5c#L!4(6Sez^E725JpI31i`l z9^<5)dXU+O3)M$KW?z%E)_>DD!a655`XY371c#rV5I{))?}@5$EWJ0|3)fEm(FiS? z$=rIEoa7vFY2WvRaVB2}w>K8kuJ*!5&x%)Hgc$r|?f|fbbMx?oNCNucf4v(3k!jQ< z-?UH+JDok1rvf@fln9D(hI}KZUS@W~pfUehllZxvnt63C?4d$BJX|)Re%^Q2L7a z;a-K+CAM)i6&}TZ+~K)d3>hLI{>DJH_iJm^C-$bE+WW^9oF#l<$!|OeMO*nlk;UMZCt&6OX2un#qEeEQObBU7rIn@gGcPzdbUX@YKGpjc6UQOa zzIG~ZY^mfvI=YM@@p?Z62!(yONMY+!uTK&eLjg~QKvl98Nt5H+_Jjbe$fz3dU;X0= zX7_jTjp1p=hBeD>)&A5UMzUUv_xzd37+cDQj7+kdDF&S-v`dwdWi^0#5Cw|Br9?tRvwa7oMDta=<4;%A(E9Hk5uY8F20F887$OhqkA=fK ze@T1>YlqQTEp1K&*l(Z^CjB=IyqDZuV#1I!ms*Pn@EM2TU zKogZ5qouEGIh+*ZpOO$Ac_X)Q`+r&hZH|&;Ynl&a)?X3z&ka@d8Iq5>jZ>si-_^UG zo{OO&w*ORg@Xg_@z(<1bJbfEZ4V=a`55%U#W})Ag4icy(y{*fBj>ukl>hx3o zk>Dg`%GgqSZb|ht))Aut7W(aX++Mo$)w;=V?aPnbmxA zosnj*L^FU42V#xwxD{Wss;1-FlhK|lo3&;QRX|UfeCyIWrJyel) zT#!YJYZv)e0gFEhZ+T?rkhW++j20BG^R^(FT2B5iZcU_EX7cH8%Gieszdpxb zw445!|EVXk!&LUmD3B1(^tTmsFTtz%bUV3Fkm2yWgVziODe9b_oc_SzKAY1SW47~k zFlBt71}bj;A61@)!cGX#m}1I_C3N7HLoIKYG%OVTzWB^HGami}o|RGxE!xH)QL^lo z^ncQv(Rxk9-vtXG_437f7A`J{Wo1k%1Epw%32V8AR?0LJvup-LlQ#Ror6WJ~06c12 zSc5%vFdtTC2sd+Yr(G3n%KY_D?Dqtqnh*yE2Q3&MKw`Wtvv8j`L9i1?d4x;ft@USIX^_fdN_$d2REX31O(7PyRj z(Z8=#A})UGup7Z{%RbxjW>3_(F@ch{Yo}bu_H6k7*aJ%i6L~msW~On5Gvz% zRQYuFuGiZa1`xjaFINFT_tV7YCKJF&=-J)e+yG?r`mCx%F_7rou)Dq<2u$9yhqtpI zbnGpQ;>|oL#W(X`hE$h)&JvWW+ocP&8PH{JJa6ys3gcUV{QVH4DU!I058ab%(Dqx7 zS82fKeRZH)Qd%-CSJ%-naGWi04@~SNS3Usm`EqRaI(V@3E-RM4&v|%q5(mgxGy#J{ zdQ7@EOd}LqCMPGwBjiPVZ|*<0t|9878rn9Hj23@N65N5VCI2_|U9O^prd=-s6&E^6Wj?As0HOaKaYgL3Azs z$&wSA2Z=Fz8^1-2e75*5r}^{7MJMChy?O6?5x#HYl}^NjCt z79947y zvZ{QgC94QqEL5)fMvZ%?dtre!z7oX*!2beZuh`wQ%mi9IZgaP5zIGF#p(}!(y8CX) zr&*l6iNvOM6#gGi=NKJlxOU+Njoa9^Z8vt(7>&``wrv{?n?{Xo+cqb*`Mo{gI_F2{ zSJrAfGkMo$pLP`KUf?AYmJmHmeKj@o3`$SB-_*_hCQCP`bGCk7V zQTzB!BYe0tW`l45h&uswjYLffHYXI4Qo>3Zd*%I8d6}L<>9nva4>Tk(qDjECgVcIUb#?Q5u&MYTC}mQY&14G@TZiPC#*6o=+%&_3Q6UuLptj z=SLyzBCjOO?=-6MGo(u3yPjs7q?a;DW$Xb&cVlVE)zcDr1*^YDLB0Ii2YS2Om z(Fvg-PEakE{`AF%g(k;Nw6VYN4L7%{Y+EtxLTHJ(2eMBEsUX!juC!G|XYq<#pFBD)Yl&ou zmNHwS)qgKlp-LV}3iz~7eEvwfF02sEb%ljmgYZ!B~rC& zWb2v=oY26csRRS_=)nVEX3rcsT?_0eaTo`AopZ8wL!!zu0WYrv2FCCie23dluydPG z5i)Zn){ZPW#I$dCsoXy=CKo1}ck?qBaS|(Qf{9S3HJofPx=)655Q`#|#?O75wTrbG zKzOng(^gUaSlJSHEpwy?;p0w)+SD^$xr&A=ihn6(FEe{_u@lK_R0hfvh>H&nQ~x*x z#a6=wd{WL3h9Zv>5UJ{$B0v%ofwJ$LD$6fpJv?T!H%Tev6FW@}D)G?2 zgSq3JGz8!3Bd)1kVhdZPK7@riTrTxjx;k?q|L-kyrVfe^@cSXDUH9}j?0d9`_633p zy#@d&iVN&3mCICNd*gb0MZW$B4dTdm_`VICx0dQvGe^KX=qWEiWQ~;b9m|Nzg7E4@ z&$nwFmoq&#+r-8tg)EB83csedJ-R#Z`|ki~Zb_|n(yx_-_BRtywUO|E8lfL$VC$Rv zwyraUQ-&H7qh)1lTkT{K-@MHI{3ZZh0r3@4M_@JZ4FaHQ$~CKOU;dRVaqK$PMxCrx zp^>Z9c8@G55b0q8fIfhnE$3)+N4NUp2jDry!>@l__PnrvJ66q5R@MLmqLpuf5cy=n zTh~b@)FqT>&xn|Vp`BM$t)|H6{hP7M%~2mIh{NW6=l1!3zQ;|k@(qw=gW(sXcVLX) zFZJ%Hn-J*iN+Fx~?;2C6gUP4dNP)a|Tv4Oq)AGOb8$GNmQL6(+lx+#YcVqy+_4@pV z_;~y591;k2rxoqG;U3!G4>&HrdcM3M6u?kJ4m5eC7g7`HHebRCJ`F1X1<9|IzR$UQ zExwE7TXLi;Ne(r?1`c1Fle!ZpWM<3)IT(cPTwGEX8TEbwYvuK9eAA}XfYNmAmG!UC z(9mQWRzlKBaX1%6l9MLYJyGlpiBx;C9u9MjzB12Wsc}h@Nv+f;vyG1Cs4<6WzDc`o zYWpY-Iv+ z&pWtrY!!8CL z!%h1lxD09pBG(4arR5dg+XE~!heT+tvIqE9;XMsIOiMY2UI`I{#!ht5ZJU$OgKkIZAkX#TK7P9a&IkOUZ=C6z^y z+D1ze!4ZG;hpCGU8Ni|Rr28i2Px+Y!_lK;ae@_hfb?xL4e{zl}PPabOH%Xy-ts)-& zWYFpa-xJW|ix{wmq(Yr4k@KDtxioR@h-*EASIa=Co<)Z6>|I=3Qo4AOByCc7n-)#d z(9keFQ0VR=;k<{Zs(r50c#HY;u-n`xzB}BstBRAT7d9}yI#KOz`O^vorfvZN3L>PJ zc-?04?ybudK-T~`L;y@pl{yN1pe;bV!xBHAVVcFJiM4BzIw!rw!K=PRjkA&@%9#?> zIvors@-xdujTT67Bx~ZX^%r<>{FAE zwo2K-Y%0n}nk|!#ag3wu4G;3mQG_-Woo!U?K=u(S)6W6N+J3iXY5KV?Cw_KQMu)0Y z3b`cI>{uQqP`c^&8>r==;9Sy`LQHJLpS+@$xCA639T3;c>h$5a8g~|cKr%DM?#eX!<7ta^0 z^2n%Z`3-tjRSNsDdzTjAe&kpS^GCO8k|`=qxFu+p=cg+tBto>fY~ySJH+z5bXw}U? z@*;KWsFkhFmF>qffhz~c<##g0vF>w*iUlw=7}HxOit$Yface!ai(N=xDlB9cj8v0z zQPgMHRo=tagx z?BgH;@*Fg5MWRah+#)&@G17uPjkl#Meg%qU-Gi6g)q>FIDcR{80>jH5*a5N=Rxm3#R88Rp;jrPC+pUNLhyT~j;T zqR>Hn^Jlw!=VpnwljQHj*H@GyA6t$im)1I7{CuXp!^=2;FFJkEY?fQ^2m)FM+0_;n z9`7g#Z$<$)w}q52T8L|gJUObW^oWJZvLvb0IeyGQG64_H=zP2y$=j|$rkky^#kq|#f~c0I`UFR^_i;~ zbF0a8AbWo=oZ30UlD$Y9782LE;T&+vvs4*HbjejO-E905E@piRiLrrdQ(h<&kmmt~ z-qHJV)>rKeE%MJ4%vjl6gMtO&!XjJ<#K{l!PzhATF(l6op;cag=4mh&^bCIf3=wbl zPe=elp!F${Rl0_6J)aLi2g}RrzqBe?I5{P16+xGWaTRCuU$y9?K1UmXwmzv|o3oXq zXJ?w4+UAb8^V5t|w-|`pP8Dh82yy(Gn9rVn{8WCt^c!jrKr7p=5Yot(SSw!;MD92oi%0jKf%uJhF)X z#8-5ge33qloK-2kNsj#4|68cAjZB&zUj6N;o8=e7mmyVUKTGyX>>FAg}Z> zl;MG+7=1n4rZ^MdO7g;(l_-ZJMW5^xO%nZc{F=Bd3LyoBoWIZxWl)J*SovVkIbm9u zJM@#+=Mf}L8Do6&)T9#0pgc_2C~Es9Xl9sctvqXNo$Ml?4q*{XGH}GtD@?L<@gcfc zs4lz+y!eMMd7FWDpLzulo*5o&PI6irLFc#YVj zu_8d zGB4tRTmw>4eS^$f+YVKM3p$pHWl7WP=D+pwhU?U{Ts5t;M}X1VoDIiacbzH%AZh=! zw2bWS?PU|jF1Ds0tuK_8pixZw-` zGu5+Cc3)YXn?SsZ=twV#BYfFkSe9@ioSrS1dG0*6)4T)*nscV2Q6gcl%)-bAL#I!q z!knE=JIOH|je`P&5(mpX-J^lX)O#4)Jd-$F9dhDyB* zvdQ;?U_Vb3Ed=lM!v5@d@bv6Fe+Ct&fLU>8jCGkPO)A@@fgxvUjq`=7BBC?PT^i4Z@eIBg?VG*flVzx>Jc*Tb3fhU` z?ZcAx36>Dw(YT&KmXM3BZ7eXpOyp>8O}nOeC2eP?C^AcrcM|C6DOD}Q!zXZfn85eBE7O}f zt25`o0aC@S<$$mJb`0T7H+E9sBWtzMR+%AL0|<;cnyQW>GVd;oS25jCVTd8^MV1dKcrD0m=8*jv+C~|{J4}tR`9^O=> z@b5<$G-4Fx3eo_cz`hnLEmCH+1fuXDin)wF3V9N)Y87vpVFj2Mh#iBlaN!_!m_#1* z!kV7Akq50WO=ilLsDG)whI^{Y?~#1& zfeY#v+m!Y%LCZ;!JPJ&PIRY8myPU=J(QhZ0%@r4a7s59Fmegl4t z!y-buS-4sImzK*@Y9iUM)sv#;Iw-7ySmYv7F)$-mh#1^mzD?6&6+`6BV@pBcV3Meg3p|6I--Gc|Dv z-EYrNs!EO30OuQw&)pZbpvn=8gxHHzk=>?^(Y$KLMwLnn%twmAq55yc#GgL9pZRT^ zjhmN+;AHSudXl)P4@;zR)dWDZ0je;dk^yD3ChqR(z!7d3B}7BnE7(%JlP35-?Vw{T zatci^XwE}3Yz?*phmSzR@zixREu37&K9SONI2%_2(jtLp%XEa#pK$9*w{jv;>=7K& z$IpW5Px2o}B!=RsnGmw@L5G_dt0_jiioweL{T@lBm&ld0h{e0MUBA?`UrqtXu2c8O z)fkXe#hDoRY*^n(#7W5e+^{-h^bq6z1XO;R4mbGyMe9*xJHGHI8u>Sk=qcnP<1ozo zxHk@;511-nQTAhED;N*I8kDK9Ikfa-UnhKMiC`RH{`-2_{7m^qje&^)oO50qJo=uVnS$@TfQkDgRZ~Z& zXz^tFysp{qgyZGK^RYuB!7QJu=LW4rA@`v3J@upK`T28kh8(9FZtp>XMBSF) zs~g*VKihP$ut%mQ&jD5c{rjy*yI2tGa;2=wVgK5sfq;MK_31{t;}wTBGV+w5;Sdl1 z>bPIVir+)DLd(e3G*kwY@oJaw11l(RlkjqwQr$nb+0!KC{mK>}HWj%g#_VbR`}ibc zyhRE|RlioM5qlybN{B+ z7=)$41@p9Nl&j`{C(#~~Z385^-3rdlow0OuoI9R7t?Xo0T3JR}!TKb}(b^|ZRC1L+ zz|#e^#(IIpnValweuOp(4ULcx^ow0|U?!FwvC%aR7Q6xRhtqCaOvCAeNYC~sDCP>a zP%>l&2bCwko)s8eL?(*90UZ7)WFNmPKB#quUfoi3yIH{a;`5T6C{`Z!zy^Ki{tSp2v8Xcj39sm%AH|d zyZ~@=1C$#3zrNpmrzm4~C}VKlZFC?N@v1vJ6#x-bw+etT0tO^J2?>eYmp8AM`1mg| z3WSvZzs1rIsN(d&1T!5pvDb6Tg!OrF^LXL@*~(?Wo-=QIFBn-V=Q>oB&dQ=rjW{V2 zzM=A`S(^p~S(TI^8^Mjx`>HzDn#moo!nPkF#m|*%GwNeMd{TvD1U9u3$!*#;hShM@LNDFR(fwBj$>leNNcj{QhbRtWfe6)JI_|XL6a6rC3-arWCB5KuD1jIDqBz9mZtZPd&Jz??5K)l@9k3lM-%e#m7xiOItIQMxHJ7)y#*>W zp2hQ*uO1?Ywz3gr+A< zV4X(|Q_8#xF4vw97i>u;60IJ)3PrRRN`|v%bM>69+yPnch1D$g-7garmHE4A>I;jo zy}+81G^ymD2ST)JbN3%hS3)AR?P`GY@%*7<^zLL)lh2t(@D^~w0Msi^KoE0~!=&(0W{nxqO+lNj?upbYp=o@GyHrx$nb$aW^ou{VkY~jXd_V+(kPe0GNi|S zxDjQ^&pDJxa7mQEIcZ?XnZ;2k{icXQutLmzR+Adh{r*0Z2j1Grw=T~YC0Y>&x2om{ zQxX1xoKZe+tn1{JV4mUjS|Jg2Nu`5HbVe_f=Fbimm3%;8$9V1y6E%HuVP%hsno7ii zG(cmGGTISMq*P-D!Wj^7;gm*vXeghx{Or$$h^EB-F3pmP<2%F#i9<76E2F_yu+$fY z4G~~UVWi0qK$yQ5EFO#Ce43*uM~J$X;+U{eC*dnl*AyxeEKDZ zQSvn@r(kKqse?sm0tKRdQjMobk6d9qCF&j;j_U6J+QVESg+LrObmP1#r9T~+FQ`x2 zAJwb7-&8be=`)c2o?Snca5lSs2s~VD?!UM5;^Cdnp4>THypl<+q3E@` zX9Fx>d8QTpF)Eb#2X9b&Ro2A!W)%R(+oCMlSa3Jv$4%;5hjZr3!@2#*y>;rMCU2_!nR~P2czA)N^kK|`uD-GY<8h`)uNH7rzctMh7}7x|M=@GUu$bC-YFpxNF(b;=*kG{8_KQQdwL@_ooTRxmgfM}3DRBZFL&PSyWZV*|GH~} zQ^S>CszAf6ky*$BNo|mVTTAS!`L`*{c(8!Jwh{H>R8Z3R8Z+4;+OZ5|#)g{|fHI*)=EVSsn_78)XfYaj|ax?q4b*byxb5D_t(>r+fs#L2KpkWQHtJAbXUFgDp~f=A+D&4^gPe zGyDWB2CWb04o5wob(`({ExzxZKC$0F+;eeR0UesOrW1BcHnsKj(JBcamy6owda-5| zpm`q1lU_nl{$RyJICN3SK7i;Fz3K{l z@f@ceN?&rT6>OC|X|pu)g^&ICXgD)BVTZ15eCyrr@pd`I1bC&?r7C@Y{=pp_Wmy4* z_j^d&->@OY;$OKl%g;viFvm_-=UgnETZkF>@pSiFTfIc>`FOQn)$$sO#GF?lVbQ{( z26DtmW@T6~vGR`Z^zehSa8yEdgn%9;UtrbRdhyYO0o&lXGx;ZT@~> z`yK*pg3s5Mw?Kj~+^xL408kO|0Uh3Xm|6c;qis&IXWm>4J46qjWN`JG{+=j7f@c{! zc*eZ^knW_7)(tH(07$d+LyWH3W1c(L$`H-*w28-r2vEQh zTDfcYY^m5YlJPxEu-L-$u7c}srmpn3Y*wZe*g}9)@Zshz%#CC6EH&K0P$R3m-$Y3EE ze{OscoAA1U1 zjV&3Jg@SxMhK@JLoHlD)_Z6#rUbjez(pz9Kb3@D&{8~s!O-@H7f=^cpO|Q=;8!w9w zkNZ_VVlTht5=!YmDJJauW4M{Oj^_ij*nYe0Bv78%tM@jqHw~BtB6B~Wd*w0pXe{n< zper!my5qRQ*WallZ^X157y3Jfm~ud=e6W<>*(lNq0Z16cKA~nMTeJr`UYL!Z1_}N z0~?PNt%8Yqg(~2{{fzb6RiazP%)Sn3aOA>^M?k=WhoG&Zp!KRm-K88s7GvJHdU|m& zdvXsPrhWFp?Ybp@&#vKv9Uj{+9Ov;F z)sDf5-{-*HM(nXv%h4026Aah_33HE3S$@ZSsf)^G^i_lLPe#cU7t#8~#DIWC4#^Qk z)F9SHNamI!EG5;f?XX*e^tm4^GRaTnh(;zs3@x^7vMCk(n4p|-yt;)=!gzc7p4b!< z6Dg2*wF1J>=WI){cNYvj$6`SV2x6s;q z6_%I<947WB?TT48#dwBrg;n2@A#?1W?4soyLqLBpZG26y2(7??_ zd0g$Mn`hu8wBZpg$yc=UMNyAn7#EUM15Cwlaz!n7mWWWlC8`hLNXza{2K|<*!~A$t+ry0xze^0?&`6l{)PsZ>E( zV0=*|W81_J7lK>U2Nc=&$ex}P_EX9Pk&%(W9EZN)4blPr#A@hpj~*}A0(ju+=H~u| z1BzU)Yi8GrjiPxAVtB=kCnWCT+wU5*CIgvCSm;VI&-yk*Gy)v23W)gba)4L`*DTe?1G-0Dl&6{!H__}E9~M$yV)W5 zJ#X@Ufur4KvEGfEI5jWxe=8_GrUsu}(O&t>gx#i9Mz9693jgBduFjjJb8xCY$l>|h*#0w ztWf0xX2JE~M(Y91RA4+TwsDLIv9orAWxJXo<;)5nV`W?Y=i88z;h5n_+~HaHRj!JU zK5OM>gYN{KxcHv7xpFZ4rR~{X{J~*Zk)y~1yC9^`BImVVhCT=Cb$4C9uwcnu_Q#76 zvzKJN4nK5G7RjU{Db=*r2F3*_UFy)K0KV9g*N2aH-+v6gd{XevvC~t!9Hk(|zV2>; z9yp-i_^}(&XQ;8`j-GGRHNH8PVEV`s8X^?Hrmg41k|0SrqXg zm{)?;qv0d|CtU-}Vwd}eW>?R^+LFmj2_Oh@VynGP==-c(>3vU~xw=Xw^_q6mi`jxW z*>3G}JNUpI&wwJvvSTb+N~JChlo@?+`@Svu4v&mrf7N=a(}FIq(%S-(8GF3Guih)| zABnTHWm&wgISJQIJa3l9E2$>{70A(1!-$*DV%CO`xCr1%Dbl0@l$JiJfNQkbS!IL} z2%dG01+zcVG~-&?c3j3&XUs6WJ*pi;Locekjn+Q0lc~{}3rG^MjkcQywYa%gC7U10 zKTV65H#WB45H~=xlLAIRT~c~`F?d^By)NHh0QzdOc&${y27qs{1W4SiFyz!n56=L1 z+iTMluuL(OSIzS9?Tw|g0%)k~?NCC)dU4B9;D7W_h~w>?$lUZwTwca5R01v|sUOVt zdkP0=iqxs;7Hrh&G(hO%YHM4Bq~d9o@ZHa*any9N((z+jBxdC-$!?_bahPRYAz!RB zON;wG$>*v-|19jXPLKcB%a2~=(8L}ymo{M*;oG3yXu|Ei^-eB=T+LM@(Q`AG^Nk|B zlkmZ6>Zf>Q$K9_`HFi9%f#pVE>mRqCMmjtywB$aeQ3&AA_Ccy}nt!%ZEq*&Bdkhz7 z($>2COjl>j0!5EjIe6ITG#^nHTdG?0*GM5wQI%?Q|1HqQ5zhOx`6y2^pO)n8R8ThB ze$xD&a(?k5P^kD4lR8!yYEr48SZK?t)aW)?oAAhGSVPwZI7**0H}~%5Re9csE966e zxL!E?8(k1>r_axnD_>+47Jn~5^!%3Kv?wr?uMZLrBeRA;iISC}tHFqCgq3K)RnP6&D{L;DSS7bb|$evfmr%)~#kkSG})P?7siVf^x_r zGK{wEHs;o>5W^Koz^bc06h#`$*tWy8L{Tr{2m&l*WVYUp@oFVwy`h{lVadMf&shbW`Qys)x5=Ane&KG`nM-H62PBE{`*&(ACvqgl8Owue72^6^&MSR zc{XU~$)wO}%;$dlh)x_5~cflaForyS{%?!flvtN_o*3?7%%wUSe zd5DEv!p0g9w#tXe6a`jIti0^~@8<+kc!m{nuzFKbZO&27Z%|6297^;Jn%c^H@jXi{A&rn_&D|k z43*v6+r$P~{2Z^w(|?7Knq1;hF8q~}XiP@-;TEtcZ!kj4ZJ0o}53=g$#8V|0Wgo& zdU>QvWX6USq+Qz+=ADX6{8Rv(v%WA?e~@G^@47Eg)0w(cW2IKpwoF3UU98@p+Ro~S zJoSgAmVG*NCC)L()A=WRAKtPqt<^GYDj2Xb1x=O46|s=Tfqy*m;I!NAC9E{xa(!Er zw2K}ZcRD-~lcWLF514WxGN_{G+fe+FcjR6oqSA$G8X`m!*^6)~Ob%%{K0zXeWIzwk zVf;OajJ{rwG^`!pv9IU$Dr3S7JTO%p!BU|b{jy+;NcUn zbTUnHc3gc~n8>BX`>Ls{djPznz=0V9a8rRXK5!x9N29I%+ln(V1-YG^HI~l*!6T@D ziq(4$I9kTm_1-6uxq-LZ@cm}^r3f&LTb44)mmIlBt-QP0Z7<4nqSBXhm)Li|^7QKjpVtlK$S0z{k39(?<+k4#chQkW$3 zHFg0@^$7Zi@Q#dBh0=C(B&OTl$Vqu_r=Lm$uxjP7v9&u{pr5GB*$0kKFNZrEK;NIk zVfT6LC9G+09S7$x}y>FQj&js|c2=J5xX$|0~y9>vAg z#m(*mjMH{a-`>E#^QE=3VDY57qhsQq_R-Ji)19|zdbWmBl9J+fQqfqtU{Ri{XKL!2 z3fRm5Wt%A?Y$uIu8c2YyNLcH>44^aU`9#xJbxwp5dXH87z_nUy9YyrLHEIxS9|&En ztnpnUK_~#_MqvykT)o_y%t_n_y?j~GSwTLlj(JpV*h6*f@iK8sIax~d_1SQrQgLRjHU;J?VFX?q|&&cd3M4K>X3 z-r#=G{1W}Fpc3AOBUL(ZI!6bZtaLaBK7IM@e66zlq`?wg&(jM+JKq!J#;-hep|FZ1 zhtTXh=KdF{>3@C!O#yt zs`r80_nnW{R82#Rr$5){L!rsx$ywm}kQ4wK4n${i0^r`CTuu{kx?8{af|cONv-{kD z>Rw7%z$j)7dU1b_RTO0(E{~>6T9n$q$O9qV08AeUt1eeGt^+NGcQAX1p0DboJIyern)00^#dq=M`nOJr zUBR`x!@ZL9{*zlYvk_Sp^FZm^Q4m!`_%2MvopOPzLdV0T{L@{lSEV~C%_4dijDHG2 z_-%EKtcnE_0?lobgfTr&6q7~RtyhxM#%PSO>i`%%negYKns4l&co)e+1Rcl)EVS>6 z;9>zKs0isL9nJ~K=G_q+^Ir@4JsV^hQQ8@WZgRG`ukxMm=veJt);9ZIJsmIwo*GM# z+gwhwhw$2SjV?+s&rJ$UDIV9msi~X90p)76%IA*uef8sR6A+cOfn}H4M9x0&4BdR$ zczC>nCbYZS5qsZZd=J>4ExF>41uk^Q%c{VWG@LyoIQTQ5xek~Ce(7eXBNRY|{kM<; ztbQojm-mew{enQ@4{+VQxS0U>6b1(I71`DT9WKd0iR3>zgx&u9;^Tv_cdUZIOHv;e ziqYi=c?w`ha=9WY11&bWU6BA27i@A~pP~iQxP#BTjs8t%tcit}Qi+U7G;3gcb%<`` z==sD~fQYo_`{<`sAAlCI&`m(bj1`ChRf+~*g7G-o`6{FPF@Q@)pFN-@)G4_49_abn zDflMApz9F~NDfg-1hE{AX_?tOA3(`HC&Aik9tMm+2aWr~58G>C+yB$oGP1qGnv5ai z%M4;!Abw!WZPO+7(iwqOHr7eFb4 zemQ{dwf}hc24as*o(~M10-Zn~Py65x+xGsGs!n;lLBLUSb(8xR^#QySB|x8IbMx@O z;w263t+U1rAg$KaUfn&O3G_W&Z*@aR=P0zU633AKOWYUHrkc;;lxJyf_aX`!`ufJ6 zjnfzUz5UyPyF|-3deRZzFX9?aUhWcL=xHkZTrq>lN_sFE`jta6HU$QT#r?Z@)S!^u z=L)Dr15Nfqs7{mDiD}8isU%*B)_sYYl?)4eq$OCih>?KBKH|va@LH7Ljd$$GEt^n* zc>S`zhYggf!&7g*9GDZ?4wGeh3*j$itHFs}%Eo*tU z-p-tv+Mb0;XJ=Fk}C{$+#{@3|B}ki($x?NxdS~^Ao2qBP+|5&e8PFH+?T2r zH-&QA=IXpts)YsoZ!8`uExQ?P4`)Mf!^Mr(PPWzqIs3{#nRTJfAx1NQXsz*Wy0n;d ze47*iDct6h+G%kLW4y=4uVm>r> z@Z~&|vG3Xbvyq_Y>tlDIRVoNA0I=oQthG*_@wzUpEbsr_Ea6)ZatP1cxjy^DRg5Dh zOU^8XhVlhkw3nb)C|0+mSKkq}MaOlU=2JFTz@k`IxfZFiUx3vD<~ zH7v`ig*;Tbd}oGvZ?~x)Ww=Rz58OU>I)>0&WU|9V5<^mm26%6Ky5rv7yagV&AmkYt zuLk~u6gZu9dpT=-THpnYE+g20Sp0j@vhAb$#mf4E3G1F2=vjB#k4E6^AxR>VH{8*c z#RFn0&eB3#2!a%rqY8S~F$$`+%-@NUg<%}Hn`{~f^_lbmPn&d6&)6+mva)JS%vap^wQ8PXSGbY}1@hBbJ*L2OZV*LkmQaPmq#%LQ|4x)L*F;;iP)A zm(mnkd2fV}c|W4-e7nxY%>*3kk!$n&u+5`IrQ%?a$ikouaLnq&UK|=LWgN$RxYFHi zRn>7neL;b|n6+=MlyYRbS$c5a1hoUlik2mCmDBj~gH%qLgQL-Ip%@-1b9r4N|LWQIFm*tFrj38r3zPVOexn04rL2-=pyB)NtKB{VUOdZ}v0 z;WB5@gg)n6n*_3YQAhUNs+hzW<$)uv-*>WN_vfj;uD0ofdni81yBR6_BTWe<*D!F{ z@zdYfFfP~0&FBpiID%*P#A0w`?c;^SnWZh;61b2NP!|H@a7d!f81w5T$Z+z5@=LG^ zGqDn9kpe<4{SoeyIX%qLmc~au%c_BjqK$=jeL_Hxx!hi9ruBNOPlY*mDpp+`CQFk! zZH-<&#~dk0!1uA6WXbrFRPvV6|AOI1K3(H5&Bmz=$p%}+vocZ6E(9JHwQm#?XUOjJ8pZ- z-)Di&x<|tI-jBY1+En-b62W~+#?Bu3DhUo861zS3?jC>g96|34!RG?OoondSr_qmH z#;2|0FCBLk7njLZ9p5@Th>mYD4+ix&qeSK=}eB;&iJOcqVq7+3I z?*@*>0J{AHjDI+cg6Xggm)LEyp@+^7Z=c%&!s@y@QAIRBYp<^E5VG~ez2M)y%KVRT zy&$Ji$HbYD(Snkb0>xjo*6l*i|)mg$6&MT3qaM74YN9I$)8~pEKl%zzP@kC3pznJ zgS7^eK%}3w;v1Z;by7)o^g-zRbiDg?o@fkWU!}7so@3Jn@ zO6+{(`nIE^Zav9alj>r`@~@|j5qaXNwBRSbkK*0m0Tl;95+T-iAJ{j1f3N*9fnhvG zqvf%OQPf|H8(LL5SP7)>f=#kw;@l*j)!R-TfnQTq&!%FCNZ%leduQ zx1E$fC&icynVBNaPb4(42|z;D0#d&%KuIQn`yLYR$;oNjmehq#ob~;LLB;NKz2$8~ zqx(w*r~A&;p!<0<=<%$|Hyf1W8v~Tc*k4Ww=?XfAID$5I7tVeZiuupLQLASE5QuOh zO3UumkjV+PzcorERlP%3&AbDS1Aun+PtcB7;x9i!H7Kjxt@73_yfQ@R*KY`{UQR)H*2L1n z5phO&EFF8AF^(9BKxl1b1TK_-yRSPCT2otFR9dQRUf434QWV+h!GkSR4(JeDTGIG; zCu9;-sGaZ85@}ukH_$XUyK9|cC<4WI$Xb?2zj9+o{FPG@h9&(`bH=bZUidu~5z$8JID?+FU(6fvi)iSVS zB_+x=2y9dWw}C)4svpzxsACtP<#)^5hPF{153ij40L<&>!G{DF!!>A@4u3NE4{;~H zY*0#}>`?u2^un^7mY&{R1`F6$hZDwac7}(nYt`v^-mkixukr~Fq@{h`+gInhsa;%Z z^2RkCt2|i|1QWYktwI#O)fOw}Z_9WI$5JegP?x|u=QcG9d};QS!!IO5bRGBn6Fgq2 zygvH5;nh}p&}Ffs_12oUKC``DWJs3hNjhmdqK3>=1hOKRV)IX#BY`cyw7FAKUOr@O zpJcFw%lBvuGP&}YOM6t*!NT~Tbb-dU$YPJ;sOx5d@8b9GFa`~rjZw?&0C-#_vsdR3WUS*0m1xb|uy2>LzKbKWs245^kZ zozv7}(6ZJA#nJ3!r)svu2IW05~9b+T6 zhjDtX`o=!yMQ8tjS!5d%8z{q{&*k&PY8>!+A(`kTw9L=u?!hO|CR190D2=4uk`@1` zdSvO$&nh6d{IZ6r9xSS^lyJC~rI@F=%`=oH-j>Qu_$GC=6RoKX zH|M;j?hmJ$HrlQ7wp@kmo!>lt2wH9sii)us3JqKeV>}$;G27TNnF^o>{uU`0z^*40ZBnA&#X~bafcL|0C+G zg5v6;ZJl7j-QC@TLm;>YCunej1=kMl?v1-ca0?E>-QA^ecbB{WQ}@()qKX%ahQ0P& zV~+8SgljRGS}rpW>-5tK8-Y`vkxxn5I(nu;#K6j1#cKN?$Hm;CW3 z;_4=#$nD1Uggh=UbPPk3gvLF9lT-Tr;{LyqL4BXlX;cO-IXKHxsn1eeW*Uzi{X*0b zdH(c7voaPGWy`eqeNYP74na?s@0nh*RDM?tWFRFy+r-H!0Z+JJ*`| zlQh3yd`;SqoVhH((LmY6NP(Rm)ML&-<3OC>P)X(9e%~Ne*O0_K;xAt6 z#vSL$Yq{rjKI}z0-2*n82P0`k6vbjl_3sQpb$G-wYg0z)nEvs@F;d$_Y-1sJJ5ZP& z#F8ir3d3|PbfD}<^q&)ziA7-4|2oE?j-3zz?+FDVX(QXz^Xo#F4NAnMDH19Q`nQ5k z$wJ9NMD7D!Lxw?7)Y19e*gBTgnUVHc_h9^DB%m%SZxkV?zG&*#^e^s1v?pd(R>y-) z3NZNQ_lgXSY9gxA!zUZRA(N)mmE4g5ZtcSw=^Wga(8D|bdtVBB__grJ5sT5er zEva`T#|!20nxDF81TuM;LKfW5g76;u8#{XT6w(E-0hJXiJj)H&LJ z*$NCtOcGG>P3(+;m|XPq#m1I#N8WH3u3qlEsVos>;EgVNZK7FH_=6r1o< z){uI`jNxSvs!))_183ehjH^2wNjOP9x7L}hhpBvK7Ut=d^*w38cboxwMYinh+$Us; z>3_|>&otQ+ZrsD_Wo1x=YK#M;JbWmrcgQ=)bMI#YJ^{w+p?wd(MtRw>E(%wa*Epk9OC4iMS|y&bYTO@3rhi(0ax4igbf$#lBUn&b zNH=F|OoSXS;VpmCv$l`S8zQM#6ky9B>6f(V%WXLnj@IIJL^IxcQ*N9w`THEX!d13{ z193fcO_y3Vs1Ga4a9o}%b-rsAj4WT~{+X`TYt!ttIUp0;V3ZSUcPv44LJd<^qsn0} zj453GFD6S__R8NEUMsP%#xhTpey0fwu4u?MFp` zChF^_3GZ=_bKu`}KQf%7nLhugG!>YbgHyQ#hJbrY7H{n!Cmx237u_K;lrj)oLe}4w zC)K(^IZldiV*Z6TJrmTwhC*pQ^tX{i1*RX2GG;`hr59@uJ-ol`6>EMcEV1)+WeZZ4 zGYa>gvKRy^raqxn)YjMc0)0X4r=;!rXz27b@&w1SV1RU)nMneeYDfS(??0eE5A=2e z*o)ELV}agQnk>&NCwiL41)o>Eb)bFIA!&X>|LZ}19?ZEA2zMumELdup1d^d%IP>*@ z4ldwhk5S4s3oC1NOUv+7zBCY5bJ_VfKaUGcrb1|s?SbegH?Dlup1#tkBHerQwCP0Y zrrP0k2?-!g{v;v26Pup@&d~okNRdCUl944Iton!;V76pOhb_H^J2YBvu*E;v4zu0< zO*}O|KQGKAD53h*^JUmo^5Q$SZT=Jhhnt-ql`DNBu0#gQ&49VS9ZzVWt~36269Mg^ zK~x^u%~BiacjKaz@#lJZ@p9Vb=5>n5SYn4m6)Z9)E$pW7*$G%lOr)Sa3k+@JEW8n> zP7E7zViBpBQT;9n{irpere>?b=!d93kKq`Iu(iodLa5;bmCbC+yee&fM!lf~l%z|z zpYmX7z*%<{7=7vqtMYMHlfv(`yME^@k>f5)`TWAD98Qt6E+-pb4V;evf{@?g1t$Cb zW&d&6?iCjp=|p@^_w`;kt!yNo9)a@N2;L1-K4gBU4WIW{@|Ev8&EW6E-a8ooU99)B zeX=?q(>u53D|CtZ?0sk0GWrFjllHMCMa$;4FQ`KJf8W6W*R@<;jxNa|#|Q?ibFkJD zOK22?5uxau@-T+8I1qIdH4#7_69r8Y{A%3NoPE|xBJJ&zL zBA@lntH|zJK74ysl`mfH;!>8hU2ERZ@76q9`hHetb1OT`iqzU)#_+o++CCq*78XVq z=o-oPc}#w}2oaHh?{cjgu;<#gP3UJd-zkR81!EP>L*i61`Y=@C!Qbh* zjGlCeoFr6t2T|0B`9^T zCf3`2EY9AHQ1Xs$NQ5KF5f4@V_5ma4`MW%m68F@y_9iR3s*$ItJF)cntW&if`a}eCxqlFz{64;_d^@jKIr#v%P1Lys$h!MbSLEVK<+eD=v^z zC+AEecA~UQQsAV+Hnd_+rhJp&U!wby2?iC=<%c=%1 zy=s+*71X8tfX+Z~8v6tFYQ#uIPo;TAV*e&`0ZS%p$QA1fv`wyj#;YB&ps3&Bx($B~ zqawBU^h5AlCFsgBUeL`hdbKoxyiBhN{=^wEMD9=7&ELu)NNJr$y$g;*tA|47OT|3p z?ZPg%2F8gWJFsA0B#5L>n~Y17%9o|awoGz*ofjAfsbdDzF1G#S3&8dl8sU)i%OMXl zX{lh1$r9*KP!j5!Y8a?#-i+dX3;SG^y>-<$a^nWawf|+932eO?Db6>^*e4h>$if=3 zYNTh zy9lpRJT>qT{+9v)3OGC3d^D@{B`wE}x-@{pT$WY8X%KL8u}k8D(d&x_KkI2PkOk-3 z*;QRzrfL4)>FYUvLB4aoZgVD`=B--WNtRqvNo+$l&tEjOa`^fq^-mvukGs%%gBMN> z(Ex%2F~(siu;rWHR@EW`?kw6#bC_e2M)qpguNN(KZEmgotz$DHCtv1BL#|N+sFP9J zvgqV-2_&w69fKm#@#SQ>&B@8A>VySIFr$8RIbi=p)+%rdE$Zz@47C@IZFUdC3)dT% zR5*A@p+!(_FszRzSf!K%cn7WDch&H|zl!L7d+EW zcwD};wqRTTkXo@-H~J<}&j;uQEQJO$TmTU!P^b#je+e0witG0Pwsp??dwece)Qz_5 z#-|sA)&tR3Ya8#Z70s-23|B%(Q{8eV;ZSOUkUKz0SYGc34J3EGPzIdZ{0;!{Vk8-E z@SSv#M`{5c7%l9iF@q5q&CRSpg1mEUwlrVw#W1sHfV6l`XLGd~NbP#YX;m64NU6vG zFr;SpElQv!9nNWu)#qivN34o>XJ;tkKTp|z#=N%IJA$;aN5}10z<1EKRCk{DqyMvk zXHq`UO}u*ObbEypK6)z7h;YW4aTf9Ep6=PDD-eAR?O8Req2WO^#;0n+!>9fEyftiX zEjx;%e52zB-nnxX)=w4+Im^lk04P=2X8U$fW zW%{6G#9YWlI8-T99zGdExD2F#{(1-Q(KMo$lD&gEz7Vmk;bXRLpaaE#MZpkah`e-3 z-q$o@?Z`{W$4_{I#DcCVY$DIt6GGnpYD_452&l|PeO(fR?jmF;o%a!IgEn0ix4Idf z?pagrftSJEgq3=&-HFy@hC#(^HZzB=7;=V@eOdwE5lxV;xXgq|XDl02TIWTrC6kIH zXCm{eWeN}L_xZeEsG|ySh(Rsa%q*ma4&HG^wqO^|9ZwXFDa=0B+}$CX*}2BZqFXcd zznm7>NKukm0*@fVF%T{;>OUp@?Y%n`$Am2na$;CS2Ig^$JV*JZO#w3I1cjEwKmGM3 z&JFf!EB3VAy|dJMDRnT?IJ}ZOs`Dl)QY+sjYzi&(!r0U@<(sCBL=}cL;{s;%vv!@g zqaPdZ`S$4~tk?Evz3R~m!AWkSxb9Ez9s?mqPb0=He_kG*z6-Eb&x;$WG>ck=xM7AM zlI}pY!4&_KrdZzKmlh3o;g?Vn@CP53K&O}YU=Gxz5$oNY8 zO(DYve--^ulFns|9nM%36 zbphg31JT4LW}w6_!@=E=WPIc&Ev#jol12@ZOfCeI|BPa7K+1Ps8=%cRtZlr~hMBlyCsz&2?Y-(>JQgX^2N zj!xdnDKJD!{7(sJOvM+C(6ebv{i1vq>&HX`jDHVQtU9m|o*TLnG;VY>E!Xvq}6u0M%M8 z1|9VfgfK7%ZEBBfP*hrzRJyuEj^o8QOpG}x|FvDTvcF22qeIAKpAzVr8&yNJ;(vUf zY!$jg7!vuG|J{K$K_LUEo~*lvzdx5M!rfKd__kg0BHXzV)r;dH{B8W~{Nd+$)=URv zJ9@+XVeG3$KtU|FWLF>3{$c$Ju&=ocV)OoJ%_7)NqVIL9@wP?w=BMd>g;mbM%tB)5 zZ5v&j^*elb*X-%_zbncI${m=83L(ll?Aq!4CkNC0AR%LjPBeMGp%I2_LA=c6zz2~GjH20`e@Q4 zDAV8SYl4S9$`6O{R+M8()JgKPv%6u3K8kIW9)id&K zS_ux}@UPPN1jdqaI5m{rAPhe+C3?VkKpkmF9|+5_ZH4?BwPdUqr?#Rnq0tp(q@}Ds zJ8r-Dv?!S%A$bHi=x6sOmD1JjK=j3JF`2myMeZ0iuKse`!g}LS2)t@Y@o0pa_pptq z%8sdae+2+8_Bn(SdG90m`?O-Zu59?YxyN0((IPq4^=rko1b zlE);#!pfhL!S=giK9-i$`>iR}@CV&N%aoiVoa<9Mle5xzU0b~jk0R*#MNrS6bDaDf z(k96WtC|!ShRX&8eRM3*qPAmos7LOZ5(F2o9lY9`xFPD&S+<)FuSkq@P3(#CCl$ot zq0x~{bIin;)M7=2qjFrdoa1{);KRL8NwX)}+@4Z@jc}>kFm++!_)F zmhZ`~ji4UkqPfnik}xT1vlwR{ER&X_v(2q)rKe5T9!pPy5!bT=S3o73R!%C^pHHXc zuzlcw%34+3P}AqJ&w8YH`Dn&0w*i(m|$6qV5R#I&GZp`_(@q zKa(bShz+~LwulNJy{6Y2JCQ+Z|Ov{geB=$aPDkL5Jh^^6_! zqLT`oqDCM^EapdNuA{zsXA4cZHDta9G;hCS_!{#bnP{wd2N7pcT$fm`$O5int+x_`9PTSC@)bIKBf-U9A)g+r!ULo zvb=GUa;8p{n&@V*ONxGO1mpO#ZQ@+8JXYIbLj~Q?^L`hI6vl1wi;7rFCwU1x&JPqg0Vt+?9Yc26T8#Pai`~b zmbYtz7jq!p5t;zA&n#(#U(5hdynwhtd?HB5=jo_Sug%^sF%c(T3fdZ(*LK|$pxWdO zK6V+r`qGDsQExs81ibmynNI+J7<^`vn~z}hKw!C=4Y?Ww8;hJjBLyH|{3 zb;&3;`f=mE@jY==2k4Gk(&`+0e>He#vTOH-I~D@$wVQkW0!8)H0w*L3FPkOH-63oH z`DD_=)tMZyRoS3SCQa6BK(&I7r|(9TG=gpKiaj0E{bi$X?gXJdZ*%#$MIDd{u$_H7 zpUOJ7v)^~K0mBy@cDsIdR21+Ft@SVaTQ5{zcLJsWDzjdTMU(bM@!zZ_ug^Y1KF>aH z2ESKyS6dvgCcxzuAQCsXq*SBu#OGMSSF7{g%=TAj&>0){V;Q}dWT86NBH-Qtgz!_> zh>{y$Y%|*tV8Z}_d7ZJ>+*aQ-@`s=4U$H|Dx&-hX*^G}xt?0G6XJxlNVO1Km_A3fdA911A^ji!T zQt70d+f+n^;vCoq=M63~IR1^`2O0t6@P7Z=O^p}itdC8QE zaB8usTX12V<9(U(dD}Y=Tl*7cW1}6UkPcAbgg;j*e5{O>$!Of-Pf|I_ zb5^Ye`Jv|&P)?`G{2@=*V+|H3UH%G|E41Jhq%SNTC}7-fH1;gUcA+h>X`pw@&HA{m zk?K+Wv)_0cxEj|SuhC@}t5pV4D!|WAx{vT`$k^MUr?_h<4eB@yG#_uPtGwq?JC<4F z&VoGJp>_ERB9)Ef>9pWOW_|0l&Ii5Z>gIMPr$2fhTX&9ZC2F*BwB7Et>a}{NS~uF6 zv;{4inEFkd71VH87+F%rj=@KE>xO(r=jD##!A|Wb2pjt%`EzjE|5rxB9;uyF(;Mo~ z*qnI&=_&ZSx`1Dr?|CKUwP9Pr6T41%YT=}O=hL{kO@c#6UIh8A$zP8SV8|5 zm$BK!@x_Cp66>Tcmvjf#KU?;r^FL#5Z==3i0dJ6|re1q?@`oDKBhq7@BMiDM5E8S;EUVFvzyTE?95A_!3(VU2LH(TI4Wisw&)Qk*>50u zdc!#F!!4RA{W4icCDu%=>b95iCUBpQ954aY!%t|WrZzSxG#Wpuq#zss7RVSF?$qd% zu4WUI;?4Q-*z}D}Aa`GOZ>;=53yzPF3KDZh)&HBaKYL<66zt@lyO5rH4aQlEBT`zE zfU=apL4oAql!USYd|@h#&+F2p3$ZV%_iE8Y`jl`pN)Uz7l z?;R^XxWFD>b2FTR_S6JIG2Rf%$Ig$<&$yD4Y5Q68W|EbzJBPu7uZMk%LzvEq6hgDk z5RNOua>>~rT!&7HMua%9m~CzYj?UY!pu}RG{td!p`ell0mfHFz}VAe z^r;_C=Tk%Alm(1fPU7}c)bUnRq25Xo2Qr*jz3L7~RDZ{e`Ukn;RUY6T7;89Q5QQ&y zGbEV~kwK@+6(Qb+akple2Hz6#F0L;Z*+-AUK>H+WHs(2t2nZuDxfYj6x)_k{@a0j@ zlnrJ95|}&J_FhyvJ%gxRWXLMMUK~_)4S!LmSD1`dL9*64ezD1K!7q6agruTLcsts- z!{p>7#Tg<#9Vf8Nu0A5)XMa2ux$~6E@{s+|kj9dfjAn0WSxUoh`;8pe0)@@RI(K^mfe z?)K|OQC;{EjYZT(%)B{OC;zBS z6yYY9C?~v){r)|czdXE64PFTxRC+z)(sA~&IEgvCD zlksFj=WOJ)6`&O&=SA~JI|f(k}FMU>t_QME9pjGiFLo%!{7;}CdA&og{N z%F-9m;ma@hwm8;((c)%smKd#!KW8Y)`NjHcF&dYKnWdoRcs7j`{&L(6L?6O$TWru; zYw+z$mZ(mTEy1Y~Y@f)Q+sr!Sd(nTbNd9LWV?v)GyrD#9)0l5@TZPGVKSPw9cxpQm z7Vch#Mkk>SJ(3!Y#RsjAP!LaFEqF566%*rDf{!h(Y?r5ez+I9U08PEBxSl zeg4DL+$q3_$228osG1yh8t&1=0JF${5>2wEU)PTt*M_8J%Mu$3xd}>-m7|oLNKC*r zWw^DCK9(S~TP3nzYe~9MT4Ie~y-~cjIyAmEa&du6J%TzqOqV6EnSYzPu%=DUx?y5& zp13Cp<>2%mUl13HSKz&jLCfgVSI6_4C%q2mAejMTp{C)kxq!%Es(uKzc|@8P+Py0$ z525uX$Xys`zZJ+05!t=?0~S!O5zu8H-s37(He}=d{ymHA^+3Aq>WT?4G5XPsuF!hJ z-qwLBN9SlK+_FQ?ijVi(tIajE_{qViV>%-iT!@$}k{`d;Ety(6gncjT`)?=r<_q+V zOQymdBn z2wm8x;{l1a1;u2*m;8?a&{dNo4tYGXS;%s-L0V3UvL6=dX6%GySm!)`oR=#-Tcq?N zgzKnC%lX|?kf`7UAw)Kf%7 zs8SvpKb^EULV?L;jdjKXf7Z#yQ_~adK!STPfYs%eJMv#@^DiYbGrzbjxYM}OQD6+i z{ecSvD9PxAdPLKVE3gQRS@4B z_p@>a$PU277MTEnF^EvQUTSRpGKs(%|MD1|9N*Pt=oY(#kd7`vq?qY9Olw@cmQ7}D zfuDQ_kdu0qV@0&vPhN0nWUZDl1f;@ucg_um^Zd0!>73L-7XF*3=PIg{fq8OoXZDdZ zQX z*%13B_2t1#r9BT2I#dEQE8LZL)-|NoOxC-yvWAf$wD&N^s^#?x3Huv*X?F6#U|ctj zf<$DdX6QiC2u`#wSLYQ}99*2ky2f&>nSE#l zr}N(i!a^^?RhB0%w#}NLvnWP^-gBySq1^iO4!07_)`5bxKk#!ku0$X1vJSi(?rb~5 zpMPnHw0ouKbgmGJj#-^HXBnX0{jFN-3{zF*52tF$Loe~+4~UatzlG!&BAWks2L7Lt2X*fA_R=a=*`{3 z;VZt6S>%b4v+jkLt#5zO!{W8I1Wg}#7woROZqeM&xB2zGPBj2cM202RKre@Xfg&EY z3|2BOKI&6sxUjyAahzcr&1e38Y>U!v|8ZEa{X^o)P4wY>s!2p}y~|E!4MBgjsCAwU zc_6eAgQwrMe^eAvLGqIYOb9Bo)5(QOG_lZVX+9mu`P5+^mDsGgMlStliO1j za?ZEyA84Tc=*?1`wD!eqjrQfbU5`qe{`A38Hr@gCWp;qU^SZ1uS22u-}A8VT~U3J&^;NjYd-6O!Xb z-o?ZFW-sf^EyF>eLEY_fkGE46TQXAGWW3Egc*{_0oXS5ze^*P{H8eqDFd>-dwj-nM z49msCO<{tqx3cGPdZ>1|xV5&n`|66btgOtrb&V56E>=Gpk^B?VRe$7YFFx2rE^UY!QoeP^9yd#eBW+a`#GZHA9L)V{3R5H;0Jc*T1C_gw?wqLq{O zU(B6|G*wDYotKuZD?q?;zsJoxi*}01(#$Zqr*^(2$wV=};Eia&0lvsTZ4#yV_vb6- z!O!WOXm$;>S<#yn<8?$(QLzm*U%DwcECl~WB8ROqBGi$);Iw8e64kTOa(r6PbEua) z*U)gE_Lhpfr=J#n@}xlA!stfSu5_XK?oLS;)=tj)1yQ1T5l?>;F+{nm zl^@$27?WGN7Ty=yKi?8jh*~Y5!qG*OZ2_T+y;Sq8t=_N%fJ4@w&r#L(g2>i>gIU%7 zCh)izXu>aF+}b;%^kt}SLa0YgNjMBfxXCey>}B&)hR?fKBon0j-W`2}Q=wxe71BF| z<$3P$9z7TEDGZX*+|1v0zoXr6!ACv9X{*;c?(^9BhLjAn>ZC-Yi%p(6^EsME*?GP; z0#*=w73|CTbh|5n!kfao?pddQ{a5FkV&?@EfTe77zr4WIhJp`nHH&S zp3ArIDgkrp5{vv!@p-2631m@S7koy2znT`Qn>qgcZTzG;4DA7i^p4SU+5JtH_?;K+ z`O8$Rib29T-A%%Mhciz~Z}U^>JKapy#S&ovR_>P|eeUYN<13D3Yt*4Rn9c?3bP_wE z@!-T;W7(t?1W$G*50yUbQ$`mYBaR`HC!^!ZfWHCHb5rfT8@)n$D)DoJRE5a>o29Zp zX+}sDo;=1?;#E6n-(27I2Pl6_4@zpE@^Hv0?d!0c>0DZMejPkq;fT22vAk8(6okZvy5uyCZ@jScdYdqdE~eUk6pMYERVu*ow}E z;3f2hS7q7uohcBNH=AIdlqruNzKcvpU7Gp*D#4=MX>AZwfe#W7I_A{apb%%%8piQp z5C=XJ-CQaOFgXNHf`d{nG>v5YdwL0hx2pzl$I4t!$+nye{<+nuZ;ENsS~2e$wHEybGpBLKw94n z6qi-TkYMqfhN^&31%WXw649A{U|K=3VAq6CDsmp7SW08ip;lZ~RC%T1WqW1ODGJM_ zqaRuVZHO_+P`Q78@1^MPg)m~~MIj;1U%QO|@Q$fF&)!|TKA$GL9r~e&Va}CIS?(K0 z$T{vL)rU_-tOzQ<8l)bOt!5oaoEjV!G-db^Wp5^7D@(5_p`Vz(;D3{MCZ0jfr%5qf zM3h&7gLvNMLaah1MsauyzSd1{?r;j=WozqGHA#d3Cb!|b&OSVmdu9ZVW%xiWYJopO zMZ?lt?CX?}+RkpHVJj4eX-e?Uxl+8>7(e=>#Kx=Q2gT3Y@pKM7Dh0r^dXt&4|I|ci{0gaokCAEBNlcAtHoq(KU_lGi8XEYwxbrj$NNuL z3i2_=wVV&j=?Dpbd}H1zFhFwR4Y`a~IU9ay%gZXG5RU?@2Hr7|sLHETNkx4&70>C< zVjdZ)%b<^t4HRpQq;$gWOSx=P0>WU@gz+g-b)v;Hxl;+v6xTC-}YBZ1v_%UoFHn96cSE< zT%18jBqq_On!w=+n3u`kE<*kzH;BB>i0lqcd>QI~Z~Awi4+Oc`)&aF9Kx+CQzPvun zfRw}|bMesppW|%Ct^jG#2SEFc5}Wg22yp8J$8&va{(Z~%p9%wH9}@mkVbqj3L_{Wl zOT>S;o5dOkU>b9}+K~mE2{Ho=iThtQc*{JnmxoLhMOcpa*0Li0j47p2kKpWz+~ z0#^yoyGx_IVBxR++9MW2ea z-)~2{*3PcIT`UALW#jNty4i_Q-Nup&!9a89g%wv=UWs}EQh4=@N~?BKToHq18eHB& zpl`0FZZ#O{^jNl&t{W4C)bWA0Eq@b=Hr{cLbIzmQUIPAtKW;2+Ewk8651h9}t+Hyai>9Z9_e*G#-#WXeP^sp+7HCiS9W3@Lqj+_-iv8<%FkIWu700 z7YH&!HawqKJRe8cE)Gi7c0l6*I5kr-8Thbj+u9-{xkMfhl{hSiw~rV*?}6C$)6KQe z>yDbx?<4BJgP{FWH}}WHu9ct19$00!GW3VcOmI$(u&>GiUw?u zXj=48osi5>;s$Rz3#rGpL)Oa+5EM+EaC&;&=c{iKOESY(v%g!bqh|nEgY<=b&JXZD zFLXZLL(*ha;ZzC&dqZ?014l=c`BOZ=i;Yp!F51sOe?aL%(BPfW;PDDrg^zs(Fodw; z#@c5d&va`@+1OJp$&;B|kZt|IvmGb1zw6&r6jPb+RdL;jiz#uu)~e3e_iVXYUe4}3 z*IO&HDQ%1Iaa_DLIczAdW^_H{o7_k$s``{dzldl^_zgTWY{w3#Xv(#U6MWMmC>gO~ z+@3o>`$)H+!J1u#66~ls!iLhD;KvtB>=7-$-2s}c51kvxoN!u-5}PFUGmua^ z7WV)4bMaMn2mF2}K|q=hD4oY1N3h4$#0K1Id!Sf89{zO#2^G5H_!P@bgo2$*?SoCWn3hoJ>jQ#q7=(Xe8$d9s7?T$q07kziU}gkcc4 z!Qwb|1|^HnH5^a)U5HKi8aBE@NKE>OUBBsTtleKNz-`ZN;3a@ z7eDJ-+u)q8W^;{q=4=5x&M+h>A3bZ8um3MO6`E>~*=bGQ2hXOM_1p`3?O_CnD0n9; z1wBC@<_gTIRCTjUsR#z=spsN=7bu54GslrKSdTH%kVh8HB&2c%{3|jk(silYY>cBe zO97SQt4CY`WrLfBopz^{G}v)g!&j>2Z(A@&FyKoB=Bt3N(7^$CvaN6AvrweNHU&NA@sG2FwBpxjdRi-95rV>rpT9WG7!?hik}|nVd{PMm+t6abe5J(tn)^rjv6tj~N<_nbsTw&woC=p^_B{yo zkNtS1m#daX(E027y?D~yF;w=uc8PC$w;t#|&CyG%93zPNT*D#mNy2`r5zU$Ct>dJv z(W%!sWUOspT%ufswynd(07tAV{AP=VJ8P`axg*6ofO{Mz-t{<9=0;=Z>-xPDZq zU%$f`eN!GH7J!~h7_^N(aXHwH2g6rk)Olsgt?``ah(Uv876 zbtOw{B23|rIv_i@pG5)-zsl|GAE(W{FRu+Q4)S9-1wW4fx<3H@jJ%9_e~9^IX9LL) zms?`Xola&9%Z40;(ht5HUFR6nk-u<2ok1bC7QxqrS!^q=-(dV_SV5uCI5kGY zD7H1I;u3|#9sGfcvL4>zZ!0&j|!MUEm`I$+C1md_2mP--qYj-sSQ^1E8rj>Mh9~It-oH07tJpn$dv4J`=T$HO?eKv7n!_}r6@|)-TouJ64(ge=+ zTkq+m_trASC?>q0wwnJ=N%!_lGW&|_PCxnB@xOt#Tal+xuN3Yl1^Jeh7S5eOP#~5zhBl0is;Yc2!2fo z&IQvHri;s#wEEoyp^-D62gJxrz8866FB8HT1}VufZpjiN5|(bZJbAEWwa2&!WwV~0 zRz0o$k}VGvMd5h;bewPlmksOLfaVvMllV`9EE1zYWD^N=V`Z%Z&4WK5)I*gi6zR+9v6ED9HPru*cT~)0RXe<)GHvOGVNdJE z6d~|@W0#F-TcA{0=F8mvh58**epg^K|1r~dWGIM5W@QyCsoU2X#_wxi{PqPrl_a)o zw+wlJ?^gl;ZeeX$avVP7dCQFI*S;wGGM79x5jSsa-AP`3J_o zI(&}igF&biJ1+n01?Vw$=+;$+=xt=?z3&Wm*?LRwvV?b4$!O3ElgZRON^%Bcy*Vb$ zk9uuaXdP(h*j1cc(<0G*kX529sE`~dkj-j90C$}Uj?Nxn*F-+g&(K`6WQfDdTcVL+ zdu4ZRS96urve#w5j3yttUSpyE^-G__XAf;=-iYZAXc5@IGROxB&3z7F5gVgpUDGUO9oQ55mJTU9 zGA|n2DW1R{g!ffM8s#_%`s@QC%vnBnd%xG`J5FJNaPG9zQXSz9YiG)TC(UFWWa{_<#=?Dp^2ubq4SLHJ12Z}~j{+Wy-az2I} z^y4$H`<=2J-2M}5Om^~cNjOa8mLfD!_;yMW{s(^Pqq!TVzusdx%4$$%<3@;LaSs#F zK;OEySHt$DKbh>AQw|mYi> z^<(}6=Tz(t#!*E^MxzIRT+v+#6qU)JGIaeJEHq)sqf1W{apF~1cV4^ZZI$4QR%bzK z915JhT$d|1{5@}0p%fij4=-Qp-m#O$#XY?*g%o!~8f6%ZF$9!`EJTaw|hrCxCsq%D}~c?00Oj%rVPC@Izit zRUjIPKrfb(P#1KuqQm~U&D+`eTQHgD`!g^iJ3hb{lk!OxuNhsAQ?~1OuXcc<$pps_ z7U}H__$Jl>P}1wm^+{?f#lm{{h(O3+GnC3qU!Ki?FYaY#ffJ!;&I13LUfwUr-q3K* znT?~mb_f~FL=VUL5(C1Rjp4A(kpA{;lqqQZu@s7Ra7 zJ@$A0_(tcGfXG8vj73F7ow;$^Cx8QTumw?28vn4s=dk@T%Y9oGNQ;l7y?dl% z?_X=JN3M1|<-5nHPF|MmgkITP$*O0HTsw8eZbVq1i{t4d2layM_BvJ~D6h$*nR@3C zjqsmZCfZ45lg?BRJqgV(L??=&P0^LZC<$-j#_@k^%l+XNC00Qb7dvKe57bYK*IsK} zb%h4tdp~EgQ3BCr7}{GZ)vFPkk6FEi@f5QP#Q5r~*Qc9Qsfe@lTFkSKMuh}yeG$<` z10yNb(fw8RQwd=3OWA{PYMEvms`F z!|PT#vorzG18i=`noR|jq(0*chQV)2%2sPs*84K~DfpSYBQZjwRK<#)c{xuP(B~g6 zjV1-!vT@Xe&nuNwdFpuFc#=T-Pc-Wtj#(q;?ISbUxS2kiL!laiU= zb;^k^_~w&`>9$)GU|9S>Yor?aYTtehk3FvjPf_Zfqz;lm4{ z_puazrMfGR_B^v$JB+V<*0pYHXq<89Ty7-rV-uV_VE~_lk-Fz7121iq_{!0RyCmTQ znX{>sw&CP30>hPM3vT|XQ|M)%X!uoqW-4Ho*)}GN_ZD>R#&rVMO5G`*FTYn9Vmt>{ z;-}Ey?9?Z`wKa?l)oUt6NAuvPr)=IFCiFTaHq5n_+f~+dG)Jqx{oa#v7d-mdSG(~0 zoErN)WH|gQ~v=5kB62+L#_180Wl`F0yIi+j?xy9F5!f8dt>7)32 zPD<+OAVaZo6bhxuHB`m^loHe^jA>h`a*|;ND=L%TIh9`1&_7%y3a4FTV>1~kwC#29 zBW}6PDB6mx=?>R-hza>vqvHxQ_$0+M@-n}Fln=euO*QtgCeXpXwNJ#RnGpbTNzu}; z+S<16hebZ5=lg45+It3KIpf)#|CXN!jj-po5a>Yyq54Cqcmav~DbX|z(oONE=auFBf1RT5g+t+@% znFr|NFEhsW`d4fSWJQ}e_h38XZ39%{QEw2snP79H{`2OY&a+OlW!f1$G2BUNqI#f; z41kDNy)?7w@9#$!^Mo?9ecwO3XlM4ub2qE}8gNRHS!m3eG2bM7zof;oz7PIfjEj>nrZfxwx|6H0N{fh#8G8FMlc^7@QDBH=yROrf@U&%B9PpOgg3iD{AtFuJP5QvWuRN+PKxCfN^D|vw#i3b zhpX6pCHhra)7)P@K$0ZQg-duBL0$D3#_e%$ADnr8>;4+ zo(af0Xv{f)^oL{W@4ku~m`bdq>7>5}ziebjQ3aTh@74-;JD84@(Qayt?LFx$mOlMI zn%+4o)AxJ-eoxcXoo(B;ZDVS(C)>8|$+kV&c1_k~+x}hid7ke-)mp7u_v-H2=ehSj zj^i~XVClUh!DIugdFO$=WDq5$725PSa|pYKGw53h9kpZW1kxVjFFzdmoede=+m}6E zd0gJ!6^5MsaXpWy(N*K?jgK;h*dk6&J9txCFc6p+?jKG@N6@=q&w)oQ%u;pj@4Aqb zgyzv%apjs=662tS1WAjV9)t41PEn6Og{NlPB83^mZ}A$MGVaVRZW;<_TBmkuMo}&A z&1#+trUswqvN5#~mESCp7Pn9NECqLGIJ3U4ZV5mYt3C@0jcFyZf{#6~PA=!;Y35Ys zf>YmxlV<-(9uXu?zAD%KCj4R?th{&{QTR=O>(Mx0U*bD0v_oS~vl^w7%%f!}2@4ke zt#cto$pNR^6JsKZ5iLWF-SG+9BKuN!1=`6yw>_C~2C8+(>I#$!IHZ*jdg`GzIeHRb zmjJcW5BhfID^<-4bhx@LR>%W*Lw#RmP0`XgXNh%3-Q=1Mk$O3}{L)yf%As`F40GGE zY#HUR;UVi(nM!-&+kMb#K}RQ)`9x)MvPjWUv)FhgY|JrQ8o}r2#!xtu^c-7Sq|{Zs?|Ddu=|Z{3V;o=x-;j%*y)u9uT7bzi6~G6;m#+C&tecgb%+` z<^6qiA1MYYyT!FV9Me}6S|&zLE)LAVr@KW%cy-do#|9x6le?`}#}dk~NleVl!nhIx zN)wx{op&BklWK{iQjD69!|FLX%H<6LQyq5yD((Mnxv61!WY<8oeRz_aR+2h`C$~rU z-Nz$@!5Ak*n9&3{UeF6RqNu?HdTE}vVciov7d5s)J=_bffzVk(amu5b#%qW;dJ0tF zqE`0#0YoQ|0pQrjqAV;7_v))2!x{)%9X8KSx~LPK0B1X5H6rX%AlQI1gx zvj3voy6z_rYwP=3^}2^#8b$~1Xd65q=1!Z%LMbl-k%kjDmE7ff8m3%eCXdHV_;a?FzlD%d^0c9Ku>ti60O`)eBvhD10k zmM@<-*M~N&wmh^clGNro^_gfWQ8kC4a?!<~v}8rWR^~e>!&bLecgy;;T!|dG=280b zS`-XmAvz8XytlA6c)T_o{Vu-pubHFt`L=`N=UzI{OY9f(5hcU!hyHN`%dX&gVF?4)IOM(%KqahTDe-O=_Qg$Wv9F@v?;@S*sOcPQ~yy&i)9PDBJ4$? zU=gU$gn--~5STrDVXRx3Jf=71O5vGVYNlW-YH0m))!o zk|Hq9Ur*=|Ift(7Hdu`4uWmpRFOL)+b{!5ig)1<*ThcwT9o+w?AHqGmz)G<43UYy< z{Ef-&xqMLn=qRXZ5#mz2d!WL$yH_i9sxICt|7&0vp4tm`Wi_XZ)-vp?5pCEHCPBBZ z8g-ZVONJ%vzGSXIheO+S`8E}e*e0(ni%6EDqVm2rW-)~q{$*~b>e*Gp%9`1VCXqvk z0y_6%`!ex8c$07bOrR{oc{*a(P?@Dgrl{FptK-KgaM;ZFoQe4YNXSW7P0DfxzGo{E z7WGs9&mvy0&r0M|S-VXz7(c9C5j%rOU4xpGf+FhJ{UUNLzGlKAQiCHsd1FXHy;rC+ zFXnf^PSFfk0VYwlVucfr@9t%^k0x@NQ+1lVQS`_-4w(<5(7*CK=Lc8e7hPr+D;%nv zzbRQU6)!Jx2R%$F{m>!BG7GvQtx<+AgQd0$^8f5s4j@DX_rH^ZmnQsr_`TgiBK`uS z{R6k?%34k`vJh7b4@@i<3``g-z@Oc~Jc{F2Mz+z`1TQ-qEd#yd{l<7>oAtxQG*g3V zdb|hTA!}!$M2g8fGt9oD#v<&ulUl;qpd(4d>Ksp%))V$%;CWU(omO|1BDg^q zNQhF163?EpRQ0Qqx{-=ZI#>O~7E6>EH{z;Lf`ME_1OMoEXV0Joq|yP=WN3o|`2t;$ z#gl;r>;=uhizD!rA&8YB?(<3KO${9rnDG?~d3|@Ez*Jc^0qt71Pn1%>8{bAhlIA<>&iHntw&Tr_alAKJ04J zW3o?QqIxXP;qvM#v78D(3mA?iD4E41iXt8oA3kzw1IEz}_4PZk1TQui&0ERICr=8` ze?$LQ&;Nb+z|t>m!`sP0|2m~N6@SR3X~~@xL*W|ObE{5ZTVnWk|EtQ}^Q!e!a(D&* zZ-cBFfEfrHVJZ%_i_w*tpHF9=v&~mRR_diBm{FNSY4jgeYLnUABwW!X+tBW9;t1!a z0k3ins1(t6ELIbp?VP#A zl|g~`8XO^;YhI6+LaOii_VD?6+II@U=gK=JB~>ahsbxBgLJnnUc(_dc6qwaB&0!ii z4G<`VpI6DHq+B2d6BQJ|iA&&w@s?;-hmnY} z!H*=syC*0@kx&~%DJSSA#F=8H&AwxYyjxz)((emU;o5|Pqb4wTA1moTUAVe$2V?w7 z%kCqTbc__6J7s-7Xqdiw|NJ<7yQx42nFN33EcIb?(I_YZ!GaK7(JA-+-;$aqQH>o9SyDLEf4jXS3%rKv z**PCWoMypU4aP$bRd9;MpkYh1(N`1Nn&kM=)7|7rvS6Bd>7t%26bgfq;x=#EO6ATn zuL4@~r);DWmIL0L#Ws{^f1FwyR6R&*Tf%B;)ypOpbG0@<;R@PzTW9qcFX}NE8e5)&e!u^?i4fDHUBCuu}^ zWu0mH*u)=*rZMP^c0LC!lFG$6rLT0tQOTV9>dxXpKhO+~L2em#TICqytrEU=H|GO) zXss@XV%I)OUl%lYFWv2tf*rx9ka&cSB3AzjKVkRgOQlrD7giXT35_8d_3UvC?RmpE z6gXB+)p67K9ANIAie&Igm_;UJccA`AVwC(M&DAG}7?Qw<3Qi zF(|w`mpzM8>iXj-NmiL}>^DH+aL`ItJ&?)i6wo@#m7o?ou3lqz`XJ|&upMRMyiYGR zXK>lYCt7E0@;&i*;!+D83ViA!Ju-Q3OaCOjo9xtDgwRL)?=^V(hk*3DImR?R-{MQ>96=HXJKf&5|tViAE8(x6+IG-IS0m z2@}mc)=KERa)9x^y6UE%;5`fnKs#T4KKf1@>3u+N$j2_Ue^OM?R7jS*97_a(dwgob zk=lFBDSdAG8BmSj;dXl`1k}XR7m)&Jl=W7Tgu;Ivwb8Kf(C`pIW$ZPRn>&q1zvYFN zakO-yorWCG`nPEO-?mX?J(4JoYoHrEDLg616_!8NJ=-Yixo`})rz8ds#@V^Ol2fWh zkC{^O$oL7NW4+|ft6D`k#jt{A7WFNui1CLZz6gWsvuRAnIkPiXvB^53EoqB1E``ro z2UulDZ;~@pA?y6vp^iQK0N+H+AxH{>{L9i(MEj?a2xYfmV)ER;&@fZ2WN>Z{`LfG1 z92gQjOio@Ok;E!PkyJXaw|Qp(*7qF5I7@L0=b>S7sHB$}a=Xh~R0yKv-vN%gc=4oA z>NVOzmXjk#l%WWCJ9WeOMpjmtKrpnf@4GWFx=y(Bz%)`6HmvG5tKmja6=W1Va9Ops z+2|O};%Q0SYEQ+`eWKquM+e3Vf;e&|YbHKhK0hBO98Is$K(6%zE~RC=AAs+Orb57z~)5ws^t*Lz*KVZuDmOa6|Jk-RDr*A$Ug_?xR^BiziKotL5( z_s3N6uz;NCuYAjh-EcM7ftQ`K?R5kKvM{$ z>$<9|o44@jTMKQyc$gPNBOM$(GIOzrc{j$`hul{=v!|#pYq!d5%Ek9c;yN7ULApOp zh^X#{RixHj9Sp+I+FI*Jy;tF9C@bzR69taH!-XJajjpixW=i0D`8~IqSL^wNo~l>d z>H82+#Nrzn8U}D|x&_Ll(%XAF7b$#r&q|~JFbxj~dk02|d+IrRfMC_c!7vJEspjfo zaNJ2{ayGGq%khSCn)epgQl{ni(}jtqEd?%*PlB!2Z3ge#NdF%9u6nme@Zf1At}bWa zC`zdNgXMH>Q`f{~MoX*PF|`4rQn=Toc2R^!oLHwelxjYxEMif2DDE3&(a7z(K+BX; z)k3LS#h$x-%@WzPm#{x{#|@RDKZU!40_W38lHe|8&M$o%8+c3DH7zYG8!Kg;EK=BV zQKhg1e}v|WI1dwCw4on)<}S@gCRFLnLIxB)dJ)O|kxl6h!QQf5ax|m#miCJkd`Q_* zcTXL$Owcl6j!dn=*(p|y%INAXM`|jo$@ud#-(R5f#Xogv zX%dfy!!g;Eqh-!$$J)q#2Z}QZtOf^yYzoc=ILW%N} z|A;0t;u`R%Xm{9$y0rAa4C%<@^NjVq;W}dxD|stpT#4oi7?5TMp@Efy4jys$M&gqO z=|oyqNLq-LqZ4_grhhP#%%~+mOVOjHDFS)qlCt*QqVYZZ-z)1CVqQH4TufzC`LUL% zBe3L{V$jN+!v#5of(Tu}A_)aOzR`mbvDYPID-Q>y2_hq>|0k>aCwj_$sKPUAv8&lB z+atN=m`FQyBY_DWWtrUBu~xHTn6-2cR}Hg=*!9{tWj!XcQ>A8- zN{Q1_A-zfS8HHY=m~-`@RB~zDzh^)phEOwnH+|;c_3f6|OhY9Er@l&ArH%`V7ZpXu z@o1{AL&oBCnoc+cH-Eb&&k{d|J!P&uHBiNvKSvHGa>t!T2UD+#hZZw2j{2=hgo!7# zNWCmLr&}(ZQrEa)%o~B3mY&DdC7u40bX7mH5H(Ry zHr+e-Q4+&;F5Da)Q8uu!SWQkFMXC3k?wF=A)~TE>d4Ghi{QrZg|8F{lw;d_C2cJ*s zEI^cIN#*GC8VRRl%*t~#P8We-eVyHtpGoeN5@BPcNh8WlF~Ti+&%StH8VSKROL|;f zh%Oa1rxNizx}WY4CvswNu+?G_MW?- zpg>eGy;!^3CmO@|jTi-GH}m}@@onw$oeF{PiLgp7@}FIemX5)o0oRnzUo)J>o2M)` z(eBI+2=oBnOu+JcdW!RJf@k8{K00v*%g}KJ7W?ln^)ax^f7JbZ1c)^eLRv;B_{BRd zHJ8LX9wBQ_5Dy<1r&}{TiNoRc-lWduvqL(~_vn0M6RSv#o{BMAWiWk5nmCX0wxQrN zmM0fu1?{G;aeF(Q8?h_EmH~Xu8uB^(gCD`( zAOQWfvG*1XRDt`Y-_Eb-S@P1D()jLAu>WX2ztXby2Ql=F-QB~Zqn%}SvA=jeEjo3F z9=;o&U(i8DM~#Q2Ua{Ro2)+O>_-P7=x$Q532XYM1>YJN}3V)|03n3+vY zgM%x|cUH^8h^KYIovC*c#Y=&MEY}E9(lSs{p>mb|(UrkJtOOuB0tjuuIfv8nc0=RT z&KI?z)E*TZ>-cnpl6G_nq~PtE z;2np2c<3pEpnGI8+2n$~MGyh^A=F7J(9~5gc}L!>K4)UKMQp&~?~Fm$?dxa6ZYYM^ zvF%5MO~WYgqQ_dg?|DPv@kFIYUrwl()YV<^`XLt%KRRN{m8BmhE(|U=JO7-p(d%}M zY;`;t>AsCl9~Fn#e)bYD^YQnQAmkkEh412WyTw^@*#46lXS=^(kq=QkJx}WaP^8Q5 zzi$~BZYMMfH^ZL?2!OuI)cs6GZ)Z|3=kQ<$S(+*-smsUQ262%%DzBV0F)GLvX&*dTL-R4l1f>B32=;C58O+Oc7liIY1$ z{1y|$g3X-2(`En*Gkmg()MDz2W{0p^&0O@?AVTj(+*?BhlXEroKbMUo zJ-LNsiZP6+qVc4lw@ghm>R!SmN{!`K=>-Z$8MrDGpB(vR;pCH-d%mrbLb`doh^^N` zo9C264w#$87DBD5PcbE#Bs^wS)QIm29@1b)h-JSxOOcR?DhWAajz_tGb;sbb5kj4- zApw#7HXjj;I+U0IOTMZFw8Ec4dZVVMUY@0`{pefUtHt(1vkZDoiy)^Trg8F!pyT97 zd34gIT-@y-6fr{tF+4pb#E$pGyvoB1h2|qXydS%XkBtzf-^{_x58{Lk=#10yR>o$i z^l^i;Q5p7O-(|o-Nco~+&~G$R)S~vuoYh3ee#u|JiHIXW0f>i$ut3W$N=POR0>ju5 zolrAeSzR_Ze}_1&BA*mBGU@Se)fh5{3#4NE6--wjD*7-uE#3Eahl!BG*?Y3e{<12k z){-uX;a+6lF4{3FZIIbwp<;2=y{0=2a-W!=B_BkisQt?;zMFW%!Rll;s=Y&E;SykK=ITWcF+HPi)ZS%yeEjf1MP4gEBt zP{9Wl69^dsINDLFsu@?%1|H51g04U+jdeI0G7c)ZEr>cP7fg6ROf2Zs+*p4^E@YH; z(Y$ipPHo#NjOELsvtLlHmV`BoY>Ivbn`o!JYK2mn_;0hQ+FEY}OSXvv^p@syMt&h9 zuZW>L+H;#!U50C{`#E$bzj|FKgU8JroO^~IdGGQYx-V;0$q1v>h+a^Yk=y-)(N zn6B|COwiis8~#pYu!DDbQvT9;T}NY3U5L7_Pw+oK#oI}8Y8f!POsC6sKcO9t#oa%O zFF4D{IUI_{X{?VboHvm928cQHqCaYDya*Q6mYza=pCGICx?|!Zfa7ZH2KwA3V{{Zs zTtWhi0B84VyZ_ILGa!Rn;$n;w?U5&BltQkb@Wl^C(nzqsKl%PK@B0?(bw65jbCt%j zC)Kx8mBG43_pflL&2~JTF16ZSTLT%EW~?V2-XFXI&!f{C?d^R_-4C=duLl}GI0XxI zO#+4Hmkf44iAkV^$tfuQ4X>UyAG?OXQYavYd|BkCPNvqhR7+8FyB-!efZY1z?|#~6 zn8Cz%`}?Kq{d{Xz;bSj$rQ5d`vd8W&0iMIQYgi9}KM%$FzI|RVuBAdH={q;2pv?*2SulNzx#zm_9Er8UeOrTQX;Xmn8p-H#4@vS3FVS% z9!AA1YW(xtB!$`{EmSni(+DX83;(Unv`oM5i1nAhhKQ0Jv zX8L1mZMSqYn?#i+f+H_$-AtjN;S>QD=-Em`$CZTdfXX!Q};wVXG+MNMF-0|WEA!oxSNH9sFDG^4JH>f@KBI~7A5M!sIHg8A3NmGaDU zd8-!{o{024j28{q`~2M-h5UsXuB5Er_|wZUGdTDwF2B>SvQaAPWa+J;M<3SbcWHDl zUCE7lGED0q048@>;DZTcD(9b67WlNgVR`u_;yF+PFnZYIb9sY>6M|4lNJwO-rx>}| z#DL6Z0JGZhFGQ)^E3mxW?(Paqf&ZF}d}x@{?drc|O8Sv6HSDUw$b^Vf4rT@dz+DG- z>oxH*{wEe- z-;6T=>6LCbWhGB9EP5rHW%bQ%Q^74hlb^SGA1tX1nWj|>!1aNJjcasofV4_2aiQsZ zb8`zK~pyS&@>_-B|=ZkG?d$Uk6q&WOA zee&!jvNUx7BO$B^AlCqbqG%cD9G^xE03n-r$;S4E%w>IZ^OWN>-#9Plf}%AVNxJu9aO~f4_=p{sFv*{7ktA~XC~VR zuOrMCnrWa~y6hNUOJ%rm9tK6DK@idUGt5QyCGx<3kw@lYeTIv%-PpW1ikW@;~LNZfvTq-+zOT-yfTD~IM%8N$eE6AiD$?moZxS*AWp;nM%mL`Mh* zg1*qlFd6u%5(!fqBjyWBAxZ^B#8E0j6LoxRroFIq$J7lskJrSghQ|7hYl-Ysw#pwk14$qK^pN*8B1YE6HXZs0zFKXs8h_dZNo(LPg!iV+hM*< zs7r}lO34q?$V2hFM7l98#i?a4tU`Y-l}|OeiM27<#{1cogeJGOb`Jj;#1cTIM|y7b%Q5aLp&J!I0uk5rM!AN1m_nl^CLo{e{p)--sjEFI9J z)l*_Vwz^6Uq}TOe_XDt0k^&N1TH4$Izj5{InPV5JhA7UM`25TYgr%5&^T|*n#u;zh zIfboread1i!!QN3oV%5m{6v+1-;@|0PU24zPv?pBQ;z)pv+t!e5&`M)lpG8!vJa(g z?gw#3!EyWve3^}5JscRC@+e#$`+!Djx|CVmYjEgoB#TH43N}d-g?;Oi+M{cCDfUi_ zgcLI8A>&Zo1M(cH(BX#<1<=A(R5UJfn2XV=sil}VrSEBkBqVq=iL*tRqrIL2QOVqR zw!2SCu|m*EVP086md8$Qh34W7t&>11(PB|h)qhpab)9!7w3efDu$FYI7Tj6YE!&Cw z{z5o`OvS$1=#e8V0C7e<{qFbEgVqtRk)c%*$#87lWe@*U_boib`yCnk(&7xa5S3K> ze9_8X&3P3(%RrxpI}O>|Q3Y{sm#X&cT5_ zR0RGfLP!LHy|a1KR+oEh40>%+DG%P85fZOMo~`X3|F5)k|EpTLa#MA?63gAb40@ld z^XqNSS(fSyBt>G-dY^QlLUk1`y>57~CoWi2WvU>@A61aXkYZO_(tVT{YZDgMBezl7 zmO*i}}G?NSn*l)wlAL`%5= zeIcDksY%4DUx*ujoLe5fbk){=(uOj?*pm@Q5Jxcq{o_qvQL7qMnVJP5xKu&{=`p=} zM6Q~tp+h<_ldhjaKmVC%QzC*H1Zcc-!3q&Yg(P(#f}*j-r84VC&*5!y5zyL)UZ&@d zPGSds^uMffcgy=u7Rg-ZHlUia!n~qmre*FwT_*y&$$FYyA(fuZHWLs`h20&mcT5OPl zh=4x+;O=V)m;23^gW}@fx0}wZIF^--=>tll1^mKInkJq`S<#bnt6A`i0aV&XC65zz ztxduXrfD)uH4ccJwYD)pRDfJd!{p5vb+^~^B>>g>_`WVS@h*Rfnp7@#h$~H%&uHl6 z^oIgXQVKI?_vpo#2wo?7d$-!e-KsvfueQ}C=G$831;TFBQ1=2`>pkZDspE(XaFQc58fu3?;x)q-ESVa z0I^Sqm;myZSGK}&YKT0mQgr5WMaL);M^aJol2;EvLen>Az^=2E6|kdZWv}OHLSi@5h52tpoIsn+$z-@OgliiFqyhl znG=n$4-+Y9nNm>IP#g2Fsvp{iBice~tQ?Z+iDc2tB2lseCRAUkA}`HWOc5pOsP213 z0Ei4W40}vNJG&rLWT#dmL|P@kGISo0N5)ZDJFSu_tnHa&SV1fQjwW=9P^1b%-cw6#&0N=zt$57R^=LGxGn0}88v3lL9^$Lbetmzz7DTU+nB_XrkV;xKl#rHjxh^Lv-&-pYaU zADolo&TPM8zjg~0NY6Q#Nkhr>{;;I|Tr%-+$H?p-%ettJ@(HW2?lWcOp+0r>R91Hr z<{1Cc+8)3b0<=k8@2^-`SO!}k-mF@5fbe%x4aKyoTb*q7lW2=fx+P$Gbi(%kn!qQ0 zAR`2@pBz2q3osBQPIRibkX<}mT^-t>UCLWDPZOq0A%kptjhUlIky+;;pM!|e(#E!;iA-WAP`O~Q%|2i$h0(un~k)x@7as(HC` zQXWt!yC`Q_pPwt9)3!V@x9hj+3-*_Zj)J7jg5UvPaw#JUF=@3@O!TI2I+q#_VwNh| zEGN62yPsm-O}xCxR*(|~k@f#W5fmlP2~50QDRT`iPe)kjoEF!QqYIC7#;=U-oQB6M z2f|#o4!yHoGtbwWm1;PE(Up*-5a8M|a|_$vCgN`Aj#rK|!J=0G^vH&x`kgJ(S`c*F zx;O+a@&lSG)MSU#W>6G6nmd(V*W&!slHt?u>nnmH^!R$Kb11^rXWVw4!Q7w4(p&9R zLc42k83zMo#<4}4#760EKD*fWP(Jea+1^{;p&{|(i;H6ADu;uK*N*##4DH``@pZFI zALG97HC9+SrjJHE?pCjAArKH|LsX#%0=?lS3P1-kkfw5ZCE)v@z&cO<&n^F?;QOwQ z%jXg_Eg;bIdYMBWkxrSMKSyp1XRO>b4Z#hTnzwBb0uc%z$i`l{X~xH$l4S1g?vTO1 zD4`}6V|@(_baHapX~Vzw$O1yS7MB)}&Q6TICNxI^e%c%OryXMfJ+nEs<>c0iMsZC| zMobLyyz516N4+R2o1%2Q33jr{Z;<%QD`#zcZ_fyNfCC5hQ6fn52K6L;X?tq%f zcmGeC>+#X?-t^}Q1?(DPuqBG`=YI^a|5X`f4 zGIR0D8Z}@&T2!zuWvhqL#b7?}J_B?O=>M3u72%B0ZI(T`8hjl8U20!8{U zzXJ4;iK&UY=H~1rJvJv7*ZGCDKt1TR98CjY_^er#0%=I}ol0`@uN?v;{+7b!73L6J z7>;u>1^Ev>-D2IE0!0MtrOWggH0xVLBiJU7Xp4>Fd#7Y!cmbcVeg)pi<}6Pxr#q^b zmzUpO*T^|OFHk@xZ*GI{uc>PJv3=x)G3v>mf25a{q*26x>&)PzcUxQA6(52%t9i=m z%UpF~MM(z0qqy#q0rJz+O45Eihbjm>`8{rV#}?h2G?P<_`(1hl83??8eed|(4*f%~ zYdl`Xa|Z`oZ!|3b0s-On`HsNpeZX3>#nT`A$+}a7;X4A93;?&lc__dY+2xa^{3E}j zB9Rd`t+KK~SA)cYT`HM)b`i~_v?O&@mc{*@+*Yn*GLItWwm@C)z>^~9;HZw`x7R&) zj`zp6Q)}akON{1&9OZOI(DCtcUO_|RMKyh4Qj#=Tv(4Jr)krPb41qajR2}*dR$O?P z?4K)XD8A0P6g2-DyP&!VV=Aox(TbjAPURmrY5_=UB*k^?zk;jP((>7V3jIA`IaQ0+ z6j36XYmAKwcK#XJUq?L=Ac4|)Z!z@(7R;@_nTV+j(g==o5zywK0INkG988a{3btr0 z0>ObLIZp}&PQjY9k)x79KtOPHT!K7Z&rAhj4_axsTYjKd-D+WwCf15-iw`MVXUViw z-wrm(cyZaIkfEg+Rko?MfvS3q&E&>~HA=v$jA^ck#$na`%%$iG;52?N{4T3EHZ9gk zLN?a)n}TWI@!KUT3Po&HUc8;jmME*px!C+NmbD?t(epR%Cs<*mla~yx$CtT#q`6f( zm}BCi$kA{nElc*AX&Sg8V^9&13{sk~F;&}&s4*1z_(%eHlCW7I5;7iJcm<5;X~V$6 zH>Y*|B9h$hf&s-(!jD9Jk&TVt?!x&KuL(9d6L@t(oeyA;4^b>^-eE19K3`KX47}lR zhhLa5_P(!?sv3qn#m7!ALM-!}@kRJ(@!H0H=r8m(&r93!(HOasK4p8S#GEH_QVNhB z6AUr967l7bj@xMyFu>Zq?`#_c339{FH8hEJ5{g3L_c>m9K_0gm3lrmd>RKGKj7(=;A z1U73Tc(RFE);5eKUiHmO^CLQv`x8EQ97>y=s{=9_EF}EJ;otb-=lN8Vn9m?~M8}Yd2C;tR=B`axI+QSB0o8D0|(a0f0ySuxb zt#b7wWD2-EA$1;E*63Q!Qqy6z}>tpRxD53CQQclkM*`d`|UEn`lnYylfFlEGV zApC~F_l*h2l)t;bue1I1;cjmW%ZFIdL<5I~hi7Ew7H-x4Y3%k30G-XuDv?{TQvziY zpVJR9p!FHpCYk=w)fKnQu=*?6Tdl+M{DI)pvm1)w__8tY<#zD(;3virtuqRna=j|k z%$9_k`zXE};CozYIXBsiz!Ipsg7EWnpiQu3B?JdLrxUa0*t~6zC5%or=T6Tw@=r zqkzACKg=;YoWlEeKJD$1k}s*c6^>Mf#8^JjuGYD8dSvXb?ZL6_=snEw9s@Rx&mWFkyMTX~ zGTHukM@;_xW$A5K;Dcly1_lJav7vMK_&B?;04!jjX=r3v^F1m)+mxBPIY;z9pA~?Y zIA!!2^Vj)KNkeOUL$7#RzBVxd8GHb2n`Ox>nl%Mkz$#RyEGU%!IDq~6;~EZ6m3qISDOFo&*hqDsl;ep!jaRjTi^QL_!s z{>wd$tlZ?y4h%zs<1oIoNov|L6yT}G@On7rioxfba@_LFCXtBAPulLoz~H<;Re78K zyv#AD7d2BdG;{lP(d855^h@uTsk2EitDGRH@bqse{(E5O+tIY{PqQ~B7Xsc8d!8TJ zIs5Of^7bc_de^fn4Wg5v$xflI2cI_`9czML-z6>mPul4NMMOI8`ct2#fkgUxqa`2e z=%6)qhO2SCkAwz-Y!hqeG5tY^5cKBHJtCVpCVO`040O!{>e|V`4pPC>dXCsHM)t%`f}HM%p0kKj4;tiH%)c z(H_~<#74bP-W2#PYB#|De$b@a=Y`AmeZ2c>e}k$RJ@xp4*7523YZ4C+7A|(Z_uHda zG-XVRas;c~tn~IX{s!Mh5)Zd#lfBM#QA-O3Y-|@Z2BYx4NiADilwy4h4(svJ)Jzs4 z1eP-9xIp;2fsWr~-&i7K&y=kR69;wa8ar5v*m-*9U2tanXtL`nb$`TTB=>JaBTq5; zzaS#3Dm{Zyt=Dhu1~{Ku+#~d40&5PD3e)$9Tv(+Is703wRY+>1<#56{+N8oTs+HlE zP$VR~xa;0w1(4bL9i}w!^jK7Lk{Ow443pf=X1L}H>G1F>r;(ZMFW(5VKa<*F8YnT4 zjW(2+3nb;lEm+f-N>$@eU=y*NEEvaflbV#|m4VRLIaRHMmeOYn?Ib&8!ofNo-&Wxp$_X z4UR~Wiv|i5sji{3aKP3SwGlc%uc_kJoNcqoh{j*`02x#zCW}JlYIu7Z!wu6VD$ivAcv5P7Q=Eh~_1Z9wT(9g+;k0eAD!x1PeoSc19Y z<4`BS;g%*c$DXfT3O{vDpd_~WWB#Y2&_0p2DxRDz%7!=rVsaI%izF^hVO{Zzn{n!z zZ@Sh6{cqA(F-3JZ2V`W42wsZg|vW^#LWZh|BuKs zEFGyyJdk$M>a{5=;#=7ipNPn7Q-j%SGee`1$l?|@i7XD6g$g3(0dK zn^hPAQC1cD?CvlpIm-^T;sw?!G+xPU--eg_wS4c*CVMAQU4-?&9`utxWeb>Os&pG{ zl(S_N6cDtUt@38gYHMr#7O|I-aY8>V58MZR_}_4VW0?TqqhJWrH>bQ%PUhg>`D}E{ zy8;~6*K$uBajjQZxzB;37ySYZHY?VY{ZwGk-MwyPnyro2mhG4LO~1WgL{jBHB}5F) zjF)R89Byb&%F5ckoE}KBJr1ZI&INj47&-*YP<;JreckfS?&{*_1|E4FyrPnl(CiER^(8N$CmLUG?PlcCy~(90`Nbr4K*@y1I0ApL!8E z?f(9^)@*Auo?;&o8Vd5t`3i}^2>f6jMU4H$n>+v8k%&bTwLPv1w8+qqg!_5Z(sGj} z2F*B)*WI>+>}J}4S^v!q5P>Jh$j8^;`}K7e6aCP1rOi30Y?KF3j{^PFB6Q{(ze6v_ z_1fUO1Wh;!IXQ)fwk|oSQqI0i`(S1_bOrc@JT6v{u&xvrj2wJYxMFwr@H6u)ey7}v zKdUwK%n83zFF-em!%aH^4Rm2kOK2ID))J%LH~$Gx*fD)O5E!@HaRX$z$q0BsQIP>s zFj+vqjLUI+ar|@XVgqQEqc%5nrSb3pVKlR1S*^*q8nFAje)BtDYawA|%|L2sU^&}r z$=OxFg|vRUOH?RRw-kkfg}s|!+6p}6p{=2<*VPdztDK2L^x%JWIX5)-2=Hi{TAu*Z zdV~d-Ek0mN2If8?r%N?VEG^PMFBJCuZHb-cX-#|#{5?>2Iq`3AWhw=92FF7MRvQ7GWfsFXI=WC9T`9+u>= zau{wT;eNfZ?tVO&iYQ&z*4Vevt^zCx6l@9FT`mu<`(KX;j`Cl}hYT~=%)1VRp_sj zGW?zo=f)l<=oP0l>uDY1&BO4HfBzb^^~L>k23lz<;LQtf*rWOCwq>GUqlkbWRM8t( z2&L38niVcJ1*Gz`+|t~^Ma^w23<8O;gRAR0iv^flk6O)7=hPzMqSC{Q`M27t2R5bZ zLA57>Rhak$`%=%W{UTo_SreCR82OllOzf!?e)W{oL<6|MKc#>(X#&t1jgODRR#(kN zWsph(M@}w)$)H z=yWUTE8K;|eZP_VDt4co-x3C{cMXf@iG?D_%z~;4vJyS$bc@{LDzIBqCxX|xHBcS3 z6H%%jZH$N(QSz_)sE{cg?+crk0{hrkvK79Cr!Z)Zsckqo+@~@v?r_Yf(|)JSqH&1S zVRXOOA+d|-Dn z-5w8Xw|WOA4?%}Vgg20vNl7`2mn$<@DT=R|RuLtF&Iua>nUD*}hJIu2?)=^L_@b=Y zRJ98MssWFQjpx@4`I}-FApe#dgpqU=fVc#MD4F!d1YGksXi4HXf7)qYP@-c+$`zaR zO8qwtAOE2^6DDdIdptHhd<-8vP$JZ$Kvl4UVTL`4EuGa?_ zdJ2Y{kq`F4p%uH|VL*(K28tOKY)mcNpqNah*@epf$<9PCNCpPIDII24J^pj^f#S<* zZV+BUQ*AdRC#FG8GCHA7qmz}+@nSe(uX9!X5_%ED((u!lIs!ybqJ`Wjt&<*_)OevV zSdoeYINB8)2qGcO9Z8HOMuC#S(yj~4lYE^%aa#3tvC1Q|q$ z-*vea1rvGJ!)_j*QYVgb7rNO7H)F8TKLhN(X=H8(g%FnReuKA>LWIU3(@7UjD8`x; z4=h!pup3((9DB6iA=l6x5#^w~4u#Y0Ya}qytkH65e}rux^cstSb5WbW8R=6yv8Hg6 zi=Q%hcKIqUjk`;z13B$%=MBkWhgdD7uI#ib3QFza1lJ^Ffz*RptYBj{O>0B`<$xjY z%0O-x&X*cO66P#!23}tv%g8FLN76Tr+C(e%r$SPPGCKGi@?32TfjyFrE+N)i*iRaz z_)^wx_Xh33);H=fo2z&1jF-i=*o-|LwR$WVsq?q(@%j0ubHm&g>OEBF){EjFRw?Zr$*D8eE+FZqXDBUZm{*1zpr+mUDi9XX!#3EU0LT3wlD7z z1iqQqqP_3!@Av0de;?&4z=v%;*Z$Yz0`2b8?ofC9gm>fh+IZl`z$MsVm2HX%XLaOZ zYbmP%z>kJGoW70B`3zu{bH4$M#oNyWghiqySilTzZ^LzS|4*3;fG?ci+L~S-0o)n_ zQ-IGQ<}`tvN(ohoI(enpnTD^E4;Xhca&e7TX|;sy{u=Wr`d*>{`jwTnzZ*Nv%*olq zGM%Zv)zu03TS#kQ(v@nKS|9e=_@DlI^S_?4sHv+jH#_6ByIvjuZs+bVPT-K`Yja%exWlofd>579cw7ho0V7 z{X?U6E{8i1kbY;SZp6v zh?;av>q-(Fi^xAmXCNx5c=FS093CFuGvrd>5mzKI@NJyIr&r6id-R!M$_Q5S7!jO5 zD=P~Y7EX~m)%|_4C9Q)8rf>iGFz0ZzB->CwH)qNBxh9j}JB08Ga7o^BoNYEm_J;x* z$7%Wt`OTl^O+#0T0^Xe)oH52GCc&CjLP`t@JA@m4dHx2~-uBrnIXXj6hfka1avyui z7+g+QpjZO#v8QEobab^*pFodUu_t8{ETF8@(pC96T?Zf!*)z@w!OU`p8sj5=m#$OO zFsiHnujlU-W@s$l{>cBM=`4fdYJ+VZBzSOlclY4#9)e2g?wF#1H56ooPn+AAP&+ClRsi|`XrUY9Ckka+d z^!!390G~> z2T1S#Z7&E+U}xFffyoU$N1KOgcNfZgk!k7h?BS9v}_=5f;Q0<9&%4_nfWt% z*m+ZL)q260aApY62DG;_NZ<^g@IV1NJ-h6i0XgkcLN1e?{~crq8@2k(+I(IClVe#Z z6{J%Fsk1MqD<>u=n@I=gxE8HqI49zB!}q(?B%*92^sC&wOe! zm7yGNzVwRW`{BH?pGMWCFh@9(qScKTrL&A5dobDzxM)&2Q!U1W`+4y%=%b4q1R};i z`_i|(E}BtP*)L{t7tD3ni554nGvZ(m6G+(UKBvxc%Pb8aY$f^p66E2=^!j=eC5mIE zM|S5KZ&N{GE4$bU2Cb}6lTp$ycoJ#9=v_POtREsk$D+#Y?jexmp%#JOoHWfdY>RYP z+D!R#3X4)=PY-9tF<IfXFKOSeK)@9(w} zSDzip!limK{$0s@#Wj}=PGTT!Qfp?EPK>95r*A^ZF&mr;=Zv_4A_*XiI{TA~ov$6l z__>JGPVCPwDWZAYdFt|XEt=+S+z^W_cpaVqpDc;3_KLt1*U~JyD_C>fi!)Onmvm!q zFj?J(lTr_qr?0p1F{)gUWBx$EajsWjM^a0x>nWn$R!*bUhSQkPSzva__l33+INJ*J zyE^F=2|Y4IEOY+1@BdnS3~!x>(+eMPB9NKrOfFr5zH4Uc71$t9Yl%=htMNR1N{#j9 zwKHg0A#?VvC;jDw=d(@kGk`9-x+IF+kM4(xo+>w5jX*u zR2bZX3Uk*?x?)SY#w`(<2$Im?T;&6=VoDI$n(p%M<}We(jnQPbAgV@*7YW-+`)h;- z%fw5%C6R7WE%U*X!h}x9!tZ^Cc(@TD?TxrQ_@WdyS;hW_&j^<-iE^M)^4rSfB-36l z)(+n0|Hbg78l|5pX#eN0QVox8<=JKNmbJh!wL;3m1a8^yKQ9LEyjq+0)3YbLdmz@l z^GO{9ic$YCa8(<$_BZb`{kNDP;CO(W*4;W7L%<`Ogh@x#sP@nZ9;m7Ascht#63T{^=A*sfdS1Y<9K;;w++G;8>`tt}3h-Xlh>>gmokBF?d66_QUYk zvY^@PR{Y9Awl+@~{4{)Jzc)8%FV-9R6Zz#zZ~A{5yZ)H9YV#$X22T zzwFxT?H&o}R`6q_CYXzKK>vlby3WqYChKMA5Q9imW|)CCM8n$7?%@)KwAFT7eyZ)= z=S2p+ZjaooWuX7PWZWiG&fKrtvo6xrdgY1HBiQ)aJJ{r`+4glc?=4;UV=Qk!41$A$ z!{>F?{I$mL74dl5SG1|ZQO;BXHStpfDra55YX9F^+8EZrUc?hxS8`L4QcBftXk1(r z#{3@dA!(lAr?hbN0fL&3NWkm;Bdt=iy72p@+)2AfcNl6Yzq_6D-yC<~^DRWjDepaz zy`T^lx74J`m5l4!e`H4COfPJ%jsZRK`NdUPAmSv<836;sswz!jxDM2q7)4kU6AXXO zG*XNjMfSwZT0Qr<{~M`&ccNp*d!mMk~ z#K$7M?~=KAsfw9t&Vn;O*0@F1S^*PKRAc>5H~RdZBfOR*&<`x!oD)EU{EaycI9g~S zN<{urQ2M#KT)2%DJ;!9K20SobzP`y5WGR37qM{HtTE9ZX&fNax6Qc8fXz?HD_I&{k zF}U_!?x9vqVjzu{WrXdKJI0a&SYjgmoX3)Q+G4h zhbyDy?yk<)qUCZ;YXwGT3YSn$(nbhSL=kn27ZC)nS~D?B&^-RGOz{~R5lXxT#oSt= zdG)aha~dulabaaq5T&e^o|cJkmlf35+KyEaXTGac;^3eq#wQS#W2ROjVgkb|ao5d@ zkkD;H7@J$;>~OwBHGVSwzST8nKL>7x(dfB0MP##mht6@6Y5=yVt`;qUafGOI9D?RI zEuxlrB?&vrbr>?6DcuZVel_wCsLyPrO;p>_Qe+OOsUPG1QMIxpAqX?*%LkA@#7jA; zH3Q}Lwf1C=bmWbDWr`ggf|W@jO{i7thB=t|Th4zhH;>>F;g(v&6h6~w9UGXEep~Wu zJ@8iN+{nz`y?5W*?}`&T8lRHQq^3yHI;{Q2>Y)Lmqm13(ZPRd!au9jswTsCABZ=y^ z^GsD)m_potgIaALp))h!=xZIoNYy;vCIL4hbbNqSU%rZ>4v6x25Nr1LE&Sw#W z8Oj(N@t3R6E2LF*WKdClc9@M)V-6plUn+hGRXUz3pM4^}(q_NuS72`wcvNGtosAsF zmqB<0@su<+Wn~FpPvC`(&u-r4&*_K%yZtas7-Qe!QV4>YCcZNXxbFzxr-#9-(-O>^8#0*mYg*yW{|W*(rqYaQr(qd) zZ5#DNYkjr(KEpHK27fkgu!@vG$N{*+PKh{KgCdGzOrzQe5Y_U8!GlKdfvDQ_7^(bP z%-;}kd)gO;cgo9IM%)j3M+{hUt8yU3Ih6q>MSujP6|bo2 zr;STAz|T(PEHJ1L^{Y#sw|7VZ;%y#jR?tI=xf>p8ttw_>k34bX?iJ z@a}gu=`FLjO5N@4lao@J<7^k-Xt>(b9Xk3}>MBrMRdYg+mD-T?XgqL~-uB;kGpqK$ z49G7|OfNwYGoIWOriQ0V==i>I4B#T2FB@ji#8hgQ(%Ze$tV+Z(vnoJU)w7*{Ox)a3 zb90G1d(CZaiELdA?#7px)V~%GNNUu%07R|gWC_*5`FVCn!k{_MzgVf7sX+hqs6PbJ z0#vbl_Mg$U4Y%xGFk_SG8ZciGdOE=9e!ZQ*MvJEl(ZGv6+mVUj4%GpT13Q$s)`x2r zoUPsu%s?Soxd_Z_$1bY5lLHp5Qh=PP3eq?|JEQnVcw}Cxt*c###sx}@j_DOiVEX77 z|LA@Qx7~A(kt^v396%o*7nJdE2`L%FY_{8y_JO(C^I!bs%gID?3oCK*Dt4X}g62DP zBU{cd8aMO;(9AnzCNe;|b`?{PIv@k`Ok5R`IsObZI z+|$aF&d$ekOXAL^24T&ogCIMjHXkD3_CrQ4^Jvmc5g& z=u-;&C876LIjgIl*f`jIz2mp+j(<$@8=?}ARh@|Vpz>}CM6J{GD(hHzluOh^d5JSL zis_5yqSN!Tj6EF#-fUX{(=0TR)>0r)1(-wofW$F}0dQ!m~xxyM2K@C3N>`23) zQLcBtvZF4e_I&7a2Q)Gb<($;9Ye?yIwkBF$oZ=h>!;q6@NQk|RVNhFiAe2oct${TDnI(iKkK%xRt*Q%+) z;4}##>o18Ag7w6hHpH2`)_o zcN4YfZoVT^1_QUCfe!aPj3IlKj2r% zT}$FYY@qmsW}VLXxuydb0%#V`ZLYQyXEHy`Hl%My)YH|C_c%>~j2afUX9_$?)DS|x zf^UQ?O>z3V?z5VI$7Bb7F8y5o7Eh-mZpApq-_$yIoK}5(gM*WiZAghF#C|gP;G;J) za_<}Lf;KAaUM`7ZY(W^w-I>}>7(l;8j4K|J|n2#UaX!Q*GR^~TVouljd z?oG4WVSNQf5jcq6%B|hood&rc2J3M&y6?lwJsuG#(a)Kn(Izf; zeUb}U&dy(z z7~A&!ZOzsZ8ueG4d>E1}KAyJ8tg2L`lsQ5eQUzDPNjhU6t~ezpG;w!wc(qb;V^czw zg$XX{vlm@l+&tQ1`6*@>AlFY>EywDv!$AS_t7cne5D}DwK6}NCtz-CjfiVD)$LIqf zImviX`c|`O`R5FT4gs=za!p&_Uiz{oMPsjf<7UBZeSc< zu0hXef> zo%mT7ic%`!Pi56&rNc7w)fszUNF(%B%-J$=JJ+WeuaNbYvyE=ww_Ig?mSR2n1WNQ0 zk&I;iq?WaAGTj$-=CslIWZoFvJg@4o-q~o3%&@o@i2u_9IQEbK)v*S#qZBs}BIy95 z**0Cn{Y&4DD{Nazi;39nQJ(EV67;IV!IacSHnE*nW<w?ei77W`8QBbKPLey*ELqK)HingG`$Q4eZrB3z&!PYQf8 zpZrkO=v`;m*QGTzX{r(Hn2OAq#5gMb#%{feBbGQ*$mKX1lQ}cl7%HtfvlNr389x_r z1hckQ_qsyoGQf$a?Iu7tU^*jm08>POY65aKGGI|Q#Y<`8+LLlFB5zM9{{w>{$U})F z_m~?-ajWv+JDyl0ZRFaHCea+p{!%uGzSD0L98-d7ak|UPeBb0cohvkOegHi{G0+Jv z0>)Rsg5_P_dopiCMsA+DmDTvWlAOSdu?HakfWX;qnScxYMT&IoOOir2uO6U;MlD{M zO#6EszeOjBPLV@aRcBTK^Ii%7klOx)3oOPfn*Rgy*3_S(!u&av)BUrxbtNM+i)sbW z$;n?SOT|+5dCF1){Siudp?Fdm4#jLr5PoSrDGF_Pr8J6^bulW^moGQx4K#pAMl(Gt zuc)Jv07NM-&j9Q${u*(+6p@i_+WKK@n**F2%u37BbGs*+ZH>>jI?`zJ{19f~JzhtR zz$CmPiKYr0IR_JG%N5cIUoQEO?Qm5pG+KQQ+3h>;v6W7o|IMoAdc4w(C};0PO)P8a z=#MxCUo6jy%JFEv9PBqi*fxU9|7t~;7$ybsQ%>Ue4mDTu^c6xwDeXzyVcX9D6loWus+JIEx=fifG26CzBRsv zZf$!;Ke{94+LoY@n8X;UhhnAEr(PhbG^sNL+F#jcKpdWGj0r2P)omKArnr5cVW-iE zl&<8in-p|IT>p`Ti0_OJ@T*ebY-b}k=+}Vsbhg@qq1cd{NQJ+L`#lQpf}qrY{nLy4 zmHF8T_INODy+DX51w4GO%!^D)enNlD7@iQYuBpp0@h3&P%^y)|Y>CG;2$hGHOn_wM z#<2_CKxOzrUgMBiPaz7siAy6&r+LWF62z#TwOS_u$I4funN@tkDN04B{Syl$t4^c% zvod@Me;#@2C+i1-A z*a7y+gN9nS{}IjYyK%81oGLzl?jzZlP72~N%WcEQlQUmX{Dm?9wfxp_oNFb|&N#U! zbfG%OpM`74KHNC3hsa?Koipr=rF$;5~~TuphXuhqWi{Pq3ReZd-0WA zA=KE%#YP27^8DaU%|dKj8XjksR+_YZJlHGUX|1>bLxt_n?{vl~czxRB1C*dcSgwpQ zOM6(gr25wOQGSxniP0rAWMaO-%eRgU?Q~B`nSba{*iAG%`))IBDYN^3BXsyb?d6Be|E7q&t=f9au9lnSf$k6cFuL<49l(=? z`lwIN(mKDXjNTe#$yq3nPp7l(>p*X5pS^y?X-YiW^&utF%x<9Tt}iJ;_EEIb?8eZc z*R-gkivEbyP{Ibk%ti*9XJD7lRxa9sJWPk*byK zA|;`O4Og=5fTP^c|0f8CQ;+-kqk|lFr(h-zBidgCA(X(eBWMV zr_hFG*zsk^TSlR)AH4OD)?jsZ_AHm@mtNNE)n?P^*lq)#5hF*p*ov%{r`vJU4KK}F>z(gxEd-I9h``Rx15HWf5vOsQJM^RheYCH9-Wc>f?rVh@%%_Dl`5_;}DT^R!4{U*~(K1SayzUVi^4 z4V*r+)J~v=>EZNA0)mz_5)ffV93Avu;?;gci&Y>6^t$@`ps+%2BLWqs`3u;Vw;EuD z#Wpn|RIsmEcbVomjC8+!&iX zY@D_)Rh*ETGLc1e$yCjt4~ebA+nL7NxSx2E@%r)0j6>DZ)^mAaZyyb=z>TMqgDor3R_pdfZrRDm^wsj8 z@V40HwpD}!aN^688G%aT6(+~pY3a%+_)&8v_p(QG{Ax)DvCh?vhd1ygwyf6G(R7QZ zZ;hUymsg9+J@@*6A6W{axJE@$C82K+k8gojJJcL0Hj%PYo)RvTzKD}GT$i3gFTx2r zS)8yXjXjcm{I`#}d4Y~7&DgMG39j?i_EjfwE#UAZ-yz)8Iy}U};&46&$g8^S7fHa7ab49!i}JfI{}~V7Ov@-QZ%mg%v`gP*o*U( zx}b8rgi<`fiq7>5r&`ORzMo6@CfMs5WdNpN#ZT3;X3@*v-!Iu=JES%Q_GMvNhXki6 z+avx5mM8kcaze+0k70ONRb}f|I_w^vq4XB^fm27KeoJLvj~PEPme0a_^ZvS)vj0N6 zU)F?u*T)qpKy}8t8^G-BQAB?wSZCc14FffNUpqiaPu~9jQvE`rER##>Zs!dWW($<( zlb7z7?-+Am`p?g3yh>XuEhHVHWUB+*=I?W}#GG^|VeN$^)<1^Ap5M>y8$?mD`X<2n zUJReih?ORq!#3{H*&a+xguNaFvn&SQBxE|ioNl}%FcH%KT=%GUB7&d!_JOD_s83DMn=~}e?LF&#etQWw~&dY80N?i zBt=^bN;=idJ$~fz6_Es~0_SxZG7*Fz4ft*vKq6vdV)Drp{RrDE{HN~n!W~ei(%U*$ zU_yEusXfXNMx(ba)W!U0DMxHT%YBN(_Jf1o`L!>;6LfaKeT9b{IQu~NnM{=fuxyDX z@(wgs79LyKLCy1bNmUjWn0T^IlTA#w`jfvDJu9}8CZF8F2kPf*Dbt|eUu!yhJAXcan~+zSR!ACFELLgtJkT?>ZMq7Mim(3CFONee*zvaZLtP2^ zhttFi=C11ECOVSpW-uEhJm z%bmNx$pKEddWnLf;>~o&6)8~|U;@w13&?Ejg>w!ubEx#XeKO>6Sgw!Odya;uvMfLu zSy{VX3s>x{D-llb&b6LsJc5K}R_0}9Mw&e~emk)fzGU|A8k<<&&Z`2swyHrF%i*sBH& zkQ(Uw?C@`k-;4Myz&7?qn}OX%t7I3kDsviLn%Lj_-yobkT4-WO*`lqT%R$@fJc6U~ zMTSWhruaj};$$;d*BIc=0j{>Q^IfrJ^PESV&5yf|fTyKkJGOONI31Dn)N*CSAhe~u zKRQuXNc1h!)9_G8547IS5k_n*@k6@v0QQR!vfcAJ6~cOkK}TARR0sa&61l#PsfXzP z5hZB)Y)dDky4R$6QZmzWULk=B&oMiny~Br$FuJ*qO&ah}kmV3h#A7#A8BgpKlOZ&= zZbUfT#fx)l%Ocv3tMh+=2<-^HcC<88+;Ag*5GwAq`cl1>`NPUF<`4WS(PpfZ?=|GR zKX~h(Z0x?m-D{gSVTQIg&98n*HAs(06M01|Z@2c6Tya5T>*nTl3GESd=r`WIUXSBRUO0Yy45IsfBJQP{ zHzq@p*DNwC^TnR!Zr*rjpRl2zWh^b#(rKn#7n@73BifPnX$~AHPu5R(suE<@L4thz z1d};BCT5no8rHdOAshlL=e6AnCFWRn9EdBSq7q*ua4E7lpo8$v{V@2?lMV&JUSD&j z<1I>u&i5FdrzCayxYxb2faub*PE+?aMk*>~NOC%_L!`AsvTUJ(iH~S8 zcpp3NRD>LFc~#^+JJWvU^I;Gv5l=VLrysBBlD{go3^HWMBYuWVQhM@~ogA$M819&S zE=Yi0A_wzR`Z)&cXp!5r=;;D3F9>sp&d^5!&P%fkndB^_vU5U*Vls?=DUkcW(wO?- zwu$BGSm$fI8~SK?gmy#LSsYG>COTio<$a#V%8;I+qQUpitUty-{7(dS9Bp*6w9kem zLDL;WLKLgM)=ZX}x7WK+Iw0zp*1p?Y_BX#ggC6Nj>Y~@j%-%*8guNKtil%m*EK(m1 zJnx?yB&>^nN&oik(cx4qZ{i`3=9X_`Gaku^_~=9r%i^u0$ykrv-m`+uD~Q?QQ9HJs z#KyH1Uf;bg9O$e*CNZ9LSt>34<9@O(-@TL%AufIux;isu=Mpr(Ft1Cj%Q8W+ zpz=Q4J`@y&xgOBYb^pAeeXP8$RJ^8qKB)BH6*r{RyMghtc2O&Pxm%q*COBeT8Vgf- zUnGyRdH_B>t%~Dd2pb+`OFC`f)j-s`O2#Vs=RxYu84FITuVYxG*jt;ExHyARS3=^Q zcKPA8*}TM77)ZJUNDp35q=o;ZGXd=)b`FjKX%asX0M`U~qnJ6KV)9L`oT2=8o&VF) zH#F~BFuK{$X6|{$uMuvI3kTGnhgj3ug3{*pc`w%1Ha2!YK~iv0%hQ^y@poGYs@*XlZr!PFYOhN>e&ZKLk+ald=WY`thak?X=m+MX(StctGQM zK5G~bKZYA5l{7T;&F1p5p{_1s37-nu2$wu14FT(i0P12lc#T zpT0%8gyLoCX1Tloh!NQc>=3tD>6yj>zDs{vOu0x^3d$1W!tumy4rbl^R@8hZhWT$i zX^ER%`dfZ4w!}hu`*$-ncR5#`;~Y3FkboA>*z}OtzU!W#+TSlGCPp!kG{0pV&_)VT zD`MDfcMoN4zZhy|^ABx-g_djl`&s;NSb)8On6CGDkx&~Oo9j#OD>j8^8#^Hrpg9I? z0be~l9_%x`8lRDPo<5~n41Wn$`{(T|)Z>^$@^PoUvU%ZfHciwxM@s4aq7Qtl`j=Hz zv&!h)OG~u%NY+1`jf1wkUv$CEB=t^b^eD^AZ2e9jed6F3!D@ppsZ`V00%RAy_18=H ztAu-=HveP%7EMh$haZx;lpBWHyM`Z!WhaF@M=@u`WAUn|ZerleVp;pCNMjVq6(g{*orY-}eTx?I%A1jH zqoC;`g2|D^`bF3XptG}dcS0su?)pp8EEf6;>29-W5wg{9lCz15YulQJy1f5Gjq1c; z-(6@Ukc}}OXcQ(K=p?N}7Q{q3YvY>Ov3iEehAI8!of(7iea_Lp-Re#fm;Hu|EU>^G z#OTUqdp8NuFdv0zy}#1DR_CF=yNYn)SiywzCt3(=)IxAzW`&Kk;rUO15=!^lm}GGG zB&dd_8J`8esum6PizGiO_?%t`3((2O*2CKG#s|w59ZtZFZP{d z8++&FsMHu|OzIFUJ^#>ax}WKdlg}`ajV9b( z2_fqiM^`nTSZybT4!z!A=dPTh5T{6O6d@#9TRV`0Ie$2ha;8J0LkuvVPGe`4rD^%R zabbt#>*LxPc8Ff>!qhd#cX(0nQ`aFRTzKMw$M73WI`~aq65mYnK)Gb+_(#)|3s$C+ zoM0{8ZR#`R{467Jd3!$*C+gk3yP02&#j@k9cwTfL^OpLsMrWS1l@T$Yx0O=3#unZA zH468;{J#oU+?GHi$f>Ks>G6K*QR#b@xz&h0;+_{FMXM7ThA=9~R+BWU^Ngjd!Z2xx zl=*zpsH|pUQkt)dN!#)3Ck%N=FS=ADc)rs*?S+otTYTlrIE1PJ=CqGdyZ)%stre`v zE7z%R=f$glZl~8XHbSDm`|-~5fiolg0XZY^!U!DHsPU*5J*CyFe@_ehR;I~Oo_ zHn0q>+yA>e6Y23uGt~q?5Qi=^$g6UT9vB zf9p=ul^W2|?(lCL2Rr7PLto~uEZZL*lqJu*tjGFRvtjmbZ3&V1Ttn1!gYkjqk?0-# z@v6J^c*mpV{rF3xa_I1w#o5m@LwC9Q=4Gb(W;KRDU}I(f)%)sZyprX*sOMe&J@4b$ z@To=kISv;hEw^WKZ;xE~{U+{dXCThwdIus#12I4pLEO8vuiqz&S8b!sH|k;AKQGPD zFM#Cz-tabvl1n6In|9a>d}P`X^?$ulnrMMI8UJbW*l z7Fkq8k@0C|$%6Z7y0Ye$nB zDje;j^%qT>CS^kmNFmu4q)I(z<7?RSf}$|?yj znh#k>TZ+b0hYiHo@pb#20fOx}W&kVVKW6xL4ZG3moAmZ!PeR3{aXhFhf+-`dfrd@R zR1i!H2gh*a^mWCRQMmw8C9;@SWeNtdOc{-fz{TCoqxL=CuI4y4ZT>49eXR_@8zEEC z8kzqlhdvxhiclvOe-;Qy1Hl(qLp&o#x(tD;?3Hq=;cj$!b#=G8SXl+CxvLR=0Tw8d zqzH|h%vf=2o58;*W$88IlM~4&+MZXxH*@oNUR`XXjmEpgFKlj`SzE_2D$?UT0=o1Q z7jD2vcw6P<&ydiJS~T0a%@wfi`jX1E7GxrmY3>px z{yy^YNHWSQp*vyFf@le&;dnRf+Dz>BC@F7LPuz@~Ul`x>($QmFvux_?8|EiWfdm;G zUj-6Ap!v8}?tCK%8EgON#)B$?D{=1X_VgHp(&lgf*&6B1Ag;Rx#sAh<2816Ou|3kn z_M`Zsl*E!Ie6e7ig#P_``@`W? zFg*}WmX5cjbCO}(6XtgDiD9K{CXhux`0wtf`*xJ}Sni%h*snK>@*|M^F zRY<@lPRSQb8XeEU1UPU@DjAyvP}(hgLp!w-(InW*J@f&7+jE9k{#VC#i&2iTk4FFD1nnL zt5$OShGE-`G>OmP_WPCpL`W2l=hI=D=i?69fT-G1ct!qY+Qg?y{IG}%CD+}2H{ zQe3bX6Pne$al2#|12F?&1@-d`!CwFtPOssZ1(T@SgMLABm0z65H`r48!#z#m@c;u@ z6Zz}Kp9y|;Xra4**mGd6mp*`kRI%~7A=-yKEbYwk)677%aB5H3!C2ovLPwOdX^eCztQEL*5{ygI06PEFIVfE z+q=h2UkW)23{;eG9BB7VgSoA(t&zgS5lCm80n%eD`02YBzqNqJxrdxxCiO!BwYwkD zv%}Zs+b_%wcX!!c9>i5-1V~ROK*k(P*}emY{?Xpe9_@9GrrFRR3RFdpnRAYzzR8m+VZp5 zzjl2MO^sHk!*2khL)N?{2#oO$-{t1O?4rPSFG=4nm_7OOUO;(uMGFcI_4hAYqy)G| zI^0qyXwniV_69$+0OEtH8c;*af}~EwG?OII)}1um{K}R{X_WqNj`|_CcDzj1;NaYZ ze_Hhmg{PJA%G#D2dWo8blC$lXj+`z!Whyq$@vSZ5fo`c4OvzA{#4VbJhAN51+WAOjJxG^hG>cP&H0YFUS0~z!wM7%G73>IM zPEF%MBa}^OxD;$sY8LXj^3mV5@CwzV)c~KA!30R)&u|2>Vg%H2h<3G*d~%5$A)|a1 zHFR28iug$`f)g8=3CwIE*MO1`Q=P&XH)Uzu;HLEG{Zz`-j)%+Jxe?7)*E8%6%K+@i z4LC2^;UBD|iX4%8NoUEOqcVvQV-9cw1xXT0g7KB#V3(}+Mc{g_$9Eqmusy7r+|Z^c9j#UdsF{m@y~ul0wq9AR5+U)3P2C zjiD2UrbzH-X0q6 zS-LVr2&4b!0TIR0IjU>lb(l9&7mw#$t|n*=PaiqvIA3SbIk3(EL6KU0PvN3E6DR$v zkL!F@!;=qTUxnmeTlH)}?s@~?uo;~RIwa*gT<~YcZU5cR(<6$2%XBTUxabo0b@x>A z&pc$iAQT8M7^zk?sExO@Aak-DTeV@z!HgJ2pPlnXu+dIU@*KW7PQ>+8oCXR7Oc{xaHk-cVn4-ZAG)Gh=A88X1zuBNi>fz+Q65sZtTe z7)zRIE0r}&ye+;k=INU~P1YO!YnCcoAe*`SOI)azOjf0dTnj5wI&dVs&|5BxdS$sn z8LtcL{a4o8$@4o(>`P_Z&POrf1ue<&N9reitnT8Uc?iWSb_r=L6m*|OQTbA0NjZwU~a zSLZkeiWa^OD^))QBYV>XqkexEh#ccjfza=f)~4~zq*+~b&C_f%r2B3>+U_|CmrnxG zG5o-=Fb;xtjr&QJmT&duNgY>toB$R4MKS>h$a6X!Z*H7Qd`d!sQ$vu-#sSkeZ?T5W zPa#3ue;zIe-%ZZ5+VhVG-?h#kBT4)%E_T&fAIi<&hJ_5c90~}n^HzBN5SLjD8WVqb z@UYNyjC2I?dIV6!GQ*ijc`qjEdUAD4{r|WUf94}ec^9_f*OITwo9*zZ zbHgOFc}<7nHlSb(rBrP7ec}FiP4YLo*aa#kF#e3-3!{8lYP?u2u;{X=EPObCB6M(h zp^KErOsdu9n&bcXYIb}5VCt%CxP`^AUuOce-tu@Igz|V_<0o0x5Y!ZZi06K_wX50V z7v;ur@b^mC6yOQxY1?gehN%CTot$b~UB5z;WCI#i0N!x@zmqc1c&cw`_)^*naNo|X zUvH0v#ecN33ZP7y){F z0v@}6Bp;7?aLFcarIIb{(iQPj zF^XHhFD*cVae6!Aa^ru|GL}sgLb>yO3f{epA@~Oi#Tdvr(dK)M3^d)iIY2P( zni^f?5YOt2Y@G>gm4Lvr00b~U%I zdkj9#bNtv9M*uOXSm|5}(a%WRaD3DmSLe`eml_<7c5P7|#W50HeD*XFaL^_`&LM)q zS=Nq@UG@|ezVaSM)rzDq%^M16>$lQ7mt%u;{9W88iANKD*5w8CZOc2PFtfc_frDcPm+1mtl3K~6AHg28VwGM17^ zru|jn&3z_95nZ%RYS$ znuRT$K*b;20A@x{GrWI@^_*p+UzTL5T(67kAmM7s9d7zfq1k%}$A|Vc*vRe3193~p zlOyAe6i}t0MSrPBipbGCF+-Psq7x5BP*Edg4K6UDPHx=)wY$ZwnpxZFk~st>M1u^X z?v=fdy-#j3lC0^NIR=^o>xLhpi!n^>m~dkTJ<2u0KUfuL8;7l;#GR{>WQmbUiTE;1 z!hUujWgYQ0Avb;rMkHg^N#CVL#frDK#R_UwFdLh!E3}#M@zfa2vuAsIuzJdiOVi^c zn`ka0-Ytseq6Zi^yT$)Nj{L;u`?C}aux)kcGnmX|MF=W9;lBl^NlJHjAT`+D8Qqgb8m+^=Rz4EO>A%dCbPx6%8Lm;YK2V zzrJ*T#;EqMlgd|@QDK&1qe_o5o=jb}vTed0ay5j2k+tiEi$ERrt*Us|Epm?3GyZ;Z zS5?(Yb+Y5N#$MkNb-@USk6Au*<2cyvV(@>E}AicR}Lg~5z zgCFSp@l|#2997l|A2r({O@eY4l&;Jfqp<^s7pQ5#an7$sZsm8a&GtTl{th1zzJg%N zr;paF?fu1>x$vvGhp+D`XA3Ju+9J|#e6NB&8~=P9`H}U&BX;|sh@qd+;Cd4Z*!c8p z#@HN=x8F1By&X=xeYGQ4sy+f}SgV~USNx-oGyaioygF-kb9(M*%o?h3?Y2gQq^4{K2ZS%LU9Pih- zfK3+_wfwv2%Xj90WS|^NDo0B!g@5V7)IFelV_vS&H}$;`!j4ixhuQQMsog%iX#kKM zE!&Wz2E`cmH&7FqeY?x!6Or~l{bozF;?#@u!>PCMKK{?+ ziXWDEdG1OA$1JZG`h3Gh^k?hnr~}I;cj#E*g@~9e=QWZpf1N9u-k|!}x&H@XL7%=R ztVCFaB%sx3KoDYc0l9=i0ERFKv9_Sd3$$@@%pKFk4XmvPX05@?9J`>6)(T8v$TP>j z&C`NB)f9yVs~l)+1ckO(6JTus1Sr)&hOuMWMoq%jEY0=;L=CJ6F(Saq04qbR3?PWW zGj5IYlJ-(yr6d%VKv-f7_%u7VvBByL6-cDAWJ!X~E$!wEuf6ge&YwPm!4NWHF^`%5 zSr}MZxySpzeV1SV>|e12gmDWYVW+c0ktSYdUQmC-TtkzC)gX*}J&eC_x$45b^d88? z#VJQPNqb7CT`5UiyF=AB)a!z+VwO9neF^rteq5CCkV{;_ii(Y5Jd9AXb**v07eYDE z4R>A`hGc0v{|Pbnp5mzR0%wO4ul_1Eck_gP(8_4#GT8g}82 zFEJnodfT!6N88Bxi>O_A{5BO3UhiY7x^aY6k5#`|eIh(%7Fjt2Z0WHc)f;IcKyY#S zJl}ogc`lxs=d)|qxO?>q#oi`lIeF11*;qj}V&a)LvkOaz_AKd{W#(UcnQZYCVcdea zfo!%ZcDGpX?Li7>!v-^_o+TON^pgas6WYp!qDc1=?%#Y!mTFF&Kf~o8G-^S z@(LV?g9sETDSZFx9rgbGDce5bW#g5Vs6e=Ot055c0?y##<(h!l21GVM*br=h5FuI6 zq=?&Ofx>DB3TYsdib6)1_6%_l(#TS5XB*@iSV3Vx34!p7XDZ20JhRbDn3oIMq!ehQ zSzTSF*X#1kGZ*>JD=)L#>9BI|o@3kxBMx`4oOkG1h_l8PFJzS)UDyDFBJ6 zy{3mS?d-I%%cxa$^{qVD_ocP5UN!2hBcs%Tw;D56jQ&cc++QgP!jLeGh{6yRs45jw zO2Qx{2!mSMZ4G4dwMa^@#9-0dfvELos(?=G&Mkqfk_G8v-aD|YER#z5R+|dEb=l?K zHKmk4&QcUP#vEipR_YM8Wb~HhR?nxh8?7HR`d;;QqOM9&{x@>iPJ)xuK(ng8d>MmP zQC|2U;OX}G9%KqjbWG~k*5)#`{H%kXt{u{&cIAk^sD4fbFjjTA)`Ha1B&Eb)K-cTB zWD+nn#*UTG*i%our^j=w3+e#=Bq&@@U;RVXUW`9O2?&?pCmHNQxbaV;(O`CVuIgK= z^QA&6SuGYQ0rAnhFk%yz?^wBi61a6T|C&MkICprQx9pF%ar)-j1gPQ%|0SSO?muoF zoGiI4OUbg7y}jM3$BXK3S)U5DF6itH>Fm`#k>gjkfVR->4e0d-2ad8p}W&cyOLilSh5Z*-4(nhlm= z+9gT5NXoVJ&JA9sf85D_v{_?FhXc~#5ZI<(N)n5#m7n`Nx@wjsY;7iNZ*KaP`L>$S zmieWS=)%z5@3Fr>lF`-G7tL@mU^wt)V5>-b^!mxfa|o~n>7dW%pjT}zB|weQboO?! zdsHqw=`Muc*rc%5$%~f0Z)4c)>{e+lr`Fm(XExktYq;lQe2!e=br;=%{Di3$y&Nx< z`-OKFnK5AU={h#Yuj#(m+u!4#Kj9>;?X#sbkm(pf^+a{&3$DhBnqy|_6I=X|E)HYK z?k%0mbrZGnnMhql-W)$mJoTLZW3b~6>}~A>jYo%ji>+&POMp&yrL6cZxu`*cC=fy;Md9{Ujgti*-?Ic~OLzw>nYnK~B5O}a548zKCDRItysT5K=2411HV`au6jb@`_ zcUe&@Av^j~ZfnF1&YU^J_rL!pYwHi$+T0{h^Xg!ahj^!~ck)_Wo7~xnYd^w7&GA1` zdu;7LJ614{VdcEH4tiBz$3{!8j#QG%zOHx&e*ma3(^8tfwN=(`UqcRe z3G;$b4+w#97}84m%oi!G!5-TbY%k2xi$mJ&MF>K&nR!4^7{R`hG)%xu>ohZSLx%kU zS$`9e=SUfVmh`p;Si6M`Bcj=eX0t`s&nS#ja**JajkRB#WC_ENnYc+%1Y|{l&b1pD z2&Zl#V@s?82xB+)CpZKxhMU8Ig&AL}jLeTxSVAMnb{FZ0TGUg7TDyR6*1 zS5}Q0FvLVPfBLN1Eki zd0vfOU}9`n{+{d*%da)SVr&fN-(~9;zfF#|DsX6G%w#8TKGBv)S++NdN>RqQK}srA zpopSqf-yOYHCtZF)*iHERgQsEUQNRo?SV3ZHU^WWo|))CqB@8-4tP_sQ?0+DTNpgf z_N~A;J=(5ICafLhqcQ$mW2(5QrIn0NYjNPQEf*`ehZT4>X4$^lTJ|1rp1Jd^8A*`i zuU7~Ar#pa4MsICYDjrYr`l$d-RTV1xDKU2Y$$CDz-{{?~^3JEfe6DfOcN_qAS!HY2 zJNRq|^3As;_2)j!xn5qg4wl#NH!aI1^M5i82SCi}&C8+BaF799UYJ^4k(IJY{T-Xe z1eQ|O7F{rw-_^p2TAKlGyyF=0?o-c`X?a;^jZd=0>n!r}8q$Xye(zT>E`9ZQc3AdIy-s=kqi*uY zpWi3;1ol-_i!ZxtIX<9pV&7b=Ib*DoQ^ih`LVCokXY9D++xV37u=5YUX6bjCa7`XN zedG5vhwhoYA6TZTMU^b2Nt=Ae5ogj}@%ZVVv}sRYo1|BN>uDKh);l(pW||osz&pvs zAIqJI1lM!&;4|3+TWy(!Dc5(Hg&CF1A(=Djf2(hGc|FRHI?Md=YFo{|qSd~KUHu?@ zI{CZq2tDlWs!!6V-KBJPjohkZwZ_&<@F=s@r>ygKB3j|XyvLWvM;h{*$rR8b@$CIFLKOkyAxXalJ!&_-d5pva|X0l2ufSb?#UEEN=) zAum81308qnC>bK9lQ&jDOc2DVpn*^!GM*ufn*?Eu3L|9DKn4v|*sPejF2-$$^=ut! zBmoZiutH$0TlAx?MQ14*i?vS6*_r}XWSAl$%@c||C(kn{-J1>B?QCF*l$e}QC!Bfh zC7wBbnuT_o1`@|lw}%3`-EN<|ckl4K_ugUk&P_=AsdEHPT^B&tQ}WH#Ob@7@(z0~4zMYgI-{>H2Tor}{VaV+49KBwTy}dmLJa~4P0rH~2Sj+hfXSjIb0%uO2Aq+zfH276< zjaoJ-V75KOcVB;U9l6T6sU@kGrFerC3EP)ma%))&l8la-UF?5 zIk|iqP23|_4BMJBV&oh)#^BhfG0!}6ftO!;fg~C5@Zky%?yrz%iFW`S7oX4ww9d#f z$ENOgw%NOV0~tu>E=qD4fr^M43N_cH&;@-gjb;nEaEfTSM}N47E(AkBi-5eJlG`3p zV~6Eu&oH~xCK)E=MNVE6t{!5M29!|9V1__8k7?2GU7^Wmb zQp%(o%GlaaNt_#t5e6Y#d%e24%DuaH+1uOa(xpqBKYyMe44wR^tyjaZs=uAa{;k^t zm}6axVmvr891hvp*=A#7o|%~$78Vy+I<>@pw@a_Pk1=`-JQ=(47y#(L9O|I+o28Jo z{&&=m*7sM^w7w0lK&A4%t3cM#qJba?Jj*YrKw2rJ3lR_~qA>C?!PWTllvBELac=o3 z`x{%1t6W>3>wLuYD+;#=z?w=5R_meyZbm@sXbf0qynflH^++}9Fteiqq*e?EjslGY{5}m_9v_b#v^ukSG97j1@?qz>cU@Mp&r(XF zC?bwyq9__?^LjRLT_XB8&pip|W?4p-W#oB&;5ubHqP3>T3-TgA1Z*FTKc_X{lkDL- zxIQf}zbt^{N!XN!)tSSNJpuVn?8Lq~_H=!A)BDi!K2P)AuV1R($Ne!|P|mktybpPl zhhW82!jJ`RU-H>3p)bVS3(8f0_|&T6ZRlpHUa+I>@3t zcozG)Xp9vc!}@%y>DDN^x8!ynbEluUmJv9iF;+Y8U|`o=Na! zPt+#i%JF7(vjH&bmH{VhclMRm;hbzCW#vc&Acz0>b? zVvl2`GuGndl@WqK1w^8O)d9&6_I6Ts`Wbns32cBeiogUERxnHrMH#==2%TFS001BW zNkl*aNu@R1hPA7*y!ChcPIHL8661 z%a8=+(kvB7>0+l^zv#rcIFybp3&I%4U3})@phuo3Snc9dX6b-@(8J~_qHqrDB2OJn zI3Gf16Oukfk$^N5&z)zf-KG^rUiEk+^*zlVu0Q0%58mhFk3L}i!3vN%#bjx#xVA3- zul1}*jX*m|bLj-utbnRc6It3|WfVs>_p`GrMJEiaR0Ioe8g2pUnu`LoNMUp~v?!aV74 zNN(*Yh9Bk2QX4hcN3^fiH!=3D-VW9WHIumO@qmTn+O+=a@Ra9yhB1~#Bc?suVs5_8 zgZnG2tlXv3*>ZrBmu(feY{_#$zYl4WurnNxuigV;(X+FpD#WyA3B!=E-9!{Qg)tOS z472md-U8`*Kn0Sb z$SY^Jb7V_|RBllU$^pt!B8BoX>m{K8Wk4B&w8F7-Z5fSRqOA1e3QJ)%xy?wdCAAuB z0x$uPku?OtVjC$8+FA-3kjVxELbA-@g8hO~l1x}+O+u`aCk3}%gA82pr%B4)yLY+v z`88g8=_SsdKhNC!JiDD;FM&G&x=@0ZhdZ;L)J8FS>oCd4={{nV)yI7n;Tfe$O0+Qy z1_RdD*H~O!WMN@}vuDq;ySvNg#yVM+xqdECo|Rg=f1SPO!3D>X8>PX4Cw@%mS$07X z`13vV?m-o!-JD7YNgT(7VSrLW^`t@wRG=zZW2FwV`Je=U99yr9<5>bLX_}JfIZ2X` zWf?^=k|wUla>X*vbe#lGs^23S+j@N3^7$$Z+BaQaIbdNAhI*=YVVN?aIQnv5@)&ZA z&0XQ`7IDOLly+<&_bHZv^)FX76SN~{b+x}%ca8(x9wzJi)Y1!M;~ckr+zEc5zE8Wx zgiQjW)Al{G`qZX5Ro;o|c{e7J>?NoD-4Fr>gTYkBaM?b{8uPxi5)`htDP@~AS}>xj zZDAOWF^J3kWx6I~AX{szcBYhtPLkBipqF8SM(xj`^3m9-@5+Jv=J4{W?>_-jPwd1_ z?5niH7Vww_)Touy~vkg4MMv)GAme~3H$aWmRG3bfJAX_jYG80=5q9^uM4 z#NoK-2FP^!E$$ z0CWhkgogCYT_G_=;DAjLpk#=OVw8$NCBCMt}PDg+gR3_(U9 zLyS}yp~zK0CKX0X3IqibqXG&cu|_+IMWYcq!{iC+pi42x2#i8%0eMEA3=pP36d756 z7m^-iscTHK6w)E+9BcumaNkV75qTUkL01xYy#yAK3 z$Z?k!xo6rMfd_PAx6bY&6M|lsJkBBgdwV z;*eImO?!TpAPNbih}pS$PM-E^)*}>vs=4xYT zwpv`g_zZvZqrc&`S6`#mYIrtft-z*sA&zy~YBYG^@?~CqZ1VNlEV$7T(^uC7S&R50LZP^uPwtmN$C0;lKaSeie>^6B%;H0Ci;n_RWXL<7r^LiZRBJM;%V27^93 zJ6mjSZnBr{QRo84%@2?wKv_i~0vGeJ49H;xp@Gm?LTiymAPq<(u*OoPF4nlU1=3jr9w+t?S&r$e_6o}%3i2c9dM5OT8n4v zAo2*f0SB&HV<@bl*Xyydu}&Pv#8JfJ!U7jAUSw@;jV#Oj;*46&7m^@w62?xR-Gi;F zjAK~>xv~N`%6pbzF4nctPC`{u2ZmJ;RA5V;m0RVh^|5FDxUyU@-~d!x{ndp=n|iEF z_czaT$D-Bcg3)o%t@=Lky1PFmcrwc8aff7yMjZxjO&{}p8TM%G?3+1GtQJw#ejj@5 zF&?3Q%mLu?3GGq$9fbyX6qq(j&lhngJkE1XV>E4hWa+n7fv{Ka3c@ zbuhOCiOZPU<@R#l=)n(`^8xv6#@naEK;RR=>G#{0lZZ#yW`3uXqNp2!DI%q7OlDCl@W4*)nD?`gk#lpgJm^){*BNz_T9zI%SNe`tR{{9hHXB|A+7Y za&1y(naaU1DP8+?h193!|6x{}upN|!`uYYQjtQ2sy0XgV)~1sO{e}*NPVB^vX97GR z%mm4mo^s0?GGgL^KG6xbBYV6mT-|YJrq~c z!*DTPrF2rO06ROo+`fH>t*vb^hPXLH7z6~uNoHcfY753-t#F^JEc}E{IMytN3XFA& zT1Lwn%KoUtJA`nourO{AgaJ}W@;sv`3al|iQAiLdlyCt4{M;N13kyVzm@oDXjh#@5<8pI-Srzx&_=KK=Alc6U4ILerXQar)G0E?s_}|M;UHarWFfgb=K6 zY&bwo2(mn<(QLAOW|=qs?DesG_$)gJVody2QN&CX^XzlqV)@)zgpd^4xH1qDQE%&g zJfEYbmCL)2`q)W()MA}!bJNGM5`%u6Zd1URtmDNC7dd((tgI~^L02K5+v z;QB|c3onH#Kq+_gjWr5m;o`G|LJ$Q3jhQx9Dgq(MwIKsC6=IvSt}U_&X6V3ki9ie` z=~hBF+M{)5h6WMy!2-qvWJVCmh?oWu4I*M<*&vn;8bT3ROJpH15QY&^D41(CxqRu{ zTs*hT@~QKjT3jXyniNE&HXtX$+7xXPtj)-al-=DO9$RINcYXg*wfsk&VL$e7& z5=2gpp16f-FTm-uqlGF-AMyd(Sg-|3;J{@mD^Q?}^bL;9y1l)_-8**(gOF28OPoG+ ziq(57q&7pAaZSrHVXaO+8Jv5xJn6wPd0D^49rn{e5$n+(AsiUGz2z9>7cN|2adD9- zjwp(P?ta%X$9%(C)%P$WjG`KVD@SoEm22Ni5Tu?SDFtP6MsaIP1qR28wiPRF6uZ(G zr*=^2qLMQfxWzleVdA%ya>+G`V`?(ZW2p4Rd}LbVF$Q1@4jweh@98HVyw}+GDS*p~ zIeXms!tsy);=tusB|-W1T;~bze#Fh|N&)q4_4CBot1=CwJ>J7jI`0o-3{T2JkItDM zN~xayy8QD|>@pz)?RJ}1t3{S&6@WWp@dhYW+vekYmtgNSmbTU!U1%3RAUwrM`tFH^(Jz)`lb@rzyS9@ZAICjzuj4Y^wxHY`C za#ahwY!~)W2AcEF_)+o{1iXIT=_gMCho5ZLb7CiUVt*7i?d5+wAo0sF*D&3^bBE2% z4FrNg1?JY{i`uc@)2~!6e;NJ%WyDr~5=X&Nt6{(Bz5kFL7e}T4QDE~IzV8!c(`4WK zb;jy8#;~=y#ozzGe@~GY^aq1Vw(cZ`_=)`?+T_~>E*5H0fDD>MttHw^&(b=3fi!L+ zv_hBwMTAg_h6)fWa6kbPltQQg>*bO0vcI`hXyIdjA(1{Fwy=)3D4Yk|fvj3%^BkS! zq{AUul9HzhMV_IAKv_f5?=tM}llS&u(1Sr2k_3=$?5=aqx^*#fF*)c0%qT9cLqDw} z)0PxYtKIfy3~3HZ@cQLTeE-$&@SSfxN6ZM!E$0cw7>2_kaoiw`0&=a{+S+DgV+);U zE@zcQ8;hktAe`e#dwJ+ea&J^7LO38zN#P__dwmykT6zYT2LVb4mGIzf7{$yk%=4{p zf1B3K3{e!)h-2q0@_CJgKuTJT2LJZo{2ShQ^9}lgKJ9j!xrGIUlH@f<+S1Y~7UmY{ z?(Pu^$+p8R*B5^@&j^5o2?O=?~an-J`ePW2Q61-1#|{XU?L#5jg>o2x+JWk%|d}$bq{- zgGflyUXLtIK`JhudxjS;UE;;dmw4vx+`e~*Pp@7j%`>-%LPm}~5C1=VZ}KF^m8JXr?%?h* z=7`M146;ZTAB$x@Ser?D-3zI;Y%~3}k``KMC%q?Ao3&ZDB&)8jVikuX=0s-3=))bf zxYvh>j7$I|KmuTVv|t82e7Np@$Mc=@9jv!F?=UzV9$PzU5Zkd-Sf4Q~a?Yj~%%)3} zNYHvfRSB%sAQG~^$C#X{F{Gn0qCZ6U2MC>@hA9K@*e?q%(iE4a@br6_Tc|7^8RX}i zzNK|w^qwf24j1PaJbChzs;U?bhuk>4fz}B^EF+On_j|3Id+jM8xI9mT%S6Ma?Hek# z_cV1U@T_j75{I-VqHzSOqibr?Ku8e?1u1b+hJ7}hA*E#hV4wYi1E$j%gZ_ZZRCphw z&}E1mYa`4;UfK|W8~RS?U66r~IU_xF4p|!s+EC`2pta66k+bzab-QV&!+!O9?flUt zihOu)&HV~uN`&|pUcI?9A-UyHS7V>H`Uk-FEu+t+bS-{PIZwjbN#UBNsHjZEvuDqK?qY1Q#T!E%T^P8d7-1w7X>W&} zgInyMTp;#u;?fb=ki$`u1_DtkgpfEH<68wdDe*#JYf>nV9SRWMK-(?9^iPl4I?uYC|^erco!lMo3(`}@GA~q8H9*Vr!q*QN)aTGwbG1sNBri?FBy-= zD5-D`_V*9Db@w)(eD)b>FT**9k|Fv|iEww?vm#@X`)GbJ)H0u zSC>_g=maT1ONI1;BvI&o)+}_i@FBmASj*+Rsjfvb)cGJTEp^Oki$o_WY1*Sd8gX!V zK#><%YZ>(WF%5*JKNvKGl;~(Er%EDKiZd4DT*wpG<(xuAZ`p@t(cE><_gGUh9FDks z`wrusUCPrJF)7sZwH&B(4y6^hZrvhD z5>B6=a{A(w#bU9ND=)s)&RRKqkvHrKc^@Svb6Z+j75=SouN0#*zfh&PmXZ1kCu`|XtY;ItI;Aso0LR^ zK4-LZz|Es0{`$ASWq)rMEd<|w{e;tJPkH|AjHWp2l?R8KNF)dW zK00-HVmC?Xmx`ifGMVt~*)z1(+`4ruNNMT>r4**B+ICVCxSjiX)ySet(Y19XRbwCz zWGykORS4C{8cW#<+>6+cOCg%*+3rV(kU9oDN=foO$6Cv9IO62wCV0Ww`B{`64L4z( zZO8zDXrjp)`Ohk(qUlD8)ls+3wQ``Ln_10QyPk`8wGqa95^X=k$}^1x^qqf;kaM+t zkUz}rBlxd$k8AItQ&Z#kv`&Ov-nPXSTLip%pZI#mb|VU-|JiGo=W;ZtxU_HRt3;zN z(8YQm7{1Utm~i=Ty>ET(s;XEnmyKk79o4I~+DI}BA<#;rbeqFh2tgXvWLBb#n6ek5;!fVvBbWA6~=UPB*vM;xe`oxm$cF z2o8uML~{v2zc*xW?|>VJCoIzuP7RSdL3)MsNpnmvXj>dENF;YY-Z_Meq@@d=GG9{8 zr&NnM#d1!SFJsiK#ha3HHihK^mP;t|K(JZ^MS;a(1tIFzglIpUA$n&*O$tPE5gds4 z@ijFj+TDa`BC;$#o;%7kTZ0}B*dOmOOndEvaz3sp+UTexNl{vp7bV|)`yGG!>Q6j; z_!t?<5FZ^#ThGzsI_iuILt!GY$WHjmdG|OB;JOckKTr8 zOl^ZKwf7F8Bxngjy|g#1iE9_h{y@2VtPhdOiH?MgRAhrebDWkEsRCJVtB_Z%*YDv8 zq>Zs5k0g$k)R8jEUWavE$CS3}ZQC)dS!X#pIp#NCe!+kFum2~r*_5)ZVl)Y?&V=6b zJg=>)Z{}Q^5ZT<8lnyn~MZzylQtsZniwC~>_FFD4CKP3zFTO(`MMGwnj*>(Pbt!`b z#WIIy&sh`}&L;GPL=T1tFAzzJOcIj)J(h{YP6d5C#2ZVwm>^7vGX=h|u$0KTB*_(r z$pEkW)Na|rho-JAU@L_1jIxvmcklA~=b!PLFTY@NamH6){ej>A`|o)E{3-dOAki7c zvZN|4dpr9`kwl4GOL3NCUCH?Afa8-JOz+-B>Q5Mtces7$04F{{r4@hrZjMYUtne6T zC}m0MDoSB6-eK#f98}g(PNEc4sYeVHqEMKn#Z@`VDzsBLD$3HJvObyWVT%PiUyxJ< zSc6d-p%i+&gA$OLlBbU!!E_4Cd3X!8H-iw=*_&7TArH=3@@3AWM-RDqa+CY_@6+q` z(8-KMC)5(bE5~&_1cc}&rn)Sn84l@^xJ0scHEK%=iBt+HL;F=)kt7L868h2Fz%Hfg z82@#Qt_@MSA^&WM)UT=%@8Rt1jDCMWlBDeJ?lPH7I6ZxiF>TbWsVYp&IqRXxF=>pY zs!FOVNFjT-Mo8B;1kHHRJdfrcJGszS8njsJS1uFXs|Wd&O<@>m3D`?r)Jw5R#@2VX z`wn@ub<^Eqi#LfMABh#6JYLe~*Vn1tbW4||p~cER*OJZk*b)v{*>CJ4kJ@#THw%cpoBwb$8?mq%JWU zz~HUL8HbFMagV?Y!RoX;bja4)u(;@G{|hCtB19eh6xei?^=;d}dW)YHwcmdIukimZ zsZrzI?eUd8ZR9|%+*^8i|lH6@kFF;#)7 z3d%Ca*$Q7-Op#M9b8L|#oyFuiRXz`7Y?(t)$|T3@geco6fgIR}_TSQX z$cjLQ;=|m(cIb4X*?@?~l$d}P>Ed~Ohw$|wnzyGE5ANJyZ#Zs-cIjp7u^-n9B07f} z>v;I+5zn8W;;Isz^$;;Kx4Y61vAne>se_eBIpGO;8iB0eem@jRJ>Qxde!mCnQLe@`E(XQhhEGv-Kp{zy6h*J@bV|C$N z{YdL=60&}VaGi|}|0n8#cMiBFvLwDT7jNGoP(q^hdc`E>6b@0)LQ3#1=B!L`HptjI zTT7SLq=pMs$$MmNu#E3q#0p;<8U=NvNVud@l3TZK@%iVUlVw>n;DtBT5*oAw%v4fvcL<^(a~Lg{pqLt>XVOn_~bAA>Fclf(^r4s(c_1BZ_&Mk zc`>8%1}{AG@*?E1ElWnD5h#oI1@mRjlc#eQ%NIO-{vCJj+~L;ko1EO*L+Fo5$Aa%3 zKV()caH7IeQo5Xlt5{+vaX3P~w0Kgl>5-s&674e*TVdRSs?6~QlnK)G))n}~BW;gr zCg}CX=$#zl45hT8*{KB8AJN-6K+rmjJ`mfu|eTRUIW(wsFxn z1y}ATVt;;Jgs5mq;Elv%;}p4eoL@b5rH|}vzbaC-CPx9B3-ZYI7?kJv>UaYyn;D!eUlrl4HTp(;Y;Y+1G+X99U!72&(95HTuO zdW-ND?+kd0_a+i~4nZL61TjLg6WJ;VFdV1_%gnbBZUl@+JYPgyLMAk+#07{09;wHkv?q|zlwA?al) zM>lTptB*hCv(JCc7hitCgO46?>-KGScXsIyh9qf<$&Ql~001BWNklnJHPPT@kdYgo6 zyH^+AS;K$S(YfvQ!h>|6Bq)h+P?SM(Im@yrw^~O__(ZrqpZ;DcuJR?(8^m;wU zyE`1-IOMy({DsF)pHP-DCtdfvUaS-`I7o}2j^#bdc|>%M@Oa9~fGjAVJmS1JU~C~1 z8j+4E5iC+o+UsM{WILL1qDV#~Ms`7#IrjGk^m?H604;|YBPmUe^$H)OPpv5#2pH|` z@Wm&ea$|p=`E1HpfBFO8Jp7vH(^E=OVSR)~ z%n^38k=}P?dW8@eYkB_sIRMAU$L#Lzpp;~}%vZ=xDJ4p%SbuyIX;hP$U3tv)+=*TC z7HEF&8q@3Y2qAIKvRs-b_hB6o-t?W`Q<`@q$oF7Nuoh|8e-1C8Zz!|^qdO6{<>cCLDC zl65|Hr5ow~KPq)#S+-WLHk#L3+sNwIIeP2ysE+7uQd6vbukUNU?3eBX zvAOT>JeRKIbvrI!hqjJ&pYs-5Y_Y}93GHR<(5yolN8%w9lD)J~Uum=uXfIGrWG?uX zNo!cJYb~R9PQ@}`lIJJ9#3*Qo8c)W9%<&5Iul;!h>RHBb{DK0O`Cv#k0QWiP$`3yIm!eR;CI zT?HXuZ#=IQ1TX$nv-BZf>%Dt-+27j@_uwOGEJRbX)e?G~wRcdt+8c{%Ox{z* zoS8aF(1}LMP=!N=-wtWh{q`m&F4v4TZ++NmjCvkxAWbv&_V(!a2b4w0+1VMDsV*B7 zFL8xogB9W9V?C63n&@}qs7_ySCNzmm=qrs%1)d&OgH07yD(LkY?DiR!`|P=jfi{dX zPeP7Ep>&VJJ4_X$$zx+P-Z37JxqJ5xpa1G($|C1K{{27rk3au`r}Gz-RRO7@C@XAL zGU)X|OAMCjY>F0wEJ<(}6apzd-dVgC7;9J*IrGyc6FbGGhMPB!8Se}@+#QoICM*^e z0*8|hq(eH3@-{dPL{i&(ONF6OmP93(VM&!<r*JxJqJCI4n4iDJ0e!s`)u$@&cU= z5Hdk#L#&iIr4hXyddK&e<`%!WfaMvk63F=0qz6$u#}FJKMC>!EGG07?LRpp!heO8W zF-ejzolbGiH%9M7CnQ=UmBhw->B?f(hH)hoQpu1{T((B?K-|hE&ulHD3DF7PTAcG( zTaxDmMNv?e1;#|RG$C+nQkh+ccd1m2!jes1M}X;UihJZqla%`p9&r2iZ5}^)OjVUk zCex6AHyZJ!l=Iz&a{vC4PUf zE}y%_+rgW55`Gh}>$=Fz*U58!`PlkL-m2kdGcmhqznWmZY&YMut=_&)-qz4slVv^n z{oYFSZaoHe9g>LGb$&G$Zy1|QlY`e9+w2n@lU8%{ULs^W<*fVvP0`ewj%$=tUJ|w6 z{i&-e@g}fU4A^3eEq*Ap#p8t|0TLk@>5Q>X8Oem6l_>8K&Y|K2xN%NxydOP6c%%)a ztx7Xok}w0F%u6QA1y=ZAM2dz3MD$M;E}p6#)?25_x^r#2WhoV2Yh;>WM9d-ORgfQ} z?OelOv0<|C{!gjjc31!YKcUydkGtQi{JsLNdsn|aGVa5ySsU|gT;&b^1907WHvO`V zqP!lj`*hkEnsvGKO=o(4JoAH;sf%|N^CS|Ci%njex|h0Uk?}s{lGtL46*OGr4_!Pr zlhW1*U@GS4r#$`k&wTgq|Hjg3=0@U+5;I$b@XjhqAsYj>YzbQL0-@WmX>FfVZxfLQ z6!=J{#%&&m(YJNv$QSQRoXoOmFNNqI8_Ij>W|V zB%1MfL@&)ysx|aGt-X3@E+~KeO`mgxplTWyF>n18qu_j2!N~w@S1b)17l&%1& z=??-ino00!NP$}ywTyr32-qOSEU1LQNg1S;1xW8vfO4JJw!#FjRvRmziXZJE6RRqu z-S_U}JE_TcDMFyG5|Gr-RR9LGRCsF;D3FpY%}`3me!h-wXvzMSUb`W5Bl+sAe#Up-K5EO>JcDkVd4uTG`?bwKhX>LY&h>tC}s81jGr%fIly z{U853#XzvkKq!Gw;DtwJno5B+hQj46{4!h<#f`%QY;@>WLg1xD2#Z57t8$7-j(j9= zvf}9QkfVcL=4a1&^t?bM0-+@ui8Kz?^p6&a3+EArg(#6|7zuh=kN$4L;_(Et@OT5Z zG}zanFEZ9yEi4j)qVdTH z&D$(^`uHzAd-ja`_aD&f^-0qdr4*ylfHX}>lLW1Flb_H!3!=?!*!|l@tzcj~QptIq zQcp}C9KYD1T&kFVPTJ2P_eV_Wc>!zO>8ccWxmyll?5B~;!%-qmOP zw#v0Gq5rDKy#9rF+{zV&h<4+WvEQGBH!$+3+skXKHuv|=}mcZyE%QkiWi$7K*u5IHR{aPUb4j& zTf7ZuC&NTM@sN7SzzIfHGAJ#5>yR~>+jd>;U?FNFkV8s`QlND3@*F1#z44fdH_TO? za|?(huEXJlYde0?lDd~{AYNdd$2w2$9Sdt>UZGmLs52=UC$oG*V^bQeal7$Nd zt!#=^M}Ku^vA%VNTr0Z}tFzvkhHZPNpr{iyJy$%+Yty@Ly(r^3yZ?-adeP3$yY#Nd zfw2ttcDQwNlf%OUR6h&SzbmJ$CCXa)GbIJT`OO#n~nN@ zNIy-#QI#R(Ckk;5}dsNY*>EU5G3c87=fz4DNIPbncI zMAxdojCXd9je7{TJRL4-BmU^wK#g9q#%><2Qpx#!j?AYA_S$ex#>CX=o@>8p9Z$HrswEfkfsVf5a28phm{s91%}`dpw0zp zCdd-O?Hfld#v{Jgic(sf2r}^!i}oh;k9EAQ0H+`s4H@)%7~@$i3PdWobNm1|G0dM& zIe&bPUl;@>(iQk(PB}ZroINK=2UwY52bwaG2$kSfAAca}9o?Z)8P)~Eu=E}!KnfEG zTnSo&7U82ri76ITRYj6$Zr{Gety{OS)-oE6NRk8@(^v@+4Aj<{6|%J}cijDS>s)O( zU(Gid+g0P36kGHr&xW;nEMmXX5V^i}?CDBA3lZwZbUNkv^Jnag#~d9UHFE7wpFANi za=h~h8OyNo`kV1)Wh&pzdAIN@UHBGTyk*q$yLYcGylvEhJg>9=Pl;7`@VA7Yu&>z^ z5nGR4>tty&rXUb9I9S#>dFxM2@YXqfyAkqT>EsQ0uQj$wE3oNz=UqE& z_|6*Y8b{w+W$1^z%h!={-h^LbyWV1pEnW_-kyz(Z)}dUG3-iumN=Idb+>iuZocgz& zk&m4;2;p$TVT?yr2C|eiO*tG48A~Xo3{pkHA*2H=9s?re*Aca+I|S*T*!j24?IAx+ zWen4@;OXR?Sy?b6VX68oRlR4|NFgrG?Zq_<@edoXde7Tc$LnC#)asE+vbVd(fByUb z%(G|D_}72^*C4BC>j($2cI=0WUt$}3JLparJ)WC4Px$M<`fEI%fBV;eYslPfMDDBN z$JWhy4B7O&-@kg_y$dN7`v?2{_RHULbace?=cnY$9BW;$(QT{P7Qc9O2%VUBR7*&N z!&OTb7pGKDzXz3o(2*4kj)>iJ1c}{RbhmMnT=_1#b68RTS<`9|zC*%wiYV4&q#}{a z+PwHuG?VXa55LuBi>@vKewEloN_IwLj&9swFc?Hqs?%YJmJs#=gbPL(DJ928H~1g_ z@gK>ul>hmE`CrMh9>4zVGrsuz*X)jW$g+%`-5qY8+~mf|(aPH}z?4ABE}Y}cTF#t9 zAxNa8Ctx5U^$_^=1eri7U;>;QD9Q>iC26ME6EGkWtOP<=L=vg=5{t(GAwk~036CKN z32Qv5kYrNPm(VBV+g*nhfp?wZgM%wD@~|hP+_U#h#Gj|(Xydc?crSwFT+QWsfhK(F z_tm`d7=aszgg^u~Z%%Y0ercU(8>iZC{!W2&M2Y3PYWU_@;aym-A;{8{+qdtqx4Ro_ z+nQr;N6xf6jQn&X=2e4N+ul~(n>G?n^|RZ^)01T>gTVk}3`J2;#eBIhHQ&X{NDtO^ z_KxovAs~@WV_PW0#XvIL>%m?hpK6L(PEpNKq$ulArN!nI{rrMtdBLEZP$-Gi6|R>c z6G<{iKx(8EjD~%(gFVV&pa1KdulRa7p*TLE7^lqqlCoHmD1}H<#Gub~Za6yFY@^MV(P0(m|q9nHD@tIyC!$EatIDCg%? zE+ntk4wS8>zr&3eN?~Nm-u^8P50AN+%qXf;Z033J+rJ{eD0u$+ugTA*FwcW(mx=0K zOO3gBhSM2NCTNv{%J4#9g+%oS3=R&Mj)wT@0PhUWhE^_xLkWirDXB?xcpWn9VXVVC zi%vAR@7(6(P-^? z)jG-4W79^XZ|xsI8-Wz+dgq++KOYHbAt5hvPM@DL8jiSm>n68v-Nt**a=D;7ttd=^ zj{Vq&W^8`FzRGXx7ivQH!&otF@h;;X4S4-gc=bNT|7e1CJwmnK_AW#czshrX7s?5j z%ds-vSPxVbMZ3M7bG9i4x~T|yz2GR<@ApF_Z;a^eDq5__Ci^z6Kv5Jcj!?!}s;ZHFk2Bz%46;wr00ZmZ zOuq5xm$F{;3#u|CH>8J~XgDOr~B$3OgW zRmy~40_pZkY-4W^zBRu9u(Pwnz5Dk7`17Ct+}Us2a$k-&SvNO12EFfZz%%F%xPALJ zckbS$mu0vZjr7atySCWk~^QFqd%V43#rT4@3I&i4n7bQ^G}U zRVSfPf`zdxOvT((NjT%1lhef)x|s+c*8tO`uNB%QxNPhXHO&X{PA(g$RFH#j`nV|cK~ zU^rm6-{)j^m&2R4IK}eE`32|W9;5r8bN7?G?7AhB7pKfG&Y3UfJfBU;s{)y74)%8t zrbqE;#6(K+$}mJS%KDTD7K<5q5#+hkB!M(Rs)W;JMS3yi3!RW09kX-$E`R#{IeF#i zA(7UjO>mY8bz8C28Lq#}@$r35Zrx$=)z?&hf>E%0?>=HYCw=@p5U!@6C@sZ2$16Z4 zxJ8Ohdib;tgB@HtLTZii;It+gjTk=oh@C-!D+^4%KsZB2MNb%d(vm93v_yGJ=`$9~ zoat;vRaFcJ1B4JvCKp^>oCo!==(OVNsGyFb!zMyCQO@xK8ADD{JleV=BYN#RZQZKjP^4h#NO*uPYd+Sed0B3z;FsiBw zTL}{7NR&qlg%l-HmMB>U*&1RikYouqk!0E;wP7MF z3SZ%IO>x>;vjpK{@w&#YcYm;ZbNC_mx}}9)7mZhctjB4V1&OV0-ZF?O61yGHgE zu2r=2-kNyr60@C<`gRuVS4e?&UhJEEsjJ5b+SyA};6|nuJUGYE;US-X@(Fu;dx6Lm z-E)hTNL?ud(P*u~R3$n|84id1`m;|_T9c*OrKjPorz$Fh2dxvFf;sRUI0sHKoO?^* zDvY%VCpa{QQjR%_PNIeIn5yF3SSAY2u;472RFu{-(uy&GRCOXm$^sY>qJJmea&9Wl zP08F_a1IUhv6M&>-6QegIOPM;YDHL1mB19oGh6b+8H|@4h#@;fgOCl+-g+M+d23PP z7oO?nm64FhF45DFl9AM>6OBu!4T#nWfrcPnMKGvIw9*WR zL((M1B{y|r!$H2im7fk*wXb!#yjPf=Z`eVI;K(@~3^1mmjK;uLF8S(G$@pj$pdFal zZ`A#RBUZ$dLq-qo@!Nm=d-}I-^29B9HeX`*#@zVmHe@}{pHEqyzCgMHYvv^73|-8~ ziWw7~a&&ti?j2F>?r@%^%n~4z+&Ma6Dd72RfA{R-5?C&z@AE5P^MefNfiIs|}kX)n+n`wGI%{Y}T zokZJ^r?zxC!Y+};9GlOeDv(&D3@Mz96sW;~n;(75{;s23%$S{>VwMX;ImZ@rN^7yk zQsf1~RurzJa5=O29AgZikt4;a`QQy_Ph-;+$J-vBifE?L9c>sjQ=r4&_7QD5VpWNRUdPb?_Dy zQsA9$mb>-B!Q(<_D@DkSV=53HB{W)TBoZk!Qicd#B@_yUk_l3%Na!l0@F*E2l^8WZ>Jd^Gc;w0qCfF!yZ@8c1k^cNx_kZ2=7_M1PzUkupB2XK|K;WEh zCI#!VEsgo}ms&Zucnw^xBhLB8lW<#y-W=XP6VsbPlk*ay{mnNLfc5WJVq5*Tcq`~g zz{W4{l7Xr=;t7JPj0iJaBq8dy^^T~Mrv_q8_>jxAy_J?Yx}+xK>t7?G9cjHwky9&# zX~+0ah-zzzv(+B1jxO&0SD&>hfN1~SHBbjKxZXSDm$ath;NXDIKKqQ5ljF;s>G}&4 zfdmZBpCO->j5)E^o#1L%XQ)ht6cQ~H6d~7b0W5ILY{AqTmd=pd3hTgP>8BYznb89( zJe4&}Y{3iZcp)9ad3rLTaFVg@bD%_s=Iik2&O_xLOKX_el5EzexVGhs+j%z+$91$b$Z&SOOTQQo73A`vpAyYZpFu6#JJ#Us6M z)=L?Jlu(8c1@4iePLUHLfP;OqQzN3oY(wg9c=p%j4+GhdKJ9xJ2w%TPzk#^ux(uwG zapQHaMQ0r9mj3d$^>bfgJiB6CyXq|A2|zCmWG>EAl_h0Sh8)J%6kQNWop?=2Aa|v& zNld}Q1J-hI^Mqgj-QV*0-~BCrI6vigfBcGx5Zw9VH{Ac#O%C-Q-kIyHGB8l23W~^aWyfz@5WG zZtm|>UgZ4wn}=9aqUn<)yBKm@Zx6;t?DPiobcXesL}?Hu1xuVt$a-VkcpupxVk^T! zrhI>1a(`#c@OVW3;43byz%MRHGDA-~q%$aINW91OQnKAcWV(YXL6nZMP*lAU3n!WC z0mZ=~=D}Tx;Q%$049*?)!sALwA|=9FiZVx=CBo-OnW4M~VIdQY@7!iM1~olrAr zDaKUTYKAIGs7icUfC1wQ&?!YsMUf;a-h1+8j`Q6-<82Pw?wfDP7~k}(SIz0Kp6kB~ z`EW%I6l?Rl=-}r&-$gWz8)KNy7kvHoH&`3w)o07*naRH21KqEJFdQ&`BWE2AMQ z>-ifw$h)bAk7+*%}D<^%9Cm+O><-Mh0r7?+f#`_o?4_ zw^3W+>j|$2ZNqtl^Q*jS9B%@*CszpG)|wwrwMkNw)jnxuk1J#~>nao?uYBiN-?s6% zu`8qAH83>BaUq)DyE%B99^8X>HZY6cp|nKm&YWC{pfS9mX-OF(I)w}lq%}!=Reo-r zBq1W#h9VY(Q&%|VX35f7awVu#ia}FJLFE(+C78v1YZco{36{b$lMaNZl$Jso4ltA? z!J(C)bgSZHFwU_w6;oT0r;@Ulf>JmsFe+t1$_wWiBbwV@NXUx{S2`+F@z9q%vlTBA z*in)hf@QqF(g#of5{JQ2;?Q0&&>2G|Nf1=RW1VAZElX=Dya(rzLXc|Bp3>}Vh4R5E zRy8AU{T7={ylr(6(P7|~j7V*r#rr_s5bBXJwv!uLT&lmF1FxYuUXuXXNaSub%W{cP zUi)X$bBeYUD}CmMDM)>w_t5Y6+1uMAO;d`ZU~+NsT8n^sZ6gLYljA3Vg zpOXjo$+hG^o<8RE|NZ}N25Jvy$K7QFc^&(k9+8HzzbENs)XU4o80;Q zbG|PY{PFj{=iC4I0~o`j!xO%^|7&(~!}H0E?0BE~a>2vr=X`VegkHJNPB!LvN7GAp zIM_X*7#(mpK0)g-PWCu_@Hyk&0l(TmV%H0n%Nb9fJ;9Nph6n85Jf=4uF&Ydx*xkb$ zi!%b-KjggXp#>a2_yUHz$g_tG@)r!3XNYP^;wyU6v)sSQ@Z(Q;n(Q*UIOk;Vh+BgZ z^PPQ0hbQDopWWdO`u;t3@+JLq&x`-(J7#})!jq?SyiaimTvejV1=1{#K0`}^RF2YF zmP#Sg0Yy@9Av0c74m(@IqC}MjWh~N$_ksW|f;x_~7Vlih$7c*_l7y)By5)69)?l#h zRE<}d$F8L7d86Zar@gM(QtJL+NsZ6~V=artg2#^@qqXMX@Q~x<6SUS8MZxKdQ_8Z6 zib1U*yE~`3_8wpI+Z8l-=h&A&m#fe7y6{(g?`(@>=jz~k-FeP`(Ab#UDg5%TW+3Ix;U02rMHD|DGJ>O!BUlw#Nx8{I!ION8S zo7_6N$tNIwf_aHhb;JV4VIFHjdb#+JA(nG3WeZjI=N)G^}F`EA?Lzb&kqSAVLB z{05fm7luv7kS=jp&yU{RV*aN=8?p8Nl=^aC6z<_i-NB|V>n%N&#_n{PBUv#uzdvu} zhafUiANEZ)b@N?ul5lvW7fnt}pz|79N=;DP3fnoBlp>Pw(P5<{gZmEL+6Mx$T2H(P z&pA$kRqb`%;cR1&CQ?M=9l6?{)tu{wKCbQk*XD35i*-+}t(9|q zho$ngHt2?}?UbO2NLeXvIDeWX4Ep`mYjsKOH3Nf`3Z-i@v98nN(thh@m%4T|36I%f zsjQ_Go>D0aDOlhr5sZ{#j${$bE2Tgu8mRL0gGHZnw3Y zE<3-7wzXV3y9bn%q)CGCf!uS}hRFR_xRtuA7C!htXb-7}#D@r7XDw%w3m%?6CsUu3 z-8_O%K82a#&iIJ5gcsjEp*WwBN{ux+CI#6~@#7&vWTZ!j$ekU;99(|@;~kKS!Ht`w zqkTrHXCx&i%P40P3MVln7_YESljs4rPVOUBA1?(5M@Njt2h2>t(MMxOH$UN4(qr+L zNBrgCa~?mrpeQT!?wH%3d_k@y`C`Gj6^#002E9FWwnvrjP>BLLJYp|N8SM^H&%b6c z16d}dzF?p&v;AF?oqb-oJ)A1oAMDUe6i)|ZDwQ!y2dME5T6?TpqWccMzaZ^hpw$v# z1z1O3=9uX@VmLq~9^cDwGNGhm0#v$>>s6G)9qeESdJ~w>v0h>EBvK%;2%$i#rfMst zgW7=WqUj?r(N4#$LU}N{vReo>gMnB3F^0IsC^efly`YzRl_Yc>pM!Y$h z+;>YI=KaTJndqyxZ?VOXN7pI6CShxAl5Un#lIKN~W1gc_kZsmllOzdBskQyXZ&{Wx z7z|d3-EI_by}c%Zt+gxC&TzT@Z|djjeY#{d;w8lI7F%rb!9fFf=kNkX`@7uy=pOe! z`iRkRgwi_5J~irD(P&hA`-?UCAVD*UZ#}*1A1xvKk454`ejtc4%PJVSaNvVvbBM?d z(YbhoF$Ka~bXl^!OkYeWg=TdTQk!3{FGYklB-kOAC44y~F_ zUVrj*6}j;;uBE$#yzV?(T#d~Ui-MPVdcW>fUhS>?6r|(kHr<+<8xsoMma%F(e_6k9 z)qQN(e%VIdF_OO?KAhfaoycvszc+3B2Nm?gd4um3-d4ZT=86omqwTz=iC*M&-sXWD?&$`d)GU4dgnpIuzAt8J+>qxC5m5{}KY7a938`y zr$eS}#HHH!5_HOar2#9Hq08a;Rj-BB-ned78zUW7uTeV|fIvzW$aPPYU|*}twENcQ z3d`vj83IwFH++{OtdlF}xp@49Z~yQIKKk$ejt94IG0MiwW`^Cp6Xr_r`-gvFI?d6} zBdkRlhftoRpE1t*?CtKOy<#K>9POP@ebU4Adwjfq%<#qu0|UFm9%pt*k_{N|>~pLo z>CTYd!I+)ih@HV6caCo%v_d8cr3P6p8D)Fi5Sqa}=X~-<9)I->lV?xJB=iPDjt&lZ zW^<-5PRY;D85|xl*u6<_G)C$%m6MoWk7TSFA0||KikRk5YP>7)+QZHcz^$fJUQLI@k`w--%BPMV}>rJE+=yTf)}H|xd0O8wbX$9@c6 z_dM$>@6Zxf#tb14N|K2LV+@n&lyAQIhQV;a?#Fw4^xz|kqGU3eFquw~LZB0glrk8r zn}_l8xk!`B_ochO%(`&Rb9jwMbd^N>Yh78auR>pbo-KYn-jq!4mKS-mxJoAaYWe6b zws^bPB;8y~D;Gs)oJJs|Xb9bqpSLA>vn-?6>opO*bp-D^iCdGmwRCeW+Z^)G`;9Wq zSC#j5^Yd=8#TFkHv~w1OC+TGz-a2M{w2$v4oR$l08RX%@#|OjE3Ypsyx{YB}iZvp) z{=^(!xaOQngluC4{^=3sH<4eb!_)_|%J?rIi)!R3pV|D-4(!FUi^25d3 zmp>Jqzdtvjd-WtGn7-EQlWdCf>h5e9s`_s!Nuq}QFR>z&!?SHO1&nEaFGut5=!f|rtxL0e-zVr80TK=Z{ zYFkX>oqMScy3oGj;kAsR7anIF)>~LRqTRnM-Tb~`v&zUDy}~P6?0i!aL6^u41dK$9 zC}!(77y(6nhE|03vSvY-sBP=VC9+9emaA`SP`6Ik@BS6;ZSxFq!etS9r3SdYV!;HYr8s=_&qNEBKtq;)6< z!g@-VGqLlKJx^#iK^-_S4Sm7x!SOgUzH}Aqr7Tz-#Jr)8U zFQ+^!=P2RPy^v4SIFGBsyQsWlf#(dz3tMukJToL-3S^?FEMOfIQ&E-$HZ9pfA&p^b z4RZ;LRAZII2mx8bjD&LuqgXdod`_3%Z6`9-$L}IKw1_L_OSL>~9X;EgFUohbMp*b- zvbd8f!e6dWtJp-EUe_)!pYN(O`<3rk&zo0sNMBdJ)ooHLw9;5(@h(Ja`o@`|EvFE5 zTMR^QUGJq265xV*-7Qc;kV-+7CYb4*r{8|d>G$80e*O_BH&5u7VAOzV;h1<&KAXbq z1<5F(CqmtnY07wS!2a$&)uKXM$`&P?5PAH6b>kS#d)?F7w1uNDD)c&OEj-7`>oM z&ZyJ^(o?j)K*>4A>>>7{=y~QoN2@+kSe!AG3y+%!WGYaZLiaTPKYQ=lB-wSHYd(AL znEMCxQ|A5xMJPt%jhK5Wb0v}j zMc{%IMN))eH%xm|)m^?Sedcj{&xdo;lxqVvKme>2QQes*kJ)G2wb#4WyDZBlvJ~2} zaWgL2w5^(9NOS%!9lbR+CUF)q37FjW+eA@>=XyAHlC9d9Z9u?njKz;%J}r>jk&S@v zRxv1*?5ozxW#;D>7|0JWF*(VB=>vpe#MP@;34;Kstj^K{JXr5YMo7=$L2QU|h=| zo2G~fq$Z@3vo?v4?U=7j>Rp<|zxJX%I|i+;@unYO?TSo2j+3*c5Z%v42(%Cwkx)x@ z{GmMg#P1SHtCslcls@n z-=Dg0pIuz{_pPlU03l>TqlX~YdP{HH49e}wr<5*Wu;Bm?KmTmL&-T|?mQATxLRl7J z7*efNh~n^5Z02_Y<90r~tFQFEmu=aUN+pz3L{UVm-6E68;CUX+Mw3RfLEHC9z`EXh zX_81V+p-zV50cGg3H*Rsy+*6uN&y@08c6;Ob?_{j$>NBG2GiXFd6P6uv znGG$wbJ_Z{ikd!Jz5_Jm0oOcV~vZz)=3<@Ei^V7D^4SGwZ=x_ z+7@=G5ph5q1w=YR8;y`M0izuo4FvS^<Gj$#?Zo0MYAq6YnG&@49LVN6w72^q@pC^){a7?lDNjuMANhc z4ObG|7NL?vSmcomU>GEcQg(r?NUA@IKuJ;x_suPvYBXkhAalbeztdEGl*mbrP?bjJ ziWDpsU3Tr>{-eLoKa4!+yuL|cV;9@@)cbEKcK*?HoD%L+94RD9Ds-&D7$lN7-7|N~ z*}c98=xzXV4G56{>IovKF`*`E)hUk5FgbmIg6DE)c9v_)WvV`S(}&nQae%_!J+zev z>lWi90}Q!_907J%WZ&=rqf-ZPb0u=d#!(oJ0^4YW!*g8EQtn93!qr0YTNvB4bS~H9{D4(8e={oadq3 z3|M(I5mjxdMj;UaMOP9@1-6Z41hEn{T#LG;2`qz^jziN9iIpaDDrnomsC9&>5ZMh7 z8S;B`R7x%_;p0S2vT-^Ug)zD%h#D5E;bL5iD3e25lF)K-B`9NXibAM)3k^bgw1|eA;cFFbuk7*$U|PR?+*}(~Wuf zHTnUylt$D)SYN)MJW4-*)b@VVvhCs!yYgiaOA86Mh3z>w85f}-iu?pP?ebi7Vi5W! z3fLH#E7Cl$;vZ=+;VYaLn!tu;Xy5$l*Zez}jUEO%A7z|2U3C)LPp{ztv zNa#R(!YJ&XD}+FsP7bHdy=SNI{nCjcG8puxv&5z=MfaIWzqAt2%V=`B9GOf8DPV1V zl^_T|SkL@?E>vZHu9NQ(A@yO@0_^l?jdLyAk>DvPI*UeVhelpt0@W0*kDf-5QFgu_7 z`w}UVdbTVJDJ0tTQN_fXFbauvw4o+s2OTi?nXdaSBYiKsA!i@vzV(o_tL|&74kWSh zN}Wa#_pSq_Yzl*eWHK2Hu(Y&{9|nE*={MQ*8x-h%-|q9Hw%p@x=P%y!*qf6~-{=0w zj$Sv|-e}WlRngZbn@yAgK_-*o*zx0JvN;;H3Lk%XiF(y1H2r7xN^n15tzUY4CUM^k z*_*)FMpyc@F=B}0)o z52j#llmKQO6}aPGxKpV&-0=ZB%nj#nQn5Fhb*5V_GP5t%-;e7No#$V=0McTL_WdukHIZ8x4XmK*t&>1sTsHm&;Np3}Rb78f-~F z;}RRXm{N8^E1Z_6LqRT}7mVB2+S|A2&b@5sUeMP-_q~(3Pd`sy#B3g1n+u*E-+XoV zeWXN41tN`E7n{%P^#9F2^v03VF-9cGh++kS0Ur&qPibMv%3qy+l6Z-^lL^B96Is_9TF*GbmQyA(}5Xu%UQ>I?jaA*JqGPF!c;6cNy z00AOXK@}>9;woZroj9At$0H)75iQXSstDOY*oKyJF^<8)!cm5{)1qnLqpbv%*B~+t zaLa@Uv=d@08zCAvGQ?G2xe?xojTvqeBw8DxktX4o&6$r~lpil*Yl^MWD z4=n}CQIIjnOc}gEuo@8h$pmlWMCXiSqA2++l|ss%-Y5Dxl-Xfk?;U=yW+&1<+P~N8 z?^&Hsk1D-+y0=ztFPh3zi%&57|?1plN^Dm+CuEbMtOKPf67Ub#2?maU49)!*$)%mgc6mQ<-?$WFGPnbF8NVP(WC2<{R(@ZGM-LEiQy!r;!HikbqBmLok84-)J>H7)PyMn zMoNrQpj7gGi_vw%jrt4D?=-`F5hR`EI-4sm<1sci&gs*qC>Bdtmg;iw*Xs@L+@9s$ zy?d;!ttCbVt-EoG{ovl_no=^&{}gv}9rx-_W74Q^8WCHLxpxEU|Q$ml4w zYK<@qc<%Yjpi5r*Nml%NTatxz(hCecZL z?R+lF{=IwHyLT`7e2!Z;Z}Q>g>(pCKEVsa(sVSZ~c8oX*Sz27=)~)NbnhkUu6Pt)$ zU+d0lNI@U4qZyx=;OwbWy!8BYeDdKX-u|EOu(-TTTL;~mkZHZqSBo2A!Ta~n?M*bj z?+?26_tF15{Za}^VPJqKo;c2)J$on?i^Oq^)*9dUSz2D^`t|GFnZ3QCq=_>^l4o)= z=(1sENR}OK_?VALK5j-pR$DP_4kg_-35C$Qix`AIi7$1 zd5#=8f&sq&{r}4R;yea}C6h8F{kT`|ZXS3xkCpyb+Rk8n|GIu0E7(?W`N2JByK{c` z=>Oim`yGf9*`Auu^j)))C@H$S#dc>YDH$3b;*Y-bZ3c%%n7w(8Ti35pu58jF?px-a zOp{%6XFAU&N8=9nE=dHJF(#!&PGSH@#>V*H|NQ@;(WvvQU;mm$yT$&Q1Dtx|I3|p! zEU&Uk0_1E9a43hTI(T4^7*Hnh_=5&Fh9rt1mZ z@sjPel}Xt^`o?j3kDXhibFcJ%-RJBqkI#F%6Y8iy3yc$Ky5C^m@H+deN8mJviE$){^nvY!&NLw78&>Fs-B zAOr#gz7Vu!Lene(O9(8f@PxoZqGA#nb&|qFQV?MXqnId;@Z*?v6rv(SAv?gjjPYwt z?!Eh423rB1W256JiJ%n8TD7{m%AMIey!YPw+`V^~M!i8kpW}%qp5TS&pXZG?UT0`% z2$cf7C`AuV>WyCkgh4=;(XHcDYtq)c50Km0Pd=cFv87*b7{7gU+76M$8*aDBO4J{{ zuo2kp^~;`d>VCVCWY6Pz9?G(aI}wR}chRO(NusYF4N@w!06%Ca35jfnOg4j(l8l|f z9T;c-;TeX;MrcGKgZUhd6Hl;b<}ee}GmMOvkhaT2DN9z5GcizL*vpW!9c(~E5%oBt z6^39bY)cVqg9{{R3W07*naRA>buO)EfYi$I6OQd3nv%W;jWY?F;cGGTx& zuTd{A6Sr!V@*Zk*f~Zhp-B_r&fgI4dhld$D;3BPLbUG4zua1g*^1}f`r2_eZHdSuo z`wiOR8lj1ZR2}IC_$Fdq#7Jp@aF8NK$(T@82~?eyDkHRyBt&EaLM*hXB8`PYBO*iC zj##foRI7saK!u@09`*__Un8srDC6OnfItZRP(xc21p;>>Pv9tgEs(}0z(qR)Ffk3G zhSep|9kz?qA*<8IT4VI1!AG6-??J0^Pb=EmS2y;shojT~)M9!ou`v)vA&o|z<)uY( z*$fCMmWq^0C05r~(|JLsw3B_exesGX@|e!ff17>4_QiTAUFP%JA3f^cZCAFJo%FQr z0EsQf#Mb@E*12Eo_}i|0apZBg%@?t)zlde}BFatx>t_*>yWKsz$I`WM^Bl6Xvqw)l zG|V08*vJAupdlJvO6Jaa{XnndI7wu$Z8JPPlBAF6d^FbG>h-F@G59=HIp7KaO#;JNCYuaz96l&+0j!$1^(5d6YTLib?j~ zI!R)i@EQw4;%g3Fb*TGKFXmFxo7B3$roir&2s%1OwvLg#XEg6;@adUxMQSALOa|$r z1ZXMHQecEc_ib!?#wytO@xhbpmqt1^xYSON%jY?K_%MI+zkZKwHbbRSrQK@bxDK}M zP^nb;_h0-w|MrW2V{vg2BN9q9%d*qt?jdp1xo2W%aI9p(=y=t}X|+ibx(Ltnl88^O z@!NiPHyaaUA+anQFXIuUN!>A^ltd^AaT3Xh6i7P(3zaq~Z4hx1Rk2Za-llCn`W0y1 z2S~C|4wZ&@=GkX>@r4(eJ}})?1ai3?D=Vvf^2x{i%fI{!D=RC+ag3)tI{D6A*X`1C zXsr<3gwGJjxu$#kL*dDDEl=BO{~C%*=4+%vr8n zxymOWe~jM_sFW-Co|8n18;v&LSPILs0lK;Nv`)b{nb5XtV~{d&9!Rb=Xrob5(TTvb zl;q^`V_f*ww-_BA;eWpUHml`2*KXZmWPA_Lzw|QSe*Fz<)e7(a=GWZ2caM6thLnu*5iQ#jogf^P-iE;Mq-OK9Q zD%pIV7(=;MWodaSaf6LjsV8QA|ciVr_`Rh-}tF$C@Av@PmL(1bD`CQ;=Vh^<1)E z1}~e#%Vx>u^W+B$42_JC$>)f(F217}J9L17nQ7Kt$;sh7hYm)JO-_*?D4;S9#w7?Y-3qc%1yD3=@B792_h$Moe75KCo4dPlAT1~uCkwRuLSwBrg#qn7)RaUJw zIqj2)d~~paAFg1TI(gv|%M5Ml(2yS3J~A6&Ihs&vLg^E!CK(N$Zle4MA!|5x6P*cZ z+cquX)6h*KEr?V?ksj!frU0#+q!mPn5D=?6+L|R&cM?!MH3~?hu!Ms$3TYgqc97Zz z)kY0ksPPDARioQYoIxm{@yliMks*#e8j%8#BXS#vk|y>nq>^Z1p@Wh@z0d4>pguhbz}3uHRoYb@q!^p3g@%GOK-F zwa~vl^i2&rp7XmtYd5lMS3VEvrC#~NoK3cq`vR<=YeDF3Q9Ap#hbYHRplHXg32cbu z?Wbq9EURmq>U{6~-w*yusqnmn9nWA=TYrzPS!>Mgl-}g~cFjOirI9MR#W$=BUwe@w%>+6JJ$UvdM@X!#&QVAs`K@hOEx=OWDrQL4f zSuVrF!wip%;JO}-Mm@Q{Tt*0ioADSd4iXzptTp+x#Ka_y%aV+ZjgiadKnTJhV7**seZ4}v)uK=+Fg89;u{cPrR!`R`N!xF;y1GiaT&AN@ zTb9M}@G$vY9@leGO5r*#01Jx?tgNikYBnhqiVT%X6bc0lP_0y0TVJPAsbE_c0|Nt$ zjgOPfW|2ZrtJhgvSin+>d_Do+K#)hq*|-dY&IzkmB{7tIIfE^n)UT{ zD&-2wQVa|Xkj>@@g8&3XQOx|pJV6lLr&j+kq)VCHr^Q%GF*z~G(W6hWXU`aoW(B1* ztyVz2-XxbTaOm(MjvhTqCX=DrXmI87CtSUHh538)IF8NC!5NMoJ<7<)2udkx)hZu; z_#tz1b4Zyu9=VRoV6n)Pr%#i!CDP6C%Xi=B;^iwWFD)@TGRmul$Fr`wFdcDT% z>?|LA@Bz!q%LoC-jveLHsgq1i9pLWVB4H>n_*ARQT)uLVN@Z>XTqaQL*|V1uCr_|{ zdN0jZ6U(;A=kio46=ce4;rl+dTAfC-fe?b>;bG34J*itH|AI` zHrsOpHO&`1N00A(c7XdDDN z4VDr_SXi-!IHE4=G>xIALv$SBNJR!g2FN35qbNi&aa=P=6t9D10Lg%m6fK8>a>xM@ z7OoapI%QK)f~?~aw0!D~7W0>{vV8d}OTYb)8*jb^l{$`NAux#4iB?F_)ksXbp|TwZ zq-1$zl`Ge-v9z+vfteXHUN)_F-M7o^+XMpLT)ABbhvc&`31n`>_Rvf+R(9IK?%a=i zr*;O_LyYlFVASUOiFC5r84})}C#Z8IiXsBvhk=1)KWtkJ3>3f^+P;q+_*k|@E}NrN zD&aUbuI(^1Sfn^mU~p)N$-R3h4G&Wo8e({Sl;X%Rav;ZAyGdY68X23iGK?yN76RLK zi4jC5&E>3PWEc}SLYksYTRAja0rf_kYShNcX9;bI(II}bMypyTtgJ($jxDAs6|=Nj zO~O`#KvvLp9lR#7@d$p=qAO`sv(M8j_Yt>dJ9P2vu$6p(RnU5Ctg zhG5yHvQ)(>SUAe2-SW{oK*#_Qx4^GqT6JXLV?_o_CiLRcwa64oIOBWJjXJe@71|AS z7yt(0dN{U&l!A7y4OQ*am zpP%efD}S-&)6x@fH}`a?nKz%81TVx}qG~(Wbo21q4vv#V@Vc&>q+d+IUeEKoV6Tof zZNE*s)u!#Y2|IXzk4M1?i}7PpH*c0XD^>m zJAOWapj+SNQJ!nrIwlec`JR+A^}tTOu=|Wf-DVd3QMbuIN-1*rJd;yXOiWDRI8H*f zY&ssJ$>yd*ffWP+E6XdatgKL}R=SvN&$+|&=-1MXn@B-rAyWf}ObrqyF(%1}@Z(Gj z3SZ_C+#l(e(o%M!&)RL?efKx~^4{0l!trq+D?V%E!LZr;4bzy9Q3c{F`>SXFPZwI~A8-Q6f4CEeX6(%ndd zbSd54-N+9CX^`&j&O>*1^S#{r-RC*~p7Wf&_q%7-thHw5ey`|mrmm$shC<@QW3*{i z$VuINoh?Z%!`*3T7-rZz-n&gaU9YP&M3gA#tjI3tA_*euSM!V<7L69gS z&dw;mTQ_TOXFcBqJ>F)$qzvr4qwfX3!Sv3jo7MWO+CG4l%;g?0lcjBNlF591l##8h zTcE7dnGDxk!RffoR^D{(l<9qMQ8|z3&7*H!FqCHd{0UqRdzq#ES_g;QRT>TxZGI)4 zF)!~ZMdX*v9sB($x=fF?_nBVDT+oW8)Aeo_)IKjaKBHiAp+$9?PUn?cv%<~Jc|9x7 z;KK=!&YwF4P@$oE71CE%+x^rNyA_K?+0)kgX%sH*17`8EaC+9sNcxt58GgAZ>#op{1Idf-?6M42wcOyvPkxbwP3>yD^l)Dk~?i zR5FW4ObklcmHR!d$IH?z2N#=2f#+kAi>di4*`s-p)dw)CJ?sYJlST4$D}f2`m(Jr7 zdE)u781l}anVy01e1qgAISl7Bd4AW;JAX;R1G6lz#GNdk%ui}%rz;*O6_x)6TwZP) z4;Ndrtf&#*dOu%eU4X`Y0%bVe=Y_$h(+-5G?_V^Bv0b)J?|fdiZPhikAH6u1al~aI ztpk;SR3|BKeTMnma*0@HqqDX0NMveuqEtKu4uKh$&ol3^DFzvIt;t!bt#_Qy^Uh0q znr%z}+#IfL(;4??-WT4aa&0N{Toyb)m3JyY+`|Z5w#PJCIn|A6vxH!*se@qgQkFU= zKR5N=ygWe8Yy}?h^nC6t(|yjUkV*Kv9v^k23($q(02zLA(GE+J9lt5?vh$Mmjun<^ z!O+GgBxX%2w16JG%~0(=C5}f6gwpVa)~M>TCt2G(kUL}?-B!UrB7mO@t}%6R@SVQ; zmLHFZf^u;Vc9M5Y?%Xb#hK&oygcM6X-zq%&&zUFAs&YMcG0Ug(cV7`WK0XON!pRD! zmDiYhdd4Q{a*w{;;k@9el`U_BCu$&oee*ssa^2#epbdv+9myN7WF99%IG+0=W)zj^ zI-5cc-K^b8i-sS$KF)OOPBZ}l`|libU;}JEdfq7IK770Mf?Q9*4m^D_FM1F-h0-}0 zTInx5QCuf9So?SUbYjHqHoZ<{0V%?S)M!4LvnLL@ zb}JeSW>hl1+Fn-n3%t3%lcs2O1T{N;uc|Sc@h{%kH{E~jV(k6LnFoGi^|}hmYgm-& z(!P~5*ud*obbb?07EJLdjzAtk!;mW;cW22_|I}`qqYI0HdYkch96~EoaOX@VtZ7ab zjAZ_<Bc})suK2c`lauM^%*&YHTG9O+VxJQww6vo zlLJvJE-F%Wu*w@YJ5hqq2OA$r(v$oAMbEflP-Nk5N#A87u?P;lv196i8th?ttM#vb zfV$EuRS9|ujT{Ee7qPKXE5o$;_&H0Q&U$Ay?(lHKI6Ta_oFp4AK7iFwDV=d5S&zcJ zwmr!>i0?4517(qxg4uv*^1r+eR0+Qb^0$V?(Kf^`uHk>@^EJxR%FBO2U=SnI#tdZW zid9Ph?Mw7<53D!rPcJ;qZOEq|?+lm?36)&7w=FNf(%vp4{U7vL#LAKA@%PdXU!8}=^TtiAmO>nyc~a+sax|V<`pl#-nm;w3 zb9Pk*qy7Hzl>ya)SV(`-tEVS;DUwFK@`IZ6T7kXkd9!MdTRw z%4!}2D)@aN!ajAc9Da%z&KTGm$7BfW7wwjwRtTx1WJ4tS2;;XW-=c)c%*!^^A4k(~ z%mOSi$VA-1sEXyY!5z_Gi{#IyzM9QfnW3~kUzOwH;~ToW3%r)&O%KP7Dg!1=fxyU< zOS`_=AD7N)@2gr85F5*CHgXD<9NBFRU~TX0fMhxa<{!iY1adB6`-t{%eUzuo==gN+ zbbSID4Z-Nu(9l_n8%$D4+}tew8vn_Jzvc0R%gM5l`}P~Nk@Ph`z30@P?gg7snfx&R$k>U1dbvS6s<5soi>{|2;42~x&yc-)v z;3An6`;_PtIPLUFAh$gneOnH%@CKA(4URjU4^v;wOB?JrU?wLg(>c9;3%aRhW@lms z)(^ibIGP<3C-K)yT9?Ll)MG1anqv-==GNASJM$qE^Yr}kOPXtSiB+Z>y}xHk7{DL! zeR{Y7n5f8YuK)+E-rd|Dwv;qDdvyG)TsmXHZdqS89A`EH%1vGG>kB>oMm*%B#UM!w zSD6Cz&n=#rdwxNR()JhIay`AhTsN1KLn9*-Hgyfo5BMy@IS&?mw=MJ&XX{}d(Q7#d zui~$CgDhdMtgQTmO-*tmPjB;`Tf9nrnam%f?d@$`0-5l%oe@5f8qH28K1S{Owy{&D zu&}VD2CpCh-s~=Sl~RYP8$6LE+tHwEtpOF%J~V__U>G7J;1;J^(hm@j>)xZAs;b)W zZv*Z56F@dDuY0z#4F_;2!SA+(V9>nI&irS@ zu+TGkj-us$P{;g%;c<5t7xV-^ZZGRO?5&G!?<8@$U*Z-iWSQF8Mb|;R)4mrB07Cm^ zPrxgPMnRyzqvLJaf!*$^5Hb<}&=tX~hI(@EjaN7`8@>~F15X6AO363xyFon`E|t|w z)=`JukT~A6E)4Bv&j8X>z%K~GC8sra&KHe1Z1$l=k_gCG&5Ir+PZlXu)z%KQzC3(R zZm#N+`P|a+E2Rhzk67xbm!!j(WyC=}A@7gija~&7X6AO3=i^p@li0hJLvVCma}Kf# z;&avMnZMKodGbevZMF>|N<p zXlUV_fQY|{iEnUzm00nb#B`H?wu148rs$(ff|97rhYtHEhxBVI^^a`sHmr5h+fa1< zwQLsbd0J{j&se~7Rs6*(qW0o7WTj5MGX}>HeduZ{w$3*G&JP50)_b~V7kdC$63YvaX7z+vuGLZgiF@MeYM^Kk$%WG>< z(|*qWbU;g_+)wv0fS0vber#mBzF1^o_>2D^--A384C{w%;dlaHqHGfkBi=D&R0C0H z7V%(IG9&+RRPuM!e$o1P2wHPiXm_YvrsKkBWFh_m zz^X({Y?Q50q|M+*m7~#98_PzZJYZvdJVInbBY49s%}sT)+a_@Iz4GkeQO0NL98pMu&iw!X7$dPSE~3T>Hc$qr!IJ!h_CKsF zy@qNUHmyo?sS}xAGI)3JrY!@)H%gH zYo=@bx0OF~i%RwP9gkPswJ6jm=PcXg)yQ9bqy9|pzr^-k6h~X0+%fJX!{Irnf4e>N zXM+@S{@%Mu?RvXk2?kGf77V%=ezMJZ_x@i-;1jxE^gKcqs4e>v5_o+sA?kcuX}n)yyB;J+WiRm z+~Z5s${nt*zZm|I=DnTHD(C)bQ=y)({?UMky+^R;0^NNx;oJ8b{IVob+tTuKRsjKp zl4ea3M zzL?RnW#;8Ygwgdn`W8vV^ZFM=7i}FcdXPGpjKQ@g>AHvP?d|24r*m~q?u^)P+&itf zKUg#BH1%1QH;b3*(xeSjtDI%_uJC!_5)jGVZxzTq?$5Sv_pNoN^LZpbJrt#6JaB=v zlle^Q`VNM%9fH3Srj6yVn-CE$5MGTt0E#`Z;YUEs9KCX=?4MaA={|Hu%iw%I7l610 zi8pu8wmyF}GTQi4p5%6+x3W2MNEAuLHxPgTF@!un5ehs*0|(T!yQhsFS`9W_kK3VJq#E%l@*#^l| z@}L_3_Gt{o<6YJZ7xfHoDRYH*zkH-em}2OZ7W=$P%_2Vn!iCCzSgN!8Ax1xEB#Uvg zk~haLDX+xCIDF2rPhPIQY?fMLW)9VSi0=;zFj7*ja^nOhpGYK&&3OJBQmY%``NNHH zaiQJh8gq5Ua_3353{~{c3vxh{_T*3DDpFR^68tv^4HoxJk6}P41HSke3p|~NJiZ16 zUM-a$EekC@VkDG|Bnz#0yi9yZNHDYDh~&BCxwLZx!5g%|XvzVXIn}9xu+Q%!qg^LD z5<+=n(_=Qn1xeA+4Hv0wW#B6elPPZ+sjwognf-fdnIzHewJ>8-89w|q@0JUnF_s+Q z*N?qP_-RY79mCl;V2a^m{XSlJt8&a{;=i)V--$WPf{2*?2nckD9k~A*nBRBN9kJQR z9`M}4Q1Kg_s_FdKT3QN$IEkq975&I~7&ZKkU-}bK)@}SZJy0xYbO! zXcYP4p_H{VXn}~ngk0yGn|*JYW8Y9L;u4YOqudrR1_F^h}GMotCtQ2WjGp&{c6+!N2M;!4-WYRwvs!4wxMbt9|>)qI# zb0?({JoKYGZYjM>g%OZSRtHc=9b=T0%V$sDwT5xr+!RGL@0V0!2Y0QtY^)j}daqX1 z*GuLoW~yx)c+VIkiAohSP{53W2rve?LCIC#1YiNuz(r_|tzd!lZ0) zjbN_UIy&~sk5?b)sEqS$iac7am*+4kG||{}kow3=CW_M+kqZa8Ia}oSUUezXexUGp z*h`hmlGFQp#z#yueB!L~lEuMrQHEUg356nxl_6luih~&rox9OGYvrZFEd0zXE3MAP zVWZ~?6Oo#EPG4{rDRNpkSQq_d3L!u4!o-NUP+@2J^cyxArF1Y7+CM28$?vnZ)`3Am zpsM>^wsBeqdC^*NKPUp7CSU2X0b^LG^6{+az&2ZMow>2PUKBSF$cqm9mvmMp; zAyQRS#l<5qadk}w!r)s0eVb!qoX_5pHL4qzab|GxLB^~aR)b_L_IfiLI;3@a_i=MF zboSb2e(e=;JUQ>Y^#$p~O6HB-EK(NhY%2cNw*g5RD8uogR50-G0O|G`roiRk5faKe z$jp3a!yl$hrDq56?&7%d#QtjE$zdLVzG&I;Lhj^7 zm1&!1GxaSje6%NA=SHqAkW^N~tNzu8tLfdg>~Ud?@SZv-tm*u!d=0*{V_5?<(a?q~ zz6}j{8)@_v{DSil_iUMtnX7p`xRm#7lgd7(YEJuD{ed1*GG%Jpt^e{`Y9-+p0}JAd#?Zvcv}&vp`o$19gzmag@8td zVWpC3Wj}@UKg7fAI#HcKy*{wU;ift zjXcnf6=@Z1r!;hQ8{A< zo~CT6UXD-#sJDrUiNO58jdpNg>2DBhy%-)IZs)p93X3wNNRRBWb6v{FDvT>mSNbPz zv$k}$c$T0#m0_V&b$xg0Mpr5RjkvUQ<=%GRjTdOyj5O>Z&DJcwBv%g?%J*8Xw6N-kp%(^~~xH~vr37Nxlx=Fs?S1m`RlE#!8#~Q4# zau4$7F%uws6Y}RHe({#%bf=`L>e~;5Z+crsANW6eLkHv{Ow>;k&D2J{Ga^^pn`=^$ zP4{H)5|*YdY<2s0(u6wpon51)PPS-rdv`o`8 zwb*}s>w@()CgE|znn;pYZl_FA?lzdI-Bl7@&?l>iRzX$yg--463V-_M2##Dy=+oaX z^>5SrmNqK=&wqS?_#Jsig+_8|7LV;Y6+;$toorJM)K(1U{_{J?&ikoEnA}2X|DT+n z>6dIoj1R)-qGSeDQC~}_?|Md=1q6aZjmR-08PGc9iG#>~ePO~yRBvtVUOZ{)T)5}1 znD`Ko*0&DNT=woaGgnC*fysJ+LC0#|_`Oiqb1z32dI;kYNloUMsm(Dba>Dobbt)aD z@xO;h!(Eh$$>g%xs=0MwI-#CyqJXWsYFxjlWpI0jeONWlv|MELV%JT?eI?)1N}X zJFMRO!ft;V{hXLP{hgVEb-4R;bKmS}h6u#6l7DwRLL81Km-Rcw9SBW@ZNvr!3!zBi z{%!$=4!lXCoV20JiZLeN>*Mp#b*IEa-!OOx{+uCRr7W|{gX_govgc-WQ<8`Zl6!rIdyr!!YJz z6#gVf`elJp|69>-dcy7#C#6otNvtq{?X7yZpL@LApNP8+?JFIk2ZbJ{aM>oz-D7kT zd*;YMtoItu|6BiK54}b+0q~~Gm!R!{U%J?8IJ%$7kk_}z|B)=yd{Z(gNXp(@op=8x zC^jjGvuk5RD7GQ!)^n|sKdpK6i<8ITwn>Ol1DV#B9ORI7I5KDv<{`S8(C~7pi_^je zSL?+>%~BRVz6ezE!M%eAC?!nOn5Gtij+-ah8p=;;_(?n2-cLf%he8kmD{W3%lry1Q zBRGiPIU&h9YE(zBhJuyE2@T=u&mQKrw>)?)w*Nxex>nf6LTK6e+=AJb1gL(9c^e)3 z`<_t>+^tD8^b{d-Yq3E|#+a}1umipLabK-97t{^QC*Da(EobO73hBl+&XE~M8AEY} z%QlW1egwBI3Ki={tQf6iZtFdI!!~%;d9rVq*c7SfE_E{QYdD@uaf$ z-#~>??<;>N(+A`K_UJO$3ai_=99fSsEaL}EmVD)K@4M{%t+iz3b@XJIv=S-DrFO5qJb&h-DP2uQkp>&N|l7e*xWX51Q>7v$ZE~(O0Fs$MS!tKqkK_= zT;t-};hkfX>z>;&{c?eZErvMk=pAxQClv8mp%1~%$S~rBhOy0mqH*hcwzK39um<`L zf#On6(iG!2@;l*cK8JAs#o6oT(P0jl3-j6ri+^RrLd)Njl=PYEBnX&`4EtsmO_3Ek zf$5+9k@6R|l;Gb8O!VGL+8%bQMby%QYQ*n^N`HQFu4(?cq#9~ugZew~%+S+i1D%az z@hNUFzJG9L1ER)|EWc^PAnJ^aBl5TaFC3dhIfzzDC210A2IZ|xG$`1eNUzf{FkM6C zyzk^oYiQ{b)YEK|$|3Mme)5qCS;}{A12*(pB@&Jq>bB!t49-{4?_@{rSl#O!qs|$y0bSi!{xl64m8FqRjcd zGDK1Def-saR1zQG+#gzgktR~oV2U^tuF%uBS#S|l4AM5ge65BRR_@(6HYth>y*t3v^@Dj`-M&b=^w^YM9 zqv`UElH|6KF=y!9D8pb%b`5JMe{AtgZLlL?4Vzkcd4d^xL9~KZMrN z{ocGI72)i3k&UP%L8SbjFCStAaFOTd=MB7VGJ!f4nZ+qzv}oX=mDXTq$SL<#+Ed#h z7^E#hk}($nq}xAzm`(I{4vvLQqO{9qOn=s9nOUL zRF3#ZOxI9Zq93!81CQbk)GNvJVX}t2qf;rAeL3p#JrpU=CTl$>#4!ZoB>z$>r<&FO zunqBfs`J^}9@Y~7-k`bBEt6F5al@FVl?GOQR#r8G?i&N30Mds3p8jrSW94urgX6ZH zasg1b<}mf^Lbe0F7j6UugjfIXd6$&$7%E#yNr{!U_1WXa=tc91SJYk#-Z3LXMOC9r zf#%vLknn&Nm(^@k(M|`DkMk=l)NsOv1<{E^O&*FpaU7u(h6UGC@sGl{{pN~UY#_Lw zXg72OgyDdKC+Y6_rZp%{63yqxQg35DAk4g=!Tt&6!192eo?c%gwxPi-(`{ShmC^&X z(3|#|8TJf$oLPok!|sKBe3GRmsXv&_x>3%Jz2g)#mDhCspf+J)EgGVprh z2NK-H&WPjTtx{o85ne=Km$Z@{!qD)r{pIesXl^IlqIYZW^$a$+g1932^T&(NOnhI4 zL8EL)Zt!%?7hYS*_yLCx(aN}f#gS-Ta71}3#)yBFjo^$U3b4R8|1Rcy{rLBG*!J(C z#8Pu}7oc3jwCE{fs#C2~Be3oB-JWGW8}`55QVvMjvq(%*YpDAX)o_Qmy=?{tG#IlS85+t7GoFkwJyq-a4eNGk`6m;XlTUYZ2djBVSsFsx zkT8Gww()p(0XFFZ15L`&==spy1vnt9{}?Go^OkJ@-_mz6DiEa{N&-x6pq^#tV5hBT zd}{ycAtUp6X(q5Sn8awmw*H<`=bwLkY(xZ7>M%@NS{nVbR<360`U6zw+D}fFJF$t~ zdl6akFHYNwLGkDocw0~jxR2|SXwV{wiO0anb@56mzh>9VUFJ-WV?6k>L7V0gP$X1U ziMxRnL9fgOegsV9hTZiN7wDXoE@cl;X70`%Jlp7Pa6OYDOv_mB2-rE5;6GADfRNa) z-`e9}!Dwk|{V6L0O6v}o_74}vuOm_nxt6rZI}?2%f7TC zbbfg`XVSv){!$8DPuJxTrbHC6iTn3d@#YxLKawg|7Rmc+Y+$pZ0R?^ZZWlX+RCgy~MW7SL_BSiVF`)eLTN6agy)4 z^W}{#orKAG>-AoEFGonQ?kopJ8yum<_WxwF*_Y{I?=2XjoEK|`tCXMZMt%#graW>E zGtGlC2g*RWHh=8$Ju(1N6Xs5|*n^mZSnf~!27ktc$?0JkB7Tt(c}Rc#8V@F~q<#J8 zOSvV~qm?VE@+*MM{vzMXy@uuHmN1rf+1SEpo2r3_vS*XAOq>!78$g8`SZclNL>4OeA=n8&oX6lu@8Y`P5E-Q#c1H zL>AT!^=Lxp{LLqaZWi}&B+#2Yma+7QhJS0c>Lz^yqLnCCHNSa0p`&@k-nhsEFffC& ziwp2;98MirSy@k**X&+bAOJ$8#gD)#+wb4;JNDKs7?6sFCs_s}bDo64J6Xq7Wpl z7T$%UV{>-k>-O~v{}K#G7T<4HYE22xz!nP^Al~ZNFOpScz=QCWl-y#vSLFBb+Aras& z=C}Vm>o|AAZ+&Z5*%oa(_^?BFN7#Vz5Js6j6pInls4NXH4>gPTQi?&Kg9;7y%Lj^# z{*I-B5489zqFXpWgfP`|?nyZ75!~thK)Tdvx;t%HwvWGCR_|*S=ro)UH*$q3YV1nCTxx(Y6diP(Eo6J3@#K6Y z;ggExmzIl+lhZtsr{ELMo5s0Bv7*T}pzuHdbTd8MMFZMq=1vT?)XfvxvV4$Dk)HrQ z6lqMjQ4sQn<;Mh+AQ47A@36f+i#IJ#N46I@K4&;7UFQo6_~nnASl$OCJUt%n8F09J|hq zATAdcev-6cJ{SK}R(dv)-~yZz2#=>h0^sdIFVo7`Ex%X~OH$Wuu_R|>YdT%OxP1=R z_0i9CsvA5$W<1ep9snI7pIaa0K=9Q76(=AGo9?!?nyw!plLuG3HxHNYI`J&T*Gjuz zAX9g|enK-{~>l1tH{d9S9W=gI$qwfTR=^JdKj>SiwI-2)H-^!=mO`9O84I0sxrtYnRq{M>T>j-lcYsX zJm_X}e4Mj?z654Z;F$&PUSUZf<(xFTByd1HGcqz5mMF{5qI@2W7Nq1E3NRDC2jpsP zy0pF!;V^2ijy^w*a(NsR(kNsK!WnF8tyA8pI_OV>Pc5)>@?*BLyI+jXsL0|}o91-#R3TW`rB?sq1`71BUc9`V?30O0_@>BSWefrFT{5@3jf~wpy#!% z7#&mfL0fpQ{(#D4fIm+XsE8z;htRJeyvGqZb=v@29CUQppNxgKM}~%2@ZIP?mjleE zqdGGql_BBr#IKYe-YHtiXr}{uk>pP^PCSE7ylxt&Ml$kL=tiJ|0N67tq;-`Q}e29ofSKi~Gqe~dTTq2(URMW;ks?aTT z`F2skKFalWI!rsOMcfWeoqG`!n(%0EK}_0pxLirrAMl9wimVjLSp~|B6w7awli-Yg zMZcF`5XSmXeM`ftbGyjmnPb(D+g2P%wP0~X|n_&tRawCK2c=Q?m#NMZDX8@ODN_ z$shYcxZ$r(k4?uZUh4S$dnhP$!ztxIXj4oRGUK~}^-r(;4!yl1Y3H;B)W+Et$wQ-! zFZaaPPx)^Z_y0Z_k1Qjfb^8)gB24oNrJ?_eGqx#1i?dNMaiYGFs^jy7%B=4|;Oh4; zA_~G)m^yDAiOh&;ifZihan~P0-`Lrc9>mVTjn4x{$n@2#X>VI6~rSK7L zTwXg~ZtSYaUAB3(cHjmA9>eZn#+rB3$istRv67ZEvLCjgc^KFaK_<~|bw(nCmZ_4V zr)MM$Fy3{uvavaDk0AI{T26yLilpnh_CB;MO|%VYgdQi%=U#!&!C6m-daqrf^K9d? zvn#EEh(^at^+Ju4J*lJ)H08Hpvb%+|W#iS0L@TZvPTU#ndQbbazzGQlQXQbtF8omH z@1MV^sv^$o&tu#FnOj)cTy}wUJL$ML19Ok%l9nzRoF`yg?Ek!eDe`D+&)Mx}*+oNF zH)rhYLu<$z=)={#&{yHzH#S7dQw~b*i*=>Fu+&s{U z7WhOg;I^fQi+um5lrhh6qkyEBtc7E<=jvuWXY_mmz0*6&x-J+?{14-@(bft)sfLc0 z*=CTH?GY2cShzUZsL!6;$AteZPv7QEFeyX+Qg`qbf2HIlvtMh_^0E`WT@=UdL-1#%V;2K*KVxNF=_mLv}u18Kp$HX*9%-Onu4b2K;V9EHbFz*g zMFeDoxaBa&wwY$s=>-lcz@IjA0@=xWxyu6Co1T@G6%j_HOveKfPZiqmIHLs&uYkh9 zMGWk3=IQcIzD5fm1H8%Ou}itbhTqLA{T33(7o$S+0}u!v zpyeM3M4t(?M`Ph3!+>i1Eu?7q*zV;S2IR%u@xAj#HN67oD|}>T6A2c9Z|@h^mT$^0 zR;F)?PiEY<64dHFc95&8s{Z^*W}d0F9sy=00Q~@iadbrV#>&HQYs-mnaqIT%z4!_o zBrBX6J}>$~>MqESzc-TP6)Svat9Q5q%)hg`u8x7FS=gX$vsmN&=FD)~j|J-`Lo~AY zju!}+%WprzTO1x&HvMa#*`}T?Z;pzTsMd1guXl?(I+6oUx-1qB4w1&mw9`L)T_muR zJKrU99s6Sh?>v8I5yzx`o~H@$Bcfp#BtI2#b~#w8KZ63*@5W|v+{SuvzX+`f;xkJ~ z{_?`Y`hA4u<7R@7ftMGOEvKNRiLtlN?2v&LL+UWH-&$WEtxU+yovA@NwD2z#QzXY( zwI{#MXj+D9FjO0A2|aY(b^KpAaqD$``R?bqoJ8 zeeKOlnx`Y3<7UTzo(QeJ2%W=UQ3NT>oT{-Z??vHQDwB=FvFB?FLZ$a^#7(*2-u*Xi zl+NuHTdaxHEC1D)*Y%hoAVz~V-QLhVMs)@q5iR2n+Se$(QsTun%WxSB4U%yC{Hadj zl}_)hPb6F&cce&lqI8CbEjfG6jerrWtf}dyJ*^-LGR>1JnWhdW_ot$35L;4a{z`{d z8*qS4hbg08D}o#8Xd^>L7RVV2V3^R-mxk%ipQLaVPpBN>w9sfuh?-LViMwxIb4Bv4 z4~2hqv~?EWiPjqCvkg?B=KkDLMccyjhX8jftySD)!#<0LRVF|bzsy+c1q^p=;+8cr z2GLYZL$gDZ!w0dI2g8RF@KP)dtKQ@1ycf0{BSWS5Qa{n&Ed(EdZBUz8R~G0g1CMPKL^>W{iy`G(L#?$$ZFmI6n#sxEWu~0CsO%D= zN(2U`on+DEm-GAYhiFEKU3!~N z&v6k!{W{*{J2LbJLE3A*QC@rJ{LJAYIUA?MyAwZ6F*Hld5)kj><5bq$lbBd{e9S8AYn4VkW` zo-eBJsr<(fm_P&Kwsxa)1ketFYBX;J&T0V1dF&JB+g}3s_B+=^uibx>N6vd!?uan& zK=Adno+4P%YaJarqz6s+;(0<<^W>o-Fr8>e&N#g>Y^ja@LjET=w^!vp!_y_Rz|AAo zVk}gwlCAz@_lFiDEO8n^+MN6^Cb&J6K=lwp*Q#;KaAD`#x_YOBcZJ`-&<`4Vm<8F? z`H?_lA~3G>Z7jQ#E0&*t4e!yyr*T=&m^okC`^+#2&RQic#4~$qZXjk(ZYg6oA%3X8 zOikPZ#>b2}&&_WhBp1mMDHbx28zW#qXTEmJBX+mphf*XZe%wpE2;O@?;_|08lqR1i zn1t_0wwS9Zu=TZan^C(cfr!W87oYfToA0QBLRQT~1pXTy46%j^g6d2;)i$y+#dl&4 zOP7`4bGNd)y_)WY=!Vw&tSDi5rzkQ1;H zDfvG+viy9YXLAVj9v>s~EH1tdYU&OU1G6)vnpgBWagBRNWQR3DjXbx!yoJ+x`~J$E z2rJFITwpgZemy}=7x-~udMoDZTZMq;?Cu`QsS1=wu<_R=Dew+ZNvT!|OmVg} zIU7p!v8%w45nU}kGoWJXmYYd7XAoiI046yjXZm|pW8+{O!74YS(5mA`4-$YEFn*&R zKa5$(ZV_STrZnin$=Q!VQuSt+s zFNq~5EeZ|Fxw??#h=-JiKF$R zb26~BNtgV^zd->e$nbcp)U709jXSrLln(dLp| zH@I(be_n1JWW~uck{==~X#2<+hs82Yx-tqE@u|?%LHeGl?6hqljr%u$+r(2g6o2W* zhAilu_2!%M^E5TRt(AQi5lAN;CuvQLX&sdkVGcSuoj|W-@4!2=*<$7|h_CWNH;%5p zfkCG47NMPeoXMr%&-OOja#5vZ*Wp3`J{iis0LgQ+z3?M9UPH^u89vv~XR8m%*0@zy z50tDorBq_hUV9$fHCfLx`3Bz%oA41~*a+m}t@=&B0OTylJ=oPqp(FH({9!hR>Nx2~*gcrqY zyu0*Jr@|?kEK>cCoB`#iEf`Akql!@ON0Y{ zTW$l?iR0V7_8uYVWba2Q$`+Kfy+Iw~*q;jQnGP+Rs6no8PYoWdS;f{C$!k|h=ZPkp>VL%C8 z8EzFgMyu~~NE}s??4Ez*M(9NHtZxyDR1lh9p9KNvj2xdym&?$Zk`~mMwUSbJVDOR)O1E z?9ck zGsCOao(<_FxQ8na$$L|3gc_T}K{>Z1D4l{d@dPEA6Y?!M^vl7`EShB8fpSDSS*S2u zC@CTc${<0K{$#>Seh;RLMTis8Q7K`j{DWajW%xQ9FZ>CEJdZSPkmwqg`j94Md-n#m zP?xTo77i>L#q6cE_O7dGPLOi#vX@PleOo;P-i@Z1s6QNv@WDoLC4tZ(>^^q!%rCt_?8YSz}&NLTwf3ZSU(_6)lg|jCqw5B=1 z8*Qi@T(`eKGbgvQB-{6_ACNv2uprRD($YiO0(0{Epm8xjPmRQml9mi^osv;T^H!*B zdj?svcRRs<8;OI14l4|Jg0XQTPnQDBid73gbS4{C#EL;y8tc+^CX>6s+#%rJUOb=< zi{Ts`E{=64ViWn7f&7tWBd>>(9+4MCOS(EV#0VqheQ5S_E(9wOS|%RB{R!%w?N3ZF z(Dg!U#21&chP0J-co0ll%Nwwj`A`5$?oyG3%b#Lo zHd}h3Jh4$k6-zj(gjrEtEebXx>W>ZlA*jZU3zQZ2zWm1r?!HVbL?O5Ls;eOXW9$F8 zdfuXlqQ}I!=6&ZYV|ZWE*Ia}3yqEQ&7uXJDfSpCqtD8jofkt9tKfUZ+w`h_N<=kNO zOG#hcSpK89L#B$fh-~%GccTm;N?Zxr@6@ms$0|D)-g!ZQ8-F8-S|&s39b z+qNg$ZnAApZn7tvlWp6!rl}{}?!D)KUGGr`oz=bf{$j1qD*RFBi-vP%;nFCQ<_Y3S z+9jEukiX$%^#Ap1Do401_2coae532;(<4D2tRj8b`4W;^L)jS4V1bHDK;GA;@S5;A zo+*B~fCQxcE3qgPJ%~00i}E`}FIGuo;a4NOEDfX}b#8Md{JywL(`zR(A7f6Ki6WE}g0ZTdN^M%#xWF53Px zPnLy?_+hcZQN`$h(nKy$a=M~J0fq|a*GI?De&RP_!C$D1wO8R}ed1>q{lM^TNFRIR zUt!xAH8ruxOGK`8v zHsW--U*I}VM85q{f4J$hdY{4?`xzQZ;8tMo6w1JaPd4FMDxus@`2fQ$6AUR`*_?*X zsWWm;x_pnr8%*p3CNTb0`-=*R$G_#YegtFE%rOxsG1}2WK_c!|9G3YiJ<7wIOW;W2 z_K1-Wg++ZZSk|kv@WHs66Fx2;-uq$MqR+y~KRTNT6yWQB5M3o*K7fU3B4z?xqbH z9FKhSR6o2HM>SB^%x`v8g&uHCc^{*eel*D^3TP0jur1ZO01~@(AJd;7H0j@*&%a@T zPZX;B=W=&bnIfEZh$cqxv-Xz8d8{z=E6y z`BNXqaQmDSBQ{>P49>P+ZoWoSL?C$Nau+U_CXpx_PmXnnSvIeOH)%Bv-FN|qJ4Ey0 zUr%xRKTDMvF1&iqQDhKh>nHz|pS88M@mOlSS_Woc#<6T0R|Th#{XXB>3!_2o46w3! z^5lQ{Dfg8M9r>jdep@?Z)Kq>-9S0_eYGYf%-!G>;)#IfCX&BkjXv25r5vQDM)m*TF z!xM@Sp`M@Q3Ubw%qEeP%WPw_4Py54SufDT>yuAAb9{^#}G2ji>;lV%x@2P8*ey7y} zO9D3v5BZnDmQ$?{Te8A{igi_KWE%E!{tzKcIlNG@U48gqr3OVB3S|lshBT?Pky_CA zI{Vi`2Zw1+%P#q!H1R%DAL4sU;V<5M3W%}VKBw#18JN~@L<$Gf_L2TrER^F>^U~FN zX1{F7>$J8UB)hj+yJcuy>>Okc?w&SewW;%&SO!wPM)>D)|I!uMxG5%PspLA#tKzQf z-0Bn7tp9d42Q&Cz9r#b>ypBEqj0!6B4EAu@EEzch6;f2*C*8&sof66y@ydsLtldqP zKvG&O>2N&7=KIS~mR9M?$qrzim+b%Y;J{qD~+*}6z^C^=GsMaiE0 zuz{nEIexd#RynM;OR=ZyD||f`K?Lq>mb>Uj@%8+1DLs9CwfMnkTKY`XM|(i2%#S+%w3B` zlwoX^L|nbdQ_PfRxk$T50=ApN5_wuD1#xS_zhTw5qZu?cwNXz#JqwGIIvIyZW*5v* z85v;{7ZRl~$D?N)aG0y`>kGS}QRUPK2vPr}*TYj2g5o!t7QWBmTBL>rlg!a0aYF;j z0=vecw=uf)K^)o1-dx1@IK^QuDc=blr2&1!XiEIgr3I$`lrVgi(FOg_&p4poBb9Vu zI{Qz_<-i5};lNAqUiQtdfV80au>&hFM-lgi^vY7k8PIo!JwDd_diBcmqahDeIiUaE z$3Pi8lJCGjJx-SP&?Q4HM}+W)3jwgUIJIWtGbWqLbH}nJaK2R}{ryqK?m2wgiLl{) z<%vxQ+^(Tnl|E3Ydq=%UpZ%cXu0M67Q%mu_M`1C>4o8~CM;{)&i^O2U9#K+%yO$>Q z{z|YIgvZe$u~Q(15qosY?BqA%-Ib$hB?uK3Y)3$NhX8DB0r1u6X1h$VVUI;pLiv6d zfyv=mj_dWPfIPJ_+}7?)0=Mz*a7Y-zRFaIs>)YWQB{gV8r(AFio$pa2cAW)b?Lo?p z-n*I{1X;D&GBo+m79|b9LVUK(x!720y|Yw9w|+cS>9eymYVUXwK%iDy4j~7~^S`6^ z*Gyq|6Y4i9*rC5YQMd?N%f?_DO{WAAA*?Wbf}{FA5|1RhaULS8kHcc6S&l``*5ojw zNnu6C9WWRA-HrqI_4-%0iJ4jG>MA#0yHK@Y?xr0J9>RYirdm=lgDwb3%9SrN{96L6 zkYMjZA4I$NgjG(UB4myri1R;}I;R9QiesYAIn8BL@8kYgNkq}1^`9ij+)AlB>hJ%Yg3S9K}@l>G{8+!%<*}y-5c)aPxMn;GLO57e8cDi z4RNcnT&L2(eq{y)gxjt_pY*v31BwPHKH4_Xxw$h2dQ^&q1qTEnV(a|8Ks}YiI~+eq z3fvn10et_5lwXNYMKILP0=+!k-Pu$pyQGd!=se?#o-@b@30hk+r!j;Q^868_de_}- zWZl3YMsrSt>`q4;WxUSO26x@jA(QL@Gf=un7QkCrPR^1_q~_!p54v7u$ORG+MUeI} z86A2)3QJb7rKt2gNC46gq^Jqs1c;))16uTHvj@w{ygVflW!H$qW4!4s?m;*MuN0BmiL4AxkGINZ3$}Hr0+6k+Qqm<1anK}3 z6+UyLV!t+(iUT^ijG_aSvSm`te0!8o;Z<3&I?Y!lS=j-h7_6UhSf!e3`!de(VV^2n z!tAN}u=7GFQUu)4f6tLOgtn$o-}5!=qOvE$(6d?|SBqAqBBd4<0URj9r7XFln2{d#R4{XbJ-p0C zu^>*Pog0^yc(Q_iIy$g-+RG(`HNo^*J(;8sRt&xah5NLGcaD4Z14(mPH%1^9CP zHc6V!zON6J)oIfGZDVM%HJ_V!I^673o}?jEybeF{#EaRJiV)!+n1{rrklL`x^UlrG ztzrgaE+CdQql#4_?e3b3RgNHc8Y?U62&0UXfT&T$Pg>h8%i{BYuDiyL3x;;GD zdnZvpIjBE4_QHQxqA(^$((GgLglA!4k2YEL-oAn9;JbR}BD0YGS?Hk~7O8+y_V{P_ z;ftrU!B+6CgUExSx#vc`e+$RmPV9$gzXu%>#X%dIR#&uNx4qxfl(R*kK(0t4u*(pVWi9!4rJMs@X)cLyv9W;A)PL5chS!4bfq?D0~aKiFbuL9xDSs_>;k1A9}u0UlZDtULo zX%~7d=#mJ+TQE6^vO}fdu(uH`bxJ5;i$^xx@X%J2->u1o+}LwmL zd*#R^ZNi`_1$4=6H{pXy)-yDW*GZ;_RP@g};gM^re`g%~Qo$J`FYE#Xn#p zueM=lRZPcgv6)mDyWlb7u^nLu-NGi_TEd2~C`;y#Yy_1Vg*Z?9NB_$94c)y_tI`Jo zS~M7(Z_f47voH#%gj&-*uvl@tZrAvYu#xHH3ovL~oYPm5(SmzWLOm36(&U#O(#g#9 ztrevra#u>U4iyW33>e8z(3j+X)|l;zLo~lq(*XoKjWTtz zCFj~LFF_xTGOtsDe)VU+{|qImNa(T(O+Sg{Q^a9Y2d~ije zPB1xls`~ieLD^DZiz}wy6EbeH5>7tAs4P{It(_|-`lL+@VasR1UO?O3o?y!tjPco- zEb*p*($dU5yaf7QOul0vm8mM~Wppkm-<=R+mY3q^uzvb3X)N}-i;h_m67?58EfmyR znf)hQc+%MPKX@Ef3XnVxAG@cX;jt0Jq&ZRUe)`HB3V<$S-gvbCb0T!?O9z3Nfxsb_ zzbyaAoetqK7hx0Qib4tBu}xX6OHS<(bL10M-TjSlv_A_|49u9Atfgon_D|zv9~Ziy2Q#A%HI?#P_NZ8(VVaDM&!D9B=Z$*b~=M zQf!v?3%X6DcFS5Nwyz>I0Q4hNVf?ap2W`2A=b`Ztd#PmwPaRd^_6n9 z)Fo=Jmbe_n+X+KAxio^R2-WyOSpUc}cu``|M32Bb(GN|dl97YJjE`56z^>!*l}zT& zQ#f6NO%E~^jR2U11G73{l?;S0vBeM_c%%{On5Qne18ppWeuv~NJT~VTQyj^NbSn8dH{3sx35pMn)VwLEFgY3n96Dgc(A}u{wGD}s<5KD_d#uN=x5&c1u6{jmc_ssue-;42qu@~HQ5au+z;Tzr?VyBbQZCL-Brw8sVgPTME6>j`nBHajLd{Ed||0{?drONlv#$5S61 z9S_60&N#5IqOd-pbqNC`W7{HP%vVI>d2uNs>=I%+{I8_=NE|7UDKjGw7OljsX2Tlgz8I-DJb|2w7onhQ zcm!@XU&!{Hs=)4-!(p$52}zteQmI&nyJpX%(yTbgCWD*ix9}`eh z);4v8HjuHh)@Sm#!cvm~TOL4#1lSat&Vr)LfFTF*zvmtAZ<&zzp}>Bjg>s0Q>}fG_ zlL#o0l@sKE$LrkIKu7Cc#F4>9X>Y|U`(={|6rP{Tl}+YBs9%ieKB<69fRl7N$Q15V zT*C^%j@i|&ZECvWT@e)QD@cfiD@SO1 z=*e?+>#CR|!M7sGHB^}EARos{N_K5h#U|cMx%ULl5}C8l9_qb{3{N6@`B?RyX5@}x z-Mqm>PSYy(E!e>q{?8>&GD1C{jiiVfP~S-e>!brQQ4?vmEh(Bv6S=F*UUa1F)6B-QfEgMChu^+*@$clYfqQ!E| z@_GW6E1Cue{_oGrfQqXYh`9pz;k~_(pVKnaom$ODmnGc7Pp^6mKl^EoM8{M(h}m(* zXmxgu0pjLIfMwegM(C%hSz~5}3h&)o58q;g6KHXRieZv~(R zFn08uZ|aQdGA^o47XBsMS!=ZZS6G6JaBn~Vb~hDo~`RW6adU9r-@tL(a)3Whx zx?KJ0e^O@`-hb-d9Kq@2aSbk)L!{4$1cltQg_y$@yYP#dS3<2@SDqm<2`rqqWi{Jx zX3!*rsF3Wxn(H5gn3fVuu(MjiY?==%s|&0@1+a(-_w)_GOCaFwAF70Dw$}|D82I-C zWZ9agS}DW;HTEcU3%Is&WELWL+>sO_ov}mxGb9+)U?njmNsvfFuHcxupe*wb-r`~9 zwos|(#7V6C-o>Jpui(OkG`*P5D(Hy zB`(34z)Szu%$~Kb$8$!&ah@;-y(;ttdSFJ6a#K_Mo+DK`y-a)n3})Bv3|55+cD`9? zf05*+U(pO=3z%qQ(TN=Er~jqT~3OR3hT7 zH9DqTrYq8a5d09|tFm|7s(QoxP?Y!jdkZ|~`Rf(m{h_h-`dxGSbRsT9yV}5&MTAN(8K>A#UFkfrNc_wvmNAEF z5O7m@93|`Vy@({r9H73(eyFgP>bRUBe>O+v`IF947=;lzbwgygEOAlw@by-mSzFOV zv;OaHNkSLvZwMpTuY7!OlJBc^F}~NtNZ*c886`BWwb~j7Fby)n5{w_=0O3G2^7YGN zB3!9gk@2x;45USjVZ;aCAw+S)#3r8uNcRCnH2@nm z^gO}<-p<`|XM^jhb-+=8TV2o8{U1b~RR#j~yc#@tIZUGPSKje9b`Ad)wSdX_PntyY z*nsgk^X)Gkzzy%dc{0zbtL-{JRsvP9Gx(JMhc&`VM`O=*@0lrK3+;uP3R z=dj4ii>_)&dr6UOSfWB#j662c8v6$q`O9cfclwEw6Lb!(2)0*uzv0>;OWDtLSj39TVtV$QiodOJUBX&qfo zhRFE1f^l%yW)dQ>LePjsG#i)?Rgs_~%#cV_;L2w@*Fv-ESrLZm;*yKp7L@kY5JqqWNIkclQ<~=#h4qs_B$26ZZ zFsei+O%j=$Q0Dx?b3Uup@g;+Pq%D_BytD%g#juf9AxCY@`1&tW{}Qe!;^{o;C&?mE zFq~;uYwPG_1}EU6`lky4L_|Qz4oGcjMTla)x(oxSmigb&MbU}gEU)vrYj2wtMk7v2 zBm*QU#HMNKWbplcBNMppUTGY1$~>D4n|5LP)yuzvmc5~0ZnX=DM($vr?uF}n; zyv5?N%F>N(6&=BPGZ%aDye*SDb_o0HMT$vG4Jr?`BiBJ4?mu%K%G_J42#Th<7yI|O zLK+Ms3hhPztm_9fzIht+F;GR3eFtscVeRU-UtlTFH8Fqs)1GEL+~TjA^rF+m&B6(F z4BC$}>i*)v^A%JG7Ae*gpX*0%&4Nv%g_1-^UHWAqD`Lzd6r$$?JNoYZl~x74|0QL5 zv}H4mHvr4YNZ2aspyy>MtAn}elyHei0sgt*?)Gy#dU9MUfRFL8j;}YLa@yUO!*IKx z_${GX-x)RzI4`TauV4U@AVaKCItdLyx8hwxd1{GgLM=#X!yn)TNeiW5M{#VlH3l=M z0FFq26JXJ}{<>G0Q&UqTL|+8~wScF} z@WZ4W)Y2b7kahk@h>hAOWvP575|AD~uI=G50gD{7rb`NV>491*Jz-!9b{i|29V5zh zr<7W>Rf;jzDDu55sm}uF`)vV+1w3Hff(9^&1A~#6N2xK1C6VSx-(K!QV7FMJw>JyV zJ3n7;_F_pY+b|ZVm`yBaba?#bMmQCWVheOW=-!!2wytpV8W5J`j5w4EnZvMzbnik3 z*&?q6a+pw%7Ds;}|E)DF8^%OBdcN|ZR}x{GA_09&6h#t2YV|v`QevT$mAqIo2t%22 zVBiO_bHtCXwv%#_CLAR-{M1TH*BfKh#5vY4b;L^bpPUsY=dA}_I5}r61An$diAm0f z=*y-QiM92+d{3>Anq$j5QSlaIpSXpe&F*xG;e%f5O9*Izwve^coiRX64iuciVyZ#% zU9WVX8N}T)*BSygENI|U;8)56G&_Mb;Ni%A^m7x;V5zywkuN{EbW#+ZZmBW3{VIJ+cu6n zjEREusy#;7F$Nc*ryz-%ZK%e08we3n_xx!4=7MmL^rhI-L4K)iYY`Er*@`LJx3)Lk z+5gqLMoFNAP?Q8-$sDf_?hcY{Ug)}0M*aSxwCYbu^K?}HX}M_)VLx_Vl+YnOxqtg6 zfWKM(hiy!{39lJ4+sQX@Hc{=W|98!Z>jI|LSadG{F`4qcV+ZmSz3;!bc5>B+G|+hM?Nt7`*mNK5AYj8 zlD>J^Q=1aAiYti$^7&Z{t`J!y9)%TMt@$HBcgb`67YoWn8`HDSM-Z6=ap8hc_feCh zj>;a~s8T!exri(y%oo6>F;&XFNQ3K`m<=EE3Tz8I- z#pyfjC~hOmHk^S3!?QE{I|9aFuocU;=AWKEVSSH#G;w){vo%wJk7ve;3OZ!C=&D5~ z!ys9=nWg+Fm;zmo?}>Tr41_i*C~%@BRq@WQfsm*Rw>9sAbmGt!c~VkH7TS_CfwDrI zY?dQmijh*k2liOBQT(?~Ui6tIHcO+$0ucw4q-TC;F`6!n9tVm396latIoYzWg&EtqCs+%*av%ga3z`(TpAq| z!&$O}VS1(O4y1`2vXZr{58RI6#q=0Spb9_+P{y_VV zXVTCk!)0#YsCshx_M~?nPt#f41@rl5-Xn518C)CxEI-=!9k^dg!-6&&M_r^LYr_1` ze+IAdgUomeCf%AChp|NCaAT!tK@MB30iTksAPVA@N$25bVyMQ@@4!z_5Wmo5U`IAo zCgNM&lHOKE{)Xpu6Qcdz0Y_8LcU^Rn8yKk1JHc0Jxszj}qd?9rk1SSmfrGb)En`bC z2gTyT2}3JX$<)FeCDHpR*gNL2mXl>@SbYtFQWQrk%fk z1Sq*rc^qGl`VpT1`!A-z<0Yim8G~gilGk9sg-X|!t?;(3 z*7Q$ZT^l4ZFq}EeMgzIT^<5B?Z4exan>oEGRVl!j7)WT9a1m1VvaV-EPOA zSb^8L>Mow)>uZ#>scP=cm1h~u_)j*pvPyXdA zBq^V6cjo}z5y~(#E-o&B%917U@{3|7K!?}y=a;sw3kxxv)?8HaBRu{N6uBM^wVQkm z^}fYPtPUs7TrogDYhz=RnQ9f7Y(cKz1|Sr( zpo{E{zh7nY3{4^Z(CEAM-hbW>!V=$$8B06a8%Y>I=Pu)==}zs@5_!ba&F6BAEmQrlWP zdNiN&k0BF-$3J$vfTk?vL>n;%ef<&qqh@FnmD1zvZdt3N5ui-MXc3H!RR(l=zaqpn z`x7V0{DeiLQPh+%r0=Zl0w5)X^>rN+t&G!G&nMOY&bAYf-;~dU49J0V9wbBNEq}QFZMUl^7bp$}ZzK^Vqh!3FjjGnczvAZ0l%yD?UGz44&qqQa3 ze}|%Rfln5d`?p#QQkLNjV)mDcv9XuOZXj}!pQ9e&TM}QJ_c%~m(gd!*yo>^TuMI_UZ z7yC$C+PzYSKchm@9h&_tyN~uQgfyIW`PgE|N$r8DVHQ-7RxpI8vS5J(g>0BG%km}Q z6k|76p<&{p!Sw}6bx)a|txOVmjwtXy9Ym#e5(-55czyeVUpg+FMpkP~{M|Xm68F~& z0eUtroGngw5P&#RF_DNOUigPlK!oBXb$*(sl{4Hx`FKqi?2w#~+V9piu_`<9q$l1% zrp;f&VtPXV0!?ESg+j;*eZ%tFN<35cDz$>@Aiw32}ofj zE*tk8`Z);te&|0hx#e+%VaN01-QtD{Q9q!=i28zo|6uG6-_`g25&O#K*$1E3W2-1; zzNUjojoaq<50t-Fhc~`It^*5TnJSarRwEKrU?O*xDUO% zjpRPZ?`y|-Dm_a+J+T+MoZ{%b8RZhhmxht`bOp;N=viv;RC3~;sZsFtnQ+4b16s9u zJdw5rk7LfN;rd#j!8cDgy)aiuVsg2;eAWjz9MN!HolOCc*A&VXv+Ww=3wI;Pc?K;K#9<>n$l#watF0=PYHjE`{^L=z5Ppm z-@_WFHz%;3=oGM-YC8h4EL!Q^F^M`+P}+;K#&^RKX@jKCD}BG4*Mn=?s#3%eFobUt zdAD>*@?#mQlrj^h<4utUXPs|Kj5bue{8m$kU35t@2;BVUV9{~J3R*o7|) zTo2fP_8AHha#pe85HHBy{C_O~PhbN%bJ`Hp6SsbvHspFR*>B|XANok&DFe!`IY@D( ze>9+&LMEw!19&T!@m&;~U1&ttFhM&h@IX&cBK-Lno=3JA&EO5H)msos-Pr z+4X2Wb3Z@xg)q5F`~@!!a>q+5U16)4bK^2&J5swn2wJTi~7T1{j^5M1MB06v++zF{so0 zZ^k_$0R$m<0}nQ3j-R$Xe!v7NIhfTqxn=SokUp=AHWEf*kH-^MEEjamR6V(mHk{*^ z-n{+JJQW}qPKuRQ?%tY&Wv-%pod#>aVc07}cM%#eWn%@xk#=)lQ!x#^e*Vizw4XBg^BkRV z{$@ZenikN;WAJ!4Q<^6J!__byJ;e(RNwTJoq)-TE>ZNvZjST(-$VKSEt?nLBk#L_s zqr2J(BfPqc&afGxr@%Cek4DNv1&Nlj$3+t?tR0dGpTHZE2RIQL)A6vb=nKs#FD&CM z{K8?g<3P5;WTV$gjW5NbXVW%0%p7q2IM`iCF)U_hMK9?P|) zOkG6QCM&#^{K;(Lu9o*HM2PrH4^9Qsn=Sao?7gHnw}@ge-!_U3gSE2sEOzDv4L6ed zY>^>Rs^|8WO#%_m%+M(&Xbk}@yeaYNoQ9V8$M60dlR}NxFmhnxgs_mev>ONVsSR!2NuBTlJNmmOxIghDJ8 zz}pNZO4@>uXZc{C&!IrfCB%shNmrW2AuGQu6G<-#jC&7%YQp}sQa$G=P5KzcAZVNE^}6E zRCuHCYK*{|_ga7Jjp7l(j2!8=yZaKveXbh8%b&IBw3wv@cdO=TsFx#{fhM14A`FVW zlqM+Hc#8f9c+y)~-;p<2Mp4D9w6YmrKLmOyA?60v{*zhtdrutE zTib_-(f8fY)hBPV@TNm8N)MISR@wK|7Z=rg3t@_$31>Wkl}ivIbMPb4mZ5^~jZupl zyMG+0jz#y1s%!`sC)V$ZM5Gu^O*ssgKC{9V5LB+PMeqzB&stHJH4yxlZzhuM zYb&@T8!J!QmyTV-s^gkGgd+J(l+9v>hy}T+I&5pO-e%S4W+S~WTsNTz8vqsfygy+B zZGa5<5XW*Q3JfBOj`^C>gZu8<%JuFjT(`f&*2B$P3h$#YdflNubITC@{(vom=Ry2m zGgf$66QN&Uky zSMDk*x@|roZYASm$25&zqz{*DSd}+jpMpB8b>)6(cM60U*jZ8qJBU>!VO8Sy(n59G z#ZC*nB>`l4Ag;{+FEG5kcpTNSzuIt~MyC44w4m}}SJO!PkJ;}3GHDOM^xm`X8eNa? zc(ko6dXNi)7!%L*d;B~!Lt|VOOopW<@M>@ioxK4-MtCzT zL3n+~X;9!Qjs-I{&ZRJ|64&f&Vh2utx*#cvabZcPw4MM7Y!v$d|=^I%aC&6fgJDpaSKvs=ENI%~* zFGj@~3i;-bE^NRLX>Pr2zMQVM$8!2T8~Z&?>G;%pL>hcde}sMT`KC9hoA2}h5V?E9 zz_=E35U$)Y776ieC)YIbk|=I8JQ@r9>`#h%*uVcJnoYPKXdX^EoV`UZWXIF-wZrXy zrC%kX7&4k&`W`a)rz_d@x~gGHbM-ruiA_2~amL)aEekOzg=+K&ERJwbMJhQ_;V=ch zGcGL)8xB34I99N$NmUJTI9+vdMK_Nvw)i^iE?;m_FAP5mKB^qMWw>R2Ny+!lAT5QJ zjZ>6w?EA%LM^%k2_rKtLe4m{M`Uucalp;a-IMQ6C43NQzi4*7R5=-la$!)bCR-dt5b+hvmN@=K?DiVouS5r)l&HAR<+K1Z=Br^e?t6y8taS?{K7p% z7{cXny9jB=CDzkK_`>j{k9L@<2(~kNx*HdYxG|m74M=&2Jn%Y0l(y9Wp>WiC8*BaB<#%ykD3SoD}XNUg* ztb}KK)(V3s$aAraudN&51#j4<(;I7uO&5ZYIJ5TH+w#+uzuU`q$1hMJ*PmlsRi0i~ zoyI$AeLXxB{*xI4WoFOdyG~bX{BG*#c`ElX&WTtacLQIP$8<<|kV5Z(HfdzPmGGRh zt5R9qSl=$&e7u-zzSvV+GwYuA0EC|!CfGWiqjn=?&O#J|WvzLmcoCLvrspLp={fs5&=9# zx%=Zz?8%`GinUpd8%K9_5L%#Q2;El8=yix`n+(2{)LvBTxk%CR@YH2k!#7nRkruAq z-8c&T+=vTUH|FRnGx@DDpRR7trtD4qo4K`=h`p}g-WTm@hkqG2vcSRb$iw6;hV4Mr znnt(XILH*7l-h&*;DRXJmuN1YK;J$1Q>@v$d1JhNT+i{kfhgLir)htA=lq}3U|2Lc z^Be0iCMe>x_0F*Fr;Kj!+8r*y@BRs7Jl9}Qqg%{#7N}`dy<35Gj4wNPd6JRrHWF~r zAI$yp7wqBt3Ei!8taGim#S`>1UB%$Mwg!6xFL^w zmX1H`C41tHKmCNd8RLRP2On`NU-x@jTK3-sxaphvoUXyVpwE_U$6)^Fe3|eu=)Co_ z%h8gOR+l3Z%Y+t(F#-7B-68^2(PbUKf+s|o;QD5?DtHyv!Z1r2kC14sWl6NKF>- zJC9XLjvC=&dwfDnj8R7G#HOw`8ySi{2H!g(=XKBg6-X8eLSn|8@*gtKc?$sRESFtu zLK?-Wp8#7k60(W2P0>nTVGZfFlapJHrCO2i1t6VjL&$F_#f91=b2!d-TKXGrBoc`D zd)x1IF|BB%6qyy(X5@zSWQo`U)gHo!&&m18n#41GabJ+I8swxTM`dG$mco;A8QhRd zxvjiHzqW@rF;m;p#lSaNAQAV`6n=H?YxtYSE2hidXB3?HjWzG6EK0kdMJXfS(I`cm zHX!=PQSMX#AayBaZ*hEwmBFl@*VFz6`;9&Vbn>-t2ueCsQwXlcP>6}SccBlW^B!k) zpXZimid6#yuNHecm+AC4mJ+}Zeztc&|M+8o9OT|9I4PwxW%TtANq-}+ZIy1T2--Jb z{S7SBf|r1~_4wMF_D($SJsbAF-Rug%uBTHJ^EpBPTquH(BC8g=_RR^7eJ00-^D=lX z+9_yJ2$}&p&MCAO2uAPH0(HgFHGr!?P)s!4l>BgGA`5~_}Yz*BD z?f(2v7esFi59squw8YC7{{jgVK+QU9!vX4dScf54e0noeIvQDI3J8i*M)`)U+@@&t z4rHlGCDZ`IA0SooUqm!O_C<%j2d&sX2q@Q}y~DosY330lhm$N^TZFvket)Q8N*KA* zCKIgvvg5R6k?AI3lch@#i}5UABx#Q`q^Y)pZutI6AAG*K>HC;gumDo<^Xm(XtaR}# z12IbFRvw%Bo0JK0`f6aiHg9A!ISE^jd)9b`7`oJ#;wjlV8@|HBkP2y5v#fg#m&%)> zT$~+$zs6S^OsllH5hmjoW|xG~sAkvx<{p*+URDezIjygDjD#|rUC~YBk3#csQbhTk zaP*|*cfTxnFvA*VIqu416~tx3YK=DkMbN30+wG9#q2p!qDVD;D;Ma^@^m?D7rZJ2Q}Eo1dEqp(d) z<80`k+MdAI?RADj==+Gg?czTWoEt%aEAAy$F5E)leGm5#ecE23Ztjy*J{;z>QRFUAi z3sM30>LMwPS>`Rqozzh$PAn^lm;Gh@0q7{mi!(pIqSv>(v(Bq-Y-twMyFji7w6;R) z`-3H3kL^D~0ra=A0N)Ka?J_3wS?be1{GCODHU(29mJ*_+EC+Yp1<_{9aAjX7I&c^hM!Fwq9ZoS5$R6%Scy%0mpgoFHB zfXn{KJF}1cexMGf9l3F^knw0Rd3*|*6ct(`OP>jHKr|Ci-w2LgyrE6Xau-Z|3&m)3 zy)-Fg6CtNv?`P>;lEH;8%Twl>Gs~FM?eXj~Xs?FH@nr+Y-67997yR{v5%uU&-f#3- z6d=e7RSQ}s5u(2Ep$Ufcn~Vkx_1Wf>qY(y_0JL`ptZVZHQS3cuNN(!ARp8zr57_eNinEs6l_1g+)K>i^lihZeB`l8ZZp8- zJnRgVzSto@;D}L_0DuBOZ8vMd29U|Wm6o6Nt$xi}kg-zUE6hfm=CdM_q>dE+ zV;u4#zX2%l1{tcW;o$b!0WKGT>Vx1jBVP3@Bhf4BUSDTT>wi=?Tc^h%zhKv)3d2@=u~YCDxA))rvndTWU*zpotrE15RwTCt_uTzv z^#hu1buLCEOIvpB>zF?_D9`9NZhts$HPobz*Sfl22+V4(-FT>iX%SnmRlb&b`ubW# z-6*5z?-+c|{Md^|HpmizjYG-^ZuCerZ5JzV64tS)iOQvh&yzc%z)n-U4JNPup`6-x zJVAT7jG?BQjz zEV$U{KDBor#uCUBC7GC1zFc*4?%y%Kv4L0Jb)S9{+Q{J2LfIcxn>$ZZXoeQ@`X`L> z8u0^6_%A&Mh}!~64xVd91B`K>Je$hi5(BD8rjDr#vS5wwekPNvC6fP@PmjB?KvLpn zyZg=Uyn>21mZ!_h7=$S49~;QokDT&EzQJhbbRc#b7>hi%cfX)_zk(UL9j~!%QiM~u zNjh=TMQ*FtIdpI{xxGVU-(QJ;RqKkIYh_0+-PvQZtbRje8Ulz8jiurRtA(?ryjm>q zx&sg=A{^WLI;7`!8#g$jDVD!ZIOaXE+-B{`f7oxcB-$9VD$()Zm}9a0JXL+-ifB0g zm46y%FSz}y?qae07vNhk_PZK4aC#gu{NK<0Q|`G_iY3jt1#n?wu@_-{Ns;0B=BojW zuoba*f)udCCM6L?q5%RI`+=13r=3W_zlSQr+#ZKiQYDemDt->HTKjHirmge4C%BxN zTc=KYWxfk$`0dFpxORa7@BsrChT=xrK^gWME zvw2)nRi*_byp4jGP)#zvT&0t5Btg|j9I|{NC@RU}jAPp#+$3RQY_dc?!(LGVo^3=^hbjF@y|9Ou z&kZRYEfxwQ>O;{y0&RA5w}2lCp03*|NjN2P&hxMsz~fy!l+~4$j!)O7`v-b1Ed>&> zK!mrJzIO5aSrj}z*T3=C|8Acvs$3il&vCbofJ%DMs(!Twp5S4xPW2)HzBpZLgv;d; zkV*(7l=&M>CI@T3WrfY>Mgple-wmIALln(Lu+V0!>DhEpQaXaypL5`-qXMI5v?v(2 zlhY#jP& zXLG&=!U?*o=j5oeQknLRu9v9}+|_Q@t+To$tcZX4?m%6-h|5MvnP#!T%u}$rmfKhx zz@c-)9TTXr5p_kMs|fSV%w39wyO?hmcMfrTb>F)!B6~#N#rZ^I`cab&2xvh!E z9rbd~=q-3!>Kk;hISHlbDP%}X(5h(#C1xmDO2#v8agt<5V1=TTRabuTlM*uM2!<_G z)ygQX#M>I20bm3u{hj4iyGIScF@ov>H>ZB3ZNenjYp5jkw2ji!k#u zvTO!6nZtU86R&;<#z31yh39vW14iZ$4qFpQ@c8Q%9bcbnRSv5dbIouTqfxh1px!+Z!JD1~MF~1If1^8O7-wjV-T8+o~ z&;CY0zfwo%O3-Ym82kmUKTf+-oIXNmFSJA%`5WW(?$yh;U#8jI!`rn!OQ0EdpSX1Sbs?$zd%v4 zNWTwNrx>b_vZ+E{#DzxBO%(kzgzW_i3QrH5ZTmfWna9o!*MZ349M~{+k6mfUfcZ2P z`8@_n9An(ZRYC0FBtz5TnAn$)swkYw>YuuBD)0N)qi!=ObOfn zUo~`o@`_B~YJOj2c%GRH`JpOx?|z{=n?q9sG!fZO5bEupJvs&}KcDzI3rLinJ)?J? zM%WiR=6VWZDF6Bs*LEmO!?1D7Hn#nX{nYWsX6cO2;%N4hboHpJ_VFcEfz(ZCQrtSz)wH~5$TO9 zpC+jmiO7)@=IX-zHJhO$oh{a@F(xPPKm1|ygT|iLQuPmdC;Gt?^7my9_FQ6gc4Fin zg9?h-bb@3ENjqIsuwUu$rPN`yP#HycQ+-0|dUeogGS1<4;p6dV=>5#F5o4Q>7ff*> z5)4|CO)_5sg=BjI{epu$8p5tC7^a~$u{0NEW^~gs$`I)%v{GsZpFUJ>_1L#d3BQ zl6kaZ^fC1J9xD*DNIuMbe#mpJQ9tDPaw#f;Ft#7`S^m^nT7;KsM%Aw$h=tNG@U6em7mxh(`HSp&Mngw`7<-A8O>Un0RwQyS{xBN-T|1?q@*tu%@ zc#Ej}mtJC8n99r)f(7yaK^EKaXczC$B@MT5|AQC60cAg89sztPxkS)3-dYi5NMrrU;myk5|EB^d4Mueu&|G!>U?UN0T@j+g<@ zEOd!nNB7FP?1Xjst|_D-Cz|v{CLRF=4*G!Of*%t!_08HOcoBF{u)(JPe|Q2uk)8rJw>N7$s`O71QttB&18q5=lKt23 zU=%Q^9n~o*#f(hx^NsJ8K42>u)oJktidc#BHvCpP6x)A^yLNpB&D=j$Jx<{f^ciT3 zYx5&j;!C1Y^6_@1XzHh(c-KkRZh$@_FepS8Z3w`XDpbpca^MO!`2Y8K1DtVU2pYBO zp4e5A0`Cu@iJ^N#JvxAQl#$QXvH|Bl_rk3PHZOw=#ylQ_plt&t*AC(e!uE#~O(5c` z>!qS`Rj|tkgWcz&cc8MyIgN2Q;0qc!qZO*QLVT)T!6p`>F?W4bS ztQP_CQbCtxjbu@fVCZX7B1##(Ds1uLq1$y5;3$_6+*!&C7@NbDq?U|NrITLIWlK() zNB^fG94wJ{{CIOuR!#m=wMTu7R#MK;%Nm2YcM!zDNaEozY3mYhl>|2?N0cIV#Ft=X zM!VeL>7Ube%i;Sz!MoP%k@Wfa`O($vu@7tC^i}ncxK8XEIkA;rZ-R}*G3NiW04zDW z%Z2h-?AJ%RB7884*p}Si(ILP}m*`I{85i3TUO7R5OR2;{vjEjHcvdb*eWUcZ54MA?t|IP%7YHli;UN=k6(Qc!muVWTk%66Yzqd=Lluq5sv@;iab< zEoc@uP(v%i8A-;E&0LVLMe=ILXhCNo?}jeJhxMcBzj*~hhlw5Tvye0;_J&-J`MNXK z@~P!yr2KI-_`D5oKgBIr_bzlAk-iL5b>{%4U8wCHeoZWNNgX0qqct6WV6J!KElHigcHQ~lVe-pU1=kl;YayIK zeaGS-S+X#6uFDr!ha z5mB>nBM-36pnqC>XMMUo>eM#`qJuXx!O|VHZaZ$Q2ZuTsM(<#on3ycJx!UUAy;$cC z2}+wc8+bqM!=`PxwmU;uBT>zei9vHYJs|;Z5XX;2-!}=9g9GtRrmn=QzYyb|zEA&s zUSG6jzP?yeP*A32WQkD+#lw=Xr*EQeTArTv*)ulnCbSq36N8j6<+w02t+Q!4eEmko zZ@DY3mT?>=WfN63Fc3AVLC@6jqpo(W#fl6-~qY z5=iP4L|!3TGJvC$kmnSVZh`#APX#7WL9|sk^&Z*`DLqo=ZfYjCNLJ`r*2LWYogM7Vt;|$BLODM19LiR+C04b=WeVMYd6YI6?|Hf)c7fA zB;inGlx4G-)KxLZOE8{{(egfb1 zwWJ=Ur~}ae<+tPeiZh_r+4>vsFViJg(whWOx14x_6n(*XlP~`FAh-J(d~Vbx!QFMs zL@;U~t@F3Lbs)&tr4+Ex=n{K^sC5zxi3(LCfHNK78ATS0lRk_uBC{7^yl6=*>Hw-5 z8O9o7CCB^Ynb9~XBrkH4Ore9I!RzMyDM^*y`8}ODu4&U>mM2BA2owQd! zQHrW&cBn)Wt2r)*9WFud*F!$XJ1X|v#q(G)P~H@RiclsQ@ch>|fak>4_f^a1al>=1 z*(Xb;t$k<#t5&e^p?)Um@gqREZH*S#LegXARk;C zrrXQ0p^U7D$YRkN(?V|41zb~Ep^<}0Feb2z-7o4LjxDp&ZD{srrZ_f{X}_MjM#O55 zUAkhNb!-Q6n%n};1Ug2>P36A)HgQ5mrQ+YzV=Q7tIS2xB8yFht!1Rgd!^O7k=Zme| zDW$Fb)m7Y1buEKv_P2ueSl=7KUHAbYwx7?=us!U@fOE$^6F8lDb`{7nial7jN}^=z9_L2|HANK(~auYWrEuW_}@JSNrDwu&G@0c{?j0|%4?LICQZnKi%w>VG2_ zwNbcJ*Sw1PpW+wru!*Q4cYaD{1k(N%fS&2wQQRngHsxW_s{mRtx` zxI;XrT^xg>?M7G_Of4O4hpVIf2HogOyUSNak8MQ8)!(}k?>YjrZtE_BN34v#nLO=- zb~!VHm)w2=tag?+eg&#O|LZ@?UdQ8i|MmSVVy(|D1t*5>%yE6363TpL#CuPr4j%6Z zTUGlDY=W{fumIWvu1XF~+*r@xAgV+qK*<55<1J;Y7R4+}?1oX~w_3lbiO}RT6)tBA zL4qw<0M}o0oB-xP{ZJ>Xuh9NV@kG$(a~S|vRY@ML%H%!RoG{7{4M2gTI)+6J8iDR)SRw+-i(SXcxWl7NO z<&ORcDVE9G-7fV$D$KpCrD031REH}kLUJrFyrhDbFnLs^lP)*Vs4q>TWjiX<7n{vXdtAbH* zfk65dTH9Bb{4US#GW(`{Mn%}|8=Zi(%`bZJ(1i zR(=FA&0C5b8MxlSjwi6$YIPzo?(+T9~<6172>|B#d1*EWq|XhNc)PUb0-=wQhkNgbd1zJ#mu6uv$WPvYmIz5rZc| z_MFHHpl*?FH~czL@v41t%e9VRc33XQKPbWVi!2%l9J5q)J@CW`emDbCfTxYe&e4Yl zip!h`AoLaxM|LJqUVrq7B$5xIp0FhuL94yFIBp_DqVCk@<97{V)^h3X2#Y-Yn<9UGHXE>pRNb8lRwPj2E!<95L6ilt;v zcAd=Lzx#T*i+;Q2J(%UzPg2I4!c5JzB1{1*!bHzR9}z`H6Q^z%Cr%o865srt%x7_) z0XnIk={V85n|3%gp>|8lnmh&9__Z_ZYGI%JKI zs`R0DL|qo;4dKnxffxjE&(EQuN*OhFcMkXhSflYVH*f3MUDe{b!wvGOPG~xd+W@Sk zYig$tw{3k_=LPF^SfGHH@%6HKkhjH?mz6G5=MG`iwqxZnP(G5IjEz(OK4_r{>bn`h zDe-xR|9p!1BqY>r_GHGIeL^HATMQebG!oE5Jh-^ zzG(Dj9zFfsT4{Zk<71+kQQac;MP-P2DVT;xxsJ!{#mS6=to z8J+98J7u&IpsM1Pl-Twl`1d0mD{K8Cr+U?8tjj*iyH|Hy!Qk)cNFtQpwAo7qy-kt@ z=E_|rUe3{-GqV0}4N1gfRDYm6GEE{ zxxd0ySLcYQ%Qx2dME3kk9;>m%;T{E(QG4sAUpg>LE{CelU`W9ep;MC)#hgBR;fbdx zmZDiv21Jt{M8az?!Ws?o&un-Czfn>+I#8Pg6WD^Kl1in*po0CX2j@jPlqQp1lNDSa zpUM%d9yRtncIbeI0FJSaSL380>@V`0n7z>KMdf|UE?HeW4l=J$QPSHpW3&Ql6{`_U zzdH`mkkn8nQWg7~S7J^{(&)4WhuP0-zkDQ>06ccVTq?ZwIfX@-Q~e0*tQitgR|IVC ztU;w)Z}9+d$ZaHbkP#d2IYkAV0o-`>_|PU^EM{=+p|Z1MVxsgU`8A9RunI%4CNiyF_e2=S z^#pO9I7K|0h#M^X-r-L_3L-mvY3?lb<#RQ}_q;wvJpFJB0QH{ms)-@dYwrV0o3K=( zm7&?v%GzGXBikh3E&RMiQfaBVLkr$-F!HpxE}Ddp6Xdc1CIR+w&aP)!o~+o<8{aof zpO1)7@ix?*7R1U^a1Em>b`!m-?T!|7+vaJsWmasjfZw{Lj&Poeg(S z2xG}gz5MPnuqeKRIC&O;U80uglbFuV72UgZM78;R(eyl;^A^~4*%G2u3auHCIFzk& zhmgJf{%ztGNaxud?}%xRQ>a?1swE>AYuQvVuQ)j}-Sf4aBi#x%Hy&-2Nj!anUblg- zhP1TeY_2>+B07@Tx+u-bhR~?W7O<^`E=QNltA*a5t8T3wupG90+x)!$++p;+;mqWF zhA7#5;Xf^-EvM7#zip>8z~&V_Le#{IE3!V?kBH7k9I>ZTaiE)+v^$yt*A>_@1#*>7 zi>4pEK!09SHAf^jPzWY$K7Eb`k5h;$M`eH7COel$*u7AsGt(3hti?(B%f-*Es2du4 zqw7)gL_t|fOKY!h?DX`1b3YyP90UBHoj`{LG*Q z9#yT;X$AH^#;-A1qv2HPSGanhYDNb|ty~^DRS$|sGbWCW|KotIC_v1uiaK5lisc}w zPZpKj@mY*r_hCPhO4E%Lh54%23Nb?&OHiqVr6j_GMb~O*zJyVn4`bp5copqwdrFMOh_2ya#TC`Iu#9;^wIMlWGp+_YU zd1_PMu1#%W$ETThkO2))6|AHMNWWa#dcP8S`JJ|oO-= ?cN^_mqvA2*d)ePD=o ze*e3W%Yq<$k>jY*&owU3Yb+nL8z>9bEE?=|FpJQlceh@B#Lrq8vQHK1Fn+7j>R=xR zGQk65p`wa&DTW)eXFg7_H8Bm0r~&xrhxC+}m|%KJERS`Y(_Y$j=Nq?=$!}uW`t;#jESWc}ZEqO9Ie@CWb;QaTW*RgP-{o3! zUew`xxgw2>lD(?SdC$bubqlMzwEYjbrS$K{YqckmA1@tv)_GIyIcM)vl|EX&H;AAslD_qu35Bse%c;Bq;Fwmf94u5F0({;N1A zF7Z6z+BsgcY7;=Ue+kqkMtHM0!%nOVhwNX^n{InAy#k((?RC8_u(RE-Ic4xWlLqAl zhQlNX3l!*BSb0YcWBA1tppW{9%Pd!AWX5iXNGaXV`V8sD7y+@CWQ0<+^5)J=2&UV| z@}b+VYn9{nOh``Q)o}_qY(xxsO7Wh^m8P}S016Z&$4(&qYGHO?^MF%<3PR_?5!-n} z3nU@Mjk^tYMt(6LtfqntBqRbpic3DmX@&Iy53wwqoWPbsO<(@5{g4n9xm=#8KusV0 zsNBqw&QPZg>*ywJg)k+I`I1T5`W`H`rIF$v#8^qOe%CY?G+~QoD`I)^u?6knogwIi zAQDm=L`In*%H&`+t0O+O4CiD``UP1GeC^n31$t&R0(}}PzdSvEo*K}MX zf9-V|n;O-ldHQwT(r%6Y~R^!psMWZ8l0M=-m^Hj4H>6)^wgVA9I+x0*6Q( zqa>?IB48$OFr}>2%t=^@aFO^2%jmRhD4r?*@)*@DrujYj^_`3FJwWRaX?Z*t?2EeO z2!!dg{Kt^vF#mYjq(`=Rh}3bTONnxo(5WGqa}}HU2_`@g?8tJ79&<5D^C*!p4q+TT zaWu-lJSL=9wdj5u#i^mq*Z1!%ux9_&eNoIQNvGSOUifYfCXynY#6dV(q;#w|hHp&H z`|IYT`+39SlKLi5I7#72+^_r`0t1DIm~CP@sL6P-urLAYb&Ez|p6cij>xE3RPnT_F z%sFt!in^^=ZG$Xp*4P^xR`9GoPPD^=9_ z%#-$qSU6tQ9r77XD`sfAC+*#w{sKN|2-`b<{jYO%*b_Sc^8f9(?SGuw+pEGLEDZud*O!$B5xR%_2K6 zA>G%*FyFp?EhlbZ2BjknP}5__C$sJMlPE6b;+HHnKxgz(p)gVBqoS1ILpR#5lT_}C zFbHk^3>0Z2sMRiDVisFk``d?que1Go@8wB2Ysa!UXMMzk(Z06wnY>{kpvbFE?e+xTUE7n8Pdo4Zk15J%~!P%TF z`--&kEUCHY%m^s{Za*dD6I9v?TZXvr;4Vo|8}TALn@A=Xx?>h=Fo<|jQx=&M*>&5w zhKXj9l(b;)7P7JF z6mUwD6zxrI_W~<>8uD+YKXwNlb$ji2sHg=%m77VkVycu=y~81>kvTFt>ZSq^)f2uw z=Qs{lG}(Q;k#le?3@_3|j?1ueb0hS`7Si)bTZ)H1zg=V|09Y zXZ16-@ySl0%-Li7ykT_zJZl5yY_Jy<+bk}ALi<83v1$O4Yomchuk4~C+V;1b(Whs> z;bU`~w2Z@}ib40+an4Xioi9Qlu?D5>I8;im>poN@iuRY8s^_aQ4UW^a>7AiGvCi9b zTl=#ovKNN4IG5oJnRLj)}QBzWEV|{Tr$nz8fmRkKvf-hs7Kb z?9qi49IbnNaf-p;ksIWMpnxuuUf7_n;1mM z7{Fs}T4>Ytm~hwN=R)i`a$}Sg;NjpG`33gnMt&)yS_%|7QFfv4Oe}XIN!(R>aD0k} z6VVS8J@7IT5ITX*s9!q0W)Bq@xmmEVmQ?;OA|)f<{^z18o{LP1R3t0bfQh8wTB_2h zSY>dS#+{U#Z4e$IpY!vUhLg}zNCO`v!wZ}V&6u8(ZBn#o)`!!+B|f$W%hj`6B)72AIzf7%wY zc;+7jKcBE-wG1XHOj9G*wCV-#)2}0fbT{!d9ltrstp8!VOH>YCJXq#d0@Y7zKV5-W z0rWCJiSthhou_~mTf=`DmR(Xwo)8WDoo~_5$H$-WZR;yg65VYYY6rs6 zLmRgm!oH;RNL18mnOKJ(uNV7OpD%(&6G_6Idc>Z$Ukv}6MO+-vH+CO9U{tl=z{(5W z!UIia5}PI=KSfxHA(`hqX{v|8EG!nrJNLDX_Jy)C{!`c4Q83?%Ix$>A7KhrH-G)K!(^0|10-z$gUx zxl4!&8CKr3fso0=Kn~KDWLUgkL25?MA@CpMw$}%9vYOHUeo)2z_@L#qphn#cyXiW7 z_#fVWbz`e|i?)%KSFi`Ek!guo9kzkB)S5X`h=6W6G%w1rhNwdSy);)R`NEVvpJ>Zi zRudk%&4NaoN6^3m#;A0Pxh*@A(l$|SX?LS?d{m-(Ba8)u@cj2A$0sVK(_fOzBS`9P=u!)f7tOapUJQVt)^$H@$*jH5fg(B`^zsw?)cH+`0N)e_>#HB&7 zX2dVgp+V?Ww8I)9d<_0KRB$rR2~9MEyEhye6ap zVRg(ID08?oRm5#buFi;EF04T@DgPSqq|ua{N7nz#0wk10qRb7LpIh}#Ad)d7Lt#ds zq!o~-el!!h#4W9FSK_n1mp&=ueB)%D3!YrQ9cd;Ob=AH<;53BSv;>kCqobqEmC}H$ zQ>hfF1AH%7{^{u%!UpPelV1G)g&XSa(JYs3(sRsp{<}(k(&bi~Xu}<@;+)13&uFD^ zBIuz*I5b#yug$^ZKU@f-T&_I$Jxph)eV)c?p07*(w+we#RJPT}8=q+pwu8Xf5m@H7 z)H?0=hvA=sGY=kQmr=OxpO&BIHD&ECzL(1#&B$@9RTZ7u8p(pl8Dg}O#8`y*yNz15 z1xOHm_JIy~4#M5T36$K=eV`lR?8oHI?X{LVU>gTGDm_h|ulNLBcMxT`r*C(rf&fC` zgHWK~PCe_^-jX1D8!*|y6$ohlrVkvsK-E^fLd6h)*wKg;{d{r%?l6!-Nh z=VK6fZ9&u39;*D+jWnYo4SEYub8+9<16hz3v^&4Rf4=&DOul`LbB0Ck<8FQm$Vba> zxrdWk&%$tOY_^Zs>UjrA5O_uI4%(X9*kp%Y!{8mq;iRUg?`Vc!>@tNp&}e*AW#$(}d9rZopRP`tzQ4Y^#7K$H{yMa!cuLF=W!Me`xU zhTA*4Lzi!WOZrU1G+;>5M=5AU^|{Pf@|&hsM2io`k0w9H8H`Gmtk!y=@<-XnFr zeK>A`0_xXSpe7@GZ2Cf9vps~+a*UxW^A2-+&y6r<#jRr*_ zL}DNDv@4LIwSS5Vm8ux#afrkgvn?!YY%Ec*{7f1RytK0_AJ7&E5t+Iuuc_-8H{mrh zu}ELKH7}-4QB`eTv#N=63VoDvy?bJ#TQQoZuT5H*rlz`#4C?DW*C>6B{Fuuw@~-y>POQZn;$$}A)i4smd>m`ka0 zn}e6mR!863Gz40jIK|Y(A-&rkoAJl8RfB?Aae$weMS)7WzNKMQ(Y-9kDt=+3jEY1m z9=2(_wiqQcP1q75X?R%i?>rN7Rqnofs1z;wapzLPHdLP2v&l=N=Oo&63QddbP<}GncgLc?@}0HmeuQY zjVKW-=hJG|=j5xhLJ-CRSnjeH)B_q!h_Y6lRT7kbS|`gZ za;1%33~GfS#_9gDd3Ayz<0Wc6Q*cL=Toc4wY$giLUWHblF1WSQ`#>>roizpuvWE2f zSoSY>=HdM$-}vu{{+++T1=~7@E6Lj|Elbg!z49){3JQ&YBa%a@4Bj9bEM&Hzb2#8+ zZks2ACw+m%b1_4uqKhXcQC`|EX=d=q&?W}>4Rs9-Kn5q&roNKdBsBEHjomzoI67Yk z9XE*h*{idQa1=VaT)_E{JwE1O5*BOUniHv@&Z54FNBY0*?`@A#@E|XQK*arHihjJ( z6YNOkKX7VvrN1u+6t+1&8C{NVzz{*4U==QopIs=@WB7kzL2qqGZ5_X$dcmTOJ1Hb~(n&_dYfY z%=6tm?aDJTGxvVJbiLWO`(AvHuMdNVh&vZ5XC2s>%3@0Y-bao(MDeXe*V?velRSccONy%HnKm+0KHeHVl3n>ixI{p0L)+bwBi4s&+t8 zEXb9~Pa<)3D3%ZvMb_!)IU>Un(bDbtqHWm1v|PjPh5gF&<{)cB9F4KEkhlH1G2M#;R$D|fZ{&h#)%Q-J$gVa?u;77v~vKP zxvrMdhcE0Aesce{f_0u{eKvtuuayfKR*glB?81fV(!{y^7q?-t%jI6EZ7})@#@0TV z(X~MO57)+&LZ{(bLp3ifG|t2M32~*{OQ~&87YARPPp` zb1B=h{f>%u*n46QC;gG!xNuy^oD_${5jlK#i)Dz7i+ec1dts#SbH>I0Wn}<3mSO6{;Dtm+if_KDW4XUGEqR_o46v)D)K<7~DOWVhr!^oXzb%-EhR>@PAR8&IX<6cGYpnltY?I4p2bvq0 zjJgL|u9I<$ku1EPsfL5L1?qIQULSN_J{M~3&o>d;YfD=v130_4j%z-r_86vzTn6&JhsMwVy&)|&dDpj>nM3MS%BGuAj-mh%J94Y`>)A3TXHGtW4Qvw!|6 z>j6|GF9E2mU(P$kqho?&Dh`Fx#a?_=h6^^~Rs#d51|{_2=>Jt0E@Z!_GT=R)BFlR{ zF})OBp)?Hadvtu7M=pjH)2628LL|V@)BGchIOx1&em-T!e$few)QDUhe>3H$s>4zzHi!+vREP(-nPxx% zZZ}44n#w^c@C34QHkaR=T5|}6VFO_#A{E1J1gfDvd^YkFT)j-wL?6Fh=MJIXLB3nZ zl!XDO``2$Q+5h=WkW=!JrPG~o^#9$;wQp5q{BLLB?&!Cr4LcDS>$rFX3Hk9S99{|@ zVo;_$@E9HWS26@@+(R~KtKHN!o)!Ga7WuF6N-m26uT~=E%!TVzNd`5N0y&d-9UhMN z1ehh3e@>Li9XuB|W2W#)TwZsv3di!Hjn!r(XoBKtA~wz>1UBHU)Uq3zu=TGTFVkKn z!4Pyz2-Dxc@GtROrwQK))_o5N)`54q{|{^gHgej^+V=Wk)%Lc|_XAtgQZAFr|FmVf zZF$AV72V|LRMP@UYoB?G=030w^gMbW92~fP08+Dd*I+r%7GG&;TPmQuMFaJpiQSBI zcJm`s?{mlw*Ffsuw?7RR2TbqHft5of*!ZT4zwh`NM_*SRm0|A>$%l=XY-^)=#>fB+}Z5L&m}6s8IB z{e1MLg!w-5%qOPC%)vVR*28C5%o(_Y{rkfJ>nwx`-EnxKQ{5elNUYY4y#e|GXhc*Jl(7~n$FJ>(K4hL0sx(&ueG#B5t+Uww=v|n&=fJJKSftHR&_Ds-`_V-PVj8$BaPfS6 zZa%HYMeXPadA7)xKR}eA)voF(e>ZCUx@g%X>{FL*#$k zDFm%Kx;O88NLqHf$SE2%gzkiCp%O7&mxM=97f1m-=HX-C!UC-*e?JW_*>-7kEPh{dJZF)&T-y$Ffv zvoDDY$#N!vTHuv-%>B8w0M{oNz?VI8 z4UWKMw0E+PtEo{erl7p`&T%Q>Cu?lS)NA-ij5}2iP)&}WtB*$%rY%yS-F-o9aEOze z$&bZZ`iQ-E0jNCuU$qhZFGw>R7mQkC_G>Z;;eZ2i%ex`YNh8!3k)_S8tftT6fcYU4*g2 zCnU#n@DVCfBBzI#n^w;=16x5h+x-5_{if}g0>?Cx_upKF$$v{{Sm3r zfAoC2Awmb`n~Njglj*|^ffcb8S14Nypfn5o;FOP`__K;wT3ugZ!XKqhIu32$%|k=l zQcg4z?2%b(oeLT0Cxe0m5*hx6W#o@fq1IXM?J=n-3Z3|at0n;V1%f4H!LLeThKMCj zEU|$qL+mKLGic5PxnOxu^l|8?{p!0;Za0lkp0N}Sic(tqBBU2C6UiVKpAW>PBv@74 zXz1`q>(48O5HRe7^^J#N*lBXdN6Q8k%XqG0)L-E@Hvs@ze%S@xyEa_7lz~H=yt0{&H;E?6yrp5gnTy0YHJB zUH_cKZ4)xf1!9rdyP(#;o|Asvo7(#91%X%ck4!D+P&)BGPrYIt;fUAbRZt11QviK! zfVk)@R-?YPhpKm2Gf0@fY++}9$~Q`jyG6Ez(LF?$BRb*FC7Ct3M9Cy$P>DtDD=lF~9$dxulZ+OJ?q zmFw2rAHCN+E_KYvm*mK7tbb|J>MysAjjW(#(_UqPXQ}o~$Yr?D0!2wJ+kG>PZBm}%|a^LxOGX>Ng63Re`M1{J_dT1&@gCO zDI*kvEF>*q8vIB@#ZI9l2;DscT<(1I6f?*bt#mwV2acF-unMMg>mB@W8dSOMUyAS& z6{yHY?qR$DOmygqY<|>zJIFa*<4dWjWcq0PtvX8mbHr$>pE$3I6eYLv4NPQR8QqhhR6DfV)>qk@C0y>4<;p zz26J9eG~Yg(vnQRAUUt9Vu3OCKWzo>!8gx*!bn^0x&xHdAu1*BX6sDwtkef82`BZ8 zgKLzo=YtyL7co_>d$pv2eVVgXYmq^py|;qvbT&prC*GZ#;9i{DbPw+r-H5Ntjb}Ci z3zYlJ0!BmC$z0LR9@i{@jmFs9I*RC!wTWpGfa4Z!Sl#?PF3tMBQEqshJLB*=-v|p; zXy>WW5z_(tMKl5bhh;Givb+zviV|EF*8~rE+VgbMY3^> z%dSs>l1+he{HBe8u{*NC7<@?hh+E}7uaH^W&+Km#Ih3%wR;-)%R*MHj!3VR0xe~9P zlYl1{7(pq}q-JGhAJ6$*j&XbHg9+SaV&)xR>)|6c+#Mt2?y1qT-Ot+W5?evE|1v#( zNo7odyJ5+D?3T+{u0XYKv=_qsQz;Ns&C$PvX01#IwdhEVc7p~drajq@C5_cjrdd!? zggKdHCL3?^%)-A&o^l&^QxHjs2|J&! z`odD>^@S99s3D=M5v|B<_&L$ITOj|#S1$b!6U&gKbNU4mX=ozt?p~ZAsKQvT%9t`E z3`2AHvU7?`^s_={YVacB>0qqT#Qa?@Hb3ib$VTSoK8*{ZTq@SIJr!IT18C*%vlcFX z5M~y#W(ca1UfT*v0+3$uV-8|8ka6+#c*1aI|HVO^(gY?-!j<|ra_Ml~{r?(yhL+sraH^o}UDm~|3akqhl6VwNm>on~-wd!J6(!k=5K zyblAC!@`l67L)Ssf<{)rIZN&%0`MydniD}&!;z*HCc5+N%KD~Ovye!4OjBCNqHn=z9_}o*OInvn>d&3{;@?bgLPzQAb z)d@r0*x)Z`){p9p{O7UmDRf$)MU>u|aZkyQ6YYbyCE2DYUue&}#9rm1FIK%Y?~8 zd!26*#-h1GM$c;aDP98d4XS|C)jx#5BNUaAV7qbE=6kEIYIr4Hy~3YCna31v@c<5t zQoKn2ERTdkVE$pQRJr|if)}eoxU?L$+ezQ<+kDLDuY%i$BO(*hg&&i2>>ZsX}Bb@Wc_vgSC*~ zzk289;OFBMf$~+7MN*aT`Kc)Wcu*0#3r7>T)01j613__TXaCb1d;;)$>>7rRjDKC9 zU}c%$GR7vt8CU88U4=Ht9?Iz4Wyw&(zj;B1OC}j*r)o$P3FaK<5P3rNe#yeYD3tbb zI4EU`zsD3OA2Q=wS*#3PD@HB^jad&nRn#NVek#S+2f*TT?b$nm`NLBU`>7ksDYEaFOi&X3-^0DO+Z#5MQBEEyRYqQF93TR>z3ir;Fz zhz<82zj0svPohE|H3!PyQwZrYMsSYn6Qunb)A2zV5%Bx(}EjtCoa_9hTDHiiMBCwIbcz|e0!Z5QdPZr%_rR=NHq%VA@ zMeRzj9i9Yn;HscqonnnI-Gi!wpkO%KYiD^#*t+gqFyxHNBLaWN@5l?zT+6d(s|Vqn z4Q~%zjdF5Xr47$Z{*P5gpNX%Ble?{mgEstfoeDoqT$01C?M+OIpSL<#>1@l15+D+a zbJ?R+$}1{wGSqapfmJz(jbn7&7;-_q@f2a>bBj;HmV1D+^PZkS@EJlYipRF|1*!@- zUqmP2we2H?*lP4W?oI7JcpcQ)d6A<>j~Fe>sKv`k1?{>)ANyY+&p@J7>gpWa9XFNw zzGleCMqdwoe@r+D91cU)9LL|_e#cO&WXSV`%AG8MJRF6A!wRs|wjgD<>3ZiFpd0`x z%i@Wl{o<=*Wi^W%hWvjton=g1-`9m(pcHp^8Qk3+28RO0Demqr#i3|%cPYi)q3Gc5 z?pmO@!+U@K($r zL8BU0{94}n#F#4<(KeCCZz^din+oa{uy*#E^ykGPs_-6(O7C%9bI z9bUNARuwMvmrg?tvUQv3*Co<0N+*v|#)|~gb;?yRsrT@+SH1=%!kplva|RF;15*`NJ1BS(2(biQGr+EZg)k63cJ^(uuH5ce z`Zs>`!rqnF2kSx;!Mmkhpf(zW(0CpX;Ch_`f%M#&cqU(dvq(w?thS(%`knn-U5~ZO z01~Z6fOu~{k?^m}uZkt^{C$Fmc)vZpbS-*Ip0nn! zu4-C5ua2np{=|2(W?V4$qZs<6FgEV^ z*k_g@aDmxOne;Pa&iQ!*!8!Z5)SQwOH!1&u%33|?6i#Uie2A` zT=x7vQ|y|L!07-%Z;K3K5gA3~X%Nz<600fX7`tFv*(4P>26P!lb7f?9M}it{eHOEx z+PqLHM0v)KW~^1kMiehKVq#dd&tAUAUsR;@G!qeIqN$q*j3iU2`zF~AzW!1nmln;A zr&Y2{kC(BbNW>tNU=-DrUbR4G z602X{1A6FR%hgLtO7Mt@jojT~ZT^G#`X$G1`1*clp+ormY=hxq%DKnO}mXzR1$o` zLlu4?tFKqf3OJTf%J$C5ed`lpQ~iw&p?UP*UG=1-`pPpyEo%(u6s$6Ko`nISyIgTl zzyM7O3h<~}7IJa;vlrSIjaeqOF@|fy>w=ispmj{EaRd-RN)k1er65!=8|<$wa{!}* z`||z|M3Vdd?lmdm!jpe*keb)M3HOa78|T$GeD1&L+``hO3>8TZexb$w=PW#+8oArN zIry*#s*I^rFed+@@}B_dcQV4hb7b+yaJv=`%&i_KSM=>Ev5R~bb8&D5?%Z-y3Z60Y@LR2j z4F-qaln(k@jxD1)-UB+i(Y9Y#rf^y|1Wk%aTGbVc%MgL~gE~2#Odv*zJ3*}#1p$cm z*boNKhGSkSTgYY7i-s*_3QwF|WhDQX-tYAcwm)g{Ux{%i5%|ARdx&bFOsA~F*W(USQ|r=ovQ9DC}}=GaSjH9SqHaxQMxYfuhBn= zi87~3z=;)3e;`X8WfKvZguWN~lL&~q*F834Qb+S=LqM@dvegzaO+y8P${qKVdF>`vQyIY|PHIb|Ya3YhcZdNkVy4a1y|@2{ zqj$GoD|byNgtL`0YcOXjcq|(;zA~8kza-{5ZU%eITKf{q4vmg$mN~dNt`l*%VESIS z8|Xa|eO7G?QRZ_8-h2<)@9mj?@FM_u?Rgl767zl8Z`TdE*g0uVvSKTCG; zT1?aDF*290Z87KUH0Th*xs(;&Q*sq)Oi4=X60lm6quUP~ zjITsw1s~93SoM)r>Noy@5sDn0GVO4bg#sy&)d?5FmAHvH7Gbqloe~V8_02iu+nKFN0H?NNzCdS&~WqwC6)HFjVo-ZPQ z#l^dhbD=eFUbjCKt-4JMt}YpXm?jVYC;&dJ${jvWi^ql_T~szsC9oidCD$pf3$dE- zvxtPe?v&H=pVe@67*>mRxf5Y>POSsE7RKFCUM$$Z91l&M42^2LJ7alG}UMRaR zC__Z)hGvjhiPAH7cSdm^gGC;of&Q0V;Wj%5N8i|A#`X38az*e_!ij{uqk+-E)yP1U zOkrek-+lMJUyk3MHUToOBil-kCA|0)>D{C2qZ;!!?>Lc%jSIllH2HIY(%pl*)&C5^ zLqik)0D;j-w4HdSkYaTv3K6m6;pJM;?T*nZ!SVPN^`RRGvQC`e$1WHPqnK57JQ?PY zncN4$T?T=HJn!=yA9tz)2Lcqh?_&|ZG*0Z*;A!>j<{5jlXY`?gXQZZqPt1S`1dYF8 zdx6!E{RzOG z@K=DXqi5lcd$HQ!@L)W%-$~W0{1q~Nv7k}1#mNZNG3gR2L3jryxlb@iW!h474XEvXe~vVsVpa(%oOi(ne9~AD|;v5TzO& zKEkpknYr$REMY0>)L{O)Er-V*oOVVXAHftdERvgCg<403bm#JxWudIaQX%=4W#_mW zL}?~TSU@G>1Ql<9ye}t&Qu-H;Tn&VnjqLCCIF{dmyfE`5wDH-BiFbzdaca1x5n z-}H|LJ#O!0^noJ3Ixd7q0tEWc7JnoCBdhkF>aEW${e{+As$wK*PH*Fl&Aa44$bB~2 z*!*CXV3v0g{99<-Vkk9Lgy$mNco!ggv2kW7PUHxU)|x;*I1+tcbd%p@U924p9mI=f zl_8IhMV_|rqr}|^eGVV4)aW@7n8(a3f1P_CYMsBNypwDbE()SnL@gbo5-|~6d86-` zVG^ainp!=5*~|48#|yprEcCXg{1);U`pCwb6F$|HSF=vmW)DqH7E`F|bs;l+&C>Db z zSY^7KsC^w=5Kg)-*6)S@SC>i+L>6UTisG@Ju6V#sP{&yBBEg>}^bD%*d?E;VDh(KU zL_E~i)9SB&G_|tsv7@`xL*4djvR}zd0?P<|cKdkKhBlCq`})`7W#8ZxTjX(Ad1-z9 zldZ6Rr5GH?ur&RGC~B|lIiK=wre#I|65&soG5tD-GVBU*9jzBt>ESt=C zHA6`GuIvu&9^eKvK%=d5{d4iYVZ%7FsFjwze-ZGahJzD(*?IAw=yzXOnalEjZw;>zE^ts0Av*&foZSNP}-} zlwq3n0+~Yg<5pK!ISG&jCrzxZ%5JUzIT4e@yfT4POiWW(1zLDF!&ke}>H?I@Q*fNO zElKRF1be4XhuiZ@@!d_N@^47L)-{sK^9=-L>Hm{ehUk1oN zu;h|-5GfT&ys+X@hXjy;mf~Yen6bM}qmF%9SGV-vRK?GSGuaQx@3?SuPDF@~^u;PV zMh&&O^Vy2|gr5C3UIT@%qK1*5H1){i!DP{NJRDNLM7|rb?macyba)(Nuw-@rk)ITX zoH}$&+{RS{A;C)EGt-HmRx$QBY5O>oT9d-rH6D|<#64gd-Cpp`u%D0J?M17 zbAQ0%v5)jEezr7KYjfjZZkfjOZHJ-Xsee`E{ZlIQH)9JAi1!YWYA6gCdIhQ&77;YK z#M-6JyQkIMcZuHvzq{S;^}uWNaVVe7RBTAk;ZHg^_;CU0FvN&WehN8vz#CB-KZw={ zO)5kOJ?NHG5hH1L){$6gYohgy(Oj$oV2c%u=Zd4h#x^D9-z^oHmpOwH1Xr2u3Xs|Vrh7}!JHxVoeg8JPM? zZGu=30(4s;`Kq?5%LYO)4$k20h*m1*mD#9hR`Fk?&wsrYQ_NSg(gb=txNpD`4ZBlG zC^28R`7spGanvY6m>m=0*|AQyb_Wzcak~~2*E(c#VrXhl+C+lYOsBH%j60>H(jwz7 z-JaK2@h6&x3_Ak+?ni)ZjFQQ};i8&?+BC5nnO#Y44KTe3pXhP6RJrTmLd7x;DTx{8 z+G9VtAco%XmfE3gA*dWIG=05H655JEN?OR`-fLXOY_m|^$a)h_35RUtsgZPjCfjn?L5$e5kFc zC0w;t>lU{^T!rS@Q5av16xWTJ%CxYDjo5i*d+cXp88k45}&DX|eD z%9mFR)diBh$#E>#q!%vQ$9$I@9`1jhLKEmK>zFg4}_GU>5aVcJ*8U!2rP>MTE0(SnTM$BVqz5 zBY%mt6N#3;qaEp)*O4)NAB@ir`9swsOZ9CX5^2M^PlT*pN@tCCygLG08*TM~3<`pg zB9e?QNcuSpCxg#l`z?6rx;jcv5(n0doxLnxHDMmK;TyFQiLcX+U)cUp5}{bt6=(Mc z43p{%ND{eSvdRXz{u?UfUX<68PNi3@ow<%n-sBChb6}U1Ks@DptO~46R?g($CD96G zL_yF#VI8DcDjQJ{QCZ0Z94O}IVdnM2KrMfC{|pFqcX(k-0>O7g0!7sXF)_z?T!KPH zo7#0(hYsyHail^Odc*glny81jhlM8(0Sb=4q`~2KxBF9Kf?h=M#RcKRF-Js@^bfY- zeMVMu2IHNl&%$T!?Kd}y2{6TT{hPZ`L;mQ_cIP>4ukL|sul}SJNKDcFp*6$?*M1F6 z`LhMQ;&ehrzpeWv){;b^e*d=pWKvCHgw&HaIk@gN;~wSTER6w)X8;hUHU9U^sT)3V z^)$*(MO=M=MwX@Hfuj3qKA@(ywMPJuHg=KsL(=>iEE7?L;b#GX zwGOXD|L)1FO5K;Ivt~Z06D*pEtb_Te&8@XE8g1RKzU+DRrsngjUc^JMof|8CuYHPU z;m4%rfNK&FpKA+V{cKH^uHOH+PMD?2wQa5AN~}8*XRDHZ4>r7IlrE8<@mjMnXePLAR^A0uii+1y!h7EkEtv&K66Qx63cQKbHKyfU#$?EF4;4GHm~su@1p$AUeLHfmwVBcN|j!=ly`04yDK~llOt}8z*qK|1wslYp+qdjN!9_$%s<*6Y4k!oM}*&*vrOg z7?Bkd$?HS9XVA*NL$KhM4Lx1HBbS#R^B=r4g}D7~R}K)v@!#GHXxrdqqX z6sVWG3dSe8KdU|#VUq-oWr&b}Nn4W~+56*w-QO8!XZ>hJ?~#%tp%8`ZBi|KwcJ)!Z zM6d$&AKvqopaW^h51tw${p2P(wi(6&F6OW0>nvMhkqjXHC1G{I8}cK_{~F3xW)o2Ld}PY26TsL zwmeR&l>DnF8PPWG0kHryr{mZAN1)Y^*8P6DS>M+7LkW{;v;LHi+pqMj;fE9>E1&p< zLz4O{LaBVK=JBp{M5GPsLE^JNUyD)+#-xz}S%sv*nb2oi`it;W4WW-T-!BCZL$DHb z#*JJ|GMhKN34;&918)5E+aCDG7n}|bQY|OPoR4RuJD%@8ueChEQ*#vc+d9}edo(Eu z5&{2F@L4vqQ4*Ouv1)eEDeDh$U>Qe%DZOpr3&t zj{cwGsO+xFMz9F@@*QJhh@Z*#E$-6LrF@qC69=pIG*Atv#1mx(ruticD+^U_w}fTr z_Ibc?R4I?MaTdv2LV1hD8F7Lz$baIZ@uAmF?LSdEvo=o=<8fvn#nVcQsqK(f&hqp1 z8J5YektT$&`4bcMEiqdYJBc4#61@HsYF;+FQ+)I15EB84H}6I za?Kh|Y6zK%UHv=7_%Sx`<;`-(OEZbJ1|=#T-X5je{VRUe=nH{u3Rw4M+Aj*glo_$3 z5K=$M?#;{=7Lw48fMX1!fIs8qiK_RCq{JMwf-S@FMC6(`fY?er<4yZJk?AJR6fW6w+;OcK^sn=7P z3$Sp6yPSeon;otL-WT6Tq&2Ir2g^6NZiX>$+&x;lI(lQ0)pZaNvv|8CQ$Tv1z5@p= z^HQ6Z?gH(=Q4Op)dV<=QVJ3TD-$dHzZo?=NRWVcm*bvh1M&$19?g>mpwearT$~HueS|8-BH77>1!WcyuCq?o`iCQpF!i^QLCfnzE8)cNS~qk z0obE{oX6%P6^md%;J^T1hfWOd=!5G%4o?*j*_CV)5-gmq+6`?T`?+w+(*FKA#3;m_ zs4blW4JE(!aH^7kwNB0H%(;SWJ zM-Qth10kCzCYclZ8WAiKha$(#Wf8GJyOW%FX!rqf30sKOpn11Ejx;O6aBsXn3coEnhYYoJX z!!F^UmzDFN$XKh$9dGmd9r&`Ay}V2x22W*~9@{LbT93^cjpFklcHZ&*=a<{f7b;mC z6^Dg~LeiJ`!54H^99#9)Qa2UcpAN%Gs$?)-7eCFK-giOUM>`aN0U(RlDab`RdpCw> zW2>@xV+ZJ!R&0JNojqeEhyjXJ#wfdQ#cLiMxYBGq_8VJIx2J1eok2-K;7)s8QBBAn zys6D?&cHDCgAMX*3&aB5$a2)nV7QW zRFV5hA)}V5J9I5bq*v5nLZ(J=N12q~C4G^r~WJ#^WDFBv}ToxAV$*XY*%JEkODY3vM&4qeDk-jG{VEmU5^Dye*ch*?BkL<52=}(OSuWM$3dW4I_r!W;CrQRo_5y;={^PV2Gm|5ultK z$1Ifb&18rC;uu3NretMihRsG92BQ%M_dqSW9q$N`%v{<=SS>F*Gz_mq}0{Slf&nq8TJ;_qnX9_VzT_Bz#T2*~epezZ22*L{P9@5B=k& z_m8ggA5z{|4SGxxY@rIKIe)@>F(tCH$p6;@bVKILHJ7?vK2QGnwMvBt>vR5}>m{ms zW_>09ysb!k@cg{0aYFM4Pz-tZ#3$>H66xyoyXY10n)~?$XJ>y4>p`RY2JVTlyhRa1 zbKD=n*15$|L1R0*!AJ4oMX{}_zTAE$C4+Hw_kizKYwfA;yUtLl39qZWrR_ z7s>($r@IpxRj>nw_g{6+;e+~w<@`qTr?Utr+rGTw@>n$;h+7xaFCONg$FJuq!1mL zZIss6j~3rE=d(*yZ(6vxU@qQkX(*gt0P@ea7N3T0*-)b-x*w*0; z@Xb4AI9c3sXHVdaGUQI#E;#C?j#;*?Gp}b82l0lCyMSw8l;rg1`(s&C}L23Qu8b4Ibdq(jhejX|0!%DcLxAcag;OL;^hr`L{AxVJX z6GGNzxs{G-6*&l0FbQ@dz7-GoMN``rHw3aOE*-faBLpVW7Y*Zy`U@4!984msgB>^x zY1HSU3HjyG~4Sq2z!WvOrO^IVs?8>AhA{ggy zY>P`G=`)hSvarlfNkvS&hH6MgrZozh1hrF)645SF5$QSA*Fni|ckw!16dp&0n@Qf$ zS|QEJ6uF`~GxDaATVb2gnn0ZXu25DqV-GIXY>Ox5w1@I)-nOYPBm?y+VxsjIwn0Cn{%|0VMfiPOGe) zRzQB7r13U_#g`13Y|0Praru^#qBLdQsI8^7HTy zg!Qv*EOxl;-ccxZ7ZT_4@&J_S2ad$eL_XpOnVX%Q@n(~+cb#^`-xeFmlPt_1COo== zcX=6^vj5mQ3nby#cR9!EKk;A&_@?hgsga;+A=eDA_8vHDm+&qAlNev+N6 zBUG^7D;(Xi1wHH1HxMaG2fp2ov$B97Ls(9&=vAiI2ekFN~j~-I#7vDAPdulJ)D&zi<#OA(_E1o!l6@lJJFwU2{aIC#^ zhJLIR0?ajdMe!mTU@Sjp!z=8Of&CPwdb2a7Edep|$7si&jj%DHCY-6>FnwLfje;=j znV22XbjAwI0bh(tOgek^T6|tSCaen*VZBs3uki@AdlThS(w6^K_&T*1e z%3T)Q`5XP2H{|BEG{jTO#6e`^G$CYLGr&nA@wwNQXDLDBC6P11_ESwX$gC16E)~e!fE@>tLNDy z`)c{-MW)=X4_pw)rCz45w@>Ez9XDyJCY<1+H;4STC<)0I2)e+j$C9=|<=o<^2v@L5 zcyi;;uP9f$q2}yyWOwchV+k?r969&)_0inVuzJJOyHS8)HUT%+Cs5>ZSL6V=)Zc_l z_}@+l_`1HDv;~u=lQhqPUb*e!?*pujh?O3B{3;v&3iD2G7UIT|{DtQR9RPjg_V#vD z>%aTwM!PGSdQtQ+cxDl8eg*cq<0sHA`!B5ba1S>JF(VwdT7M=|GI&i%9msyPxb2$Q z?}zIdC4c4K&mkK%e(L=Ax|jyG>Y8b$@D;|4m)j|0e+N-nM{F){?@Y(A0#l za7Ze~I;~+q=u@e!h;(ft0MiNR!rza%n?YSyL z$01{uA6}%kGfXn0ayfuR>OcD(jB z^YT;s;oAunL(UeDkLdf^NWt!8h4r1W;JtW-o(GdG0#k7CF#x+MOJ;S-FZ9Zzi0lj9 zxLkYs3v70?MH0SyT?9J%?F)fQ)8)ftQ~jBQ?nEbVQ7fdn6G8%8?bkwN-{CK}J!Q+| zby8NEo}DRW(|1*A*5u(HS#U|As_slc>m^aEs?H~oZ%f)-AVy)uNicURT*WXv6G9t{ z2c%RZoHX*sfHBEI+9_;EP<4#s*tJ{jRpZb*Uj0tCE^YWg7VX?AvhSueoKfdp?-aNO zEy%n+aCa#QPlv96mpXO_qoeITP?>b4JG>R%FT zn~OgHM?o=~aa_I``7XZ6B7L#?ezI3w4VywoZZ1tX;wZE8LKwR4deBXUG58J!nzv+9vQCaIF7XuXMAUvNpoIhR6 z-`z|K?|(6ZWdPBp3ez()cjp~CMnbO-fyesRfUDNOi`KlcepYs_wOn+o4&Lt?*M2jceQtU=osNMT z^#j0oG3L+}U`GIS_P2ZaAdIi5fNoM-UKbH3J#twXTX)gO2$O5>#& zdo!xP^V#V~xffnKTI$ncRp}GDWw3lfnI~@e71Ujz707ACSqF=v8gKSvejaF)QQ}cQ zG~#5hGoPL^fSi7u1})IV27juJ7KgK=+VEvzw1ZF-Ay-#M*Ird~7yFvAn$kn!U~ zSu&vyil)SeQhKkW^r=fM*ymZhC2f*jpUNOPxxf-r9jVAzlO;lxks+9THSf`bK!*em ziV=#nWX5m6ry0apaoc##6fO+OoZv*ys}@Rfa~V)m8Kl?4v;DMLJecGXrRRXc(g}}t z70-=NvCLPwDPWFNf?G%bStvt1^_a1XZ}Z*6qp~%`@CUKKJ#}gvo88|vHy!56V%W=c z>gn@%N31E?um^a~=-_HWqO+~vaOp5dCKYhzuzX*q z=%`D=prfif1(IIVv$KnrEmg}GMhhr# zgXAPMd!tK1c(BeuQr-{A!;uSw%4nOV?9 zixXT|xN>gwSZ#)4CF1r$WMSZ8NuLNR;GhbG_-vt65 zc>?;9M>S}TB}2F&Zb>6jS;^^=XcTu&sDbnlNx*MefFvKM}c-dd6)CpD6M z-uGHE1fs_y+0S!^8PCZg<%@CHMQO)Q`>bL0cPZsA2U%skE@pa9`cEe^DEqpZuXDkl zH?Ot7CaHf9;|o!Z)somq7|dZ1l#1FNC>>dhggIsV^1V`O^61Jt2Ap({H~7c8M_p1s zF6m?p{c-)1rywkAVjW7TDpU7lbhYdmEz>)~2hIVgk$LZoD}JNZKD@e@7E`1Lezis1 zKUJ#n2tE}p!r5&bUq|Rp0CS*|{{^R@Mac$V)mkaTV)SM{Yw>a%^MWCs9C)GNGG`s`r|O$-4>9Tz68ie?nlKx@MJzAl=X5y+YBK9fwlQaBX1+jH9qL;f z)k_coO5X0;vP+hh&dvf&uH)I0o2cX6Uu}KQOMv1f9DL|?^BEc_|02gL6^V}jJrOzp zJ<&KcG$iOM{mzj_n?*b3e}ZfEOS^nLvN-ok?>}BEVFm)pCPHjA=mI9u)x-;_ep!p@ zWgoUP!FV#XTAGEP?WAFGqgqBT@0qEe+FnH(1hs`u+1q9y6eE1x$V;LgbwxSQIIm6; zc*U95Yi;r;aL${+tN3hjjxGqRdiFAkpebz>BRFNks=0@{*|$1=nB`-ll2co8>1a`# zSEoyNFJS)LMu9JX@Ht90L)f&CF$zkc;YILW_(g#_(d^0y`zn%|N z$_wx8<@bAck^r2@YV_W5FWu-rOJ z#h5@=%WM_yFj#D9nCx#)sw(C31c-JW1D{~Q?C~Ty+@3DNOwD0;z6s-8J7S-c2LNT$ zpUKk%<7n{KE}RsOSu{6B%BHTFd&8fxNA3x$&kkKEZi*+=mJou=uYs>lquSMLy{L_x z#($cMfsB=4a_U}IR`MMDFPLs<3BOYE8pspr(hG-*KDkgqY2tQO7R+=fu=zT4TNSDl z$&gRy^o#7Uy12s{k3X@Jk73kpz~%DW>-2G;fFTi_{gNN2^P+Zn{t-o9T61GHp~)=v zIZV#z^U8I!E8^Uc69i6Nxec6GBPwqfh%it(Ox6S})vXn-lxduLiSUj7ZWm3adwLbt zU0nsbfeD3>*lF9wmUjQtZATd*h*`S2*&5Ku(fmnr`|!dJc`uw0d7$0cj~7|X?6T*h zLOni}MfD*enK%uX|9lzvyW&=RQE8)ey3II^citeB8B8aYQF8MPt+!bFGlD2R+_dTO zKV8!?5nzQ?!9ous2Yx^z-5Q3FyUTr?pSLdk{q$OQ`V{7>5#BcBn|zb<|E|BXj5o7O zX$ep#XT=%QW4$um5w)jIbp}}ALJ!^Q`EF9i5`R5bf1qvR%FU%#A5JvGj!#zen(=?@ z4l-5~(6+wR)r8&HOTTm}xgazUdc#aUl{^+sXJC#=_w;wt+!oNA6Itw_V2cj>Sl+DJ zdb2@QVAx-p>)ZRB%ItJDsL0<(E*Fh0HhUrLf5?)^wn<1rC+I@c=>oY=TT>jMCqkh= zSFua%#!D|lH@}@xXG$4*ZvQ>TUEJ%VFl%Cav1F2a3SkoDS}gTfMwuH;`jTJ+L!A2-iNC7O}lX8U+cfMPhGczJbdf|@>sBp)r>9& zH~9MAk5W1O_gI~8-+LT~XyIh)lK=r4P8$dDhFp8mWKT%xqLwELPkssa@VWR<^ga<&Akxl*d)*ft{IJ| z)u!*^v0`iaFzeDKFJlk5ebbvPlv*8Gt&&eM1H9VNKw5A2Vsl6Sx-k&UY4!tv?gyF| zeuT63ABQp+31ZMrFJJx=ROnUzwI|gI)r*jf^z>tvLG{d83H-ilpj*WNsCvIpSc|5^QmW;Y&LK{e0wvaqe zUKzwNQ$Mfp%^2}3Ksf$7cqmMDQDz{_jMCNQIk+c}{i2Lj7gUzTxWBWrGyH(^#ctJ@ z8>`!uBz7#G<|o+f$95j%p=@A{Q-;s#pH4#xCo6XVC8=*OY;O-)bnPRgaSWoN(%mbm zL=huCfc}#mskk@Sfvqrh=HIs`&%ZLc-oGv7{t+@)sSZt}We=Lt52`a;Hdkb?kJ9@> z7r|S_V^mx8k0W&#TQ>Nbj!U<3-`gF423F7agCDgL)QvvXkd(txVnt3Bi3b;sz&eLO z_e#JMrb_J{c=DZ!;RRY0?UP3*sxQ?+Tq?G{foYRuWNhIW_X_e}O*0SNGyT_SP$*|y zL*}^j7}IQK;yH;hP}_KKxl1(qWIpfn^5UUkY%gBwaLk#<#oxM<<9%0REBQAu$+z0y z_OL%<(`~n0qbIPNVEot7)oo2Z;aC7U1^U{B&vx>NLTH6RhFk|CKW zV%?B9l;<13mk^J#1C2UDdWR_HizcJzYh4MnOF(pY5R65)E5}i`u8Y;z&QprwqGj6| zTW)#B<`15;oJ@UesdV+Mn71{?_ns{8UK^JxGan6^i#=?uhDWvdu4v1w)pcTWU%k-m zAWkC_3bRP$2%8n*$^~^6Z@#9w_dSB)G}yS$xn5eFjW!v)YU?uRp~rU#{g!>}?KUr` z-7gH9A}qknbKab(J{qU7+pJRq!t?!nm zDZOgxQ@e9N@5%K()8D_9=>$`({Mi6JZ-Z-5lpCnTHN8S)@?D#wA_n(o_xksUq$2*H z8c{<)5o_NR!%5e!>!HuV7qe!O{P4{b#ET zKxZa{W+G=lTmE93=j6YoW|13^ay#y(p}D~8bpmsk>lKEGJF)9SQeV%(nTZVSRa5}K z77zt!G8>dEUL+Rd17X@gU(5;cn#7Kg8oAg+C9gIE_?uEbmjfh#9tw0$gDh`8Fx`EC zZt$LTZNH!~#eKh{Gx*}Ugpj0B?2K(P@^4g$M6T&yKNk=h(C|GMExGp$dW4lPOfWl) zIZ!k6aKZc3+$wAYYsGR#@O`8Oe=J12d2D;cb2e|D*F!#`g!`s(c$MtFLouNr%u8p? zjVL!c!)`08-;lnO`q^7#RZfA+!icHPfqFrf?Eac+gE-YO58H0p`JOFhP|&R!$$-t5 zLGG=8quWr8G;7*M`w{LBo%&-2r?&Wq6`d*!P4MwA{ZfaUq zg~M4Ry9enhh4d1|YvHmg(TN3by+OjN#x6Ipqe|*vV1(gzivnaK3l;sew4165pB-{sbupcWBaR!YOZ!?XQ|MF++kryD%stkbNH8}Q@6NuH zjrX1wmxa#j_IdGks9}7#{90(sKP+oLO}&^=E39r>;r@GeqV~QLm)kdC$XL=gOvzsd zwV;QlNzNb9NFn(PS60ki=>haq_|^sbxu8hdY&bhxarAs}+LAQ#X@obT+I^1;dTj7d zugz9r`+6x8|G;0HQpnFKA5Z4!(?h^%6wC`PpQw@TNtM$b4TdQXFM$31;vNWB9lW=h zvla#x12tTjD}T0XGiwgFkHjV^;C-4Q7m9T~QuL7tca@1FjJaRnCN@j}A%#nXpn2v< zS85ajsyIOF!AStHvCHS_Z@(<4@leaE){Q~6hmw?CB~>?69L27~P&Y@J`D?SGnD}-Z zrIaRfqeAs-R8DqV@@9$4(q7}OiDTizlQJhik+Ze>1x#6s;OY50ZljuXD0U7fSsSY! zv%YD3a=usjVA4rqE8HGkInD&E)`u@Lt|>-I6B14_LUeL8apC`z!f*Z^kx{AVV`ZWQ zHj`p`OkGa;U-_F%|E0TjYWVoe`(BXVY&`gCHC#I`IB%r$$Ec6cvx~h3ecnV%)^k9! z&v7y-%DOI>P~}18!m$%5cs%ArCiC=Lo>jB8;Om|&xG&1~3iKm*?0Hy`V1QNU+;}8U}h>|J_cwx5o!o!&kU9viYPwj_F|p1xb)0oSh&T-}3!qEb4RsOS6m;qr03xfJWa=lz`LxQJlG zIOxMgVbQSRYLPV3XrXh)JVKKjth7w%HtvqP@kgyNZRYRYJABD6O*(|GIW!)XBYERSsi<$_>QSz)S>Of@;GPWW-uG)PKas> z=Z`!KM+F4be)RZgOW=MS3RqcR-v%evT}|+H!x~|`|30t3=c$XBZ<{G6PUNGCxn}i2 z(xf^E8#?4$19@zd3*+fz|8b0e`zgbg+;6IpkjA1oCZJNYU|G4}AYWA!$IO~SxkQ&( z-bXafdZN5j#7s+l=r@o*X!3n76{gt+zD(BnTul@}V~w9fCMFzVQTunoxnw_hR}Yr( z)y_LqADF71`mgJ@W_NkdJL(ICM#P5Jt5DJtl@o*CqSY#N>>j=ZjhD{rU-q7~8%KvW zDX(cjXc+z-zqhPB7KTQ^xlK7Tmh#l7Fv|8QH?5V`^Ow4wBB86&%tZ&(9`5kJ2l0GG z4473dV1W*Y#hPoG#&xh@UAv+&y|9O3UB)cW8Owk#=&>-G1Yw8XF(_cl^W z=pwlN0%RRz0B0zV-zCZE5Uw~d2f1l=w@%ZW0RIg~g$26B!5*^uwze!8eOY&!h+jB8 zqpR)z(Rcs%)ln&uCJUcTKMfM?^3y4*|K*UBt3VrAhus#ypndh0uA-srS8^yoFCam4+Ty53HlS691nUz>Jbgq&&sEPS4}bxFF!Judr^;CR;;S zw7kze1T8|r+ADqv=P{2}OSEhB#(oK!EhF1B_UZfmL(~jD#?(mCWMYB2xb*+Yq;N29{EzGBW<7L9$Et|6YG!V0Ju+jR|7qa5&ie8RA#?|8 zacP7j7q(TxpKR3;{xf8yjaaEbU}F3ft=Hv`7Dw@h1N8^*{78s^r0VebImS04wJYI- z@hKWC?i|ICPhT0Oy0l6*oQmAw)cqq4S4tc`p9BItf*6)euAT&bm~xYFqDXU-Dq_92 zem~y4lR5M?o$L^vb!Rk2IBP6}cP|0KqoR*VMpYrV-^TH>6KU$|7X4UV^Hn?19w;g0uxb~%0NmC9*C=cy`(z4Wu?qwdMovo&Lu6O5# zFo)d04P@!zs3ft~_lCqCq)j#P6@}|V!Z12b%=AS0dts%-ESWzB=f|>7#C!yQo-MwG zciJ+Lb%nh%lX^uo2i2hM{X4|neRY{Qco-HSH1X-+6zKSX7{Hyw%JClw<-)aaDmG{`}%D6t!1gH-Q3F8({iGLeNIvP;xEI3iTMi?waO>ht#Bi1oUMLe;CwgJPIyqsdf7i@ zQ9akDX4Hh+stNGtbjLgfEHQ~`{H^T=(kYMbWWT%w+}_^SFMi0FptaQf2-(0fSBRW<3_U>m-s3c1 zpgklGKJl687DWZ|7<=!8mN`)fQxyMI4GIl)g3M*_ZSLJ0lqiD`ZG(GqHe%CySxkkRa?AmpqWEhh-dHH zzc)HL9({+I3srJBn~>pVw2iAB(;K+B`uXyM%L&rgi#j+ z+s@nLodVZRUEqzj3HsOo!ce61GI1iuAV-ek%Erb3QQyoCRqTGqjE#ck0z(;5yfi;z z(DP&B>Dk5A!PVmgsZo#5M5n>OeHe)Mu#Ujx7ZQM`NQZLg+cWbm3-|wBiFz{rFs_cs{{10;&*Um z_#_MG@oe^;@&|FIdi*-KXbz7N2B*GK`N6IG$TB>wYrj$m!ABPhw_P@cwdl%adp+f-d<+k z%6N(i(g$aD!MRkakukz4-O0lr93fxXWc35&I@PE)iy4xk5D&C9P67X~M_Y?(WVJa* zii9Y-3!?E9>d$_%-Nubxv`+E*>|bSj4fwdc)%k*JE74m?a>H3d6(kHpe-&14uca)J z^}OD72EIn@`}7_g=RsGj3m))DxcKTv(?0ivA)PRwhrx$ofV+7;Kb?#nd}1ihPGCjS zvz3(nG{0t@xaT0Teaqr06?W~gSJU^wY>Dn>wxPYq_(QB`o+bbG{e4)_GyB_c(Bsov zzt}5S?DBDeIsGa;s1}NZFWssWnkY}Up#*B);?)>Gse(^|bYVz*JV@MWoV632=sI4- zD=&@E!c{hs5*H=!yC`)CK7y>{({+}wXdLM${r2?UPe?=1ONPaVXyv(KFk%|tc1nD{ zc;`PvVfpvlu>QFY1WFyXPa*x!)j$s)wJa@cEdURMf;o~F@FR+Ptn^>SH@r7b{+ zUxinh^mm8D>^JVv{Z1yd!q4FO^=BhAIecD0Drt;}mZp-O;|kXy-@HP-VI+)YY1ttT zKOR4RjDGLwZslQ*@vzS5uN$1E;u#A{`1Xc&#d*0{2>QByuln-rKS)26fYtM5wLO#F z`{p117A$eeIN-(_=3llpN^%fAe12YM?yo<2IU91G>HPmU0wsnhhr|%8sGWx)b;VPM z_s2R&_JG+;?s19Gfla+o&IF0BhNdQ-)Qrwqy5)+mt^B@}(~nL?&#!!v%)C&)8R=&3 zm8;vN0cOd|kg(OKoZ6H2dNr3xgewbj?kRSep52H|W3Q?93;%VV3-~oe?%Q+<_+LEd z$Nqgc;US>d+pqN^?+g%v=21deA_=1gCr^rz`tDxY=vzgM0?>$X{yDqyL=2}Yjo0Rb z;31t->M@A{VIHhhE#CTQbMDnHU0bAo@8BUy88^0J54isCees3U0`}q|j#*rVVsw?eicY(4ZFj|Zx9<&45ddn{< zp*gAA6?=KvQpcm66#S1JDdraws$l7aY?>e5ul2m>CnziN3kdAIcKMy2p1$KC*@xME z9E2U5s%ZIt&dR+-IfZKv8`v|BCePUPyR~g!yn?r&#&5?xT*Qelo4DBlSv3vvvbWk; z+_lX_N_Q5&w5&eIEq(r@G6V>=x!MubkeL4AEpG;_A9TAu__@SxbZHVqnJ1col(iV8 zmTI|@+^?N%38D17X)w`b*$`2WtO-Pw92kc<7u2b_ctpJ~^EZr1#=;petFd+^Kkij< zA#SZ#){Zt4CUJN3_}lX&_C_9b7xX3r%kQ8M0^;kY`<&@73|eZD??-lP!}lO+%K1VZ z6CK=TS&Wd+z9!lLj^z&}##U%E2EnEt9Hff%Ir+pZG*BUHbM&i+Tv(d8QbGb_Y)Ia5 z+=>m(!GMWK95+e|?=c}f_r8^gwARq*CoP?FBl>ohywrZhH3qGcY2eu;!bO!spAaEo zw`1dXq>|vP*Hy}`mRxwB)-;7Dzq?Acov*A3bvKX`J1#4ynY9hQgNoQq{xl#R7@#!w=KyO-A>Oq(4V8q%>3C1X?+Lz-#% zm&@9+Y!=HZ`W_9KvBu*N%er_$3%-v!PaSL6+uaT6>yv0&RG`BxpJVjv@Pqx^t}ZTL z4VPFl5XSb4qnq{dq&P?%H#qprl~+62t}uk}b3Bx~n3u}HLK2<7ff%RmhT1yj0iC%D zC8@XXjrI-wdKYB&sNMroWGxMA3=a*=7f)-p3J-k-VVf^=D?h&0Ec9#lzHb8Vo$cL< z&iq7x2CRy$|9t9pjCF*nhk0!BaKkF-U!d_ZqzoL6t_WIaLCH&jm?u*cloah{N`^VG zm)%VCaA8avZ;W;hN)!&>ea6$C6v>M1UCHLFGd9iZ4JRV<+~;$nrysJ(<5~6Q)$vXk zG9NToUL-QFpY%QJEZ#OKc$!E{rlWZF7p-7Gm1HzS(*)wV`_1SScKbfWG%!r-x%;|> zNDMc|b!~`f9C)7Y<`0ovaQ$XLX;QJ(OP3`XQ*lok#B=w1Hz`KL?_0mMu&wHoE%}^Z*w>6ZRWAc$ zA^2P`p`z1>qw)x#p7@($&_@OQ^kTDe(80}8mB~uHXKr4;YoPB8L&YGmcq$6P_DqOK zw^s~@N|oY4@AMW;7R2F;;)Vx?4<2GVv)M5dDx>r?C~s!^%%d z`3n*Su_Ols4wkNq%pRCS_Au!g~iC3B1NO9213#4i?1^Yio6I=UO6&Vm3rAt9vg z{*+deuZ5#_{b@(!6W7pG<=0(gdQ|iq?33x<;twE6{YV;_G@AA25AI&y1@gCZx9NzF z(7+!C1ybP0dQ+x2tgUm64gLtIgfwzW1Jo!lQXqkmE_rWSC0b8ih6Avwv?2NIpL(;|? zP9&nlAqBdW!6)a>o?{KARaJEBOXXC;wQFxrvX*UMSXg0Glv!K9z#;qxYnldOnmJvp z_O=9GfF3f0>97jI+Xi}=^Z|{`=nZC)yyJm7`9>CoyhB9#s|y&5%#|u9Yb$Yr){$OHbF-JRIZ=4mgYD={7?51lNK@ZJc$_3t4MO^u2`Yjp7B`+2C0-33mITHD1b^!wt*ad2SDD4 zs#nw6L#*dEQlWJPDOBd)DX1g7OM)(|y+gMzxHeao? z>nDfFY?jWm$TzE4ret&wX3Xv$pR#VWc^8Mfj5nqEU)T=5TyV8-2(_6YKvJFX*#5FN z&0AFcW{mn*n}~qls?MtiSUCiPpO^L z9E#T3}DfR#SVpRT5wvwbuc?DkQe&E;^YHHFWmeaOK%V#2M4 zpF4znzw$WM!8*g2b0`&|nP+~oF!x*0v=SC14XEjuBwne+M8KZ0cgMEu*CN9^cf=xr zTXUR8p6+$c$Dv)^bJYgxZ}E|YaLedv-h;hl=&r{1E;kL~!1SLM4? zZrNtwYkGjvnPZuBn{V^r<41&(2;y-g6#t#*nXgZU#@1Gw`09H7&*KrN6`*ep1WMvX zwrx6JlxVP0C;0*1uPW;M##UqPfnK{jo)qQGV%J_e z^dFt_izJRVH`N`p)r|W)9}S-es4$w;SO^IHpEmAbqu|H~FTkA((jr^^q)C%WZg1<+ zU+z{JDIO?NiIkJ!8kU~8&(!A~zet)fu9~aQ`O!|=z&?K5s4}no_%&MPrUxj=7|UeJ z*vDQXQiC2lEa-8j@I`hNI26dJn{Q?CT z5hNUsdP8TUtV8FQzR2TA*2s<9cA-mgRYdp!w$!Y${e7HZonraPtgDVJnMbOlQKJN-F>h=UlbnU-dzz)rkx&2M|00AKO zYvJm?wMJMkr6{|Q z-W@L%ACCXuOHP_3YR`Yqm*EeTqFVMYU#Pi7n!2CDfmAM`mx|w6m3Db9aQiThorDta zUQ)#fhW|VfDFL?<09&;H%x~w{#A@{f>qg2iI#KIIqO->mUEMtML+8b4j1f`mX&?S7 z=cl5(>$w!@kzxTwvdrx~QVBY~?tEMvMqSaA*pnorpAoU2Pdf^;a_ODms%`#fzq}S! z*tj^Ppc&%Y;%Q90^pP<983?4BA;DhQ%d0gHNgO*Y=!h?AQ{2Ki>AR~Cq zUWkv?&w7F4QTg-^XAm*Qh9)gS%_)Y8yI^%^x9<1OW*}P;V#`(=Z#?%((FJ0|O@Vn) z-(5Z-`o7(ugIWYL-E5|(f5W^_iz8iCSPYJBzLq$76#7-%%?D?)3buJ0L0p3sOxD(I z@fNBXD&k1()6txEG^eH``hvAbG0I1V|jFnK^K=2gSLC$SsGAwC@B><(j~E7 zZW-&|scmzdPS0yzjl3xpBsSB&jS|0K`i0HLz=!sW8~e=iq@rv@r%CvmiG3rxoNtjz9bi6PXsk~Qyq?`!RYi(1S)uqXb44{{eE@MGWNJtpD z!Y+Yk!dd{KM>F)f1yA>FgoK3snOCmyn=s_^Kk%hxd6zz}6^M4oV$WKBYrWgR(j|3n zHsa4^Elk0;*iQY|L(o!~0=9h>OAF)fiWyd?>$`f2&U~*4zTg4)0w=l1h+=`v#b0Oi za51Jf_y2ha4hT^8vA(1bfltV(P|B&RBMo|P%KVHY-qjGgCD z#oT#eAOQTDTA%uisL%BtHc?$`yWf0i{qGQUAcZW<`90pfIej$gQY+Y{ULSl%0xq0B zbj1oD$H%ieg*BDUzH(x+_0=@8q{r?(cF>A%;V(|$g3`SFHx%amcplF@GWLV?o6Nx9 zlDIL3+}ieTc3{GxdMfQLfmTCxn0v;SfQKiI>s5mX?OsXlh(id4CBN|T$!~^zupNmy zP4U-MV@ERX^inEv)OcD44YJ0j^E>}I^-xbof3@DC;;&+**vL5eKnEexu=FTSs69|z z4z|G8BdzBpAl&?6H*_(X4gWF{1bN)LIm_Zbo8jExM>O<$xw$hn?5xA)HLzc7suj!g zrhP}FQnmfSMHOua?cupn?jtf}pAyw-7JABgiBHzm4~xib@3V70+{-Mw@XK3nf!kPN z#$lXxO~~qBJ=?4QwoY<*n)dfu=i`27ntkJ|^gpGCX9pXw*J)cY+j?1^Uz70_OT40A ziq&0Pc0n#Gn`>9aJHkN&g(*SjGf z*04VwwGu}m_st{W?TLm(>h&OX-Zy(??1n5S3H|HQ1DiEpL&F={<4I=^{lDS7jtVoR z?3j+LoMQO-rk1VkrMVI>LJx+L!>Qt2XNIv!4`LOJQtHb%AmM?0lGNIf_4jFFlBWSR zajt?g%GS$yv`(BQMthmFi7K=|o5%3QkE*3z!b{pK+xQI%6W#tj(OfG@^OBfrxUiC0 zqef4WpUBP%IwR^f!qyT?BZ#Bb*%hcAt+?l;D;%am29aZbS4rVM;CW4w)-x2&_yeQ!}y2i z{311x*g37}+zDBx=-g1qE1N~Yu{L2Pk@kkpm|Ok!O|`Z{1uk6*aw0{*U+|DJzgW+9 zBxPVBLwfXk%FvL;|2t-|0~gpHWgXvM`|Cf7FIZ6BLRUKf5QcsZoP|mFN}WWfbXf?< z*_vzZ?9>749DIwdPzRi;*pY5-ktB;Y_s#Y{M3j_D{t92L$pz<5FDNgk-X7|PuW}n3 z-Me3Ig^ap<2i)2u?SrQ071RTvfEv))bO{KCqzegz4wSg~TD0fDE3mw3{;I=us(Er0i9k>X zAefVj2?zD|Jn+5ISZcbux&|wTF+tk5I`EaZEc0qa2Zm^Q?|)D0(MW-8FLSnD(PPkeBNOjoOBl<#7xj+d*`%^?fU5m~RUaY;F{@;W5{!8Kl#p4AG!pqZnJ4iiyW z=luQIl&n2J$HW}>eRDkc*zhdd;vAE-u^(u)PKlJiB*0IScM&nlRf#T)P2-1XKyKgX8`* zey*0gqzolzVaa<*^gvE&roA`=(qz$3Oi2KoxP&^i%op3e#xa{xu!i5O2BH&u+u5iv zr|qAL!#rB8U-ihoc`8$KN^Vt96h^*>JQl!b$*V}ZhCs`k$(dE?p$c&jy%+4bgm`oG|0^F22NTB*coKYqHDQ%&OMoh;6k?oXyl-4AIO zHs|G40N@p4sI-)~sKio}Dw+uQ9tbq66@F#zU3JmIlqBWvM=|>#7ilPXx^Bw;XYv~% zi3oX8Vi>Ka`ORir__SEIx{t(cElyiKFNrvyjCM8~QkVYCwwx*mSL$L~PmynCyQa@Z zo)({LV))!z`2GRDswDYghFEi_5`t#gOB^~FLZMF9Bd&ZmJcyfl-uL~f?K34+$6Y2; z)UT|9JhM%*zh>VozeQ7{BDgJYlZb3U<(|+eS4JFc5;ssfR(UVt#!CzQ9)6mO7F_KP zp#Bp+-0Xs<5DOH~Kb-fRsMcoBnmPm)I>_%ixyH6uiEYf2_|FACiUKD<>F56=%IQC6 z?&OwKF`cxRGoVaPO{tFJcBYJkb#;lrggBr3ODbw{-Eh3f#7!JKC_fz5OE+lk(r*h`Lcv;KbD-JHN1hAB+!U8CzSq zuN4Z#6dgY4)hKNYa^3>)KHBr*!w(ROqcP!#XWU*c5)L(GcYn@L5KUJc=L!GBHyA-W zh2GNveCF-jr*-+NyYPIuYnkK6{C2!}K19!X@_$|cKg)p4391|O;|EG=trMlrN}GBE zZh|&8Y%NDu9<};K$J>e5<-h_~E(L6df1O6BAeMBN7)!U8NRAk7$ zoedH`D12U`d+;aSbD)P*5wwm|6sWAUxR-Wt5>n>2Yy;GY$5h_Q?fZZuE;U=?I&jqZ zyVkM#JBn07#Ri|G7n5x~J}9?~A|RSaRvz9M6zLQgaDsDt3#GaqAYksA^${P52K{jy z8EBa#9mrt@x;ek!vUXB;X_31b$y0DiGG6x3pTD%Kck0XRX|hR9XubVCul+i&2S8fy zu0Ba!lD}98emB=7>12+)^4RD2ntKH$GZdFY$6GBJo3%?UHBeC1ithMsQ5L4v$!H|z z@%_|b`E9W5!{~m!5xX)EaQs}LN>`$coSMywZRD9A9&=;XhmT?9v0-4ZPMz18M=14G zrMs`ErrLbThjOWHp}tX$-?+}G|KVnAb$gfpb7_APd?v|Zn5=-6p2hsWNDbq!Je64S z1~eg(9ch|4EybSZe&}`q#~`7$)(+b8tm#4eNlm#hQ1#Az-YMcEUe%m+^341*Wly5J zbH=cveMMeQq&>mczqwSlevtwet-LR6y%FAvWg7gdl}WT)1#TB(Pk52?RVfJ69|dZD z9T0vuOkobM&6qzN(x8t#T45`e`ROBXUCm`DB5h8*KwE;CsB_vA7K_S3x2IQ<+qG+O zX$mYMH)x19B44RiZgbQBY?XHbSkz^kWcPm9rNyKa-CJq2_Ww6R@Bes8Y^nR(fURR- zC0Rw^0lJ74jZ(b^ZTerSDiQS;T2VZVRCTVdDrS*CX}1#2PdOCOP3QSoe|NrN4gh4d z*D{XHzTwkqYMMHnBoHqGi*$cA1CYxab+^-)#UabO&EwMgN0wJ@*4J zt?UH^fKo?QW3tN=qj>Ms9BE*tHfv|DHLVVcCA9Gl%-X z+OOc^hIhGU_Z-;Eq!jA9jngUNWWj+e-03;;#d-IL$q< z6cbsH-}+>YYjoUsvVYxo#o$S<24R_0lpgQc_F=SWhEyC_idtuscWm14CENSB>JbAH zE)c7D75za?8E=bch8gzj>k5_qNP6c@sVwt%3YL*%{!UX#(1ip#= zgxT&Y07i5|Wa;D?fYB%L4pQfk-}@<%Pgrh_ZQ(Jhm9&O6kbTU{qLnHyQhug?0E1GJ zu}O=eObC4FX4a~W`i+V=AAt-xX-$5bXUCxv|9A6QQJt6%YGEqM`EKZbU{j{1tr#jH z;w&puBsW`>Zr7q`w~bgoSpBmf@Cq7SJkUTN<_vSgli2V}JNe24tvB`WIo|fKvFjgB z!ZkFvnH%jXiqoMMXUqh0BWd;X@>%|~5;oMmBCAySmX^i`$w(X07)f+_IxH`00>~6k+(r^ z)krMINU0BKv#8gB9TUc}nD$zdjPdxIcdPD#KhxyQ(;U~GdcT72zdhClwId&Nd;V|ccWx6F*ppJRtcGGLa!ae+l4ENmA2@S6TntDbOb7r*o@eG?VY7N5_O$WjdQ(R)3OF>;1nsc4+#3o_kR|+&# z-{R{vOlLLP81&fqbjE`?3?dI^Bwmzdt(BO}SZOzzU|p;-97PHf73Pou0nt+}Tt382< z^vhZf$Kz-7e>MsaCuGg+arTM<8by^@avEJf29R$a*n9z$JR4Lw3YB>SQGE>IqeBWX z9P(;SNH)RlADT^GNE2mNzzI0(4f^GPgKBP;F(UHAua2q2HB(!al@cTF}Dl6 ze?=^xBW^qnLxfEs*Qbm!GBRY81uB|l1(2Ezoc5)D<+T1T$l>d+MF@eu|LIZK+Da`g z?6xln(f({`SP-dHGT9c93KZv`JmoNlx$r2SmfPo!|1+Yd;=~kN)Mx%DhPu_4GK>x4 zyN@sJ45t@!@Y|7%(jrc9?8IH=RwPnf9nV$3cc ztMdoYV!h0eNQ!y=8V`DrOd4+;ywMg_5a$IN1o(Y1%D$z8u24HC;UvCpp1%P0^?ZIC z*azuq|M2u!Jz;~>Z&!FojnA0fX{`gr=bR)i~kzz zYJN9RRQVcx9Nyx=-Cw0eEU3Q2GS@PbHknYSef>GH$*6eg9sY?lNrR-yXwetN1Fm;* zzqUsIT7heu$~lFMJNCxt%10(p0eqGz6vs>XOk1?j+)d%qTWm0nOaof7yY*8+&y){U zNW)j#`dE_2nwetk59YlL-#ilHDim%n%-NOd$54YDHN`(g4j>dy_!5p*;pp&>+e*1= zsF2~uDOVi%(KM(^OGga+&{5C}Rb(-wVk_gTu3#&YfBdCOn#^l#+uuUXN{~bnSvD_^ zLR@st>?O9bv->15ULV|M%00K2HlUI$5Y9BoNjQW@-(dkJ-ZNjfA*2_j;AEm%6EV4f zeyN&MpCpvmVJrO2uN^5MzuI;Tzq|spk3VNg=hbWYdb5iw@75M%`^!EWEM^E#x^)!7 zf6)aKE&d%$*av!d554xnVV;Zajj;zsGzaZn?}Zf`@ZK3tHLfY+>i_)@Z2K>_5C0F% z)k?OsVa``tTOUt)V3R}|y)k36XMTPX_jGq|j>$5Z3Hy&#@lq|LIU`s=A1%pOLuP9Q zngrfq50-Gk{5$x@FDnJEZ?Ev1odSD&Z`Y*V54WU&_dAGeY;4bTlVzAR5)IRUgd+6) z=3lJ`!aI69vhyv8;@E_k3DtjBLBI%6k(Tq9$hg~kQqK-P-0=PlTAca_1>=b~gi`Fh_6`%=VwHP+WA2pnn(dYY8M`^4%y<_2 zy~sGs6+g)xWn$j`?MjxBYKa)^-_Jma0P;!7J*Hor`h|^J>w{sOt%S1}q(;pE%uZ8c zjz>M0Rj2aF(GuGTrqn`p0gHNN_(f=9-)q8NDaKtZ=IwRyL3- z5R5a}>djJavlGe5;l7BzI(PtCMw$J+$6jhknFd$rUT?}mj)&WMYi!^2jouaq zZNt4#m|bt>*4P-z!c%F1UOa8LqYoso}uPtxyx?2Be$lIxJ*U-wm3vc~xrT2|Ayq1Th zH=j7BFXVBV!-pZxTA++nRUM9inE)ATOWLtx^i-EH+}xaYTG>&p+jwnIA1f>CYwPsS zQ%ha-d+@6IsmL1mdIW=zp4Q4JX$6fBl-d5Sq|nHOphAPbjyS$z*d}gu&L*uW7bHJP zXFdq~vnWK$MFq@!e9=4=9a*zck_s&n%9f5Ou}U|lTF>wDW$=F~U4%a@ zIW~QK^tn8}PCXP8KAb6$AtPG{!*&bycAs;rn1r)X^{D}{5#?UCIGTlBY@}r2f5dhD zvo}GvR5&i9Zs*#92rHKK!2^kWhV`l zs#w98flD*umdihkNS8MjfLgCf3#@2?L!F06?Ga+{S#32@&R6vC9ZkD)%%Kp#Y z!ehTRr7Yt>kMd@=+&+eCl%VKxjB|!q9ZOpva0>D<{0P+#@o6wJUUbE`%yNH$5d((^ za=Uz7^cm$>p1TfsBbCWBt6{@sm9nu=KZG`b1YG`hSZD5Nt#s!hQ7Y@J6jR!NV)SWa z19P7$*damE-tA2Dh7!?gPPG z_PHxjaarB%>o?Tr?NJ^(PV`B#*w>}?+y3Y|1y zJOlg|yyHC_nI6~FggJ&M&FW$H*GyqbPKw0L39Gmv^Yg8qsoq{VP0ghJa%sCzuEh=o zyIE|s1T)=B*mw{BTZc{HKc69UuKS*@QvTsYFsI0}AcUtC{Ed_Kv|}LR0VtOhtaDt; zEa^%h!S5}Ed`_$q32496Mp{SHAEl-2%uYEx~4W1h>_VmD{k?(a?Q z9OdIpt$Z``c?()~Jw#LzVDPtVDTm(lU2dmBmrkWmGI6LkZBbD=c>5@WZy z^(we}A$D=FqG#7t7xkO>%_TPZs|$njky&y;1TJ2cEBMHAU4n=3!?J5q+6@nL{It&Z z4XV2Gcuc#nx z_Tz6mRedmqOH%JIOLD?sCYG`9m)@=31GsMUz;N=0nZgzACNo&=Q z|EE)T(q3@-IM1M2`~d&lZJ)iHXwJMsoZqQA5kwlfkn_N6;~(tg6M^4qY^PFWyEg#Z zaa%n59+N!j`*IJ03M1>~3Z^xK?rn8_x4BO6SqGAZ(K5^%vpk!uW_x-?ZV^>gusjge z3zlhL1(APR$$DH3Gk8`{M;q|`KJkY6;FIKZP<`wGo5T+Y%pN)f$j>x3?>Q{ z>J%cr{brojFk19vL4LHs;cu2R@&;>5E4t*^(^?u&Ez`Mw|I_UMH!=E_J`LWo_>G8i z)x<*`w3c`*b&EZF&5B@>#GcQlH{P6H3bFOC+_EMD*G08R$Ay26txLeMW+yO{&hjiXKUIxq)B=;SxHIPtHk_-*A3-gvEp6{i( z&4qq{`3_NzT~ZN~8$@hV>di;{NVyDfg9f0DZR-;Re9N~X;k`@X>W~mvSao7_5(({e z+8Hj){F+bf<~Xxx{5f8eH8fqlD~^<%`t^K~%Ni#5Z2wMC6Sv{XX;~}bbVl!sc^CZE zjhWC0v$iAjJqa}|Z*A#EDc}auW9rst-O={R8$lw^Sw}-mC;gQb*?l|GF+)mcruB^P zZ@beyf%rbvKV@5}mha$p%?(?C;n7mwAu-!n*%9g*yI5b1{f7M0xL$jic3$2&zs_l} zTg)37c-ZR(zWpgb!E#G32wl?IqnSB>+7awCH=owLh#RT|3J~BFQyiH%uRNcVg%)eX zyAf?1l63FR-uLEwUCf}yDJz+&q@u~m^>eq+bq3y8&y$4mVD$6exOC01D+&Q-^!B6> zB8Bhd#tp~tf*b)|*p!&RYT+ow@MGUl)4Mm+5ApXESu^HvBHE#BuOis_hs1LBsg(!N z-Dex%fM9HMQ30c^8K1x!PHT+I9y-LVX6Ar>UnVcSy||r!h?UJma9|NPceGy4#WyVb zH0fefLiz6Z)fWR@Z)FoR_%cYBEuJo{CMuZv`gI(=_8QSVWq}O`Lv_&Y zl=tl^v6L!D0jyFubyaI(88X?WFX<57$jUol7?*eE-AU?zuk$}bx>E#ykW;&uTph$0 zF(pDiZ|ZOYpl1(r|7H!S3do$HtUs;OG$B`?ay86(W&Ye#-W`4VCY9 zwx7w1#uVj_vx8(uoGq_%V|o{3`Zw8LCL2-7J@@hAf1iBxK@03Yv(_DAF;LBgSh=oQ zQ)A-{7U!(29pJBN2^u?eH@?b}y?c6pI)<=HZU73@T79Tc>2VGQ1PDw|`cGLbWE@;%x>`50EvyPk(eUQSt8b+$>G2t3w+cDgCb{8lPm&v4%82KS~Xm zlT^-E%J}-Y!d>I-lgy_LhoL9sr*RQCCMq2BEcFPlMxA8Hj+2k`YC%ECfPEE*|IN$J z_%HHRMlux0>B2r*zayxt<3WmW{Rb#>UN@?-1~D~kee@;IBek&RZ*<=;&!_V-L4`L5 z0)rW896h9)3>{wiOT8KPSglR>@PF>nI+T4Y-_ZxnYS;^KsQOH!>$Sm0MLeRI)~MEK zcnCL8?9{6*aeKBPr)l|H(M_3lkgB1RcLLo(&mB36GO?L$cU`ki)5h5=qqs%|nww50Czx zoW6*?m&@t8OpPCe;li&%X^agU$cW06zu)fR!1NuJk+`jV)LSE_rN37Zp;v!tNUN$Q zz>b3c5(m=6Kklb^vFF#x-ZMvTu94@G!)bey7fU(U-iTeIg}Nqe5~%)e>;4Hj+B|sT z8A$q$6=k=zMcuieI}WME3O5&_T8eDL=n~@o5GG&B2tg3D4R92u`;2r_>~hid#hov- z#wUo>=5X@%%5fqe8qmkL!KL>1q+$62l&tK%F(30R_><>muEsfuyB@=ld{xK8k&__K zljx9$mHgIwa%M@)<#q#=Nt?@UH*G4!g>AA(b$bi!mh%SmMCZgcRBVC5KZRrdeHrXJ zxD?)SY8PeU`!@sBH9#auo`#D?UFp7j6U#FH~rB4#PXZ2_VPk@8xDFBneESf%l%b1r%U}@iCr>JTQNI9pMUE` z0a~Nq0kG(@_(jDIwd@s#|1_Yxb8-%nM7T`jaRDLNYTaoZtcjb`Q=&WK)E9G>8Tuz( z|3g89qU_40#2jM4?itOXzzA-(>c}V2FTv@go0JZ#e?ej;WwpW0lUl>GV;??>Ykax| z%jI6zlps2NqJ6~itzOCsJ8I#_D$~ud*|bTdxV22u!3Pj$5s|itVai^)H?cXaDr+F| zecH>CW)7caN>$H>tevOmWOghjFEf#Le*wO4{2?uzMEad2qe=EloBrWONCpB~SMXCo z;h8$OiPVmy`p#E-x)j55M9iICybc4C^i9=9lpL5&lHP_jyk0ClStQIN@bDTo;xO*P zEtS~mSu62-N0-{=kc4l^dcbs$X`@A&IFdhiVXvxL?Kp~k2 z+xX@PWHi5{prEMJVfhDSx`qxO zG(GE^rsvBvoj{)Seyp4Fxj2*E}V?&3bu>HOR#e^3vP_I}IPa*rE9 zd3G;nsww$#R2tw7OS}a*n*vfc_E(1<#lcS{wnLx0nm$lCZMhKOdq*~JX(bs)s-<&7 z@%rcXB7W9S-FWQbcbRwPf>G_KL zHExLJ(FL>Z{=wx7NmPT?m!-c%g+?2o>p(y@jFL2Ujszb6e=UG*OE@#biHa|5gx5f; zZ^Svt?8un$e#%9yy`=E04c4fuoG!k%T2+L{UvWiaDF`(eU3Y7L8c04c$J)KTx=x=Q zNiu?A-oYFWq4L%?4df-4(`46ygUvadM7a1MWTUGUb6bp!*9__^I2w}1d-SO<^dopo z`4MlKDLAF3r@?~qRRbqIwDbjG|AZslW#fo-(YguEoEZDA(gjMm=WhEXA#z%(mAFY} z@<+-;hxzc&SPiOxpWpMcw(;djlFajKUSQwMn0B%UUjHIeWZ&+wXY_rmW7k~J-Y>yV z#e#{Aq7oJEceAW`E)UpD6+ZMDHeBuko1eS#>&=3k@`mClu5S)Cgn@M?r2t)S#mublVwO)-S$$e5OPv-G${;zj%~g}NE0a^f1qkgL_w9~T zuykgJ_?IuqmWS)d+)N%hBaJWRZDXC6t(bD%=~|R|U#h()KA18G*T-IOth}hClW1P0 zg|ir~2gwR#XIdYh8uzv1hMRCU9iS()ZEJ}znM2%QA}zrK@+-y>p7k#xu_xeF_qi5mFx~ zKZ(ymg|ciXGq?>@(Hy!dlr6TttT-$sKu^4Ga~YM%X9E=%1uynd7-ESPB2C-5tgdXv zJMu(!w%tdbmmnjxf**giyCyH!>pJ4vauVNIp0^J=n-P#&LgW=q?u~@F-#>N=4=Nio&-mjav~>4`UhdyNJXZxx zY6m?i5g8Z%|GB5A0x$a}luUZJQbCx?D3hR1$q65zVixw}`hV)Bg*6W4B z#~6o(gQ~f?LTYK}rJoqG3wd2EvZ(%zwhw(NFj7Rc=Hj)6Z-`kIm`74z8&e*GqY1rj zP8S8960K?Mjb^3CjS{m75*obofyh_o#YKU6#V9*B|Gdr(W^CP^Q~I{RyU4{s*79TL zL3Mn%Ny22j{_nN%?5qRF8mThYHZa7ekp_pgGGtMW%2r6W)bX|x7W}(&)_JbZ)l=Sr zNa9W^H-kdaHL-<%{u^PbGVZd{#nmxyL%QdRj_T^~a&#z8sc~HY8LCXH*rT5?|Aow8 zz?ZRvxK?CvR`tIbrbWk5{gZXSiyu=WexqlTp-yi%2%WD`3jfJ%zL7%48b;1aqB!Z( zYm&KorDwLlSQlCc+N+CVu`em}9y#$K)~$+U2C1mRd`7e)0|ZwHFfMqF>fkRAK~yzI z`)PA!z?C!6{Py=f2KkyfcNPawPXMYbug!oVv(9(f>>-S#lOIX7;LX3j>E{B@qd#bD zt0xP;RA^ep3`AOGTd%bR#Q`em+P1nrr=WYk*tj^RsNVCpUMPv(_b_l!cqy2;k&#Wi zbBb}sVJg8&iUzx_5LS&i+iPLD)=ikooOM#~isf2pkY5#$1Oz-qc|$7rCCg5*jFuVq z0gK@1x3i#s=MM{cZ;5ZaL63P4x66DC*4CZl1zBG_PS>lfmgPlac1*u$GgeMB3-h2w zChOsQCBr7pDf55N#KL=3kdbNE^Mzngp^cHjJ>@*~pp~3V?mAF7bDrpgl1fdBe!Qd-XDtasIo-zqgfQxgzQ>AE3cc1 zHe(lkn5==tY4cgAM-EW#zz&C|8>74r-3yw*)IaVb@X z&Wh9Z>g=D8u36j58yLFsiww0ALt*juxc70lK>&m|W6?0kDu&-{)HtPRwR4LY9ZwXM zgj|XG834jjlCq9(A)2|a>kfK((=pcNji1G{K-vuJ(e-36%f;9*t%a`WStvye8fO8w zm~9-SY{u$rdrR^Kf8ZDxVI4w`o-z=l zpL~olIw|9y41-|T%bNdCgTc+YI=hL*i^dCQa{*t=Q#`ckXVdDN6^e6h^MAVsBHd!0 z2?z=7Hg&zA0o_i}1N$4CN}iBqjlsneF!MfOCia`OZU7(4%OPc6r3>mqnX@JgYL{vO zJBYR03f=5{oH+Gb3qL1$c|7^Z3(Q|q_If`s-6fn7w!qd_CXG!eI5pn}9J*oz8TjP< zh+kla8SUq!a?IWOI@4yih6}cvzTeeYEeYCE#miy;-1}#Tc9negn?cR>4c2|&L%K}R z3!i|o5N(iiH;UKb$k=&C7vIj#fI_Ow&^Q4KJ83<>`HFQ1iK(B+;N0o9GSc_-J2K&K z1l?;TAy#1)1LB?F$gq1Saev6;pC}BOJFcoE=mZZYDFk-W-s<3_8DPl^^z*qqBuT!( zOK5gDjM9UWD(c;;zj=M~wls8boq#{ETaSSJDs)$9LACJny4DX0?3_1;BETC%n6bX2 zJIT*>gnHl~tu&S3^^01Cxgfb374Cgj*G-<~MM_PA*es+&LR5seqS!nC0s;q{%3pSK zdJQw!Y8xq4&d$!=MKXDS==nJ{D#}e!;^0o-{KtchR1TOybx8-EN}POHX5TYeN@U;ot>P{G>4^(4HIBdB-o?=Li2Ou1$XqKZarjBM6wAOI z39LzZK+T6ate_USS7j%{FnCOif=@Y?tfCSMEG?n5AR>gWr^ib3L1z##kAQ_mGFyCH z(nVN{dPlAO#4tLNpdT0iW`GiUdFtOXd*CEMo+lmtSay&0_IBzMXt8LNayChQaCWIXr$nA7bQiuy(PJY6mxcGO7GYI{J+@tFx z$5=?T%a=3)s{!fRZdpHv*+(_spqjif8NBr8? z99})n1J)^z@>(Za>J)WW)4BK+=Y`h^x3oYHh_9p}WZvU+-%H@HYZH}|mV8R-(TF;o z9O>qwLN{=4fV*(j()zlT-TGx}LBrm`!4Cppg#=(&$FYw{B#hsHr{Hj8)vmyz-s(nj z@{yH~sC8?b zGxhMcKUtjb3)qG%%8Q(h_I#`8W`6T>?HvHH&Y)-1TBMWlYSGAQ%&=dm8D|9;kNEiTfr`UcPq-8SmucVc#cWGpR*l)6Kbl z)jvHtJVO%V%JV%l{_Ih4=HITN@mXWxZhTF@Y0Yu0R*6o-Z1O#2g36?6M8jD`$CNMv zWjF1&RC~cM?XRqi$Q+N256=we}V62v3yS-)uubEE3J3bzu_fBkd(p zc2jtPc#->D9Mrj*ol$9t7Z7^Zc)kQGhmZ6I=2z64!Nuz3CWQ0@W(n^669p1;z$Vq& zWtLmtmj}VgQ&Wt#ce_)r9SzXkG2JeYrHb!ei0&R&chzl675h#YcPra%5rGebNw~I+ z{&z$qZGL&Ck8B4YSWRYdxP{!p!~RJlJf$HqwNseD%;mq6d1q?Ep=jlpz06~5x_KGm z-kYdZA|1FzRe_N<%v$;P&wf60!JJZhZq3H^wr<6lOUw9~NmHh4+VXaqxZ{Zx&$(6S zn_z1a+|l9`dg|7vjJdIF`1x=VeSaS@L0$6cHfx5>riBK>Ut?v;RP1`WWjnVmrQn=j zb0TpGr7_LIk2*fX!OwYKD%*!D<`D7>Pm@EW!t4Zp3Ih~&hC1T4TWYZ?^e zTB6vXw{D`e+<>2g46NHJfP*@; zjhVDba`5o*9PT0NEs~X5G)W`gp}%H-E$S(rtPTMYmxzSCyOH>hwf4yFB9rz{cb0+a zVZxCc%mmqVs}AK7b->A`=$QZT=3S&@wr_`W(Tu44$i)T6L@5E!Jcl@K5|ddCZLm()+tC?N8hAUyx%>X1v}l^hn9?n#@v+xP|ME8WmcM z_^vvh2xzkXP*P#nP@YZSBpNO*NwZJxWYja51@YE=dW^V)MC4+KJ*TTps$kmOA4x>x z`46dX^721Rs2AkJY*CFHBVn1f; zx+z=?ovm?5JjAuh{dlCxC|NX3w26(6)V9Px9zw)8#l7(v98Slg4xlqwjRjaf{_OCT7zSyry zBZ@KNno$agGUp%zHd8}Lk5U~*2$~cbr$s6S1;)5t!J=#M?5&cX>n$iVZo3`p0qXMb z2=L26CL&wT>0x1TV1t(L<^p0HC}AIfEXz}~e^Ay>CttjX;8cKwg*!xZ&B5l`p~IJ7IWcXrPjW*5hI*MH+C1e2~6 zF&U}#h28tyyw|bevoSHP{9mH{%??+dsdCMqKogLr!y;X_F7_bLp1Frr4oKc5nWRe8 zdm2wgXT;>fDtuDkVL1h3=<>#=Jh%KK$(oDNba1=h{LF zKIY`)?46&-O^^*$ufg5vuv@5j`pK&vy6wV z&_~;gWmbTsxPCFK@jVqK6N?U;q+8aq`^bA#790~BBPvrcolGDC!KH6TUQPzQABRKx z6*DE_sR^-Q+=0RZL{|QM-Epw6;AydY4ZU>1wO9LKH^GVR4Hccgn zDIQJ#3w7wg;+WSGL55G36cfGGwcD|%IRErpZ#PF#DAX3j^}&WW6aA8QYaB6Qi#kRg z={KD-Zmc`UbM|4US?0~bqZ8S8djCPI25ON)1 z@1C!p$r}fgj(wxJR>@x_myWMD`Tikw~53?qC`U0papT4TJ_$&R3IO77G);j#23^+?}b0vvmIbP&E+ z_qdoFVB!h)dg+}lN!>%i{+uu%6Q#+V(!Db3;iuKA&g8!SH{?7A3Yd(# zQf|K-%xZr+BPyI>4D$~b@N&FbjSK24l0o@4IHJMeb3aamJ~dw5+}>|O-}n0RBwM9)q{1O*(!IeIae~#w#f5P(9{z}`&5h_(t|v>MHh^p^-!k6tQM){O z^qJ!AUml~y^;)M_+Q`cjpR-No<)sVD*#9;RzT9d9qcTnzYdk%G-y`qKAW3vw%oabJ zao{VQv0<|)cN+9b z^VP$Cp4(P0+}T>o^*D4#S7z4DDW{DsPLpS&K5x>~M?Kf>a$GfhWJE4CEsY5m*&RwR z&!ooaZde8w(>69rmuvQdl%!>3%C#zZW3Lr0&lu$LXuqwUaQe7~lMNLZfK|&iTf8tf z&E75_s`ronJ@o$d$1xQTdU0~Dvp-{_B*@?tn}TAr8Y)f&#Dy7~ zWI%|;X4o2P8(!@Y<;*({r0n;@7M$;qNaM#d#rc?Zj6+u#RW}8t8`ZcFWk-!xh~?!C zb}MyneRI48CxMSZwls0A)gubX4NvD?D!inCX)Rgk{!5{ZItnI#xTY*bin+;HqC2SQ zel@CuZRTQ)1!cETE^?MuUhkJx%-$$9t%hVG5;cs3NqRnRDverZH{t+dNkl>={izm? z6bTI3dJ_la9a*G19Xxz%$=vwocozazFqV7-VpuO>X|QSf!R%eTqSNmp%6*}(A@*+* z7>+kajR|b{J)7iIOwZ=>kgk}0WP?7bujq}ns->aL-LfP$OfXp2f11b+^Pw*`vx8DH z+UPE5h2f&w=wLf2A{rg4CT(~I5w$r*;hf_Z=(nn?b4g5rs2g55cJobG)=FXMCh|Xi zSayxnlT%u_RLdHUE=+GRA_|H!1Gc)x&b=5C?pQ-_PO-*_w5ap%)^$Sm!8w1n_m#%9 zr~Qn+`#H6rvph=FoJg;{{8MmhvlhxbF~#un4s8D;6jIQp{1+Y&2MqZ52B+N*l|3x> zij0k%PP(hb^zU%YRZ-CS@JftT>t-8oFW$B#gEzuTkTu_rwHYG7@{5Oy657ZYke2yL z`i7tUKnu#-ja>h;oz^3DLf^6}6neThy<9oZ!_RqaxN3Xi{wlS(>G*OE;$DoxZ>~65 z%)n+tKD4c_a3tq`yUUIi$`!#X2K#@BV}Lwal`>6JZQitqAe+3M4^0v1FX*OqFKhAa z=tiSG0vmB;<60a~?#){k3TX~pb`7aAmQ=Y#;>Ytv*TsBDctcZd7I)<*EawG4yS)WF_!hN92<${^Y z&|YmUU--In?UOh{+t=4OJ~@ev9+8okXYKBuTwcx;9v%*S=#oXB1_uXufkQjsO194N zT^GD;uRdN`Tg{>38IZG8U~08*v=uYwWD;70iwqYY&e?vus1MY>8P*G7iKYt#$n8rNyjBsrcFHr4oWCadzIv>A8rB=zhtp*D& zpT`kyQc{vTOVq-^7oh(DsuKXka|4!E17SHuJ}kKB{YK!E1M@C5*iNnDGhe_X=+HgW ztVWbRNz8_LY;3GK3LgqBk}Se<+-M&GUIh-0k>Z?LfoO*jP1@AMj(0XhIj7L5LakC$ zwnQU3Cbl-{4foO;bq+*GJjx*y5I<1zMTDNU8B74-NgJ!FZI>+9v~YE$aC56`zk58U z%%8C_$%MC_%zlpxY-W|2a}Sr17Cb(y>NIAVbnuHOH^o)!i5Srs==g9mk)83vHpTA9}R>j2VC?`M_U)H!-#ZJ0D-jLXYE0-IX zx!a@zcPh?2P$lw;mQxsmNnRfMPH3maLQBu75}5>^rmxTctq+6mX7tl63=Hm1xa~{c z|9mwTzPcRF(*0gw-k;1d2hy-CZSUg>KNJT_%J2R|CXO5{M!JUOBV}$Q&a9wPnQhsH z&PmJZAF%+qpR%;uw|%Z*z8#&x(I7q2-K9n)UQ+rDMR>`>D4ncM#8$S2q!C&i z92`_MG*ewIW71ds}%7tnWaI=+$YIqQy4#_2qZ&TFYy4fJ=Vevrp=I)X3*9UTq?g zmY1v4GB-612A-n7ANIWc8a+oj;s?d~!`XUUr&p*F{^oB20f?K(Ig_t_w8q)`FQhO@ zs!&PB$WmNcl+}d4@{H06x5%Z(-;!Q#r*FGl6Cb*fXsAGjjTStTk(K)Fi|HAUwJ@G7yGc)W>%aLN8(7<-JmSQ zX0gW3a!nPN0H&8d^_hpw$&xu|1k2>9CrA8sIUMr}aEEbQ!aUmN1VO$_UVD5pN7jS)g8 zTdPr(y`Sve_HhK;PqrRv%6M!3yULEn&VNp1=%w;W<0Hz=)7Bb^&>JhYF5+KUwy)^tweomt1sfcnj0{Nubj=> zGdzq4RM5`6q&i85t>K45{4tVbQ!!w0L1?}~x%1_5l>gQ0X8e?u4>Shi^HkZCPDrue zTT-#s?vnFgAJ`XBI%2_T(C(d}RUuWeK%F#F4SWzRV`ersKY%{Gl%9cza2yjoj7fVm zSzc=86#vp2w{IFTOeuDf)Y9>cFpivcn-@JP=_y{_^?FcA`00epwM8&PF&wDdv7-ib z^!1^@?T$}OxY#_ta~q1S0hUZ~>;GL^BMmbP3wwYQe%`_u-g8@P_lYv28d^PX@42}F z@i=Yl3@6Y;N29v^?S4<1hia^&lW$a2=d>xToGUnRb3=6|;{DCiqn)=dJkm5>wwz-E zbITdG50NUAK*o>>h#u~Zk4DGF zUe3r+s4=JL7#UHejeQC@zyuJ9or|qL#m9aD`A;oQiPetOhH=qMxIZ;XJdP^yf#Pg= zSr?r`Sdp6C+}}TYCIJhG-W*CvV`+ecx|2vj{FvL(LQ=NRJ?dOUX^Y#rFvdPb{Lg`m z?92~J&WE8NEgpS7I(Cf#9d4to3ZRkRN^_)!zB~{w##R=k}kA zat{AMmQyw)b&m(+_ELo6K-aUBYlN?JX)w-j{~oB6nw6 z7RTViHa17gnBenm!r;>--dG&QZ#TmRBA)Ih4!_L_;oAhXotVELwLB=%V*eM=i)7-= zJXqN8yn`}AyE#w+iN8wO+@+Z)^$XvPi)C^k!9YjL)pA%i$#vx0Ns@ug{pgOh$rw|8 z8Df8`4_2nA#`Y)9r}B%Dvk42gH{Th$bNx#E7-^Ux&uTIfI=oZQEN4bi?>1jWwembt zyxykR02ge=>Z98+rjmWDC!h(^NgV(n1P0}7N?c@Mg2DLeZx0Nx-yg5p8vUrIDz|kv z4SeEA36t2q8kl)-R_^~> zcmp5nI*nyBOQJm*7YAkv+dKNv*j>H?sztj=MnVcE;`t;2Pt_+0!&0C+dTSOCk{8|; zb)=!S^fjXS^D|M6F!IPtB=OSjJ~ihZ<+s7bkm{j35@bP>Ll z;R`O#hA3i$eGC&Nr)E5Q?&HK(j4}A~1!00==qLnKc$c!#Hdd&7Mg^&3-_6Yh9NZxT z@v)G+up@H9P7l?rF82z3p-p9d`^Wb6x*qU^7ausew}usH`buqq*7t**-&pOiRUPOk zW+UC3WzKJ@uL%d(-X|pJQ1vh_d1e%F1{AnUeE^2QF%6puhFfIHyfceZ*LL%P4mjoZ zCW3umI z=ZVOXoso&F!aOe#ZPq=xmS;)RDv*;!63;pXuaO_?f8JQv3xbkv<_F#Gq*s$3hH*403mK|yS8hL9=^kquF8@91~NOCgxK;tHF?8@{-R$)yE$#NZoP?T%T; zmuQBzdEYlReJmv*u||5q5A{#q4n`ANAI>L<3;i$;6LQ5pA{YNo$aa@NlvmZ}$v-Zz z_AOeZpR}#w@*nWerYwyXj6pnQe$azLomda$%hHAd2bURKDb6p0=i!6dpRWyH;6e@K z&6*M)F|1zPSD;_v*{5#bl-tWxOqvfzCku>qZ9?Yl5#}~oW>3W7BxRjTs>q)5j+-h{ zWs|SIpd|01B)`-znX%X6;Rc9%h**nbMh&Fr=I&KCZJ1eEg=;boOpx%j05to6*~qGd zJ=Mu3c*l^c`QY)JCN*VH)5HorwKkI!P|KQ`eZSxEivvnypkM|-I2(|BhtUv6boW(_ z0=G`;0u5#HxisV>fPZGmU{JW8j(!2*n)Xq0@yfELK`W{{w=shL38h*lDE2RR1&NGU zAXk_JL5q-#3_6TORsk)^BbRl1?njzE1eK^SHz7y40v>1^0r#ktT1h=Upe^SgHlUxj znYq+IG(p53T3V?9{DGWV`svfB9sm#?vA~`K5fKtn633`lEL8tN2U=G}`ViYp_Z5e) z4aAw#!~0hTU7k5wZ9OMzSjp<{{ABFl8YrjW_Q2%A=NvBUNz52&APBdbQo?*6UBzQY z0#`U2MnYu`wBaQ+wM$CoYMKG(HVD{w=uBsPV$w8|epfyWCFq$ZE*1ZOJ$>gB+l*|e zyYDv-kx5t1lqk`?TwHxi7l^0IS>grXj(OW}R|HO0MFzUNMgO9=FXKv5 ztA(;_HnKzwlt=-cwrs`B_RTRBQ0EZJ zkix_PILP&QQAzmi+3ml+0Ek&-Kym%>$-K?+Yspn4xi4&SGPdD8;`FQCdU{D)OrYHu z8swz`Xq0AbxCu!~i&Ys_nNy}elWDi|#zJwL^6mI%Y;ac_nNs9CYr`ZVo?WPaD_hj% zksm$)Y}XDD8TB_HId#Baut?>^TUT|8K)e0j>c+3Xc(0tlnyP-cE$#*N^BnP4n)_Z;YP%7r zG&}*@#>0TT)s}La*!rWh^>R-VEw~h^Hv#iA7qaXhv)Hv+8fk3XXlK$A5?=B9J?#le z$!)@s_u}QK;5q3A0|Nrk)a$(dYKb@^ngns^Ee9A%ne|hvQ_h=1(VjA#D9$gSM^koP zikVCbvTz4|@%k9x0Y?(!#IwklWxM=Zdk=XE2l8AzJ(VLi9$Gd1{J?yt!Ju4?v+yvhLXn*h@XXG9nbDdOlxw6YnsxwzLc@7{>&B zw@kl&{ps5g3+2^G?GR%cQ7|>PZ*$VO{!z56pe?L>`?3I(dp7S%1Ph;_{W1!;2(6g?6 zgl>5<)#_uWEyE_|cjz8EeM=A8x#N6*Hgp;1-CgJ*@-S^U;VMu6D-2YY<>vtMJvqy? zy=S}5U-|Fw;x>$Bc3SM;Ei^?pT3_ElnDB(eGd8fRwa)ww#}LQY!G$P8y%Z}^HU|(2QBO+>DHm|G zhTEuNr6}X7!#E&$sW$Ul7D-$qRPF-*+TF{qKAAX?uQZnDQ;rjuSt#uT4g1ngnzxct z0$Fc?pDf>=TQts>S>R8NRuONP0))P{?2Fgl|LJy%pz;;p>lDcK!NU~lX`S}1L4#iM zj#wmGZ~~MNHGWjVaX7>C8BJE3!}E@Zb;X-t4(ypRT5)nel)T*cYKO^w)y%~Oiwd@` zt`3+DD^BK(C9r14j*S1o@a%v5KBFSETMc{F1G5+Bpa@sJl~KEpi31I$kK?;{!VCTn zyJI^+?~89C2pEa-bmfrawKgw|IZ#G=I%SG{(%9aJrJJJinfcp%Aaw!1!TWUpEul*2xw^S-W>JS-hv{IaW#j<&rh3v}t2NIVb3`S?lTGkfT)uV2!N>IB^WW zq9K zw|78GGB6-jyKFC7?9dp!j^+*>^kfxk18?Wi{y1>wUux{2yKKn<7r=ZRJnOVh`lib? z@b@nzkVpWy36?e}Ek0RYy;4ip*cii%@V;#B7PJrmiNdA1Seot%IjAE)_jNwFdkEwi zOOWl4D?3Z*$r_{oa^BvYvU|o820jiJpPebHlVxfNd;u~%$sCB!{~w1u6EKh{S+THE z`XRsV3(oJhLQj~KU!u11D0e%=9|+nOU?(o`R*@O;et|3F*Sy}*q)PMjeG^3vt{`IM z3QritB>O#Allgb0*&%ND%YirZ9A$EEJUo`rcPPIO8A;R8U(NQeLROAKesKgDUf9e0 zwg8v|WhxT8woL`aYPbz}l3!wPqZ;&dVoqJ1hu`x3vA^J8QyIW=H=bcCNk*a${fMKV z(V)*ULus;v$`83&$A~v$7sw^kU^SwoM%5c42G4#@o^=Tg$DiSt>r2o0bmEJ%f~HqV z9DXAdaIuYy(H2v=vMp8Dx6AQ$$P1>x_i?qEWp&`wUpFzKSh zw(|2yo-E%bw#kwpqJt*?2!;lWF0YETvii0NhArE&qI1s9FS!i&)e%DWNLb$VYx+2M z(*t$qA3ISvNDHtqiGmg{;)>+GwOZt1Ex?Gj(Mrl3wL#JD%mYOYbjbIMe~o6M5{{h! zQgW!;#qDbL@!Qgk*S^M^qu0JQuR%~z{qlFA72Vp~%X+U?!EFJ^a4=Ah<*zpsk>zFX zgkWrJtwo$uf5}>HI=>Wo9b)&cZ&s|c^ocH=#p?X>9l@B9&Og{YZRge)U#@?|0zM<1 zkS0st8VD=~5tK0M55-mNEJt1l&3K{c!9oUaw}0oCpI%`Pi|Ff()>P>*Gs6+T_Len= zi5}Cp5ApQR|8T0ughfyE&gFvMPeXq zx*Q^t&CUP|6ra?z)M^$#J9wXv>ZK*_`KqYk z-MsKRnL?W!vi;Y#9Lm@)ZwOVUUSD)Av!(0+1tYX|~*1yspJUz3s*mibyON|o%Zjm4h3rPVH8+DeIm35^59%$+QxsbwU zGksKF{`n}{dR9?M$>sSU67#@^(J#1BbkYp>fHS8=kj5RvAhCCnalrH|X zE6#Ph7#!WghnWT2fTUXttO5gb0qgU!bu-hg_nE52i6K4y%Q09)QG>kh2bd4ysTQ1a z!>Ba?3^98sW}vOkoR%T%9RH&6@IxionZuwOQq|2y1U%AhD`m_QI}#Si0)34RgF{0wUc2Im zKqCVzGUCph)-f;uR6iWNyu)j2qyX#=q`^4-CPysvFh0){!nwJ*|1S95pUv2S1nHtg zf<;y5K*(X#1=BRjdBPJ12aGY{kglu=fR_VUGXQg52?PCDe$NQ>QC?Avu)q0WgJj?jO=rW5TL7AOvMTbvm?fIvY}#V>Vp zJ-xFP4CO@!zB!%L{SOO%@Pe-MG*fMCv2Ex68?NrGT0DYHOp)O29-!9#q=d8D2vqr~ z=;$Ae3>=<6my#$KKGCGCUACfKmH4E-l4l6?JwEa`Ij$F~GG4p_mi2KlMRxqlw;sl7 zg=2ib^SjE?UcgQ}fX|z-^?*F^{2ZTt)sONzl33cB$o@(zs8()Erpc8z4^?tE%`YlI zikt;S>wE|>LDa4K>z>Km7#7c#sbb*kd5RqzD~CuWrpKnW9`;l63$3qVz7$$9n8wBB zGeL0(ZX(GGypqzs(=Y1MRN;Mv-LG;aL86)ti%tA_;+rZdC`O%Y0yMS&PtK^T<;tNyH0@ zAmfROLlU&R0$=t#3094Qu1a@Si)-%oU9(pW`L*p^Yu%iV$*8&nSgRBMV7~6>{7E7& zW`C#l%Agd==kFel5p)C7>2*d1nlSS>qaf&PmF-k5UjF6Bmqcl~Nm@qhT_+mv`le4m z$l!f`LNuB4^ldZn>JzY%=>dG>v17CLyHZm#eSEEZJpE#GLjK^e3{39~jeL^!*GJpH*Xz7%K%;;-c2wQj zDqXfGlUf&yn zaNT}&BnLc0)y!u!5Dt~%I|E3GDr0qfd;cYL=wDXXgLbxnS1h0t5PnVDbiO|mx>HiV zbb34Of}yHrjqpKE$RO9JS^0M;}kg9y1r@PEn`drnS}Vn3?OTTj5*TAKnb zzPX1-3V<-(onD)vSaTBTRfb!~oOrI|9EU1S5jW1*I6qC2aT=p?fjGxUlBzfbxI$Ea zl0d-Mht_#DsS{ThGc>@TAx_8-Ru4tRvCdN}QSGm>SMInY4zrIPgMhCV!m7MqCV2iG zl!@#{i2QrsTB=s5)#7{03;`P!8C6{$KB(~d9N|*odi-nz#{f> zD1wbTdOM!(0sIX8>}@AWWq8+BvPf;R-7UQCJZ~2oCsJy_h9G%2hJWF)KGV3$s->+h zN1F(wp&#c#Z%;tV2Y`@9ha^RMB4T1QAnv?8-D^~8>gpM7-<_@k*5|njTLkG%ZB*2` z*=m@9vPj?Va$$d29xYzX=5@ygz2vdoZ@+GPVIsd}r=CS6m2B|;h0TR&J;1I`wFFX`4R@BJ ziVByoFnKd*5flUb762&?m{BRJTAeYUcXXvlO2vi|%|EiY|BSkkHE#{=!S`VEzpV{)sE*;We?0DKGlZLRYHoZG ze$#O7#i0znxdVw)g=xn%?wMq<`KmK;5;Fuir+W?zI%*!yJFpB<7q>|&!cgJGC?{!^ ze=85;5T_cK{2uT8E;#XnHlla}VIKl|2+Xc0*&q7fNR21?3J^DI*5{?oATwBGLV=VG zuF{27!~46X7dQ1LyJUIGRD1%tGIa}h1U}yz#ztuT6v09L>OpI4vQc^zTgFqGS;`aj znNO2%;Mn7lYs+Rr$ZBJ*WaBcz%||tdj13-x2%ZQBpH#o6v5P-bH_(zZh^7kFy`^UY z>%HtI-@|tdW7}3OFruz&5ch|+*K zhS@mqfiBF9+z{oHP{5DKNG8qSATQ5}b+5?p;@lOSFb z4V7odXU!cG0EvO{_b;|++V55X8Ur^k@R6zObwOnA*8(9q@%HeRM7!tJ7ocpQ;_6T6 z672i)%`yY#nXgSB z(#G{~TLa(gi+uXkSr>Yi2a|i^S`jpP>{J-|>CcLLWtUYW7Q_*$k3*Ig8xSX8#W6hZ z<7G}e8>Xe~;sNjYc$r13EF>A3s{3MHhkPyQn^v8ic}p-@M421ztHoD8*L&RpTVepM z2Ec~E+X~}Pe0)Ux`?%t&m0C>rfF2UheihxIH(Z=56!TA2mD}x^&`}Kh#O>$K&VQdn zW;iq?LS)Cx96WNu9wL%6mDD9@q7_dWu+eAiLCpbA_-X9Mr8+ETy7U ztY?QV<=QDp@H7M1!h<+@*wy;37E+i*dg;En4}ft#-JfeP;_?N(a%E1yV~~#{^lOx; z?qh!^OX0EM;h3mcmnOKP+0E^#T5mA_fGGh;MO z!OV#>;0ONomUz^o#dY^L#ikeOY9qk5np!T@4cj*gkmd-Sr4eL7D*>*k z5AQbnUSjvA$U=5!j*#t^S@Htzm=?aK6xGQ@N}JD?ED%af0bP+~`3 z0B`R1!cku6@M)n!y9YlRxv)XE2U+F>{)|nix8PaJQX>mcz~}<~lwLV@jFb;BYY6BP z|5So!&g#8*-hMMEevwzJg6IN#xK@Rbqaku|+qQUtXp!3ee#7f$7n*{nTFTa3xr?JV zO=ci9^XSxjo*%dBoHvCYW0!!Bx8=R`Evw7Kg&fyc-;9{(043Cv$Xm7rCs8x$eX<{H zYk>v}zL54R7}enZKB>7)dWSlGwnVSu>R^TjKnZp4S)Egocii}jk1=BgZJJg(&9X1X z6e%KC^QeUi0`H41ez*-?8W6|DMsvE^WaSCuX#L!Q!o z$}d{|6-)nsumDk-I%fSBjh+(FsM>{?(>TxIQi9yeX-FeY51Yj$QVsQvm6$I%sk5oD z6imXEQ2V;Sux0M~?!P*|@}zGGYx$@w3EB$c_~EafcgPvK#+j3y>PsD`rAd{N53zNlhwUO_Sw2ce;3}zlvmL zu%t{T7WE;fRq6Xftl>(rvS3YYDtkdZFDXoRYkl>nwn#_0#?>GPL9t(*B>m=7^_i@- z%cLXy5}ycgXqLwp^H;ZwyB*sCU3XJ-Jn(1`nS z{nBYL$pBr%HtvG@DZ=T5|BB9`#nX)G~gaJ5yJoL6zgo9E)r>UrE1ghM(EcO{+cn8WR{~ z<=dJ~5;pu2@r~h>FxT7HUmVHPTB0orU6AK%$K4RmT1#zvHro8z>^gaFDg4E$L>$NJ za?FWz<=qD3oO{kp4HkV_sch-2LHi9{hGO=(NjQ{Yui59Ap9j48u0(b)X`EbWbo2FP zvnJDU_j;-`->4FcvzJtmcOvK+<4v?gZ~L)w6}RHEk>9<;WOhK>|Iu`oL2-6L77k9Z zpb72}+&wr1cL?t8?(R--cemgkoCJ4wcMm!YHv4|NwN>*As)l0Tn%lQeKj*Y52g;>} zl}7b1MkY+;Oq5UYw;?320NbVo)TvpwWb2wC;5r4l%?>Ekq+?^_pXhym>9z1T3W^W7 zV?A^ZJ3SS9eUJ>8Jg@5>8mwc!g}etqKBd>`o0}gYZVQ3@sHv%+_U@RUp3mz%FYj%- z{GT}hiC_O!OG8C-`j)x(*`ijzOT1Lw!rnctZJYPc`{>83t?tQ_5%dPjSjhYKI<7>d zE8VDKz@tWN{7=lE5|Kmu8(l8hfX^>!y7wu`x%6nU1f7%vxHk|+v1Q;Hdz!-1;@sVR z0!~_fux_3s&ELN(h|7w(CCW8QOsN2*7tVg&HSJ?D#m16SX3|!fLXUk5Xju5gCj0*t z_p=TnY;?5jjdrgPA^#gV;6iQY?w?0&a`0|cd^PJWBfrHanG0w+-GWguooSrp*-Sv&(q4-hR>`M@%-G_6bZ?EAhC zH=11zBzv+IA-&9+Gx8@><*jDPdegV(0q>ju{aKCRM7Vaz1@_G|Z<4Om1mMVI zh4LtIa-N?6l}VvdJ5#&pNFZU1FXVMZW$wu(ZN1&bw1=u~FJQJTm+b;1ye1 zTGBKy7-GtGe__l z&Xx~|0T=-8UcLDM#Y2S-2VHcJ$K6n*t-1N{*e%=7{TWM+k>k7n9*QT!Pdv87TEKgg zIR2$#@f`SBOzI+Mcm#k-i%L;hdJx`%$se>)Px&^wPPI7DK7FDnl?5b4FR#qf!S6s@ zWqNi7CA!O^UJj6&bcZTY=G9SU=fCP|ZcfXOJ3K&4V9`8ZCdpD2>dsaPNai9RsoiLR|nU=BJF{E@R1M<)D z2yX2?S6Z$>XAQjTtZ&Tb|3SP!P^C<%XwzzeCIj$Q1fwEe3$$npkS;rHbxC*VqD8JV z_r4~rw>czF9|J?|Z(o5OP&W(Q3kz5&xT&`_!`(c;z`8#rx)qqR5Bq{(`d8>uWfaiO))g;9YlkhAJKuD|hD5f-ctuxTA{ zrY=H-FO=L<(+SEc_qsTs8%3$*hmD@)^B^}Tjnm0S#wGRTF5G=>?u|%92HVnrYje@I zb=nXd4MZi(%C4uQ-Fj*2RPp=`$%Td!R|cTnKa=9C!8g@#DssBF4CRT|oDexBBb@A8 zl$((ky`iMz{BTJPknx)Gb-hpg#Yxa)Zmt?d>wJ8Cjc0RXT*_tSS+R+P3YgImET{yu zlqye5HHkE2rxMs2{hB^=c&}O>$%;;IzwMH`Rg=YoXBN1^b;_%3~O z6*{91T^(!q3QXvPe@h{6NFe?|#i~I?=ajp5MASgg@$^&AAd3y+*iAIzJ4BfY4UefN zv|Vn}|BS?O2oK}N?(}%v@UkI6P62D2>~lDrg#;|)PIb-%hXF(s3!v@-ccBmCtyWxT zK!5WAWpl-C@22AydYkq17u%Uh*1r7vsq*8x>(FiP>BsT#l-uFqvKOwS{Zp`i=8FB~ z>eM0R(PkkT5%iuBpi|o6*Uc}VY56sEI`6(#C=BOhs`u^&4Cyr9d}iye`w!&@NGEp$ z32|vxK!-eL71B(7rha;_^dCn(_)IYPWl;Upp^XKevg%(zYuX5DaQ@X>9%ojFBobZ& zOQ9(?25UnN+JieP;W~v2ReRBN<|#aF0wP!5+mu4S$Ix_$Q4bwpd3v(hNMU@Lcyoh(VvP*dd1fE|b+9fCtd?C6{~ji~8t~7>3V{YJBpx zhvX>(RZEqoE)_oqPc;k<5rke@kEi^k3YCufL*Pn~BhZL;pDqZ+LSS+r_x!-!6o9&o zNpsC_X2}5pla-x)9D&3)9;i0tm`F{{_mN;Q0wEvA~f4eYa`nFS1uyC=$_)OXO>wJN03brOuj4s!BvE-*p?z0@vLs+5L-FVN#RE-V~ z2o#89Q#=a>6BjX2&{dJF|ZO)4_^3n1ByYXsnIwQAAtrjXR+3U`t zYj2H{+0JPSRP0ifusc8u90;qcP^a(VOkZkh#`I=3gDS%VdJTjFXSjUInxb>~f`{&2 z*^?eA9RX<^i5)&BvwQ}eEMQpl_$Vn_P$K?(FfzA?Nk2{>^lu~;b3Ii*mY>WjWqhM@ zS#ze_FW*j!r!}s6XLpbM`3yg+3=A7}+&WADRZ0W!084OX!|>Ddtv3P|j2)c`x6Rxm zWUsMQw(wo6A!*uf2*3kRt=D`DEUzyr(Ljs;FzY+sm8Ahs>r}db_+6S%!+Cc=1F`UC zNyp)?nB*OC*v*oQfahnJO5V2vgSRsc)8!_haJcG$Zmrj`kp}~XRRYi3SANEv%kZU% zHLX%+kAs8JP)lKJVQGnAXDk=2TC@0{A*()h)UrwRy?4jN7#auiKQgtn-90#eYh(W= zK%EeFG9ST1v$A>V!}-LKbz_vi9cW)3=Axc3aZ@(P9MR*GNBsWqG$hgoG`l8fLkQ}_1X}`BQXntunE8E=*%L4c^7=e705*jZtFdk$P`d|+SVu=^$>(9pF4S>1 z5VhMr9tsW{q!U?P7bjn{x|n>aVQc(*+bN?aVmOm`T(TLT)(M+=z0SgA7yeI|km%{` z_=EqPmuh&|LWxy0HYT1FvcGpmO^mmph$Sxv6VpW_Ypb4BR#I7|T|V)3Zl{H>gpKzm zu`(5TGctBjU$dYVkHst%TW+oqvZ-?$fBVYS$`|gZ$9q z#)MG9FqtgUZ-glWu-%E{{6^W0HS-!IInb!5M^4U&C6Isz*J6TW&NPu^H^fl8ZDC_a zu()<4E{`4+NP{BPL`=yj=MrLTm*lNf$i^)~?ZQG3$tv#Bl+$rbv~UAo%`I5!vQMum zFXbvBED$oj7@HV10bTkAHNC5zr@-v^mKXbnP zF?e21%_?J;~4smw@28&~@LByp{Ui+(jkq zLS2LzA>#e@-xk7J}&=C_- z@SeDcN&PPv9d!4;v7s=X^%nE}3s(6;?pa}KVHr~N3aKPGcrl5xd0ijF_2N)f;n=#> zsQ03$Z;hb5EHoE(&L<88v1#a6!e8gB_jCR8q%1eS%9-c4JI@u8mEgo?Xoo%gYW8tvy3g$;04eA+QOPF8^TV{P1Zrad1N(CKi_4nOnAw5^cywDiK_j z{0bF2>Ahd$51nm1;2pN{>gojxiw=)BzWg4LpjO-XICIxXd=CVMoUG&VX83h70L-gZ z25u61b9ukWf1`EixzQsQY#;ub?^8&=BZiyCsBR`YmVOd$iY=fOMp!#_3LYFJ%0j&#JSOGxB z0(_^<`MK}?>w$y_?Ol3ok^NHF)Hm3FuF1Zi3!S%^b_U;?)%G~04h~W+ zscSGgq+n9OIx!!uwb;Ba8bB=eILyqw!vo&a14c>ScH)7WxO=nbXTSZF1zh=nr7Ofu zPybkBKBcX!*{W2AZFIY2Z@*o&F)#_50*EmIw|#v_!(h#Nn^)IshRLwG=Xq|M7f>sK zjCKp)A7K`P1lQEaH!|#xPxtO@dIW^1WO4WUq;hY0hD=V%+i$h^$DJ=%s?&G5g4ybN zZ{UGu=-|&M!Go#I&I-y^BY5!j{O-R43)$&TnM>)BOlK5l&wPWQA6zAayS<`1_Q>T` zTU%R)7QPiAj^XTHy06n+)O*3?g4HVn@NCDotiHm0jc_rwl1MW@A(R@x4NZaV0OgA$ zlzzsg$4>bms)8{$z&k0Y4Jk@NRZ6yw=c@-;rjlbckinr!oIot8%uMIb zhNvBLnCdIYY>?;ba9P$AP51+Eg6&A-%H2j^Cza9RS;DPFI;~YaJC0;_w z^mcLe1(ANW{$4HjESzwjr$ayJzZco25OV9IJx!=d=(g5d)~aV|4t^)j;Jt3S`#=yu3$i33li_nI^9PXRP zmE-;q>RJt#5$=&8BbZ0~AH8%^mu@uJNbJj}>C%t_k)OK|;ugAtv+o5clG$c>R#_=y zH$}NK=MSE*Cm7k;1oywY2eSQib#lNZFv*+hVh4x253;Ly0)i(rGsfvU(RxWY@$t+i z5Q=0M9x=2Y^T@wT7~y0hq%jH8X&zqYjYIIElLkpeUF6NqX@wq8GN3i_^lwb#*yvw~ z+eOe1^nC`r`S}dLKhpovdt2(%IFukLU9R_+A?2?78_qlQD32Q^m3cP{WX@>Phg~qQ z3lx9g=n#=H57JEyVS#(v=T_LEu0}m0M<1Ix1q9uTz9GIv%H6@_VXqfO{|TAS@nM7Q zqfN!0z{k(eH-2Y#!x=RiQbly#W7suHhTN&_kSN$-p$bqw+b%!_afws^ z%|OyNJ^3kOXL_I3*-YGKDTgFyhUi%qa9|}R%i&ESrEDWIhaho>w@H?Rly}a(>&7CjU zSZbrm==sAXGlRsIAf6hj-8}@v2>?`}g`HiTejPUhw*VY?h;|=JxGwiw3j1TuFv!EY zDMnXGUt?@EWV-X4rqZjmU1fo38_J(~CO^6Snl;GJ~zson6_tt=6{p3&U zJDhLJplh=n!c~NwY-d}^$zf ziNM20Vn(5b6CG*Do^*&tLO$urtqTlaZb73%`Q3i>hxU^ZhPoKEJkt}KI(XWCLqkt-JLCtfE5wOEazy;=AbU; z@wg&SXVTy6&ozr3ozYG#i)Nqzjr}lGVZqO}niHS5ckA%DCI(##8JgLpf@S{JeDioZ zNRF>uvexDC%NqZ}^zXD~+6zMBKWPBD5YqXK0jui?<`;UMC24SU&QlxS`0Ww`81|>~ z1V#suEwnQ7$z+WMU-w+BQ|Z1;8O%!qOtlvf#7xy8ou_%)al7Zu*_KbjV*79N*`tfT4w0`8t&X zCRZz$RjW>p=>cH;u(GyMvbu2;A@pjp<$38g)#D9!b5>2c z`B~?@`t^-Dpnv-PeEW7bBHtO(Pqeh8k&#(<_iq;lNL*F@-JNlIYS#05YjgJS0;oM$ z79VX0&Mk{G^LU324k)>Md!~SjS>Lh=7!;h}ju-`>b}010Q{!F#iY7mH{r){Rcgtp# zHD}$jy0LKp1auJ!`R4$QH!;62;B z_9m0ppZ0OS4rPrKJF1R>I~GZnR(D;T_FQW)Ph3VX#bg>U7UOTj%dOUJ8Xqd@Ilt z9X=pptOsuluJt2RJCj(l=%PLEQdcwvpLojXtZqoJ8RZyr5Q8fO1|8UTrQvCTGYkR? z^Xh6IJh|>hBCl0vJi+cA%p8_^a=tvR%%ddk%gb2Bjsg*c;$eMWIymvVf^Fl~I>Am$ z=bW;ta|~j%aa@WS^d9wbLtg#WD-!3d%pp+G}4L2A8*o1f~H?~nh1#4EOIirLjYTpHKfhTazG`MuN{(VlsB^O8ikTd?mJrr-}`Rgu=Y^@33q z3Izj5R!Nw6FM?7b59mut!qVcONlm`b$ywF8MiSc(#EPqnelusIWPyUW>;8@K>@f0= zgXB+$sZh~HPjKDiI5crO&Qi=;mM(3qni>Iyvr*E}&Bx!e^1m-p%v9zWT6bE}rE-&~ ziIQqK(UTGa`?CI#4#HM`luCsCpq%RHp0{?RdVeJpst+xZfG1A_4U0eHeid7A>=hw% zgLY8eovzq%O*hM}`y_VqH2vtFOet+8$H5bD1N~o1wJ@4||6Aa9F4_=`3j);C*YTjW zX#~ljV4q}x@WU{X0((M7?y=%|2+upu6<@lBZ~L^1mq{$BoW0=Y@K5fEbk`3_<^KKd zGk7T7FJ6ToToE3zY8m~A%ZVM&^6Glu{s^BLdcGGiDdR&>w}h+)*%10l-Oy&B$ZO3oyOw*k{9IOD+nSYgNUHFh2hs(;hTtt+{k;uFBrisq({s=dB4E%g-Lg3APhN&*DtGb zln=;4g?Jzq^16BFt*-J;<#zVj)b&mcUk6B#x==--1kGTr*^NxG#3F_uiNY3e&}p=e zlGYoor5HEroBY-<{|xKO%{|-A#94scJkM3FV>1$6!lm4gIN1Ht_8*%A3=5FP<4M>B zc>CAJFneDn9XuZZoyYgktjFh}6R`eb(86-pZ5OPc{<|Gd2j@e|0|sA5d4G2UeKDv0 z?^iY#AQXOSiSZvDoN^7kkrek&E#KG3N%`z*+A8%(YqzQgzTu-|ua{g89=B%>fGZuX zw6fpq`7<;G-^~Nhk%67MI@6d?#FxF%v9$|X-P&^qxIzAWbky#;3!QG@naHi*IgtN0 zs#qb3Sq#hVutBNtt+{jkuM(|%W@8dN{ z?8$%eVCwo;{nzRo^)0$q)b09SQlVi#P){$7y@2l&1dYd98RIkoxpV-J)`yk(DK zbB~W-;(2n?)7$<8NK4RVdtBcX@v|$PkLWN;*;l)|h~CqFy!0hjZ+G+Q-atGP6i#fz zh7r;9X6O5Ej6OnyWB-CG3%(fj8bcw(31&f@l{hZQ@E7%x)r6Ib#6)EC5(H3y{{2A2 zeE4o#k7|#NW_(|Ev{;JcK&!Mgn?|%?e$#q{HE$oWmv`B7v-}9=sks!}c(Mx67Kct6 za_R+419T9ZHKpdhl#M*FsSA6}Acy#}wy0YjP>crRKXzC>2m)L=62)iXnkTiXm>v_)!H8e(xcpMp7pO zPo$eqqY&DwM7^Hw?ab-S}ofKuR<;nQP(YJUjZEd(_PTgrrmTI@8mLYpk7 zhRw@3X)20Zt24@qK#iGVLC7f{;SBXSY5;KS!4}vKyz-=L{w_#!HtK*Dh&+IpOzYj90dxQW_TjY~ z_Qex?J5Ez-iyyA=B~Bi1w~JabDCg%8l;fY}^t>!V;gbP0P*A}Z?z8YYsnS{Ok6_aJ ztv9d*VZdFtacK-va{9ji%Q6~t4^wm`1VurCAl92jbBYHa)m{kfT~APO3Dd-N-2P^f zl72<=!Lxm`IEd53FRO&oDp+MnbGDSu$^r#S2JWPJHovRP#a;VcQX-^*h{Z+>%n1>yGR=hildUTkaVY;GVQ_XaZNH#3Y91w0OkNj{kmGngUSmr|IY$c z$}cLJ{{s z|MtRhhSl}<#_e_apyBoO1V!TeB-nPnC5hZ0b3AoSc5kaG!f2cEv|u^6aSlT&t=gzN z+R@lL6hY$m7ZB`)fx##WOrzS}$t)YN`e-UCJR$k5%uuJ$5MP~%d7ARL*q7{q+t&q<Rt$* z+hpE3PKX^Y--qH91~lwZ0ht)|0uzxR)19tg87h=oFR(=MJ|H2z&IL_`$m9qje}G~G z>0ndU?{$r*Ol?qn85^8?S#l4$ktMN=x%u|H!k<}@8~PR3YY|bb#_7Wv8ry@tMEw5P zwaXRZ+62$ZukGvl4;gnsH1X-|e9}pR%sAzQT=3_Nr?i*us<6a#4+7)KDj%!R2qiwc z36rZ|1ziOp4!-!H55|{layua~>UH|7Nr>gKuO61Wk%b_0eHEW=BmdNrSE|JXAylYC zq05=)xP&1mtl#VLi)SGyAKW-(=>@5de29oM?{Nx>nj z%AG|n4%&Df&v<=nQ|DSD=0k8zRZ;tD{g=+n$t}#_{jILu<(fEk6mHKw;=h`gY{6V0 z-sfIEY}`2*IvZLvvLen*M zd}~YxstOJYX>YZ}P$}}%6{Uqa;f-*6EDUZ8X_zV;QRRl~Sd0>K@nr(FpNyo_`r;OS zRl$D^<&vgnjXK6Xw-G9Cy&ex-xwm|f5AW`WkLtf7Wk&I%crmFWqD-16AC^*;l~MD0 zJQ9AH$}e9(b-sQVSi3}%G3$iRDIP)iVRzz6f`W?pr{EJQ>Yw^Z;ty|zCYeg2JAGCG zRJ1|sY&fBxe#NQGp+S%KfG$WiwMN|AJ4{eTn(r<=c8^;gYs>5MMC$Y)`vy$}`J10m zy^nt41F?b1*l}>al5swyAw4&))9Ayjq|vT0SA@Vb`qJ!JXiINYr3CfwMcLLa>iJoFs!(dI0IHQD^1PVhA>5Fm56ijpZO|0cT8Kq@5*Ur;>zMJ z>P-V^KAB8qU1RY+rm!W^kI!85o4nL?sAc9BT2_b&Lq|)CYu+hOcHdWC<)?Kg-+g7j zzNm;^wb|}-AxA6=4ZZkSx@t~-If%~sV+GmeTnCvY>HhYNYTNdX(JmeMV&Fg6dHoK= zJw=JIvkQo1{RMvcQ={h&h-u0*IlMt~niI46Ud%dJsanqCbqk9O2;97W;Q&a0p7seI zR$QAD8&*Wz&pLW&0!5%yb8BPg=7>5O`EDZj+xS2wmiQ(UbB^GjL9BAA*6e0=4XfIk z8!03p^reZN-4}HB!`{~|`9HZ4;nP)9PfvJC68Ba+Qqa!TWhcLX*Fa3V{=wq1{_#N+ zmap@r*w$Nwfy?og-&792>}v?gTqK>^IcHT%)~0Lcj7w3o>s2dXb6cyG1LvtNH~6e+ z8tf2oXOKB^cdlN9e@>udYi|n`EDTFy0yW!VGW;|eAMiIm;1&yDbp8P5d?u1^h@e%@ ze;EB{=lrjlI(84+A!>qjXbePgLmUO=n*RF>R)zeY5&Am)-8p3D|5lU!i@$!OAn|{N zDxc0hs`1z|eqZ5Fl}YU*>lan2T(IOQvy@XvE{RTULDkO9NNsWJc|GF`c<~5`K@aZe z;04M_+$1VjTbAh>N|inmeq|D$DJiI6n*r1+xUJhuDOCJOY*#B8>+q2bKXy{}EZ5C* zQXiWytc!IBsY@}ac^iX8!QP3~tdeHE@cTYK-!sS%2sWaXX|H)@x--5ETzDjl+TX4d z#pqs+Vh;EBlp!E-{I{h2wRJZxb(<2($go?c87*kGPrA_Xe*Auoo$mE6Xg!eyp>$Y{No11s8vCb#Jw1UzrQy+V8R z`NjPZ_Fe`SKe?)V8$bNuZ$wvA7I3EIA0385+B+>gAsUVK`+oV=AU2fd?kDkI+ab+( z`(jSfRJJ&VBIb|N?SIi?Cx>%!3~eg;acSOY4bDVZjBA#J%9vw6oWW|LWM2}K_`c#9 z_=4eplhRrhx$E%=1m0Ejm*H0SeFkeV2x^myV~z4}w`0)QL9JH^N}E07D%&78v?!FZ zt6*WRwoUl-qRdG_W0A52U0Eev!fq}_ij$_m_`{SW4ie8IZqqN5e4;O2;T3d!t{g&G z_lw1MUcOT(Q?^t|Br7Gwfihw=y!{J1f1XTfqnD+lQ=*rRNtZ+>QBvSCKT#5L#WkBt zZRCfkRTq*&nz-hz0z+M;l$*EvG$?CphS%MUnoXN2gD7Wx96$TCA>n!H3L#-4az%Y( zTS&Nd`nO!bZAL~y<7yo_Fe2eFmlZcDpGM5=^mxGwWc-A&&cv7inCYo|XQ;9!v{wkY zO)~JeXr!RyQjmA)v26l`DQJTx8tGcwq%T7So^2?&+{|*@x#q5)n?&tF4B^E)yGW>c z5$BnAEcd2~IpE<&Ob=hGGZIewya({5#K9wezq$B%O~8&O#m|F3cpXAopk1?eGZGj7 zdP8`aO88xwHSKC0SFCzb)Nok;hzf zQ<}A%>S+5-i;0Ou8PdPw;B0QKG@MzjSFinT)!3F{7=${4<>N#C$6A6yoeOSR!ZKx> zXN*g^5S>|vF{Zo7pC^$$L>xc;h;Je+B#p?$N*V^lN>vKK4F7eK!<85*5Q2Pfz#uHW zU)aaS^!fVLH+G9O`IuNGj74n}jvOiGQu%@4+JqUWqdu(ZvmCY#y-kj7ZjqCFP_l)B zlg}=0St}ZA#f10mXVBi+T^r}&b$2wJ;+Dbm`T7k*YtXwUAqSCqFK9aR4{~GdA~lNE z76~O0e2$q9O$u4us5DcrYvy&=E78*O(o?6wYcS*v@+@T8l4V(wk)3@w4cW^FNQ%kc zqqya*o!o1``0cmHHd}jOM$<8x$$tDa9&p2qE}@JHr%~G_)1oaFonWm-feCewsg_jF z(%YwV-SsC46m)D(34<0T7G0sRHpGQLGZr9AHXIN!ij4-Y*Mx?)rd|m8v2@Ld( zuO`>KoDMnPhXcSuEXtLD#ibp{$W2b3e~p0r3%GlKA(=bnY9Lc&43OI+R>pQd-Gl1^ zJ?eD5E$R4zSC4-&FtT#{#HJhcOaNTs&;x;i%jMm)mX?8uiBE`n+nelVxt|-ZmO~EN?*4+O4~~C&MTn$c#fK;Ck|5hQ!-DNw49~ zsTHO|k=-?X+nFVR+PW&spy6+M#C$XQGEuKoaB!)w_)XZrSoQ z%`8%!B2cb>1_c-LkWr8&R|M7_%hvoaNT(f-2Zqxsos;-j1fMjBQ= z&da)`r3wpWnf721w&L9RLCGR<+;>zTJkyFWB=1dvvMHaKQHrOPm3j&-p?f8Xm?&as z#$(t0m(mPvIfU#umAT8QEPvFyAb(}l&v%;A5x!M{^%pB*DSY%}KN`}9BwwL2r-Jd_ zgu7-U{#Fk zrA*VRb>fkihfN}!$DV$6Jy#fZ7I+m;-y8gc63W1iI|^0}CJ2RM55>52R$?Y2uLX6= zcupZXCAK*kSU^|YfEMbm0$eykGq97)<+^gv8PzOvER}?~f)+5zC{m+g%9n3hO1LlO>~ z2!vB4UZzn-h&HMPjRw>7I@ySDQ|drH-ohHLrhLDoVH$jWLNOWr3 zBvF#dt9WbahC6Az6}};ev=s?;^(b{Tq{8g^3Qs|Kg@7)ju2BPBeLA)gQYCZg18ibH zb72l;*q}wj6KTVnL6>50+Iv_M4v#W~=uhXZAzqkv3KBUM$}$Sn5%$rSG8`!;QM&&;N^B+cM4=KE!tE&X<=!k`SiYi$ zc_gs9x_Eex5H9XIML4aGCH{Hx&+;qL5OCAw7Lj!MmtD@1h*@Z7SuIm)JYQkv?&R@j zAGSJ|VGGTe<#M1#lBrK!8XHGcs#Jvx5vByj^zuh-iE`=s>en8?Ovi2m`Ct`-%cLWm0=U1m#Ij`Nh?`dB& z+CBC^Z^qf_cRPpCR5@O4c+GL_Kh~^MUfKb*Wt1)ZobKxW>0)2;>3kHvrY4_Fx$@?# z(7ROwZ-6IAkUpLmtBr4j|8HZ+iuNQm0C;1}&#MAw?K&{o0?s@7F3(fUMHccZ@z?#A z>$|O&>zniK9@(bNz4t!|U7&u1iF_Ur+(pmb(sVBnkXkWnv7BM4mRS*&!{-+*UakuS zHD=|0wouG1oy{nj&DguS_4B{W-o6>Dc0m7O-SuzIOnq4$eD*B=J`Vvc112sTAjI(| zMCctu8M`nMuwhNyp7C{4et*DQM0qC`C`MDfaD3f$)UQ9*)AeqAjPD!=!{VhsyPY_5 z9|!4@HFAGXsjFX!v8eq}y>o}HEOAcW_3H<|w&Jt0k?%{s8>E{9{(9w)Kqsx_SZ`-) z>oQ)iO{M~g$t$;2`@INDJ4CA1cTyx$)WOOfhUJrnya194n7ZNvWB&a+s~(4fS1U=_ zT9Zmo2j_IyS&Prd)7-Y}Gpv@c0mB}57wov%)f^gS=^q*_9ut@AQsr~eqf`Io;Q1*_Viu5_=VvTA#P=&Tz zKbyI?T>@9FJ>Z(G&3=o*z9l2S0!vN--A0=JDv?HvhLY|VDS_&O`LWdmNqK7XXcAKv zZt-1km;|n}=TVhfVynt;Hfmo&WdUUhO~jcW)v5_Wa4t2+)rv)sn=sI8!m(F?jPNpy z%^RqUUuG(qk*7A66bny6bA}f)$(pf%OT*}Kf}>^-o=!H3?g#ZeUz~leHJufRqY^Vx zxHt)|Y+W3bmB58Af+$*mPJ>ragftSkHt^BBmHUKoD?%O1)x4iAg>%UfKA)G(uj1Q< zal_*uFQLO27JT5y3P7h~2bRMk)hw5iLkBLeCtJ5y-n9cz;yR?vE{ z{lay>H-eBhLG04El0DpMRZyGxPc}!4u=2AVP6{)ZcxIC3*ZOt#M=wDi2|K?_pS8~@ z3)|%pli(jvCr4~SpJskP@+o-n@J*!v#QdklEtHah&UWmTG`$jZZw_{it^6nUwv)T-dU^Kizu}V?%N`SWeQ^-4iY{XX_4r zy{ofS3+T^Gws^Xo2U2mK5X1KRLtb9bGq0EQiAcJoU%^(RPt|znA ztDna&qZh8uzC?=u)StIP{2sh%;)U;N;UZoh9iJU2D?auW4sAXSo#>oGHDD!J*B3&u zf0r>I7FVGGkI$|NrEgXn&m7@Ty0GjmX3~#`A~4a{jH+}Fbt=UKp*&yVRn4=*Ij#YMoxwP zYm>2)A!FST0pY>qYrT={M$@Q-ESZ*QrEs}&%iPt39tkXvx9`m=r~PL8pNQ*#Q1#%W z1{2-fJVSH;@XM8%Gs@-$P>ED6BIQmC$| zG8V3BYt6)*nSz}1O2`!>NTCUdT77DPpAYY_{S4(Y6*)iQ%p$Z4!o?Bnzn>c3{^r0_ zKMoGelZzCWVxh|5Sv7pVU}!ia7nPoA0ISNAN5xXBL6M`JoZ!yeB(=09#7UdtVuWI3 zCXiC%i;z>!E}*D>ovP>HM4q&p!K;L-KHW#s@r2m3p}mmC~KTP36kr-(I>M+AJwUBt*Y?ad!$5poB3v zmwzGqwP7UY7(x=gp33WKAQVXdGNAJ*+(lhRODs|*)w)F`^!-uDU(?E>eP;x8=9bsh zgHZPgwo@uj#w-t`W?rYd$HQn?kSmboDV;FPU@PkR}bmuMZxrJv_aIB`LtN?-@n zkUecoTtw6B#&oL#WUMG;MP2YbNtO>C8SG?6fKW?9tR++*0>?NWC*!m;lX4$n9h-O; z^XDueh_Xs8Bf}EdED(8@@XskHr7)uY^OLHos+|1N44t`;P3okAgr9ZR=qg+pHMLZy zURHKC;3flP?vEkpHK;WT2qv%()+0AyEjnf4qzX$gW^Q!ZqY$fwo zGj{eyNyI8?LBHd^%2m;$q2s* zO1p`oXGA`#N9fa&aYnC(!Lb>QsDvbtEsntksoC27nmOlEj-o~3)Vy20mXoj$euCdiO429kMY>WeMn_N7?=@^dy8GQQT9mHh()dLd0$M zwX#4F$m?#cA3?t&%&?mvm>}ow^0eEY!I{-PBzAOs?++6Xbxu3OO4AR!jr!fi;Wg8u z0k5hndCdLKdvk>iJ}UR6zjoJ!70IvT*z$1kdTz4IFe)kGOj2Y>b__ zduJOWMgAaiA*&!z@!&+L$g-j|?l+8PY5y3OOO1fjT=-#|KTmxGmq%&L2K=G!PwGFE z&#nkVXu-eVs^zx{_BOMpOLcE9(dd$APg|^70f0Ex+ayVjKn{~aEt~^hEE46b6nm6< zu!Kn#ONFxE>36`j0|60sKErnxObstzJH729t!L{@$SLZ48r4sBy~Lnz>nZZO=1aDU zv09{}6gvwIM4?h)%PcY-axeW}y++NWRd_Q;X|W|JyFVyh^|iVrE=7HYoQsuiM9M6D zKUg9onC$b`slB4Zkjv$p>92Is%N#>~&lJ z7KJ+rgI5KeJPRmlWpQ$vCq;c7 zs|j+%;CI4Cf5cU9zhLifiBc8X+7@0#`Y_wb(Yt7KTIx^nwnT`ca~xDZ_sJQ0`t`FZ zKROZ4pSyS54^VA+zPagp-cY3x3mvUlEI%F0E80Fc@_X1rv7p*&Y&7u-+Yvfi)SXXH z>W^i93+dR#2LH}?GR!3L_e2k6zM?PNX5sP6xE&UG0F*RIfslZ>fZ7uRTWe|($q zckUiWxyh8L-_$*!s{I}Ax}_+$?>p}(UH|Ft{U5?9d2d&uBz2yD$kmU@LSCO8B}gIA zS#WLso$L8Ya7Netv+XP7rH@%7V!WHHigC!lglwDXFv%6Z+3<48uO}^bt0}g`$tM_%tg~(m;2{cm!uWnvXxRJ{Vp;>#r@< zN1ez4QH}&mk%W-1T$H;@fRtF{7A#!oyxYBQKNp9!6bf59n~6Hv)sTn@2Ni^3$HZ4^ zHE6e|jzz{XM3cglU%f7W>aL-wr4NS}2vv#mqac_JD*@g}8_ zOXv40JAKx~VI-+WV%hj_=)#752Uh#oGkRU0L`9WELOCfJS!jn!ESZ;o&Z^U5IM~hE za(?_%k7#AOYZ>(e|6_bUFPb%@UR#?lqht`kNt#%LyhnRf+o`jWAH3n1`0vS zmI^!MUYWUU`GU+fkOK-yI)`I*>&n<MK3EiX()+jTATgq^X+HD-NryH44+-DB z4QfmdP>)O5mvl$Gk`I>CWQMx*I-!31zg9VnN?ivq5h$YJqgL<^m*<|{*Wr0xDuFK0 z>ID-)4h8~Szh5b7P6}(!w+SzW^hU^3Awz}{caJ1?wpZHOdtr0gTQA+mRfAg+E0eIL z3yA29knMZO5^td8Or&m9rCMYPly>DVD~oZYz|~S2dAvJu<|wv4Kloh<zFTx9s5 z@sIhH6Zl9nL9^rrA&jJ7Mgl*G%$+AB&ggkf_yFTw<}k;-(&dcoT;t!1#haH&eSm>5v2~dj#qGdS0kyj-|&z+JTsf+mZsD6EiWfRXr zF;gS^mAMxr=`PAT_{lgne1X!~QP7B@07~0Bw%#v;)K;xtMtB9$DkrO?drd-MgF5+R zP-19RI0uG=tQ>V9N(d=3g(W8h|ZYBpwzQP{nwsJ6%8(aLWDotA-~BiVuHXO zCfP25TJ)P1u{-hkpX5Fr9iy5CqS&TDkt{rHd-cj~f7|ryw5e&3_^970V2CH7n;z&u zJhaiWs(0KKN~E|F=MFFT-Tu0>P2hO9E5x5b;+xjPa;JynFNaT>T`odG(`xw5eb@Vf zw_XLg%QHZ;YlP2L#Y?C~-^?p&>ovyM{GEaZJ4L|}J0u(21CPoMaY{2T9yvgo$*tW! z%}I9CUB)eD4Z}(MU@RAOT=fU}`y=?eF584#k^APTC-AlJ3eB4Ya?20A_ zncQ~MquM5*S(OkakabZY=!voZ9?+rcyw^`mNVSZokVT-2BQtrY?DpY1L zDzo*9kh~C_N2JH~cWi(e@fIHxJsCfLlJftM$PD~fZZz{Ci$I7lA=qqixY!xOSZ^|y z_mO6V zhqeqVM{~+Dg%I{#wVocOQfNQjzgMx%$uRzJVT%6>tgN)}$j=J_ekehu5kltC21c~U zD|7cYd4B1_Dt`-4WiiT-MR=dxseG1$St&#*U}k!WOO0Hz)r8LfE~oGg6dBpfhdPKx7`EH$O6Dkp0M$0L$vN+;<+8dH^ZvQ!ag35q&KK_){)wN5lS zMP+glAwx0~SmSmn$%H^vBWBN@p}Vz4d+jl#T~G-IO`tWQ(K&z8PBDbz!EXK-rz7&- zfuSC7^QiDF%|RKFd)+#4Mo2;j@W`O>whe-?;D=IL(570gQmIx6^YE<*ksGw?BHXGC z$(rRMT;m+v1(jvQNldrXDZpD*9DxCNEAi9_~MJ4 zJb98AUwn}yP3UyG1>kIN_j%zUZz$Iu-z(EirQN{WQB-V~MjYSmnrB6W&-42T%kLevg8cUgzIp!qhfYWRe?(78gM9xW=TcZ$ zU=J)f{mO3R{WF|-#{maJK<+*_KdzjyO0Pk6;9!L&SJdaXr%6h;+r?;?_r)pmbI`!# zidKWgR1#ph!3QcOyS0C(IkSt>v)F_mb|3j~$HCOqSIR*Hx!`e(ao0^V(+H$^lMo%wUn^K0f_Q&mkJvP-9S@*R2~1tyEtA z9_En&l;5iw3QylsB~+Gg?0GHvM?`1+WsZG@@y~Qnv;W!CVYPVoIq>8(YVHp!Fvnjj zJ!{+2I7=G=CIAzHiE_YI72ajWsLGr# z!_8w`xzq7)URn9=)7k9QAA_wOy~`N%Fc^RT;5{H^P+q;i>GM=H)XHMpRqnZLK2J#? z%4ZXR6afQn9G+CV`&PKyD3KYC|OxB<+N@)X24faI;ReH^F3BCk+zf zBtc0OG*V;}hRO3YoXtYE z!VNa{I@_HlTH2H*y;xGM7|0;gpp3u-5fC7bX=Hr{8CD<=q!M}tlz_NWh57_U704E7gCKV4Pz`2VhF;JN+lwSDmm~H5mllhpJosQRH6#i zN{vb-!Vf8I>vv#KMw%uxx3}}K@GfFORsby8%l)0H46T&i7rC|;VVo^RbEBLuj;p|Md6;v_+BZE^SBU1Sh&;lg>&oH;`;?vbV`&1Q3?r{5?LtnWBBpL5YF zGpy^_3s2b5EB27-o0fIH4Rp|buu~}RgRXOT5OT!49pRPh09l_3{^0oIn0YFMD8eVl zaoi68i~cp#@e&uddC=oG2m+!oqA}T^R;v>PrN_Q8{hqnjC`6H_NfENy53%0ubaNvi zQKkhPST_8&8Er=Q z`XN_z7JR7xqCV`vU~?9FZ5wKw+nnP8#C?T~;F!j{nZ3zlV&LX}gO{Bqh#B}EK0VG_ zeBWULzhT+(@M_+r4+p69w(LWl@OLV^%OU-1^V8517cuxg_}~7#Hcs9dSKE`x&3&Mq zF?ncH*CLmT*W;%~Py%4%>K!IGQuaAa-w2K6jboVdXvy_(^HC4>r2kuvSX0LL{P9hPNMZtBt}K?O9{B8!DVjEn-rG*nO3nP|qe*S66ciliA6Mh2lmq_FvJ!z{-1T8Qm+(#ixu zP(z9uaw0?phE!-`2_}k=GcyDW3#jdN=ygca9zmw5W*Q?b;AsjTE6OQl%DH7d;Uq%H z!h5z-ty0Ou3kzYxAltC2r6;bCwmfYVS{Zu19&s;*Tq&=LNCbKJ7#r3*OG~d?t!-Kz zrBxmx+TgrrT~1tM@}y$M-=mmZMlIKUyR-~$9){m5=aDO=v|;m&&F8tfxy9n6M?{r~ zix)3&^5jX9B;oGeyR_SFvMlR={RY4;|5!OC%*fwfn&#G{E*Cn3<$y?_wcO{hNUry|IpIA&v^s8 zI{a|Ve%&ryyZgA@z5Y8r=+Rr&INU!^Po+`KxOdP+-0*+9@cKi(Q-5IZ?YD)F@U?H2 zzD)q7Pg=6h=@gmKbsD3Fv9sb9giox;WrE_NrVw;95uU7+(o$Y46W!f!qV`8&4ry z9&<`Dc2>^su_>iI?$mEqx$@0Hxuf)nrceS7Uwz1}DfDFHLB0d2X-N5VfRqpN;jAsg z9$7}7pCmBrxI10;%vF(Yc&iN?t%#X2MxwL(ej{qCrLP?(KOlXott{ ze>Z$hczJV?3dUOx%Y}9r%o=MD_5}1K{k^AEdgxj9TJv6>%kiI5lV=sH2BW3dXSvtL zI0m|>dh+kWTG@dpBi2nb?s@Y_QbRAB$i0dWXV!Zd+|b@(oE+-z*>es1wI~|$z7ZpN zN`BTW-{+vEfq-?&7Tz)N`L#ggL5W>i29d+F!sO#@baWryzH^@=eh%D#8yjP$zj>oO*f{-cRS zMp%ugPFJYRHwYK%$fbxR&Jfj*PzVB@5oQS)0i*C(jeYI#Uh z>3Phm!oyAJ45c(_mXgE?olb`&P70vbeOr)N4te%j8P@+$$oj%(CBpGH_lBBcJc&){PahKeXiH!hBfSbr#RAot3CATGO z+U=*+)1P2wKJd85V|PooOIAr^$*z^fDiZsW+ub5!{+;2>j~w&t z!?q~wD8BrIF1@Ul{ z$~zyv$M%y4EI+)*>eeRy@O@0E5K4do9coOZv9OS4{+2awD@sCGRZmwlEQp%#lZ*0V z`uRnsdW@^L;)~|z^`QFHdF5hKQ95@_kb}jA`$fgQbm4sc`Hpq(X=K_;i!+o~xYhU= zWmI=arb2(3tSBFQ?Z_Lts2)odw_>uF%q_1)@+AA74lLIvW(deggzWn@BW^=;5{;_q zroXRRF=-zZBGa+UqOezbWNa0m?o`%V<9i-TE2K6EWv~n|QtUo|#m-mXbF_1au_BBH zr6W==#nVbDYl&jY@hiP--P6uX(UiUk=GPZYG7;7AfY*n#ZnLq-Ogw8+Igu^~&gwHc z2~j($XJk-S+au19P78{hN`5L@^mFHuqH3k~Y1OeOy(U}ih|KD;M50Wor}KPA-0B6? z41`vlY?Y`2V?wEPRq-w}aU_1`)ywO$V@Oqjmm$-#6_sk!`bpif*>Yk^<(H0H0!*xw zG>J=NAw@*&%9OvUvfU*7m;qyu zO3{=S=m>8#WVE}BvvL=8ddl}-ea(^O5{!qmyUVQKSz&o=i+$VWSjTaw(Y8S zhEz1E$_Ho5iIeH4@+>7WA#=r=Zb(eVb8qaix3|leU$uGk=pnsckL~Skq9}^vbw*M4 zJgs%fYA_|dOZh5{Z42f80vE+a+st*XV~d3DmC~FLk*3LdWlVEHU1zy#j3EpoGKpQ} zE}?7hOZsd|_*Vbg?KZt$FTRd)Ox|)V?*QNP8I4Do8|Tb&w<@<5U92Z#-dS~9D)Tp^ zgq#Vpx_&*+a=Uo^wvUrPRFd!}x%gD0($WH|v?&kT?rmH|%(EtuL+I%j@>_ zH}2{#i8!V~RB~&PPKc9B@Ur?%0v2FY5{^j$VF=?Lc1Hmx`-gn}{Wh)bHC9)bX}S*W zPLp}%xN?%;M3tTBb z^G9tiD&MbyVku7hK1Ybj2_|#vI-#(tD(z#G$A(FlH`j$+30j|ibu6v5_7M5`!qGFx z+}Ax8B^k+zK3#C+?>+fm#r)4BM`@=Q6AISrdZZv<;ANI!*A7!4f98<%gq6?rJf~`z zo4Y_xpA%;wTev2!>QD+1I0zLXB8^mFBd~{>#^?mGBM60$VJ`mNMza?`6hc~ zF{iQOO`0CQ8=gc<# zq;f*q7jng5#lw&yA->{r%mm$9xv!A9iri^x@_E*li&we zS5-hc@6y7vCQw>0nTd5trUXvwGrd}voU}@R7CsH}`zxc9IHj5>)Tl@$3hT5r$Bj3u zj)FC|Fkqn&S|Ov5(DU&34+vHd7_A*JcE0Ac)x~K@?r&|xf0m#z4$vokMh6Fk-k9My z#L@x1mV?AX7%R!AjcpVnG^jyHaN?r}ZLG0_9VG5Gg@rAO^D?7b8 zn=;e!KToxoA4ANOM;MHV(3Zq<97NZ~-DtCPe;L(}H@&HWkB|ZfVoPcx(8@yvLyR}T zQ9ezfQ942rZ-7w-Y^Oh!|mP8xPc)zCow|Gq*!C7^uoRw=qXEyn+aYaL>gCKh(4w0r%8-CKl2<6sI4FjI59ba~->TK4BI$kWe?V*jdDciH^R4;5uv$!g`g za+NFbM1i!sZfa!mnNS>iGIeOd8nBAG<7LtTV(W|R%zIHCQ~aF1z^Nmm&rCa0EG6}7 zvcqox1sBqlcdoNEPEXG-uc@lI*x9eYN9IIs-RyZCn3s!XYKWohdscA+LhY!N%;TBs zy(He5)(Wjcw2IJ5BX!)v_1K_~M%W`oGn6!iq+zT$-XkVfPELK#%6CzJ?)q>ZNl_h- z=QmTNaRALc1r$*s(X-c2zL?3rk-0p)3=>xK{B)Wtk{1RNi>q{&I6FTkvEWJjMadO! zP4St+UtuO9bsLw;h9=8H>Fp~Dm-I93lan%!Oq5FL>5M>`7~*c1#-om)j*rI>)z7Sa zlJXX$Qh06pam`od|H)@&^*C!+nRU9JlBeQRr=LF~4SD$)Cs*K^tSzN-;^a_~l5=%Z zb6x&T`P{Ig~Q5<%%DaRy_(nLa`g+LSG z+9B?eO>?tNZ>Wj-5hH(q=lQsiAhN({V*P{(kdcQ9M%a-@Q%7h6wy+S=A+o@>8+2MN z+(rWtDoi*cvJB?PAi^O_E6cP+><&3n3g3%ehx)#k5c^TdBbpE*BW^P*TMA=vvR+K5 zDk((G9QlSYr5mIk046WUD=v-$ED|zCadLdjtAzsvaWa=ZWky z{j+Tw+p>|Cq}goIZnrWQ&W_{IYB||>Af?QVl*Xemo*%~%52J9>de@ZmQaqN$3^y7n zCOt=rbm1T_KZeXAd!2X9?De@A>lS!BagjAltw*N|+>ZpsK$R(VdxeDhm&#gwS?ulbRwLcAK|>iRLG(tai)Cs#h1iN%r0-sx({V`!8{ zp=t$WmQAU`FO@4a1|1W%CZ1oNP!gR6G$NZ84O-Hop)Cv=qcs!#sFa(+BP-n8d|Kgo zThO`8w0;7nGdIwPJ#>Folwsp1<67c?u;Y3_>QKg`HZW)UI;W z=O?*NlxrvDM(P$RRe~p%CJXUorsN?b$b>20T9eDkwBu|}mdI^gMor6i-B?t%d5$j< zB}G+%uo6|<=VCh3o_7(MLX?&i^F>Yjt0PIXjdjy=WDpY@4n=-)MhGU|msTGn(hvjN2A-rF%c^8`R1#y z`S$zo*l-&>US6eh_W}3c8K8R|`i{lPtLJEo%z6rA;+V0*LTbgRKjP$Dp98f|x8I>R zSfTx-1FIlKY%OI;i4eKIAnV697S|NcY5Ng*yAr8X zq%bljJp;?eY1z2zO{~DeKlTX+0czk8=@1nOh$NPXkWq+;Jd8I$4NqY_V7a@7-DzVr zIz-qAw}qoL$FE*7Krps!hDtLY4pArj1jA!G1Zb6dK~qF3LMv5pF$~4|Jnw#@JWi#X zoKgbaY83_&B@6L-+%u-olb}K^>yBT_gxMS4%pw{ zCk(?9;Zr1KuI!rjhGAi?vp^NIw(rZdoob&t`{E+8nT$myT_2b4H<)bQkgcssByQCM zReUb>94UlgJoY#_Ii9fYO=I#pjzgo-pwVdHx-Kg#E7*3dYfi~pfglKjY!gkodB*d+ z>{*`YW#>|&IMs(|;WI8U-p(4Qd!~AwvZk6hrdcQ7MBJvlE^u*NWqyC1Z6fn#R$XeO zy6VDbU6)?8-}%8FkH>|~J%tqFo4o4kDACkO(f zD9T-9#7SoP2PSu$m$E5|4VEQnNgQlOL1Z8R#vm*Y03|?~L7afGb49|!H1~?g)gtAp zJ6kaY7ccsm!*pE|Z@wv1iQBsGS4Cbg=~$3*N%hW7ujh$%W5rb`i+Rj7Gx2Iuo_(<) zbbdt8<#B$Woj1z!ken1ot^p=d-fE-g(}+@B)K%5A%c~2hiH=nHyex{tO{(Nf1-{yB znT$l6mX@Qy3ZUgK(QdS9OAA+9=)|p^u3323KdbzC{V=ml0GUOPV4h@d=7RW4awqwJ zi9#{?pr6-cve_?HehOljjyVliR$Av4J2jqRAZw@7WJ@CwS7{VT-|Sr~u8GgcPu>o5 zH^|vFQx*Ivk&)##e^Al^vhpa((1mBshC-(@WO=*om_AcX-&m3tb>4p}+eWer<7+h+ z>R+>tyke^|FdFx9xgg1*KcM{ zJ`EEafs$Tbn0Mm5UrheL`1oHU4r|8DYW<5T$BV;cx(7x;iRjPWEE|+DC@ru6M_4GK z&_-c|Kv%}cx-v*fyEyJ?Y@JKwp@%1Ur-!uFLtIPX*cM~o$MZdm<+0?nX*RpudHjq! z54TYd?sN3~a}J*W2f@(};n+thjoYwj+BO3dL8wr}5Pv^Hbii71ao3xe7Dz{8*%Hgh zq&#(2w{^8pBTuOV&#ic|I0oT zJ(|*r@p#O^!2z94hi0?M>gp=n+Yg8$#opd-=9;=_ZByKcdYfD?PU8C9tG?;=6F2QCnJa}vS`ycFV~bxa zzAm*YPAzwpQVFRWp;T1(9cH@nRDY3Q8kd z8AN`(+LhC>P6%;h^8dEN9u9|D5cgsb_)IC1Eo=(0jtaZq&k8(#S(XVj6)lX}sm60!)EAn?><+;kIxF zJ3jUBS$Pm={JL6>CbCl1tDbq$tch0gQLN|G3N>qnMWT(eJIQQ;V6t=7d=_2mimCZD zd0WWnSCRcLzoS4_Rq(|wQ|xM)f;y#%P3gX3+e_cIPRKAOKU;XSxU5R%ad|$@#~D=a zZJG{5eRgB__|pWo!p&6LO_>desn+E4{JhlJJD-8cb?h8aY|CX#H;kPkrj0-4xur1WCrz~YC{b*aGd)x!Bhm%P+!9ecg%D3&*_P@zZAX)KkS1C3 z#+zL7d*Z)*{4*FVBuIf!pp`~gGEq)5weHe2vPl=zfG`m#AG}l4;20TsG=-*NOTthi z4QOpR9geVDOY}DG@no$-=kWuM@89L0hNm13PKZV$ROsQ@7DiYIC6QVnlt6o$Xc!Up zL)1WFEj!4Tz-U8gA`B5Tjt*IQ*LrCXXE}OLMS|pt(xh4U?BaD~br}z61}!zA43MtC z?b>wiFX5ez36BSiPJO&6q@f~Y7$KE~)FC1o6Ag|S9=M2ppJ?pk1_8R+C2-py1c6Y9 zr3MYThBjk3-i5vI2}c2b5XNs`AsUOCbCI=?DT8|QYO&~+zR%R6zA?xM{B*-YWdnsM z|I3UcjDaW$>G%7*eEE`Yw@atfVQcF?o;PMV955P*6D_v1Ne;W=3(- z|M^BoS0OT|xp6-4`f46B*U6#D(x_fzSr(4t&}=qoHk-Kxuj6Jhc&nR2QkTuX=QH-k z_`aVJzFKRv(kQLbI(Lg-=k|RT{eEpY9TLgm0%d%ejjHq5u)n|puM2f?yKfSzn@{o+ zle)c|miM<6_GmQ9ev~SxhIvQGSa_}RxnGA155kuie5)}5&b*db7}s?V%2r0t-|I+)XT{BNyrio6` zh{lIxY-E=j+L`1AlfSH(VnJC_D?x+y~vJDT36Ow#1}I%&JPqCb1u`QpqO<@&}&j|-qmhLth-CR4AS zD3AgzJ8K(Hy5&XsVWQ)o^H6#YGg89EYX5b#nWPt%4^FShYb(r4S+3WNKLRpRH$9lv zdwh$?ZoTk&!id6#m5XC?gNw*L-RIezypMDq6lpfHg-iUdd9CFh3^WKUUQg=?v;m#E zxSu+NXXTPhWI8F+2(%B;2>bzRbc!1GQOyRHw6UaxF_MuV&}kSV%V8J^q;QDrCY}~3 zER5ygMTYQnKo}TwJ1zqm39LvW1A!SE)KFo24Q%ZI0*jD1po5Cv*OUvby1W;)N~`#S zeEgp*ag)g?X*r5a2oc4r3LB1$n0OMYb#6omXoLi}Y2&Up=sxUWh5_Ee0MA!M!x08S zgLt!mG#=6Lh>U(oMW;N-41{EBjt_+uUe0GSau% zY_hzv%$l`UB6))#cGc{8KE5BjX!d=d@pznB@YcC}FOFB!+%H!R!={znwOOH_q33uL zE}a)x;4Hi~bAGD&uk|jnz&v5+L@3#=z)9pvFOw;$iWO8{)Lgt_Rs+RfePC&Mxl3I zWbQ@t^LjAPTojcSY3;o^Ty0WJ6)p2CpYpMb+x|xcfNVu7FDKaV&*at2@y9fjmZfkz%wz_Fgs9(EX#J$IL z$-s4p>q;;|=4L0S-F3wrUH0~xAt>$NrE5fS+$rC7x$?X&g=W!%fhhb3C?C(PWkh*n zOKzVY&r_KtkpWvsjD%1{SV$bp&YGG&!(Ftge2WR)2!w!e1jA!a_g-RptJv)pvfV{u z1A@qar!n$Umm*FR}?Se?~E3LpHyp8-~n8X{Ars@qYNA&4vs zPYNPoVRgG$ckd!k4)I^UfW##=BHcKpll-MGSCqfb7{6=#{5ACVIiWP8q;f>TqsF90 z%z#cpI~3giM^VJd$q75VJ8W%lv9z?rlP6CYjYjP3?9lJ`(OO?v7j~0z@lBJ{(^=ql zpcG2v7F67X`_NgC4hD0Q`p)YAMI)wkyojP`V%!iyWTb4>U2};5PP}qq(er+PoH4Cc{0s|qoAW2=b;&P5tqvG}_PoscrIE-kiDN#hmjtc_La#o3=; zH;NQ{WIb(WvU7RN!CCrWMOrwIuel_S!1Fo*H`))iA-8l#%8lbO87xmhN&{Yyz#84lur^axuhf`UQF?_ z3t{q|ZmwFq9&yhtyTOZfWz*k6Fh#*zS#EX!IYarNoNt;+$0sr(xS+;M zHl)N#Ss?{7@zN!vB;N31$bD4DR;3eJt9eD4{OKr!L7!mf6{D5AbXMFO9cY( z!;piq$I&-mGko;|`*e?oOE!<6K4W9K!|-62um1c;2G7SB8Q-I{g$^YCiHFA!?S`~h zY~)58cge=M79kd)6sVf{w-_fmR~#kG;f;O5!huF45W2HeWY%qE_z}p|=?~k#AkcRLu!ooH-MvVc15|Y4nkVA*YQVU1B z2+=|dfr^vHb{i}$-$86{vA4X=csxdjK0+((#Ijn(+vLl+HF<6?Ha6W3xx7f|#=k4N ziNgC!1V&m25-T`A;N0*L7$#8noMO+U+*Y zW-}vuL10Ymf;mcv+#m=D`~W}jY6#tXVHU0kqn&b4fL9@7+dCpVzavm zuJ5liKWFv31tziRV>bh~QmS+yTTZ3{%?#P*=NkNxw`-$R;4-3E(OX#F*k@ zqUKqqpm&_Ox$Z}Gb$5ogHC^offN`~W1)}tkB96aTuk0u-bc=&JQ);Q^M3n-#3NDsQ)$5uj=NNn&sux=8{vNsYixb$!R9MOjK{1c*=}K z!bN+O5d~#DHN#4!Ov=jTQkJvhu`W8lF&mdl3-xls6OjgIc!5-RUc7dy3^$Q>QDHDO zb&6z4qHdrp&Beb(;>S6@OCp3$o|O~2q{{!KymR-vBD*#tO{y<8@lKbYP2Y;qZMvvE z6}8m%Tni&tR?oN0FPi#wNwrr;>SA`1@}74qos5%rxm3!ZbtkLR23(}{V=KRFA#`hA zcrrhxaH+`8m5AwbZ58Jntu@NTv#v6lNU4}u#MHP3E~Jr?UBl z5GZ2^q{f{1=pzqv;?Z2|B9x6MA`Frs(FRuYDUxzBNg<^n67tPHGAScd9nlN#DP}U{ zGU*)3WV=ge+H`Z0ks759kyL~tqSQc{s)>&^kow09!jqZ4)XWl8gq1 zNJlgTG=;!*@8C*7lvvRlBXC+vwC`>sKlmvl%clSRw=f=}&{$GnBd}ukZpr*tbU02a z=Y_Ydd-KAzH*@wXt$1tNa_L%=OIvxl#G%T9Amq<~{&ze-;K`FGY;QkgJoY&{IwA}s zjM15%?d>6T-;Q^=zcGd| z3<$%3(P%`!-_NXe)BDocysqogXf)__I;^d&(P%W#TI2gZ!{HFmi(NA-rHG=4AP5+b zLbuqTex$`Bu^4BJCX6jRpPtV|DC?F}e8b$hyg;TH3y!cc-?Qzre>+_yAZ${g=?uBw?0d6K^ z8qNnZ_V1aK%T)1m#&ks+lBHwibRM_wn+qNAXmvZ_yK4vX<~%6mGI zoA=GsayN5Jiy?RQCo1<>WQ&O-^-oV}xrlGNPc2G7Jx7Y zfyM%qj$kw-JU(W0cu1?cgs__kX`{79Cu5~-wP>!dV>b-qSaNFM`{QHua7ZL1tyUY) zA0U;%GT>?n#zF@n_E4dZ#sqtP^qPay0BjrIOe&YFWOg1DIPt(Bh>6@}lTT^%PKn{7 zP9tS=&rx!etEnjKWV0;>gAy79gfc>!5ZelHn=Z|b4xOzPqT>L6cnXomiWE*1;-~;& zKq-q5L*zktY!g@(O`{P@t60q?uv`=pYzM2;qr3G8)gRCwjpDq8Bb1Jim_l%sf^QX( zw1(6*b54U6z7_P)78O;9F(GY`6@v$?a~SP5NLT+0FrD%0N=#RW*a3nibjkA zQ`FCzQZ275as{TS*xe@2xmYoz3WkDSwBWKil}~HkDOH{|A)}f?o+ocj638iRVFZZ8 z)mV|7E(pl+|HSck=EbJ0qb|KdF<+)|ZO(%y$J2Oxx#V;kXVuwJufSPgfgcj))yK1u zWO7K%K2st$9hZvy5dxX-*(tndAr5*vf2MPFLO_-cm^V+ zXaUlSEwl`=RkLwinyYtcZQRE`IVDmW1_Jyc3b0X0eo~jq6!KPTO{Fr(W6qjM`Qf&} zq*nD6Owo}=N@1c1tu+Vx2ROFPo%K6(dp({#d&XeUXK!zh@pugA++8=fw0su05*GCy zV|F*lbI!;$;i5)M<$EV@zARx~Oe=Mloc&gsD2f0WCg-&_SeDEzc3sz{)oRgdwQyY* z$8oT28`pIKGD}_G_wju{b|vro1b#pmh1oMxOWm_JvDB~WCg1xexc^;Xfdv+L9hk7p zjR!zcI}nx?pYz2|g|n2UqVQ>IjxTUNuI6fafpd`vFjw19aoy_STVCOF z*Ot$NJb%3?$3ZFYggo#1n}FJUPFW0GD2*w&3A=$WOWgh-Hr`}}VS!u|rPC!cR~87+ zBwSr=X;J9fGSy=j{^rpNvNSKE5a9BoQ1;$6_ZtL4=C-&dRS49`j8Y_))fb9SC6jtG z*^cY8h>0mF6~4uq`27A{(QE*8Vw;^jTkAM3Vc83eL5lc&q%a5}v(J^^VzqG)5tzQlI~Wrl1+?$9u~!^~kzh+?`Z7ir zGMswq$R&cJY&$*dR6^(`-X^l}1?TElM2XN9B7brgcQ7qO5yvN1D175HHWsa=2JNj5 za=gxP_k>Zu&#)iRRR*C21`Qg7jxCpM1A1toECLJ~=fMyrFnewXfW z$Wh=!7=rJig(0@SEfWFddao&;f;{y@85iQF6xW@!ZNebn;NXDg-#+KPci-dQy?cyC z?;?cc#fxuIk;%(0**tI)))fm}4O8Qx&gfPbZpQlZCgLI?0N+#@-Ut`ksUEQ~k5$X4 z93NO9rOehqO2sk0JF;8J{mJ#RXW2QGK5TrN$ zjYUeVoL~2;@)BkxfUk2)(Cb==%&WF;=t8Q*il%$u3kqowt0+@9f=0xItt57(oVq1W z-T#(KPvjrh`t~AEbJlcAO8SBlb@rR)Y*_~6;$6$m;p}>G|`B<(*^q_UG&DxLdUMXZrC3uApiDFGH2IMz@R2awvfn)-= zq!sVPvK^F;C+8@PlAY3~m_W8XrjS;#-Idx$QU6(45(_DErLIX_8I^Wc&mTev9LLG> z5rq*-t3=702sXA8pNpd0#YncEpR{DmtQ+%}EnoW-1V+SebhU}C zYz?4^-31E360x#U3xP5MMQlxECE1b&90W>$5{3u^#^iC-lKjVGTD}l2PiP6*NbE{D zRhkzGzVyFDf=mg(@}gQK*n}*xKcH&rwhlfWDhXaBj#FCO$t3|ur zrrB&^NegW>Xti6|mW|Syqr*e`{Qc<; zt?_&xtz%1DOUjaBK}d;Kn(^3UJofPX5N!mG>(Fks>Gis?^1&F!qamZ=kiZ`yg^lal zNm?yz+rhRi9NT6%7;<`g!f-T1Yn{kP4II~v%P0!*JRjfp5?Qv`SW90PxFjYvTFfDR zxV_8mMftqlm{z~VdMOU`qVSm#n8kRpU<&hSW#euo&Emr*H$9cvUWq|SjZr=fPtm(O zcqQ2%A{uv645^g*Th%_mz!Q=B;IR^Y<*( zXhFtON^@{r1E1C6e?m{`fw%u;i?RM#QyST24ZO3l?)401@8q7NF!|wjAc@@*5!D6mDal7kGWJd%Yg(>vvdQ?xB@N zNQot7L4jCM@TE%5Dj~;gyJD(?>?}JCsxBVVMWZo>D2nhrkK^NGj*m}DG<{W2oL$#! zaCdjNpdmnTf;$9AaCd^cTX1)G1_{C4T?QvWaEIVQ1{<97ykDLFg5rXz5oY$2#FtaVItKj*~ux73Fev_*#FQu?=b zIVL7p+fhnyfQRKGjo+nM2=h#mD@kOo9z7dMZum^7aCS!Lrm@5lo@uOibNDIL?YZ`6 z!5qIy*=mBKfo5urfNjy`sxj`5Y2=c`qalJwd|3M%rBDZFm^56QxyXUGuN)~hLVBDr z?RN+oS_w-rIuk`*_MiU-%2OCDh{?IT{t(9|k^Cusj9mRq*s;)N85W#wj6w@%QjE=) zBthzg!&4f^4lgH8->-%9J{o((+}VwtwdEvLp5nV%2GJnVA@jsbSqno}nimvOP@L9xrVt=DwUp8FpTtrJLr z5Sre{1*67>24HovIS(l$XX`m!H4w_O<@dr1Y_ouhc@-1{US-%hI?mfQ5&N3GJ|Bt! z3s+ym#a@n8wd03p5C5k z?^Eg<#1n|TeR)v*$!u!jo`xlQAB2QO)c^pg^K%YBv|<1rh_{@nJXB5Uz3Q;=LrHTV zERkdyX}iO^M~DCahq?8J+_qFHMy$#1J_=vb(;!#q7>;u#)RkS;*k${vW6TLDlCP)4U49To4*QI);ZVICCXVPqT^ zuQvN`LYo-R*DO)H{>iU8DQN@~VIV__i3S}#Zd4kX2rI4@3=t{{UVi#fA;-{;PJ_Cy zaj!{N{MWTDv(WZ>B8E2={GEu!CSSDiE6!MoG%Z#kGV<))Hjlk-jzKzQ&FmJ?--%fA zqXMHJNqmG3N`-J&Ym?gQYREl=?tFb^`{;SP0&v@30_ny1&1FKov?R)xnb?vD*d|oC&v1AZ3j(|IlPbQ|7M% z32Swy;)ZrqF8TEcWynq<7pip|Mu(ySX&hp}_D9kC~Sdc;(9WEy@^LCb#$Da|v_Ye3$JN2PKr(FGscU?SkwStbK+Szz6iiMu@k*cpIb zdq6HaZ~UIQ(40Dqw5{@l%?>}N8otR|J;IBZu%$35C{|ERvX&xDy~o@cJWe0eDBp~5 z5Uor5NwkOwe$jO1J@YZQ3r`Q{OBL#CEe7o-G7WAqIzgxDf^$oQ?I=E{^lkP}Yfwt2 zSz;W!^c5e&p!!n9N>}RXtAp`reqg-PuQQR;>|ew3U6mlWD_xiDg=TTUQng{S_X?~8 zb=Ym=8?hd6F37tmaP?^dkBv&2I3K?9B~S_*+gl*$$=w(a?ZjLN__t4-|5P=r7(7@s zJ9peHT|1}7hz*D9c|EYj#KIy@7(r&y*3mI>bxoGN0iUxo9OVph!@D-PZf3KeQicpO0rTN`g42mSV`@tIysGwkJ|SRy z2SNiVdct1!LBNALLthOH{h$=-P1+|MkR4S~bF09Fncn9ga?-iE`Io!HXdY0HmG!O( zfS!21u@c)mI*PpLdCIq}lx|%zGjk2`-1LsnY#iQv6*cm|B>+K?&CpGVaYJcBc7kSr zn40~43!e#Azx$K|fOYd~4vbW<^RP;(M#5@ueR;R$EC4WwR*nUOduES=G}QqiL|gu{ z*rCML-p}_q8>I|@N*GL4*V~(5CS>Pme|@u}K`9pSV}BW#VKnUV0iKldrT?8h`dqXD z51BzcQgfn1ZFr_|w#MoL%P!&nI{cH9R$b1Dr)`_}>u#i@k#cIdG3qVpnfk(=J!Z9% z^-77}1-z&PvHc03L+hFbo)W08VpIc0Mh*naSDpUKk{9G(eJ5|gN3iQ4jNAVv#UszKBpT2QO*v=6>;#{REs7#Q5i;AwMsfwIRQc>d zRp=!@v=<3%YV7G>V|fR$z4V{Zw41m+TXE?CkqK zYq+07*Ro2>mbG6t@pP{j9g$8pf3{510jO+qC`2x-B!2HO3 zSO*4C>(1Qi9Wsb(9-+J@QzOQ(6kowW$*5x+*8z)=Cdz@3(Espu@Z6)54VrG#s@LUr zyz>-rK+8w(73(X>EAsBNUj+Wrx+XzZn!0edW#^ek;EQgq(O z$Xz6UHgX2Y9jIju8 z<})GUvq2fsA0*QleA-4%PFYCH`v&cxE=g_5u5PQ1W=%XC!|eW3t$;6MAz>HX4pIpc zo2gzJnwHg2EAoK@BiWjypG9Q6VPx;fiy(l z_AVZ-tqQoGPXt!2&ugn8v#PH@zzGH0Jo?YCiM6jUV)y?FUc(?uaGF}aT~Nr({V#!#`;6q1%0K_=fT6ES%`;y%|7EGEqWRpPttWUWcp-UV>k>=n{Wa z%VItJO;H7aa2a58_NFufVo~}p@O>kY+AuPz&)7wuFD3uOG=g~yep`FjK$bw`jObnr z=dQ9i^n7yGcZ7@bNjUH|cgJaTb{0oZPw)9Jlh{s1?=!0x4G z!FWM8JnxS{30`k6(Duf9@y>Z5M_blTYJ z7~(KOgj2mF2M?t!iN9nw)8xns2a4uZ-nxhgi=0fhtXC?|y95uSt*PYk@)mJ~r1rx_ z;Ux^#)vZSxMhDi_V@FP(xe!$!mPf$-!+barKbI+*XsVK?&%No{U2it^1N_a z!Y%&@CdeA{Am?0)w$^oY_m8ffNvL-9Vc~cXhx*;#Y5||&<#BnzZk!qGI8VOz!GSVr zXcKO+j3tE(YLc+-rfyKyl@Y`zYlug2Z|{3`yQ@_QlPcwPO2IR|YbA9l zn=<7D;I zyw(;+H2^*Vvf;l2e9SoD9v|%IN-z?+J@?~DlGx?3(_bo`w*mG&Tes>p=~lB*-WhZK z=i-=uWl>-$mMe;*)w*L_y$(xa;i#?sm%4~t*xE5LST1III!pIj(EHR|U%EXzLi+Xu z6gGPb$VQA-u8$~KNa#7R_f5no;Fh7gnfH9F6AXTP$cX*oca~S@7MOD8S>SvzW)^Vm z8JJLM;_n~#_S_m6LlxGwzP2-cz)1D-Y$o~ugee1I_BhqNww1QekG*f6>zX+!;#4&7 zz@PB~9x9C>32*la|1K`ThGZjVDoAku!Y5K>6CM_7|H~ij0aLwR>U6>UY@IZEyEU43 zXhj)J>^JV?41k~kW%CW~KZy5spoi%JMGgtt$TRTce23TRV5oa?_3!v&c9bU?*m~54C?c{C1>v|5L4IFbmuw{Z0~5) zW$fvQMFU^0nPUlx`VbD3Jb)Xq=FtmP8yY_$)ziZ|f<~Ytn(4QW?ST`#4>zD~o)@B9 zJ@@e&-6F-znz58r6xSP`Tdu(8H6!*Q0JJOc;z5Vr_27ix;A?*s6;*7Bx$mvo26{j+ zYd8p|M+`V`*VBzm&sRimQ2=jr?y$K70oi9OBY`CS97nzQOD=r1)f>8-fiU;?a$^?( zZ@xW`2V|iZt{1QVly66}z#`C0h}Y2SDyeFL$o|ft?DJjg+mKc7n-?yYp2|#ae%=+)Z|@I(?8rSGETQS|8V!tAVw-}_e%X|HmVS%<2-GlvO|q9-`XVx zWLP=*CQ`8%Eg4!aEl;q@zw{Rv5HWPoSr^zOU(!U38IhZx5A;o;sf1IORn!1lZCYcG zPl$*3V}YFkB=C;EW)S$+0N$*a%Iyve{Z{dER|QZ~8!e_^d_n@skD$%@@-_!J8pL{E zQ@o1~K@ky#OMmmJksqg0JqfHjf0$rpvEiGt*?~rT!|)TG6WkV)65Cxd^8nT}8%Jm= zprGuwVKRX=TY^n~Q(=d~09dCp#}h?M!f(ckpL|3!%#pa>MRpEw;h>>H~ zv&A%o83s(jE`_pKWa~>Qf-zh7d=$*_1frF% zXWpJU{jR4zp{uBhlZBVRcu69{R-*%O@%d%zt(U)MV)NX=#>&lph2XI{H96eccnz~= z&Dh>P@Ag)RN6-Ghe*O5ECC)O1EBaETK#rxQrN!&{?*~sH3DAw}ooU!XD`(F>WDnf+ z_WJbvxYTR;@4?Q_0hnr!wil{r`#zk5XH@EqC+J)gh8f(f=*gXoimF5eNe zRI~Af@P%_BUrHn-BF|h~Kd|$iI{??SeCyKwL+i}S+J?A7o2O$)a~emm*lt0-Pho2&^!$RdLdb5*1Pv3)Sc8^3_Sr zGJN)n*?jW}rw?!-G)~sEjBfsDtb2#!s+-te59FF zC=*h0QjShdG^TI&bux+7G?axig6m5yg5ULmqw{fEZP6<0^HH^D`|E6NTL6@BbCvOR zmC^Kt=etcvpC=?$!b(6!Zrw8H;6#u+4~Id+Cxz0PZ}0+^Wsq%4)K@|%&?885ch z#BMZ##F=y8nCH?jLy5TrpO`MjB^rU&(|JKpft53yiAtxI{8w+pACYUppVsH#NKJx> z8jWanJ&7e^IcW)cd~WP}R#Cs9GQkA~8<3BtK!#=O=X^ z0fq}o7Iq=Ii$&q$z**J6oM3D@w#tVnnmJN1&QEUKZ>i?zlEp3)Etez~{*)$^kTX{# zIO0*)DRXWUPtOd?M)_(@(8jS75K?-+(L2MIEy4rdkE(~lGx7Jw#3Lm!ecQ79{4v9d zP=Z{cm1ugv?7L083#uM1GK)>KE>Dhfj%j(K1xEs>MOO17n7mSS#-HjULK?^XZiPv> zh68XR2GqXUj~v8Z!xp41 zeCv6rcKkq+(C&YT`SkR(*!NXhknkt1ONCq&YH9g*hx2*dR%x zgrK`1WeVdMP3^wfJuMc*S{n72oMcGmrm#0}FX8kJ5e5Plxz{ZCgPz(D5!w*$XEk0$|Q?Y)mE1wB_0UXF@i)RV@u zI}(S7nS}|v&CR$4U`O;Kn}Avyge6hc_H7Je-+AqNop9a^3g1zMBd8|NxW|FP>)Kys z2qu{%B$m4v@;u7NgDK!en{_GvYai(lLqtEP4Yu=ax7Pq$1O7g@yWaOC@QtV>UgtUy z;;IZsGX7qgjg!5;zFizN z`?Cx1;PyiinhRyRBROvL6ZrFm9G?&9z=yU^SlWa%rB&t-R-2>uk3)AxrTS_tvOHoP z(Nqt)_g%8WNB#oBZ_E~?SQ+Y<{O;y;jREZF0@*`Ci z>$;w%$>EPyHa?V3(2HwG1XcZ(Na5D$HB#>z62MPAo}eN@FI=4tDLoxFiyQx#nEB?| z5YKI_fj?{uV(Ojd7S6o#0d@;L{C8;GG*bJ!E0gk#AMpKXrgM( zn2hNHE8r&P&$>EhDyZvhjKTjAckAvqW9I0Y5%{>GIy-XtXj=;@csmhm?CzEa8G>C6 z%x6F8dp*#Sk&&6}j7;TxI==N`m)|;Pkmr%(N5kCPz7Vw}dDV)nEV{S+?TLOkstXC^qCVk1uIBBgxFB^2 zA~*zbTMg>8Co01wEj{>a_hA06^F)d5CsE+JpZjwhuTE@hQ-nl6Icy#r==B<3ZTgNn zc2BE2{PcEzKH!$HGAHKF1EK<4C~`f}tX6}?`;0m1voYAR^yE;jjL!($AIWSi$oIZ^^OlGE@ikc_JDu4K9uUY@%D z(8OD?gAtAAA!Zm&le&lbwb8$}N*l$9jX^`6NFvSHM*youY~JjkXGaD;m0+`bdVhnL z#uDJ1XVLn#Ac4)lpLmYGbm>fIzrZKtzYuc1PseWQa=V%Q^1pqY4ST$L@E-R6yU&c2 zGwEDolJ6(4yQ13++&l!b9b1)bv>g8=scW{o@9{H6(-t$+%Bwf9RsW-oX_%DBF*~hS z4>HA(ecG83sx|ydRBh*yu+l1qr8qq7>!q$xfz>r#FDSr4@XB_{GvW2)5Gf%!=8by? znFb~fP=_$`FMxQqse-qM0z7ya;M4e9F807u5b(&->D$SNyNI0n6?|46V~cJQw_{n9 zQOR>m6g#r80~SW_$4{2Vie5K(7R|6Uyo~gJUx%`a@MGQYVKy-#VQ>Q3OTnD@OXU*a zy5|3{FufZ;>LIP!<0i$31d+(I_kBa2zZSTf5Xg@8&#TZr((Y%x-9Wtra=rTNqivOCTxG~ z=%$>K;1i6dl^MjDKTh2*W#~H?6L3GlS0kRIx=D(cK$GlT>@z2M|A{B5N}fn|(WV1q z5pR%wayf^AIVFieIt8mp>F_R1R_zzoClO&40unZPkJCl=Y-Pnq_T9FC$%tls#YSpZJ zADr;sWopD(2^SnIL-+V1s+0e1Gg-a8%CXAz@sG{o(vq`C4%&C_tgmx?Sd~AlAo^B2 zv2eh~(B!Fs&n}NQHkGf&#yq4&4tR6S%AFAm^~!`BGMVj>{`FA5#R(&` zj7-RmF;b7Hz;3rmS%iTaOh*BayW}k3|2^ze&zndOByZ_qR_qOLV=Qy}M35|J&BHJ> zW)$Dyd}kL_f;KL$5LQVJ3ubWAC-39kMhT{4tAEeMA3xwsK~6JjiR1WkW94@R0q1r< zb94HiaXWTFg!~TmYOfmKAatT_E(m#+H=QEM{0ILLr2vSqHUk!Ft^++K#CquQ5i$Re zrc}Zh#V;!D^PhIcF%5mNIKfcQUK{b`kLyhnv*#ifO#$fp*fbeiOOsKy+*u%P2%s2@ z-X53k8^xZskbjWQvK0eV{SyrJJvi`QHUJW1@w{*J%0R@SzrDIpx!&U*^LBgv zHr!mf1bGRXFQ2)ZatugmUf?ZWiG^5)YW!7=9!PvU1eh67uQz|gx4TwvpmPAy3`^#1 zQp!+%l>sM1sT?nv-_pW6OJi+qz1K6L-!3u&e0RrJ8}Rh4=k4Xf^<~vP;2A_!6j!!% znoQ3kI3u3|Z^q-y16sPccHVY{PE&*i-`?_iK<|(TS#+6FP8xnn|fejEk`&PI> zhLj3G)xnGRnR6Ez*4DQ-50`6+4PUzo&(P&d-*u;`e)=|ql22~Cf!^Yj=G1{9`76X(aJYEK*J|~V5d`y{kQS6Ehae@9xG#{k z$kPy+t}-iOOpe7)(UkO87k}CtQ#~m09cI?oBVn2>V#`hqMs5pf%fdx$GFS$KSa=qf z#6?ZoP$^`Cg^8k8nbhe|PV0?#KZOSU^hI`&dM_`EO&W3oDK=bpG#+whuOBl6R?Q3X z8xD5ZANVIkRlu?{>Pil$oYQpVXUT_!%^}kWV|Ge>N6APqUNHH4bft>%P453X+VU7$ zdhd8Ucr&6v{q$UdL3T3Hd6H2-O7IV?DcGtaeo61rvOJiYirVsi6VmpR+5H{>KI6nsKhuc7gsL_*49|qq0bp-OA;Tuo zZRd;DT^uP$JN?}ID_7CG@74ASJv?;LrU0|Lbh^XO(Q^UFUTK0=8xDXgMV*C~Be`q- zxQW`w{#T(i!*4USItB`7^Tpft@mB2hyFypd6Mfa)_Q1slA`Kf+>n*FrJIY2CLwLXR zl8YF_9wMA;PyMf31+v;_yA2w!4Z>E0!|363hK72Fw@bZ}-J9F{8Jy0ytKVvjdZ&%K zjQMidN56A$SZNz#a7sa*}%d12k^hTJyu0{0m*EbH6T z5oTSNk@CKjp2~LVXBMj-It!5~+LQZ_Zch`gW{K*nxv+aEtqxnJ!ujNM*zqGIZ)Moa zk*Pl2@yXGKwG&>#jPbMsP9rDdsLj-U?zs}*`HSam_L##!yl1*`Tq-2xBzuNfy(@(W z-c2X&*oC3=*~BHYJc(6{**`7h;w%*(Zrqhr(FS;ASrmuZn%6SftZ>5;^od19o9{?^ ziDsy0T;M%|g|k#3Xk$lQxj52%@3oLmv3CS9^G|7i1Tia*#xc$d$dl8=_49_8C3bZ+ z$$T9B*-pud!lNN>^mvmv`8(CoG~h4CL_?IMOazz}a#+@mR@+RC4Cwj&#Qvjl&db>K zZT`WN1bkaZg<{m`n?L1Dg0V&!8uh?aAA-rvBUo>u>)H1iImMf{nEdd_JS?x5c|*f$N{}( z!^-)epRD87l*;f1Y_xBUur%JiBSas>;2XMp-b)J0kO!6kP_j z371%lmI9o-B|{z8r-m8t;+!hE{nV6$p&LiqIF{+eQ?hBj!yJZ>Nt?mH%1{_z`<;Id z&gOdRp(di1Tq(OD5K3vav?LIC!n5^o*D64axw5`mHg8kk*(&S!7L@H`gWyrLasfrT zgX$O=?woQOY~NL=KKun4HF^d{j18jzo;jWqjE-Wkn;>I6o(u?QZ#EM^@-D~wiu!GJ z!xzAHvfkyM;>0bD+HcKe{`(@uiUe8S$|fuDCE|^A$$e#IV~42MD`(97rmtLkv7Py3 z&YAv91!)GVHYZNDyt;1cYKF!@kOIjxY>oL`*U}-=InS6I20-ch=4ONa9AFKvpu?@e zC0u7<5>CoVp8x>v6i|C$Fx!_4IN8Ul>rq z`>*D36?EG7Ki^k5+Fh;!5dP&N5UUykfHd?`6-#8yEKwj5q$l4Jn}LG^#0<{fNhf|& zGqVt3#i+eVHpQr75(!j5r2<$cdLYfMQ+i_=p8*K`c2_B%KiD140MriP)x(w2r$8bD zdLyP?Nv9aAEmK~)MH+aXqT>RM47x@Y&p_R$^Zaiy`eK}dl%5BHp+4{9@gf4MBZo~z zDw{{FJI5PT%(Rz8&3-f1K7KC6m!|}!<~b6>0cvWlkZ*kT)D-PP?BBE2&E4(738n(S zfoi?htSMS`@=1C|HIAoSzB3;rI$?8cY+L0ji~(zX7UvLBhsL-Y*ig5Ab7Opuu#$H~ zq3$?o?bIe**^1NIhGzFBH+Kh8dS0dGpZ zWCO)3ZR|U!ynYx2R#zO3UBBs)EsNEliS@FJpvycu_ilEN@(6x}9zn3CDYTOm#2j+ zM-}~#b=%7)8#>s%V6dmLP$FN8G?=;mg>1Ow&U(vOiXRv5?qg(VSVQZ{%5tzS z*i(KioZQ+p2yCe;a1Tr{IA^kJd{b82oQdK7$A*Y666YI$dkCmiPdNo|@J8q}tiheg zV8Mx1IhY`N`J>y8uIp(bIhF^2O`L}IKt(w8+xkk$GXB%GAMW=OD#@)aUUivC{ymH- z`aglAIEAX}d*m!RUSAoukA%DKRcQtMAMtB@9^V6BG}G(Q=&*>_L>JEF8RK7=BR-6s z#P)Qi@!zM=XsXu_X@_>MPxQ6GjLrkE!EvIU&ew<`JKHGVMnh;ysgeCk5I_g&%rTk3#>UY|r@*vpYx8k>!HG2s0-edV_KDl_>ZZI~KekuOmSmto+ zk$3i}-vZYs(G~p^VEYtcmRej~f?*A|ilvd)2oIqV5)%4H^^adlPk(^_zaQPfS!j<`6y^Y@8Z>#*jt#9d4E~%1@3&jf!-rs<*htAGU zYY-&bTCX;ezvc=Y144`7{;sC|u%?T#bQ`&MUq3R$1Q-0Z;ZovO$IuXvRGXQ#ET77b zOGZUbc9CFe%*Kpn+$%nvxTU9ODvh{db-4K&uvWZ~|2+=C1+oxBYOwj+#TiIwr<~B4 ztF#>P!Spg9gdv+rYi?6v%3W{FGtCf>#&{LH2CwjG)88zDF{8=ECg^j>zr)$&$L3P4 z`Su=fPjkgQ!>>7w{`zh`Q8w}v&03qx#lHALSK2+Xw%i4LcNq8pCtCTIwA6Mr_vTl;W1h!vmIUixxtjh3!HYvZ}Ryl(7mgRtcM zU)2L{-1C0XrCP)N^E@G76m#(a@z6*xVGkG!){AI6b{hcBZ3+Z_3%abowLO{DSXJwI zIoI9@pAQy$nHPiXAW>mYNdU@#_WQ>Q%SIrq7ZG?p^v;v!!i@P-qw}$VkF9;)s_lMG z(XOhxh&&7zc1exr#9dQM)9YaXfy2Nr%QNtSLjiRoj`)LJ|H#nPJ#7 zdRp5plV0}c6eF3rcEFKP-_-g~^SQ6%+JX5@C1bp6^hrZ|%doDMLSIh9&AAngGTqZX$mhzPI|m3c0ryl~QvWyo1)X$cJG}u7w)(E`ARi9;R70 z56HX)Mt=-z=dF2wWewNDoi;MrE2A4%oD(ir!j04RrR+biHhdcVudb=f-`KpfA`DI; zYY!=DMgf%L0YAzUh)OxxX?d2MZzs?*S{hBV>fk(dpsJ zBH;D9;ChehB@;{RInjxbGFj?%%9tzd-{Br!zbafzOf|@`7`Fd$L~!fn-1DIy3mD`K zj|JlmaIux({4;dYk1kBDXX8}gf5%=7n&)AdaS`4UN=4Ep^ZysdAs_niaOi1R`)PSu z`|!!JD|qn{#{4|RKDT`lDBn;|k3@Cs@S*C##m6|%UER3jdn6e{@(oEiJ$8}e)%bTOP*jgztu`oA-y0s{jaI^_?Z{}5+RlL zPr{$$!bh3=WwABBF=R4b?0l7Z9g!aZEQrRS>s@}vY4yi$QJw4`ALM8NW{lB7GkzM-OARb-iOe>cpSxOB4_#l8QglG&v;T9Jc-?0Xt^Dp*~sPXA)$e(uWj1{4nxE`Cnk8&?eE>cr3N*%b?|9(rF ze@GkVC&T@+IA|mfYzhGYW@CN5O67tn7xC}2J7RRi5}j!LA2KvZMm-4%x+Hotw}4Tl zt;VV}A{jsLNb>f9c0eWunVd#kQZQ?-+cja8jiEp~(RRRQ6kHH64j3v1=q=w26FdVR zFth&X`#ivkH^MmdHLC_rosnrp4SuLUb$vT$cjGeybP)!Y`PodPz#H51^%fPU`LWD` zx95VaQk0CISNAU6I6!NEyAOO5+YG$$_jy99;;8=puc_Vd7&l{K2|J!%_2cI2;oEQ; zs}>-e0}5-v)gIOS1+@Kn+@j~@OiR8YR>obdk|?20CV={^2~gQ*;^nu#-^*6NZ!aCQ6}^TSJ5F$7LJ@$d=^Ev&;>aB@lwwaSGxrNm7l1SjULAjL zHJy8~RvUn}1Znep!d$8`+8a+}y?OM95BI4a85t4e?Db2UFIS-}G3L&{6ni@qgKYX< ze4va2paH+<0Xh+9*U;h!V#;jfD_~tZK`n1-l}`zE65M(1?p*I}RqiId9B0jl31A&c z!ZqQ6o^Kp(cy7X&-H&|g5yyrHVpRaQqXFQT#JhvuMOxuB`%uL0+)d^DJ3Di|9&w-J zXH>+M(HXxz&1Rb+!9=X8tp%k5MAcPg-~&;OLFdTkIVGZGI)JE(;%atTFjvqn2KIK< zpjXeF-ua>`C)>096$M087W9RDr1T|%bW<+E;P-8E78C<+G$4J)KPbn{jPZ1=SruzJ4w-gFo=utm@ghvk_tQ2RyVWvZZD#p>qo{1qTc zRzkrauMtm03c&d0I6zOWXoXz#MTRicfhMa8fg6usVb>Bg*H;sG*j0#o`%l^Q8w%PThiSm`P5*8G%2l+0N;&(H1CW zhSDg3xu&@U>6m0qDBCdE4sna?-j+Lr_3>t=QU3B*ygoQ}dFriS{bn;RzPA@=P(@a& z?kr1T`EO+BPlbk^y#vtN4Z8`_C{}Yv+WQPQ9=7dWTaknmn8UB2P-4Zn`}4mYz_kQM zwfqKneDA)&$Fi-a8NsUW#tVfC0{i`i38@XVULn+dQ2*0R&1JWex?mJtTg%3kqF#FW z(FSyr{2yoP!u);vt<_j>_N*5u`Rs=9v_yS464cQsP569bg{jFt-71~)WgGQT10pkn z#H`|p z(K*&uP1v26zi{N~7rLvY?<4Qjop;#5Q|1hql`d|Fm`e$tCXH0EJCcZedxXzqV)_H= zThv(L`&SEuY?)koH%&HU(6r1BYW`}!vaY;iCTwF0J;xiK?b_cTT7dfNgDYBWKp)yi zuJvKJz_?oX=lSIQ0{Kywhpfe4ZJwJvA4I43gzu1 zaL@sZQWR|t2f&c;by#bR!;S5368s{bAqU4>S+svPZaUBbD+{wADe5S$QjFIg5s2~Z3?%I*G8Op|Pbg5{m|Li zgjz!j+;FcjIPqNif1X&&Yg??sK|8>_zm)T2_Y>5H=ft{j>7uc-Q?J_-$=CP!{lt-H zXH&K&At1_lTwE;c|CSb_!i;!6k`}0| zDI<651X`w#qzPk4>RNkMv&%wFM&p3GUiPsh5#7iC z?hZCSv^s9k=c=?hzX$>&JIApA@CVF1#P&~Bc~8)X;Wfu=h-@#wHjbox zkWZdFqr{fQaVCdM0B-Hg4I%jE>?w-sxVX!_So=-gJm3m6n4>TAtxGucRw}3Y|5@J|TS>UJ8yH&n)MmYQAQ7@LS)aL(02n_xDh(F7y4FSwAx+Jy-C8hKS zoqVDSrTl=vhqlIkFbFR|2(qSo4jz_&@mu)9?}!?rR+t)Mgy!T=HFFEd8O){8(isL= zEG)-vtIRfss=&+Ff4D?_2`Dh?dBW^{-sfD|TBDOsruF>U6z@3_G%Ze0EqBQ8tdz*m zHj=0)t~ttR3mPkhGYryjO!kJ!YO)>Hm*Z;Cc15Pg1v8f*ewrE8P!^OUUMJhGesarJ zYDYdWs4?<~djeFCoFS-Bc1>ol+NIAtnq2mBN zbZir&4gbDuZUCMU^$7&F-ICsb4_sOWBIMQWKiPb**i?-nc3>PU=T{c^Z@8CQM*eC4 z`!Vzm^XZ;;;x~8nOn`0%7O-m7)U~!+?b9m0JW6N%9TZlQCgd#Uu@=h*A73NTz)xx7 zZ9%hC7`tBX*48`x(caBKtebV4R@s3!S959_Ya&efku<*Qj|1-1Omm%*Yw92{&S@}R zAS7G6wYPYt2QZk|%eQ2=h}D*8EDXS00L0DDu3*2^g2SL=2p|;If0cj5yXJn!w>ml5 z`c2IVp-3xWX(TAstNC5+D4sAm21y*)TrIZ17S09q zZSzk7j=iVO%psW!`%zNG0XTBnypOR~QV;Nw{UTX&k&cw|Tmeaf%o)bIGZVViBScri ze>1%)Y3S4>Xq(E|>5VGcA>V)Rq@rreW3ZBzfB-R}(GpKp03CYw!6rH>nPGq4&2L>3 z4(~CxAyY?K#w=63-Occ?b^*3Rpo_ElMAvcy*U)mBFjo6Lgz1Zna=L#EKEs)5ere2| zBLX^~Y>f-K-^}2xF!2A1-@~6>(6RXX&dH$mQU(3XoIq+!XZ9LCyy|hiwgR#0Ad5}1 z?hoxT3H2UowtQ~1%R)vv_&;PAnp#=_=N-l^VY#L^J3SsSp%65opwln2KR%v938%2C zKUi~GO#ZE#jITCQq{hvKh0eF&U`X|yf_!$I3`6z$=`Elfa&#MR`NV3r$QYz463)$+ zRt47B2h^{@MB3!Lrq65rEfe=%>m(Pi9Mvc{QUs?HR%lu z6$S!6H#a)hyZt*|((7lJTn|6e*qNW|Id)sDsnE2(FdK>3I^`YSPRyn1eR6QQUd32z zaW{ERZ*Z{#NF#unsqwoHjuXb21VzU7_sKja{N#Yl z-wupDw8^c1D8|&LHY5nn%5Z@Z&;0H-tg;P%wuuhHayck>cBJ%HtdqKvwr8DyD-+0 zGs<@uKqC&C9W7G=T)3`>(;*+w5ha1QMguq?=r7>_EUnPH)`+MvQw~6X;+e-%GRf*Q0&HaXSq;kWKiwkXPv|BAV3cHAU-}X^Px3Ek*27 z5#=6z%JN-Nl#J*Tq$wop{NpAW5nAiJB4K^*)USWiBF50i+!Tb5k~wRs8P}@qK>g+MNxpDYD)h{&bq@IPU=S z*L(VWlS5Ha(QVZ}Jw0P3x+SVO^r=%wN(~;(BOMQXNQ8ow^3K0uu8`^8j;+R1bdcx} zo|B8x+&AkQ_nOxws>`V+4@ig>ipOTQAej6?ZS3xzrdzGK(pBY>gK-IHRZ8U=yZjuv zZigk#`D=d=_uT_i9G*(H0z16E6kJ;T!pPr#7;2=H&E?i)xO&Ar|yyk*w< zpV@llgPU!aybdW&d3~SmD9Ywh|J(5RG_) zX4_>@q`POg)3i9QN1$8Vaa-OYjse%e+y*=Fr3V_oXTaOC0~Tw!`lCipgXZ$i&Z@4b zXS(3^xZtYbHQ{XtT;Lb09u2gi#;7)ip%h;>?_bHDbHpA$0s1*s;JxH4gz7a(>98%H z*G)$Lrc|nzqWfU5OG;LHDB*ovjdag8b2Rk~Bsl&T#HDV?qIGO|(u8-Z={nXY^+SyS zkKwBElV=Yc>*>wg!3FW=Mt^}tlbT&g@-igThy5-O=fzw~Dw>(rf~xucwOCvKbJ`mz zCRUY;$(gpt%xam#K3D$^7Zb7Pm0#1 zn2NgGw+uwxghCD>aKaMB+|(J8t|3;pkHl3&*(_%wSPlsXF!7Z85La0o)C(wHZ8=la zoVBrQ1&8b7B*}O2puPWQ(g1pejrRJ)U6E%xTOF;KUy*cHtj@UGH+qp};)1F;}1Q`>3vR7@>hlFiCJ;=+bwB zO9Wk@#N-D8N&ANqy7>Gj@#4>ap-2M_;~J*A6Y2Emc)iUu_`|WYjX5CHDvpjy8LETd zrPVqC!GTT>?fT!?po>!Kc^ntdx-8<=XaVw&(Z?08g&R?jggk=!r6)gTd>=Hw(*0H` zC+07EWc<|54%-8fGDitrvUY|dp>o;wifl2mUzUukVWmkamY?MBEL+QXIRDM2zHqA; zzIx*(EVuG6(GxB!70f;S-wy?(i;;VxAQKL{6~A;)vO-XmhnXli*u|Po_0w?2TUdH< zhfEy*503s%R6|M@xL;uXwyv{aXN@-FHzeXDdiT4Dex85Qy1(gS_inDF;=JQ!;3XLR zVRIV4 z=a0H8i~tom;1wQ$#<+PKiqM_hX-4ES93J4Nb#83w-m?DSCyR63D-7(c%T;d8PjkeR z_`E%;eA})Fkk)z?fLpYrq(mLHBBqzs2D(1O#FA&>0@*!|_Pmv&Qv+jC@^x`_qeOf9 zu@fs;colFI#7q8T3~BPXVp_3Hyjk-B?h|_3<12!I8gjUVR+cLOFK}{EEpH4m)gxmg z)T{^&YE`0`ee>~)o{Fd%8V(i0m83rq-hHb7Jn_14GqwZ0G2xJ+_l@C59SR^ zfUo3Y?Rn{C3>d`9`EV57|2J{P_wBxR>}Pdb;HH31JCM3?g>j8}J*hQqS?{)e&iwfB z>G`JhZYQ<%W%c3nupyPe@u0j=?62Ea;G;8Mrk2xNPyE4YQcG1#39i0XATfnm2kQ+X zZqN_k0z`JO_?x`&|D0^$s+@mR5_32pc+;B0Vm=%3g;SrC{Bvh@>Bjy>FRj9Dinzs) z`Qe5! zIE1m_OG`^Dn*oRhg)gE9pj%vFLA21K4itOSY$ARK_5$Rjg%&*VCmu!&5Zu6u-gA5WP#x!eB&^X( z&mnFQ!Ph7QVd5F`BA$;<86wm|$poS+*xj<)W-%#UANQ`mJP_@?S+QflHiL*3bWXK?iLMUMDp5+VOgkSD(IxJ z(qx=wr7!z|nQ8P{Z*@01umq$)Pk4~KRVtx5ANZ!3#ICn>MieVRon0W_g@-Ps*6y6v;bk=a&@x1KxmTyYjW5yhS2No-SoY-KfkSKOJ6r&WLTUF% zl2Rks44)&SflkHw`@_}xa?2(wlzMf<#X#n3Q{?A9e}PWN0ng{tXCw-aWI5zQszvj+ z69dYYY=&OFNg%LvdTuOH0q*E3TkfpGpc#jpC7DdX3E!@Dq**S{ z;&^Tv18kd|uC{A3$0sZLl}0JhlLxy{hohomkdgin%;9#{$C#lx8AhIy1v@ z3%i*JSN$<(J)X5J%CCezj7R!@M$eoS7tB51!1%)#X?h)zn|w2*&b)IUfN^xe8im1k zy$Y!eSQ2&omt>9o-b$bURe#K&;#PC=Q7#A*%&xfAY4f}UXHy0$#b0XKCwujdFlD3^8tKAxhT#?{qK51n{TBQ7w>4#aI4!Q@ zv)o(S!-$^1tg-a_xFy3dF-b|#N0xW2l|mD3LhYHChIUIKy$DuOpF?;<==L46>wEM2 zQAwu?jqx((in=RxcT&2YyDokS*vI9Ya3Hb=DX{UC94wc)Hh#o7`&lG6Twso?csHAp z+Fjf_62M5!LpUnTfE%*=roJ#fP%cb`m*LlVS?Mv*HvrakIMB}^ky>r<-lmihyn1*9 z-uqEf%5we4r7GXtaJQWW+Cjeq^GZ}g0Cda|k7y6`KK`qn^9RLmz0Bt?JD-(vCe42X z-XPsX+XktICDYyKcPdc84)30U3;!kqc7fEO4Foy^<9w$|A0;=vxncz0_$d6(W||;o zyF*5av|ixT+l-{!Pe-hEg@V@KR`^>{_7yP>JP-lSc9dy>X!9&pr)8AQUo&vW%@PJb z@&WC>*nAM4@>_*yH1-f`Qq%h!5w+H}b(jqJw0ZB zS&F;j^Vuzl&Q>wtPkFn(R|M`T=e>rQs(&f4bGTf6mv|sDYY_6o@RuOOBSS1O$%k3! zkXoy`Rn(%0p!<7rp;70;+Se*Rc15MSw(d$#Yqm%D=AV6BpK0&mygm1#H-0y;+h<5^ z-ep$3&U7*O?&-;Y(&yRBO{H)T0n1e8oFaG^nL4{)7t<}-X3e>if2giLZL_<-wB5KJ zmNlTjxbotXyhO_KC~J01Yz>n+5Dgs%ae@n?EDAhth|0@x7y})3$qFN|qYQtGQn&us zQ6ox|f+HW4rx`YmOG}KZ&iA}vg<7W6)U8UMJRaN=keA6R7(B?!)mjjFuA>r78QzQM z^u1^H@^tmEsPuI6+UdFo3A=e?!F#}f07le(FN@;e9~F%oD>9Z{znBM5*d|e2q(ON# z0KQMe`dgrWs<}Od0cunu?fRqE3}fZ!sb&CyQaN1p0Pmj+1s(^5F_h7G{Wa@a0%r z{W6lKTCv38#^`u=d(|v7W2MuloZ-z~-G&%%vc-}XZALs+KsS~bcj1^^ZI&@0dB60ZtRw~!oGrn* z3-ibbG6?8&k>8xG!MMq@!L(e=4Wu)cEbJA)@Tlm+fpyCga7hLrKj4|{|NMQ$AaS-% z{oqPqox8SrRP$Z8OuCt7KR`Pn`cpNHm+;dHf!35)j&E8AI~oh)e| zxqg~fMmL2^!hz`4zsjT(AiM!l{K4GPl;lfwu(ub!`P(UZQQ)Es@YJ&D?|`z(IIwXwJ19|+gD8svg$!s`(gD$W68y({7 zH>Z#-8%2Z>DQTO0HOtS^{;Oycb#jhXCc_!;XUw(_8$+t7G!B~~p?mhZUi}A+*%Y{V zYVx#hQZuvB)pmu$$a;e#3`dEgL>t5vQ_eV4)F5c)ByV;Pcg5!s^+(#H*?0=Q;wRou z>_4=h-?pi{9>sh1?;PKB(NNP^S^NjzGWqtxs$~4vs5IscGN%5x>$ofAHx4`6pi%gH zQJ0kHYtBd8@AIchQ({bkU6e%?yF#AuB^Ayqt&f^>>R>|frTe(EOQ3RQ7Yo~oy)6ca zL~-jjTB>%=?1*1>afB!{ulEez0^c_d-VjaSpQ>=*oha3~fM(+vTW_KJg7%lRk|BaQ zD7t$~Xde3hNCeY?aT*j4cPOE^>< znE+lJWE$_(5NBe`O`_A}h>(vrCz?VZHt=deaDdQ3L!3WjH>&G1e5{YSejGmv-EbO$ zyu2|27qXqI_b^{rG(MIUP})j`4dgPdWooO1SSp==%Ty@r>F@s$`@6K%R&ABGXZ^JM z-E*Tu*4OSb(v-}xAd`emd1NVjQX4)2p$&@XbqYQ{zQ4O2w+OEV%>Vg6|Ll1|Q%@_j zHwunUeB!8qRVlwQ|E#X=kgh!<8WK6atbPNU>%d6l#A{b@x&2!zp}to%#navdP-49v zCkGzyuWbNQVQ4DMWqmt#n|OLC&OxZ0dgGbqpC7HCBv$pR?)u#|$;6%PKl8|VwW%RP zkZVNiXQFeXjbX6K++R&Xb+*8fD-9BPIA(LxAM)E(>k=#|4J&g0sV)(Hi?-NzP3~s< zx|qP`XXosmysKr^x}dYpk6W3H)=V7ST5C_}p%L-kd5ty4yA-TpQ`t`pNAlUAPWW#P z6%=ix{BgJU#1C zL6{VrLdW01+RHma*{_`k>mnJ`9yhFx8W7eY<9aF@{Theb=#EI`Ox50;j`Ud}sA*5zkcj?1- zqXMjeF>V5J=jSp>gI3tjJ`ZWqS{_@kI6s$`v89vNo`zMAP=KW+|0neKb}MORW#yMz zqV{+y#(5)HMWawsO>!^92x)V!1hKSV1B2JU3xzS##Mob@xUptJdl|$!8hZM}WuOos&<+gGh{=qcAvJ7xguY>*E+7`TN)c zu;@d89_|ED91nNff2^zyymZ7F1|&A(e>Zsq821gsgk?p{@S_QFzJ9UL`9sbBF~EVs z1_3!xcyk66BK+Mkn{_Ak%6XY;ao~~1-^rYLwsbfj+GIN=P&f~;NezlzmX$R%Vhz)V zFj&y^DzNJnOM8~K{!L_y4R{gJAeu8l3nMunE>dd3g|SAGXrW08g#m^d68{oH+zqid zDsG9Ui?`BhSZJU)0FExp<(NJZr^HTaJ7)Ax-@vzmwKYVTmB2%?rFZ$FNuZZ3Idzxc zB1Pb5Uo#}eUeZ`l8?76QrS-vQbvss3X#MHtlYOW? z2uqSPyzrG1VpQa>7;ckNA8(Yb=~}!OP{yljxCvhKe$@8k0QTpsbUM7#DV_@{UiW~{ z#|7$T6_oFEMEJ!3Hs-`8k1xcg} zJqm_foo;#^VrgGZR&9Q?_HQgA+3%f+!#39=6-2Pf1cY^=k?7k?r9Y_Or_9*_A`wDj zD9&L0J6ecYYqC1478FCSLM-D2AB`WSJ;<$Wi&7`CO_H6SEheKW-KGVPnkP<5=xYs< z5QWiRpCBdb%UiKPV;mhlh9@VpwbO3jh!8cKZ#4N+*j4KP4PC!j)qfLl23F8DcrnQI z?ub+g88Yz$lWe=QrPOMWnF;J(Uc&p1)U_<@7AOqq2wGIxa z?I-xyO9>FyCdXY+A46zNj`Hw!M|cjR4AX!Av#}c2y1=v7JDQxsQA{}fkOH+xZ=W9n zHl%5aOa72ZBE|mN6gJfQ_JxSpByM@D>YEybXWWTDtN|@Pi&1lqxGhc-`ovZUT2}P2 zD9{7~?54tA=mvUWz9F>HVPPBTb0Qz?<2c?;%Q8&a6Ti;q;;6B4OW;n8A$y#|YgVdU z9BQZ(NG(-H6M$cHR?E$<4Ued~WdxKYW*RT%P1hr`1P=hoKW`)@sALdInWG_1`5MCx0^mx61w z@Zzy@(ku{cVYyTpjB%5Q|DOfu{2S-REldZ_9{S1ZhP>;=D9jv)A@)xNNkF&P0EJZB z`qz6Oa}mu@FaaHlr2n7}xu@Wd)Hz#)N2su%Xz9IN{JELlnrpJ zkt#kIP-0Q_Z2{GN4F`Xr=S@^>2 zkEWOepz*MoaB-GgWQp=V0P9Mtb5%Q@!NbP7kSIkn%}~H1W{sntQa)G0o{o;yVKha zF1thF^aE-$*K){D7uNB+Mw{%wG9JwiZF(gUm$q77aj4uSYVuw(JPPFjVpJg2&B))- zh=eO}_xAR0wvH++BDDUr3HOXV6r>;|^IZ4irrm`_Ld=$2Z7&`#Ti&@WrRk1+4k zGOmLQRqvnLW7|Q^_8Hq-{lvw2tWM=ZWBq7q(Qul(i_z0MlGK8tFMsVbX`w{uKWL%o zbH(Iw=f6c!A#22^c`-FgQE0;tUMJsNNX;tfk_Gh(%EGIi){6aGrv|%OUZd_G|FfMO|hXya-ZGNIS$g_4n5`raG5x&>9m>((x1%N3@Etc(?HMDOW#C+(6k_$@8Ej?K!= zFuDFw4)3Dp?x%hIFr#Z;gyUQ{Wgt}*u_}(&1cOGTMoX2#N!A3^OD=|fi<(|Zs9Tit z*f3C$i9Re+(LlguUpg;xJ{n#m79DEDLiAG|+uPMYzYGLCZRdY?fj%=j!cSS^xko2; z&m24i$?ktv*xit`13kU3oNf2uBdPYW7j9`2Cz52TV7XYnnBdBg;{(KHBb<47;}$tg z7o(^qhU@x&QT~?p-kju?veR5N@9m;_#q%w_uvPcWJh&t?xN>Gt#2mWS2@XHPO6YF#d%R z%-3T780IvCybOyTM9_IJpG-QlO)(=OKA&pW9vBznT`}?UJoG{zVO-x(e|M(;l=Rvy z2Aoop6qjdS9Za^I$)^T4Z_Yjqkdc#DH*`qRSleH0r*e~G09S;&%W1_spzOHs=cl%w z508|xRGb2P7Qc^Nnw$?YY*(85dV*TGQ^%P6)FJ*jNrZoNSR0Ef_XDEq<*NUi{b|lt zcUD^dtsyvYm`BsD^LC!%w}+dk01;K42oYQXhb`gi$|4D8s$p%Yig(IRx8os1Y@ftx zGTAgGoOmfs`~%7&)tH(1cl(5hZc*kuagveC+qlzf&tN3attYB%UnS|A|3W!Crz8e6 zs8BnuJbnn>IAx>=MzTAH_gYf{k`;iIyv-Om7-ljg5*UbHn{OhxRpGlK(+Z8PWZs&v zR5>>Y1uNp=a8Ln@v49dW0LxnE4Cb;+_GRIyzwN1u(IK&U%;V@BTPvq z8t+azhPEv2Yn)14PFa13j0^JHj+ib@Jx%&B(b77yZMH&tnhryRt?|&z2R<6>GOxU8bt=1$pQXcfMM%^}z?5-rzfb`|bhTkBrKq zRdsD$%oT0Jsdhf8k;h)cEw2}F?^`NhdC*OOE&_Lo#n}`!@t4Rre>fMHI1n{?52jm( ziDXrM_8X&;t&~Cvdq+NbP)?mVf0if3L|cqyqVk5^a6#DRi@6C{ARK!drN0+hdyrZC zCqA3HpB;KO$5t^tF)tl%V@evAt9ioghLR!EkZ zW11l8Cd?B8A$2b4U4e@=l&JV@g>Siu6#kn03%slrKx7=BjSR^ zY7-q2x?MZymF0Ea32m*;QY9Dm0?tWnFWR6}SYjBQt2hhBB57x#x1xQfQW zKFgy|=%8K@x9p##C1W4Ej*$F+E-gAOF5xBf<(wH|cYivb!ZHE9^yAptBZl%N;>e1r z_o+Vx)(@)r3Vj;O05?4TGMVJ@8giL;O>=2DPOi(lTAsr;-Ee^z^QS3B> zCa(ROX$>P?=e^q)I^C$IIlmYptNj}fh{ww}0q;(GZc!Aa{L)(c>j1Kz8B3$|+$thQ zPQme0_lyd5c|rVlq=rP*Kzo09SSCKRc2Vu~gNpL<(uLa4TYYSnB)>uClSl_%?zf*_ zp)cUN4v4e?FqvgUX&C6!0xI8yKdTM_MObA2D5AELFN#>v^|q)P4RjEm`n05p9|z)J^WC;EvT8-SA5tC9Ezw zZJCAN*CcR~H(LjQ=zQ5t(*BW&xJ>TaT0_L%WzaZ`kPukB3ppE87x_Fe(=?&!?a5GL zZIz$sjDtXB&Tb@JQZd13tW8r{a^5c7P%|p1r=insD)nQ00>|k2{7c6d*Pb~m&Xz$s z6!*DtT@d2T;GQOJZ7f2j)nn7NHd}ji{#F+AS?jmff3kH}UmTubOj@ByDTQW-wARGV z^y8WGGhbkdcGnZu7Y>pST&`KaQqpOJ4`|Q+)X(X*_39A!?Gg@lWzwO^Af(rrT*}Rz z$-R`QAEvR&FE|;G)zo zreAG9+)&(@&g3c3c}iJsYC<{|B=cQOXbMp}_cSnviVhkReeFSeL_<=B-};$!9TXO2 z4$@IDVy85B)m&+cNRCJjWB4uj9RgP}ROU1mJ2?FQ2ou}ssJ!Bh)r9YVyYN(Mci5T< z4qjh%AYc4aKj@n|IfX(-f;T~JdKHv!EtOZ%L|uJhWQu+tQnX1zVKBRv&bRi_HeU6T zj;QoMxSeT_+_)w2exbcWRQ0bK=p`GNojUpAC~mU@8Sa3C#KBIJ?0_4u$IZXt61gQn z0E`Anb=xpGhIMB=UHzfpfFEa`B1!zDf!x&-6nQ(O=-n;L-q!mH6nZ~yQe3nFatEwh zEqNCg7hs?7waE&c-#N&`C*n2VC9EhUQoPJY-jz_i-~%y5)IKjaK7gj};#19oK_YPW zj_e2i9Pi6q3UIoD1#c>?>IWsk+!L0Uvl`z2(5TD<-ejl%GXqo5qQ+O{36vi}a(8_1 ztI{JZMuK&qarkcEd)p92spF-@+{3~VsD8HoH=*%6VOb0LTY-Y!xsLjl;kZ+H6^Wwzs{pmFP2yGGdsGel*Rj*MacW!cz%m|vIHM8pW&-J@ zugN(X{hj}wz2kqtuU(wNQRLHFq;L?ugT@40tE2);;$JyUImkGO6?aV1&mjXBz;qB> z6m?D`7s%PMZ2;EgC9T3wJOOpX)D%wcI`YJ)PklmVt2VC;{^kR@AyzY(QGUqT`%Ub| zU)r}4bY))H?sv6H3|ZsYO%gj0DQWGnIyR4dJ{dLRZ{P4z!(S2`_F@#p@BWx7Z|@H2 zNNvqA$~o{B9{tmX6-_oRA{Utiu*Xl9@mL-cX~+1~5sa@qbSF#3(K%yjf`;C>* zH~Y+$m7qLmNR)yC|HOq6GYz(iz*MbUAHFK-7xFL6NEWQfn=1I*-@yyhaFRiontv9% z?YN}_BdcQMWK>wXWkfrCDe9o=0cRx09lk>di&|l`L~zKVIOOeh$Z!@r*qDX11K`{? z?4u)I$>RSU{!?{#-@rMRzDWClPuj0T7u{IX61u!j8Q1zb*`nVBA4ot)pjDaY0j1`XVo6bk+0aIDHUvHLd!r zU>Ajd(tkO583xouuc>Eug+BKT zuPeX6UzM@zVDHvx4lx2G@POKYI|4d|mwwnZa`We{f+C>`Dv5IM;yuaH=g^*~Z<27~ zAV(x^13%NufSZCs>&v$;3H3wb8h@tp1BF3a>F?4LZAD@6)+b3r_8}Yvi^vvls%9^% zlUBdVxkwt^TIk@?(E^4W=EFmv0Fobl6onCM?W)t!6I@H*alAi$yp1Ep0Q&1PO46+) z0hjwX%!9|M(3i~Q{*To<#$OG`6JlnzE;qmfxo<#=5}}$>d!G?k9jSyZIG#W1 z{~Z2%n3pBvu3I*irrdPwP~TY-JoWY@>^3}0q;Sd5(<;=q;n3tq;uj(eDRe0@1<#LI z3T)r3oI-(a_wYF?5YZt40%HGYHu$-L>z4&qn=z*CVZu(Z5%!(9m2U>hu^<*P1e=k#tKtSgv5 z!RDb(ShQ(Qeo{Bn1boEe)#iobLUXN0g1X)`$aHci0H zEZaMulA9WnxK0RRsm6ukZJ}TqJBe^{=9kpOo=-lj#L*s_@~k<-OR{C#HD_}KnX1Go zBd}%SIhfs8@N#mV9aLv{3R&OF;NPG7nL!IM4TcR=e4bduYEqygSTlddn#&?o0B@~k z?(-4z-4|`__?ic%kY-gYI0S5#5b11|3E<;EmF6_#uF^FtCHMXUrEXZgxk8jjAUFlV_0RP|T zgjte0a{X_UR?6OgJoALjE4$NW6Xvxt?&?8{zw_n z?rSXpE-L3-{<1%po7&Z1Bn>}Jr3|@^o<(nUJv{_OtM)Z}90_O%;<$2?#F!R4AuMr?4KZXtzF1N_ zADd%J_3p%p`D}|q=O#LJCTd>My+~g&HDE&EC{K@9g)}g1KT*(HF|a%|a0xaU4IV3e z1EL#~^q;Nc0bZ2>1_oqs%6kK<9?q^xipZuOP)iq%pv+_xIZkLT0c-aAfWdg@g#{zc z`y@UohLmCg_~Bh{yk)4dckX~!cd)9Xit-liugp_)?~W#jglSer=%8ORxRKm&`&|)s z=Y@Kc!9;WCw4d{xO?)kU`v_(WpcDgAR5Et6ox)>cDA7-!zI%5JtQ$%um;p;R`0jzg z@d#iDn8!&X-bG4J1M;i91LpCE)BWX*VTj6)A{5_U&)OwfpaWJ}-R!pu>dysxPqmn&SPNeKu)-=UTY$Wj5=)-J#WFL2x5s zcfQc?W=9TYnjOe~i)Y>l`Ipbq2DSYfn`HR1Vt#o{Yah*y-*D9b^RIa}4oBD?X3F)O zfM@%}EIS8$W&g`c5&6z3FNy7IS+@Q6H2BQ>-o5A~pJbdLAcf zYeo~eTBH5g%0%peQOMfnY<E$4t{QK)=jSvtPZJ+qe5)_(Ps>o}*INK@_+9J5{HPX%7jDBLgq$`Y z&#hm~DwHQiIM5As>Z{D+r+(B(N=qEKH=LJIbB!|4H|>hQk2lKbs62(eA&eikh|N~G0VMcz9m6Fwzi&=wOC=@Ua+i#u&$AHCfc4$`hY;yW zoB!WLo!?9OopA(vlXaIt=r?;)NP4=gRrp*AE%et-yo!3SZSG{=ishs=j|GnwfTTqi zfB-yy$fWzLK-oWWt;1nGHGXM*wTbgKG$w5Uf1lMGV7%~2XuL4oBc?HK^eHF%!t~a= zNvV`py=5k}8{Yb`W%F>?XQQyV}1JQyXj-bz+CyC;6Jr06{Y?AHIXQql8=jO;pM zXRtP6^SIq@e{tK6|8jdb;nTJDw6gXZ_k&4WOd6%AsPMnO6Jv< z&WDcm)6?JhHW>ZpFpg5>=?b$+A+8_I?S`dPBTn=Vaw&w8;%VU3|A_sl_&v?KSKJ0Y z1UD@IiWw>*Nk;ZBZG?Q^NloPhM`5;@+zvQkvJO1jhZGX#U|g`gN+OHe)QSp5CdF8tu&=;YN9TJjQ3($ zkbBqHW3+jvW>7^GOA|P8un1%ar2_5!=0KzJA?I_b%9Hydq%7& zF%UV$Ee~!^i?qhK6R;|?e|y|NrDyqN9)r=*p8x!C$e6&D`3>CxP9uT{t-a%=%A|F} zf|mAn-4|QOOY_9YPtU<;CIMiQ(yzWTDpY};TDsU(qRq<FBgO zr0IU{C$XpofXAxaXVGVznXTT}wbo~z$i#iBd7trB>mhG?VT@lT#uPLa3*R2ekbfBI zK1tCRR#`6HupyL)Gh&eva}dT693`WS(*@0D$+SsNF~AtPIa zL;<1fF#^UG9|_&?#Ldgnozi*TWY*nLLH4Aku~;F468AC2RkeOV<_?-wl0<4EylwP6 zGV0x>iLkVEOIyIn11(f0rXWB>cmWwpl!NF}x3^{&JXUb)#<*r26Asp(#&*~q#_zZ2 z-fu+G@Pg!IiPTK~hgJ+ltA>>1sW9B-#p;Rwe-8M;JgFl$U8rCge*fTy6X$!0{~wOjD~*2sf1fga10MCyYiIHH}05EF5iqTPrlA zE1uQJo)|jeFC;U2_-}Yud$eGvhWy(`%xpC4d!e-6mRg0oAUvY9sg?`vRY6`%dZvn8p8N^0=lh2cp) z#>T1wsH#QX;w%4CSLY14S*3!I!pdYj)Qh7R?w+pRqItbPvxbKU*sxu(zSuM>%L$yu zn!f=PE!UckZzA0Na3Nx_A z*n|{jGI(_d+)R_7>|?j&p;vB=)(0yZ4?5Iaz)nB($KXxj*Q}bXAd)1yT10{<(#R{* zNL;=qmMeXY>sEamy`6`|aLF1ViDi;d#oN1ec^(%zjdCKd=spqVF0FvcWtI2z?>ggy zpw~|qG|j8Ci>I*_-w=*pwvr+T!=f3QOlIz6B{7-Ns}DiG`PVol%q7;gHd99~KXV4L zQF6h+m>h5zC&r@qcVY`^?E`JUj%7u1aAKuv}WqeN_2(j$TBNYp90XJrF4xqP)m8^jh!N*7UUhF*B-+AM| zKkNNz#bFM-<5E%s(jW`&6u_M807N;A8pg^n5fr6`4;Qsb&ScHn0m|?kkGERbLb3=dAv+FhMQQk;&eA0UbQ8_Fp^%IqePC3 zAYqap^GoBR(K&K6dF6)r&uWwQiHUum#K(=ao~5ufJkh_POkidrbC%|j0W3SMAGdh| z0eS#Gf&$lJUee9}z)-K@$>%t&C001SKHQHu@$rUi>Vha-a@ptfd+c;<$m0!MCJ+Vf z*dW_5Ey6fdn7Qg;QZRWd(m6NI3!G@!KGdDW77zo7FYt~~l<+9$b^$6fK;bkF6$V7` zhBsYs{WL&8tp>>$JeN|KsQZ?+%Fz5eVMDkLVTlT<Ff`ZG94sd8;L1G>Zg#gGZKo^sf2DHX( zAwF=$c)9DrNSNdt8DT>gWchfhhpE=qHhf6v>0q)5;7gS|e+W*N(@=R2#3n5KY3c`z z`E%Xo+$MHDks@pFr*-wrV4kUm^A*#UJVVuK77&TlH2)qrAbY!N&e7D^Ke2_qrny=a z?+1|;|HpkGL5!vVmoSh_0>f)f>@e+cr34@wav^=WZ6DvgyT(?*@^~YA#0%(VSX^5u zX(@aj!P6ExgAFZ0q=-}_%s^JU?5+3U*(6HtWB@mm86h%I;A$=OnocMS@>yZBLgxswm#BH ztT1QWa3@%~`b0ncv6)eYCI0D16LZQdr3k4?2*Zntvw=LDHlXtcE-nSTUhB|r&l$4; zTyWY6coE}zZ9n?CMzoc?CqZO!RnwC=`=LLMPfnbU7I^^VV|y!QN_1mk)P!+&Ycn9$ zjG!(!iDe?~O=GYpJAOng0I%OderIPWS4pe=*n+ZRk7kuxT>X;gHWd{rI2aVe%1 z3n0iy%hna=MpntTHG%B3!$hUvL8U1Alxf<6Ogb_K!s zCEk~T7rM=lmFjB-+k&>E0`v={Xx)b+k}D_8t0v8-ZMaeLkt{;wxkT4`7Sp0fleEOx z(@zicCZsGf;fy2$^S-uKMRJiXG`)17_o>;wLo*T$>2CSvO`Z895W7qx0gCOM4EmBaPli0xR355JmOP*PPVJRT>3Fg_T?NOJe1)6KIP4*RSFk+dwok zGxIBC)4*H8|M&JbiB^6m%{ODNQcVB_MMoTpCjpFn9dKd^`5_CxCqHQzbxu!yXh#7)DWfo7$~|?`yS7b zs1i8Chm(Gg9)KeWALI|dMcqdrnxH3j=N z0v@;*JKA=y0$3oml_)~$@o~4~@Ac7Am}JClYqeJ(p>1m?kd!?zx04VG&o5;7@)s-I z5M+6}fyRDbX7>%~TZb~>0~eb-sAR@d0uX`?%-ez6WTN~2PAG7DGWvfsopn@{-`B;z zAmY&7-K9t~AT8Y`NK1Evf}{c>jdY_hNQZQHcSsB=Ly2@ZyqDiv?;oyZ%`o%KJolcv z&p!JTxd}d#@r$cdz~vUFWI%Cnc0Ag1_Dgs6U!#!!0TmWT%+>{r$k7BSAKQfEe%>p6 zvHbDmh4ED{2Vc(DZHvK{ri;gLaUo$bS&A;r+>YsD-K!acmCbASu^&;UT$FBG`=Y>s zJb3c=eIw}Y9Zp8PbOrZUQqsK0{F03Q$bAQ0FX;fAKWAGnIkd zWVp1v`4}!;-f~W^Zy$|~(*R%r2QAiQn5d9EuhkHe`m^5jkX++_@C6in3`O!iL;}g# z@@xPhus%ak_g2rSL;qq)P3$W8F(;Q%0dSb=-|q>RHy>je`<=b%%*g-%+ZdDkf61VJ zd2H1D0|^=DuMR32eszG&6Byur>miccu9?Jdw#R_;Z3EoSCo}2Jzgk;m8SG+zvOPL` zdf#5((KXEQrDK7-=tGg1S-`g9C~qFNJxIvDKLz_8jrohju2G6QV{4Gy|9s?YJ{k_S zh>LkFE+2ie&s`pg$@;$#VXa^Ktcp)TGb7Qg!}2qL-OIK9^>6D^U@3!9O!z&!s;jfph9QDtUvAxiMZR4pM6D%ETV;RN4oeQG_j)q3yfJ=1eMS^q z)+scA6Z#sI9cI9KVm}MoagCjzA~^C;jDx)?Lb;f>zAFOLSjZT+rU>8D9qWKC`YS|Z zn%OBRE?cL(ZgwGFPu4faN&LW7cZzI zkWU3qYTT&~Y*UGxH#X~17gf)jTmr9#?X)R+^CR4ZN-@^f_7>_U^xaQ3!N9lDrBNF_ z`af~&p@M!x+A&Wi@2^kko&u+V44x$Jf4pQpdfqv*m`W(B=bG{?AZvwpkcNilWWVVl z6lgu+$gP@c$`MQxLSfTynQW`m7=hJ)KXQS1`w$^IoU-G6#ElRMQ!bu zV?sr?Xf;*R7}*5mHZ^^r@B5Kj!nmbnC6jhF{gutJtC=#|hI1>U-V%*hAc?h;R+>FI zTU%bzr*H&7UcIvbR9eyLIDF3YZb4*1Y!4!hWBww3AR#xGA+n~Vv}|&Zb86cooU)P4 zJ4*;ne~tdhUAwoXtVVD`xbZ>4kws)pl5DPIE?j~Q%+kLR_ad(df#Vr6I+nSYY)#qJ zyxlIV{PkE9Ljsb3%zV-PA z#;2zJ)0tGhD-5Z&hyypI2LFBFoiv*_XGC?$jA? zfgDe-!Q3T1L=50WG}F?~3I+Motmp!irUg$2`3`1{3^vtl{C|4;jMKV0w)_TQ;*EM= z%)-Yf9c&%Sa_I1~^0TIt~uO_4#nHXvzZ;3dy}%V-mu_ zQK{6x`LN}{FGkR*MY3th$~hpLH4=T`C;_00mc34}j05&OMON}x4%{D>MM)BUyaIdZ z6A=wt*=y6fCL4eL1P0ytJziT?^GUuJGtNmMsLZ(4J6+p}*P0ab+ia6~E z56CF-0*T3pXX2M?zNZs%bE~mdRRbTE{nHKYqobqQYZ5^)_#NPA>KU23yT>~R+`Izi z4i5D$@mgX!3(Fds0>bTE+ui7^(`Qe>?2}d;lt~p|HCpZR&m9ghAMF~p44$83XZyN6 zD->zH`e*NZv#_$+Lt?xhbg|N>6<%}Zd4H*PPq>03B)a!VJLXOTq=Hg|a`&AmgGYDe z-JPgd%L$tXDR-3lqs{sLBB1@%L330&;fMX@*AR{V5d#r5*Ry~8#(-E4!l)f! ze=as%1OnhDN!)_*i@swp-Fo=OELy+DT9>2BvjKPX6Pg9L^K?s!_(H6PaJ=Yy(e+N; zot{xUb=d^{HAbHpY@y3jEn!IvaR+*fz@FD{ap)KuY9JeHaw<6+{M}xG6I#L4L8F`f znqd;;pQLiCCDhzbSs7@4rnm+QzUe3S()=N^F)5}F#R`XWTFvnJY@X56*Tv43w&@z{ z8hjY_#2dg8r=@-O?k17fZ*M0??@cmZBXRic0eMtxY*>c2rF1DEhegy-*kjUUz2lMp zNkDG=q)=3Z1JA-sht3h(JCf`yHH(s-oMYXe#2!mlc;1K|V5X!v%U5G=lyRsfMM5l) zJKg;hplExk3&wX&*?n6^GU8Mh123b)ciT?gce2_dycXvVa^}>wWbPMlF7`p*#^cc% z47!E5Ww`&0TH7{M@A=5%^xNh5{Q-@_h$j6=-eee%fG~XegW=tOr@`^}4tgU`-1gO8=tk!o+H$VulTAT8%m$7# zevFcmjRYnT@O*jO+q18->aQpg)i*3kpjuhe^xHIVfhkip6*FFs$!`DOljjV7zKwkC zx1oba#Wc9bRl#j?d(qamQ3?rdvv|kZ7~*+p^VE7FL;bF{C+DBW;B#a1>i$+frA#B5 zsy_K4yIMke$rk&O^`&=jrmGm;Yq)`I6vtQ?ZGhXLhSbA!E)p|6{U#|%m^E*F9=A_R zPJLI@jE_>t){9OO0b3vPXO@73)u>wCKUg2Aq_5Xk^0jOkf53?mrRQ~1`!6iVKZ|bnMw#ycIDe1o{y=+jU)%O&o<0 zvdHXfVf-;IvVm80A5D_3HoLEDB>6cSIP%QnJ$Nd0AYlhL!((IC!C%a{C@m6);dc+u z#0`T6H1FKmZ1ecnCceJ+iMA_MgkKa+7xh>ln@`CS^eH4IB#!S zXlls`*vAQpud5t@6_&`>=@+~1oWF2t@ktLi$=lU^YXhh5h+g|%P5%aMBYbS~7(c>( z>!=7zGxx1%K=jLf-=5rjwQv4midB;KKVH`?nfZH%O=FN8-tlPQy7?|Lp)=gNrRHrA z5hnvj@YZ27{uZa<=E+#wpJH)8%bRI*$>OEWmAk#RT+PCYmWG~(lYqOG(=OI{=ixE+ z^8;-ihSWQ*?NZ<4{u4fuS$91{{hX?~A3DWIwd}1KI&Y2AL4Q944A8qkS>t*gaw3@( zJZ8!|)C+aq>KmK3PIa6pN}GcG=I@4u6|Sy9Q4tgw0UlYox#ku#&phqzBV=1t8w`Kw z19b3=gHkA?y_abWHEgnO``wK$Y;xpz@hgW;C5Zi%_*`v0@?3T-1KtkzHV?& zT12V-LJJWR7BSoD!AMF@R?tcukg_+N)!7^y8L0vVknZuJNU~&`9BBxOMlce24f%Aq z3bq%hMAfpzHVzLVPe9IT=XepOSDDvkz4|&!#JkhQVq;g3(->y#%q1uovz7QYm$c7SNNoRj zeLxG?SizbB%C^T%L`QeFK&Kd-qwY_qsj$y+$YSIc8$HwAw_YBeZo6lR`lz-Ef??nf zHUj#LuAL;=0b$%CP}xppMa5U0FME4bovadUO=9ug^XW_b+^-g1 zRi}+8tMryNX%3uoo%_+up2=$_GBsMJE-4ZbUGNTbb;aQDTIOcJ)O!d`IV9xA8+c@w zpKmcDU5xmD^*iyf+$UpThfWw)3hDBU8e(ZiG9`vSnOm~@t(P-nqjg>k$u~Q&l=>bE z(KWk8&$FVKcBTuJ`%Bwdu*gb{&DnF5_UJ<1quz9&?k^Et6_Xz9nK*jU=H z7RrBR>rbdNqr7DoA|m6=5uza)-1KKI)j`_W_#u2~?AYVEoTeAJ8shYYLZtb@N%$|A zAkP^5l&e&P^nbLuL2Qw?Njv8T-*Z!8q|m#yZQvb^1pif|D1X&j6~ldyo1*KqaDOT% z7yA3djy5~d=9XinIb~n4seD{_fpX$A*4-{Ls}$2OG&u3F#8iu&9rH$;&9lSsb=sg8 z4uQ{Ch1jw{I}@^U5s|H_(__H7u>O}dlJpspDXH=RSGLoTw_Dqas&KYWwU0r{@wY& zO@sUc0u=}~-%3eSL`@E!9}LXsIAEG%E^G&a{F*&UB2z-Vq(febaEUeiT(oi66$M;e z$kCtO`Sw{bvm$+O$5&Qtz|z9(!)l(0mCmp2%cbr z&q83qv< z;$3#9+Dsy8xbL{R1x5t(5AGD2uS@l75+^%l>?Mm(WD^dD_>0b%qpq+w^b?h4%L&+f zA~Hp#?ZzdQMbH&GgITpmzs4u<6>~s5fPCvM1)}M zc;O8*l_xZ)EY~mAa^`E7$oQ6gCBj~+VXK(NZa8b{Z40zq-kyX6sA_Dq(!hzHvA!u- z#7#*jMfcq<_Kj*ynjZrVK#rtcBKw(s6r&0$HmbDg*U7ZZOe&Pm07JdGHJ=(BA3Bl7 zryx(z<-*lY+Eu`tqhDItT-n*%i<%ko6qZ0q^Px1JRHl~Z2Y139Pt?aCaJX>cLL44e z#D+>q5X#8BcPUDs3I$Q6=1$E%PgY*?Qa>XtJyK#Snr1(`mwui$T#-2BOFtOtaxE_%~c(jnNK*licx$bDz+M8KfqCEk_**u-{2`8XF0BFO| z%nU{+mo%h94(Mik=ala5Cy}3j-I2w(QqDRlu}%IKp8ggV`|Wkz0#h^yt-(v?G&1w| z&teQaGE8=B7@j!7yU1SLI*RWbuGy;hzcZrTKAuiCaecT4UO?ldx2$0~DInD`VRCrv z!_SX&l6jf{No?(QiuBUBnO1=S?0vRz^I~-nY#i){ll&&I_X4!?p(4{H-_z%KLb zA@CLPci_;(2#m$RCi_)~{Mm=_{uCzX5wO@JA+fNFtC^+EWLng0JZunV+)3>FW}b4o zIijhGOytY2%u-rr(WVhJgh-d-#&&a&evgh;&lJmncN~ercHoTCNT|<5aP*4l?L3tm zq~b7L6M}vxr6e6ANICxB3t(|)^9{n_S}om!E-DYfd0l|MXoc2Bw|h4_1xYo7Ns=Y9 zp(-)YZ2oRD`q0DKUf)63;S7p1}QA`XalEK#+SEZh zfp{;BHBN?I!=nDQwrFj8Cm9xo@G_a)&G1wi2 zgc%g7XQ#6m8|6}9(?NmW+z*A4!jNp4sdu_9MN;)$W)4W`C!b)`{!-PI;aR zY;92tEM`b(45HqGiQs?}!GNxE|1%Dd(66C*vM^S2nLic;~2-hLc_)HGX)cRZ~t5#rc_!#Sua#1iw^DXAPs9Ll?B-1zDV1tU!gIE~Kl)Tj97rds< znT#ieYk?z?w_A|t0f}Pz^_no(OPlh5(JM|#%Yfb>^KB?xBMUn2%Q@QlAv^u{HfczV z{S`Gk^+rmC)Kr~`~f zi#Z-RG3R^zTU4bGjCT2&lhV@S7sqG`ZcaD2H3*CW_gUCf9i(I6ejizeRR1%;hvCa< z&{6mz$Sf+0Ih)FkeZ&GM(iCf?fH>kgt#h$4T_3%s4#M2)E55xE;sCL2?>N#|JVezz zO?+~lHy*~y%V;sf;)B=rT_-NY(!ZB9z9w0(9gSzJkZb~Siwjg5qCko&o`Ph5VH>0! z|4Xei1NCrF>|n7`!QT7Z$dcpz?88O?^S_w-M%Pap4Gksv36t8Wp(rLd;`DXm^mNy3FrsEzjzPAjf-bW;w0NbJt$*8GpdB!*^Zq#bbe0lC!YVW zvfZ^5W?G|TezzzzxPcy2BIs1A^U|Vz09M2O`56w);pu?Z{lD^ic6Wqhg@L^aWe;X3 zgJSE*jFFMv>PxZPSkQVPifO%1V^O27YN{IP3dN~+Sw)^LZ|jP<5P!!<{^%l`pBI)3 z?Sn>RKpK~*_3ewM$=Qn!mDf;8iI5?^NZ{~5Nkt8gTaNxW3vGR!ne*2#*DSZZ;RkQ8_WKU8 zCZ8r4`-WiK9ah`*p>AYQEEvQEYC;eA6(%rWgoR?x>5yS<>6yAv=Umm+HWuF(17BEr zvU^u!?0k3u2Gcy6j12o$Z$mIVd_)bnBTdVM#y}w8WrWGYQxJ)mYsg8mr-ZNRYnf>_ z>uFoJ03y&rPPWEQa2^gHj)BaEheB6lm&t|cLK!+e%@1C#zI~RMU+?NYl0wF~=srEJ zVY63Q+fCC0UY{$#ZJU~}(F1;3-^CChI(N+fBR`YPd^k3_{{&VDkPxX_qo1!)u2s(O z0_(DYB7h1KEZIMa;Gv+P2&7fTr{EJvYCbq?1Y#x#!;pe>vdTjGbUuuIT_m%*oN%2# z$)v^UR`In7ZvVa~`ew6srLdgDU*djwyQF@$hR&Eewcpn(l{Z&Yq7cO&EeAq|0(HgA z>Ku5E9xRQaz)oeh9eXXNU0hHgU1VsHMqe#Ou9RSDHYC6ChcWFB?H}kr4b>u269oU@ zB@s>C`X@r0!f*XyBPj!iM2VPJ-@XnU$h>hnj~xvdTZz|KXG=UXqWLeAHHVLm8;xDT z5qZi&huK}&RC2&TAcL}do4_)ZBT|+kgoitqiwTY1Vo0(E#dQEzj*Y0$QIiKf44H_4 zh0V1{J`;VvAVSx1Ri~)Fj8Q5_%hJz%Tb(`G){|I0mpW(_3G-Z1h}HBBzsOTUMKi51 z<@K*}q z*ec?p#5)oXSs=O|H|0+>o#h#L!_Lnh;{3l=xt}t0Dl^SwcAg5oQRJqM!Qh|KEYz;v zC`#b?ZO6a4xd}dcKBYM-OjM9ubqW_f5mD=lFd=UjJOP%f#?#Hwa`-`Gn@MNQ z*=xc;e*%AY_v=y%C)J7>JASY)=ouM-MUQ&yY;I*`>oJw8xV%+LaR8uF8{Y4cgQ+PX z+=9ZTY-iP*NomeXQfcJ^JS6Xbq3z&bS;IkakW4!}W^TOsz}p~&)XNVHj3#X>`*6W{ zf}0U1&X;7(%s3Jce5%K4=%`-_dUNSOgxhcXH=D%5+Qt07eSIfNHhf(ZvG?!Z@%mOO zrvJyR3X$j8eD_CHmrg260?`iXf83ozT)1XAkUPf(P$p*F4Kb(>rvhb*@ zl>R*n)nx0F>$54{zOaMW%(19UDp=i-X|h^(82fbd=iayT?D3%83tJ*(yR?j-}NIQzc8{A(-WT_LK<^k_-NvD}97js!#Ok49Ny z0bi(5hiB~z_?|MvPUh;{yPwUgI5mGrcg6p-^GCNh!QS&$u_ueuF#`Zlpixu&PkNRKyELqIozXKtK_T4JQr`hSIcQoxpX1 z7KFP|SaLmmemBA)N5xk7rkKy*MUrk3U|sS6uiNgy-U-|~8?fqwa6f~dTgFP6Wm~R&0pBl;9Rf+8k{9akuI|@cH!_(Bv+-jAGp*LUl@ zsVT;d(d>QoV@2RS!;kEH&iP`sk=m6o{wI2$D?r_sl$HZgOE!&tG+P{OCW0VmAMhus z{q9l#;}cH~O_M#2abP}h{k{BqQ3@5@?!Z5P|E55r3#b3ts4Ca8|Q-}*M|@A%B?ZN3Rm17dU+bW(Z8yA@xQAs9o;*Vk8Xlx z(&cE&d?d2?3CYESMRy;G6wJ7gt7wnQkQstL#=zxf{!)ZPmW9Vv%RSWs_$s=;xW|l}Gk~ zjSI^ReZI<^KkjxKG7*L&Og|D{HSp-HqCH`aRQGD_&g57_Xug`2pkn)N9zx9ll4%R^ zY~u=rpaq0+-_^#&JGB=sr-iXqV1e3!Jb?+MW4VhqJazTK*wJKXA53E<@E6v3fAG>T zDPJ|P%nri!wX9d0F1wr+?^Q<+a6Zk#kE{LAVlDPGYfT)q3bmoSqJ6!+vc&E?L}F^j z+OCZ>%b1UPn%-q0E*WpL&}f|HJ@YGv>yxQ5w7ilr5}9u=6xmz!!}UO&(}yCdembWT z2V*U(5K@SjYH+4cwg$2insG6YAdb9X`UqOb=RK|S+begmn_XTooA9VhZcpWdtS(@? z1xAh90KHdkD;D7kz;TTP;8;`1+9vc*41pnu{(=_K_?i_>k`^xH&&t#OHq zkBuzUU5*^w$Emel$C+|*uA6cTv~Qz_u`sHhHx9#Ki3zc+Tou*Lo#pq4mtGIEZJSlE z0uVOiEUIQ46dC%JQ1salP&!OxF!$wzz>h@s zD8iHdJRuDx{h;z=tIKyyl$87K+lWNvB=~vV$di6B=zI31)J26bcY?GOQy~XBCl0Hs z_zx8jR+KI-Q&wHN11@nMkV=Vwj>U?3Xqf!56uXz%k2Q}=OVkw{{k8z?9YA-RZ}yu& zg?qF?V&b+nN;S#&L$j3U@7WdNWX$_~7Yzt4pnB9g7Mc956TZK<2b{i#h9t9|_3m5P zp`ka1Ep9|@>p`C;-pS_~O6G-cjb)##4-f!!bN$gi*8NDpgEREQK4qqAXrCHQd>k4fN2$%Jd}z8jx%Bkpm}e{-EM`9OnVEo)&JG^BGwXaf zAxFb4INSR&aa{K37S1b>EzTnUq|CT^(BxsKZL=Jt#khNTLCC(fRJC-)v#8k!q%VSq z2Ox6Kp-*!$LZm<_+ueQOmcf{J>sjPk%~?t3)$1~V^1Zvc012;r=_;Hit)R7iP}vsH z4odL>z(^=bXyX1Fr;=g#_U)gUk#z8XfLsdQfA45jJtOk*{3{r01cB(lAHQQORR!-p z5&6=!nt=0X+>ZazXh!nV$>r?dn_%4MoMJh~&asT|U(D_9DkimW|FIIl4xE`h?;9!l z6v=(*FZ4 zCuK~b+_l%b7=}MwrxHA1VKL^Nxq<)Oi1IfOI+O{jVIk&;xgdBV9I@zJcvNxGww)yr zTg(yV+Za@kO7yYROQd!tTsH_8|XMGGr-cT`Tttc$T1?s(G?` zRno7hc>nDqbDuWF+G$&5pz%$$q=cl}XsL|-9pcc<@N)iGbJrkh%6uQp>d3>+>7*80L3Zc7j(ycwSa69+`EuBM1$ z%j3*IC^TO>KtF;hdZJ*bve7i%oy|K>r0SV?vrb(?rWVeJ6ThLrF|IB(ycPM)`TrvB z241!vc>!P{QM1hYo7;FoXi>FPYh#ZL1P%4<@1 zJtUJ$v5bm;k1Fj(PJM&cy2PI`)O_l5XO`Kk5GfFE7r>U`5J{k1{u&eRkox&M#^=Dy zB`R2gO9{XHR-)MEy=RglJM5>NX)bp3|hfXOE zSY;6iWIqP^FATSFV;}=zq(P|Hw4Vkrxh2hYRxe;+oXFK)a}V-VvO!Y2Oac2gq+* z+)uQCK+)in{Hy8!$jghud>kt^=B>)1YGrhRUH?!XL5Xbt<)>#bBRldY*q5VUB2?_ddJ zJ3qn(;us-}(Q6u|Ghn3$>i{UMffW$Upy*T@aWrd&0ecuwiq`ATFG?{R2;I&jvq8^| zYDKzVzmuDV-DH34`r2YYojFIf=q}>;O$n9l8)n#l&m4xxGNtf43ePzD1UbA(WN-U}s zyccPf4U_JJPS%Wh{!puaB7D=XI{#LHY}eziim51Z(uR+k+Hx?39mQ3?fId=z`)`=2 ztJ^V;$*G6R;WqouFad6wHaor?UV69AFdwB|v1jv-q5VupL|KhYu&XOUmoA4=d2lO3fB*xXI7yG%-W~*0I2rcjMp;j*kKveZx@Sd28kXKbzbuBf0z({QX zXxp<7Wx)6cj?Z9Ot*WaVtIAjNzC3#kK6Cs&ZdXd{g-SSi))tVkUcGt+%D3X_oFyml zfO_96o{Ix<;57W$VyrRpO0;ZX&Y$|zA(=7KQ&&>=3~GjIi5IY8PhnO**ElY6eYVXb zFi%tDmT&kgTRv~Dm@6|sx+1aI8&xxnUArhYI$c468JzWi>zOP@HbvXg?X4MolP5ZS zK|HlfM<3oAt4VyE`BK5Mx%XWJdq4e+aPm^hs-yWNK}KYt?-~~20+M~83QYglxWxG- zn(y`1w^-%U()i*XO9Gyoruw_N9k*-VdD5H`(LnB>w4sTb-3lV!P8;c$%Q5?*L8;dd zDB{F>aRb=&3W%@IF7~VHEBY6k>aNn;?(LNm#>-|{6BWVeC1Kw#4P`}B+gRs6bV283 z3kJ-B-#a>PK3ufe42E*#@s8deHC#UCZN}m4_@4LY4t!gvCV>5gezxWO_3`=GZ3+#vP-OY^IM-RX5?mfo^tgnEaRsQ7fu74H9Q zWGY_`?tk<-A)%;5vwT($l(UGQ2nPp;Kk^DK8rGC3zIT7|fGz%=wKYkbHgGCwawY@0 zD&+ODQ=NC~RmL4?v&3e!xqJeq@1u@qG>4TNJDC=kun|zX&e#XQ3b(ZL_R4lNp zEjH~*ODCj0DZUe-{Y$O6{T#tJ->-~S)XA7 zlDl_a(=MYq$;SM2T5Wsp)a4cRPc)~cq8AO5k{BU84RQT&6oi73yQb}PV^cDFb9t3; z7DZ^ic7c?_cY2i~zWH^cRK)KjmK(9AB>q=bofZ}qbVTHATJ$f*C;ucd=Fk;9PqfW+ z=BCC9d#}aE#z-BFG)buTDuL>Wuq3JC{jM-dfRXvf?9Q*68ks7% z8E_+=o$&+HkOeRz5e<~Cz*6{Zk&dm!BY1C-xfonl2(`E=t)3F|D!Tv?fGkASgSf3C z+_r)8#7m_2<&_r`04^UXQkQB*fX(mGa?Gi(9 z6`Hn7bZc<1{9U=XyX$ard1MZ{g$Ky0SowkG?PmvLCfyZ(s@I#7Q8W`xf&f6giI*1NxtfxaAM zRsW~_dAEsPkaXjseuPXF;b}Gfu4H{cZ|I0<=a4VVdE;`O@Y^di6#s1d%{Tq81M(9$ z-5Qp1Zqm6~;zN#UO_$Xam9L{z9hn*IS-NZZ1?b+eq)(;YMrC7-lJ6|QR#{>qMOgo# zhpB321>Al0i6YK)i`q#pn`G6E9jplOYVVl9%XMx4^Y`n_EY&8-D~F7>z@23ID60=U zPn!&0e(gmnOX$|eijl6kcqvBR2uSE(_ptmbCjYDsYY7jvjpWLaKmcY z|E~8x5%!<99;Z2h=V!Ypr!tipJVrU{qyG zR0LLr;|DNi1=xO%gx@Bxt!6!fpupz|;8IfUpa2IrC(w9O%t}5R4+C1l|J)XvyPi1U zp+7WbswVy{UJG%WGJwnUI0o%ZAhTtvJ}V^* z^3P_) zbSYx=i3H$_KPt|^IqSP3XWw&sD^jWxp;;(h(3KPJ^93xvY-@}^1g^Ya_4_fH9$V)p zt`VU!e)mM5{B#t1`Zv&Km9%_9R@)xRM1#hf>-eCvibx(z_~&?P6G(Zgu?jdBTv7~C zos#o*>W(g4_4AS($u@*|`%ypGTs94h_IRRq{tV#v{#q{Dyd3h-pmxR;BAO{bzUS(F@`xzPC;{~W4T7OGpGaPXzhehqvsvZYwwj+Zuk?7%y+ zTGytnn2?*|ZJgeTkR z0l63TYK> z0AyxeTa-JseK=b4q26}`U8)_#t$+yvQ{cm`I6-c11?_?7JCi5YZ|UJohzYfLYAAjiL+IJV%`3>;o0`J z09L{h&xYGmIuwOCd^uCu^|Zo&CAw>Sp=zzKT5m|LQv;karn>)~7M~{`oKW7JG!dZk~-t4w9G2n$R zdwp31F>Wt+-yOAN9ggegVywn>ja2*9Itsp9bb19c8ZZR85B9KW{mf0nbi0;lgUY*$ z&y1S|E9M@H3|OxXv5W`I{ab@#k*RtyW13=NgiFia9-Y{MlJ@r2Xl(L4VJl&abv1&= z%fYBmI@Jpk3I!>uHy21vAzi`#&h0LwxTxmRGf(C@yq|jrL+HY~zWUe2=*%-yLRfV< zeuJ)BWei~_`-{jgDCRrz4Q0S@m#5?W=caWp#16B=YuJU49)fI8qgQ6ZGYc1G()tbD zVYC%3a7CtUH+a4wTW&Qy=4;d-(;tR(dEI9YW10FjU)F?e^2nmUgm@50knCjF(vygt1KxIZz4xIf8?2^@*f6}m><(|&fl0@9yN zDQluHd!k}e3ajHmHY+`(w3NOwiLqg^cBc`-7RFGl8qdrog%0d=0K63v@)W!xX!Pav zjvQuakTUV2xl@@+?nK31U3|B2IoYT3#7DI8gNG_$B^>j5# z=2HN&P#!;UvmAo}O<))BVk&oueUpZdLZ?9qpoi1ZYqT(FTa`lX979fnV-bjhi47ZD z@{o4%8}^M#aL}a1bVPlR3;Z{LtYKH9c{=!%GzwWZmu^iXQ0JrOnYoqTEI2x@nIcRH z{d+z5%YwB@r804gQsnbtQs2-;&z77u$Aq`3TCk7X7l+Q;&ILm%f^%ZKC!ge_Oa|#w zZ2fB*Hu)I3*$~mM6Z%Vwd3q2(yjNZ6b ztoduV8rov4hGTHm=43-d```!>IZ1j!t<+Vx1Zpr(h5PGp{323MZVbI_1Jmb1FPP)8 z$k;eyAq*~2uN6Kf7}2bp6lyXtnZ`zw$|0eL;G;9`we?(8D*r|6$>n|F!~3gFWDQ}5 zqt*nKMcCYE(dekBqb<-lS6*#nOj4=v+x*FU0}*M4DYA=J@8nv9jXTqA>J*k4{cP~S z)<|b~&tdbVaE2766^*Shu;ZS&rTl>Ray|P;01ETdc-opfJXyLZsqdwy{EcrFUcTAf zL`%${S@0n5tShP4y}f6@oul@C9|^~W;X;JMBFH4r72p>Q{%gVqOa3u6XZ(*MRUb{j z@cus7mzxcr^0$O)IgVL*@%ziun=)64bS?Czmu9>QCv4Pgelkd-gm<0Ux$j(OjuqHNAd&h2fQ@ z)MDIsp+ss9lFT2IZosDeBLQdvTII7y;FSE>Ful6EGHYuOTggk%t_2Vt{9-m^F4PhQ>$S-ehcpSOI?GmsiFep!b=9J+Iovi6tM^l8oI)87(EdL>=u> zLTQ#pA0?r*@Y)$l$wM9GLivmhMHYfzDqqt(fy%N_ridSngFW8D+3Mj^BMA#BFdIup!f%dpwDJT!qoY|hiIxAD!ZM$Ir`=SIlnKPGt<<&efyJAL5TzFP33uX1<5pw4{ zWx}VYAD6=J`V@lvp`=`tnD8a|Qxst(%;!?gz32B>$F9~ZV__a_D82FsE@o`{MwaEV zpnT+b5PgqtRa=DHNv%}7j9ZKT5nK-P7|@~T)OPOVLaAKS0o*`2P-5n=c9KTn^0>dx zD;?Ge&waG!j%Pi2k{?fc@}Cnv3yX0w9O~Bj0ZKXVNVqjjxbBiA|E}tLX(|2}Q-Ni) zgi4fa8@{xU{B^T3t{DpWQwJA9Xxw^hR%Tjb+EA;M)%?h*ZJ6`HNB#`Ped(E#&SfD7 zWT7&Z=X^6~Xv8Wm1V zejijfDw}E^|LMwwaPd+mm9yDUKNAtb`iqj=!OfGprkV6y7UlQ?T^S&4tHdD}g{Gge`RpQ7i6 z<-`V+FzJIb)40@i8zEyjYx=<%psfuY2IqO=1lL`yE|HEf!Zkow1XEngHy-oDawh@v zVjN){G#Vs-vqnRLaNBmZ*b{-6ZC4}J;Bb}C8jg;(Necn?xXvu$vx;k`Zy$MYc~%>< zh6ewkKV}6eq<#M>uLV`uWX}U$cB|KhuL~gQhLQ?a}dMD-`M-&a*9Bsuk zI|u$4^I{(5qrtO;WuPx>8=&@40?Gk z{RW>&I^MJXwhDAG8U5YRpE(ic`*RH%Vr1aU{3`peR5w+;9cqxIRW3PYpQvkV;$&d$ zr|VtP2(pndUB54sW~1zrxNW}~$^U2sxkb2kb_q;T$NBXVWokr8B1ezgl>Ya`7ITT=bC=&>snB2^`yX0S zn&2msIwy90U8OTe2JX^#=D+J>!ewF1BOh0+(CK<qLBse7mHKnra%&vaM{v_jUzItQY^3y9*i%h3dbT5(fw;lRUl(sNJLO^Aq>NVK zgNpGH zE?>#132@T963NR+Pfd0Wd?fKvvIitCeaQlee4Ev|6Nkt>^GIf0LGNkz z?bDqV(f2OlE)O%Jcl8yXSXS3CHNp*CP@-iyJAo!(%7F)HnMloCOYo9M%kwG>A$+X0 zo13F%pyJlb3)U;TiTjZ$z{f%6&v~gc;LnUUhdLy=F+|=%A{xq|6TY0N|?y6IH0xo<*d*b9Ti-NU3LfFgN zUT1~)AGA(ao~E}PK(WiV5Z=^zaWS}rjLxkzeXguGmWE^JgPs}N|B(ZuWVBL)1F$lA zW$F4}IGUUN9!01>Xr}Cn)15>vB#WP%Fng%Yq=pd$qyzekv%s^J&B(_ai1#)@W8Ab> znB)@!O4-Q0q~fzYej6oJ@_0OXS!&&N3l+3}_y%&~9=HUxAI;80# zy}L2#-x^e9W78s`BgJ1^M@l7?b>;o12$g5`EpBFe&(DTZ1`Qj3LDp6LOe7>fZ#7NA zxwkVcUQo+lv7pFOBnYJ*CaY9Zjd+A@q?(UGOqo}NdPvof2MA^s8qKtj1{UWkn-7Nw z%_pYP&}<#{`hAI+1@;G4|Bt4#jEeG$*0>@d-QC?FCEeXE-Q7q?NS82lcS?y!mxLfN zfHcyLbT`s*kN-p)ZUIh0p&@0{x7RHJ_8 z9P)|?%emW&box+euHL78@v42E<)Ji2d+K=b=eS)O4$1=`)#y*DRI~HL{5}tu#Gnu< zj~EI0mlBfPGNk0=s}58ZsKqW1AitdD!Qj6Q-(+DY| z)tARWbKXyaMdHB82o^_wYwd`E3a~`qx?i0eK>Cw`bw|-=eEY*nH5>y@d59XJ0`BYh zq(&|e6(Z!YG=f5Ucj})6W)*%Hxj9*5d#k8THf%DB#$V@Apj4Ee8VVO8xzVH_1^qpJ z+hBhLNx^F6V6kE4mKUYS$ty=i_5q#1XE(Tw+mzy8jvNqi42M`(KZOyVBX|7Wy%gP& z8uH*KBy1T%r8FPU&k@IZ?%vu|%Y>ahLzasJJ2wX(cSLi)KrbWVEIkXuoi-BR`}qy$ zwt2NYjS7N^YNpHvlRD0C;p2&eYxxP9?1<#rsL#4o_3538hezpjJNHbGv4=dKp6gJP zufyAmKlOw)ZQO-=yn6L!_xH>tN^t(^bf{DLmq!Z-5$O?)Rn3l#MrSUI_6CkE)Q@fajoGbrRFAMC z#iNbF5l?`M!$5z>iX4nGo11K^>rGF`!XpMPiv^J5v@$U>aaP4_TtAXdP6DJJSRKmF z&TeSZM`;&7Y?`lY#%{5&;4>QYBpwnRU4=tBe5JeCS44pHQj>MIJ$s9VkP2CbRCIQkh&4S_|9C5gM1SkH3!XO;)) z0A`k}(07{I93`#|G-V}^uPL=74qjO#gsBfaA1uERVzn^kpNvjE!bT=$9p^AztI%}o zI+^n(P~Vq80rnu(y>pDk-TedMnoIbAejCCd6885LnDRzV{V#Je7Uy^cr^Ow~ zwXGYJo2;@sd%m0h%uP7xIZPs`s35#@B%&)33x>HTK)*pqtZEa?+qkImlx~k=vUm~8 zj#-FCd0J2(-dT%up{T1KB-L-sh}C$ij+{x0soB^vs2U3E| z2_sl@DiySc(5)TTytX!+Rzr-ZA)itisla?Og1jhhZ|6Jel!?TXVe1!vw1Gt=MiXC-DR?pBQ1UP-^@xDZvBO~$(8(Jf z9%c`;%=^1R44Ym(zUPS*Pv@$#r|J1-%P!tNr(1B;4jekk&9R^8XB&Ed+uV z$TWVcn`_Ak?Yk3(W{hKIV$9R5-xQyWTuIJ}_o|7p$cS)U9d{K_xFO>()U0yYlXJ?< z7ec6G`h{{|B)7W4VO_T|N-|@GXzuXtWAhcIK!>qQ+7R`zQ`?MiGN^HS-)Ac7 zz$cH{>Y#+r(&1Loj&KX5Y{E&KO93L;P~=Ni4dPX9J&c>9mRasm4T||bmOwaKrH?&U9>K*7jACgKq<{VNHcfv| zgce&ux7^6~q#YEP^SV+I>K`POyA?bji~1(*Qvd!RRw%)BGMR zgs>EgblFCt$=3=Bkb~ARv#=TU(zAr5FB*e~sY%UZp1X3a?^%Z=kTUHIZ7Y-i%;3gw zq$rf!G(#MqO5IuVf*YKrGwrVO%AVCnv&WJ{xZfR$Lw3$GUB4V5TIA*!%?pp6wO^q( z&2C;yvCO$tY8HUtw1I)Wf?ATzk%_D>vAZv2YvY#ox(_Nb>*zEvH$sxxx|ka~VE7oH ztSESDJdZDfGQ=GxWR{KOelgRPEVsSPuEhMQla$gdBII-pNw7Het!rBe9;@Wq63xJE z!uzEb5-*c;KE+_UVb_a6Kf*@-00*v>ZT<-XE@|scS*pgB1(1cP|Ys6RQ{fJ#Ju`G67d@pZ4asTJqW4f)KQ#_Eqp36D;t7n z&)bN7176$~j25lvVKW30r^35lXFRjzN@HfcrHNHiikNMOvRG7*l+eYTUhh}k0U!oR zJ~%%a{4d3(?sKqyX- zvK1nwVu2XdmcQXSU3m4NoNv(VQrKAfjahe4h6saBLh7XiGJDdOHfh}|tk!oaOq3;| zHQ)H0t2780G2);|)(m5$rM$ib@cySl<01&bc&^_p`RS?$6-3SK7VTmQuQ$`kJ@aQ` zPj?U#iMjStF$qF>T$Su9-vV+gAoSo`piF9NDk&>-2ntI&R7kfich?=|&|@ZBWj05# zz4!8-T2jLI{?0zI>(Ff93oNi|dV?XY@=Xt9ajz}!@ZC(g(HHiez-;r7HOa_M=|%=6LnS_mEK zijxdoI~EBC0yOd z36}g8lG5+^?XeMdgiz?4E_LkfGyJPfs5YIxX5?3!Yj<)jcd}c)$H@;1UsPGks?2eL zPC2&MN7`Gz$OZfWh3df}PB&ic(gS zT)?>UzB|V-m5;ku*!7CO`G42&Za#dFW(Vf)Tt2*s0 zmWCj#tZ^xfyYZt5{f=;>?Cx^q!W<-pIVt#t1Y63;l+gDTu8zxYsE3>ayG6=hUz7|S zYQ=UH!d{p%MUW0lcu7#>lx<(6^r5ita)H}H zX9htKGhj26TaGnBpISKxE=&URub|X2o>@zr+W|va2qvBkV?$kJ7+pfh7yUABF4+%f z49nu=@UJ4NBK@c;6RGf7Bz6-gRx5XHphuOMUb=zT{GW)a&rgQsI{PT6!*Bq!Bh6(w z3T{h(GAGO2)ehoZEnB^+_$~9(Ij=aS0khh_Sd>rZ>pCyIj!GxKLR&`(fY6O}D3aam z&z`unZB|>4-?#pO<))`vFR0x!{hTJqZ zAjc!}mn21TcM{SNkFHtdj6igGcJrw6Dm9IYo3ev&yGmY6Y;}qCN#+$Cf4Wa5=O5sA zG^Yzv(0?xlUC{g)O>)ikTw$Qpur&v>D-W?K_lm$PTIgk3Cto6Gn*)`Xs+WzgG~K&H z6+2J7tCiaTuR)vidldn`t_yQFC~xePGsI(<71wtvfr;(|EAbLioxZG=eTJ==-1?pl6fNK#$ri31PFgK{qWE1% zm$sNoiL7s5A&*J_SKYZdQs(C5Fh306_d1ys_6zNqucKLFL0-lK4}tdev9=IcAauW2 zg>AF!aDUk}xqa5{5JQJWB#sb7@2^l5%BAz!$1!S9BGt1j7XRZ-H#Iwtx@Dmxt_>z* z%xcf2!EOL)J6)ZY3?JSgQ*abqV<9HOVsE+XWR3~dVZ+%%<=i{ZbxajSi2T6Pw@zgh zvWD~@!>4U#fh6yBJ`dbPaX9};FvP9Z5h=j|%Hxg>m0|$on2YOqNTklJ81!t5-MN<% zAQ>nEpAH-n&W*?1kbr~C%r_jLYHP-7nlNDfeD_EeDo*}_7I#Y_^WzT{(C9N{)ASqy z+kjv?v>w%xjoHdrmfFEC8DRIYWRMeze2A}m8$pdE(LiX=yUl8Hapq>`!9`y}f~jBn zN|eqz0VD z@^scupjp5py$x*GA7+JHl|%LU?0Tni-CE^;y)_z6rN_q({`@OtR_U$+dZ&#=IPxMM z3(aa!x9T(gCBhE|VC;rUKXT!7$Kx`TDW@C`Z;91KL4{S&SUC2Amd3eK%BpbiFq7Y7 zY#epLTR2{0vw#DjE8iM|b zy@#4jZ}FspaHJ&6!sxCNS>+w$Ic%G#ojM}|{kbxf_NbnQn@+LHIX@*K0r1ePJKlSO zS4~!Dhwfvp9(E84gqxdygv>+b!Yy}Y`Q z|0|!-HxGCW8OkHiY{0KgLbB?`Yi-mgF}OZm>&cYRY+fvx+#BEX05=`bsR^dg&u8P# zw7`kDfYTzWhZi+f>VMsp*=nTndA(GJzU&7+?TA&{w#}kvA))&J9SbbElH3iL6)7bf zjf&;pE~4m%z1n}DR(z^wy%aABzPWi}&7+4`dwreuj9$*2P?bx~l3n#W)amM4#y$n7 z+dG5ulcCeoKGbf4LaOy@#ew!A)?#qdk5m=hQk) z2_`rR48mY^Ir=7)-h@t&nmS|W6!nU!QKERF#T17*55;SrVrAloJSF>Q_=4f7m@q-Vdov0uFJ&cDT z@@zgQDIGt%KFJHGA|xf`Cr=iyiCfWdr4Q%rsI#TJ8sQJsfwkbhJv-23$=l%|Ksogn zb?--!oVanmZlN%pv4w{|gPKVv>B!2;#LV9iNAlO^wYA?N1!C zoUxEZJ?)_R=;z)WI>?SrW;Tuk~%lXbrHvwQAOc40CFkVuIA8v+W27oRxU6y#D8 zq-3a+&8wMU1&;8sy$XIooIh2j(G1}B&=6_DhpGsOVqpd&BuM;8G0albY)D^pT+*dK zhk@^U(EvXrV;jtlr3m}WR&34%lOR}|XX3;A><`5bk-6%~+);8!HBMUYQG*XKKmNWQ zhZi8Gkl=O|jVyL?{~=NcACHCg;ggn*>H2Rr`Z6wfO4?=T^z3G5H?UJgCg`8Fmq`ee zdjAk$E{>LXs^K}6KLe!1Q-lWj{v4knFX4XTa84FZ#e!cWR;-f0-{?bK5e&>T?u_rU z?C95Aa!pvF)wJr1oc9~wlPB;xBDv@e0g7+1^$noAb4|I-DoHz%eC0d5WA|N5^D(5^ z1#_G6)K1Y2C4GxFoqz3uWwCqb{x_ikPcp*`%kJ8CvyGita+3CUt*EEk;}mEst0!J+0X!oW95GtB}JToepMaR%Cu7pv#4#I%DK zxcjmP-<+z(Pr~E~*ZJPDtWh+|U=(z}gpn^sO-zwWgI3LAz_64>iG?(n>kOvF+AIAw zj4}Q58@Y(@s&>Yf#!XI@-YU*Wx8HJGWyAFn9~~Q7tU@YjpOQE*n-s0@&>q}Bc!ax+ zMr!WtnP$-+547#Nt8)d5N6=b0Wyi=fJxgJ@vnH-jZeyQ80dUih0cFM+o9YR6b0>e#})U={`JU`C+Pa$;tYN;ufbh3G$cS{Eg*+kPcQOJQYZ zjK^Yd(Au~C(#Q5{RsD01U@=bR=P36EJy+CO$wjU=@!hFZ)z z&cygmf+uQNc9V2TA)8XZyq=(z#z(9`JREB%iH}d~5Gj#Est+TJ+y9ss@-`W>=V7vG zamAO87?bK&oQAp^`k}!E?uH7Q=bj-V65Bk}dwqA47(a#Av}I}sR~T>uP%%gQ+HO85lmmlGjOo46U@YA33}Qlur4Q8mmKE7hqy)(Cn;Uq0R4i!!ElW5AM~Q&ASg^GxL>8!m?7Ngsu^I%fdqK zA-YPM==7fJkiNv7>~k6yf=^*)ktg?n7rNtf>Fb}P0nr%fYI0&qMXEBe{`fJg%M?JV ziWZMBVMX+_)%)vOe)Nm`Ya@}6=sHwXd}DcoO-R}w-4g%H<;wG;C}J|1Mj{DO2~Kk3 z8!`<`C)a+-!O*VL3?VW*8&MTw^rt^fT*}#dZSe`MUJ+xR&!DIGUv4f~Der4k-#3Zt zF#Fi`xLf`BJsmvSKSQMkr_uJ7YfoemRu1v6|BP7wy#2QzMGn(n)Q_F>k_Z&f8xYgMd&|Mp7E5yy0@GcTzn;-f-6avdJ|; zqqoqj2tz*7N&-O`G(-v-KY@mN4px&9wH8wxGRq4)>Kvrha(*WFi%aJ>Jp~bnexJ4A z!^8=M>1tO;G#<|aJWpC(g2qa7x&~5-)>Xj6U2(dV zUYj4;cJei(gE)o*oR`)gYJ(`ceV5U9bKJLtCen!BEH6*H3ys|yq(6prr?rR$M_`(7R-1Z+L!K3AU<~F`QbJi- zST^PG^6fX;CsoOA%ViGF2TNKkvR6m)B$g=0%(8qvERGs@WyO28xdaGz)|+a_;JG#o2jM}Y z%|X{Pl1gH+k1e%!8EK*kb5NoPOJkM-j-mWLY(`g5%_{Yw7p8iU6%`FfCL;%h$2q4I zC(L4j0+MFjsT2Cqr`o^e7KK~m)2<3xXa`x<;#G7$Fs$T#dfKcKF2^>R6zbxQdPy4!CY2}@N6TEC-y@ifxC)3+v&Z2Wa)D*n=D;Dv4|-&WaHxE>H*(Z+(t;kTbmfb6${jrUj@>RzS17s~31*=MF1# z?0NsygLCY$$eBwvbSLnl4_Mx_ZO{=uO5Ct~vV1D%uyb^zM?OZMxFT%xjVmBK8fv&Q zKdfmP1y*sLT?YBvKW=Xb@WH5l|u|!ZNT> zzYmMOdaGV7S<{XZoS&+m5y{8qwq%<;^)r^hZa#vfW%)wImxSZWSd0jX6-n|lJG99O z=<`R)8BN7lHoSH52zB-|3=T#8u)jIbIpA{@$7_9eLG6BW zMO!jV)(~o&DR`XX{hgF&5sieppOLbbgt-3$W2#{!_e62=*IzDc&Bz;`tjZr>tUUf= zp%7VGpmi*Zanh4A%ZMrP`^vrJ5eBrji$mPbPVLPQna%yo84DW%8kp2#-T|K(3Nx07 z%VK78)MFO^6{mqsUja`c?{8F6{- zQIkXQ*e{MG4Nr}_a{%@gbtidX?DeW~|2WN(9m(;dk7BmVauq?XajqT`iVRUaD z5kNk486XU2UF?K3YYWPqrwsPhq$U`7&J`?Ioj>MLrF24W$N29*A7GIiEQAeBSk?~5ZjtK=<3fRR^r>sB`T z;$2-_3}YARk#d-7PKB09?b&NfT&mn;M8t8&&zjARWhREifS6rp)EAajL;iblzespI zSlo=7I-CdU>|bksu*M*Ts5aPDXB1YW{$&$|wWgs9D~VxZ_x;a;S<1!`x~OphvWPRn zWt4;DhT)oTMMdT=a|hm!4SOeVW%Ba{j}oPF7<}{f38e+PF$^fD?cWWiawf(B&n5~4 zNH+tXHh#qRtB8norT<1U*BEjPZsZ!5aWBUg^l6(3`&I@dDUw2uPggde zOYGG&0d>RVi|0PEeZ)}%%IuIL`c%QCSU&qCZ9mR;+Dg0o?`hHt69RQVGQuKXAPc!( zA?ESj(`>ng8+VTVysld^8j>JV&L9Ccza%^5W%*`i0WV4I^eZcig+{U@Iunz1fp*lFKD!imT2fJ(1mn0Pvw{42{X zxltj^tZ`e3O31iWv2&W)30vX`x2WG05lX#$d%PKjMnMUzlbCFQf3c%T|aYCaXKMpuKBzW}_nU$l~gW>E2BRVdHco*-^B=D|R`@ zQz~8xft?8z;!oOi$6mpNj3K{b!sTA7;^$dd} zu&);u97J{Faq*l$%v+dqj%2V1m#HK~5n9OQ0jd@cfm}@d;mOHKFgPITmtQ}F-~5&F zT4oc^`@7i|>v3J>?Mouf^4q&E8T(Hz8F`s&bL;A4g03OuA7Ax1ap(gm>Gu!!Jn2;d zP?-wp7UPXAosMD6G2v)zLXp_l z#N)$z{#u7t`#n042)ag%ZZk3SR=YkHF{5<5QpFu6Q{?uW2cDN_=aEvb*Pk(9W~Z{; z65N;IOPK26>C1+heJxbXOIM-b|F}s5umlD3U*2DA(;GhSV&%@@HNmh%RFPxZV(z%i zvxuC*s^$pQXg}&CO%MmP>IYhO zMt?iF|xRJZ3<1(+-&+OkVyeBW87A z%UfYMtCjNRQv3jrV<& zja+->^F|$`1+*QxP*^4V+2X6h>8{~gdeY{GqI{n7Zp~_kcf(T{rZFX;9F`E28~=rD zhq?L)wZC>@TXZx1rhx4TiI_{xe@#)T>9?o6phgPK$I?2b%P(zfY2;gqgB3K=9@T}g^ zHBdc_hZ;Uf!uXVFj%_{-pU^gpOL5Y0|4}42(fji0v&d?J$f{YzWZ^0qMG3S~L06*S zk%G>vq?iV7BB(HYWkF2uLyDWL!do>A4B1{(R^$r(Ue?85#>BOr#M(NhwUlEbax+|t8(U}8FExUc_p8^5z21r?tl&Z-6|by-IkV> z>FVoKp%l?{IOn&gs;AkApZ@Q}E#igb`CA*^FVuddnDA!XAuV9L0qm6LV5OA+c_z5^ zwzpxx$Zz!oNZq+^Czpxn@E8&z8Xq+{GRRmaQ2m#VBhW~<6-}NrpL&`*d)6c)YErsw zduC?nbgGQEY@YAjpTI<iby1PW}$^n;((Km*ukua)kLpw6zraX5)R(g$aG?a1u(l zmnmwQSF{osVI03{!y;MLdlLv0>2oe?j)8Yh4&MN_s;IJqQ+T;`GOht9!iVEuDI{5S z0%%641RmeSSvJmPGPkD2&(j({cxG&BaK0l5Zov7gk6N~gA&ps4;Q;!RTU(cA3fIZKLHOR%+IP22_Z@94aE&AoIOf&)9N@V; zY@h@3q=154m>NPM2OZ6XB)?42%AeuPe*Wu2e&+x;;9=Z#xx}I>^p~c7gz0(p`M&vb z;ouL@SZ0a}jcKZi^lDXh_2a+UNE>oBky7`AP34>^ee0T^)M)P~DL-Q*haDK_p`@jv zta>(~_~vY9^$wmsp3M|d`Om#+!R(RS?K!RU%J+ep8N95yx&;NC7a{Gmi%o^ux_%C! zPKzW0ei`Hsf9`Ym0$_%kI2Qi!(H3hsIy;^gkv~RmZ5cEyR(>C*qAgLDiRo98v_B%c ze#cTAUs*l5T5>I&+#8hi%aNo6@1xIzcfWlkUv;kB^fGifnPqJ907iVkmCxe_LmXq= z*=zSofV!nrcK?;-g-*fGj$lf<^RFdHBQnXoy|gSt-4{aIfW6ab;9VHO@kzg=@A8tn z-o2iokDu0JJ&X4DIg0Xc!vjo>G)s9oQ|` zWaW$0l+w=1jPFI&bFjcrW-f7c5pC5;$7?vTWHBvn%$Jpri6J&&EJQbvFY41EquEbW z-~eKQ*DMlUSHVDkrHF$VEQ3LjIPtPM?p-!~v&`l-A~%D@dPX$?ERh}e1VapmTxDV~ z)CJC)nCz)EeleYN*8*x-T5T06H#(7M`3Jp55sh|G zi(#W8sA>;tSQc|asWGxAMVFX2M_)b|$8G7!&!3JY`Gpz=^G|t@#&T(sn#I0%?x=qB z(~(FVYTw)!HB1x4>$+MO)FimX+o(p=z_0c*x{L-Y&3(J>4w~F)0{4wx*rk@n3z~k0+$fb{{j1j z_J4`~ek7g!aOMx}jFsD#L4Ch*?|NvodQCt2HhkJSSkNqNSU3`SrfZcUF6{@uaBpUP z{6&eVFC6Koe_Ils%|j2ri-gXW>V=**u^*NLpHCjPySNcn-SFu7o#->y^F{s>rXG{)_MzR=W^`b8 z|B1<;Yfa6$rjg4_mMQ~r1j*{v(#e(L$yju*omIiH|F9n0E&)T~UaL0l7RmS>H*m&2 ze{s{$#?Jdi+vU9+V&6Mqi^h2G9EnO4lmlSi^(e@&UMettO+`voNChx&oKGIU!T_ND zn~qj*qmw8jEAO*jH2`_5R4A5B7nZ@LIn{q}fVS+6xq6ol48}V6)ir(6hzjPVI1S}n zd56<%^~2EWqxB~M7~5Z9GH7{?0Z?XT6H5;6^!<|KDn*7qvKvSkQ<2m6e( zhQeAaTdEseIgUCGaL1De?gA5LrAjZ^3;<@=iq)&K2fEnCg+K}0DHHKeuurMP3e|(K~;8?n_|S+n@BBtbMbt-^Kak&xb5WpDg0WNCG+9;e;{zWos{A~{K?@s48oYj?`{8=O+aZ%uV*n^!sZyH$e=R`AD6!}h$3JHTfB(nA zc`X|$=lvFnx21!_X=rG$RA^3t<46Gst_9aiVD>P_6*j=aS5G*znIg~C=MsW=Qbm9j zas9fyd-MBsPRalm0e0_)WF#e6gY1U1boErm(j|C_7C9?SMENk-BDIOWl&^D*j5&QM zRF~{ox`g~q8@*WYW>{3}#58!ES{VUQQ~#gavC5z8`rcVN4nYu&46yp=V=GlR>ZRj` zaTgDgM4zo$89%Kw$NV;>(Z(tG5SH-g&mTGDLQS1uI(2Uz{);7=X3~M%&5rIE-5MgZ zNUSY=6IcZJKVmIw8V27cbSwY3d`LJTTK+3WPp17j>@uyEo*q*grIq!w25yB0HIWka z5MEOQqVl@xC<6*if2F3=@WdNl)A83YIS-3GA~DquujWzu*`b5WAkqrbsk};H2!lW@ z0D4B@dms6)yH$cZ9!v<9?4Q>xtNNu{ZjAi2acrbkK#dfpfbozhuoEQ&OMM;BFpuSAkNh{Z4;wDlqEzJU@gtfIbXmT4@%Q{r_o)2;clauff zDg}>`W3#wlhupuNIPU$#_JQ7yoi{??p}4MwB>MvY&H3Fy^~LXg@-yI6d;YgNFc$zK z+#YURSMI@M0&iN(u>dlKlBA)+J;sjn1ztYSeHy@Clyj&uZX3M4*tuOk2>|!n?X8co z-xB$%T%j`k><%A-MXh6>VydE&+m_2X>tfPR(0~2@f zH6;o7GjZ|?_7~JctPDs5JySH}g-12Vg!-p0Nz$yi2vELz>`|R`+_M4y0O+-U)?YeR zkuw^be7+$FHa!T|H+f@&M~eV{;d0h>PyXKh)_QyUH7sozPI8<8U3TotqPGiBw(L|b zDRpRfHw^H`rIA1gc&sqFSP8!#x1Ji%Xq(=?+6R*yPWO7QVNwC99~`~EEz0<=yYVv( zGIn|#W-}fivm=vwmkRZWMg)kniEWGcea>l2p6?un$@QR~ILpq_L+PTM55D-{Pgh=p z>~O!4NKBfazKKl5I52Q8=F2ElLNmaILmFm}@Le4fJH0r~>y4qAK; z=uYxP$J%zr+z)10!QgZKaK2vX{;-}zzyo2Z?z_(g{7L8YOAUmq5jtR3y!w4q^m(Wg zSdhvPgaPRsZ~+f_Y5cH`&+mW7-LFbgq+gB^2ILUL9P_tNufawzX+NXu<*xc@4u8*l zKe^5EI0-PfFs>fEKj|C;lv}ia=7EPBHn;21CYE-th~O>SMZekIi1!9gn=Qa907xN# z5}zwRf33wP-@?-wub*-4o(!0WZFGktKRkJLzBV;;4aV=hp^DE9hyf8(-=Olw_~a>( zS;xGaUK)>Hr*DJN9d#rjhON!&Ya@|+y?c)Q-R~w+fExv@wT04ze*@AVl(Da?zv=$m zc`X7sEC0^VTB{X6^H((MoC&>wL{tL7jp6gAKxchGgoPjg{ejEoOjuOA4EnhEvCl4|B}7xFnub_3)YhWCN>9uWh#!K# zGHXeHZs|qiUr=>tTqu+wj5StH!o`*v1Kx7qntz!% zaxGzGcW>#`U#rqRxh(w5Nb@SvL9%+$;=>ltv|D&)rXINEqoboeT8(0YJiwVa!DW11gV@$_((#(Zh^IXD`#oPAT+e+uV*h~gtOQZ4~K5Q# zWEsurtGs|ayQjPA=PYX3ZFLQeidis-YzHhj-t_d_(;oE9tgLnLOpB-r|HT1ia#OK% zO?*dq$R+#vrHXG6+z&I{$Pm}=X zy(a)4Y2Lf`%@OiRI(h89{zv--?^kWK;w;dLu}?crI5)Sn_;I^Td!6g9$gS064=MX0)7>U z{wWdlNp$hQH}Lz*T+PYFg$i>Q`ttc{F|bU(;%tL=MQ%wmFao5xZ;4{*fcQr-oy`n| zWwjMiX7c2No`Jy@fVhG5J~yCRwrsLwdf~Hv#p!vv@%DkqGn1;&84cJOWuyg-!RD2Z z(fV^yC{sj1zL#E2n?7KnmDV;gRAd=k_YZ! zSo7=syq(@bbq%Vpf@yo#wMS$_?`IecmxLY)NFx)h0wds!{_|A?e6oS1h6po)HjlCF zju?2i)z!K39I7k7Aa>u#k>+QPhDn}G31!z8O#ecoYQ(Uo_6s_QR(?XDB#jwhc4=i3 zvc06DCznIm_aK}l`i$`K(qqy4pNIj^xe;>IDrMUZHRqyZV%2I<@VR2|lR^mza&A-J z^hLm_C9PIqu@FZJ<-|+lfen2TI4N1B$2Unk$Ypg{8fp|ZFfAt~MJIAi7kxR0<=nRt z%X(^;tF$kmhee4H(?<_OmE!qDAJuOIJ0k%jK8PkPp1|3CU6j9Kb;(~d)G3i>bdzm> zIF>Sr$mBJjhPqu!20uXLYkmKXHm_??RQdKDZ4E1aj8ycCU@3bD_s;^=IVWsSgE0q^}+`n!0T( z=?%&I1N@MVVeEEb78`h!NM(c@v zL!oaNi*2p{iGr7C>l#_#k>S7$)v@b#q-*41kn0Ts|NpfmN>ZuDp5<*6(%&phSkW^TP+eSZ1IZw(H3 zQ$*CNjhu=xOC2r%*5fAtj|oQHWtjXKwkT_1e`ZUKiq;6BIG?w7djHhzBhq?9iC_Isi^8#-vo!_j z2Sbd(R3r%m@W>B#cT?#*1Y8ycZjY}?3O!C~wqGs$M}u^j6gf3wR>uPG zEJRv963)8bu0A(+uFpX>NPsigdaP9lgM?mGy{gFQ^WVT{osP2whYY#%wb$w12iGna z$ATy4gZcicC;lh*LEE`rPryr?*Jo>5$NQ`o9}tCdL<92xxNbC0cxbIB0_c>nI&Vi@ zzPoO~1MY-~j6+is5C1uou;Z$+`W%X_iWv@sSN{yrZzBS4Ub7j0%x`JY+ulL9Sd1cn z+?6E}@ypoB^N-Upc|;m&)&_oi0LJ)Twf0UG-w z({cV|0)^BllAR%yZvrz9e9!on#o9+81%iR|>``&w@Z49U!OKWa>o&7Z4BfDxE0ssp z5KBo+aE*Bf?{Dk0=H&E8WyGA9C```J!|^PN0w+X`p@GRPhqI5ds6?3or<;KWDI8YI zPt-z91~VLUFg?saxN~d61lCZhJ$u481moy;9zCov2#A&h*R=#!zDh{(+26MLI}5K_2=u?( zn?;7fQ^DY3wBQ|oljL`^UHvv`ydqJ3OF$SrC1+udydYN;$$%KmfCAt=;$`7R@#mg@w4a`FR}YQl9=1mPatF9WK>-{5L6!6IQJ#$aX=-tv*=F+U>Ai)!i1y*g4N zTHE0H_8MK1Uw?nlp!g$f5k{>n$?AokiOEi~!|Z!S+JB$-O|1pW-79b~?OuzMkTI)& z88TpswdTG3_)om;M`TI4fF!*FbB*YQM3`{BPKQO^`|!QNiI@^r9HXYT_FvaIZUa~Z z%Yq(@ogE@0EpR&UZ0lWEAPViG;9>dRqp!zME1FevY^>rF_1yi}lFUE4Ul{?7}%?T~L&aLh!?a(mf@^~G1Q zAPNLb9LA{6GzLkF!jow`x~wk3Wbrm4YJo_d*#XP_!u~9(24z3wn`kxHRn%dnu_zF6 z(wL??mROr3Gw>5Lc~2_g;1VdB9ySbTwnm13{fhh*>7Dmnuj_CXi_7@)LO3t*i3->z zu}y9F!2@@m;&RQ=o%9$P$(dQ+79WR98R|dX?)Zc+11bh4Dzl}EFgwUkmtFh;YYY$h zFI`ckleY7cB_B#=cJ|IDM00p7-_q0h6UCRwqtW;0mP$n{(2G|>WBr;)s~4xj;Z2P4 zMD;(KdmLQaNAFKMMq&*X9UalSKbfd{(5g7j&0Zr>X$7&)Y!*+~$bzTdr zSkwsGRi+r7>QF5Wbejm)zAwXvteu`|Ebt;DzRPRgZG<8osf6|YVG zAM|teD@WJ&xP%^ueLx4p=P14UJURa<3>X=#&%y*8GzUgUj{!pe-Xs`YIASW?0y^yN zo@yZIeKaHXV2%l0aOYKH=ytz{0=sMVFThpt@aQjOqk#gWL4Iz2emlMM0S+0t4EWpn z?Fg=JK?jlnzTNF?y|>%q9v}RSJn)hO)DSfCQRg^$ZraL!^>eN32f*7a@Ew#CTwIbM z-<>=P3bM)L9|NB3&le|8ae$F$&gq`Q%p?v##AsB||-ON)SXr*wCBBi&u!;(osOIQ-)e*?`wt*PL^VInE64WV2zx zy;I5ep9OY6y7+yt`_|Sr7{lkxTH_eo;s+Gj6*+F6;!I6Xqj^^`!V0yn?K}sbdar;a z^tRhu!t7NxNj889Ae;t#oo_ANz&@_zL-c7^(pfE;5Yf0(Ghn^!XSa5T07(v*- z^x5YntJACgQe35x9gYrk8;!=Q&y}h^e(?@VNH{2PshD1&eZ!NZw|rr3*P2t5^xTEO zx_JBtpOB;Jl)n%zGK!|Ww$yiuPXcV_WP6NZc=~aH)wE;Mm7kc18F3XQ*E1^vI$}Bq zoAQIJ$;4C0zq=F9#<_74>ser8CQjo}NmhM#75Li22w@6z_AABsKB2`zE1WN>-F~(Q zdp&UvpMEJ7T&ip&8iD~&YCXkfG`!Fl+{Ia@auRg*A)u%BV`!H?B?TR20tTi?)4{lo z^%(bJt6roOmr+`*NG163608Pvv=3>qK8I7r_faQB@|i|w8e|?*I>v2 zfN+NcsQGw!I~SL=7992Y!RxgwvTn8K{huUPEj0R7Q@}6(pO7&;0PTHR^`s1_HBmi}-ap#SikNkSCm=2QPuwY+G#ehK}XnZK7Mzmrnq=XKa6ntrDDVvG) z!y3%|1JRZ~tJGb&J9w@!oaZgMSuw(oOtHCwA=-sk77N)Mkv~hdL(32Cg4{4JBN8v9 z5%W8yl0o03VwS#^o2YAeI3WeIoIh?$p4+kJ;3iEQY-Gk+S5-9_PoGihxre)aJ5_V7 zyX>D?JZULO8XENi^v8{7Lwu>c&LPVWi_6aoRMuS4%30%a98x0|-{m@=kjAZt5kOi#!iu=YZ3uu7!vflC zop`z{HzhhbOGV>v5AAOr^hW1*98c=DZ!YPVjm;joyjRKqGIp^xUG4z&V}R zlaq*&p4L^C&QTtE+lL>+@z;1Mk=J<@Gr*TLk;$uducSrH4pxymT!jUi=w!idWYqJ^lcUC;9T}9V!qI+IxT7q*vi`M+HteO@ySgbPQF_>_a#w z2$u%uvfJ~^4%^i2f=2z|X&*Akvjx)_*yEFKV(>PwJMPU_=YHCEPj9#;0u{NDiwiC- zPWx&UfbtBcymvopx|*3=__<{6@R;NXR{Gj#40m?ryia3&OpJ_DKrZ>g{c;X2tP`&dfZCaJB?E3BlaJ@D`<4g9A|@)2&<2&g zf?cQf%eUtyqSIgOzBPZ=oWx&LS_mDsa^7a{0QUvxH&;*N`)Ozay0d+_&x$j7z^S29 zn=$dKW`46EKOJbXV3?3kxO|1=*@ABc7%=x+zRRG=7DJz)X<*n0Ati-7b3D6Wy7B?R zPa1m5E5uKuO)XY?d-&Px^tbjyeaJX;L|9phw5DAjT&eU!7fLscEwCi|b*U!#G&6<$ zk#QjJiKx02#siEtIBc0*crYix@+oN-q+}@NTz+qR@lOe5%)uWP8y2|}k~&nIQv9&9 zAvr_*bIJG9NZSfA1H@>+7sV)E)||rM%Ltt5Ll)%=7~j~Mg?1vZLnbVX zaLjF@#g)!>H8P{!CJJcu(zLCFy&s+G092!4G5{er{9K>xTo%@){g}LDOD-j}Yo?G_vo|TGA z@}VbCa`cE1I2TtJjXJLsF#fKXe1>m>JZN^p@F1i7euDQK?c?I$YVy@DbO9GrHbuR< zpRGTF@A`1AJ0Z*0|18@*W9OVZE_^^d2N#^O^caVUt7{@nNYJ|5_Zk1Y?hGC~!$^*A zeymB_?tcaOYxh|Cuii#Ne{8-|@_?tM7*oL~b-Q}dI|D2mYJuBhkxLhs9kkm8-Ou35 zMApSpORmEv)$L0tb%2cTEi~`rSC1PCPjUSj-fho?Sj~ZO13N*G>y z+Kcnd;|+0L_DTfHEo<(`%ZVC==+`;C1|SU_&BqZ0Yd5#OZ@z&E4RyS~pUgPDwQ4c8 zgSL)SZ6pbjdJU*M`5Acw}RQ)W2kC*=ENLS!pPvrA@yF3O%EN_xJaI z#>UNJQ9mOV4%EUs{oy1$cjLIjKQHx!>Fet0ZDu^(P~TrYUHPEX06Mq( zs^!V+@fhtX3b@|WWQcWyX*;KzFF8Gz^VLcKmv3-r2~r^M{#ZC%;c&;bYTmQ3&%i0z zYAJ##HZ$QK->o#zbqk-N)7&;zW%Z18LoN4AZC^#FjDOp0-*(&eoY=C7=e|~T=)?;k zztNzk0`c!R|Joz3=ZT*fYit=~cXNKY(v#H)`!}>}yi9c8AWYiKcqD=*^$E8;-zjwb z)!c7_p|v%(!NN}PRdLxmah1Q?4jWtq51osf5;>c#Q#q&H5gjn+czM+DOKB-c_pL|u z^m1AGB=RT4rTj4=m~g`Ser=M(N_Oith0;AXRkNw82_9^c~HzGdB^)EHxzS2ZSHh7&LEF~xVn>>vA zcwq1x=7 zl0{?e*HVVzc7$#drDQMYk44`Jg&-k_HfU48hp7g+g#2-pj3-Ixi{49*%;zUe(&S)|mYp@3a1fSN*N0RA zt}YMsl3_c8N1=rv=0@^;zC@+VL*W(tcjeYpQ|spzH5`mjGWH?Zdt zIcnZ>dC66!#poz&$u1}usmx^3J#~o-&^I7vgskN7;VWyvC{4%K4kNqj(QNxGg`o1! zYuSMk-k3i;cyg4ly+0N!nOWH-UJ2B8@Y%Jw27JUx<V!=R-tKhifdsTP3lMfK!mO|k-vpl9| zI@-enLnD@4z(HZ2wiy%+R=2-JK2yenv(UfkgU}Y@$K$|MO`VOoDo%kL<0O~t%{aI* z7A;QnNGF`V5D_}{`d^}fpjB8qyGc_{>x4hUd48M;i z8y?A2`v-@m&GmA&`dIErg@uJoIu6(;^UF7HlsMLE06yIF>8?cqgvYqMCxKZwcryV1 zCG1OS_f8EA#4!6M`!tt8Ah8}l90BMJgF+el_rmEvtpAScSu?Sl_4>PdYKwE?PykwegoPEC3=}W4pL!CU{4ngl~T^#|hkT!PV<~bR`SOIEQetnUG>m z|3CjUx-23O6Y~GNJ5*~Wh{~^VM(Og9em~@IZerhP+L)&C5|mtyu;ocNhI%a1NAr0x zOY9<{uodQa8Y@Mk{=jY{-8sYs6(J$DJc%dqaAHS~EX0}ATjf)GVbw3^ZK-Sw-r$b` z_j3+L#J~m(9@2Tuf9VbJiJv84is8i$psnhY%_9*Ig z8FFW*m&KsbTp2^xv?y)c9F$Y>Kk@X0eO=N;a)Pc!=7$n)y`gF~j~SiPU?K0EhHkX3 zno`G~Jiz`QCqYz8nRxf$>*1`s@y58`yK=lEwmJMvPc&Ljm{(JhaUAAvv)5l1z!@=2 zogw+bGPim-S7PJSkA97TDVfUgw#0BZd|BcBHh@pxnKmZ$j3|K;3-+%!^FsFW_Z{~9 z?%8a#l-`5tbDhqmxvj4A1QyiUr6p4kIRt<#U_k4(wZQI|9i@a{-qhsJ#q0ROjeG7F zGA$r1eWMAZrUTv5HK|@?NSwheb%fCv2jz2Aj3KymEUS*ax=T2AU*D^IlL;pX@HZ!k4jP+@tA#~Z`CC$TEw2Cx-*odTQ{yi_- zrZ4v1gOPeT`ga;s)~*%$ZOz?N6699>ViI{W+a;~F%U!w4TPSKEl%d4-baqTG;2~)E z53~Kl6l1y-e}5OS#U>`;M~Lqq9ymaq;~lqMEnInZ+%93j=t`0l5FYT2Bx8SoE<>M# zLfSBf!T?ytii_p^qVAWD9t4I3U85rf>-(1P2bWjx0$BDlv2&!f+8&L>Dx55IZY!R`TzL4Z<@>_PCTE2Sb+Go57|)RI=Q$s6zcazsaz})^GF>ekT;1|Jdqi)i zLnEHnho4e8SZOv5iZ}BGACT;t9^fsK*@#ff!cW%XnKj)11t|#L#DUoKllT%(e|EFs zFI)SXaWMe@2aCNlG(WEmSVW@-E<8ZhRpu!Q-8>4Jk zX<*|V?sJ>(Lnfsxo^6o%ucxX1ufJz8;v%xbn>QY2c{qPmEIIhRk*WTBFlH_^ZGDLGnC0}eyMlKSKxEJ;|R24ytdnFJy_cz~zS`y;B zx7oPSd7`*Bbm5;57Y3b8uZ9$@s-wNrdg@8qy0nx@glZAh)0j+4MfhhrrO}Gt1*0Gb zL&gIE_OC+*JB*{(w$0pG((%tX9)n|3ewdQ28FkD=SC{Y1L^Vf$Ne$UEboRs}# zktB}${C=PpFg9btUc-8SWc(AIj2+vBxT8FY7;T0_)t}8bTak4={IW&C`5O*ABS*o+ z4_*%Ws)Bj=hC-+xl=NXKDh{?%$YhbEs%r)j^V?*=1itXF1iZ85;F~I~6l^@4kTA>Y zzHC-L1?UMXG-awqgwdX^zk&Ax!V^*Sym@J9>Bok}t}|1~wI6^88mHW0uOr%V-`HWx`NU6n z{2g?|mgD9eBLxt<0pf3Xa#o+wKT5^OVl<%DyC4{~;gW=3GORQ_J1ZWXB;_amA zr=?vhw40~nhO=`^YZueH*?fHMhnHOQe0(~G3hpVXRFGUDx8#2JPT*mmo$LL3aCvSO*DSSZ^^c8V0(>Tb zLPEmK>=H0CTm_F~I|-K@wSCmPU3tY-<67suhpUABjCKzs_JJLXPHWQ5 z$laU1=?Cz5TzTelw>1hgT!piC!RwdIUI$iUg>fk~8UKo0)^>yzt%?k|M{HLyl5k1} z;q+4Eq>Y5QrO0d<^|p&$b+Z>w@WVYkuUGT;F9Y@uFK#9g60b9!j$QeoH$--gH&itV zcC2CIpaYt||7Yhdiroz+!}_K!0pQA!Aol6V&(Jlob4~mtxbh%#ls)ceB_nf=;I-s_ z^^R~6*8~}xJG^*cvP$<)Q*QNa*?!NJx zGN)`ZFIh*9N%3}8ty0W&AC;IPKM zHCJUN#&%8-p`rbGJ6r+kLMe^TjM8<{k17%T9QoiIP$GfUFe9q+?|xl+N@{ch8h8vxL0 z)_a3!lM13LtAT+bhtmn#=Et_s0cSJ(HwYc}s8gp)VArytrhjV-m)U3C1Xm#=Ppt%t zniV+TLARF^lT#qT@!rgRh+{4)@a56f-FlQ0LaKIVTdZ#br9=KF8 z{5fTELftI;MlLl-uGIy@Ls*rji0lZaR-~PnTA`IcEnolQWYv95{{b(6AiNSYG3^ss zF)ZnEc$+0L0m^`)kqd{ZjFIbWy7OP0mWVrT@A4@K(k%0EDRQH zYYl4+yp;|24-Gx9xjTo7$m+$4BBe*1RKn0>%w@HTZAw#k)CLl`ppQmr@lke0X@m+H z!s73czO|V{F$=o=ki`vSq|edX`Pn6)7V%q^yEVn0@#-4bFJ~HpoIb3!&%Ail&$ShR zS1z8Nn_C+n7HHS#f0n-s{Nd6SRI00MW;OJvL&)$v8dc?S@=k2+XRi61iEqB;s*x%X zYpFgcf&YbXI~QLXT?dht${ zs;&V7NECQKgG~!i=F}{C#-_ZtW5Ex9){Vh8bbs9~2(Rzul?F~TD8;45v1v_QhPZ%| zZ0G58!`AFKS@o&SAo4E_P$(R&-2KA`<;0a>*N$!`p@gc0drArXm7t1eQn=%IrL^;TRY6< zs`mVHe!pnhG{2?&v`@|nIY)B_HnTNnq0!klPL%7J(ENOnZSJDGaDmm;p>h zjzry{YWdG#^vity;=urfj31_fjI5tGuU6S_M1@PYPvzen~IB?(M)8f$A z*i|%D$iz^ANYHrjj{w$~+kOp}x%rxmx%rq(D%s(*0||_QgV%z>2VdJRHxGiA{HXDc z2^2K^&bI{&f@N5^CCjyctE{FK)4}xk%yT_n{TCQ0vwdu8hp|zbgc5 zJ39ah?RxxiC0GkIFX~b8il!#;6SDaViT7y5`ms5cE#86m?r9u|ec)U1SF> z5|-~_GviDHOK3n=So%{-v5(y)~ zsYPSeda2!c*vdeN;mh94;tVVUNo@j#O zwBbk&7b#aQQ8PE%%tyCtwx54?bJ9s=4VAM$yO~*)X+E(ny5#Q8SU?JLz7AL!`U#=P zkYS2*D{D_tRQba@4iAkkzbl10Co1uO%tLZE`b7}hK~nTl>svg;g6+HcSIFhhB@r%u zPn;-yR$Pwns<*He)JZ`9Xqqi_G@#cF?UKT-a!VLMb32P>%Lc{ zh}k{8rD;BD}@d6NBHBzu8;qyTLxaae5v`||n9J5=L-u2pzmUJ*(j;`nQWAt_y zZ|R@AJ8k!7_8e}ubngUqY3ZD=s@-?e%vW|b ze0=5ebaj8B_r#gud5Yw_x)Nj>H!wU5)_$&@I*6ZoGsdiIj;&s%dH8nT#NO{Ic=!3- z+4*z=dFn3>5otWxXhHwyRE&1}`&PG&MmCnd7**>&RcshQ3t7dHLPmOoA zdl7{oG_cje;AWsQ`465^>vu$n2}Z<|cassqjfyOKo#yM$kY;2wm`?9qjJX!IUy7M+ ziN5VqT|58q$CtZtrMV)7Nl7r0gZvEG$YhNw%b6IC%aHt`1$RxwN4O2l+9C;ZxTF-~ zG-C`T<(;nzKi-b~Yc0q(Z#j0B_qx~%ip}4-kyB2Sar#~zY>|TB&>+?565F(wv35~& zJcjWt0#VkF#Dy5cC`U*pTrI%BMsy+U1n(8$c1o(J`?oEB+`q!%wHU0&2mk?*z#1&g z?!YB;!Il~HRwBz`EWH&uaa=>|TPe&ijpsUsMn-+HQVnOlP@;H~zrx2K;?|MXJCq+V z35?>z`(d+Fi?}bXhi2!3r_!?A#i~^tA-#v>$5j$Py(}lp^X0y0Dm-mL_K0o2Tnt); z*#^vfmg*iD;bNCmLeLgbCRdYFZV?;#5X@^2Z;DsOjuK>=f-XkE4->0Mo@KSb*gI~C6qW8<>BTI$|Q^tF}ut6zxBJmssF6NC7m6LHx~VZoJU zZ0ZXqNX1p4^k?$EaA(r>Ob6q9P(0Lmdj*4Pb4pDejQB#w?KhXiBVp={5>L_EeC?xV73c($jB;Wu==dcUN?7`FBD$3Js*dhxauF+3V>Zv?pN-pF z3c!BM7pfcrI@zHi`Di8)9^+yb#8u32;lATzmbY=jfd4suutr+z zzD|`Wc>VP~C^V**-Fz3*-Wjh-Kv`H_t{8R5?q*w7-$50T`FD0B;yWx--@O;R+q6i0 zL$#k8)#fMkclAPD7`LOb>=2@iJjPL@@9gy+vR9}6i!$8k7W$#Orh3O|7ZgOtt9Ak# z;nT}2povZ)%{MlkW%=YvilJQVS*FraERW@}B! z7mOgShc2zmCMj+x&7>F~Y8$k$PG(h;>gmek$XQU;0bhzc?1osZ*w-E_!1;-M3PazX zYALI>c_EXgWi6Ys<@o#?h2{u+#4eRxi#7G=tr&>XmIuDCa}Qp4Nf{aVztmH}tZ zym4Wl$*Mxf-Z=BvZ|O-j(7?kJ;=Gg{?q%9fuv!>S8YZlkp#IOL9_ZJ=!Vm*A3E*~m zE1k)%S+8623dTxK>>mWhm3?_p1_}{JU*;1)!?>Z@%WaWVJpdPCY+&}%9fw?nPHizo3w~)$jl_S-h-m>lEq9(*s+Pgzh1f9*&LJLu z%}st~Ca(wjq8&QG%O>lBez`yRfu#CC2`hT<^vC`SsIydeJ96VOP_D zfKwKOfv!{J_qI#MP^-`h^BnY9b}uD-^?$z%)*_O!`jmSH*tJOFoZ587cQ@6;;Iyel zQD}q};)~5~rs^+;c4?^y9dsnp@)mS8S0^)`QWZ)(C7V{G^GKmk=rg1c z&=s?||Hi_kAQj8MkKXi3n;Jk=nLtPi=Ugv>DXPX#nueAO)Jf2RJyqic^G6TP zusHnHXv5&}&MV7b;wUZbp>Gg=P_+HPPHdR!#KxE^>tO3Q*s>swMvhSuuEb)kUCigw z&gYz`GM_k!i_GWHvdqCTBGA_8JIrni8E|y*nb%l_9p#^3<)Wr%BrjA9mLPe>|84~( zG8wg1qiE7x)Wrc}C(4p=UcoYeb-;T_o+4HU<7#I>sfDkc#0xWt9A+2wPRc8@vlk^_ z>XL#F+AtH{k%w#m*Z19yaf~o*bjDnAVZL)B88#eOw=lR=KZo2AgCqyoKCaW4E|PfG z4pC9>^f61}eVqdOzP9eiilUJ@9fft9Nc`(cVDxe=`16Ku-Y^XfWW)iX`q?TVpWp6Z zqNDHPl2BomVaiQJ>SxT2|5Ih1Y-b}KFP_^Amde=&ftYz+H)z4P&qt@r(I1)Tcj;u{ zDv8~7cQ?H&+Z?Qh!{c86kL~6jor*f6GMg;EbeQGf2!B<}Ces_>~EuJ_+%-WLT=j zoIUqCDd0LRH;yLaC*2~2I^r|Tlzp*aAM-BHgR$W(+@ml0v&?%+s}lPHxio3|eCCxq z+t92Vgr-r)pY*EM8B(`-cIKVV^#XlkY7T2Sc(5@=Z0AFossJKv7e08)gRXS#L8e9E zyiRtf+14+~@CSiaP&WEk1!ldi@&3fC&lx7=4s|(UknJ8rel}PbTF2~=-fefCYHskj zPjR<8bVJyV6x!vzm}6@FUO{$)L@V;FxN&f^KlFL8|4w~T;TOI z?^E4yf5PP`lcq3!uXE?NN51{AZSk(|eu$RDPlym*bB+>fo}5XIvUw#qZ3ddTU~B8V z!g3bEa1A}Z>{)9TAH#H)!ok`6VK)5pQC>uaY*YG?_i*TRIb-!_rb(toZ)ysC&#xnIXyub~U!jK?kzKt&>sP1ct92dd$OC(l zSe&{IA89^*w0jP+{{>8PMFs32?(ZcMF-(+TV}=YU{%&*NWHLv@h`rwgp&xq=4nh15 z43kXJmmTM@G71U`uD^xuu*HNIwy%^D5%u)rgk&UywG7ym-^;X+i;|XaLvzbTsc5<7 zkwvsq_MATAe+!f#@$$pOPgR#NG@Q;LLtEsh@;~z+T3Cwp@u$J+8)wU6kGd>UShQo= zkHoh=z&J$3V09B-(GJdV=aPZ7h+_#d#I#bX;`OcwE}9%or|T*dA_<4j#=wok7VY{- zB!Ulv8ymaoLbN%6%gH;1?qU38yJ>XsQ0Hnd&Ot%jh@nfPk_+&L8zy@zwch`q7a$MB zql#lZct?7-sE+}%1ZDj6nfz@NHQc)U&b620f@#V?5>)j@vy!K*r6rQaYZn4;1fpME z8?nJ&59tSq&9af>S#Q4I)px}^Px6=&a0Hlrz-J#zCWnXi3ji<}i57hxVU@w&h^E*72_h!G9qQ zRjvH>l_zBuZI@qm)rn4zewO!b6FYg0vL$_?klBW8OVP6d%g%5pg2)!G5@z}913#e| z)?MXl3A#o{nGRcsS__#YG5_z^-p>{uqJVOqF{QCKZp?6*Q4xDNj0+^85UMGpg2|zL zrLePX2!iYT&&wZXowm=!ggD3?+A3r}Y8Ca2mmn%4PadLkq+EyN7Hnh5Wbprv#u$>E zPzN5If7nqol z3lrv!yp%vf7F7g+Dun*bUTsREW1+#9!p5j%RoCK}`0?(@C^>M9u;O$%N2HdVyNhqSu7tSj zbx^)l;u$1=h%aJ*w`z^&h&uoQTXx?yv#IK1_+_t2eoL8EhE*R4l(A zi;wjcdxI3{F85Yj_DBBe-Olu18W@SthM*5vB!d`kCG2P_+9@rN(llxg)?q`U23WQx z4!bf>L)#X49Rvy#@eX4KnzV;!nft~s5AB1ZZV{vFB#4@**{;mLUmrugqS3!5D`#$J z##gMUpuOnMpAr32=bCtcrP1Hrm$E4$wFLcbl~lU$ba1E?(|YK>?w$I?7gU<&owdGP zB700E3rGA}_~yDYx;kenJvM;LpzR0eTma%%zos?_aJGI|!GNTE`Njf~tY?@;+8gfM{9PlCu zf)`PZ#RyYtBjb5eVbEDVqHRK@dxDJk>E#dkLWadXV{lSq9%(;EJM5}3s(1?qg68*m z(R`U8`7>M3r2a-9^ksAMg%-gf z?wlf9ebm~U)4YXkmRPx=kdh`0h@$%W8ed|UZZ8a%3URmFT+se{>EF^aGixz#Y28U+ zPh1zRJrPLW2JbQzYK1iffhl~TZyI1nQy>YUlb9s56>@m->+-xkf&^k^#J(1^&03ex zn^)Mv&5aLXUPE6LD@LPn+{H*=VJbfUdO|TwjRRq5o+wk-3iU^qq*YSJaURhEPSk%F z9?xb93L)v<0og?G)~uLiKrQNvb`LL`ynjGn(=a}Kp!#xzkOb9GQs7O3CaNzy$Q>#s zi~f{u;W?>IrN8Q@bUI3q|1U=yvF%K^mCRa zrss&Xk>6iwU)qYk_h#5%`zhitUI(Fif81Q5u=YIax}D-~4IhSnOe?V0b&VeCfh2J48PdCsysO zG>xWFZ1N@a`E`l2-uPtZ4){VDDth&X0@brO6e-K?` zy&TuQ(Uy^~LJ*p|3%*=&?>9Y{Ll1555XZh-)6@HwPs(u%Ps7kAcbF?%5xpe2hH=@2(M zy+T&Gb>+~jnyqQX9N-BpDwCWLeM?9sVyO^Qr^45SnW^p8ggpJPQv*};gWt!Sn1J6# z;z&w%k`r&0@gU!#5y_R*NUJC~6DIKER5doErN0%y!Cvr+OJT0|(1vy(qES);ORsro zFj-d9XZ+WsVXgQQMR=jn+EI}FhnZF5!}BAPwe_V8Z%;vAR`_Dhs-NP8lUd_CKgTC_ z)^5GVIR5_dZLd&=)=Pz55LA;mI-(Up$J0$7bWS^}X0L`nn||~3&Qb-Hz!mZ2{Rzc- zsAfL|PWE4O1juMZc_m79x|?Sqot#G@B}~+vV}blJd+Fz_C9sYmet(fm6q{WI2{aI2 z5Md|o{#(J;QHuq6%XU?p;wuq6@FDe2Ln7YRKeo?xS9qH{9B9&<;rCa8&LytuHi8DF zw_??Yk8-DYDpO4{_2b5e?IKzbs%CK8^tc)=Q`o0c^9PN%bI;`p11CLS_>*sB;_~eM zdd~u3^LexyZ_7`zN>uC+B+`+oHMo~)wt>L0WKec~`w(+c*Gf`a7igCWsX{bB#}9kK zNP>~X#$Kb#92an?3!hlR*coFus$rdwA%`5h6L98CK~JqhAt39xO&%&AgGn^AYjNDO7ek{R_|72frpuXxG2$R>#%59Odc3{bnfAf)%+Batcau$i*Fp4Ksf|8^0*dEt99ulf zPphx7#gy`}1IiIBA8Ujo8X5OBwv)mqp>|ZPCkP9T_x^FgUkBb6?RFufy@J3AWVhk@ zI_L==E;b9+4~+Jx;BP2V_bV-gzM7H{)|QFsy4+p-StU2DV2tI!0 zkh(svP(WHAId~ZtSk~qa&7tk8A7P)$q1l<3LQ236Dyq;8TSv4a!bsVjpk<2h55jvZ zlB1HvLCQ+omGh6I3v1<0K-!&zV$NKA714%6STd(*EBL>G+!sOn1x_lJPV7@7iz{n5 zLJ>ob;7RksGA!8Tw2e?HyW(EQe5pKNmw&D`@(?DtcrweN-Vc0VF_;JgabR*_NlAYh z?8(ispK)lt16dxD!D6)|%}L|FZ6w81MCSw-E+eBaOfc~>`?MO#IDWs>`DaYdAx>DC z&)RHYY7lV4PJKL|PVN{_iIc3F2RAC<-6QM4&|B6!y7r1C%V@0XyniBF*2?+~BQ3qvJ*{+U0(S&!mp^IA z^xk!P;3>9LaugM-&c31) zyWXZ#ZQl;4dCGqX*R|e1JQh}cI58JN>?-g%#Ck(!DX5naNsZ&WtTm~2@}-Y3!b((8 zi4lj+Q-J6qVN;wgwu^3^BoJ3(+q4Dcn=<6gk($TeA>H3!1%%A7Bo_}lC)h3N+Zcu3 zU{Sk);GdhTr$g84A=j3E*%}eWlCqkb?$ZMtketI#B%aD!)mm3!#@$r=Rg{HjztrK3 z@a-Obhe1!Ue{3rM6)Fn#7QuxFjZt)8J4`=)jb?LG$T`dqlR)RrcxYv^bJ!>aw4n&( zs(pdRvPee>>xbuznjcps>UNaegawekPq0M~Jn=F=`|lxDd>KJ6IP+@CPy%%;SXx?i z;jd{_ck}e>k0ty0SKfSYE~m2*QFQ3W#MBg;RaVQbGu*{YLn^k@v<|-r4k942{bmnkRInTIY9qz~b zFAEmit*0FuWvAY4S~A#TIlPq5>q*ZW@l6>NJb(CyBO3xGKbIH6X=P>Nz|I;|hmY zCW&bOWVDQP$!AYa;Bf<4i&}%;qMG-9)Ai}qg<9-eb-U7<3iar^|5=SQ#Yi*NjE6N% zbK&0z7WBW=Vu@E`=4&d#C@7jjws6x@XDB0ne6X|i8%&@<38sxfMSeej`Mw?W!f2W$E z;z*Wj6PL{6=g%H#(-(_|qu=@=Zh%)oj~7tN@zO!Hap)=0SeP`Y-yqy6OqDeK81a6D z=iDib3zHUwZN`vwd}>R?*o@f50vg2ct5NGLCZA?$AZa4LWzklxU{ok{rLL0Qd+Zv~>LsyMh#59l!oN{;KEkysa+vJi911LXwpk6GE?W(19nE~_eTt^l7gXeu z`4`_MI)8@DDePf3Jk7dYvQwyX3)gt=Tkn`NGC|LSIrrKPoA|!9 z;)}FQcN2QyE~{y1A1Y2chksQGH;jVl8Cf-nv*f;QqwDjq?Rnozt<&J0W?P~V zV~V&L-GPzFtY^wiIAS~L4)Owjgaz*J6CaPgZ|?1yviDRd8?#-9BGXb9(ih^}jC5g6 z5jI{|m7Gn)Dx5YfKLqHO^lRn!zSs49V}WVA(D>JwO-SjuFOj)+Q(78l;IL6|^Tw z#UtgYVz9;afyqHBv{6-O`E0H(T@fF(K%RADlfmzc@$uR!eN&m(UG7P$lK)Le8^)I8 zac<<%&Gk2hcB`L75*(>4OT@9LDvbkKIigzMB4G=T?_W@UC^|<^4?Ont!~1$VI+h{L z@Rnlid(0t`xK+%dfGAdvauiJbRiDy+?$=jJbA_jO3c-QH!;TzM&}|c32ZwFrlr!9- zPV?|8_~k1=QmP}b6;H^O?ZTppMVe!XwJcFw?T>^qMqX+5LDaazEM@6ce{@Gre}yx8 z-GyH{ioZt@XQLay5JD!NjR782hQTQ5vhuO#oGPHnp?_!Se}gf&>5w@t_klumw|yiK z&@!aAyfKUv|GP74@n%jp8lN2q7!g#CWAkBNq_jb192Nyx>VY1q4>eD>l_uSMGcEHHi zJGI5D!0(-|JwILRaYm&ectu1LdGbYag+7MclphjHMY}%gM==-_6E|))R8c>+nlI=T z9w~7D)s26}-z>d@%INa)YG!esa+09W(RuNYPE(fzu{SWMs!OiZv4gQPI4_=~8u~@2 zsC=YExhV#cMO3V`bCyvNo~am>XEuYA`HW9kD8sHP+S}t?5Lu5-gF}0sO#XGd{;>+4 zqYL-4%P8TppNZseaHDS+@lFDZ7b@S`1a10&LGe9Y@+{<~H+e!CcuQx|L zAg1)4vfVVvi{f(*`sp6wwwZ*>^-E(W7Ksf)14p(RjYW9^4N8i!SX*Z+R*iwwxbig2 zzHz($d8VeSw&*(X0f)*(*XsXA(^-XO6|GxX5s;D+>23t+20^+(knZ^D?hfhh?i3M_ z?vn2AmX_|WGueBe3m-1LSr4qa<`-kUBX~wgau@#)-NVC!x5tmk?~&dKj&wL$`ESmN zd~_Degk*R$b`Eh_8f^!643IXHwjA z*Zw?7RIZGRC12OjL>rtsb{s?CyYRm^tG2D3w@nq=PJrjBMipxg>VT&io3R-?JOdO3 z`@IVqF!upp7G2hV6?Ih+3h1Nf!3rub@!@iY`ar?^4<%3)dH}I#dJnjOY)?B_~OryEqalTAcSA(Rd%ZVyqkHn3!>l_Ck53LT6+aUxXxlx~; zfKY7*ztc9H9hL-IVPMpnf2GU7@dltA(dp4MC@pszQ=i`??ReDA(&2;jj zqQLVe7jQ_?6#AJ(Wc*MuR%3tkwEdd&u9AsGAY;*!pQ^JmKV$uG;yqP?{Yc~05bJ=R z`oBB02B}5TkG0^_5>y_Jp%rL2$on&VDX+F5-VRNgy$mny&@>k{g3DN6x zQ0Kidn&d~1)j<|RBMs+RWKQ%qoThAV|h zCH^71MAzCq&4ihfB{8m0mdwAez{G-HEbh9Be8!j#+mfkgUI?rnYfUu$^J>J7z5iEG zj0tRhpI<*ZI9tr?+oOY9Mn6n?>%7W-_OeHL5ttm>?PS6y%F8 z7%Y&IohAe&_)eLGj}fOw2yrnj`c|ATVr&t9sIiywti~>xGC?d7hl7gRuAro1$Rx*x z50r>swo6nIplq&$Ae- zYH4lUoNj(ZAUta9R4vQzuNKkrOXJ`vL6LhMr zbKM{2NI??I>V*4WC7DHFg?w}{e{Y~a+E-;NGyO36*h5EKce7p|CAi6&-?hnGM$zdr ztUG5=?HT7+^NCw8&TUSZQ;Dnk12#0A$PXytVf1Qccpme)Op-~^1>-Z#{Dn^a>|aB@ zk;BZ0t{5A8@lBM+z>UM*ACE+P*q$7VP_n)ea$ftyOzNyx7DhLz@TV|NnjM>V%p^Y= z0>Lgtn?c8ok`5Fm71af zp%mJ-=gke3@&8(Ys;fB!Cw|dmk**f(5>W_j&O1pw|8a<#F9x9zGbxTkOv`6QY=v(m z3N#Q|PID3hwS5?Wb3E2wp~}-&EPG8zS{XTL*d!oudp>zyNO*sItvidp7!otq62x}C z8F-fBS*LYlao(Oc^C4)Z0cee87mbOE08BZaRiSwL#FGd#3B|>%X)>Tf-8fA? zHIc>;`=+y~Rs40;*dv9-r=@b!2Q?Nb&H#4aWjn?Ahv|fZxIZ1UE=n9q_chFSjgdcE zae`GXD(6FP~87x!a7Lum}J$fC=|XA~*S{{WVoBdq##H66IiWxadXG+paix4Gj$sVA0g|e)f^0*V>*b zecWY^J56@`)K$F*}VTe|-$7WObSS5So{aY*U~CY`OVn zJuF|Mqo@X1H7Y|x%W7p##5_cSjk}bs_56^(aK!{5pO4Si+>cd&g#V?_b9r^cYQL42 zONr>)ElYO6@2-3#uhF7n{%}+=m-{Iu^4v9$-cJ$EuQ(rsyvJ?v-6P+;iy9K>D(Hh!xEC%+C&Z3H#EYRg0o5$}`#=F=_n9`TVuf&K^!2tO<6K4Q;t^-e&53g5)7h>@0e%`QQ|2!_DRndFaH*EKc)epAuOIzB2a84v z`;d!dLyPY}ZI6oZ?BAbdG{0RsT57G+4ICwfxz#P_?cyF}?g7SPry!#$fvV~Cp%fN~ z`ukp{|Mccb#cw2U@O`tuIx*LVqhI#rS6g1cXe{mM%8id3#B0tm$P6TjfHhNqQKN2| z$~bOSCovh{uIsbo8vH$ZX0g=fIC*ABN%Dmi`C|5a`M14IDe0=Z4@pGScVwby{1fis zC_B?#y<6#EKQ8OKyk4{9bxP&`VwS5i9vwS$x&@gK!=R+(Cn7XY7khg81sHsa>QxTNiz8B_1*R0Vi9?#PbaV|s8Z&k0k|uJD+mI>L5B6$`;tno z+3FCI^}OG9w)q}lbk^S^MWKY`ChyMzgT5aMoG-3uA+PHxslZDLI- z5M{Jq7IVM}W@#)gLQLM^Dhe=7vTB$1tf5L<^&|+Ka614c^LZV&u zPJn?{Nf5+(HZ&i&qzGSgp>f+KGMD;<`43as&H{`Y- zY^vd3J`${;;ilz3_}l3m%Rmb!bO_SLPKl22o)!Kl+6`0d2&y`9fgsc1j||x11@tY~ zV79D?(&YPPLu?Iv_{?A=l5e~^*$b~r&-bgZ-(Fn7hSM9n=u3aQ^>2-`rW3{U??0{~$~oNA&acC>tc?@C&{PP*EKSTImd* z5Lu~>4_DrGb?iS_!>D<*8TJs7Z|}5O(fRlJQCQdxEh}NjP--^0y))M{G)$0Y;>` zxp_%hSrur&Z8#y`-dTQrZ*uz#cQMWWIJ>nnEIz5c%S1&l0igUB&oY2^fEXlUNs+_` z(r)#AA#&Ow6y4jpqV!5f^gQ}(M`b_f6wxb^^|~cwY4fc>y}kzfogbBhzehA3*OY#q zD1BEX%sfNw*gZGTczv!fJGhJiYd+mkDb2sSOK(^A%|1=+B#YBEG%SjL){gprQ~*7d1>VuKH8G;` zL&D9JPUq`an!o*QIQEsV{~=@%p3_(JHhp%6ekUfx_i!Q<_((YH7R;9F!o02P9d(E| z+cyEd8|0(MiG2bvG=b(S^y6mE;#J{?hXmjRb+!kitaxXc@apf+!L}ajISArMHP~)^ zT-J_qemX(UJPU~f;HLqyQ2iCReamX5uAWM_15Q;i=6l#vX)`i*Pph9bxSya32Y?#& z#{1|?oU7jE({qlml8m_TLMX?v*t%ZEd0*FJx*rDzYG(TX$>KD1f9YSmTGNL6EoV@) z%43(H!#Q>LP@-S!BcK{FT)dI{4f`q>`3l?lTFta97iz<-uCZWTTt5%ZE7+`BJ^~Ze z22!M~uw)n=AED9pC?>?eke+~5zwEnt)i?r3cwH|mM;fa#?oBaYs|=H9oCFs^PDA)2 z*;)GX+puBtlo2my3yqiz^Ad`x)cE*0@@x#%7gAM<-+bLoDj=GMp;I_gCXdr5Q5i&$$=b~5qtNkZQUl7@@UA;tYj9*1-L z>@e41{hL@Z_`+8cQ!}@K`~#Gl`Cn&cQ|pY)?9~806bC3#1AkhTJPXsel5r%x8AOx} z$M1kIY5*n}OYEd|kaq-%L$IrgPZ`PEWH{&wxg5f;D4s z0OrRAdz>UaT7{A59Hw7$vLz3Ny?w)$>0$x(aKq42^DwK-DQ^_O2s<5M11I&1k>b?l zp@8odsLT^8uqT^24L|Akzv0h+NkL_Y-)9r#|AHWa-b-$KVCJ;-{-6G`v^lt=OjGqr zM6lG#XJV4J;O=je_b4iL#V(ruR2p}0faAme(8+(&an1l3oxyp@fWLIMLG+vqEXK@) zQCiWVXJd46Jgq!Ie-21^93$$(yNN-@AdAPo#_IaCiVk3V*5ksaY`;*EKv%wI<0E?{ zV&=-1bbS;y#W1S)`>P%f=CXd+>P|z0F5O0ZG|JWLmYj84z&OqfMEvz7BlJH07iDw* zScoa;4Lmyl=vOM$P`n7P19cRIiE?A6)Y8e>Dpo9et?LGuU7nGyC!A|vxHhxww8Al3w<8@oCL*n24 z4WWSC*;C?0Z4B;H=K%MbwxjX~-(?y*-)$3^G=-DvLwkMWQUrPRr}p`%tG**T6dmX= zM%euR5UF>z(2w+SM|`xsa=9Jc%B~Q&FZ%w(HBh4{@M)I5GapY)#MyCjBD$kVVpK6O zBWk#c(q>05t9wKfA<@h$giI?YW15!eGkgBp@5qQ*aA{ajal;yl(d@mFC$Kl04$Mvv zs{2qU)C7x$lObrL2qhIR9c1x*@|YXu0g1W+gDmu+3qu{!#wiJm8|Owk@yrZT&v<%c zf(9^CjArl8Z)E@XX0c2@L0dU#Z)hHs!N`dKha+a@zdxI zt~(^C{ElKa6CxggDIVPk9v>H|koN=ZqH-)5C|T`;zjlYSM4au(BWoWL>rT{ehnTq< zONQ;(50-Ur&$j5c^jG>WTzH42IvROF8unO|d++D(fJ zx4Y>aZo8UfeuO|1E%^F3r4`B0xAL3rN?1Qe`m`Z+snj2;Y1a+PSu-P_C1LUQ^mj-nk3DrlpRo4%uI3Cp&cUvFhPG^Mw^|}D{(99tt8UdR zO*BsczX|Ge(w(T=J!Hr{o(F#0JtVw#GJMObEG$0ug-Fx_s8Ti4Y_Y5Y#;N-pzt8XR ztcP+7la=1n^Cj7nAnpw4^B)H|svlgpER`k2_Dl;u#k61CEZiPj><(}XZ$e>*VPMKp z$L|;v{K+*!*2_7Ge?`)sT11||14BKU)tKmzNCHjGX3vi~TZKwL*@c}p+u(%eD~gAj zZC7MWLNOu8i*I`#C&!q_WQ0EX72&;q-;!*IsCBvQE&~yuV_jTnH1?L?&c^G@X~&CfIqrW3%zo?$XG5Ci1%voC=%#d%?l&F8 z%-Nx`=g@c9BQw4zq(GAo7tJw#=eWL9d4_v6+&To;WJB%Rm}iav60=a;$pQ{mS8bOOk~S+~A`>{cnbUAH}0qo&_85 zMp~L{2`9jQ&Z|XB*=l@&F8-u_(Y~(kOBmsYEaSxTuKC?mUKWnB47|%LoWtX>UmWme zHA|FlX`w}3OeiW;74!UN4~WfWhB&*UiKF4jnY}-Va!(`YlrQvtBUJ8m;UsBf%b7hu zcQRx3rDXm}y+%?XC^cKyvB@;w zDFqfuxlfaGku;K%f51MQC$8Rb$yGw0v?b}mO-_v(MUc>`0nchYNVTzY0H<9+zZ9{f z)z$umJPc%TAk*mS!L@p3so6D7yDZ7tT=X8xQpxKNLKerbZ@a^pdt~|BH zE0fYf3ay%PlTwi13@z{_Z=M+L4M5wEtFsVB*>?|PnA_p~iMQ;F)v7=(Z77-Q&4aR5 zdl#A~KDA!woBXLvWuy@Xp9>%Qzmg8-6lsc>9e9np?}C}Gw)bJ)BGp|ayE|eRuU;Aw zL05H6km&h$s_0wu%|w_*Nr}g=+Uu+P=IfQW58E7V+l6J1{;O@blq&R|!pgrI+zb1! z&(5;H*$A?QUo7@bokLw1yH}-XpO2S9$~YBuG^@ zT)BJHD6zK4cI<)huALPOh6j>a*b?zqPP+=${VPO;qA_}ZuCM-ym}>1Ph=MhX=pg?Q zh3LEMU4t72Zzw07S&~5{^r!sCgC$@6J@RyC@`Nkl>hCK9t|&}uT@*j4qHH;gJcS8#rJ*}enLDRgMw%Ggh}()&#KMhl&xdM zui;bq?A?-5sCU(Jjwb15oePBUsS@$J%p%!e;E70h^T)6W@~C`EcE~z$r*K{LBEGmC zxe(*e(|-^R{5irMQTh$3>Hc3obS}0JMpz}T;pG%N2BKaeh3uVu`%sXx_5QM)>)fc@ z;iyNjtdg0xHxUgq9$p%-i2HskBqR%Yzs{MN=#w^>|8apPWB9|zB?d(SC{U??&^=yc zIW6`z99?VbUU%!k{trnRR7nw{2DoD%0@*6*3RaKF3Lw0Ma&ZX?8I4yZ=ilX~-LT?( z2-h}v4m~D8PcmPblmt4Y^ z$w+-@PTjtq-a7Kua_e&iCfV?V^|iR$OVhX}oC2%4DaD)@vYrgsdQmV+npfP%NJ3rJ#!Z=u+Wjv7x>V@7W`DV$1TvC{ zPQ!E_e2L+fzM2jLWYyy0V!j&pVM`pUM&Nv6;RG3GII9%V`iO*$%iqxcyB0TY%&LH$ z1-b^skGyWGL!Q)IOZ0R~(GBP3qvUaeI~#iXF55m;=TfSY^Y!#W-oLdS2zCEr2rVhJ zo~85VFirZr75hkpe4B2M!*Hzqzr|I+A6cSkMCy4jQS<8lbTm(*ES)N(ku#1gD&*rK zy1*qU${o7%gC$m9y{LaPGIzu5mD)ig+_{tjx2h!l(d2>(h-Nn#YO82DtbHo3gDp;H(k9gxysDh6dPvxsMq-TVs{h zNJUw(g2w@d$WrAr^fo(qi9i1WW%>AhJ%%pe@K>+#e@GD(?}o#j?BN9_*{6%Np87 ze@~gVsEVdn7Gd-|d)rbsoMO^;14q7^3PnC&V>R@xdBAU|OJ8o%y7MxGQgOkqNWbIVn`O>%p9`s{<8fZ;b>&pm6l~r~j+u8f{kNuWwas==vDw28XO)rquq0wP&0g ze8!va9%nGyQ?DK)rc!H0#B~cV8zr9gQ`D?-%ej=7riND;3QC%3em3DBO37 z%5q?^=;=>HoF5d8;0#?5r*QSztW+sgqYxV(Kics+Cru#Tx7LIeVP8K8k<{at>2Pez zqeXoN@83eluZfQ)VP~<|q-+fqDO&=q=g2cDd+!kCBdqk($>BMym-3g*CN0?2bTl>q zXz$?Y$Zm3lJT#Y!%5sYc01!L!P%3P^e_Ofez|zemKGM0wZ~0=byDUTNVgtD@Y^O&SC+k~&*{@j((#9GJIthn zMXNe40A)LLT8ydUCW|xx;)F{#Pd8l;esB)f?)iWi6|4vV94cfZnQl-VohnCx@WAlW ze$esorO7tYWeUYvL&DUfn89^0wbT4z_*=WBL(co|+tUsna3`ZgOOh4{ew4_YUN17v z+}>Y(fMsa8cn1czQl*&Lm67%-XG6vTenZt0lxyK{9c&~fFm79 z-e#h8Qz-{kssp$3w**$)Vu{>GX*8Yf;H%D zG2$RqZz0(J{;r2Q1sHcNfw3I_N)u0F-r#Wf^@6AxVSA_gjdzt6o5^20!Gay3pl@8D9foqZb8wu=_5U(lsY zyHvn%St}6*q1nWe2=wWr81&^w{_|8Q5s{ z_m+@tPuNs2Sxq4(HY8peGI^MA<`KmUHRx@7k@W$S3<1g&dWT5Wy6KnMmG%oRrX@$Fow82xlf*J9vkdcX#J=v?>jnKt#_T>|tpfzJoJK zhEHU>$(I(Xbt+>zv=ZSPw{w0 zm1QzjJ6a9)$5|GvADh$1{asf=1xY~Hf%kp&k`0F%Nb;)n80;tns^*g=>FO3OU%~pd z$74`W6a!FzV%?ah0TvGN5@`>BV+buXomtF=M`gqzfP zoojgAUulF-CL5&na@ilz74Pr6e2*Gt_4A`w;cMu+#G3`5kvJ+@J7A{Si{OrMdqYFv zet)mo;E@8-FNZ$||M33_>H9Y4rbEfRH#U&c`{^)K4l5w8IJj)7jv*^>Nl( zvv6|P=I+9DB#U3JMHyhoZ8$f3BK9@goPek|EvhJ6zRVu{HxQ?%0?$7-beBYj`*F+5 z)sGVqR8m%If4VM0uie}S68OM__<-31QSe3`XBtIzq<=`U*wJG=y7f&$#{1-6s=en>3dI%Ttci+n{t7oW z+@-^xf~kZz_#}8miDRHJoN&MDZ0_C7bmF2^JK0r{2`xy8yVHDB_U9HZ4)5yevX>;U ztK+uY_mEr{kLq<}vBo-PRxqz{= z@jU+H?;q{l-zkeDr7GrAC!n$l`Z{Jsoa1%9Me|!G9ES)}d-$KADQ`h@s*<7hCtJ+< zsrwO^i;wkrK}khqn%X4Y&`obFFSt zvm%5EVc<-)slD_#`lNcQ=hZp6^h2D815w|NyYkuvM)E;ttImKzIyS{^j(;~Ck;jB4p@{I zTDoV7rRGoiDL}R`*%{dY`B(JPOQD)6Eo_xH?P~g(@<8Pli|Y9 zeF6Gf`*Ec1HjU^ZS`=Gwwkin5g~HgX`1Y{pt?rmh=rBVSMm7 ztWM&x9{gvu-6KE_P=mX5zku>mSX35gJ4h(kYQ0`Qu4t?ctx4=B2efbR5xGGAwVq)- zpf5emIQ9r?d)jX^0)eP>QaH$g4+lElJ?3RCqHU|rkl#KD(;r$NjaRqJK+q5%NrQlr ztE;P<(Cd@7TaHsatT#45~<^4!zloi@F858l!*$IU+{n+4c0~ zRRs4aJ)JXeaRx}f=X-T+!^LG@Vc-OUIM@?jDin?sVNl+jY#*;|Mm*obCedrHyRSYH z>OA*wxICO9QWwp&)(nHVCEyY8=B2Pt%95F8$?ZVO+73@9vpb(%bU)k{f$5%d)#6kx zwy*q8)yeCtdgVe38A*OjI6bMC;d>W@sGzEX{-bY5h63q6*-uOKo~K&F(pPj)KD0w0 z8lvD6b2C6@QVXvG<8=p|ceAbsTEHlN%)cqZz8bF`co=^3Tm%1 zpieOTyP_GLtt@V0u%`L;lsl%FmjvI>d!6XX{^Zv1sPY;^q@ zN8|_$TkjXdu8F&@YZT{wlV(e!-<)Q(pS3o=T^>&6((P)G3`bFdYr*;UAIK*L*~zrU z#V@(?tTIa;PMn&#D=IIS=Vtyp#nx;D9rBMbA@_cj4|X~0$ptt-CIv=j*fZOTK8Rkn zxF?1?hhfZ^ar~{)CnXsYG#V^&(U@%sEKZ)Q5`ku=Asg7GZ0bBR=5nrZBuqV<KqYBC9Z_BMe*U_6NPqA2(ay_wr+I&v)U8;-K>2w5!B ze68VS){q9fT>}vQdw*O~MzpcMf#q^nM3oLH+p)d7z{zyGqXBqI-@&9ZrbvT$)ar## z+8!Vv{fPhZGXejrzk3PhnoV{AdTpcKRGELXo=)4!Z6B~-MP+>+)M&f?bm>Mg831Ic zXIRf`3^(U(4=Ah&L9n1<>bjItxvBHM=YV~D4XDf>kNY}1LHrLSUjL3t^V);gbo&;q zTe^>qeix_lbkmh@gGgbIYlgN#{>MpglAl~3{I%;wBLL7I>ykm$9HhJaH3wM@tB;4P z<9pSw#N*;Yx>T9hWpUAW64dHNg4U~v+1t_QTOw60`>wN*D`a4F0Y?W&DQ|YXpNuoz zj~Yxh44cmeXqzu4W`9oaHDASLjU8WSY})VsnK?UHZF`pU9tBBdv&|1@9Hy*zK?{{V zXB~(P<&GfK%j+3)_4(=gw(9r+he|F3TG#vdm5=DgN#lpsy?T{~uG<1@W79d_&dr}C zvA2On$bFp(q%3N!xo&eihul2jqek6)Hx|X+54npxq&r$kK}lLAZyQQ#7>cz111yoU ziE^&yfu;XMZ;d71q3|kB>*4C;2j;5hQ+*SGQ`Ci^K3AE!xua}4l=>G|->26bj~c8q zv!}|y;7?kP8G=VirB2t5a+>zZEJG>xiBOO#x#VkwZCBwiyqYnCI90912TED&Ysz2^ z&zY;9YGv-5h*vbcC0~7L?}_a&TNuSkV93AS3t%#Z1s5mF1OHd8;ZwfTkhX{%@a;ZI`ZAGF&XVrXUT>b}1Ct|_G9VeZ3T zbqA}O`NM_@Ms{>n3bdXyv{LrYA56RDa*X)Ix$s`JovJe7fAp7_UYEr8mCKe^N!lBP zNjRe*H%3$bPMVn(xU#4a3v@5Teas%YUW}=^qL;mNA6$5}K%M+iIIH{=#vXX;GPEU? z1R|MAN=skLSkA~0N;C=lyehhDgKcFkk$+&eK_W&WrU@Fp0Me>j@sEcncT;9;VA^b2 zvoPt_xG|o*W+ILu5_vOhenM}3alRaM4_`(s8Nn7=&4ww{;Iv_J?6JB7L?|wq9HsV6 z6&3B<+dtxT*nb;sfO$nzlRFUcmatK8Z3$cc>FI%e(V|c80-tn-Y_FkF4No|g0U)e{ zy(m~c0%=%3^JizW#MscKQec4S@};)k)d-{Blk1=xeE);_I8))sUSI@VI@6C&65lE)jH;>g_$PW@@K6c?4JFID5A=&<3&TwIC2y=UYKEQ1m>EmtjM_a_&MRxKY8^JhB|Dmi1~cBClvAJ`$QIzyUi zv{5$w&_QhhEy0lEoEKz4qqyAb1l@zsXPKMpE%Gn9f00RFPv?k{9ZIE%Jr0&EedvTZ zg}6kH<-{cLoks?OWV-9c(A zif7mGE|$AGv=nE;m(KR~*DCZnKQLj_-42){tqFP|sjL!nEbibmSct5@%p3g&7!<*o z{GPYB43uc5sg=MKZo-+n@)M{CRJAk=&*v!RF<$a~IRBxG#BqIy5+ku+wU4Z@lP(ca zU4!#onolsq5kMU?VV#?sBStdE&I2+|qpFbOdmz&Rb=D8^0~6MPZ)wJ`DGH&WBLkK2 zORz1F(V5lY0)=l$Nr`TC&dN{w{h3ddbZMB(nT~SORROeuz(^+cc1t2%mHjpzMqbEk z$Fa&YC9YW(#d{l*8vl_cBBl8JsxS24}c6 z$S*Nva^7x98jE$R8fp|K&@SJ5XJ(jy5kv+%P}nv+x+A9hwm$u{eIiw+M=Xo+2=Tc| z(wgp{mo+VL!C@myIzsG=*bB>}uiLT9F=@!N3p*{s9UrHUS_z;@M)|LK;ZE{<@jzWU zQmWMx$CTC^dD;~xXS3F^;a`KB`L?yp<*c8|6+m0LypMRF`Q48n$$MkAT)mb)3-6T- zOdwEG3!)LvL!7HFrAJGKN9Ho-OBtIUQREI54p$B%=I6DpWk(e2JGhyM?HdR`2|fw8@qTIr+Ka0Ba1fZ5HF(-HUHq_F$Zz=A z5umEf-H>lAmt}iA>Hcs>^z*Pu=`|qV@I`8zxb5a5E=8vPWTFeE4BJPhwlXMdCJVm43e&}s+K>ko+HzaON z`e^6zo6Fppsa6C%H!ghn6ysx{n)B+?fqsy{=Q1dG(-C0Yf{l-+M(Q!EevNlke#otN zp8Rw9iz|%gu0ej6s(^5M3Z5?NfWVDwx(C{_wL!-#G9=6Zkti*D{bJRSa&%J+c1GdD z;43dYC567`sD4BX?H*_==Fx7h78-lXvC&6z{ew&1iLCk1Wc3-<{MtTheO*$!p6qy1 zDrm0VaRHK&@KO?kAeksy!*mhi!t;wTI4wkMy)UA=BsNg^dC}iu&m>cd&L^kbsT^QG z`>wo_bFWuegToTjz(@KWl08ddGPR2pWt$)L&0%~3HH6b=PCWn(N|>-rA&;@@%g!d8 zx?}Ji;~23%3^m(9PJh$$7N_Uodbgp)tx#}C6|VdEIdxBF$+#B{*JJLVhDpn2ge*61 zdneu@p+CV8LUTDWG%+!;n^v(3R9cZwpXeuctAh}{TD+pfd(DMtHW}d_s^8x%{%szP zCJ_om!g=C4;T{w&v~L^_`~z)L3f}=lQeWtkIq! zEx&37OMi0=q!!dmcMy0*zI&t7^BB@8U%HECFJ9SQlpx~{HR008^v2Ys%c z?s*#e3?0M9cq$W)*WX3;#yDj&?UR1n91VQfPE3rJ)a~#w%4=_Nzn=4|jgU?FP!h&w zE8QAzTl!JN$DoOt=MP${&zvnf+&_2$lz)r$R^>_O4R*K8z4vcD+>TkEW}k0}Tu)8_ zyfQ1GK;-FQhku9R`HZ0fLLT~#280r*hjuYpzMJVv5kmh?_JO${ zDpbdm++a_cLt@)g+NKu;(kv6tn}_~A7Al1kF@l1S=(WLxiG?KG*@bh6%tY58OtMAR z5o(DHkBuFc(>F+dXy52(@@HuwXO0g#`1ShH{l~;4@W_&H0bpd{URxeFF(=z*y)!u*9M_MEm%E+Hc zV;ow>pv1%-;C_ImzXMuk*X5g!H8i1K$niaWsAMFWTf=k5XUuL77J>?YOsw!1=3y<# zNb%6oa_~cFH5IAl*^elMB)xjCB|qY3)N*SCDm;1Rjt z79o%)SGYnF4hy{?g!9&vj5jYx(t#3NH}#$G63M{uS_7dnTsW#K$p%|dya~Bg&KIjj zQCp|)vKw%)p8*Ko$V4h1XUw=%SSQjYtBk+m0%ml6u$E}m&}64&;qqZ^$GeAXN}J+}z20RY`bpGZ~z55@d% z(+mwgBvEnRSrIX`%eeQo_(32z1yl|*s=kcCQ*8hI8yKYio_EB4_oE{ z7kAv@^k-4Y7d5Ho5@d;u8yHVil9|1Hf;VtoV`$`}cIh)?M-E(^yqo#jg+xfyn}e_F zy^u$*gCe~m1f{S_5mbA{IFVgn*VDuFZXJ7{NST5ejwHKA9$E)!fdGvF{SKN4T2N3BuiH&<*nZN_VHv;RjfdXRe_d>(qf^nT{YXP15TegA$6@SGXfy&q7XzZWDJ zHVebM8aYKy*VuDPlAvZ8Xp~(pxfYP}{P6&yktq%MmhU5U|8t@2@ z|6~o0w;L*=jy-3)xYLSPaB1bILqrcm^Rw~kA%2AwP>8SDD?&c;Xv<&NwhQUnR&)BN zMgsSrv*Gr)c!&v#WCU3-R0}p_^a}!h&e*^4O{yUi!gM$R0?6_a@Wb25=ERk)B?dt7ce z+B^z$eHRy*IP)^B%jG`p3ZM45VDTV-<}O=1m&l+{4CE2&GSz%Nt4@<*dHzTkkeC+fe#-M!-SVH{fK=S{mY}K*-83``(Qn{>1C-Mhc6dCGNOzyD+4H7l36-V0e36d(h~a=|2J%bY(90_lM7rQcaPu@ZZQAi+ zN@0jnQv^9(b;&cY>izGdG~kl4GYsDkiCai!nt)6g*h}Y=^dA6eW%q5x0wX`RmCAowR5 zHfqI}6ecuo<|#SZdiNcAj^E3h1Jj7QZxy8ov1StMZMR4-TRaIZiHQBXVq6ENap;?E z6ZRhPUq`KxE=Lp}RNNXL|{@e$}m2HneiW6%(9#$F;(f zKl^WDKR`9_Rlr95kaF?=(e#ypbpP+)8;0qg?(XjCHcU*OCd-z_b%lyLss z9f_}(d;7hqT$5&&b+-%;yY;rTShKNXO3SNiSk9v?`d9>Gs__ zMg2Quy91B-Ncc)4|Uzck(+KO}5?SYUB>oIr^}jC!bKe2QKNpnK%$y z%21K)&DLK&PT*XZf`NpkXU&gnprX~2a4s6EwM-ky%jiwV5mNCd z-ZppZOZX?87DzXVPvNm_I!<(?v+ucQSV~qs7WHvlzp(1L>2?< zLnemD$&nQl-q`aMy?p8RsgkrbRdBqol|2bd5xFMr@L2&psv4Qu-x%l389}@GTSR4A zsC$Tq)Xy$ylltDtFyapUx$i2aFBVX+sb#PsdPug^rS5f*XFg=sOHnRDrIivW<~5Pn z^-3vCgP}g`2_N#xd3k0E)gvr%W1pAc@=*$PWT@#q=U|ZP(Kqg|gjP1)p4;~bQ7^?e zV-CPj=u2B7f_(KC9GaI`R*H04xp_28_}`m>M)#By-1zte-~moi;t&;(uo(USx7O$x z>59+C?AAq`aH?Yul4`zn2Z5vyf4*o}-h5LldRw@8vT*DH!Y>DK>Y1`g7+(6VKll7V zLF!rjXUn=M%~Ggz$Ci|j0Xg`&Iv)DickRj{fC7OZIS7@k2o7Wx;E@979gjm zk=m8AVg)0FJXOug{gESCUFkCQ-lk9AYqP_{_BoF;4dWV0Vcc%c+)|C(sjF?lwC zk2F>D<&B%KnLTmOdB30~{JvA~?+pwRk_7LL=CDO#0SBR)IqCkZ!LGMm1qwq_DVN+N zOFePaA^hQ%jbrO-zt2Oi14Ca*mBMrDfCVE+pvGu7X6CnRpf9EwO;_&3(VIA+;^)z< z#MX-;Nbg=J`?q$)V-bdxGFxsBV+Ae>$H(R)9ab7n}K^Tx1Hg$DPx&PqTH@ueu z%VnOjj5*FD6V6lRwiTJWdiWBd4o1gJ436E^>W zEh|{R{LXG+|L)Mb4ym~b^r+fbXkTsK{7(x&m4n0Gg@Qo+C58aE5i#Z+4&8f0zVY;C zeN1@irnmyuFSJ5SWXy4BH1J^(nS+oowE0S9*!H=%ISx58vyJDFf@MnE8N)lE_;gR z_XfIj8JSq8r8%q9*&4^4dYQ^(*SwP0jNEs9b;WJ zqM9M+=lu@u-NT4r{6rWkto`ASy(P@b$v*>R2jq!(-dt`}h_0{pUAtD*9; zq+6;&f-jH`nVX{RU$NnS+1(+X(dEnQ*rr+^zR9M3N2nMYKZk(UB=Ir`501qw49m

    + + + +

    -wMteju^vfeFqUQPEYF%uIA;q9io zYO;ue_cw%v@VEf0M?_#KwA~~EX@|<2ICM)w!eOm8hZARcRL7#w$D1|`21Dsb_xvL^N8{X!0m_)eu=CXLwhw`iBWid z5ow7^KKIafq230y^n$ASehnaXn70}yyX_pqB3sEvw4H10Mx%CkA zopy3Sa_o^UMT40WuZ>qm(z)@cU(WyBTfS{w?w1Ue0P!}%ld z?|Y==V4iv-9NBQG5}F;xjT!p=f1r%cNX1yNlRB83_AHn7TwUR{F{ey3YOL)wEBmWN zXQGs7=sVGCbDxLa?S^`%HX}u$r9HYzqCTl0w61&Ug5}d=DiVjISe0wyB>7cI3*cy1YN@1h@)7XuBT1 zXjkF4O|yR#cf7_{%L(Kkj=2yd;+gt2NDJEha&H^|xf_D1qk(|UI*R`E!_|99S3wcuKkyC*hLSw4TVzk>hZN>_i+Y}SeOhMT-g;*^ zu`-E6MOX?wOl%>G!+=LoPg0+mpgFLcf(6u-8{-p!rKd--Wj|tip06pjMQ!vuz3U#} zd}m^d@dNr&TjM?Hq&Yo6gfni?nd18@uio>iw@fi$|N5^)@127IT@jC3TwjBiCMYGtXFU| zOs=k~d-g~!CYZAaUq2c+zf$`6QGOCdv(6|)W%EhWvdAuFpX4P{V&Kk=qB#}P4SE%v z)t@DoeRf#+Hld~h1xfGCCQgniDE$*e`T4c0vq2yM;L%ncv?n%yp~kHPTT*3h?c|O$ zmDLE~D~-cRp1HprJO^^DI+U>gWEZJOA^%al@ED|P#(#pJ1qloP7zW{2S%b%~V-85B z?#;BB$C0RtSr@|=+?1V`gPl}LLnP^-#c2sz%ukY~pDQYh@%dqIe`-1|ib2n$ias+C z136c3df&T;;V0%thKS2Y z2eik3`t7}QIy@^Ha47)v<4bXm_dBbuDOHD=>mMV0_|&xe^HpXx?xMp6u+g)1}lW^J!!7YdoUc)W!m`9xe| z0S8D1xr9fNfRsng$5At5d%m2BV)7_yWE$nLI@nkOr;Q7d|CB~57^QzBeP|X#lh%{? zy*5f#l?6CcS6M#Nu}O9^($}+3Bh}~WEQWUNN`QhkU{l-7DZM2+0Twv)uSnzd%UPBg z?oxleoBL^D4R{0#65Wn!{m|wF^Jm$`##Q`Ab;P?F02?C-g!_1T4U})~xXlc^Z2CuJ zUF?@JxbCZVArT=Nc>sZeXhNxs5=tuj-(h7*6iY(<+#u201joIz>?=nCKXna_au+9Xncueu9r}pW#DYO5;0^Z9j2;Eg6S_6i>_~NMF*f( zc{!JAQKZQbsHo<^lKrFIt3Ms^BQ6+ZpoDjB2jSawTAwLh=3N@Gmp>@Bta6jb(QuGa z+DW3X2#|l^t&!bIrg|X{apWpX=ZsFEsmIi0EwU|Wt{jK``Wck7>SJ>C#`*Q>q;+j< zU`fy(!H$55D(XO)>Vj?jm4hdn4hDZF5Q4#(LLN&&K4!D9(S_)E=7`d>Mx5GLK+Q%f z_u3r`>7a|5?azA2N@&fIzJLvrJJqQo&YwIUa9upd#@Lkr0SKI>(vtbmwBOH|Vc(&5 zY*nwGynDy?xie-&8s!w-CXznBRWNKC+3hhQ~`iVGEj3k}Eq1{76s3Xb1qfo$mb{;M;w_H>WypBa=UW4$OOv%P~9= zN2otVj-ISr6h>#*0Bu$0DkqPW1cGRg8--X$4x1*FOw3C$8U(OgS69~xZ&U-0c6_5N zGIo~?X7E3(UfS-vY|~unga#haWb8rFN;@i(pq3K zZ?J}|SfhU>Orq|yySiH5a^0N|Y@$%d180h)IkWC(1bsggrh8aax`$_uh~G#hiVL+p zf<`;8hl)g8Li;9fej}%{4rYoDz3|xhr=bd;4C`*dAusZszI+8@2U?pQ2*5G^ekl-& zG`0!^j6ZbE{spB;XvnAE96c9x_1<9HXtW^4se}B3VMX(cUYq@+K=>7iNGA{*+b9$2 zyZx_}Y$wA}6sB`;srw_+?3bIng<0*&13S!2jwALeY;yN!$kVDN8mUL~0If0qmCPOr zJH*WoQ}X?0tD&H(8QI`+MHWm1Ed;~)v{OM$Wl4-tck3rjbBUn}!pVkK`o8B?!nKs; z0dQNgwemDA!zRPz0S5I0cDc_J`pM4{jqvR3uDx}m%L*30m*#S2TN!;tuqx=VBflcg ziiQbW$bD6GEATh{^G*M%|NVA;T^6DVC;1rlNMWoL>9>TjW+n#T&#tz7xN|zh#2Wf_ zMNsKL*vaqNnopN*Y|Q~S!k%p)BfPG&2m3!Qz`oz-)Z%SqF#q%o6-|x_`hi$WZoeVe zOqlT2;KpDQ60(>@K1F}8A5j;f&c-v<`f&FC9@(_AN#0@_huF?QprIWRIw^GWdQo)*xu7XLGm`Xyjv zC#}VqKa#gdHzniLVDee$==Jzq>IkAWC85IN_r~gTn-xW1!mGTvUmyXN+yN<(?{8d> z>r(|=>xaVIMY2umb4FI%ITR>33Seb*fW#OC?v2fp=NTZo7*B&)?MRcN(Gr(ap-Yr6 z)gmzmg29cr-1~@=La!7S5?uK!P!h{VX|q^W%h8_IPUVCx9+CkDDZ+ixgPn}P=}yv< zn?nWp3r6;6M-u6HW(H84-N@s?cu<;>)R?F+55$TyUf4ksCtmd6NlDm5fCHOtvrjdg zaraG0*tk2`BXi5kR9PTm<8CoM-?Nt_o9770u; z$+N25013f+MyoN8_S6KJG_lC1r}43Y37!`#35w|_hA4-@hmiQK{Y^l5(=uogfn*?D zOhRnL>?2qg&2dFJn2x7QRd)}xl~l^5nr!+h%jl(S4lT)k!I@0Gy(vIi0^Q8qzVig2V9BK=x^zG4@P!Ti zYESuY@U~ohUNY}PgY2|u5q%<)h=jP;ipHoa2*pUZFBAIt-BO;WXd79=~M2+DHbW6BTn#)OJ~b32=g zUAH&O%g@+-y%cy3$v_YR{IzR&I^bZ{g22uhCphrEKfJ}UgJK#7WyV8sqCKzC;rHj8 zopS9K4v397xN`+eB008+RU`!mVrvMZV9#>DT_=Z2A5AZjx#qZ_!?ib4Jh<#OU3sIvCyB4Lhhlm@ zpniY!MoI|pkxdQjg5HZ+B?C}xi(H7dbta-W0xX(4=*t0vzu07tbw+}dXhal=`Kfbw zVQ-+8$U2C5&a^QrV(sV1l)5)f@56?2J7Zw|!m0m(kpTUv{BuzC0X+2DxU!xy;Lf{t zJn}vQ)`#w5z!j#@pkdDF8pU#h6@7;@k)9nJu&H6od8q-b%{GoQ60LRH z;6zSxDPQ<9cv-1*(D^_XUEW2@Jtr>2`wY;tcOf!GPhL`9wqFKS7#xTpgb1Bi*xnz# zG9Q1C@OPUa#Wwyfi`ewnhG&+9Fk&5u{o)Te8*zLK^o&4JkuH_gEQ3*LF(g2`pIRCS zh{b1*U-4$hca4VdG(WgR>~8-$Eq-HoiPZxG`5hyQVGoB>oL;GC`9OLXkhTTC6Huil zkIHx=&L68rcX$3@Rk&BY_LI6OZ=CHt?XRP`{fop@8#A@f>4^to*{TpNAUOg$_^P`( z_cuc(zpR`&dyUBViRv?Sn?jo-xSt<}8TCd*;X1lERk|F$`*>JEgxqP^q+=a{jh#ER zlx)Xm&)KP46i*u*y|UawS80g^N$_%96;UF$Z)8HiV&Z}XlVJ2YtiZ}A-)fXQX~nR3 zA!4#w@vD<6y}SN}SIK`-T7Do_BNh9fgmn@VTz-KoaK}5{b<9+DaRtNO*(ZBv!3Z+l zapIp(d6vDT|BC0N+jm4RfS{)LeaVkh1p=?G?WPP3*ve=c>ijdx??;ZHAm?$5X;n45*fXQ}pxY>E`4U_QSW)%0d z{mWUihtloJ0a>xs*y@MCKLA}HG~b6q9tUbfN#0M~hGC;4jZ}`@h37nfVVyRo(VOTtt|31b5~52dAnp(XjTE7GxX?#AWF9vnhiGXju(-an#Bf=r2=x#MV+T8Lrp zo>dwM;eq1ZX?{IoU4}pAf}e25*~lgWH(g)uYF_U)w=5Y9>p_3^|64muKhzF!XRDBE zj}ux{uotBs_M(YB)a2>Yz+DN+E+8ngz5P7%R#>#LNT0H%tLmp;cMtLpo{2hUrzd4p z4f{Z2Nep&~gbvp!@sz%!PGib48TkK+HUBjt$^^Z`Z0`w`mY4c5f;-d2gA7=qNkX>K z!Rxko&Ep*70cCT{GzjgZ<(c;M}nTF?>z}C%8#Q#|l=! zCy;y?k9VtZ+2zq54lt1#v8QDW%O*ePJdpjO2IrJ51{K0|KPs~sv4NQdsDJ<3vZTAj zq%G+dy*2up2+6vcoeQNRUXU;~MFUdrK)n~vK!6jdaq?TbgzIIB%^=zs2ZbX_b4Uy1PD1(_&&Oocl+X z2QG=B6mUrZFz!8;a&b=rXym>>*+WjqTcL0ca324pvv-ZIa=4UqmU+g4?m@=Rcoeu=00X9CA7jGRx`!)|c z(R{9ALIN$SWNy;3No$(1P~x^lv7Cp4yO_K zL8~ZqGlWNwi2)XPn-t6xw;>NQihfiZ4iEWwV8G*!cVYPaTY$j5t8@ZmY&Nr2U;M~+ zJcozeT*QK$$cS8{MdWN9L<`W@B6AEI)qFsmbqwfigda$Z^&Ld;e^f>lJI4Wp-CySb zPp)YvOlLJfKJ;rTh!j02pyk$fes30vNu44`lffNqYxXPm@s}A*egJ0D%OZ=_H$TFT zlR6n6mIrOrU<~g~mOjVXv+CQ&BBlyGy0uLF$2xr4 zyT#l7@y#(JW)QG*1(WAHu+nO_!{KUSK|2|>FUB7j9?(Tok$YXwSH0dg4cZb3Y?^@9(>qE-vy-*9}}5 zYiY;+2qbu0_bpc?J^sG49+l7`jv))sOv`Zf04YflKsVpi)*?s|LJ7z zVYIPO7M`|tq_C#S&~7JsF~*F6f zlz0>)FILB+xx2hsp&QKHOay#Eqy|P5apuK9lL#6xmbM7vf%E{Z2|VL3?x$rTpf783 zM!BY34x&wi&g>H6gf9iw|NN$V;&It|iRplN4#rrY@)cY3pwEDCc*ZVtw)v2Avs#j+ zQcxCx+T_urN68snKM^heuPAJ4!5*V5nsw_ablG=%A0V+EPFF|9-sQ2X-5U7#p^9em zzatrV0#rsVVWG#|m<0=R13z0Rpqh47Gyn^@pY)CpdWpFk#qK8n9rLqS2?9|dUsD#z z#S5$k&Kq!gQey*+JLa|4yHiXYp~PL)3KGjpo?XR5u2u7(=%%&e#9M**eu|gGD#w#_$D2ol^6{i3<23iI(HpeA= zXo>tL97);Gkpq%ZWZ>b^+-Zf55D*Yh7|tM_rv#KT;6==72k11&DU5M?ihFs*ioe|{ ze6vRzkQ9|oSNE`K;G9O+FBD()F2E*-<5f;v)E`^HpZ`}*%7~^reqJi3?Q`#o-+X6k z@1FzKgiSdVnO`;iTg7z5-m&Y7EidVb?$1)d*f0@e5r#e;FEmbKq*MV(l7SlReVZr} zVeB(o`6OV#P500}QKHXfo5WWSeA`Q;{e+6V!vmdepqqQ;l7lZPboeyZ6Al6a4MOr1 zIfggj@nJNNqCp!20Itt>u9&wfw;F==Aw4e8_lJz#@fiW~y1+E(1nx-mw~=rc^Tgz8 z0z*f}kzq*pwi#zw{ZH@a_uZX_zqYp6*w~cpGc+F%JUM)Ec=_JZ*F2Aa&Y9rn#oSDf zhr{O|G$Voj0ig|833*?)B|s(xMTc4l-A}JA>p)&j*$s{8Wc#|A6xHL&E7lu;lQcZX{O`Cg*J0@ zYzBjAe+v2c8zRs6xa-<|Oflj^#zk`k)!TFk!y$1Fh`y&(Azz)rqV3*xWr_kyEuALE zS2J7YoY-Be00h=}DCChDfXMWV?bCUI{eC+>_@mHUfSsMq*4b2}gV>$i&BH+WsV<&?=CF2b@eM)#- z`Dcai9ed#-raWIBn}g?q+<_S4gXLos0cjs`z)DSJBN=Hs^REdRSSrIe1HMgQPsk+X z0+fi0WR=@;^OF9}1On_?+$)4=-5{}@(7yGq&Q5mMOjOA^Ic?uupsKVPf7N$EkNWej zb*Ed5&4s##XKK60;$4WX2G7H7Qq}UYYggTPDUjnJ&vhY|MYgK-=48kQT`XbZPy#@@ z)56+lRC`{aa=S>>e14q|!Q^N!q4<)!NmDpM3ww z)w6#S_KeW&STW?8135nWN89_mLUR;x+Qt8e+0ubK0a4=FWCZ8}E+nCJl;XBfI5Cm1 zrb4FRpCBq#wq0xhU2ppoQr;?@t26T}bxu+$7#uIs7_O2KEJD7&5PJ)zQ>b#PkNo@| z;>tph$7ryI{X>rQ8!LhdwCcaE;zy$`C`iC*C?_xf36v$D0LG@_dWC<#<!L^o|nrsik0aL9^;=yph^*p0l zGVt=d@#=&8{yvB5+e;h zz3UE9JBL(X0^E9w)3aJ%^tXdW^r~Dca&zF$F9ozoSh~rNsl#uwW?gCKVO!xIxo zG^z}rQxyvUu7$k`*V0G5H01+l*cSqhH9r;7j-M_53BMd5SNupMezmumpe3;>CQQ&vT1c2kxdIdqz1PlAx#!+xAM z;nbN8PX_>28sv7=u8Mi{Cm?0X(^j=aI?^CAB4EO9hV96CGtpqLp_e&7U?(3IC}(sX z4V_)6fxi72XZq3_{7h<^;O~x${!)7I`B~e`TPbH|tY0(%UmdkOp3o2ToKYP4+bf0{ z4T>$;8?*WM>l8fBd5g^R?+2y(<*Ith!ztbvPMplp*`^&XKS@QT!X38|BN30$6Y&q= z)Vp>aUVZskCz$07cOWqzeH3U3 zc11;*m|A_eVuvZU09Sb9TpA0wc@r2&o8R*^V70_L zA)DS|=-&VIf$5lf-MM7?(0W`RLp`cEnAo9+o7pQ*PW1Pt*uV@&B}65B%vCv)eyoY}y}&={Ndl2#n)iNl;j>E)TxcVE*G))w2;ZV`wjk zw`_=5AgVeCRO=v21iSUtYa%qT=O2*{A*sUuCD|gcE!jJDNp5Zk-S2jMK04Jnwsp9# zeR*sX|FcoU)@b?(P^f6|wJGD{qk(D1(%E@O6RURmr_=PnX^31i3bUvC{SsRFRx2bD zCdt<2F2hGL)o=~E`AL5%$t%FBzXZ`CxoGPTRqew8cXE(z(}Y*S)hbm~XdC!wJBMt_Mf**YfvM0mH7SUzCFWw9{=N-&bNoQ6Q%N2^6|F{)5?*Aj$xT!EOZ=aC z#_$;BTNRt&8sQ%P&vy0P%U?RQ`ABSqFC7?-!Rw{tD7F}g%t76NMMflvT5AW*+~xOc za|u!f#d4MBp~ug-Vcc)m9nGKGico;AP3~#tk8?gCYx&m1M6ZpMTKMO^Pa)We!N4$$c^{j`hxMhe(%Fm^gfO@s9%#s7@Wq#k>c> zXMkd&n~}^@x;aT|v;0o@lAZ*c27%ktOpuRxVxO~f_FrR)K1 zcg&E|W7+avJ#u&AiANqK%QhxX1U_8XWFwhLio&1eGk(0`4F4xG>icbT6>-EYOA!j! zbTDP`WOGrtH9AdznCameh+4}gY zmQ{`Wv8&(%+P1$CEqofu8&rf+V_9SWajd$h07dZ?s@lfWKw?2>;_5j|>J-}k;L;1MQAb_G1<UpI$}6GzY=2r=q2}Bqqs{;4P7O3y?py$m+5jyt`(?bU8D z+vP#JrK2YEYnmYhJBn0-7JyZ{KvO|Q>RhP9(SX%cL{~U$WecDT);>ji><{LD5*P&^ zNSVDKBTXpc9DJJquXT5K2NP1N>gpsH17Cc(Vv;q*eE-~k0v`cZLL`{PB217Tbd!fQ zKMxVW$ z?i&(35;6_oL@A07DP5)z3*>33Vfdtdq0URT&5P&r2K%-Ce{fVBhAI|sI*AfcgrX5=4=Jg${ zrxf_dohl+)t2sAs8hBdtxHcL!X(a~xx!wNE@1?+pE;A`up>vA9RfvOZ=*k6@tXh5wY*4>&B4`Ywdy` zm^ums>j+e?t4xCGqp8cf4X5WY!r;fIoo#4i|!aI#-%Dn$d=(f_o4JT1*f zQ+159_eWoWDhc%E_u4aTBY@q25#mJR7e|CK?Cz&N6H8$K-;S!AeZjWrzDx!bL^Bn7 zeSp2d#|`da#nyo*Z5siC+tJC1OJ~Kxd6-m%p5XoZHl>@OdQnSW9u-AX%e%KoYv9bt ze{9aw+E(=Y4_=EiIzT?@#MYSri;?YU-J}B__02h4Ua3eEHy=JDOSQD9i!u7va)&=^afVWVmH3~SbqeReP zXmq>WKy|2WxAAbo+|=kz3%1#USV-w;a;}Ucl>Rn2=?*t%32jZ{7<*V@hc;8c$($Hx zinLJFFp}>Q>g;}{V!~R0+QEOm>Ro^!0tkn7>{%?u>&GrRYWT;MaAcR9)5Cn-4)?rX zU09E2-?O{kmpLW>3P+THD1>)Wi+Z_P+vLqOnF{wB7fN!8xsEM#`5VJhEirB|h!)j; zEBLI_!0Ka{!M_Di{Q}uCIkn=gGw`=c? z$;BCXH(VyqiE&Uq&Q_CNg0`s0mP)AJG$tg3KN|$o0)x&&$=qLNWDNIzz||5?6X3=` zqTv1un)*hcSqc^$y8yM02TG$Txg4)%unLTC^2(MFM-BZ7%5cb;vdNvl@8g26S#oY; z<&;l9#|L$kVT$TMW>{Ot&Fb~=a` zq#`MDG&dWVTxHOmG5DX&v!d_VsL$?h;uG8nJ5TyczbWpJUVZI-)1eEz7P?Cqa-|V!A6?k{3$5L9l6;EY2BJTG9 zwXJ6#Aw2IDZx} zlWgq)q2{-m;vz5o*SSS6s*5$=-o)MbAaoG3^b{+m~|jF_@lQ8Bd)u(hZeJ*rw>3tq_&8$L-|d#QEZkKLBz@m4^`x##{1a&J zEp)y%y{}#E!$K+O>HB$1II`fq*MwoaI?e8YN>f{uG7uG+WF=Wf<*ryekrOXxP&^0B z;mP9){oTo#stE?GZ&zJsNI@z;`n(pOv?pbBHEhLX*8R$A!#EuFQK`J>jdi2P8SNsv zzxPBPz<5DiEXHb>#C@y?Sr2Ra{>S;b<>CDAueg8u`Sv38BnF>*6a3cTj#?LR*p`uv zUQc#-v-WvZbl_URW%|3hV+e{EY`0jqtWy>3p zlS8f3>|6$~_=)M-+)O~Bq!&_G^Ug8SF}(i~mL0-NsNu5?Xi$;T-_nX zctr}mM1gxn%=(cks10%J$K;wLx?wrb1DX4Gdv3!MQ$NN{S8Wo~`;A^w@zEDQJApl? z(2@OE4N*27MEp&2NIte2Sp_|+mE`|~0vVF`u6C83x)D=eU)XU(jZVs18C_z5U{7`4{xv)Ue$4mYhx8u1Pub;}DRdAF zpJ_P88kyE+91NFdA2V$iOfyTJ3(N?mz!oI$Qj7Luz#)B89x9cr>&isdhecMi{hs0# zylZ|rufy!TwY}M%Iw=%5)o)V76t=#R@ISln*(YM&C2#?U50b zB{4+i_>$5cG|NU;WilAhiiCf{vvjw&t+EV+ZvN0==wt!9`= zFuz@7%-G)co~Le+eQFwupeSi~x}YT@6@O>^^_P?@CPpw6Y=lxnNaOsTn7ZYo3>RVl z{bQ$xy>NvPeWPE#V+y5cc0i5F@T#9*pTMhJA0LQR=;=z$uE9DNuQNlh9TjZR0-knE zDkFjXY0=%)^}5`dP+6fgX?Wa(XJbNkdDr|Ca&ke{FeJ#3@^7UG`<)+j!((GcZkkKM zOktej&lNgXOJ8DA(~)BCl~&N+*yCfEXvZSV7UkxU6o}C%QmPx$sl^=!IWTH1l$yEJ z&v1O)PK%cqH}l0JFq(DMmZ1Oc)q*t`~s@JN!=nA zuFxP6CsU2G7%EkBQCh6G1u;}>Uk&BvWL$C}s)D6B;1Nz*6;W!11|8(>+oC?zxOX|` z^LRPtjD#?K?e6lCu)m_IY)`K9wG#-({UCb6HmN&H5`qzgl-e8r#Z}|+q^=n@S9p-B zZCo_L@v@rjo7ZLHHNEj119G}Ooyr^N!3acn1yl@$H@{0N*7oava^E0vL*I6_-jR%|Cn)pSrn z$~{l+7 zlX4)22VFxpI=xdo_0`rwk2NQ3s}8e7o? zetTXHW@3CSo;lX)pzu1@>3(Cu=`ESUmHtG*scDM7%eoqSU19@tY;Fjn^bhZp`txqUfqj9=OGLeA=N@=45UcG zC}Mp61`Ph!mG@J$`qL!8*(Z~w>==;-jlKhJ|CJLfB9QLa5%S3_n_7(J+;42FB>xUo z^&D29T*hbSfAV)4A3^_a=JeAT9q1^@9id3q{yB+&`vY&z`r@3!RgZQXeoNNm`Y>R& z3UVJKf`Nz)9KL$U1y5_iPp>EM<4Pc+gsc-SahdvQGg~{2U6SxOyc93>!QZa#716LZ zg>5aK&1Le2+eogFLh^YX&5RSe;<4h&U;<;Xb%`_sCbPsiv5gB)CrI;UsRs|5ShhTf zigWpT^W|I(9>cs6oaxgqHRNui@ATnM?h`-F43|n-e)`^L+$EaVrZc3Lrd!gJ?VCoMh zFut)>mZ(SU(_&zO85o5-vTi$}ZOgHSlhPYM5XPXcoh4-lRr3!EJ|S>0SFSf$&r33c zb;nPn^*q*Wgo882V-sB?NZ=^l0{pnWV)o|YbC&)C#+??ahzNr62jNdHQ{E_Ds?*7U zX90d{RIY_0`Y;`gs^n^0(b*p#{EUVXtyD3Z~f5Rc`ajjbyYXe~MeFlyCmv#{m+SQ_KS7?JwtOg;kQhRi-^!PK& zuSjVrZz6cB6h&0VV|wE^#r+ivP@Y*zmw}GGS(t2GS0i*Q%ZH*vzw-AwF%*iJ{T>Xj zeXaD)>-_EFH@CPZ94;ze-jLDE-ww8uwr2~X8cW2i(P8R;88L!iOGwd;48{Ld8Y2PY z?t%tXZ|yca*St&~BV2r>1W)F*WT?f~%Sl~W6gil93hd9)Fv+TlIW~7Y$ld1~1mC?| zrmMFUiSMvVy&3lcoHvNWwzL~rB3>R60uB9gl3X_q5w_p0a=Z?`bh-vQXKQn1I@ocS z^Vgxy&_ad%W{k8cU379{?3WREE>RGYF?t8Xuw8=xwM)?#n$Bz4hm%(KgP^?_Oc zYV5wT@O+Z&jih*cvhdL}^tW|CnAV!f!T3}Rb4R&9XFC(y+uPZ|824S4lZi!wV69ia?a|H%(+@^TJ4JlV4DVp$ zU3-Q($K$TuUvba%zi#lvDECWL{2-1SK(5gYvVdLa)I71WvNEgrN^Qd6{rz26tN7M{ z`hAwPmktvU)K87N6g3~Qx`zc8eEYkuzB=o;hY^@isW6X-K%a!MM^n=L$jLR}5*5rL*VArPQev`nbTMF1D}$08U>O06@{I5qrPtrs0~F!_ zX*8#$pywYHzE4dRlqhZssPwB!0UG&6{a1rR*}x z=k0u8Q7JGx0J*b$t5UjgCv3Ta4O)vDmU^Gm!m9u2$^L*D8myn}T@2`oP8G=s4F_xS zCCScgNr7q)^#Y|+jy)98rRWz!llHoR+1_XnLBCGRpk6?~%Is(BH-ufnk=`AblXk%Y*RlLn zbH7CxgNmw>jf;VhJ+8ny^n*Qgw2}T;WlO(j#vB56QBz0|0@31znAkUUESXu{Pey~- zT`PCD*Fp8`zX!g5k725+jGvp+oC{2x;dbj$FTE&)FzXOMw;%NqWO&BdGuoq2+&kvE;>M00gmV_$Lt|)H%y;0= z>NeF6xCfnxkmf@IJIDI&EsuExH^{#g4l@);S;iZBIXqQRQwLs8V10H}VORWB-Dn&pVydu6F&{k2fPVy1+DwCUS7>>vi*q0eipLWb9!+uZMebC*6X zlk7UacZ9gyACLPjRPS&Sp))vjJ%p4|A0XjNgid7U<_W42isNSQi!jZZ+5aKG>TE@* zOl1svJ+6aR#w3*rPFx~nxk70w!GN&3z5w( zhosf=zQ>Z!LGYqfNMOOuK~pV44qDkZ9K!3og-tGSy=4lnnA-Ox0`nTunO_-pLl}RH zZ7pPg8WUmr1*vk!8zHG~4{gbAI=aF|%L6ewC1VC>XXnc5YWo%L7Zk)_T;x)ka6W8x z2V$i%mu$_+Z=7l}-3-wv>tXDxKFg2soml_a%5_f7D) z-;g_RWFEC<4qHSJHDgQj=5j8Lc^7`;u72#PU0#C!y;l>R+#Ckh_*mil|s7 zO8{%aO3IZDwszqatkl4bidHE20WQ+lw1-=x8C?(gX<0UAj^h}LbGl}=8ZdohxyHAk zX1D=TucAP{`8^iU?hBkB|)UVc^zlQA^sE z5D`k~04aYRh04e;IE0a32{~+BoJ`Cwp8Um=jvXnmy?nDyP6-Lq`IyX}{j+fhKdk&wU8iA=BEnD=+G1b=xHNJ` zv>M4+Gvxi&8(I$4CnVYK?d@k)pl*LQ(u2^wNxxa zFw3gVi(&Tlg4sl6P8UtWlwgN@1?d`O~U=K^ySn$`cUH)Hz zK2ekSi|Xsk!VN7fr{2E4s_N?8#)V3XgU+k&nGhl@*>T1~o!{^cRKEPtLhW8%bhGCq zpy4PbDqDkN3n%+swzL(SzkJno_SeVLtNw{r$Sd21sW2t=EU@dj*bCETo*k`pJQ^Mu z8F2Tc%?7Ui^dF5u31)APkNzofIf@~HQt?yk`v+34#v9-Fr;t1C3%ywb`zE5R_*;r^ zUn|2%sW&6apYK?rGN$c@&^`93e>t%n7<+Mx2lKjE;}fk|dOM}te=2C-xQ7Vzllg-N z`LDGR{#bptfD!5F?g-k;i6w}@vI`VpiaX!lMVX<)q8Ww=a0qDs91aG49x2Hy+C(i3Bv>4qsEz=s91MD4}g_F7}dm02O# zZ12w%T@2QZnrx3d;TWT=%&dk2XT*yU_`>FLnhVJ%U`~@s`IxWKhkJcdB=-g^*)I?! z;=HMD@hZIaNh=wlqeU*RZ6M~Jc5>{4N#+wbdr(5W0B7KBvxjAFV564->Z`-ljeAu?q4=L=c_2dG+Z z+w+jja_fQX9*L+5mq4~(=Z9XDcGn21S%=Rz;m`a|{zTa0oACYyarFHyD@^K~$nlLh z1rp+PYwG55DPT~h;os5diFFz;X=yYmDJfgv;+q;`o!5n_IsQO5%n>OofKBQ)jP2mD zP+YyUR;ebR?2fOGE;nMh5s90zc?LSp#>$Vht2~5Xkjb5c%b$CLpcCBYN4sf%H60&= zsWQ??O_}+Crps3`f2MpQuQ=82Ac*7##%iGsuI`Vhv)CeIUrvn6JFYE`6ZN+(}k8O2zcOx%a z^W=`3m6d2iF$0mr^cts;J%uRQQz8!f$h%mR)6*sB<6?G^v>{3|y)c0}D}{A!T`JLvD~sZ7=uTsq0__HqU<aNlJa5tKflYg`b3uUV?Bb&8*`frEpU35) z!9gtBx_iT@_p_iZsowf~H=|*#_MQvDpr_>ICQH(nGjcC7I!^}Kf6PS`Z*4_y#XcR$ z)@Si0+laZ+B23Bq+o1JoYc_+U(&X~#6h$wZ^p7udC(P+6^l?wzP^`NylCl1bl2>0$ z6WHBS{vE%S;$d<)_rNm-xOd5OJ)~XR&}AQnuOV?Ccvkd#eBc26E_`WvoS3J6!qtgq zvU0zf)loezxIU2o&yGRR_j1s6=@{8P{|#?=6)K^XTfZVDsq?3wz;5Ep8TGO9z(vxX zH5fp-P;aw7njyedAz%(ByVcfHTHjAR3NiozK1gL$6upLQoV5Qs`yIwx}F3o+vMM=?Y!bo>sX(9uJJP#x+&o8Na6<$N< zKYe1NpfQYm+kfu7p2-)@65HdHZ}-%E&$mm^zCYI&r*akni$g!T2%M1Bb8-s>|&zd%TiYCtepB6yo^TdjqTMZ0LSOoy8+uIR-?9}d^aupzbC^JSK_1_UjY%Ob`Bz*(=uv2W)tpl2jk@ozfMo(Yq z17qU7*tNj8;nOFqWAyC;=X?h;pMBgQnNzoyG|az9!VHGyJNQpl%BGg)0m|6mO#CHE zLN+9*ya>xL3vJ~l#aXOO`6Sk1_M0ur@k-40ZC|zBw@S9~cfVpc*njE7T?vdKQ)qTe zJ2@ScQVZV7@(TZX&aBo*&8pkrYH(O#QPb@aIg3kcdHJl{qfX=vR+Vz`Na`d_;c%6X z3QLhcN_q8Ket&k=nG~el4#Mwg?Vt}P#_sHaG?dLt)Uwgd z+GGYEWbG-wj}|cg>u|#yd^S|yz5$X0jvg!`_nt^brJ=^AhYZm4q`kRa%KB}Akui3&j0KG|A&@y(Mv+VTbChdYIu7&&?%M|E_GEK2#H z5o!{_Ji}24hK+$h?8=6QqTO9ivKEyV-s8U*uBd|BeAAD{e9^>N@H#kF_#ncC;K|iw zo62bp>~-E{Qb}D$zXp-=`!wnnGNBgd@?uJY8Dvd7UgM z6gnO|o;rr+64%V?F{?T{KE^vaC zv^5v+ZUrk3nnJz%{tr=a9aYuV{SQ-$(s2j@LAtvefrCg%Np~yV4T2oHK{_M_rMtTu zB&E9>1VrFnc%Sd@{qK%(#~qiw&)Rd%IY0HqvVf37(TPA|Ii*mbQIR1(&7CGfhw6*&t3nr@elKA>b2fYF5r_cdfX7MZ9UN|&p6ByzZPxr zOtD>_Me2XQwz14d{ig`9de|0<6?;?eJI;#@V2{Furh3^P_OQG;h89b)Mz=W zP=-(Vn`2>dCxOu6IeE!%Ib{vS;9o7_Vo|b6wdHFP$>wvR8~OhD_`3ffp$Wq{)PyLva=T4$iop#4 z!XfPVNIbU@YHgM~4uq|LQhcFH*S+@t+!Bd0J%yIMQRexA))RtQ(xJn|Q{FTUp5AzY_=QPp4L?w&!IAsy#??X#p~>l&h?13x z^F+w@?TA{6Yc|M6bAF+mf>Qh|emjAnys1SCw5VI>JEAyZRD>m9e3Xooav~V$-oZhs z-=Qx%+ZQ5Pk3^&};11x~9Ntg$MA*N!T(7&ks^!)ft&XOVsbmV1rt-hNI$qy9E+KLW z|I&c^q{^O!uv+EVR30gWqDCrr#k00J z-&d!+QoP`Y0I{rz;Gvv>F9vKFz-x9UNT6gOLg=Z&3gd68%GX5V1wCC(O0YJ4ewrLr zIgW0Yk>LwLK|#=TrtmUq7po0Z4s1&1D7{}Z)Ym6dLIC|GJZ^^|0zRt&YwA-42kB5>+=;8hhbIJQthOzKUJEI2+Oq>Hq@qW&s*$6k$$}%}= zTN8$$WjFrNKC>4OP!4k>rX;eQ8j}IqN0fR566474!+m*0Bc&AFu^pYu!d-=;0Ny5&Y@qaG-Sh!2F5`jBJ*a07(!N z_%f|)$LQ>~3r`OQ+$@R`FCdUfS1|usOZkI3S#FPlgaa+-hXvhNRUxWzZ$6Mc8WIwM zSo;E71>@;wu570EpT2*&ME;=Ck=g!zt@@F5kB1WZ}(!VD|S7} z>*Y%CVA06+{^Pync)1i{1jE;Zk56FtXYxa?GQI97GLq}+&C(Hg8GhM~b}mOH46cUl zns5XL?Tv0p8n`G+2y5zudn`;@|J}>y*IJ?PHtL?sVh41*$#K2fBCPQ@koIr1J0uqE zn(pHV7zQpLRATQDG-Eey?tb^xSyG4nbi$?Z#&;FtnP$WDZ(c;Fb+)f^gHv!GyCCO8Ulc)07d3wYltKUm1GvywM8yC=l>zA(+;7>K3&rU1f zOD<>#J@rhzi-uc2zj1Q4;pWgn4FXzXVq)SHCfVnp!@>;$>K1D z5fSGEz8M1WeSg8~lE|X!WVT6yH?sW86doGsOQc@=lnhL}^t+@qFO<=X8}LSusvHRr#IkZe{WT!fF<0uV zFk$Y4ey{E26|Cl>MlCmPmrtrS|IzS#y?I^(W7O}|rZ!%YPAs-jG4$h62mcJ!J=rqY z`b~ZUY*PA>GA;Ixf)@0lLVNWuZ>&h?RMj}d^J*P`jK8Ic>)UilxntQCo+-oeKeuyn zQJW@V!O0#p!XRz#w%OxZcvEbk(Vtw$-x!jW7_{RhA)}&1pU>3$STv=N4h-rZ=%n6A zfk05|ZoJ|EE@fSPP_`Ig`rG9vrwB*F^+AoTEseC0gjmhNuMaREJ0bHOISBwSrWuE? z^Myx-f864^$n<&68WAwI8qLB%@uGMUR)0z|tB2oMb7w^6*nt)|j8vnov+?msJP);O zcVu^;OMZKGCG!hG{2ZkP*s@kr=ty|oDV5oNchxr2lEZ~e3qWNVa=u$Ui(W3=zV z8JLMG4W@wjusWe$%ES@B;X}+pd|U$yxq5+m9gN2#!Nqtk6lGFzFaEaBP1?apbD%xv z+w3qK8VxNixTdw1tama`e&C?_4Tw`lWp{oG4U9L-{wvHABW-ZnkHbT_i%R0JF}rH_ zK7zvXkcDde@`=UFeGxZcu}rLIrx5m?lKjay>io5B8CXPIcq>vBMuzm$?-}b}EyuEN{>R$DT%ehbFUs$dw8O2@ zI?xC`dDpRXof_Ftj|$66^*fvD|{0cvR&7OqpWhp~ZRcNE)kKg9Z zh0s zM8!lZq;7mPzvAU&<*GXIoUu~}=XPt@R2=JjX96__fvh9(yJ%)2p19897h4F* z*y^Mpv@34Fz|&IujNPcX3JyF`-ZX#EWs0Q+`b5s4RBya{#v3+5tD9hlWz|fIal1Wa zm07LX?+i~HZWrvXNmRLVxn6=|0Q_2g>`CDa%C#^7uf>Rb)V|Jb6+jh6%evA;;{0eI zZi^DujkfP2OV~}7qd2QO1UuR6Y6P(l&<9+I6GCCRhse}~yTC9R&v;-{zW;X`BL0$$ ztQ?o59l3TJ``CVs(y^DwVST8$EP znPy2Bqf zfrncf7{|elu%LEb9b0~QesG@ov0|h+lwus~tADCaIMzZzFe64Mo7;YIE#x`3GW#Zo zx|`EHE4hf1X70!uHlt+7W`eDV44H5kXsRW+5u(7H!dTwqj7zX+3U}LR1yksA9i;C; zK@Yp|Hz>6tK^7_@!>K|CG2loxD90B~v%C45q4DgXaVFOSxPg^LP&J~ym5}v&zn{cW z7%9g*Uz>iYZ~^-xDXWwMWkTB9XMyD484VcuXAxF)NxlTTPLi7y^OL*Zww7AzGT7bO z}h4#=4<(Wrr2daR>}R*OId2Z)AzubqlD0o9Wv{ zbB`+9(xMWBlbu(5k@JGI7BuCGAnNpA+17hZ>T&D{e@)UY_0BPaRTUTQLr92+*08R0 zPT#LA;5%Bdl8;1*RBM(ruCdQvT~`-uIa4yVQ4$;KIRRuWlU$E2-5TY9@}yt`(`M|H z?7{CFFJ|F+#YhW2A5)V4h+GQzXi$pO3|w7ZS@W6r?sLJ9n3W(Ni64(5nw#b7)tK<_ z9SYCa@<(>=^wBvar&*P=jU>k~CIz#I*9*F0o)4m?)S=F?g?Ulw1CzQ}Y3S=iJulF_ z*@F)>o@(3dCLcyf1I#pLZn)y7TP6N~hWT!CjaMa;9uj&#?7 z_z9R0@1M8k*71TzgEJXsXQKYALkL#@PWnf%fO|@T$mf0L1nngQWC+ZOCu+^>^B;`{ z;(BTAe-~Ct9&rjknO1xikQ0-`=efo7^y$;@8J)rd)#N?eW0vb7cxa%}%(opbzyTBm z^zHWBI>aOK5|z}o*l$MP?5z$74*>9XZX#SK=%XKJ8rM-int>n&%23xs7FqLyHY?!5 z$d*IXbQ)hT!jN*bxN*R(t$AzQs9Ibm_nQ0-YAuz zUpZLs*sg;|<<_Sy##(@Vq~k;Fd*k2FaS&|R4x_48;T~q>9!tE zuFa)5gj9$^B}M`mm6n@`rH@Hxap3?BWu4usc()@nGcX0sY%aKksd9sBi(`+zObxj9 zG>u*WZjsb4hjs1RPh09)|}fPC+I?O3KHRg5{w zy@XY-Ka52k@iwF`=@Npd>j&0{@CH`V1gcuf>%U03wGzP;zNg&;4J{%7 zHPWI~=d+ru51dlO)dim#P`|x#b*;4;e>X(^BWQMU4@TE-fg|LW=62VWVOKECT%cx= zt4IVZETm84v+uxiB`@UMENE2Zzr@$bGaASRhjMMcqeg)wQ|y)EjlW1I8{x~B-C7i3 zFr+BYdLFAYd>yM%Tu{$K6^QzE>7*ojIGj){|KhIfXYgDcy8 zJOn3K>jOYng!@f!>U9*9XSeuDcA*mR&Dn!e-SJ>Exv^m~h@TC2dybA62S22rN|0_( z2R&9TWyp#V|9}JtQLwAutj9j}GxOR8c-htCn=(fdIYtBR23WwB$kK9+GgAv5lrEN5)Djy4A;gSO_Vxev zHjnd@(}nZO>4h;=oDwE3-~gx<{eI$EaF(ffK*xG&83Xu}eUMf-hpQKb2#j!OuIQ8; z_aYMk(jIw;l+)m;OI#1%eidI&d{@*Hq%5`ptyB9FbZwaTlO4el z5`=uF$lsSnj&V&f#Gsn%b{mUXx~_&Xvaap?{$vG|TA#HMBk)x6*9?ahUCF!Yw z#ts$_*I;2MZbDkj3h~;twyXUq4L>9tZUFhYaQ_T91WDx21*NXO@!2(1hqod42mXd| z)|N@1mRF;vedgyY8rDm}mZl(cdV4fe)aiC;2n`>9a`-hcZhiV01QrO{&4c)C*^z!m z(~loffIm_N8LMQ#w{PFBY&4!WyVAYB+pCeTS3HWMLMNbnc#Pl42JD~iv##X98$CQ4 zIJc2~{zRNmNTA^MCZ7l=1PPy%dB-Q?J0$ihS#LYGTDfIZCsC(wX%x7<8DrSZlN9Ny znH-z9m!6efXc=5;8y;5p&$DE-ZnccvBUlvoYS3Yc17)2+)63AvAU^Y+MIGWJ$Dk+o z?3VBZI=AxzA|jC{93h*Vrtd*cRiP7#EaTv8xOJh2$nkcY^MNmoVJFip+>ibSSfycF zh)7<41>8#9v2Um+JOb`38aNZ0DPkP;N!UoOprPlCTCH>6n-RmCk$%x ziHRP6FvAFhZ_C0CatM+#eq&L-z^&s1ezA=n z&;K6^PX8;b@ZZMvxkn=n@!KxyVL-r+pI5ZpR{NpMLNYS)apr!8iO!h}#YVol`$)~1 zcmf9(1=TwOOXZv1*1zVK%yGqM~bnS zTk+7?PrU99z>eZywL7geXl9}Nc*wHR!E{DckD3{pF7=?+N;8OKyecZxQTEu9~4Nh9(x0 zwVQ}yudv!WZ-PQI6GyjV6mmoGQDw0$^PYTCq?1gyCsO=XWK}t*l@HaVmkCqp8f$=b z?>bQsq8$yZS-B|q98;P32&o)TeO27+n4E-UcplY*wWRCOf>PB2D7ta|RogsN^_#pg z(koz7i=*y@^WVVK6#{E(X_MI#i4$0^efO)q_qrJ;Uc3Yj7_A;;d(FIP9qDwRE(Cbo z6E*I`-VRGIpIb+!Tt8Yr`&@(xjIRVFBsBBqc1fEdnZOJhWFrQC$+lPw4+r~;_E<9$ z+_E3aaGnesqcNbjb9YUI&Dl%y@B%mBzazWqSkpN;z~e1T|(f`})yvzTaj z?f)9fPgdB8K!7p9U&e23buUE$8fuIEg^#8IW~M=%ekQRs18Ne5w`CAOh&lqn6_N8b zAU~G^TgXjp<-|H78Avm>?yVzhNL92j@`n39f_#K&9!3TEG>Qpbx?rZqIqS2kA6`Mr zXn=;phblMTdeq8ZG|Q+<#Z(7slzM-wRmGASiw++Fu`0jfAO1>w>(-u?>bck|9J=n^9`>KQe4wuaoU8K*j(`Z$9EnQdWFV zGU9Xp&D($mRLlIOqYkeP5*}8a*Ft<$H-vzk{U5xNo_&P~C|YzDB7h3mtQ`!$@~B0b z+2ozjX_JZO$cdTE#-)}Xw#x>bVH`z)TdV>-=yW?|J?r0Ea36Aw*Q|}sXub?kDDE)uyfGSBd!j-^1zft=UR9*>VJ`qn-^RS2wM=8w`dp`Yke`4 zp@S-bdZzk3cvvrZLU1aqPZjB>uWo9c3}}(HxF~-Zy15aWk7i6cC4VG;|2G>-JD^lC zdJyN5q(fsOIvl!WyIbAHz9qJoQr9VkLSJ6~3wEU?Bj1&f`hqXaBC} z?&HsyMGBKWcqz9jx63$v%D2om9wttmx@WS6`yzr^PEFteNEo#Q7}_HiL+0mw`4u1} zQ4z!FF{@nx2qTPwyN$jNr~v*14GqnTOXK*=4DGF(8R1jV7Oc3p(4#74+^>H-9oLVZ ziI&OQ=?0&#LK3f{2h! zavHtuj)soTtxG;|{l%V&H+D8Hk9IMBt2Y=_>*y46E2P{|eX7LHXoj-yi{{g$`|$Sf z(73G!@&@rNmrJVeG_X**eK0(RS&F29>s7arAIOls$zEd{F%SMfF2G{FXOg}e@6)Um zrdMSBhas?<8U&pdp#zK(i)hX--XV)>9-jTJmnph*L6;i>HMg#c7Bg*4ugwWQDsTcw zlR*F;oK~q`0YI3ZdDb3RO}n$VH^IHM53tKFmz|f0zz_t`MH-|G9{Va%6;dIA;QIRd z{16IRc46TN5LYB|G+bWJE-)W0&UAIW+0LA{^Hv^*-^0% zk~<_4GK}Or9yt(Za{@JEL&Mjn!B3c9acfz26_9X86D>atpEIAkoimbifA1s5pRBO< z`AU?}E_M2JT{%2SS0e(nU1@@@7$K4fr*1l@=U~1Uc{t18n=$XaX{O_Vb4z1NQ>Y>2 zU3xOq*zGId_^Dn|ZZ2i0d)~FRfviz13oeQ2Q=wv$?~G*6fjB#%IRY6{Sg+=75#qr) z(O<8@YI~wLY7vh^@w-cIs`sBqSaSQiiT+16=e=cZ`73_frk6)p{_-F1e3RvyLdJwM z@dds;3==ZULWmOloK3HkKt)9*Wz;QOvC6>EFl#TIgFXQB*#8rqOE@jg^GAa;ddcSs zNcNWzKQ8sqQK0G@5W1p7fe@AnvR;>v4k0u9&-q`8VftlJ9HC-kkW7Ta3LijDcW*=88R*Lpe#ivE`F z*H7Lt(F8V(UZz}J$Ebm;R)iAehHe}icQ!stSDs9QzehWZ-Z9yUSiJF2b#LTK*DVl! zq}^*d8BHE^#9;bJb$8ITpH0ZJHosnPK70FZqQUmfiu6}<;{i@i&ZOkz4}}&s0C0=| z%PS6;$=22u8#}xG&hPGSsAeT5`~fr(_>qh+E;bYB+vEpx076~LOMWGjK*N)1ZQH5C zyP;sPs~Xn=uspxkAtyg5D*WuGuMhS`=c97c-;A&CffGN)<)b4bY(}8=*^u!1&Zmqi zOsAxx4FwXWVD?CBdC%g6m-fUC9>2+UxogbSc-$0(lP}>#5FdXq{6f*M?=4TGVC-~G zctE1rni|gO=Sq3(S56w~r>$PR;@`x>ZW_vfbjzjVGpd+c6;AckVdvgMe zySvOWItN@s_uah2CAMt2+zcp*)&vtULkq3Dycbil%|#*v*Kj@mpWaw;nq;}HF=TtN zMt@xBsb;MGL;s0euwXs0^uv)0*>OM>|9R%%l`>~Q^(WQSun`v3$mv_T5Q}GUFdcZ{ zA3O^^eO9n&^X3)SC(e!dW}VgRzkh#kYlO1&FKs`5z{m-v*l177>*>AOSwLO8KSjvi z-_vPr%0%2YzcM3ekbiPfwYgg5L;Wh@xjzlI(n(v9$ZJI|czB+0^J&)h)VN6FX~dr7 zHmlLZx<&WKwRMmx;Sl51-3tfgkpekV8*;f)>7-MAC(^{_i9n;d;1KWmn&cH zgJhSHuTig6p&MPVchcy#{lP3dxZ$&li_yKky`2e0J->O_uU+Eqr0z)w5e3<{1p!2D z<;4j}C|Rc49nzzW7J^3~F9j`WJOSjir=^0hvZr0{A$+AlV`K)WQ zT7U5RsKxE#aZ51w;i;gnU2+F|eN9UZfv6fvKUjEZBtWTf+6M*(maGAsBqLfNEt#5(-I>g)S66TwZQAThD&vbU#Y4+O1ct@z;wqq^ zNO#@A(m+WL#(UMrZ}tO^77Y^h>(ehCl`i-kep>oPbvsG+Ify)e=AeG`)Q z| z_0%BaK_)G~n{G!g64impL3Glqt1EA? zSa}mk!tb=;DMU&l>;b8@CCezKjL+S_0QEO%syaB%ysGmoec zQI}7v?1!o_zvaJMym9ocm$_WNbGW!sFZFaD(%Mv-bwt zm3Ks$*F2@v#U8xFZUOBD^{0>tPxIsV=LN)gzz(aD! z#Xt?w4+(y9{+gU!l`n!a?GGx%qn!^oX+KSHEW9Y8YevPOaUiVl8w&~m5cQp8%yh8&|S4&Kcou^N>hdQqnA=;y6bKQyp^Y z!=W=2dmVgZC+!b6@PT@y2$&f?arEfJ{~HfO9hZpgC!dX;hZ+t1M|L_}@&!jaSlTzB zZw{vJ>-wb*+yj~3YQ-y(Xf81@(+>aZMZTlO)}U)K673=UqdVU#uDMd+Pf(-aBhL|v z23dr4Vkn&5dsJ4mgiaMZJKZ*(xb2o_Z-)-EkPMaYjBbtBGf4N&EYUPOBkito=O#MH~iymDT7pVi-O5Ye6FyVim*@wP)v&pXn z8q_SYXJAb)4dji{jAhe~nf=Us@E9XB3*`r|c4gL1x1+}Sr$cV^e}pY3P(afE4and? z`L6U&7w_Z}4RbnfNlwBGiG$mNJmTIBKY#J0vN?gfwu^4G;hG z1Cnc07P`ru&G&TBuGXaUxIcIQn!$nkNd zqT=GL=4RdL^8*(_Fsg`WMKcf>6<*U4v?tR^#sW@^5F+U{?cdM@iLA-gk5F1MdmX79 zeKZ|CJt-=RBR<>!Vw`T)cKSC&gX5-NLU-);2#jJqBE|%oZVzqRki?-`Tue|6czAeE zEP$Y@W?hm2zOpks@^Lh zwjn_y4YoZN-vJX79!_h+vMEN+jMr0Am2-f6fD5+z^&|J=|DjazDbW!0h~RD_?Bgc@ zqWW~iz6nseGm@y^zg>({afzQ7CRHeJ#Ml_Po{I< z4+rz;?8y_td>ybIX>3MpKv$P%2)rtEbac8rkDF(>2ugtQeQwQP1=7qepjyV+26DEy zM6YZ!H;*>pIHR4-+h4A;wem;hGKP4P9lwceeCKR@p`BxQS-(PdZhZKgh(r&0S|l;! zr5bv>Zqn)72biJSPq5>>?ktcxNb4}RjINu zL8avCe;jiCoi;8@>Ejzgx^N;$Fz(kXm{%l^0D_-Kn-6eh(>w611}H~je~wNCO$l56 z!sg>Pq1JS}(tU$t14GV+EB9CYhb%OhNtX=nM{79W%PIBK-}AO)b@D)x0=^pW)q*C) z%`@V}$0j{Af&KC`Js@H-X(nWwB|}1ER4qAdt3ZeH%=+;~!~$E%k8xc6w?%&|yT)n* zS1{_};rgqo7T|faGoj_qmiukSa0Q{X=1)f`<|ywPh0T}^7DjMp!gYYB@P?u-mU)K2 z=UU(MWy}SZ>2RU;vYoI>Wa21URCzf*r%a9Kp~cK-QQm|usP4U*#lwBb(VAAV!f_HF zTq<{d5Q>zTnU>SeP$=zxi_n%8)^9KP{~A19y1M_Kf0@gL`5r1kNwl4k2dh)6{ro>) zkNTKEDOe4?3Q-KBdI?EGaf0#hi9Fe)%*@`i3a9yHP$=P4A)*X1WFwSu11s&NWPN(? z_(!?`!!nq;$Ap(ng-(jx+3E9?^~R3Tp&hL*?c1sgmn&xlktEojNpja@$bSRuQT9Du0@&lhNx*wOm|slc9ipmo8|qsu!Hipt8$5;p%zm`BYZ z9zJKqGkEX0ci`BOQA4?dK9B;V;~hB2JfS2Woe1WD5eCqmt$e+B+p1_XeUKvsFzMJr zDyHc_!*L9>kC*xeJ;`YtFImLoH4i{*!yE`Bx5uuWGK-Qbz&^H_NAJQ1r|v(%9T^NT z#@@y+-(?B{l(kLmiUuX}4y?>vG{Q@_42@m8W#whIa8m|sJMXV}JPGwiUsTQa366*y z-wNBfE=^mzWRU=@HN|6;We7k9=N))mpCw|WvMN#OJ(S-ATQ_>#4}thbU+ra-+#=sF zWFU;jcutHn1rLW*&L0AjJNlf?+YdguGD?%Al^`w?%;!R*pAElfV)YuagH{{p!4A3E zd)H4xE3t}&)gTkMhY3?=T^xs~nOANqaF)#7fE#6{nL+mY;Mr{jHbCuY5UB>B}1vjMXCN6;ap; zjBbuq>Mb;6+$kNeEe$m|@Q38pAK-w_9_4u-y}$=NfR;Vh!piEY!^^iW1EBThxWLhH zJv#o6y%sd|>$OsG^8Z8FHROxdELQ0F61uO?cxVXD?KWI7xn3TVk4Nf+_9JQh>a;i( zK-3o0?0r#o%rc2ojzfs2p)%7%9bz4 zp!Hsi%ZSMz9A%TO0xBWqn@B2FvXT#p)rtEb&2D_P<}%>%a|@jQf4s8lJ;(I;B4aKh z=)E-QR_+VpFk(F8p%PS4rbcnSG zUxlZ>vkc18ZbB`~Bv(btMtqHPwTM}z`Be%q2i*Q!&bN>J0vo@to$K93$LlF-rPzRL zh5{vlW@llu2!CQ~muJqcqX9x|eqi^dR7(ydchXXWNgSi+fOP(yVqogz-F10YU4ZA$ zE2=?Nu$w($C;i)S5ma`j8T=CQC0m}nMtaU+KV-cC2yV0cI60@b9cpj@E)LvufF%$B z^G@o7AC*`!_s{Hahb;V@jXNV&7|o;0UCG;n8Ec)d8glEO=1MR&>{nI|Z$2 zl4{i0@JWz+Py1-sfa(^Gp(kGcGi%2J|5vx>3$wY}fYHBz_0|J{DT)JDi15&B^49Y# z%(-&3nuU31El%Udhs@(p%X|0i3I-Hm5wwVNH=&)Rp9z7qn4MI;rucfzoS>U2c#_&-k+V35$+;oqRi1_{kzVq#hWn{7fuJ~y0_ ztt4GNy`Hf#td3Q-gv7*Z9r-SN;}i7jG67x46+S*bM$t0weWEQ~s#x#GpaWBnX1&=v z7pE-LoTYK$az_sjt)I@{6p?_#sr~)mo6smt9i80XuSg&|I&-*lt8BO8ui~rR+nYiy zo5hyAeg0w{aX+kvh6X3mhvF|l0Rnr28hBJW)TT-0`IPNpEZh%QO)?RaXDU(?m9VyQ zr!3YzOBC!-KA65pEoXi|x_w7d7rB=yDseA(^$Dy>5VdA{q7vtzsy)dQ|SwSTCOMemQ- z>#kCyN~HatKTx5~H~wid?;|JU4@y4`1K8!u+5fI=8~dpL!!9Sb>sFCDPg<_jxr-U| zoRv1XAZ);u8=~9MHx^t{YADI*B&-t$C|Eqna*r1pIu!J=U0q#%^9L@CA8WIIiO0)O z<-A2}7D6IzvWVw9L&pBQumAT)E~*mRt;wl~OAFtx*F`b)Tmy1h1<+s$ObiSek^C=V z3h`gn<&sTYSErVBi)A4Ug^PMO_a&qU6y&$ytLKB~L&ZgO0oR0Qe}eiHeri&tt){wA#N= zU#|05sVO9rTRpv47bY;`2TNHvyFU5de~tqim<;BGPXSj8u7Eg(BD1itP@-3lAGqD1 z{o@q4$S2?dm~d}{UOpj@TdDz7!f&m6q&){}m})|h1-Y~%=%H;1Y*O)39d}$VGd!== z++&GfsYl0W#cU3~tVcFb!&hQMe8O2~`4olbm7p8Z&8I4r6207_=Rz(chMg_p{x4SK z+e-54j-LE%w^oEj0!f9)&HcAJ0t=R2An8@68&KT*ccrsuL%M_2EGTOb;f_X@^1$Q2 zwo)L01LBUKJfA46&3TQEIKC(o z7_HohP2B`-KFee9CoZqjfPPO;o@nS}e&p6}T1@48opwMa|4-Ro zT`_>MSvMP?ntfsi0}CA#{$d_O0Iiulq}vE|E(cuvRb_zo%BS#>D6@fDc}N`lKUE3ShGq2}usuw1!T9BmUM;YvsJ> zJj-;|O@M%yp^eX(?N{@y0KkRFE4_S&&qhIHsM@4{TzA=xO28fAI98{;E@3k3>_tQw?@)kWs!ThTx~5@X5Z4HkKneovKmv) zr7;7mCXkJo?R)ivFtGjZ_G;JuE4&PdrXonUu+LzS42Naod}TN8abRCtXn}x@49>Fs zCI&R-OJv7b91uATF%SRnumO^lf2w?Ck=Z~E8E@fDGK=qP}$0#M?cK3Mzo5_9Jt{9CTcv~Cl@JKi_W zk_a%nKa^XM^tx`1#puO(4RJ5$J!Cf5Mp#ph9t*WX@yWVqm7=JqWh$t&^O@@xF>Tx@ zMx3tXzODBUnXx$%j?&C_!@IVT+J(JBT`;m|Ewy)TgLf_EAu#bDZ7P^3 z*ChP*U8DI{4fh^$t+i%CF|t-}26gBtQ^j{T)`IM7#rI6H@4G23AK(HvDSl{V-zZ)d zA75R4iJ-vj`i*^k_3*v;jtVQ+LYoWeQ|qm!Bduxi*P0cYKvIMqSD$@BYunFhiWeBl zj%!-jhR=|iv2Ytxn}fj;pB;2<$e5%B&7N>F9;o$zht5|UnA+CKE;$BG z+}lo+NRJ`L(twvqVjfls4ld-14g^as9ND$WcV@HO2hyTgt^~WUY0U|EC`>R{8;*&< z5?@U{uXXT}MwZ%MteDa!QuTSDsbQHKT~YFfzW0BbWrz{h1RIYFfbT+AY4@qR=(Xkh z+Cu7)0$fC2&N19d)CcE>)QTv_n>f*+%jf*IR2D%D*;%CeBOYkkM}f+~efU5)SAnX( zpR&C`I%ILU#jM(aIPeGt_mv5P^6>jw$n-If1pZZdrXmxB$NyPKfL441YCnwP&<;~N zQ^>Wlv8*NyX{?7oNiJav&c-I)w}tqU|7Ru1Q;P$Zv>bORly;;xy{~w)?eP6590UpK z*!p6~?5&dtX;@fPv5_PQh`F{PW10K5lC28|h$R8440)R3SuZHMOQUls-rKw`sVIOR zyvu7;G)X2xa(vx{@BKbKBBbm_P}}WfkCkh_MT@Xqx9(xymyQu1$CW%QRT0XCBrR9} zLd#wr$JNl5a%+KtHU^0@M@mkUu{KNNbHyj$am?d*f^Vx6X?)xP;{5sFzOi#C3s_8w zOG5@sq>JW~q$9p!y;?r}12Sfgp1K;+Qgj0f<*6hIEiEmaqO+In#`ciKQHSj>O`Qrn zi1j-xWJgPWxKG|CT$M%2(pTKMHpOD)zrV+BME@Yh*NRRpoUhkn|`iG?Phb3o1;7G=;QTy=oti=B3#1x-Xha63ozqo@A!05e5-E~E?lUESOy z4)6pT(McRx^NN)Df5DQ6k~C_4RbmqzSVep`po1ldQ_yRTV=6ltSuG&ibP8-%Nns)9 zkpwspg7ek5BWVpRul(VpF(zJ(6T2>n7!1`ySnhu>*#8LMWw*X5%}_)_fJZ|^ zdxaD7Duzu;HZ4X&OA80@vpbyr|8W6O0siW7R4ulH&cn+KeG+S?R|#}Z0Hswj^+h;` z@7JgppIcZc@*H7+b-56w3X{IOd9VOP&03p9igRpkvA5&T>j`Hy1DiVoA+3|yFAWvZ z)>wqzFan1i=0D{=HL9T%-PcK?JZmMk+*r<`|t)~(E- zIV<%(wE_uvnOP>^?@}Ki{}v=wIjU+@d^_Ghr9-kDd@pn6@_0ZIzYCzl-x&>jtis~W z#s!B!C=1Y8fya2@q7P3dbz*0alqF)K=SwgKJ5gR8E&kA+E}Ab}6py!YdBO8pOFWyf zqnqTl9Fok4B-};^46RFdR+lShS2Tw(Ov6Z6uhq%u7bn_C1tq4ctNS*rIjf13q&Sc>xEK=NH3DsHV$ zKu&UM#bbzvcXTp#x~R$L=pppD;i2)fcX642CCC39 z;%DnX+7(fliBm1fJB+x&-{(!2%=-c90_$n_tD_D_@b{s(`OJLo(x3Te3pSaX1$e~s z%mS-{nq_xZvim$8Z*I$0Qfw`WfmWs73#WcV;0z}Hg^-S#NTxd;3X?=x8N$oX(vYh+ za%WC=AqX80c`VRWSQl?_!Aj+ud_94T5?{h++u0dMT5WNNX6P5Z-5xssI>#UCFjH~c zF&p}UtClNaA+PJQ-Os)c*<^8HaTE<1w1I$iEvBFW2$`{RpT zm9?*rAs6DnrSwx;j^YSEUC=8Ysg_71@5XA>3n?J(m;fNfU?S^}>3kh&tIr{#MGVZ? zNUaS$#xKZ~>fWVCYn1D~#}4hXk|58wqH;B4URBp$+iv~&>&dbic)ti)js*fg%VKwB zf2NRKSlL*AJmT@%>|so~BfZffl}l(ht8i7I`$C63~5LZnPAEI7R= z?a=@Pm})lrmY)v^g97FdCnu+TSRi;TxB82ULT46)>P%b*C}W7E_5d6fnv&l1M{e^Xr6M@SB7ash*6$ZIt3a3Vfum+MG zTpJ=3j_v&@7t^S4*UcUILLjhdY`a;9Fq*wW_&PLIi5{`Tg7hhXGUU?FSuz%zFXM{b zk^0B(I;bsvW13vJ=)eSUZf?1KW##LZI`nvgz*dVqyf?p&#f6PEXnW+qXmpC9cG!4`|D3t7axW2x6q5jO7|d zOcguiWmObRE&@-B!DLFZx;M^jWI%b5a9qJ}3!3ZAytP3!r(dqTr1I}%iBTk& zP(JT9@iIIfkaogHuhc(P^n=w{KY-^?Pm-4X&bBe-`m2N?k}>gse5>w9ao4 z_WO@#VqV>r^sZr)ul-80S~289Y)0k&vt14xCvzl)MkHD zorA>>HYqUrG%|(S*3$CM}nsUI1v^^$M1jU(ZYaa zRc(EmDwL`9C5}=;P*?o(MJYjc(>$Bbv1Tln%!BV0tpUF+ri!0ADM-e8ET~c5_J}3E0ncxw`)jqB)$*nf zS>aA)ijf*?mL!^L=p-ysjqQ8mSOIW_IJwLzb;d*eQis}lY=TCPucrLs@&9ALVKh*4 zXFbMBmY^Nly#VXx#4epn;&?CQN{N3n;Q-hz!%Y(3pP}LTKjWyh!wu>C=za2eE z){c;3Td1Z*ZROdRkj_(rVPfXsErC2i=3OeQ80VySz)<2Vgc$!$h5bIwD@$+$7*(WjvnB1%+RFX%;)XG;I9AUo7Sh*mqI9hUfQ<|&~M-)2$XUJfj+xklGa++AkKTzZuP!t(plI_mYt5z@5Z084`va7gN$Nhgqy=7Qc z+xIpM2-3aj?oFq3cehBlbhm^^mvkzi0)jzw zxW^r8$+RYMf%(vAmI$B<<=zQBG`X7bE%JIg%Or@_sUaf&9$5J8jqWM)PjfgM_IlKF z8yR|c^iNh$L__&jR-;!7W4pYwylGUM{Ju(ot1_QHiKe)LY?QgO(hfk2tW!ec(68O3d_@C}x~L?XCB!3MJbMhK*5wC{PJDzjK7Bff!sU}Z)R={F zGALWFI-Wcl3%ng;$|*|%PAwnOx#b-?OOR?UDU;2ynOz&ifbwMqmBgN7Lo($!Pa5BIa%mdkQVhv^$cT?u&Q7(i&+ zfg}wi8yxX2&D+u|rJeC1omK>&M1{hHws1U2R2yI6MAtlu=Gu-%je=4@SXHF;VOx~G zcyhVHAK^!~OKQd|X@$LKI~IM~#k!FYF{&|i#N;!O!ie>+p|J2MH_>KnGc5`8rX zCzCv-2gA!;GxpAuDp4D^hWVrTtMa?szeplpu00t_&XB3H6cR;KT*!3H>DzoF}tg_A%YtVON5F-)CdyC$8)h_^-p z`Gl{u^VM~gXe;8GU(w4r(;T#IfJxHJ6}G#A>`pp^UG!4B)_qs`M?v(>S=Fx;U;F$2 z^+ZfY;^p_3*kCi*W!v!M5VxLuev85OU1b#6)X>|ErzT{4?hVc|g(}7BWk3t^~W+eVEzIYf@oDwIa0J( z^#txNTvrn7!6A9iu4Mhorq@a9A3h}{DHJo!%*gnCbK{G65hNgONL>Vv!KDNI-HmY_Yfgb@taGQ zkYpm;&*smfGZ6^g!r{eIKb;%MG#yavKWrjxw!iGRz(;Ateg4X+F{s^IO+v$(Pn|2! zLzXP(ScpCBzv!_;>&&uB*Z_~#(29uFsuR!8=;`QW+XX*bvAz?VUM z<+~bOj?&B*fx?Uzfw!2h{@3V`J=M|K(v6j?jb)U(DAr!bA|ZmK!@1Kbt{4*g=jOK= z*JFVgvt8D9dt5=L&>d+halh6 z^}hH^&F?-8WlDit`U>Oi%S*m}7W|u&vdq5(e`mskmP|i#F7J+a^G7KT;}_F&hgW3jFFpK4 z9}e7`b6C7vBSBic-%K+9hYn6X!d(Pk?QZ?u=}x-!^tZWGa#}rM2*fxPyUVP;Oc&>1 z`ZXo_bmerUjI()z{;64gG-rNZ^ZMPyYp7+3+36F+l8H2ry1c%iq;9W0Za=YlZ0hP- zF3eq$)}{+Pr&C2^>1>O+z{oCnDftx=_9arb616Ih8uyn>B$<*-T(J%_NK&|t7pG5_ z5Hu207+B|e-KuWt=!mY9Ii8?l$<=U_<&S$DyrFP@xqEo}yDM+=O*jJ{udkeY^8=vSgXdwejds`?Bs$w#>Z zVBY;LUbbPwiL=%Qx&l&+h~rT?3M2W;Ao4h==v+$!66BSqwIBfpET^w01oLq(XUkrP zserVeK=OtMU26(HZuKV{3u!T_*~TpQ(r+p}mF*Khta?nkgEnwz0ZiDi=kU_0bCsxV z=?g_(9`4KXRYiC{p!Noi|L=eTWZIuRwh#}EkC%L0WN3Svu|gS`tSQWzd{>BUD3h)M z7W$f_y?r-KTy>gy9iyujw7j@mpN~!VykG*FMbCzP5~f%J9^aJuno(4*{<+m6^z}q? z-GKCt!53jLWAOeZI|tZBtSk-av6DDoe*uKC43hFcAjlVC*|jNLl*E-lu*I$Q=GRQB zqQaaBYGgx#I52AjF|4%2qaNQY{_CtxL9}zfQRMBHj)Ma>5QQ2n;b@HNn_6;4{8i<{ z2)fU=M$lQ~ygRe^a&ju!IVY|sfP(?hH{K7^pN5f|QDrJ{67PZ8x7V+&&@XJUipoV3 ze~^DtV)bc2A$`Euo|H_1BE%|*s21`4@&?Ii>~bnesfRBg2-E`^N)4!L@iNY(9z?2* z1kziVC25aMm+PXR?)DVwh^~De2~iJ+Ejak!CClFuEXC@3{CN*Ll@=GWC6n;>jDXFW zvWF$>m&IM{U8|L?p)Vc#0C?q-=~nJz?6cxBA3Cov7uK}G=D!qRP`wrU)RbWBjjHea zloFQC`N*6;i`97>@50YQ^r0b=76%!q@&-et;=84&`&a?WTLR7|_&myskHxW!h#SwY zu0rBrVg7>~0G+_IEyuf0>0=7=OJy~+)rn#QfE+Czc6F~Zrn2%xlL?XL&k}>61?_r8 znnVJ5+Kw=iAP1%x(e#Vc?Dbmr+qmW29vE9$r?B}Dks@bjXmeoxI{>S?gs@ya*m0g6 z%c+%Jt@4$hrMEb}Y4QJsnZBpxGFp;WlY>_^*i#ICUBQs@_jOrIV8*O9L0Pn*mr>m1 z=WI9s-Y{zYFWjvi#a4Png=8IvEb2+JGv!GvMbCnq0{2PFL7>*jMbMOJc=H2Mk=j8` zBiJW3)I@6dK&goU<4+?h)tQo>p6=JY^%V~cnwFQTfW@wj{zFWT9)Fw^lZ<(IF(v*r zNak>tDWAsBwy842tZfQSp6DpZ~sZKHh}?p zJ;mBO!5CW&h>OVUp)ywUij{Qqz&6;bvX04XE)q=r##8+L=dN;J44-~s^^h~~1Gnqk zb*xZ$40W>A+J=JlpDCZZs4WS5S!AaS1R=u&2ic*n%8VwFSzz@EW+N3A6D~3gnu9%q zn!g~fJh~lg8nCZQ(#`u`zJ|sUr^?Kvu!iuNk<_CkPwO74h-4-PB{hs3|G+KqSsm`4 zjv`WyRWm>Q{-)+TZ%HKAjmF#=|P^0bjkg|Pnva9`*Y$tk&)QsZ4`ef-!4mhlZME?W1-20eg$cStM5 zZYTmnyGi1AQBal_1HZ-&J$y=M90~BXN*LaR)#jsP)_=8` zQK1o|`fjKe)gpa;zP)LKttiy{2nv6Ke&~%8Wwtk?s|D~?Z?HKJ*IF-+IbN$=q1rPR z2%io)o2|AE!;mkjfWi%C=|^-hM9Wk8!wzaN@yD=Ur^d?y?D;Sljy*C-n+sv{z&Ga4 z+4cR!w3BMjX-Eg>QkpQIy0)D!J!}PX%5QG|{Gu}NYf~sP%wv!USWXyt;eh!B-jY12 z$(sBwf2N%eUxr*O$(}uc0STY;LPvYV4Jj7x`{AdK<;oEGgOLpj@gP0Cemq&fhMxbQ zB2#F>@VZ%*{b7fGZS|M!up6E2j=i?4JHHBzH75{>6e-DpxlnNDZBJh?7gLGK%%~r| zM3%ofM9LS!l;RK)*eTq4m`7b;C>&2VS#pQ6QOQ zh;oP@MV_nQ`ypxM15?n>*iWJEpbGvu2ofmXnROsMle7RZjj43UN-rE+Ix5hU!I&D9 z1qrQ>q;KOoK5p=10Iv$4hek*p)$v-);K~YhiAf6^$t>+)PnUQk*(+YMLNcMWylTcb zez$r`v&*`wV;LtI&S<49jlqd#t5v0M@3-uWgbhZkh_0`?{E{>*zubOI%nb5A>QUnY ze-Z!?PQWir)VMcj1`!_@swa46-?Jcq4*(bwp3r9`TdCi@@pc}Nr1BY{Tb1wl2DTO5m7!F0Of7rMC_yit?otf-$*`Gvu@68Uej6VmW>%?3I-0lUi zcBVWbG7u@h-gL?a1Yw_0j?tJ zMesJwPHdiTovmn{-4O9Ay_^c(sX1uARID@_I@y&n&3yRIn~*&^tAf6q=L$Kxtyyc+ zbtm_EZjPq+a+x<0ZjfnqLm7U0`!p~t{?TwmGHTN66j6&RG&~SXQYJ*IE8sL}tGI<0 zogEJ2;^G0b7^yZEG=LEy1!Tf;>qmFj?hekc#KKdQVrtPzk`?o{T}kzebvn%ZHp;L% zqJVvQM#gu)_HjcSBx|F!9`^oATF)2dup zxd?E$zcI2;C{zGLh@Q}F@CZpRwmL) zZBTz7G6!o+QIC?go}kuM2#$o>R>}%g=RD}C?;b==#Kdg=`ul>O?y=B!I#S+Mwyf-o z*0T;e1yFl9eM9}=P_TR}6V-5p*kH1B5_N{Ayu!xwJZRgtb{I$YpjDy+nC_pyflG#+uilDiOH4D)Vrx~1BXY2 zn|FtZbXXj|5qCs^@P`|)xZ>Sg z;lMHfX^&BpYpE{!BZ4ctPKRNt#&I?AR?9LJ>b730PvtW)KS8aSnHbR|RVyeGA#rGW z8c&6*1vcU;?6%HoVIBX2#+5}cl*`4~tKv1jw<2&Ra70#Cqw(~O{(Z*tTvo2X-!=x} z*LXBUz-brdBR+ca_SX$3P_Tq33+BzhqISEPa-pHT_pc;&C8>@eZln5OKP3vxTwYeL z!1rXSN`8xElR4fH^TRa|Tl}d{4yw3htD|+b=As508afZ)`}gXxxA5xrasTjq%2P7J z79fvSxa{ogyN%ZHoPc2n(k(bSINr6kN`P6+h=(l>#;|+Y?76M&pd}YDsD#mH7fsC5 zWoa{aWYuxh_BP}C&{0`s9qvg$jF(r7YF|z^Q+_lfeDek~nsGI<_=6 zjQ0t2CYs~5GRNzW1jpPCIDA>jWqybW3$rp-2lPpki}21b(h@#%(qUJNbbdO2lU=BO zrI*p7%ZOjS!}}M648@F_hox38(Q0J#Xtf(5rL6Qk4vDb)g6h{Uo)Ur)AD=h;^6`Fg z(<8Wdy~n?u?ThUw7EE>CY^|`nUdX(FTycgQZz@9aYiWT0Vbz%3{$eJj$3dnh{t5Fm z?2~0ne(F8tJbuu^{bNDw;X}ZZ(R)NZ>|$+M5MR6}yS?47V#awN1IPx9f}9xOeK z2}Ln_!?H$&!z3tJ^TadOtn#kuVr={90|q#9lvlMHQz~3LM@7g^KBYVQct~R!vMe>8 zN~_3v*U=qEoKBp}YByim9mD1U2V;ao{s=2SZu@2XOO?LR1xavv_9kCsGr@bB63UJu zv`bQ<7LLPK>bYW?Xl+puqVV8q@zyuE1SqxOZps2H)F*(XF=syPA0jf%lhrUHcYB0B z?C7(VboEjh&&(}TJpRuT#xHDWY67Drw!;20hxc25XSP44${z}9I?vsq`a^SJbr+cf z*;1!Vds0U#s>@qF{M<>E^5)%V5V?ZQ*Vtu>v=DfSsEmp&N3N}HfT|BKL{up)rg#z< z4|X08w&QgI>sx*RwC{9-^ZpAfzK@(7AkUkXPygOHU7Fe%_QKIRz|hA>2l7rBQHRD$UbLwi>g_zaU(~ z%=vT~d@hYkrcn$1KQ2Hb5)HN0+rZ~x%CLoEdaT2|XTD7xj#E-kS0T7dfFXm75y*YP z(*mcMJiQXZNB26k>YC3#9tf+T;3M@mLk1lwV4tv@t)uU=8Q%ET(Uq$MgDJ;J>fno; z=S~OjLPRVPhmXjj7*P)-!~0*c^0m&T%$C_O29vCr_GQkv5uj+NwS(A&PLxz90V9#TwL0jX?P$)Jvve! zRgm8IrOhqE*xlXrq(&1r?+YDT{^a(QFK$&ybinAH?E+Gf`#-l>wGe^Sy7Yzm&?BAN zpI2Wi6h4gHgC%nQ?P}N_69z`;s9}<+360ekVRo}=QfyCf^d{7k;HEg+z5Rux3qiFc zRR-eb>ldB`eR$bNXr+G2dIRA6h&_~=Ff>WfiCJRf`8M#g7B%e3Yu(+;!y^<(Zh+Rx zV~;d+IhlX$6Lt9JN}K8Hy(BkhN952$$zbk?f zmX5whE`%`xpHap(R+nWW#YKLD_@`1n63x@1sJenJchviMhn%aV0s1ZrpSOhEi=Tr0 z`p{=&LOd%n-UL3MkYFy7V4kwT4~vDn!3lUNS+m5u#y^BL1S4txv{Iu#GTfL_nfU1B zsM&vWfPhs{pm;kiwyt&1f->Km>LmHSmHBe8g)wk8j9K7(%?Jpf6S+oQ1x0{w^$*j_b!I+x1usty;&RrFxj)mj$uRvCjMad zxGk+LFiel#FCvp9q@;p`y;}LXkTg6Yl2J(}%{~o}akUQIe*}NF`1FqT9i$RLszDt1 zGG}Oz!r`21NaAvG{*bmm?}pL*w;Z*Fh$A=OsSY<-{d%S}qKohOM1lbS-+r`|WMp#>a=-iZ&Ei z0xv#AE8;?It%=GjX^c;soSdRTuS^1}XyVxs!E|K!pp{%_;*|lLAS3+A$9mNKEVo!J z^FHDB^e{7lUMN3QOddtO{wlN1DY5ZY;I%=`w*07g4$Wc zqHlYSSC#v75HtPHl`j6`;0=L=!l%Jx%ql{{Q z#E#?En0bSIkI0$@U!@B|v;XxE)UxqdF`a-4MWVt1NvNMH;(HpO@7JSFF9%ZrUvz#j zPPyYi-qp4>E=%Hl4PN!X$Ih)I6CMzjPJGecRdYbdrXTaAh~9-1^=l09^0XfX`DCIG zDARvwT<)g55WI6TOs5=__12otln{$P3z#YLco8&Er#Bi9 z=o=>c?_NbWXW)^BXRuM&GDiB*u5F}Lf%BDZ?k~!Ghog;Q3MBjgwE=q)DP1XM!lK)v{m_&^eNHW+=55%J)i zeZ5LuwLD0h4nH;H_rbj3x3(90{XDvwS{$~Z5!qvbS}!^mQuV1)GUr`yuL58|2q#PX zUeX*H<|^Jjqa@-hX;jf6EvhY5e=C{K!ckglYW(Vejfd-hXwps^u)b&pN7P?Bq`8og zEq8uXfd;6<^WS-GRI@NYuES{y99XpR(5oUDNz6(TrxXgyvXEGdX&6Y8>cVFz>Dm%B zA;I{+aFj}96qG;IqR00Bhb}CXZCSpldqcpKBcx8OHME}OB8X^tNaNz>rup#3aX+T| zLJbvo`qDF;JF7l`>8$RX>fFMHqbGF1oC=K3i*pMau%O7{Fu#S_qD+c^0qdvr`-f-# z&F2Vz{Oeg;%WPP4ZJ2{spz6vBtlX_=(Ofy=FWCS5xXPkSo984)e0p7h{nk}JLT=(iyZBh^RQ=d%8UEkrF<;1xTOd;dN?sfSDU(wc!pr=qrESHD^H8#*qIVjM_W4>uWpH3L2dGeNSy(HqBDj0Kx)|`Zh4wQ)DiY^ z4k2{?Gh)tG$JRj`YgceQ4uZdcTa%pts5;|ykE1xcM-DvNEPvvER}mlMd|m$U8z9vt zKo7bAU4!t41a}ggoO}_@A1OAWQ3EgjVt|LYQ4sVI+kwh)F%^TE;z52cmT`D(c_vZs1v7mZW3er_GDJ zCxU=MF)kC?iJ~T**OO4E(&5-s)D@^gSIDlRn3s=R|Ch;$0H8=&h%@|@;K&n z={6%K(Ym|d&+WIEkKwhbp3=%3MOhZ|1}wR|FG#e~K03>r_jQTmj&giZtzP5hIq3~e znFW^X*flvQNF{BGPx#}1s}MyDR$*dta#u9O{%Ik~+=17xM4UF$xQ_Dl_f7^k8zQZV zS)=b?p9TR2a*lx8IPLr#`lXDD?dU}`BZZaf(VYh>S~{Y-8!WvR@>Mt77D+ixRi4X( zX?_ETz1??eP-lbEx!9Jsz(H^({CeG5ym`S0`XZw2zzeWo3McYl*c>Hp+}Wc)bZM*= zj=2+_VesCO3HIV!w94r*$1(T041}TW)d|x-mOchWh6&Qp6T+RlqvhN17O?OxCRFP# zk(1K4nMI6B|G%-7j{hTj^A%jn!+9xs0GGsE_)HrI8U`k2KLfsHNlrC@NhDD3V&1+t zChKe$^ZR~NT{-QLE#>9lP-LhmGZ&s61ZEzJOZ=*%1NPBet>yyG-FvdF>f-wu73vs-6@#d3{#4-0AN&PkzwA-#hZA`Y?H2F%;NxT8SA5>Gb$*{c9z*7pv7>Q zT@1g!wuVW@@_aTi$lh^X(f1*=ZBT~M^>}Ynaw0gn+xVz%!G!?Db?rs<&1Jb24&mL7 zvsqtisQ!#(UV^hIzM4(!^z?N7>!F9YwTRD6?T|a6u0n=OFJCDV*)aY z4MINW>rb1eH4S|#y>*7qXJ?1crewyEThLbZxAgmWQ4iYAS?}XGGr`fBI(}|F73ok7 z62IY3ml}(#KwIhK)GpOPvRJ1A5-B^ivES3gYX{;ls~ji0NpQf!7_^{U)gb@K{OgqS~&q%lC(VBC8y4iLRVM6vl`dAi;n%Q)Kv6EN{3pCMy6miHXs%0?kJ!t+b4%Ga*|l z(Z;4~X4Kld)vk)hr02ysjCnqEc6RpadN^<)H5lHNWJiuEH5f!696^2ZRUZ2gur85G5tXvSA}1048! zqL;xIzWqkJByuHyWo^#&A#zsT0_c6_4sK$IL*BMH97mBBcckQRko?hM)?B;N^d4BO zyUoVLi0i;JC>+PA@x#K1AW5ra#;eP^dP&Eav~4K>G6yip#oo?c#ChYa@czZ5Cft#t zxx`;KUo|YiabFP>_Asoz z#I|fTLlSpYt`ja)XDRUax_u}?{1!nl23pcyOQtBbB2Luwda@rYxYmJUAig&jWGi)acIXdeRw#0`xrt%!rq4ppEI&g{%-!@-L(H(gm;^D1;E%AqNSQe zk7n}JZd>DjK#<$g`MSaOGEEta4Ie1FN*<2{y9m0mhIufpmGGCsnON%EkB`IrraUgBS@C!I&F0)X zp~Q|71`Zv#mDdchpr6jL<&I*sf0t#tMMmzV!~p?!&VW0qPn?vGCtl*_Ft!jsWw2QU zN6YO&0|nq|$rli504ko2v{c;sZ_A7lsG#lhA0c9;lSV4*1nG^u*t%MlcBc@wZpCSyXQc%Wjv#V9285D2a+Pd=|}@0 zftaZ%s__47#s)e^x&?M86!tAS&Q-A@;^WOWcbySo4qx&`LlPE-gSj-8^hyAyv&|iU zD4k966aA%Yy8v?9y1INvf1G&lbr`kSBwo&v!}RoiA`K>nnqN1Fzx6U7q+LQ5vjZt} zA%H$3qsZ}VX8$PeJIksHRG$%tUFAE?I>!^yLZvk)x__oT=NAUra)BAi4 zK!gtW{;2Jz?Sw5aFhsj)>c6(M*K0i0^#<0yzQl(uk8j(dCnpu6i5`G9NuqTC2sh$P zKLEruSm{?50W_ZN^{5g5h+=p}S~^E)@#a4x!AFA0jhVQqTU-0K*V8SEwBW4;PSobP zY+_<3EJQ_y^ey(Ym+;C(MB3Qv8E(vk^F~)3r&zWRcXg3^P=0rWMjT(Vh~ZDsAh!`{ zx*k|33$k9b>ds$M4_^SK4NKgfAX5AJ-K%JTn$VWLnx>zg?Yk!dL+R%>~P^K zt*klzkCLMl*htF=iGJFG!nfPp>O3zA^d?a2GERX01XOtl@ZLEPP}6B1r@emRN60sRh(QlM$+Xdx?Fs?Ed1rS?;}^}^tV(L1>-v?9 z3QN-Kyv;C-VUUjz-Y^$J2m1adx4yx(0w5I~+nn%=LyD7B=`qG=JD2 zGE}qTP+AR33(5g*_Ly+sN6q6XOU)SgXHuSLprFFEVj#@tS^xhng`!4JCf^bRmsUrgt}s9u5UCUpDnY z8$A`kvZBC2vuBF;z!$(j#V;);gofMEtq!}{$q=>4cy)+Ib9}egIAR$3IK+XGrl!vS zgTP3IBPcH=s+{HJyLP9}_x61W2W{Oy7<|$U?0v+*0L^wNIKq|P&CtSodH1x`GfWqX zFXuFA1brUGSkn#SlC~VoUThNTw7HU=)RA6E!bXj0eNFDIP|x5OXkD1V$3{Vy+!sEr z0A8A^5znR_bU+DAN9@KD;UOGA)zPLHIh!zI52(UFpUxPJ;*^a4V4gUt{ahh>(&)ie zh-e6S`J8P*umH3agl*>_kmZ1Yh-iKRk)U2$cAW1rK-BRyV2t385unwSHMfPi5x|YB z);UlkMob22v`{E(-@N(ms924zyM%T@)%3ZuC-d3TA5zuNkuh@+cG(AWe zPZHn%?@`&^`{u*u#T`lYR6sdQTQDaGNH0z` z4Ni6APTdKMr5{Z}BBDdiJGk~QJ*PdJZe4gLC*KBWip& z@DmRWma;Ovb3}#x#(Ew+I!5|hx9&^OGyjD7w9+pLEMrYOxEy*mfxup41?c413ef%z zGDF;n58N<{*0Os}n!vfQ7`*(g&VBPEK9~vsf$f{G(P}WJw1f@~SJKK*mJ?x=YyX#| z(~96=Cywu?*$SBxkjS=~f))%^ym2wyW_rm^kj?YVl?2BZ8w^(*!M6>_&OTSxn3=|E zeIIQ8W}J+DQv)wLd}b;LNYdmfZ4d!B2#R8*FUT~50Z_hZ)MYjgyVC}uc_ZE36!#Ry5QNl8`rws`7cwkbS*Sc~+e zfHcVijmRD6J)@Qv`GOZKwGAfmfdDSEplw2Gt4Ub9X=eCWCn(w{IR8}q_~v+br%m0kL9H2veLaz zkB-#SokBz(BHV5m2`t93YN&Dus5sXbtN@UI%Y3U+2bao^YfFGWS=;ZD5AE*m?r`*Z z{=~lNdS@Xpg0KHi2x2Vkos*?Cr1|UR3%YM!T=M&teQi1Rb5TL%u$H+%b9|~van~a7 z{(*?k?G_E=ttVXNApE9}$+ak)aA%G@ULqeSR2_{!8UX=CxHC^YH57(oznxFG2Au&P zW%z?S#ux_RZY$;@(Mbv%m2F8ApB!HP*Szn5(974P|JuG*ajcq!TA86b63WSxy}iTk zFN=$RFB2&tT+=L5k`g-5fps@v>+R>~7b#5*Tp*=6cwiKVk!g2b;F>kE=yx`CAQ^C6 zz3+YfW@vz#ZyE6CJo`n+F~Q~VM3WC{qQ;uB0MSK2MStY;6Y=Hn;9%n983HW_#qVwk z|GDk?1WR{!TpAjhjE^6G>WhM~P!R5FVP*9kIMyc0f0go^(tA>H^YOj9d|N^bl1prD z6}rKHl#Le%3+;cjd#=tKW};Hmbe;TIHf@-v?Ku_9Z=Jo6LlvQLXUvq1y?txf6Hn6Z z^v&S?Wlc2P#q)N7>4-Hi6oj9aOv_XUYkR9%VC9Xy7eiybs%{ExW%D+R@ZQ?Zw0E>B z4K$w`=ms8ftIMQ3cBtSNX$4HBitaxLUI41_!7hSXKMyj~w7U|EKfq@R*?+N^tv_hb zp7rjlyas}ZUe5RMVC39ts(!|sbJgMCwCBIckAV=*DD)fw7LYbP%x;n<|j>US<7$la^5*cMIAWB(_ zxemszCuloJo>x7TmFfs}T0XBYFAoAfR;Y}`Y;0^3Q9n`v=nCFs;vo~9g!L3$j6WM@ zVUy=84X+)~ud?}zi-6he(`z*sIs!%w6E%GL`spNAtrzxM9xHhPwU(c`vaV9iwWj*Q z%7+h>7QTHZOPdeRw+Z`U)3vzxYqeymK5ni zy;LdvdM!MBkY-1XM(7O`IB0vQ*LmT4QZXejsp%q<**9XO3d0z)CHE?IeVX8E)t#iC z&gS=+$*)Zd233anXb&VE=fi4@V#0AzVPC5XARfXRrLfJELyEtcv3A$~XnW%x!4Xj= zz7Aw|RzfkNE$9z?a(!%_`ZvXFSETJOx-;HGKV$I$MvZF`OlRJy1Ote$KD+09NBy4< zmOeCLV&l3J{2T-Xva$36nan`gq;MP>ETrE~1O%nGbnsG)IRNj(+i(|H8|sjxh7f-S z^|wN?qUoDAdS~}Ew+dk7i6X=rKq>iMcF2+c#S0nLJ|v@l;5XuWxX@I;z7|t=3F@-t z<2Pkz-Sel{bOc&&Pu6&#y*P*zM(Z^v0_DU4 z-{M?Lpvj4s#wbVTYZo6vIj#?d4TIZfl!-PEc1to6LykU|2S(G6XmG7PEbQztT`9c- zLkk---lasoaXAo8&UN6CUps&B$?Lxd3n)XtC+&aXLBiw-yg7)yfBOSiAYF~3`WKrk zLEo4>2akqTh6=um3^@dG?T7!g-uKYLdaTI4EpnP`;`9=||@qY!E6^;c1Bq3hwCDM!{U zm`z*(_VMq_=2Ih53JNpp!#n<;B=cde6QP)6`By(R=EKYl&v;U@Op#zPYDnrl>YeJq z@sAd=<)uJKFKKp}QyujC?x5lDElkQ>SVIE?zkot-NkV^qq9V42#?uIrmwusa!>vx9 zOgP6r(brK;Svg_SGhL#=2Jp@K^#yR6n#KjfLHjs$V^cUkuN5{nru8J<(BUo&d#!hN zeomD+crg$(a(2e!wAhUPd6?nNXOK4l-sW!YD|omZJ)gLUPJNM>IN+<|cA;X~^yi-t z$9rC2N`+bl|2bv0g2ndkYfHE3F7FaRr~F6tT94z;2i7C_q^C$TnFMsd=s(W3whu^s zy}rS{)n}0*F*IzsihaU$Tp8xMDtOb}nAN92{6B3cz z+6I95c@PIRHWu^E05nw7s}k0Mf#am@lA`g3;IG@Iip2cFk0$WrFfdy=&dHUW74c#>DjHnoidndUt6ICpz$8- z{`fq325>@D!Vi_Dq2i4nTRlDlaZ3uQ#7`y1yo952U1CF7Ixvy~XBL$o(yG^S%w6_Z zyl+_{xZdCK_vwO0Qn)3|wR6mMf4=)Nh8egBJ^9S-(!4Ky6Lhm;$P7$abo+-E*utwL zj!o|KD3(kw#n12mB=zyTffyV6y6?8%P1SGe+yVCMihrv5O>=5tMv^ym=R?dE0TF9A z?kKwndE^jVN^a?}kGtsm$T^4h7^if44?gqC6_}Iy1KG3(ALPZGB?He~v%+%AJp6*t z_GQ7GS-Yy>g6)z|j#H|r#6jX5Y~apMi>eE+L~XIPcJ0*}aUK4cmz|3XLM?9o+04}Y zdYRFgtMtm)W6LOEYX`xlI#WfwPm)K10aalLK0Dj2b>A>iO*gDN7#XnL&qtQG^&QE59xELLNqd(o*e`ElK#Xy{8!swNfV30NoM(vcBt)w$0zE<`BNcMSTGt83A zYg__P5Vv%?;-hnMR}#?nPnk^1F)@j)@Fe z0%%m?MQHg}O@Bk6?Ruj*erJR5V^D4}lKMMFXShyY2Eqz$ zSVlpNt`wQBEO^j0lpIEHxp#33@40(H+On}rv>Z@A)4$D8fJ}E}h*RjB#`P26Djd&L zWfGnum{#e!0+tOpZ6PQK?Q$Yv{1v;DXp^TVttn%}0o5*!u&>xm65nfA_sIwzV!*?B z1_ODR6krwtlLOw#$@0pkSP!o091+^@Pt@uK-`(PHjWw@sTq0*e8B8!K2sM^rDo~#3 ztB-HW7Xb&$lje!XeBS`SU$34S~oyW{A zVN>F^_^GV!a7r6xJECAVI=%*~CuD+??=)Y4F1V#ltUR{Bx1{F(y8zs~=qa!-!8?Q62_cN@Qr6U ze!pym4H6$opI>|w>od>!y}iUEJ0vZ|1?0Bxg&U44we3GozYNYHg6gLXvswOtLn#nO zfoL&6P@n-r8QuBQ;YFXv=?dl){S6q4hu9!K|48yH`{Tzxq#z0e2_7yS7yaK$dH*)s znqZ+WKu)V%9Z-3m)MD20iGUV*b8~|gB^@d61FLIjSS0lMhcxQ5pzE9SNl_as1ROOd zj5_+K+q4L<;~M4QgMERo%Hh%{xAueTc7e6ff7B%<+1UG-w@=?UKv@Z!1f$PCmy&R$ z8ODHSTODc&;4i=%4;LBvlZy~5PDvPYcV{Hra4AN`z{M@BHfzeMcSPP2AJ*ImsJY&l z7iAUAc2ibsX1fVHvrg&%LoICQ`wG@_t0KX78=WW43HchGXm8Pt5Dlv~F1A@LYz?Gx z2C>e}`O{WwidGC(9D(b^Mfle}e&94cI^qC^jb?Ft)r6>`0z;l(iLQs7=QKnB7%;iJ z59Isp9H7Msk8i=9u>e1{#(6Q#u?r)j-REd2Xs6VDh37A!Kn>NqPt7|LTLGX+=EGX) z#C%9ceA)k>Z5Y|qr*O6YCtocfv-&gQYRL#FSv)GMgM5oTS+faXeigbP3s`EsH7Kr) zlKZXpBm8a+2W^rZr3w(DEfp}xj39FWlPea^L^s?Cx7n&GO@D)3zrc zT~7?U^0yr;ovAX=;O|q#lHiz>yaXaKpkhILF&`#;nL zMHBAyGD4N8)(loygy%KCoW5<6bm`$f93%v}ZzA7#d@{P~i+$zcC(P+9QlPvgLOjTY z_zqn6gTsj5DekvgYz24ADo#G&-~Jh!Yw%V(srF(nLk?A?IS-OGRPXvWUcKh@?SfkX z3yBhFbk!cu)P#P?(LJf*wv6mzR6DM8sN!C6*&l7hz6k-007>P@zI^A=6Zy?hyA=yc#-W2U4?gl* z*Hu|Lv6!fTzYOQ_k&61&+C1FT$rT@`7q2nL$st^Gx&1m@UlPHb_3iMc{>)&RN(u*xq%j#zIejU#`^E@5~C6nHFB z%$=*qzN2gZHQi`a-SkzOeF41@p%4!%H#~Ui-frTIaG< z%~5?qRVK0hVv{GUIg#g4%`SVLzIo^6{T<2_;phJioJTzZnuw3>sDs4S5ns%Oxkg|H z;`ub)IWLZQDpQnxua1wk={D*C_uy@n0OMpEPs_NsIdF1 zv*71~w_jIf$XL*r?$n6$ZnZSdRoDaVHjB(=Kc7D4_2i5ugh(BrqTv&#=q8`6$|~;O z)uO`ECM(>XRGOqcI#wA(*~oLC$%;{YiI4NbLNh+-2{GY$LjQKj2MqoQM8kcT40x8C{!xQOB@DMNP3%T&Hg+tMU;zdUX zJYZ}HmC1!F{{Jk7scj=p_)!}OnBbR9D>4YP^qV_4ply2)kJ@M_cRwW?obOKd$LlHm zU!fZ%$e;?2A+e|JQf>T*;TG@*Zm=ctk@(e^n(3xyZcR6t=v{YjjjQskj5E9bL*T^% zYjy11(B)l)Zet{$1`eIEv|<76?B7neS=X(Diw=oPTPX=H`GO!%m*Cz57}Tr~7Wyqy zlMBya5%!S5SyNt2R8rd8vMFwP{IR10BGT@jvktOhkHT@Meu662*<4Glf)e~g%fzA; zQ7GN1rVM_JOojY|nD{fta^0H-L#Fb#=S>+)D!+#8uCA_e9YUq#tw|n>h6Pce{3p;q z=$9-LoeDz7)%#p$DUA~9h4T1Gx@uybI!=Y#0p%eq(e>2dc@UVG)yQ5c{wDnW-nM?d zd%%DC{Tam=L*ND>Mi;m2TFpuDEGk*04ej&fdH9CeI2-8)m{@b@$gSW=#7QOUeY4ic z?u`4V&Q(`_QVhaaSx}r5T&4q_Men!Il!=PaGC^CG0k);H0o&2x7umTB<6D=z~$g8DJdP@-oH3RbegNpiJrzn2fA3KXV37>wVa+wJIZf)GL0JucN7$1&mOuCpQb>@6f(+{rr3=!%n-{ zF~_z1-{z(_-l(XP8=QM&ZM#Pr?e?|>TVIWKB&kyR_|Tjqj*oUPQW<}|G|B)9q8T&= zO?{k9uAKR+`-cjjuZn_>GWaWNKkLhnVcgx*h3e9psmSAF7I^dC! zETIc}aFfp>54*}MS)3wv<(LrX{i}15HVbDe6+!Xnzw??vkyWtHk)TBu=ADHFUUljs z9Ly)!GX0`5D9@75-CYz5GuOz>UYpM5QLjwzo}|~&R9j)JZB8#AkzwQoc_ov98}fkE z^Nm6)h#^9m5KB@Rt*F{WOUs+{b7mha5p;BP#_-^a7sWF`0nd}^JmnD*7W_;>ll!+~Y$nZU-?R(^epOTir>5e)oWcYT>EU*& zGlb?MZ4c7E93Yz&2P2<|1+T!{f^ zi!%Q}nKZl)+^$gmQ`5mJ_uaLnui3gBgY7vK8vcue71;q{l^-eN_EJu6q{tE#eH`3jc23zUklxp@Y~Bk^2*O8J@<&W^YU} zSy6vRRs$3=(&WyeQJv9U$g;M+!0}djR-{J#LP0gjrd4`rfDBml-@|eFI*!MO$_6=X zwXh9y=rLY-lit%|qyIz^GC7=q&gRyYRAI1kBX_;WfTzY&G?J``Pmi-_DsXJ$gPZ$Y z_S*}zp5M&4iOh#PSDgnu9ZD>DmbjWIz9(I@*y{Phz*S|&;x-vDJX~1cEsV`^qJ*N4Jw$~e`9G3KpML6I25wRFdOgTvT~l$M7G<+k1}bn zDenTq*EIdne-_+OL2#SfB4@>9y2P=DemLk^QD4bv)rwFDPdpgHl4tyU8v>S@#jVBb z0uBP&%;5(D0^C!W>Y`oN^%PhA>#Uy-6>HYLcp6T!MtdDOZT4I->HzU|3v)mhTE z%kUgs(nLks5|fhJTzLKo^R$-y$tS;w)HNIbF{RGqP5bJ|zHax^eGh)ot1HGmT{Yzj zunEC9@Pr~P_;C@#ofnF07xF*c9>J~)wVWTpiG};9R&Ty6ZWy_0Y_)OsK^c{#A1g}9 zV;U;PIN47ty_n2ljdxP)NEUQNc;i=u!Rk&S8fZ5dqE5tE>ER|nd6%k6R1CtS@k}a- zLGIm(YvaIp2$aecdDAm{M)&!IVD%l6bX71w=Ubx|F?qZ?~;G%;0jImy3R_Qw5XbmrjWIEcaYfBf~)c zyu$OUPSHo1b8|61hU~$e#z1oH-fRF6qY%A-^zRF0A8S$r0GgkjirU zmSaY6n@yz%AtM=s@11KxM@P3=&TRRlcKgs(%U{hHamD;Zg(!>L_8-4P(*Jzzh&}m= zwW^ZMWR6?ps)te5p7C9UtN)PS45A%u#b+wK=%T`c&Dye$|t2gj)&?gZbn$ zbM3PyJyj{OIx_GcZeJKQO>6n+7%^Uz7G#>RGAg5Kpu>8~%nEM&Y>xP#lnE$Lj?`iTLdVZVx`})d0TEP|F9~Kc`{ph%T*Jj% ze7Y#S%O=q#%vRgJi%mE1n@>y7wq7>uEhUY-IBjUCh)5Wr8g2%(A2 z$!XRsFLR)_mV~qd-}Xt|r;lo2ni%sfUfUDrc1wPfv#ApB@)%kV2Hl327yZ74&K&$O zIWgqZt8b&U@bV%P&BP&%LY?eFa}zw(`pAkpLwa>-|vM5M{?V98x{~Vlu!) z>Az?>`igFseAi^dNUN@)V!8LR3ryjUl)kp-;5pyB(4mg-k42&zQrlBxvEQZ%TvQu@<& zQjBMX!azD~`V76qg_x%dK|CZxjxO)j3_xq_?8+ibXmNEVpT^pvxHHv+%?{N^_=_*ar(QRooz%^g8MV`3!~ zWX$5i_4(4BBAQ4#JtO911h?Ix+*cZ?@va=xmsi9 zriR1O92p8-h5+%H@K4(vlCw+=imVe*h%5zpovwbNYu=k`rZNspVua7!if$9!16|cz zGl~_Bdmp4t9vytiKYr2hf%23l^6K6m8^?Fz^OM@Caj3VX(|Q|Q4M~Ts5g`-;f8^d& zbO1AVSz*ld{dr_egCnI1P6{K8GLJ0CCMB5b{zboWvR;XgPU^hL1e{FcaTrbVKZWIc52=?;BM{iP}@jQVOH(TjmNQGE#B;#c3Q+Ezs1`s6Igc zAMv*#Ao?YvVZ?3K!PtG`F4UyQ889+3C4u^5;8c`JrmznUR;{{j5Ou8?Q$L7 z3UmHMvFeiiiEPrG&w&_qa^2FznDJhhiQq6Yd`X-o;S;aGF0u=3_Av6A>jkgkzVaV} zJA<|ZqWc$1I2Vtw@&=@7Y19ILLcj#xAtN9E_-tIy(1e79I5o5kP=V|o9K^jRcNh;; zLwkcmeJrcpUUhRZfO^M+3dcL}8r1<8onMI_pO}m+Xu?{G_T3GEx1V7HMYuS1VNh?h zFSriZK=Bp6Jx|1!45jGK?5~c8cfRo~q5I9j)Zz^6q&3Adk0L0i2?g?_U|{ z@l)p=u9{skNK@npym;TRq81OGL2~bz;P2f?NU+X5{TzE8cbAhHrnF6?W7Yd`p}=Su zRY~jMmKh5IPV`PWy((O`s0sR)cG{_)E8i2WJAK7KV7fgm zD76@;?xn}WFdy#xfa)R{mkFpF`!C5JSG`yp)nY!|yoQRo1ShpkMwgY&H9C>LFZ`#J zi%z@xhm$p|W89>tQP`5|l8*Y05Qnjx-Y1n;%4d7OnhQA)No`Q=d6rblwjrYRs*&3e z*js7QgEJhpFr_~dV6;@Hq~x-|Qj9UFgBjhpv>Xk(IEQZVqJ*W2Js0tx*?e1)dLEwX z_elE0!ondFhUJqB5hKD&Ir)H@ zVPj`U0`;T~C&d55nw+SV-( zHLwR+oo*F|Jf5)m+KGW5^}0b8)%!uRD#nwp)mqMN#H-TsaxEP`*2)=M(ChlpKpB9z zLIpJ^Cr9I_gNb_LkC%>*I1>$>JxTNUUI*ZgldebGwY8Mu(7E^=kFQ z+ZjaHmf7wfT8$q>nYA`{y=%kUTE)V9?$=*U_>!OFA?6RW)O~TqXH_B26>OgZT@WM{ z78kN6?eS-qx#isv8Jvol1}L=;GllM&vY)2h3fJQ^_e6Lv?&xnXV4TK1(LvRbl!WY{ zLLn}pA#iT%f-XYEv$D^PIFt#P6k1-TYi)zB#l5E3-)9j93Zy=#|2e?m<7X#0iv z+>DlcnjM>r4vV+z%K6ExWcFqp(;K3+ip<(1ECSBKjL;cV`@UIS#Zqc}LoM1KWwxb5 zP<0oR5k894shCrw`}_G{fX{!}5#TGG_#$~kH&;9URUHj1iJEVnU$&M}zK^?fzI@c4 z{(Mbr<>LC?-fV5klx}4ce$*I~*a^?U_!&L*SBh9^nz<` z+os(pCT%1*!+$zH@9|ek@wM27c=iQxF5*&B1ufb$$qpc?S4tOxf_YDIFq-=pz2Gxj zik($qEDiKjd^T_pY8<(q=_w{BtWqM}>YiPHf+UQgm}otnKaV5moi_tLl{l%Fxpf>2 z9+5h&3IPFEd#QnXtAPgPC>y`p_L-KBfgYQLqEG>|VE1YJlpeRZ-e-M(xA|}&-3Oel zh}XHolOV}j3nGpTJzGz)wYyy5A~(*FgBhp^u2+>DUX{)M?rxiXeUi_Ref?v3a+n2f zH8U77VNX)ucKtUz zsjg`=Z~&Sf&9RayJzsfa6deK=DHSWZ^R|-sfkf&iX$NJhYB{EmK;Hps`Sh)d=;hLT z%#giKIR6_>%E^mTqe+I0F^Z>}S%BO^(EIho`)voIvmjPqEm&OIZ?wA#-x9#Jabecz zvP(-#J35Zc40~AHN&k+X33h@p_+AQ{xi!wWBS0(1D{A2+iVbCI5X_G`x)?aSON$GJ|VfVhV4{1lgPy z8=>uuRIF9z494kfY6nl-NrLBepiDpgr4dw;XFDr>dskKm$)_d$K}j0)jfZw~W)oN# zddd2-+yt9G6q}MB+k;k11UD_}8Z%I+JA8il)3y3>JM~3VXKfEhswGEVWn}lfLl0j$ zmVH8VB1g~P&J!Cc?jnHYgU=ZS(RE*@FXF;dsxi8wbgHNK&Rf8eHwVYy^2N1{Inm=Li``uoviNAW$8VeiGjpp)N2sT8`Z*PzaMjdc|$ zhV`raI6P$blfDEIz)`jDuJ5V_<@#7v`vVU_h$T(3LgGyPE5M?S2*vku#G6RD+Lm_I z9na-Y&Z28GhNorX4RXYX8B2OsOzeRDplQmY$oxs)eFpz^`V$gMJ69Tt99V+Yy6d#e z@_R2EKDyNMlvw@Y;-C5CtSauF@gcqz6nE;r?Y1Heq@U!E1YTq>mBfov`^(b*)J%QA z8}lfu%{S|>65kuxdO9zZ`P7r14$^3a`Sf}uSaE0X>YDJGFOk+2h0@v#r@LD5g{dg;NF|5zpwhu_fnsU0-UZEEE)0HrwwXf z3Rx-jVxPZOCQ64}DB~!lKa)ZSsBf-4Yi1`?Xu>TUw&p$A;vaSRkGOKh`)f?=|HEbU zius!EmsR;`DS^noJ^!_w7WO2?xFeI`NL$Ce(oDYm8OMg~t-1_%J|F1lA0bMwX#R^x(;c1gv z6sOSW)7q@6A)@rcTJn6NacBZToYW@c8E{c_n{MFOx=StWpP(>Cc0-s1xooAGr~17+ zK}@f*=TzPOp^6?W^Vky$ z2J>j05iN_;+#K>0AWE-L(v`wc^IyH`_=dB=MM>VXKWpEq`P=^Gc4)9(y?yOz8sMym zDJZ%D$onep*@)i;Yd{t~fRjYN-SKB@nr8VvcLFCybLGib8@yI&0X|J`fW5w+iWn5q z;o7L`jsCsu!1g$N<`EH{udPsk8hfjhKHhFcl@y~jTPVDLXrBx~n;l*~e@2lbaj*&c z)uM@$IsHn>E=kQ?!PVICX-gFxpxw+L_Q`|a&DpQUo@BeRh8b^A` z?dQ7xV(}rAO96LKr z6_G5;eq5W_`2aj;*eY%jcB_oECmWKC{}RKgGZG%xJwhxj5__7Q^$7q@q3!>hvWcc=WRhL)gXlA=nKRn=Au- zh_an80;m%%Yol>R*%w_=V|F2VFk-AbHrKqID{r~=!~d_7bCA-safN+C(4=w3Yu+`6 zr2)!>Y2x9CBhIzayJfZe{_y@V$8?iBH_kkbE42?V->r%n%3;4u$bUQoRinlUn+qCg zHfFwc%$!#09RVpvf7+L;zXca}^ZcLXE!{h6T-X=Ik2EAanhbf15nyt9kZB%sMWt7B|vwo~VKqUJ# z&IKjZT8pUeA9?>co0xPB>xVxX4nkuo+2gx@8 z*+{N>>=}~E@9^u-*^ZeZaJGZG;Kdn62Y~2)*BDz$RKj@%eTzo?@ORg;E}mlxmj51Gq7OY%5A9lgpwahtX%7B zS@;^;u&6{^beQ$A*e`!ED>Qx){1LIWY&j zL0JX?g&4v(VBzCIIwgF$n4Hypeh-oycS>$DYiep1`yzYV;XcPp6JX}qlD^zg5utSO zG&~cfhuiipCdLls=H*3dHh36^UNzP0k}NJD&Fr$$vmc&aUNRF_O6X$DoCf=FeTBka z&CFU9Pq*Fid+XshL!kUPtDi#^X0j?iHG6r$^=w1Hhu7wMt&;?O?Q%x?DOGjZMU9y# zyt|^Y5scr|=jC}_-Jk;CM3J+oW8*}F`Riq7kUc=s;GT9HolKe+B>m+2m&pjm ze<2T4frU|ZvHpLBagMu46bRH_2AEn^t1@fl+}_BR^RmE~U2k4u%nEI`>BYtUC!MBsQ@X>WP}CRQUREC5Z6m|(zr=iC@QKt+y;pks5>a>8f}lrj1~8I2nYmunlD09nB@ zuAW(T6foi;1uXKF1+(lB$8P?wR3K_?Z*MOSeF5i@CArB7sA%`|z1Gri4?MI&L05GR zC@sJRZ>)D!w(C-d&ud0B`8L%T8XI8j{(NYmhBcvcDr~o7ATet@1nTcujX?oMgU&D3 znGtDr%zcvI>z+Adi?E20-6Ln^<|m;Dsj(fZiaTr#i6t54;o*8HyGnVz(kL&LuQZZ7 zFV+`0xqlG{XcmAs)~|BH9hZ6`Yuo=5lw#W<({YWMG+z1bMqow@ssG#5`~`bXujrmt zL63CtO{BW|dL+Ak(adsIyM6$k&|ky}XbW$is?o2yHm*1eNsM*yQ~wPat`3olHIV>v zLU?dWn3mT+-re6fF*b(Bp%n2S-eC2L1dQk{WKE{Et)xvjySz0idIhBq<Wj)&8 zN}3JZY6S)V|2X+ngYuvMgDsRe^JrXMysGT_K^?HORWRLe$J>nkV=$oFG0Tad292HP z&3gn%#=Wk&x`EqZ$Liq`If?6$_T5J9B!X zjYzqS=buN7kk$WF6;&(+Nfgt8Dg)5)+}AV z=I)xxo;=J^dO@IFKDD~JS@@eztqP;QuFmoLeDBL2e)ewDXYG5gtA~db+W}Dv_6H3o z3F0wwH?uPCcj>LtuHtWo&Q_gKiSP}_hd7!Zio=-Qj>&dwFx~3tEoU%j>NxcR4@oC1 zJYIXbu2lGFAGz=bg1wN8LP8KXfza-UHAgZc@BPB;q*pd*D>z6@Wjc$w}Osu-0nCmpWHf9jj+bRjEU4raFK8+ z^J7xgA?0|H(ntxl3z}h0`=J{Z#{>H+BZ`WO#_sOguK^AVQz;bW*-a`4YnnZrskR^{ zC*PgHr+O41V?Fw+yaYoXG{LhCbDt8k@QMBL>H@#&M}R7X4E)T4xmd;eed4^z~>A}_WKZ?M+D)XN3IuQHHS%}M8fy8F;ri&{WCEE!(WT7xVeD@_6+2`&UpF+Bz zPJ0n^Cm0j@)tfWH*>YKSA)0JP7x8CUjq$orrUzXkC$M0=wX`hUwxA)#bd~xo1=v6D zTV+ExPZF0RHlbLEnJ|^In0X?gU=(Xvb|pC@~vm zM+%WvQVDOPO4&n}G1pZg1Lz>!fP7R{A%PWDOqpakSMUuVl}uKJuz0(w0EgU_`fp>} z*g_qHXDiA6L-q)dzeK58IU5!JCKqM)ODY)7_(ew48gLur^S~AkG>m%>u9*`}O3K?9 z6Lb0Z$%gN5X>2c`#AH8qfy9UChsC5+WXx8Om8Bv=UNmUvkbR~6FK;W4Csq7JCjvy) zC)!MNf*#Tx7|XTF+uo7)r8At8ztnfPl~OX4btwaMtqI?{W+6uHEA~R3iJAs3BTS?3 zJY{k&D+NblbzNce^4lG1o7|+klzRCb&RYW~E7LCszx(5ncN(89X@VBw#%;S}_mTH= zQI)6Yy9QUjq!h%(I?NY9s3lu9@qP8E?l)QS)n{hV1?Dc<_5Y)}vhUBk!b%N3{H&12 zQ+xck9mlg#-yi?BkKOk-2yH)-=&F0m zH5>Wa(+?ex?&K#?RpzF^a?V%6!3NE@deh`y`CGl)Km(lVC0JKG4*bR7k<{YVh!7(V=Wi3I7+pY<0gl`PD4i#co)eKm-->oKd!=B+h|j=RtaTtl&lqn|l$cgSkjZg9vAtfJ{ zSHnaY&P2F0oy{B;7&R$TFlNlb6`H(7qQSBbzyheHS<6bofEL$Es>(XIO)aQNeF10@ zu5{zux(Tp?X$ngqv<@!GN7ZkC&^+FeNB6ut`8^aT#>vjE!K}+tPlM|TUs<3HKsa_U zr*-rOF1$22IKaFIq_0!7@41`Nz(pW^uefkmPGFH_7>9}gRszT>dF!`8-@&jkoY}Ly zOby&qkw#qFc~J~g=8$@7Dg8^pQB-UMmw#-lY&d*-(VcQly$x}Z;3nOyb5T4f0M-JX z@nQ}I!cWtK_INHZOcNyZXcCGvp3vtQq-z>ZK*`nalK-fVzVKZcb#g%Yl#zd=0mRj!Iq zv>a#Y>m`=A$A!GqG1dzu9KvCCzUE9#YMIy~`ef7mf+wMn%=hv%+a3FX;I2&rClH(? z_=1YtY0(xLPign+)=q-j)?3TPPJf{U=XFZ*{LirIl~7<|5S2?P&gXcZMYH#^+7ep-{MrzRg3c#P2w4 zn6|puP`j0OCI{vTOP<58FO~(c8?PIgh|!7D$h&?d_2967Cx07=^HPu^v>-Y|)8|Ff zK>8Y3C%S`|7Rx7pvPOCQT38}~*3BlZBoVtr{5l=n$`1_zh8fkoC*KTSDK&0_8NKnc z*_!A=sAT~UUyvu1=_Zpk=z{fOSaL~Sad!%l3d9O;K%gB!rm-C6~qt! zYLxSkBlnwE=hLW@ZnX*5qT_OO5fOMJnnl!q_ zGuV<%_uP;+SwNLa>AGM=Y+Y-its^?nmalHV*8-T_Wr&H0XV<_$Z!tSvCmUXOaI|ThdcY~X`Iy-_4g;v#=E=3ntsi* zBiBGAD!czz0kpSn2M(>N(RLUZxYN}YOxp=5nLr2Q#OgPLO%vgS(y=Xmq_u;n1ElgL zIFCX}6{7zFSDldMubXR-Ul_zXD?2*>1F*E1g#H6yCF_6o5XLeO+zJQC27w}Z4cbY16Db zbV{ZiX=?SIXT{eF)OvZJ9=3lv!}xT4CM3bDkQ;6?mxwxBeJ3lvgG!Cd?>-eecKY`- zpNBb|g`j>t7xKOyoPZU2;UA-$=Oj*>Z^=x-fsfiOUV_5?p6bWS0{|Z41L=QB$Oa(r zX#@NFrO1Fwo zV4-78ibe_fr@m&K1Nrf}6jqz+p5&C2w4^0>`n6n*{$tMzGz#Kv+^l3^Ds4dDQS^G7 zURN5kmg;$JA%@2#{7$e#b_o?h5@Gtd8WH}e_{GClBhEuw*05FD1UEsN>pU099H4?z z`TNj(_~L(%`lltjd<6x2Mx@k)IS_@C1*|-7D(HaR<1}b$18yBK$Y*pkcK2Yy=Am)0 zx5rLaKt6JR!v)DEv+d`bLk$VlCnh^--#hO#CzGaq7c3jRHtsBZWJ6_q^2_ayrhczp zY%*H@n7k_cnQgz>b_bg(Q9q2t1=cAVSbg`LxDJQ4g(I);^KSgqJ97)-OIyKq%NUMFXCx$M1zv5^s6w<+GPD8}ropz!w~IP*hKi>Y)bW$#^S(m-Yat2A03L z8+wcAM;gq!iEn3M|0K5eNU#_Jqtj*E_uLBOhsCq(!T4|Y;kA%9P#{ClR~;k{c<(-eYt^|+T_A2iHJ7`Yt19reaxi}oyNYQ$UY*FG4snIo^IA?{wg-s18(Or8 zG|fjq#ifv*@~HFKNXF=|voU_1U?9ZP)eVQW)3g`HKhlGfQYAjbF*>`~g(?+Da%6Uv zq-z17$uUaExU$fO39C?sSu5EAa7B@H-7O1P7pq{KJV?TXCg@?Jrk2xmvXx8-zv_mR zmOkU7mWjVgt$MpSI^w8o-RYEbtw9=MT+!N!Q!=4jO^|2cx&j6}8MJtRe4}(3l4_W9#J44NUMKc3+8hIjN#$3_KR!E+weXtW$_+Kr6>&in5PDWVwtTE=VnPcX^ ztYz^q#|=wC_r*|zkt+?3*d;TRiuAi-PrEjWI~W~D$^Uk95Z6G=BeMIO)MtftboVm( z@SH(B^vOraRS529r%$lmuw&)&939>LUmeh!=Uco^?VS1oE|g$C$ zKEKM1g)d35>sJd`0!YMc(=$jT_4yhlBuq+>03A&(Y{D{#4mTw)QSsYEmB&RBS?0}6 zT%s=y!_4%w|J>e}DptKR&4{R|u-{bX&q#o{&?6blNh9oforW}m6XJSD{bgVnrizNE&X7YI-cgtpGLoJ8%|fVVEN zbMZy?Rr@2(||Lgm%$@;L3A#X0%B|;K3M&HeFVryH&_Nj5vlY;1+3^kf z-u--+#H3QYAjvrp=y%Ak>t=2HyTTNfX(T%-AxzaH2NzoU?)HmKA9tq8fv&*38qHpw z+F3ZAxC`+M3a&>k$4)u{%X{n{Ga^b#N)rniT|&A(UIO#CZxKK(CnG?POzlnK(0%qz zlh2sJ^S06nKpz^+Kcl10WuuIVXn7kCtxsKtZXd*&8N?`3hKw`NW(gc9nM5x$#r)5GPjph{awf?|mxm5ZRG5|lQ~_8a)ovgx z=_#Fo)#wI`v>R2(IjhP675JY&4J?y#mM_3AT>YT$URPIF%zO7V(6oIVPGgE)N)thm0Ju z5{4VQxe=R8PJlTLPT5*hl!QgTf(XJPxL7iB~ww!eg z7)Xd+slW-QR@w{nWNu{*Tqmw6m>8*9T$xp04Ckeju9G1^JO0`2;1QHc?V`8~J6 zYyHrmA}Uve!ApweECjrYM;_n#X+c{N;r0F9`KeC(1p_`>)3h%b(*G7+2>bv* zbe}0?+ZFx0AYGMBx)uo|$XL0$Q7TBH=>;w9%LJztM`AGj45Xh$Q`KLY2++OJCo5 zjbGzhRa5Bok&zH+f(Mo@7?aIgtO+)+wtB|3`;1l$2&h?)O+1_P8@PC$h0eJirJ}(d z`kq&^ghET>q&!ux^5=Xd6!f)Uwf}&`<%#FnSdbM1-`8KkC+#*QnW>0l+`9Hq`OgZu z*ZYN^mOK?Wv)m%|^VsPMPhokrUmf=!q1(cHrc(-~@0%|7#)%C|Zj9307o&;!#1-o3 zYZomO1X7V7ClBsrB>~BA%}GWYc+@jMyNQbLX4B;=?AFkyh+8rYO~>cxsVX2cR#dZj zt1pz*nKDxmqyXdv!q(qW3Sjx|i4sPtw!B2mBWnm878be<7Mgq!Iq{>m@81z#9WXd& z%-`T=_*`?^*yqImHFm@SG)AJdcSv0x$RS<;Eye`&pHOb-z#*H%J7~OJIhK`{G(2#1 z5tC98;VI~AMsL4}8HW0dV2}Bu6+Bh`$ahoK$cCwfx%`ZLn(l~jLo;i#J&8Q;jQ}}t z@>pIiR~Q0fzh>v}BdLuM85NS>&z ztxfzAC%%aY5u<`Ls?>hzC+!Ye$Ox34_CP5oVV(07*3FLT8Sc_M&sx~oVbJ#nEl9I6 zGmx+WkmIG8cF*d&`LFK~fX0$Xk@crPz&hHw6vnQ%q_h*eLD2<{12|N}Oe|ysz&K%s z7=K;xown`FvZAomy?m-)KGkW-(_zck3C8|f@<2)w%&7=Si9S{_9Jl zHg^uz-(E@_!;8#djoST_n}$p3zG2wC-F=I>c>A@ewk~kq7JFul#1YxJ_A!hvEm_i6 zBpUFw`Y%!JUeCJZ$RdzpiJSGKm@3VFL>dzz_dIecQ;GrWD#JIdY+h6TT=}6~5z-m@ ziG7Xw+)j#u$P?35=(%YU#MAfkXbn3(WHhz=8mtnokl055Irz`ZQ-jA!Ibm+inAJb>a#rQ%DK-K!y zb&nK88*K7{v5GTeM_eu&m z)U%mVMn*<)FGmY-SfBq}5`sbr@Ov6mo4c;U=t$V#(keXV%BM0hQ9U$Z;}SH=fFr5O zrlQzeIaJYC{)0BrRqhkKv2}zkyGT9zAJ_4R>@gy9#FH4e4OpZNY|h?$xtk*3`XS z*3x{f*kAGWU(_*?JPlFo6b#f4pfe|j0t+KM<1T~l0P`v#dC}5ub;SM_9s@y;n0du1 z_CGq8^W}m>v%1&cdT^X_RsM1zBX4=8n^MI|E*XhnJO-qz2} z&UWn0)jzpz3EmIE#PY(Wagi&-i26KRp`pwNhHA(4nVM#vuxUS>Jk8!BMwoAK{9kcn zl_0HSk|u~3H>hk1FmVgyT9Ja7kE*4moeH*a@OD?X#tJ^C2%$ucbz1X63RtxiH_v#Y zqSXBU_`LvPz*0?{k=XAr{EM@%U;p?9fyM{1G+S8XP|iRrV@yE#K&WJ%8Ea^{T(k(byH9 zXsKcPkUDhXtuZEXJ2!dQtM$2fVQ^HFMONHw1>_{=$Cf!_@#KKfr^dv&V^(0HGCdQp zJx{ZG5{a3Y@Upl<0{v_s-d)z028RF1YC4GLXZ9N#FSRhprbde3hFhW=5Y}XBhX;Ir zkBRWt#4B}zrzg?83n@xwi0!Q`wzRaAJ=c}}0u%72>AyPJsH`Un9kuMZ^TmAp_^sI- z7AEnsbCkcacHdR7+Q)7aGry+@l4p-w&+$46y2B&j%&IUb$Vw{8ZZyw@^rXa0iJ}O- zD>f)T5JP0u`o%`pt1)cA1h+>POo3#-jrxj8c3%$7K!H)Sq+v5R76b-4ZEj;>8iFbH z)$3a5|K%Z>O8EAiU13FQ)fr0Vq22Z}&q(cbunpM=J3(_lZ|^o?fm-DJ=kv$WV$fe& z)+y@9`3epLY2mkf#@7<@Aur_U2+hRjt6q(RRGB`0+2ySlHVj{G1OhcB= zp+uIvavU-JNtddjshXfv5IfYO`Ybj8)}Sf}#+Y9=eto`HUc$lSb9rdNrtjdHvg6ff^Gic^A>j+yl2E#r1yif1Ma+W=iuHrKWB@1NAze9g zcXXt_CCv)~p^gB9&5N;7Pb}t$=vjSWQAvpL5g#h?K5C4H*m>iPg< z*luc;$bVoKYjdJIwsWK(`IHlb95d6ljos+2J)tWSSJ-$(he47>QTV*%&uM^comDEw zgpwIZK_bIYP;XHx884W?1)an(QOBZD)zlOL#3;|sV*cqPl_^kPd>j$P8LwwPnOvK@ z-x8n(UtPPXRnM-Q1)c|ig!9g2(*Dasf$O#IV+_DjjA{xyaS?Z|t>td+$gL;X+S;}O zQ?aR*{ThN<>p!F(Oh4v+_UxE(-H=phfm*FdWcU0Sr$UGVsW}6}F*U#Z($eT_@TP@^Q!QJ{HswBeezbCG5eCJ`{Oa?c%>093Mp`e`&UN)9#I$2Qz}aMMJOs6>gp}j`~a(+d3MQ z910Y6L%o&EnSb5pRk=Fu!XJZb5p3@Uo?2pH0hjHJHlgy}5n5eReeAqaUD;u7!Zw6^ zjUcyc^@X1u>veNA~F)t;GO2x=}i1!vJ~(;8nj?al=H)nKypUK3s{E-ep(mh zkB1~6NWx9e%slEeH9d$MAthBM3c~}Qb*$mMFRzKtJx57t*?mR^;$WG{B|^>W)$Lj{Zn_gZ&%_%v_(n@NgdiC~=*^1~ zBBEy3|4qH8Q!_6mc6|gp_4omP(TN2)794C2(;F4hZ5!vsEhJac+m{#pBq@?@G37-Z zV6ha31kfmh9%nL7>NQz+`h9gJev@W4KPk6SWt)9v#~yJ|AJf9ws2mVRXT0!w@NLY0 zdynEKsx{2Lsyg;fORhPSyID0Fawm|TV?eIT@UPH)ZJHi@2ZYjIXCtsc;-NVT5(=sW+WCb}Eki_#0sMtbgY^CX|kg7dU z+4Kn5q^!pC$-}$bsvPPV75la!#SMpmxyk0(rIAbhl&1nb=vDx-D63)yHf@mT@K(O8 z_Y`)s3(4jnkg<~_qj`8tD4=2lwXg>=Iq1rVA7DH0rQ>!H`|qO-&Qrk#<(${eC5V$N z#%v0i0q>_r-+})R*tS3HzRVi6#+`jVynz9baiHReu4T00_4^LGc8B>;BQ7Q#eblCR z6Hupf zP$v&gEf|_b(U1@qhdo;G5(hykrH9$_mX+Z<7rMFSQ+!(J&8aFo5(J2IybOQ%KaX4HG)yvzzGZd~f$Aq#&> zgXO85&it~)hx3P3YBjTih2hG(I^Nc}zxgj%EbI=`vvxzhOV0=$`>F3LUTt&b;EjuL z@vsq#<51o2?%qsM^!Z(UyEn$JiTZwf?`?Q^Haf~*Tz7kWn?G6jJJFEaX0N-R;}IMn z1m-@P75(}AilTRb#J!F+`@_f_u9s7E&eTo`TM}lcthJ=?-HqU1f6r4*YzgX9bRclv zwUFNV*|EmIa&>>ww7TKbtXTszoMim=&fe)j#ViZ6YA9##hXWDluU+X>ZG>TJ@zQqv z2?(9Ge340){JYp&>2ZfEnt{wmx0IoL$Y zRr2`GS+DteQPITgF~)dZxr{3kl3?@qk2nk5pV!vSUkk%$ks zv$o;E;A6iIvi~GRPzxJ@&gy`M4U(Ul)1l9h zhc(*vRAcO@<_7HD@a2b(VKqAlU!#|7O(dEVS-(9FDYG8th28ol zy6@tg@4NNfKlgdg-*XP{yVpC{m}8DP#?i%O)X{nqXXS0Dz`|8=9ey)W;>}&oDdR=+ zx}@*ZG;GSJCRo^Ae_P5`i>0y@O<5Kd2ZcOt4lNG!$~T;|1{F2YfZvyL6Md(PdTX zD9QbcgL6+_#y8pp@2B6e{v*VAP7L8f64mvN4Dxm*x{rQiWP3II&hY%npN3?V?>v}v+TcIe3g*Mc*I&ZM zzLuK=b}%V~XYv8I1`WNoO(2`p^6VB_;@QfrOE<#CK>IVcdS~2$+#)R6=k8;FYgu55 z)jV&1zx{N5g2>)4>rR*ffVGH77?e}TXLTw?z_>~0vw@1&?UmECg^bK+LDBadBN-!P z4-2CI?w5lG?4HZ+gQGfnfu?qn`?KjuAWabL9%&2x^lrkB*I}t-&hAb}0t=@YL3`|F z@hJV<+I?xQH)n;nKLFM%{@>IGt;JX^ebo22V7>z69L}$_(W&s7#|mPRAYJ`>hM$n$ z-BpT~F;=Jg9%om}3#ms9SfheBb=i_6vz>h5Ry=P0(u`&8?+V+FwIWnNSPP^(0`lyl ztJ9{&$hHTV6bR@gTpf4br@jN~>RW1X#r@b`@EM^l;H6K_WRu8J{BQ(9!5;RxvWfyS z9*M2Eo(8!kYYz5Ye45*L($~e zLO4~@i{iu3cw=zJe($EXES?X_51Op~%9~Zq+~}IwH6oQklgS?JKEFTqY&>ph^!J9} z+r*yti+&RK4h!51$2oF38h(b9hp_fns1^Jaw7gk>C2%G83Q_82Q5a6^>OYi|n#kSA zCMp!u9lS{eyuPU0-+;MPA`L_(iZg@+a;u+}21PL*0uRe%ME?qvr#@GxIV~V{Z{D4q zeP3CugO0-tsHmyarxHFUO7XCk}#Ab|dx5tL2IF?(WHLfKI{GR;@t%$fc+g_N4~uVe9B zq3-qfsoDi+*+iMb@MumEf}DhDnD{xiec%wbZwPm7P#`?H$d8CSFeqxa8ix^e%gP-% zmn`JXJ?)lfWe_0%B6MSD&Pkh3?X>r?GD*(AvSKPXK^a9-9==_octy+y`R6RKCpv82 z>1<7@M_m1P+15rQ7}nt>dasUo6Q9O0&u4L zt=jn^b*8WE>q=k7akTyVSmA|{w!(Pi-t>FEP#MFBPbFC_5wFacLJ2uDA-;4Ngr;+x zIQvL*#6HcL2z)-MNB5#{#B+{5RU-&AUwC;h3OY^YrS+4jTlIN*YP`x(67`&E+#>g- ztlXE#$|mC8Z;MGiSe{Bh2SN0m>co>f$s06ADD1+Qrb`klsik6J=$a9Q%B%66HpPdYx`e z7-EBE*}f+sx>j^@pmy8Ul`t4|P%NNLT1u8r&Q>0eqs!33CnJ??DxX_9=o3MfZp)zW z3$}i$-~IW!{5|6d4RVW~ZUyj7uFw%vPP;xnMtk{j`@dR%W52R0g$!+Vtk%rNfJkQ| zY}C=&+0TN!<}($Xvr`8Qa+$E_lT#sa@9b$3kU^*pdu!c#7^{L!Oc!T%W_jm|m^gTVPRf`ioDDVJx zqxAIjlptKV7RO71uh}f%ZAa^OX%7HmRa!bg%oWzIFPN@ya(>PT-e>ZhjIOSjUn`lk zOuv{)9q5cCz&4aIPIK1BEv07mYKG|?CUWOsJ$wD&B z4M_w=%`F)JK}V#lYtp@G7o+=qO~V$x3KL05cAUltsk=T)l1Mf&3dB^7Ce&yz8w(m5 zj%e=fskDONAeJV{ICB2y(MLJn;0+S>p@Pa-PRwkgB1F-dw13ZM;45DGNWW;tz}oXk zuH#MKt*?J%Tv9AwVJL?kTev-P2sEiJ=@m^)_TXO|xAM*$vW zk9trJT$eymh!z(HvVV!O6IB(_U$4)31_9gttSVAR)(@EDKG(a8Y z-nSM;)o%hM^wrt@(Suk|&cA&9bQ(H`Y**8#Em+}vtZNL(bzn{E5d-$QtSZJTFQ}$K&pkg;bZ(1-_208|gR~IXth`C@l~$2I4UgPj@_|BeY$Og;87mpc(q$I`Nh*q3vk38{AWN zz*#wb~2@U%o}E@a_y;@nITABLQQ;*xJM*>MVKpy6i`S+o`NUqM?JG#{qYUun{MC;i5s=l4vhbv08dRQ`NlqAVZhqI zW2Pf^OGoK@8|$7Jo~fPLt@JZzsusmyI1ERMyl|ij5l2k6MKy^dFH?eA`rjy=IJc%f zc{iC+BgIm}R8JDnY1s-phK|_$`I5`>G>=MJR;g)Wh2gQI6&Z)h1zqkpMu!ug7cpVJs zKnR+39VIXtA|^qVA~96asutYb*ys_Oq%+9w88?B3J{6AH*=-wp(pwhHz#B{e3F6@p z{d21|b|w$_7M7g8KojWS7^QC&`3u`g$${9l9q}KONaEqAo@swN00cP|tcvHoVY8c} zN^&#HW4*SHcmE`y`b2Qq-~Dy#RTaq?=4_|PNtdEsDv9iOu$E)zyqvNa#Po=h*U=s@xbQX9+!af)TU!H55hJ*wYNEjh z9hKM7)Hp;dxngb@VfXr#yWd^uKx_(ExS{mIZLTuwOEl;zN6qvF3JOS63I;143!JWC z)0Y4n^+DVzAb^^Z_cB52#vvjO63p93P|$y1V0iZSrOWbpcAc&85lT7Sw#ge)tu&5$ zheN)R^dOXl$Dgbb?OUv*7?5ck;nH@l0zbc}=+NoTWgz|%q0?4tQ0JE*GS)4aJ- zfHDN_tLI@*POXjthZ^uc0^H|d3A^RH?Uz4@+=MyV@+<{XW1`lwD92j2coL_op1IPaz_dChcO_dO>?0pW(Yx!h46mZ?~0O^C=E-)PYuvuwG5b{c$R{9Nif#$$m z=NKcx7Y50@bHz+{40LFwpKQQ`;07T9v6704ijgz@OCFwN>`(GS=?bgU)lmO7vy{Nu zy+9!5n2od{Wp*nsi`Y$ev-I8*nWD*9n%{`fBKH37@|G*q!{v~DpX{PVF?wfL;&Esi z`Fi9E^#^kTY+nQUOV@=+3A}403SKzA>}vrySI%pFnN=}jj5y39Lzo1qDEGQGs6+3g z7`^{aGvi=<@({Gd)$%yaX3yz~Qln8LvG0h@KTdLWK)ibwkZy(AgrK2)q~7strNYfB z)8Ry4-fb&_KB?;Q$@xjYz4LO>BHH~K=`WJO9`lI2(l&ZV*)JKNfM>p-(>8HzFB4Dl z+07mSqpaNXMHTZpE)a-K0SkUOYExN?EZfd$_`nu^9y^U(yaT%Ylyg}kd}PXEM@l$l zWBy=!o6SO+1v1gtt_(5(6gdG)ES*EZ_JKR_i$Z?ocU794Y?jd9Rz1x2ap&eo?;W5# zQq1{8H@c|7cF@Q<54`UEMrIKg{bwZU@dhkODAfL1Nn2hgq$jUg`|h2&_9cw9Fr*}u zK;C-JYv29eFBmWxX{M4TaTrgXe$IXy=i3ZeyTF*;ejCOI1nB2#Kf5)P_;fCbU@DNY zWYRY-%N8%eme^KUr$B$=7VJP-mS-d^(+SNHXy5mfueH?&$%BYh|7PZlU!pv z$blScw??F~k9Sq6j=e*<<1~0w+;y_X2PF7Ri#9oY$DdFGHYx2f0>$mDv%J)!zTEA6 z;aZ}BoQ9prm_7M;dW|0vMx;JYfm6cB__}j7_}QhLHFxzrFeb`);Td{#WH;A5pK{r3 zkmiM(id06#@x}y-I4D+^!1k!7NyA8aK7o|(H4?byqQL+vabz^Or~6btzL?lgJR0dA zsBW4b*1dU5pcF`l0hUp`y=g;U`MESlEgl4coe!XUdZaMrDF_a%gYlZ=$ha<|!;OqJNLPp4-6c9y7gA%)RSb+oJWOweO=-rNwH&M97210}^V=Mt za2g99$q?Dzw_+i16TJR;WpC%4Zmxo|8c8sH{c*&Z;s*vbq2?YG_g~zXJr7IZ>o=YX zX4yNx22~C+A74blgRb~lgyIwM_RHv9(Y->Z56DOynWXz_2 zsrs5g&bdJ=tqseU4hjTLSJ&6TANeDTUQuSV zEj6$sJ7B>?`lNYy@~^PQkCriIZYmH_D&dJg8V$*;YzV~G8m+s$bkk~buU+;eLXTJh zZD-Wox{~BIu*xp~Q!7EG72pg`>vNz>4RO+MYHr3Y9`Cz+^zK=AJjf-f$MT&)kv#Q1 zgXvvpy6C?v%P$#MQyXENjFT#3mYfSD^!ykDzbdLGtbNgA_f6{7a2iKVHrkv-X#MLM4Jn4<6lSA75F zTe{$fLLNHifP(;pJkgxsdsC#x)Wo{kr=!>6P#bTHlRf7U2Y>ci)%WjRe+0DD)qOe* zK(6W{0}Ot+acJRZkd-zMD^!cs<|IX|#R`PzeS7LdD5%(E3(fA(i$7o$?&1k0R&_eB zcYb;CRBOLY_F^tD9RwM&XRQ-s%@W8w-f!C`J3%cN-)_H8eQT2Dm|k*K-%*Nu^5x|9 zoT;{agOZCr$X6RA%=K@j>+0?%24A4;0D4jT{ z`%DlpK@{@Jc4Hv9YSzAi3ei_w^7<(;rmY~AaUD4}YDt-_F7-P)h)-XppW8tAe9)X# z)#(toqxX2k?mRn(Rz2iPSj)?}Y!;AnNDIQ>xX7?eY;p%pc$Eu@8QxlFGUBs=9c|!1 znQ4~tA+7CHr*zyLzO6Nwk=(ud#2ck(u@yd87q@evyi4lnn09<;`V~ivyeXhUwi_Px zA7q^w{=LlS4R%e0^h&KDriOJ^b}AR~K!r(=g?o6&zD$&cFVY}_`&Nd*XzxoU7I_v{ zBNDT3#N0;2tS6aheKh>Bn3uIheF&wxX!F|C#2DW*yQB(j!N~~hcSEFbI+mrRc$A{H zl+R7whVp&w@&`xMp9OZuP^1Y@P~QPMFsvP7z4HcSAi%rdt`R@NeE+f zJq|``AZkSK;@6HY8A{{2&t;X?k;k zCe`G?b6~ewoDP!zyZ7qx{2xb}>2r%N?WBGFL+j(Ft*2=U9;4B4+qI3)g3g;wfs;@8 zr+e9d}#Fg!jq;a4A4?rErv z&7HtbdIjz>VBk86V{z$SmII1>!kRu#@y~6_^UgiI1YBt@zSIHRh##-uSPhC~B#Jmi z;x=-cp}z{?_$-O(jw$eHET9>A&$etUSOM?9UtsIfc0FnX{?IbTKd@8^i8-3xl};=| z+|sC!B?;vok70q^3*-aXvsi5aMO!j_0`y|? v!Hnggfhy#cpkW_wkYwy6)K~Ed-&;ci1H{7jMHYsA z)4a!1cQY=BbH{840yb;e7u8LmC@s&oR$p|q9mxKcabCK)T<+7NK3eHDy6L4 zNaq^4u^v^%>+)H0n07G9n+>&QSE#`@_ZlWF4?Hq-$_#&g>Y>5 zu`5kU}>t^qo#UX6iZajpcJ#Gep1If z5x_~8VK$R@`^*_W{`2v#>8pi)hiUdRzn3F!X7eU{#JOO5T_Jy!7`HR{*MIsF+r98D zK>^`FmDT)Lw+{mWGEx?=Zq5VQOrn4)(6NyQ?(P%YY5A*K?hkB`Kuy0{rphp_d| zmpOE<;=WW|(2`0$pIEnFZi8Ww-OekG5Tu-I>Vpu^qOot3)LO`w5`b~Ix&jJ1WB?_c zX(zvk{v5RrQu(sj*|nS6xZn27Ude;ei#DG~_i*3v-^Q+SU&7M}?K^xDaKQcrxfkCu zIWzUx#mUtqViYrjHi}m9gUUvNN_ZkH-~HJ4bYzS8f%T+!^O#IfN7L;sFTq1V{A$mn zSTjdqJs4h&bEF(q%lcjiP=fw`pnG8a8R;8(6(4JfptPv#a}HA0Iar}9)%*IpZU=g( zQc5-pHa50+{%>k8A&o(87L&c)?A1;zsKu4gI#)|Hed>_kklc>zBS$EJ81`&Z?O=8! z$3TJUiEmY72@_v31TSVz*U4~7B>d1_{XIKq_#c+Yx;dzk?8P?_W`7KK#I#)a>Ao-c zrU@>(Av$8rqr_~mK2UW>YFaxJ>D^*72b*mtYMc#b6>bo5C3V5RA>apS5FbRq8=y#b zX`?^NoKfLtB2D~d#cf;&dRNemn!YzDJH1&&)qq9AE5_}Nf(DgTJgO2v$I@Wue8n!E zo`VC&dLk4|%SWY>*rq)d4i;jh7F=9hz?UWdn{VOs{d3C$>tpLDCVK-7=6qz_yw6pB z-$)1zZZTCF`4QufR`eGVpM5h`G+DZ$lT9(g80-=>>EPbvW=W7G>kd~We;JsAL zrb;mKR%TFhp?4Sn7%ugU>a;69*AWV;Z(E`wgatq53 zABJXhlY2eVZab>WdC^}_%tkaLI%6)?)z$UV?;pou=#^IBGgo=R zHn<3?1^TeZ+Y0i_*tkO?e~h-b8hX#SyE+8`*G6%7?`TkPRz zp@Y4Yv{nxvzbI5R$!=IYb&R1dvHj(Z&$;GeXJ=>1N{`1kWmZ-BhB#{QgG={V^*{>` z;*;#_;8-fe9%`a+Mfa_!ZeBuA068~{lNAQ)FFNT!xBK0lJ$Ugxln zn}+cbmUo7ztHVaa(Tb4v-Hhc&Ll|;=c=F;w@{M#1;(T0pWLMNb1eCVX=SXV|*=oS& z(SIFopIK9mH`Vd|%!>13_%EDU6CBxDc_CEph}ymE^zIT3`3A>@)k@#1q4fs>0VZrO z`8pog8ijjXpqy04t%O(51*=;iNF0Hhxeh6 zJFH$u6AqK$LG&*3`%A8YND^#wux}$~E?mOK1&gGJ0)_(e%s?13U4m?-$=xBpcmIbq z0Fkrd(RAVb2LZk&-Gg#r3g7IZsy{HuvknV>o4e>g8sv~F+~62vV!erEi{wVC%Vb%X z7hB;dp>Ck!EfZMpb7lug8eTZs=Kws2cgp2GTXY zmT2Fh->;b??-r@RT!I$|{}*S9mkDQexmcSDPW7k>D8RFmsd zo$JBD+B6Ix86L(pNnf&y(07=CSM~%84NwzeR>;o`_nn?0X5#FGYOLa;lWB@@R7Px1 z_ueyBKz|rH)8^v{Ex4H}3&-^Aw#~%+=FX`zT|@gjqF_;ZovJ;-z4P@?_o1U5sq-PK z_q7cxxKQjcT6UeMsBF`1d+nX|YbTZ0XFvv*D9yWR_D^LFwG$sB>|ZR#RT{y+hzt5X zv~;1_eE}rJ<7}5`?Vtfq^pV7*M^|2ISP^0u(m!->DnTTqCxt>&IRb5)P$3K%L^JJ8 zpU-Xo{CYH`91s2lAY7ZUFtxTW+uJN6t2_j}-xr2w$mi7yVlYaRyK{7Kqb9Du%bbp% z3}*oIYf3G@W#0`5tl1!5ll((Av*u@FA;9{*(ikpPOHLfAHA_-siIo~j_J61&luCt(Uu1B=T=Y^c1P;Iy^ixx5F zFdh=*jOJC0YevArXi%1%e-L2B@c|-DTq1+Md=wYF&qZ8P@>f341T5f$) zWJ!CP#%TY1(bs?-*o33L;$y0a{_!%|x4#KY`J`V-O3c6SinVZpDigy%xI`ibefrW8 zgCiagWHnk#HVdr(rzQR%$L{~*hT|q5_}I|zOCTbB(d(%POB-15`M2sJX%C#QbQ^ky z3YoykL=ztOzC`GHwSfc4dJ==Z9xnoBIoIu8bUTMy%lm1)w=SHzOcVZRI}ysn3=PVi173%!mq zJ`C^3?)%Xv8@@Ir1rMd??X6qW^9$WW;mL{s)0qFfMNqFvTiYVZaJt4kY%r41f&LR3 zH0v7d2-(8t)2t=MUog~>xh#WbPcRw3IhuLDZ69#nUoZm0;T6o2NaK<9a=I&z*Q6u& zB?5Q1gf4X5C@mn(muqbDp)>uy9rakuJaDo)N0*x&CANPy7$Vo;Zvb2-b<$;T+-efMnSMTGKC z@&9T8yr&LRas$4P_B6&z56QkjAM1PQw|ptkQjkWv%~*IaSqx=QMl4$^G*crja_0wo zBorME^mcN~>GGd&ieVHx+8P^-tP_4Xr_UpwUV}$Dkn)!+(ti-C($es1h_>M6`R)Fs zE>YLV^WlXdKr9Z*5g>mZY4R6@VI!OLC&}`PYz7o_v;X>N!pNU?B}& z+S06ySq@O%0UMICf>RGL2B;F*lf5wDQ;RAmESD@1hY6FP)+1tjYYkXN` zB0n-P6C&fn{`tcKHrRC_UKEhc0tl-Qq?_tYgubnMJ`F3H#t+2|;qC9Fq$ChBgD9m` za@{cWp?Z2Q{(SfUo@FcsF9tC-b-~}(3Wl{BYxAF^(1oO zaS0xnGk@DyXf3;DKe)~Rtt7u+zM>wx81l%(IqU8cQ|CKvdk^a!xtnrF%(`gMyE2El zHHt;li=0{_8-=B3_mej2b)2`R80Ggix?O+0*`UTMM}jM&x&z#!8+XZfRms5;4+ksk zJ~Tw>m;~?W`NY9_`|8o*kYnP`z>snem88TIdId>Dh@OW><8ErI{Nvy6yH)7$>8vFs z-qvezG@gpJz%pF%wyZQxR@Yd_c))X~t}ij*2LOBq5`>W6{!UwLJeJzd4QBl`Jg|C{ z(1JLAurx1S0zYKV`Qn<>ao@X--~@6>zQU{Uh8peS(i3oZr#Ct|HPg9Zy?fj zROqA^Aar?L=%HD|lCGD-I)V2@-?u)5rbT_^chToRf9fzm`@$rOOuxgmxqE+qzirtT zbejp<=Z=1Q=#XS1R2bqLCVUMfI|@Qb1!cVEXkKG|eGi)yJ$Uv<0AQZhu5>DF_+H>m z*pp%-+zA*z;2(eUTo$cOb4Dpu1C1C2vpL|wvbOcB+)mu;mw|;hQfONC*5i1!AJv9i zn!oz1wvh2RIZ9ML7$&p}X1pIy^|8SU#OGkOjB5E*innQ8Q`qWPqlD+4CcFjtcIv~p znFj%+t(}l6Gdpjn1fHaywPXVg?~6}#{z;QTBizty2Q>ee;ZaeHq+#?F5q)QKkYD`_tq)5LSH{{>>S82%YV(b+ITZ%>s+pwV?3 z1Rbb+lr0gXedYN%jEbG_x0rC3jzf-bID~Q#{$)?p3VpMJxsQ4aJ3J@?>)!8pV&^6cojj`*m|cdwr*h zVWtzZMNNSnH)XJZJ$INgK-bL0@0RT070~H+-uvnlnnm+qz1OB_0LMUBe%!H%p?}|Y zdomvg3GOdy*Yon0cxnXEWYM~SLt9o$VcFtfPmcQtjp(OMMESNpzrAl-fjZCc=sB~) zCR{KQA2BDZTmE;l_I%>jgL}Q9p`mEg90+I%*hrgW!d8^m0+$4KZdK~_H(a`iT$V?3 zGdbx*QebQ)?#moZW1UKz!Xc)+7qf<&{Wc=|ezmXo*qxx57=hrOxvzN)e8Z2H3$e7J zy@O}?5ut)cG4-Qkn__vrmfPLe)aT3=qg*8KYCmHHZ~zPwAgM8*IUug3njY3`)b{fy z1Q=`l`cso>+Eb4%2WwMKnua}&`=dzrekNfgjrcrEdjA-!*zUiwH334E$2I=7wft$% zKa(!oCOyj=;2$#Z^2$)Dff7lfMt+BLoyx`r!*G7Sia`*sE~MXYL)}7kS;jejq@`B9 z$ZQ}?J(BNlGQ|h%L{0VMWNY+ z(Mu!2;!L0N)4r6eg88mP9NE!NtKQ{+21vs@G((m5v=XYeUiE0d&hC+cu5iRh z=InEXo9?P_r!F}{dDPD&w{)+bnKsvlmT16qBst4LfxwCay@O1dLW47PwK=!3G#8~U zHeJh;@)q8RA!^G!IDWyMu@4nYl7WnHCgPWQtyjx@7+nuigfvo6yOQ&4dr%tzej%{Z z0^=RPA{f_!yk@}peK*2E)(2b0pq!xGkEjsCFysk>@T)>uXWUnkAHYb>Dm=2RmJje^%18V z$@@U?g8+=*fe-cZrQiW4F=j~%xkf3e@PRi>cXrtJMc^`EraV}kv4n+(;Dhe>#AO=H z1gdr-DQFY>Ss(z)hlir%Z(L0xm}LJ^VI{7CIdkS3_Tp{CQ1-oi!4ap>(S7LpU4D+M=O+E`80x_b)zjY>pI6B(SuW%7R$H#P2WanP zSX@FU<3KiIHRo`f(29{&|A0c+BZJyou8UF?Yj@NM1TTad?F%HYx#rLCvaiL-|Ef+H zHf#0ZF@KY$O{_-nb}Cz{IIpU})@XkhbM;JY2XgW3iGl+8X zzjo04^WzfVVPJ;@JNYz(z{g+nCD_@JcYj>jJi0JUKJ7^AsH3BxEOGwwm1G+|X&CGj zfeY+y5QfyOT_X8H^3{L!@#9Z%87x1j|CBLO&mB@kKDLxc+-_{(`o<-<|*fpY~)xwGe+yTRtvFk&yeJ6FvtW*2OQ+ zyB%f~O?T61SAZDxDB{9X@YhXDF&ON*pbf7?`ie}HMD6}`KBu^%xvlE@TF?N1T=JJ+ zJs+$0bY#09u0qP8WpPi4lOm4sE3ct?g_k5MFTL9#>t#2Q`pzd*9>?Ck-#WpsJ=-cm zwx}7%(M^321x`QL(8{LpohLZ{w)gG2RG~0zaQHwQP-4D5 zAF)oc8<6-KwB#`#BAPD4##A=IKqC86tR%>|&F?nBGm)jV<(tg57bY0&^-g@`lrZ>8 z#;rZTZSyL=e6t@SgdW6{C?Ac*lp!zpO&g~#7evWSSc(u1TGDzb8FAYVa;JU$3Jq@p zpF{v7!f|M_Lzn)>OVsHSXfxVXoLwwe2aj_->(|ya%enx4YN#*?~8yi zT(L~aD07QrAiSr2Z?urB8tV;lgWXl)iHtxf_WQ37MXD^oCeXf#cV|r$j_<<`n8gSi zq``D;^>?ipL@LdP8z}03Im^0he`~Cr|F!yRto~G%eZ%FciL)u=raWWIZ)fR*5WUyY zL>*?YS=#?NCVI-vY`fah;p>(9zT(x4N@C%GvL#@Oh=@RZe0h)E_x+igsr0Asqc9bcDCIJ%b1cm?Ue|(%U z4gdT_ua1mtpU!EGone^KzK9!@JN#2m4gPcnA{YJD_#arc?`oMs=O7v_xSn56dzBp% z7(&^*Ks31#0g~9YMIvbRz3j}YE2#%gLow~0pgiEq`Y43GPPJ$aV~n%I71njBV(5O5 zc42D<>5JKjQ4Qy$b7a^gqwSHzf3t<^05#=@b6q&HWT3MUE}*XZGs46RPytXiLQ`Yy zo0^)6G3`ze0em=c;?35KxjbuqMZQNWGBotHbelu#<40c;34hM?d%`WvHk@8(&if!( zP6rUvgP8h$f|oP#7^Novs*usVY$dz8^&hfd?Y2M`=Kwd922H6eN1PSszOE3hnSU+)ZdL?Md5b-KTj+~4Pm=#vwP3zaqqT~?CA6Ejl zve>36^aRtT@qmS&X%Z1=*w%oEQpVd`Y|i=_jl!MCkm{QEu7e$Bz<5f`B4x^YJe(5-#1w+yf?wb zyXVzp-vlAOXyjxYI9r~D&=_y?Mav!Y!JhFB$4UvET2F2R`bD=#kN;{t3AYuz{>#2U z*TndzS&kks%vAJh<^en)enNfd@t6K_dtbj{tJhSjzZetLd-VSCZN;-_A-UAHhT=*o z)w|bjp#t(U>B1jlXqr77t1{JlQ>z>$u6HbP@=@03hJ?D+xlR|oA0*jB?Nh2MddBRaYFVCfUYWRBN? z<_!JoY_wp>H_1>I`$x`j>f77f#&fk$pKv|&ici(?m|^qSy7F$;){)?2eoB8)N~^bM z;LlMW2ycPnxxSL*j?RwThp`F+@Yf}@z29c8WCS6*ACGeDln`&!>xq72EGQ)@B(h#_ zT1ST3bDdP%uiYbMCVDydHLX2$(Tzw$+fFBI+x6%= zvy=wx@yXfW?$2zTzmicU|7pqMm%h*Ag69C}6}>nh@1?d^9ed~vU5r0?jNk73a)LKH zC#v(+SnKShgrNR_!H#3ky!Mv&x>c*y0`5W~g_O>AYQZ)K)m45Au?J0appm%i+#9wG zwlLQIagb6&62@5nqPTx420;| z%F=2UzV$e{GTSUXif}l-D|fV(NU4-b)13ZmWJ&AbU1YoXG0#h-zZU?J0A5mCp z=_Xlt#6uOn`Pe}TD=QxEj4BeWVyT!1B=hL7aLJ3}sjz;58W(aXx3TcMcA?$)Qk6&o znT4B~)U@+jtcNK`v!UvsR8oC{&s}VDp)rdDFG6QWkcH5~_*tE!_nX5x^DksK%QCdG zkN^Ema%Se{I<~f02yifh6p6J*8NUh*itIe>hs>{r892cQdDud#=bjEKvoc9K(86K@)$6ZdZ~(&}8MAsNU~&VA zK*{y&pX@jXA$eX*?r)hfhSD~pKVLZ*^nsDP#dADZBvLhLmetH2O@f3VlLIzJx(^#M zroO#>EKsI2)@X{KTzZs*iLVHhr0a2^i&JbC%$V-{=cUITpc0>}BPS zpxX6e<0quCEcUBL?}*=Fjz@;pV^NClD;cqZpAg6ZZv6D0AIH#&c@2o*RZ_=eGJ2Gi zIHNP$a|D@Ul-+2-nh9w7a2Y}@=R5p!Xug} z$y{X&OfLzt2Rbzd*t!s6|y)V9Gp4EgJTYor6lnRPW7R{JhPZJ-X`JP$S_-m&2pz|7A(B{)-sN zhsFQ@&^!Z$2x)lrMZ*xlk>KvZzS%9$n)_J#<1s6WB;=vbNtPFM4qv>T!UTpMH07dQ z+tNp509m9_h;_~k(H5=>or5bm;#lYiB8J0r%nTU;DeYr=|sNG z;5%JC3Gr>crEr*5-krS=V%CQOh@OK3QCwWyo(`7pPpnDNIzZ9zT$kZ)+fjwG3ctx! z21YqTR3oL6J1>=pX~5ow$9j6XPxFVy0@jE}lRPc9f6tkZwsdJibdHr^56cfR&v~Qr zb?;P^W>tqcfWMxg+h3+|>D6V6<|^{bKsW4e75&835g|Um`Pb@xUo-81l*R7#Xow@e zi@w#q#8PMYn(Q_SHaV#cCons#d+OXz0(VT;qpefz=3U?AuylE!5M`3kKBCFzNF=4iAYoRk(em{*lU}U`a7_onU$guC1T*qXgsmXR zy3e|Q-QLRSREmKBs4gJDa8*^U*cc7*QU*{+QsM{os@YkI#_+h7KR`(hg zoXFB2PgfsA9qQ-n$8OlTxCV?lt?#5cTk{QvDfebwA*ny+n(~z_GL;G|W%jDS+dKmN zjNoOfsJ)~R=)!%hZJ~ExyBB}PrrcxoYs|qQEqYtWm$s{2I7-(`Ily!l#4<`sO5*J0 ztFq0*ut9aIz^y=;eFqJ|GWpg9M&Tyz(i8h_eTEa(NrqjgpW{L$@*wj8xI(&C*0n&J zDtG?n@bE}-bYCK9&^N4HXKkLjnuZ>lorWSAs6iFft6n8l%z#fJ^YBLTAbfAz*X{KU z4Re~FF!cDzz61;BHQM2HmGWkVkEy_o31qtHLpAcb%IY6KvJzpDzh@%>^YyN-E^(XR zBW{jcse6(us)&@jmcgXhpYDS`uEjQ#r5pChuq7~*qe%=Z{wsh2BQPKszsQ|>y0s;^ zc{^=M+8VOhnyrsK>d|m00G8;^EbgEEg1`7j;IlsbX^b*j{?ROECac;~={kQ3ZiAj5~uC&W#iHxjY^!r;UaW3EgaX4PEna0yMTK=>J zztnwI3Qo*}maEY(>pg2cs3wVB@t0t_(H+|v{CY2Y!ql?Zbevn{zwIm`i3%y9dS`Ij zoe%9-4iAmrN2EkDI`irzjz&B!n+oFLwn?G+z)g*l9V6X8^it-ZgfJFS8ob0Wy+Oy; z`Bg6)?5#hDsDpJ(%Y~<~`0Oz}-S^Yhbr0;*VP$G+YEb1X4z}}{#r~Z9Id` zQeTkNp8Wm&$pRRsah)W9lp|`D$4W+KJ%G$O7>;A9LjFgXZZ^||O$s)zz|f%G9 zIpk@iIy7}_%2Sc!N80xDJ9Bgd(Rv2g-EUbz^rRB1|FHiRvZt2VVs{4ybGS+OQLOkL_gMb>?3d(rFLAqY?UBLvTu>rNx*lruRK}w(M6O=1+8Eug5 zd;D+^Gz>PAFab^GE0z*}fEy~TExOQ{B{n6ry`Xn0D=FenJ^|bPz3Szdbtak}9YLGs zZ7%whA;uHVdsrQb+t0bE-njgabz&NxbA-!WBFR!FOh9TR)E7UgG!H;x%tQq0DCsu8`q=!o~et@F0( zb1!;cP8D4oJT_#QSMww*b%fr|fA6AH0A4W@-sc|a!hiH$o>7plr7cdwHd4^e`ix58 z*)u%YKO|sbf$V*IJq}2dl%T&0LueZf3Nb>LQkg}tQ{xAwNa*>$Lq?VEKJo)N=V9AG zT+8wFM(peh&Ld7IavsE$wnc)hVpX7>5R&r)eM^r;c7Nfxwks=xC{hWy`1KF=tyK)DUo0!EG6HQLzaL+C`7889t_gcLyP_f4i3HrP6ULb(LdYFYx^Vu>cNsu zzqTlmAODyj40~2Ttf=Sb3xI>?rm(lqL&c%4FknIj-&>W6X zM9%Dl}CsD~dH_-*%X9(bL#XqA+qOuzH8Ki4^_~}<`IRinkh`q2$F86v*9D4Z@ zv&rBojZLN9n)%L_V{3HQd%=NkJP%30scNt2#?W>!AN0zQit6h2&%Te*fNhMSff@kY?JL$M7D$-K^+-$brbBeiz zV{JB8d_+TmwaXMof!z(suQW&-UcCl=4_At@k`c%@qF6{t|huS=j^lh^S)2KrMWjQo{nEn&dgBF9qs#%!~ydaqxY81P;M#C&m_a# zXdZg{l3?oTnKH{eRxA)8kX z!~NN>S(%#Zc)!kUz%Y~Vi~2$Pjo5(0(e(1$J8ZVJvXx9NVTjbRxz1)JdDtZgd#9cb z>SAM1nCc|r3q2h!76-}`=Z8A`MfZdinfhlI_;SEM>pTdWqr4{#(iH9eq_bmweEh(l z*)blKfu2x=n-d@>gA)9xmb@2u5XL#~3JYwCK|^M4U!qifO;$n}A;9ICRfIVFFgmi$ zN8wg~FQyvF4!o~+fevT;f9MYJigG+R8fvk&=;cJJ+oy}(*C|=GWj*l8P|Zr6G)E){ zFwSk}@<{Z59PmMWIczV44AE7Oy}Hh?1_R_Fn+efKy)OGFHu_~975D}lB-{rd2F*1b zZ4|fY-CHCWZ9DeCjc+Q#FPT3aa!dj3#MF$b67a^T4?oe;))ux_-v9yAjtTkT&2+#0 zBY5^~_dOvc+D~z#{&}eq8!^JKxmVYRVB`gzO;BlPgFAFkmSkmwzK_- z;T%+w)tUnEGZ1}04JB5BRrc>hQcpe|>EG1ZR^Tq(ImTrb)aWm+J9&UCyL?M|c+69@ zQlGahB~^`h*DrwsAN_sLdzrEval5hJh)rCfXZ}X=56=4> z&5d|1Bj_H@vyhmL&s5&wFGr6S9)`leA}o-!Rp>`*k&%#9)}zkb%9+sBe9K9K+!~pW zfd)f(ArAGu@Upp*<-ai(El_=?e)?2(|CuGrJ(+XwNw*sd0bP!#-8Nf-E@T7mo}Jj9 z{}a9$L%2-uNuD^|CccL$DsGwkc$fb9ctDZ!@A_&3+{hwnwa*|VptAq&mG-F-oQRfO z>z+^!QDsvf$k?3C<57e=PF=M;UHNk>v1`Aqp-S>&G`+JjRCgFvo%rc#pl*y#q& z#nIBDUTQX2v-U0PFq?kZXh-z7PnuQ~q)Ws_>sMZh{?qHWQXXa%iKUT6GUf)Do_IyUP6zoD1ohbqc$Bez9=evvn4@jZbffmKRgV;Bgihb!WC zxK{CJW#|0>ZyTGzG>{4%G=>i=OVjIs7ftE)+EZ++{~pgzkFTnnCI-!GOzkw8s!I0; zp_BP!8G23;5zMc7F*4D1Ck+w6;sJ!-m56(TPmD~8dZ$9B(x;AP<^~1e&T=d%Y5xy^ zmCsy2ABScgo@CtV{NW1iSyd`j+uGZM0<*6cXq2kj6PI6G6Qk*0UPGm`+kp7dMhrRA z_CgOIIE6pI{-#h&`w|^UkE{oqL!8Spf7jgGIpr#}N5>o%Y;3VxVDDJhB|eE(K0?e} zZF&6}sGmxfVf;2}VL(+yhr1@W7`sjI@;Pt#)p15o0Y7!JEN!x4#k07yL0X^ZQ2!dG z^Q-za|K?AF?oVW8(Oh0fr0cwENSvs+*V5RLn6T8V{I4!)+-bp2h_Y)(7{@T5&;1;4 zY`VfAwQI!1b-@OJ2BRf&Kdkj(%XupoxK5q-CHKx(eC9|6xC5kay@?VSTTQr0F|n{7 zFo$~89xO<+;uTx@0o>2p_L3-U`Aqjn(XRPsxLIVt!y2IgQc6yv%BFkgZ7U2f$Y7*gUsvTugZYI12%NH`;fbG3bPM z*uvJ>gYqM-LajHCk)3Weenx=xMV~e45(iu}fLSXnEG)epl-N`4(^Q<>sbAW`9fvFDz!(gGExLS7T4?fhc#QfS+4rcW zn5sL7JvOy|+%`U&;0UGryv0TqAJLw+CyW}@If8*bhi-83m$O}NxqhYh^*K81ixVc) zU|}(MHJaM3C=_N=V|ZTK(!z1=&fNj#hdZqIf2l;&+tg$NYCA&j)5yq(6FLmcfY?~% zGQKAMyMmN#HLWEhe`!IzzAMq373T>w%*$;ZDDUNzKmF!f|L1Y7%CXwv13IJowzcb| zoR~k7BfC%`Fayhvy_GcXS$rnUaUnwYj>xe7tfPLaZ?q2_Wh;A9f5@h%q^hZ1SU;5J zQX;Vk6%x{X{vsDYu4onWVI*GcY%zUx^6vEgU$brgtPK7}H3Aa9bKw?@Q&rc>;2E)u ziykJD{?l^~LT_+|)ZmrF$8}kknS&ue0Ww+yKTpO;kE8m~&`_UilgdwdH^Xfwd$d?^ zWzg}*yKD!OO?DDa)HeNTa!kNKf~Or?NsdOBE?+(eg9NzFQTYNz3>NtP(_sR*w}A-S zp7>$=6k8fCI7<0I?+;Q~bkMkDDOakY8S_Im641jz2O>-O0@dSP0xlcku+!-;e!6Xg z86yVUZ{)Jl5r$5!lRN(6=C2ph#Zp5wZEWrz&Ey6Nx_BVOe-1D8WAAG-a#tp@2pBIh z8<5esGHOxdej4948KM^Kcbe-QWH;G(z{~w2;9y0R1T)LLNB}47MS>1Gcsib7mQ)7 zGO8L^2#J%xhgzKHCDRk4RvS;FSpTcYxf_%oR{2soySY>n=z;@|c=^Z)WSQtpzFR$r zFfY$sqhjE`EvD-DyX2AK85t<$N*|pMCc^5o1_$6MRxao! ze%z9|34U_jQevc^e!HtS^3~8et$ETIVuV1DM>zCr#Z- z-UA?OhVqH$rM)iLRMh&JGNnD??+gg(?758=2B+mGH$#F}z){~ldu_%0Dr)pVb*sYh z6;4i0x*$vfcR8B+jbv9Gsm0fB&=5}-VfJdPj4Pbx1b54ZOi&*i_~SrN%PaJib#V>X zX^-mk$(|uFeSka-P!@vOSJ<66(e}yT@C)bS0G!nfL*G4MIF&v2x%b)cpY8s`< zA##20%JbOg0eqRl)A7~l#mjrPwkQd`zNbma&K~E^j%i{}c-nLO1?UQ`dJQyQ2mdcE zFMPlUc2BOuA1w*=p@Xdgn7|;sW2c;t@h|ViTtD4(Ub>6f`as<;qnJq5hRJ(u)|GD4 zxSM#flqkb2^0cF;>qBnM2XcuF4010JfwSyA|A9!g^i0I6!OGov6K~T8WF_!$4B3m; zkRt=ei!Lp?xquB9^;=5|)%f^$<=vdZ7Pe*4C>;yRS*XAwkLdihm4ocLg z;j|}k3?Ro+!O;1KId}Tw3Dc0(M#dJsDCi0unR;a`kqu9ug|Ik9zfumDDs)u?1s=7J zoac;m3^|+7gHPlea-c9^k=i2LC;%;BAmAWND~D9a9OJ`<){!nlC4p2*V!u5(F;F)k zf?}t&1PL~RL)S>K5kbJSbG`QC-Kg03h)2t)(7GqPOoUp63H$vy$z=Hy>j5_+dX)6A zy1QPdG_qa*0F=~+7Ayo(lQ%tqc$kTPSM6U~-5m7EJe~oUiq+i!uY0LGuxqe*dGi8* zE_z|qpLSNi<@_%jLe{+#sROj?*`;hzZJnGhc!!xQO)ujThS&)pz_0n%g(?|u-)=L} zlWIxxmL!BlBlCX+ZvK`H8v}w8XkeK%@n3`Hlwtwgt$asx!0T??nIP`E*dO>+q+&j2 zHHn|r1qM#ynt&`-fP+pUca&cz~$4|$< z=)U`dW%A5E->)ddSCW$z9d@bHdy-#&vr+oy}0E zTKt-RJE;)3FyFhSasSeyeq-kIY}tW=SMOIl2Jyt~EEy1KX?6(;r9}eVL+4!<2K0Q9 z9=gul)dXosD|65TtO`0?M+aiZ3L^cE?WuRG7wM1NB%}Qr7F<$?zW7mdZG6&A35=D+%TkKm2qTCuG%?@K`DRf_!$w;PgAH!n-_c}a%>StHAu%F9}ue|L8%1%X;|M* zcfK_g$K`I3U0pSxMr9NWHH<3S0Hf`Dv4|G_^fp-R;^|`e3=~r$*CuT)mK7$E`6)g9 zSpp*Z9m$pR=Z30oL#L&cVqy>Tp=$hpD+qwU4`tKFY-V}Oz!i&=Q5?H1nuBG-Q6Z$6~JCAqf7uA zJ!H483r<~+o=Z~JKe}Y!e~~@%WmpnvT5B34CV*4;(Q8gk=ciwUufVRS^|yXb3)T0e?e5{^~xaFWBJXuGY=A!e;I~{Z5v)tC;yGfx_GP zg6J624++WR6M2;6Lmxlov7%F1fBN+}l&u`cVUVAX>3fA^b8|#?;fCcHev>; z#{3;|YhGMDe}NtZ-N#Wu>UIDtH)usTUVU#Ls$F**X8IeHl2(x-_V0N#WE=-vHmwlMv-1^ zL+_m>R(9LX`px^l|G>z;Rz}`@a|IgcA~F$RC{A|o5C~+iSP*6Pr-3-hC(BV=5^KpsOgprSNAy1N}RuiW2iXwlkeW>SM(~beMi-Hw8qrz+PqyUHQla z3501Kx{DM{T7o}t9}qza0LifH>NQ~VMHaf{ZYON*Am1>rC_gAff@x%G3gz*Q?K3HF zZjKxgy_QdyO2Jk%mgM*EY(hp_I-Sxt_n8Bx^`oN?%{AdFrGXp^*Zxioyb~bBlgh3( zd842bj3g~o%fd5_Fud0J1MzO5n!a5gIdZ-vBvANO8s$?G+ub6d(_`%rcfzH-iC)?; zY@k0y#*;ex7bBJGFS_wZ-(>|1%Y8E0&Cr6n>6FJfFM>EDzLpDAPxI!9=(=<$+1>b7 zy|=lT`y=zqhcTi)H!?KepY8?^GYWG;m-&INI?5^p|BwDw^}-iy?#-5{G^fQ~ptlfl zZ}k)#1vJ`x$Q16FlYXiycj%lvGl5YPl907O%_y0w?`4_L=1BJnmx$cU*|oQklMk_u zb`~JFuC{D-jz{Q?Cwe7r*^f#KIDWL~Sos!K99Wj1k31f6054nQV0BcNO2xV$=54XB z$VCQ@`{RyY&%nCidX)mfp6Dod5o|E@BdP~7wL>r&?cDdZ9t$O-si~>dlp+UW$%3x$ z9VEUj<$C|qG{Fr_g#_kTNbe7flg|sWC=$l~T&kE(&|mn8A^pfAlOH-=0-SyVP)#uu z)$X3r(CYt_55kr0%O~DA;9hzlilWY$UUv!8+{r8~ zlOXr6#A=RYZGQH?1X{G7Gq=UQ#3yY|Fg_S^C;Su)&9n{cG6pFhZ_||D{N}>fc7E9V zqL~*XzAJ(@TuxdozlhmKOK9Pp=#<4@MT%RyOJ&)_=nJ2Ra+}lUaoE`gGO+{Yq|Yf- zCL}5?WU>&W2VyAM6%H`-=K}5U_6OiY(jVXQ}I>~abR~mN;N^QZDIB<+jtf} zDK!Y{B$0QcY2_f{ODx2q6U~S^otB?v3~}xU2|))k4#fSW*S1ksQ?8c1dus-oyshPy zuW6H8&wMuzig}ihN0~()eA1x}8e3sLz=Zs~6^#!x0lh`^AOhZKQx~A_3~?bRi`X!J zfQLj88K-|UMf(X>fcg!hnUiJ26kae|wn8(7$)7t9)4}*{Hv3qZ;oNj#o-}S|7U)cG zl7H}2cEz%oIDwRRod(yERaY`qGxO^pF=AGthwT7g4Lf7^QK`AnkV_c#JIt#JC@={b z^*ccYcXx2E*z*Q~_h57e`ZRN2;uNqIgqRJ>jum%)3mhxNXn#@~4*R=afU@@U{$6kR z>+P1`V(ITKT(lkPyikh~p%-ZaU}uiZIBD{`Yl^hsDfF-W8O=_@tptvYmzBXVoM$4f z{4JLXMsu)`PSwF7Hgr!`I%Ze&u#t>+^PvIY1lreJI)>lnP*3O<{A#aH^nl2Af=l^P zUEOsxGitfd6!M2m$`|aP#f2%2QSd$ZoQAT=>t}9;!W~5SIim#)N<#Dv7;Y^$L}i-p z|4x_lMPcee-MWk0viF1-4{kBC$jQlz_Ax>ZOW-okN$B5W{(j?TSZhQChknTHu>esn zKlW!NVf9(^X!#uMuNa&$hULNN}o1%pEoRD+unyd z-u}JJB*yZJ01Pr>Tewl#gx!s%56GLPn3^~-xlDhv$K%8TTZCkc>gxDK*V^NSDP>_$ z-4QlCo{&?F#$J@ts#(-x`vx{L1ANVDW+6kp+Qc)9MU3Wzsm-UDOpJ_5h{8;v_fW&h zPvC&;T&c(;z`X70?1=XH2d_;gb7GSzSAYzD(-P*=x zd1ELgR$q>J&wqJr8BZE;wj{4whwjF={e{j0oHVbmtJC!YhQ-vLqzs`2w1uk_e(T?v z+;JHk9(J9xt=7Ve>Ulqd^0T+`mZ;hNQkePccmHR1S_~0>E{D&;t0BLx$IbZn)4kEC zgtXEi2@}ue+!g~aZ^h&m%;AM_E9SHpS!?foALy2-FFRcwnqJ8b_n5r-!P$nYU45E^ zP_L#b8=({a`reaYO8M0XDbqavib0Y;4zHx2rPE4?dOY?+wiSY4Hz4x*yg=chVhDwAfk}=~+ zZ5RvJV&%_-yq|h5I=|}L`bSkhxgKL3k~rDstbJLXM)G7{x3`snq;g35nfmlE-J#M9 zi-1e+So=aw7Diksv{97Y2JKgr|dE?A#4^$ zx?&5NS!)RI^gE8G({LcH?1%(4V&b8d~jpuo9#v!{4_ z8QlQ3^(QQOgM;ijMwu^VB583P0Z_D?fEkj&u*)!CTmJAk^7@sRX7TXSq zWhIAv8W++terwwfC={CBtO?0f0<3NIJoHof&$zTh>|G33R()-0%NLJR5U@iIuWMzz z7ca4&g3AK#9wemfF?VmTT2!$_rQUDr=NJfcFx(C6FQFXRDU9Zz9h%NRUyR)_dn;0v zS&&S6P z1f>ou2xfw91b2sB?YF>yPim=7qd$(=RkTyXjP==tkM*rD{%8J2sa-4qk}bnrYyN`g zIqfu3*e1kSZym@t9Fz0fpPGJS@3@5x*f8f1K<)By0@N`+mOfawzCKy1#lZ!OEgzD9 zH0F0%kUvHGOAt1=I507x7A7+-&q}oFUV2izIee@)A;XyQ@#==#n#=V5%I2Z;Z(_c% z3vEBn9vW_hz0z8KQs)W$QKWmuv`&ivo$ z3y;=)iQEgi8MEQUgos;CI3^e#hsS0o+qzzG3~JN%;ArMb^?UF#xTZaA?#jbyOX>iS z9zgzd)n8Veu@zCsV>SkDrQ>-j^p_p+E5W>lC~Y|T2q7bZs9$pp;5EuS;|m*<5X{_E z|BC_DYda-PAEy6iU8&z>a#;Aujr~VhfZ}~#V9`Ik0jVtu*iWV%D9-$B;kTNKzGQ z^QL7<&kx&C9zU>{w_%8OoGet-C(JmmLlzwY>Z*a3QN;1zpt zJP#1Nrz1w@IL+?nxgcfG|Bng7f3fvOh(aQnPpm$mS;3zw;}Zd73rA=>;&{HIJ?|7zQVLW0~GU5iGJy=#+c8s1RM-c9zu z|3D$lkS?nIi1d@!k0ID=_N3e*zJE#B6XlfTKNLR1F0|NAS`ARRz+VYeI~IteEmf44 zH#i+ES~?d*A04m)Co7qUIVNN(B`z=hEFn#P z=|%%7)2Kt?O<=9=%t^MDpn-^HykTcz`~CJe1%$88s6XdR)@WATlYk|5lWcAI8Le8n zS6Yt|2C-*JmC-8kpo;<+r0ia9&aM4+TPY@_WRR4To6GPE@iqw|Pph*dUC6ZHeUHm` zvA~Yn+x*-owHoB`EPJ&vY0{e-^;-)(Qgml`M?wl}2Dr`Y`9hjm5ng&OZA%+Qqc9f43svTDGhw5Cu-rvu+=#o`o7%3E_-n*s zbevaY_Ki09#qgRkWbx6Vn&tv_HZ~t`=M|r0Cv5N(vO{2J|BlBt0LO`LD7I38UrjU?TY$_r?_<=^n1QYj-ZLb!SF}dFU(Z zZruVHv)u2ahdE7t=SAeOw~zSlKAvbYTjzbCcYcz3e|7M+&J8h}B2j#Y=}i*X)vMDT zP~q8U^;^0}&%xrK-2D974^sj~CVgEYi6@)becum^D-$-f{TyiW*SCdLf~Hm1f;Lb# zm-YiE@+Xi7+lLrMk2UHy>I9yxd&tRc3=II@cRF8OyAYO!q7%*u1-2-`Q7YFutOo|o z&JXo#y5dV*gt_riKm!jSRIuyMg|;`?=>XQI)dCuQv8JtVzV2)oh{}jInKBmYR2?EPq&y5De{38{ogd$f|O&!OHCmAOJ zi4s549{L_QPvYXnV{2kYHW^+~k%Z3_fDnVzoVRR-y5BXKyLDxEjJd7BlOdTnvd5}v& zlvdTj8y7|2W^ZQp1g?Xfj48PKIWQ7dA(&>LDuUM27Z?1>GjP!NU`3`-sXfUS(^!aG z^j%K<`fQpbJwY1kJWfgU)$Jp@C*@vc4u+ z_Wm2|Zko;)R=tPeRH+@ai|1}9h9I3mF+TvzQMon1wyZ{%mX^+(3UguwlMD&Mes(7N zrW*HxDT}SUyVe6XK)40|$0K*0m?_o_tmT>7Ti$e!X_T{*qik;i{egwg6|TLWezUvX z^Kl%@_&X=b!Kx{KpHBkx4OtcR5bi^|kZm12!o;execwE-l9lyB>h8)X1pT`iLw_wu z6Y3w-Xa9<`y@|ml)qU`0^-aOMiOk|1!|-I~0@KOq)6bo_JnesDl4Zttoo=tE1)9 zEzm<}b(+25t9&)Q(;?d*lUM=Kgb2YOjfh%R>Z}Lz$WX5wjy5?RId{^f40w^I2x^x~ z2`k(&sTOZYW^`5?y#A|~S9A|*#onL=?gpt#{-UcpKTO{`KWO>=Mo>dE@)@x!hJDMf zbhWyap~m!JYrE|OqNvA_3@EYW{l3iuUEG$FU$e@%EWp@oFu4ZgELeIj$kCv@4?4A& z&tXjv7wn^w4y?zRDa|Q|7go8F*XyKV@HMv~2Bs1!Zb&`+gGg#>Yk`}FzAN4d?z45; zou1v-q2=BF<|UcwjWru9Yp?H5mYOwW(3ug>`}&K9N4>StiU>u7_-xv!zq|gKDjm`8 zS00j~D5D&ahr-ix%FKVGDWm`pRJ?l2iA=^5Zf<5)-c)jyZxXV%y1<@{Lu7?q4Z`K(p&B z(;o9|*4J^|(P0~lms$qg75cjS-Q^9KpKo2rT%Cvk%Ku(gW^5CIfWC=EL>K>E13jGY zQB;ANj>6Si3icjY#HXHE(%J71SJ!cYcb1I7E*h@(`_wZCn1;ZlSkudJ&f)g_fwFHF zPjBx?0|2a<+jHZ(>}%+($8bu-QT~B7vMT|kK_1gDRAttGCb`xb@Fhj}SMZCeOIwmq zf^?+?&!09$;n_NcSt?~zi+sK&l3Mw;WLX(po#C7dyee*nRG_%K#m6KCX&7LpiYx;t z;o*^#DFdS$&h4%%l0AEjVUJ7U@O0gvYD+AkChY9&-#)`nKtS)LE>qx#bJo&EN2rBc zCPC^0CL+BLtyg8!n~ublk5lVC(Hs0W(oqnK)#}hq|NQ(-R46*^ry)hqix)4L3D7$; zu2th9r&_Ps=3sE0C)hoG`#2_s(W&Ac{=m^X`q=RwXJ#>zpl;i-(e-=!4~es?5dGa} z#7{9N*C+hGu8;^_)rfydp*+ipiu!K&G1QVFk zfJUV|!YP?3?GMYZ`X*D@a-!F}irrUGXZDV50r@R#!=ebcDwd1_%@|`AsZ3jl@BbeA zBtSo%a;D)Crg+t-i~91Hv~`vSV;qe%XVr{#YRds=BS;SMA=l}`64;6PyXvsPTOhA~ zM5pEX*(5)e#4S_JEe#iN1&&R3Zx6tP0b@PH4|KP3>a4Fi#ALk>f_LN2Mdofml=e;X`ITP^y8Eo z48D4@szUcwdyaYK!wM-k1}Q6tvk*E8OTt{F7MCgfYiwMfxjrE`7Nd2$5OpbmRFNhs zl3o76VJP(D5AuWIM(@9NWK#Pa-(7^wWJ|cl0y+q4&fPqW`(5NHy=q==xM^dkhP%AV zD^jO-9+@v-dOj}jQfVw2;~(8)daiAC$?s zn20GZq;q$olBE|S=YNF$tOu z{4t6p%#JOcwd<|FYg{{H5qS8jiehh#e+sh{TWGRlA2gaXfTCs^f#|qA*<5yn2g64t zm2oDeAm5hxKuACl2vES$hiDMh%cZ4-xTLzwBXZzIikBwiA zqJBTZsyJ+3?ILnpp4iYg(7s;G(pP<3&=8&G+7?Yye~rv>slMdog*Wfx=zTqQf%khu z`fpuyS!E52@N*&p>46@gxvobm{Vj6ltpEHE`xQQDNGG2xzG=UEx_JZcX6jqfZj*Gc z`DC&T>CVQ9NnL@Hlnj|!4Yna?HBBzbi~e z)Qhp#rNAV`u|;4#5H$sC@fiymuJo9FVC+w$pJ-C*dYTwL0ZqMsknW-OYNST}+;gacpXv99sNdfc#eD!QbP zqC<(&FmXWLcyP1FwGN7ddU#~T9}?+)IwUf#b=NW6t#E+As|a#QojN6QG(jt){vK)D zElw{*k`_fQ9uTKK1L2(0b8BwGeQ!C|nT)m>N?G0HlhyJmMt`%@7j6Yk80Y=EK7b`9 zRq9L>@jfScF7uL13VfIeRJueUG$;y^kk>x7hMD%$aTYS!eSf1lM?Sr<9S_&(XoAnd zjA)Z21YEIfXAHD0d=#25Aq(G#YkfU1z!#)){0$ClT#EFYZdbsD6bxgs z#WSapD%C1*EeO&YlUAF*F6^_@>#}}_TlJ#kyjelPv-?O26S@oG##c>GN$y%$5S4yT zH@fG-?vzdz``xBL;p(CSfeYBoZ_Dg2=lA#gi?s^Y*;B8*v1-nHQ{85L=-=w;V02V7?MxibC}ztf>z3f#H}*>87A!y5#N{oyi#-nqZk5s#VQ6V>A6uQILj~ z(uLR(3`t=+RzwEvMzFtJTI)?tk*k;LwE4aVk1WLxN+Y{Gx z5VplP5CFay>tFA*qt10ttLLVV-s`gOzcz7?L?-_hrNtO-G*jN3$f8o|N}OTS7BzjI zjwpG1cFS#Itlpb{gz+`8hD&p?LGNJ!L6<)1h|$>b!z_n0cL&?5@D+>PYy#7owbsqN z&7BxSb}1UcQ2BXiJ3!JtG$f&KF$>;@{wy9SPqg4Bb_xpvP3*?f4sX6Fv>^B8BK=fH zdcw45&q1VPkd4wY54kA2Y8V!e#}MjK(goKRX}~E1E>E0i3|DE=UHH87`!8 zxIZ}HZjlphTcjeZJ4&!yhg35V3Cpo5;_|$>A!7@$LKISYd?RvBke~2WrgeFdsXH5pLbri;G!wb=Prxp*%0(8rC~_b$tm+*=zBIji^v7aDq~ zu4Cd1IDSBrL|fIV^E_MmPLq*le&Aa;p#banUKTeP*cgL_uLj|k5R zORnf;tu_Psi+Xddze+`5$3c9E+SOnQg+cFp;Ii zY~Wh+zMSh9HkXiS1V^{08}yc$s%xs!&ER{*9ajF3?cA%&r=k`0hHv-Ue9m9V`yQ7T z_-F*Q=ZeTKJpB!;|J9I1@~fV59q-7$0Jp6i^uk4zdn`T@7|(EpPe?}|$o)f-N`>l5 z%s&p^_*P-c%_Ge#TOn)sAN6{;x$i#qTPw`TWh%vkW?*z^=j8CqHHhKSrs%#1Mi^?XkT-(ik+`qN=ji!i@5 zy?s9e%7l#3@K{rXNFaei#@0Su!_$~_r{$>_N@F}nrXJPYshSvWRL`=rP(^)xsAp3o z!N56TZp+xqbWDr!9Qkb=po^R^q8U`bpq{esm{1RO!N$|LeCx%U9AS?0M9h|hA&(-g zEAr0EOBg+_Z`Ntt(^xpl(|4F!1?-C@t+nL>S2@NTOMqyvTfQQ1Lp7Ez|EIM8M_T=M?^A$O%fSU)A8m~-3;4!N65_uxUCP_x5Yi^Eq^QOzlcPks3Giu|S z`4lkkt^aNpq~?6cg~4ZI7t{9dE^KXz0vWiCD=I60jynNeSP$o^?IQjz!sFLCYM^+I zH(%gQYi%T5Z%im&S!J*f0If^Jam4ku??4#5o4MXTc?Gb!D>mkKcVT*&7MYI?Y1JC% zb-vpFoUGf+M8wU>wVvqx;zBNdo^qr!p7M)&P;|CYTU{Zn=>ZYu+caGOEjrt(ZE2-A zk*UG)1j47I2i8qqNE-%DZ5Yq6C1CcFE0}dy@ENbKNYQ7!vPyQ*d>+r4M{Wfswt8Ue z|CnX~8rfm?UCCn2%4tEUygd9;5a^m#Z9+c}bJ62$oWszA0#NX>Xzs~ML;KZ~n}>z_ z?XJ`4RI}PfUFDUdES^VSGOYdbc5x4V>5}Eq)8pdh89&UUB@c?mzD-%GaS`gly%)F% zZxAkwzH2xBu!noQyH44t{?5xrY(Egz{=y?}%<5Q?20l zM=2_k-%}BL3-c3}-x3TeT)2PhF&H^+_BT3lh5^po2=v$N$r z*(?YW<{H0!K$p$*kS>W!>5_5Ma-G*B+x9LHV?q2dLNIU$7|sBXR#$Z5Z`2_}he=83S{%CLZ?G2*Nm^|hXA zWzrFi1Q%IE`HXce6vDO6WQp(frvR+8^qzSA>z%1!f)-B~;v&MPG_aM~vya|JwN=H7{Q8+v7OpD=zinpJA~5$8~XPSlsL< zy%;pq_xn^=+9I}-BOUX=;2dFh6bhZt?Zw%4!d$nICGw}Rg;X5b=4SUHDGhGMxL;KP z3pg{OtW2(oWC&~z&<2sB)mgm~XHqYcj9VGZVyQ_Uj-&+)f5MMjc-w}z3b3Ef6@Q}r yo!hzBQ;L*KC(P>ri?`B?Xf($~|bAY~zi!C(|ubl`?C7$FJfK|7CICB=Zu&76=M?c6-Z)-1pm*B&@@9Bx!ptf+IZT-99-R8>_xn6J?-sXy&T;T zYp0u4z%PkFzog-5Z-cn+=E`M!-^Ctg?C8yPNsdd+-IGf~TtbRVTv9<&LP1=TOJA4k zs*y3hfDJVa#s#|qS2Om@Se`KVGGE9P-CM9Eb9f||IHSg=do`I?=#K$+Z!O!JUVHUi zvCm-XGK=rfBv(qe!L7y)e6$#)&zFxK-XDeg)(d+6R&Yhx1;jLYvHW9vfAPu430Fw!xb z<#DBm>vd^r<0b zRU@65-m>GufUNcFKLwIx5q$-?S(cXU!>SU+b2KzG=%0xTzkaDKZl6b{oll{oizqeseQ8b5J$ea){qz;`$4Q~_b8Vpj3aomj*OOqDOcxX?YE@|Rl0O`js>J< zbW^Ru-`2NtJmPs&j^$pD@4gyK6*wQ&-TmJBg(goTF%l}*I$Q5PBi?6Bjo6s@i4-LG%7_bftUOt?bSc~#*bMl(u22)qp z_scO$%(YKGA9K~4xQ;|l7&GO?+^9(Z#_4F}`*5h~vd1F5VAGw6O@Sssz17##MwQ-u zk+e`Y5(J90seNN{qTEj5 z*d2zd7;N@<#b>Zc;C-dC%3(WkKc-Sk-tUhIf>lqR?GUEhy#CfgTiif3_%v+wfJcX@ z!@Do9-C-~5>45T7@OESMsx};ah32jiqgAFRJ7JsqN|9(pm|_#@4LuxV9{ph4^U4kF z>>IqM+uQwLjn0q;G&?)w@pe=|xVnJ%Zod$?vG~7>&1;tQKcj6Y?DeG42M~;;}3t__Uu5fp|CVrcR{_6lU1eTBFa|l&1Ce>+_RhJ=%R3{v3g!~&e8%hepCbl z=4+d?cKI$`Te5ayqTJO*vxcSH!)zyb7H6%J!Ki!09k^oKij2RJ_b!5ly`Zv&8LbA* zh{(HkuKII*21$JjN!@n-2-ZdIV*y!RUWG5wWDj^1w1%37aZ~1AWtUK)h3u@J)(ng$ zl{u;*?u4ez^>?v;S_rAf?co$lCLT75No*wyR3?8=)_Y~vFI7|PpR|WVcNh?^W`Ymp z36joi$X(4hEGttF;wgWPi=ly8h%&o9(sh!LRV%_eM8=TKIy8UB&Lc@?uI3Dx4$HD; zwOWTPxqYe0S)!J$U-xoHD!RWF6=lP34-q#F;@6vk&XMNW$pV}>;S_Q^)W_*MZ+mzT z?*gLlmW2*<^ODMTuF-kVo9$j~FZ2qS2i0IKF_>C|;_L@z2CQfUbBit{C2D6&!(*D& z$ZckM!%gM`VNhG;8%1-p-gMZ?s%V7-s#P}4rPfjZhRwTe$Fvro)b{WoyTflcDEd_6 zzOrP!t4)N;*=?H`wJPRcT1MgYH0()xpE{$!01v!w$jZ`0e2G|CKYmFC%lR#WxjnN` z;u1m0=jto_)|`eN4s%~dXH)c*U2n_}U=UGhrSj~lUwAWRb_Y%jEl+lvbTx#F9zujN zuc+lBs`YJcxeTiH*$oLW9ijdP7G^?xA8LYY-iu%q%q(B-ou}7lMq-rDH7P`Jo)`;l)grwvlbLp~-!4x{HQQ`Og)DH%P z2m|BOn{Q(=j?dlr27RiCw>cRYp>AX#J93Yj;FIH}XOV*aiQ-D(zidb^jgVDu9|rFg?4 zyN$TQ?Dwo_54|_X?a^RlGVSf*+V*7i^Xe^HA`MJvG&vZv>qpa0Wo6}Jpb!q3a*;_J zS~$|7Kh3D~fG?-y5+Zb5+uxbK^l^OS=Jy%(cgXngG#i8qoVW%RHCoQ?8z}5AqZHYE z{9|g_P0d##T7!yLA?@SJ>gz2d4;!0w!c09da{sTZUbfv}i@YT3U#QMo%Zm|5aj;NIfno3eEcJlHcD zDZNhoi&l?J*8nkM49Q(ZBV530rs_IXyZ{yu@C zuQ!?u$Foti${a%$1@?tbR(kqD;ZTaBNu5PRaj{5HS#hx-LyUXFL?Yil3 zVLz!ywUmU1{+6y6g}VE11r8&b~hmuZ$NY19@`x^5_WJKP#y=jb`9Ms@YDYGP7lBbwG*rH zN>q{P&~|ofP0YS+Yv;J&AWrUnd#p(#y>iti-QyOk;CnI((E}}!E)z+PIWAq=)hH@A zwcYx}a)TL3)wUPM0v8o_)qgaH&4ZRhw=KZx5)@)DSyx%){QT!jOMn!3J=SXT%QSvq z;2zT_g^jA|pvGk)0VA`Uj9`aa|^porSp@!Wb1Y?%_E}~{1I~`W|gZtcCqUZ~08JV4`8f4g_=_y@x)>I6qt!`+5 zA8<|n*sY;OqmgJ|T5v1*FrPC=RH`#u0))1`B|KX^awODQem|BY%NTQ%xcB zm$*MHRr5cE)j$lD_XJe2l9!oTpW1yzVGl$PH{XX;Pk`FGvH45(3Nb@X1M6!D^VM#j zQp?#u#sj7h-rFJB_mXVo;tB(!R!ko#=};3pn5(O+OYjehGNF&rEG%~F-X!H#Fp1VV z>dp*|Fmyg=?|YP*;@ul}CHJH7XYW2`{UiWaxYuy+E_26x=_i44F{WP@&wP?$v358g z#pXDDsALuV+kPCoYhHUWuS}wOs)K&hZP_=NAXfh8LQWH^caH0v8ZxqSKh*n`YviRr zD=vPWH_t4Pc8PEv?b^7zmTBir-Wr_!x_o!0g$T8fWxMbr`S)zMiqh4y|Fe0J^)Y=x z+f%86dm8In){l143ocX7pt;9pmk^_$^5vR2iwPLqC^DV_W7l<_Fx=*-q(s7wEoH0c zqIN}0=L{FIiRg+t!~%9y;;kv;xV93TEohjbA+2F#nBG0ucw>#DeOgpjvw$xP0U=j4 z-_|~+J^B0%%6-j{W=Ga)GEG$$GGQ^Sg2my z^}Ab(VhTRiQ0G~+uI7X@l43Pld_0&|0zJ9yYw0rw?9OmeCv8ow%MlSinE81ykw0^6 zQZ+;7DV)}I*`Cb*Xhb0xSI`%)a_1UR$LB{io7us?`3(|tGb>l8Or>&Ku8x_bKTamf z*DSYw9W+R$7aN~GcMpdpI202^W(CBL-`=|;Zt1XhxI9FwGeM~_@+(A4{<-f88C`+Z z5X#t&qaahJzcs%M!O$Ikd$>*WVgDy4tA;s48J?jG;Ee-Hp?aTS_UqhIt<1I(?xP< z!x4OZ00@STO;CLQWt13f67s$37TBktO%R&ut6lo7?I=SzWk=aG&4wyl=JG2B+?Xx0 z?{x75GJfcq5J06mqQnn3ZN_%_z+j?|?GMzdo^PNRMY_|G$p4stee(-Rfa${7en>XJFQU~pMkGsl7qABeFT3|p=KPF9pRZpw< z>4Eyd?y-?cCMVoa%6Ek|8g|Ux%xp_V9Z&>>B#yybu5keQT&wOFMPn8I(-{Iz}FDZwKK~AyA!biDJkWg7@fhX>U1O zGP?*`@%j}b2Uf&kmq&b79IlvNB^MBNMx}0CLfKvhJ?zvSJZ$`3dBnvs%u4C|fSRJb zt-oka{qr{@WjkZoGUsF8m6-U+^uno|q-WD7o~X14wTJsQ_A___T|{2j>~U%`cd4H@ zrv%pZ)Z-0yrNd@DX(>6%tdVe>pKAzpkXioEe)>W2`aQY^px8&6g-(&u&xN$}x#Q{Bz|DDY3cQ#=EKeYfs=ZV)Uj#G9$ zetQzjj>*^|Zyq>&i|#w5HqR3Mkhm>|rq|n-ufKf26+D+s*tg8%@53Gy(3#X&)_loQ zSUl4W<8cFLGt#^$QwV-Rd z6VkuMIlcY8aP}*GqWQM0l$lAjB|u-4dBi$^poM=-b%kq#e}J6}?J0)N>$(TrZ{#!e z^7McDq#J=Ys-(Y^vSobTY0%yd{E|S!-d95M&WH+x_t_y=tD0j%Sv#(YgXZ0_c4R!i zV`I~!#zNJR;lA+6x`%J`7uMr`h^2pj2h@pkyYaSrhbGs`w0CHmb}H_}wI#$$1A;FE zq=VKBzD~DYVnttGn~|rqjmq@`_vMpjCLn?H9qAt0>KF4UP%=VJVYds{=S#Tc#umkDq+>zxev2(B<@+$!^2p_;a-BUVk5~Z^$ylSe zxDIUb+e!K}xE<{0=60u;(tco8I+}7i#Pj?5p_crkGy$;D~HC`#k>L{!oM?V z5YGbNeTHXhOAqvk;hYxIO0qE+xq_QGPwA@7Wbh6T-hG#>1>+0*nBS9aW~4J**udcc zM~ssoeuvj@O1uD)f<_<;Ic~=>nqbb#fBLeG;`p~+`?UarVM<=Vj^k{zoQ_y)Y|-?7 z0s2dBgPr7RPHGr1*pQ#lYFK*u~qyXB6lKhcw zCSL#P%({`MAf|8*=Y$IZ;twdfV`g%y3GK2B9=M(Z<*_HF=U+57HmM)Hums}N)W9MM zr3Z2Ri9XdRIws*gkl5`@r$C)PmO}(Mf+8dvPa4%DAZ@Vm&TJE zPwJ86Qm4QY&6oBfaT%Uzp-dQ;Eb0iIm!FhI`o*KM&~Y^2H;ZHB%3VKrw;2&{pp-Wz@}>5hzVSq zgcS5Q6H0)`D*+w{o8;S&GhF+Qg4?u9R}o+l6ekS^bitif5>rmYG#F`egNuAf+;ErDQb` zf_jIGqELsfl+~t09Y|-juI=*DNr=ABJN^}4=A(qNMXbae;WFdmdET$v^z8C3hQ+K| ze0=%c!MOr(QH$T|Rho>T3BCnNXZmRL*Gb=x1>}VSugeapII@=7rNH0+&2R5B$szpQNG#M|)m(XA%t{oZo9wbXd@P6+Vy4~$8b zo7972E*|!*=S%pfMe(x9gVD1HqU{5s#OlJblT+3$c;~#~z|Rzz~R~}CR^?^BgaEv8s7|RdB}Z^SVlrKB-1UVs!dEMMHP{sv07&U*Ixf3 zN}68Md=_e}O-Xc;ue-m^sKfqF3o~@xOJ{Ztj*#tl*)CI2zk^z5i`VUKt^mgcAzp<- zVeqoH8*!S;ZNAH#?YWUO>~UV7O{&1Urt~XaZKRRpr(eus1>NNJrbx3ZxEW}ske)if zz~ykirgmMs`^|qA0VB8@0YXF|?GjsP54*MWM6{JqBzd-N?mebnBxU7j%l<=r$?mSx zz(D#T(MUYYW#g+$lzFUC7{?!T0SSq zEiIiS#T1G@x8&2Yn4G5RHYG=mf9q7F%TbhXfE%7KrH(S*y#$s=-OZ5iWwKyk!dJv2 z`w?gG*CKJ>;~M=uEnbuJyBu@+C?W3DFBRAeK$}v~X+rNN}C%}D+i=~`DE7ZK- z_zi%w)N~nI+le_cs8DnCK=DhE$Ax5CPToWVW?;@yRSvGskt7%+fiQ$?=Mm8Y8b+qJ!|?FUM* zVGny0M(zWBBfe-+WVAl)KTQMXv^_jDa%|$J&j2j&u4(fJ{es$ZnlIt6wSczv7xx6r za@7+&Cy=Vi=|(CxMfY!ZMkIh;4{hJ#GFeg2u}BtK_lN!b5TN{WQLG+_SwQ4z@u{6& zU=NZdfU&6?Y2c};)bL+wdRF+#(=g9E@|!o!vBAw#373Hd=y~`hOX1^xC~C?6D}G+s zW2EuhfYlSQ>_IKWOUC?g%Ia<83>iA4SFrDL{`B*AEkn^sD!^l%+fJk`vQZ-UI}@VdSh5RQr_^3LEyuWpD1j z{YmwSHHctRJG&<6#>s|N>V#;L*+m&;q))>H2~p^}Uux%--lS`!q^;W_YNsCkCEtrw zNf9|*0^?okL@>WiA;Duox}nMJc2CDMxsiv2F^lG)nWb3!GhZ`Jao_C;Xl&BMjXZr^ zA@S2?rMEknn^dC8Xq%S-8T(3F_D>p>Yc9`){7XFZTpE+CSE=qJ_2{^>{Nl+`p$?Zf?9ge8gVnXQ|WDcm#&H5400wbTKOYJP)aRhNd!ho=f_v`MLM7 zzX`}i?;cSM_}3EZt|XEP>A0#!s~sf>rEt&I>gfr< z_Hys)vXK*v=krKt@WOVgQT8~J57HIv@aIYp#*8swBMRdon2p{)eQ-SWAj8ckuaBKkppKgD1bN12OKtVCBbvh!FP= zNUV)A3hFhUYByDN!bFKhKWn(Zm+U;TX)`a+*LQ}aXIpmnnpjhK?pQWrx#{Eum`_V0 zMd`lCc7lh`{H6nsM4JGiH_~FXBpL(AI}=*%;9h~l`bxOw9NELe;~UxBFTeHm@xg9& zGn=C)K)cl@jXI~K-dLR46T*s;C=13 zs)7(;_#ejll{xjfb9%;-D=Bi*!q}F3)Q^8FRqnFu?_3GWPnv0&Px7i?_}dGz9}gpmwr1r4 zN99Q(0i){?2S?0F0j;~x{!6H9LRWnT4X6h#9l$Pi{1%&`4j&D-792J>-SxoLxj2}P zJJ;;pGjY*^a>IBokL&F_317M7YIfHOi<&JW*nBkn&eWiaY`;{aviDH*TlB3RFQ9n_dFY>-BeR{G%YrJ8bGc5+oGZk`sdyTT$Pi7L-Jyz^r zrfBezD9=^*<=o*wH~?)l!})5wtu_U3sq~K^nseuC!y{hpc#~_JJ%&8;)kfwt^Brz) z#n_FtU_!|Ce(Cnh=m5B6HI_})(PZzt~N?I(G*iCKbsQlG2^+!s!r_`$1u z+U>|>jm0JPR^CN80_bXY#Z+yrq`b-T^Oq6FiiTU#nSG!7LGXoFf&ab5O?YSj*Y7}U z8kB9GIzC?{X8b3|cSbRG26GON9k?u`cd(=byenFsdu^f;w~ta;8jP_SSN6FjJO2Q>c~ysrU(0BXC)L>#sgpr;J^pooY4 z%3QAUT%&hK2rCA|4Xq03j=_e#yud5(ROIHyzV8sZiIR_ft%saA2%X-a7#2EVGc(uL zY7k;j>vH1ElSkHn$qc*)xUZ-Tu=`jcF1>dY3^>Tyr$R?1qLoM^9tEiNgj-pM);nIm z@KNN^pl8?NC+{%$Sq(#iF@Cp*8O3&hcfnSCQV>lo3a;Xmo?)SVl9#}SF#L;qVAH?< zM>7jy06QYWHRM~x!HI7;TT7!maN0y0(FQ6YSc|5;dVN1<6dB8Dr#|KP91_;007T*Q z+{7IBj+Od6oz&*q5CCD(WCS_o-KuT_@^L5n(4ppx(S#(Pacxr)qv6VTyy4n13ZKDy z-I7!7Q^EvSLP>#;H%5WK*7V?!Msk9{5hX0CP!$^`_K0y)Kf@NVe_y5*K4oXy%e;2SGJcXS6ti({W;#!EU z8i*OWJ2Rz-hCC5?Biz_TIp}^Jg1A8LT?7oVK?e0X4L$H@k#-6r@yqH*Bv!Tk{#AM7DVm1e-U!|lq9 z!}T$MPRw91HMzJ=?+CkYy`MiV{}<>#2G5}KGrla%RkIB8qbuAUnJgh!K7P`cqbg4R zJSq=3nx{YLIy-P1I4vCvW;-J={P1nyW8#hXE&@3u|03-_ngEnA@)afJb7-{*Sw-d0 zW~>;e1l8y-HX{qaPJ*$C0S^KLb+rdaeYG;r!+k`jKC#lU16vN-DF?G){uBNQB!wcP zZ{sk-wOwp&uEld|VwRS7IjSaHx~ShYSxuo_W+X#=c@#2Q?iui^7&z|-klhXl5w)1Q zTD5%yzo%dT*~c3{8$!l@96^1liw&&QpjUW$(D6yU-U^!OhR}!ol!zgqeyiE$6((f> z5W8H>{tg|TD9Fupjk||xGO-;h8nGC0VNs>$jV^nK_!U+8LP=J3*Pu*H4Ng4w^hwKl z^6LKoJFLQe8unqIjxK~Q`hnY+h;$G`g(7ZrKZf>EqhP$7*hL=eu31nW$-9$}S;_2F z)sr51v>!e`y2wo+aP@M|@f0_^?K_vd4Z`Z``pMIbq)&A_oMUz5leu``yx-C43CmDB zE9$KGhB}I?O`|S9Z&06P93LE02mALuh5c#tUb z)BmJxFcVrkdihNSS+k`Ck8`T26~7(WftSZQrnRIDI6VcjbLrCIBbKVqWQw{;E_3k= z_MP6o9Ig!;b3YB6`{p`mf)JH?d`E#$zRtCmO8gO|0L-UYb$lB zK?dF&st1`nqB;ku#L9QfEaXz1E9s9cwsUhHUg9lC!!}(fV?{sb-tu~n#ZfJenfHrU zTV?3jb-b;m1`;?#oUzo<4U#Q%)I1Li$hEvVjUr-a4b^tXspucf+__9GXb0t&V1i9t zb`Xp|?c~I^nL|AMf;{#)LD}e1dX*-W7Tm&7=Ca5zYo&1W^4picdB{5I$&uu#>!N@9 zBLIq8WNggpYw3a-hg!`RDTS7k@5S^p{0XDWja7I-8wu5=3kkbJ0KExpSUExDOlxBSS4Ln_Li7*2Ju zfooMt_K|axE>W#s652wiP$MfuqqaSIuYhcXyBP_yx=Qdc=@V)2!QQZAIpct2*h&NJhz!Zg6AXoyFxx_DxqRAR)(9_8?>J-(? z#j-4D8qkxfI;M=}Gss-DKnA6?@7e$^zdQ9)rXLA4QC>cYB=CWVXs(p~?!i z*7h1;g_}n7&3cl$=Gtge+|i&&r7WTPe$NwM6L?i=4MgPYC`VMESU9WiUJC!n^!oda zrL6tW%pbUvYUkqzm2doYP(4k-l0d0-s!1j3`u$<1i&%17hW!Gmx#4zOnql0i<%Ly7 z##5K&rJnR_xE>AwXlE5t{Z)`s;ev2QtvmII9TUYe#jAH|WMfX$_FV@WzlG!pvyH<@ z&vuv1$}du64-Injv0hYp3uHOFOF#{CNlCy9jX{sV=%oY7n|$|~V8asbY4TskwkP*5 zo&=er#PH2cKN~FJU$eZ?$~qF8tk37*ta(5ves427&)iuGSxORhE+U^z-H?*7H|EJN zwdhr$ zKts+QnSnn{0B~PSLdJvOQnZ*{e|tFD!otR%YhsdAX}4Q|tFyH)Q(@WLCA61+u6p3- z@p>Ie(W;M^PO>;3eR&CobK*Veq2R14a%PQhq7nI)ZG%|c*ZWt^rcI=76$8Wo-WDt? zC(8vDuPbm%+7mtwxh#ulDr|Jeb)Mb=@a~Dj{*je7Z)=V2zoznj9U}JdRUB=H4Wi`0e&op4lAZ@ zISRKW&k5hFvKSl!Qg_7I2u9G5jI%mWRk0rLe|h}=Bj8tA|7~e0F)qs9fvz%&^|6)p zCl#r!Kqk-|sh@xIn{4~#d0Fbk{iZx3&?-r!_xvOmZ^$V8QG)ybZ)s#b26QS~ta0jF zBUDL<*g+L@{=5j;tarJ16jF(G*%uOL)cN=r7)QI3*|gQ!oi6mr3tknJP9(4lJHsrY zHP7esK;pG|3lMvm{OYKTagq_VQ%O5cktnR5R=kIe3)+!~4WhtLRry=DU^9-;Ub>M%lLIE79&U0zCptdU_^e;MJCiLDE`2P z0!$(z4qDxA=5_tNhLlT-`roHg20kEl8g!i4k%LhCxel@s|FVOH0RYF%QG=*3MIW&; zY8Eg#*dqkjEYA0FHmgk;2yGjt&5Rb)& zs7Ek`CDka00tdOU*T?06IaYJz_RGGo{K3d*XnICLUuO6Uz}#>C!!`;#0o(9o0&RqK z{*ev5^VN$tAPrg49c~r0d9Y$xehtWt<$E1Gk^KXztNtenn|i099Ld5sSUNSHbd9_|>-s zB#t@#%y`T?h^^DG|E+1>oqD%{7&SdCe!RiR310Uou06c>cdN@?f%Pa$J1l~_MAsfr z%oqQI?-`(NaR-P9AYl1}@$Vwe-ojph$9Y`!nC@%+(X5m0N?Q}Au^jIb=M<+yPP1aI6%Fq+|3EL4_7W2HmTP7frHUR|Oqc8fnfw{|2Iv zykK0R&QEH6Ff5MB%lwZ~SNus$3Jr7QL$x{r=$r2(?C-d6fAC=quL4*;JCXe$;;=Tl zbj~{sFz^;t21cJLuR&r>TF`q%f2D#aajvwv`HEd{a$J~dQwKh z5y-y7AKHkmD;=KNh&zQ@f026n7|Tx7526Nc19ju8yt$O`w~k6?K&yrjEj~}VGR>9d z_~_&ijhhU#bo)Pp;P&RGS)eTquuJ5^_&dQA1EDvqKQ|W(x(0ZE=DNDO%^5!q(>YrW zOCKb$MM859bm8geMKy>%P`pi>EBgOTKv5*PynzY2W$91 zYu8z5=*7X%3m3Br&nK=vBq7zCy~6~ev|BoGZGjpTBVIG&mXe>cOpxSJ24&)6&ijHUC_W>OHrMs zP9u5(WIRwC=L--zkr9i`z2WaY$y*J-u6vZwv6^`1rZZcaLuvf?TG3=F+FyVFJ-BeP z%TIUxD@IkU=n9XD#=BWyl@D{O(^8P**LbUtLKS@`+5(jGFI_^hSHkNx79I)a=Dcj4 z22wc?3JWZ{vj7o;@K-O$t$oM5{ipG4b$fYvac*PJ!3Tm?=OpoHn~L#iS}g1gkKxgZ zB$ct>nQ{tQ*vG#ozIGyRM2jI$==tQ<1jL;{WCC(;q>mcmJ_2-SnM}WM4llsfB7BM~ zzT92Rc>7D;aFa*yD$`R^rWB(@ZVi|qBwXk}iFM9g`32;Z3-kbx{$wOQRR8pX1#YpF zCrkgY&1ZAu9P|F4Y4)0$sTF~}KOt!?ANn`@y#TV`u~tW#+N)QAYGx-3C?th=-K!jN zrTl=V(z;7Rbbgw3tNYY+e>szdeQm*m9Fm>xII*+VjwhUB*w=B#|?YSCDh~7keb0zT8WZo!~&Co!Fos|zoR*^O9 zCw}{Yw`TaH#iE1ursZAuiIYgwm68L3=sgAhW1Zo?+l+~F{(ne#$h+pP8FQxk-W!3S zn4y23?6$u^DknJW!AbPqJPwN92Q)i&=UaBEYfaXe`V{Ux0YTXH(jXiEl#$=e7n>@O z+YU=?>a_nk{&dB>Et*x%;MA$@sV^uNc8=mm_*stJyO^csR!dZDVRC4!1dkyBfD|W0 zahWPRCK2no7uW__8rb%F_{tx_^RHg_EoMDfeY6Th7x;i>;OZOPy^v3w>U=4oANI>v z0w4u>*( zQ443rGct?KVcWexvlDu7Rj)MNRZ|-}pNO50X!7iE7rq@6>vfW}A&Tz}UgF{rKJ#NM z#vAriOa6|ZO3}P{MCjv@jqSySnCzqY)m^9;&alRq)z`OyJKKO@&{vo?0_*`vPg3yR zYDlT*1Owl~^WqX|WG^)y_De(qV{NZeDw^GUZEffCZai}!HlMQyP=#&!uIUc3qk;9q z@0g2EAA3xA;cM>ASuH6VX}Z7RK5(w)M+^pvLOm1EyZd|bT-MuC#7_ZkPlk#`BE6Lz zEQ<^6-|S@sFMx66JrA9WJ{4OyG*T?k2t|5(lYF##XmkEry`j4t*a-BuCnQ>f+rV*z zv|ApzAXV}&iic8b0U-AjY%hB}Odw@I+1g+NNL1!=+=Af1*$Je_OW@78ZG5^zK8#<2 z+jS6URy(1SvNeT4{VhmS-04FRUWK@>Rz9!lbqIeULH~bI*WFO zc6(M9_OnUsZY_P#g#gwmqb=Nl)4|~GXgw#G?xal6>){9Za}UH<7OFz6tCaTnB53=H zzY72B{O%;Wb`dn}q1}8=cGoX(UC7_CD9KiRQ;_r0jjHUqE%NI9@1MMzL1GJ>#F=xi z2nZ2ZYGzfmKRJ67`1|O^s^-5PjaKmu9CR0E0ahz_>*jZ06ds+NLL50NdxtjoaMXP0 zcA(+N;}mP=qqX&@)+R&tMxtYl+e&xOkA{W#B$02)-+uDioKtuxs^nNBkwehTGK zGN_D?98!=1tcgKlLf=FzP#MpveT(%er?-s4?7ex$JKRmbF&4KK3{IL!PnUKAxH%)) zyiLQ-Kh{=lC~52_{q!^}5LI_^{<$ZUO2vch514G{EodOWn+D&9#&9EaymED9Q5KT- z!9d0X4F?=pV?bA+>OuNUU4I7v8e5ygGKYBXXF9VrtoLC7H0+T878U{;!gN_$W7~vB zp0Y<;-^njE^AGBM(M14~4S~slXF)og&^V>s@~{EgT3N>_zs+T#i)C&T%0V%P+Z$0AA@(!q%fEUNZb-rA|Y-KV_y`DgJz8X3oWkyz2r8)&hUt|xRdL(OpC8hHpYO%a#utmF9{wj zbPm1AhO{gZcVLAN0XqWKTbT6ZSF8(G3rgAj04pKkDYm^I&pHZbxYCg1(zIv;X7#Ch zZ?cWOPttNtw0UQCTwU~uo-`Lh@GIN7|q6Y`|OdL%AvH%(8 zXgg^@p{zM@FaClA$9`zHQ(TJ1?DdspcNh(t`;u6C=qWPU;ZG~y%mjvMAt7ZHhB|w{ zBmv{D?_ndX;hoL&VdV}usW=F*9ziMtKACk4883L$hou24Xn-1+vA9F*{pD8@d&_7R z*W|l+p9vr{kbi}<1G|b~U`AiLU<9Wda}UCh3?M6P1CIoUfQy!0S{Lx_K^|&A1LdtW z>|&IW8>-Dm*kfvzVUVS@urLFsu;2{CiR=~hz#x0D-{uO8Zpr^a=8h1E9!UN;n&Rgn z7hChScN#sq2?nqo${`*+h#`ZHi>h=wYli%)Io8aeL!)1Pfw{s@gUMU^yNoYE%h+f# zgS9in-{Vxs;S4$n{QXt=R|iLUqY|8WKq`C$IeZwvfo}I`-m9OSmb^^)_uQZtbb;1i z3kx29=B|um2XS%4idaJZf2gt(@*BNCn&O22jwYKA+*)wua^mB=>eB3!bGi@x06Yv3 zU7_=?CzjSg;y%duQBm36zkgO(SQx3&-zRzI5pl7{j|VO%uHqvwEG75_mC$uxv`dhK z{empD^f^dO-#K;$0RYmp#wjicRhQ7Vhijc=LV#}9@a*459uzj;jOfn}{B!ncccXRU zoH}X#FyH4@tOpGLX#qvYVn-Z>>m+wrU168S8>8%;op2T#gfw`i`|vxpyx9rVa^74S z3_An-oY$$U)$B4CL@%m80n(u%K{tQoXEg)$vl5je_uxR@gPnT7?>6U|4<>kE=*WCEYogyY;5hP$h7kTbEoW_WeaJkR})HGwzj{%SPuYHTKtaT@V zEdrb4<6oq{;0R7TfK#IpR|hU?A>@WmqLs4r=xN%Lb_3&x{?|W+emcfLX&{7Ebi7O)>TPh;@MN1oS z@qxD>2yKow^HCfBta5Ur3%SoIb3FI=0ILr*nxPysBOQ zJYZh$0H_N%((JhJ3c3Wm5h@`!U%q_#DUvgIxSzTn^^Ar+EAU)vl*3IZz2uZ-Ta8lP zGzTXaqA`W70zTlZ-$^LOdyblAPXQuDcHE$R95m^ew}&s`R+?*0a{Y1kDcbe-X* zJn}xq4%&H+oNYi5@RS2CQA35%iKNt?GU@i)>g3^Dz{3*^3!k^JuxR`C&Co~#6RihM zd5WIc#c2U?V8!=({$~$e*YX19-I6wfEt=&%Lf`Vz`Gp-``7~y$F`EC=gNi%AHEn_+ z$uJ9C^PGu^$?f1QEgpr~jPI1eBX{A%1`cxk(0glx6c}J&89pv|uU}w;dk?_lKvF{W zG_Z<*F{f`=VG=Jd^EB@TKw2OiZivrJ;G1a%{O>_rF4W}j0csW)*h^2x67K5bY`5fl zLuZNVUU%l)(Ossv{2$+#)^LLmgb9CI9-vAB&QT=4Ju^*zxwfu%xanCUtQpopx7k_U zss*Y|;-JOw;0Jdyda#gbgov3Xo}fVdPu=)J%lXebKbW-uBcSyp`sWpKmF%-OpAEtj zfb3yzr^pP8$YoA7QJLHWre5}s|NrTiG{7@NW&)ri11>rDx~V82YryV0DWR1?DTtLu zXSnl{JzU$rs%aOYwbSQSarW;=hm5BpF!DX`HrD3>0~0N+T*jl5Wr8MvJ?f27T{x6tT5{9ZamD2d-G7w z6Y07dKO7A#&iDQsEK7^jPtzFB_MT3GopT~N-%D0j6@&VvrMAgcT5(u$6@Mg5j@Kv? zn~-54I}sg!a;&n4B4|E#+N6qsdBH>q0RL^}hX}+LZ_OCRl^GdwG*>Dp6g^_i&LhwFsId3=)egZxUd zu6iGB&#Qm_^Y1jMQv{I0hze`nuf_wdQTqA9GR=i?bqzzwkl9>v<~+}* zH0;okK~K*=IES^#yW{nnN);ivh4uBXGx?>(PaRWSZn2EG1f;RNN6XYpW{U1=I51en z3aI6=rlz#dl@vU_lLRApLitpQ;>j2Caw^t2`^UOOitb|APYo~Mi)U5kO+Fv2W(#;5 z({SDh_4#J8VbsORTS{~C4+SfX8MDZ`z5L`4gRPc-WWU9xl)QM;bhvRaCRKv@c@kpz zQ_QP+zZ@0XWlk9hA)oH9)lboss7rH6(UczN=YlmOyQMb75f|kBUji0bUXD}O(A>2# zjj2G*o?Yo>H$f!6xu+65v~}3pCi$A4eQM;WfBkKu1^oU>LC{nj1l>dgw5-g~YI78` z=hS^`Ezt&YxQ?GGd}$JIF-#$3hNsog%kp8Xj+h+{?AHb44)vV?W?_Xcmx8k6Z(HNV zs9AycZ>LAFBQb9wj}=w%eY-IwBbqtF)rffg@DWH)*8F&F4mFIIR<#28L3Rp8cK?+Mtlw2=EoBO-%CkSFf^4z!0>v zUPd>a^Ta)aE_;5k{7pMHI9Q)4tdQSYy8y*2l7c<{V1+sw!4{TX=5TmlyPi_ebl?B$ z34xQkLSBPT?wPll3`Meuf8|C*-qh?Q7MabDfVr!Mu-F|eX@;>5@-BeaUPQkjub8x6 zX{}9~l*Mh@KE0?zA%zH;dd>!;rVA+CE*~$qH78T2;T7%R;KlYaeSQ{jSa(BwchKQ= zLiblIaiwcgoM|Qq_Y2VJu8yeRx3{k5OS}!BMnB@`4kOwTR`~K7Mex&K_`ZMe|HIZ> zhgFrmf1p@|fPgee3n)k*Lb^c|1Zg;Q3L?@-N;il|NOMrSI|L*oM1>;=NJ`0}yX&rf zaOOL|d++n`JoCrQ?6ddUYrX4J@7kNH6cct14D7<89&@pugSwB#jo{dL#fa<-!o#}o zUtQdX!e8`W86Y2n++DpLu+jUpTewAM(Nl?v^-a#x;1F=b$+zMNrQJI0y^K93AId4z zehz}3BF&0T82BXp?Couahr+?Hz?!fN-~{Is%-G}g)uC~IXOKB5%*lZPd7!VapOQq_ zz~s<%fW?xzkG=xcYi%}R(T2J*?Nm!wGIH`aW0(f;Bx~`xi=X#=(l{ZI<^kTE2@FXA zE+8YGk&#D8RaS!PetO+;HE;SQ37cWZ0CzGejqHsLMY)i=n~p6Av&%VQ)D40;<6YOF zOJ3Z_N0rNa?Ut3{(H>3Tq2&O}2QTR7OxyBm*;Bc$3PUqFtk`xP9IGRdtDZSACURKF*XTKEDTmeH@0oO+ zZno4c6|BHaBR z8R3S$r>m`84`3Fe<#mLwc6>|+wJF{uule=t@w_k9$T}~AE!n;f`K1fD)c0H4Ms3fqq`6oi&YE=3dldJI@>{}D5Rr~b61#{Lh1-wzN0Edfl3S;c+ z>pTBA=2x=(+TzznSVKwsI$fK-L0HasRbW2`y`a+Tw}i<=vns;^=BaNYr{a0ANU2RF zgw*wvHB2k9tZcY10~1m*ap?vlZyD1STswO1U&IxRxfp#luU>c#YL|b&!Ety>a49Q$ zbk@Am$XYcp8ZkK~d+a|bDMOH%xqU49@S$C33!hKz4P@qt4ep151^hl2=E#A0tl$L) zI|90E+70RPmWf2AKj|eJL^jZotQC|n5&j5xUJY1mW6s^cwK8?2i2x~0kcYX0iOv3W z>~`9Mp@kflT8s{ohYD1?K#jGRZTCe#$?kyPm1Z;3-~M#_gb-TIQRtV`{SYs}`jdx) zNj=RCV=$33Ys}a0ai(U5M~APq%Zr3r z)c0>YQG2WKvA*YZtsXf$2d_cDO3)3I|B{Nzy8a?WyA8Uygoaw{JPJU$Hri3jYqOCm zaDh`t7+|mR@v<&S-YrT|k-PF~SL?^l$;M2Z`}8uC)z1!5CGx4obAMUT`J7ht)RYN5 z_h)|3w1HnPA(PRok#M0VISoR94W&_UWf8VR!D)O;`-s5PxBOK%r$_{@J#&VjXr&&! z&S%eb$_+voOF>Tw@mI88fVF4so+B2x7CLqC3EFbZbW6*@j%bpu1IL#1m^v{aoy{S} z<4W3@rPE$6*G`VV6#!aG98<<3a0PvL$giMJnCZUJOAnPAYuL)Uv8-$-g*07!-8S{W zwn*}!{>s47K)y9tg!g|ZOo8o0L`J7$!MIwE%Nr?GK0MGB9X^Cqik{U$n&9RldhE2& z8_p{iIfd;HbUQBSXno_{;o)J1zL?^$3pNA&g9#^FaQTgh_9vpL&|tXp@ols+MZ zmu&GK!OT&8kH6zCDl5KbFf-(wDgPYtqVfrTihPzM`9sHRq+(y6qNKj%5%%(SXxiV~ zf4|8@E{KF5Vh$SbOI)En_78pNb9;G$H8)`O`t9?ZYdsU^EhSy#M8`7~7b#5P?^MSo}XNR)6U z`c;E26UHB9OmBv!UKSm@+%{p{ zY}WtqUUYiuO1Y_rzm?q>JsuB$0IDqAA3Y@_7^=jSHnXxxX{P0OW#zDPK?6a1cr>zL zNt|RCgVvTvRu)$Z*@1vd>--=jq@uNDz&M`Xegl_+kIE?KN!Z{Ewwzn(;R!*J9vh1tR1kDp2m^#nc2c5-lqPNCr5dLckuU~* zY0#!3ZdSo@^dljK^c`_~8=k>kdXg-fLDySrZ&>!hwJ!h_Y;9IM*2&;6A_BQdLhlXp zICS+$>mc-a5uoM#)r??YmI8w?FA@AUsNHHYq7`+7jXz$Hk?-l)5s`Ade}DRP)y}T7 zVhsFxR*^*UZ=p$M{8uJB+@P?*$?hg%7W~EkR5{J+Gp>zMTD@ME3y>6jJ&Xu7ur}~M zltrWV#0I*?kqs@%)w2jg(Szgvmf~X{*#SlKCN&BAl8}k>+aC4=MhUpqD4)4ezPu5< zm?+xX;%nu_*N8}z?B{nHEI)n!+uGXTMs6<+MVWxrx^bVeU;R_|>S}G4NYH>RP^^0Y|Xi zw@Hbyys~{UZ9`lphIlN3?E1QXvemvJ1@CKHb#tpmDd|&6;`SbAN~^WORzY)&$y}$I zrJewffhPPH_Q9I{aLz=mQxaL?D26JLHV}}5UHWtZ-Cqx7aI!?q)6tI$jb`Wwoy(sm zG9}B`o=CpjTBhxYC+vvsjW~VwNRCSp|Ek=8EA|Akzc_b*y@8-n4-Y5*naIbrg0982 zr#TP;V}BiT=#*i+R@jHv*Mip>o7QCPo^CDP@z@3^t13{6HdY<;24YpiS%WQJN&+7# zYl^)}`=RW)FeyI9u>OPyf!}F9ihL6m37{tOH$bbAdDaXJ@v*jjJ3Aj=5M*uDkad)h ziJ&rA+@9L6fu#ZGhal(z9ZPz75sLeXA}6A1Z{PyW4o-KoNP!J3?QM^FSwq7Y!cn{_j3L|2hD*5YP0D$GG3 zRNNbWLw|>kOdcBS0d3!>9?vzAn+u<(DAJ2Fn!3ZG_9&_(CMlS)0faqa%EAmg)waX( z-lTmG$9c}OaLNqf?sXUV(+S+st~{J(6;`g^!R3)6zxFWECc@A&3oCxO4LiK4^$6UQ zNksD#0DeBt%1ghyATwW3w9#kiKM3j08E(+Tq>Jnh-jkO z>L|&OO*k6ls9zP=*1ZqOBZtFB0%RDTe~6(!Ec3}Q8t?|=;U_NmE4x&qzV7wKt0twn zK+@SW?t~N1YdOIAGm$K%CfH&gV4(?XA*V~pV@JK+=RPJUEdWGq_^gL;xqb1zt0v&n zX4slcSG4r;GzzD0YdMd!0SYZp_%G>rAsUMLs!41+j0#8uiQIv-bShfT9a{vTU=_8T z?Lh(nOYKQ|9*R&~dQIC|NYxJ6-(`F~jg+Pa0;Au+2~_`Fj4`+VCeS7;pPnVisK~{U zgNt#s=b<6~WEsLtsBM;)NVx{8pWkfQjvyUk;o_-OoH#GTAFb5xC2{ z4JjGv-TaHrREeAhrr2URn8m2NObPsoMonju?=3td*TQll>x3r&_z(-SpfJeS82@-Vc9udqMuL@1n3MK;c8s>O2JtpT znqv>VuyN0WB|Ri~me`$1Nz5oL!9_U013ssA{(oJ~@AUc&^q{?e&`RjxIFgUzP6-z` zL^^n}L6ld_R8GO(1J5A<%rNh-XNQgrV`N}4)L!grQMkhZ_%|Q|43ID!3hBqRh2hZz zdVk`gLdeO#+mDMnKs)P`uH)?b=97npSw3E(TZzu6LE zX{$=z;C^D+|3UhVd)G<1W}Z@bdtHbORm?I)SPI?|trnn4e^ld_o(&+SnPUNX{TrL` z#bi(Aev1aydBe*^sLXO_p}@1bxX1F|G)rnHome>w;MaORRx=UVV>8lFIY1>$5tGsY zet-;*{tk1}*g0!bmFTFMz3S)i~&*9<46nOL>qdH+6n_evwhZCS(DREmlgbNuA&3Uy%X0JCyz z91g#zT@`2^>7|qL=r2;=w!c8?f`@TWV22dao+0CRvf|H$& zD(G)!+V~e^hq9vbf$TBL=~;L<*`Ikv*J_IEM}!I7Z|W&YO?89omZHdQtxvi?E5o## zFY%9@${lny)6cx2>+#s{Su}3E+|v^1>A1h1zjMH7Y6N#hA9*mxA(M77Ftg+JPIy^j z9bi~?UEP0!BE8hgVIP=2L(UiN^AYZOKFgsPGRbUd=3tWDM|dBtg_RY*%xoNEf~NnU zy_vQjqmPf#x%!u5{Q=gX=)um0hK64EEl^5(hW?}Df%P=v5h3ADv@7kk78T_C;}}Ol z!VtYp+qp?#$@ykku&&VBU;|M^AH1;Vj^I54ZSX>B{Aic=^A=4*iA;h8Hu5x=NXxnZ zjs-8f%H`RAvH+BW%PztFwC_pi8Vr#{cN6K!1r6#YViz=+jkEBtMo!)3C%OeF9OTvl z!ch2}iE}mU8l~pM*}ig`A$okQ~eXBj+TE9v{pAP8NvlnY3*zPtllEyLu*YC9F zY0DHf%^TPm*e2(DQztig>(%_<2lhu&w8S^#Q|3Nu%OHe33q8fje32cl^lT5c013ax zAFJxPZ@;?svz$Qpr*~4kjkS!AaP>HIM_Rni$e?MB#2Uc&as-v+9+#nV9CjhxjL07u zJ_6fNK>@({!HjV|#x5?TMm~r0d8N`agbn9+PpT2qFICiE+bZDqWvde8AWnBphe6WX zx$|A`P2~W6pG?t17x;`4wrSTd^8Rf-ieAS{xKGS{g-1JQ+MXj2K~->RJZZOvdf z(6oZ)t3WqMPbWm+UQibrrs6*sd&`1FY{H|f0zjPRx3#tHwydo4KHh_#d`=dvxIu;D z(?e1kpu4T)Es1Nm&|PpRo_as4Ink5L{S4U~x8c#@WC?TE$>wj8WHFTnsST5g{*bno zo-u8E0LuoNGJJjyUBd|llE))@UTd^Bgy=1I&Lv@ zS#1y}IeuNTMaSu6c8!bj8RMP3LMqqlI|*|JfwII-Pe>i|9S9+k0w`d+RZRZ?zoKu- ztzG`^_WvVI#XU?GnSoexiL;n(AR=_w<~7{}%|SZQKViQ*8AI0~DJ>Exy-(jg!rb*p zW7v7SJvr;5i{aW0?bSP-3%{yN^T?cQML6$APXTJayS)2wRRwF;(g} zd$Z7EFi77zSwb<3*oF0q$=HRhjln48Yh2eZfm7~kT0goRcX=y^vh|2Kw;>w_zw-oS%wws<-(lar5D4*t=A)w4a}#MeM> z>J^&nAk~r$02BgQ+_%(?8H#!w+stxNoxkm!J}kzg0eyIH;^B~_Fk6Fn-_A+&khkAs z1wG$UENU(<@0pJ;&Z3&vmpph`|mL5g@9v+(j%ew&6 zKJJc*A^(vfe^nR1w{u=r)!930M#j7-c1@H7dlZN$n*4w19{}YiS$Z&0-;*!93XC7 zOi~$`E>J2nTYjP^`I}l_JCCzo^(mN`?}t78_DX3-qHl>l{lifAn)Ozc0a|$W%vsp= zm~eDVM%6t`z@C# zF5-|-BHseP?>?zAm_ALNyZ~og4tV_tP)80%R9EwxSL$-I-d0yKnE?1lJ%u%3wYb)2 zba)~(=S?D;@S_|A`Fl(%kIV(ahD6nR#BqQBm02UCR1J7R0L7rayeh=(g_(!;cGz!| ztLe?|%YYRC!z=vR4tlpqT{#|rNKTceT)%=Zj2D7?1!Wr$V&Lv+i)Jy!9uROj`3Q9B|-_lv7-3l30_vd z72qoH!F}J2t>Fm8RdG>AE#X@4kN-~2!8N4ZXlUHAt8?~ZR1fo4R_NTz%zwf~K1@j%=f3;LVMJUG+K8=EVdHQ92Ty zv4E(^%Bq_(`a=-WyszGA;q^DmU%1NAVURj6ntS(RTb{f1_#Q~MI)2xP(uib1G_|q& z9T5TvW4r_X^mBn>I1uFqQz7*^v|BH1<7M?Ygo(89h@EG~bBkF4123S)++M?3^zAE; z^Vw#zsr5%PxuqIlUH$bc0xm!g!rvN@DossF`N#Q>SlS7b;bysrS>TqsyM6?rJG6=A zF&7^my<+U=A+z7_b)j4^9O(vG{c>9ASRc+0$5Ql z?>js#ZEc6ct$8)0AW@aOMNCj3=YbF+&~b&VM=*VBi6uX*VR!lQPmm2L>&l^PR*eQ!M}9y?jgI$d!~R7 z_gr4tW9p+-dY(48yx;|s+_hx{z-44?j1P=*NbQG##el!^3QP{X?2_8{8g}6Z4o)~^ zLUJm?EIJlWHT5IoiwI1+{y1+FOSOh+^MXk{Cs0dH4j>UwbW>Oa&}Hs~`k9KH=kSMz ziC|JtN)Pnk*ZoJMnDJWXINOjjPXQir$-ck@4RFR6PkkrClYTef;Bq!3@Y}OmhQyg9 zVA~A$8Lk{d@jzHJi!jg#x}5cZT`Z6??INg&$KB?NL67V5Z5Tb`T4KJCjZ9s9)Td^9H2Pg=uSUNLg^L6CLh?hjhpJq3`M-CJ(M#inAFoJ)@gJ5TBM|E(sG0`h0@#44d%Q{!Q%f8a%!=UK_TqY{Ce{ISmCc%y9A}?d&T2J(uW!0iJSETs;^d zH`Hq|k>YL6)7KW1(#~A?gE0JXgyb6*akmUT$n2Q!1zR!l(uV`W;yK zdQO)N`E3~)2{ZT&jHR@{g5{_t+m|I4zW;^@0wsilrw2~US#RAIcVr}yynkVsuP zHmDoc#>91XWeu}kYXSG)r%#9-@QbJ;@tgLq$DlRi8VUT>_;d?S&Z;1wPt-_}kzYpV zXApO%-_eg2AV95PRToa{Tv}o)F=!N6DkOCIKr*BZ4DmmtG-zyMQq^L((opvr@;<@} zhZxrCUhXtfypr)odV?crW_~H%D80HQ0~~fo;tSD`CLIUicUq=90Bhg&XnKDCzVht+ zj}H$4@93U)1Op$Nbr41HsLv_cRG74>Xt?avsj%N+R0`{Nw{%a^Z_buw4{s_HZPr&Z zta0C3j}Xv@Q;;-0u3M2fMXo*Gbjgkq)jEI z`}Qj(rPGz5gqrIJf#Rt4n57B?fwxI-e_x^Jt)(NQ(sYI>Yr|>jx*{`{GCu$je`ipU zyQ%K931H*cCUr@w12Alc-`mPV1bG82aXp!arF?-oVGM#wIY42_%sF;YS~@dLqN6&w z?2h+gc}Duerp)Z^fDxs^oPVlz3#pO3=%vEQmyU}bM>Uf6ZLPvnCU z?DZcIv3fkBTuZzOLE*2g-Na&~MNGpfFOvj-MmM4BZIV@&d}bL&;5N+@F8>L zjVmttJI?rj)dS7$Y~W-n<@QmhFDp^x_7dRr^yI!KU~Ty9S=N2kF~DA z8K(ZQ%fV@reJU#iynvtpuXnT<)aDtqhGjmbYPS}adj6LFE(46IlmC`ocQ615g#N+! zM1kX@0r$)Y1CZH$F_8ZlCn;OA()~%A8k=H0hC;jA3j_QeKD+5C^6K|HUX`B4qzEw<$D<_AS6ROna!a_4Ct#3rL25soTM_5({GMw=;tLw@VVyCXid z-#D+WpQDbfHOt-5n~t7-2_I`$0QbcUC@IK_F)}8rrsE?-K+H)O$s_(_5oYLfXaR3@ z#s7@heDlTu3|sOy7Qny&yJuZqyb6?0Wdq7QM7Hyh=o`VaR-_2=OD)ahynK|(!AEx= zY9;IQ?_)-szc(#!i4^jBVQ3tv4V+>tu_@_Y<>dXbOj;R^I5q& zOLy?i!{C@Ov`d~yjX6d-5Pkz~;V82_#zF#pLnOxJwUEbubp_K0Z*EtO*;yxJDi8Eq z!w&p0X?P;TqyKyn1j3j3!0ktJ8TEDEgyIY9%&L>gt>4oq-wH6Q+VYmMUt;k4Bu%V5 z5rWSFj9C(*@+rS2Msh+TyQ_iG1>&C?T}CQJ4JNH2wSjn~?tcGF+uMe3XxKzMy9hqO zkYQL|fHDph(z_5EZjH?cPFN=gYb`HcF0!obDYzjFq3rKydJBuVPIQ2)wANJ$$5#%hR9AQXK0=->39DfGKn6<%5v6#xS_D;L#K<-|pTPpYzy# zwl-&Bc+BK2Y}U;j#8QR^J8+FMgt-1nJ}HpeWXMG(|0h{7^;hfA>g@uNy~#Avf}g5< zN$w>maj%IR*;&Ws##_-5`I#|Cm*Zs4O-u&0=?S(M#HGw@Jx?()yeK1?L_AwJM3G*h z5*ksq$Fwb5r+(;<3%2uGn zr9e9x9`~j1VKezz{|jX?+n&Cn5mn2)1YQx5fY;Qb@M^ zn5U?z*;|&JdI2$6cmvl|Nj@x>4llbjmq}qs?@I)=Sc>+Bc z64;^YpZ=M31Bz_;H1Lxb3XLd0Re2L}r})(QH}rwi*y9|w(3%32Do6=d^@36W!RFOb z5CX6;){4N<)Re1-|5?B5|3pVHEgbVJyD&m^lX0*8z0TPsfXXp%iwhDsOe6?Z27vb^ zCc%|DE|Xp5>*m0G)kJL(+{#J>rVgKJT=SE8pucfaITKQ8$?t-51q72Z=zV6d3~Z<7B&o=8EmsGGM?Xia zk%Iw1)y8|$a|t8L6!m)@c)vnF$i)`HZ&HIegff~H$f~1B0Y$vi!gsKjt2lG*H~{2B zgO`niansGm%;QXo-Na)uAGI+Ig=(q#?~svy&)~QsImNJpqniQle4~o1!9Mj)Iu&G< zpu?SrMS*zqbO$a+f4}Ypqe{P?bqRd?^AmUSil#H%o*BOnRHnI14ocIBy5%YS^3S7^ z49?t!5}UTbCP?TjM2Q38<^8<)75UOfBz&s1K|mK&e$K`DaeIPp-&+t8=cY6;kr-vQ zwN@U$Zdw471j7-$qgWu{Jz_7KHaTNi(}UTmD;+BB{n2m*CY(jaL+F6T#g z|4BV0ad2LRp5?uohBF>w^h0<%@FP9^)sZz2#k?Tc15XPAKz^pKkXYKN+3V$?wu2`3 z$kbb1X#SMmC2cs*e=4W&R|^Mz-YsqAuTEe`DXtWi5KK;F zX-&Er#o^I@4hZ)GYu{>qC_?aGcP`Fq=^}Io{4ZP$hI0xoE#t|Rg1N^NnXYo7 zd$9VQ?9M#EVj`f;S^@p!#N2SS>o*M?C^g*8ye`vnRrqCB-u!g2wmg?`TXCw{?#4N}i0{j0z{K+hmoE&r3Wh{o~%ZxPFBNESPTZ)?(`FC41 zVY2q%4iygsFRs^oZ|Y0}1VgC7S91!5a}-f$xqnT{ZvZ+k)N6x>Hjk?l4kWC7T6B0R96r$3S%y2WmKAo*?{-g^BC}hU+>Y_fPT%2SfS;_GIb0CQ*xTpkSdB zfGJhY5~NT*xHW2artSCFo}l-Z9r67y*n~d<@#Mlt2OImc71y3O6e4uI5r8rSQ%FP8 zLdac_C9W0F6;7jO(WS!3)V_t2v3j6!5P$$lLmeS^DJoPNq$Xn3;d*e2)O<$XVc*x< zt2{d5aAY|>e}6yaBe&1tH^x938EwM-Yo;Q9Q^>lRXd=~0hjo#g9sdv_+emy?4@8U^ zg_zikpg6Z!-_!7m{BP<}HvS2RT2QoxuZOb^({6mp3;ML@)^Sa0a&9(a{vh#r;*oEMkaM zo7l`&!!tR1R==59}=|?5O zRu6{@eKTJPtbK^;DDAKEOraIuH6KOOy~b5Q$7WSM}tk1fueMuL_Q?W z)7!WCr4db(Ctn`wyLMFn&W|%2TWI+MCx6<_RRVSqq(>m%EG#VeiZ4BkECdNzz3P6O z>dZUWZ$E9=I#J=;nL0n6iaBC4Q+RW`mz)Rl=Q9C@z!x9lk~;&&pCA>BDbmSZD0`*l zB&!i?tPyI0`$eV*rlGGSnnF!sAea~<1%G~&dNPzQ-4##t=B+^l&XAt>#l{ouO zH^Uku-HR~~krRIF(D~U-?@F##6BMC@fLRATMZ7Y>(J>$s0_F7Aj5L_4veCcZ&}4*{ ztR0je8<&(eTQ@Q~DFcf68@Xe|4di|%fg9$%R9{{)l^}u5yCIkW&cIUE~@5#J& zb7$v5$fWM3xkJ|S$N!WID6jFKW{uepsVaQ1hwgf;OVFz@?n#gFef@&R$+J_l5xhyD zit(a}M*accjRa2Au~ZH4AVBguZ2Pa&KhPEgis)-_%JR(D=wj{$tungcz6=ht{nlFr zUH(>^5%1F1NBI7!DUde(FNiV&cLBA(+(+jcgJZx=Kr(gYo(Bc^6gXNq95Wx{Sc8E( z;e?_i0A!jSVi~Xt*G$f|(K718b>KP^n-E{`AhS)9&=%X+E+ah4Nd8Nw6&gQ`A$5TiHHS(I6U}G41akkzA4L#G z{}Ade#XB_bG>KB5g1f%{$>-oBV6rp4nt`Chl~!JD3g2|$JDw6XQ6B#?wyw9dtZu$)M*n5nofNYBl2GgfFE^cE zc^i%mrim&j#63u+2XFeH*D8}6Gz6Jc?RQ7ryv-bFdE4Y532J6&z0{RA3*=&;5uTOB!tciP^iNK$dqRg4$4850@ zZAJ0MVW`1VA$2573~Uda+l3qh`KaU8tA_03JfbnSoWv6eyl5leuuZQS9`WcOK#Vm|{`z z#^1VAUxx!4HuM~OHh7{o{7vK($_!d5r@I!E_NTJZssYsvOr-aghnzw#`BBsUB-mkC zhVB5oXj`pkT{}j6?iriDHOwBZ33b#!@geiEXpra&(LL~TZ+qDSD9AUiC#*Ii(QXg+ z?}4m^l}PE+hA<1t8Jmn2y0Cj!1)l3^IisWIja=@^`C|u~bMWCx`8(l~GkBMcHjkkr zMFqi^2?I)&6M($vP33~dK4d8=snIKmV5!06$6E8BQc*<(TjlKJrj6fu$H{qhMcY~S zON{CxTKsAVXc)EpOV9mK=_cS*B3Adcz;6=`?-My!5W3s@a45MYw$V1sebu7@wBIC@eJ4w7gSy(scEvl`G-9WibqrmZZhQ``#u^p9lNTo_YTjAzH_^Gv0~+S^83o z-*@v{$iV{+Tlcer`1K2}#M?#hAz7SosP713iSuTipV6)em9M&d)ApfP4k>5$C+<;d z;6x9IV!R$80V>JeE{mq%Yk7e7L3XCYUx)F^R9yFVjk&%$GK^0I(EQ=y+`Q2wor}Hr zM!uEX@zJdr`SogAu>tU?F!7y?cqooq_AX{h?q8K8o5B$I_svJw&Qw>=5Izj`p&;&s z)yxDU(`g;xKGE)KdSE{nX!l6@R`JG62_&&VY#A83n8v_Pi?*b_=fWmzdWZ!v(pNt< zoLk~=HK_;^JV7#)1cJU8a@IyWpfiB>x&L2UJ$D%sc|%q6X9dD6H5bA6?lfN^xPOfz zHyzcE2KE%oQz_=(3lL1Xce|^j$mQj-OfRuv%%VlOUu7VK=yqP&Jf##JEuUZeVBQZ{ zNFkm+-!*2;YweB*aM8Ar#D3VkhBM^BzeF4Yj12{Ffu2B3AuH0s_LV*HSce{V^&e}& zU~c=DkvaeMdB=AqJ69_UP<4|xQnZ}m{rkQcd|+|>wZ1rjLml~*AFE&vn|0sAMtZv7`mMem`c;8gsX(0duUcC2#R1Eq8KP@!2?QX^^b(in}5A9 zeyp>@ql;@t;uOuhHp8P|IF^@cK5+n?bRubq(jpho~+?)HDuefU2g;;INRi8p+jw*7Czs#Zz1` zC%#$V{PyDGG6;Tg4@Wa{xcTxF0sjpD+Gg8uUYf^d_sd*Fd&X=ADeUEq;a(V-)+LPH zLC4`PE#mDQx?U8=@2r!~)~V$z0srDg3=HPO^UQ;I2baW@FZw1|XLp;^*`Ld1wm5Ie z-Bl=`G_|=%l1QD*zc!r9%;y7GB`-Gt{~Yg}m!fMuh@7a@&PD8EB0iX=d%HHJ5I^J- z{;t<|b;KL=hU8EZ-wCPK<2X3&w70c`QH9D!iRgy}HT4g0kVWvk+DqE#v`2bP10}w+ zwp}rl#q#}{eXPnd|Fa086G**dvuVv%9}L>IH;$EpMdhoEjO*x#-Q?B3*4xB;pXt~IVluiO~uT-cUUdmH;$E<`%3+#p>sK<)bS#;_qQ zH5_XBZGK89tB^G#H@Kl62ux?<{S1+#b{&46m>-|rxVL%E$1{Cj&+N-hODn6zla}X0veLnSoz>)QEO(y5O3}ds|L7NLn4;qjO z@1F-RYV6FcTq_c9{Wv;66L&=Or?*j}PqhJP)8BBYx&Av$$kbf3+COc&%SRh^|5+71OV9;y5u zFD5~pAr4Xo*}@UHz}bIZo*aJ0y@~f^w<{Rk zV+Wc$ERAN+>SSh;QoT8xT^NK?M{va$vzNmDknA`=7(c{!rO88u&eLTQMS|{`;DUGG zA1QA<8_u4%k1-Lj)IKoy2{{^*utRrgXP9ULRI70UgkMhv_?RffjkgxWTgThjT+=;& zZtz$Fi1RtbjN8;i^{Ysb@f#Jc#4Mu}uhF;!4R5O_&Mti zD74>G$sBuyBj|62B{kDaPl7%(Yvx3xR-}=awM^$-0I%gFU!$bs_}TETTUbDhVAKFRDq#VLyk3T z3|l^^K7#cYgE@!4HZ3fkZ_XPaNb3@>_Kg;%7;mWyxYN>|@T8XEF!9CXwKH#xR`;)_3rZsk?lc&(gc27U82gC}RMapzDi@ zi|l(n$m*aICjll;<|`~K?~{?zKnWe!)#T-jkgxRyeOY(DD6$z@f4mdqB3rwlrt3bm z!9!Pd(|xSP&K+o!jz75B1#e*Wrb*s!(!PR`YBT6@q%&0^bUt8q?#XxHymg-(o2h0( ze%2PhAfanjGB5YHuz2OubHo+lTN)BKe75P6)^=2#9I}+-y!IJDTlwFtZD(TLi|NZP zcCNbggxqjAcHPu;V@*x4mw2C2G!GC2z_-(B&gIWk6K9|2-`b@mwWaJ(EF6NLEm-o-!juWf1PvH)Q3jbWci-6*d-ANxcX zktcIB^%zK+@ZF!jhZ677Tbf=@07{2(60_}V?(TZzMrZbC%Lolt5Kli3+F*l-OM@;l zw#OWFIuK>_Ex3zeB@(?s$F%Dx#p!OOcX2qc$t|pU^o3JY%J)|9-n<0JMSGf&Qo?Lpb&)prL>yc-^N0Yp_+OJ1}}ElF0Gk zCr{*Q7<28o7ih3WUqz<+vxqG9oislMfn5#fYuClej@5t0ByfS&kkA$JwwdEp>}1#H zL49$wq9Oh-F(jK}mzL}8I9^$9&$V%g5dSP~K3P}g_;8$_x5o0ZBIr=?JcX5%RA@f=$a&-Ceh>6yF3|I+c}t)43OH%#9jZC*R`yH*JxBh~Q+x z^Q&vssG_5?k(MIm{ok^edJp%9-!jbLh>Eck4oI^<#i4C^?MEd_nY6bQli~umuHC3? zBRk8}YD@Xt7)ZN5;GcKc!z zm0@ARhF*0bT|Diq!iTN{zcUJ}c7lzQ)!~gaOB&qEb?jPlGW+#-%4oi^B>g+#v!D1 zUlx$Vc}Eb+`w`pcvNnDn?UdYC5U0Iw^%}>Llj*&W4&*(A#1bllo>g2AqA}AOXC6eL zleI%*=V;k}_WqF5BmCUljPp8Oy0Pd5sp>Hw*iQ;D_1S(hFS80sCZs6ZzP#t{L-y^@ zjaR2jG40iKA*}hH#m9FhPx^Sy|FmEQzNm%r9l4mms#FFw=n{P|+ANi6w~1z;mX}jt ziMxccCmmC6xO`uyT`It_0x^5$#42N_t!bR$1xBXwi@MuL_&@G4|RP2iJWgM5cXB2_rrq z-MGaEslgS z#I9m|#Ws9&y|k_LEzP^;vpeD;=ggM3QYE&HPR-BlDdgj>fYV47eZS{hJ3i)1YXzfC zot|M!vUxOoj@|$5=RDj4vTJP|arm5tXH#CIX z4wv9Nicwt_;ex%mo}4OREvKMYYNFpk1cH!E6e4QSfiak5l(L?|#FwhZrk!#v5n~n2 zYWE#OWPH!t@&}UoK8Bn-@3x3w7m7&nmq}Q7A7sR(eLCXSeGYCMsbS_ld6Ktdh|i6K zpffl$0*6!pP8+EJ?I-t(r{lv16ob`6Zq5t=7J2SF~b0GFmHQBFA=1ix#im^KH#I+D{Fy zY2%&{0I(&c2s)YN@%q_Ru+@bmaVr2tbUo;+Z|K?wL_kx2TrScYglXsw`N2{!ao@o@ zAKU?s>A=(17^6`ehc7ln!H4Drx5H>ahWq?e+SoZ>jOzj(-M;h@-6ae+$0?MDj~C)- z<*V{lFALdzP2)neyOnibLg0yHk0=4)ze0%a{5hz?jRaqIzyJfv9TmAbRQ1zKCj0_1Jyd7T|4z7ExuG`y^$Xfv%yC~ zb2FdbIoZAbPrv`mdK-6INLiEpn;D}ybt<^%2Z)|X9RK;qs%*PhqIH&>S2bWS_bFJ; zU47T}53==e?8)euhALWKRi}J2rXbDm_f64jJAVyt^8|<6w)hb~@A)E0=axE1Wped{ z(D$MEL@qx~<@E^)s7*QA2nkuIB;48Q%f<(Y2FrU+*Qi za_@Qhc+ud^E*n!+NIpLIu^hAO7-jQc9cnG*sL^-l@~RS$;!t2X9>D%;SbbU^_6Qu5 z09CurDLUf+^#PoXkasK@Qc6`H?@Qfvq5i+k06qj@@XP~=kxW2&?k_+vq^Zn;u$TM3 zK{Kh(P15VvhFFZQWI1kbHJ&yu2ovhDjyauY6P z=DuhlR#LEZRD55Om3+>0oBSOAtmW~UzUXM$GL^V}kuNUBqh&FVpE!Biqf~|*;%#OD zZqH8R23U>Usr2Nq8WVDZoh_n)=&Px3e>%9+x3s=8*|jvA5)7J`o6UfVjb6t<4vo14 zsI7cc>q-y{LTWJM&|8Bn9dtjAo!PZlUMKOox95x9cs|~vDpGNb9kG7C3ql!IQEaa! z@q#zczTU%dOT=?+`=jbJORqz_8^Q2x=ghZIBx`rG%tO4~>9)C6S?EvlbE_4yK2y(S z32?eC_41S>%w1rc%WVjsby6_E_wmWm0I&cCOo{OZ>>$DGBH8GzzJ+M?w} zkfm&|qa}Lz_Tum!E$2tUQZ_310FTR-IVxrLA%OcS& zXXOa&#~n=kO$!z6LB1<=o#%^`)*}^CZqM+WKRoXDT@}5&en#VAZz#F`4Hx{ccALk& z-giQ#t+aV|1{sT*84-zBbPhMU-z3`I;Y^q=^Sau&?2YF!CF{E(+_tbl*phIq0{6v8 z>2y}e87XZR-Dz`Ux2&8Z+3C4xAwP%Srn7i<-ERoT)5BJuVF=`g=Wl~FH2*vAMYb)o zm^){Oc~%Ztp9LcIXC@7}(5A%g7-A%cti3FjQ&w1BY!#z$6&bk}qww1t1SQfWS}!Ma zSyy(XdvU=v-F32<_Y@BU*?Z}I$*RF+9W@`usNbcq-XD0r{#N(J@FR3^N%kK%7K$(4nha&mFSpuY`GB8gtXF!o3d(w zncNS676;Cye#}S~QH}$SMmCEo&FmKpN4Ts5IMLC|2q*llt^>E0!Fk#m{!GgMPH4A~ ztL5m!8-lqAe63ZIojn}u4|jE#qmq4GyN0-TTB+^suNM6|;~M|endWovyqErc=#itI zRK+J3_bWlEq>HG@U>9K<1=Ak<^X987Yd3$WiFEv+8NsD{ema%ri?wzlg6ciHx;BIP z?87a1kcE!wDT&MEbX#_Q;4?eXMES|-(d|BXxERiU^DvP~j*?nKhXb|u; z7u_datsLo3)Qu|^38xMR5lGcN{8pzRwQx{nNuSBq(tikzX3g-r86u$FyCmeO^}Ouu;Q>#% zVc=1`n)1Ez+T%`)R{wclL%&l~wdk1g8DwlV!|qKj^Bq$Rwmy4uDQxq>=OeoiBYs4?_LpgY znX`3OT`MlHMOa653jTd|&>h%l#?GNWvyPDKSjwNe?5{qX2>-s^f@ujli5J+Ig0+9br8@|Dp|EYR=LrKE!E#_V4dkkZl>3Fzl8LK&fq z%7YQtjBQp5xxlec6a#+F>!Mb_w1u1_IXB3?e`k9!Ymof2D}b2woe%o=IH@ z+U(HPQy_k^NhY$9(j-SB&|HAJ?=Q!Bft%>n>Yi(@x!_JHDsWWkdhbTnZ&_{LQS~+eB?HnWn%k=jXfj!P9OxHS_dQ zUFC*9Cok{kK*-?MC*EQKLPqqBoQr6U=76I{KJUT@-0xZo2IA7cAd%MSMP!883ZA?D zI%A>Y&lL}*@yS~MU1jB+7uNB9GJ;|nu7`^0iuTvakBLRe6Y1*)6I)#AuF<<&Q#5B2 z{4_ZI-B`0)q;Tp-=adn=)hrDb{haBddF@R}mvn1{k}~-hDIP-4u5+swFPd7D?a}e`?{`=}S z@0{Z5n6*)xRiV>a6#wT0+FTlRO360|Za67}0`}enX!r!Cn-DobdSh{SZL+`C=lJ7Q zCk1d$q^R@nY9qSmJXwzoOTE)A8k11#+Jjc&;kT6w9#1$t-WjQ9AoU{J^V%;CoBMcJ z(^Lq7`C2~t_umg4(}HeSs(hn!JWKpO2>Mg*x<9I#-zYb?p_4sk2sAz>wRIiI-``ux ziy>yNX3CfYJ+jxF%TfeNUSds54HA7pxLj}4xSuV;`Iect zaeoeB(P2KcUfdG?A&2YDgIM+fAtB-eW*)AG4{ zdk+GmWY^;pI^eLs?(-0*rYY*@`trGt9~0sgJ>1Jgu%X;{Wy>@4YqhoQl<~jUtXp;o zX7KM-$?RD?JG)>OY@XayPuamfO*Ze{ey{mj&2v{{S4#JR@p}76)_=0g=AVD6ti~s? z6^SNjqJapxJ+JS7RV4k{EzN`W^ioC^3rf4qQP%8*rNe=*4;J!0c6cx6(lw{8X$n-# zuI={3Cd!hZ7AhUeV#yrdAN+er$mQkHv&gP~ws`m@>#G5>2l?^KlArW8W_4GmH$RyD zjZLr7-WY(8k-$$C*YDowkd6HE<;n+X50{RK`XxFz!>R2PCyL#uY%T=j@K`GhlOccO zVdpJp4W^-Y6gsJl8_93_PbnbVpSMLb;f?t?5s>pJ8?M<&r-`Cc-+x8fo18|M*CdSA zjx+|qdX}W6?e!G$5_|B685=M;@j$CVJEEX)7FI)i{gjz`9g(U57pK7!niR!dd`w@n zmVHvKIRtU%jsv5;@>2GFY;HR;GrQ)1-MVIZv80NjY?>{lKAV z>fOat--Uz7UJwLPFB}~beTqqa#1h9Kq+Uy`BTx4rsweVg2C3DL8n>%#gs2jn=Za5}rUJ-{=cWDW^%98cD7}SCZcJ6ZaIl4>mLUmsWs1@j@+vu=CH)#>(2KOPPo82px7T_ zEyjO#sma$}OZ9y*qtnIjSCh2B`zw-a6vq@9w1aT^OdAwcbu=+^KOvr4)hN}84FbWM zYsEvhGYq4i7{U_OEz4mEV@)WW8AVVAzJ|Od7vaF*XnJ@9%W*l*N={DT&eMNOp`%UN zs1fhi3;!EDzFM>6pVfibx@V;IROD;_M7{2__I(;!5k`+;BXF~14gegi5m~nh5%%#` zaOT41Y()37ex%4io&Qz^H~fdfiM`N6m=#J)_Bk(um)8P!^OPbeRhQjW(;h=B zaeWHr7>+`EK!N~^l=wK9{;?F)zYf#UVKk8784`@W9DG2rGs7}P6#01zVUP`69mjQ- z+gD!xf>V~3B1~9~p!(6KvocYi`gCh$3%i67!+zmblyl7iI&61htfga{`C+9ow7)zk zvNqyInU{PR3BjoA8}?^XFmI{dCfHBx>_Ip>(3{#ggs&tq>2&)+`!Jh?@p-<*m$oos zVn%^`Qu{0KbRiW?PweV}`Rv$Ngh>475&!OuVls4iT3TA?=xAi}(Pp}Etzx-h;I)t} z=S0;#k(X>J{eA()pWBhwd*8L{gb`g_l+!3%Mx4LrN3cA_FyZB4lHM=rJCaDt;4-2U zbwV(NID+;ym4x$O)AGk_)|7so_%(Lg*zxK8-U@S@_q(&Q0dyvLdn!(mH`EcM4cz3_ zI-h5=IvibsimrWrR*}rjqxXtnXF}@G{HX;c@8{I;CSWHKFH0AEtzHyorlLA8Gy?^9gOWN89ojsy6zb{dIo! zcuxE*BA@yrfg?vArqv^FRr&*BqJm8GbI8x|0_2!B(^03Sv)020!lv;)`tfc3xLoUkIwf$kz8o!2kc5Df+7(S77kFks-*=f;WoK8V_O*J z63VhbFX?CH-;k~8BI;PwdfbyMs0RI?<_&@c=_7d*%zIvuliN>fQubA|jNKDDX+7}| z-^onRaX)%NoUKWh5*!)0H6BJuO_9hEPf?`qQK+QY@8t;eqhKL#ZC{0aX z7ub}wqSF+h8)U?qp}q*JK{z1*Q&pE^b>nayBWU<~m2%qX3}Oo=J^-Isg4EIpsl{;< zqj9(zBx{RVczgE>5_RtOIO8|X%+t5YJG;#Pn6b0Xd-m=U5qYIv(|?orY_5oeon{Yt z2}dk))K7?^2q{MpBMQqc_RYe=PN;>|uOfwNRm?l-zgc|_M1yV$%@Jeiv)L`7EW1v0 z+_HJg4WVPrbVb=LuYKmuR{h|)R`#|P%OHBw6}UgPKN-9JlkWiw7tLy_5&cY{nnH2> z&|cNW*BTV{dov@KZwq$;{(?VM4U-9p)SujONoZ;jxH)5}rC0nyVPZ$#&1IN>R? zP1y%;!7$#TulAzTTRkW7nQ)s&8FJy|V-06V(<`Xdr~#`5NUKy%)i;@_!>#0A5DiLc zem;xpBRZZEcz!;ACa(BEo%Ca;1d7(bVwBxYfDryZbKG>AoaR*>+aui(M)b9CJ;QI3 zD09eDxA7_)wfTTJSeoNrG&YAT3$lrq0a<`>U~32-cx{PjGHgZ{;yymR=b9jwT>XOP{_lMx>^6FETfQB!_0Z$R20_AD^ZR+{yfu{v`I7F|G==fe zxqWbOO31C>-_G&c&s_KuP#LlXp`qvUjcNfh?6wq5t$WesC+w$u*Y${|yVi+c1T%cG zpP|j#!a?xsD~@6bHF^7oKhavkNznL|@xYO75U(v_s$ca6iaoibVa|!GHyCN1LX9po zEXz`KIvw3`qwb8y)f5f0kDCF{9G{Rnj9QOb`B3; z88Fgbp^{1@2GE+64$I35(}$hZK4ntrFT*vNf+WiVgME&)L_QhBQO(uuAIN-@PpsW( z`k3f{aEoO-<>Ki?yz9UHUrkaBD3(B2mffOg=*Tm}WGd)+DZK7D>$u|_p!YWJjGqy| ztz(K_MJhd7qYr?UXzIYPB~MVI2p?g?GTPe~A&UM#>tATo>)wetv`S)_sg3Q$uokoN zJQGl(L6y5cs@#YZg^GWUay|Q36^cm;dCO$i1sKMhsAA&Hs$bq6%&;n^ML=%!OCN*x zRqHCqS&*7x)m*#l;zs(Iu-Wh`Nkh5FO)XQSH`K~z7c$93)Ux1Ir6Od zWQ3kW@d|QT7BAmnbZaQzRkk8wXllUYOwF{L_Ij#U!zughZud2jOy7TYKb!q6Yl!?? z&cPIO*nYv}dJr+`v}7x4hgD&9Lbk_C4IGulg%raGMWyG9X*9Sq>$)#&DLQFGWjfXd zxwGVz1V1uP!Q7VMN9g-5Mnfg7d!uwZq0>;Y|Kp#a=XBmK)a}tiOa$jYFK;&7e6P4d zaC5VN{oLVw8;8iIY)cB%L$h_k{EirFRbKCOQD z@ttj9bWVmdcz>$EOAkgzGgZE6ecYC5^?!2g2|LeFa_U$2Q^jK|kfTCaFnKVZ#idn{ zY>Hzn0V5@f20I6{i$7{<0?pnx<5WGnK$Lv+B$$A0hg9LF13K zE355D+nw@o$-hw-d$Slj4OEa={0h)DzMcCv4qveRzLcd4_gU0#j2#c6F$5~p`ClPZ z{keKP_12|ay~F{qvm-OcnQUGtM@oOz16H$oOHRK46*Zs^$0>s7(bL6uY5n`8YP=ue zrf|wTX5PbhH6FxsSg<&i(BV4D9Gm3e!rD?N9QV)R@%vkwX5=W>jgBSQ4Q{T^@gwq` zx$jkQnNo;F*-Y`>dn0*FYSuognPYQB6$d5ew#JjuROj_+{K@hX zTQ8}1KV;opk1FjjAZp1#-#b1IH;Lo{3Uncii_=JIiR8rcXc&bK5V!@zh)+7fQ&FiR z*a2~D)`Yo@0c%AW64cMM5lVvZD3-VHy4@~3uj^Px`+aog1*AFoy4af*4J zvV*9J4SFolUkXWTB9!pl<+ptDq)p}rOQRV@fZu*S%2vmlD;k-h)4O$MbENubp8jRa$X_?hYx)hBCDI1BWQ5YT*hZa1DW!FwVj6PnUjOE8qQ zLn2Nqthj1%;i!2!E1?r_>|BfJWfudFE;1$lGdn3qX&)@K znjG3cNQN!ur|k!%U6f8JECp>YtVVF*NqD}MqSNPAkp^~{odwZ;gR@F6ZguB)dz8Kb zore9Oww9mggCCDJ+~LSOaB6g;x+1A~zm3iPrrz*)Jqp5MyFLhrok`qNF#-u%+UElL z^tD3!z|ZJEjUY*t9Q|>m&k=LTJ!R3Vpp{@L}ZwYo#eBt^Jg&L=i7KgI7Kw}Fjom}IWc{jS}8Z#~GU3+~R%lnqzDf+StwPcQcQD$CTX-9vjIq!RAro8~$Z+rl(gZBvu*3Bmy zAMkTJCkD288h17cnd_PNud;GC;e+}Z4fG1Axs>J+SNffWO-+F;y@h7GOGP3}0`i3%;nXUvGz$6Oq(aCeH$ISmI$!#6WWqqb&sg0h}e_e z@(f4#(hVSoJ1N*K&d9|1bCwu8cPnZXvG2~koVqxYHKMCmaO!NlmW) zt4{Y_2zo8(Xs!qCpn8;e)E6=k&$R{7RR$sxx%=XoHZB(I#+$NfA0>I4e!_0aU$*Ae zm;kK597!q5 z@%Z_O-79tLCG8K&sMZVY5SJ`PIB$)H@=hE-Ou9K~)qQD8@%gtOHluCi)j5B@KM;Oq zlZlJ~Q1?IqC!j>i^c8G43vJIiU-xkt22F|fYqe)HTN_#!Q=|IE+PswDXlim;0-7R}`*+b8=G_P+o<4L#a7OlO5J{A=nL5%JZuR#vX)V_>1vL@RD1fl(C8P z1V}9|+%wSX#4CtVEjq6{qfbo|jw!e^i&guu`y%un^)Ffqc?>g0YN0KtaQo?3*slne z7@7+W3iY%BFL4C7!I)pMg?+zyZJ|#rXf*L1K~#gvo3wam_ER>`?E_biZ|sdugml@6{KTAkGFk5gZ3m4qdNJ;!l}s|-P#leyQ76;6L;hnb#D!C$EzCbCqgDO zBl>~$4y?iFO=RI;bz{~3?cc6KtkKXQ=^XVv^X*&L| zYdrvDV0WUjfdFm8mJZ_-L0A))PS?ZkvJ|BPBB<={^YGoKH|Blj;J85wVgF;wt>BMP zlL_1QnB!36fw6-Pg~J|bg%7G+_g`ze-Zc^|qpxbnvf7=H%SA@KH8$*TuU>YMseA>? zQ!!H%HF;}3#M*chatQXduvy=MF^MT!up+R`DLy5ZP2yBB>qL3vv8oGEgM@5H)9@l^djnD7C-3v{QeE`~$mFsQe~?h;rVQia%1lUDj(vx-xg%&ZQW z#N2Ibi&*G>3QzE~(H<*BCENz#F)8MOGncyuB8dJ^p>SBT4~dVE&zT0&$O-2a1p{;I zME!dr6T%1Q@E$>zE*{;`ZjG6$jbn--q6wxtIkQGqFhLvsHF#4TAH7oY1mVB|VFpID zgtHk(lgo*Q3}vnVUqilGlrz$8SMq%^h|c}5q*$p;r1@X-tiIpo4EM8XUeW0q!tcqIfetaemG)8BNY}> zZy4sAHbyIF>t8k}52fa`Pt_}b@$gnZWt(idtI5a4EG9gMQFi~`mIEdShAwtIJFkE|hu2;iuQv_1&@{`PGe(M~ zQnX+pwfhuR)^m6$tx0pv1%H)c<5jU<1%U>gT-p;vnamA+ii@YiW`7rLK^uqc^WjjD z=>N!NwR^XU(@{g%ee?qD<-^Z?i(2Zm1$;&d-is8u>m}-zrUX!BZTO_0rU;@_0zuQ({8|W zK=;Fn{HB!~-VG*+gMEjtO;8ujd%E_CUGHGi8wX7u=Tv917-$LmvrAOP3koYa{k*{& zW-Qa&x#7&C=Cpv#NgOA6;SsyO!dJxeMJ!1d@Q19Q6hrMA($e+x4U+V}Q;jJOIs)`5 zPXF=L>Xh%7xZ z{_`}p2yV;|<%lKt6Y>|7Q;x6BYoY@X&1ri1JiME^eaWqc4;6o2x6+KQuvBts3m!GuQB2|w2e3X`EJ@+AzSOmmp)6iu;3-HEOj7f^aKtt%c5mO6II**lnm97J2Cxm zgkNAbRElUXlCl};BAS*TzrHI*qDpOJzdwF1Eh_?}Y?N)c{|&oZ>7=Qb+CFIH0waJu z6bM$zrB9i|W+ST(!JO5ErL zB533~MwTuCaBb#>0^eDFcWWJ8!HTykPd}AMGfC!zkkc@foYqJ$3}4~yH7*qgq^zE^ z0=L0OdimwwMh{vC>xcBUA{B8p)z;e-8TYXH11SNywo*k^HKn$;Hak7#YwK*!yAtfw zwS+nhlC)Z@llnto+OTHdA`*1K_Rx04st48HU2unjZs7lx(A}7jdjuwg@lfKS(v;R< zJ0tAJ`v>>&ENl@g7l{HKw&oucN1_En8c}f8fk-N#mz)LSEEs-rge1+)#8?-95+_l; z%cW|TTV>VfrdV2I0C5=csO8($&HR$CiTY^U!9R@wwip*F$cZOAgv1-V3xu_gw=e5A zc6U?t_Vqc=#jOASV0R@1WtOXc?Ynhpz1jFI1EO0jqE!5I6N_d})4$aJe&)+dfR3DI4<<}~ao`*k6tQ3^V`9I!k?PXQHvPw3T z(4$#In}_B>%!ap}O&AVKYoB>@>7PI3c3j6v?=v)TmIA!rUJW6AzuXj8G5ee$&L=v6 ztYk~gWw*R4jXrVM;A2K1YmjZUr5g8dMrG3lj4 zm*kY%K<0Wje!bI+Ev`z!G1aS=ITj|Pc-CE|s?1#{<~#{M`W>=_MqL_Xu6(gD`>#0N z@-Xutj`jZcb!p0Dug`gAU|&4!XOCiParJ#{U)!b7K&GZrCFHqnUcJsFPk51Ya#QjuJ1udTl5|-1LiY zZ1?d}Y&5J;eW;sVx{|ZXgk)!RH5==D_h@4l?cu{z_UJq)?hX;34f6J?A4C#g1Sz^dG)n{o6X3fQB4+`cFAv!o%QG)FpFhgp<56&TQ4v2N%{O1pmp^xG=D=NMzF1x^{qXmV#<9i# zUw1^%3E99pX5jcr0X^{D>B+7qhB)Ikyh_Zx-8keMPzW6V?mHJp{?;Knvt=(A+x+=9 z=Vg@L1nf`tTd)ZR$E-8cA8;<8#p}=Q87^HrD<4be;zqTwqClJNEw?XIe1F zfoRBoJbd$W-avFk*-iuTPRgH%f%4o>p6Eo1 z^MJH|jENy-{f`&G8%ra%x`LDB3D>eY8C^t-uzTBdM_!`W>3IQAhP85Qp)Q-X1%=I8 zC4~s^E2@C#(lb98Y^C_TTMbB5p&quPDjWylarw;oPcFV#@1B`|&Y0XPJbF_p$tVEaBPvqHbp>A}b^5_O z_8*=DIY?TA<%a2CzvM@NT+RwkRdIjlor^e8sRL~omnG+~ z3*{sLvIH1#AR)=wh`r)sv*Y&SLkPib?7pfkln9Ors}qgt4Bo2Ga|$3#qzn7?5jHck z)AskyKu!Wwds!a=6QuyBhX`X|;9bg!gr^v5h&~E%b73+E(yF|xUq_ZC&V^5P)a2^> zU>T_-3)$q0J&#z-Tw_X-7P_rBud8v%-OeAZAg~za2bQbITy0gi5;n|_Zx_yVzCY*9Fi z0Qid)wrqiN>3I+i0WG8?lP_}y>&6rC2T|&)oS^=VxBd{o+z`M`w@@JRZ~CpDy;Rxe z<7&I$Wf0E)WHCkr=w1HVAJjJN1Dg@Zh|LM|m_8F*%$@{|$7TYEM{y=`CJA@Cc}_0W zEsVPm8CF<+&_jt%p=otwXMT{QF`G3d$M=^e@OSmIiflIF$JKk(K6_bH~*;=>nNA#Qm=SW2qQb zp)<eHA!2PB!4~;Nm8%`6z1Y^i=urXC8pzqSP zqO0e_r!t~=l;zVic;eWp|xNhTL;g+qML=8ooGU=pp3>Ms3 z-+_p>l`aDyT&hRPd;POJC^yBCoo<9mPMC*=88qlMSZBu`Fvql88Lpj*eNK<2ZXJ3=`GF7s?B<@b9Dj`$N2t5Cr0dFdPWPj+KJbV)8du zc^A>sts`o!ci$clqxQx8T55MB0?@dp0~45TPPj#v+jaWk{g<2Tz=ts!iXI<_9{ul0 zDKL}I`QKE914)uN#-V^>qaaX>=Qvnk&HRo`O3?v2q8CGsFX zB6?#wvPWZnVpm>6TcYS=b_r7R;)joy3Qytj)K|-1gamuH&7fv2r?=6SgAb=_DCo{z@UMOHz%}*c&qJDuCyJ?Pz2MhbDA!LT+Ad07+XHTbS^1fuZ9P<67_GNNG)e{OgSt zN4mC8rQg)KQIl_0>w6>1zo~Ot8lJow99rO>f3GOSF0PO5U(nzlWI^97$)+H&RdhN> zzUqp8m>Q{g0wN6!f2R@ zb`CCG{O9_SW`#KG&z(A3deEcF%1)n`e{~y4LqRH%dcNP9NH=z9kxuzi^;pil7gzph zyQ&r5_pEcKb*2~txbO%159&G0kwIVCBrIrYMGPtxoeEy%-P>z?J)rc7_cJHT+-|JE zY&h8jhk1n&2G|sZ_J)^%Wx-)0Qd%{ zjXJ`ZwEKBgui!I5DU|#(u8IU?1ZLWtMB1Rqx{t7;4xk032`$J5AGSuDaNn<@>>1*| zs_J-Q6N@>A660@cAfjYm`|=NqQ0X_%uQbPQJ^|RB z!s6;px(nW|i}KnF@lQV1k@@V(Lk*AQQb>zd0QA|4FeXYPx(#ckpW{{cdPL*HpHSE8 z%?ih!^fOX-&u&cGxsmwcQQci9Ce5r=j%Gm`bK`x7b@u9h&}H{ra@$itd;g^H5Itr5 z{lbHGyPRyA|8S9OpT+o9k1k^KIo|l!gRrA3ba$1v@Z@8*14zvNFY&uld#n9F4!Fx# zJjNN?Lgh7n}Pysk-2R z^HFlO`p&~(WX48`5xYCsco!BHU|LhzfKrOYg9K^6dQrzOn&SRV9?#OO32a^((j@@l$2)^{ThXKrjtGra0KJJq*j z5RSRK@e-5Sm^<_0c^Mfz-X(>Kv5u;^Gju$sT&5*c8Sd~5zq)qea+e^RK{8D))NEg+ zUpihnP%rdlEf?V&6t!f1bv*9#=Oun3T00e*KwiIRtXKUZ9bI_h@;e>VaKj*SQ)~>| z&k`NE=0GL-sE}mx?YA8Q9X#a=VfF9SexQAbx!VT;wz3jQ6XUzC=YNs0P{_4x^bD+ z6?Pf?J_OT+p{qa%GU?>y#|Kd zhP;&5_8yOtOX-ee9DD$Q{^4L2h1b+i3V4=JEfyvEN!SE^fzwmo?H|5me>d)mK*`>i z2_K(D5ysw0*zcnjU%%L0lHtg6bKJ=_-So0%2C}@$Y%G7X#~(}&dPnc-@@!;QqE2L{ zZ)DG*^0!X<&J5Ay##>E|hIWd_VAF`uh4Vn-{cwvVu5kK(-Zn{meaH&U-rruUCQZx493~3xCBa{`)r+5E`=P0 z&KPL=boDw_Hz!IUK5Rx9fe5DwMqv4z9@*yEu`M^#uj_f?b{F>trS@5g+1>g4>gSa9Wqu#G7RFcI>an|GDC`Lx-o**q$XL z`+QSdbru|E?cFrt7;y0aYHy!de7Ge$mElDls?Y}PE>Re#qhI~A-qpz+Kh+y)KT;K} zeOHE+0x$5CKNe5hD!K*$6^#*{Yrgdp6taGv=K2O(He< zdLCF3ntW(Pj^_aAY~S&4zPXxKsFHp-Le#iqGG0|(fMb_x(||1zWI{+C_A1N+3T1|`as5}58g6aJn1RcC63iD{=88`0?9gib>o*b^kvg{!Qo2=h zna5|Xw#P{X3KdK@hLOuFE3-mQw7)6Qb%1}f`uwZ^hLpZodoa)hR290t1Rtcu**uk# z^lM=?UVIDn3R}z5sp*!LMfA@$C*gu%EbpaqU5XxG6$K=-tM8HF^s za;=0~o?>{v^jJZuJ!<@(VjGh` zPgV2`GpNyymJV`-E)aN75`GMrn+6JT@lc3cYt}N!!gfYFLL_+L% zuGXE++QOm*gUE0SW@gmy*Lj>V?9RCrcSiHtLqC?$v!GK%sQ+fQWmbGExQI0gJb2_| zObhAlAzT0-NEZTOlyij<{pL(SUw-y6zG4#m4x(Fy(k_2-lAC@>lGoDGlFB9wgJA-A zV8K3;HZ8|Jw_RnG$}T||%a`3-ifc4Qy^CC`_6;T8F{>%%#d0K^4_Nr#JrPv-rzkEg zK?)N|{@p$UhNBD~=n+uzSn%NqTTG~&neFRBs2LTfUfb$DJS?-6Lp1gO*rB!on)y}9 zDJSV*qnZ{>EImjldtb%jcfk@vT+E&Z$Zn;oPz?N|l+ML{-o2)GqP}ok189}6^?H&k z6g#8Bf8HNixO_!_IsfU8r-e8RK?SzMFNy(sUbqTQGO)DDTyX$@Kj@?$Q_trqAIGZ% z!aK0|rp$q=XuZ_Q3e2`gSYvnz&|RlK_Jf)3Pt?1FVlElo<*aaUyk2?%cVDTc&^$;* z1bo>7%GmTTv5Khmht=z&ciqj|vksi?MyfKQs|{Lgg!QONl0#U28iN&0!O2QZK@erm zC(_}3{iLgk7U%61)@&6*aYr+KfZ_+-CrZ)1;A^dE{ufSE!{dDEkynH7*fS0dsrkkq?9tc%ehci+(Kp}LFPXsgK!rQ-8V^s!g9;;> zh&F1v8I{3po*+VBjU!IK#$KB}JD8{k^UIDgP@60`RWT+W$5X?9Uktb6y~ZI8@|I<4 zJUopBAw0ft^m!a}hPEH5NrEP3O$TJY7{?bFQm!zd;W4T??qI{B=UM&I8!yi*u{nFf zTY%;rO?U1X3A&6Mrwh0{rii{!EX{*sATOdXSAL7iQ2gHm_|1h|smW`V0s|li)g7eK zg|i{PH#aBKt|w-Yye!L`&q@n@LY)rLa8#TkK?~T)6?3mxCvTudP=7C z|G;-?s%g5?_S&Ad*H`ICa`%>vHlKFQagnr>X z&{;v5;TZL6|2(zI3I>T59-2)MD21CecpgiF7ZVu&M)tUHSJ_n6RKCEPk1lY~Eft0W z%|7`_Xa}02rTuLTS@VAp>HfYKnTL4pz>r{#%PBS;?pILl&h_b1UtXBA>+dWmfiRbe z`AfMYUxEaYi2z&K1g7OCpwqQcY_ps&I&_k|+d5YC{#AY;Y)YV+298Uu0RHsvy}x;i zC6emZ@GZeIf;-(_>%TeWJ2FC~aI=^kq})JDnX~tQoOG6YH;feLsxTg0ju3s3Rt=pQ z>~Cty9zor*75A~NP4BWN5EEr;0C)d!>uM|(d@QX#vadB;GOTjE_vznsV#NxsA|Rts zjdcJWaiZs>6WEec-+xtOscWXxN*fWh2=dZkZr`xotni(^#{F#u@*bRvO`EuZ5e>HU zDIpadUN*AL1hgARUCPU;+)d=bz@05!SRMItiU00(+Yb7T zRZ`ehoH~~n7UMt|5`%<7D^ zS>g{9MeRo*>jq^A1#{LEWVjoZhLXe+8wEWzFo5lQdU?j^qRs4);n6ABPDubXp7a;Y zT_N{u;R4M9BVT zH4sqnnxkAzPJ@5&^K4ks@)8xcErFw9q{DcZJZ8&LnPx8_c%?t-g!lNQrEkz5YB^G! z)NiY4K{(8sKIz?OWYm=}NmAvybWDRW;`c|zK@?K-{x(wnAnF*jp5dl!%UcVZ*cc9aE;%6$$3fto zdN6yZOQbdgb1jn5bv9P^Kt!{;HdPOleBXSFuA@Mh?>j2u8`Rr#;EOY4lV^lJMeB#j09s8Qt1nQQdEnl?hlT zm$|+zygZ-z@pj`r_xPExYeK2`V_%!d%%%ovgK|w$=#4DX-G~`yE6#=5>D6RbQAPYb z2i>N(T3EGn?l;<*`%Gn-{Y^VCJN+9~{Tf=<8Xmm#OimuaEO! zcfZ2(bd+X;Ufy*n5s|<~g)O&YqA!GB6RZYi#`1^OftDJA_4M>z4z7-2aYOB3O zz144BzFNGp%CJZv9!GR)f;IA1iJh%*@_?INQ3_j&(wmL`MAN(#aKQQ)s~dkWU33^< zc;)zK$HU}pt#7zh)~o6KAD650JY6qo6i@F+M+9(w)UBS`o4&W2siK&?b$|Ru_Wi=6 z??XOk4c@6J+S~I-Mno)ImD$;U<`NFU-?J?Iy~)p*y|Z{UsB86Cu>bFtF-Gx#VY!^On6kZP{cHk92a>oX56CKN;iCyY9(^u7e z5%qyc*tGK2E-<3o%DC)!d4(Lf+-)Zh^t6L9VuE6YrJo$WLaZ9}nY^AIGg+*@MV>Gk zHuKrB37nYB^$P%cHuzEUtmRkJ4gFv2XxoV~jab_jWeyk))z$z)d*hQsCt`L>|rS)`qx_ zdeK5J{pefeZrl}?j&}T;ZZ2*vz622Rk59FCUBL_3vVXOW*1LOxE^uQa<#>tc`GQPN zP4$3nw>6vWZcx{^wRdDoFFifpZYK4ySO``;9OOYwLW|F_ji%h{KRzd4^I|b7liJA) zp_Hrj3s0<3#aYY7(Ehl(Y4k<+d_wQ5#Ds+U#YLXPP75xmY1xXj0v)OMZ0SGWqRio^ z&Gki$y4q*LnXKcEY0kWl-ak+{t?J3tTny! zZg8cTT`9s=IEy>_(i^d;VO8rR?<>VZ&)D{}P5yGxQfc1nObBt2NOBNkBK(L%{#y6( znU7nXq-_Y@U1)sjf1f~VZz?vV)Ilh$@y!(u0Y>;oWhXSYin=%@2$DH4sK=bBuZg?$ zGrhZeD=kWm>Paf^L-Ih_g`R0vua+z+Y7z&5gsiLHG8WquNa!h)&m6C+M*j-doaY!y z?5<4Dz%RI?8u%0d#Xx7b^#`?doab~nrH26x(5-&K6r%I?mlUQ%`T;mG>I&2lmH595 zJj&bJ$|NG2)?n#i*nbPK4V32Z22HYWO<*`9MKyCe${9dO=_%lG{SH?(ze=vlU!Ny< z6q~@1I-c|ulHzN*%YZZQHP3E9JkCGo^lTXo8|_CjxW#w?A^>qgnS=5gRcIK7Ur$XO3`8g-U?DV`E=j;IA!Dw~9wDZa0JL;1zjIz$9InH}Sm`a%aTmUPzqsox0BqB@5kE9qQfnM13BfQ_X(TUc7dG`tM~8<-;~LdT*Dagi zpQ@LXERjJJ%vWFhS12*kpr1RlReieh!~#fD7uzFTaEBA@nzp~iFIbRWn%EU?v}wPf zHpcBb``9L(lH#!cSEkh`FNP{?9DpOqni?D-L$S1fGoEa8455uBw}(Xo&Q27sx=F!+ z9Xww*sR)CwcKCR9N6#rndyyDAsCfKzx*OZwA#=dv>(SNq;lr|;89&{j4!g0{e}!rn zcH@YQ>nDdZT{;)ye48BbUH2<*k10I&T#v+1?s$%o2%ZE7R1(LX!4{!EZPukIC93GV z>6fU(L+LRhM@phmBp&nDgk;jC$SGUa&&VTLC6MNypXc*S{;0HxI(*iu&3d~CM0nE` zI9KRg^S&5I=wZ;kE)@0U+uz;nz=oK9$<(aD-(-`;&ugsekn!4~bQ<^Cy_7cY+jP{I zKRlt4j$e3`O!+sJY^>WK#vs=+-jCcFKa!#K+-CV^E4{npKp2l8B!1Un`tl`xYilbY z-JdXW$wB}WZ2rsrtI?(Rx3`Mhjr;#n7IYZ%@9HWd+(9ukb8(^3%`>cP45iiJeK)@5 zhKF~sv(g0YkHu{aKP)V43_>gH?~*#nTp6>JTU1wPw+K;y9~_ATr^`U45xg4~8IYRa zyrG7+=l{Y!MJJ&?iM(Xhp+Nw;B>WIp^9bbwc+W0`$ z88mAoZ$QE9VJzr;rbF*w?QIXI0am1yvj1hDPt2$%^NVB^k^%M17!RNd^mpdq=){>`_;Sh=} z&AFlM0?$|q=5DF8%Vef*4(A96UU`H+!DGE|FA`xlGPp=TwR2+$Jj`|#D|jE(tq=s? zwHJ9th>nyRC9pTtw>`7TXkUf@$o})$?=w!4*_AkP?C8k5YJ1QoT#PLGGRGaiMzdE? zEX=VH&JIQ4uc2|kHh zqF2g#qF#n=y}Dz92N+Ent1$ZrQGP%6*cG2{3}~}cEIvQ1ft8l;&thw1GvEJSW_pP^ zhi5DNkv*DU=HroD_8d=>%dFQo&SXRjAFGlx_=-Efn=VEgKJW~;|G~#KqmaKtQulX} z7>g{qyoC|nSzIJ@Axm0azY^_aom~fjBLFqL@l?TyBepqrDG$*-qP82y`Q6SIK_V55 z^{N0ZXOC9-)CBcA(@;mO2({X~^R^dcVLtq#Ht4bB&+}P5ee_q9ngNY?0Fq)>&-Qzg zM^7eSPA_L!Pd;q#To|oeTsaCh`hm1%la;H&& zX@yuSnM;@L(BY6ro@#IGKt?v}_5hc31gmV#^$#O-mRi%c*O4qNEI*PYT^)`N_so`p zGHjp2XrutS9Kdu%tvcvJnvtm(Kc7LbLAwYRmkCYYEi{mwWcj`m__EREwoSI+aPD#J zI}Fr@tE;QSDAOC*LqmEt?w85t{1l*oc-4z7DTo#wK!JSow1dr47~mlEg!;Q&X};C_NVkUJnJu=X94+#(2kZx(KED4pU%p>-Y7n7 z6v@oLzxf{6D}CkCN&d{2-xJRx84x0U+ZnkuKCu>GAHl?0X|uQG$v3!P-KOuab=l6g z)QiU&@6Et-llUfkJo0YO*V_5n+PS|YI&vdwh4+-hblM-X@6UqXFNrPIJK;<@F0^$m zC|w}mRUHhG81=Z+{nasp(55{erb<^gULv9D6rKyXTBF*tZs=1|pr3sUjNfB_z8##I z!$Hvlsbni~pU%8DmI_4su(55ZzrQ4!b5!ASmfHnQV6hShiL9@0^G*XxBu|RUqnrMpOz4~`4U9Bw*) z$EenM!|)#+Ez7XM#?RlFUp!+MDb^6a%82>^x_ssmKi(A^)uDbYn*VZ5qrQn579Jjs z6o5vgIf4HW2{l;S-8gwYnwT1zYizo`nB#d}^Mqy*%c13w$#bX%)XuJCXDUl13gvnK zbH)4w#iXmYDz>_b4_lKjE-Nl#|Kg5(UxvD&gkW0%tOGIR4f$$i+H>6n#}*v1AJ|3*E;jxv*=7r%uYvt=j#1- zQE!m^<(M*EM?A0XFV1}p+)-2I1ctjKQ zTMVX8n(b-Byk3MzyP=?edi_;Ww|1&O54M&%5-lMuO)dk* zik=vjT-;UNx%t7qG^K>6r}2b*!)w{y_HP8>>G8>Vc4B2F&5<69@6o8^&>&9tx94j= z;u%VherT9TBXqkPKS|)9i^*elwCEBT+uuHWlb+5*zc=EI#~DcvN{4pZi?C0zBYG?% zBJkDZ9Hn_R(9R2(@C<7=sZd36L(Qt5VB)~)BwY!!k4PRan$v1y$V@-1cHFn(A~w7c zL?6%U^Q5V1*(wtzd@z{t#m$s;ouo+DiOoO{tQmeLR`-2wczC#i%V$z+tF)`0KgM$k ziLtbgW}Nd&sS_E8HOT}sF0N9)=UlPTCt|oGG~*kZyT>9|pWlbVT6jjXA83vX`V8Sh zJXb$33vp&hgO~b1$m}Uarz7w(`Q?bTwpAGAp3t)Pew&z}VA#=@zfUp^*3PfL>AF1( zmhNJFCr8RwX%;l%z{L_>dn!jK$AO}%)%XGx?^MA2u9WYfS2Nza8n%`e#TQwpuyO75 zzVR!VVu(}PQi#agRl8lJm(45E@YL5jt%x}GfHF?;JA|v{Vm5Bx zvQ^L2yiKdb?Qcqh|ICBQ5;2r+O$S9xVH)~Vo@OeVj1APbZ0)QauSk#wxH?e~-sdrw z_i7y3RKnIu`mrMGmTI0YW50j=wz)jX)?54e9}M&id34fUwr0X0m!;#LqD@<@EI|w4 zGq)FdC~(!D`_mWDdU<-1`TF{Ts`}IfI4q~7r6szN4kklY+o%(~<)1z=#XMRH6;Ea&iweCj4XQmLz zNy>^r=d3zb@**LxpM;0~q6qwoVa+zAgQB6;x-&cGd@9+=ZKx~p$nK%^S<~Zqs-woGm6P?U?%?=am zJpzKTDpk4OU*WW=Vv%IqCr>|DawEE{=c4={M+VV$j8T~Uu+`Ec(R4a#xIT>)zX5jS$gIPRCt~BZ zNsnT#0^!QKvSYRx78cf*loV+NP@M8T=Z$D`aR0{yrLYmhk2oI;ajx-N%6#5C(v2oj z3i?+RSPv=5@!N&)*o4kg!B5m&syx@F`S;3BxZDD?Mug+DPGmh}v_`rUGQCXffMYJm zbbUqcPg+(>b$Gf^Q17>}Bjvqo@<;zd@l+T`-eK9j7r$G;-&OQ&oH*Kb3TY&8#xS^n zD5vknuapU!?X}*xHPGX-{{1l%NJvhqYVWG{eAqfc3T?e!IOwZ?LcjOXN*D~PfFQoT zv+1@j&UHS$bQ9@G(tE*f;08u!XN#}QQ<^I=0`nlaT=OtskaG?grx{PDuV9hJgSCNV zzhYlac4FIuRwH8K*uhF2^M=OnPnEP%E~BLk2@0PlomeIBNEUeMuQ(ZLr$=PgK3o3$ z*z15W(2^aERG0VddY7~Nvi3HH3vF;n~|%?|HeG`p0{*xS=Qx??5CVMCa0O z{maA$s!H0@4;8Bo0$}8fSv%V6^_A@PNi`vQe6mePQu`q&v>V3H=?gq~xtj8BrM$2u zp6_ZG2I6>er>JzieO6NTJfSNRhaTIzD(A(~yJj#8on55wi5r}{wk2tMx@^eHygF?v zbd*GoAV^6ayGWEeE!5HO4wfD%V=>qB393`T!=I<6Zw( zuFHb%ySOT94^}CXwg3U zmmr~tQIog)`BG%W6yjI6$9zflNiFx1jPHvFXMuRDcMTJ?UX~Y4p4}+U`A99U1Bx79 zgfQTw=Exx;NEM&=i-V+YStn{7xdvGl{ibFsSi#hE?NaPo6Y2&zIkOj1Tl_NhKX8AI z=N4q5y~8#;FI)KI&GmF`lt20u9>LG9m+*hW&$Sj+5!qrb+tgdR-Nzc6f20>O{$T=` zrr~2{Z!z}G7_p-+LMM@ot%HLpHx@VI%%j3p|q35qkwiNR;K@b@IYGRjTi+5{o zrgkpP5Bc@$*Vno_J?DY9&pKc6(^F!6gXJi`MSjYdJYcxograPx|im+*1GQM@Wyo-vyTk zGNeSXIAR$d>{D?;^Sf(67De1an=VA{+uiM);;l`#C>w#ekxzEGxUJOA^*0`$##&si zKT9o|2T2l6PQPdSR@BAbR`8}OEI}`_3$&-o1SZ3`F?OmV9qyx@m-^heqq%u&|A)|P05316{)HG#}3&)FLj3lV1+W78OY$@DWZ zY;*<~vvj_Y2Qfi<-C-@ax_`an@X)E7IZrUg;q3HurJK~Wv`sgnnmb;x&5WloY~%y< z!H6}HF1sumJ!cwzaMGg8h^mT8p_-iFxZu~49KxSP7$KGxDIWQf;zRSHGnpNKzSpKR zrNQC-5M95*49Q)iThlqIN7xJWXE!rCU@OYY;&F_>L2y8Le9=8%7A9H1ZJ5Xmvmd2| zNY$(3Rx{H!vfZ?Qg4n;HwtMeLK`*%-erRB?B6se1(Agq>z3e7}kN%Ly#XjWI5XGz3 z8-lK6wU7*l?$hHzdux2sW%ZQkcRgWg3&4cI_{Zlz zA&})kTyGaY6*uWiUy>G+I*M1KXa)EwrEjdlW0Sz#5~7eL0V%(x4r%`2#bR2IP&!F! zuy%KoBSciEvfs0|cSnMBzR5t02Gm%27B<=&N7H+>*6Vz{F;J!LQChMgS3vv8qKZvQGpJvH+eD&FybTWc^a8zxd+1Mfb6=@2- ziZfNnIJxWNet>G$_>lilmYFRmmNCRsK-Y^@uBO(j(~PIIWRZ3cL3TBqb4x@)WjY`k zhh2m(%r*xzfR6d(v9<{|YzA93u~C~1C1(U(TAhnbB~OzlZGgPfmY%KofApe+Hv(0c zEy#%L^J?nM+pw8e@+_3UwX1`G*T*M2r9D*J4~*(g3Na(7I+Idp(glcbWt!#{8T^d| z!*KG$9Zf^OV&S>Z+EXngMpB=uzi(bLq#?Iz2$xn!r`~~Ku(Z&akJmYdi<`-nQ7`ZR z3qMbN%Jv=ol%M?4$>Lr&AOEU!&r2AR?<#Vo9IFCFjPfvH4=Lj`yu!U!x+luDx-a9xv zT6?-qqjI7~B&W|o!vBmd{2xQ}gy_mzog)`kSR)c91QN8Gn#b##b}$VZ-(LfPXx zaCy!m2 z>F)V{^RP{A3k&_HQ(>L=j3g=%oO3I8;}0$R&(e1#6)hvRN8(u{?lxAVSNBqawvx9{ z$h6jW9SC~{O1HkQ3X@E!f(;39aIHf^cw{0(2vFV~%n&Wfb_3!-06ctDzHaW;SWT9Y z7>wY9&bp6IL~$i?O|+6>xuZRPaaU-ZgRVsf*WH9NW%qK*uV zn6kE#;d13#j833fx#Smx;^V8UL|hko*gV*jT+JOq4TL)` zL}iMPK!@-!pt3iIR(K#EiHyi3Z1_HGxyEK zsvXdeo6eGZ;yTH)JKR(ozW$3wr-k>X?zasSNRGRU(L>HWF0$?eOY^boy_xKu{@_yS zpI<3_7e{ga(XN|=NRUk5vzKCL)0We9FD`c^E&cuPJ;1g9YJs1x2ws2t8$tj9cibXz zV7%AJFC-}j+|wLzm7LQJ>kR{`bmTcmg6H;hjlO;11Xcrufe@324Obw=%c!&8UY0WS zZ(1&T-EJE=!v&NdarO!r!)u9L5&YZmc-jU_{O%f>IYVN{IwjYNZvULSAOjJ^%$F;@ z>>_JjM|CE|9v7F^gj1fKpRe6rALy0tnX$=hGah+vY~z8hC`oz>zMoe22-!Y2>E(dz zoT$e>Etz)KgM%Zt&&~=H-Ouo3-ApdgOp2+3JdV*!W}vE<_utcMi(d#B=KU-MS1XC0 zsT#Yv*4)nuYd3M8_jXCtJgiJdSd5qj1F*3 zyFYX#>>!W?)+{N$23**6ACk6vPpmYR zDIUL_p6N{Gf&~$)kKjM6DJnZHR*{XHvTru&JTzDl;1>whntPcS=JUjRABcXt#eyUx zKAy*Qj=VnkrBym^khbo!aK5r{Kp-ge984Gf#+B%IHuENa4*vj}NT`&+ORe%BJf^~Q zH^Km0{lthdV(lgnV6qD)Uw3B9h7-|j+U!cv);}~g%N{o@Wy4;md1)hqS@seV{*d41 z=I}*1M$piM8J){mQ`NQccWRnTS)nU)dve|_U^&xuZ)nohm>&c}KT(yv(O5IP9P<_$m&LRP^MpXnIetXd|D(E z8|vlH4qS|RGATZvd<#~0IW&lh|0(zJA}K!p(+DQE4{xhEATO&WAEq<=dp{7U!=|9FP*1w?tz|rB!~wi0k^Ng zy3U7^k*u7D7uS1qHs@&h{{72SztXKA88te$=kd0Bm24un0Vw!&mJ&O{wsJYa+*M_k6qVOt z7H)t#i+273-b8HdRX$J}3T3j@O|*u$DPr|G^1Zgq2zmZj3y}5vGnZBAmQd4XOVfFg zV3eK_%DLDaszt;gsfoSWw#6=GB}(Cds>s*Q}bm8|FS z@y+Y6+e~SEFIk)2SRuPUY5)WeGH^lyi-${}?zV?MKJB58tc#mUa&URc2NLPbaqhMS zPIxcKTVgGTD4}*GQMW_6!U&Hz3I^Ikt?=UBNT{Zxk&fyf21lQUQSN-!TYSWs?93ec ze9Gy!*3zfUph4#9Gp}ay0@(Qp?(Z8TuNpvd?RI(RnUSr$2Ttq;vfPvR1d4b=qAo+5 zG7DYsGCt@uWSm=09;H^hI?;gzJfV_0Al>iOx%6%N;)B#mcF{^M^@$0Qv{3{Dvk8-= z!OKDE+j&wkNn+$L?~3R{DdoQm5uL~vyvQ1?H`zlY4J)6bsOG$b{h^8=k;6t(SjOcD(7Q$>7l0vdb60Ms#HdbsdY~S{GOb8)IafuKoqer*_uS@ z-T#FGF~o}}*xTw5$*I+9N|)-gLp5HJ`3{x!kWAEIJ^yAkujGd*9?i4F3P$R3o9Y@L zSG#Nb%Jts7WQJkAtEL!YemJegF-O+2F8$0UQG2!@t1-K@IuG??L zesA{dj1K8X7zKyeYp#(C zA%>6Nr*j6FJog(lU8N!*2KEbuCLxUf7kE_O$IM7n-9=f@pfaejsFXUbdDQTS5*=u+ z?Ac_kHT?K}vq^MJOi|gCjGV%S7Zv!LZW5`tU*TIa`v>3LxKGB*OGJMaaJ-I*koW%U zH(gy5y;6}3hS=<(w&;ivXB6EF)41q;A*RZG`EMgB5gXY9z+ET+trfh+2j|yze`RB0 zub8^$m^)@K0`>o6MfqQ!D1oBaCm3I+8r-%u2lU)jZgR1*x8MD_niQBwjWxm*sK)LZ zKK^A~Po4gXn?ET;Cza#M6_eX;tFws>$ESud>u%HMa9L)Q7eS?UP=l>un1I$1&-KuX zaFRXx+nh@W=DoC=?Gw}G6|elron#k*m|eZ$M344@KpI=zu>o6NAW~M?OtK>xT{$ju zG&U3mx!5G*(%-ZYsp)N9FXpFHZP6iVZLZtzpU-`H|^q{T}1^%$IQ8iRCKYjxDR6e-HAp8qm$xuA zi8ue`h}5g4A!yQn#fJ%Y-7-U}>9JuP1?c+*N#l{DoG_}$-Mfu<)70KLXMEg52w~Lg zwOixD68wZI!d3_5fJdxDXj!s)J}Kv!Jxep^sgMh=;v;)RZU>w@$Pep?TloXt10(MBNTiZ8$Pjm|#5*IPFSyR}yN zvYMt9>l?#|Zg#F;O|yX@f5Oo`6#(tRd09n^U)w(06y1&6Kr6?A-qeYUqh#zk^%R;a zsy)@(PwrjC>%{uIvyus!C7}3Aw`f0R`K6HW_iR+6rwLcARCMIWE(>QWH~a zv|M5(Z)auzUWIhMJ;#zA!FoG_f{GV5NX-6jr@IFmo7_eDC>h7+tv2n0U5b1GY>aSNEt|YfQ}DS#dpvdlOsPLoW8^8NP~6l)mY%Vx&;^SaLqT2j3(#1! z?dfwE=5wY`FPWL%PgAb5eYV+z(j&Dl;VLEcRWR6p!FQFU1+%P1Sc2NkOz7Ois1-O! z#b^v*YSyHz{Bom0C`o8jUmL#l~PwJdrIuXye4S=!b9G8h%kL!YfX zDhh=A)~Nsu;D57tXi3S~L_t}N%gKZuGbOa;htGy*6MAD}R%2ePvw z-(Fs-vkOcR$$N|oChgS#8(lgWDhZPXO*AK+Ub$SkZK!o-hq#46Fb?Ali;W{u{mal=;N`Qm-x=7lMe zHEdu9S`d^rY}o7$8_Owxa|Kkj#1r*)aNeM#fBr<}7t`LTF=TtDs&8W#vW&HiBAxiH zNEjt8P5D5YNq|l4{(}Z002=T!0`!ZWN=~Br>~hjI_X8{fz~J8ti9;V{eMQz^TUWA_ zYy2<|@yZBVWHFReh%0D}Zk$PV<94H?bCa!$*z(yAuj4dvZl7)V)v`rFdf-dD*1%jW zhK~S(##`?&b83pLv8nOUzy7`+b%kVrvYk;8L>x`R3AUz>Q9=-`ublmLnGBpjhCVoV z{p%MjgUc{}4G`cA4%fJ>oI(Ss2+s~{|1Kah)1=08FnduWfy*?tmjruxj{s0f97U%i(K}Zb4S`O51rw= zDZV<10ep)k!4~W5n5L}64*;SI(?A|W$1UB%p?{im004T}0Km33cew9x>xMFMn!4YgG6~PJvw84$_=_liNCKNZZHq zIWpF60N4^J9e`F-BfeK3nDwkRlH2o&m)K~iGC8wj3n;V@{ zgAXR`BAD3mQFK1dI3p;cjWD~!>Cu#P%Y67wIPz@nclg^k{rnzI*}B9$@C=-<;g909 z?I9UV9--h#slABxuUdfbWMV&z=xNd01wHH3+BU^$XL z0+yzT#7m(r!qV&CW|M(EiTU}8ZRhw20R~`M#onz-2@hMBhC0!)J_77Ln-8-`uDQ%c zj;AkI@TlY_iaHql_-}UqU1~i;00HxzSP&-3)xs zv?DC6jvOIu*5DxVXTiMFR^`nj_od#XMbvGT zYI_CgxX17@vmYgGhpFF24fS6{5mP~EOHZWAvA>pF(suX&v28R86!5(=dV|Oayhgkt zy&*1~B~nK(MQS!bkH<^TGHPcwH19o4n04hC- zjBqZ*u^`aIG7?~b$>|#r|6JO(JxeNnFv<(*DA*6yEwOY7P;LbRU|5E@uhqQjHpieS zTQkZid1aoKyFE|x^;8~z8h>5VUSb$cA7i>zIk>K$9me~8?bUG3D<8$SoP5EEP1Sn^UofKc@2V;rbQ-K)vW#ary zNdZ_RVUMm&RkY~O3?}dt+6CmjPrjZ{FFURv1|_!>6#w^q!od3s{!{DKO~4eX854H0 zN4mdnr!Fa9`cn^qbd9(*)0ZeEi^<> z>Z1YHN(H2t^^!#Kk;gh!f(FS}j9RRWd^eZV5#jhGdbPn=>@P<^ek{DkoqYdOU=vN_ zVO!t5AAs@0c6F3zfWS*%co|E_F)I`1M<*=?fz#c5#wOBdrYMwTiXD!6RZ^q2kLk*m z>K2F~m6ztg{b&KV?UR@T+_rMaNRc;PHOHpk9$&%NsG;3c+gca{aBfPMsgCQqy1GMm>l-qs!}SG2OM?WPOLL7V@j1osgq zT^}G`@Hb|8%nj+Mlr}IHdf*NJT;`0hT$R3?VBMP95PY%Wg4rNeZ8U;_lUqUJn=M-f z^z@MBS}TRc@+6#WVQk|xnElQ{O2HazXSSc@ly;W)jtit$3)_FLdGiYs8#97;%=*(0 z50eF8*cG(z8^uDH$ojt{WrdX*+-{cgP9~S*U-%_GmBs&u7HK1QqzC2GgSfak^?+my z5(|HKqD<6jUTLm_gqB4M)8 zyXgA!6)%w70ut166Z{eznZ0t%c=QvCW3Blk&3L}(eWi@+6-F^eGAP@Ed~`KE2~rEWB4(Kumt19-p}tgNcy?G!P&iR&lJYwaHB4+7zBNnK**lQ1M%2tNDS~ z$8RzaIML5XttQ`+={Tu+7od)<>y3xr*%%PKcMZpWzdSR%DvVl%@;n=L*+oLIPG?2y z@qUPe{-VIyQ^LLko~Pm8N&N**k>nh1*#R|LOem{aM&>qK+enW)t(6i(EJfE|>P@ZuV~h%IYWJ6aPEZ@gnwqy~s%vFV9tGN&bU24Z3J40uTis z>cIj=CWH^OP^zBKjg`uFu>Rry(*Yk>Rg<#QzFL-95x`cPA+#U%Jt9_-I7!^Os@d=p zBTCURMr30!T(L|9*|T0$Ivr|w%JcdUzkue-rAIIo(}VMCN6KFSvrGH=Y7{E2U_c)q zuykO0-ZHSs)6u&y2Vn^x&bj-(>X2N^2oQ1}E|Kn(^rYa+w(U(@%qs>$ps0-x-0 zb^;=Q*0eqx2?AVY=K#&0_L_Su$ty=>->Jaqw^S5$m-rcVbRv$H7b@g(bMJ_5g*n#_ zUbl1#M1k7sCMFPM>k)J%LvDgPrX!?Au5-2c!S%)$G)`FkNe(wu;Da1TJg7WD^>M8JBsADzqW22{EMK&;93QWt+D5;?WGOrM*ydXP;Kt!`yxnJ~7v@SNk)yRq% z4E>L3NO{W;5>us?t>CpuiA0Tm#0`rp1};_@xUDLde0%y*`I$#(^CLS!HTlitCFz`=i!-0ebqu<>#|rg~#sH5f35 zCrg6cQPZPE4bRB>4}t|D=VfmBbgemeSv&=y93oZT{PM_;FFVi0A?mO8&qy3V!ePg?6U)L=UNLh6Y0UAX z*(Vq5jb`@7K=1xKJ(owpXV0mrUIK()Q>%RaEZ$dzE5imCC3$8>IiqN#1lxf?Dgdue z-w=*)fBnyhIU_A5uhreF3~Gcq3*-|RBVhFuQlDD>r^I^CiY&X-lH9s4Fe5vGDo>r9 zr{74ehenAAT1>**3emu~2cF4r{)tXh#TZcadv?czx30R2nlhgs+J5V7n%5cuM&{Fb zLFrTV;<5Pf_hAE`G7S*X#BHd3`PP7a-9_&r>Zan=X{z;wF07@m>FL=70c6sN2H3)5 z##Ts#BI){X&*#g|qDdVDm@9BCGni+WJn@~L{&M8^A5W=^E6UiHD@ek68)aPs%K@38 zVgbq&CxVxH;I0Pv-V2C`I)aJ#v0R|ERZVV+8Z?i-^aA4qCMTTKPg&o{g#!Tr8yn=&IGOzR!@V9xbBrmU+Xh&|ydex^C#)bI-4C5V;b%PKLh!JitR!_U16|1aNUE z6u@6wncApD6U3A=tG=Ii#yfwKDJV*+=O5bnw z?Cx%{W}60F_4=1c0ky;{*i2+BzTrrgYk`wfP1suZZ>+1rm9LzZdi>jna8fu4a&yH< z{|T6&4#Oa~JJVWCdMeXJ8}YL%b)&p=TQII+7!W{$Bk$6ak36uvzsmoM5OVM>G6FU8 zRwvVau=WZVnEDCuOb3FTxFePh3uaixIX(`O}boQdOpA5tbcp1dzvH( zkz|6a$T{XEtQAE>%;=i^N;NI~(PG{Ad%M1{;jHRO-OuYL8}Rwj(MZeog1BbQLrS-X ziNCXhTacqkV1an}HpD<0ryz)Xa|h-okJKn&iH{t4rfUrg4E`T2XZW}QlrecZRei>i@R{7*AJZ3AWfTT5ISMb#ihL!rihl2W3 z;O`=;BY;W8{M2o22N?&17*pHu<*nCVC|Y!`>c2G69QeQKdPD=yLaSOBbw2#hUXW*i zy};jY5*n0l9j5*jspk<#0U&=u97Xm0b6?jg1kZmCm@#0;_}kcs@AnCCIaJVExQvSF zQ&H(DWw%&#MUKXMWp|&H&zn0s;FT>XjlPsm&Q!HB>U>|+&xMtjgW|Cj8Ha`GZPqOq zrQ#QM&It=^8*YjxlI3?E=H84vdClmJ=;3VP^`QKvc4^V*6v~@wUO|gb`u02%L z`>L<@v+Q|(w8Y!D9CLOFcirAJg(oDuW7cxvD*~rn=OCR0EPZ~5$n9l`P_=ecc3!i! zw(Sp~7K|nVE({VR^rM8p1_dI4a;3YIxn-dyt#x|r)lByIv6eB&KY+|u=SeT^qP4XZkGOCh48iJpf9(0$kaLe1Rac?wY8rQcAJh~Np>teNq;bO3edrh>UC7OF* zGzk2D0Qq8%Vld9>1^f2Rh`CTg?~${`88R|6Zmo%Ku($|CgVO{=8|^)mW41XLLwrY*euwx8XQ548&*> zf4*}zk>3v3zFR(yY*$~d8Q)R7Tanp`=|dZ~F~AH!v9^;W&Oad!6#E@~7*FhJf1D^D zPx7*7DYV2M&Byngwam0mq@p03DmLQp3h{O@mMK6#*;W70j~c0cD-;@P(E!z6LtOfV z-Kl!#KMlXn!C2}ey8Rx1E`d?_>D=q&{ z-4h4%F}`Eh0kte9DlO{Ud)B0~){vR-@pa}~JQF+aev^pEcE8If6SNfi!u5xAN&oq$ z`}rpE)Xl(Nh4>lepEnmZNfB&O2$Kc!KFFScer^z;fe-)aY+#A<6dQ!3M(%*aV(s7% zw&0*=1d4r1P)AJXJsvjF@OR8uNex{v)47Pa-F1tye{Q?;`JLe&x9e0se_kYkW^m?R zHo^G6S^ytn$F9##rxRIgQU}cLSiR>|9Y?<5y2v>B9cz|4|e2#qh=L?bVy8qtTo)9CO9dAax`R@>T&;wAfaVStgLCJ1dIy=x$r8gI8; zU^3BoDLd~qOaz`yHcwX`#_z1P{<{j&N38Lwk-BSk2^s3iEKY+P>qUfG{1*H0a5TdReb3h~0GLN1TM0i3tF!;^?!DL1(l z4j9OGH3)CSo~yG*gYXMHLxPm{JmLR9&|wTm7nnO5-NQW`i5W>kYr4|%*&P3@hin76 z7;N6Opj9<5Xap(Wp;G7d0Y9_@BFf?&)_^9#y4B50m+K<&wP_ zgT7eo-z`hNvNy$tw6|E{o$nVUla%S=6%(tm37+^6kqFWa}}=n?i9oF4w`0#VrNY9N`~SAX{+mb!Pw|MWn&;1jct z>qUv4e~U=Q9|>}GpZUdw;H@3)J83ur6RaIqWvU!EzEPyH!sDD-lJc&*M6&zm{o!T_ zF;$zgd++&Oxc>vdgEofP(6+QQR-19Py|7RSB`T6mPg^PuZ0b`DoL8>iHwoYMY~0?c zHJ3pNF_q<5O;ON>?S8!2I2Xs!$U``--NEbP-6=Q@hd|+rs{%kizd0R_aPGxLShIse zKf=me&1NXc^0&Fl&DNi$^ca1nDD1Y|drg?VvEhsaq_%kyF zke;=zC@3JMu8W%XZ<^iY6h54adaT98-aYkcN4c^1Z8eWGuila~_0T-GX~omTwwfZx zC=w(lBoy?>hHWRX;xVt+Kl7HE+U*Y^GEwCX8;%aWe=UcILAP!g9BA&)l7yeHCclE# zd=qpOG4y1QHi%jDK+b2+mHO1NN#WMjY91r$)6{PF-@jEmS4&2B0}T)nPN0MZYT*8( z$Gc8-D{U>v_nstFw8<*9w_EWMAvA2gH8u7M}=)_s4 z{YBF7qBG*yBl=sps8G?m8?Zxkl7DMd7`|-DsSjs0fHb3mv{76GcMG_mv9J?R=kD0k z>(2?hliv7UhK49E3p$sFYO??UP_0HEZziWe{2ZaRemS-jLQyqvzB<{C-VHyWFYxqk zpzieL{iubWq1*bkWpaGF+J=n+;+6S53NVhL`?=QM5Xbf4cz@@es7E;%2)?)9g5Z0# z(XED&dxdOratf`kf{3#N`5}e^ucpy;8;^#oNx$*&(IfLTx$RV;=d1z*%+Sol9bBI? z?1_xMJJbP0Fn$B*dN5UhH8W1cP?{&rjyDdu_dbt_dFIUm=TKB8@N62;A+|DAP#>b} zL3U1~C3(XP7o?EwLW<~5L9U1itOYb;a&moQ`T8-pAFiX}C(pUmS7fSJ8owiBEt})a ztj);u4*b515uJd#(;qRh$VUkv+4@6P0*HzG|B|EPK#y;axI*&>MFWVLd@}%z{aceU zW=0T+T)ftBuJHZXo7RxqGMtH1>KAo82D{S-IW1b>bL!MVl>QG>vjl84^89)D2=HO+ zuoelM|8i2TI|?y-o%=S1F-9X+;v5(Q0Gqb9-AgUE{=WrKnr$S(s?^v6J*gunkTY<> zq81Ubt@s%L(~9`uF12jSe+%A{ZwD#(2*F^uwBpW^rQ7o@d%NBP$E7^4tRB?I@6K4l z+xHu&6dw*09{i+~_wGt6w?D?-amTO$E6fNU1L_vIh&RuQT^ce1BI4>RH)1T&1;l-l zw*bkBqhv^YtYEnYn(GA1j&#T+fcm+z2$WTf$O>r!FngQ8hym_Cl(SlMPCBt{*9hu) zVQC}XZ@;*E;x(tsY#*B|;7CTv@KKbiG3YzXl)f z-xmykrRcH?XWox(>fX1C1wl;%SA)TI#x9Z@u0u!4;#&F#bu<>Ry zU?==Zf!oDSB2^B0&W`55sf{l7@;tPs5FkB?@PBJmnsRy=+@4O8Q`d#7n97NGC37|(qy*J z3L{XH>ORe+1b|<@2Lyk-KdUd1OK$~-P2f>LX6N@O{KqN%F3cwcMhiR-kjbaKExX~N ztZ3~e5-Y75z!>hfwrI-Lq#g4jW!)tWvLYuRz#pzYPAowaVFmz#YIX-yoda0_4$1_e zaT_Le-Es@ErwEuSXw~@5j;N+~?7`wH4vb|y50s^z z8atv?NcfZ;M1O7Jd*ED*)K4Q^aTAa1{vo;PF5>|zdH%c4t6ls$+%L3+0i^FYLDG8q zO&r;&;QOe%^!JUge}Zd1 zWveU`U{R@(_3Gem)4Fac#zw;W72<=j^|XhYMit&SBZl3uh2KOiMHFrT$p!!^vPU~v z#-TEF{Lh{xJL^3xRgvB#ltN~2uOWG09rZIrw-MQwD#K|mqp+^@Ay&NSqo{T(&o}u` zTPda9VtK>)(pKIHRpu-p*L8jn`G)e*3TmP8i<`S$R5a!?50WcDxB@!S53F>xQ{5i& zmmiSdc{-pTEVO*E(s*B0S=54*nXG%#Ft=PSkUjV|>=AjT=Yv2ebiO+jA2GpTMGn-L z$$F+k_8!a2u^C%$FMpptln#IoMs_tz`tNaaPOopv1n1$b9lMf|pVL3-|EQ_dwTi(Z zC-dcu+rq~Ib;X*9^}R2J1wWaS&pn-6W8yCTm59iSbw#@w4=p9Jv)vU}Lecn+gyWFP z%Eki5FHRH)g0XnTOE?dC3}`9&^A#pj4*sdTd&R`dN+Jx)XB814jOJ;L z$l$;2k4KkhYC@N%2hVOgYWMzPaMEtgv%J-2^5?{@-I{-O{5Gqj#h!h|#JdEG`~I?3 znl~wgERKO7#=^y%n()|ldSW&Qw3ytwK)k49S>W;jf zuXt!vl<6{+>Eo3j@P16RV$>v{*L={f|0s6brrMX*Joil=D(&}I(gg#7XJPVWvq_fm ze$N>;NPWme8Z^JJREP#(XMyg9ycQkGYF5dCLxS#YHz|@`R7<6+t`7n@`W5?FBaVcU zyLnzGBY%1MmmzhU@+%oOD&^Qy>*8>31i#6BkF96(4Svg%oCJ`VuF_l6TblQ$bibk8W*B=~ zpPPvB*OQ9QidTG5`G^z(qwm>#t!HWpc6j7MxsVRBW$V6{vhqo&%FgTwBsv5MvRT%G zd+@8;0&l_A!|cA6N~pmb7w2>@s34Cx+1sBQb|kcsd_zWlyn6Ekjg0)B>~8t5t^WMF z%Nl#D{{scIGg>chZ4z4A_{8BgTUq5~x_(|2`L(_S*@JhKl1}IlTG=qNDD$4yi1?$p zqq&iii^DZh{YNPA^&SGjwCFq(k1j?l*T@$AX*69hF<3D!7q>DYNUuL(ph^eOqAUL7 zCD61m{&L&@yj4yy+RTA9ApZ*Wk=yxl9JTL*1^B-A5WQpSL!yV~>%O0r=~EKSpQf1c zlYLaqJ6tY98lRe=OOCL7>p-FvB>{$SioO3$=d-dk+_(7K+d1&jpWTI)?Qv$ClR%$ux z8C=T@H2Hh6gy$r=ugIB#1NP2d&o514e`~L|p^x#y2@h~?AV-!F1G9oow%stt-Y?Cg=Ip;+mp9gkDaZM-T+ln&}ym-Zc_t zp+Gp~Ixc1o{Gy~7qr06p*sV}!8xJpK6-Fk1w=K1}lLRUj76)4|H0q7edHjD=ePvV} z(b6ptT!TY!PjGihaF^ijPH@-Y4grD7E>Y>O#4500vS&u7Tfq@sKmHC;Zokl>iknMD!L&$WZIG0*(PM_QWLf(FPtw2L6|V z!o+P!ZoixhNIi(2A>f>z$l!1wH9h8$+fT>?87_BhDyHC#&-q#Q6U5GK!_pyZaI9ol zp$apy-^tPfc~44%Ik=t64S&SM6KqR}2A|36h-k=vjd*=+9}MINw&s|~JMAb5e3ho-+9c|Cr&YX(mUkM|uO6a%J**-|l8?W-+ir@cTz%?s=R=oN|-X>!{B4Lhy7 z%ZBFm5ScY%RQNX_qGQK-yZM!w;GPo$LH`%b$G7*fQ$T&ipbD&;7kp(b}@ZWf4iJWW+I6G>1}nBhd?&rGiR&L$zO&M_WVfR z&mRcgEG}(~&=?xcF(q0ozn6hEmw*IIS zNjg*oMe4*aX*Hb)Wtb7tP9NcaMZ)6s4IQ|Yn>T40bAiYSP^A&SQokQ;l7Rwd;@qxc zydbwN3Y-U5386rL)JtTofrwGI2zTJYcH43Gs5povHIP2EH5v!ZaT6aC0nz7$r#aw2 zRl6bdodp_3=ZpJmcBc)-JTDAEm*RluZv|#NeUmQ&1h6u*?kS_*ylj$YBCYP0DGV1M zJzPv(e)Tzc)8B@5#em=H)SUl&Ddp?#s1VbKuyq@o3Oz(WjN<$Tu|sIrfxSI7&i!wI zMR6WJp5jQY^Y`(8Cw{2W7Jw1(JMA@up?m?i;@NBOg7q&y1LL?7q^SW5v~h!l$b7_w zCIrWov9TeybRIS6tH@)A@oQ3kRz}>DS{;*Xj1gVW6;NkW762&QvV93#tmRb40vR1q9ky z`Pt%fo~{K~Te)l5D^Q^A!{11`pZ4SkpL==g=&;q_kng6zcs|@q5gD+AWvC|I4!6{? zX2{R)YwvSsU$amWAobSt!hcBbW58!wFLvmJ{sfN-4_%?)F4(>YMJn=04q%k?39=Vp zzSO78uKVYrY9gqUQTYvou1CIsUCXHryPllv`!~FH+>b{Um){a!M0^}bN#?w=y`E1x z8t|1-8h`1`Bc2pWC+K`gPcfHEG1qlkcBk8?22!^x`&P{shaBxSZ@Me@M0&RHmX_1F zOmVzG7O#_KyR3VD$`_eDO4;wtQ8+Sh$q}(03_=&nPPhYblwl)EMWOpN)^7w5!aw@m zJajf8|1_C#$$4n!pCI-_l+f_pkXkDa@WoM>ld+hlp8jAXXdwLDO(j@w%TiitTBp^_ z?-|`Cbk3oszqjVQt<6vLuC5BZXm}?u!xaNnY;0`pSzUyyH+# z-{>D%TRQq2!r+afJPUIrsNi&K0^7N(y(bGB)X=}?m*@$t$;n7I<-|JGdkCjDMG^4z z!0#6>(_6$@1PXB!*dW|IYaJC$SN3#(GX+j1;iAQhPX2;AC~Aj?q8~eUgwnWCzr+V# z8uM6vl(LVB-8P}N$j6*6mDM!m7`#5(>%3O<4nrWs$f1Fpv$TbSEhdhQ)fwCUw%A1k z|I#)M3_7b|=V{^evd&M<_ldP#I|uA3-VaEowK`i*>Fj2Ld5Gh2mjMueHoy9YQ+k0L+1>Q1F3RX4u5GWLmdr6VUU3|{9DMlQq(%<1ek%^khd2xSG*V$@D` z(os*38fEAA6L2kCzsj-zA#! zdBPj8;(0j33JBsAdT_%dAaB3pHU`%H`O| z=J&#s6{V<3N*9Yhd-F@vvX)|0Z5hGs?&o?vZU~f3E7OW?Sq1uSKd(IrF~XZ&FX88; z!tsw2ew(>O8v30QKLi~g*`rU-%#Z47uCeU<^L}v$B98b3LRnCz#+#`}(k>yXTBG~L zcl!*}wU?SW+S%45b9IVh;1>n(Xq-)s3;lU0z3uJ{*1|=Z5+`mO3;SG1_;V&dcW69w z-IAcmCGZO#im(S9NuZ?8;X&QhyV}uk43ZxEnhX00bysj<1M|moYh{ISqSOFt_6w%{T- z=1tX=R6>kUXSxrlVCwYYZ=;1%3Or4;11(%m4{v6#Zei`U^9J-kiE0um(afuC^wKkg zG@#0qg-X+g+CaoPtdF8Zsgopm&``l<{J562k8`441Q^i@?j%Q(d8&n+l#A#rW0Dr1o6*h7n!-(R^=c z4-sm3(P`w-p8T2g)VUFVKrq;OeLgsTa-k(S$swokbQg`BXzG*sGd2fNl%qsySYIOQ zOPjV0LwU`vZFB_sC&Ep>OZ`OkSh%Vo%vcmSm>vyr#Mhwg|5*we^Tfp@Ih1VSp<)b~ zF)?9%;JYZxbWWrb|}ws(RrE%Fix{A7o?Wr1j;G=JrIbZp4Vi-bY;o#f&Tz z?70>`;S`T}PyYUvPEwN+YNiG^&fBsY9Y(9gi_NH|jddd*x|gjwk-^v+Oy(=Yy~Q&q zghhVd#v3SuRHEp7R^0TRmFzO#n{6aw4I(BkHy}=_wKs?2^ob83CbaK1X8U+?(dj~k zMVHFCaXw_&W@DwsSmqF|pt%-SStBq4<+5`&aCX3V7L z*m1LV&Ao8HHO^^ptz=fIwgg88{LqK=wjV6Vqni;jlXPM2g##{=j_lY4@(}VKV z;(Ge@dW1!heY|-+6wD#EE#^%u4^7o?qZ9pf{|W>=`aC|T2C$s689w)}ZRCjDOf;X3 zm(ZBzEZ#tgH2b!$--9Z#m5L*Z64hE5oEDC?E;yAKajU=z)ukz42M5Ketka%F?%1O016wcJ9_*J_?9In@JZ@j`(NfmksEJDnzx%xN zL7dFz470S%7B6B_yU<@?w}**bT$Q#G!i5v0*^h^r*OU*HmBE8QWgG>>SGo#gz8EJn z4kD~B=D#wmP61@N_!&;B<=@PZP%WI$*+uV6ZUOKVqA8qnj+>aJATed)XcUh@D#PBc zK6=KCtWPd<+stn>>d|eImWj)spaD-_amIA<6ti}F9$`&5)r7NJpENUx9=q9^MvlLECGSa?0cJIGIm!XHI(F-1Um_i~-^x6`m~OxXAXOPZPiAHapCK2xa9v{cSK zQEc7TA2ee!Y;j(ip7~RA@9*W+6ULcC&OL7wB~=1$v;uj8Y?5^G!pw5eij7zbwR~*? zegi2BcXVhWDBXpy*t)!QBMF0qDqC?%Wi4Xvcz}|DAThx&#*DCdEN*GT%+i!&Y^EWa zy+K`}z{B%x(vc~p%xCvwSCBMiLi8f*UR=Xi7q>K40S7oHtjNo8&z^o)(TFf?7-Nku za%n?6k;Y8sSN{9vqw6InQjb1wPR+T^8b08rjUEtAhs9Zd2#O+A8z(o*`&i{s6=*=R zxkPgMo$AB9GMe1>CR~DEk22Y}eLePB0a=c)b4>i&4Y{Ti0uqghnJjOQ>UiP7g~0EWf~6Bi-rY2a;TJv+1xsB7 zU^t>Fu%Rv0;CX8L%>Zs81%ic(%~o_F!&~j;RQPpHV6EP7-n8Y`B8#1`fbFMvhBiBE-0(j0WPi7- zw?tA)`1f9hZ1OGW4`Ng$7!Pg4ZmA6KX~)MxV5s z>{9G?ct9ikcL>4L_vI6NY1Ej_kJ-bq$R1Foi=SCqeW?kEmNXS5b>-9AJnPd|0gyL+ zPmquBObotU)iLk)(()=op>*r=v_bv;D*lW~~tJ)|T z=xbflh{pOx-E&s#m zS5tF)NSiS`x172J4MNbd1j!T^E~!qb%};lq?vS2znS76p`W5h`sI41Go_HqsNyu!M zy&A!?sF|OC=&47M)arDzqO%OBY|)i82~SzE<6+Ib^AmndBtSj9@SGFQFQJ|r2-DEt zbKmu8{3TldW&H?V!#P93Yx1;H|F*kKmo8uIJ{#e3t~f>H%)kPd^2!}2H#LLqX_$A{ z;WaCHQM|)Ph7EES{a5Q|fOeq4RG=*v-$cbMQ-i3MF=XkWgpkt<;S2``mnZCX`M)U|-Ny=<>4^7y&F2@T!r0Nwiu@}kN z&C!jb#FnGo%dFO>mZ4m)Dq>QO&mR)UvThBBpI=xGlF)#Vk>z=~MwA6N{k%~>ADs$! z)T+~DQ{yET^t=5e$c$fi&U!v8XvatL$iZ`|HQN(%uu; zh+ZC*=n^bvRu_h=o%f>=$dFiaG)@ag^W}J@41&OD<6s~o1T_SfuiJynIB_%j`EPs_ zIY?p|oq2%?kW%Pm6cweAut0I{`(G9{x$lv&&T0@y^ID3~)#uU>!&#wIR|0!2q@w5+ z4E5zg`=cyCLq(AiiPa3qvE#@#K>~cA=SC|asNfRV4YfpN{zz&W-XeLe)!fWfO{MnV z&x54JMciE+NJh@iiCqEb5AA1iUC`aPb`ko2$6QBuBw6|>8GsdY-j#Y)o8n`59Q|TN z3lrtIii>}%9r~6@1`CL|MH?73{>)`i_WEyN*h`8~9v5!>qzK=D9lK)pR&hgV91x1X zB5!MLZCe#z{_u*lIcLuv@W<63ug_k=Qf*l0mn3%#e8Csa`jGR`!HLnztNS5e>^Tx+ zt7J!s+MYgxWJ-nd1}Js~AJCP|#kWL1Y5(7_TCaSIN#Zfsu^yBy1&Y@AW=@DS=|+{R ztrrnfWSl0c0jYmqJ(@fxcg>1gPwA6JYgTV}DI$^L($dfH3G4=6G_X%f+|4>>HyS=N z7C4Izl(lI+{aR{FnLfhoY)SxY5b=9U(&0qERiZ6%_b&NuD>enClnma6q|L);f2g543VMCDz%{z^)H1)U>$cKdq%`^U zkF1eR>MSJ8sgcZ2oT_yg-`9#}O-y8`kZ*0g%>#CK$YSi>doQd^%XV}jV`Bqlxwq|R zGks(*1(y)a>a=(a>#NTDgvAV3GI*4We|a>qccoKf6(AgJ`%PBPx_yvpGA>!HS0B6P7E4HwLxMv%BQ7$ zwk~gF=_1WOLm~-;!DcDc8tR`oVsOogY+d3u7Z(?4>VPq!B^lVoUDr9!oO9)Gb4%!# za%+IvZ|DoT&G(9;-l|{td3igpGAI3`R|Y^pRUU?Byn-F2LnzVZfMYK7>!1>2R$+im zOu8rMUcFKo{Z<0&+(0MU!=X;c`qC6ga zH1up+zLo2EV;N_!>_3WL{p@Wp*eQ=v623%&dOlbR(7!Kqg3C`~+K9r#B(d#Xi5N0x z`p6>qyzsWjO7H!94j_C2KPodLnoEVpBb zkVImdN9ZjTcGkKAbdhFi$uXsgzs*<`k~rqtN-jKq-rTXFCcy{b0;MJ*iqFzR5=@Xr zym$21HYUshNM%m-w)k0S3ST4DwQoTQPc-i@HU~x0WiH)s%!?@N(rC5J2&>wHwh+*b zGi<-|z5{KD8nR&5QIrZ9n0+{Gt#axe*7X}*G~lRPbs?Opu0KYzHa>oqm|C{~WDhW%dTF#K3kAIgW=x%-3ihYHn_ zho#e^gP$_VntPP0GU+NR9-|PEkTUvzCCmaBOKn<&Ydkq2kOoc2a#Lk|`Do{(DpA`( zMl+{tlC5bk!R|%+A5bL+Vb+eN=D4cveqLE+LctgPtC)D!j0lI3fzVLl+bTQ{PiKWW zhJjy#kbD(lxNnLrtRh(2;lDK$wK;)N!FI1W$fsPVIom}d17NfM7bxh66gohlaFv$g z;pVHW>uZ#ErcQFkT5+~+^6lXDI?)wb=O5@O27NBH%M@eVT^S3re(R|AF(EswMda747G$Sfcx0+ zm-1}rNsFTqTHQ^XbO^K3dyMO#u|W1l>baJl-$d@)x^@TVrN`NxxBaAe8!ZDAV?CS&I*yVwIB<)*!1wM>cRkXE`X<_ zBodHj;V03AQZ<>N_ggY8dO7jAxQIcZ?am{w5S|wgav5ShS0*4P*N4?T0>*%QTopGtPiFe&~WVh&h{ zd1jqR45oj4+2$qGr_xfFs&2(=S}|~Lmt;@c7+Yl^{&KjvF}`y21=X2%zDMM*o}_Ni zR!bIPHNLyJfTbjNVOZj2ZtAC2$bg_0$kbndzlmJm-SlJ$rUAzkMZ(o?kRXoBNl}Cd z21rNW3I7AG5klwza6KCWY(wP)W`)OY-aPPB=T`tHJhai7@FM5!^AoD~vnl|TvwK+s zDX zHEO@?MAly)KLT0*2?q+zD*>L$DXsmjjmi%BP_f5hk!J#^D)87-Mb;w**&_j0GU*W> z(Exi_(#{#L9x=N6x>Kt%bvnk;@&u4jT^Raft@f6ECbX_ zlb4p7EbAWXj=3$d#WyPxcY(r`4DDEj%Sc6_%(R zYt^b4+AH&;uKG|pg}VI&8HkWb*C=Vq#?1#co6(P)>6?0nEF3k6?q$jRRXGR0ALFp0 z;zzQ4d_Sjio~|9yWy=OpV=B->NJzJjPey=7lTcwx{*>!^`^V|o!^<&?7oe%^0WA+< zcKRw6uYD@b7Dx#gBi#L4H2bF0l-#mGhx&+YCi4Sn4ofHL0-1;zZ)Agv6KoN z51!h%Bl!a%%x&0T={>ATVCoVW7SXGFt>hH19fxjjUk6A@7PaWS4#uX;psz4%*l>68RSEo*pR$ya&pPWVFBcCw>a7GP|a-+e#HfBht(e}JD%D{U)|A$@!2ay|psaxB|zFpJt z5!5?UURJ#n(CK7MQH0@tTX}$u2n(|jfrkidE6JZVuznJCp>P$k|q?_)~!)fI_3Fc#96&oA4P)iG)3u*um&76GdKb1(Omp#Vd?{Q|g%?@qv^h($dYu z*AfaybqXkTU3;I?;^7i#ka{_l_m(eI6SM*6hYmGT@l4p@N%x_nNgD0>*-`#n@f~d< zP)pzA`6e60LAdh4I+DxSODD(~9W>*wIlTIkah z2ITM(O!sl{5gx3s)X)1WgMF=T{Fc**d+lrNi75EhQ@dKgf@md=aS(f-jlERU{Axr; zp5-sVqyHZg<#IR2l{upvf))eOqHL~oTsz+WYA`G))0_`y9s!`tw}_4GH*xQPEYA%) z)qKWXW-ZxFQkxr{ckpg53}InyQ8BnHYIYII!NbsiQhI?A@4B&m)2Str8f&No)jM$T zhX7{{WKWH@H#yM%y1pK0N90`G(13;@@JD_t+6DZjc}cEn(D5<1tSo#T>of zeOg0vLSU})B0iOwm9^z+tb@^<=y;)m+e~|0GQ#SP#Wa-~DW?r4o`K=Wf-}~PpP@9w zgl&8cvSEoozFGBiTkQr{keSCvchU3y8DXD@$k^2)?A$Q|g{P8(6dh0kfJOpAoB4Rv zoD(CiMK#5*k09TCA%|`wt!S3Hje_ z5CRh~6^pSm%8gQSai}@L?6ag44It^ zx>vBFjKlTn2tO;Xrq?U-877B91Bv*~yKwB~W1UVk$R3Dv_mMdP0HE^uYQ%l-l?l1> zW+m%)YVw+tXt8-y)p&9vBoU3CT)YAjg^qH{f9nBd zJ|8Sh4=BIXW-0<*UA@UqJiN#n&`E(}5N7;s*sQSuCA+MFT@icYOJ?-Il_XFm$Hfr8a| z@uKsi7*&tY&-!|Ln@P|CArdUY-AW%`6e4b_&V_Nj_}WWU10thsb`l$UM)Fg|u^N9? zOXfDPg&aq^QP@FoG;2aA%r4GZN4w8LnIkJJfTv)@3O4^hG+e_opCYjTUAp+ZWu@@X(VAoIpqz^WT2wi? z3>J4ZTz~`|v>`4YjnC5KVMwHm-ARjc(Ze+YWn_8qoN?XmH4w4U`9@8PM)tAkTHmMA z388>&36v-J+}UG*D~fv)NE^r9P}@|QaGqz3BlF9lL6vRqmm(2Al0KaLJKF;`P7G*G znkZ^)bujhc1|LQL;|a|ZQg-=ZE&l#U+f;(I^xS^K5mWt#pA~2M?-_iE=8mc?3{@FG z_KxPRUrV%Hwb|xb(Y)y-3D72#k1MyWbn!KQ)JLRxO_%=u8;SXRzDUEVzjs^t#&wpf z+$z?22kZr$m=grhWT086qaLZBm6aRYOLTKeA=##7;;zzr$b;-FDCH6%0~&D~^Ftlm zERq^*s^s%}c5f`5!clUd0($3K?ZgMMZ8mm?DD%YtBqIpZfPq}7^kqF%OZz*lo3OJjX09sF}3$)&DhqBCzAJ$OS3%lc-#&MU@JG3Py?sJ~5G>`vHFoq&sZV6Wsx(LjKLRLPl z+C1+-@Ve-Hywi0DGoG1KChl0d)J<;1t{Y)r}@fW08LogT_IeJ+N20t}G{D-)7n$ zG=6KBmNZwzN&xCREj0qFSwP}heETwj$GcR_>= z;*y&C>%*K+l_32(0BKV%k|698f0n^uX(K6M6wy%ke>_=gK0+s5?TFta^^eh4_(W?V z2KC3=50Lj%_MI>5P%J$U4;}>VFMESJ{c9z9OqwW$*>M&3@{7E~tP?+T_?}i^^V(?u z>hs0E=^#+~#{29DqVttc%klv$1VC%8<@jfSJLV8^9qCxYjX`>(5V{oE3xGde?lPsD zNhS>|qH_|kM>$ej^$?j!HUI*(N?&krX(iRg3g`brqA+0Hn)5=YXXn6X;v`=Ble& zirf<}`G6!^T@ftum>eMY9*-t#7)Vopg#%8`XHnlo=f6Eur;vGjc2}d#IM0X&9F*`$ z*mcdAa|KGi9FGAA&7^X~ibMXQ{9Gb<$-qN!7Po-m{SnLM;e;<1VDQjp@&pbT`J(MK z%&7pR_1oVfFUiZNCXVi5a;9RpS-qe6RE zbpUowwQ*gI5favuobF^VUKD8|8xW_cpd{A25?PiCe_{EiSS=Z#`2TqM5--(+OYwWS z_~*t)i#>^}jznic$HxOG7|@*nvqtv0G3D^%Lca$)R<;E%r-JMl(D76^u?+$BkRb|g z3N>pO!pM>x5DuKT`UYsDzb5vdRmkU|j+?~b@kJ_+_B3M6a$$J$HA;(1EtpAEsfZ7j z_HVV6A5;+Z)Tr+c8^#z#yeg8$M7(ke`U0vXH#;O<|125Zy5ub0olYA~$lDTzBF`-I z44bd@5E)an9x!I$tEo$*>;(Nf@)Zy7t%1{1^$092Ed=i`KQVT~`k>pa`!Yw#t`pIF{jkC_Ny!%In-{aZ$;B>3+LQECJ z$BVJ0*5rZKX(3x|oiDRQ?an9qfW^XWP$SS96k?*X+UArM=@{|m3khHvdRtzhd&RTS zD9|i8IRPl@23?-Q4sln4&rz~~eFGrl)hVi!Z3*C0?N__)8vr_gVTD*c#atdcr~$g2 znJ2*vrk9m4Gc%V-8RM&ZU}=;r=}KKd0(h};y-%gvkc%!x`j&y-MF9z%jyl`2>sMsG ztGAZY@-yr}7DL*l0+t48ZuuB!kZkB%E2-r0rftHac^}Ze$3YD}E;k0sIro1o*C` zuNwEK1l$hH<%X~AD1>Q6!*+s_ zFSi7M)4DjMFh}Vp_0dyT8Oncj1j*$Tg*-YcTXc_1?K%*pSuF)kZvat*Gm)L3&fU>s_)|uRS5Rh)m5IvuO zHv^E?(!0v(;x~<=e%mj3PEd3bpx!_TN&EIH`)pJIr4MjFG~|8yoQ^tWmbkGG7#9X! zbE|j~lH{)Qw?R>kNAON`jJ%Rdb6qq*!vKB3W}`sFkI%2nF;H#=v$lD+`x!i?WW zNu(~*#g8c1>T@$VIywiL(Z-Gdy_Wk{y*Ux%_`nv>I07tAQk^lt1mP;u0Sps31Tdvp zgWlK1P%>zJx2x-^FJdMA-TlHE%D>yd! zNkzGQVF+V|Q<{k1NuR2`2&u%{;t%RRR_JV`8LBGS8W|o*=0|@{-?WV43Irh3;fv&4 zx+N2lm@zQcJ@j)68na`Hs78=4-6dBzA%sMt06~&(T!id7yJ{}(2yMtk+3Ey|u?lr~DBd{2MM;o5*AMONkToIOLDl@w`B z7_(sv5%_;uEPZ?&wU3`9w9*hdv?)2iMMGFKc$!$m7n<`a_T&wQH*9Nmylaz*Fe_cN zuj~*n=|X|Ss)H(`{?h_t?UXzNHMZ8MP14m0BuSsFlaR}(Hz_AmM&Cgtb`^)phh3?>fAARnK|JPH-H^T;qRn$Iq8+0Q;`6 z>)A6+(_z^752Crd$&G@{{Iff|7RL;H&pz!6ycr@#0 ziG)rs3vk^I|K|meoOmd!G-pWoN6O%x4_gXDcgwN7SS2x}ZKkM4<#{xn(uX-@RnU)EDu7SYEka;=R-B)`H5gZ>{?wlMC@A9Ll^k;mbjlhI z+m3};L`gb)|F!<7Pk#*GPOzl)S1Q9B&cX|U{I=serLR!Dv=@6J_yu(p!G=%$hQ{9B zHir?DF4FisB0&=TO`R(5i6X7Un_X8WPiUeCLW9^P{$tsJ`-k$~Ecx>I-s!)?uATuj zhW-70+{od7ZJ{{MApbN8)~^+J8m*@1RFOdwwxZ%SIKHvV<1vV7O;RKz~p1axb{E$0eIa>jar5L&|!zP%`BqKlt} z9t`9TQqbOYA+|e8$b0+9u)4VaKc98xQ*{UED9!%u^<}?cVFEw?)ALuR+&X?TysHhG z)DTyn$wX=WV-Z5GH)%UONE9W&Ig1T=iU6Vmu&Zw+tUN$$>;{bWMc8_6YCapf`E+H) zj`2oqm!}f>=;(ME?b(wqwuDy>?6wd3UjAK5br*gSpVh}cduZu$p?mFBpRxp;7LRN- zz_+)&!)6F(LCPcit7d5(h zAB;apKiS@7>bs%sY)2WqovN9EgWL&ea1`t9GPP8Eh*M*3*@EeT5wz@#7SOx3sV3uQ zj8)K;wruw-*Vv|#TiXH{yq>Ix7$9`2DF8$gq+RYPkZ;Ps#Vk*a1sp?wi!@1z;(feu zTm>+KTT`8GD@*2e;FULD1kbPwaTyW4r0+sS3kYM(3L>TQOzW`8hji6OpGtOkdE4yz68=e0O$(|}mU~LbptAeTc z3#{cQj*Ev-Zcx^jCF3BCABB8^zZ_Xx7YuBfn^{EFq!Y4x^vwxg`gFl{TgHhXeQX#U zJV_yc{Ua+oTH<)NcOcrt_N=almI*)m8Ml=$;)BsIXP>A39@^B61$I7$clFLaKOTC; z^Eus#A|)d?z6*UP0)50hdF1>@`C{w^X;Vthrt z^e53ykbzTOm-=XWP7{dlkWUGq?slTStlLe!*sh*6FcVFkhw$q<`rfaHpOy*(m*Oem z`ea4dB)}pNIJn2>$lXW9X>Q+j)A4)Ca4Ts@ud%DXVGRm@mSUBu`VIHX;i{Bpb=bSSaw z(eefN>&tCc*N(13XIQVzmXe_-^j8+&4HVy}L&L#uMy|e@AJ?xDiuQ5>vX%S}RLe?F zONz5$jI6AzhSLTQDGDqg`-l4MjhR&5**DCcgKHgEE6WpI52KbYHN;BKB8CPM{Xt{9 z1C}UzK`&%egrp$-#rY!=2ebe+?PQNQ0YRB{x;rI}(Murd_FP^4nH>!_i2EAn<(Nb= zeEe=eHMGicUVb(obHlriWO>wUYTjPgRrDlhlZV zrdC)u-e%~;yw&-w**+(HufLg!mOY4hAN9Yc6s6!+_|Tz9Ktd6D>WxVEIZE#0e%S)|?z`@dyj{aEQk+AasH_Akj$wE585nrSCHl%h{NNKZgMK z4NLV98rs=Rm4EX6y*EEUe^lkmW;6>P@!`Qiev?PZr56PTvGDKxOG^S$LJJdTcKj}t zh)^_?y>t(;XgkOSHMZbqSHUzz91=sMtS=y&I|&eI?~%Bukt z!;KYS(HVUnitWhV;pk*=M!vqj3w$2P;LtRWPa-$VF73CQ(ZFN!Yhx+((8JAbYGx++ zp`{7fR=8>aGvg-cc>6wE7DLH@T}*F(-yj)LXsuAWId3FYO@9Mp9SWf0MO~XZ9Jf|| zT^rpTj}lCm#6q&g4w@X?kpNE3(yi)YwOko??2_BOLw|DV!-QAG?v8%hhq%Z7p?4Lu zZ|xYLPm&}CAIfg!!Iz@y#qult4NOdL`>bKc}TA9e}liBCi8_G;?Jg|MG5$(JA@zbgz{Pz%pGk+oAa93a>l7q z;`}Bw<}tqz@n$?c0|xfjtC{Khuzih{x7T754B0J$m0i2ETQ;yeCWZtZrk;Inow}PU zORrmv&!W_u3Su|s)4Wm-*tpq*LckXKcO?_zeT~)KkYIz3qu=HO&i1031WXd(x#r_* zDP^<*$^_`qv)-Xj?yVivgvg5^+8foQ-#7uQ{(s91S8}6jM^RQT75A#1?&jn`O?9nt zTMy_{pH=CWC(RXWOPy9`g#qm1>VC2g5UKlZUZyM83wDj-;)DD=%*zKbSC6D+S(@l* zsB_VwT*L7SkpQTwHR~Y4M|UIXD7y#B_O;kQtfH!Y`pUSwFhfkxuul6}Q4@y?fosd& z_T-kKA7q4bHhTJm*IjFJrBlnw!cSIY%^bC;b?f)xaeqWaOI<&xLM#tn391czM>16q zx8o8SFLaCeUzN~XH+m8(h9ToL${*aq47iRc$Q?qUI#lu<`Sw2I>%1s_x0Jv(|KtVi z09XOwsEA#27vypL_CaD$D&SnC{9h0X{U-?3W;ybyNaL~5!!?hB#?9CPtf7AV0dNb1 z&yD9mcUv+(-v(SCX=evK-z8??bOH|*4T&Zri}#NjvR8{bh1)gOCj|>l$=$vkl*e`F z4S12Dma@N|%o!h+`6;+?w!t&?-`Z?|_egHL=EL$ak>n>)`5MrtKvQJOlSI(`k`L_v)OvAupj zhX4Eh8evC}#-^<53*E3HVPBsa(F7|=Eq_$;K7RlHD0ai}bbM{y zjQ8Dc#c&>4rDQd(=iPFfn$%}si#b0|TlO5!b(QB`vVh-ZRh_TDt=pdZbJkW?P)0W= zD^TqhzZszP+T6bkYx?>5Dcbp;_v6>1=J(Y)}qlHcpKy)5n{r1{PUzEz9ok zXaVe9E{l1CRta``^}Aj9Y@b)8kFBSu#K@cHFymfvwYe5^DxabF;0h-d4zpEYuHfD7 zVbvK~*JTqF>>*71qtA;+kEz2-YqE>Pgp@1JR$nA`bX*&7Al1oQDCN}%OV{Yp5o29l zG>cePTITkt!98lSWzo1U>8c*h+?9<ZeTephBV>JU8(d6EptP<1PUnOM{S;te6X6ZBRC=_ZbZ=^~-6W za}^PMHaam6Wsxc&$BZ8x=HSC@Yo2AVQ{GlueeyC@<)R#GLy0TabK{gkK#3!prflCD zdLb3wDeumZ&Xs5O>!N*&c!KsX2Q=b@8RNu4SW(}|Bt`(!ElQ&RwM@t7M=SraDleU!w6FrWWvTcNC*EgPNMdZ$@OKjeCzGZ_jo$Y3 zcU8`89nkb^_;mYlK|Z+u+H)ouwm>ffX@f`8RC3p|8+Wv^ZwG{r^{JIUS zZhF_!=Fe3*{y8VZ2{UUSdQxat@05EmAR;*t)0xHE8$WwPrxxTjzt8{+ZGNjyEJYIn z;oD?S)Q6d%&EiBKS^u8P%n;__2JP)1KQp=z^9YGet4nM+lm1+}ngs z+c~J-v|nW38a1q>^In_>nUW1rUm{O!WL1Pb8my8aGhybfY{<~x_pK?!Da1j(!IwL7 zs^G;U^2{XbZHf{RuGIh!qx-3Os9k*2pPxpVzh7QLKUOC%0Al*9INHqfp`$JpuvgiU zmzGkFT$J`(^|DTKqUp0_UcP^?G+^N=-SQy z%f5Hp1bXA$@>jFgqhydiUcp$;$>_1KF=z&03j_B?J!CYvux@5{NdWm*_Tefy=u%+o zG`Or|{q~iya=c6a2gSeR|Kq!L@f5($u}GTyO6oi;hM$4e3!}hU4@FH~8bZB{So$M< zt&vWXryu*f@yTlKP50fQ5Z@FbAg*ZDyH_)RUD?@`>bT3g!)4~->a;2Pbw@M{tmWUP z#&r^V2))ns@%6eqF?}dUt=WIgF4OJ1XnAWes@y+^zYCfRAWhOtBxzAfr)EHPBtB`X z7GKyQZqWt)KdQbuEXu8W8&L#7Vx(IK2?a@&28AI6K|ty54q@n2Y8XmHKtO5`5fzYb zkQT{Nq&tTer1RSk=e+Ol{r>QHU0&zf&+NU|y4St#wf5fgX;9G1aMl2|?SM1Hm7c8JIP^bfh`*)M0ZizO0%}0#%D{1)4e%z4 zG2ip1UbmTl;FaJ|Hi=84@nO&KQ+d=)HC^G`t|A+pr{49xO)pw&4K=Om}4z+52X@bRicagUtD@l72p4Q^Dc zf*-~5&#&}Wioo$lb=%s2cBCJv&h@9nR1_&m*$oXDBO`ix`ucxkg!_L}#`F+dZ%c-$ zB>oxAZ@K3mM|2{Y>VhalgI;=?k7Ms^al&b@6i^ec_}hkEH7j*L9)}q9(#4p$@$`m$ zhl+jlKx_NoV&Aoo6Z-soBT4kLNt7pkpC1@)s|~7qM1lYH#gvh$yWuxLiA*kH-Tig5 zs`~fIfU2USJmJ4*2#-^2+)NBxApIi$6?XG814+zD3h1+w;R^>%6?$*V9phB1?t7kf zu8&TZoWhsw2-KE(7?s|64*ELwjnx>|^w()WHNWLH_d&$0` z{@heRZ1&*Du1m=OPxI$b%GW90u%5e=B`A9Hit%;|qA?C?_kg515nn#D~ z4ay`3<=eWH_Fq~P6_u{CE5X^V zle?gYH(RGH@#*yy{%oRZRK#2Q7Y!90h)U$ zn^(m#Bojt*4;+R}{_3ix5B^ael*`96Y={M4u#`8%E{YT8tQ;k^ zZopHQ#$Fyw(>kU_qA(P_;TfC`PSI=nkLE ztkJFbs8tq#$t2T>eM6C9-kL-6$u;0r9u%$QXW{J{>p$^wR<7ygydh`}9#$Tq?ncGn z^w);n_XeZoY?4Wm-wi6*vpkeXMzJ%47p<``Rt8Jnt-Jd;a}(I~*7Py%Eg>s8-tl`s;`gzF1XVX&xoYi{GkxJ-e&G>gx7jz=EZGRnuP@KOpt&at>L6z@+S zA*DT#0U-`5JFMKEC?r)QAjT>KZ7#yObudvl`V+NkI@BOcL?^HVr0% z>n9x+`>wu^Gw?I3Ivt%H(#6H}?$!0N=;m;;*)`9}^8PFN^u1r%MxKIge|HCwi|1&b z!A;*sR-89W)qG<#-bDMZ920cAJT(uv%W)3aY<&SAS{yt$@qh-4ea&amTRtw89`@xE zpG-!fhf?8qeYwNIY1Qc9Dogb8B^vDWu0x6+eN-x>P7CuCGTBG%d3gD2LQMrWXhCS| z+|bl@OrWX9sUsAOpYXAX$$Y9Ol63W^`Yc)FFuo|$=2P^Vr#kEMAhl%LeSh1J=npSd zEw!sN*;51vN5CaEPy3&P+dGpXqiMwl=E(Jh4hxgigZWs@U6bdHO&R%BVOPhNGM3Fm z&VirfF|uD3U`2am=umceRoq^+;CBJJ*gxaE`M+_(l2K&9;yU+hPsuHP#eMyxuEYsN z;ZQNaQ%5-`-TfK{f6m0kY^ z-%G3QAjv0rnx5}}lR^!lu%_c=h){UTcAa6bBkYRUygXUyZ~L^>%_ChO@EC-8JGgAq zA_PK~1f?AK8hG*iF-K;WJfgophDGwWp*2F`>)3k8<)97+{^zi69x#uORGGm)UW7HK zBpg+iwJ%8t7jdUxVj!y_f}C00-roMFyF3!n9-5q5&AQ=eyLWICu`c4i{Kh33#@s0I zG{k5bN3%XzV^zqOQVT0bk;SP|XBvL|m=ZC?|Mx8zzV7xy$-iSNhCx3q2lTS2G=X1A zbx9r>5=)!bm$DgEDXu*rAWs&06C=xklzU1DV|H?XpkFu8RWk0E_-ipa0cR|;%)XgH zi7PlkaF8Z>Z@ zQ-WIyc1n+{>VcC~_2wVBQDpfqaeko3K8ypGfg)};K_ez&rb1THSTL>m8oZxn@SE z=ScE(qsY)AkZDUo4&$JCoBC<14RN8dYRo17OYkS}B)l~ku$$kePNdR5i25%j^HtNd zV=F!xqv~IEh}H{>Qdl6`+u=!u4is2Z4q%wAR#b{qTiI)UzBGii8t1mYWD2m&EdSYU z;Egi{e9LD9+uzA(mbpfv;9^oc-PY-Y(0wfR8hAg6pE`3TN3`-4 zJnDZ(LzQoOpG37xBzj~#k(raqMv;;6B9l_n`s6uE8j&-vV>01lS1;4r$s`*ZxLH$} zQZP?w?Hx*@`s_B-gGp{JL(sll1l&mF1&kT%Zo2TnWsSsttKu(A?gbAfo89Z&Eg3#{B*`Emn7CbN2L67P&~-~5oX0IIdSA*d_CYJ<&` zNgi9XFUSavBDjXl0xyg0;+Ov1zYy75?$?&m?eE?jDSI`1wc6tB+G`N!i2nMxOy}g* z&*1zJbF2WQKicwR*s2j1Nh&Jb5B;veo%u1%;;NB-t!uHwgBHQWd=@Ri#J8?rKp^`) z2vAw_ukhW1Eu2nW4~sY!#tYQtYbKmWEBTx^J%nYkDz4K0Dvzc3aO>0mM)#|+~CHTXuFn7dMC8;Z=_i6+bPpfAWv zZQ85tY@e{W4G8gIo_#c#%m()Mv8s*YUy3-iGG?_dDIG@G#y`19%n5$IofG8Ozi!ja zivsT;qQ!ob!Bh%RVjmuou}aL@F@^K6>fQgSCcoP(e9#F-tSi7>C+XwY`BfL&+B|YN z_GX_tbEm*vqs0oWFl21^_|8orIRXdHUrD8ft8nxU!18#S-I~|-9WlK zdfcP*vHYbqo#LQ29UA4OX1cz64=fDr0TWi8Q5oa2YqU8U%Vaa0lFxO8QnW{Fy|AWt zPH4<4o!RIrywvC1LV$s*|Am-QN(#VG!DI`Bf+FI%N!F)NegeS`^o)$n3EbKtD|Zg? z326tg=sxMd6WW3a&%Er>fqD?}WbP7Dhed)d{%tPW|KV3w?DU@+Ht%Msc;U?&ytTH$ zp8P^-K)@g`{V00wrG*gtjDHkJ$Pnia;^<4Mmuldv0x1rn-dpeQVrE}FT*$uYiS7#y z_I24k*45q+51b-cI^5`9^1SJ)X1dKqscW2J?ctK8>9hdi!uOq~vWNm47fojLy7~Od z+W<3$4z{hgqL{C}ebwBuOOsErpG^%wj~1to^$N&mObFy9!=RWZDeQIt{jrW25q=a85aGWIa5`7v+g=&WU;*!!K%ml!2bny$ zxH|&1453~VQ*YKDzJgfV0tur91Dn{oC>R#cOAD}--|2=wcj`4yWVR!AyN#H_{pLIo z;ll+s#)L4vx`s~O9#ftN_Jd+ou}Q{|aWi>=7b^qy<@6Wfa8Jnio`u7hr*}I$V5X{f zDWbh%e7d4JxK-07ZW%g;S@k5{|y7lZrA@+;QOHj&BZsV@>e zt}1de68fCNVj;p-9;r45x#}@AjrSlYn%)7^nAUSv_T{RM?HehWy0W?N>ExM%NEEnz!W4cfi*7gN)7)udJ@OOxXJ{kk>Rvk#nePELGc~;HR z4puIl%={m2?Q_bbD^<#qXfDCVix5g=dwD*o&QNi}kuE6`!_ENUv))D^$7299VsZg9 zs)c5B(}V*9JSg}E_{7A(((I!yAs^F=m477@I_LNO<-$P5H%o)v%(1RVLH@HSV{dWL zCrB%JxJgW9Dy4u#6=UkUUU+EW?bJ=_mDCU0UJ$)afb)sMWr~1I4YLmcoMO{QueYkX z{$f{t$CKW<>LwAcyM#Y>TGP-ACmJ>}E(qed>Ot}Xf6f16mjGlO@}|ssHrsX2 zVymzgbJ?+T7rpbXI|p zO@%#YLf9mXG_-&?3FU=oPROpVe#y^&GzgM|tGW^jAbXGH6zF{{p&&_<{m9C}p$k~u zr(hCtU}gmc-Sspe`ShtcYW4MyZ4ZitF-IGMP^=&1VViN|p*C_1I8G}V{30|sL_AQB zxoGAM**o3`(!WNA^Q2#Vz%?tnY9f$g0hlBU-POgKix&TD!8=ud35{MAbef5tny+w- z$CfaPN%;Y-(L(Mbmh0x^_~O&wWxAJPdj3Ymfmdz;pKLj|VhB?#UY?V7lOle+;sP9h zo7>w6A1tse`U|o$fLN(B7>HE53124Mn_BanmqpiJUkNK`?0hINV~$YJ&E*z*9ZaOM zAUc}Eb$S)vUr=`YBR;b3Du^|gp^Y$tHbSt2OY27RV?hiXqKTo`R2yUnyh*crbdDwf z^9O%1CjYPH9v&KSj`sA*~)iF_q`Z=>$kgT1q59? z_6%&;ik)nNikQ0F3Q;jzMFtjTB4btG#~kmEDJ@QPzrN_Ws|!e>2tR|tzE(TgQZ;r; z2Iw9K;ef!vNtAM~frOX?y~(61Ae^%O5BRDnApfQJOW)9a#X2!-_MJ`l+FbA6U}Y0S zJ0suL-|r75VwOiLX8d;9u;PMP9gs_?Xyy6-uxtbxR6>c*bR!6sadJ>nJCV4n<{>xQ z5#iKgcK03wBV)XWT=+fA?4L&27l0!bF@bcnui`c@BCdZ9>Nc|#|4&F}b#hy}R*_>yrcOJu-ffF`? zh<|*%V|>ZuGN&w*72w~vcOe5Vwq1=mS)CxYZ~P5Du%`F9X@7^GZSVCyvk*eP5v&xp z9aFzz-k(oIDlC>aJ~kUN+WSL7p!$DAUu`gG7`$GixbgU~g zf2~^*tWy_{kIaT7^_pwlZ6yE^SB@4UD`amYa3)Egq%Ag?9_&|R#(#hvAG5(NQB3R(I=kI?;>^2#U#l)R_cOez5c~giO33ZT)#u z>>~S75>OzDAkK}2B$zl^d4g8t$T4}0MFzI7>8rb(_HF9k^=`Af7ru4GbLPO9$*&%s z&2%NDAHe11c?rbcQT!=jWT=ccex%Zti;8(|;gZE6NT5wgUV0DpwR}@HD}p^vqO*6= za+q30;Cwq;&Oc+d6(IV!hgE$A?IFZj4U5EHq62QReBrtF*HH+w^eaAGs7A%HVt&b>N`Dsrn!l8krzeB{J)YPBz;NGXKI{qb?h(h50+ z=)$(BmFQAfqN(uR18QuRyPQJSkX^ZN)pXLpy1J(!Pd$f}8Ez&7-+o%!ro+{%H#j4b?FkG|Ei0_f2}2}8Z=dFARk{1TbCz&=CbI7;}?(7IDUaj3L@U{p^h@Gn#_D+bM>L_MP0C; zRJ0KLV20R7RTtM@5{!95=oj_LAUO+Acg&0y5yEBy)!v}H30ic>F6DUdPJLlyctw8e zre1qED&~jIHO=4xoFa85^#)1bh*3kx&WbVL?}iWwpqE^QNCy%Ep}As>ycSdph1ceO zV0;1VSoN=rV7iabZr4l4x8fG&wSl}AMrrpBDeIQ{sa38zk&h zyyoWSKMQPx;bNr*xUW|^FU^euO-7r^5?E$1@_+)11!?*M9qKw<l$8Q`+gqjr^dTRdGh{vQ*!mJ`$wv!D#*j!j4n^>2H zTuo>&QLt~~u7tR6*E)Fj_Magc&xZu4CQ|!+UUphf2QX_`uR0(}-K~)j3EwzA<9aM- zlYJpneuz{hW?W5j1Ihuy~Q!Zh4^peFb_muo9r0U(tkBSDvVQ$Uf!bYOlLP<@=kOS%;$a!kd_wnty?CZ<73S&0qLR{pL7mf!M+u&bpe7lZjVH%_SWMG4* z1B4XAB+(0;n_dB|6tnHj34zJl2w>q}rot$zFq^ z4G=`lUIG|sihzPUE1kPs?yu81@%uIW3dl=ol!koCkKyr~_XpoJP0w}2|3t+QUXC`- zykgEKT}*qVoJ1^RLF0c~bBy^+2bssjM+ z`^T+R?L0mAgoC9n!PLio+uZ}5UI>}v!;DX#vTn<_VHF~UhT^894@%SoT1te@^$5PH-Dyy+)C`Jgxh?|~ z1K&ScX_8JfnfD^ful*hB5 z48fY+XHa`vcPrpCZyd}LzOr=BpMISp=SY2mA6_R*}=MZq?pA6?(y?1eu)yUH3!8T((|5 zN3^jT6#*I(V&!6JKre?ZeP05$rd9muspqB8Tfhb3aZ`I%T^(?-pLutGc2GI>PDbP( z{1h^7`Td#F>umLGaS@gi1^m)FjtQ^tXyMFi#R0MNMgxCHV{7%aOq05!QFHU}v@=<$ zW`Mle{z(@XRpz~=wN3yuLtH#vqcOPeS~Nu}k7gf#dg|$aZ}8>ryyeHIYz6NUxYo~I zLpMhw&LfHA+LeW^!>P2qD}EoW#r1w3I>(dU<`aukR4i!;ZrSMeN=-|X15Gw!V%x@< zws%TRye;W7M$R66`N9)^`*rhU-fdwTCvy`=-OAIl^=QM%o%^x%v0Y_u9x)1~6B_tR z@)t&GBg{W_b7am@eUw~@99Qpnu}ewPw`Ko(f>`UUsC7;i^G9QmLwz-nDCf(m+Ms?1 zk4OHU>-u^>4JV&fM;jcJ(#pVYf?qF_O*q-5OVvCW^ABz$3*pA4 z?z|W)NR?8@yPbfZo|3WJ^4Um=XA|*WD|V@?$Qj=QAWP%ZIWGvvhK%=p*U7x6xgqwl zzPl#d8kG}1V&`hu-&X2oc&Yl$a4dNt!h_44{>g^1L|UvWS?QDe61~mB`}_A$ebM_= z!(|87C;rxSaoYbW3%i4Oy+sIN@C5--veiuPTr6|W@TDE3Z4Jy@b+m0amiGGIP8piZ zT@9Su(vl$OwWsa}Dk%`Ls)I>b{kPR0KYsim4?k7B8ee2s-pV!WZ2N-E=>fEz6Dm>Gq^CyJ^Bt@4&=i%I(`*ZHT?Zv(P#%{A%i-ii2ADbLY>;^l4g zM^wENj6Kxb*JT>aM0lh-8yhiNLFH~*ART`9zI{^G)I+KA)U@1igj%w4`vuTIe?B#S zj+DYwLgjic6Od+vgDo2TO1EZhR64oIG{P^_=JIL*1cdKaC3JLj-{w1$gum?VY+nY^ zZWiTt{gpb5fuFXc(aB~j^xRHG@dUUZC_CA#=-#ivtOXc3fs}cm_SjSVd>4$!crQV8 z{TdWS38Fw0g?*^CktV@{7sKHPek_!fl$Gu)iQqjY7&BlH-!v2|T*hrgZs7SfSf@_A z>4b0?djrY&(+YY3QH+<5y~QLRklxz;(Bt8eZqUH{!z48?+u3703>O5WQxNr{!apxX ztdR?OV*{wNPq+{zBqA@{3xCE^XS9_h3L4@0!(GhQ`(SD<2t7{S%Dnwq23hpaDAsP$LW zshXOktrRttM>fwdb8~ZhRpuIdsel0IVWGd-(;s5J`0=-0`a*D0rzKUST)!Q!iY-Qm zo`t1tp*wZ6B;(|&cA-&gx#Q@o4jgSqwXkE`{`=bfm9Uvzh36+(y-I}#>)V&~I%jCL zx)x*>dm|$^5b3%~4?4IWqzVTP3~Fh&#@%I^{@(P<{U~m0b~K3x z*rm`AKupwcpvEk%ys}u+utrEZu!2#mqZQ<`va%v>3ti)}{@Zc2D~nIbzt_A;OOgJA z&%xrW>eCJ2Hrv@<*N4(+KpZggQ$o#7sIPs(wu>I?`QYQUD? zL6r6k!h2#EaE5Soqq|f70wZf=`({Pod29qr1J42sYQ13Az3FvFMgO5j?VTtxq329i zVU!H>GPG8?Iw2p_)OsAc+&nr*mTFIhV5j({yAsmg7C)5VktKrf{D662Bwc_y)4$0+Z371Q^4l-sK|7?n^u)*d!A?s zM(!dQ(zp-PehvSCUt2OV(Ao(!db=_512ou(twJl641f$2iY-0(^R4gJQsA9hOg{9> zdNOgxG%4PT>`s`uqhog~rMiJ_RiBTXP4s`Ol!oH5$?$D}?N0&yRU{+heE(HFX2p}Y z=HUuD<}q1mGKry2+V7Q~KObo`SLQR`S|JEqFN0M6AeMtd5#f>VZTsH;)~Cuu5)OM!eYCsQ%oZ#0a>IYa_veb0wRMgmHb0bxr;x|o+r1U* z4JzdT&HWVN;glM0ZYe)9i9GT?{XKk1gVYfFp(i-VH8a>JJ>ufNZqR-2n}csflScGG z1VfXa#}sjp1Im2TdE=Q3(&7wN8LKc_{L`!acbiN@EZUzwkqnKbc%9Vf zfs=4F8w zSI!dQ)lZg?E^2NDij$N)#T{CEU%jHP<3)ol`UID(tlsn{vQ;1YK`QB$s2@y}HqlI? zT3qz|U$XqA9R&-G9t-?op?gos!XEzCtnFxrhw}t2yA6K%Q*d=)vjbmuCs38}`lh|9T=F z9T9OQDkf%RL|R-tGBJ?`iNu|qeRDvBkILDAtryWyy7Ht3)12~>IC=I_{Kg_qFsTrVob?44ff%EP0H}c3XPe-}E zhU1p9zt`lhWQ(Fu@Jy()toR)V`+s@?*h0G6klW>@v-9nz3E9>OotDo&YyLwXn6Pls zcQje|Jm6xW->)^Ajn6DEn^1n9lqM@e%0p`H5u$y0sdi=0fl9HWuyxRmG%_E(&X+&l zJiVjprFkAxUx{jzZc<@f1ksy^wv%i>-Lp|K9ejbETgj-IAP5g&ji?wG!BP70*F7__ z9?~HR3Dkb2Hj>IkTAz#XR0>=eIGy^CrD2C>;2Ic&b{@t2NJ();=@2(hj4Liv~(H z9&l5Oix9ztnNwjKyG+iK@5o>L)+~8aFegtrJgs$8ferlBb(K^BsRQvYR<8?#tcMQG z%Wbahe_J(=7dzBT6FVuW^DYo@j`;pz)sK#384Wni_~Ivqn4SmV?ky4eJ`%>9b-R?9 z#*sSH{eGq9caK!oQ13d)A6nF{vxk8+6mlvHBcffaNB+}?2@c_RG1+z1VU)uG)2Dhz zG^GJk>ysU*rWlCh5#{~116fu?h=}eZO-+xU%ioj)M)GfjA+(@K8Y{6yWaPi2`DEQV zU#kc-yiWVHr(YDQJ9+wAeC(FFpSkJf-ih?PeiIS9>#>o2Gcsi!y=G^!ib+4z7Na(l zseFFj?t6McaJ~Mb5~BeQF-Dy4LrAaCQz=%XD`RO(u ztC#@Vt-p20=Fv(6=@U>qJm_9ijFAU5k>Q`$wEpV5aNk;gbJW(v6X2|RcBf!xojNOe z>|n#>s7(1g2y&Ezlyb75W$?J?MR`eke$(?3QaIHbJWiwQ56Zz9Q9fb`SH^a zR7{XxsYo!0vnk6l>&|N~Zx~f961C%)qCw$8k6X^b=J!U*{dhuB9d0O)f1R&zE+$gh zq{M)RG31e0oyW-$PuDmnZ!l5*`qNP*;IulAl79Rwz>(zp@6UCyPgg@*);kNb$`4R^ zLH!cwYM7d8G6A)Vrlu7ztzuM+gYA{I2&w{$4eHmR33E#NNlaGR7k5*%GSlS7aLmSn zzRJ6qS@J8G z_g^;z!q{+s8DYhG3zXQ5UQ~ZN(hw-kYgCIH{X5~kYX4RxGEi;QeT8Y=IPGHQ6i6X9 zbA=h*sCUdm0TeSA(jz8ppp^8EbFITx3j&)HRV7VTAd!gh7P}L`fl;^lJ#PJc$mFef zW^mVw`)uP4Azg8p=rqK1zsGX>&z%Y}4-?)7xyt&$1Gc48{iBR>kpF!&RRAl|a?Wx< z_vN=QWCF+8~-n5h&#m=kq*B9bKH$?U*1=grsqZQ1zT=R;Fco-GIokiM`zG z>Aw_k_wa($uaa>W)QxWs!{*4O*+fBN+A^<@-e|XO)OaIq;wAHEZDiq@(yh>=fdMt8 zo2Jjm1ocCByCzx^C+lATF=Igb0*34Fbxihi7t@lfaEl8g2lYN(5MrA{pZP~2Kvyc| zynJ?>-Qda1Yk*&W{JlN7u6imU-a=vGc~^9A`_~h5Gc)|`?Cf+&*_D^|!+~dEWu103 z89co=^mS{GipCXZ_poT*_pd%Bs;j-}E#|)8Ted=wvJeZ7d@dU@=-5 zAdC{obeE3=6;p{X2zR{I7!KcK^jsfC1hHi|?WDa;$u+gthn84BsZf%mwzu=ASxeJs zv$!7{SmKSh_?s%~2Rv0F(EjbHB9$+T9Mp>C+ggap`vpRyYwkG30{D9usuqR;f$trp z9&ud;W#Ky>Xl%yPFj<*KE0Eh*GGZ`2g^Dqt8~l06nbh|m6iL5%>eX(|L{gg&-aq}8 z@KH01>jy~UJm1-DG&ZcP+E%*G3K5q)9oiZd2J?Qu33fpuUB(VD+1evMD=6ctnOOCI zi3=h-f;x*qKKner%7aYkD8RTffPM5vG;XNKhoIq>gP(A67)Zjcp{%bJ^@TeH&=s?L z!qx0)tpKgTV#o#{TptG<=(Eyh-8*ED(AILEj+hY?v%B}Pk1ysosI4?ui`S<*x3&qk zA0E+KIh%nN6(Mx+#}~9P=6h+4p{gOD@El!afAzX$X)q(xOOkq($`djjG>beW%*}<> zMMUWhh(LE*p6$7jQkLnFqA}Ow6p0Ff;JmNX5q)`G&Rt@nE}Fo0sscom<4G&09Cujca~28f!kAvy+?lcQz-L#??Hr=9+FZ+g`x#VRw2bOAhEM zTHg_Z3gvK!y&*R1)`Obk$GJ^3xi?0Dw*bjYXW#b(!>CS`OmDyy3D8N#PV0P46wCB1 z5ek=vBbH4brZ9LjcL+!y!+E8*2w!urAA2q){MPsKu*JXg+c$I({W=JrU}>anW=NE0 zR=Z5}ozpm4|4|)lTd9UT>BaWIu;T+`(L)K8S#L0kEY}blKnjo21BUtG_e!%-CCyp~ z6QF9rX04#JC&7Ub0NOoB;pYlFZ(M#BKK}A57jwehy`^*!QcW>4PntBkg$e*HC0N;9FGEmV+tv;nyBt7*TyO7`rGk z&WR!Atd%wF~`YUW&OqK>J>pU1;A%UHbNmna0R-7ZngdKBx@f44V~8*Qv5SOdouDXW!w7 z<+#FuRjTGV>reH75{y>wC}brek=H|xGI`G9oUn|&uspFIuC=BhuxTKKT~6zEu*yi2 z^r-0p-LU8A&~>i#d;n{39+Qb&G+qT%=4Qx}ns==!lHEbeCK5V=Ba#z)`kvD{s|z&^ zPu^FUv@cVS+n409mva6D*EV>*DJJ+>#cNTJCUoM5`B3)8#oxu$92A}m`<%vt32Xv0 z*lTz@K^`Rp5j3)M@M}ZGczIjf;R8uThdYUf_C5V5Oxj7o6$(H}>4#{3^eiy){n1eF z59T64zJ`6AlzHx~4PUG_JGPjBKrs#~&te1m>#LRs!nj925X5u_ZfgO0+DJOk(GZZH z!&tK;L3q@37iygP?^L1f{&)rSEdaKoC#CnUD1kLUk592gS!`r1YOZf9lhGE&boT4# zy-ot$AhG_S`$OR$p9#Qm98hqE3xljwn@#N6WnFBw^@CbMn3%T_6>*=DUw1sDApoH3 z0mnN4rVO8BiW>-gU%B9b&s z#z397->efkuzGqgH1gk`E?N|Y1*Y1xC(ooH`=%}LMLH@Grz#za{sK)Ou5q0(X7)!~ z$ZQ=zuOyWBC4z(Z6PB3D@k=34RRC-a{Ge`C?>~)%2LTRn3t&D+4z8wn@Q#en;5RpHAKz9rj6^ zYi=6_M{jBNZv54DJ9`;3<34@3dD^~ds^ypdVpduX^u^kTv)jq*-~PBJeAaWB?SND3 z)i`HE24ko>H-V})Ngpv@aK@XH{ zg(ib{Hc6J8-6bN7b6W!UhX1BE$R4h$D_GwoCWg}dl#l`XJ58t<8@G`g`Pj=$0YLiS zEpxO=LK0QccVr#NOkO`-<0PB@^X)pQ2n>h72Wc1okkj@~oiT`)n5v{PJOo+YLQOgG z-r{c>sI|rP)&=%#JV#4yCvAo&H_A$)5COB3%p$0-(`MpFt5UtWl1~10@s8|N5U*(l zyv7Uy=zCY>k$1xnUvB>n)g6^vN<=1NnQzQl-6V9$jX#Yg+!Me3AaJqi5g@p1wY)+; z_#ik1f?s3lo6Ng${6hKeYh_-F8-9Vz~fN~7jv!u(e8Ad0!t&f>0lWr zrMLGtV@)y$h!LFxHdCrs+Z)aT1Ml2)+-v8}j5tc|`9uc~?gIbV;tmVj?B8+jls$L{~^FUnAmP`uS{^t)ro(>>Xm&x(J z-t+r9vC}FF6@A;!csU!6?{p#2;Trz#-dBT_S&0UtFVi})__I3Z2CU+u5Z##j5*s6R z8Z|#`#05Xs&;YHMMY6MlzWF|?Z~Y`~%zS#ts_TT$kyj#tO9Ir*Y$VU;|LW5x#oS*% z?a{4p@$A%Zw1=0ADoWZ*Fvz<2LEg!eor>PNm4m-CbN0qZ3`XAb)XghnJW?0esWb0E zAr5rl!|N6b7fuP7TUVNPHpr#e#-&}3a}{G7tXKRHDwfIwWhaNuS1Phk4!my)(+>J~ z*@@P85qDTj`ozfg%;(TSWy_%&( zpIJO)C3N_fgZHc@a9%r_vi8ImTHq+;GH8jyy(Ck)Aa?oa_%ucQV2mclv5g1RM64Fb zYlD`?$w>w`jMJLUwI^W(phi6d9VNnWSb>DT0JlJmP}l1Pdx#QA5YvNUdTP&9y$THJY zC8Brd8Jl(*)=n`lP@$Ur+_?pWV9X#ef&TZV+dOi%aUvd?_5_P(r^(h|UDtbDWGYB{ zgBn^FeL&uPYPC$;R91CNb6mOsTRI&NJlk+gi~hJIp@wiY`JJGj<6ewuW@v_ms#?_? zVf2Cqs0wLZW(!;Rw64j4LuTRX+S`iLl=}|@l3e_!W^R?%b$EuT??Vx!e~u3OP|HSc zY0WV$ol3rrVxYh-f2g*igz#Hh;VqZKsWA;MJUp7Du@$XLwXqZYogX0@jW~TSgvp+r z{bECt$$s=0Dc9~uk@Xvrv_v4O3^G+B5JQeiO~W6QqJKq~n%(j_7nJqGY(A?A#*i6Bh-S^ zH@lC((UKhOVa$KKQCcrR$YntXw#}v(&fB_lU34vMfOy4}M`{q1+4z^y_t7|Tpf8Sq zS00H}EXKUBp~_ra7phapeY-X<3fAmKGsv3Q09CSrdfs3c_+xNfNu68?N>b^lnUGf7 zzk0+3?=^09b)~FuT^gWGe_=Ck&M1fU`>$KW#h~=L{He4DQXXS9ZG}+SYe=5>QzSy0 z*<8(sCa`fd-n6?g2m$-tJdlsP{v=2j`QL{Z=7D<}Ca)e+AP`iwc4fqxAP+i}76c7; z{dV{I?fgz&e}SqwKrVrb&$Uv|VbTmIc+elHz!SK9d*BDVf#KWGPh2`Y1zGHAq=(;M zEa7n9Mn)LWm-&tjjNdg&8%PB2#t;GLjPI1?)s{nsVU3y*n93pcC=8=8@%$$znGHOPhTxpdGa;5 zWv+P$>5t@!_@&Q`i>{@2g%@TXSptt|8_L=D9%wsQa9ERC?{WSnQ(+HHQ9Pp9kBTrYau9GZ|S=*4T{&OTmey_g;A|e!S z?r}plY!ht2%W23*6A7B8fSZ1&SJ%ErVNj&E;&M3%!~k`MoTJNX?~>ckPE!|FjRY7B zi0}gM?eT$XD{Vnw;2-*>(|=iu{vw;*ZC*0o)w^^CxMy6KVGLC9X;i4$l#BlubOAv4 z6zKRFq7)o2{-|p!XK&&^T^*&hb0qN#bH$KF@MN zg%-N9Z-jHKVQe_EsY#;0>QOr=_Lb#adJ~0TD!PF#DERc9Of2$H&7^@_^x6^C8M-g- zAm#3=GRUWWB+O@35z{&UzhJ!-fDU8bB)ww8TDFcr&{iev~vjN z;n=b~;5GRgd6@=@XMd6(bNGvqs{4_Wl1`75**|1uyZh5R)(imR(mm^~y(@zwNzPLp z!`welgnY?I#TeCpiDq1;d3UC3%%qID>nN?&xFHh#U^kgg2d4!a=}G5bwf8k+sA8L# zkESHZ`P(%5uN=k~P%(5mAN&5uc`a~cpbAy{Ee7;HUHhc+k>T)K3d2>F4d zMPg@)e^IYlU+6EhPOgm@UaZm$+V%OE$=EA6lC+v{vdOCNFqXzu3ziuqO+22v#D#hP zxZ=8Ac`?@-+NitiD|d=aFr=j4wCtz8!)T|7a0Rv1s5y!uz=z`t0&`D({oEn6nv-@= z*$AKmZBKeqwCcaAvJNMxnGu8q_PwroC8AdeaNimd#RN~30s8CMiSL+GS?$aU<4rX? z)Rc1T-S48uf4E#B0KHBPg+xw+D7)2y$ZD1Uo68}|vc^*G-*0-mSujK$KDqzR{2zEQ9J-O^RR^WbQw%puUD4V+N_19eeMigFpAEpNR= z`h!z2oz`$yMyOKpodV#-*ga4b1NEQU!{yJw;``r`@!q98?=9r0yj%HIFf|B5GhNml zSPmv{$sfHV=~?Km7D2W%*plPlQGN|wLhweuMYb#g0|;Rr{Z~-@K|O}D>AkC@q(zJ) zmvVziF3h500QV{JC<~TmuL1d1oM0Y950MNT|pE zQRGkU-=Z-Opv+A(Fq@+zgSh>b-T>~Y<~EuGQM*zA>S>q z5D)3)+LaDTjH4`g2RePmm<--B8bnV(LfF;&H3=6TXVeSUuQW>m+H7zjP{|L$t@>$Q z_{&Df1_i;%rbi^*9TwL<{a__RS%_rzRTl^~ye>Gq-at}fyGia)rf zwi63aQBB<|jiK?zr-}1Iu&NhWCJ@^nW110dUg)m@A(9XUx#Lfvr5j5^jf|49V!+)=#Q1=4(25!3+!wn#y830hoS&bdn4luSOi81gy8{k?U9>0p{lu)B3;SdzfB#hp$Ei#_?bL0yo*vZ>yWJJyo9C?Kx@M0hK5}tu2rK z0VVYj>bn2Jy~5&6be%0V)SO`Lc0;Sjy3f^Qczefm_1*4!ytU>DesXvz)bOgkq(T4p zqHpL*ae)oq(1-WWIezEWfRnUaj8JO+JLly5{@R$N-scxsHIAQ2iePd2ho6 zoEUfpw1wsZTu}jG=n6>Jrrg*!YZ`&H8~{m%D5hHpO2Cw_(Xp^B1j)p1pZr-luSXhI z^nft@ofKFJT#P1W9!YrKMsBmChgU7YsDA4~ID44v20h-ZC1aUWMeJ-YjG!4vR6u3~ z`3z>Q1f~nsj9{W*c9>|;wBX9m!YWtZxh^4d#A zGz56$tp(R>-IKVKhDg`$fKsJ#?udZKeuxX?2o=~lWCNl6(>YUnO$ z5E)89I))g!yWTT+-_P&+{w*J`YtD7f+H0@9_C7f!N!u+&S>6>APjo;2J-V831!7%= zyPBA!8k%nwu{7DYt@3YI^d$RNCfX&8n`ODPYMpdFh*FUvz6Y9-ZX*6c*vS8kDc5kG z*~&OSoE`_1F@5nw0};Q+0f=Ql31-FpmKzJ*zIC&TN2W)2Vc%2+y#;E)0XTojb7YXXV6U?PhP{>A5n# zvNW*>Xw*hogac+*VGo^TikEf3H%Pldo!b2W!Fv9gD;=E=M8b%x4u0{n?#l0i<5vzi zOMh{F;gJ}SzySAn+7{3f0M1u&SPt+bi$-*qBSURR$s#+g)_p{GsCMsx@)yrq=oQx_ z9A=Kqjv~X|PJk8mWR=sXhO}C`x+eaEZA5dI?>{fVKMQiwUF|0Q+JGYPd@!+}Usyfl zrh#xsNR^(}KIzl{I100y%DohtZ1x9@)~^(u3|w{Vyqg?UYev-?B8xeq?v9xWRe!75 z-UplYX66M!E$mg^i!d$^J#fp)WByF4lXN3AzJeoFeO9inmHu z#~*6K<%s#gbfglu1HiaJqC7W*HFORnfd!I7Z5>_Pv7U*i3(P8k%^<^$6ki@%IEe4WeDrnSOt zF9gByhNn2o_`n`}Gm+IpdvI<7tQqjwR-iI+VkYn(M^y1|KMmRQ6d9T(Qvh(5- zsdakPcZ(@iDi@i4n%;*7L;;jYT4U}Dk=zk8t=dt=TROi9isqCx9a+I6awe27wS;O0 zz60iV6JjuKKE3+CQw3Cimr@9&99=ALXRXg#Tvyz5YJ<@QAZ35&`$5FcGy0Yqh+5bK z6JiCVAQ{;lrF}kLd^lPMwkkIxh2Du#6_trTKK7V!=op~5C<#8ZoPh5JV?{LCe%7l3 zHA1b+7P%u2Ae{>2Q$VAAqGx3YF7q}kesRnLz?O0;{L~d!6zC|?z{BUH5`ke}?ssR< zJ_0FJ#9DWp?S_*}8yX2}xB&Y=b^66|Zyog3Tkk}_q#o3K5`yRz@C-s>SHrMgcsil8ZeT@8%~P3W4urvX5IqT7=J==>&}F%;WbN=^!dZUuUw|MoagJnz>o z0y0Loj(mWV+u=4Wxhx@<4JHd6e$mB1cHaJg=vw#TWEBxGK$U@cGGXRmo&t~lAQ0(o zZ?>POI!oL=dN3bDNv+iuX^s@yXI(wR->V0!u^6;(AxA(}0F1m8bx;%ij~e_}qx~m% z#anh&Xg0qIY<`P^9nzAytLHZx-H%Tj$^x(mjNgi^gQ8NLqw!$g|8-pu@R4elYQK5Y z2DgBIvzQ(zZaT9Zkb6Y*JCER}&<>P42q`(OAQB(SkpZui(OlwH_$wWaB%!+P_t>NPbS*v$dgf)+A^`e~%(AZgJ1-3{@z8u10Hpe`iIl;m2OmURK=kTI!6aepk*A$!+ zHCj*v0R1p@8P`eQq0FkpG84~~76nYDwtFTclU$lbvI0K>cmIz~01k#3ZOhKnSP zTQ80Qe!J_qB?$q8f-%ulOV&q~Z#pg@vaM!%;AA_*a+_iNa06v(aRjdj zr{0+LmV;_`6;az@jS6w)pervc#ycK>DZ5n3>4~yf;6Ka};%s2oL$&DDei4ie*B^X$ z(^^W*49@&(F3=DTR0LZxy%W^KFunH#x;+oB(a^llCud)7?@ldRtO|iD@K<}OfTxeV zT|N=m*c;J{*MF57dp7;u)H7t*EHPw~Ym%x+Q$iW(*|2*Gy^Nq46BYmuM)A1}E@1{e zfuEr>%@@)3Hvjfmc=1~rps-Bs+f9!}>uZ)JkZ!btA5P;Xej)TxSbrc2l-IUEs}T{A zW@$+Y?bK|OXPdqKJctJBE!`ckN6lic~)1-=bN)UD3H!(pI-laopowbj+shA9&OZ zym7>-x{g(8OgW_?V6s!-FGrbPOj2?u8DLcSn+OD8f?rgK+P@lg-)_A<>hX!d$GhgX zb+m3lB?ML|X&mq7RCj_akBtRh;rC`(DFKIw zjBaJ}uSY$R5LioCP2|~9rnS1AUl9Y-9lS{e(Z91Dn~qrj*Ne**TeHCV#`yaLyE@AExE3D~jLoB9BLs!{NBH!FEO67>__FL4g~@>hJrO)ep& znfu;Xznb0~0UZ0=hoQgR$H?^UvOlx27>B{x&l-Lak2o}vOkH$E_~6}_(f`kY`ENgi zb-49=0>Jm-Swc=@n*W6vp9C@jRMN`q7+wb*ws3g%Sz5V-La6SSljN*=k%k&*`_YJN z{?P$oiDv4Cwth3|yjX46#xQ3(SDyE%i43WyxvtnF#+&Q6o>IGhsL?-svVJzJ`-HYv zDF6LAML&C8?pKHP%>+?}7&AaS6Jub=mTdg2V=!vz>rHMMp!{#jhZ;K77d}2PXu^k6 zr^f+2`nYi~F>LIb!r@;jT5q;i%nc1N1xaiR7-e=@cNF8)e4Vlv#J|Pn6F7M2ejdKS z9S*a&NF0~+j~MF>9dKV66;9sJcK5&pk%@Z*KQTJ|dIYwc){R{pM6;ROtx`NY~EkpUA%Bqjn7V<7$>Z^=@TO6*_ z)U9THNAXW=pA+6F9sywZ+?Rw`d9jYE(*s~c%sV!jqu(x)0x#1=LxCWkb)G8gs0bqM z?xT>TR4hLnKEO@J&NVg_*1hc*pi*EYCie9Vxaqjr;22^pQvRLR=66eBwPuy!>u`Rd z^qIPit1^#K!)jDLP#xqSs)?zDFbXFWB9yTvh5rR0FuMupI`_gtr0GEE^!Pjoe7=l) zmJhWl+2Hbw(%@I}Gw)YrrMrM)H)J*?xCgx`kw#x~ojIEMYEm0HD>(sFMEsUQ;KENa2u2NTnL1k; zBIa5R?#)H*isPgkt%$69>pK`oJRr&M+Y%_pXB<7)Vqle6mvI3~L{bPK;40_TpvQYH zG>v8%XDcfT#hF@1%o|yaEBql;tJ~H7@>WogMS={&oUM1%=P_$&;UA;-aSF z31@r&&Qf|%DMjJBxlEp+8`1=sIL9 z2pS%(#ml#Y3=>c}TI9H6vAq`vAfV|Ph^@dV-g0yroD}f1YB!bDlq9#W*@3S6cEvJr zQ;<*IrRj86MKGRvzeTq0ZyZ7Se0xl04Z(ur(tl$^NV-sQRDq8<*BIs1jwkJ z)5hnm1Sgq)K=pI=)&I&i!Qnt}{+^F5!xh2wZ|#PM;L8hiP{pxvy@l9MzZUU6$fS`+ zyzTY@1^c|$FHf$oWtToY>@XgTyQZ$-m7^4K0uS8b>*yuTp5&P+D3qa1?&TnRs4n-+uDJL@L3+ee<(u>3qpAT(|5v z;>DL)%y@T0vd})$4&Z+4AJOj;*_3hN%g1rc7jrp0SC3VVGxRoW`Z|K1pYFNl#!B5+ zN!XW6h`|(2UA3a#>?jIp$hWa9axI;}GBb)WnG9R5-#~vryYEiWBNb^m4aD;hGe}MR8m1h1k7Yb?KnRA;FkV2y=Zr?}^-z1GS{P7L!Agx{z{gq_D<>RuWlirD=Rg z8lR!wVC(lUT_mZaHC(+U>=8HtlI;ZScYJA6$f3+Hon%7pUO5!g_3yqLm!rmY-njDwbEhY2GtMw>q94(2eZKE{#O}n2eO~pG#%fO)K=_TY$Q@x z@A;RxjpcVlR^z;f$l%o9m#d(?<7=Pa{nLX_$w5ww*q_b)xkEqhbpKl-sd;n3yBtW# zjpOF7>?rT}y8il({+vi3TfR%ulI+}OiQ^v9Aehp9IPtl;-pLM4*QZ9D9=S&n$C1N` z>$%CPl`Z)CLyld!3pZ=g(&q(q&a*8xe#X08%F8t-D-epVRJ-eSHf|x?J|lD_FSnS* zj5_LdiO=D>iqmH@3ny5%d?O@YmAeLOXW$>s2>!n68uD3Y3|R1(H{B6NWT>m+W+75t z5n;nu=7RFzZBumZ7JQan%t?QiB4{W$RGf5wx4LiCtn+=hOjeoNZ8t$*lK&|%EAn@> zUD#`cJc(ZUD5*DWm^=tN_q2}%s|l&Axd=QPg0E{keI==5+kwN}+yW*=@K$HiJxIRA zz?tMPsHWl>WVf^9YxstiyZRhhso{k!Llho%X;1Djk(ga!7W6l!2&OHEVz!g8FUnF5 z`qJKM&7;5L`&zApw1D=Go9pRP0*!+dK3(l#P?!-JF?Imal5eER-t@IFWMgmH%X@G` z6@Rnc3&u7(_w~qq!PUew=}cjELNmhG{(6J70HMgL_t-3CtCy0l6msm|U ztIqz~Jctlh{$id?+{;}v!)0tYREpJwMKuoIynOAK2Zy|s!9^njy3uO_%?f+sf6r27 zR!Co<(K~(tV)T#2K9}pB$Mv&)Qz};MaHQ1RL^3=<9nu5Z&IP5EU8e6U@Ga})HQT+# z37eM@MS+30Fi9PSArYnDdW$aAeTPFBv$on00qB2yPrlnFCp{HMX6MSV-r z{K)uzHj8{X@~d1;q_8H~x0#_lK7Lyr{fOFKf%7uGLCzDW8Ar~}$PiW?6VwX}nL2Y$4hygIIF?7)4G^QJGy!zSLQJXFkxXItC%bnTGz3 zj$_D#l`z8Pd6=-Irze&~<>|-bLa#6G;UnwK9$X#Rt#>kQw>M``;%G>|j7?c_OL6_; zK9d=^W}5J7J773`;~gd*LZXIP&V80fL-clJtJJSMN?AyQTFz-|DyuS(>-sO2P zs}9+F%jPr4f>u1MdxJ-Mv0KmV1)*jI+CuOHbjkb5+(u+ui^rYd-l9;b2}Bt?*H6>X zD{jod19zC$VTJG*YWO(F(~d0glg(sqCk9nljS;t6nX}%2ADi@p@}F&LyW;efqjb%Q zHSsk~EAe0h-qGge{i&w<@M=L~d43@FnSi!O@!^x3^Uh|HBn9VpQ>wRvWA{ z;9g|*@6XE`%EGo&rDdZ(^Xa4ZpRMb>EBfk0-8i;Y*aEGA1`xDs8U9INts{4Sr9TKi zArh?4qUqF@^}kvE-}C?{8@U7oxU0Nn%bt7I7~wP~o>IjQi8@ zL{#2?ufQn-lQ#ps#pd7^m2IPg@}=3v^n0*9*O~@ zk}BhwF&@QRjlsCZ#qmp4l1Zv;diyo;?zNE#;nYoT4y`)kmFCZX*C+t94K^BP15~^t zrxmZxR#OLF+URN7h`q4UyR$PFCqAiL>T4hP$4a`3D+1@Z)c_qS5;;wCPuj5|k#I0t zPMTWe3ho-qG4YfuoCHbNZT=mIEqutoa?M2Zj|*+f2eax0*b+neq@3yB2jSO^Nzh zv?=eY$x5QH88xGpZDP*OcMU~n@q@s3a1Gkt(Kztax4LjR?9*#?Fd%R@6OUsvSRsks z#~x@8-+m*ZOazOOUa#1Hk>C8Gv?V~Zj@yjxPHuVyDEv&u^fN}je=jrJcr=u@PN*#Y z_czc>Y9LyTQW9Io-&$C>lxGyCXYfjgd#4!b4>X$kGmT@223NWZjF8~&R2eEzC4igo zN_>7(csK}fUVoP`dvcnLBQ^5l3d5YR3b*OXs;SRwYb(6ZK16&GOppk|vU*`9{T=FR z#9w?rMe`0#3Wer5_!L=u<#3Zkz77)ha27YcL5m2Sa=k&E>m%{4TK;)3+XWRRxd;K_ z;JP;k(?=YR8Hx|^$%K2imvETR9vI*N3;q>c$NbeS?1EtSy|54KA>*gRgjDRcP7U`~ZvSh*0bh??})odv_ibvoyW;@b(ItRQrdUB3LgCgR32cg&@;~%aOA3Ku=cMXUUtBC4W#8v>08a` z_lh&r5br-E8$C^7D9kO2VL{r7!$JYpsci_`aXYP(h9GEaM!agF z3F+6DH*X6}Q>)kZQ!;=`-D#El!pP5>tsK7oN{|}WH)-IpS^0;1m{*NuYpm~rIlF`n z)c%8^=7v_OjPAD`XVzEF#inhK+x0RnD}OF7E~eRPJlquWwu%1{>hcaIhbcq+hH5*> zp%L?q&3;I7$`h(srYE4sA31?O&z2#AyAsq~N>YLQQ*-h(s%_`CV^Y09ls&}?xp%j4 zxI-$=+EcXmEU#bh+Zd+UzIqK$MeTakoC#}Vww&3|q_Q{! zPz=fY{?T-ybobg`5Vys?V$MF=^aS_RJ2*IiMqhi-Y2NOI_mgk-{2Aq8I$s-?y}m#- z8dcz;QH34)urgY*-TLgH^lQ%S>hY&$k1j24J-B`jx>|;@ZvTH z1+oD7lv9fHeD(XXNrAG@uvywJFBgg|LKD1x8J|V08DSu2Qd-1=NNk7OCk=N+)86<< ze8om1{rz48x%biKX~0T_!%K&MRtUZYk$gTs4s&o^5e;H95-!TAaR@7TWZSsQl*~K& z(t0Y^Zsu-gkXmAvc5(=nF26p^k>9>icH_kV_%lsxn!KKHewx`vqhCZXkupDF-y`tZ z!zs1<;9$ht##27NI3e!=+f%jv2xm&HN%(c#QA|8W>PWafS>Z^1ERA1^5wK&5l-D>Im-@@mUJNQ^dtN>T*c7WN2uvBNxg$N z@+mlyq)ueYS?0LkLviCx&*9^d*w_8E9*uZ@Rylo96f{$5&K&X%`-P$>_N-|jm_~Q} z8=00MGFBdeQ4uHoatoni|K>Vm@@3@x7DaLsc`WTjV_Ei}+wLpKbvzWc=6NpY#(`|) zrKb#B@N_pxtM;QipMa>{kk?m zN5trh54hK6O@04tZCRg79p-*D=9E}9<21HaevDldC92t$+RHWhB{JEWD#$`wP*8l8 z^2>7j2ye|SAE03LpNYz22#a0Beb_3t_zOS{C!3_899|>h+yp;C{@8>=u=|Bg6oAlKl7{kETBr-%jD> zt_Ohz=emiyyo@%*`-W)!!Lp4zTsUpt-QDtPT4tCvH}t+bK7NyI@BaBF(i>%|z0Afo z3p7e0%gwQOU9@=hhrVEb$y@cM5gDc$F@enBr(z$n8^$Gd7b$w{>~V?-XJDot2hBJ) zJ{^?42=WMpn2Sc75jcKTlBbr!9yUW5J>chzPO%v!$GYLW1^tu&efiGPU2~-_qmH+K zEs=N15>zO?Hs~idIS=b$9X(3ht|Ty;S^s+AZeJuh1apaJ7OPP%h8XEfTGAW*=LMh> z@+WB1GW_PTyYFgyfqU4^^1%Wz+ z!6LjjkHot+1F74qHq{A6N=Zo_3r2*v1zhmT9?q9+2tX0N$KGFrnz_Z;!NrN)#`qC9 z$<<1uvnp4k&#CA6l+md?QyE0MisJb2=dKqf>yNGj&xYG|uu8X-HU%@)19q5e;aN6q z{B)F*+vz-lKK6ZChr=+lDR)1o6@9F^a>Bt!;mjaz-9&w}TIjZchlOF~-Q0iv1wtm) z{jsW;4%+zx9sz*_R*JgxO!It~FAkYOeZE^A_U}68DM?`K;1+GAyjbc_kVGJUb_qO~ zQKo7>U$VQW8&8|^?6-{>@>#Dqi%1h*+udRd*aX{{J@qXiTLTr|%Sj}sbKhn98A$lY z?)9?z$Bn}Ic_hQBAFp1N!=y%=?ZDBZ6LGuyM>%5&Z%6cu1qvJ`CS*{PV5@* zv|2E-vYrJYR2U*9-8Fb6ytev}UMJYQ-+zP>Bgou*X}gIZsN~Z!Q{u}lAw@%s4@x+Y zF{9x-g8Bn~#A2t;{&7C3QL>+0WoAPTT%cN(*sL zEcxP)c}Te?>4ChJtZNDfQm~9psA)S2uoym$Sa9E2cMCP0P`uCUZ}k;UnaoiR0>vLG zt7VhWs029sA=lN&*^P-S;kD!tz7x`|?IirSQ^~Do$Z@?DkwUao20gQ)=!)ez9lv|J za#N7<$g%4>_tKUaRF;4Le_1|$S32OyiA$mJodKBkreCNF7Yjew*11D2tE+2=ZpHiAC|F%x$pIzq+#mez^Eyd=CoGHrx%0>^t zB3FzuEv#R(wv?tb26REx7rrNxkq1g)K%3$n!@0ec3!Chf`>gvjTZYY__r4jQu@IdvZ%>1HWT*x5Jo4my+Fs`I(qF8|c#LwbWey=D782m2%jByyBT(KbBQD;l~*Gqs@~x>~V|jH$&uKP!v5b z{nE)2(F!PV4*VLiyxCqlGU3(}O0D*n0K+N4E9{#tVlyR!ylvAXqA)$KZGo!;3G&WR zoU^wj8r!D)91TQ|eZ1-?Jb!48iph(1t{u)!J9zopYmk8(^qN_PqPV^?JjQ38Sni8b zE?7-PVhJNwYT64fPEA%G8q}mesYyQ0;i^t1%L!@L2KmuRr5bTY>`USW6akFvz-6Vp z2MC~f(P@42dA(OrW~CT^P{Zh%gbyBW+mEWv4EV}pQ_1=*d%7X{)*aCaB2uC*Qo1nh zrTOo!V{S#2FX~+*-}79NyV~B(OK}f8T_(#9%`RH&<@buaicLFo6AnL=^ew}eS zNI>^rd?gj27I2Q)-qk+Div5npmB~^5Jb__md|aSRHxZ|N+{%tvZGw@dxGT*h9wE5y ze$Q5ca0{zvLLllswSYi>?P6Z$(Yu)AYZftl&HKtcooBbF!_vDP5Y6Lp@g%saxWWyq zoj&|u3Xy}-e+kxCX#hd#+1c4%#RTXrr8A$ol!&?@M~!d`XUSt@LFG&oxjN)n3Zlu~ zqDRq!lkbylmyLDL=0XFlAy1>wM8g$a$aZ;cCzAo~+q}-+435;d($J~(e}kAIb{Ebu zF{7#U8RWM$7^=-4NqEe^QXA+8UlG~1y1u9xYrOQ)1#)h18I9(F>v2;Jw4dy+=mO`x zfgI_@dElO2D=6NZuqvkN*2%GezMd*hk@I_n-CG8-4|B6U3l~W+<}rU{?Zq^4+2}T6 z%=B)dtLDD@J5_15k=?!`y<*8Xlb#EaOw{zuDzBPOmp}bxy+bcAl}U*acd@G=s(HW# z<>4+amtNsD;)`-k;x!9#VRlG;==AU-A<0j@l?Stv#>$PJ2+k`5ux7)$WQt2&tcQH)hs&9b9tL4 zg9nv267Py55)B54|E0)Q2gbBzrE)CJ8807-HeLkfA?&bZ){H*T_ptT~xaOp8P+Nwp zsQawydcaif!_k{7jOcw-g8L>JQ$H0VALrU6F@JrmwJr0J+8KU)!jE5Dzki0aR-m_{ z@^pnUbCkJ0 zE4aRFvLsS|@HhE4OH$5_5#orzQK9)S(Jnbu{=zDzLL>!JAWF0E>C?8=$)~feY7iX& z{cUP8j(32+Y;8f&Xy0*9!YftFRD+ zkH>s9N^enYmN!g4FBctQND=uLYec4P&p6Ssq6b+iaj`Z7w;*50HFH7+J)9)d(M!F4 z|G(&e38H@uQ7lncK_6Bg%={x(aW|)p@8_TYm@sP|bXKvFQ@hL_b<>CE+#UGL;khMe zk8$#GyX4PGXxcJi|3NJ@^W}PJEu@%6coa*ssvU`pCQDt>!>q<LHk5CyCfZ=b;%6}r3 z1bY&5LJ)$2kvy?D6USacsqhec)JX)B==xL8rV+G&xs>iWuboVD`k4GFL!Yb-4_7qT>T4$yq&`d#wqBA(9buK@+Tv}X z6TPFoNrGrgmO|l#nG8_Gq61ke<>$>LagK^nsSbO`dVLF7*Vb-uDavvvoM`Y-1P;a{ zzeg0LVjI1oaC%GAkgt9lG9Q(bNsmv&W@ktScij%(i1nshFG<^VIlPNzem$G)d# zHZ!;-q_h~WYh}On*1(DS(*>aIREDo-6$PJr7UdyaXh<{5mpk>rRlj0Iu&ebiauRT% zD=s?MS4EeTD8cF`Vy~TWT4}0xUDvn?LlpG}b7^j91$ssls8G$^GnhAjR>&A|nNpF0 z6bZ&Tb9`Gg14zg}4Vzw--|y~UKnT^^WX7t`~oMa{xF>p)IH7|O%zpBu7eO9&p|qJUzyN| z%$N-GWykeIb|qsd9h6yU;itdg^768lw)T94z>MI5N%o~)3UMn}`+ft_{G79Xg2M`2 zK1)e?W0Y|-1VG;3vW_Pka<8BiCj`+qaW6YUsPn9~X^q%l4W%NTUR@Q=mVP%lDh-o_ z{z+!=#$&Bv6rByTs%FxwhScUXRg}-x)OAPn`A9eo*-N+46^O)yJ{ynA%Y2 z2}kXu98up39gw$bv*&v(N~2e)8e{@ylgb805P%6-tqbg5VJ4qpy_su#{>5@4_0Mv zXpZlFDPkGs>;WNg=jJQy?AMkKpqlD>IHKvcSveNDsHH}n+U*(=v*-)cC;+Abh~zdw z+c8KDaiTj4_v~L^^abizMLX|O_L?^Mb^oW}VZAD*4X67#Y%gY5hOYdS9>*-BWZF02oZh4Ri(rp|Aj6byz}8iyTOGNP$i$wOITpTCR;yvWlrz;%B8y|<_33Z9uP^_vu1d6`*@kCVw=00040w7|e3}vYtP_wa34I2( zKl&q#5TxL^=Wdwc;^A1-=v~Mwy&WU6AJ?lMZ2tD(~9h7(E;w_ALq+1b=5pem1J73pd2W+!ACA&_&l3pE$cp|^m)jnLj& zZ5T7*+~04A(l+**fZP%T@=pLk_E7;1Q>53NMy=?>*#Y9We=B_HAzOb154k8ol=6%I zD1bTi6;%ni{=@TEUmqwg`DEFe|8eh+5_X2J_=?%O_uaAa5Nwg{mPM`Zi5jlM_uxox zO-E{i7=IgW*sRENvn2E6$Hc5vbV4v&Imenv1*^MBg~Re-`o=`O|7~alU4H*V(HdoH z0@0%Q8jzCET3w6u?+3412;hX0L;=@DFDhDu1CV3d667qr5`uUqv66#L{N%3~>ibzT zcUYcEKxzL^fc!l2j_=$bTal9{AG(|M+bPx9e&u}vSrcor;L8H1|mR_M*9C(HNc%Qs4}Buw`BFC5>-NQWabJ$V>#+xh@QWZ ztFhhyVH?B|r4aFKE}jCV<+S`p0=?xV?DJ3U$RuMQgKz?x(l0UXsFvC`>@hc)Ng5kD z$Jn0?`El3`j1O0Iaz3ZYPCS!7ynUt1Nob>-mDXhdXV{MTRI#2|;WH!aFK^XVBn&BS zF*B6E{sl0A;QtC5#*MCGkc-phpuBZX@#}LBn3AB*U$*E^`L6bDcl*=SfYMKyfxbdjKJ|Mw%n#a`!KY!s_^`DoWC3G&Z0_TQ-D#iMW#_hSDgHH(i~ zp;8|{^yA4r!VbgH`REsdJn3wm1hK#QBEqPb(7(Kcb8`xqStnsg$-U4o^2*~CZXS@! z&dtf@Oa57-kosS6U>xuXyf!tw4L0%E^&Iy6W$uSmg(33GuGPZ23Qa1Z0*=F|g2Jiq zCEixyqixTZ`Fb6c5JwcUA0vemLc(zWr)`Pb7v#Z^1rf)u#vTC7l}IANM%9q+qY(F0 z3}!^uwWTMDgKAH1IGV8P(vi|3>b+b*6^s&?L-F2UHq^iriZt4s_Ums2_;u+tM;RtF zlq}2!9d?6iEz&&#$a5c2+R?q(Tn7P;dlQ&3nv=Tw-49q|I$w}cj2`y>SZABBJ3b-t z=}AZxfA8&m3oY5$8qr##Q(o0!v)#C5XPhWkv)Rbsz|yjY-Z{ZAAz+4_at+K*S9*2* z1~;B#NV`<6V1@Z%xwS29pke!4Wh={hNae;-r^JNosMD%V!7ucwlb}T;gQQ@Q;J&~s z3Q}2(Xa$ONM!3)O@dm3AOs>?lf>@^JdexS8PM{Y5Z|-^V`U zOezw^VeLHYA1Kkyizpp$;bXqI$CJS>c3GWQhhS>EJ+ zZQ&Qv!=k>zM8^3`^@*}7tH`JEMCk9!dm~7m3Qd;684a??0KU;@4v{Wyy<;pYiUy+Soi08uexviDO>%JUH)mk!zbtK4mEW1p&0*y9ZYUyKfKX} z-@Q9UDbHRCDq8U5x%}Yl31WEiXJ7nb&S0`DY zZqrB+W?XkGW3V%fA6cRpBemFbiM5Nm_m-|W78XH2DjNXE`2j*|H{5Vi+rA630v#)EJ}9Un0{#Au z#f^`o=jyz!GN%+fwA8^MzrgJ?+sgi216u}x{javGr+n$+%^^mT@TKx}$av zg9OvaR}GJCCvfS6%VQWtcj{I*O=T!G_Cm-eaPVoNJw#1;!trF;d^{qf|tw)!r* z3Bh##LkZnLJb@wA!*6n6-x91F9To)O zJ1JROcxc1C#|+W{+Q=T%SAHcQBzXI{4k`&^uhA^q!&-VFjcqMOJZZ;+t6zlSF(?NU zk8NX1smSdElgbJ9IvjPyodbB&mV~ri8Xsa!F~2eWy9vQmz5ldlXzL~C+;l^CXCI;M zIi32}dstsX_v_uKBR>UWco;eh5Q?vJA%#y@;3}%gWM;z3ax}PCm~+@<$iY*Z{`8di zr^RD~G2jav>I*dPKxGSGf?3Zt{v~%C{{U{Jqx_OhPTYgQt^8QQNP|8k@*QBMFB=6k7l>#dr!x@k<5djFFG zINSW_nj&{*^N(lOGEkMYAG^5^he^pe`@r8kBv@||Z5?76UBvvks#=my+y_Z{8Eh0p zmeW~69GK08MICSR_8I0x3-K19vIdV1+|lC;rJKLdU&| zB*gov>Iwqdm%C`e!2B&goTpw zuddWe9gQLhS?wPV{wOFrR!?^9H<-9cs;HahqBTOo-$ug>o4rPMhp>4x+X~7=zp(x>7@0?wmM>4f=spg>}dB_e)alyaCHVEto>Dt_k#2+m^Db zp*@#i5P5y_sxRE3+{oVG{peggN>K|3irPPd2$i|1FBI!cxPS9&Bbpb|U4xJz<7bpz zExdhG=Rr5ttE2RQ8|OsUoq=4kOno_BjJj-M&2m&#I|I6%~~5jZm3bzDtXb1+r=6p_JR5!jI( zB&|XE#y~EPT#JapyjkK;Rf!*Y;KRX9XDzQkSxuuYc2R??g087g59?&gEj~R9R3YH3 zxLeZVs2ZvC{U0uppLarjG5*}!9U*VBoYQ5kfXY;4+xKD~xdx3yyieN1Tt6g<9Wnmt z6*xElIKx8X)E0KkwBEQi%YXSU=2`_vHFv%&g~BY80f0G+^pfbOr;unK+?D=I90k!( zH_N%9GP3Q)V=cY#YcBWKpuoFcS6iL|sv2nt+g4LS0qyqT4@S?tP-%h*qaC7kIcWxz z89Gl>mL4l7CoGFZ>Z-ITBN}ULe%cbS{~CIa;kO3^cYzB-=?malXN4uLm3zG+!bin5 zbDohU?-4FiI(-k4`;=}AS)YYzRX#|h*0BgRjR^jnw~O;DHa+8QIO6n{e)Fd)x}?L; zeS8tG81w&N4AVcQKzBq+7r4%2PTTt_pM10}2`3%dZF6e)uKa!CM9q(Ojd1nzi_>pX zBAj&XW)|KtyCE#BVe94;`~t}pb@(MV37w)?)3wsNKB4+|KFnHo*J-11iCNjJqx3AJ zLe96uj25G&#$Do&E;pmYv5@@^60fs=mAIo2U|ACD7d@s-;51y`zP{RyD#C2zDzWik zCavJ5C&r7(3`PRwnKp|{8qxaA#-1aHm3$#Um#{O4;2SCnT$hd@cVy!~IVlZ})G(Bm z8*;lhS|F96aAdb%aruTrLrh^j&xrg%mCZb{^~M)yHqDSJt_{ZbAFUJ4V(~a{Se9k< z_>?o>$c>E-L`ynZ`!aLwW-57#e`~5$E||%gpOvb&xvk@G6vVX`vJ?DvrL*i+D6=ou z9X0dVA!)VXQOuWe{%R6rEGgV2;dJrN%x|nWN`q-%GrN#P2}O7?JeWx`zOei_|C`8; zf6=Mnm|9(h-wm}ccm8MO0ZuR#=46+mlWYF9nDU{T9sj>(2UfkWY?Jt%Md?h7sDvC!tTCk|)TOCe!@ zDkF*RvyZ9nXh{bt#l5j@ADwQNjj}kzFi5-@(_<5ttK^N)z|?P+B0G~7dP}eMwmEaZ z06_EhdZm=2qz7Ee3o#3*RWkGQ3r4RIaDiHiBoR-CqcPG-V6F?$TimfJewd##E}O)e>ldH zvB`0ZeZ%+egj_PgQfRpflbR_TD)pO|pGJiBu!_`MJ%@GSuneV@+3@;dn0s4cwhNr}u2PGoMQw~5C zYP!DMrdfrkl;fOD)j9xb`sj#a5MqH)_vVJMLs0&s=a>qzz^xm>*LMKw2SfU$ev@DH z`rB%9VmkM!H7D6yH(l{CtoOK0ya=dda?Fop91r^W{J7JeT(hR7dj{wjVM^(qNPgV* zh-Kw~CoULVYF5$!Q=5QH?y) zuOP@c*lJ#<9LwO>{!vk9T}5p?iSTcdZ~6X8mG91TC|7$KZpA2>j!Dvk_|3Ny{8jIb zgz)%N@aQ89(mU&+%M}90#%3Vr2XJ! zhcdV3_*=zuRkWO)2~C%LGGf8D{q$2SE;v~A6x|U-vB1gaUkx~|{vl>=9Lbf+V6Kq~ zeIL~A`GVMA`r~?hUR*9S61z_Q&w~W7SUfdp^CDGg34aapHZHZ7Cghlb7RKZJfksdz zA`Eo37%tv{7B@wDDAhE=bMvVrX*>-tbNc#Q;Zw>r`R(_m3%~+TCLewn@IPzT;=c(z zC6}m~BO$O|OLyJ>FEf_=P&mAXI*iZLf+Kk~9W|tbR^qv^W56!OD>RiPdqNKS@mo8S zmi534i!X^H;pUB`w}hNvME7l1q*21tPcN8x7+uoS_5Hov3N;KwzaDJD3Hy$2ryOXQN13-i->*{l3jMAzP3 z(~e}GMIR>=e{iB|6SU_LnfjKT8mP*xf4Sl~M#(&T=|l=su!vr7M18unzYXIHq>5E*3dv)meV%7uP-;}+6wVx4l}6!SfJvvwME7*k zzvwQTFfBG+tfr|=seJwLyM?>r!!2Sbb=QLqGUCJl;EjV>-46(EY)<#_?po;8_`nPr z-I1k~3%(CzF*5a4K#_)*UYHx&c1ZsJk@XgSQN3T(D4+<^-6f5*bT37M(7N4XYX2YG1kXqWr)@)SijuZ z;vnrGRV#`on0Q~@FE!sS{@%g$@u(M}R@rD5|BG3h_Y4Qym)xVMhMeE>U%*@m9Pnq~ zWjPMO*o8(TPQ6$g=DB6dotyrkP(|ocCB(=Re&tDon`g4-XhZ?u?o7FrA!_P`JcriT zxB@Kw$goOmQ3o6e3I)dpwCUkr>r?P)Bg)u&`P3PhaTIWfU&7dSUyj>1g0M5+efe4G zO=Slw^;@P^3$a-p0Zxy^Undht2`v2Y+&m#rB2?pOn68DZIp2(vL~fg{N$t?sa79^A zG*@Mv)Aa$^_fT?w)?{>RIHw1Kv?`YqZE22cvNydpUiSfDe`O;(aG+}FQ{#;ZY2&=P zq>o++ys;Z(l2xel$!OG=_X}e@<@v@qrVN@ng)|K|+!)w6kY`j(AsWOV7DUlE8Y~!F zf{=8%?P}pF#X3EsWELoiJQk~kj0xmU8_GpR+$tWUz4!}?3up~!9tG_z^3+Co#g}nD zyV(#K$8Drar+y__g!`kjxZej#pBl{vk!4 z&^ZFv_JEcs{PmDUTVc*2o14oI^%J=KKTOW-*BQ?&=G-_93`9VI&kqP=jarY~6U+ZY z6!`?{bv27_XRplutJ}r71PG-2&!IL;@5>~f$tf(LM}N~K8vmd**vZXh*>fGT0n!eW zYc}?8sC)w#nBI4{-lQsqQpDktgRpsW5@FEa+qCz?C@KcbL~BJR6fpa}?V)3Uc;}Y$7Aj5_i`9>4ub( zZ0ciLXqSpnbo_S;X5_rJp2~7YIH%S&#Fh7tu^*^2PB7s#xp#Snyc5P;NNNbf;94?+ zQDV>elu>rhLL2CFY;(`*??&7;g)e~N3O`<8JWKSYo(C}YxSbbt*5yDNsqpU|y=5-6 zay4%EBVCn^K;&YJyW(I-zLTS8BkFmAqoAt@`_G56H2YWW3j9)F>(4e{T4v!@+GH{OE*y-Gj@FoD7+>Z=HAJGk`!fHG%slckuK zqC+EXZS4t)UE_R(D^KAfYpV6G;RuB5X$lsWogmeDM<DKoZVO#n;+%)0VFvQGhU8l4Wy^}jpLB*cSm#?`2acv>n!*{miKWZnHCU*Jq?+lZ!wPH3$c}3Ekpr1X;p)SzK?(rGQtUg zB*C_wMYHA+4EpQLgrP?eYgORN+*-2U^OQPd~#&?60UL(2g}Kbwh+| zYq@1*sC;(6kt`6>_@yx!7KBu`EO|XIn(Gyr;ZwuSCQ45Y+7&;^Z9^xY;G0{V&7ZR~ zPiL)yJ7KSYEv3CSzY2eJKt_)nlGl2E9JY)}>3fvhB3s_3kxxZ36ldoj!+?o!$rRN{ zfcC!ojr+d)?0yE?1}%uk0O(@?3li(!X++a0;l^ppU41&e20UP=kW?Ew@elv;0dQtpxV-BEX^x81Fq15sSn*MF*~GNa zH>?q-+v~g8So9dy5-vH;g#Y51h>*vMN;8{t@&5?mP$iWc3@{9oSb-uXv^P4)p!g5MF66_ ztw3;z9Ipz$I^9{3j*pgVR)1i%94Fayxu34x`CjQG-=A$iI@3|h34cs4YGKZ`Q z0ed2KGV-w?>&c0DpCzR;hR+!5Qq74zUIXO8VC|{ykt_sF=+THmJ#A+#aoiz$NKun( zS*y<`RY$FSK9!=wS?3PeBu*N`W8OCM)fYvQ_eXG}haF)1bc&Mqjf=f4O&W*OSoD#s zl?l;P{b)fAas_s-TW^|bcTpx9+;*R$OUa4o%VnW+ISEhewOn!HGfBcGr}}irJ;twe zDtsnwaHRu!R3$M0T?UwP^>;BAU6TS@w#WY~&y384O!QYV8={pwb}?%NcyU0J+dMw^ zJONQ=)~bQL37-EesQhv=p3Ni8f#D8y=`S92izaplt|v})wu{^a92rS2oHO+&3^ZiX zsfB4qX*75HU7?ze_SeShV7*3+mb}W&w*!wMFXK}jfIFIIp&K8~aP7|?{At7+XLGWJ zeDAmk@b6im;tcCvN7`1b?}!tES9Ac6cs*iDYg>LT2>6Ut+m`wT)ww2mcN8b}TDkJ* zttL9-tQ`lD!6URYeYH*K+hwX0RhATFEL&)m!{TxD7+izFvCrhE_YHK0=aNf>#~n3& zs)uFfe%;-a`)rjmWZTqH0UDJyVC%vB*O^5FjH^e-aWU_hlW-JSA<)JeT8f7E`~r+x z<5c8m|7-hEJ!eA8b0z};s2CAyd7UlNfPxzabq*rDsx`zot>n6XVz$~@{9R0zzmre1 zpm4UqrGAZAA!K}m(|=`;3u(w9gAAiT{_5s2=3PydL3GKBGS#4D`&$-WAw!gxO2 zfDy9%CzB=tRw)duK~@Li9O!DC9+6iq!BxvZ=-Q2Wm}PsM^PEqvO8Jzf)smIf537qW z(R(`4&IUm1fA7hj6`x*hZB+A6;Mp3iv{#D=mY$D!nXi1u1f;ib1g6UtKXQ0~nV zkE<#$AQ(EE+X-kdhH!b15`-N*U0?mQVqng&ikRvBWn1BM_vHv-UDR- zh`=3d=X+qR+R$AqM_ftGxaH@>{1|5V(!)b{_yJ?LRy1E9ejLfs+~>P_`@YpTX=s=T zVzsKzqn%#^bWlRd6yZMaRm#LYZpe0)rNk}Vw~SQqgq#+-zY6nVRnE4Oyu|`~Ds!h* zO8m!f{B0Lj#oLjsY_e=s&HgT(C`&zt_AWVLJAC~7a-%{Soo!tXJ67K~$gL!ThCn99 zFyGyI$DXeJr+dqbtHYI=mO+*VnFyGxkl!{iOnHyInhof?sO` z?EPs@6MH2$YvNsQ0jLry8U+KN4wW)V`HhJaBMF01LTNH9_F`aTLGr*G!^WDYjZlq3Hd*fkC3({QXDj6>OT>8?XM0on*Sz4m1E~=M_VpLi7=1Tv<yxy(HUX5z>B}0 z?c-qZHKcntgj2j4C5KrU=1iS!TM>}Trh6+t5NaQ5|4>*|_Rh~gl_Rh;U@ft? zG$M2Sd#*AxuC$j79bfh+I<}uI3f8`iV%Qx=hD)ZK6?atBh{1kMT^Nf{KY}^jcdR5J zrM#ej=+8=?QQRwu^q##=gyU?4?s>KOcXRl%V;kv*m z%3tSvd#>p6e?#A=#(50!;=h-CP>b{O?#jCQKP9j(klxH*J{YNAoQ#O-OaSeO@%$O7 z;mW$g->My+GWfH?_D2xik!HZH%bnx*W6XlNC6scd@~M2%%GD^aiz&wh45-R+NRtx} z-|wt>`N_&03F;~QRblf)IsRuEDWRi_`OeEMT0dG&q)^3?hLWv#7wCu_eQ*c$N}nZa zSmoIe#L0L|+Z{>=hm+>|{o!bcEH1X@ipsfcc%@$wQ2=nY`jE$1Q1;JLyYJ56Z_q~a z#dUjXonKDKQ{Tz>yAm<0dgXcFE*}Y;2|6!sWDH?b2gX|dyZ29FWRNYJJ+Q5?f0B(X<%{6RJh#qU9D+jPa?PodMH zCXuM<@A2O~z~3v1+n(;+amFQL2FJ;qRa70HU&rm^`|tA-PFIbz&wcPpTGzW(b?&Dm z47W||JL}AvI~C}JR&I<~LwFzJpZlc;;?|%1PNTDTh6emMY=xP}p!#Vr9x-Yt11y%T zZa<}(sW#gJ-<^X?ArgsUa8Ys|Ws1mp0nt2WfX>QAUo`c%QG|ViM%;)%SZoOFy(|kS5`?{PS^m(P*Y>yxk)!Oz!F;_)dcqz6b zsF%To@L^yLBT*^3IP_u9cU;aD7|+S5?mL?mlmcm}Ub#L_uu3Zz!53D36D{*&_DF@H z@9#GQ&>Au?-SNh5lg|TM^PrpNopLSNc@zQxvqf2(!0!kH*$e;fRefHo&+r?+ddqws z-I*_)dCjdU%yDBB0_`P3SOjEE=YNviSQOtI7oN}c`d*r|@?%B`7}-rDDX$GnF)C?m z&Ycf}nXM+wM`gf)Nla9bl8nW_f>0V_FxRd2<%L=E0pJo&kKL%@!k+QuP5#2whl##+ zJs5|uqllA?jm3Ml00glS&?Ov^@hpC$`#1p0nCpT&8|=+;6^tjQ>Eqr#`7td%cKV2= zDRyUG@FeQj^a3J3dVj0-lcYvnh*b*?lt*qH3gM2QVtR#K`y3P53pH@EY&pzm#L0v8 zVLo}n0Q-@^&%^m`&es%nj(aN(F+MYAAhZ2aFZx9~x))qKhi-3g725J;en>j6oEeyy zkfIv;l%(r5yTL@A$_O-zS1^rskrN};@9awB<_gTZesaT|JFoPoIWf~>u}OFqCEqj? zjOUDPk+Lm){yD$O=^43gudB7s^; zLtAoeNp1$KNF?_%n~r*Nv9_VMc6E-}X@P!#Zb&ZK%A2n!IomWcr6@U+fd#8SQ{EUR zNO$a8IOZH4X>sxJ9Q=8~3-^2EA^WUVH{)`SJz~q3M2&1iEm6K81j+8SASR8W#wM63 z?%{Hars~S{I%N3L|L}~3)3Et-a_~VE$!{R!H{^`WEJN(p%*)jpGDS9nX?isjWt#ON z;XlXl8ppbCJi_N_NaV}Rj+3*q)N3AuTCsfbtCnLC%`dB zqAc%L$A+F-tU^d^i*8w2*RhS>j}`3^SLjEGk|mi*BehpZL4J|NB5R9XZF>q+e5mp} zwgi?J-Mj5LvO$}8YDgg;up;3?aYspJ;8p8PJ>v=7%cBi*D|@T0Y%Aw=T#o0XMeb!d zs&By^EEuX4ArC8sVjkNg=X7RtYdPt&Uxd(g@+2#yif}F8a z^S8!&4PG-X&c$XAfSHFM41cqpD*9645f zPGRUl#fO#Ki^0>Tb;+ULA*bMNH?L!5+k&TmC*5ZY*y&fz;YQai~4 z>T@ePB(QDa;^<1U_sd0<%cUc0parzNqI^@j4faxr3SMSe&0jKRiXpl4RT}LgJuq9d zPL0Z-UIxsPO>Y{Ek)uTTG>O(zvf0I1^P>&P1ivt5RX61o4{C`Yjnj4#-S2wfj8m!B z@5k6l5|JFQOC$g11u)-2I}L)!x*cD>9J@Id)9#`+lUhv+V!DYeWRM(a_6|OOUWFL( zuCIRIOM3J6AH|i+m|Gf+H*y5zFx)3h$=n^u3SC_u+&^!bE7;C)UW6q$7v)rWQ@ zEwOZln5SROK>vCBl*N{m*wMu`P_`2{OV6|`aUi@^4tn5SZ9~!|*V>%LA`dnhEojs% zqk=6sUfVe=G6wUW=mWf(W_xZl)(^{EADNa@cn7@8jwJ7LvRv@Dr#S-WED#?i*7Ai< z%(hm4b^gRtclxKteC68E@$0@6+J*jiXbnQ&@N~qxA+%1g{v%1QfkJ~FzUG@3z3mBu z@E@(JK+Ff!+WPQj-v)9sSUvi^`X7pz{q7`leO)axJ|ABHTrdhKR}7L7#+%W219b<1 z^u;71E{plbJV$$N^|UEKIK)HL&B-VTI1a=wKQrVNfd#D}ghwONf%45T8(?zpY)Eh? z;c=Q2nyFIx^#^1_17l7?ds}eA61q@Mvm{J1Enj7JLsHC=R`iSZWm7acPra6@k_94) zwvgS@+Md+oWx0`p|C0~dyRMAy;GZ9@%}H)0Nh^?hl!5siE-4fo^q+#OzjnP@>X=9Ca3;Kt?G%3@B3a!#J5b7~4dR4}2 ztE&v|gKU6H#xfjw)LW$N5pZ#9Hbeu2sD$!`0dEPIXwrOV7~r(bJr>mV^LB{BwNXJn zuQ&X-!ddO~(bKw^$I+jpE4!tCK1)_pvTRc?+tDw^v)PTDc2EnKp0o8Li5jyt8BKDW zQgiS1rhKXBp>w_n@}E!7;HRNPvfZ%K3=4?oX0IGm!i>!PE?DM~WbLN=gPCmD9ENH| zjY?nEk0Q)&1z8h;MN+-mf=>=OlXYjSpoeg)0zduUIW+Y7@dhK>dHkQuQD%ADK-4KR zp_=ZX^FE03F`?e^{jP-nZnygqZ2K4nD#@0y0xa0Gb91V+#1FgKGSRvDX`n~_zyUco zycr%molmGX_Am%NSmfg^gr9O}^|N#O<)TOhEnRG5H=I534#bBG>9^E%t&?K#8a~-G zU=k8#wF%kU1T{pZU}IJ?$-jXSh4|m^u8S+5Qu0)UMfVC<(RWH!x8p_EGdRa8qMIqpc z$Ni!RDIMw7EaU8^JQE1Wny;Kz7Fe3^C_gQ4wk(b&1-t>WNM3wT8jf}8xTvQ0bA}53 zYr$XtgPdltp$KUAJ0~TgB^@MF(3O$aVWE6=ApDm$Uu=cZJ~Rt!;8>} zylq?XK9`Pt&~_HML0PW3A-l+JE%=UiwU__D?R>C%S)g_N?#WjRS7-a7k6YAjzuDd8%*ARLehDPOWHgTiXgk6$2x(Um$!s9O z5Mc?G!_|%d^0(Y_p%Ef09D^kJutQHiF|n`l-q+ z!nv-56B(x9@g&3DT06&W54K}q{Wb$rtQCni$YIfENaA{I^3-!Uh&E_9gbqAl`E1-5 z!dGsi9QQflMI4YPV^qB40`l<*f8~G(&HYH}Jjb8s4`-Ryo7q0`YcS+aMipq?6X-Xe z<5$LKlHoH~Uo6r}Em_(Xu;YMUtw_Q^8Zv;B!dQ8+P3G;!CRkvBzK;|aupIOMbIM8f z4H8@D^{@LL8IRgWV;d6W(q+$2zXax!jm9i(jEdVh?}1Cru3=f_ZebqE%9RFQIx=$k zZks5j7_EcHD!!Zfak=AwIfIRC8!-W!*vs`bao<0EF*`9I53*A+aNqWOP;fp^Sf{8` zx5gSx5=`eY4TuPqHjK;U*rgj0TMNnE1pv#4)hxV%^YS?RA|N+`lX`bgI)8TQk}cZ!Q2%n5yj7>R#P; z)Bn9S+#E05Gmz`CxBruka^HoTpJGIm{s1gO=u$s`jm|&wZszg=3waPfEWsJ&7-e5e@$`PCJH&@ zmZ}el7vDLd8mhO8bNk!I%v*h(O0iIcE$=xs3De}Q{7ylO!zN8l)3s{?)S{s;gN`pa zfdx2}WZpC*mD~xhVwW%$j+>yZ492~1Rv7V zIjBP)|L^M`{uYh50FgP2P6W1YxGpw#udNl3Fp-3prbpo4dD&e3Yp(G}zC|Z?-fHkn zagRN;^e>PvR#J_X!{A6G6w}D zTkj?l@wV|plPK^6=YJW zqOTn8x8;jPJm*!TATqq_J$`M)@Cr8QrbO>bpHP03^FA&ksf}}hb8$Mjy;UOA)M|M(k7a<)GweqQT^E>kr6e*Yb-E?wOgKh{Hz&i8C z6qr^M!wzGZOd{B&1XQ53d04^QAUv5pB&b-oz2+?*h*GCiJkXu`)a$ed7S(kA7 znXUl}mW-rsqv6exrXS%wuwlr~Gq_J?im~A_N{!gR%AkKX5nUL~fSD-6*AA?|rJP=H4buooqF15c}P4mMiy>MT6!2_2MU{2CGVx`X9O1(PMCNG%@*XDZHx|+O|Gv$ z>jQV({l|Pfz}B@o7!?SNq#+VJ0f77RXA{} zfY~8Kq&KvsnWBfATb6WWGW}%k&qA6n<1rViczg5O^`Sl5G4m9#-e7NUZ_o~pbzWB_ zb~ZI(r?sL=7l25DRJh5yJ=B-|<`t~k1QYZ)Kw{piXrTf}-|3CSr1Z5ha28uSK?~%a zen5~EgE0_?eRKRjP+%1R%!`t9D`T=5jN0$*0xjrCO#i#*I8h9eL3F^%J6Gg4q58m` zflkjc>&MWe?rdlT{ZieRgt|gf^H4O_T12D#wD3Sr!X96d?+2P^94~(NKC(ibT`IOl z==!Nm3Kgk*Hd6fRTW1mess}BqRE$t|q%~i&e;B02iEvM1oru6LzrF-j`w|@!ljgr^ zMUnb3fB6)E0PQy(1!oQVPGbCySubW&mH72o_A5u7Aa+d)#4{Fz`rUkNR5izZB|Yg6 zD@hxBqWN|w&JXfztEALF-^$#<*P%!Jx`+RUZ9e zy-&JjH~@wKLVBL5+L7#4ycR(&&3~X+B5aQp&l_%O<6qn+QSbJoYtQw1C(1OB!PsV# zlqY*ImWS*QLKIeNdW*v@8j!z@{|9INGA7bVmNNm~+|0wIB*rjaxqU-L5squQB-zI5 zIXxtqqZ$ArKTiHG;kWcl;vtR3iP1*I_sqt`iG|IUB(|$k7i#R$Eef;mTXW5I-C;S- ztxL;`jqLE(CMHFz#(lczx@02kX=L`3)Bu2Qpxab3(vXE77;15NI?3|&f9NG#xf{TL zEFo=ibuxI9len$FvU@FR51yD{hk4n}u= z${UY{9vmK&5z+!h_C9^&tw6ck8U~Y|plpVo-SmP_YrKXrjlVM@QdlMZ$&9W9VE%vZgcOC6+fqTxjr<-oLbe2rTtEL_&LcdqPa%dLJ#S43^DZy!VTVn0Y z@t!sbGHsh5k1lA?j<eVLq*Kz5RRj+LYWDcVoM-*r*3cnz|- zDrzmva{Z}(9QQwTP$U@xyZ}$RGrx8=LuL>eu;t_a$@vd~Cr{bqF)Lrm5bN-QbK=(v z$~9kq+Zv8XoNpWX?%I7Eu43GEc#6&9upp+h%*Urb$o}0@M}mSn&zJ|_FJzqUc4JgL ze`W_XyV%X0y?C6P_&NQFAowjpN98b^J&_Ccu8Z5Slu=w)6vSwg;O~TXEVlXFQxr_+ zxZ?=G`_nW0k_dCS6-&9kDyh-dp%gx>&ds>*cZ#*s0Cb#g$8pAuHm#?KX`LCkPzuYy z5UXU}UTwu9Q#KrhLeYmL{tJPvH%xTjjuHfRfZ&t+U;oX$-tgfM{w-fUQX3d-s1Dlx zIDPuGKS(_RW2@xY7d4EMOJu->x+YLQ;)8BRZtTL-OMQD=vqr&Gufwk7xH$US z_}EwtRan|>LfLRT`9(3gDH}pAXd*OQ;lt$PZCW$p*`k$;s>8z^#+#s=UXSlv0W>f< zjtC@<(r=FU9*LMzW6rJ4z-7s_x86`gJHa+G0IMYPMRVw#WbGg1QB2?dB;A+_dm^jp zVq~aaI&<(GN^=oFS$VP;$i+n}Ht$-{0EIYVp+^-JQKgc;;^F?l{6vm`0Ou3ju}(DB zUYII5Ex!&yq!c*sKQrfZq6^4yzYOCxKG?K(ErIFG)*R)0s16`2EVBVQqndY{x=L+a zr{mbvm!K@ipBrq$mJa^zzF~g}D2dRQ|LwJ4kUSc6XKr(W2pj_8;Rbz}TOhX&rb4&h zo&yKXNBsVv8EIce34OQ+q$D<^Jl7FZBNGmkY6HUfr)>{abGjxImqwGCz>SbmtN>o1 z2@R8zwSgQx57!{(JwaDQa6IuS0aAZ3arsusoR@Q`8YN>9>1?uK{?aRBtq|7Yz*H2e z;owAnYvHPIvJ{aX^T?Jf6o6j?Zj}gOG0CRyKmR;y>_JUXeo!eC#M50zoc!w8U#j&+ ze5PvaP!hXXFhMzt`PJ_7_3 z?mTFn%G*|^LtjLsu7ggQ76;dYJZjLe3WpL!54-7)A2FDh?ni6DN^|o70_oXFuztN012!JsxGQJ9 znNe#_O(+(e|HYp6Lgy)|!-;r~2KmZ}HoHS&Vj?>ag>ZGMGT!gCk(u$#qDvFVa=UWi z-R??OLwX`-7VYi(w?JJXINQVLn4B;fL0MV2z7l}l4eV78Lgv@0x*a<&Mjic4|MA;A zs6a!)Wn9)Mow$4;xo_nu2R1M^{*~js+;Sj#&qHbQV$(}X5vm%`BI~UeDl8*o3ovuUZThoIx5QS#CG#e_ZeS*f&G?Z}ztB;!T ze$*h;aVjv0*G5ApwYuk@WqS(p3kHNkAW?1Y)3X6mscN@1&YUJ&G9JK{81N5vyny~~ z$$xCT+ak+f8#5WTS`Ii;mp)$&!%p~U86J9Y44;H-lJR__w%uyEH~vaWmSU6hOzDAW zFxa*%k`)3)=&+#uIC)cL*{kQCk|fVfV5kBlV2m}CFiNa`L+jSet(Z~!!b-GpHN)&< zsRdC^<@M-0{>I8)>LXYw=4iblVq$%_g5NI@09h#soB)czbMzNnh+_V#TJN5xNN;|O zdgGI&yu}png8G5io-FOf2iegHoJ+#;a?(d(sKAP)bms1}_Aj0+AbCs6M`0m+IJ1E@ z1ItT93nFO~!NR4>W^=m-_qo(*AAGA2e`T~F-TMY+MCCu@e6ymWcJiDTA?hWlC7(VL zgaaENABT0g$`SBrY~;9(I0bVK|9$kwUfh$Z_#ug0!qu*$E?)cv5${M?D?WL|DxA!u zThPGDD4vAuw6Jsbnt$JjY?*MNiRZU4lIHBSdC^qLB*}`7m|#3^K*`x_l^){5dwWjf zmgL4**kchvWTs9pGk>RqjyS4NrKb19L!C!aMwgszi%W7OG%{LTx?jaKSX_k<|YkJ<&x7M_)vj!{h6Iy+O0)wVTd`30zcB7pJtQxLtewU>H(GCWeAWIO~6o$qwdwXyz9ZW`lzBkwrzHF+Jkp<{WQw!v=g;^bB9Fc^47|rn!%V= z2UgO&>29?x^l5gK`k0dW3G4gKF0DVf^ZQoz3B^$}7*E{}E74N-@;w0+X~`77k~{W- zF_jYbF1xJRp7A&aF18?t%Vz1;sv~8DlFLE|o7DQ{_Jz*1o@3(mzBP4(WSwpB)_p+&BfUy8QiDSOK)`P?3>d%-}X^XrHMluB-_hyu&@9$P^<^9;@qeG*a z6YWH3)Uf%B)js%TCvENg#x}`3LGzYwJ#Q>#kQ{2ZP(1pbFbPpu*eaI8mf8IbxdKrm ztK1jVI$iivgw$L|MAjt1|D})<@KAzi%=BLd5djQ1H8nL24b58!5Vk?UgK>d$@+KGr z15uMVota`C^;#*=h|mxHRZ8RNu-Y#(cysg1j5ug&#Y9ybZa!MFY;+K*pP|ZY;zf7l zDwg#EvAYOQaTw!!;UsyNR!pgEMk#YE$cOBWm=66&0okm58Wj(A^eV${_{JBpO%NS< zgRrz$-Ov0tU5clZ>UX;3L)~M-G0SXY{#-i5@oLpe{Jt8~UpbRwt-a`+CbmyYj7Ndg zpezyB!|tg4nnuqwmriAhhs_baH7}OO*Z^i&#GPgVQi1 z*KrYt^{U~b?F;4yM%QeKNUPj~N|XVenxv8#cXCDr_ z@`GFsD-MjxGcYB%%*JHnm=_QV}N$}jUsX4hE;^w zLA=oFoL40Dsd3-m{{1Z{rmCcW&QF458#YdjxAD()?36Lk-9&?iJ`SQvITPss?DeGf^8~d(bP6R=(cw`{{Vy#%H`9xNz<#w`vO>6XhP<{O-L8C zxS9FxBBnlle%W|A|FY?B#mZ=>esE{ynsw#e`%dG(bi%b~0=$L5{3lq61ei*5XnYE2 z0|zws{Kx-~1(@^@r+ukz#i3-$)+-khOWc4u7kyKdVZr0%jBi zKJIRu0c^$vJ>a-oYT5V7d2hK5+o8+Bladb*Fo;wL(+f}%_~Y{mMN3w8 z#&%9XCOwuy1v;wd$F^y;v|-K*Ts&NbDeJ>XBa&EBX@B?xS2foI1(l{(J)QW9dd;U$ zac}AP<}>X>pCNk?3w+Bg4KUh$dUxV~CsdET*A&D~Q#8Efyh8rTNog^`*AksQ)irfa{TRv9Vwo$N__z>dz^le2jajvZyNrY@z(jEe4U|5DHbh-PV<5FT@8;lk~UaRdUxB1~^@Ytj*(+R{Q+%%Lt!ifoK z?GK3+2wOvQxIXswxF%5wF^mZjEj=VPV;5#FcWo0|U0$N4+g&bRaZO_Gfrj@}0HjKt zlS3oZwJ{zHqGc1HhHF9a4D(U?;n2h4?;C>i+v~G<5NBFgiT=E$b6|p+{ey)VfQMED zy`d z$H!*u=MMv5U}21VDW9r5MYy7cA`MIOfKn)fxu<6Wr`|Nb>PuHGSTBp3HO7qR2r{cTf-^ep_8@^<>B-D&($=fv4LPh3#+p zRQoGN@jxCJayU6#7>pvrb;#=Km)VpM_V0DouhZhCITnUFWWlOs>Mey)BVvqu8oh26 zpL%1x+QM=iKO!E*-*Srsn+aN08g3WPn&#$P6@o{f#1Mb-L4@eyRR0(Z50w#%g3r#T z4&2_-r54w6Nxd-_#|+i(ePoVfK~iUEV(aM~!AVVOh>Odr{N)*It-X+ukC>L-x~QU2 zU~;JG0?U)$SLj$9(N|5x@iF=p{h}K0Y)q11ekTz;cPDr1;3vSj$^d4e6&CWgV^86y z?)$OB@8mQY`>^h#X4k}?B*NKroB1j!*4Eb1`3iC zkP+oCoe3HhB=quF9vt7QP2wkE-PVV~?G-~7YYjQ6l;pN$5&`3xQL!})F| zcu@+LK@@I_{g+~@ug_mG3b5WhAMp;(ozpckX7WLb09GeWf$HF+tm|@_^9Ry5DHna8 z`~EHj#vGvpx4BsqzY=>Lf3T5eR-*It@F>sLEdFumL4f&5mOD22rnZj9hxvQ!hg;C2 z8|kbaY7#8;P}Aq27I{5SZ3sHxu@Oe!C_4Op_QQR)k7@+5e2m5IJ9iX+fmj7jWw3 zIGf6tXt}N(ZU{6cS5l_F8?P&L(?G`5%I>(AgaZTE;TC+YJaJm$y(f(G>R~$gza9sEmB3IpgXi&U%hOWtf)cyULtGqbkogo?=|2!Q^{5apR^{q9ANL0etSmI{%`X% z|0e!nU)2B+J~h$&o7JMJxZI%mG0pi<5Dn;6xsypul1{_ZY$Eg)qo(+& zc>{gReHdU(%?r?4p%RGQMu~{x;=>;k`0x1x5S@V47 z^W4NaoE`OL2#5M2R*i}=ZZ2Me)#yTi+j6Nlv$Zu_u&`?qA3`q|)`Rgujuc@3hzKCg z)a+O#Y(?DV@hDy<5y;BQ0@a@^wB_m-i$-yuIw5uddlv+n%S@sGhKfvodM-zh)1U$h z)+DK$>pE4i%B!Rd?=ZfHiR}ln1u!{e{f54uxVjGLYi98NrkcQev#uq_yGi}$Q!Q6M zU>48195WKpx}84Z3%Jg@eYJ4Wy6}KLP4aFW&D5h}$mu%u1F}|87IHv*vJtBNy8ia$ zhb?ez5B~5_2|G){0VTve04)M^MZyzSrIEQ2oETHHE%MECodr^Bp~iTy#uw!w<~-qe zR2A(3Qs&mwgY|KaZ!a_B)Y*rl9s`))inG^R#u!N%$|N?#8eXR=@8as(y|g5^*re0x zG+kG80?bY=+v+al)H#@Z(ig#k*EH{o4wim;fBQ0N?^>9n?X2^yvFMBUaRClUfhDGV zHRjwv!}{>eCVGY(o%$c71U1CDqeI6IGbBvXL}6su@*d1*6y5oKrEyIf6Q)r;p7}HZ z+o9|M^mm)lu(8RGyP;IE9bu6ntfhC#4cCfCTR7!cpSftH{cA2AoIn2M6@{;SaJcKA ze0$({%jUD2NtE>2>MoC0+!MFa>W&~`W^KKW)Xt>ANKU*u*_u7`0gRmTaxRSf`tTk%){Oi(@^@WW(|$J1;ad|YllG4vs^SKBK=cn9?|(K&P6AM( zcPka(jog6iKOni80LIEA!oniXVal1=w!j=HSg?#rd)d5OvR$yCmmhSu)5vsa@1SXn zdv_y>j}G^<)BLeNc611jkqAK#pKUo7?LR@21DP$QfR#DrgaMBo>?n11E09ODofo)&drSBrTX#=hnVcsL#|++MefjWGP9pHRL7pc?f>)nlAU+7DRT zgVf|P0ZVPC$Hfc2%MsAz$ECnnb$7D!s@@v2>@icb4f15TOlQQpCeen)lEN63!s(i~ zR!2BY;l-PL&}~K1p;uvs<$dzC^6dOq44pOF-=MjIJM*nw)60z;s!_r~s%6g& zhBZF9^z}T{!qfdv@e0`hZYN`%p}pN+t&Kc?y*1QJ@`r|DA696q}My6 ze0z@`WAH(x+?$+~ygca|HGpqex4Yv^w!P>@wIUH|fqFXO#&bCMbk_T+W46 ziMYwI3t2Vtd!`Xec74Okhh7)0XsRG}*5y~y%Rf=0z0dqsW&Fsfg^DC{*4=$38y~L? zXtaO%lhKv$-J+z<00K&FzmMzWYR3)}dJ{i%@y(mxZv*+%1%~L_546c-a9{{^!DH=w zQ6J^e$Zx)^;5fIfS14oC%d=2&UaLHS%C+(9*WQf1g{Mnr%0~;4?o(bS4D`nn(N5dK zOh9~tc)6G`?O4aK^y6UBnbQa3W!*rWG_u=rVC?L8+WU9b&Ci~)XO9-G;WPfp#)oba zw|0<|f54HcP#i#an+0A+@b<6Z{Kb8ejk9l!OMsC4HIQoE0)Ozh9SKOAQu$|^f^zl7 zL?OQxxV?}ILV|&#ZrSgpm~Hb**HwC1gcbA=dbji*t|mltkLe1-+#j7P@dg_$c1jdS zj!k+k*8&wQVw@ZsV6+!$=S9l>62@*b=rYyh5vNwfL%hv9Xf52x)hF!-tUqJTUuys46fB{x z`H__VaouW~*MdCF##Kb_40tNs~JV@_7${~e+D_rsRdZ3qb2H1(*vx8>@f@6HnTYMD{Y zOJ9NTA%JoLVh~_9>zTi^?CfMsyl?hn#kodLiG+ltLLZ%&`SUm_1`0^tev zsaT6Fh<>uJC!4gYO4H)$5vN?|@GwCpib^O`l9l`q2qs^oO;Dx0Jlso^tu=h>K;s;UT z(jIDHM=3afN&&3hcwZp$W1t6Mjq61Y;;_u$oX-DUjQ|V zLGJSYxYr}AdqO%rQlgnC0OPD^5&WE<$t)%?v7GUwwg^aHAq5y;B>g)x#>$xZ=Ii@IW_qF8mNG{d&b#df1MOP)jEwx~I#K4s({{rZ5-FW1! zSrriLM^1KrEm7{pahu+rnZc+RtnBBr?GyQ9HGBGTNl7mOqp^E~!Nn6GK$2BwYA4iL zN6D%H6anTWg~UFz+rxmzEeFFaThtcKQjZpOOf&Dex}Eaeo;C&u>hS;Wx}(pvt}o6%8Euwl%2nyHCyNNS>5Er7HuluzW2tXDOp+}y4#=k-cIv@-X#s}A9& z(zT5tAEKOvEAc7bQMQvzfqWC? z!>`N2jki3izT*NZZ=ytr`?$`1X#;KZ!fVB3DkrU z*(>TP5>CT%^m4~uKV^RapvB>Jw~9?U92-G5C%d=9zkTyp!X{o0sC7XBVBqk{e+HsNd^)ZWG)6;or*2Hu?lC z*_WLyZrVFicgjxHcJ=xdUjhfU3*0|1$Ywqi25YAF zO@HGmn(r)TYh#>J3C!dKJ@!52Xv0B7c3zi^9EO}+_DQc@RX$DcoBB<-?zAa4IFKDc;)BRhk-dFF`0T1v1ma%Z;#b8+NpvOJCH(F4rFIr&heS`QjS2AZS4Bi~YXST6@8>f3M2?bqZ)j0@VO?l*5ecAKe2RG#0jyqnHi0y0LZiqBzQ~wjY z8T9s!a*^V9$r`=pxlvRAP@P*YcbcVDZO+NM-OxHOzg-s- zskwK}X)t8|@3oU4l0It_yO!U;?xPjV^gGcBqWO4NxpuGuHn05v17Ypc4|IZnTu%6> z>#n;sZ<;Y%u4|P`w(}YGQhK<1K?~3mhiBay&~3WZbpM9SGCP|xXk%&%HKOP zjGf_kG(J+4Lcfge`G^uPkfj+5C7j-%a%kP)(NAn_i771=(r>;H{R{@&z($1Qy9j1P z^am^-TWv6n(XQxHWmUf3U=zwxfHM@oBqhiQOG%tCC>&SkKmMIr2x2>~UCDLtXk+^b z4=-emqEk}WoVH(L>V;6&3}+K{En>i#`;FN=PV0&$fMqE$X zJ~S?9vJ@nWonRV*H}c59V*k|U4zw2c%t@7UVx_~lzXZM^(xS)cOnAL{GUhkKQ4sC& zj8VA0xjlLHZ!%jyR_$&1MCJJKuG_j>Gx$R|lB|Xg3{}TyulK+S9kT8y zzucO8vc9uzw_7rI>hz8y-#&{XBZfX_#*6@Jdft^YqQwQ42BJS)f;V zS77n3(aHs!+M?4XEk0lFxr7;8q+jx+1L@_lCyA_|zp_LoajX5h=ZWd3HDNLTx&qxH zkI&B3SWLF6FBbV1nYAsJJkolJjAa*4=uAC{XaqH23>t^F z*1F(hWt;L(P$A84h}hr8IJ+%}P@ zua!LjBQ6|6K;cq7Qn?s#UZy+@I_c(57G+j>oYOqwCp#wos@V9nzGUov!*_Zu$zo#D z`Bb6gm)EsxWQvp{ie>QlS_`=SyYHnndL)sf-`+=;MJ?7jIjOuVsy@vfvq6HD7nkeS zG392nCuUZsYw;@iUZ>l!K?u|jL7JL^J*lm_u}s)s2BiwX|AhiZH63tFhBs;^b}|r zE*!6VAHYsI|7ln|C3bjokc*AI)7iU+jy zJSgS*b|d#*4i5Ia4(C+D3mP;*C@sL@q}#EZW2j~3gJBF=uafs#1RVHe*tJo;1TN ze?L_bEFOWXeSb?T7Nx4Y};1V|fWfjVn=sO1GYJs7UsMA+YaJ^wv?GQIK4Mr&tR^3dq4 z)(FXQ-QVuD#=3TQId6K(Z#E64wFiC=af?B5|&L6J)svO+a!N{MPQLHNjhGFhPpCG?2~ zD=m}C?jmM=#Jy=Uz~3U04X#qA`OvEL8}8yymkGCLxDV>;cZUphm~+}ORi`e2>~hGSfSPeOR=Ue>~>-{pj+#E?Q! zD<@Cd=e|f^_Ff#t`0l(o%GRrw*kJ1LcT->1d9nG)+AwxPXT(Zp_{w=7I>RHv1p0j7 z`ZnQuc%awJe55z~&WN#NF%hvv;h6f-zOqiXy75zhF`A6E{=^H6`!%@Me3?tvc%r7l z@}3u_>s=kG5r96OVE&8_V7|tYTI}|!Y4KE)vyg*_i2ce#u^8FcMv~bnzugwB2eH%r zz46CT0Jfgqt;+GN?o<*dSbbO=Ei|FPn$XkAcNm}Y(?a(sf1$yx>#SJNo=%q=cZUGk zEohWO?^Ahijq(~FKp`G{=E$$*+UGj(+ z>GTEsb^T*uJu}uIF~7513VXTvfhp}njuUAWQjKm`4LpviT`A!~qoj~^>FXM`k(^K# z`vlW;F{Jxss*G>Ye{i>XMs07NF1T=w@&#sT=yAo8PUX zJqv}cq-2GjoVrQlO+bOpd#{_I7oShL$cr~ot!5@weVpk5FP1fflpd=|$vV%MRr9LS zP4dTG&*xx))u_1K<0C!wzK3QLZiwlM>ehbwov87;V7UpF`#i7PCkonz*;a*OFy?kc zeSJlumnz0dl&x$nrPiX>6c#Pmq0FJ?=sol~4~X0nZA=>LR35@x=$h8l@pE5Us1Isb z+b4ueUjk-D@5NL=6A9o%{n*Ti!I6|iMU8QJ#3mH%zl2ei+&El2{?)qs1a_~qQy);q zGx+$U+~dZ^NO;Q)OL8?2pX7ezSywBEJs4X_Us&7!#e$`eIL`&RCGbzd`iR_KRpnDr zeZjT_==taNGeb)aN6NJ*e+~Wr>wp$t+ZCPl)B3Mk`iF^~1&f{iRlJb{!7{FAh(PE` z!|LvIW&Bz1oM0};n-kdSz31iEPJk)XV_QkTT4b1f*gA zkV7qmvVJYsjc?>+fGR<7472L>zOT~UJW#@pbJ#K7Q?p|~MuRqX$saO$?gqz^ogl5H z;EKYs%}LEUkIWP7pl(U$*GqNQFkI*00YWJMCg{* zIcE8{-!hlV00N%Si`v~kIH#ZM0zNjmsykX=hHlq;S=9Jm86RWJwI7Y4>*mr3e~UqW zoMZqJ&}08peRef|u6b6b()F_{zS*zm#Gv5E2M4}1dh5<44>8&`Hquxi)E*9{%w42J z^@bmwVq;Ej1}NrMw!hWMJRE@813gDFk5V*sy7FOmG?Nw6&$<_te5CGfi&U96-5brs zh^Ag!mrG`>AKGtMvLexEJ_{}*NE6PYr3V>XNqge8_54J|#YYaHVs(jRnZ~RrgoB7UfVlm9Ht*!ZdI~RA#w zieAklIA{Ua<=X>ou%NvkNWVQxo?Z6AAb-p4r8cAy8GCtUb+dcS-mp#|X@)baGf?PkvLhQaYFH^8;rUATs*tNiH?Ew!O!meli$}&^3$sGH12OM;YV(#$LjdFw87D zDXhnhJJ~h$1<%(7Z>y#HjEmFO#J^Vec66LO^L zTFb~yQc!4Ld57ug@o!$Wk?SOcE`AT!wk8%FGTAy)Fm@!jM3&x!9q#d}a%NzlY;EUQ z+rVD^(58nA&NWHY>G`_ZKdqy1u)b{$C3Zd~JYdfd^mQ(3Z3hU1@w_^#(MQ~MEgtRX z=~syI+l#olM+P!~AVN4i7PURqm95XACJMH>q zw{D+&b!_ct-Tnf@^5946ud>BiBvXJ>BV_!>q+b{dsG^NyI!@Dhw74M<>#s63XhpKs zQ}m#?#^&ZeUBiZ<4Ju8Jn-dA0WtbGi_Xq)Z^%2SwUXx?sk-q05Kp?rYVfP89kI3l5 zryR>=o^aA2L42wmSFL%|Smy+D8N^y_d>Ns2xvQS!l;x5b$L6e}Vp$*h2NxJMul>7w zWzb92^#Q?}bbol9SW_^BbuvE0z}e)~TXI};g0q(yI%dNggdkf(SR4J>kezsTl*5{1 z#*q2o&lw_w|3({Nf5D@Jt8z+bJhMyI+An$r53z2qfv|aU^!BIcdS0?85Fpp!g2J^<%Srt99s@|C6=vF*R|+f0)SGUz>~9Ojnh0W(iOsbW zik_4Cx4v#&cQRmP@#H%Fp57qeEVk9QMKD}iBvd_qS8bKl3LQyd;$kwlzF?jv%i*NO zmW*+p0uT45c&Wa-o10DU`Im;#_L1(KUNYsq*}^Co*K4TLfp|EU_a(9H0)|w4af=o2 zKM|7XMV2ugB)WJwsV+ONC#B#Q9^O20L>`PtbM!MjF);SwwkdiotOH*X9kb6A#2b~W(dH0-dxOj2Z=z`XVSd&@L9=GhbJ%-VZ_DuFJk%Z!@JR9Ds5u{I8Jq_K zt*WE`>GEa?bvNau;4I}WYRnpB@Jaw)2-+Lk54vf?rvwV~!@HYzO%`qjEwRr@q*YR{ z8K3MnjX{H();w1>1E^8i0&P@g&K{8RnY^8eXRd^NDx)lifD!dD-J}LG*+!`W+T|&n zKeLISS8r8Mkp!t8FnMHWKerf+S8kG!NUsz~sD5YJb(<}@S^)&zA1!~AD$|(49Sn!)H^W@ zSO_&5eulveHEV`6%cquoTMdEGiCC133Mon+o=>(z)?M1G%=GgSgK8+-!auX%;e>H>+0H2ac4qiB49$KT0Q~b4fJx{ z#KNYbWwxxTWRwigOj$BQEQW=pak1mov+Gw~>s5u*HnnGn zBr$mD3xJO^P@9}()b1aw$M5)&L5`~D6YBL$kGx%;G4;1emFMT*yuuHTd{-=|%zp7j zk)-usc~V-LL`OiUKII7{H&hhgKU!Q8z>WG7*h70M^>M<6Kr-jeaH6v1qdcBq@t9p9 zZHnqxBh zR9ZQ1S|UC{tbFs_)rRomgGrtVB!j3F$H&J92wvzF|K0nE4{F#ULkTkb992-XgV1?3 z+vN2i7pLFCtjv)}+IO!be9La(xm*HkP?rT4NFBe4byah2uqoq-2!2R3+=d7}Zz`V| zF=F=F)+*l%k*36Iz$)~rwfe@pBQu#8pLJ3;E^{zN^Za8Gg}%<}!wZQJtvm$ZE0U6$ znTB2yk9yhSmEd=yHdG#UJIZF7b`bOE3G4VjUcgt|oHC=U0IcAIsZ0`kxF~O~`5hpO zc0VqfUg}h*Hs##H?wY+gi}Ge*5*9C8Gqa34Sh(s$tv+0PQeF1nux2^`Uk%y8D&-~R zFznV9Vw4L0>l^;*^mef`m{yQI#^+MT)m25TZ~C&rEJX>@JFKJ zIAPIm$YSw61ZcngS)Lo;&xzwQv6^D8EP#3n^nQL^_rlxoUZ#}mRYW4pl)YaNH^4lr`rQP-j{l0b zgFvQ-x!#WelBl6N-I$81Fz2I)e&r02_m3zmNz(I=nsh$>(Cjk@V>^Ko+6`rka_Ct8k-;6==21oxL zls~lGZ`&3tfGdPGM-m7hp%J!I1a0dz>}3P8l%@)oX_+SEk(Ex*-7miW2+ox9Pn>XgXa1(rLuf9tHkEGLjZ%N&K{_$FhT!7B zID7ul4O^3gb^Ope)0J+sbIa-&MlMaX%$J^tcCU07OUdzx{C%p)-#}1n%3^weVS1MS zQz{c&WYkWEK=1V6t?)6>k?^8U=01v@$N5~{;N72gyhd~x9u)iwugsDrvm4}$tnZ!7 zI3m5Mtkc-HNW-2Vd;6KB1Gn_rSY{3#y7m!};#H)8BN6hD_tzLmr;Nx9c@uc{Mk=Sl zD=Kj!PACyeEYU*$Y+aX0oNg&}bF>opgxqd!Z>K3Gs4hA2p%iXe;!pQ>@aD~TcMM{< z-r=W3p6N$LGRZ1UeoGSq;HZe9CizrW^SwR)k;NcqH?w?E2Cqe8B0mXerH^W!0OR4ITK&_-wXkju0v}FKZ&^N^)8g9*l z%R3>odwhQEIJXjh9irMQZ3*tSYdz&mzAXC3xB}y}Cz_+}hZA^t&SL=(XD84{!@}>$ z0nh4uL4zQGPI=6>rgz&i%IOD~T>e{r{n#c=N5Q}9sy%&|`MHj9Y$m8-_g@2kcauOp z*;;?aL?joV?MkI&qF$5k<6cVp;&~L&CJQr^D@MjF-c>4h$^=9Yl#~`VL@86$+Z}i5 z*UH1J?zzqUf0`FAU2?!*Ms%1Xhh98S6o%$JwNuC`sg*w2=Q;I?$A_&~n1AsguvI0_ z1g62?$3MrNaJr0MTBway^0`PSOaIvzksi$VNg;+8i^$`HUf_F+ic0lw8`J(oVPy@Z z*aH4?RaL_sZgWd%)_G`s1IncERR5=(0=GbZ5=IbFsm!QNI#_w1&$y=d)FuXAZ&k~_ zwM*z z<+aw#=}-noW44fXKD9nu)R{KDjY`yQ(QiVLdMM!SIPmHiqGxMad$fK}$a>Hvr*ewC zmO)MpFyB)BZv6CZ@mOF=$Gv#^6vL14*&>nW-*qp7BgUXW@<<-uz3&k0s1U0XVBoI5 zbqz;x#4;;ppX<)_1N%jxzcA@U14O`~3uW8UZ^7dW^`PPBkqwPTI6V$E=mAO{U zzpXT>(fKc}Gt})>7HPTP!omcxeJPO83!u?S=m3!?_ru-ljvxpTk#vIDhWbR$Y%G`X zFkM@Xzt7RVR@RQLQ@e6r*=dfIMX;93zZI&4BWJ3k=eVrA_)sCM!L{A#{D8Qr)xHyg z@zR_JcWP!PZ*HI}x>ye0Cp|^mL|0Ew8pNZqs?GX(=GTby{_jK6BfejTuT=+UHeX{k z)cKaYj2=AvL|z??OVC%q^};;|*igHq4VtJ6^?zkAm1I@|Nte_JHIzvbNdsYtt?gx9 zl-g)9Y6Y_^sIKlTK!9o4kF*mtp1jkh&ON; zdau6#JQ4brj)7re%!Z9PcZA19MPOi2{~l1Y!xuS$VWctVuR`L2JW*m7xg^AX>=)1T zGo)YR1J*Al*KZx2G|EGmntD2DEv>C0Z6kChbBAcbK%7C8e#H{{U zXK0iX6DBD)|2N+f5I#2t4M*JikBen?D_c}OPopwncx}Hacy&Pi7h+r&Xq|w#OU@85 z6>`Ei{=H&(vgvlA_X#b96mcqJ2dDTZerEFrBvZvy3uY*)5&J@jC%s_J&F9ElasbAB z%`ZUuHI7=z6R85gBc8rz!yLB;ZD-X+!T`{Axp1TBy>RyU=MMWlnCtKQtDc1`Zw&*) z-`0;oPJ_PZeMU02{d$hAyc2Z*7Y_{mtEUbh5XYz7Ef5_{>lpsa_|UK7a{{9>HwZW7 zJv$3lQ9_O)gD~7$ivKN0FV=}NT=nTk`X{mZado`zyRJZ}r3vT+((-Z9=?C8YIsWwx zZWj%W5+TEI@g`Z#@Rr-IsVfPBE4^8tB)1Q0#q?x|__?|rlK6T$x7Q`J5|e^Np?HNHl|^&HWCca{Qs71{dSU;WYtyg`5| zp+?~Jm+jSx(Txx&fPq63thHV(-_Y7$x^NDY2+aJ$cnu#QX8Q+}9$rjbID8UiM zh-VD>v$V`!I|7$cL&P8I!8Xxbs8Gvy>Z()DH~_v($D&_oWzwj*RV;WptKmZHSy?XU zGlkhk6PBwsg7|#7jPuIR5{A?54Y+Wot&ilqM+HWFEAS z?BqI@!9u=2_0}~XSWDBQ1D(Fv;?lS5)^m(I`^gcL@3MRt0i4k{XwI*bpD~1+iMuv?Zm^1S8AxtOPx$blPVdIgn;Yks0hLo3L zs9g$?Fsni-Rxa;qA`*j_5b@<80=hzQ^gCnan(6yzT3HK}wi8Z1?wXuc|9nVkbM8)+xOJmF^3p`XUm@2Hgajyb@{10FVW079{@K zlpz#FM269oNN0;_#_BUi#X?D1p8xCwKeCNTIgaw;GHdeu|B9-$yIBZp}csNTUL=!74@fYd0b)G3nDny5(RCrFX`Au+f z zF-gcE1D3&1^|Hi~vd8acj{ zisgok>PF+R3HeQKz5rYjH`+`*d;rsgke_@epvrorM#%3-CSj_$XR$I<`~^SsC(1UT zLU91%pLiuyntf%%w{FNj8c;V&d`XR}(ES8gFSLH%-8dWlWQtyT=^*C2?K$BuX-pH! z9wVKKfrDT2F4~yk``s{@(WDx#tDMx}Oet)qp4-nn`y7V(FBgEqW;`acR>v+3@z{)K zIz>3sEWN{6yP=X2F8&4VzQrVO-UHbEXsaE367uMsooiL*T;p!lpGvX?Vq8n}M>o^& za_O(c0vc4?B6=R3Q{T+{k1tnO;mGDNmt7~SHr`>wA93+eUYiLM>Aw|b@X?`j0# zU3^(EDTmmt4~^|HluP&RI@TGTso=G)QuF@{)@L@jt`oqNEls|3a^Ky@&bSBvzZlH= zv5)X!qh+H%@ZwvfqA{4h z|1hRt$4Y@Htbsiyh{#T&cq~M%+?mgH(IT^XyMh?qmCs=*n?31OO>{3igiuRURg{k! zfo4D?R2ct5aNQ`DJoU+=pSxKMO=lXMS|cY1BIBJirR#1l$I}PRV^VLdBnzs4t&bFF z>xo368uKW1Yq&>koDNr?mUeDw$g{QZCAe*Eh1uDSV&szZ4jONdF3#DFHZ(WKx+@!J z@J)za1Rh!@te+7LWPlEu9f23|Z0jH?;A~U)y1E?nZFjz(;tC#c%yAwaaBJUGKq~7Y z%>3V@$Y|)h-xC^&Nebi{1kqf9!G!>70~l-ewgR7cQ$d#b_N9?eHXz{2{Xs)ET*z<5 zM}D`<82&0JpO)YK(gF-3z`k#~U7@D3r@wZ3`B3~d-~fMI#kzE35WNr+fy7q@-5)y} z-S<=kNo(86jS$(I2^QOqZr*4p=D(C0T$Wb6Oq^y6I--v^jq1-BeZlLIdZ?RZSk!1H z#H9OOrbr8&M9MW0m7$5IfrW*o44RQwdUQB-5k2DdtvIdQPw^yE+DY-z+StHL%Yn?r zAFGddxp;zIhIMv$36X^r#gHtvg@CoAMCirQa*y_5R zl#Do zad3zzDcS8#b2|WVAFWe;a0Gz4@yuHRmKelklY~Rx`@{CO&{u1VLrV7tkL$Ah_UxW3 z6LwBIyS_6SNi?jF=E8Mr4?{|TngMBwKOJj`oNY%wv-ndYX>8yxU*!k;UGT85lnUTC zZJdR!fBFW}BPnJ4R>KZz^{SE98DhJ5hkDsQZZ7MZ*TqYuf|l?H>CLXp5pm5-`n04Z zQv#dal=meU;?)#gg23pJF428=f4|yPj3HcI3V;lgA>i{lS2pfXgM-|U6FD8(qKA0| zG(L_snmU?C{p`Knc{LlpbJeu2nBpHRng|FUx^1|XpK;#%?uNtpo`}lat>@q-i7nI1 zTO$?q`{(oaOGkjp=F68tMAxE4dNk91>yv~uBoagX&;8tyjtFDL@&>RqYYW%3d;lbS zxcJ3v$!ei96dmxZ)@XQpH_W9nLBW1YL>@b{CSVXZRort;ZLuDEFqzf}9>KWYP)V~+ z79t{T7ieyKBcEIt&)%Epzqu8oihI(<6utRIJ%@974S~!Mb^{H%z1&%i!Z5ffX4>b+ zf3FZ18tj$Nv?w+CPUHR9aPjcuaF&{Ss2rd%;DG9+OS=+18&;q#Ea<^JY&@u)j=yev znu}UZ`L&a92JJ*_y~kav<&DEaO$fNGvfA3p?%5dPSAH@e%;MCQw8nEnD8f>8ZR2@* zPW=G>h$%z8z5D7Fp}5#W?|?)1Dml|!2bb6LpT5S;D^DNd_ts2J@6)vYMD%~%h?*zT zs@X%L-u7T9Bm!kgc>RA)?0?#vFL2+MirOMRklvfZd0!DKc!@9u#eLvxKc!2kvQnKY}Yq|G#G^we)05+ zKlTM#Sc+ph*>g<-m0lflDVtvDt_B$z*e8Pq%ss0X_@mITld(Et83T=l7}G0W^wgGu30pT*$Ix|tkPO|-cqp8n%3{~Y zdOxWz5gwzBbuAu|%eI}Qyc)(1Yg6Tqk&NZWDf27b`;9BhpT8RF{wl|({^v?u|JC%P z#pj1|joFr7YX8l+R_q2%QUxQ6rS3=Sk2UYoCzO4E+gm;DoHyqFq%jeotXHz4mij@}G$`@W558Ara0xo?jYHoa60! z#2{=TUB(p%nj-|Jk1X&Vp#ZP_aOP^t@wQs>|9eb8S0WwOwfF^#cmR0K_x;+JMZd-8 z>*Rk$g7K;p0S_!1i=ulC$ioGEPOza!=c_e*z$Go^n3Qw}rFI}K5FaeR>qR2%q4+c8PgIKU8f<2x zB(zeuKLu9)Ax*~heU2;XWN-dC`7czznUY25S`>y7!$aFr)t5fLtEsO-A9!{dxq9jh%^x|!vB+_Ax|biW)@-QG*{si!;)9Y*P9~f)7)$&;^wLa+IrPEF8=XP z~jur-Bdkpbbw@a?B`o{v54GQ(2CTF_T;o>BVbT4U zc+n4x|7bgU5n&}87ykH^5YU~F0|O5Rtj*?C{D4m_e2O0O6|K~RBhCuGOZflxb5r|v~WV}d@uLj!rbDIFgEV0 zI7fz-eH`FU;U!`-i@$K zK-*i90gi-F#(}Y)#r8HB#v&Qx%=DfBehsDO!t&r+YwJ-h9Rn}SK|DxIFyE70nx12Q z-BLl-LX6z(jp)pu=IqqPZ%N7z8AI=te#<%Tt}l^C=A-A+p3veq#iQ&L9x$dI#SoIY zS1jXGj+-W_kRTv#WsZ$0rst}t0n5@?_)XQri;b28s^yL!R|GjYq_hqCmW88dX9L}a zzD4IjO)D+A)E5O zZGNDsbuqz5ARJ^|Pw%7xpq(+`9P8VAsBZ>ukq?@ICuvy!|6n((%zzs&hqXprn`6SXrNw7JKaltpi2?+6Ep-Hc!?UwSo!gZ zE>L~>^{!S#gYiAc}LkD%BS{YqepM3`Q z-DeKoZ0d$|R{)8-!N}gTHuZ?F$4zl}gZ|ea=Eeuvt5R#``{W7QadKHbOS~^oHKiDn zE9XhIBWXcnua`TC?G^63?(_7MS52tmBTU$`1>Z)k6-Eq^#30DbIH4x?V=KQ?qd{}C z-EMQHuRlEy>GQ)FlJC*pMEOLap_AnvM&Q~7s~R>qIWtoxL@rA&cIqU2fO+j6T;n`8 z6NEjkoo)#nFJ!4OfLwxXnzA;BS z;_o>6p_Zdzg%%*P1JAq+33^D{{yGf|JnB~)RN8+nPp|b6K%`_RVT>j{Bx=($ z22M8&`PG9(sv|HjQ^bni@XiI?gsUs?)%{1d*nP?`wY^-A^Qu^vy<4GNVa8znE1Yl7 z09P4&C?h<|*ZSA+!Is9z!*%Pgvdl|nrp}qfU)VxvgwAbyv0;>{AjNv|+Sm50IWCkM zSUt7+^qH8zj|;`{+gN5+&ID@#rxN?RQ94m3v%u&zTHVIwZOmIR6G87MV4x~1 ze)d>WpV5Oe_c@0?Fj_}*Rfjq8(s`Dqzud@-`;z8uja828vB*bGMaR;8oTs`T7* z!udu!R#`7MsgpZjGa3Ub`Y6wq_Kv+|`m~6*iS-gaQ?y=LD5R65>es`%c zJK~-%&YbxF*m}#bDA)FTSR|#pLqVlW>23s+Qo2MyI!3yYZnmV-%t#0f-6=T=!Z38# z5QB6#{BQQNANTWnkM}tE!beW->$=W!t#z*TgldBIxz42yE@kT6=!Rf&+r8rKSNXyn zCz@Niny6XKZR##N>$s6Z_3G)3WT7HLijGg*$9(sXmg^i=R&F?-sz}D}2hoBAI^Bmi zYIUOxUsbwWe{KeUxgp;S_Lo`@+Tn95q7gB_ zDf;SXH3Kn(#nGCEjKauJ9)6PC>ejVt?!H(ah79|9=a6$-0F2ckmuAC2)#{{GTT8({ zv1E9e3Wg&eV!MsId*j0%2U~DFd(JAOhjA{!IgMZ`?ZW`U-L*V4jrpL0fP7}+s>Q|p z1TL$BRHhKCk+To0Wn_(KQv4SB_N%Sn^N4zgys`BU5j$i`i)Cp zEDhC3CVO*uVhQsXglI8=E{?=lH3G^=yYk#J8*_JA!!62)^E3p5Ax$^u{^BE@VWIkC z7@I4m2mDDgB+BAIEH&ToV?+hGP2-)08)I|gGU()}vXn4#pbd?xhjCj8Lnc`u`eU0j z>SV@?$8X)&v(f8m!KYj6)1#)P3}?XH{`0yP=X`a|#TaMyg7uI@0)7PlZ zX_BPd9wHz1crxUrRQx6%EmlKzMiipgijR6_XYt#2l^vJt&n{}=DDYYCJCKC(H~W+N ztPSDk>oq6YS+1m1j$iIe?uPQfLW@jlym65={Jj-T7XsFBH&kgdhO1=f^o1We%>0gn zlO)Nbs;PV#nk}KuBKDA~N{7I)dE{E3Z#qx6dbW-1o!c8@Vx7pL^m&=Xqn;$it#oZ% zD7P#z5HM5ud84N)S0~!+aD&K1se^LPsk_HjWhr`RN3hXP9+wK223S5yh`u{%9shIE z#`Mfqk0;D-71rXBTU6>m?g~z4VHAx!!YQkwv8e_Qbd~`Exe&>+^UK&YfQ%=LuBEJB z<3}A=`w&AybqiHcvHPVkb>4!JQrCk>S$j;5d(Q-$7V5ni8_Hrf8!@c-4aM;zLR5+{ zIjHi?D?b~ObG~^!)x<1Fg^5#$i5G)hmC9#TZ0-E1q4mq963?e8UYlRe(dA|Ee)ihR z&)1n^?xYhlK}T5|PK4}$F;;46{jV0hi??V#9p^71lV}ZXHKn?8W7aL-wd+Pdeg&e> znQQi?mW*2cF+RD;IhZ3YJ6Ez}FM-uwfFcr%3r|uk;G0WYSNd8*oxrVE?l@8!MsEP0 zj(2|Cvd<0t?cdV^&UX*4c(3A=2Z0lY-1+x}?GLN*?gJ?r0q+hIU>1hZaczD>psK-p zcifR5AQq~9dxsVLaDMlj4p;=c9vbJuNx%hky|qifFZF;-(9+L@c7g-Agd9EF*-Kjm z^35Bhit?S6J)q}kRTFW05-t){fXie!iv+yKd6a(|0J10vE#5}ih+W$YaW+LR7FpUC zMOS+tSk@6Q9hDXjPw=?Nu3N*OCsF{5^A;{Oc_WpX;=Z2-f3F|L6I3+6-PL7nAVM?z z#-(myPIt;9qmclc90j{ExD<(!=sxkT`T2Fx^4G&4fd|nql1$Bj^GYJN?Xw||)+2(k z&~M7B63x$8mSi%~xk?~FD<#{|ncLhylcp@;`>4B|eL603#{>xY`uWm$2$o~OH9vS@ z;0heRhUPzqPv+lI_o5r_{-1LONKEgz$vaHo;(sxLSj4DtLaub~lwBo4q;nEaQavrDXx_;issfFbbcjdy*8f&#Bya}5vStGU$V!R>=RAoy`ZfJH(&_8eoTq<`pf?fX@7NM%p? zD_lj68ucia7&F%xN%eW7SCPB*4?1amJ*D6Az3{$p@M!n)lU#}euB8i=6;qR;+a=F{ z4C%}5z>_a`WfJ+HGTn{3v~j(xJPNS8`9$3C-}xkb96)+x8;G8gFqkJ(fQ{^-OLf(q zVXEvtEIm`Nx>UP55{bk3RX=XNmvb)9SoAi4;_y;I?6Z|2TFP|teDv>w_g;cJpQShe zUJr@2TrN~b4t+H;V8h3jGX}5SRf5JFzZWBvENaXFyVGiGc*V5A7oM*84&z^D!ZKrz z&fmT#vYW?j6$tJUH6}dz2x9C{@GTp}rCR30=PIKEAKKf;K8o*+?Pd3E<+oO6Fn5F+ za9K*!$po+e?h_@Cemt%8g)klxy(w~@{M}vli%u_uhbcf}@!M;Df`wtHwK7!3a&&-p z0~6KJ?(MbN`7gX7GDhovhqoVp=pZRy=%zkoK`Hhs8g zqOrL;0z{C(sf=^|i-Mtt#Bf5i`iu4{U2NAQ6^Zk}*52u4StfenytO94fr1zVa18Kg zRwC*Pe!26PZZ(MhIn9t}A9MD~i`U%G^s7{;4wFBKRh>mL+Xgd#G~CdptQlMuNnRWM zHex_ovq^cKLL0JeU1l@(gK(4OubtpI?q{im>+c(FT5`ABEJXTt_8U{TbYSsx4 zpamM9lTWGrzUQ=39OUz^l%aqLSDJmc9PdI43Hn#=^wGHGbEBIS!6RB3d+s|1$L}{i zIbuKH_Z=26%bL1H_XzPVe(W7Rsl-F47E z5&s$E7n<`o1<8qOc5$;+a~zG5!9!y^u_#P z!@8-`6PktVom0U21P#wsM z$hY^`YNOUDi?3*uF_u{54izYme$j8TICuYQ8-Y+_dEX<9riQq3ag#4LF-Fg`)hVET zCWs}|P9-rkSnf`=7UguewmVhHbn)CIG)UFqIde)dY*i!{A!9zueF%PKU|Uw*ygn@6 zph2E*+=|0l8{1zJ-hTZ>diQ%MRc2CCZu{Bg?%_n>*(Gl*-UT0T$)9l`e)alvVZAqw z&cWGPI_3Hf@xy@!TQQ4KQt%`Lr~Pw6EhSV?g&v}5>|p$~j43zyDes4q<-a`3k^wok zfuW)s{_5PrQ8)1ibw{AN`$%d(jf8Gg+;i>|&rAIbh6BlxkDFgM^a+X-)(t$(rlKlC zKy?zCGkLvXq}!pFhB`Dq4Kw;Mp@Pu&F`E+I1fl`d$MEDK9<)%$0>cfAhk=W6URdio1PM|hfkqWAIA5OE|Dc3w= zb$R1oTAQ5DkhRIIfzwI3^RUh0z{H&a=XZwN>F(jwz~{}h4|ZtAQ(K4Y3r0ro_B&&G zRg8z=zWkj@d(WEwyc_yJE`Yq$1qxEw1n26v5z1Kcma4v6LXh<$rKdtvTAAEITM=Jt zbjA<7WRt-Xe=57h+oPyD;S z#Oa)zUg#fyRHHnZq z(!{^{Md{n0!FD>)%W=R5hRo*Zzms57IK#j|eYt*bX-mY&DeQrU5rno1aj;$?*DJo~ z2mX;*K$9oET|4jW38Xvpq@t5dPk;KJ^Pb({{kJi_;>gq}aB?5zsJ)a*Tc_-$ni%$z za>Y({u1&qgLz!>H(9O^Qq3A`C>Pp=xL>)C}b_8Hq2cn&yuK$cAoD04hi858j zM0MC^z5gN?iie33JtQ!hQ~mfs%L+sF6GcGE1E}1^wK~w&2J=%o>JEuL1b9=EtfS`B z9oHep*OZj@{T=%nrE0R-N|{so9n|$c3EK)7xDT=yEUn8IZ%%mf^jtg~H5)3p!|=?o z)JyITT*jXRM|l8flz~izvy~)`?2EQT2_Sba`d!^2@!u~AEFnr9M#&?=1Gf0YN&B$% zC>~%g3Q6s`du@EMC1a5;PRI10d^Mvg8o^u{rNB@myyC5pI{l#W4M}KpK>NerV>lr= zFmtZQoISn094d*4`Rqxm)mbdR;=8S%k`+YQGaS+23?+S{@8Yrvle3Sby{a)RY4O=k zb7Ao06Y3>poZ2;4y5u?SFs7s8c_WyMwK~vv|A;JZiJHRAl1oM-wuD)Zyp9X;wENv& zCO-8n;=OC~IC;LjmQ9sc4sTnFe0I-d6@8|Kpy{B3050Y7W5CcL4o@h)iSz!#+hEt4 zQ>MKbUY0UbwjxZIfYwFcTUlcSFNdD=8Rf!FtMuFL;nn<$b_X6*SBt|R4ov??^KP43 z`$C{y7%mYI{aQ)F@Hg!WB6A3oy&X1kok@s6HOyY8GnKXTd-_q1<^xWrcI=K(yO$CT z^{=Wc`+iSRCgYljS>|_zr3A03su+mTA2mVXXOFcSu%@?#>YW4CEqY-5v@k)1>xQP+ zeIQ$*jK?6=Y^#^-P!ETwZ1Vb&I>;uy;!FG+amqXzs;8qVc+=Ef0Fct)wzT}#A$HjN zi5wG)4AER0(!F=FrS}D&kagZ9-O7sus})vW84bd$=jx4Yba}P;3%n&<4)n>}1i1Jd zHL5>cvB|HtMgn_1@k+T1jn|XX?w4AT=O-4@n4^}km)O>Q^&2$51&^y{1&|IqE`Y@& zQTpGk-A*=V8(7OwRB_IM>j_@h!czLhyZu|iQos6F{tO6V#_a(Ni(eif?q#p%)n?Nn zJ{7P70l%v{fPZrpQV}}=c$e*lO@Kh@#;bz6kBkb_%2s7LRBzCv=eg84dxfZgQAMNa zaucCuq7_Z93w_VdAW!SORJL`azkSZby?y@(KKvh5eulB?+QS0kzr(X#1U1A9u)(PB zCX%hQ`$Ce$xe?4Y+R?(Mfg!rpqB~GLhsMR`pPHHsyB=UirXn369Ruyv4{1pbDUJ9* zhcKM9S)t6iHMR_76JwDWTLfEOgSyxUAN!fY7c&YV*-y&)Mp=hi0)4U91TZnNC#BBd zlq}*rY|^$@MS?;NK&R_#&9v}Sr2gq$Ve;^NzEBf-otq3rcz^i=E>{2^Gm+|vE0dA& zV7C99x4x0cyTyP`+x+P94^f27zXP)R^>`}hT9w;7MEre5)qMjn=7IlrN&2sMqSD}}HX zpN~EiH)i+KKnj(C0ypv68d44~R+FotnSVC}jqTkZ@!-+s{Bi(d1MmMAtO;wmy}6ui z0EKLCZ(Fw}hlSz&t#f7V0EOWJCriKJZ~C+_WjM7VUY^oA(?mLA;Yg)Av?kKP%)SCq zr0@%@sj$!8w4Imak!xrevum{D_Y}@KBQ|F(1KU@QIa4_^{BN#qO~lt0!>oH$qDeY8TxFTo ztU!O{`*Qz%{HkKCkyXGS~yp z(W6ja+0;$B@IZ^Y=2O1Hsk;{7U(^QA8`v5?J3}Vq96t-<0JGo(SCaiEwlV-GcY@Yt z2|0l!SmK85X5hxDq;%wsMg0hFy1Q^vC(2uuG9LqBOS*LSr8!0{(HBQP*q;qUN~}3x zRpUH{t4D-BlU>5f27F@Ho~%Ibw|VRneE9<|)&cTtYn))Q>j2Nb2PTb9*m8$M9;M-7 z2fe`p=&UseS{Ud&Uzi8sQ1)7ompG3V1I5C8MEb5=Tjqw{t6j)xL~s#UoPWy;$th%) z(Wuo4!{bzT)qH^H!_ENzC>)euw6A0OYLj9f@dyDq>^Ym&*b?s7t}-SGb*I;p6=gsy zH9nc|Gum>#O@?kK-fq+;rtm>V%3P5Eckah1@(u4|_hzg43h8-!G}@F)bolHK0%*?T z+oXCo{Ro5c>sRu3=1fM9wefBXmQk4m~_y7q8Lt zl*hSs|7k%%ln=Xajx@}yP-Po(Cm1-d? z{;17B*z_~EZBD_j>&GL8k=->2lGmbjJrW($=|L9ow($;k% zv4A-Y$oX+GR)A4i0Zd(bRzmBi(9DMNeHR*yKg_(osPjD9K}SMg>QE%L3W zXzhMe!I%?Tp|x0^yYoyqNhv`R2XMmV6|R`6d3Ajgf({^v=LjOz27D|$y&^}xI+YUQ z)HapCT`ZJ>qV#(@cy&P5V4;Yi^KzVl+=MYQ25Lnceurs#@+9I?RE!U7B>A5zHk?4`ywG07-A zPv_Vd$e~nr&((JvvpqGMZS{?5N&~sO{zY*uV~o%UNovT=r(XK$4dkQxc;xJk0sZd| z>-L`>u<`%C>?|wZ>eS)nJr4hnqX{|x&iO?RKC2XcRo#aY#uHZlj#=M{ipK2xE~@Fa zwrUKfY!WA_?Ok>0+=Z~pY+w!4RvR_V%EmQG2uedMHzI-K@Q}?0j5dvSv&F{r3f(U1 z2-9+9106mE&baaSj}^?CyrQ044?>dVz6GYHMZe9 zA&nkvURi1oM__KCsNtJMS`!2Pi| zHPzAS%}PQK<~8x1FM9Mr_Lo1y+1kNU1k(XRnMrcf>KCvH3nZp{XT$$Pjb>xO6x|#Q zPCxx^c-XR)IU^!(O6gS=fk;1GAB2#5W%p0iJ0D61T)h_3<9%z7Ijz5Q%24J=Emu#< zVKTwme-a6nUFv+mdSLmhikrnpGVP(JNW2OUXCM2syW*f+?{O zdk$7{)x5FA#2{@9C-pZD6|Kjv2fy|PODY?{IS-eE1DaZj%4{0-bnfCILaEX@4naz~ z$RM`p>}5L)SrP8hohv`{%eVs+Q+QHK?deqKiBbDad#2Z`;63n=p{@1`rV?GUc4?h% zrG6i2-Oikq=dD!0;sMdZEq{|4WI{s(<#GNq^*QOIknhTyu59_7Bp-r5h1+sl86X0njTO1GpB7bNz#XfU+ag2cyi zt2QFwJt2MFE1U}X#K80blUvVwDD}`wh!IM?W@Q#{dW~ThNVLwR%(FhONAla i3Y zxyT9^$DkSJrF5K1#&R_HZIBuW#ZP{2WE6L*uCqMta9pnO$>|4wPo*@{1u@|E9QRAn ztp|QFb7PF#juMIFLcCt6LoGnqdvZt`y8U9wKx6tR6;*gJB@2FUa+76E4afZQE!h8D;K05sxiA?|pPO%CWVL(f+t2;2s2>I~^@ZGK_(4Wrta|_7r3)MAGA(2E` z?}Um-pV7UMR(yiF`rb9_+}gpcLdXj8MRW+ZBi~4kE`8I%4J;ERt3}}7rj@k#Lj~(X zmAWi^3!_ogO<-u22p$BF&@P!EJD(l;J_zXr!6Su45|U?^;OGfWH3nwDot3XP>l6DZ zT3O0au#WonL*+-0q$AroN%{c_3xoZEg{Q zeccS>@_6QUp>w}=tom#D)wDeH6>+w;u2IQjTh;7!0ljp6`;B9t*@k_*=`5jp@md0U z=u($k&)={(BrC_O9;fvkB zc4IF#t}%|@uVMta$eeD@og>$`PpLopsfK2+2bmJD?#JDplb#%_UE%PRw+p#&%V&Of zf>liLOiJA1w%SzfEuOVnF1j&__mrHTl<+!}Sm~f`=CMp0#y}|t!UzWP^#W5eDW%Wv z-yq9@%p$GEi;ns;v)le#+0Cn~<>n-yia+4-b`DoqoU?Pc{yE{sHEjUf8ENP0@NcfOY08Wu@8d<{a}`82vTHrYI?bvS32i6 z)miw-JX)5=uiA;SL?Ezfq{U;L)vZ{J_~Y(9!sg~n2Z_We6ffLW~sksrM4 zv?OQ9lV4o~)rj>Q-+R1=`W`m)9oOJXsv{huFTPwi(fqM2%>r*eXH-Ys7=uHmLiptu@^`5)BO*6FJCYWg#)7ms0Bua z;YH9i<)+CR4{2mm4g7&Zp97v0o*So^emCdqFwX!WKra;7RMd+F@=So%^+C3qf->bO z{}R?sR*qDiAYNy6LCup19<%(J?W$>qPmdqmoyf}bi)B(+9%E5p=<3o5I^5tJrY#cxO$ zLP~8G!X9&~Acc%hEpE2OC2y{D$$Uu3E4coP>gjWYqjUV{(Y0N;I{3-+@_YXWv9yKE zsrPfVY0YME246+*s~;vAQ{z(&KmHj7i2qq<{`~WJa|~+C8%-?PeOPSt-1^hHXxV0b z6*^$6%ZU9HPT2&mFYQ-MSt^;L>eG#O%j0Zn_sI6C53zNYJTSyu^3I#m2Y$?bts^q( z+n)}+H!I~=N?OM}-Q79tE7ALr85#0s|Dr%+QCF0pZFkX^&>QjO_d4VU_S-%c@!7S@ zislT`aI{{nhTd3>zgBExhBmZTh zlcX$QkNf7>`PvzHq~pCm{lU5TlBl#I2M_5jD5-Mpo(QcUhsHdXILdq=?CtQc$77BD zl!|T`1_`MrXB_%`cm9QGv8{trx65?S`%`H-BQfvs9?N%rw+bu|0m%vRX69E&4m~P& zilwlgI36mtv@R6KrN};@E{XbO{{3@ifLUc7us;%qc>hq}&@b>W=~yD_=$7xF{T_w&x~*4nhQnyuW}|3-l~6i!qkHCZG*? zZ=b(MFRw*gGd$bqnhV=hT zuZJqn%9%Qm_@g8=zYBnt5_Xz>>+5@Iz`LqoX`n=mq5Oe40+`76*pjVO(hCkQS?D_) z7yQ2h3JV(}pmeWcdi73;t5f?76c}w?1H3yQZmtw()89!C8aR$l+9d1SV*Y zu5snnDx6l0adN{P6)bfdHw7Y!uw9s2<_$RYR0s+PKl2Reo1eM$ct3Lppv>X`PY9^r zcp18I;=L8L6tdSfK#HCHK(-C=3q71yiZ#>J&NHB`;u>4g(frcLH;3CHaBsT(vH$9X zdJB)N7tNkugwnv$<-#S?3N}w`K*H`dGmX`~nPJkiXuNf^)n7{Am%)LQMuvUE!{U=` zC)+|=1#K# zYpFskHgqCSYZsH%p;m~>uJDQ&U9lQ^nIc48xk4|LftVsPN+u>?lmgx)x7UoDbD9mjiY@2QKg5DNJ zINyvrA8xjv=h$ZDFwqG9T)3X{yleaB$xKr!@U5k8muBlUCdzo}FEg%r*XrhckY4Yr*NvtA%e=sP%>#{rFN;ODAkV4E5zBJnzcBfVCdQFb0k{DTSD$@Ckgu(yseGG}m z=8IMSfdI7gb83KKxwOj=GWg|Vo=)CS@7o$H>%!+iGv!({n~RhwpMbfd`z=6kO!QJR z#tmaER5b--g}#34k{r`SBk6hBk zGal+M+YlkS)I5)mOEvee#cGmGHxL@v^FFMl73swzwL2C(@jONNj9-3> zZz(ZIA9fh!GfemZ7DTq7Qj~tQ3XMi%OW1VzmY<%LXr!xU2Bl^EFC~3?3yD^tc3G$Mm-eh3I;u~0Gw&X3Ar`cy(VmS|2pC?vt2(*@vB)JJj z^^!-lGL2qh<`!e-?#TNCN;39Vn9=h^#9wvOx%yq)RleDO1$ojV_}L6`AZNRX*}58X zMOosyq2w`4T*>&GdpO2jb90H}L>Hq~{=co|oMy8Eh3EPQRjTfW`op*f!r7ap|F!k_ z{1b5ggu$2suS(PQU*Ma-tqcYon3TL;?29ga{c4+XXq5T{MBl&ri7)Ku^W|eT*BL6n za8RFJJD~2_Z7S+!+WYq$VL|Khi%s%SDnQIsb1JrVYEfp|ENAG!=agl?X;C{u9kOnF z;xY65NGnV`cdLfl@nvs-IAjdhg#jB%V8{t%c#1tx4GTi^Bi}$IM~4OPkn*4++?ALp zgOfD!gh-Z<*)e3uT`*c;fqys8hu zI#QpoJ_oSF_EXkCE*{kS=k>Y&>Aq+}ZSJ&_7>4%I;LlCpKNWlv*$N{8rX~7+q&fV@ zL#sDgLYxCnp|w~u*PoByXB|(UEv)jDzFvEPjZN~l(gT&r&|ss*LgItcQBNYz|2-=A z{LG0DCqOegK)T1BZcJ!37nK)jt|ftuyhbD14VEg~c4>DY3XX~-98pk|_G$rg3j?YF z`NUDl>{RqMw!csPsX@X=QzFF&8Qi6{fZblILUIGWTQdM&P*(i@(eifVbb6Go#7il! zmbTlCEt#PSEa)p~gCd-3O~fnLck)~16*)`81If0xNWlMaq9UC$&h4*C#+H*bq`b$~ zytzj0YQq3t^gV?-un4W3dE%WNL(Ls40`SQFO$qdfM}UUA1{~L`>2m22F;Qlc&qs1f zng-Zc=ZVKV;n=&!?ulY?*+)A$AJ@SkW#bXc8I>@*Rd95qDJ%25 z+LR`3GTK6C*Sj9^OK>a9L|yA=j5r8k@3wbRzkaZ&x&(wW zw}^Pji7Hg2nX!Oz}jF6Q>KS z*fb*bW6HgJ>IN`Fl>o~TdGq!=F|b7{y6<9;MiK_E&5~$w^qNdw4WpvZQIko)RTtA= zDYz+(nYNa*)85|gWC3>=!)E*b$A(-DH2D9>dG>aiceP8#OmQF4K2%AxU=jO@%5)*E z8SmbAK-22BF^~NJ(-)9oek?q{*klkYcNi|ho=spj6{pjtYXYM|-8v5bTO&V zap%4*eU3F<(Zmy!CC0xXu(ZzzDc1AUex>9FL=P2)BA$RnQys-Y<{cHJxe=eAcIRaK zwO7|k6QcPnH*PkM!p9do6}Q%C95%VMoT=d7W`B+oO8Ej|=(!^skd!RRat3_rGa`vO z*yy0e4=vnS57hCc!(5|U`OG7@+HX^|re022mGK&f-B#l;ymFxRZM*gjtVq5`06ZWx zUZ#K0V3$w;Bp=y5J-<4H=NxM@a>n3NsVYRcXcMk0Xe6#T8qX5n!>Mb}4cve>ZUeW2 z@lL=1(Zs@M@w-NNBo>5U{Hw9G8OEu{^H!x}zp-xcg}F!UlW1e1aWW5&#El17=bd(P zoVp=-*F_2A1b$3@Fmyq-=)&mYG+G5W8+3BzL-2YOBEsAF{!wmD6$ykMb@bFrM*&+? zvbbXU<|`(u>pG3bLUt;+#-%toDL!vucZudTpreW=u;Xf-l=~E4NFz}h!I%=p#)IRJ z&1)=c(HIz*(QITy9%9H0=!+VRfCY z9AJ6hpafPPYn+;!W`wXjl=dz>-y`PA|MXWvc%&eAjXL`H{cIH}N`3B}Z#3_bb=kM#4 z4NYD>>1#;nJJqs^VMA5dU%zVx_h54WpFg~xO+lUlfv^!+i$+)(sD2Hu5U?`fAqPi% zwdH8nE6ikNKmcID%Z87E>xBu90{}{yo7{OSc4esGjJH|O7WvFzHCE6aTZfZRZWbsRf%S$%l`4r`7h~$0*km;_+ z!X47&2!1YOuVLzV#c~bmE`I00;@BUD_mP6KG~kBrF@q;cMlo8nKJu(U+nqNT|4x=f>7fa8+r&VXpuEg-3hnH68%eKg21JPFHi83YWgjoD6Sib2_`~ zsH!_!5Ba+>9}GOxP;1V;-GR6DO9z~40LVY-VaxxPr{$3FbZ5?&Jq&m~_MF4X}BH1|6e}hw#OR+^^9-^5HKtLSOxh z0t-ei6JTRyM~wMw-zU)u01;@gcx*~Kr+}4qWHd(S#L%|TpoVnVw$P=zs+L@Oqn8uN zO|l<%=&&wJGl&tnoJ^v!WNyqfL7-_BU4=RM+c$l)0oZY~SFLH5TYuO)w%Y9%y`3f5 zc5}h$V6g1VL;I?H0(q4p?4rZ(707`91bY?NY;Fp`VdJ>9FIsu1;FvieCSUY}~^CWCUu_Z_agOr#dPX zjgfR~jyMb{pWIQd(LqN-wJ!*U!M)JSXpugf@vVdV2TSWQ3ddF^qg@lzJ&(StEhQ-2{?Sbq2=w8u@i&@wXh1atT}NrxTN1DyKDX z6%)hWML`0vQj_oEQ`TvySe;$boc0F25SP-h0CPk2%% z#mFXe3iiAMSy_3{cRLW*L96(C{_m)c^0sxQb0PB>@Gf@-x3zahQt6pK&~T66v-8u| zklKfEpHKH%f2GHh<+5sezge~aOk4EZNyuvCBe4m=kz_&BD|)r}@nffxL1v!Lzz5qw$+an^%;lHbR5iqy9URA|h)K zbEKAm8g(B2D??&wIi2_QyV{4reP}e2CEyRbT%4BV00%^K(bR#cY(U@>4F*)@RO0G1 z{R(bJ(7VLUy}v}t@|wq3B{mbakq3qys=1n!qcYoW^a*@HBJmr_q81rd@A|4FqEVWY z!-?JeWps;Tv~X7~RY(w;nWTk4z*EU&X%nZ7UiPW3E%Oz7HhD#A^cX*$4qrepNJ z+m@D-gQjT<&UAzWHo1)>-wy7y2PiH}99{_|;EqV~?pS0`LQUR`_oPz{6&Tu+=#el4 zam#WNuuX3h*0;62B5{1(WdGG5%9$%3_=FgHscW=z{dtT<;30G9Z7o!v-jB_Jls+mV zZGbqUWVSx8yoITy=@Pw03fAs9%Rw}0fA!^HMoJcPs-ulNJ%G`*)ceco{PF)fxGIYf z$Q}I!z`($T#R3}kihl%{ zyH7%F$jMCdK7ZgN3e(0^l3)K`)kF(epYju`vP-~;kA1zI2rOEFsiwZKknsa4)sak) zEsw0!#8j+31nK8NMQ;YBl3J2ri(pya0uh-c9L;(M&>HvK-pI)hCC=dC{xUy|r z)sx~_tuA}a@eh|Llt4wocE!B{l7_lV%gPcBnc(`##j~57$4>z$)JU9v=2B91bqV!* zz?~uDyJw}C%v2R=m1GX{_Un_&Oz%~S9S8RxRMgbjSgh`{f%|}N-8b+627E_Btn1Nr z&{w)r=j~~RA$~{-fT+YUkFH+`$Y^bCwQh|ql%t1{D}LM@Z0`|_1{XFkF9{59duY(_ zK59AphrX-=pekr<&maW5{90{TFJQZSlQc994d$xpOSmB`D=gMO(0pBNF8AidWbXeTgkoAy;+_fX6da2Fqc{YMa?#IZ`7`2rDyTBt4{i}y`ek9 z&$$T9sSbN9mQq|!l8eW3JHd4U%X%=a`O@)RnNuIOK(d#v0#65LA+GxI3)Z3*zn;wy z!lfT688LvX{Ac|VnBkR!xJ4YaPvXe}4t{F9SdIi(^}q7jtvqBVMdTMb05Qy4J1RcI z*X2-fCYG?1r|qe>jMjVpd_n4bm)MvP#n-vXy&#k2m!R^j!&Tjk7{#BfC5IL%*;or# z(1o>$z(eT~F=^>++ZUHRlz(HTySJye2jsd>Ti66{mu@p>fMwAb4@Xz0%j0=g*O`-X zA(e%jQ#Gh8J>XLfz=1D8JF}uf!omP^d2S|T`ZV#es1R8Gz%NYE2Fk>dZ9&TZ&g%l0 zNg<8|g5=ziGmgA>GL3tfTJ*Ac`jRv6JcXC0-;3S|dpzW$+g=pedt2zr#)d44Y5ed? zuaW`uM$zpINSM_vv$l7nKrB%MbTP3NnM~Xvn039rZaRj+nYPD;&6C;eVyH^}Gq+^p z^+Vfb(Sr0sR9=hwo79i%aV%m%*v%$`<%}N`auklT*WFAz(Io9#I7-APYF?wSzI_!3 zoiRIzfjbQsc>^>v0t-&Gr2y6J;*Gmq7yJ=O&s7!40`#u%Fc)e>8>U|Is$(z@=}m0F3!t zRgsIiK`Lp^L$1fKMwCgxvfZeWA0QG2qjBKrL`G~n|H_ia`whf_iPYLarsn2Xf33QA zUWi5uEO&;}(Bvq88?wWkINI^sfCtnl`XWLn7 zdc=kuhF*u=$FMm-#=NfJJtE-sHOh@ma&Qt%+hYvMeqpKbc zP<-56Y>?`;e_N|unD&lMGidi5BVd(S`BG$BoBW9Zp(mr;3$+LrtGFsQ9ODpfT-_f- zfFnlx$QQcJlZNvX&zs1JKx7D+mF(>i?^?4d=8}q)BFx<4+rLoQ^2PDyy+T!h;mCZ5 z0}wzX0#ER%$RCiZ3le3J`BRfXG?<>kBPZ4uc1+%`QSxAT32q!zr<~W@dj6luzn8xo zo1d!OEH|wbl_KihwnN!Jd8xMQplFQ1YgdxMw98